diff --git a/.github/workflows/docker-image.yml b/.github/workflows/docker-image.yml new file mode 100644 index 0000000..c18a82c --- /dev/null +++ b/.github/workflows/docker-image.yml @@ -0,0 +1,27 @@ +name: Docker Image CI + +on: + push: + branches: [ "master" ] + pull_request: + branches: [ "master" ] + +jobs: + + build-melodic: + + runs-on: ubuntu-latest + + steps: + - uses: actions/checkout@v3 + - name: Build the Docker image + run: docker build . --file Dockerfile_melodic_18_04 --tag mins:melodic + + build-noetic: + + runs-on: ubuntu-latest + + steps: + - uses: actions/checkout@v3 + - name: Build the Docker image + run: docker build . --file Dockerfile_noetic_20_04 --tag mins:noetic diff --git a/Dockerfile_melodic_18_04 b/Dockerfile_melodic_18_04 new file mode 100644 index 0000000..3478946 --- /dev/null +++ b/Dockerfile_melodic_18_04 @@ -0,0 +1,7 @@ +FROM ros:melodic-perception-bionic +COPY . /catkin_ws/src/MINS +RUN apt update && apt install python3-catkin-tools -y +RUN /bin/bash -c "chmod +x /opt/ros/melodic/setup.sh && source /opt/ros/melodic/setup.sh && catkin build --workspace /catkin_ws" + +WORKDIR /catkin_ws +ENTRYPOINT ["/bin/bash"] diff --git a/Dockerfile_noetic_20_04 b/Dockerfile_noetic_20_04 new file mode 100644 index 0000000..2f6f221 --- /dev/null +++ b/Dockerfile_noetic_20_04 @@ -0,0 +1,7 @@ +FROM ros:noetic-perception-focal +COPY . /catkin_ws/src/MINS +RUN apt update && apt install python3-catkin-tools -y +RUN /bin/bash -c "chmod +x /opt/ros/noetic/setup.sh && source /opt/ros/noetic/setup.sh && catkin build --workspace /catkin_ws" + +WORKDIR /catkin_ws +ENTRYPOINT ["/bin/bash"] diff --git a/mins/CMakeLists.txt b/mins/CMakeLists.txt index d7c1859..4b73601 100644 --- a/mins/CMakeLists.txt +++ b/mins/CMakeLists.txt @@ -34,13 +34,13 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3 -fsee -fomit-frame-pointer -fno-sign set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g3 -Wall -Wuninitialized -Wmaybe-uninitialized -fno-omit-frame-pointer") # Find ROS build system -find_package(catkin REQUIRED COMPONENTS roscpp rosbag tf std_msgs geometry_msgs sensor_msgs nav_msgs image_geometry visualization_msgs image_transport cv_bridge ov_core pcl_ros libpointmatcher) +find_package(catkin REQUIRED COMPONENTS roscpp rosbag tf std_msgs geometry_msgs sensor_msgs nav_msgs image_geometry visualization_msgs image_transport cv_bridge ov_core pcl_ros) add_definitions(-DROS_AVAILABLE=1) # Add catkin packages catkin_package( - CATKIN_DEPENDS roscpp rosbag tf std_msgs geometry_msgs sensor_msgs nav_msgs image_geometry visualization_msgs image_transport cv_bridge ov_core pcl_ros libpointmatcher + CATKIN_DEPENDS roscpp rosbag tf std_msgs geometry_msgs sensor_msgs nav_msgs image_geometry visualization_msgs image_transport cv_bridge ov_core pcl_ros INCLUDE_DIRS src/ LIBRARIES mins_lib ) @@ -127,7 +127,7 @@ install(DIRECTORY src/ ################################################## add_executable(simulation src/run_simulation.cpp) -target_link_libraries(simulation mins_lib ${thirdparty_libraries}) +target_link_libraries(simulation mins_lib) install(TARGETS simulation ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} @@ -135,7 +135,7 @@ install(TARGETS simulation ) add_executable(bag src/run_bag.cpp) -target_link_libraries(bag mins_lib ${thirdparty_libraries}) +target_link_libraries(bag mins_lib) install(TARGETS bag ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} @@ -143,7 +143,7 @@ install(TARGETS bag ) add_executable(subscribe src/run_subscribe.cpp) -target_link_libraries(subscribe mins_lib ${thirdparty_libraries}) +target_link_libraries(subscribe mins_lib) install(TARGETS subscribe ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} diff --git a/mins/src/core/ROSHelper.cpp b/mins/src/core/ROSHelper.cpp index a47dbaf..ae4ddfc 100644 --- a/mins/src/core/ROSHelper.cpp +++ b/mins/src/core/ROSHelper.cpp @@ -116,8 +116,8 @@ ov_core::ImuData ROSHelper::Imu2Data(const Imu::ConstPtr &msg) { return message; } -boost::shared_ptr> ROSHelper::rosPC2pclPC(const sensor_msgs::PointCloud2ConstPtr &msg, int id) { - boost::shared_ptr> pcl_pc2(new pcl::PointCloud); +std::shared_ptr> ROSHelper::rosPC2pclPC(const sensor_msgs::PointCloud2ConstPtr &msg, int id) { + std::shared_ptr> pcl_pc2(new pcl::PointCloud); pcl::fromROSMsg(*msg, *pcl_pc2); pcl_pc2->header.frame_id = to_string(id); // overwrite the id match with system number pcl_pc2->header.stamp = msg->header.stamp.toSec() * 1000; // deliver this in msec diff --git a/mins/src/core/ROSHelper.h b/mins/src/core/ROSHelper.h index d850974..1da00ca 100644 --- a/mins/src/core/ROSHelper.h +++ b/mins/src/core/ROSHelper.h @@ -89,7 +89,7 @@ class ROSHelper { static GPSData PoseStamped2Data(const geometry_msgs::PoseStampedPtr &msg, int id, double noise); - static boost::shared_ptr> rosPC2pclPC(const sensor_msgs::PointCloud2ConstPtr &msg, int id); + static std::shared_ptr> rosPC2pclPC(const sensor_msgs::PointCloud2ConstPtr &msg, int id); static GPSData NavSatFix2Data(const sensor_msgs::NavSatFixPtr &msg, int id); diff --git a/mins/src/core/ROSPublisher.cpp b/mins/src/core/ROSPublisher.cpp index 291c2c1..3f32360 100644 --- a/mins/src/core/ROSPublisher.cpp +++ b/mins/src/core/ROSPublisher.cpp @@ -419,7 +419,7 @@ void ROSPublisher::publish_vicon(ViconData data) { seq_vicon[data.id]++; } -void ROSPublisher::publish_lidar_cloud(pcl::PointCloud::Ptr lidar) { +void ROSPublisher::publish_lidar_cloud(std::shared_ptr> lidar) { sensor_msgs::PointCloud2 output; pcl::toROSMsg(*lidar, output); output.header.frame_id = "lidar" + lidar->header.frame_id; @@ -465,13 +465,15 @@ void ROSPublisher::publish_lidar_map() { // Publish pointcloud in the global frame // This is slower because it requires pointcloud transform - pcl::PointCloud::Ptr map_inL(new pcl::PointCloud); + POINTCLOUD_XYZI_PTR map_inL(new pcl::PointCloud); ikd->tree->flatten(ikd->tree->Root_Node, map_inL->points, NOT_RECORD); pair pose_LinG = sys->up_ldr->get_pose_LinG(ikd->id, ikd->time); Matrix4d tr = Matrix4d::Identity(); tr.block(0, 0, 3, 3) = pose_LinG.first.transpose(); tr.block(0, 3, 3, 1) = pose_LinG.second; - pcl::PointCloud::Ptr map_inG(new pcl::PointCloud); + POINTCLOUD_XYZI_PTR map_inG(new pcl::PointCloud); + map_inL->height = map_inL->points.size(); + map_inL->width = 1; pcl::transformPointCloud(*map_inL, *map_inG, tr); sensor_msgs::PointCloud2 map_pointcloud; pcl::toROSMsg(*map_inG, map_pointcloud); diff --git a/mins/src/core/ROSPublisher.h b/mins/src/core/ROSPublisher.h index 6d0e678..21432ff 100644 --- a/mins/src/core/ROSPublisher.h +++ b/mins/src/core/ROSPublisher.h @@ -81,7 +81,7 @@ class ROSPublisher { void publish_cam_images(int cam_id); /// Publish lidar point cloud - void publish_lidar_cloud(boost::shared_ptr> lidar); + void publish_lidar_cloud(std::shared_ptr> lidar); private: /// Publish the current state diff --git a/mins/src/core/ROSSubscriber.cpp b/mins/src/core/ROSSubscriber.cpp index f64d94f..cea2852 100644 --- a/mins/src/core/ROSSubscriber.cpp +++ b/mins/src/core/ROSSubscriber.cpp @@ -176,7 +176,7 @@ void ROSSubscriber::callback_gnss(const NavSatFixConstPtr &msg, int gps_id) { void ROSSubscriber::callback_lidar(const PointCloud2ConstPtr &msg, int lidar_id) { // convert into correct format & send it to our system - boost::shared_ptr> data = ROSHelper::rosPC2pclPC(msg, lidar_id); + std::shared_ptr> data = ROSHelper::rosPC2pclPC(msg, lidar_id); sys->feed_measurement_lidar(data); pub->publish_lidar_cloud(data); } diff --git a/mins/src/core/SystemManager.cpp b/mins/src/core/SystemManager.cpp index bd20268..075a2a6 100644 --- a/mins/src/core/SystemManager.cpp +++ b/mins/src/core/SystemManager.cpp @@ -174,7 +174,7 @@ void SystemManager::feed_measurement_wheel(const WheelData &wheel) { state->initialized ? tc_sensors->dong("WHL") : void(); } -void SystemManager::feed_measurement_lidar(boost::shared_ptr> lidar) { +void SystemManager::feed_measurement_lidar(std::shared_ptr> lidar) { if (!state->op->lidar->enabled) return; state->initialized ? tc_sensors->ding("LDR") : void(); diff --git a/mins/src/core/SystemManager.h b/mins/src/core/SystemManager.h index 22d147d..2adc738 100644 --- a/mins/src/core/SystemManager.h +++ b/mins/src/core/SystemManager.h @@ -87,7 +87,7 @@ class SystemManager { void feed_measurement_wheel(const WheelData &wheel); /// LiDAR measurement feeder - void feed_measurement_lidar(boost::shared_ptr> lidar); + void feed_measurement_lidar(std::shared_ptr> lidar); /** * @brief After the run has ended, print results */ diff --git a/mins/src/init/Initializer.cpp b/mins/src/init/Initializer.cpp index df9b678..fc47fba 100644 --- a/mins/src/init/Initializer.cpp +++ b/mins/src/init/Initializer.cpp @@ -321,7 +321,7 @@ void Initializer::init_lidar_sim() { } // Get the lidar point cloud - boost::shared_ptr> lidar(new pcl::PointCloud); + std::shared_ptr> lidar(new pcl::PointCloud); bool success = sim->get_lidar_pointcloud(lidar, sim->timestamp - op->dt.at(i), i, op); assert(success); diff --git a/mins/src/options/OptionsIMU.h b/mins/src/options/OptionsIMU.h index dd3bc89..be45478 100644 --- a/mins/src/options/OptionsIMU.h +++ b/mins/src/options/OptionsIMU.h @@ -29,6 +29,7 @@ #define MINS_OPTIONSIMU_H #include +#include namespace ov_core { class YamlParser; diff --git a/mins/src/options/OptionsInit.h b/mins/src/options/OptionsInit.h index 86bff6a..c54fd04 100644 --- a/mins/src/options/OptionsInit.h +++ b/mins/src/options/OptionsInit.h @@ -29,6 +29,7 @@ #define MINS_OPTIONSINIT_H #include +#include namespace ov_core { class YamlParser; } diff --git a/mins/src/options/OptionsSystem.h b/mins/src/options/OptionsSystem.h index ccf07da..9bc6f76 100644 --- a/mins/src/options/OptionsSystem.h +++ b/mins/src/options/OptionsSystem.h @@ -22,6 +22,7 @@ #define MINS_OPTIONSSYSTEM_H #include +#include namespace ov_core { class YamlParser; } diff --git a/mins/src/run_bag.cpp b/mins/src/run_bag.cpp index 4cdb3d8..001146b 100644 --- a/mins/src/run_bag.cpp +++ b/mins/src/run_bag.cpp @@ -169,7 +169,7 @@ int main(int argc, char **argv) { if (op->est->lidar->enabled) { for (int lidar_id = 0; lidar_id < op->est->lidar->max_n; lidar_id++) { if (msgs.at(i).getTopic() == op->est->lidar->topic.at(lidar_id)) { - pcl::PointCloud::Ptr data = ROSHelper::rosPC2pclPC(msgs.at(i).instantiate(), lidar_id); + std::shared_ptr> data = ROSHelper::rosPC2pclPC(msgs.at(i).instantiate(), lidar_id); PRINT1("[BAG] LDR measurement: %.3f|%d|%d\n", (double)data->header.stamp / 1000, lidar_id, data->points.size()); sys->feed_measurement_lidar(data); pub->publish_lidar_cloud(data); @@ -198,12 +198,6 @@ int main(int argc, char **argv) { op->sys->save_timing ? save->save_timing_to_file(sys->tc_sensors->get_total_sum()) : void(); save->check_files(); - // Call destructor for a cleaner termination - sys->~SystemManager(); - pub->~ROSPublisher(); - sim_viz->~SimVisualizer(); - op->~Options(); - save->~State_Logger(); ros::shutdown(); // Done! diff --git a/mins/src/run_simulation.cpp b/mins/src/run_simulation.cpp index 2ba7ae0..2bced23 100644 --- a/mins/src/run_simulation.cpp +++ b/mins/src/run_simulation.cpp @@ -108,7 +108,7 @@ int main(int argc, char **argv) { } // LIDAR: get the next simulated lidar range measurements - pcl::PointCloud::Ptr lidar(new pcl::PointCloud); + std::shared_ptr> lidar(new pcl::PointCloud); if (sim->get_next_lidar(lidar)) { sys->feed_measurement_lidar(lidar); pub->publish_lidar_cloud(lidar); @@ -129,13 +129,6 @@ int main(int argc, char **argv) { op->sys->save_timing ? save->save_timing_to_file(sys->tc_sensors->get_total_sum()) : void(); save->check_files(); - // Call destructor for a cleaner termination - sys->~SystemManager(); - sim->~Simulator(); - pub->~ROSPublisher(); - sim_viz->~SimVisualizer(); - op->~Options(); - save->~State_Logger(); ros::shutdown(); return EXIT_SUCCESS; } diff --git a/mins/src/run_subscribe.cpp b/mins/src/run_subscribe.cpp index 1bc227b..9097d57 100644 --- a/mins/src/run_subscribe.cpp +++ b/mins/src/run_subscribe.cpp @@ -80,11 +80,6 @@ int main(int argc, char **argv) { op->sys->save_timing ? save->save_timing_to_file(sys->tc_sensors->get_total_sum()) : void(); save->check_files(); - // Call destructor for a cleaner termination - sys->~SystemManager(); - pub->~ROSPublisher(); - op->~Options(); - save->~State_Logger(); ros::shutdown(); // Done! diff --git a/mins/src/sim/Simulator.cpp b/mins/src/sim/Simulator.cpp index 93b6f21..fca5bf8 100644 --- a/mins/src/sim/Simulator.cpp +++ b/mins/src/sim/Simulator.cpp @@ -718,7 +718,7 @@ bool Simulator::get_next_wheel(WheelData &wheel) { return true; } -bool Simulator::get_next_lidar(boost::shared_ptr> lidar) { +bool Simulator::get_next_lidar(std::shared_ptr> lidar) { // check turn string sensor_type; @@ -739,7 +739,7 @@ bool Simulator::get_next_lidar(boost::shared_ptr> return true; } -bool Simulator::get_lidar_pointcloud(boost::shared_ptr> lidar, double time, int id, std::shared_ptr lidar_op) { +bool Simulator::get_lidar_pointcloud(std::shared_ptr> lidar, double time, int id, std::shared_ptr lidar_op) { // Lidar id and timestamp lidar->header.frame_id = to_string(id); lidar->header.stamp = (unsigned long)((time - lidar_op->dt.at(id)) * 1000); // Delivered in micro second diff --git a/mins/src/sim/Simulator.h b/mins/src/sim/Simulator.h index 62204ce..8db6155 100644 --- a/mins/src/sim/Simulator.h +++ b/mins/src/sim/Simulator.h @@ -123,7 +123,7 @@ class Simulator { * @param lidar mins::LidarData * @return True if we have a measurement */ - bool get_next_lidar(boost::shared_ptr> lidar); + bool get_next_lidar(std::shared_ptr> lidar); /// boolean for transforming groundtruth after GPS initialization bool trans_gt_to_ENU = false; @@ -186,7 +186,7 @@ class Simulator { bool load_plane_data(std::string path_planes); /// Generate LiDAR pointcloud - bool get_lidar_pointcloud(boost::shared_ptr> lidar, double time, int id, std::shared_ptr lidar_op); + bool get_lidar_pointcloud(std::shared_ptr> lidar, double time, int id, std::shared_ptr lidar_op); /** * @brief Will generate points in the fov of the specified camera diff --git a/mins/src/update/lidar/LidarHelper.cpp b/mins/src/update/lidar/LidarHelper.cpp index f0d86f3..7adf5a2 100644 --- a/mins/src/update/lidar/LidarHelper.cpp +++ b/mins/src/update/lidar/LidarHelper.cpp @@ -89,14 +89,14 @@ bool LidarHelper::remove_motion_blur(shared_ptr state, shared_ptr lidar, double downsample_size) { pcl::VoxelGrid downSizeFilter; downSizeFilter.setLeafSize((float)downsample_size, (float)downsample_size, (float)downsample_size); - downSizeFilter.setInputCloud(lidar->pointcloud); + downSizeFilter.setInputCloud((*lidar->pointcloud).makeShared()); downSizeFilter.filter(*lidar->pointcloud); } void LidarHelper::downsample(POINTCLOUD_XYZI_PTR lidar, double downsample_size) { pcl::VoxelGrid downSizeFilter; downSizeFilter.setLeafSize((float)downsample_size, (float)downsample_size, (float)downsample_size); - downSizeFilter.setInputCloud(lidar); + downSizeFilter.setInputCloud((*lidar).makeShared()); downSizeFilter.filter(*lidar); } @@ -154,7 +154,7 @@ bool LidarHelper::transform_to_map(shared_ptr state, shared_ptrop->lidar->map_use_icp) { - POINTCLOUD_XYZI_PTR map_pointcloud = boost::make_shared>(); + POINTCLOUD_XYZI_PTR map_pointcloud = std::make_shared>(); ikd->tree->flatten(ikd->tree->Root_Node, map_pointcloud->points, NOT_RECORD); POINTCLOUD_XYZI_PTR new_pointcloud = lidar->pointcloud; @@ -209,7 +209,7 @@ void LidarHelper::register_scan(shared_ptr state, shared_ptr l void LidarHelper::propagate_map_to_newest_clone(shared_ptr state, shared_ptr ikd, shared_ptr op, double FT) { // Load map info - POINTCLOUD_XYZI_PTR map_points = boost::make_shared>(); + POINTCLOUD_XYZI_PTR map_points = std::make_shared>(); ikd->tree->flatten(ikd->tree->Root_Node, map_points->points, NOT_RECORD); op->map_do_downsample ? downsample(map_points, state->op->lidar->map_downsample_size) : void(); diff --git a/mins/src/update/lidar/LidarHelper.h b/mins/src/update/lidar/LidarHelper.h index dedc420..91cf904 100644 --- a/mins/src/update/lidar/LidarHelper.h +++ b/mins/src/update/lidar/LidarHelper.h @@ -31,7 +31,7 @@ class PointXYZ; class PointXYZI; template class PointCloud; } // namespace pcl -typedef boost::shared_ptr> POINTCLOUD_XYZI_PTR; +typedef std::shared_ptr> POINTCLOUD_XYZI_PTR; template class KD_TREE; namespace mins { class State; diff --git a/mins/src/update/lidar/LidarTypes.cpp b/mins/src/update/lidar/LidarTypes.cpp index f298bef..feaf853 100644 --- a/mins/src/update/lidar/LidarTypes.cpp +++ b/mins/src/update/lidar/LidarTypes.cpp @@ -23,14 +23,14 @@ #include "pcl/point_cloud.h" using namespace mins; -LiDARData::LiDARData(double time, double ref_time, int id, boost::shared_ptr> pointcloud, double max_range, double min_range) : time(time), id(id) { +LiDARData::LiDARData(double time, double ref_time, int id, std::shared_ptr> pointcloud, double max_range, double min_range) : time(time), id(id) { // copy over the point cloud // copy measurement time of the point so that it can be filtered with time. // Note: we only store relative time to "reference time" because intensity (float) has only 4 bytes // Note: this "reference time" should be the same for all other pointclouds. - this->pointcloud = boost::make_shared>(); - this->pointcloud_original = boost::make_shared>(); - this->pointcloud_in_map = boost::make_shared>(); + this->pointcloud = std::make_shared>(); + this->pointcloud_original = std::make_shared>(); + this->pointcloud_in_map = std::make_shared>(); this->pointcloud->points.reserve(pointcloud->points.size()); this->pointcloud_original->points.reserve(pointcloud->points.size()); for (int i = 0; i < (int)pointcloud->size(); i++) { @@ -58,9 +58,9 @@ LiDARData::LiDARData(double time, double ref_time, int id, boost::shared_ptr>(); - pointcloud_original = boost::make_shared>(); - pointcloud_in_map = boost::make_shared>(); + pointcloud = std::make_shared>(); + pointcloud_original = std::make_shared>(); + pointcloud_in_map = std::make_shared>(); } Eigen::Vector3d LiDARData::p(int p_id) { diff --git a/mins/src/update/lidar/LidarTypes.h b/mins/src/update/lidar/LidarTypes.h index 16c6916..2adb652 100644 --- a/mins/src/update/lidar/LidarTypes.h +++ b/mins/src/update/lidar/LidarTypes.h @@ -30,12 +30,12 @@ class PointXYZ; class PointXYZI; template class PointCloud; } // namespace pcl -typedef boost::shared_ptr> POINTCLOUD_XYZI_PTR; +typedef std::shared_ptr> POINTCLOUD_XYZI_PTR; template class KD_TREE; namespace mins { struct LiDARData { - LiDARData(double time, double ref_time, int id, boost::shared_ptr> pointcloud, double max_range, double min_range); + LiDARData(double time, double ref_time, int id, std::shared_ptr> pointcloud, double max_range, double min_range); LiDARData(); diff --git a/mins/src/update/lidar/UpdaterLidar.cpp b/mins/src/update/lidar/UpdaterLidar.cpp index 0973fb6..5900676 100644 --- a/mins/src/update/lidar/UpdaterLidar.cpp +++ b/mins/src/update/lidar/UpdaterLidar.cpp @@ -47,7 +47,7 @@ UpdaterLidar::UpdaterLidar(shared_ptr state) : state(state) { } } -void UpdaterLidar::feed_measurement(boost::shared_ptr> lidar) { +void UpdaterLidar::feed_measurement(std::shared_ptr> lidar) { // Record first ever measurement time to set up reference time (ref. LidarTypes.h) FT < 0 ? FT = (double)lidar->header.stamp / 1000 : double(); diff --git a/mins/src/update/lidar/UpdaterLidar.h b/mins/src/update/lidar/UpdaterLidar.h index 7c1de35..e794709 100644 --- a/mins/src/update/lidar/UpdaterLidar.h +++ b/mins/src/update/lidar/UpdaterLidar.h @@ -48,7 +48,7 @@ class UpdaterLidar { UpdaterLidar(shared_ptr state); /// Get lidar measurement - void feed_measurement(boost::shared_ptr> lidar); + void feed_measurement(std::shared_ptr> lidar); /// Try update with available measurements void try_update(); diff --git a/mins_eval/src/run_comparison.cpp b/mins_eval/src/run_comparison.cpp index 74e1520..1c1cb14 100644 --- a/mins_eval/src/run_comparison.cpp +++ b/mins_eval/src/run_comparison.cpp @@ -31,13 +31,16 @@ #include #include #include +#include #include +#include +#include using namespace std; using namespace ov_eval; using namespace boost; using namespace Eigen; -typedef filesystem::path PATH; +typedef boost::filesystem::path PATH; typedef vector VEC_PATH; // file and directory paths string align_mode, folder_groundtruths, folder_algorithms; @@ -217,7 +220,7 @@ void basic_setup(int argc, char **argv) { /// Get paths of the ground truths VEC_PATH get_path_groundtruths() { VEC_PATH path_gts_local; - for (const auto &p : filesystem::recursive_directory_iterator(folder_groundtruths)) { + for (const auto &p : boost::filesystem::recursive_directory_iterator(folder_groundtruths)) { if (p.path().extension() == ".txt") { path_gts_local.push_back(p.path()); } @@ -242,8 +245,8 @@ VEC_PATH get_path_groundtruths() { VEC_PATH get_path_algorithms() { // Also create empty statistic objects for each of our datasets VEC_PATH path_alg; - for (const auto &entry : filesystem::directory_iterator(folder_algorithms)) { - if (filesystem::is_directory(entry)) { + for (const auto &entry : boost::filesystem::directory_iterator(folder_algorithms)) { + if (boost::filesystem::is_directory(entry)) { path_alg.push_back(entry.path()); } } @@ -255,8 +258,8 @@ VEC_PATH get_path_algorithms() { for (auto &path : path_alg) { // Get the list of datasets this algorithm records map path_algo_datasets; - for (auto &entry : filesystem::directory_iterator(path)) { - if (filesystem::is_directory(entry)) { + for (auto &entry : boost::filesystem::directory_iterator(path)) { + if (boost::filesystem::is_directory(entry)) { found_data.push_back(entry.path().filename().string()); path_algo_datasets.insert({entry.path().filename().string(), entry.path()}); } @@ -354,8 +357,8 @@ map>> NEES_init() { /// Get files given directory path map get_list_of_datasets(const PATH &path) { map path_algo_datasets; - for (auto &entry : filesystem::directory_iterator(path)) { - if (filesystem::is_directory(entry)) { + for (auto &entry : boost::filesystem::directory_iterator(path)) { + if (boost::filesystem::is_directory(entry)) { path_algo_datasets.insert({entry.path().filename().string(), entry.path()}); } } @@ -364,7 +367,7 @@ map get_list_of_datasets(const PATH &path) { /// search for specific extentioned files for analysis. void get_paths_of_run_files(map datasets, const PATH &path_gt, vector &run_paths, vector &time_paths) { - for (auto &entry : filesystem::directory_iterator(datasets.at(path_gt.stem().string()))) { + for (auto &entry : boost::filesystem::directory_iterator(datasets.at(path_gt.stem().string()))) { // Files containing timing record if (entry.path().extension() == ".time") { time_paths.push_back(entry.path().string()); diff --git a/thirdparty/libpointmatcher/.dockerignore b/thirdparty/libpointmatcher/.dockerignore new file mode 100644 index 0000000..7b13292 --- /dev/null +++ b/thirdparty/libpointmatcher/.dockerignore @@ -0,0 +1,23 @@ + +# Note: +# - libpointmatch cmake install require that the README.md file exist in the docker image +# - libpointmatcher-CI doc related step require that .svg, .png and .md be copied in the docker image + +# Graphic/image related +*.svg +*.svgz +*.png +*.drawio + +# Text related +*.pdf + +# Files + + +# Directories +drawio/* +visual/* + +# IDE +.run/* diff --git a/thirdparty/libpointmatcher/.gitignore b/thirdparty/libpointmatcher/.gitignore new file mode 100644 index 0000000..914d404 --- /dev/null +++ b/thirdparty/libpointmatcher/.gitignore @@ -0,0 +1,10 @@ +*.cproject +*.project +*~ +*.swp +*.cur_trans +build +.ipynb_checkpoints/ + +dist/ +*.so diff --git a/thirdparty/libpointmatcher/.readthedocs.yml b/thirdparty/libpointmatcher/.readthedocs.yml new file mode 100644 index 0000000..fd431b8 --- /dev/null +++ b/thirdparty/libpointmatcher/.readthedocs.yml @@ -0,0 +1,20 @@ +# .readthedocs.yml +# Read the Docs configuration file +# See https://docs.readthedocs.io/en/stable/config-file/v2.html for details + +# Required +version: 2 + +# Build documentation with MkDocs +mkdocs: + configuration: mkdocs.yml + +# Optionally build your docs in additional formats such as PDF +#formats: +# - pdf + +# Optionally set the version of Python and requirements required to build your docs +python: + version: 3 + install: + - requirements: doc/requirements.txt \ No newline at end of file diff --git a/thirdparty/libpointmatcher/CMakeLists.txt b/thirdparty/libpointmatcher/CMakeLists.txt index a3e0a3a..c82c54a 100644 --- a/thirdparty/libpointmatcher/CMakeLists.txt +++ b/thirdparty/libpointmatcher/CMakeLists.txt @@ -1,11 +1,15 @@ -cmake_minimum_required(VERSION 2.8.11) +cmake_minimum_required(VERSION 2.8.12) +include(GNUInstallDirs) # populate CMAKE_INSTALL_{LIB,BIN}DIR include(CheckSymbolExists) + #======================== # Project details / setup #======================== +set(CMAKE_POSITION_INDEPENDENT_CODE ON) # add -fPIC as required + # Extract version from header, done first to satisfy CMP0048, # see `cmake --help-policy CMP0048` for more information. file( @@ -17,17 +21,19 @@ file( # If no matches found, something is wrong with PointMatcher.h if (NOT POINTMATCHER_PROJECT_VERSION) message(SEND_ERROR "Cannot find version number in '${CMAKE_CURRENT_SOURCE_DIR}/pointmatcher/PointMatcher.h'.") -endif (NOT POINTMATCHER_PROJECT_VERSION) +endif () # Transform '#define POINTMATCHER_VERSION "X.Y.Z"' into 'X.Y.Z' string(REGEX REPLACE ".*\"(.*)\".*" "\\1" POINTMATCHER_PROJECT_VERSION "${POINTMATCHER_PROJECT_VERSION}") # In 3.0+, project(...) should specify VERSION to satisfy CMP0048 if (CMAKE_VERSION VERSION_LESS 3.0.0) project(libpointmatcher) -else (CMAKE_VERSION VERSION_LESS 3.0.0) +else () cmake_policy(SET CMP0048 NEW) project(libpointmatcher VERSION ${POINTMATCHER_PROJECT_VERSION}) -endif (CMAKE_VERSION VERSION_LESS 3.0.0) +endif () + +set(CMAKE_DEBUG_POSTFIX "d") # Check if 32 bit platform # By default, libpointmatcher is not compatible with and will not build on a @@ -36,14 +42,14 @@ if( NOT CMAKE_SIZEOF_VOID_P EQUAL 8 ) MESSAGE(SEND_ERROR "32 bits compiler detected. Libpointmatcher is only supported in 64 bits." ) SET( EX_PLATFORM 32 ) SET( EX_PLATFORM_NAME "x86" ) -endif( NOT CMAKE_SIZEOF_VOID_P EQUAL 8 ) +endif() ## WARNING: unsupported ## To force install as a 32 bit library, set BUILD_32 to true if( BUILD_32 ) MESSAGE(STATUS "Building as a 32 bit library") SET(CMAKE_CXX_FLAGS "-m32") -endif( BUILD_32 ) +endif() # Ensure proper build type if (NOT CMAKE_BUILD_TYPE) @@ -51,26 +57,27 @@ if (NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE Release CACHE STRING "Choose the type of build, options are: None Debug Release RelWithDebInfo MinSizeRel." FORCE) -else (NOT CMAKE_BUILD_TYPE) +else () if (CMAKE_BUILD_TYPE STREQUAL "Debug") message("\n=================================================================================") message("\n-- Build type: Debug. Performance will be terrible!") message("-- Add -DCMAKE_BUILD_TYPE=Release to the CMake command line to get an optimized build.") message("\n=================================================================================") - endif (CMAKE_BUILD_TYPE STREQUAL "Debug") -endif (NOT CMAKE_BUILD_TYPE) + endif () +endif () #================= extra building definitions ============================== if (NOT CMAKE_BUILD_TYPE STREQUAL "Debug") add_definitions(-O3) -endif(NOT CMAKE_BUILD_TYPE STREQUAL "Debug") +endif() # For Windows if( MSVC ) add_definitions( /D _VARIADIC_MAX=10 ) # VS2012 does not support tuples correctly yet add_definitions( /D _USE_MATH_DEFINES) # defines M_PI for Visual Studio add_definitions( /D _ENABLE_EXTENDED_ALIGNED_STORAGE) # this variable must be defined with VS2017 to acknowledge alignment changes of aligned_storage + add_definitions(/bigobj) endif() #======================= installation ===================================== @@ -96,9 +103,6 @@ foreach(p LIB BIN INCLUDE CMAKE) endif() endforeach() -# Install package.xml for catkin -install(FILES package.xml DESTINATION "share/${PROJECT_NAME}") - #=========================================================================== @@ -106,29 +110,41 @@ install(FILES package.xml DESTINATION "share/${PROJECT_NAME}") # initially set(EXTERNAL_LIBS "") -set(EXTRA_DEPS "") # compile local version of gtest and yaml-cpp add_subdirectory(contrib) +#--------------------------- +# DEPENDENCY: POSIX Threads +#--------------------------- +find_package(Threads REQUIRED) +if (CMAKE_VERSION VERSION_LESS 3.1.0) + set(EXTERNAL_LIBS ${EXTERNAL_LIBS} ${CMAKE_THREAD_LIBS_INIT}) +else() + set(EXTERNAL_LIBS ${EXTERNAL_LIBS} Threads::Threads) +endif() #-------------------- # DEPENDENCY: boost #-------------------- -find_package(Boost COMPONENTS thread filesystem system program_options date_time REQUIRED) -if (Boost_MINOR_VERSION GREATER 47) - find_package(Boost COMPONENTS thread filesystem system program_options date_time chrono REQUIRED) -endif (Boost_MINOR_VERSION GREATER 47) -include_directories(${Boost_INCLUDE_DIRS}) -set(EXTERNAL_LIBS ${EXTERNAL_LIBS} ${Boost_LIBRARIES}) +set(Boost_USE_STATIC_LIBS OFF) +find_package(Boost REQUIRED COMPONENTS thread filesystem system program_options date_time) +if (Boost_MINOR_VERSION GREATER 47) + find_package(Boost REQUIRED COMPONENTS thread filesystem system program_options date_time chrono) +endif () #-------------------- # DEPENDENCY: eigen 3 #-------------------- -find_path(EIGEN_INCLUDE_DIR Eigen/Core - /usr/local/include/eigen3 - /usr/include/eigen3 +find_path(EIGEN_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library + HINTS ENV EIGEN3_INC_DIR + ENV EIGEN3_DIR + PATHS Eigen/Core + /usr/local/include + /usr/include + PATH_SUFFIXES include eigen3 eigen + DOC "Directory containing the Eigen3 header files" ) # Suppress Eigen's warning by adding it to the system's library @@ -143,11 +159,24 @@ include_directories(SYSTEM "${EIGEN_INCLUDE_DIR}") #-------------------- # DEPENDENCY: nabo #-------------------- -find_package(libnabo REQUIRED PATHS ${LIBNABO_INSTALL_DIR}) -#include(libnaboConfig) -include_directories(${libnabo_INCLUDE_DIRS}) -set(EXTERNAL_LIBS ${EXTERNAL_LIBS} ${libnabo_LIBRARIES}) -message(STATUS "libnabo found, version ${libnabo_VERSION} (include=${libnabo_INCLUDE_DIRS} libs=${libnabo_LIBRARIES})") +set(libnabo_DIR "/usr/local/lib/cmake/libnabo" CACHE PATH "Path to libnaboConfig.cmake") +if (NOT TARGET nabo) + # Find libnabo: + find_package(libnabo REQUIRED) + if (TARGET libnabo::nabo) + message(STATUS "libnabo found, version ${libnabo_VERSION} (Config mode)") + else() + message(STATUS "libnabo found, version ${libnabo_VERSION} (include=${libnabo_INCLUDE_DIRS} libs=${libnabo_LIBRARIES})") + endif() +else() + # libnabo already part of this project (e.g. as a git submodule) + # (This, plus the use of cmake target properties in libnabo, will also + # introduce the required include directories, flags, etc.) +endif() +# This cmake target alias will be defined by either: +# a) libnabo sources if built as a git submodule in the same project than this library, or +# b) by libnabo-targets.cmake, included by find_package(libnabo) above. +# set(libnabo_LIBRARIES libnabo::nabo) #-------------------- # DEPENDENCY: OpenMP (optional) @@ -156,14 +185,16 @@ set(USE_OPEN_MP FALSE CACHE BOOL "Set to TRUE to use OpenMP") if (USE_OPEN_MP) find_package(OpenMP) if (OPENMP_FOUND) - add_definitions(-fopenmp -DHAVE_OPENMP) + if(NOT MSVC) + add_definitions(-fopenmp -DHAVE_OPENMP) + endif() set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") if (CMAKE_COMPILER_IS_GNUCC) set(EXTERNAL_LIBS ${EXTERNAL_LIBS} gomp) - message("-- OpenMP found, parallel computer enabled") - endif(CMAKE_COMPILER_IS_GNUCC) - endif(OPENMP_FOUND) -endif (USE_OPEN_MP) + message("-- OpenMP found, parallel computer enabled") + endif() + endif() +endif () #-------------------- # DEPENDENCY: OpenCL (optional) @@ -174,16 +205,16 @@ if (USE_OPEN_CL) find_library(OPENCL_LIBRARIES opencl64) if (!OPENCL_LIBRARIES) find_library(OPENCL_LIBRARIES opencl32) - endif (!OPENCL_LIBRARIES) - else (WIN32) + endif () + else () find_library(OPENCL_LIBRARIES OpenCL ENV LD_LIBRARY_PATH) - endif (WIN32) + endif () # if found, add if (OPENCL_LIBRARIES) set(EXTERNAL_LIBS ${EXTERNAL_LIBS} ${OPENCL_LIBRARIES}) - message("-- openCL found, parallel computer enabled for kd-tree") - endif (OPENCL_LIBRARIES) -endif(USE_OPEN_CL) + message("-- openCL found, parallel computer enabled for kd-tree") + endif () +endif() #-------------------- @@ -200,30 +231,26 @@ if(USE_SYSTEM_YAML_CPP) /usr/local/lib ) if(yaml-cpp_INCLUDE_DIRS AND yaml-cpp_LIBRARIES) - include_directories(${yaml-cpp_INCLUDE_DIRS}) - add_definitions(-DSYSTEM_YAML_CPP) set(yamlcpp_FOUND) - set (EXTERNAL_LIBS ${EXTERNAL_LIBS} ${yaml-cpp_LIBRARIES} ) message("-- yaml-cpp found, text-based configuration enabled") - else(yaml-cpp_INCLUDE_DIRS AND yaml-cpp_LIBRARIES) + else() message("-- yaml-cpp not found, text-based configuration and related applications disabled") - endif(yaml-cpp_INCLUDE_DIRS AND yaml-cpp_LIBRARIES) -else(USE_SYSTEM_YAML_CPP) + endif() +else() include_directories(contrib/yaml-cpp-pm/include) #note: this is not working.... #get_property(yaml-cpp-pm_INCLUDE TARGET yaml-cpp-pm PROPERTY INCLUDE_DIRECTORIES) #include_directories(${yaml-cpp-pm_INCLUDE}) - get_property(yaml-cpp-pm_LIB TARGET yaml-cpp-pm PROPERTY LOCATION) - set (EXTERNAL_LIBS ${EXTERNAL_LIBS} ${yaml-cpp-pm_LIB} ) - set (EXTRA_DEPS ${EXTRA_DEPS} yaml-cpp-pm) + list(APPEND EXTERNAL_LIBS $) + list(APPEND EXTRA_DEPS yaml-cpp-pm) set(yamlcpp_FOUND) get_property(yaml-cpp-pm_VERSION TARGET yaml-cpp-pm PROPERTY VERSION) message("-- using built-in yaml-cpp, version ${yaml-cpp-pm_VERSION}") message(" -- text-based configuration enabled") -endif(USE_SYSTEM_YAML_CPP) +endif() #-------------------- @@ -231,9 +258,6 @@ endif(USE_SYSTEM_YAML_CPP) #-------------------- # link rt support if POSIX timers are used check_symbol_exists(_POSIX_TIMERS "unistd.h;time.h" POSIX_TIMERS) -if (POSIX_TIMERS AND NOT APPLE) - set(EXTERNAL_LIBS ${EXTERNAL_LIBS} rt) -endif (POSIX_TIMERS AND NOT APPLE) #============================= end dependencies ================================= @@ -314,7 +338,7 @@ set(POINTMATCHER_SRC pointmatcher/ErrorMinimizers/PointToPointWithCov.cpp pointmatcher/ErrorMinimizers/PointToPointSimilarity.cpp pointmatcher/ErrorMinimizers/Identity.cpp -#DataPointsFilters +#DataPointsFilters pointmatcher/DataPointsFilters/Identity.cpp pointmatcher/DataPointsFilters/RemoveNaN.cpp pointmatcher/DataPointsFilters/MaxDist.cpp @@ -341,51 +365,63 @@ set(POINTMATCHER_SRC pointmatcher/DataPointsFilters/CovarianceSampling.cpp pointmatcher/DataPointsFilters/DistanceLimit.cpp pointmatcher/DataPointsFilters/RemoveSensorBias.cpp + pointmatcher/DataPointsFilters/Sphericality.cpp + pointmatcher/DataPointsFilters/Saliency.cpp + pointmatcher/DataPointsFilters/SpectralDecomposition.cpp ) -include_directories(${CMAKE_SOURCE_DIR}) - file(GLOB_RECURSE POINTMATCHER_HEADERS "pointmatcher/*.h") -# MacOS and Windows deal with shared/dynamic library differently. For -# simplicity, we only authorize static library in those cases. -if(APPLE OR WIN32) - - add_library(pointmatcher ${POINTMATCHER_SRC} ${POINTMATCHER_HEADERS} ) - install(TARGETS pointmatcher ARCHIVE DESTINATION ${INSTALL_LIB_DIR}) - -else(APPLE OR WIN32) - set(SHARED_LIBS "true" CACHE BOOL "To build shared (true) or static (false) library") - - if (SHARED_LIBS) - add_library(pointmatcher SHARED ${POINTMATCHER_SRC} ${POINTMATCHER_HEADERS}) - install(TARGETS pointmatcher - ARCHIVE DESTINATION ${INSTALL_LIB_DIR} - LIBRARY DESTINATION ${INSTALL_LIB_DIR} - RUNTIME DESTINATION ${INSTALL_BIN_DIR}) - #install(TARGETS pointmatcher LIBRARY DESTINATION ${INSTALL_LIB_DIR}) - else(SHARED_LIBS) - add_library(pointmatcher ${POINTMATCHER_SRC} ${POINTMATCHER_HEADERS} ) - install(TARGETS pointmatcher ARCHIVE DESTINATION ${INSTALL_LIB_DIR}) - endif(SHARED_LIBS) -endif(APPLE OR WIN32) - -target_include_directories(pointmatcher PRIVATE ${CMAKE_SOURCE_DIR}/pointmatcher) -target_include_directories(pointmatcher PRIVATE ${CMAKE_SOURCE_DIR}/pointmatcher/DataPointsFilters) -target_include_directories(pointmatcher PRIVATE ${CMAKE_SOURCE_DIR}/pointmatcher/DataPointsFilters/utils) - -# link all libraries to libpointmatcher -add_definitions(-Wall) -#target_link_libraries(pointmatcher ${yaml-cpp_LIBRARIES} ${libnabo_LIBRARIES}) -target_link_libraries(pointmatcher ${EXTERNAL_LIBS}) - -if(EXTRA_DEPS) + +# In CMake >=3.4 we can easily build shared libraries in Mac and Windows. +# No need to distinguish between operating systems while building targets + +add_library(pointmatcher ${POINTMATCHER_SRC} ${POINTMATCHER_HEADERS} ) + +target_include_directories(pointmatcher PUBLIC + $ + $ + $ + $ + $ +) + +if (NOT MSVC) + target_compile_options(pointmatcher PRIVATE -Wall) +else() + target_compile_options(pointmatcher PRIVATE /bigobj) +endif() + +if(yaml-cpp_INCLUDE_DIRS AND yaml-cpp_LIBRARIES) + target_link_libraries(pointmatcher PRIVATE ${yaml-cpp_LIBRARIES}) + target_include_directories(pointmatcher PRIVATE ${yaml-cpp_INCLUDE_DIRS}) +else() # embedded version: + # This could be enabled if yaml-cpp-pm was in the "export set" + #target_link_libraries(pointmatcher PRIVATE yaml-cpp-pm) + # For now, let's add yaml-cpp-pm output to EXTERNAL_LIBS +endif() + +target_link_libraries(pointmatcher PUBLIC ${Boost_LIBRARIES}) + +if (TARGET libnabo::nabo) + target_link_libraries(pointmatcher PRIVATE libnabo::nabo) +else() + include_directories(pointmatcher PUBLIC ${libnabo_INCLUDE_DIRS}) + target_link_libraries(pointmatcher PRIVATE ${libnabo_LIBRARIES}) +endif() +target_link_libraries(pointmatcher PRIVATE ${EXTERNAL_LIBS}) +if (EXTRA_DEPS) add_dependencies(pointmatcher ${EXTRA_DEPS}) -endif(EXTRA_DEPS) +endif() + +if (POSIX_TIMERS AND NOT APPLE) + target_link_libraries(pointmatcher PRIVATE rt) +endif () + set_target_properties(pointmatcher PROPERTIES VERSION "${POINTMATCHER_PROJECT_VERSION}" SOVERSION 1) -#========================= Install header =========================== +#========================= Install commands =========================== install(FILES pointmatcher/DeprecationWarnings.h @@ -399,6 +435,23 @@ install(FILES DESTINATION ${INSTALL_INCLUDE_DIR}/pointmatcher ) +install(TARGETS pointmatcher EXPORT ${PROJECT_NAME}-config + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} +) + +if(GENERATE_API_DOC) + install(FILES README.md DESTINATION share/doc/${PROJECT_NAME}) + if (DOXYGEN_FOUND) + install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/doc/html DESTINATION ${DOC_INSTALL_TARGET}) + endif () +endif() + +# Install package.xml for catkin +install(FILES package.xml DESTINATION "share/${PROJECT_NAME}") + + #========================= Documentation =========================== set(GENERATE_API_DOC false CACHE BOOL "Set to true to build the documentation using Doxygen") @@ -417,26 +470,9 @@ if(GENERATE_API_DOC) add_dependencies(pointmatcher doc) - install(FILES README.md DESTINATION share/doc/${PROJECT_NAME}) - if (DOXYGEN_FOUND) - install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/doc/html DESTINATION ${DOC_INSTALL_TARGET}) - endif (DOXYGEN_FOUND) - -else(GENERATE_API_DOC) - +else() message("-- API Documentation (doxygen): disabled") - -endif(GENERATE_API_DOC) - - -#=============== trigger other makefile ====================== - -# Example programs -add_subdirectory(examples) -# Evaluation programs -add_subdirectory(evaluations) -# Unit testing -add_subdirectory(utest) +endif() #=================== allow find_package() ========================= @@ -448,16 +484,21 @@ add_subdirectory(utest) # target_link_libraries(executableName ${libpointmatcher_LIBRARIES}) # ... -# 1- local build # +# Install cmake config module +install(EXPORT ${PROJECT_NAME}-config DESTINATION share/${PROJECT_NAME}/cmake) -# Register the local build in case one doesn't use "make install" -export(PACKAGE libpointmatcher) +# make project importable from build_dir: +export( + TARGETS pointmatcher + FILE ${CMAKE_BINARY_DIR}/${PROJECT_NAME}-config.cmake +) +add_library(${PROJECT_NAME}::${PROJECT_NAME} ALIAS pointmatcher) # Create variable for the local build tree get_property(CONF_INCLUDE_DIRS DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} PROPERTY INCLUDE_DIRECTORIES) # Create variable with the library location -get_target_property(POINTMATCHER_LIB pointmatcher LOCATION) +set(POINTMATCHER_LIB $) # Configure config file for local build tree configure_file(libpointmatcherConfig.cmake.in @@ -473,14 +514,6 @@ set(CONF_INCLUDE_DIRS ${INSTALL_INCLUDE_DIR} ${CONF_INCLUDE_DIRS} ) # because we added an include for the local yaml-cpp-pm we should also remove it list(REMOVE_ITEM CONF_INCLUDE_DIRS ${CMAKE_SOURCE_DIR} ${CMAKE_SOURCE_DIR}/contrib/yaml-cpp-pm/include) -if(SHARED_LIBS AND (NOT USE_SYSTEM_YAML_CPP)) - list(REMOVE_ITEM EXTERNAL_LIBS ${yaml-cpp-pm_LIB}) -endif(SHARED_LIBS AND (NOT USE_SYSTEM_YAML_CPP)) - -# Change the library location for an install location -get_filename_component(POINTMATCHER_LIB_NAME ${POINTMATCHER_LIB} NAME) -set(POINTMATCHER_LIB ${INSTALL_LIB_DIR}/${POINTMATCHER_LIB_NAME}) - # We put the generated file for installation in a different repository (i.e., ./CMakeFiles/) configure_file(libpointmatcherConfig.cmake.in "${PROJECT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/libpointmatcherConfig.cmake" @ONLY) @@ -530,10 +563,12 @@ install(FILES unset(LIBRARY_CC_ARGS) #====================== uninstall target =============================== -configure_file( - "${CMAKE_CURRENT_SOURCE_DIR}/cmake_uninstall.cmake.in" - "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake" - IMMEDIATE @ONLY) - -add_custom_target(uninstall - COMMAND ${CMAKE_COMMAND} -P ${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake) +if (NOT TARGET uninstall) + configure_file( + "${CMAKE_CURRENT_SOURCE_DIR}/cmake_uninstall.cmake.in" + "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake" + IMMEDIATE @ONLY) + + add_custom_target(uninstall + COMMAND ${CMAKE_COMMAND} -P ${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake) +endif() diff --git a/thirdparty/libpointmatcher/LICENSE b/thirdparty/libpointmatcher/LICENSE new file mode 100644 index 0000000..e9f1385 --- /dev/null +++ b/thirdparty/libpointmatcher/LICENSE @@ -0,0 +1,29 @@ +BSD 3-Clause License + +Copyright (c) 2010-2021, the libpointmatcher authors +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +3. Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/thirdparty/libpointmatcher/README.md b/thirdparty/libpointmatcher/README.md index cf131f1..377429e 100644 --- a/thirdparty/libpointmatcher/README.md +++ b/thirdparty/libpointmatcher/README.md @@ -1,2 +1 @@ -version 1.3.1 -git checkout 1.3.1 +git checkout 2e7a92d39573ccde8ef216dcfbd368dd520a7763 diff --git a/thirdparty/libpointmatcher/contrib/yaml-cpp-pm/CMakeLists.txt b/thirdparty/libpointmatcher/contrib/yaml-cpp-pm/CMakeLists.txt index 9497379..2689856 100644 --- a/thirdparty/libpointmatcher/contrib/yaml-cpp-pm/CMakeLists.txt +++ b/thirdparty/libpointmatcher/contrib/yaml-cpp-pm/CMakeLists.txt @@ -120,3 +120,10 @@ set_target_properties(yaml-cpp-pm PROPERTIES PROJECT_LABEL "yaml-cpp ${LABEL_SUFFIX}" ) +install(TARGETS yaml-cpp-pm EXPORT yaml-cpp-pm-targets + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} +) + +install(EXPORT yaml-cpp-pm-targets DESTINATION share/${PROJECT_NAME}/cmake) diff --git a/thirdparty/libpointmatcher/debian/changelog b/thirdparty/libpointmatcher/debian/changelog deleted file mode 100644 index 7ed70bd..0000000 --- a/thirdparty/libpointmatcher/debian/changelog +++ /dev/null @@ -1,26 +0,0 @@ -libpointmatcher (1.2.0) UNRELEASED; urgency=low - - * Add a new data filter: VoxelGrid - * Add support for PCL (Point Cloud Library) data format: PCD - * Improved *.vtk legacy format to handle UNSTRUCTURED_GRID format - * New ErrorMinimizer producing covariance matrix - * Better user documentation and tutorials - * Avoids point cloud copies when filtering - * Add CMake support for find_package - * Added support for PLY (Polygon File Format or the Stanford Triangle Format) for ascii encoding - * Improved CSV file support with import/export of selected descriptors - - -- Samuel Charreyron Fri, 20 Jun 2014 13:23:06 +0200 - -libpointmatcher (1.1.0) precise; urgency=low - - * new upstream release - - -- Stéphane Magnenat Wed, 04 Sep 2013 13:54:46 +0200 - -libpointmatcher (1.0.0) precise; urgency=low - - * new upstream release - - -- Stéphane Magnenat Mon, 12 Nov 2012 09:54:00 -0800 - diff --git a/thirdparty/libpointmatcher/debian/compat b/thirdparty/libpointmatcher/debian/compat deleted file mode 100644 index 7f8f011..0000000 --- a/thirdparty/libpointmatcher/debian/compat +++ /dev/null @@ -1 +0,0 @@ -7 diff --git a/thirdparty/libpointmatcher/debian/control b/thirdparty/libpointmatcher/debian/control deleted file mode 100644 index 8ceef80..0000000 --- a/thirdparty/libpointmatcher/debian/control +++ /dev/null @@ -1,51 +0,0 @@ -Source: libpointmatcher -Priority: extra -Maintainer: Stéphane Magnenat -Build-Depends: debhelper (>= 7.0.50~), cmake, doxygen, cdbs, libboost-all-dev, libeigen3-dev, libnabo-dev (>= 1.0.1~), yaml-cpp0.2.6-dev|libyaml-cpp-dev, libncurses5-dev -Standards-Version: 3.9.1 -Section: libs -Homepage: https://github.com/ethz-asl/libpointmatcher -Vcs-Git: git://github.com/ethz-asl/libpointmatcher.git -Vcs-Browser: https://github.com/ethz-asl/libpointmatcher - -Package: libpointmatcher-dev -Section: libdevel -Architecture: any -Depends: libpointmatcher1 (= ${binary:Version}), libnabo-dev (>= 1.0.1~), libboost-all-dev, libeigen3-dev, yaml-cpp0.2.6-dev|libyaml-cpp-dev, libncurses5-dev -Suggests: libpointmatcher-doc -Description: A modular ICP library, development headers. - libpointmatcher is a modular ICP library, useful for robotics and - computer vision. - -Package: libpointmatcher1-dbg -Section: debug -Architecture: any -Depends: libpointmatcher1 (= ${binary:Version}), ${misc:Depends} -Description: Debug symbols for libpointmatcher, a fast K Nearset Neighbor library. - libpointmatcher is a modular ICP library, useful for robotics and - computer vision. - -Package: libpointmatcher1 -Section: libs -Architecture: any -Depends: ${shlibs:Depends}, ${misc:Depends} -Description: A modular ICP library, version 1. - libpointmatcher is a modular ICP library, useful for robotics and - computer vision. - -Package: libpointmatcher-bin -Section: science -Architecture: any -Depends: libpointmatcher1 (= ${binary:Version}), ${shlibs:Depends}, ${misc:Depends} -Description: A modular ICP library, ICP executable. - libpointmatcher is a modular ICP library, useful for robotics and - computer vision. - -Package: libpointmatcher-doc -Section: doc -Architecture: all -Description: A modular ICP library, API documentation. - libpointmatcher is a modular ICP library, useful for robotics and - computer vision. - - diff --git a/thirdparty/libpointmatcher/debian/copyright b/thirdparty/libpointmatcher/debian/copyright deleted file mode 100644 index d68ae7c..0000000 --- a/thirdparty/libpointmatcher/debian/copyright +++ /dev/null @@ -1,36 +0,0 @@ -Format: http://dep.debian.net/deps/dep5 -Upstream-Name: libpointmatcher -Source: https://github.com/ethz-asl/libpointmatcher - -Files: * -Copyright: 2010--2014, François Pomerleau and Stephane Magnenat , ASL, ETHZ, Switzerland -License: BSD-3-Clause - -Files: debian/* -Copyright: 2011 Stéphane Magnenat -License: BSD-3-Clause - -License: BSD-3-Clause - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions - are met: - 1. Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - 2. Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - 3. Neither the name of the University 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 REGENTS 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 REGENTS OR CONTRIBUTORS BE LIABLE - FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS - OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) - HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY - OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF - SUCH DAMAGE. diff --git a/thirdparty/libpointmatcher/debian/libpointmatcher-bin.dirs b/thirdparty/libpointmatcher/debian/libpointmatcher-bin.dirs deleted file mode 100644 index e772481..0000000 --- a/thirdparty/libpointmatcher/debian/libpointmatcher-bin.dirs +++ /dev/null @@ -1 +0,0 @@ -usr/bin diff --git a/thirdparty/libpointmatcher/debian/libpointmatcher-bin.install b/thirdparty/libpointmatcher/debian/libpointmatcher-bin.install deleted file mode 100644 index 3cbf585..0000000 --- a/thirdparty/libpointmatcher/debian/libpointmatcher-bin.install +++ /dev/null @@ -1 +0,0 @@ -usr/bin/pmicp diff --git a/thirdparty/libpointmatcher/debian/libpointmatcher-dev.dirs b/thirdparty/libpointmatcher/debian/libpointmatcher-dev.dirs deleted file mode 100644 index fcf8fe6..0000000 --- a/thirdparty/libpointmatcher/debian/libpointmatcher-dev.dirs +++ /dev/null @@ -1,2 +0,0 @@ -usr/include -usr/lib \ No newline at end of file diff --git a/thirdparty/libpointmatcher/debian/libpointmatcher-dev.install b/thirdparty/libpointmatcher/debian/libpointmatcher-dev.install deleted file mode 100644 index b341905..0000000 --- a/thirdparty/libpointmatcher/debian/libpointmatcher-dev.install +++ /dev/null @@ -1,2 +0,0 @@ -usr/include/* -usr/lib/lib*.so diff --git a/thirdparty/libpointmatcher/debian/libpointmatcher-doc.dirs b/thirdparty/libpointmatcher/debian/libpointmatcher-doc.dirs deleted file mode 100644 index 5698c08..0000000 --- a/thirdparty/libpointmatcher/debian/libpointmatcher-doc.dirs +++ /dev/null @@ -1 +0,0 @@ -usr/share/doc \ No newline at end of file diff --git a/thirdparty/libpointmatcher/debian/libpointmatcher-doc.install b/thirdparty/libpointmatcher/debian/libpointmatcher-doc.install deleted file mode 100644 index e6c2164..0000000 --- a/thirdparty/libpointmatcher/debian/libpointmatcher-doc.install +++ /dev/null @@ -1 +0,0 @@ -usr/share/doc/libpointmatcher-doc/* diff --git a/thirdparty/libpointmatcher/debian/libpointmatcher1.dirs b/thirdparty/libpointmatcher/debian/libpointmatcher1.dirs deleted file mode 100644 index 6845771..0000000 --- a/thirdparty/libpointmatcher/debian/libpointmatcher1.dirs +++ /dev/null @@ -1 +0,0 @@ -usr/lib diff --git a/thirdparty/libpointmatcher/debian/libpointmatcher1.install b/thirdparty/libpointmatcher/debian/libpointmatcher1.install deleted file mode 100644 index d0dbfd1..0000000 --- a/thirdparty/libpointmatcher/debian/libpointmatcher1.install +++ /dev/null @@ -1 +0,0 @@ -usr/lib/lib*.so.* diff --git a/thirdparty/libpointmatcher/debian/rules b/thirdparty/libpointmatcher/debian/rules deleted file mode 100755 index 82514fe..0000000 --- a/thirdparty/libpointmatcher/debian/rules +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/make -f -# -*- makefile -*- -# Sample debian/rules that uses debhelper. -# This file was originally written by Joey Hess and Craig Small. -# As a special exception, when this file is copied by dh-make into a -# dh-make output file, you may use that output file without restriction. -# This special exception was added by Craig Small in version 0.37 of dh-make. - -# Uncomment this to turn on verbose mode. -#export DH_VERBOSE=1 - -#%: -# dh $@ - -DEB_CMAKE_EXTRA_FLAGS=-DSHARED_LIBS=true -DDOC_INSTALL_TARGET="share/doc/libpointmatcher-doc/api" - -include /usr/share/cdbs/1/rules/debhelper.mk -include /usr/share/cdbs/1/class/cmake.mk diff --git a/thirdparty/libpointmatcher/debian/source/format b/thirdparty/libpointmatcher/debian/source/format deleted file mode 100644 index 89ae9db..0000000 --- a/thirdparty/libpointmatcher/debian/source/format +++ /dev/null @@ -1 +0,0 @@ -3.0 (native) diff --git a/thirdparty/libpointmatcher/doc/ApplicationsAndPub.md b/thirdparty/libpointmatcher/doc/ApplicationsAndPub.md deleted file mode 100644 index 70d701b..0000000 --- a/thirdparty/libpointmatcher/doc/ApplicationsAndPub.md +++ /dev/null @@ -1,119 +0,0 @@ -# Applications and Publications -Here some applications and scientific publications using libpointmatcher. - -## Youtube Videos -Click on the image to play. - - -#### Mapping A Campus -- Sensor: Velodyne HDL-64E -- Application: Indoor and outdoor 3D mapping and localization - - - -#### ARTOR: Long-term 3D map maintenance in dynamic environments -- Sensor: Velodyne HDL-32E -- Application: 3D mapping and localization - - - - - - -#### NIFTi: railyard mapping -- Sensor: Sick LMS-151 -- Application: 3D mapping and localization - - - - - - -#### NIFTi: multi-floor mapping: -- Sensor: Sick LMS-151 -- Application: 3D mapping and localization - - - - - - -#### ARTOR: Navigation in urban scene -- Sensor: Velodyne HDL-32E -- Application: Navigation - - - - - - - -#### ARTOR: Mapping rough terrain -- Sensor: Velodyne HDL-32E -- Application: 3D mapping and localization - - - - - - -#### Lizhbeth: Shore mapping around lake Zurich -- Sensor: Velodyne HDL-32E -- Application: 3D mapping and localization - - - - - - - -#### BBQ modeling -- Sensor: Kinect -- Application: 3D model reconstruction - - - - - - - -#### Kinect tracker -- Sensor: Kinect -- Application: 3D mapping and localization - - - - - - - -## Publications using libpointmatcher -1. F. Pomerleau, F. Colas and R. Siegwart (2015), "A Review of Point Cloud Registration Algorithms for Mobile Robotics", Foundations and Trends® in Robotics: Vol. 4: No. 1, pp 1-104. https://doi.org/10.1561/2300000035 or [Research Gate link](https://www.researchgate.net/publication/277558596_A_Review_of_Point_Cloud_Registration_Algorithms_for_Mobile_Robotics) - -1. G. Hitz, F. Pomerleau, F. Colas, and R. Siegwart. "State Estimation for Shore Monitoring Using an Autonomous Surface Vessel." International Symposium on Experimental Robotics (ISER), 2014, 2014. - -1. P. Krüsi, B. Bücheler, F. Pomerleau, U. Schwesinger, R. Siegwart, and P. Furgale. "Lighting‐invariant Adaptive Route Following Using Iterative Closest Point Matching." Journal of Field Robotics (2014). - -1. N. Corso and A. Zakhor, “Indoor Localization Algorithms for an Ambulatory Human Operated 3D Mobile Mapping System.,” Remote Sens., vol. 5, no. 12, 2013. - -1. M. Gianni, G. Gonnelli, A. Sinha, M. Menna, and F. Pirri, “An Augmented Reality approach for trajectory planning and control of tracked vehicles in rescue environments,” Safety, Security, and Rescue Robotics (SSRR), 2013 IEEE International Symposium on, pp. 1–6, 2013. - -1. F. Pomerleau, F. Colas, R. Siegwart, and S. Magnenat, “Comparing ICP Variants on Real-World Data Sets,” Autonomous Robots, vol. 34, no. 3, pp. 133–148, Feb. 2013. - -2. F. Colas, S. Mahesh, F. Pomerleau, M. Liu, and R. Siegwart, “3D path planning and execution for search and rescue ground robots,” presented at the Intelligent Robots and Systems (IROS), 2013 IEEE/RSJ International Conference on, 2013, pp. 722–727. - -3. F. Pomerleau, M. Liu, F. Colas, and R. Siegwart, “Challenging data sets for point cloud registration algorithms,” IJRR, vol. 31, no. 14, pp. 1705–1711, Dec. 2012. - -4. F. Pomerleau, S. Magnenat, F. Colas, M. Liu, and R. Siegwart, “Tracking a depth camera: Parameter exploration for fast ICP,” presented at the Intelligent Robots and Systems, 2011. Proceedings of the IEEE/RSJ International Conference on, 2011, pp. 3824–3829. - - -**Note**: Your application or publication is not here, just fill an issue through GitHub and we will be happy to add your utilization of the library to this page! diff --git a/thirdparty/libpointmatcher/doc/ApplyingDatafilters.md b/thirdparty/libpointmatcher/doc/ApplyingDatafilters.md deleted file mode 100644 index 5699377..0000000 --- a/thirdparty/libpointmatcher/doc/ApplyingDatafilters.md +++ /dev/null @@ -1,124 +0,0 @@ -| [Tutorials Home](index.md) | [Previous](Datafilters.md) | [Next](BasicRegistration.md) | -| ------------- |:-------------:| -----:| - -# Applying Data Point Filters - -## Overview -The following will go through the steps needed to write a simple program which configures a chain of data filters and applies this chain to a point cloud. For information on data filters, refer to the [data point filters tutorial](Datafilters.md). The filtered point cloud is then saved to disk. The source code associated with this tutorial can be found in [examples/demo_cmake/convert.cpp](../examples/demo_cmake/convert.cpp). - -***IMPORTANT:*** This tutorial makes use of YAML configuration files. If you did not install yaml-cpp before installing libpointmatcher, you must do so before following these instructions. Information on installing yaml-cpp can be found in the installation instructions for [Ubuntu](Compilation.md), [Mac OS X](CompilationMac.md), and [Windows](CompilationWindows.md). - -## Source Description -First, we include the libpointmatcher and standard library header files. - -```cpp -#include "pointmatcher/PointMatcher.h" -#include -#include -#include -``` - -Next, we enter the `std` and `PointMatcherSupport` namespace scopes and declare type aliases. - -```cpp -using namespace std; -using namespace PointMatcherSupport; - -typedef PointMatcher PM; -typedef PM::DataPoints DP; -``` - -The following function displays the usage message. This program can be run with three arguments. The first is the path to a yaml configuration file, the second a path to the input point cloud, and the third is a filename to be used to save the filtered point cloud. If the first argument is omitted, the input point cloud is copied to the output point cloud. The usage message will be displayed whenever the program is run with an incorrect number of arguments. - -```cpp -void usage(char *argv[]) -{ - cerr << "Usage " << argv[0] << " [CONFIG.yaml] INPUT.csv/.vtk OUTPUT.csv/.vtk" << endl; - cerr << endl << "Example:" << endl; - cerr << argv[0] << " ../examples/data/default-convert.yaml ../examples/data/cloud.00000.vtk /tmp/output.vtk" << endl << endl; -} -``` - -Now entering inside the main function of the program: We create a logger to which warnings and errors are written. - -```cpp -setLogger(PM::get().LoggerRegistrar.create("FileLogger")); -``` -We then load the input point cloud into a new `DataPoints` object `d`. -```cppp -DP d(DP::load(argv[argc-2])); -``` - -Next, the number of arguments is checked, and we attempt to load the configuration file. If the configuration file could not be opened, an error message is printed and the program returns. If it is loaded successfully, a chain of data filters is created and represented in a `DataPointsFilters` object. The input point cloud is filtered by the chain using the `DataPointsFilters::apply(DataPoints d)` function. - -```cpp -if (argc == 4) - { - ifstream ifs(argv[1]); - if (!ifs.good()) - { - cerr << "Cannot open config file " << argv[1] << endl; - usage(argv); - return 2; - } - PM::DataPointsFilters f(ifs); - f.apply(d); - - } -``` - -Finally, the filtered point cloud is written to the location specified by the user and the program returns successfully. - -```cpp -d.save(argv[argc-1]); - -return 0; -``` - -## Configuring the Data Filters Chain -An example configuration file can be found at [examples/data/default-convert.yaml](../examples/data/default-convert.yaml). A diagram of this chain is shown in Figure 1. - -|**Figure 1**: Default chain of data filters in `default-convert.yaml`| -|---| -| ![Default Configuration Chain](images/DefaultConvertChain.png) | - - -### Bounding Box Filter -The first element is a [bounding box filter](Datafilters.md#boundingboxhead). It is configured to reject points inside a 8m x 8m x 8m cube centered at the origin. - -```yaml -- BoundingBoxDataPointsFilter: - xMin: -4.0 - xMax: 4.0 - yMin: -4.0 - yMax: 4.0 - zMin: -4.0 - zMax: 4.0 - removeInside: 1 -``` - -### Sampling Surface Normal Filter -A [sampling surface normal filter](Datafilters.md#samplingnormhead) can be used in an attempt to subsample points while maintaining the shape structure of objects in the point cloud. The point cloud is divided into boxes containing at most 10 points. Points along flat surfaces are contained in larger boxes and are sparsely sampled while points on more complex surfaces are densely sampled. - -```yaml -- SamplingSurfaceNormalDataPointsFilter: - knn: 10 -``` - -### Observation Direction Filter -The points are annotated with an observation direction pointing to the sensor location with the [observation direction filter](Datafilters.md#obsdirectionhead). - -```yaml -- ObservationDirectionDataPointsFilter -``` - -### Orient Normals Filter -The [last filter](Datafilters.md#orientnormalshead) is used to reorient normal vectors so that they point in the same direction. This filter uses the observation directions extracted by the previous filter. - -```yaml -- OrientNormalsDataPointsFilter -``` - -## Where To Go From Here -For more information on building your own configurations, refer to the tutorial on [building yaml configurations](Configuration.md). - diff --git a/thirdparty/libpointmatcher/doc/BasicRegistration.md b/thirdparty/libpointmatcher/doc/BasicRegistration.md deleted file mode 100644 index 9c4495e..0000000 --- a/thirdparty/libpointmatcher/doc/BasicRegistration.md +++ /dev/null @@ -1,116 +0,0 @@ -| [Tutorials Home](Pointclouds.md) | [Previous](Pointclouds.md) | [Next](Transformations.md) | -| ------------- |:-------------:| -----:| - -# Writing a program which performs ICP - -## Overview - -The following tutorial will go through the various steps that are performed in a basic ICP registration example. The source code associated with this tutorial can be found in [examples/icp_simple.cpp](../examples/icp_simple.cpp). - -Point cloud registration is a critical step in 3D reconstruction of objects and terrains and is used in such varied fields as robotics, medicine, and geography. - -In this example we will be performing registration between two point clouds. One is referred to as the reading cloud, and the other the reference cloud. Registration can be more more explicitly defined as finding a rigid geometric transformation that can be applied to the reading cloud such that it is most closely aligned with the reference cloud. Each point in the reading cloud can then be associated to a *closest point* in the reference cloud. The "closeness" of the alignment is most often quantified using some cost function such as the sum of mean square distances between point associations. The goal is evidently to optimize the alignment and therefore find a rigid transformation which minimizes the cost function. - -The ICP algorithm has the following characteristics: - -* The algorithm is iterative in which each iteration improves the alignment between reading and reference clouds. -* The non-ideal nature of point clouds leads to the use of data filters and outlier filters. These can be used to remove noisy or redundant points. Data filters can also augment point clouds with additional descriptors which may be useful for registration. A detailed overview of data filters can be found [here](Datafilters.md). - -The various components which comprise the ICP registration system are shown in the following diagram. - -|**Figure 1:** High level diagram of an ICP chain| -|:------| -|![Default ICP Chain Config](images/modular_cloud_matcher_icp_chain.png)| - -Firstly, the reading and reference clouds are processed using a combination of data filters so as to remove noise and augment data-points with descriptive information. The matching step associates each point in the the reading cloud with one in the reference cloud. Statistical outliers are removed by a chain of outlier filters. Subsequently, a transformation is computed by solving the cost minimization step. Transformations are verified to improve alignment at ever iteration and therefore that the process converges towards an optimal transformation. - -## A Very Simple ICP program -The program contained in `icp_simple.cpp` performs registration between point clouds using the default settings of libpointmatcher. The point clouds should be encoded in .csv files. Some example point clouds are located in the `examples/data/` directory. We will now step through and explain the code. - -The `validateArgs` function is used to ensure that exactly two arguments are supplied: the paths to the reference and reader clouds. Note that the first argument specifies the reference and the second the reader. - -```cpp -void validateArgs(int argc, char *argv[], bool& isCSV ) -{ - if (argc != 3) - { - cerr << "Wrong number of arguments, usage " << argv[0] << " reference.csv reading.csv" << endl; - cerr << "Will create 3 vtk files for inspection: ./test_ref.vtk, ./test_data_in.vtk and ./test_data_out.vtk" << endl; - cerr << endl << "2D Example:" << endl; - cerr << " " << argv[0] << " ../examples/data/2D_twoBoxes.csv ../examples/data/2D_oneBox.csv" << endl; - cerr << endl << "3D Example:" << endl; - cerr << " " << argv[0] << " ../examples/data/car_cloud400.csv ../examples/data/car_cloud401.csv" << endl; - exit(1); - } -} -``` - -The following three lines simply rename types that are used in the program into something more convenient. The `PointMatcher` base class contains all the relevant objects and functions that are used in the ICP process. The `DataPoints` class represents a point cloud. - -```cpp -typedef PointMatcher PM; -typedef PM::DataPoints DP; -typedef PM::Parameters Parameters; -``` - -We now read the reference and reader from csv files by using the `load` function, which outputs a `DataPoints` object. - -```cpp -// Load point clouds -const DP ref(DP::load(argv[1])); -const DP data(DP::load(argv[2])); -``` - -The `ICP` class represents the ICP chain shown in [Figure 1](#icp_chain_diagram). We create an object instantiation of an ICP chain and apply the default settings using `setDefault`. A view of the default ICP chain configuration is shown [here](DefaultICPConfig.md). - -```cpp -// Create the default ICP algorithm -PM::ICP icp; - -// See the implementation of setDefault() to create a custom ICP algorithm -icp.setDefault(); -``` - -The entire registration process is performed by applying the functor `TransformationParameters ICP(DataPoints ref, DataPoints data)`. The optimal transformation is stored in a TransformationParameters object. - -```cpp -// Compute the transformation to express data in ref -PM::TransformationParameters T = icp(data, ref); -``` - -We can then apply the obtained transformation to the reading cloud so that it is aligned with the reference. First we create a new `DataPoints` object to store the aligned reading cloud and then use the `apply(DataPoints out, TransformationParameters param)` to apply the alignment. - -```cpp -// Transform data to express it in ref -DP data_out(data); -icp.transformations.apply(data_out, T); -``` - -In the final step, we save the reference, reading, and aligned reading point clouds to the `examples/` directory. Note that the files are saved as .vtk files instead of .csv files so that they can be visualized with [ParaView](http://www.paraview.org/). In the final line, we display the transformation parameters in the console using the `<<` operator on the `TransformationParameters` object. - -```cpp -// Save files to see the results -ref.save("test_ref.vtk"); -data.save("test_data_in.vtk"); -data_out.save("test_data_out.vtk"); -cout << "Final transformation:" << endl << T << endl; -``` - -### Car Example -We run the example code with two 3D point clouds representing the same scene from the car dataset in `/examples/data/car_cloud400.csv` and `/examples/data/car_cloud401.csv`. - -``` -examples/icp_simple ../examples/data/car_cloud400.csv ../examples/data/car_cloud401.csv -``` -The program prints out the transformation matrix obtained by the ICP registration -``` -Final transformation: - 0.981598 0.170036 -0.0869051 0.0730435 - -0.153273 0.973006 0.17253 0.192502 - 0.113896 -0.156035 0.981163 -0.0353594 - 0 0 0 1 -``` - -|**Figure 2:** Visualization of ICP on car example. The white points correspond to the reading cloud, red to the reference, and blue to the aligned reading cloud.| -|:-----------| -|![car example](images/car_example.png)| diff --git a/thirdparty/libpointmatcher/doc/Compilation.md b/thirdparty/libpointmatcher/doc/Compilation.md deleted file mode 100644 index ac7e84b..0000000 --- a/thirdparty/libpointmatcher/doc/Compilation.md +++ /dev/null @@ -1,226 +0,0 @@ -| [Tutorials Home](index.md) | | [Next](Datafilters.md) | -| ------------- |:-------------:| -----:| - -# Compiling and Installing libpointmatcher on your Computer - -## In short... -If you are used to development projects, here is what you need: - -|Name |Version
(Tested Feb. 20, 2015) |Version
(Tested Sept. 6, 2016) | Version
(Tested Jan. 8, 2019) | -|---------------|-----------------------|-----------------------|-----------------------| -|Ubuntu | 12.04.5 LTS (64 bit) | 14.04.5 LTS (64 bit) | 18.04.1 LTS (64 bit) | -|gcc | 4.6.3 | 4.8.4 | 7.3.0 | -|git | 1.7.9.5 | 1.9.1 | 2.17.1 | -|cmake | 2.8.11.2 | 2.8.12.2 | 3.10.2 | -|doxygen (opt.) | 1.7.6.1 | 1.8.6-2 | 1.8.13-10 | -||||| -| _Dependency:_| | | -|boost | 1.48.0.2 | 1.54.0 | 1.65.1 | -|eigen | 3.0.5 | 3.2.0-8 | 3.3.4-4 | -|libnabo | [from source](https://github.com/ethz-asl/libnabo) | [from source](https://github.com/ethz-asl/libnabo) | [from source](https://github.com/ethz-asl/libnabo) | - -__Note:__ we only support 64-bit systems because of some issues with Eigen. Other versions will most probably work but you'll have to try yourself to know for sure. - -The rest of this tutorial will guide you through the different requirements step by step. - -## Detailed Installation Instructions -### Some Basic Requirements - -#### a. Installing Boost -[Boost](www.boost.org) is a widely-used C++ library and is included in most Linux distributions. You can quickly check if Boost is installed on your system by running - -``` -ldconfig -p | grep libboost -``` - -If you see a list of results then you can skip to the next section. If not, you most likely have to install Boost. - -Instructions for downloading and installing boost to Unix systems can be found [here](http://www.boost.org/doc/libs/1_55_0/more/getting_started/unix-variants.html). Boost can also be installed as a package by running - -``` -sudo apt-get install libboost-all-dev -``` - -#### b. Installing Git -[Git](http://git-scm.com/) is a version control system similar to SVN designed for collaboration on large code projects. Because libpointmatcher is hosted on Github, you should the git application to keep track of code revisions, and bug fixes pushed to the public repository. - -Git should already be installed on your system but you can check if it is by running - -``` -git --version -``` - -If Git is installed, you should see a message of the form - -``` -git version 2.17.1 -``` - -If not refer to the Git homepage for installation instructions or install via the package manager by running - -``` -sudo apt-get install git-core -``` - -#### c. Installing CMake -[CMake](http://www.cmake.org/) is a cross-platform build system and is used for building the libpointmatcher library. Refer to the homepage for installation instructions, or you can once again use the package manager - -``` -sudo apt-get install cmake cmake-gui -``` - -*NOTE:* CMake has a GUI called cmake-gui which can be useful for configuring builds. We recommend you install this as well since it will be referred to in this tutorial. - -*NOTE 2:* Some functionalities like find_package() (only useful if you intent to link with your own project) will only work if you have CMake 2.8.11 or over. On Ubuntu 12.04, only 2.8.7 is available using apt-get. If you intent to use such functionality, you will have to compile CMake from sources. - -### 1. Installing Eigen -The Eigen linear algebra library is required before installing libpointmatcher and can be found [here](http://eigen.tuxfamily.org/). Either download and compile Eigen following instructions from the package website or simply install package via apt by running: - -``` -sudo apt-get install libeigen3-dev -``` - -### 2. Installing libnabo -libnabo is a library for performing fast nearest-neighbor searches in low-dimensional spaces. It can be found [here](https://github.com/ethz-asl/libnabo). Clone the source repository into a local directory of your choice. -``` -mkdir ~/Libraries/ -cd ~/Libraries -git clone git://github.com/ethz-asl/libnabo.git -cd libnabo -``` - -Now you can compile libnabo by entering the following commands -``` -SRC_DIR=`pwd` -BUILD_DIR=${SRC_DIR}/build -mkdir -p ${BUILD_DIR} && cd ${BUILD_DIR} -cmake -DCMAKE_BUILD_TYPE=RelWithDebInfo ${SRC_DIR} -make -sudo make install -``` - -This will compile libnabo in a `/build` directory and install it on your system. - -*Note:* If Eigen or Boost are not in their regular system locations you will have to indicate their location by setting the corresponding CMake flags. - - -### 4. Compiling the Documentation (optional) -Libpointmatcher is documented directly in the source-code using [Doxygen](http://www.stack.nl/~dimitri/doxygen/). If Doxygen is installed on your system, an html version of the documentation will be compiled in `/usr/local/share/doc/libpointmatcher/`. To install Doxygen in Ubuntu, run: - -``` -sudo apt-get install doxygen -``` - -Once you have compiled libpointmatcher in step 6, you can simply open `/usr/local/share/doc/libpointmatcher/api/html/index.html` in a browser to view the API documentation. - -You will also need Latex for the rendering of equations: - -``` -sudo apt-get install texlive-full -``` - -### 5. Installing libpointmatcher -Clone the source repository into a local directory. As an example we reuse the Libraries directory that was created to contain the libnabo sources. - -``` -cd ~/Libraries/ -git clone git://github.com/ethz-asl/libpointmatcher.git -cd libpointmatcher -``` -Now, libpointmatcher is compiled into a `/build` directory. -``` -SRC_DIR=`pwd` -BUILD_DIR=${SRC_DIR}/build -mkdir -p ${BUILD_DIR} && cd ${BUILD_DIR} -cmake -D CMAKE_BUILD_TYPE=RelWithDebInfo ${SRC_DIR} -make -``` - -If you have doxygen and latex installed, you can enable the documentation using the CMake variable `GENERATE_API_DOC` to `true`. This can be achived through CMake GUI or by the command line: - -``` -cmake -D GENERATE_API_DOC=true ${SRC_DIR} -``` - -You can optionally verify that the version of libpointmatcher you have compiled is stable by running the unit tests. -``` -utest/utest --path [libpointmatcher root]/examples/data/ -``` - -Finally, to install libpointmatcher to your system run the following: -``` -sudo make install -``` - -#### Possible Caveats -If Eigen, libnabo, yaml-cpp are not found during the installation, you will have to manually supply their installation locations by setting the CMake flags. You can do so using the CMake GUI. - -``` -cd build -cmake-gui . -``` -![alt text](images/cmake_screenshot.png "Screenshot of CMake GUI") - - -You can then set `EIGEN_INCLUDE_DIR`, `NABO_INCLUDE_DIR`, `NABO_LIBRARY`, `yaml-cpp_INCLUDE_DIRS`, `yaml-cpp_LIBRARIES` to point to your installation directories as shown in the screenshot above. Then, generate the make files by clicking generate and rerun the following inside `/build`: -``` -make -sudo make install -``` - -# Having problems? -Some dependencies changed and we don't keep track of all combinations possible. Before reporting a problem, make sure to include the versions you are using. You can run the bash script `./utest/listVersionsUbuntu.sh` and copy-paste its output when [reporting an issue on github](https://github.com/ethz-asl/libpointmatcher/issues). You may need to ensure that the file is executable: - -``` -chmod +x ./utest/listVersionsUbuntu.sh -./utest/listVersionsUbuntu.sh -``` - - -Here are the list of useful commands used in the bash script: - -Ubuntu version: - - lsb_release -r - -32-bit or 64-bit architecture: - - getconf LONG_BIT - -Compiler version: - - gcc --version - -Git version: - - git --version - -CMake: - - cmake --version - -Boost version: - - dpkg -s libboost-dev | grep Version - -Eigen3: - - dpkg -s libeigen3-dev | grep Version - -Doxygen: - - dpkg -s doxygen | grep Version diff --git a/thirdparty/libpointmatcher/doc/CompilationMac.md b/thirdparty/libpointmatcher/doc/CompilationMac.md deleted file mode 100644 index 541340d..0000000 --- a/thirdparty/libpointmatcher/doc/CompilationMac.md +++ /dev/null @@ -1,209 +0,0 @@ -| [Tutorials Home](index.md) | | [Next](Datafilters.md) | -| ------------- |:-------------:| -----:| - -# Compiling and Installing libpointmatcher on your Computer (Mac OS X Instructions) - - -## In short... -If you are used to development project, here is what you need: - -|Name |Version
(Tested Feb. 16, 2015) | -|---------------|-----------------------| -|MacOS | 10.10.2 | -|Xcode | todo | -|gcc | 4.2.1 | -|brew | 0.9.5 | -|git | 1.9.3 | -|cmake | 3.0.2 | -|doxygen (opt.) | 1.8.9.1 | -| | | -|_Dependency:_ || -|boost | 1.57.0 | -|eigen | 3.2.4 | -|libnabo | [from source](https://github.com/ethz-asl/libnabo) | - - -__Note:__ Other versions will most probably work but you'll have to try yourself to know for sure. - -The rest of this tutorial will guide you through the different requirements step by step. - -### Some Basic Requirements -#### a. Installing Xcode via the App Store (OS X 10.10.2 and later) -Mac OS X does not come with a built-in C++ command-line compiler. You must therefore install XCode by visiting the App Store. - -Once Xcode is installed on your machine, launch it. Navigate to preferences, to the downloads tab. In the components list, install the Command Line Tools component. - -You should now have a working version of gcc. You can check by running the following command in your terminal: - - gcc --version - -A message similar to the following should appear - - Configured with: --prefix=/Applications/Xcode.app/Contents/Developer/usr --with-gxx-include-dir=/usr/include/c++/4.2.1 - Apple LLVM version 6.0 (clang-600.0.56) (based on LLVM 3.5svn) - Target: x86_64-apple-darwin14.1.0 - Thread model: posix - -#### b. Installing Homebrew -Because Mac OS X does not come with a built-in package manager like in Ubuntu, you need to install one on your own. A package manager is handy because it allows you to install, uninstall, update and maintain software packages with ease. There are several possibilities including [Macports](http://www.macports.org/) and [Homebrew](http://brew.sh/). While both are good options, we have a slight preference for homebrew which is easier to use. - -You do not need a package manager to install libpointmatcher, but it simplifies things. The following instructions will make use of homebrew and will thus assume that it is installed on your system. - -Installing Homebrew is extremely easy and can be done by entering the following single command in your terminal - -``` -ruby -e "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install)" -``` -Once the scripts finishes installing, you are good to go! - -#### c. Installing Boost -[Boost](www.boost.org) is a widely-used C++ library and is included in most Linux distributions. Mac OS X does not ship with Boost so if you have never used it before, you probably need to install it. You can install the latest version of boost with the following homebrew command: - - brew install boost - -#### d. Installing Git -[Git](http://git-scm.com/) is a version control system similar to SVN designed for collaboration on large code projects. Because libpointmatcher is hosted on Github, you should the git application to keep track of code revisions, and bug fixes pushed to the public repository. - -After installing the Xcode Command Line Tools, Git should already be installed on your system but you can check that it is there by running - -``` -git --version -``` -If Git is installed, you should see a message of the form -``` -git version 1.8.3.2 -``` -If not refer to the Git homepage for installation instructions or install via homebrew by running -``` -brew install git -``` -#### e. Installing CMake -[CMake](http://www.cmake.org/) is a cross-platform build system and is used for building the libpointmatcher library. Refer to the homepage for installation instructions, or you can once again use homebrew - - brew install cmake - -### 1. Installing Eigen -The Eigen linear algebra is required before installing libpointmatcher and can be found [here](http://eigen.tuxfamily.org/). Either download and compile Eigen following instructions from the package website or simply install the package via homebrew by running: - - brew install eigen - -### 2. Compiling the Documentation (optional) -Libpointmatcher is documented directly in the source-code using [Doxygen](http://www.stack.nl/~dimitri/doxygen/). If Doxygen is installed on your system, an html version of the documentation will be compiled in `/usr/local/share/doc/libpointmatcher/`. To install Doxygen in Ubuntu, run: - - brew install doxygen - -Once you have compiled libpointmatcher in step 6, you can simply open `/usr/local/share/doc/libpointmatcher/api/html/index.html` in a browser to view the API documentation. - -### 3. Installing libnabo -libnabo is a library for performing fast nearest-neighbor searches in low-dimensional spaces. It can be found [here](https://github.com/ethz-asl/libnabo). Clone the source repository into a local directory of your choice. - - mkdi r ~/Libraries/ - cd ~/Libraries - git clone git://github.com/ethz-asl/libnabo.git - cd libnabo - - -Now you can compile libnabo by entering the following commands - - SRC_DIR=`pwd` - BUILD_DIR=${SRC_DIR}/build - mkdir -p ${BUILD_DIR} && cd ${BUILD_DIR} - cmake -DCMAKE_BUILD_TYPE=RelWithDebInfo ${SRC_DIR} - make - - -To make sure that everything is working properly, run the unit tests: - - make test - -This will run multiple nearest-neighbor searches performances and may take some minutes. - - sudo make install - -*Note:* If Eigen or Boost are not in their regular system locations you will have to indicate their location by setting the corresponding CMake flags. You can use the following command to default flags: - - ccmake . - - - - -### 4. Installing libpointmatcher -Clone the source repository into a local directory. As an example we reuse the Libraries directory that was created to contain the libnabo sources. - - cd ~/Libraries/ - git clone git://github.com/ethz-asl/libpointmatcher.git - cd libpointmatcher - -Now, libpointmatcher is compiled into a `/build` directory. - - SRC_DIR=`pwd` - BUILD_DIR=${SRC_DIR}/build - mkdir -p ${BUILD_DIR} && cd ${BUILD_DIR} - cmake -DCMAKE_BUILD_TYPE=RelWithDebInfo ${SRC_DIR} - make - - -You can optionally verify that the version of libpointmatcher you have compiled is stable by running the unit tests. - - utest/utest --path ../examples/data/ - - -Finally, to install libpointmatcher to your system run the following: - - sudo make install - - -#### Possible Caveats -If Eigen, libnabo, yaml-cpp, or GTest are not found during the installation, you will have to manually supply their installation locations by setting the CMake flags. You can do so using the ccmake tool. -``` -cd build -ccmake .. -``` - -You can then set `EIGEN_INCLUDE_DIR`, `NABO_INCLUDE_DIR`, `NABO_LIBRARY`, `yaml-cpp_INCLUDE_DIRS`, `yaml-cpp_LIBRARIES` to point to your installation directories as shown in the screenshot above. Then, generate the make files by clicking generate and rerun the following inside `/build`: -``` -make -sudo make install -``` - -# Having problems? - -Some dependencies changed and we don't keep track of all combinations possible. Before reporting a problem, make sure to include the versions you are using. - -Here are useful commands for the different version: - -MacOS version: - - sw_vers -productVersion - -Compiler version: - - gcc --version - -Homebrew: - - brew --version - -Boost: - - brew info boost - -Git: - - git --version - -CMake: - - cmake --version - -Eigen: - - brew info eigen - -Doxygen: - - brew info doxygen - - - - diff --git a/thirdparty/libpointmatcher/doc/CompilationWindows.md b/thirdparty/libpointmatcher/doc/CompilationWindows.md deleted file mode 100644 index 8ea9ac6..0000000 --- a/thirdparty/libpointmatcher/doc/CompilationWindows.md +++ /dev/null @@ -1,123 +0,0 @@ -| [Tutorials Home](index.md) | | [Next](Datafilters.md) | -| ------------- |:-------------:| -----:| - -# Compiling and Installing libpointmatcher on Windows - -## Compiling using MSVC (Microsoft Visual Studio) - -### In Short... - -If you are used to development project, here is what you need: - - -| Name | Link | Version
(Tested December 29, 2018)| -| ------ | ---- | ------------- | -| Windows | | 10 | -| git | | v2.20.1 | -| libpointmatcher sources | | | -| libnabo sources | | | -| Visual Studio | | Visual Studio 2017 15.9.4 | -| CMake | | v3.13.2 | -| Eigen 3 | | v3.3.7 | -| Boost | | v1.69.0 | - -The rest of this tutorial will guide you through the different requirements step by step. - -### Building Boost -1. Open a console that knows the path to the MSVC compiler command (cl). We suggest using **Windows PowerShell**. An alternative is **Developer Command Prompt**, which can be located in the Start menu in the Visual Studio section. -1. Go to your Boost source directory, and do: - - ``` - $ .\bootstrap.bat - $ .\b2.exe install --prefix=build address-model=64 - ``` - -1. It may take a while to finish. - - -### Build libnabo -You may need to install grep to build libnabo. You can get the Windows version [here](http://gnuwin32.sourceforge.net/packages/grep.htm). - -1. Start **CMake GUI** - -1. Add the path of your libnabo source folder in the field _Where is the source code_. -1. Add a folder named build in the field _Where to build the binary_. This will allow you to do out-of-source compilation. -1. Click on the button Configure - 1. Select the generator for the project (Visual Studio 15 2017 Win64) - 1. Typically you will select "Use default native compilers" for the generator - 1. Click "Finish" - 1. An error will be reported, because CMake does not know yet where to find the libraries. The next steps will tell it where to find them. - -1. Locate _your eigen folder_ in the field **EIGEN_INCLUDE_DIR** - -1. Add the following boolean variable and set it to `true`: **Boost_USE_STATIC_LIBS** - -1. Add the following PATH variable and set it to _(your boost folder)_/build: **BOOST_ROOT** - -1. Change the variable **CMAKE_CONFIGURATION_TYPES** to `RelWithDebInfo` - -1. Click on the button Configure, then on Generate. Here is an example of what your CMake should look like: - - ![alt text](images/win_cmake_libnabo.png "CMake libnabo") - - -1. Locate the Microsoft Visual Studio Solution file (libnabo.sln) in your build folder and open it. Visual Studio should open. - -1. Build the solution: BUILD -> Build Solution - - Alternatively, you can build the solution from the command line. In _(your libnabo folder)_/build: - - ``` - $ msbuild /m:2 libnabo.sln - ``` - - (Note that the flag /m:X defines the number of cores msbuild will use while building the solution.) - - -### Build libpointmatcher -1. Start **CMake GUI**, follow the same steps to configure the source and build folders for _libpointmatcher_, then click the Configure button. - -1. Locate _your eigen folder_ in the field **EIGEN_INCLUDE_DIR** - -1. Add the following boolean variable and set it to `true`: **Boost_USE_STATIC_LIBS** - -1. Add the following PATH variable and set it to _(your Boost folder)_/build: **BOOST_ROOT** - -1. Add the following PATH variable and set it to _(your libnabo source folder)_: **NABO_INCLUDE_DIR** - -1. Add the following FILEPATH variable and set it to _(your libnabo source folder)_/build/RelWithDebInfo/nabo.lib: **NABO_LIBRARY** - -1. Change the variable **CMAKE_CONFIGURATION_TYPES** to `RelWithDebInfo` - -1. Click on the button Configure, then on Generate. Here is an example of what your CMake should look like: - - ![alt text](images/win_cmake_libpointmatcher.png "CMake libpointmatcher") - -1. In Visual Studio, build the solution: BUILD -> Build Solution - - Alternatively, you can build the solution from the command line. In _(your libpointmatcher folder)_/build: - - ``` - $ msbuild /m:2 libpointmatcher.sln - ``` - - (Note that the flag /m:X defines the number of cores msbuild will use while building the solution.) - - -## Reporting Issues - -Currently, we don't have a developer fully supporting compilation on Windows. If you can help refreshing this documentation, your help is more than welcome. - -Before reporting new building issues, have a look in the current/past list of issues. Add as much details as you can since you will most probably receive answers from developers that cannot reproduce the problem on their side. Here are some of them: - -- Your directory structure need to be well organized as mention in [Issue #136](https://github.com/ethz-asl/libpointmatcher/issues/136). -- There might be some problems related to libnabo as mention in [Issue #128](https://github.com/ethz-asl/libpointmatcher/issues/118). - -## Special Thanks - -Special thanks to the following users in helping us with the Windows support: - -- [kwill](https://github.com/kwill) for keeping the documentation up-to-date and investing time to make libpointmatcher compiling on Windows. -- [braddodson](https://github.com/braddodson) for porting a version of libpointmacher in `C#` with a limited set of features. The code can be found here: https://github.com/braddodson/pointmatcher.net - - diff --git a/thirdparty/libpointmatcher/doc/Configuration.md b/thirdparty/libpointmatcher/doc/Configuration.md deleted file mode 100644 index 67f245c..0000000 --- a/thirdparty/libpointmatcher/doc/Configuration.md +++ /dev/null @@ -1,81 +0,0 @@ -| [Tutorials Home](index.md) | [Previous](BasicRegistration.md) | [Next](ImportExport.md) | -| ------------- |:-------------:| -----:| - -# Creating Custom Configurations with YAML - -## Overview -The implementation of the ICP algorithm in libpointmatcher is modular and can be tailored to the user's needs by writing custom configurations. Configurations in libpointmatcher are defined in YAML files. Very briefly, [YAML](http://www.yaml.org/) is a document format which allows data to be written in a way which is both readable by a program and by a human. For a more detailed treatment of the language, refer to the [project's specification page](http://www.yaml.org/spec/1.2/spec.html). - -## Configuration of a Chain of DataPointsFilters -The first libpointmatcher object that can be constructed by YAML files is `DataPointsFilters` which represents a chain of data filters. The configuration is loaded by calling its constructor with a string representing the path to the configuration file as an argument. The configuration file is structured as follows: - -The configuration is represented in YAML as a list. Each filter represents a list entry and is included by preceding its name by a dash -. The parameters for each filter are stored in a dictionary with each parameter entry taking the form `: `. When a parameter is not specified, the default values are used. - -```yaml -- DataPointsFilter1 - param1: param1Value - param2: param2Value -- DataPointsFilter2 -``` - -Note that the order in which filters are included is important. The first reason is that each filtering step alters the point cloud and the order in which each filtering step is done is important. The second reason is that some filters require descriptors. The filters generating these descriptors must thus be included further up the chain. For more information on the different data filters available in libpointmatcher, their parameters and requirements, refer to the [data filters tutorial](Datafilters.md). - -### Using a Configuration in Your Code -To load an data filters configuration from a YAML file, use the `PointMatcher::DataPointsFilters(std::istream& in)` constructor where `in` represents a `std::istream` to your YAML file. - -## Configuration of an ICP Chain - -![default config](images/default_icp_chain.png) - -**Figure:** Modules comprising the default ICP chain - -In the [basic registration tutorial](BasicRegistration.md), we discussed the configuration of a simple ICP chain configuration using a YAML configuration file. An ICP chain is represented in YAML as a dictionary where each entry refers to a module of the chain. A module is any of the following: - -* Reading data filter chain -* Reference data filter chain -* Matcher -* Outlier filter chain -* Error minimizer -* Transformation checker chain -* Inspector -* Logger - -We include a module in the YAML file with the following syntax -```yaml -moduleName: - componentName: - paramName: paramValue -``` - -Several modules including readingDataPointsFilters, referenceDataPointsFilters, outlierFilters and transformationCheckers may contain several components. These are stored as a list as shown in the configuration of a chain of DataPointsFilters. In this case a module has the following syntax: -```yaml -moduleName: - - component1Name: - paramName: paramValue - - component2Name: - paramName: paramValue -``` -Below find a list of modules and their possible configurations: - -| Module Name | Possible Components | Default Components | Is a List | -|:------------|:--------------------|:-------------------|:----------| -|readingDataPointsFilters| BoundingBoxDataPointsFilter
FixStepSamplingDataPointsFilter
MaxDensityDataPointsFilter
MaxDistDataPointsFilter
MaxPointCountDataPointsFilter
MaxQuantileOnAxisDataPointsFilter
MinDistDataPointsFilter
ObservationDirectionDataPointsFilter
OrientNormalsDataPointsFilter
RandomSamplingDataPointsFilter
RemoveNaNDataPointsFilter
SamplingSurfaceNormalDataPointsFilter
ShadowDataPointsFilter
SimpleSensorNoiseDataPointsFilter
SurfaceNormalDataPointsFilter | RandomSamplingDataPointsFilter | Yes | -|referenceDataPointsFilters| BoundingBoxDataPointsFilter
FixStepSamplingDataPointsFilter
MaxDensityDataPointsFilter
MaxDistDataPointsFilter
MaxPointCountDataPointsFilter
MaxQuantileOnAxisDataPointsFilter
MinDistDataPointsFilter
ObservationDirectionDataPointsFilter
OrientNormalsDataPointsFilter
RandomSamplingDataPointsFilter
RemoveNaNDataPointsFilter
SamplingSurfaceNormalDataPointsFilter
ShadowDataPointsFilter
SimpleSensorNoiseDataPointsFilter
SurfaceNormalDataPointsFilter | SamplingSurfaceNormalDataPointsFilter | Yes | -|matcher | KDTreeMatcher
KDTreeVarDistMatcher | KDTreeMatcher | No | -| outlierFilters | MaxDistOutlierFilter
MedianDistOutlierFilter
MinDistOutlierFilter
SurfaceNormalOutlierFilter
TrimmedDistOutlierFilter
VarTrimmedDistOutlierFilter | TrimmedDistOutlierFilter | Yes | -| errorMinimizer | IdentityErrorMinimizer
PointToPlaneErrorMinimizer
PointToPointErrorMinimizer | PointToPlaneErrorMinimizer | No | -| transformationCheckers | BoundTransformationChecker
CounterTransformationChecker
DifferentialTransformationChecker | CounterTransformationChecker
DifferentialTransformationChecker | Yes | -| inspector | NullInspector
PerformanceInspector
VTKFileInspector | NullInspector | No| -| logger | NullLogger
FileLogger | NullLogger | No | - -### Using a Configuration in Your Code -To load an ICP configuration from a YAML file, use the `PointMatcher::ICPChainBase::loadFromYaml(std::istream& in)` function where `in` represents a `std::istream` to your YAML file. - -## Where To Go From Here -Now that you have the tools to configure your own ICP chain, we recommend that you make a copy of the default configuration file located at [examples/data/default.yaml](../examples/data/default.yaml). For example: - -`cp examples/data/default.yaml my_config.yaml` - -You can now make changes to the configuration in `my_config.yaml` and experiment with various ICP chain configurations. Refer back to the [basic registration tutorial](BasicRegistration.md) for more information on loading a configuration file and performing basic registration. - - diff --git a/thirdparty/libpointmatcher/doc/DataPointsFilterDev.md b/thirdparty/libpointmatcher/doc/DataPointsFilterDev.md deleted file mode 100644 index 865d686..0000000 --- a/thirdparty/libpointmatcher/doc/DataPointsFilterDev.md +++ /dev/null @@ -1,477 +0,0 @@ -| [Tutorials Home](index.md) | [Previous](Transformations.md) | [Next](TransformationDev.md) | -| ------------- |:-------------:| -----:| - -# Creating a DataPointsFilter - -In the following tutorials we will discuss how you can extend the functionality provided in _libpointmatcher_ by taking advantage of its modular design. The following tutorial will detail the development of a a new data filter, which is as of yet not included in libpointmatcher. You may wish to develop customized DataPointFilters, Transformations, OutlierFilters which best fit your project. However, if you believe that your own contributions would benefit a larger user base, please contact us to see how we can integrate them into libpointmatcher. - -## Generic procedure - -For a more detailed procedure or if it's the first time developping a filter, please see the example of the [VoxelGrid filter](#voxelgridhead). Here, to implement a _Dummy_ filter we have to follow these steps: - -1. Create files in the [pointmatcher/DataPointsFilters/](/pointmatcher/DataPointsFilters/) folder - - the header : `Dummy.h` - - the implementation file : `Dummy.cpp` -1. Declare your filter in the header with the minimal following interface: - ```cpp - template - struct DummyDataPointsFilter : public PointMatcher::DataPointsFilter - { - typedef PointMatcherSupport::Parametrizable P; - typedef P::Parameters Parameters; - typedef P::ParameterDoc ParameterDoc; - typedef P::ParametersDoc ParametersDoc; - - typedef typename PointMatcher::DataPoints DataPoints; - - inline static const std::string description() - { - return "description"; - } - inline static const ParametersDoc availableParameters() - { - return boost::assign::list_of - ( "param", "param desc", "default value", "lower bound", "upper bound", &P::Comp ) - ; - } - - DummyDataPointsFilter(const Parameters& params = Parameters()); - virtual ~DummyDataPointsFilter() {}; - virtual DataPoints filter(const DataPoints& input); - virtual void inPlaceFilter(DataPoints& cloud); - }; - ``` -1. Implement the filter in the `.cpp` file and declare the template at the end of the file as follow: - ```cpp - template struct DummyDataPointsFilter; - template struct DummyDataPointsFilter; - ``` -1. Declare the filter in [pointmatcher/DataPointsFiltersImpl.h](/pointmatcher/DataPointsFiltersImpl.h) as follow: - ```cpp - #include "DataPointsFilters/Dummy.h" - template - struct DataPointsFiltersImpl - { - /* other filters declaration */ - /* our declaraction -> */ typedef ::DummyDataPointsFilter DummyDataPointsFilter; - }; - ``` -1. Add it to the _Registry_ [pointmatcher/Registry.cpp](/pointmatcher/Registry.cpp) - - If the filter has some parameters: - ```cpp - ADD_TO_REGISTRAR(DataPointsFilter, DummyDataPointsFilter, typename DataPointsFiltersImpl::DummyDataPointsFilter) - ``` - - If not: - ```cpp - ADD_TO_REGISTRAR_NO_PARAM(DataPointsFilter, DummyDataPointsFilter, typename DataPointsFiltersImpl::DummyDataPointsFilter) - ``` -1. Finally, add the source file in the [CMakeLists.txt](/CMakeLists.txt) in the `POINTMATCHER_SRC` variable. - - -## The Voxel Grid Filter -The filter we wish to implement today is a voxel grid filter. The latter falls into the class of *down-sampling filters*, in that it reduces the number of points in a cloud, as opposed to *descriptive filters* which add information to the points. - -The voxel grid filter down-samples the data by taking a spatial average of the points in the cloud. In the 2D case, one can simply imagine dividing the plane into a regular grid of rectangles. While the term is more suited to 3D spaces, these rectangular areas are known as *voxels*. The sub-sampling rate is adjusted by setting the voxel size along each dimension. The set of points which lie within the bounds of a voxel are assigned to that voxel and will be combined into one output point. - -There are two options as to how to represent the distribution of points in a voxel by a single point. In the first, we take the centroid or spatial average of the point distribution. In the second, we simply take the geometrical center of the voxel. Clearly, the first option is more accurate since it takes into account the point distribution inside the voxels. However it is more computationally intensive since the centroid must be computed for each voxel. The computational cost increases linearly with the number of points in the cloud and the number of voxels. - -In the following figure we show the application of a 2D voxel filter over a 2D point cloud containing uniformly dispersed points. We divide each axis into 5 regions resulting in 25 voxels. The points are down-sampled by taking the centroid of the points within each voxel. The centroids are shown in red asterisks. The centers of the voxels are shown in green squares. - -|**Figure 1:** A 2D Voxel Grid with red stars representing the voxel centroids | -|:---| -|![2dvoxelgrid](images/2dvxgrid.png)| - -## Implementation as a DataPointsFilter - -### Overview -We will now implement the voxel grid within the framework of libpointmatcher. Our implementation of the voxel grid filter will support 2D and 3D data and will be parametrized to support different voxel sizes and both down-sampling methods mentioned above. - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|vSizeX |Size of the voxel along the x-axis | 1.0 | ]0 ; +inf[| -|vSizeY |Size of the voxel along the y-axis | 1.0 | ]0 ; +inf[| -|vSizeZ |Size of the voxel along the z-axis | 1.0 | ]0 ; +inf[| -|useCentroid|If 1, down-sample by using the centroid of each voxel. If 0, use the voxel center | 1 | 1 or 0| -|averageExistingDescriptors|If 1, descriptors are down-sampled by taking their average in the voxel. If 0, we use the descriptors from the first point found in the voxel | 1 | 1 or 0| - -### Declaration - -The implementations of data point filters are declared in [pointmatcher/DataPointsFilters/](/pointmatcher/DataPointsFilters/). In this folder, we add a new header and source file to implement our filter: for instance, here we create the file [pointmatcher/DataPointsFilters/VoxelGrid.h](/pointmatcher/DataPointsFilters/VoxelGrid.h). In this file, we declare a new templated struct called `VoxelGridDataPointsFiler`. This class is derived from the general class `PointMatcher::DataPointsFilter` so as to inherit pure virtual methods and functionality that are common to all data point filters. - -**Note:** *Libpointmatcher is a templated library and supports data of either float or double types. This allows users the flexibility of selecting between two levels of precision depending on the requirements of their application. As a result, classes which are added to libpointmatcher should be templated so as to support both types.* - -```cpp -template -struct VoxelGridDataPointsFilter : public PointMatcher::DataPointsFilter -``` - -In order to register the voxel grid filter as a parameterizable module in libpointmatcher we must define the two following static functions: - -```cpp -inline static const std::string description() - { - return "Construct Voxel grid of point cloud. Down-sample by taking centroid or center of grid cells./n"; - } -``` - -This function should return a string containing a short description of what the filter does. The description will be printing when listing available modules in libpointmatcher. - -```cpp -inline static const ParametersDoc availableParameters() - { - return boost::assign::list_of - ( "vSizeX", "Dimension of each voxel cell in x direction", "1.0", "-inf", "inf", &P::Comp ) - ( "vSizeY", "Dimension of each voxel cell in y direction", "1.0", "-inf", "inf", &P::Comp ) - ( "vSizeZ", "Dimension of each voxel cell in z direction", "1.0", "-inf", "inf", &P::Comp ) - ( "useCentroid", "If 1 (true), down-sample by using centroid of voxel cell. If false (0), use center of voxel cell.", "1", "0", "1", P::Comp ) - ( "averageExistingDescriptors", "whether the filter average the descriptor values in a voxel or use a single value", "1", "0", "1", &P::Comp ) - ; - } -``` -This function should return the list of parameters or settings used by this filter. The parameters are stored in a struct called `ParameterDoc`. A parameter is defined by providing: - -1. A string with the name of the parameter in camelcase -2. A string containing the description of the parameter -3. A string containing the default value of this parameter -4. If the bounds are checked, a string containing the minimum value of this parameter -5. If the bounds are checked, a string containing the maximum value of this parameter -6. If the parameter contains a non-standard type, the pointer to a comparison function for the parameter values - -One can use the boost convenience function `boost::assign::list_of` to define a parameter in one line of c++. We define a constructor taking as argument a list of parameters. These parameters are stored in the voxel grid filter member variables. - -```cpp -VoxelGridDataPointsFilter(const Parameters& params); -const T vSizeX; -const T vSizeY; -const T vSizeZ; -const bool useCentroid; -const bool averageExistingDescriptors; -``` - -For convenience, we declare a `Voxel` struct which will contain the following two pieces of information about a voxel: - -```cpp -struct Voxel { - unsigned int numPoints; - unsigned int firstPoint; - Voxel() : numPoints(0), firstPoint(0) {} - }; -``` - -1. `numPoints` : The total number of points contained in a voxel -2. `firstPoint`: The index of the first point contained in a voxel (corresponding column of the DataPoints object) - -`DataPointsFilter` contains two pure virtual functions which we must define in order to complete the implementation of our filter. - -```cpp -virtual DataPoints filter(const DataPoints& input); -virtual void inPlaceFilter(DataPoints& cloud); -``` - -The `filter` function performs the filter operation on the input point cloud and returns the down-sampled point cloud. This function in fact calls the `inPlaceFilter` function which performs the filtering operation by directly modifying the input point cloud. The use of an "in place filter" may be preferable if we do not need to keep an intact copy of the input as we do not need to create a new point cloud to hold the output and the memory footprint is thus lower. This can make a difference when operating on large point clouds with many voxels. - -### Implementation of the Filter - -The implementation of the filter must be in the file [pointmatcher/DataPointsFilters/VoxelGrid.cpp](/pointmatcher/DataPointsFilters/VoxelGrid.cpp) that should also be added to the [CMakelists.txt](/CMakelists.txt) in the `POINTMATCHER_SRC` variable. - -The steps performed by the filter are all contained in the `inPlaceFilter` function. Because the voxel grid filter does not sub-sample points from the input but rather creates new points, we use the following strategy for performing in place filtering. - -1. **Voxel Assignment**
We pass through the input point cloud and assign each point to a voxel while recording the number of points contained in each voxel. We record the index of the first point that is assigned to a given voxel. This point will be modified to contain the down-sampled point representing the voxel. - -2. **Voxel Point Computation**
-*Centroid Downsampling*
-a) Make a second pass through the input cloud and compute the sum of point positions in each given voxel. This sum is stored in the place of the first point of a voxel. If the descriptors are to be averaged, we store their sum in the place of the first point's descriptors. -
-b) The first points containing the summed points are normalized by the number of points in the voxel. Similarly, the descriptors are normalized by the number of points. If a voxel does not contain any points, it is discarded.
-*Center Downsampling*
-a) If we wish to keep an average of the descriptors, we need to make an extra pass through the data to sum up the descriptors. The first points are replaced by the center of the voxels and the descriptors are normalized. - -3. **Point Cloud Truncation**
The down-sampled points to be kept are sorted by index, and are moved to the beginning of the point cloud. The latter is then truncated to only contain the down-sampled points. - -#### Initiation -```cpp -const int numPoints(cloud.features.cols()); -const int featDim(cloud.features.rows()); -const int descDim(cloud.descriptors.rows()); - -assert (featDim == 3 || featDim == 4); - -int insertDim(0); -if (averageExistingDescriptors) -{ - for(unsigned int i = 0; i < cloud.descriptorLabels.size(); i++) - insertDim += cloud.descriptorLabels[i].span; - if (insertDim != descDim) - throw InvalidField("VoxelGridDataPointsFilter: Error, descriptor labels do not match descriptor data"); -} - -``` -In the initiation phase we obtain the number of points, the feature and descriptor dimensions from the input point cloud. We check also check that the descriptor fields are valid. - -#### 1. Voxel Assignment -```cpp -// Calculate number of divisions along each axis -Vector minValues = cloud.features.rowwise().minCoeff(); -Vector maxValues = cloud.features.rowwise().maxCoeff(); - -T minBoundX = minValues.x() / vSizeX; -T maxBoundX = maxValues.x() / vSizeX; -T minBoundY = minValues.y() / vSizeY; -T maxBoundY = maxValues.y() / vSizeY; -T minBoundZ = 0; -T maxBoundZ = 0; - -if (featDim == 4) -{ - minBoundZ = minValues.z() / vSizeZ; - maxBoundZ = maxValues.z() / vSizeZ; -} - -// number of divisions is total size / voxel size voxels of equal length + 1 -// with remaining space -unsigned int numDivX = 1 + maxBoundX - minBoundX; -unsigned int numDivY = 1 + maxBoundY - minBoundY;; -unsigned int numDivZ = 0; - -// If a 3D point cloud -if (featDim == 4 ) - numDivZ = 1 + maxBoundZ - minBoundZ; - -unsigned int numVox = numDivX * numDivY; -if ( featDim == 4) - numVox *= numDivZ; - -// Assume point cloud is randomly ordered -// compute a linear index of the following type -// i, j, k are the component indices -// nx, ny number of divisions in x and y components -// idx = i + j * nx + k * nx * ny -std::vector indices(numPoints); - -// vector to hold the first point in a voxel -// this point will be ovewritten in the input cloud with -// the output value -std::vector* voxels; - -// try allocating vector. If too big return error -try { - voxels = new std::vector(numVox); -} catch (std::bad_alloc&) { - throw InvalidParameter((boost::format("VoxelGridDataPointsFilter: Memory allocation error with %1% voxels. Try increasing the voxel dimensions.") % numVox).str()); -} - -for (int p = 0; p < numPoints; p++ ) -{ - unsigned int i = floor(cloud.features(0,p)/vSizeX - minBoundX); - unsigned int j = floor(cloud.features(1,p)/vSizeY- minBoundY); - unsigned int k = 0; - unsigned int idx; - if ( featDim == 4 ) - { - k = floor(cloud.features(2,p)/vSizeZ - minBoundZ); - idx = i + j * numDivX + k * numDivX * numDivY; - } - else - { - idx = i + j * numDivX; - } - - unsigned int pointsInVox = (*voxels)[idx].numPoints + 1; - - if (pointsInVox == 1) - { - (*voxels)[idx].firstPoint = p; - } - - (*voxels)[idx].numPoints = pointsInVox; - - indices[p] = idx; - -} - -``` -The bounding area of the point cloud is calculated by finding the minimum and maximum positions in the feature dimensions. The number of divisions along each direction which form a voxel are calculated by dividing the bounding box size by the voxel size. Note that unless the bounding box size is an exact multiple of the voxel size, the voxels cannot all be the same size. We simply use N-1 voxels of equal size and the remaining space is used by the last voxel. - -Each voxel is identified by a unique linear index. If i,j,k represent the voxel indices in the x,y,z dimensions respectively, the formula to encode the linear index is the following: idx = i + j * numDivX + k * numDivX * numDivY. Each point in the cloud is given a voxel index. The number of points and the first point in a given voxel is recorded in a vector of `Voxel` objects. - -#### 2. Voxel Point Computation -##### Using the Centroid -```cpp -// store which points contain voxel position -std::vector pointsToKeep; - -// Store voxel centroid in output -if (useCentroid) -{ - // Iterate through the indices and sum values to compute centroid - for (int p = 0; p < numPoints ; p++) - { - unsigned int idx = indices[p]; - unsigned int firstPoint = (*voxels)[idx].firstPoint; - - // If this is the first point in the voxel, leave as is - // if not sum up this point for centroid calculation - if (firstPoint != p) - { - // Sum up features and descriptors (if we are also averaging descriptors) - - for (int f = 0; f < (featDim - 1); f++ ) - { - cloud.features(f,firstPoint) += cloud.features(f,p); - } - - if (averageExistingDescriptors) - { - for (int d = 0; d < descDim; d++) - { - cloud.descriptors(d,firstPoint) += cloud.descriptors(d,p); - } - } - } - } - - // Now iterating through the voxels - // Normalize sums to get centroid (average) - // Some voxels may be empty and are discarded - for( int idx = 0; idx < numVox; idx++) - { - unsigned int numPoints = (*voxels)[idx].numPoints; - unsigned int firstPoint = (*voxels)[idx].firstPoint; - if(numPoints > 0) - { - for ( int f = 0; f < (featDim - 1); f++ ) - cloud.features(f,firstPoint) /= numPoints; - - if (averageExistingDescriptors) { - for ( int d = 0; d < descDim; d++ ) - cloud.descriptors(d,firstPoint) /= numPoints; - } - - pointsToKeep.push_back(firstPoint); - } - } -} -``` -We make a second pass through the data and take the sum of the features in the place of each voxel's first point. If needed, the descriptors are also summed up. We then iterate through the voxels and normalize non empty voxels. Their first points are recorded to be ignored by the truncation operation applied at the end of filtering. - -##### Using Centers - -```cpp -// Although we don't sum over the features, we may still need to sum the descriptors -if (averageExistingDescriptors) -{ - // Iterate through the indices and sum values to compute centroid - for (int p = 0; p < numPoints ; p++) - { - unsigned int idx = indices[p]; - unsigned int firstPoint = (*voxels)[idx].firstPoint; - - // If this is the first point in the voxel, leave as is - // if not sum up this point for centroid calculation - if (firstPoint != p) - { - for (int d = 0; d < descDim; d++ ) - { - cloud.descriptors(d,firstPoint) += cloud.descriptors(d,p); - } - } - } -} - -for (int idx = 0; idx < numVox; idx++) -{ - unsigned int numPoints = (*voxels)[idx].numPoints; - unsigned int firstPoint = (*voxels)[idx].firstPoint; - - if (numPoints > 0) - { - // get back voxel indices in grid format - // If we are in the last division, the voxel is smaller in size - // We adjust the center as from the end of the last voxel to the bounding area - unsigned int i = 0; - unsigned int j = 0; - unsigned int k = 0; - if (featDim == 4) - { - k = idx / (numDivX * numDivY); - if (k == numDivZ) - cloud.features(3,firstPoint) = maxValues.z() - (k-1) * vSizeZ/2; - else - cloud.features(3,firstPoint) = k * vSizeZ + vSizeZ/2; - } - - j = (idx - k * numDivX * numDivY) / numDivX; - if (j == numDivY) - cloud.features(2,firstPoint) = maxValues.y() - (j-1) * vSizeY/2; - else - cloud.features(2,firstPoint) = j * vSizeY + vSizeY / 2; - - i = idx - k * numDivX * numDivY - j * numDivX; - if (i == numDivX) - cloud.features(1,firstPoint) = maxValues.x() - (i-1) * vSizeX/2; - else - cloud.features(1,firstPoint) = i * vSizeX + vSizeX / 2; - - // Descriptors : normalize if we are averaging or keep as is - if (averageExistingDescriptors) { - for ( int d = 0; d < descDim; d++ ) - cloud.descriptors(d,firstPoint) /= numPoints; - } - - pointsToKeep.push_back(firstPoint); - } -} - -// deallocate voxels vector -delete voxels; -``` -If we are averaging descriptors, we perform a summing step as in the previous case. We then iterate through the voxels and replace the first point from each non-empty voxel with the voxel center. If descriptors are averaged, these are normalized as well. We also record the points to keep during the truncation process. - -#### 3. Point Cloud Truncation - -```cpp -// Move the points to be kept to the start -// Bring the data we keep to the front of the arrays then -// wipe the leftover unused space. -std::sort(pointsToKeep.begin(), pointsToKeep.end()); -int numPtsOut = pointsToKeep.size(); -for (int i = 0; i < numPtsOut; i++){ - int k = pointsToKeep[i]; - assert(i <= k); - cloud.features.col(i) = cloud.features.col(k); - if (cloud.descriptors.rows() != 0) - cloud.descriptors.col(i) = cloud.descriptors.col(k); -} -cloud.features.conservativeResize(Eigen::NoChange, numPtsOut); -cloud.descriptors.conservativeResize(Eigen::NoChange, numPtsOut); -``` -We first sort the points voxel points by index and place them in order, at the beginning of the point cloud. The unwanted points are removed from the point cloud by using Eigen's `conservativeResize` function. - -## Registering the Filter as a Libpointmatcher Module - -First, we have to declare it in [pointmatcher/DataPointsFiltersImpl.h](/pointmatcher/DataPointsFiltersImpl.h) as follow: - -```cpp -template -struct DataPointsFiltersImpl -{ - /* other filters declaration */ - typedef ::VoxelGridDataPointsFilter VoxelGridDataPointsFilter; -}; -``` - -Now that we have completed the implementation of our voxel filter, we can add it to libpointmatcher as a usable DataPointsFilter. We do so by adding the following macro function in [pointmatcher/Registry.cpp](/pointmatcher/Registry.cpp) - -```cpp -ADD_TO_REGISTRAR(DataPointsFilter, VoxelGridDataPointsFilter, typename DataPointsFiltersImpl::VoxelGridDataPointsFilter) -``` - -Now recompile the library and check that the new transformation is listed as an available module by running `pcmip -l | grep -C 10 VoxelGridDataPointsFilter`. - -## Where To Go From Here -If you are not comfortable with the material covered in this tutorial, we suggest that you attempt to re-design a very simple filter such as the `MaxDistDataPointsFilter`. You can find its implementation in [pointmatcher/DataPointsFilters/MaxDist.h](pointmatcher/DataPointsFilters/MaxDist.h) and [pointmatcher/DataPointsFilters/MaxDist.cpp](pointmatcher/DataPointsFilters/MaxDist.cpp) with which to compare your solution. - -For more information on extending libpointmatcher the [next tutorial](TransformationDev.md) covers the design of a transformation class and is similar in nature to this tutorial. - -Nevertheless, you can skip directly to [this tutorial](UnitTestDev.md) to learn how to write unit tests to validate that your modules are working correctly. The module that is tested in that lesson is the voxel grid filter that was just designed here and is thus natural next step to take. - diff --git a/thirdparty/libpointmatcher/doc/Datafilters.md b/thirdparty/libpointmatcher/doc/Datafilters.md deleted file mode 100644 index bca6cf3..0000000 --- a/thirdparty/libpointmatcher/doc/Datafilters.md +++ /dev/null @@ -1,586 +0,0 @@ -| [Tutorials Home](index.md) | [Previous](Compilation.md) | [Next](ApplyingDatafilters.md) | -| ------------- |:-------------:| -----:| - -# Datapoint Filters - -In this section, the various filters which can be applied to the reading and reference point clouds before performing the ICP process. - -As a reminder, *datapoint filters* can have several purposes: - -* Removing noisy points which render the alignment of point clouds difficult. -* Removing redundant points so as to speed up alignment -* Adding descriptive information to the points such as a surface normal vector, or the direction from the point to the sensor. - -Note that *datapoint filters* differ from *outlier filters* which appear further down the ICP chain and have a different purpose. - -[Libpointmatcher](https://github.com/ethz-asl/libpointmatcher) provides developers with a number of datapoint filters which process an input point cloud into an intermediate point cloud used in the alignment procedure. Filters function as independent modules that can and often are combined into chains. Sequential chains of datapoint filters can thus be adapted to the alignment problem at hand. - -## Filter Index -### Down-sampling -1. [Bounding Box Filter](#boundingboxhead) - -2. [Maximum Density Filter](#maxdensityhead) - -3. [Maximum Distance Filter](#maxdistancehead) (**deprecated**) - -4. [Minimum Distance Filter](#mindistancehead) (**deprecated**) - -5. [Distance Limit Filter](#distancelimithead) - -6. [Maximum Point Count Filter](#maxpointcounthead) - -7. [Maximum Quantile on Axis Filter](#maxquantilehead) - -8. [Random Sampling Filter](#randomsamplinghead) - -9. [Remove NaN Filter](#removenanhead) - -10. [Shadow Point Filter](#shadowpointhead) - -11. [Voxel Grid Filter](#voxelgridhead) (**deprecated**) - -12. [Octree Grid Filter](#octreegridhead) - -13. [Normal Space Sampling (NSS) Filter](#nsshead) - -14. [Covariance Sampling (CovS) Filter](#covshead) - -### Descriptor Augmenting -1. [Observation Direction Filter](#obsdirectionhead) - -2. [Surface Normal Filter](#surfacenormalhead) - -3. [Orient Normals Filter](#orientnormalshead) - -4. [Sampling Surface Normal Filter](#samplingnormhead) - -5. [Simple Sensor Noise Filter](#sensornoisehead) - - -## An Example Point Cloud View of an Appartment -![alt text](images/floor_plan.png "Floor plan of the apartment") - -The following examples are drawn from the apartment dataset available for [download](http://projects.asl.ethz.ch/datasets/doku.php?id=laserregistration:apartment:home) from the ASL at ETH Zurich. A top-down view of the point cloud is depicted below, with the colors showing vertical elevation. The ceiling has been removed from the point cloud such that the floor (in blue) and the walls (in red) are clearly visible. Note that the coordinate origin is placed in the kitchen at the starting point of data capture, which is in the top-left of the top-down view and floor plan. - -![alt text](images/appt_top.png "Top down view of point cloud from appartment dataset") - -## Bounding Box Filter -### Description -Points can be excluded from a rectangular bounding region by using this filter. The box dimensions are specified by defining the maximum and minimum coordinate values in the x,y,z directions. - -__Required descriptors:__ none -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|xMin |Minimum value on the x-axis defining one side of the box | -1.0 | -inf to inf| -|xMax |Maximum value on the x-axis defining one side of the box | 1.0 | -inf to inf| -|yMin |Minimum value on the y-axis defining one side of the box | -1.0 | -inf to inf| -|yMax |Maximum value on the y-axis defining one side of the box | 1.0 | -inf to inf| -|zMin |Minimum value on the z-axis defining one side of the box | -1.0 | -inf to inf| -|zMax |Maximum value on the z-axis defining one side of the box | 1.0 | -inf to inf| -|removeInside |if set to 1, points contained within the box are removed, else points outside are removed |1 | 0 or 1| - -### Example -In the following example, a box filter of the following dimensions was applied to the input point cloud. - -Note that only points **outside** the bounding box are removed by the filter by setting the property *removeInside* to 0. Because the point cloud center is located in the kitchen in the top-left, a square region of 2m x 2m is selected by this filter. In the following image, the output of the filter is overlaid in white. - -|Figure: Top down view of the appartment point cloud with a box filter applied. The
input is shown in color and the output of the filter is overlaid in white |Parameters used | -|---|:---| -|![box filter output](images/box_filt_outside.png "Top down view of the appartment point cloud with a box filter applied. The input is shown in color and the output of the filter is overlaid in white") |xMin : -1.0
xMax : 1.0
yMin : -1.0
yMax : 1.0
zMin : -1.0
zMax : 2.0
removeInside : 0 | - -|Figure: Top down view of the appartment point cloud with a box filter applied. The
input is shown in color and the output of the filter is overlaid in white |Parameters used | -|---|:---| -|![box filter output](images/box_filt_inside.png "Top down view of the appartment point cloud with a box filter applied and ignore inside applied. The input is shown in color and the output of the filter is overlaid in white") | xMin : -1.0
xMax : 1.0
yMin : -1.0
yMax : 1.0
zMin : -1.0
zMax : 2.0
removeInside : 1 | - -## Maximum Density Filter -### Description -A number of filters are used to reduce the number of points in a cloud by randomly sub-sampling or randomly rejecting a set of points. Points in regions of high density often contain redundant information, and the ICP algorithm could be performed more efficiently with a smaller number of points. This filter is thus used to homogenize the density of a point cloud by rejecting a sub-sample of points in high-density regions. - -Points are only considered for rejection if they exceed a density threshold, otherwise they are preserved. The single parameter of this filter sets the maximum density that should be obtained in the output point cloud. Points are randomly rejected such that this maximum density is obtained as closely as possible. - -__Required descriptors:__ `densities` (see SurfaceNormalDataPointsFilter and SamplingSurfaceNormalDataPointsFilter) -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|maxDensity |The desired maximum density of points in *points/m^3 (for 3D), points/m^2 (for 2D)* | 10 | min: 0.0000001, max: inf| - -### Example -In the following example we observe the effect of the maximum density filter on the apartment point cloud. Sub-sampling occurs mostly in high density regions, which colored in red in the image below. The result is an image with lower density overall with the low density regions in blue being preserved. - -|Figure: Max density filter applied to subsection of the apartment dataset. On the
original data, low density regions are blue and high density regions are red. The
sampled points are overlaid in white. | Parameters used | -|---|:---| -|![max density before](images/appt_0_maxdens.png "Max density filter applied to subsection of the apartment dataset. On the original data, low density regions are blue and high density regions are red. The sampled points are overlaid in white.") | maxDensity: 50000 | - -## Maximum Distance Filter (**deprecated**) - -**Deprecated** : please consider switching to [Distance Limit Filter](#distancelimithead). - -### Description -These filters remove points which lie beyond a threshold distance from the coordinate center. Points are kept if their distance from the center is **smaller than** the threshold. The distance threshold can be defined on the x,y, and z axes or can be a radial distance from the center. - -__Required descriptors:__ none -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|dim | Dimension over which the distance is thresholded. If -1, then the threshold is a radial distance from the center | -1 | 0: x, 1: y, 2: z, -1: radial| -|maxDist |Distance threshold (in m) beyond which points are rejected | 1.0 | min: -inf, max: inf| - -### Example -In the following example, a maximum distance threshold of 1m is applied radially by setting the dimension parameter to -1. As shown on the image below, points which lie within a sphere of radius 1m centered at the origin are selected by the filter and are displayed in white. All other points are rejected by the filter. Were a maximum distance filter to be replaced by an equivalent minimum distance filter, only points outside the sphere would be selected. - -|Figure: Max density filter applied to subsection of the apartment dataset. On the
original data, low density regions are blue and high density regions are red. The
sampled points are overlaid in white. | Parameters used | -|---|:---| -|![max distance after](images/max_dis.png "After applying maximum distance filter with a distance threshold of 1m and the dimension parameter set to radial") | maxDist : 1.0
dim : -1 | - -## Minimum Distance Filter (**deprecated**) - -**Deprecated** : please consider switching to [Distance Limit Filter](#distancelimithead). - -### Description -These filters remove points which lie beyond a threshold distance from the coordinate center. Points are kept if their distance from the center is **greater than** the threshold. The distance threshold can be defined on the x,y, and z axes or can be a radial distance from the center. - -__Required descriptors:__ none -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|dim | Dimension over which the distance is thresholded. If -1, then the threshold is a radial distance from the center | -1 | 0: x, 1: y, 2: z, -1: radial| -|minDist |Distance threshold (in m) beyond which points are selected | 1.0 | min: -inf, max: inf| - -## Distance Limit Filter -### Description -These filters remove points which lie before or beyond a threshold distance from the coordinate center. The distance threshold can be defined on the x,y, and z axes or can be a radial distance from the center. - -__Required descriptors:__ none -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|dim |Dimension over which the distance is thresholded. If -1, then the threshold is a radial distance from the center | -1 | 0: x, 1: y, 2: z, -1: radial| -|dist |Distance threshold (in m) used to reject points | 1.0 | min: -inf, max: inf| -|removeInside|If set to 1, points contained before the limit are removed, else points beyond are removed |1 | 0 or 1| - -### Example -In the following example, a distance threshold of 1m is applied radially by setting the dimension parameter to -1. Also, the removeInside parameter is set to 0 in order to remove points beyond the distance limit. As shown on the image below, points which lie within a sphere of radius 1m centered at the origin are selected by the filter and are displayed in white. All other points are rejected by the filter. Were the removeInside parameter value to be replaced by 1, only points outside the sphere would be selected. - -|Figure: Distance limit filter applied to subsection of the apartment dataset. On the
original data, low density regions are blue and high density regions are red. The
sampled points are overlaid in white. | Parameters used | -|---|:---| -|![distance limit after](images/distance_limit.png "After applying distance limit filter with a distance threshold of 1m, the dimension parameter set to radial and the removeInside parameter set to 0") | dist : 1.0
dim : -1
removeInside : 0 | - -## Maximum Point Count Filter -### Description -Conditional subsampling. This filter reduces the size of the point cloud by randomly dropping points if their number is above `maxCount`. The resulting point cloud while have `maxCount` number of point. the Based on: Registration and integration of multiple range images for 3-D model construction. Masuda, T. and Sakaue, K. and Yokoya, N. In Pattern Recognition, 1996., Proceedings of the 13th International Conference on. 879--883. 1996. - - -__Required descriptors:__ none -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|seed | srand seed | 0 | min: 0 max: 2147483647 | -|maxCount |number of points beyond which subsampling occurs | 1000 | min: 0, max: 2147483647| - -### Example -No example available. - - -## Maximum Quantile on Axis Filter -### Description -Points are filtered according to where they lie on a distribution of their positions along a given axis. The entire distance range is divided into quantiles which lie between 0 and 1. One can specify the distance quantile above which points are rejected by the filter. - -__Required descriptors:__ none -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|dim | Dimension over which the distance (from the center) is thresholded | 0 | x:0 y:1 z:2 | -|ratio |Quantile threshold. Points whose distance exceed this threshold are rejected by the filter | 0.5 | min: 0.0000001, max: 0.9999999 | - -### Example -In the following example, maximum quantile filtering is performed over the x-axis with a quantile threshold of 0.5. Therefore, points which have an x-value which exceeds the 50% quantile are rejected. The output of the filter is displayed in white and overlaid with the input point cloud in the image below. A sampling region centered at the origin and extending in both directions of the x-axis is clearly visible. - -|Figure: Maximum quantile on axis filter in the x-direction with a maximum quantile
of 0.5. | Parameters used | -|---|:---| -|![max quant after](images/max_quant.png "After applying maximum quantile on axis filter in the x-direction with a maximum quantile of 0.5") | dim : 0
ratio : 0.5 | - -## Random Sampling Filter - -### Description -This filter behaves similarly to the [Maximum Point Count Filter](#maxpointcounthead) but does not enforce a maximum point constraint. Instead points are kept by the filter with a fixed probability. - -__Required descriptors:__ none -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|prob | Probability that a point is kept (1/decimation factor) | 0.75 | min: 0, max: 1 | - -### Example -In the following sample, points are kept with a probability of 0.1. Therefore the total number of points in the output point cloud is approximately 10 times less than the number of points in the input point cloud and the density is decreased overall. - -|Figure: After applying the random sampling filter with a probability of 0.1.
The original data is shown in black and the sampled points in white. | Parameters used | -|---|:---| -|![rand after](images/appt_0_rand.png "After applying the random sampling filter with a probability of 0.1") | prob : 0.1 | - -## Remove NaN Filter - -### Description -Due to errors in the capture process point clouds may contain points with invalid coordinates. This filter can be applied to remove points which contain a NaN coordinate, thus producing a "clean" dataset. - -__Required descriptors:__ none -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - -## Shadow Point Filter - -### Description - -Shadow points are noisy points usually located at point cloud edge discontinuities. - -__Required descriptors:__ `normals` (see SurfaceNormalDataPointsFilter) -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - -*IMPORTANT:* The surface normal descriptors are required in the input point cloud. - -## Voxel Grid Filter (**deprecated**) - -**Deprecated** : please, due to unefficient memory usage, consider switching to [Octree Grid filter](#octreegridhead). - -### Description -While, the previous filters were sub-sampling filters in that they returned a sub-set of points from the original point cloud, the voxel grid filter instead returns a point cloud with a smaller number of points which should best represent the input point cloud as a whole. - -The voxel grid filter down-samples the data by taking a spatial average of the points in the cloud. In the 2D case, one can simply imagine dividing the plane into a regular grid of rectangles. While the term is more suited to 3D spaces, these rectangular areas are known as *voxels*. The sub-sampling rate is adjusted by setting the voxel size along each dimension. The set of points which lie within the bounds of a voxel are assigned to that voxel and will be combined into one output point. - -There are two options as to how to represent the distribution of points in a voxel by a single point. In the first, we take the centroid or spatial average of the point distribution. In the second, we simply take the geometrical center of the voxel. Clearly, the first option is more accurate since it takes into account the point distribution inside the voxels. However it is more computationally intensive since the centroid must be computed for each voxel. The computational cost increases linearly with the number of points in the cloud and the number of voxels. - -This filter also provides two methods for sub-sampling descriptors. In the first, all descriptors within a voxel are averaged while in the second, only the first descriptor from a voxel is kept. - -__Required descriptors:__ none -__Output descriptor:__ outputs average or single descriptor per voxel if the input cloud contains descriptors -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|vSizeX |Size of the voxel along the x-axis | 1.0 | ]0 ; +inf[| -|vSizeY |Size of the voxel along the y-axis | 1.0 | ]0 ; +inf[| -|vSizeZ |Size of the voxel along the z-axis | 1.0 | ]0 ; +inf[| -|useCentroid|If 1, down-sample by using the centroid of each voxel. If 0, use the voxel center | 1 | 1 or 0| -|averageExistingDescriptors|If 1, descriptors are down-sampled by taking their average in the voxel. If 0, we use the descriptors from the first point found in the voxel | 1 | 1 or 0| - -For more information on the implementation of this filter, refer to [this tutorial](DataPointsFilterDev.md). - -### Example -In this example, we apply the voxel grid filter using centroid down-sampling to the appartment point cloud. The output points are shown in yellow. You can observe a regular grid distribution of points corresponding to each voxel. A finer degree of sub-sampling can be obtained by using smaller voxels. This comes naturally with an increased computational cost and a larger output point cloud. - -|Figure: Applying the voxel grid filter filter to the appartment point cloud. | Parameters used | -|---|:---| -|![dir after](images/appt_voxel.png "Applying the voxel grid filter filter to a local point cloud") | vSizeX : 0.2
vSizeY : 0.2
vSizeZ : 0,2
useCentroid : 1 | - -## Octree Grid Filter - -### Description - -The concept is quite the same as the voxel grid but use an [Octree](https://en.wikipedia.org/wiki/Octree) (3D case) or a [Quadtree](https://en.wikipedia.org/wiki/Quadtree) (2D case). The filter use the efficent spatial representation of the pointcloud by the octree to sub-sample point in each leaf. - -Some information about the octree structure: -- the current implementation ensures to have either 0 or 8 (resp. 4) children for each node of the octree (resp. quadtree) -- only leaf nodes contain data -- data contained by the octree are currently the indexes of the points from the `DataPoint` structure -- processing are applied by calling a callback for each node in a depth-first search ([DFS](https://en.wikipedia.org/wiki/Depth-first_search)) -- parallel build can be enabled (but only the first level is parallelized) -- the octree can be build given two criterion: number of data by leaf node, or size of the leaf node - -**Remark 1:** currently the space is decomposed from the Cartesian coordinates (x,y,z), but there should be no limitation to use other dimensions (such as normal coordinates for instance). - -With this new structure, the `DataPointsFilter` named `OctreeGridDataPointsFilter` works as follow: -- build an octree spatial representation of the point cloud -- apply a process to sample in each leaf node - -Four sampling methods are available: -- take the first point of each node (`FirstPtsSampler`) -- take a random point of each node (_quite similar to the previous one since the point cloud is not supposed to be ordered_) (`RandomPtsSampler`) -- compute [centroid](https://en.wikipedia.org/wiki/Centroid) of each node (_more precise but more costly_) (`CentroidSampler`) -- compute [medoid](https://en.wikipedia.org/wiki/Medoid) of each node (_more precise but more costly_) (`MedoidSampler`) - -**Remark 2:** Theoretically, any process can be applied to the point cloud (sampling, feature enhancement, filtering, etc.) since the octree give an efficient spatial representation of the point cloud (_ex: we could estimate the normal of each leaf_). - -__Required descriptors:__ none -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|buildParallel | flag for enabling parallel build of the octree | true (1) | 0 or 1 | -|maxPointByNode | number of point under which the octree stop dividing | 1 | min: 1, max: 4294967295 | -|maxSizeByNode | size of the bounding box under which the octree stop dividing | 0.0 | min: 0.0, max: +inf | -|samplingMethod | method to sample the octree: First Point (0), Random (1), Centroid (2) (more accurate but costly), Medoid (3) (more accurate but costly) | 0 | min: 0, max: 3 | - -### Example -The following example uses a structured point cloud from the apartment dataset. As the pointcloud is structured we use the size criterion set to 20 cm to decompose the point cloud. In each leaf, we took the _centroid_ (bottom) or the _medoid_ (top) colored in green (output points), where the color of the pointcloud represents the indexes in the octree. - -|Figure: Applying the Octree Grid Filter on a structured point cloud | Parameters used | -|---|:---| -|![octree centroid medoid](https://user-images.githubusercontent.com/38259866/41250974-80e6bee2-6d86-11e8-872f-c5687d7535d5.png "Applying the Octree Grid Filter on a structured point cloud") | maxSizeByNode : 0.2
_at the top_, samplingMethod : 3 (_medoid_)
_at the bottom_, samplingMethod : 2 (_centroid_)| - -**Remark 3:** using centroid can lead to false results in the ICP registration. In deed, the centroid is not guaranteed to be a point of the cloud, which induce a new spatial representation and so an offset in the registration, whereas the medoid is by construction a point of the cloud. Both produce a similar sampled point cloud, but looking closer we can see that: -- In the top-right corner, sampled points are contained in the original point cloud -- In the bottom-right corner, sampled points are out of the point cloud. - -## Normal Space Sampling Filter - -### Description - -Sub-sampling filter based on Normal Space Sampling (NSS) from _S. Rusinkiewicz and M. Levoy, “Efficient Variants of the ICP Algorithm,” in Proceedings Third International Conference on 3-D Digital Imaging and Modeling, 2001, pp. 145–152_. - -The algorithm works as follow: -1. Construct a set of buckets in the normal-space (stocked in a `std::vector`) -1. Then put all points of the data into buckets based on their normal direction; -1. Finally, uniformly pick points from all the buckets until the desired number of points is selected. - -**Remark:** a point is randomly picked in a bucket that contains multiple points. -**Remark:** the uniform sampling is based on a standard Mersenne twister engine - -As the normals are supposed normed, the _n_-space can be represented by polar coordinates, with: -- _theta_, the polar angle in [0 ; pi] -- _phi_, the azimuthal angle in [0 ; 2pi] -- _r_=1, the radius can be omitted - -Resources to better understand uniform sampling in normal-space can be found [here](http://corysimon.github.io/articles/uniformdistn-on-sphere/). - -**Remark:** the current implementation only supports 3D point cloud - -__Required descriptors:__ `normals` (see SurfaceNormalDataPointsFilter) -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|nbSample | number of point to select | 5000 | min: 1, max: 4294967295| -|seed | seed for the random generator | 1 | min: 0, max: 4294967295 | -|epsilon | step of discretization for the angle spaces | PI/32 | min: PI/64, max: PI | - -### Example -The following example uses a structured point cloud from the apartment dataset. The following gives the normal representation (on a sphere) of the original point cloud (we can clearly see that some areas are more populated) and the normal representation of the uniform sampled pointcloud (output). - -|Figure: Applying the NSS Filter on a structured point cloud | Parameters used | -|---|:---| -|![nss](https://image.ibb.co/gosJk8/nss.png "Applying the NSS Filter on a structured point cloud") | nbSample : 5000
seed : 1
epsilon : PI/32 | - -where the left-white point cloud is the normal distribution of the original point cloud, -where the right-red point cloud is the normal distribution of the sampled point cloud - -## Covariance Sampling Filter - -### Description - -Sub-sampling filter based on Covariance Sampling (CovS) from _N. Gelfand, L. Ikemoto, S. Rusinkiewicz, and M. Levoy, “Geometrically stable sampling for the ICP algorithm,” in Fourth International Conference on 3-D Digital Imaging and Modeling, 2003. 3DIM 2003. Proceedings., 2003, pp. 260–267._ - -The filter analyses the force (_t-normals_: **n**) and the torque (_r-normals_: **n x p**) to select geometrically stable points that can bind the rotational components as well as the translational. Unlike the original article, we match the point-cloud with itself (considering then an overlap of 100%). - -Three methods can be used to balance rotation and translation through torque normalization (L): -- L=1 (no normalization): more _t-normals_ -- L=Lavg (average distance to centroid) : same contribution for _t-normals_ and _r-normals_ as torque is scale-independent -- L=Lmax (in unit ball): more _r-normals_ - -__Required descriptors:__ `normals` (see SurfaceNormalDataPointsFilter) -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ reduces number of points - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|nbSample | number of point to select | 5000 | min: 1, max: 4294967295| -|torqueNorm | method for torque normalization: (0) L=1, (1) L=Lavg, (2) L=Lmax | 1 | min: 0, max: 2 | - -### Example -The following example uses a structured point cloud from the apartment dataset. The following gives the selected points (output) considering the three proposed normalization methods (L=1 in blue, L=Lavg in yellow and L=Lmax in red). - -|Figure: Applying the CovS Filter on a structured point cloud | Parameters used | -|---|:---| -|![covs](https://user-images.githubusercontent.com/38259866/41663461-7e1954bc-7471-11e8-886e-dcf7439d7f0f.png "Applying the CovS Filter on a structured point cloud") | nbSample : 25000
torqueNorm :
0 (blue)
1 (yellow)
2 (red) | - -**Remark:** the filter is not very well suited for large scan with uneven density, it is preferably to use it for computer vision applications, or small scan. - -## Observation Direction Filter - -### Description -As opposed to the previous filters, the following does not yield a sub-sample of points but rather augments the input point cloud with additional information. In particular, this filter adds a descriptor vector to each point representing its direction to the sensor used for capturing the point cloud. Remark that adding a direction vector is useful for locally captured point clouds in which the position of the sensor is fixed. In contrast global point clouds which are formed from several local point clouds do not have a fixed sensor position. - -The returned direction vector is a vector connecting the point and the sensor, whose positions can be specified in the filter parameters. - -__Required descriptors:__ none -__Output descriptor:__ `observationDirections` -__Sensor assumed to be at the origin:__ yes -__Impact on the number of points:__ none - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|x | x-coordinate of the sensor position | 0.0 | min: -inf, max: inf | -|y | y-coordinate of the sensor position | 0.0 | min: -inf, max: inf | -|z | z-coordinate of the sensor position | 0.0 | min: -inf, max: inf | - -### Example -**Remark:** The following example uses a local point cloud 10 from the apartment dataset. The filter is used to extract direction informations and a small subset of these directions is shown in the following image. The arrows point towards the position of the sensor. The input point cloud is color coded according to the z-elevation of the points (red represents the ceiling and blue the floor). - -|Figure: Applying the observation direction filter to a local point cloud. A small
subset of point observation directions are displayed | Parameters used | -|---|:---| -|![dir after](images/appt_obs_dir.png "Applying the observation direction filter to a local point cloud") | x : 0
y : 0
z : 0 | - -## Surface Normal Filter - -### Description -The surface normal to each point is estimated by finding a number of neighboring points and taking the eigen-vector corresponding to the smallest eigen-value of all neighboring points. - -Remark that that given a surface, the normal vector can point in two possible directions. Following the apartment example used herein throughout, the normal vector of a wall can point inside towards the room, or outside the apartment. To align all normal vectors in the same direction, the [orient normals filter](#orientnormalshead) can be used. - -__Required descriptors:__ none -__Output descriptor:__ -`normals` -`densities` -`eigValues` -`eigVectors` -__Sensor assumed to be at the origin:__ no -__Impact on the number of points:__ none - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|knn | Number of neighboring points (including the point itself) to consider when extracting surface normal | 5 | min: 3, max: 2147483647 | -|epsilon | Approximation used in nearest neighbor search | 0.0 | min: 0.0, max: inf | -|keepNormals | Add the normal vector to descriptors | 1 | 1: true, 0: false | -|keepDensities | Add point cloud density to descriptors | 0 | 1: true, 0: false | -|keepEigenValues | Add eigen values to descriptors | 0 | 1: true, 0: false | -|keepEigenVectors | Add eigen vectors to descriptors | 0 | 1: true, 0: false | -|keepMatchedIds | Add identifiers of matched points to descriptors (see) | 0 | 1: true, 0:false | - - -### Example -In this example, we again use a local point cloud of the apartment. You may recognize the input point cloud as a small portion of the local cloud used in the observation direction filter. The surface normals are extracted using 20 neighboring points and epsilon=0. In this example, for clarity, we only view a wall section of one of the apartment dataset. A random set of normal vectors is shown in the figure with arrows. When looking at the arrow directions on the wall, one may see normal vectors either pointing downwards into the apartment or outside the apartment. - -|Figure: Applying the observation direction filter to a local point cloud. A small
subset of point observation directions are displayed | Parameters used | -|---|:---| -|![norm after](images/appt_norm.png "Extracting surface normals of a portion of the apartment point cloud") | knn : 20
epsilon : 0
keepNormals : 1
keepDensities : 1| - -## Orient Normals Filter - -### Description -As explained previously, neighboring surface normal vectors obtained from the surface normals filter, do not have the same orientation. This filter enforces this constraint and reorients vectors from the same surface in a consistent direction. Vectors are reoriented to either point towards the center (inwards), or away from the center (outwards). - -__Required descriptors:__ - `observationDirections` (see ObservationDirectionDataPointsFilter) - `normals` (see SurfaceNormalDataPointsFilter, SamplingSurfaceNormalDataPointsFilter) -__Output descriptor:__ none -__Sensor assumed to be at the origin:__ yes -__Impact on the number of points:__ none - - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|towardCenter | Orient vectors to point towards the center | 1 | 1: true, 0: false | - -*IMPORTANT:* Both the normal vector descriptor and observation direction descriptors must be present in the input point cloud. Consequently, both the surface normal and observation filters should be applied prior to using this filter. - -### Example -The same input section is used as for extracting the surface normals in the previous section. The vectors are reoriented to point towards the center which lies in the bottom left corner of the image below. We now observe that adjacent surface normal vectors point in a consistent direction. - -|Figure: Normal vectors reoriented to point towards the center |Parameters used | -|---|:---| -|![norm after](images/orient_norm.png "Normal vectors reoriented to point towards the center") |towardCenter: 1 | - - -## Sampling Surface Normal Filter - -### Description -The above filters extract surface normals at every point in the point cloud. In point clouds representing planar surfaces however, a significant redundant information is contained in adjacent normal vectors. This filter attempts to both reduce the number of points within a point cloud and the number of different normal vectors. The first is achieved by performing either random sub-sampling as seen previously, or by using one point per box (bin sub-sampling). The latter is achieved by recursively decomposing the point-cloud space into boxes until each box contains at most knn points. A single normal vector is computed from the knn points in each box. - -__Required descriptors:__ none -__Output descriptor:__ -`normals` -`densities` -`eigValues` -`eigVectors` -__Sensor assumed to be at the origin:__ yes -__Impact on the number of points:__ reduces number of points - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|ratio | Ratio of points (sampled randomly) that are preserved within a box | 0.5 | min: 0.0000001, max: 0.9999999 | -|knn | Number of points contained within a box and number of neighboring points (including the point itself) to consider when extracting surface normal | 7 | min: 3, max: 2147483647 | -|samplingMethod | 0: random sub-sampling
1:bin sub-sampling with resulting number of points 1/knn | 0 | 0 or 1 | -|maxBoxDim| Maximum allowed length of a box above with boxes are discarded | inf | min: 0.0000001, max: inf | -|averageExistingDescriptors | Average existing descriptors within a box or keep existing values | 1 | 0: keep existing 1: average existing| -|keepNormals | Add the normal vector to descriptors | 1 | 1: true, 0: false | -|keepDensities | Add point cloud density to descriptors | 0 | 1: true, 0: false | -|keepEigenValues | Add eigen values to descriptors | 0 | 1: true, 0: false | -|keepEigenVectors | Add eigen vectors to descriptors | 0 | 1: true, 0: false | -|keepMatchedIds | Add identifiers of matched points to descriptors (see) | 0 | 1: true, 0: false | - -### Example -We reuse the same apartment section to illustrate the sampling of normal vectors. The decimation rate used is 0.5 such that half of the points from the original point cloud are discarded randomly. We use a knn value of 100 such that each box contains at most 100 points. In the following two figures, we extract sample points based on the normals and display the normal vectors at these sample points. We first do so for a ceiling section, followed by a ground section. Because the ceiling is essentially a large plane, the sampling is low and the normal vector arrows are dispersed relatively equally as shown in the first figure. On the other hand, the ground section has a higher density of points. This results in a denser sampling of points which is seen in the second figure. - - The box centers are shown in red on the following picture. It is clear that as opposed to previous filters, adjacent points within a box have the same normal vector. - -|Figure: Sampled normal vectors of ceiling section |Parameters used | -|---|:---| -|![samp norm after](images/appt_samp_norm_sparse.png "Sampled surface normal vectors of ceiling section") | knn : 100
ratio : 0.5
samplingMethod : 1 | - -|Figure: Sampled normal vectors ground section |Parameters used | -|---|:---| -|![samp norm after](images/appt_samp_norm_dense.png "Sampled surface normal vectors of ground section") | knn : 100
ratio : 0.5
samplingMethod : 1 | - -## Simple Sensor Noise Filter - -### Description -This filter is used to augment points with an estimation of position uncertainty based on sensor specifications. So far the [SICK LMS](http://www.sick.com/group/EN/home/products/product_news/laser_measurement_systems/Pages/lms100.aspx), [Hokuyo](http://www.hokuyo-aut.jp/02sensor/index.html#scanner) URG-04LX and UTM-30LX, as well as the Microsoft [Kinect](http://www.microsoft.com/en-us/kinectforwindows/) and Asus [Xtion](http://www.asus.com/Multimedia/Xtion_PRO_LIVE/) sensors are supported. The uncertainty or noise radius is represented in meters, and can be adjusted by varying a gain parameter which amplifies predefined uncertainty levels. - -__Required descriptors:__ none -__Output descriptor:__ `simpleSensorNoise` -__Sensor assumed to be at the origin:__ yes -__Impact on the number of points:__ none - -|Parameter |Description |Default value |Allowable range| -|--------- |:---------|:----------------|:--------------| -|sensorType | The type of sensor that was used in the capture.
0: Sick LMS-1xx
1: Hokuyo URG-04LX
2 : Hokuyo UTM-30LX
3 : Kinect/Xtion | 0 | 0, 1, 2, or 3| -|gain | Used to augment uncertainty | 1 | min: 1, max: inf| - -### Example -For this example we use another point cloud dataset from the ASL collection called [ETH Hauptgebaude](http://projects.asl.ethz.ch/datasets/doku.php?id=laserregistration:eth_hauptgebaude:home). This dataset represents the main gallery of the main building at ETHZ and presents long straight corridors. We therefore use to display the uncertainty estimation of point clouds. - -In the following image we show a side view of local point cloud 3 in the dataset. The laser is located at the bottom left corner and one can see the long arched corridor structures. As we move right in the image point are located further away from the sensor, are therefore less numerous and more uncertain. The points are colored by the estimation uncertainty obtained with this filter. More certain points are black, medium certain points are red and less curtain points are white. Naturally the colour shifts from black to white as we move further away from the laser down the corridor. - -|Figure: Side view of a view 3 from the HG dataset augmented with sensor noise
estimations |Parameters used | -|---|:---| -|![samp norm after](images/hg_noise.png " Side view of a view 3 from the HG dataset") | sensorType : 1 | - -## Fixed Step Sampling Filter (To be completed) -The number of points in a point cloud can be reduced by taking random point subsamples. The filter is parametrized so that a fixed number of points - selected uniformly at random - are 'rejected' in the filtering process. - -## Where To Go From Here -This concludes the overview of data point filters. For a tutorial on writing a simple application for applying data point filters to an input point cloud, go [here](ApplyingDatafilters.md). To learn more about the general configuration of the ICP chain go [here](DefaultICPConfig.md). - diff --git a/thirdparty/libpointmatcher/doc/DefaultICPConfig.md b/thirdparty/libpointmatcher/doc/DefaultICPConfig.md deleted file mode 100644 index 7812665..0000000 --- a/thirdparty/libpointmatcher/doc/DefaultICPConfig.md +++ /dev/null @@ -1,28 +0,0 @@ -| [Tutorials Home](index.md) | [Previous](ICPIntro.md) | [Next](Configuration.md) | -| ------------- |:-------------:| -----:| - -# Default Configuration of the ICP Chain - -The following details the default configuration for ICP in libpointmatcher. - -|Figure 1: Default ICP chain configuration| -|:------| -|![Default ICP Chain Configuration](images/default_icp_chain.png)| - -## Data Filters -Both the reference and reading clouds are processed with [random sampling](Datafilters.md#randomsamplinghead) filters. These will sample each data point with a probability of 0.75 thus yielding smaller point clouds. - -## Matcher -The default matcher is the KD tree matcher. Each point is matched to its closest neighbor in the reference cloud. A KD tree with a linear heap is used. - -## Outlier Filters -One trimmed distance outlier filter is used. The filter ranks the points in the reading cloud by their distance to the reference after a transformation was applied. The top 85% points (those with the smallest distances) are kept. - -## Minimizer -The point-to-plane variant is used in the minimization step. Point-to-plane allows for points to "slide" along planes and generally performs better than the point-to-point variant. - -## Transformation Checkers -The counter checker automatically stops the ICP loop after a maximum of 40 iterations. The differential transformation checker stops the ICP loop when the relative transformation motions between iterations is below a threshold. In other words, when each subsequent iteration produces little change in the transformation, then the algorithm is stopped. Because the relative motions are generally prone to jagged oscillations, smoothing is applied by taking the average the relative differences over several iterations. - -## Inspectors -No inspector is applied. diff --git a/thirdparty/libpointmatcher/doc/ICPIntro.md b/thirdparty/libpointmatcher/doc/ICPIntro.md deleted file mode 100644 index 6f247c4..0000000 --- a/thirdparty/libpointmatcher/doc/ICPIntro.md +++ /dev/null @@ -1,279 +0,0 @@ -| [Tutorials Home](index.md) | [Previous](ApplyingDatafilters.md) | [Next](DefaultICPConfig.md) | -| ------------- |:-------------:| -----:| - -# An Introduction to ICP Registration - -In the following tutorial, we will perform an ICP registration on an example dataset. Throughout this tutorial, we will be making use of the `pmicp` executable, which can be found in the `examples` directory of your libpointmatcher build directory (i.e., `build/examples/pmicp`). - -## Prerequisite: Installing Paraview -To visualize the pointclouds and what happens to them during the different steps of the ICP pipeline, you need to install a visualization program. [Paraview](http://www.paraview.org/) is a widely used data analysis and visualization program. If you do not have it on your system, we suggest to download and install it from [this link](http://www.paraview.org/download/). - -## Example Dataset: Point Cloud Scan of an Appartment -|Figure 1: Floor plan of the scanned apartment| -|:------------| -|![alt text](images/floor_plan.png "Floor plan of the apartment")| - -The data for this tutorial is taken from the apartment dataset available for [download](http://projects.asl.ethz.ch/datasets/doku.php?id=laserregistration:apartment:home) from the ASL at ETH Zurich. The dataset is useful for testing registration robustness in dynamic environments. Dynamic environments (i.e., where objects move during the scan) hinder registration as they produce many outlier points which cannot be matched between different scans. - -A top-down view of the point cloud is depicted below, with the colors showing vertical elevation. The ceiling has been removed from the point cloud such that the floor (in blue) and the walls (in red) are clearly visible. Note that the coordinate origin is placed in the kitchen at the starting point of data capture, which is in the top-left of the top-down view and floor plan. - -|Figure 2: Top-down view of a global scan of the apartment| -|:------------| -|![alt text](images/appt_top.png "Top down view of point cloud from apartment dataset")| - -## Visualizing a Point Cloud in Paraview -We will now open the example point clouds for viewing in paraview. The two views from the apartment dataset can be found in [examples/icp_tutorial/cloud_0.vtk](../examples/icp_tutorial/cloud_0.vtk) and [examples/icp_tutorial/cloud_1.vtk](../examples/icp_tutorial/cloud_1.vtk). Open Paraview and you will be greeted by the following window: - -### The Paraview Main Window - -|Figure 3: Main window of Paraview| -|:------------| -|![alt text](images/paraview_main.png "Main window of paraview")| - -On the top, you will see three toolbars. The first is for importing/exporting data, the second for navigating a representation of your data, and the last for manipulating the data. - -On the top-left, you can find a pipeline browser which displays the various "layers" of data that will be present. Paraview allows you to import several datasets, as well as create new ones. These datasets are layered in the pipeline and displayed in the viewer on the right. - -On the bottom-left you can find options for editing properties, and retrieving information about a given layer. - -### Opening the Point Clouds in Paraview -Go to File -> Open and open [examples/icp_tutorial/cloud_0.vtk](../examples/icp_tutorial/cloud_0.vtk). Don't forget to click the apply button in the properties pane in order to load the point cloud into the viewer. Now, we will change some properties of the point cloud to make it easer to visualize in the viewer. In the properties pane, change the representation style from surface to points, and change the point size to 1. - -|Figure 4: Point properties window of Paraview| -|:------------| -|![alt text](images/paraview_point_properties.png "Point properties")| - -You can click and drag in the viewer pane to navigate the 3D environment. - -You can then open the second view in [examples/icp_tutorial/cloud_1.vtk](../examples/icp_tutorial/cloud_1.vtk). Change the representation to points and change the color to blue so that the second point cloud is visible over the first. You can see that both point clouds represent the same scene but do not have the same number of points and are misaligned. ICP registration will be used to find a transformation which best aligns the points from the first point cloud to the second, while being robust to the differences or outliers between the two views. - -|Figure 5: The two point clouds of the apartment scene used in this tutorial. The reading is colored white and the reference blue.| -|:------------| -|![alt text](images/paraview_2_clouds.png "Two point clouds of the same scene")| - -You can also import a sequence of point clouds and play them as a video. If a folder contains point clouds with the same prefix (e.g., cloud_0.vtk, cloud_1.vtk ... cloud_N.vtk), they are grouped in the file open dialog. You can then play back the sequence by clicking the play button in the top toolbar. - -### An Empty ICP Configuration -In libpointmatcher, configurations are stored in YAML files. For more information, refer to the [configuration tutorial](Configuration.md). For the purpose of this tutorial, we will start with a simplistic configuration file stored in [examples/icp_tutorial/icp_tutorial_empty.yaml](../examples/icp_tutorial/icp_tutorial_empty.yaml). The configuration is shown below. - - readingDataPointsFilters: - - IdentityDataPointsFilter - - referenceDataPointsFilters: - - IdentityDataPointsFilter - - matcher: - KDTreeMatcher - - outlierFilters: - - NullOutlierFilter - - errorMinimizer: - IdentityErrorMinimizer - - transformationCheckers: - - CounterTransformationChecker - - inspector: - NullInspector - - logger: - FileLogger - - -For now, the configuration is essentially empty. Both the reading and reference point clouds are filtered using an identity data filter, which does nothing to the point clouds. In the matching step, a kd-tree is used to find the closest points from the reading to the reference point cloud. No outliers are removed by the null outlier filter, and the identity error minimizer simply returns an identity transformation, no matter what the input point clouds are. The transformation are monitor with a counter, which will exit the iterative process after a fix number of iteration (i.e., in that case the default value is used, which is 40 iterations). - -The last two pieces in the configuration are used for logging and inspecting the algorithm as it runs. The inspector is disable and won't do any thing, while the logger will print information on the consol (i.e., it's default behavior). More precisely, the file logger can be used to outputs information about the algorithm's run status to the console, or to a file if it has been specified. - -This configuration file won't do much in term of registration, but it is useful to explicit the structure of a solution configuration. In the following steps, we will replace the empty components with more useful ones. - -You can run the registration program with this empty configuration to see what it does. If you have built libpointmatcher in `/build` subdirectory, you can use the following commands: - - $ cd libpointmatcher/examples/icp_tutorial/ - $ ../../build/examples/pmicp -v --config icp_tutorial_empty.yaml cloud_0.vtk cloud_1.vtk - -You should see the following results in your console: - - * KDTreeMatcher: initialized with knn=1, epsilon=0, searchType=1 and maxDist=inf - Applying 1 DataPoints filters - 24989 points in - * unknown - 24989 points out (-0%) - Applied 1 filters - 24989 points out (-0%) - PointMatcher::icp - reference pre-processing took 0.00443294 [s] - Applying 1 DataPoints filters - 25193 points in - * unknown - 25193 points out (-0%) - Applied 1 filters - 25193 points out (-0%) - PointMatcher::icp - reading pre-processing took 0.00072264 [s] - PointMatcher::icp - 40 iterations took 1.66783 [s] - match ratio: 1 - writing to test_ref.vtk - writing to test_data_in.vtk - writing to test_data_out.vtk - ICP transformation: - 1 0 0 0 - 0 1 0 0 - 0 0 1 0 - 0 0 0 1 - - - -Additionally, 3 files: `test_ref.vtk`, `test_data_in.vtk`, and `test_data_out.vtk` are written to the current directory. The first two represent the reference and reading respective point clouds and are identical to `cloud_0.vtk` and `cloud_1.vtk`. `test_data_out.vtk` is the result of transforming the reading point cloud so that it best aligns the reference. Because this empty configuration does not perform any alignment, the output point cloud is identical to the reading point cloud. - -### A Real ICP Configuration -We will now replace the empty configuration with something which makes more sense for registration. We will use the second configuration file of our tutorial folder [examples/icp_tutorial/icp_tutorial_cfg.yaml](../examples/icp_tutorial/icp_tutorial_cfg.yaml), which contain the following: - - readingDataPointsFilters: - - RandomSamplingDataPointsFilter: - prob: 0.5 - - referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - - matcher: - KDTreeMatcher: - knn: 1 - - outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.9 - - errorMinimizer: - PointToPlaneErrorMinimizer - - transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - - inspector: - VTKFileInspector: - baseFileName : vissteps - dumpDataLinks : 1 - dumpReading : 1 - dumpReference : 1 - - logger: - FileLogger - - -#### Data Filters -We apply some filtering to both the reading and reference point clouds in order to reduce the number of points and thus decrease the computation time of each iteration. Half of the reading points are sampled randomly, and points are sampled from the reference based wil extracting their surface normal. In that case, the parameter knn will reduce the number of points by a factor 10. For more information, see [here](Datafilters.md#samplingnormhead). - -#### Matcher -Points in the filtered reading cloud are first transformed with the current transformation parameters and are then matched to their nearest neighbors in the filtered reference cloud. The method used for matching is based on a kd-tree, which produce an optimal search at a lower computation complexity. - -#### Outlier Filter -Once points have been matched and are linked, the outlier filter step attempts to remove links which do not correspond to true point correspondences. The trimmed distance outlier filter does so by sorting links by their distance. Points that are matched with a closer distance are less likely to be outliers. The high distance matches in the upper 10% quantile are rejected. - -We also changed the inspector to save information in vtk format. The `dumpDataLinks` option is set in the `VTKInspector` to visualize how the links between matched points evolve in time. After running the example, you will be able to open the `vissteps-link-*.vtk` in Paraview to see those links. They are colored by the distance with closer matches being colored red and outliers colored blue. You can see that the matches get closer as the iterations increase. - -|Figure 6: Animation of the point correspondences iteration by iterations. The links are colored by distance, with the red links having a lower norm than the blue links | -|:------| -|![alt text](images/icp_tutorial_links.gif "Animation of the point correspondences")| - -#### Error Minimizer -The point to plane error minimizer is used since there is a high degree of geometrical structure in this dataset. We mean by geometrical structure the fact that there are many planar geometric surfaces in the apartment in contrast with smoother surfaces which might be associated with a terrain. - -#### Transformation checkers -In addition to a limit on the total number of iterations, an additional constraint is added to the transformations. A threshold on the rotational and translational relative transformation changes is defined between iterations. These values are smoothed with the `smoothLength` parameter by taking the averages of these changes every 4 iterations. If the change in the transformation is below this threshold, the algorithm is stopped. This is to enforce convergence towards a local optimum and to prevent oscillations. - -#### Inspectors -We activate the generation of point cloud visualizations in the VTK inspector. The reading, reference, and match links will be saved at each iteration of the registration process. These can then be loaded into Paraview. - -#### Running new configuration -You can run the ICP registration with this new configuration with the following: - - $ ../../build/examples/pmicp -v --config icp_tutorial_cfg.yaml cloud_0.vtk cloud_1.vtk - -You should now see the following outputs to the console. We will break them down into steps. - - * KDTreeMatcher: initialized with knn=1, epsilon=0, searchType=1 and maxDist=inf - Applying 1 DataPoints filters - 36674 points in - * SamplingSurfaceNormalDataPointsFilter - 18505 points out (-49.5419%) - Applied 1 filters - 18505 points out (-49.5419%) - PointMatcher::icp - reference pre-processing took 0.0222968 [s] - Applying 1 DataPoints filters - 36670 points in - * RandomSamplingDataPointsFilter - 18280 points out (-50.15%) - Applied 1 filters - 18280 points out (-50.15%) - PointMatcher::icp - reading pre-processing took 0.00116747 [s] - PointMatcher::icp - 34 iterations took 9.28363 [s] - match ratio: 0.900055 - writing to test_ref.vtk - writing to test_data_in.vtk - writing to test_data_out.vtk - ICP transformation: - 0.993552 -0.113149 0.00713103 0.60831 - 0.113181 0.993565 -0.00425984 -0.00387758 - -0.00660312 0.00503951 0.999965 0.0107267 - 0 0 0 1 - - - -First the matcher is initialized: - - * KDTreeMatcher: initialized with knn=1, epsilon=0, searchType=1 and maxDist=inf - -Next, the data filters are applied to the reading and reference point clouds with both halving the number of points in the original point clouds. Notice that the sampling surface normal filter is significantly more computationally intense due to the calculation of surface normals. - - Applying 1 DataPoints filters - 36674 points in - * SamplingSurfaceNormalDataPointsFilter - 18505 points out (-49.5419%) - Applied 1 filters - 18505 points out (-49.5419%) - PointMatcher::icp - reference pre-processing took 0.0222968 [s] - Applying 1 DataPoints filters - 36670 points in - * RandomSamplingDataPointsFilter - 18280 points out (-50.15%) - Applied 1 filters - 18280 points out (-50.15%) - PointMatcher::icp - reading pre-processing took 0.00116747 [s] - -We then enter in the iterative section of the registration algorithm. The algorithm completes after 34 iterations, with each iteration slightly improving the point cloud alignment alignment. At the termination of the algorithm, 90% of the points are matched and the resulting transformation matrix is displayed on the console. - - PointMatcher::icp - 34 iterations took 9.28363 [s] - match ratio: 0.900055 - writing to test_ref.vtk - writing to test_data_in.vtk - writing to test_data_out.vtk - ICP transformation: - 0.993552 -0.113149 0.00713103 0.60831 - 0.113181 0.993565 -0.00425984 -0.00387758 - -0.00660312 0.00503951 0.999965 0.0107267 - 0 0 0 1 - -In the following animation, you can observe the reading point cloud being transformed as each iteration further refines the alignment with the reference. - -|Figure 7: Animation of the reading cloud aligning with the reference| -|:------------| -![alt text](images/icp_tutorial_reading.gif "Animation of the reading cloud aligning with the reference") - -### Bonus Tip - -The executable `pmicp` can output the list of all the modules you can load in the yaml file along with their parameters and default values. You can see those using: -``` -$ ./pmicp -l -``` - -If you are searching for the documentation of a particular module, you can do: -``` -$ ./pmicp -l | awk '//' RS="\n\n" ORS="\n\n" -``` -where you need to replace `` by the module name. For example: -``` -$ ./pmicp -l | awk '/VoxelGridDataPointsFilter/' RS="\n\n" ORS="\n\n" -``` -Will output: -``` -VoxelGridDataPointsFilter -Construct Voxel grid of the point cloud. Down-sample by taking centroid or center of grid cells. -- vSizeX (default: 1.0) - Dimension of each voxel cell in x direction - min: -inf - max: inf -- vSizeY (default: 1.0) - Dimension of each voxel cell in y direction - min: -inf - max: inf -- vSizeZ (default: 1.0) - Dimension of each voxel cell in z direction - min: -inf - max: inf -- useCentroid (default: 1) - If 1 (true), down-sample by using centroid of voxel cell. If false (0), use center of voxel cell. - min: 0 - max: 1 -- averageExistingDescriptors (default: 1) - whether the filter keep the existing point descriptors and average them or should it drop them - min: 0 - max: 1 - - -``` - - -### Where to go from here -To learn more on how to create configurations for libpointmatcher, move to the [next tutorial](Configuration.md). Feel free to modify the configuration given above, adding and modifying filters and seeing how they impact the registration performance. diff --git a/thirdparty/libpointmatcher/doc/ImportExport.md b/thirdparty/libpointmatcher/doc/ImportExport.md deleted file mode 100644 index 9a75c53..0000000 --- a/thirdparty/libpointmatcher/doc/ImportExport.md +++ /dev/null @@ -1,107 +0,0 @@ -| [Tutorials Home](index.md) | [Previous](Configuration.md) | [Next](LinkingProjects.md) | -| ------------- |:-------------:| -----:| -# Importing and Exporting Point Clouds - -## Overview -There exists a myriad of [graphics file formats](http://en.wikipedia.org/wiki/Category:Graphics_file_formats) which can be used to represent point clouds. Nevertheless most contain superfluous functionality which isn't necessary for ICP. Consequently, libpointmatcher only supports a small number of file formats which are detailed in the following sections. - -## Table of Supported File Formats -| File Type | Extension | Versions Supported | Descriptors Supported | Additional Information | -| --------- |:---------:|:------------------:|:---------------------:|---------| -| Comma Separated Values | .csv | NA | yes (see [table of descriptor labels](#descmaptable)) | | -| Visualization Toolkit Files | .vtk | Legacy format versions 3.0 and lower (ASCII only) | yes | Only polydata and unstructured grid VTK Datatypes supported. More information can be found [here](http://www.vtk.org/VTK/img/file-formats.pdf).| -| Polygon File Format | .ply | 1.0 (ASCII only) | yes (see [table of descriptor labels](#descmaptable)) | | -| Point Cloud Library Format | .pcd | 0.7 (ASCII only) | yes (see [table of descriptor labels](#descmaptable)) | | - -## Comma Separated Values (CSV) Files -The most simple file format supported to store clouds is a plain text file containing comma separated values. Data is structured in a table format and is separated into rows or lines and columns. Columns are delimited by commas, tabs, or semicolons. 2D and 3D point features are supported as well as a limited number of point descriptors. - -It is common and best practice that the first line of the CSV file be a header identifying each data column. Features are identified by the following names: "x", "y", and "z" if the point cloud in 3D. Descriptors are divided into columns and these must be appropriately identified. - -If the first line does not include a header, the user will be asked to identify which columns correspond to the "x", "y", and "z" feature fields. Any additional content including descriptors is ignored. - -## Visualization Toolkit (VTK Legacy) Files -So as to allow the visualization of point clouds in [Paraview](http://www.paraview.org/), libpointmatcher supports importing and exporting of Paraview's native VTK format. VTK files can be used to represent a wide variety of 3D graphics including point clouds. The VTK standard comprises of a simpler legacy format and a newer XML based format. As of now libpointmatcher only supports the legacy format. - -VTK files can contain different geometrical topologies which are represented in different dataset types. These types each have different file structures and can be one of the following : - -* STRUCTURED_POINTS -* STRUCTURE_GRID -* UNSTRUCTURED_GRID -* POLYDATA -* RECTILINEAR_GRID -* FIELD - -As of writing, libpointmatcher only supports the POLYDATA (used to represent polygonal data) and UNSTRUCTURED_GRID (used to describe any unstructured combination of geometrical cells) types. While VTK files can be encoded in plain text (ASCII) or binary, only ASCII files are supported. - -Descriptors are encoded in VTK files as dataset attributes which can be any of the following all of which are supported in libpointmatcher: - -* SCALARS -* COLOR_SCALARS -* VECTORS -* NORMALS -* TENSORS - -Data contained in these attributes are loaded into the Datapoints feature matrices. In the same way, Dataset descriptors are converted to the appropriate VTK attributes when exporting a point cloud. The following table details which descriptors are exported to VTK files and the corresponding VTK attribute that is used to encode them. - -*Mapping Between libpointmatcher Descriptors and VTK attributes* - -| libpointmatcher Descriptor Label | VTK Dataset Attribute | -| ----------------------------- | --------------------- | -| normals | NORMALS | -| eigVectors | TENSOR | -| color | COLOR_SCALARS | -| Any other 1D descriptor | SCALARS | -| Any other 3D descriptor | VECTORS | - -## Polygon File Format (PLY or Stanford Triangle) Files -The PLY file format was developed at the Stanford Graphics Lab for storing 3D graphics in a relatively straight-forward fashion. PLY files are flexible and data is structured by defining elements and properties. Elements usually represent some geometrical construct such as a vertex or triangular face. Elements are associated to scalar properties such as the x, y, z coordinate in the case of vertices. Properties can contain any information however including colors, normal vector components, densities etc... - -PLY files contain a header section at the top of the file which defines the elements and properties that are used in the file. The rest of the file contains numerical data. The PLY format exists in plain text (ASCII) and in binary, however libpointmatcher only supports the plain text version. - -The PLY format does not prescribe labels to elements or properties, and therefore files must be encoded with appropriate labels in order to be read by libpointmatcher. For information on which properties are supported by libpointmatcher, refer to [this table](#descmaptable). - -## Point Cloud Library File Format (PCD) Files -The [Point Cloud Library](http://pointclouds.org/)(PCL) is an alternative library for handling 2D and 3D point clouds. While libpointmatcher only performs the task of and is optimized for point cloud registration, PCL is widespread in its functionality. - -The developers of PCL have developed their [own file format](http://pointclouds.org/documentation/tutorials/pcd_file_format.php) for storing point clouds. libpointmatcher is compatible with this format and can import and export PCD files in the latest format (v 0.7). - -The PCD format also exists in binary, however only the plain text (ASCII) version is supported. Because PCD does not prescribe standards for descriptors, libpointmatcher utilizes the [same identifier mapping](#descmaptable) for identifying descriptors. - -## Descriptor Property Identifiers (PLY, CSV, PCD) - -| Property Label | Description | Feature or Descriptor | libpointmatcher Descriptor Label | -| -------------- | -------------| --------------------- | ---------------- | -| x | x component of point | feature | NA | -| y | y component of point | feature | NA | -| z | z component of point | feature | NA | -| nx | x component of normal vector at point | descriptor | normals | -| ny | y component of normal vector at point | descriptor | normals | -| nz | z component of normal vector at point | descriptor | normals | -| normal_x | x component of normal vector at point | descriptor | normals | -| normal_y | y component of normal vector at point | descriptor | normals | -| normal_z | z component of normal vector at point | descriptor | normals | -| red | red value (0.0-1.0) of RGB color code | descriptor | color | -| green | green value (0.0-1.0) of RGB color code | descriptor | color | -| blue | blue value (0.0-1.0) of RGB color code | descriptor | color | -| alpha | alpha value (0.0-1.0) of RGBA color code | descriptor | color | -| intensity | laser scan intensity at point | descriptor | intensity | -| eigValues0-2 | eigen values of nearest neighbors at point. Format is eigValues followed by the number of the eigen value (2 for 2D and 3 for 3D) | descriptor | eigValue | -| eigVectors0-2X-Z | eigen vectors of nearest neighbors at point. Format is eigVectors followed by the number of the eigen vector (2 for 2D and 3 for 3D) followed by the axis identifier (X, Y or Z) | descriptor | eigVectors | -| densities | point density at point | descriptor | densities | - -Several identifiers may synonymously point to the same libpointmatcher descriptor. For example, some standards may define the x normal component as *nx* and others as *normal_x*. **Each file should only use one definition for each descriptor. For example, it should never contain both "nx" and "normal_x" fields.** - -While most files should contain data structured in a natural order ie ("x", "y" then "z", or "red", "green", then "blue") this cannot be guaranteed. Therefore libpointmatcher will attempt to reorder the descriptor components when loading a file, and will always export them in a natural order. - ---- -### Note For libpointmatcher Developers -The association between descriptor properties identifiers and libpointmatcher descriptor labels is set in the `getDescAssocationMap` function in [pointmatcher/IO.cpp](/pointmatcher/IO.cpp). To extend IO support to additional descriptors, you can modify this function. - -The `getDescAssocationMap` returns a map which associates a property identifier and a pair consisting of a row number and a point matcher descriptor name. For example, the descriptor identifier *nx* maps to row 0 of the *normals* libpointmatcher descriptor. Ie: - -"nx" -> (0, "normals")
-"ny" -> (1, "normals")
-"nz" -> (2, "normals") - -For converting libpointmatcher descriptors back to a property identifier, you must modify the `getColLabel` function in [pointmatcher/IO.cpp](/pointmatcher/IO.cpp). diff --git a/thirdparty/libpointmatcher/doc/Introduction.md b/thirdparty/libpointmatcher/doc/Introduction.md deleted file mode 100644 index b99ec1c..0000000 --- a/thirdparty/libpointmatcher/doc/Introduction.md +++ /dev/null @@ -1,23 +0,0 @@ -# What is libpointmatcher about? - -libpointmatcher is a library that implements the Iterative Closest -Point (ICP) algorithm for alignment of point clouds. It supports both -point-to-point and point-to-plane ICP. With the former, it is able to -solve not only for a rigid transform, but also for a scale change -between the clouds (that is, a similarity transform). - -More precisely, given two point clouds, R (the reference) and S (the -source), ICP tries to find the best rigid (or similarity) transform T -so that T * S = R. - -The [Wikipedia article on ICP](https://en.wikipedia.org/wiki/Iterative_closest_point) has more -information. - -libpointmatcher implements a [set of filters](Datafilters.md) to help -denoise and subsample the input point clouds. It supports a [variety -of file types](ImportExport.md) and it can be configured via both -[YAML files](Configuration.md) and an [in-memory API](icpWithoutYaml.md). - -libpointmatcher is written in C++. - - diff --git a/thirdparty/libpointmatcher/doc/LinkingProjects.md b/thirdparty/libpointmatcher/doc/LinkingProjects.md deleted file mode 100644 index 259bff9..0000000 --- a/thirdparty/libpointmatcher/doc/LinkingProjects.md +++ /dev/null @@ -1,98 +0,0 @@ -| [Tutorials Home](index.md) | [Previous](Configuration.md) | [Next](UsingInRos.md) | -| ------------- |:-------------:| -----:| - -# Linking Projects to libpointmatcher - -Once you have followed the [compilation instructions](Compilation.md) and installed libpointmatcher to your system, you can use libpointmatcher in your project. - -## Option 1: Using CMake (Recommended) -Because libpointmatcher was build using CMake, it can be conveniently included in other CMake projects. You can simply use the `find_package` functionality of CMake to locate the installation directory of libpointmatcher. Add `$POINTMATCHER_INCLUDE_DIRS` to the list of include directories in your project and link the appropriate executables to `$POINTMATCHER_LIBRARIES`. - -In this following example, we build a very simple CMake project containing one executable in `myProgram.cpp` which depends on libpointmatcher. - -```cmake -cmake_minimum_required (VERSION 2.6) -project (myProject) - -find_package(libpointmatcher 1.1.0 REQUIRED) -include_directories("${libpointmatcher_INCLUDE_DIRS}") -message(STATUS "Using libpointmatcher version ${libpointmatcher_VERSION}") - -add_executable(myProgram myProgram.cpp) -target_link_libraries(myProgram ${libpointmatcher_LIBRARIES}) -``` -A working example of how to link to an external project can be found in [./examples/demo_cmake](../examples/demo_cmake). - -## Option 2: Using Eclipse -### Using the Native Eclipse Builder -We will demonstrate how to create an Eclipse project containing a simple executable which depends on libpointmatcher. You must have [Eclipse CDT](http://www.eclipse.org/cdt/) installed to develop with libpointmatcher in Eclipse. - -Create a new C++ project by clicking `File > New > C++ Project`. You can name your project "PointmatcherEclipseDemo" and in toolchains select the default toolchain for your system (most likely Linux GCC). Click `Finish` to add your project to your Eclipse workspace. - -You must then configure the project by going to `Project > Properties > C/C++Build > Settings`. Navigate to `C++ Compiler > Includes` and add the libpointmatcher include path to the `Include paths (-I)` list. Next, go to `C++ Linker/Libraries` and add the the following three dependencies to the "Libraries (-l)" list: - -* pointmatcher -* boost_system -* nabo - -Click `Ok` to save the configuration. Create a new source file by clicking `File > New > Source File` and name it "Demo.cpp". In this file you can type the following: - -```cpp -#include -#include - -typedef PointMatcher PM; - - -int main(int argc, char *argv[]) { - PM::ICP icp; - icp.setDefault(); - - std::cout << "ICP configured to default." << std::endl; - return 0; -} -``` -The program will create an ICP chain, configure it to the default settings and exit subsequently. Click on `Project > Build Project` and check that the project compiles successfully. Finally run the program by clicking `Run > Run`. The message "ICP configured to default." should be displayed in the console. - -## Option 3: Using Eclipse -You will need to generate a `.pro` file containing your project information. This file would look like this: - -``` -QT += core gui -greaterThan(QT_MAJOR_VERSION, 4): QT += widgets -TARGET = LAUPointMatcher -TEMPLATE = app -SOURCES += main.cpp - -INCLUDEPATH += /Users/francoispomerleau/Research/Code/libpointmatcher/pointmatcher \ - /Users/francoispomerleau/Research/Code/libnabo/ \ - /usr/local/Cellar/eigen/3.2.4/include/eigen3 \ - /usr/local/include/ - -CONFIG += c++11 -#QMAKE_CXXFLAGS += -mmacosx-version-min=10.7 -#QMAKE_LFLAGS += -mmacosx-version-min=10.7 - -LIBS += /usr/local/lib/libboost_thread-mt.dylib \ - /usr/local/lib/libboost_filesystem-mt.dylib \ - /usr/local/lib/libboost_system-mt.dylib \ - /usr/local/lib/libboost_program_options-mt.dylib \ - /usr/local/lib/libboost_date_time-mt.dylib \ - /usr/local/lib/libboost_chrono-mt.dylib \ - /Users/francoispomerleau/Research/Code/libpointmatcher/build/libpointmatcher.a \ - /Users/francoispomerleau/Research/Code/libnabo/build/libnabo.a \ - /Users/francoispomerleau/Research/Code/libpointmatcher/build/contrib/yaml-cpp-pm/libyaml-cpp-pm.a -``` - -A working example of how to link to an external project can be found in [./examples/demo_Qt](../examples/demo_Qt). - -## Option 4: Using Compiler Flags -If you are compiling a very simple program without the use of a builder, simply include the libpointmatcher header files by setting the include flag in your compiler. Example: -``` -g++ -I/usr/local/include/pointmatcher -o myProgram.o -c myProgram.cpp -``` -You can then link to the pointmatcher library using: -``` -g++ myProgram.o -o myProgram -lpointmatcher -lnabo -lboost_system -lyaml-cpp -lboost_filesystem -lrt -``` -Nevertheless, it is always more convenient to use a builder such as CMake. diff --git a/thirdparty/libpointmatcher/doc/Pointclouds.md b/thirdparty/libpointmatcher/doc/Pointclouds.md deleted file mode 100644 index 68db748..0000000 --- a/thirdparty/libpointmatcher/doc/Pointclouds.md +++ /dev/null @@ -1,32 +0,0 @@ -| [Tutorials Home](index.md) | [Previous](UsingInRos.md) | [Next](Transformations.md) | -| ------------- |:-------------:| -----:| - -# Point Clouds in Libpointmatcher - -The base structure containing library functionality is called `PointMatcher`. It is restricted to a particular scalar type T through the use of a template: `PointMatcher`. In almost all situations the type T will either be `double` or `float` and provides developers with the flexibility of choosing which best suits their application. For simplicity, we recommend using an abbreviated type identifier for `PointMatcher`. This could for example be the following: -```cpp -typedef PointMatcher PM; -``` - -In libpointmatcher, point clouds are encapsulated in `DataPoints` objects. DataPoints objects are composed of the following members : - -* Features matrix -* Feature Labels -* Descriptors matrix -* Descriptor Labels - -### Features Matrix -Features is an [Eigen matrix](http://eigen.tuxfamily.org/dox/classEigen_1_1Matrix.html) typically containing the coordinates of the points which form the cloud. Each column corresponds to a point in the cloud. The rows correspond to the dimensions of the points in homogeneous coordinates. Homogeneous coordinates are used to allow for translations and rotations. For 2D point clouds, there will thus be 3 rows and for 4 rows for 3D point clouds. - -![features matrix](images/featuresMatrix.png) - -### Feature Labels -Each row of the features matrix can be given a human readable label such as ¨X¨,¨Y¨, or ¨Z¨ and the group of labels is stored as a vector. - -### Descriptors -Descriptors are additional information about each point in the cloud. For example these may include an orientation vector pointing to the sensor location, or a surface normal vector. Following the structure of the features matrix, descriptors are stored in a single Eigen matrix with each column representing a point in the cloud. Descriptors are stacked in the rows of the features matrix and thus a single descriptors will span several rows. - -![descriptors matrix](images/descriptorsMatrix.png) - -### Descriptor Labels -Human readable labels are used to identify the individual descriptors in the descriptors matrix. For example if the point cloud contains a 3D orientation and 3D surface normal descriptors for each points we may assign the label: "orientation" to the first three rows of the descriptor matrix and the label "normal" to the last three. diff --git a/thirdparty/libpointmatcher/doc/ReleaseNotes.md b/thirdparty/libpointmatcher/doc/ReleaseNotes.md deleted file mode 100644 index 5716153..0000000 --- a/thirdparty/libpointmatcher/doc/ReleaseNotes.md +++ /dev/null @@ -1,40 +0,0 @@ -Release Notes -============= - -Wish list for next release --------------------------- - - * Change the API to allow only on kind of transformation, not a list of transformations. See issue [#164](https://github.com/ethz-asl/libpointmatcher/issues/164). - * Migrate ffrom yaml-cpp 0.3 to 0.5 - * Fix portability problem with FileLogger on Windows - * Support for OpenMP parallel computing - * Handle larger point clouds (100 million points and more) - -Already implemented in the current master: - - * add a new OutlierFilter: RobustWelschOutlierFilter (for robust cost function using Welsch weighting). - * Add a new ErrorMinimizer: PointToPointSimilarityErrorMinimizer (rotation + translation + scale) - * Add a new Transformation: SimilarityTransformation. - * Add a new data filter: [VoxelGrid](https://github.com/ethz-asl/libpointmatcher/blob/master/doc/Datafilters.md#voxel-grid-filter-) (April 2014, thanks to Samuel Charreyron) - * Add support for PCL ([Point Cloud Library](http://pointclouds.org/)) data format: PCD (April 2014, thanks to Samuel Charreyron) - * Improve *.vtk legacy format to handle UNSTRUCTURED_GRID format (April 2014, thanks to Samuel Charreyron) - * New ErrorMinimizer producing covariance matrix (1 April, 2014, thanks to Francisco J Perez Grau) - * Better user [documentation and tutorials](https://github.com/ethz-asl/libpointmatcher/blob/master/doc/index.md) (5 Fev. 2014 thanks to Samuel Charreyron) - * Avoid point cloud copies when filtering (10 Jan. 2014 thanks to Oleg Alexandrov) - * Add CMake support for find_package (20 Sept. 2013) - * Added support for PLY ([Polygon File Format or the Stanford Triangle Format](http://en.wikipedia.org/wiki/PLY_(file_format))) for ascii encoding (14 March, 2014) - * Improved CSV file support with import/export of selected descriptors - - -Version 1.1.0 --------------- - - * Removed C++0x dependency - * Added compatibility with Visual Studio 11 - * Fixed various bugs - * Added optimisation of 2-D pose with 3-D data - -Version 1.0.0 -------------- - - * First release with a stable API diff --git a/thirdparty/libpointmatcher/doc/TransformationDev.md b/thirdparty/libpointmatcher/doc/TransformationDev.md deleted file mode 100644 index 941ec53..0000000 --- a/thirdparty/libpointmatcher/doc/TransformationDev.md +++ /dev/null @@ -1,138 +0,0 @@ -| [Tutorials Home](Tutorials.md) | [Previous](DataPointsFilterDev.md) | [Next](UnitTestDev.md) | -| ------------- |:-------------:| -----:| - -# Extending libpointmatcher Transformations - -## Defining your own Transformation Class -While rigid transformations cover most of the geometric transformations that are used in point cloud registration, we may be interested in defining our own transformations. In that case we will have to define our own class to represent it and derive this class from the `Transformation` interface class. - -Suppose we are interested in defining a transformation type that only includes 3D translations. For that, we require that the transformation matrix have the following form. - -|**Figure 4:** A 3D transformation matrix representing a pure translation | -|:---| -|![2d translation matrix](images/3dTransMatrix.gif)| - -We will name our new transformation class `PureTranslation`. The `Transformation` interface requires us to define three pure virtual functions: `compute`, `checkParameters`, and `correctParameters`. The class declaration for `PureTranslation` is as follows: - -```cpp -template -class PureTranslation : public PointMatcher::Transformation { - - typedef PointMatcher PM; - typedef typename PM::Transformation Transformation; - typedef typename PM::DataPoints DataPoints; - typedef typename PM::TransformationParameters TransformationParameters; - -public: - virtual DataPoints compute(const DataPoints& input, const TransformationParameters& parameters) const; - virtual bool checkParameters(const TransformationParameters& parameters) const; - virtual TransformationParameters correctParameters(const TransformationParameters& parameters) const; -}; -``` - -We first implement the `checkParameters` function whose purpose is to determine if the transformation parameters match the type of transformation that is to be performed. In our case, we wish to check that the transformation represented in the transformation matrix is indeed a pure translation. This translates to checking that subtracting the rightmost column while ignoring the bottom row from the transformation matrix returns an identity matrix. - -```cpp -template -inline bool PureTranslation::checkParameters( - const TransformationParameters& parameters) const { - const int rows = parameters.rows(); - const int cols = parameters.cols(); - - // make a copy of parameters to perform the check - TransformationParameters parameters_(parameters); - - // set the translation components of the transformation matrix to 0 - parameters_.block(0,cols-1,rows-1,1).setZero(); - - // If we have the identity matrix, than this is indeed a pure translation - if (parameters_.isApprox(TransformationParameters::Identity(rows,cols))) - return true; - else - return false; -} -``` - -Next, we implement the `correctParameters` function to create a pure translation from a regular transformation. In other words, we set the transformation matrix to the identity matrix and add the translation components. - -```cpp -template -inline typename PureTranslation::TransformationParameters PureTranslation::correctParameters( - const TransformationParameters& parameters) const { - const int rows = parameters.rows(); - const int cols = parameters.cols(); - - // make a copy of the parameters to perform corrections on - TransformationParameters correctedParameters(parameters); - - // set the top left block to the identity matrix - correctedParameters.block(0,0,rows-1,cols-1).setIdentity(); - - // fix the bottom row - correctedParameters.block(rows-1,0,1,cols-1).setZero(); - correctedParameters(rows-1,cols-1) = 1; - - return correctedParameters; -} -``` -Now that we have properly defined our transformation object representing pure translations, we can use it in our code. We modify the code from the previous example to use our `PureTranslation` object. Running this code should produce the same results as in the previous case. - -```cpp -int main(int argc, char *argv[]) { - if (argc != 3) { - std::cerr << "Error: invalid number of arguments" << std::endl; - } - - PM::TransformationParameters T; - T = PM::TransformationParameters::Identity(4,4); - - // Applying a translation in the x direction - T(0,3) = 50; - - std::cout << "Transformation Matrix: " << std::endl << T << std::endl; - - PureTranslation translation; - //translation = PM::get().REG(Transformation).create("RigidTransformation"); - - if (!translation.checkParameters(T)) { - std::cout << "WARNING: T does not represent a valid rigid transformation\nProjecting onto an orthogonal basis" - << std::endl; - T = translation.correctParameters(T); - } - - // Load a point cloud from a file - PM::DataPoints pointCloud; - std::string inputFile = argv[1]; - pointCloud = PM::DataPoints::load(inputFile); - - // Compute the transformation - PM::DataPoints outputCloud = translation.compute(pointCloud,T); - - outputCloud.save(argv[2]); - - std::cout << "Transformed cloud saved to " << argv[2] << std::endl; - return 0; -} -``` -## Making a Custom Transformation a libpointmatcher Module -Suppose we have defined a useful transformation that we wish to add to libpointmatcher for future use. We can as an example make a new libpointmatcher module out of the `PureTranslation` transformation class we just designed. - -Transformation modules live in the `pointmatcher/TransformationsImpl.h` and implemented in the cpp file of the same name. Before copying in our `PureTranslation` class declaration, we will add to it an additional function. The `description` function should return some useful information about the transformation such as its name, requirements, and possible parameters that are used in the transformation. - -```cpp -inline static const std::string description() - { - return "Pure translation transformation\nA rigid transformation with no rotation."; - } -``` - -After adding the class to `TransformationsImpl`, we will add it to the registry as a libpointmatcher module. We do so by adding the following macro in [pointmatcher/Registry.cpp](/pointmatcher/Registry.cpp) - -```cpp -ADD_TO_REGISTRAR_NO_PARAM(Transformation, PureTranslation, typename TransformationsImpl::PureTranslation) -``` - -Now recompile the library and check that the new transformation is listed as an available module by running `pcmip -l | grep -C 10 PureTranslation`. - -## Where To Go From Here -We recommend you try to build your own class of transformations and register it to libpointmatcher. The [next tutorial](UnitTestDev.md) covers how to write test cases to validate your classes. While the tutorial covers test cases for a data filter, you should also write test cases to verify that your transformations function correctly. diff --git a/thirdparty/libpointmatcher/doc/Transformations.md b/thirdparty/libpointmatcher/doc/Transformations.md deleted file mode 100644 index 08a6395..0000000 --- a/thirdparty/libpointmatcher/doc/Transformations.md +++ /dev/null @@ -1,114 +0,0 @@ -| [Tutorials Home](Tutorials.md) | [Previous](Pointclouds.md) | [Next](DataPointsFilterDev.md) | -| ------------- |:-------------:| -----:| - -# Applying Transformations to Point Clouds - -The outcome of a point cloud registration is some rigid transformation which, when applied to the reading point cloud, best aligns it with the reference point cloud. This transformation can be represented algebraically with a square matrix of the dimensions of the homogeneous point coordinates. A point cloud is transformed by left-multiplying it by the transformation matrix. - -In libpointmatcher, transformations are encapsulated in a `TransformationParameters` object, which is itself simply an Eigen matrix. - -### Example: Applying a Translation - -#### Creating a Rigid Transformation Object -As an example, we wish to apply a simple translation to all points in a specified point cloud. A rigid transformation is one that moves the point cloud while preserving the distances between points in the cloud. Rigid transformations can be rotations, translations, and combinations of the two, but not reflections. A rigid transformation is parametrized by a transformation matrix in homogeneous coordinates. Therefore for 2D transformations this is a square 3x3 matrix, and for 3D transformations a 4x4 matrix. Because point cloud registration is concerned with finding an alignment between two point clouds, libpointmatcher provides us with a module for performing rigid transformations. - -|**Figure 1:** A 2D transformation matrix representing a translation (tx,ty) and a clockwise rotation of angle theta about the origin | -|:---| -|![2d transformation matrix](images/2dTransMatrix.gif)| - -In the following example we will apply a simple translation: moving each point in the point cloud by 50 meters in the x direction. The associated transformation matrix is shown below: - -|**Figure 2:** A 3D transformation matrix representing a translation of 50 units in the x direction | -|:---| -|![2d transformation matrix](images/3d50mTrans.gif)| - -We make use of the "RigidTransformation" module provided by libpointmatcher. The `RigidTransformation` class provides several key functions. The `checkParameters` function verifies if a transformation matrix T satisfies the constraints of a rigid transformation: namely that T is orthogonal and has a determinant of 1. The `correctParameters` function can be called if a transformation does not satisfy orthogonal constraints. An orthogonal approximation for T will then be computed. Finally the `compute` function applies the transformation contained in a `TransformationParameters` object. - -In the following example we define a transformation by specifying the TransformationParameters object to represent a translation in the x direction. We do so by setting the top right element of the transformation Eigen matrix to be 50, such that the point cloud will move by 50 meters in the x direction. We apply this transformation to an input point cloud and save the output point cloud. - -```cpp -int main(int argc, char *argv[]) { - if (argc != 3) { - std::cerr << "Error: invalid number of arguments" << std::endl; - } - - PM::TransformationParameters T; - T = PM::TransformationParameters::Identity(4,4); - // Applying a translation in the x direction - T(0,3) = 50; - - std::cout << "Transformation Matrix: " << std::endl << T << std::endl; - - PM::Transformation* rigidTrans; - rigidTrans = PM::get().REG(Transformation).create("RigidTransformation"); - - if (!rigidTrans->checkParameters(T)) { - std::cout << "WARNING: T does not represent a valid rigid transformation\nProjecting onto an orthogonal basis" - << std::endl; - T = rigidTrans->correctParameters(T); - } - - // Load a point cloud from a file - PM::DataPoints pointCloud; - std::string inputFile = argv[1]; - pointCloud = PM::DataPoints::load(inputFile); - - // Compute the transformation - PM::DataPoints outputCloud = rigidTrans->compute(pointCloud,T); - - outputCloud.save(argv[2]); - - std::cout << "Transformed cloud saved to " << argv[2] << std::endl; - return 0; -} -``` - -The output point cloud can be visualized in Paraview. We see on the following figure that all points have been shifted by 50 meters in the x direction. - -|**Figure 3:** Result of the transformation on `examples/data/car_cloud400.csv`. The white points form the original point cloud, while the green points are the points which were translated. | -|:---| -|![car translated](images/car_translated.png)| - -#### Defining your own Transformation Class -If you use some other type of transformations than rigid transformations, you may wish to create your own transformation class which may perform its own consistency checks. Instructions on designing such a class and adding it as a module to libpointmatcher can be found in [this developer tutorial](TransformationDev.md). - -#### Applying a Manual Transformation -We can also perform transformations by directly applying a transformation on a point cloud. In the following example, we perform a transformation by multiplying a transformation matrix to the original point cloud. Note that **this does not apply the transformation to associated descriptors** such as surface normals or orientation directions. For this reason, this approach is strongly discouraged in practice. The following example code performs the same transformation as in the previous cases: - -```cpp -#include -#include -#include - -typedef PointMatcher PM; - -int main(int argc, char *argv[]) { - - if (argc != 3) { - std::cerr << "Error: invalid number of arguments" << std::endl; - } - - PM::TransformationParameters T; - T = PM::TransformationParameters::Identity(4,4); - // Applying a translation in the x direction - T(0,3) = 50; - - std::cout << "Transformation Matrix: " << std::endl << T << std::endl; - - // Load a point cloud from a file - PM::DataPoints pointCloud; - std::string inputFile = argv[1]; - pointCloud = PM::DataPoints::load(inputFile); - - // Create a second point cloud of same dimension to store transformed cloud - PM::DataPoints outputCloud = pointCloud.createSimilarEmpty(); - - // Apply transformation and store in output point cloud - outputCloud.features = T * pointCloud.features; - - outputCloud.save(argv[2]); - - std::cout << "Transformed cloud saved to " << argv[2] << std::endl; - return 0; -} -``` diff --git a/thirdparty/libpointmatcher/doc/UnitTestDev.md b/thirdparty/libpointmatcher/doc/UnitTestDev.md deleted file mode 100644 index 7fef9c0..0000000 --- a/thirdparty/libpointmatcher/doc/UnitTestDev.md +++ /dev/null @@ -1,263 +0,0 @@ -| [Tutorials Home](Tutorials.md) | [Previous](TransformationDev.md) | [Next]() | -| ------------- |:-------------:| -----:| - -# Testing libpointmatcher Modules -It is often good practice to accompany the development of new software features with the development of test cases which validate that these features are working correctly. When developing for an open source project such as libpointmatcher, testing is crucial to maintain stability and avoid the introduction of erronous code. - -Libpointmatcher uses the [C++ testing framework developed by Google](https://code.google.com/p/googletest/). If you are not sure if you installed libpointmatcher with GTest, go to the libpointmatcher's CMake build directory and run `make test`. If the tests do not run, refer back to the [compilation instructions](Compilation.md) to recompile with GTest. - -Libpointmatcher's unit tests can be found in [utest/utest.cpp](/utest/utest.cpp). In this tutorial, we will write a series of tests for validating the voxel grid filter developed in [this past tutorial](DataPointsFilterDev.md). Note that this test will not cover the myriad of features that GTest provides. Nevertheless, it is very easy to understand GTest without extensive experience. For those who wish to have a solid introduction to GTest we recommend to start with this [this primer](http://code.google.com/p/googletest/wiki/Primer). - - -## A Unit Test for the Voxel Grid Filter - -Data filter tests are covered by the `DataFilterTest` test cast in utest.cpp. We define a new test unit called `VoxelGridDataPointsFilterTest` following the convention used for the other filters. This test unit will in fact contain several tests that are detailed subsequently. - -```cpp -TEST(DataFilterTest, VoxelGridDataPointsFilterTest) -``` - -### Test 1: 2D Case -In the following test, we create a 2D point cloud point cloud where each voxel contains a grid of unformly spaced points. We define variables setting the number of divisions of the bounding region to form voxels, and the total number of points that are contained along each division. We obtain a point cloud of the following form: - -|**Figure 1:** 2D Grid containing 100 regularily spaced points per voxel and 100 voxels| -|:-------------------------------------------------------------------------------------| -|![2dvoxeltest](images/2dtestgrid.png)| - -The points are placed such that each voxel centroid should be in the middle of the voxel. The validation point cloud to which we compare results will thus consist of the voxel centers. After performing filtering on the test cloud, we first check that the number of points obtained is indeed equal to the number of voxels with the following line: -```cpp -ASSERT_EQ(testResults.features.cols(), numDivs(0) * numDivs(1) ); -``` -We then check that the output point cloud is what we expected by using Eigen's `isApprox` function. -```cpp -EXPECT_TRUE(testResults.features.isApprox(valCloudP)) -``` - - -Code: - -```cpp -// Number of divisions in each dimension that form the Voxel Grid -const Vector2i numDivs = (Vector2i() << 10, 10).finished(); -const Vector2f divSize = (Vector2f() << 0.1f ,0.1f).finished(); -const Vector2i pointsPerDiv = (Vector2i() << 10 , 10).finished(); - -const int numPoints = numDivs(0) * pointsPerDiv(0) * numDivs(1) * pointsPerDiv(1); - -const float pointSepX = divSize(0) / (pointsPerDiv(0) + 1); // add 1 because we want all points inside voxel -const float pointSepY = divSize(1) / (pointsPerDiv(1) + 1); - -// Input test cloud: Equally spaced points along grid -MatrixXf testCloudP(3,numPoints); -for (int i = 0; i < (numDivs(0) * pointsPerDiv(0)) ; i++ ) -{ - for (int j = 0; j < (numDivs(1) * pointsPerDiv(1) ); j++ ) - { - int p = i + j * numDivs(0) * pointsPerDiv(0); - - testCloudP(0,p) = i/pointsPerDiv(0) * divSize(0) + (i % pointsPerDiv(0) + 1) * pointSepX; - testCloudP(1,p) = j/pointsPerDiv(1) * divSize(1) + (j % pointsPerDiv(1) + 1) * pointSepY; - testCloudP(2,p) = 1.f; - } -} - -// Validation cloud: centers of each voxel -MatrixXf valCloudP(3,numDivs(0) * numDivs(1)); -for (int i = 0; i < numDivs(0); i++) -{ - for (int j = 0; j < numDivs(1); j++) - { - int p = i + j * numDivs(0); - valCloudP(0,p) = i * divSize(0) + divSize(0) / 2.f; - valCloudP(1,p) = j * divSize(1) + divSize(1) / 2.f; - valCloudP(2,p) = 1.f; - } -} - -DP::Labels featLabels; -featLabels.push_back(DP::Label("X",1)); -featLabels.push_back(DP::Label("Y",1)); - -DP testCloud(testCloudP,featLabels); - -PM::Parameters params = boost::assign::map_list_of("vSizeX",toParam(divSize(0))) - ("vSizeY",toParam(divSize(1))); - -VoxelGridDataPointsFilter vFilter(params); - -DP testResults = vFilter.filter(testCloud); - -ASSERT_EQ(testResults.features.cols(), numDivs(0) * numDivs(1) ); - -EXPECT_TRUE(testResults.features.isApprox(valCloudP)); -``` - -### Test 2: 3D Case - -The identical test is performed, this time in 3D. Instead of squares, voxels are now cubes containing equally spaced points. We again expect the voxel centroids to coincide with the voxel centers. - -code: - -```cpp -// Number of divisions in each dimension that form the Voxel Grid -const Vector3i numDivs = (Vector3i() << 10, 10, 10).finished(); -const Vector3f divSize = (Vector3f() << 0.1f, 0.1f, 0.1f).finished(); -const Vector3i pointsPerDiv = (Vector3i() << 10 , 10, 10).finished(); - -const int numPoints = numDivs(0) * pointsPerDiv(0) * numDivs(1) * pointsPerDiv(1) * numDivs(2) * pointsPerDiv(2); - -const float pointSepX = divSize(0) / (pointsPerDiv(0) + 1); // add 1 because we want all points inside voxel -const float pointSepY = divSize(1) / (pointsPerDiv(1) + 1); -const float pointSepZ = divSize(2) / (pointsPerDiv(1) + 1); - -// Input test cloud: Equally spaced points along grid -MatrixXf testCloudP(4,numPoints); -for (int i = 0; i < (numDivs(0) * pointsPerDiv(0)) ; i++ ) -{ - for (int j = 0; j < (numDivs(1) * pointsPerDiv(1) ); j++ ) - { - for (int k = 0; k < (numDivs(2) * pointsPerDiv(2)); k++) - { - int p = i + j * numDivs(0) * pointsPerDiv(0) + k * numDivs(0) * pointsPerDiv(0) * numDivs(1) * pointsPerDiv(1); - - testCloudP(0,p) = i/pointsPerDiv(0) * divSize(0) + (i % pointsPerDiv(0) + 1) * pointSepX; - testCloudP(1,p) = j/pointsPerDiv(1) * divSize(1) + (j % pointsPerDiv(1) + 1) * pointSepY; - testCloudP(2,p) = k/pointsPerDiv(2) * divSize(2) + (k % pointsPerDiv(2) + 1) * pointSepZ; - testCloudP(3,p) = 1.f; - } - } -} - -// Validation cloud: centers of each voxel -MatrixXf valCloudP(4,numDivs(0) * numDivs(1) * numDivs(2)); -for (int i = 0; i < numDivs(0); i++) -{ - for (int j = 0; j < numDivs(1); j++) - { - for (int k = 0; k < numDivs(2); k++) - { - int p = i + j * numDivs(0) + k * numDivs(0) * numDivs(1); - valCloudP(0,p) = i * divSize(0) + divSize(0) / 2.f; - valCloudP(1,p) = j * divSize(1) + divSize(1) / 2.f; - valCloudP(2,p) = k * divSize(2) + divSize(2) / 2.f; - valCloudP(3,p) = 1.f; - } - } -} - -DP::Labels labels; -labels.push_back(DP::Label("X",1)); -labels.push_back(DP::Label("Y",1)); -labels.push_back(DP::Label("Z",1)); - -DP testCloud(testCloudP,labels); - -PM::Parameters params = boost::assign::map_list_of("vSizeX",toParam(divSize(0)))("vSizeY",toParam(divSize(1)))("vSizeZ",toParam(divSize(2))); - -VoxelGridDataPointsFilter vFilter(params); - -DP testResults = vFilter.filter(testCloud); - -ASSERT_EQ(testResults.features.cols(), numDivs(0) * numDivs(1) * numDivs(2) ); - -EXPECT_TRUE(testResults.features.isApprox(valCloudP)); -``` - -### Test 3: Averaging Descriptors -To make sure that descriptors are averaged correctly, we use the same 2D point cloud as in Test 1. For each voxel, we make each descriptor in the left half equal to a vector containing the value 1. We make descriptors in the right half equal to a vector containing the value -1. We expect to obtain a zero vector when averaging these vectors. - -After filtering, we check that the number of descriptors is equal to the number of voxels: - -```cpp -ASSERT_EQ(testResults.descriptors.cols(), numDivs(0) * numDivs(1) ); -``` - -We check that the descriptors in the output cloud are all zero using Eigen's `isZero` function. - -```cpp -EXPECT_TRUE(testResults.descriptors.isZero()); -``` - -code: -```cpp -// Number of divisions in each dimension that form the Voxel Grid -const Vector2i numDivs = (Vector2i() << 10, 10).finished(); -const Vector2f divSize = (Vector2f() << 0.1f ,0.1f).finished(); -const Vector2i pointsPerDiv = (Vector2i() << 10 , 10).finished(); - -const int numPoints = numDivs(0) * pointsPerDiv(0) * numDivs(1) * pointsPerDiv(1); - -const float pointSepX = divSize(0) / (pointsPerDiv(0) + 1); // add 1 because we want all points inside voxel -const float pointSepY = divSize(1) / (pointsPerDiv(1) + 1); - -// Input test cloud: Equally spaced points along grid -// Descriptors: half pointing up, half pointing down -MatrixXf testCloudP(3, numPoints); -MatrixXf testCloudD(3, numPoints); -testCloudD.setZero(); -for (int i = 0; i < (numDivs(0) * pointsPerDiv(0)) ; i++ ) -{ - for (int j = 0; j < (numDivs(1) * pointsPerDiv(1) ); j++ ) - { - int p = i + j * numDivs(0) * pointsPerDiv(0); - - testCloudP(0,p) = i/pointsPerDiv(0) * divSize(0) + (i % pointsPerDiv(0) + 1) * pointSepX; - testCloudP(1,p) = j/pointsPerDiv(1) * divSize(1) + (j % pointsPerDiv(1) + 1) * pointSepY; - testCloudP(2,p) = 1.f; - - // for first half of points, descriptor is 3D vector pointing up - if ((i % pointsPerDiv(0)) >= pointsPerDiv(0)/2 ) - { - testCloudD(2,p) = 1.f; - } else { - testCloudD(2,p) = -1.f; - } - } -} - -DP::Labels featLabels; -featLabels.push_back(DP::Label("X",1)); -featLabels.push_back(DP::Label("Y",1)); - -DP::Labels descLabels; -descLabels.push_back(DP::Label("normal",3)); - -DP testCloud(testCloudP,featLabels,testCloudD,descLabels); - -PM::Parameters params = boost::assign::map_list_of("vSizeX",toParam(divSize(0))) -("vSizeY",toParam(divSize(1))) -("averageExistingDescriptors",toParam("1")); - -VoxelGridDataPointsFilter vFilter(params); - -DP testResults = vFilter.filter(testCloud); - -ASSERT_EQ(testResults.descriptors.cols(), numDivs(0) * numDivs(1) ); - -EXPECT_TRUE(testResults.descriptors.isZero()); -``` - -### Running the Tests -You can check that these tests are run succesfully by executing the following command from libpointmatcher's build directory -``` -./utest/utest --path ../examples/data/ --gtest_filter=DataFilterTest.VoxelGridDataPointsFilter -``` - -## Generic tests - -To avoid writting the same basic test for a given combination of solution, a generic test uses a list of yaml files and executes them to verify that the solution is the same as before. This list can be found here: [examples/data/icp_data/](../examples/data/icp_data/) - -There are two types of files with the same name, but with a different extension. The first one is the `.yaml` which contains the solution to be tested (see [Configurations with YAML](../doc/Configuration.md)). The second one is the `.ref_trans`, which contains the 4 by 4 matrix used as the valid output. - -The steps to add a new test is the following: - - 1. Add a yaml file in `examples/data/icp_data/` with the desired configuration to test. - 1. In this configuration, add a `VTKFileInspector` as in [this tutorial](https://github.com/ethz-asl/libpointmatcher/blob/master/doc/ICPIntro.md#a-real-icp-configuration). - 1. Run the unit tests (the test will fail, it's normal): `./utest/utest --path ../examples/data/ --gtest_filter=icpTest.icpTest` - 1. Use Paraview to manually validate that the final transformation is correct using the files generated by the `VTKFileInspector`. - 1. If everything is fine, remove the `VTKFileInspector` from the yaml file. If not, fix it. - 1. Clean your folder from any files generated by the `VTKFileInspector`. - 1. There will be a file with the same name as your yaml file with the extension `.cur_trans`. Change the extension to `.ref_trans`. - 1. Run the unit test again, this time it should pass. - 1. Add your new files with the extension `.yaml` and `.ref_trans` to your branch. - 1. Ask for a pull request. diff --git a/thirdparty/libpointmatcher/doc/UsingInRos.md b/thirdparty/libpointmatcher/doc/UsingInRos.md deleted file mode 100644 index c1d107e..0000000 --- a/thirdparty/libpointmatcher/doc/UsingInRos.md +++ /dev/null @@ -1,6 +0,0 @@ -| [Tutorials Home](index.md) | [Previous](LinkingProjects.md) | [Next](Pointclouds.md) | -| ------------- |:-------------:| -----:| - -# Using libpointmatcher in ROS - -If you want to use libpointmatcher in [ROS](http://www.ros.org/), you can use the [ethzasl_icp_mapping](https://github.com/ethz-asl/ethzasl_icp_mapping) stack. It allows the conversion of pointclouds from ROS message formats to a libpointmatcher-compatible format and provides a mapping node that is already functionnal and that can be customized using YAML configuration files to suite your needs. It also provides an odometry estimation based on the results of the pointcloud registrations. It includes a wide range of launch files that can be used as usage examples of the different nodes of the stack. Finally, it is recommended to install it from sources rather than from apt-get, because the last release was a long time ago, and it might not be working. diff --git a/thirdparty/libpointmatcher/doc/icpWithoutYaml.md b/thirdparty/libpointmatcher/doc/icpWithoutYaml.md deleted file mode 100644 index a72db33..0000000 --- a/thirdparty/libpointmatcher/doc/icpWithoutYaml.md +++ /dev/null @@ -1,124 +0,0 @@ -# Example of an ICP solution without yaml - -See [examples/icp_customized.cpp](../examples/icp_customized.cpp) for a working example. - -Here are the important part of the example. First, generate an empty ICP object with some generic variables: -```c++ -// Create the default ICP algorithm -PM::ICP icp; -PointMatcherSupport::Parametrizable::Parameters params; -std::string name; -``` -Prepare the objects for the DataFilters: -```c++ -// Prepare reading filters -name = "MinDistDataPointsFilter"; -params["minDist"] = "1.0"; -PM::DataPointsFilter* minDist_read = - PM::get().DataPointsFilterRegistrar.create(name, params); -params.clear(); - -name = "RandomSamplingDataPointsFilter"; -params["prob"] = "0.05"; -PM::DataPointsFilter* rand_read = - PM::get().DataPointsFilterRegistrar.create(name, params); -params.clear(); - -// Prepare reference filters -name = "MinDistDataPointsFilter"; -params["minDist"] = "1.0"; -PM::DataPointsFilter* minDist_ref = - PM::get().DataPointsFilterRegistrar.create(name, params); -params.clear(); - -name = "RandomSamplingDataPointsFilter"; -params["prob"] = "0.05"; -PM::DataPointsFilter* rand_ref = - PM::get().DataPointsFilterRegistrar.create(name, params); -params.clear(); -``` - -Prepare the objects for the Matchers: -```c++ -// Prepare matching function -name = "KDTreeMatcher"; -params["knn"] = "1"; -params["epsilon"] = "3.16"; -PM::Matcher* kdtree = - PM::get().MatcherRegistrar.create(name, params); -params.clear(); -``` - -Prepare the objects for the OutlierFilters: -```c++ -// Prepare outlier filters -name = "TrimmedDistOutlierFilter"; -params["ratio"] = "0.75"; -PM::OutlierFilter* trim = - PM::get().OutlierFilterRegistrar.create(name, params); -params.clear(); -``` - -Prepare the object for the ErrorMinimizer: -```c++ -// Prepare error minimization -name = "PointToPointErrorMinimizer"; -PM::ErrorMinimizer* pointToPoint = - PM::get().ErrorMinimizerRegistrar.create(name); -``` - -Prepare the objects for the TransformationCheckers: -```c++ -// Prepare outlier filters -name = "CounterTransformationChecker"; -params["maxIterationCount"] = "150"; -PM::TransformationChecker* maxIter = - PM::get().TransformationCheckerRegistrar.create(name, params); -params.clear(); - -name = "DifferentialTransformationChecker"; -params["minDiffRotErr"] = "0.001"; -params["minDiffTransErr"] = "0.01"; -params["smoothLength"] = "4"; -PM::TransformationChecker* diff = - PM::get().TransformationCheckerRegistrar.create(name, params); -params.clear(); - -``` - -Prepare the objects for the Inspector: -```c++ -// Prepare inspector -PM::Inspector* nullInspect = - PM::get().InspectorRegistrar.create("NullInspector"); - -``` - -Prepare the objects for the Transformation: -```c++ -// Prepare transformation -PM::Transformation* rigidTrans = - PM::get().TransformationRegistrar.create("RigidTransformation"); -``` -Finally, build the complet solution: -```c++ -// Build ICP solution -icp.readingDataPointsFilters.push_back(minDist_read); -icp.readingDataPointsFilters.push_back(rand_read); - -icp.referenceDataPointsFilters.push_back(minDist_ref); -icp.referenceDataPointsFilters.push_back(rand_ref); - -icp.matcher.reset(kdtree); - -icp.outlierFilters.push_back(trim); - -icp.errorMinimizer.reset(pointToPoint); - -icp.transformationCheckers.push_back(maxIter); -icp.transformationCheckers.push_back(diff); - -icp.inspector.reset(nullInspect); - -icp.transformations.push_back(rigidTrans); -``` diff --git a/thirdparty/libpointmatcher/doc/images/.DS_Store b/thirdparty/libpointmatcher/doc/images/.DS_Store deleted file mode 100644 index 5008ddf..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/.DS_Store and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/2dTransMatrix.gif b/thirdparty/libpointmatcher/doc/images/2dTransMatrix.gif deleted file mode 100644 index 2b13e08..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/2dTransMatrix.gif and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/2dtestgrid.png b/thirdparty/libpointmatcher/doc/images/2dtestgrid.png deleted file mode 100644 index 620a682..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/2dtestgrid.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/2dvxgrid.png b/thirdparty/libpointmatcher/doc/images/2dvxgrid.png deleted file mode 100644 index f33112d..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/2dvxgrid.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/3d50mTrans.gif b/thirdparty/libpointmatcher/doc/images/3d50mTrans.gif deleted file mode 100644 index 7b5c71a..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/3d50mTrans.gif and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/3dTransMatrix.gif b/thirdparty/libpointmatcher/doc/images/3dTransMatrix.gif deleted file mode 100644 index 8484bef..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/3dTransMatrix.gif and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/DefaultConvertChain.png b/thirdparty/libpointmatcher/doc/images/DefaultConvertChain.png deleted file mode 100644 index caf5ee3..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/DefaultConvertChain.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/appt_0_maxdens.png b/thirdparty/libpointmatcher/doc/images/appt_0_maxdens.png deleted file mode 100644 index cce15b8..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/appt_0_maxdens.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/appt_0_rand.png b/thirdparty/libpointmatcher/doc/images/appt_0_rand.png deleted file mode 100644 index 074bd1a..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/appt_0_rand.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/appt_dir.png b/thirdparty/libpointmatcher/doc/images/appt_dir.png deleted file mode 100644 index 1d28670..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/appt_dir.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/appt_norm.png b/thirdparty/libpointmatcher/doc/images/appt_norm.png deleted file mode 100644 index 838213f..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/appt_norm.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/appt_obs_dir.png b/thirdparty/libpointmatcher/doc/images/appt_obs_dir.png deleted file mode 100644 index d440116..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/appt_obs_dir.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/appt_rand.png b/thirdparty/libpointmatcher/doc/images/appt_rand.png deleted file mode 100644 index 5d83791..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/appt_rand.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/appt_samp_norm_dense.png b/thirdparty/libpointmatcher/doc/images/appt_samp_norm_dense.png deleted file mode 100644 index 4b50b5a..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/appt_samp_norm_dense.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/appt_samp_norm_sparse.png b/thirdparty/libpointmatcher/doc/images/appt_samp_norm_sparse.png deleted file mode 100644 index a4fb01f..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/appt_samp_norm_sparse.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/appt_top.png b/thirdparty/libpointmatcher/doc/images/appt_top.png deleted file mode 100644 index 66fc217..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/appt_top.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/appt_voxel.png b/thirdparty/libpointmatcher/doc/images/appt_voxel.png deleted file mode 100644 index 9c9cafd..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/appt_voxel.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/banner_dark.jpeg b/thirdparty/libpointmatcher/doc/images/banner_dark.jpeg deleted file mode 100644 index 11d7fd0..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/banner_dark.jpeg and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/banner_light.jpeg b/thirdparty/libpointmatcher/doc/images/banner_light.jpeg deleted file mode 100644 index 31cfdd4..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/banner_light.jpeg and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/box_filt.png b/thirdparty/libpointmatcher/doc/images/box_filt.png deleted file mode 100644 index 5f725ba..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/box_filt.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/box_filt_inside.png b/thirdparty/libpointmatcher/doc/images/box_filt_inside.png deleted file mode 100644 index 85b132e..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/box_filt_inside.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/box_filt_outside.png b/thirdparty/libpointmatcher/doc/images/box_filt_outside.png deleted file mode 100644 index e966c27..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/box_filt_outside.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/car_example.png b/thirdparty/libpointmatcher/doc/images/car_example.png deleted file mode 100644 index 67dd4ea..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/car_example.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/car_translated.png b/thirdparty/libpointmatcher/doc/images/car_translated.png deleted file mode 100644 index ccaeb13..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/car_translated.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/cmake_screenshot.png b/thirdparty/libpointmatcher/doc/images/cmake_screenshot.png deleted file mode 100644 index a2fa6c0..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/cmake_screenshot.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/default_icp_chain.png b/thirdparty/libpointmatcher/doc/images/default_icp_chain.png deleted file mode 100644 index 1aeacb9..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/default_icp_chain.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/descriptorsMatrix.png b/thirdparty/libpointmatcher/doc/images/descriptorsMatrix.png deleted file mode 100644 index 6f28aea..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/descriptorsMatrix.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/distance_limit.png b/thirdparty/libpointmatcher/doc/images/distance_limit.png deleted file mode 100644 index 6230430..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/distance_limit.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/featuresMatrix.png b/thirdparty/libpointmatcher/doc/images/featuresMatrix.png deleted file mode 100644 index 29b35e6..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/featuresMatrix.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/floor_plan.png b/thirdparty/libpointmatcher/doc/images/floor_plan.png deleted file mode 100644 index 6c512c7..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/floor_plan.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/hg_noise.png b/thirdparty/libpointmatcher/doc/images/hg_noise.png deleted file mode 100644 index 41d7243..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/hg_noise.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/icp_tutorial_links.gif b/thirdparty/libpointmatcher/doc/images/icp_tutorial_links.gif deleted file mode 100644 index 4ea4332..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/icp_tutorial_links.gif and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/icp_tutorial_reading.gif b/thirdparty/libpointmatcher/doc/images/icp_tutorial_reading.gif deleted file mode 100644 index 064adfe..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/icp_tutorial_reading.gif and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/max_dens_after.png b/thirdparty/libpointmatcher/doc/images/max_dens_after.png deleted file mode 100644 index 30d611d..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/max_dens_after.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/max_dens_before.png b/thirdparty/libpointmatcher/doc/images/max_dens_before.png deleted file mode 100644 index 11ffd20..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/max_dens_before.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/max_dis.png b/thirdparty/libpointmatcher/doc/images/max_dis.png deleted file mode 100644 index 6230430..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/max_dis.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/max_num.png b/thirdparty/libpointmatcher/doc/images/max_num.png deleted file mode 100644 index 75056a6..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/max_num.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/max_quant.png b/thirdparty/libpointmatcher/doc/images/max_quant.png deleted file mode 100644 index 045a87a..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/max_quant.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/modular_cloud_matcher_icp_chain.png b/thirdparty/libpointmatcher/doc/images/modular_cloud_matcher_icp_chain.png deleted file mode 100644 index 03153cd..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/modular_cloud_matcher_icp_chain.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/norm.png b/thirdparty/libpointmatcher/doc/images/norm.png deleted file mode 100644 index 73ebcf0..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/norm.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/orient_norm.png b/thirdparty/libpointmatcher/doc/images/orient_norm.png deleted file mode 100644 index 2fef11c..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/orient_norm.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/paraview_2_clouds.png b/thirdparty/libpointmatcher/doc/images/paraview_2_clouds.png deleted file mode 100644 index 79df151..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/paraview_2_clouds.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/paraview_main.png b/thirdparty/libpointmatcher/doc/images/paraview_main.png deleted file mode 100644 index abef140..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/paraview_main.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/paraview_point_properties.png b/thirdparty/libpointmatcher/doc/images/paraview_point_properties.png deleted file mode 100644 index 6361d6b..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/paraview_point_properties.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/samp_norm.png b/thirdparty/libpointmatcher/doc/images/samp_norm.png deleted file mode 100644 index 61148b4..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/samp_norm.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/win_cmake_libnabo.png b/thirdparty/libpointmatcher/doc/images/win_cmake_libnabo.png deleted file mode 100755 index 7cf549c..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/win_cmake_libnabo.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/win_cmake_libpointmatcher.png b/thirdparty/libpointmatcher/doc/images/win_cmake_libpointmatcher.png deleted file mode 100755 index 15e0fc4..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/win_cmake_libpointmatcher.png and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/youtubeCovers/M5Y99o7um88.jpg b/thirdparty/libpointmatcher/doc/images/youtubeCovers/M5Y99o7um88.jpg deleted file mode 100644 index 0a1f2e0..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/youtubeCovers/M5Y99o7um88.jpg and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/youtubeCovers/McxpJGOZTPs.jpg b/thirdparty/libpointmatcher/doc/images/youtubeCovers/McxpJGOZTPs.jpg deleted file mode 100644 index 16d27b1..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/youtubeCovers/McxpJGOZTPs.jpg and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/youtubeCovers/UCCAUf64tD0.jpg b/thirdparty/libpointmatcher/doc/images/youtubeCovers/UCCAUf64tD0.jpg deleted file mode 100644 index e93fc84..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/youtubeCovers/UCCAUf64tD0.jpg and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/youtubeCovers/cMgLyLpnsoU.jpg b/thirdparty/libpointmatcher/doc/images/youtubeCovers/cMgLyLpnsoU.jpg deleted file mode 100644 index fa20844..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/youtubeCovers/cMgLyLpnsoU.jpg and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/youtubeCovers/g8l-Xq4qYeE.jpg b/thirdparty/libpointmatcher/doc/images/youtubeCovers/g8l-Xq4qYeE.jpg deleted file mode 100644 index 4b7d861..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/youtubeCovers/g8l-Xq4qYeE.jpg and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/youtubeCovers/lP5Mj-TGaiw.jpg b/thirdparty/libpointmatcher/doc/images/youtubeCovers/lP5Mj-TGaiw.jpg deleted file mode 100644 index 9c523f9..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/youtubeCovers/lP5Mj-TGaiw.jpg and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/youtubeCovers/rIZud3F5IJw.jpg b/thirdparty/libpointmatcher/doc/images/youtubeCovers/rIZud3F5IJw.jpg deleted file mode 100644 index 5b01a5e..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/youtubeCovers/rIZud3F5IJw.jpg and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/youtubeCovers/ygIvzWVfPYk.jpg b/thirdparty/libpointmatcher/doc/images/youtubeCovers/ygIvzWVfPYk.jpg deleted file mode 100644 index f2f64d6..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/youtubeCovers/ygIvzWVfPYk.jpg and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/images/youtubeCovers/youtube-play-button.xcf b/thirdparty/libpointmatcher/doc/images/youtubeCovers/youtube-play-button.xcf deleted file mode 100644 index 2b8b208..0000000 Binary files a/thirdparty/libpointmatcher/doc/images/youtubeCovers/youtube-play-button.xcf and /dev/null differ diff --git a/thirdparty/libpointmatcher/doc/index.md b/thirdparty/libpointmatcher/doc/index.md deleted file mode 100644 index ea01e94..0000000 --- a/thirdparty/libpointmatcher/doc/index.md +++ /dev/null @@ -1,52 +0,0 @@ -![alt tag](images/banner_light.jpeg) - - ---- - -Tutorials -========= - -This page lists the available tutorials for libpointmatcher. The [Beginner Section](#beginner) is aimed at the more casual user and contains high-level information on the various steps of point cloud registration. The [Advanced Section](#advanced) is targeted at those with existing experience with point cloud registration and proficiency in C++ development. Those who wish to contribute to libpointmatcher can follow the guidelines in the [Developer](#developer) section. - -Beginner ---------- - -- [What is libpointmatcher about?](Introduction.md) -- [What can I do with libpointmatcher?](ApplicationsAndPub.md) -- [Ubuntu: How to compile libpointmatcher](Compilation.md) -- [Windows: How to compile libpointmatcher](CompilationWindows.md) -- [Mac OS X: How to compile libpointmatcher](CompilationMac.md) -- [What the different data filters do?](Datafilters.md) -- [Example: Applying a chain of data filters](ApplyingDatafilters.md) -- [Example: An introduction to ICP](ICPIntro.md) -- [The ICP chain configuration and its variants](DefaultICPConfig.md) -- [Configuring libpointmatcher using YAML](Configuration.md) -- [Supported file types and importing/exporting point clouds](ImportExport.md) - -Advanced -------- -- [How to link a project to libpointmatcher?](LinkingProjects.md) -- [How to use libpointmatcher in ROS?](UsingInRos.md) -- [How are point clouds represented?](Pointclouds.md) -- [Example: Writing a program which performs ICP](BasicRegistration.md) -- [How to move a point cloud using a rigid transformation?](Transformations.md) -- [Example: Configure an ICP solution without yaml](icpWithoutYaml.md) -- Measuring Hausdorff distance, Haussdorff quantile and mean residual error? [See this discussion for code examples.](https://github.com/ethz-asl/libpointmatcher/issues/125) -- How to compute the residual error with `ErrorMinimizer::getResidualError(...)` [See the example code provided here.](https://github.com/ethz-asl/libpointmatcher/issues/193#issue-203885636) -- How to I build a global map from a sequence of scans? [See the example align_sequence.cpp](../examples/align_sequence.cpp ). -- How to minimize the error with translation, rotation and scale? [See this example.](https://github.com/ethz-asl/libpointmatcher/issues/188#issuecomment-270960696) -- How to do a nearest neighbor search between two point clouds without an ICP object? [See the comments here.](https://github.com/ethz-asl/libpointmatcher/issues/193#issuecomment-276093785) -- How to construct a `DataPoints` from my own point cloud? [See the unit test on `Datapoints` here.](https://github.com/ethz-asl/libpointmatcher/blob/master/utest/ui/DataFilters.cpp#L52) - -Developer ---------- -- [Creating a DataPointsFilter](DataPointsFilterDev.md) -- [Creating a Transformation](TransformationDev.md) -- [Creating unit tests](UnitTestDev.md) - -**Note**: if you don't find what you need, don't hesitate to propose or participate to new tutorials. - ---- - - -![alt tag](images/banner_dark.jpeg) diff --git a/thirdparty/libpointmatcher/evaluations/CMakeLists.txt b/thirdparty/libpointmatcher/evaluations/CMakeLists.txt deleted file mode 100644 index e80a8da..0000000 --- a/thirdparty/libpointmatcher/evaluations/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -if (yamlcpp_FOUND) - find_package(Curses) - if (CURSES_FOUND) - add_executable(eval_solution eval_solution.cpp) - target_link_libraries(eval_solution pointmatcher ${NABO_LIBRARY} ${EXTRA_LIBS} ${Boost_LIBRARIES} ${CURSES_LIBRARY}) - else(CURSES_FOUND) - message("-- ncurses not found, disabling evaluation") - endif(CURSES_FOUND) -endif (yamlcpp_FOUND) \ No newline at end of file diff --git a/thirdparty/libpointmatcher/evaluations/eval_solution.cpp b/thirdparty/libpointmatcher/evaluations/eval_solution.cpp deleted file mode 100644 index a4328ab..0000000 --- a/thirdparty/libpointmatcher/evaluations/eval_solution.cpp +++ /dev/null @@ -1,662 +0,0 @@ -// kate: replace-tabs off; indent-width 4; indent-mode normal -// vim: ts=4:sw=4:noexpandtab -/* - -Copyright (c) 2010--2012, -François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland -You can contact the authors at and - - -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 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 ETH-ASL 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. - -*/ - -#include "pointmatcher/PointMatcher.h" -#include "pointmatcher/IO.h" -#include "pointmatcher/Timer.h" -#include -#include -#include -#include -#include - -#include - -#include -#include -#include -#include -#include -#include - - -using namespace std; -using namespace PointMatcherSupport; -namespace po = boost::program_options; -namespace fs = boost::filesystem; -namespace pt = boost::posix_time; - -typedef PointMatcher PM; -typedef PointMatcherIO PMIO; -typedef PM::TransformationParameters TP; - -struct DataSetInfo -{ - string name; - bool downloaded; - string path; - DataSetInfo(){}; - DataSetInfo(string name, bool downloaded): - name(name), - downloaded(downloaded) - {} -}; - -struct Config -{ - // Default values - string path_config; - string path_download; - string path_result; - string path_server_validation; - string path_server_protocols; - map dataSetStatus; - - Config() - { - path_config = string(getenv("HOME")) + "/.lpm/eval_solution.conf"; - path_download = string(getenv("HOME")) + "/.lpm/download/"; - path_result = "./"; - path_server_validation = "robotics.ethz.ch/~asl-datasets/evaluations/validation"; - path_server_protocols = "robotics.ethz.ch/~asl-datasets/evaluations/protocols"; - DataSetInfo info; - info = DataSetInfo("apartment", false); - info.path = "robotics.ethz.ch/~asl-datasets/apartment_03-Dec-2011-18_13_33/csv_local/local_frame.zip"; - dataSetStatus[info.name] = info; - info = DataSetInfo("eth", false); - info.path = "http://robotics.ethz.ch/~asl-datasets/ETH_hauptgebaude_23-Aug-2011-18_43_49/csv_local/local_frame.zip"; - dataSetStatus[info.name] = info; - info = DataSetInfo("plain", false); - info.path = "http://robotics.ethz.ch/~asl-datasets/plain_01-Sep-2011-16_39_18/csv_local/local_frame.zip"; - dataSetStatus[info.name] = info; - info = DataSetInfo("stairs", false); - info.path = "http://robotics.ethz.ch/~asl-datasets/stairs_26-Aug-2011-14_26_14/csv_local/local_frame.zip"; - dataSetStatus[info.name] = info; - info = DataSetInfo("gazebo", false); - info.path = "http://robotics.ethz.ch/~asl-datasets/gazebo_winter_18-Jan-2012-16_10_04/csv_local/local_frame.zip"; - dataSetStatus[info.name] = info; - info = DataSetInfo("wood", false); - info.path = "http://robotics.ethz.ch/~asl-datasets/wood_summer_25-Aug-2011-13_00_30/csv_local/local_frame.zip"; - dataSetStatus[info.name] = info; - } - -}; - -class EvaluationModule -{ -public: - EvaluationModule(); - int coreId; - string tmp_file_name; - double result_time; - void evaluateSolution(const string &tmp_file_name, const string &yaml_config, const int &coreId, PMIO::FileInfoVector::const_iterator it_eval, PMIO::FileInfoVector::const_iterator it_end); - -}; - -po::options_description setupOptions(const string & name); -string outputStatus(map dataSetStatus); -string enterValidPath(string message); -void setConfig(Config& config); -void saveConfig(Config& config); -void loadConfig(Config& config); -void downloadDataSets(Config& config, po::variables_map &vm); -void validateFileInfo(const PMIO::FileInfo &fileInfo); -void displayLoadingBar(const int &coreId, const int &i, const int &total, const int &nbFailures, const double sec, const double total_time); - -int main(int argc, char *argv[]) -{ - srand ( time(NULL) ); - - // Option parsing - po::options_description desc = setupOptions(argv[0]); - po::positional_options_description p; - p.add("icp-config", -1); - - po::variables_map vm; - po::store(po::command_line_parser(argc, argv). - options(desc).positional(p).run(), vm); - po::notify(vm); - - // Evaluation configuration - Config config; - - if (vm.count("help")) { - cout << desc << endl; - return 1; - } - - // Check for config - fs::path c_path(config.path_config); - if(fs::exists(c_path) == false) - { - fs::create_directories(c_path.parent_path()); - cout << ">> no configuration found. Using default values." << endl; - - } - else - { - loadConfig(config); - } - - if (vm.count("config")) - { - setConfig(config); - saveConfig(config); - return 0; - } - - if (vm.count("download")) - { - downloadDataSets(config, vm); - saveConfig(config); - return 0; - } - - if (vm.count("icp-config") == false) - { - cerr << "You must provide a YAMl file to evaluate it." << endl; - return 1; - } - - const string yaml_config = vm["icp-config"].as(); - { - ifstream cfgIfs(yaml_config.c_str()); - if (!cfgIfs.good()) - { - cerr << "Cannot open YAML file name: it must exist and be readable." << endl; - return 2; - } - } - - initscr(); // ncurse screen - - // Starting evaluation - for(BOOST_AUTO(it, config.dataSetStatus.begin()); it != config.dataSetStatus.end(); ++it) - { - if(vm.count("all") || vm.count(it->second.name)) - { - if(it->second.downloaded == false) - { - endwin(); /* End curses mode */ - cerr << ">> Please download data set first." << endl - << ">> You can use the option --download -A to download them all." << endl; - return 1; - } - - const string protocol_name = config.path_download + "protocols/" + it->second.name + "_protocol.csv"; - const string data_directory = config.path_download + it->second.name + "/"; - - if(!fs::exists(fs::path(protocol_name))) - { - endwin(); /* End curses mode */ - cerr << ">> Missing protocol file: " << protocol_name << endl - << ">> You can use the option --download to download it back." << endl; - return 1; - } - - const PMIO::FileInfoVector eval_list(protocol_name, data_directory, ""); - - // Ensure that all required columns are there - validateFileInfo(eval_list[0]); - move(0,0); - clrtoeol(); - mvprintw(0, 0, " <<< Evaluating %s >>>", it->second.name.c_str()); - //cout << endl << "<<< Evaluating " << it->second.name << " >>>" << endl; - - // Spawn threads - const int maxNbCore = 16; - int nbCore = 1; - if(vm["threads"].as() > 1 || vm["threads"].as() < maxNbCore) - { - nbCore = vm["threads"].as(); - } - - // List of thread - boost::thread a_threads[maxNbCore]; - std::vector v_evalModules; - - const int nbPerThread = eval_list.size()/nbCore; - PMIO::FileInfoVector::const_iterator it_start = eval_list.begin(); - for (int j=0; jsecond.name << "_"; - ss_path_time << pt::second_clock::local_time() << ".csv"; - - move(nbCore+3,0); - clrtoeol(); - mvprintw(nbCore+3, 0, "Last result written to: %s", ss_path_time.str().c_str()); - std::ofstream fout(ss_path_time.str().c_str()); - if (!fout.good()) - { - cerr << "Warning, cannot open result file " << ss_path_time << ", results were not saved" << endl; - continue; - } - - // dump header - fout << "time"; - for(int r=0; r<4;++r) - for(int c=0; c<4;++c) - fout << ", T" << r << c; - - fout << "\n"; - - // dump results - // for all threads - for(unsigned i=0; i(), "YAML configuration file") - ("config,C", "Interactive configuration") - ("download,D", "Download selected data sets from the web") - ("evaluate,E", "Evaluate a solution over selected data sets") - ("threads,j", po::value()->default_value(1), "Number of threads to use. Max 16.") - ("apartment,a", "Apply action only on the data set Apartment") - ("eth,e", "Apply action only on the data set ETH Hauptgebaude") - ("plain,p", "Apply action only on the data set Mountain Plain") - ("stairs,s", "Apply action only on the data set Stairs") - ("gazebo,g", "Apply action only on the data set Gazebo Winter") - ("wood,w", "Apply action only on the data set Wood Summer") - ("all,A", "Apply action for all data sets") - ; - - return desc; -} - -string outputStatus(map dataSetStatus) -{ - stringstream ss; - - for(BOOST_AUTO(it, dataSetStatus.begin()); it != dataSetStatus.end(); ++it) - { - string paddedName = it->second.name + ":"; - while (paddedName.length() < 12) paddedName += " "; - ss << "\t" << paddedName; - if(it->second.downloaded) - { - ss << "downloaded."; - } - else - { - ss << "not on your system."; - } - - ss << endl; - } - - return ss.str(); -} - - -string enterValidPath(string message) -{ - bool validPath = false; - string path_name; - while(!validPath) - { - cout << message; - getline(cin, path_name); - validPath = fs::is_directory(fs::path(path_name)); - if(validPath == false) - cout << ">> Not a valid path" << endl; - } - - return path_name; -} - - -void setConfig(Config& config) -{ - string answer = "0"; - cout << "Current configuration:" << endl - << "\t Download path: " << config.path_download << endl - << "\t Result path: " << config.path_result << endl; - - cout << "Data set status:" << endl; - cout << outputStatus(config.dataSetStatus); - - while(!(answer == "" || answer == "y" ||answer == "Y" || answer == "n" || answer == "N")) - { - cout << endl << "Do you want to change something? [y/N]: "; - getline(cin, answer); - - //if(answer == "" || answer == "n" ||answer == "N" ) - // return 1; - if(answer == "y" ||answer == "Y" ) - { - config.path_download = enterValidPath("Enter data set path or where they will be downloaded: "); - cout << endl; - config.path_result = enterValidPath("Enter the result path (where the result of the test will be saved): "); - - } - } -} - -void saveConfig(Config& config) -{ - YAML::Emitter emitter; - - emitter << YAML::BeginMap; - emitter << YAML::Key << "path_download"; - emitter << YAML::Value << config.path_download; - emitter << YAML::Key << "path_result"; - emitter << YAML::Value << config.path_result; - - for(BOOST_AUTO(it, config.dataSetStatus.begin()); it != config.dataSetStatus.end(); ++it) - { - emitter << YAML::Key << it->second.name; - emitter << YAML::Value; - emitter << YAML::BeginMap; - emitter << YAML::Key << "downloaded"; - emitter << YAML::Value << it->second.downloaded; - emitter << YAML::EndMap; - } - emitter << YAML::EndMap; - - std::ofstream fout(config.path_config.c_str()); - if (!fout.good()) - { - cerr << "Warning, cannot open config file " << config.path_config << ", content was not saved" << endl; - return; - } - fout << emitter.c_str(); - fout.close(); -} - -void loadConfig(Config& config) -{ - ifstream f_config(config.path_config.c_str()); - if (!f_config.good()) - { - cerr << "Warning, cannot open config file " << config.path_config << ", content was not loaded" << endl; - return; - } - YAML::Parser parser(f_config); - - YAML::Node doc; - while(parser.GetNextDocument(doc)) - { - doc["path_download"] >> config.path_download; - doc["path_result"] >> config.path_result; - for(BOOST_AUTO(it, config.dataSetStatus.begin()); it != config.dataSetStatus.end(); ++it) - { - string dataSetName = it->second.name; - const YAML::Node &node = doc[dataSetName]; - node["downloaded"] >> it->second.downloaded; - } - } -} - -void downloadDataSets(Config& config, po::variables_map &vm) -{ - // Ensure that validation and protocol folders are there - fs::path extra_path(config.path_download+"/validation/"); - if(!fs::is_directory(extra_path)) - fs::create_directories(extra_path); - extra_path = fs::path(config.path_download+"/protocols/"); - if(!fs::is_directory(extra_path)) - fs::create_directories(extra_path); - - for(BOOST_AUTO(it, config.dataSetStatus.begin()); it != config.dataSetStatus.end(); ++it) - { - if(vm.count("all") || vm.count(it->second.name)) - { - cout << ">> Fetching files for: " << it->second.name << "..." << endl << endl; - fs::path d_path(config.path_download+it->second.name); - if(!fs::is_directory(d_path)) - fs::create_directories(d_path); - - string cmd; - int sysRes; - #define CHECK_RES if (sysRes != 0) { cerr << "Warning, system command \"" << cmd << "\" failed with result code " << sysRes << endl; } - - // Dowload validation - cout << ">> Downloading validation file ..." << endl; - cmd = "wget -P " + config.path_download + "/validation/ " + config.path_server_validation + "/" + it->second.name + "_validation.csv"; - sysRes = system(cmd.c_str()); - CHECK_RES - - // Dowload protocol - cout << ">> Downloading protocol file ..." << endl; - cmd = "wget -P " + config.path_download + "/protocols/ " + config.path_server_protocols + "/" + it->second.name + "_protocol.csv"; - sysRes = system(cmd.c_str()); - CHECK_RES - - // Download data set - cout << ">> Downloading data set files ..." << endl; - cmd = "wget -P " + d_path.string() + " " + it->second.path; - sysRes = system(cmd.c_str()); - CHECK_RES - - cout << ">> Unzipping dataset..." << endl; - cmd = "unzip -q " + d_path.string() + "/local_frame.zip -d " + d_path.string() + "/"; - sysRes = system(cmd.c_str()); - CHECK_RES - - cmd = "rm " + d_path.string() + "/local_frame.zip"; - sysRes = system(cmd.c_str()); - CHECK_RES - - it->second.downloaded = true; - } - } -} - -void validateFileInfo(const PMIO::FileInfo &fileInfo) -{ - if(fileInfo.initialTransformation.rows() == 0) - { - cout << "Missing columns representing initial transformation \"iTxy\"" << endl; - abort(); - } - - if(fileInfo.readingFileName == "") - { - cout << "Missing column named \"reading\"" << endl; - abort(); - } - - if(fileInfo.referenceFileName == "") - { - cout << "Missing column named \"reference\"" << endl; - abort(); - } - -} - -boost::mutex m_display; -void displayLoadingBar(const int &coreId, const int &i, const int &total, const int &nbFailures, const double sec, const double total_time) -{ - const double average_time = total_time/double(i+1); - int time = average_time*double(total-i); - const int h=time/3600; - time=time%3600; - const int m=time/60; - time=time%60; - const int s=time; - - - m_display.lock(); - //ncurse output - move(coreId+1,0); - clrtoeol(); - mvprintw(coreId+1, 10, " Core %2d: %5d/%5d failed: %2d last dur: %2.3f sec, avr: %2.3f sec, eta: %3dh%02dm%02d",coreId,i+1, total, nbFailures, sec, average_time, h, m, s); - refresh(); /* Print it on to the real screen */ - m_display.unlock(); - - //cout << "\r Core " << coreId << ": " << i+1 << "/" << total << " last dur: " << sec << " sec, avr: " << average_time << " sec, eta: " << h << "h" << m % 60 << "m" << eta % 60 << "s "; -} - - - - - -// ---------------------------------------------------- -// EvaluationModule -// ---------------------------------------------------- -EvaluationModule::EvaluationModule(): - coreId(0) -{ -} - -void EvaluationModule::evaluateSolution(const string &tmp_file_name, const string &yaml_config, const int &coreId, PMIO::FileInfoVector::const_iterator it_eval, PMIO::FileInfoVector::const_iterator it_end) -{ - PM::DataPoints refCloud, readCloud; - string last_read_name = ""; - string last_ref_name = ""; - const int count = std::distance(it_eval, it_end); - int current_line = 0; - timer t_eval_list; - - std::ofstream fout(tmp_file_name.c_str()); - if (!fout.good()) - { - cerr << "Warning, cannot open temporary result file " << tmp_file_name << ", evaluation was skipped" << endl; - return; - } - - for( ; it_eval < it_end; ++it_eval) - { - timer t_singleTest; - - // Load point clouds - if(last_read_name != it_eval->readingFileName) - { - readCloud = PM::DataPoints::load(it_eval->readingFileName); - last_read_name = it_eval->readingFileName; - } - - if(last_ref_name != it_eval->referenceFileName) - { - refCloud = PM::DataPoints::load(it_eval->referenceFileName); - last_ref_name = it_eval->referenceFileName; - } - - // Build ICP based on config file - PM::ICP icp; - ifstream ifs(yaml_config.c_str()); - icp.loadFromYaml(ifs); - - const TP Tinit = it_eval->initialTransformation; - - timer t_icp; - - int nbFailures = 0; - TP Tresult = TP::Identity(4,4); - // Apply ICP - try - { - Tresult = icp(readCloud, refCloud, Tinit); - } - catch (PM::ConvergenceError error) - { - nbFailures ++; - } - - fout << t_icp.elapsed(); - - for(int r=0; r<4;++r) - for(int c=0; c<4;++c) - fout << ", " << Tresult(r,c); - - fout << "\n"; - - // Output eta to console - displayLoadingBar(coreId, current_line, count, nbFailures, t_singleTest.elapsed(), t_eval_list.elapsed()); - current_line ++; - } - - fout.close(); -} diff --git a/thirdparty/libpointmatcher/evaluations/jupyter/PlotSingleResults.ipynb b/thirdparty/libpointmatcher/evaluations/jupyter/PlotSingleResults.ipynb deleted file mode 100644 index 1a52336..0000000 --- a/thirdparty/libpointmatcher/evaluations/jupyter/PlotSingleResults.ipynb +++ /dev/null @@ -1,542 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Plot Results From a Single File" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": { - "collapsed": true - }, - "outputs": [], - "source": [ - "# to do math\n", - "import numpy as np\n", - "\n", - "# to draw plots\n", - "import matplotlib.pyplot as plt\n", - "\n", - "# to import csv files\n", - "import pandas as pd\n", - "\n", - "# to manipulate path\n", - "import os.path\n", - "\n", - "# report error\n", - "import sys\n", - "\n", - "# make sure that the graphs appear directly on this page\n", - "%matplotlib inline\n", - "\n", - "# to produce cosmetic print in markdown format\n", - "from IPython.display import Markdown, display\n", - "\n", - "# cosmetic print for numpy\n", - "np.set_printoptions(precision=4, suppress=True)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## User Parameters" - ] - }, - { - "cell_type": "code", - "execution_count": 9, - "metadata": { - "collapsed": true - }, - "outputs": [], - "source": [ - "#TODO: fill those variable to your files\n", - "env_name = 'ETH'\n", - "results_paths = ['../../../../data/pointmatcher_eval/eth_besl92.csv',\n", - " '../../../../data/pointmatcher_eval/eth_chen91.csv', \n", - " ]\n", - "\n", - "solution_names = ['point-to-point',\n", - " 'point-to-plane',\n", - " ]\n", - "\n", - "protocol_path = '../../../../data/pointmatcher_eval/eth_protocol.csv'\n", - "validation_path = '../../../../data/pointmatcher_eval/eth_validation.csv'\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Load Useful Files" - ] - }, - { - "cell_type": "code", - "execution_count": 208, - "metadata": { - "collapsed": false - }, - "outputs": [], - "source": [ - "def load_file(data_path):\n", - "\n", - " if not os.path.isfile(protocol_path):\n", - " display(Markdown(\"**Error**: Could not find the file _%s_.\"%data_path))\n", - " sys.exit()\n", - " \n", - " data = pd.read_csv(data_path)\n", - " # Parse header\n", - " nb_rows = len(data)\n", - " id_T = np.identity(4)\n", - " extra_headers = []\n", - " id_extra_header = []\n", - " for col, label in enumerate(data.columns.values):\n", - " label = label.strip()\n", - " if(label[0] == 'T'):\n", - " i = int(label[1])\n", - " j = int(label[2])\n", - " id_T[i,j] = col\n", - " elif(label[1] == 'T'):\n", - " i = int(label[2])\n", - " j = int(label[3])\n", - " id_T[i,j] = col\n", - " else:\n", - " extra_headers.append(label)\n", - " id_extra_header.append(col)\n", - "\n", - " # Load data\n", - " new_header = extra_headers\n", - " new_header.append('T')\n", - " data_out = pd.DataFrame(index=np.arange(nb_rows), columns=new_header)\n", - "\n", - " for row in np.arange(nb_rows):\n", - " for label, id_head in zip(extra_headers, id_extra_header):\n", - " data_out.iloc[row][label] = data.iloc[row, id_head]\n", - "\n", - " T = np.identity(4)\n", - " for index, id_head in np.ndenumerate(id_T):\n", - " T[index] = data.iloc[row, int(id_head)]\n", - "\n", - " data_out.iloc[row]['T'] = T\n", - "\n", - " if 'time' in data_out.columns:\n", - " data_out['time'] = data_out['time'].astype(float, copy=False)\n", - " \n", - " return data_out" - ] - }, - { - "cell_type": "code", - "execution_count": 209, - "metadata": { - "collapsed": false - }, - "outputs": [], - "source": [ - "# Load all files for a given environment\n", - "\n", - "protocol_data = load_file(protocol_path)\n", - "validation_data = load_file(validation_path)\n", - " \n", - "results_data_list = []\n", - "for results_path in results_paths:\n", - " \n", - " results_data = load_file(results_path)\n", - " results_data_list.append(results_data)\n", - " \n", - " if(not(len(results_data) == len(protocol_data) == len(validation_data))):\n", - " display(Markdown(\"**Error**: number of rows are not the same in each file.\"))" - ] - }, - { - "cell_type": "code", - "execution_count": 210, - "metadata": { - "collapsed": false - }, - "outputs": [ - { - "data": { - "text/html": [ - "
\n", - "\n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - "
point-to-planepoint-to-pointprotocolvalidation
Terror_roterror_transtimeTerror_roterror_transtimeTreadingreferenceToverlap_ratioperturbation_rotperturbation_transperturbation_type
0[[0.999548, -0.00575572, 0.0295302, 14.87], [-...1.6241173.7670783.37804[[0.62264, 0.767392, 0.153118, 13.5807], [-0.1...1.70271710.2831342.33435[[0.951999, 0.225383, 0.207126, 13.808709], [-...Hokuyo_32.csvHokuyo_12.csv[[0.999736, 0.02279, 0.003118, 14.677482], [-0...0.3590820.5763530.250124easyPoses
\n", - "
" - ], - "text/plain": [ - " point-to-plane \\\n", - " T error_rot error_trans \n", - "0 [[0.999548, -0.00575572, 0.0295302, 14.87], [-... 1.624117 3.767078 \n", - "\n", - " point-to-point \\\n", - " time T error_rot \n", - "0 3.37804 [[0.62264, 0.767392, 0.153118, 13.5807], [-0.1... 1.702717 \n", - "\n", - " protocol \\\n", - " error_trans time T \n", - "0 10.283134 2.33435 [[0.951999, 0.225383, 0.207126, 13.808709], [-... \n", - "\n", - " \\\n", - " reading reference \n", - "0 Hokuyo_32.csv Hokuyo_12.csv \n", - "\n", - " validation \\\n", - " T overlap_ratio \n", - "0 [[0.999736, 0.02279, 0.003118, 14.677482], [-0... 0.359082 \n", - "\n", - " \n", - " perturbation_rot perturbation_trans perturbation_type \n", - "0 0.576353 0.250124 easyPoses " - ] - }, - "execution_count": 210, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "def perturbation(row):\n", - " delta_T = row.protocol['T'].dot(np.linalg.inv(row.validation['T']))\n", - " p_trans = np.linalg.norm(delta_T[0:3, 3])\n", - " rod = (np.trace(delta_T)/2.) - 1.\n", - " # handle value close to -1 or 1\n", - " rod = np.min([rod, 1.])\n", - " rod = np.max([rod, -1.])\n", - " p_rot = np.arccos(rod)\n", - " return pd.Series({('validation', 'perturbation_trans'):p_trans, ('validation', 'perturbation_rot'):p_rot})\n", - "\n", - "def error(row):\n", - " out = []\n", - " for name in solution_names:\n", - " error_T = row[name, 'T'].dot(np.linalg.inv(row.validation['T']))\n", - " e_trans = np.linalg.norm(error_T[0:3, 3])\n", - " rod = (np.trace(error_T)/2.) - 1.\n", - " # handle value close to -1 or 1\n", - " rod = np.min([rod, 1.])\n", - " rod = np.max([rod, -1.])\n", - " e_rot = np.arccos(rod)\n", - " out.append(pd.Series({(name, 'error_trans'):e_trans, (name, 'error_rot'):e_rot}))\n", - " return pd.concat(out, axis=0)\n", - "\n", - "# combine to one table\n", - "plot_data = pd.concat(([protocol_data, validation_data] + results_data_list), \n", - " axis=1, keys=(['protocol', 'validation'] + solution_names))\n", - "\n", - "# Compute the level of perturbations\n", - "plot_data = pd.concat([plot_data, plot_data.apply(perturbation, axis=1)], axis=1)\n", - "\n", - "# Compute the errors\n", - "plot_data = pd.concat([plot_data, plot_data.apply(error, axis=1)], axis=1)\n", - "\n", - "# display the table\n", - "plot_data.sort_index(axis='columns', inplace=True)\n", - "plot_data.head(1)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Overall Performance" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Boxplot" - ] - }, - { - "cell_type": "code", - "execution_count": 233, - "metadata": { - "collapsed": false - }, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAA1kAAAGqCAYAAAD5mI6tAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nAAAAAElFTkSuQmCC\n", - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "boxprops = dict(linestyle='-', linewidth=1, color='blue')\n", - "medianprops = dict(linestyle='-', linewidth=5, color='red')\n", - "whiskerprops = dict(linestyle='--', linewidth=1, color='black')\n", - "\n", - "fig = plt.figure(figsize=(12,6))\n", - "\n", - "ax1 = fig.add_subplot(131)\n", - "plot_data.boxplot([('point-to-point', 'error_trans'), ('point-to-plane', 'error_trans')], \n", - " ax=ax1, return_type=None,\n", - " whis=[0,100], medianprops=medianprops, boxprops=boxprops, whiskerprops=whiskerprops);\n", - "ax1.set_xticklabels(solution_names)\n", - "ax1.set_title('$\\it{' + env_name + '}$', fontsize=20)\n", - "ax1.set_ylabel('Error on translation (m)')\n", - "ax1.set_yscale('log')\n", - "\n", - "ax2 = fig.add_subplot(132)\n", - "plot_data.boxplot([('point-to-point', 'error_rot'), ('point-to-plane', 'error_rot')], \n", - " ax=ax2, return_type=None,\n", - " whis=[0,100], medianprops=medianprops, boxprops=boxprops, whiskerprops=whiskerprops);\n", - "ax2.set_xticklabels(solution_names)\n", - "ax2.set_title('$\\it{' + env_name + '}$', fontsize=20)\n", - "ax2.set_ylabel('Error on rotation (rad)')\n", - "ax2.set_yscale('log')\n", - "\n", - "ax3 = fig.add_subplot(133)\n", - "plot_data.boxplot([('point-to-point', 'time'), ('point-to-plane', 'time')], \n", - " ax=ax3, return_type=None,\n", - " whis=[0,100], medianprops=medianprops, boxprops=boxprops, whiskerprops=whiskerprops);\n", - "ax3.set_xticklabels(solution_names)\n", - "ax3.set_title('$\\it{' + env_name + '}$', fontsize=20)\n", - "ax3.set_ylabel('Time (sec)')\n", - "ax3.set_yscale('log')\n", - "\n", - "fig.tight_layout(w_pad=2.)" - ] - }, - { - "cell_type": "code", - "execution_count": 223, - "metadata": { - "collapsed": false - }, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAA1kAAAGrCAYAAAAyxF0IAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz\nAAALEgAACxIB0t1+/AAAIABJREFUeJzs3Xl4lNXZx/Hvmew7SViTkLCjgCsVKSqC1h0EqfqCWtxF\nK9SK+w51aaFY9X21Vq3aulDAqhXcVxC1LmwCsgchQMKahED2ZM77x5MMk2SSDJDJJOT3ua7nerbz\nnLkn40junM1YaxEREREREZGm4Qp2ACIiIiIiIkcSJVkiIiIiIiJNSEmWiIiIiIhIE1KSJSIiIiIi\n0oSUZImIiIiIiDQhJVkiIiIiIiJNKKBJljHmRWPMDmPM8gbK/K8xZr0xZpkx5vhAxiMiIiIiIhJo\ngW7Jehk4p76bxpjzgJ7W2t7ABOBvAY5HREREREQkoAKaZFlrvwLyGigyCnilqux3QIIxplMgYxIR\nEREREQmk0CC/fiqwxet8W9W1HbULGmNscwUlIiIiIiLiD2utqX0t2ElWnYCAepMpa5VnBduUKVOY\nMmVKsMNo8/Q5tBz6LJqftVBZeWCrqIBHH53CHXdMoaKi7j3vc+9rFRWNb+XlUFYGbrfzuoeyP5xn\nm6POpqxr164pJCVNabRsQ/+cH+q9QD7brRssXtzw841xWzflleWUVZZRWllKWWWZZyutKKXCXUGl\nraTCXeEcuytrXKs+9+fa+y+8zxlXn1GnXPW5tRaLrXfv/DwaLnPYzzewL6ssq1FPjc/J69dE73ve\n1xu65299TfFaW9/ZSuqFqU1WX0P3WvPPqanrq32v4KMC4s6JC9hr5d6Viy/BTrK2Al29ztOA7PoK\ne/8iM2zYMIYNGxaouERE2jxrnQSjuBhKSg7svY+LiyE/H/bsgdxcKCpynikvd7bqRKV639C10lKn\nTu/ny8vrJkdut+94p09v3p+P+Jbr+/eNBlgILYWwQgjfD2HFEFIGrnJnH1Lu+zykDMKKnOci9kFE\ngXPuqqi7YcG4a20+rtUp55zvj3BzwnMHEpZKW4nbuql0V+3rOa++VlZZRrm7vOl/2PXZCJ9+/mnz\nvZ74tg+ys+v9tVaaSxkU7i9suvp+BjY1Xqw5kiyD7xYrgLnAzcBsY8xgIN9aW6erYDX9tVhE2qLq\nZKeo6EByU52QNLaVlsL+/c5WXOycV29lZQeOi4th3z5nKy4+8DotlcsFISEQGursy8shNtY5rt6q\n7/m6Fhrq3xYSAhERzuu5XGDM4e2boo5A1uWmgnJbQgUlXvtSym0J5e4SyimhzF1ChS2lzO2UKXOX\nUGZLKHeX8tWsLzjh4mJK3c55mbuE0soSz76ksojC8v0UVxRSWL6fwor9FJUXUmkrg/2fVIPKgGXb\nD7+e8JDwGltESAThIeGEhYQR5goj1BVKiCuEUFeoc2xCGr9mDhxX3/tuw3cMPWWoz/IhJgRjDAbT\n4B5otExDe+CQnw0LCSPEhHh+btXxeM69fq30vud9vaF7/tZ3uK/1wt4XuOG6G5o09obutdafUyDq\n8773eMnj3D759oC9VvuY9vgS0CTLGDMTGAYkG2OygIeAcMBaa5+31r5vjDnfGLMBKASuDmQ8cvjU\netgy6HNoOWp/FpWVNZOc6oRl//4DSUxBQc3jggIngap+prplKC/PKVNU5NQbDOHhEBnpbFFRvvcJ\nCZCUBMnJEBPjPBMW5myhoXWPG7pW/VrV98PCfCdMtf6NZP78YRxJXwtrLaWVpRSWFbK/bD8lFSUU\nVxRTUlFCWWUZFe4KyivLKXeXe/alFaXkleSxp2gPeSV5FJcXO8+UHXi2uNzZl1SUUFpZ6jmu3ty2\nnmZCf0XDotVfHvRjYa4wYsNjiQ2PJSosypOEhLnCPElI7fMwVxgxYTHEhMcQHxFPXHgcMeExhLnC\n6iQlLuOqsRljap5jGi3jMi5PnS7j8tQb4gqpce7rWkRoBGGusDq/3AXK/Mj5+neiBSi+sJhBqYOC\nHUabN/KckXSJ69Lsr2tayzgnY4xtLbGKSOtWVga7dsHOnbBjR939nj1O0lRY6Ozz8g60/JQHqEdQ\nWBhERx9IbA5mi4pyWnmqn42IcBKhiIgDW2QkxMU5W/XrREQ4CU1bUFpRyv6y/ewr28e+0n3sLNzJ\n3tK9TjevWslMeWW5k+TUulZWWUZheSElFSWe+9XJUPW4mfqulVWWeZKg6oQoGFzGRWRoZJ0tIiSi\n7rXQqmshPq75eC4iNIKYsBhiw2OJCa/aVyVJ4SHhQXm/IiKHyxjTIie+EBFpcm630xqUm3tgrNCe\nPQe27Gynhaiw0GklKipyjgsLnbJ79x7e63snQtXHsbEQH38gkYmLc86rr8XEHHgmNhY6d4Z27Q4k\nPWFhTfOzaW0q3BUUlRdRVF5EYVmh59h721e2j6LyohqtNNUtP94tOMUVxZ4yReVFFFcUe+rdV7Yv\n2G+1joiQCKLCoogLjyMqLMqTtESERhDqCiXMFVajm1lEaASJkYkkRyWTGJVITFgMkaGRnmcjQyOJ\nCo0iIjSCqNAon4lRqEu/Foj40q1bNzZv3hzsMCSIMjIy2LRpk9/l1ZIlIi2WtU5XutrJUmP7vLzG\nZxJrSEgItG8PnTo5W8eOB/YdOzr3YmOdxCgmxukqFx3tJEjh4XW7sh3pisuL2V+2n8Jyp2vb/rL9\nnm5u1dcLSgvYV+okQ4XlvpMlX1tzTRYQ6golLjyOuIg44sLjSI5OJjEy0dPNyzuZ8T733oeHhHsS\nm7CQA2Wru5g1di0qLIqo0ChPUuQyAV3KUkQOQlVrRbDDkCCq778BtWSJSNAVFkJWlpMI5efD9u2Q\nk+MkR/VtFRWH9lre44Rq71NSnFai6OgDW0yM0+qUlASJic5EAEcyt3V7WnH2l+13kqCqrnKF5YUU\nlhV69gWlBewt3Ut+SX6dLbc4l+KK4oDF6TIuYsJiiA6LbnDzbu2pbvHxTlqqW26qj6PDookKq9qH\nRtEusl2zjZcREZEjn5IsEWkSRUVOwpST43THqz7esgU2bICNG2H37oOvNybGd6Lk61r1PjHRmSjh\nSFLhrmBn4U6y92V7WopqJ0P7yvZ5kqXq7nPVXeKKy519fkk+BaUFTZoYhZgQ2kW284yzqR5rU31c\nvSVEJDSaLNXewkPClfyIiEirc4T9GiIiTc1aZ7KHXbucFqiVK2HTJud882ZYterA2KbGhIdDerrT\n5S4hATp0gNRUp/tdUlLdLTHRmXyhtbLWUlheyN6SvZ5WIk8iVOrsa2xlBfXeC0RrkXcrUHU3ubiI\nOGLDY4kOi/a0ICVEJNAusl29W2x4rBIhERERL0qyRNqwykqn1WnzZmfbtAkyM52Wp+pJInJz/Z8x\nLz3d6YrXpcuBLTUVevRwttTU1tkNr6SihJ2FO8krzmNv6V72luzlp10/4TIudhftJrc419Odbm/J\ngW51eSV5VLgPsb9jLS7jIjkqmdT4VM9U1Z6Z2qpmaPNOlmLCY2p0i6vuNtcush0JEQlEhUVpzI+I\nSBsXFxfHihUr6NatW7BDOWw33XQTaWlp3HfffcEOBdDEFyJHpPJy2LYNfv4Zli93ZtLLzXW6623a\n5IyFOpgJIpKSnNnukpMhIwMGDHBao1JTnaSqQwfnvDU0ZpRUlLCnaA+5xbnsKd7DnqI9nn1BaQF5\nJXlk7c1iR+EO8kvy2V20m4LSgkN+vcjQSBIiEoiLiPOs5RMfEd/g5qtMdFi0WotERIJEE1+Ay+Vi\nw4YN9OjRo94y3bt358UXX+SMM85oxsgO3tVXX03Xrl35wx/+4PczmvhCpA0pKXHGPP34I6xeDStW\nOMeZmf4vXtupk5M4devmbBkZ0Lu3c7167FNkZCDfhf8q3ZXsK9vH3pK9nhalBvdex/kl+eQV51FY\nXnjQrxvqCqVjTEeSopI8XecSIhMoKi9iUMogkqKSSIxKrHGvuitdZGgL+eGJiIgcBv2h7+CoJUuk\nhaoeC5WV5Wxbthw4rj7fscP3s8Y4XfXS06F79wNd9xITnSQqLS34E0RUuivJLc5l275tZO3NYsve\nLeTszyGvOI/cklyfiVNTrGUU6golOSqZ5OjkmvuoZNpFtiM+Ip7OsZ1JT0gnMSrRc13/uIiItF0t\nvSWre/fuTJgwgVdffZXt27czevRonn32WcLDw3nhhReYPn06eXl5nHrqqTz77LN06dIFqNk6dfXV\nVxMTE8OmTZv48ssv6d+/PzNnzqR79+6cfvrpLFy4kOjoaFwuFy+++CKXXHJJjRjGjx/P66+/TmRk\nJCEhITz44IPcfvvtzJ07l3vvvZfs7GyOP/54/vrXv3LUUUf5fB9Tp05l5cqVhISE8P7779OnTx9e\neukljj32WADWrFnDTTfdxLJly0hLS+Oxxx5j5MiRQM3WqQULFnDFFVdw6623Mm3aNEJDQ3n00Ue5\n6qqreOGFF7j55ptxuVyEh4czfPhw3nnnnUZ/xmrJEmlFrHXGRK1dC+vWwfr1Tle+nTudCSa2b2/4\n+dBQp8veUUfBMcdA//7ONmCAMx15c7HWsr9sv88ueNX7/NID037vKtzFuj3rqLR+Nrd5iY+IJyEi\nwdlHJpAQkXBg731ca58YlUi7yHbEhccpYRIRkSPOzJkz+eSTT4iOjmbEiBE88sgjDB8+nHvvvZdP\nP/2Ufv36cdtttzF27FgWLFgA1G2dmjVrFh999BEnnHAC48eP57777mPmzJksWLAAl8vFihUr6N69\nu8/Xf+WVV1i4cCEvvfQSw4cPB2DdunVcdtllzJ07l9NPP52//OUvjBw5ktWrVxNaz195586dy6xZ\ns3j99dd58sknGT16NOvXr8day8iRI7nuuuv45JNPWLhwIaNGjWLx4sX07t27Tj3bt29n3759ZGdn\n8/HHH3PxxRdz0UUXcf311/PNN98cdHfBg6UkS6QZWOtMLPH99063vrVrDyRW+/fX/1xiotOFLz3d\n2bp2PXCcnu6MkwoJafp4yyrL2FW4ix2FO9hZuJMd+5199QQPe0v3eu7v2L+D3OLcQ1o0Nikqic6x\nnclIyKBrfFdS4lI8i8BWd7vzTpTiIuI0WYOIiLQ4Tfm3u0NtMJs0aRIpKSkA3HfffUyaNIns7Gyu\nvfZajjvuOAD++Mc/kpiYSFZWFunp6XVaZsaMGcPAgQMBuPzyy7nttttqxdZ4cN5l5syZw4gRIzxj\ntG6//XaeeuopvvnmG4YOHerz+YEDB3LRRRcBMHnyZP7yl7/w7bffOjP2FhZy1113ATB8+HBGjBjB\nv/71Lx588ME69YSHh/PAAw/gcrk477zziI2NZe3atQwaNKjR99AUlGSJNDFrYc0a+PprZ3zU0qVO\nYpWb67t8cjL07etsffo4LVMdOzoJ1dFHN/X/uC3b929nQ+4GNuRuIDMvkz1Fe9hbupfc4lw25W9y\nZtEryTvouqPDokmKSqrTBS85OpmkqCSSopI845QSIhLoldSLuIi4pntzIiIibVhaWprnOCMjg+zs\nbHJycjxJE0BMTAzJycls27aN9PT0OnV07tzZcxwdHc3+Bv4SfP7557Nw4UKMMTz33HOMGzeuTpns\n7GwyMjI858YYunbtyrZt25g5cyYTJkzAGMNpp53Ge++9B0DXrl1rlE9NTSU7OxtrbY171e9z27Zt\nPuNLTk7G5TWlcWPvp6kpyRI5RNWtU8uXO9uKFc7MfevXO7P21ZacDIMGwXHHOclUdWKVnNx0MZVV\nlpG9L5utBVvZlL+J9XvWe1qjMvMy2ZC7gaLyxhe0CjEhdIjpQMeYjnSK6UTHmI50jOlIclSyp1Up\nOTqZzrGd6RTTieToZE3wICIibVZLGK61ZcsWz3FWVhapqamkpKSwadMmz/XCwkL27NlTIyE7VO+/\n/36da7W7H6akpLBy5co6caampjJ06FAuu+yyOnV4vw9rLVu3biUlJQVrLVlZWTXKZmVl0bdv34OO\nvTmGDSjJEvGDtfDTT844qbVrYdYsZyxVQT0ze3fqBMOGwYknwvHHO+OlOnc+vFYpay3b9m1j/Z71\nbC3Y6tm27dvmOd5RWM9MGF6So5LpldSLXkm96JnYk44xHT2z4WUkZNAlrgtJUUnqliciItKKPPPM\nM1xwwQVERUXx2GOPMXbsWIYPH864ceO4/PLL6du3L/feey+DBw+u0yLkj86dO7Nx48YGp3CvLlPd\nPfDSSy9l2rRpfPHFF5x22mk8+eSTREZGMmTIkHrrWLx4Mf/5z38YOXIkTz31FJGRkQwePBi3201s\nbCzTp09n8uTJfPXVV7z77rtMmTLloN9Lp06d2Lhx40E/dzCUZIn4UFLijJ96800nqfrhB9/d/eLi\nYPBgJ4k65hhn6vPq2fwOJaEqryxn897NZOZmkpmXyca8jWTmZZKZm8mm/E2Nzq7nMi66xHYhLT6N\nrgld6ZPUh5S4FNpHt6dHYg96JfUiMSrx4AMTERGRFu2yyy7j7LPPJicnh9GjR3PfffcRGRnJww8/\nzJgxY8jPz2fIkCHMmjXL88zBtOhMmTKF8ePHU1JSwvPPP8/FF19cp8zdd9/NpEmTuPPOO7n//vuZ\nPHkyr732GhMnTvTMLjhv3rx6J70AGDVqFLNnz2b8+PH07t2bt99+m5CQEEJCQpg7dy433XQTjz32\nGGlpabz66qs+J73wxfu9XnvttVxyySUkJSUxbNgw3nrrLb9/Dv7SFO4iONOh/+c/B9aa+v57KCur\nWaZdOzjtNOjXD449FoYMcSal8Felu5LNezeTvS+bHft3sKNwB9v3b/dsa/esJTM3s8EZ99pFtqN/\nh/50TehKWlwaafE1t06xnQh16W8nIiIiTak1TOHeGhYBbszUqVPJzMzklVdeCXYodWgKd5FGWAtb\nt8KiRbB4MSxYAF99VbOMMU4iddppzv6ss5yEqqE/+Litm5x9OWwp2OJpedq8dzOb8jeRtTeLzXs3\nU1JR0mBsBkPX+K70TOpJj3Y96JnUk56JPemZ1JPu7bqTFJWk6cdFREREWjglWXLEq6iAzEynpWr+\nfCex2rWrZpnISBgxwkmqevVyugAmJdWty1pLcUUxu4t2s3rXalbuXMlPu35i5c6VrNq1isLywgZj\nSY1LJS0+zTNhROfYzp4to10G/Tr00wQSIiIiclD0B9iWR90F5YhhrbN4r/dsf8uXO10Aa3f9S0yE\ngQOd7aST4OyzISyqhLW717Jm9xpy9uewp2gPG/M3sjl/M7nFueSV5JFbnEtZZZnvAICOMR3pGt+V\n7ond6d6uO93adSMjIYOMdhmkJ6QTHxEf4J+CiIiINLWW3l1QAu9guwsqyZJWq7LSSaq+/hpefRXe\ne6/+KVTT052Easyv3fQ6PoftIYvYnL+J7fu3s2r3KlbsWMHP+T/79boRIREkRSXRM6knx3Y8lgEd\nBzCg4wD6d+xPUpSP5i8RERFp1ZRkiZIsOaJt3AivvQYffOCMqaqoqFvm1FPhqOP30v6o1bg6/0RB\nxCrW5//Emt1ryN6XTbm73GfdISaEnkk96dehH13ju5IclUxqfCq9k3qTHJ1MYmQiSVFJRIVFBfhd\nioiISEuiJEuUZMkRx1r48kv485+d1ipv7VP2k3LcGgYMW0VYyir2uFaxavdPbMyrf+2DpKgkjut0\nHP069KNTTCf6JPdhQMcB9EnuQ1hIWIDfjYiIiLQ2SrJESZYcEayFDRvgk0/gr3+Fn36y0HkZYZ3X\n0e/UjST0XkFW5XdsKvCdTEWERHB0h6Pp16Ef/Tv0p1+Hfhzd/mjSE9LVEiUiIiIHRUmWNHmSZYxJ\nstb6WIa1eSnJOvK53fDuu/DvfzuzAG7ZAqT9Fwa+gDlqHjZqd51nwlxh9G3fl34d+tGvfT9n36Ef\nvZN7Ex4S3uzvQURERI48SrIkEEnWemAZ8DLwQbAyHSVZR65du+Dll+H1153ZAAkthv5zCD3pH1Sk\nzfeUax/dnlPTT6V7u+4c1f4oBqUOon+H/uriJyIiIgF1pCZZcXFxrFixgm7dugU7FL8Ec9HlQCxG\n3Af4FXAN8H/GmNnAP6y16/wM6FzgScAFvGitnVbrflfgn0C7qjL3WGs/8Kduab0qKuDDD+HZZ+Gz\nz6A0cjP0/ITosd9ij3qTYvKpAOLC47j5pJsZd8w4jul4jNaBEBEREWki+/bt87usy+Viw4YN9OjR\no94ywUyCWppGk6yq5qNPgE+MMcOB14DfGmN+BO621v63vmeNMS7gaeBMIBv4wRjzjrV2jVex+4HZ\n1trnjDFHA+8D3Q/5HUmLtmsX/HNWATPe+JIdJVnQcQVM+BiSnLFVRVXlju98PL8++tdMHDSRdpHt\nghewiIiIiOgP3QfJ1VgBY0yyMeYWY8wi4HZgEtAeuA2Y2cjjg4D11trN1tpyYBYwqlYZN1C9Qms7\nYNtBxC+twJK1O/nd/35I/0kP0Onuodyxpx07zhwJF9wMJ/0NkjYSFRrFqL6jmP6r6SybsIylE5Zy\n/9D7lWCJiIiINKJ79+786U9/on///iQnJ3PttddSVlYGwAsvvEDv3r1p3749o0ePJicnx/Ocy+Vi\n40bnD91XX301EydOZMSIEcTHx/PLX/6Sn3921hA9/fTTsdZy7LHHEh8fzxtvvFEnhvHjx5OVlcXI\nkSOJj49nxowZAMydO5cBAwaQlJTEGWecwZo1a+o8W23q1KlccskljB07lvj4eH7xi1+wfPlyn2V/\n+OEHhgwZQmJiIqmpqUyaNIkKr7V9XC4Xzz33HH369CE5OZmJEyfWeP6ll16iX79+JCcnc95555GV\nleXPj9p/1toGN2Ad8ACQ5uPeXY08+2vgea/zK4D/rVWmM7Ac2ALsAU6opy4rrcPPeT/bVxe9ZX81\n4/c27vYTLFOosZkHw2zvaYPtde9cb/+48I/266yvbXllebDDFhEREfGppf8e2q1bN3vMMcfYbdu2\n2by8PHvKKafYBx54wH7++ee2ffv2dtmyZbasrMxOmjTJDh061POcy+WymZmZ1lprr7rqKpucnGwX\nLVpkKysr7eWXX27HjRvnKWuMsRs3bmw0js8//9xzvnbtWhsTE2M/++wzW1FRYadPn2579eply8t9\n/943ZcoUGx4ebt966y1bUVFhZ8yYYbt3724rKio89X/22WfWWmsXL15sv/vuO+t2u+3mzZttv379\n7FNPPVUj3pEjR9qCggKblZVlO3ToYD/66CNrrbVvv/227d27t127dq2trKy0jz76qB0yZEiD762+\n/waqrtfJXfwZk3W/tXaO9wVjzCXW2jdsrfFVPvhqV6w9Ymwc8LK19gljzGCc7oj9/YhLWoBKdyVr\ndq/hh+wf+OLnL/h0/UKyi38+UCAWKI+kfenJHNvhRMYMHMplQ04nMSoxaDGLiIiINCUztem60tmH\nDm2CjUmTJpGSkgLAfffdx6RJk8jOzubaa6/luOOOA+CPf/wjiYmJZGVlkZ6eXmcihzFjxjBw4EAA\nLr/8cm677baasfkx+Yd3mTlz5jBixAjPGK3bb7+dp556im+++YahQ4f6fH7gwIFcdNFFAEyePJnH\nH3+cb7/9llNOOaVGuRNPPNFznJ6ezg033MCCBQv43e9+57l+zz33EBcXR1xcHMOHD2fZsmWcffbZ\nPP/889xzzz306dMHgLvvvptHH32ULVu20LVr10bfoz/8SbLuBubUunYPULedsK6tQLrXeRrO2Cxv\n1wLnAFhrvzXGRBpj2ltr68zXPWXKFM/xsGHDGDZsmB8hSFPbkLuBWStn8XHmxyzOWUxReVHNAqWx\nkP0LMsxQLv7FUCZfOoSUDlqbSkRERCRQ0tLSPMcZGRlkZ2eTk5PjSZoAYmJiSE5OZtu2baSnp9ep\no3Pnzp7j6Oho9u/fX+/rnX/++SxcuBBjDM899xzjxo2rUyY7O5uMjAzPuTGGrl27sm3bNmbOnMmE\nCRMwxnDaaafx3nvvAdRIcowxpKWlkZ1dO32A9evXM3nyZBYtWkRxcTEVFRU13itAp06dfL6fzZs3\nc8stt3iSSGstxhi2bdvWaJI1f/585s+f32AZaCDJMsacB5wPpBpj/tfrVjxQ4fupOn4AehljMoAc\nYCxOy5W3zTizF/6zauKLCF8JFtRMsqT5VLor+Xbrt3z+8+d8vPFjvsr6qmaBvG6QMxC2nky7/DO4\n+rzjmfRQCN01fYmIiIi0AYfa+tSUtmzZ4jnOysoiNTWVlJQUNm3a5LleWFjInj17aiRkh+r999+v\nc6325BgpKSmsXLmyTpypqakMHTqUyy67rE4d3u/DWsvWrVtJTU2tU+6mm27ixBNPZPbs2URHR/PU\nU0/x5ptv+hV7165duf/++30mho2p3dAzdepUn+UamvgiG1gElACLvba5VLU8NcZaWwlMBD4GfgJm\nWWtXG2OmGmNGVBW7HbjeGLMMeB240p+6JfA25G7gxndvpMvjXTj15VN5cP6DfJX1FcYdBj9eAbPe\ngmm76TLnZ64I/zef/uEOdi8fyF9mKMESERERaU7PPPMM27ZtIzc3l8cee4yxY8cybtw4/vGPf7B8\n+XJKS0u59957GTx48CF1ievcubNnkgx/y1x66aW89957fPHFF1RUVDBjxgwiIyMZMmRIvXUsXryY\n//znP1RWVvLEE08QGRnJySefXKfcvn37iI+PJzo6mjVr1vDss8/6/V5uvPFGHnvsMVatWgXA3r17\n+fe//+338/6otyXLWvsj8KMx5nVrrb8tV77q+RDoW+vaQ17Hq4FTD7V+aXrr9qzjkS8fYeaKmVTa\nSgA6hPSkeMW57F95OjbzbMLcCdx4I4wdC4MHg6vReSpFREREJFAuu+wyzj77bHJychg9ejT33Xcf\nkZGRPPzww4wZM4b8/HyGDBnCrFmzPM8czLTsU6ZMYfz48ZSUlPD8889z8cUX1ylz9913M2nSJO68\n807uv/9+Jk+ezGuvvcbEiRPJzs7m+OOPZ968eYSG1j9iadSoUcyePZvx48fTu3dv3nrrLUJCQurE\nO2PGDG644QamT5/OCSecwNixY/n888/rfW/e56NHj6awsJCxY8eSlZVFQkICZ511ls/3dKhMfQPY\njDFzrLXLqb0zAAAgAElEQVSXGmNWUHeyCqy1xzZZFH4wxlh/BtvJoXFbNx+s/4BnfniGDzY4a0G7\njItjQi5m2+y72L3iBMCQkQHXXutsVWMrRURERI5oxhi/Jn0IliNlEeCpU6eSmZnJK6+8EuxQ6qjv\nv4Gq63Wy1YYmvrilaj+igTJyBFi4eSG3fHgLS7cvBSAiJIKBYVew+Mn7+HG70+9vwAC491645BJo\n4I8PIiIiIiJtXkPdBXOq9pubLxxpTkXlRUx4dwKvLX8NgLT4NC5oP4l5f7iGbza0B+C44+Dhh+GC\nC9QlUERERKQlOphuf9I8GuouuA8f3QRx1r6y1tr4QAbmIx51F2xCWwu2MmrWKJbkLCE8JJw7fnkn\nFQvuYvojsVgL6ekwfbrTcqXkSkRERNqylt5dUAKvyboLWmvjmjg2aSEyczM545UzyNqbRUpcCtOO\neZ/npx7HwoVOQjV5MvzpT+oWKCIiIiJyKBpaJyveWltgjEnydd9amxu4sCRQrLVcM/casvZmcVKX\nwRy9dB6/uc3pGti+Pfzzn3D++UEOUkRERESkFWuorWImzqQXi3G6DXo3g1mgRwDjkgBwWzcPfvEg\nX27+koTwRPKfeZdXlicTHu60Xt11F7RrF+woRURERERat3rHZLU0GpN1eMory7lu3nW88qMzJWbc\nJ6+w7+vfcNRRMGcOHHNMkAMUERERaaE0Jkuacgp374fH4CwYbIGF1tr/HG6g0nxW7FjBVe9cxZKc\nJYQRCf+ezb6VF3L22fDGGxDfrFOYiIiIiLQuGRkZmsGvjcvIyDio8o22ZBlj/gr0Av5Vdel/gExr\n7c2HEuChUkuW/6y1LN+xnHfXvcvMlTNZtWsVAOFFGZT9ayZsGcKVV8ILL0BYWJCDFRERERFppepr\nyfInyVoDHF2d4RhjXMBP1tqjAxJp/XEoyfLDRxs+4t7P72VJzpIDF92hsHo0zHue9I6JPPkkjB4N\n+oOMiIiIiMihO5zughuAdKB6UeKuVdekhcgvyeerrK94/L+PM3/TfABiXUmw7kL2LzkfNp7FUd3a\nMf5B+N3vICYmuPGKiIiIiBzJGprCfR7OGKw4YLUx5vuq85OB75snPPGlvLKcVbtW8fnPnzNv3Ty+\n2PSF515MaCztN05k86v3Q3kM/fvDtH/DeedpUWERERERkebQUEvWjGaLQhpVVF7Epxs/Zd7aeby1\n5i1yiw8sUxYREsGAjgPoXnwxHz1yE5t3J5CYCNOmwVVXadyViIiIiEhz0hTuLVilu5Kvt3zNa8tf\nY85Pc9hbutdzr0diDwanDea8XucxtMsF3DkpkdmznXtjxsDzz0NycpACFxERERFpAw55TJYxZjDw\nf8DRQDgQAhRaazXxd4Cs2rWK15a/xktLX2JH4Q7P9YFdBjKq7yhGHzWaAR0HYIxh3jw4YwxkZkJs\nLDz9NIwfr0ktRERERESCxZ+JL54GxgJvAL8AxgN9AhlUW5RXnMfUBVOZt24eG/M2eq53b9edS/tf\nytgBYzm+8/Ge63PmwJ/+BEuXOue9e8M778DRzTrno4iIiIiI1ObXYsTW2g3GmBBrbSXwsjFmKXBP\nYENrGyrcFfz56z/zp6//REFpAQCx4bGc3fNsJgycwFk9zqqx+N3SpTB5Msyf75wnJMBDD8FvfwsR\nEUF4AyIiIiIiUoM/SVaRMSYcWGaMmQ7kAJqnrgks276M6+Zex+KcxQAM6TqEP575RwanDSY8JLxG\n2cJCuOsueOYZ5zw2Fh58ECZOhKio5o5cRERERETq489ixBnADpzxWLcCCcBfrbXNulbWkTTxRW5x\nLje9dxNzfpoDQFp8Gs9e8Cwj+ozwWf6TT2DSJFi71pmG/fe/h3vv1cQWIiIiIiLBVN/EF37NLljV\nknUUzjpZa621ZU0fYqMxHBFJ1sqdKzn3tXPZtm8bESERXHnclUw/azoJkQl1ylrrjLu6917nvF8/\neOklOPnkZg5aRERERETqOJzZBS8A/gZkAgboboyZYK39oOnDPLJ9v+17znr1LApKCzim4zG8cckb\n9G3f12fZJUvguusOTGwxdSrceSdERjZjwCIiIiIictD86S64BhhR3T3QGNMTeM9ae1QzxOcdR6tt\nyap0V/Lb937LC0tewGIZ0WcEcy6eQ1RY3cFUlZXOIsIPPugcJyTAX/8Kl10WhMBFRERERKRe9bVk\n+TOBxb5a4682AvuaLLIjnNu6ufHdG3l+yfO4jIvJgyfXm2D9979w+ulw331OgjVpEmzdqgRLRERE\nRKQ1qbe7oDFmTNXhImPM+8AcnDFZlwA/+PsCxphzgSdxEroXrbXTfJS5FHgIcAM/Wmuv8PsdtHAP\nfP4Af1/6d0JMCB9e8SG/6vEr3+UegEcecY67dIG//Q0uvLAZAxURERERkSZRb3dBY8zLDTxnrbXX\nNFq5MS5gHXAmkI2TnI211q7xKtMLmA0Mt9YWGGPaW2t3+6ir1XUXnPHNDO745A4MhjcueYNf9/u1\nz3KvvAJXXgkhIXDHHc46WB06NHOwIiIiIiJyUA564gtr7dVN8LqDgPXW2s1VQcwCRgFrvMpcDzxj\nrS2oet06CVZr9OqPr3LHJ3cAMOPsGT4TLGudda9uucU5nzHDmZ5dRERERERar0bHZBlj0owxbxtj\ndhpjdhhj3jTGpPlZfyqwxet8a9U1b32AvsaYr4wx3xhjzvGz7hbr7dVvc81cp6HviXOeYPIvJ9cp\nYy3cdpsz7srthttvP5BsiYiIiIhI6+XPxBcvA3OBFJwEaV7VNX/UaTrDGdflLRToBQwFLgP+boyJ\n97P+FueFxS/w6zm/psJdwZ1D7uT3g+s2TZWVwY03whNPOIsLv/QS/PnPYHz9tEREREREpFVpdJ0s\noIO11jup+ocxxt9ObVuBdK/zNJyxWbXL/Nda6wY2GWPWAr2BxbUrmzJliud42LBhDBs2zM8wmsfy\nHcu5+f2bsVimnD6FB09/sE6ZXbvgnHOc9a9CQ+GNN2D06CAEKyIiIiIiB2X+/PnMnz+/0XL+rJP1\nKfAP4F9Vl8YBV1trz2y0cmNCgLU4E1/kAN8D46y1q73KnFN17SpjTHuc5Op4a21erbpa/MQX494c\nx6yVs5gwcAJ/G/G3OvdXr4YLLoCff4Zu3eD112HIkOaPU0REREREDt/hrJN1DXApsB0nUbq46lqj\nrLWVwETgY+AnYJa1drUxZqoxZkRVmY+APcaYn4DPgNtrJ1itQUlFCR+s/wCAO0+5s87977+HU091\nEqxf/AK+/loJloiIiIjIkajBlqyqlqjfWWufaL6Q6o2lRbdkvbX6LX4959ec0PkElkxYUuPel186\nXQRLSmDECJg9G6KjgxSoiIiIiIg0iUNqyapqiRoXsKiOIK8tfw2AK46tuY5yfj78z/84Cdall8Jb\nbynBEhERERE5kvkzJusJIAxnweDC6uvW2iX1PhQALbkla3P+Zvo83YcKdwVbbt1CSlwKAEVFcOGF\n8NlnMHgwLFzoTHYhIiIiIiKt30EvRuzl+Kr9H7yuWeCMpgistSuvLOf6eddTVlnGuAHjPAmWtXD5\n5U6C1bGjM8mFEiwRERERkSNfoy1ZLUVLbMnaXbSbK966go8yPyI+Ip41N6+hS1wXAN55x5maPSEB\n/vtfOProIAcrIiIiIiJN6pBnFzTGJBtj/tcYs8QYs9gY85QxJjkwYbYO1lr+teJf9H26Lx9lfkRy\nVDLvjnvXk2Dl58PEiU7Zhx9WgiUiIiIi0pb4MybrE+BL4LWqS5cDw6y1vwpwbLXjaBEtWUXlRVz1\nn6t4Y9UbAAzrNox/jv4n6QnOmstuN4wZ47RkDRrkjMMKDw9mxCIiIiIiEgj1tWT5k2SttNYOqHVt\nhbX2mCaOsbE4gp5kLc1ZynXzrmNJzhLiI+L5w7A/MHHQREJcIZ4yv/89PPUUxMXBokXQp08QAxYR\nERERkYA5nIkvPjbGjAXmVJ1fDHzUlMG1BrNXzmbcm+OwWHok9uDdce9ydIea/QBff91JsMLDnZYs\nJVgiIiIiIm2PPy1Z+4AYoLLqUggHpnK31tr4wIVXI45mb8mqdFeybs86/vT1n3jlx1cAuKTfJTw3\n4jkSoxJrlN28Gfr3h8JCePJJuOWWZg1VRERERESa2SG3ZFlr4wITUsu0bs865q6dywcbPuCbLd9Q\nUlECQKgrlMfOeIzbh9yOMTV/jm433HCDk2BdfLESLBERERGRtqzNr9xkrWXdnnW8vuJ13l7zNit3\nrqxxPyUuhV/1+BUPDH2AXkm9fNbxl7/Axx9DUpLTXVBERERERNquNrlOVva+bH7Y9gNvrn6Teevm\nkV+S77kXHxHPhX0v5ILeF3BWj7NIjm54tvoff4Rf/hKKi2HuXBg5sklCFBERERGRFu5wJr5o9dzW\nzYJNC3hn7TsszFrIkpwlNe53ju3Mmd3P5DfH/oZh3YYRERrhV725uc507cXF8JvfKMESERERERE/\nW7KMMacCva21LxtjOgCx1tqfAx5dzRgOuiUrMzeTF5e+yN8W/Y28kjzP9ZiwGE5KPYkzu5/J2AFj\n6+0G2BC3G849Fz75xFlsePFiiIo66GpERERERKSVOuSWLGPMQ8AvgL7Ay0AYzsLEpzR1kE3l66yv\nmfDuBH7a9ZPnWqeYTlxzwjWcnnE6p2WcRnRY9GG9xtNPOwlWYqIzXbsSLBERERERAf+6C14EnAAs\nAbDWZhtjWuSMg3uK9nDnJ3fy0rKXPNcuP+ZyrjnhGoZ1G4bLuJrkdV5+2Vl0GJxJL3r3bpJqRURE\nRETkCOBPklVmrbXGGAtgjIkJcEyHZM3uNQz/53C2799OqCuUSYMm8dDpD5EQmdCkr7N8Odx0E1gL\njzwCV17ZpNWLiIiIiEgr50+SNccY8xzQzhhzPXAN8EJgwzo4JRUljJk9hu37t3Ny6sn8/cK/M6Dj\ngCZ/nX374NJLobQUrrsO7ruvyV9CRERERERaOX8nvjgLOBswwEfW2k8CHZiPGOqd+OLJb5/k1o9u\npW9yXxbdsIjY8Ngmf/19+2DECPjyS010ISIiIiIihzfxxa3AG8FIrPxRUFrAowsfBeDPZ/05IAlW\nQQGcdx588w2kpsLbbyvBEhERERER3/yZCSIe+MgYs9AYc7MxplOggzoYf1/yd3YX7eaUrqcwos+I\nJq9/1y44+2wnwUpPhwULoG/fJn8ZERERERE5QjSaZFlrp1pr+wM3AynAAmPMpwGPzE9vr3kbgFtO\nvgVj6rTUHZYNG+CUU+C77yAtzUmwevZs0pcQEREREZEjzMHMab4T2A7sAToGJpyDs6doD99s+YYw\nVxjn9DqnSev+6CM46SRYvx569YLPPoNu3Zr0JURERERE5AjUaJJljLnJGDMf+AxoD1xvrT020IH5\n4+PMj3FbN6dlnEZ8RHyT1fvUU3D++ZCfDxde6Exy0adPk1UvIiIiIiJHMH+mcM8Afm+tXRboYA7W\ne+vfA+D8Xuc3SX1uN0yZAg8/7Jzfe69z7GqaNYxFRERERKQNqDd9MMZUNw1NB7KMMUnem78vYIw5\n1xizxhizzhhzVwPlLjbGuI0xJ/pTb6W7kg83fAjQJBNeFBTAmDEHEqxp0+DRR5VgiYiIiIjIwWmo\nJWsmMAJYDFicNbKqWaBHY5UbY1zA08CZQDbwgzHmHWvtmlrlYoFJwLf+Bv7t1m/ZU7yHnok96ZN8\neH35du+G00+HVaugXTt4+WUYPfqwqhQRERERkTaq3iTLWjuiat/9MOofBKy31m4GMMbMAkYBa2qV\nexiYBtzhb8Vfbv4SgHN7nXtYswoWFcGoUU6C1bcvzJsHvXsfcnUiIiIiItLG+TPxxWf+XKtHKrDF\n63xr1TXvuo4H0qy17/tZJwBfZjlJ1qDUQQfzWA2VlfA//+OsgdW1K3z6qRIsERERERE5PPW2ZBlj\nIoFooL0xJpED3QXjcdbL8oevJibr9RoGeAK4spFnalZgLd9t/Q6AM7qf4WcoNbndcN118O67kJQE\nH3/srIUlIiIiIiJyOBoakzUB+D1OQrWYA8lPAfCMn/VvBdK9ztNwxmZViwP6A/OrEq7OwDvGmAut\ntUtqVzZlyhQA8kvyydueR/v+7UmNS61dzC/TpsE//gFRUfD223DUUYdUjYiIiIiItBHz589n/vz5\njZYz1tqGCxgzyVr7f4cShDEmBFiLM/FFDvA9MM5au7qe8l8Ak621S33cs9Wx/n3J37l+3vVc2PdC\n3hn7zkHHNXcuXHSR05o1dy6MHHnQVYiIiIiISBtnjMFaW6cnXqPrZFlr/88YMwDoB0R6XX/Fj2cr\njTETgY9xxn+9aK1dbYyZCvxgrX239iP40V3wgw0fAHBer/MaK1rHwoVwxRVOgvXAA0qwRERERESk\nafnTkvUQMAwnyXofOA/4ylp7ccCjqxmHtdbitm6SpiWxt3QvP9/yM93adfO7jtdfh/HjnQTr8svh\n1VfhMCYmFBERERGRNqy+lix/ltq9GKe733Zr7dXAcUBCE8fnt1W7VrG3dC8pcSkHlWB9+OGBBOvW\nW53xWEqwRERERESkqTXaXRAotta6jTEVxph4YCfQNcBx1at6VsHT0k/z+5mNG+Gyy5wE67bbYMaM\nQEUnIiIiIiJtnT9J1iJjTDvgBZxZBvcD/w1oVA1YkuNMOjiwy0C/ypeWOmth5eXBBRc4swqKiIiI\niIgEij8TX/y26vBvxpgPgXhr7fLAhlW/JdudJOvELic2WraiAm68ERYtgowMZwxWSEigIxQRERER\nkbasocWI681ijDEn+lrHKtAq3BX8uP1HAE7ockKj5avHXoWGwqxZkJgY4ABFRERERKTNa6gl6/EG\n7lngjCaOpVFrdq+huKKYbu26kRSV1GDZxx+Hp5+G8HCYNw8GD26mIEVEREREpE2rN8my1g5vzkD8\n4e94rBUr4J57nOOXX4azzw50ZCIiIiIiIo5Gx2QZY8b7uu7PYsRNrTrJamg8ltsN11wD5eXOeKzL\nLmuu6ERERERERPybXfAkr+NInDWzlgDNnmQt3b4UgBM61z8e64svnIkuUlJg+vTmikxERERERMTh\nz+yCk7zPjTEJwOyARdSAtbvXAjCg44B6yzz3nLMfPx7i4pojKhERERERkQNch/BMEdC9qQPxx47C\nHbiMi5S4FJ/316yBN95wZhOcMKGZgxMREREREcG/MVnzcGYTBCcp6wfMCWRQDekU04kQl+/Frp58\n0tlfeSV069Z8MYmIiIiIiFTzZ0zWDK/jCmCztXZrgOJpVJe4Lj6vl5fD7KpOjLfe2owBiYiIiIiI\nePFnTNYCAGNMfHV5Y0yStTY3wLH5VF9Xwa++gvx8OPpo6N+/mYMSERERERGp4k93wRuAh4FiwA0Y\nnO6DPQIbmm9dYn23ZM2d6+wvvLAZgxEREREREanFn+6CdwD9rbW7Ax2MP3wlWdbCvHnOsZIsERER\nEREJJn9mF8zEmVGwRegY07HOtdWrITMT2reHk08OQlAiIiIiIiJV/GnJugf4xhjzHVBafdFa+7uA\nRdWA5OjkOtequwqOGAEhviceFBERERERaRb+JFnPAZ8DK3DGZAVVclT9SZa6CoqIiIiISLD5k2SF\nWWsnBzwSP7WPbl/jfOdO+PZbiIiAs84KUlAiIiIiIiJV/BmT9YEx5gZjTBdjTFL1FvDI6lG7u+B7\n7zkTX5xxBsTGBikoERERERGRKv60ZI2r2t/jdS1oU7gnRdXM79RVUEREREREWhJ/FiPu3hyB+CPM\nFUZMWIznvKQEPv7YOR4xIkhBiYiIiIiIePFnMeLxvq5ba19p+nAalhiViDHGc/7ZZ1BUBAMHQlpa\nc0cjIiIiIiJSlz/dBU/yOo4EzgSWAM2eZCVEJNQ4f+01Z3/RRc0diYiIiIiIiG/+dBec5H1ujEkA\nZvv7AsaYc4EncSbZeNFaO63W/VuB64ByYBdwjbV2i6+64iPiPcdu94GugmPH+huNiIiIiIhIYPkz\nu2BtRYBf47SMMS7gaeAcoD8wzhhzVK1iS4CB1trjgTeBP9dXX7vIdp7jdesgNxe6dIEeQZmCQ0RE\nREREpC5/xmTNw5lNEJykrB8wx8/6BwHrrbWbq+qaBYwC1lQXsNYu8Cr/LXB5fZUlRB7oLvjNN87+\nlFPAa5iWiIiIiIhIUPkzJmuG13EFsNlau9XP+lMB765/W3ESr/pcC3xQ38248DjP8RdfOPtTT/Uz\nEhERERERkWZQb5JljOkFdKrV0oQx5hRjTIS1NtOP+n21MVkf1zDGXAEMBE6vr7LYcGe1YWudmQXB\nWYRYRERERESkpWioJetJai5AXK2g6t5IP+rfCqR7nacB2bULGWN+VfVaQ6215fVVtmzWMqZ8P4U9\neyAnZxidOg1jwAA/ohARERERETlM8+fPZ/78+Y2WM9b6bFjCGPODtfakeu6tsNYe02jlxoQAa3Gm\nfc8BvgfGWWtXe5U5AXgDOKeh1jFjjH14wcPcP/R+Zs92ZhQ87zx4//3GohAREREREWl6xhistXV6\n7zU0u2C7Bu5F+fOi1tpKYCLwMfATMMtau9oYM9UYM6Kq2HQgBnjDGLPUGPOf+uqLDI0E4IcfnPOT\nT/YnChERERERkebTUHfBRcaY6621L3hfNMZcCyz29wWstR8CfWtde8jr+Cx/64oIiQBgyRLnfOBA\nf58UERERERFpHg0lWb8H3jbGXM6BpOoXQDhwUaAD8yU8JJzKSlhcFc2JJwYjChERERERkfrVm2RZ\na3cAQ4wxw4Hq6SXes9Z+3iyR+RAeEs6aNVBQABkZkJISrEhERERERER8a3SdLGvtF8AXzRBLo8JD\nwvnpJ+f42GODG4uIiIiIiIgvDU180eKEh4SzcqVz3L9/cGMRERERERHxpVUlWWEhYXz1lXN8ks/J\n5UVERERERIKrVSVZISbUM7PgL38Z3FhERERERER8aVVJVl6ei717oX176Nw52NGIiIiIiIjU1aqS\nrO3bQgDo2xdMnXWVRUREREREgq9VJVnZVUlWnz5BDkRERERERKQerSrJ2rZVSZaIiIiIiLRsrSrJ\n2prlJFm9ewc5EBERERERkXq0qiRre7aTZPXqFeRARERERERE6tGqkqydO5wkKy0tyIGIiIiIiIjU\no1UlWUWFLqKiICkp2JGIiIiIiIj41qqSLKyLrl01fbuIiIiIiLRcrS7JSk0NdhAiIiIiIiL1a3VJ\nVufOwQ5CRERERESkfq0uyerUKdhBiIiIiIiI1K/VJVkdOwY7CBERERERkfq1uiRLLVkiIiIiItKS\ntbokq2vXYAchIiIiIiJSv1aXZGkhYhERERERacmUZImIiIiIiDShVpVkxce5iIsLdhQiIiIiIiL1\nC3iSZYw51xizxhizzhhzl4/74caYWcaY9caY/xpj0uurKyM9JLDBioiIiIiIHKaAJlnGGBfwNHAO\n0B8YZ4w5qlaxa4Fca21v4Elgen31paa0qoa3I9L8+fODHYKgz6El0WfRMuhzaBn0ObQM+hxaBn0O\nLUOwPodAZy2DgPXW2s3W2nJgFjCqVplRwD+rjv8NnFlfZWmpJiBBiv/0P4yWQZ9Dy6HPomXQ59Ay\n6HNoGfQ5tAz6HFqGIzXJSgW2eJ1vrbrms4y1thLIN8Yk+aqsU0d1FxQRERERkZYt0EmWr6Yn20gZ\n46MMAB07qLugiIiIiIi0bMZan/lM01RuzGBgirX23KrzuwFrrZ3mVeaDqjLfGWNCgBxrbUcfdQUu\nUBERERERkUNgra3TsBQa4Nf8AehljMkAcoCxwLhaZeYBVwLfAZcAn/uqyFfwIiIiIiIiLU1Akyxr\nbaUxZiLwMU7XxBettauNMVOBH6y17wIvAq8aY9YDe3ASMRERERERkVYpoN0FRURERERE2ppWMZNE\nYwsaS/MwxmwyxvxojFlqjPk+2PG0FcaYF40xO4wxy72uJRpjPjbGrDXGfGSMSQhmjG1BPZ/DQ8aY\nrcaYJVXbucGMsS0wxqQZYz43xqwyxqwwxvyu6rq+E83Ix+cwqeq6vhPNyBgTYYz5rurf5RXGmIeq\nrnczxnxb9X34lzEm0MND2rwGPouXjTEbq64vMcYcG+xYj3TGGFfVz3pu1XlQvg8tPsnyc0FjaR5u\nYJi19gRr7aBgB9OGvIzz37+3u4FPrbV9ccYx3tPsUbU9vj4HgL9Ya0+s2j5s7qDaoApgsrW2H/BL\n4OaqfxP0nWhetT+HiV7/Nus70UystaXAcGvtCcDxwHnGmJOBacDjVd+HfODaIIbZJjTwWQDcXvW7\n04nW2uX11yJN5BZgldd5UL4PLT7Jwr8FjaV5GFrHfzNHFGvtV0Bercvei3j/ExjdrEG1QfV8DuB7\nqQoJEGvtdmvtsqrj/cBqIA19J5pVPZ9D9TqY+k40I2ttUdVhBM5YewsMB96suv5P4KIghNbm+Pgs\n3FXn+k40E2NMGnA+8Hevy2cQhO9Da/iF2Z8FjaV5WOAjY8wPxpjrgx1MG9fRWrsDnF92gA5Bjqct\nu9kYs8wY83d1UWtexphuOH8x/hbopO9EcHh9Dt9VXdJ3ohlVdY1aCmwHPgEygXxrbfUv+FuBlGDF\n15bU/iystT9U3Xqk6jvxuDEmLIghtgVPAHdQteauMSYZyAvG96E1JFn+LGgszWOItfYXOH8huNkY\nc2qwAxIJsr8CPa21x+P8o/qXIMfTZhhjYoF/A7dUtaTo34Ug8PE56DvRzKy17qouamk4vX+O9lWs\neaNqm2p/FsaYfsDd1tqjgZOAZEBzCwSIMeYCYEdVK3t1/mCom0s0y/ehNSRZW4F0r/M0IDtIsbRp\nVX8dxlq7C3gb53/mEhw7jDGdAIwxnYGdQY6nTbLW7rIHpmh9AecfUQmwqkHL/wZetda+U3VZ34lm\n5utz0HcieKy1BcACYDDQrmpMO//P3p3HR13d+x9/nayTyb6RkISEgIBCiyKVWhSF2tpFUfSqBfXS\nWpEfVVMAACAASURBVNtaf2pt1dtWsS3WVqvXutxaqVptq5WivbUtKl61rSBqrYhVQRHZA0kIScie\nTNbz++PMTCb7BLKwvJ+Px3l8l/nOdz7fhEA+nHM+B/3eNOJCvhefD+lhb8XN7dXvTsPnFOAcY8x2\n4A+4YYL3Asmj8fNwOCRZwQWNjTExuHW0Vo5yTEcdY4zX/z+WGGPigTOBjaMb1VGl+//ErAS+4t//\nMvDX7m+QYdHl++D/ZT7gfPQzMVIeBT6w1t4Xck4/EyOvx/dBPxMjyxiTERiSaYyJAz6Dm/D/MnCh\n/zL9PIyAPr4XHwZ+JowxBjdXVD8Tw8Rae5O1Nt9aOwGXL/zDWnspo/TzcFisk+UvAXsfnQsa/2yU\nQzrqGGMKcb1XFjeZ8wl9H0aGMWY5MBc3zKAM+BHwF+CPwDigCLjQWls9WjEeDfr4PszDzUXpAHYC\nVwT+11KGhzHmFOAVYAPu7yML3AS8CTyFfiZGRD/fh4vRz8SIMcZ8HDeRP8LfnrTW/tT/b/YKIBX4\nN3CpvydFhkk/34u/Axm4/6B7B/hmSIEMGSbGmNOB662154zWz8NhkWSJiIiIiIgcLg6H4YIiIiIi\nIiKHDSVZIiIiIiIiQ0hJloiIiIiIyBBSkiUiIiIiIjKElGSJiIiIiIgMISVZIiIiIiIiQ0hJloiI\niIiIyBBSkiUiIgAYY9qNMW8bY/7t3353tGPqizHmWmOMZwQ+p26A15ONMVeGHI81xjw1hJ//R2PM\n+EFc/zFjzG+G6vNFROTAaDFiEREBwBhTa61NGuCaCGttR8hxpLW2PYx7h3VduIwxO4CZ1tr9A8V4\nkJ/T79fEnwA9Y639+FB8Xrd7TwVutdb+xyDf9yLwVWvtnqGOSUREwqOeLBERCTC9njRmhzHmZ8aY\nt4ALjDEvG2PuMca8CXzLGJNvjPmbMeYdY8xLxpg8//t+Y4xZZox5A7ij2z1jjTGPGmPeM8asN8bM\n9Z//sjHmT8aY540xm40xd/QSzzVADvCyMebv/nN1xpi7jDH/Bk42xvzAGPOm//6/Cnnvy/5n+Zcx\n5kNjzCn+81P95972P8fE0K+JMSbe/4xvGWPeNcbM979+OzDB/747jDEFxpgNB/uMfpcAfw2Jvc4Y\nc6cxZqMx5kVjzEn+59lqjDk75H3PAgv7uKeIiIwAJVkiIhIQ12244IUhr1VYaz9hrQ0MhYu21s6y\n1t4D3A/81lp7ArAc+EXI+3KttSdba2/o9llXAdZaOx24GPidMSbG/9rxwIXAdOBLxpjc0Ddaa38B\nFANzrbVn+E/HA/+01s6w1r4O/MIf33TAa4w5K+QWkdbaTwLfAZb6z30TuNdaeyLwCSDQCxQY7uED\nFlhrPwF8Grjbf/77wDZr7YnW2u91e88BP6PfKcD6kON44G/W2o8B9cCtwBnA+f79gLeAOb3cT0RE\nRkjUaAcgIiKHjEZ/ktGbJ/s5/hRwnn//cbr2Wv2xj/udCvwPgLV2szFmJzDZ/9rfrbX1AMaYD4AC\nXFIVytC1560NeDrk+AxjzH8BXiAV2Ag8538tcN16/70B/gks8ffC/dlau7WXz7vdGHMa0AHkGGPG\n9PFsQ/WMY4HykONma+2L/v0NgM9a2+HvOSsIuW4frqdPRERGiXqyREQkHA39HHef3Gv7uC5U96GJ\nocfNIfvthPcfgj7rn2RsjIkFfgmc7+9F+jUQWiQjcP/gva21fwDm43qsVgWG9oW4BMgAZlhrZ+AS\nmYEKbxzsMzZ2+4zWkP2OwD38zx36fg/QNEBsIiIyjJRkiYhIQK9zssLwOrDIv38p8GoY73kFl7hg\njJkMjAM2D+Iza4HQghShsXtwiV6lMSYBuKCf+wTmXBVaa3f4hyL+FTeML/S+ycA+f8/RPDp7juqA\nxD7ufbDPuAk4pnus/T2H32Rcz52IiIwSJVkiIhLg6TYn6zb/+f56qgCuBS4zxryDSyqu7eO6UA8A\nUcaY94A/AF+21rb2cl1f93gYeD5Q+CL0Omttjf/194HngTf7uV/g+Ev+ghL/BqYBj3V7/QngJGPM\nu7hEcpP/s/YDr/mLW3QvYHGwz7gKmBfGdd1fm0fn0EgRERkFKuEuIiJyCDJuHbB/AKfYMP+x9hfW\nWA2cOlRl7EVEZPCUZImIiByijDGfBTaFu+aVMeYYIMda+8rwRiYiIv1RkiUiIiIiIjKENCdLRERE\nRERkCCnJEhERERERGUJKskRERERERIaQkiwREREREZEhpCRLRERERERkCCnJEhERERERGUJKskRE\nRERERIbQsCZZxphHjDFlxpj3+rnmf4wxW4wx7xhjThjOeERERERERIbbcPdk/Qb4XF8vGmO+AEy0\n1k4CrgB+NczxiIiIiIiIDKthTbKsta8CVf1cci7wmP/afwHJxpis4YxJRERERERkOEWN8ufnArtD\njov958q6X2iMsSMVlIiIiIiISDistab7udFOsnoEBPSZTFmrPOtotnTpUpYuXTraYcgo0fdf9GdA\n9Gfg6Kbvv4zGn4H6evjgA9iwAd57DzZuhI2lH7Hv9Ash+z3oI5zRTrL2AONCjvOAkr4uDv2izp07\nl7lz5w5XXCIiIiIicoRrboaiIti8GbZvh127XNu927XS0pCLE/bCx74Bmc/CJkvEeyl0UN3rfUci\nyTL03mMFsBK4CnjSGHMyUG2t7TFUMED/eyEiIiIiIgAtLS5Jam52+4HjwLahAcrKYP9+1yorXdK0\nd29nq+qvegQQEwPjT9xK5KwH2Za2jBYaMBi+cvxXuf0zt5GdmN3r+4Y1yTLGLAfmAunGmCLgR0AM\nYK21D1lrVxljvmiM2Qo0AJcNZzxyeFPP5dFN33/RnwHRn4Gjm77/hyZroa0NWls7t6H7fb3W0gI+\nHzQ1hbdtaIBt2+by7LMuYdqxY2jij4qCsWNh8mSYNAkKClzLz4eYtL3ctfHbPPXBk8HrPzvhs9zz\nuXuYNmZav/c1h8s8J2OMPVxiFREREZGjg7U9k4juiUZ7u9tvb++639u5gV5va3PN53O9NYHj3u4T\nzme0t7t7BeINbe3tAydP7e2j+/VPSHC9TTExEBvbdd/jcQlUWpprqamQnQ25uW6bne3OR3Srt76/\naT+/fvvX3PX6XZQ3lhMbGcsZE87g5jk386lxn+pyrTGm18IXSrJEREREZNh1dPT+S3x/55qa3BCv\npqaBE4amJte632+wrbdEqbh4PI2Nu0b7SyijqKCggJ07d/Y4ryRLRERE5ChlrRueVVvrhl0FWm0t\n1NW5/cbGrq8FjkO3jY2u12MwiVKgHd6Mqlwf5fzJVF/nD7kS7iIiIiLSC2tdErR/v5ucH2g7d7qq\nZz5f52T/QC9OY6Pb1te794bOaxntHMEYN/8l0CIjux73di42FtLTwevtfC0ysut+YBsTA4mJPe8Z\nbgvcKzq6Z5syZXS/dnL4UZIlIiIiMoQCPUYH2urrXaurc0PshkpUlJu/kpQE8fGuJSa6Y6+381xo\nCz3v9brm8fSfpPR2HBnZc96LyJFMSZaIiIhIL5qbobwcKipc675fUgI1NS4ZCiRGNTVuO1Ti411P\nTmqqaykpMG4cFBa6hCcmxvW0xMV1tkBilJLiEqJAi9JvfSIjRj9uIiIicsRrbXVD7SorO9fLCd3f\nt8+tp7Nvn0ugyssPPFmKioLkZNdD1FcL9CD1dT4hwSVK0dFD+3UQCZWYmMiGDRsYP378aIdy0K68\n8kry8vJYsmTJaIcCqPCFiIiIHKba2lyv0r59sGuXW2S0qAi2boXiYqiudj1LVVUHljBFR0NGRmfL\nzOy6n5XlepkSE11SlJjYmSSZHtPg5XDWV9GDo0lERARbt25lwoQJfV5TWFjII488wqc//ekRjGzw\nLrvsMsaNG8ePf/zjsN+jwhciIiJyyGtvdwlQZaXb9jU/qa/X9u93SVS4IiLccLu0NJcYpad37ge2\nY8e6dXPGjHGJlJIlkU5GPwyDop4sERERCZu1ndXr6uo65yN136+p6Wy1tS4hqqjorJRXW3vwsRjj\nkqPMTJcgjR/vFhmdNAny892cpORkl1wlJqrwgoC1lnbbTltHW7C1trd2Pe7oPPa1+Whpb2FOwZxD\nuiersLCQK664gscff5y9e/eyYMECli1bRkxMDA8//DB33nknVVVVnHrqqSxbtoyxY8cCXXunLrvs\nMuLj49m5cyevvPIK06ZNY/ny5RQWFnL66aezdu1avF4vERERPPLII1x44YVdYli8eDFPPPEEHo+H\nyMhIfvjDH3LDDTewcuVKbrrpJkpKSjjhhBN44IEHOPbYY3t9jltuuYWNGzcSGRnJqlWrmDx5Mo8+\n+ijTp08H4MMPP+TKK6/knXfeIS8vj9tuu4358+cDXXun1qxZw6WXXsp3vvMd7rjjDqKiovjpT3/K\nV77yFR5++GGuuuoqIiIiiImJYd68efz1r38d8GusniwREREZkLVu7aPQSnb79sHevZ2trMzNTaqu\n7tqGas2j5GSXJCUn9z2Hqa/zKSkueYqMHJpYZHhYa/G1+WhsbaShtYHG1kaaWpvwtfnwtfloauvc\nb2xtpLG1kZb2lmBrbmvuctzS0dL1uL9r21tobm+msbWxSxJ1pFq+fDkvvfQSXq+Xs88+m5/85CfM\nmzePm266ib/97W9MnTqV66+/noULF7JmzRqgZ+/UihUreOGFF5gxYwaLFy9myZIlLF++nDVr1hAR\nEcGGDRsoLCzs9fMfe+wx1q5dy6OPPsq8efMA+Oijj7j44otZuXIlp59+OnfffTfz589n06ZNRPVR\niWXlypWsWLGCJ554gnvvvZcFCxawZcsWrLXMnz+fr33ta7z00kusXbuWc889l/Xr1zNp0qQe99m7\ndy91dXWUlJTw4osvcsEFF3Deeefx9a9/nddff33QwwUHS0mWiIjIEcJalyx1H2ZXU+N6kHbuhG3b\nXNu+3Z0/ELGxnfOPus9HCuwHEqTQlpHhhualprrXlSAdWto62qj2VVPtq6a5rZnm9uZg4tLc3kxT\naxMNrQ00tTa5ZKmtiWpfNS9tf4nEmMRgEtXQ0hDcb2xtpMMOYR36IRBhIoiKiCIqIoroiOjgflRE\nFNGRXY89UR5iI2N5jdf6vedQjqQ70A6za665hpycHACWLFnCNddcQ0lJCZdffjnHH388ALfffjup\nqakUFRWRn5/fo2fm/PPPZ+bMmQBccsklXH/99d1iGzi40Gueeuopzj777OAcrRtuuIH77ruP119/\nndNOO63X98+cOZPzzjsPgOuuu467776bN954A2stDQ0NfO973wNg3rx5nH322fzhD3/ghz/8YY/7\nxMTE8IMf/ICIiAi+8IUvkJCQwObNm5k1a9aAzzAUlGSJiIgc4hoauvYwBdr777uhe+XlnVXxfL7w\n7+vxdFayS0hwc5Gysty8pEDLzOwsHZ6c7LaxscP3rDJ47R3t1LXUUdtcS11zXTABCvQaVTRWsL9p\nPzXNNdQ211LbXBvcr/HVsL9pP1W+Kmqbh2AMZy9iI2OJj4nHG+0lPjqeuOg4PFEePFEe4qK67sfH\nxBMTGUNsZCwxkTFhtdiovq+NjojGG+3tkjxFmMGPGzWXH/rzkfLy8oL7BQUFlJSUUFpaGkyaAOLj\n40lPT6e4uJj8/Pwe98jOzg7ue71e6vupGPPFL36RtWvXYozhwQcfZNGiRT2uKSkpoaCgIHhsjGHc\nuHEUFxezfPlyrrjiCowxzJkzh+eeew6AcePGdbk+NzeXkpISrLVdXgs8Z3Fxca/xpaenExEyRnig\n5xlqSrJERERGUUeHK/6wcye89RZs2tQ1kSotHVxlPK+3MyEKHXKXnAwFBTBxIkyY4LYZGSrsMJo6\nbAcNLQ3Ut9RT21wbTHRqfL0nQ7Utvb9W3zI0vzgaDCmeFFI8Ka4Hx5+8xEbGBve90V4SYxKJi4pz\n+7GJ5Cfn4432Mi5pHPEx8cRHxweTKm+0l6iII//XzUNhutbu3buD+0VFReTm5pKTk8POnTuD5xsa\nGqisrOySkB2oVatW9TjXffhhTk4OGzdu7BFnbm4up512GhdffHGPe4Q+h7WWPXv2kJOTg7WWoqKi\nLtcWFRUxZcqUQcc+EkU8jvw/9SIiIqPA53Nzmrr3PpWVwQcfdK7PVFbmKu31Jza2s/JdaMvKcknU\nMce4XqjMTLe2koyM9o72YIJU7aumprmGGl8NFY0VlDeWU9FYQWVjJRVNblvTXEN9S32wNbY2Dlks\niTGJJHuSSYhJCPYWBRKh1LhUMr2ZJMUmkRybTFJsktv3uP20uDTS4tJIik06oF4eOTT88pe/5Kyz\nziIuLo7bbruNhQsXMm/ePBYtWsQll1zClClTuOmmmzj55JN79AiFIzs7m+3bt/dbwj1wTWB44EUX\nXcQdd9zByy+/zJw5c7j33nvxeDzMnj27z3usX7+ev/zlL8yfP5/77rsPj8fDySefTEdHBwkJCdx5\n551cd911vPrqqzz77LMsXbp00M+SlZXF9u3bB/2+wVCSJSIicgCsdUnSRx+5OU7l5VBSAhs3whtv\nDG6+U2qqS5oKCuAzn3EV8gKJ1NixKiU+3Ky11DTXUFZfxt76vZQ1uO2+hn2UN5RT2VTZpeco0Iai\nByk+Op6EmAQSYhJIik0i3ZveNRHqJSkKPR9IrJQcycUXX8yZZ55JaWkpCxYsYMmSJXg8Hm699VbO\nP/98qqurmT17NitWrAi+ZzA9OkuXLmXx4sX4fD4eeughLrjggh7XfP/73+eaa67hu9/9LjfffDPX\nXXcdv//977n66quD1QWfeeaZPoteAJx77rk8+eSTLF68mEmTJvHnP/+ZyMhIIiMjWblyJVdeeSW3\n3XYbeXl5PP74470WvehN6LNefvnlXHjhhaSlpTF37lyefvrpsL8O4VIJdxERkX7U1blEauNG2LMH\ntmxxw/q2boXm5r7fFx3dc35T6HFKiis1np2tOU7Dpb2jnZK6EvbU7qGkroS99Xu7JFHBbX0Zze39\nfDP7kRiTGEx2kmOTSfYkkxaXRlZ8FhneDNLj0t3Wm06KJyWYUCXEJOCN9io5Okwc6osRHy6LAA/k\nlltuYdu2bTz22GOjHUoPKuEuIiIySB0dsGuXS6Tef9+17dthxw43J6ovyclQWAjHHddZNOKYY2DW\nLLdOk3qfhl5LewsldSXU+Gqoa6mj2ldNSV0JxbXFlDWUUe2rpspXxe6a3eys3klTW1NY902ISSA7\nIZus+KzgNishi0xvZrB3KbQnKSk2ST1IItInJVkiInLUaG+HzZvhmWfc0L5du1z76CNo7GN6TGys\nKxQxaZJLpgoK4MQTYdo0V5FPDk5jayMbyjZQUldCla/KJUlNVexv2k9FUwVVTVXB+U7VvmrKG8qx\nhN+jMCZ+DAXJBeQk5jA2YSxZCVldk6mELLLis4iP0WQ2OXyNRCEHGRwNFxQRkSOOtVBcDOvWuR6p\noiJ47z03zK+vSn3Z2fCxj7k2bZpLqsaPh7w8red0IJrbmtldu5uimqJg21y5mX0N+9jXsI+KRpdA\nhdvTFBBhIhibMJa0uDQSY91QvZyEHHKTcslOyCbVk0qyJ5ncxFwKUwtJik0apieUo8mhPlxQhp+G\nC4qIyFGlvt4VnigpccP81q6F115zRSl6k58PJ53kkqrTT3c9U5MmueIT0ruW9hZ21+xme9V29tbv\npbKpkr31e6lrrqO+tZ665jpK60spbygPVtsLN3mKjohmcvpkJqZNJNWT6lqc22Z4M0iLSyPZk0yK\nJ4Xk2GQyvBlER0YP8xOLiBwcJVkiInJIs9ZV6lu3zs2P2rvXJVVbtrjiE3v29L5GTVoazJgBU6e6\nxGrKFDdXKitr5J/hUNXW0UZtcy37Gvaxp3YPRTVF7Kjawa6aXeys3hlMnGqaB1EqMUSmN5NjM44l\nPzmf/OR8JqZOJC8pjzHxY0j3ppMWl0Z8dLyGOonIEUdJloiIjLhA4lReDvv2da4nFboN3W/qp1Mk\nKgomT3bD+saPh1NOgTlz3P7R9rt7e0d7sBDE/qb9VPmqqGqqoryxnMrGSnfsq2JX9S42V26mtrk2\nrPtGmIjg8Lu8pDzSPGlkJ2STFJtEYmwiiTGJZMZnkp2QTWJMolurKSZeRSFE5KilJEtERIZFW5vr\neSoqcr1Ogap9H3zg5ku1tYV/L6/X9URNnep6ovLzXWI1ebLbjz5CR4+1dbS5hW0byilvLA+u27Sv\nYR/ljT3PVfmqBnX/CBNBUmwSGd4M8pLyyEvKY0LKBApSCihILiA3KZdMbyapcalKmEREBmHAJMsY\nk2at3T8SwYiIyKGtra2zh6miomcLvFZc7Fp7e9/3SkyEjAzIzOy6hlRv24SEI6NXqr6lnsrGSiqb\nKoPbisaKznNNlZTWlVJaX8q+hn3sbxrcP78GQ7Inmaz4LDLjM0n1pJLiSXHD8+LSSY1LJS0ujZzE\nHI7NOJa0uDQlTyIiwyCcnqx/GWPeAX4DPD/YEn/GmM8D9wIRwCPW2ju6vT4O+B2Q4r/mRmvt84P5\nDBEROXAdHVBd7arwbd3qCkbU1nYO5ystda2kxB0P5l+BQK/TxImuYt/UqW5bUAAez/A900jqsB3s\nb9rP3vq97KrexY7qHZQ3lFPlq6K0vpSy+jL2Nexjb/3eQc9tMhjSvemMiR9Dpjez6za+53GqJ5XI\nCJVCFJHwJCYmsmHDBsaPHz/aoYTlcFp0OZwkazLwGeCrwC+MMU8Cv7XWfjTQG40xEcD9wBlACbDO\nGPNXa+2HIZfdDDxprX3QGHMcsAooHORziIhIN4F5T/v2ud6loiK3JlRRUWcrLXUJVriJkzGdPUyZ\nma4nKtAyM10bO9a9Pm6cW2PqSNBhOyipK2Hr/q1s27+Nrfu3srVqK5vKN/F++fth38cT5SHDm0F6\nXDrp3nS3Dd33ppPhzSA/OZ+s+CzS4tKUNInIsKmrqwv72oiICLZu3cqECRP6vOZwSoKG24BJlr/n\n6iXgJWPMPOD3wP8zxrwLfN9a+89+3j4L2GKt3QVgjFkBnAuEJlkdQGARixSgeNBPISJylOjo6Dos\nL1AYIlA8Yt++rq2lJbz7Jia6QhGTJrkkKinJtfR0yMlxidPYse61qCNwNm9g7lNFYwXFtcUumara\nFtxu27+N5vbmPt9vMEzJmEJ+cj6FKYXBBGlM/JguC96mxaWpkp6IHJb0d9fghDMnKx24FPhPoAy4\nBlgJnAD8kf57nXKB3SHHe3CJV6hbgBeNMd8CvLheMxGRo0J7u0uUqqs7W1mZG5ZXXt65H+iN2rev\n/3lO3SUkwJgxncP28vPdUL3Afk6OWx/qSEycemOtZW/9Xt4te5dXi15lU8Umtu3fxocVH/abRAGM\niR/DMWnHMDF1YnA7OX0yk9InkeJJGaEnEBHpqbCwkCuuuILHH3+cvXv3smDBApYtW0ZMTAwPP/ww\nd955J1VVVZx66qksW7aMsWPHAl17py677DLi4+PZuXMnr7zyCtOmTWP58uUUFhZy+umnY61l+vTp\nRERE8Mgjj3DhhRd2iWHx4sUUFRUxf/58IiMj+eEPf8gNN9zAypUruemmmygpKeGEE07ggQce4Nhj\nj+31OW655RY2btxIZGQkq1atYvLkyTz66KNMnz69x7Xr1q3j2muvZdOmTXi9Xs4//3zuueceovz/\noEVERLBs2TJ+/vOfU1lZyaJFi7j//vuD73/00Ue56667KCsrY9asWTz44IPk5+cP1bckrOGC/wQe\nBxZYa/eEnH/LGPOrAd7bW8rbfVDKIuA31tp7jDEn43rKpoURl4jIIae9vbOnKdCKizt7mfbscYlU\nbW3n3KfBSktzw/ECLZBEjRnTdT8z01XlO9pYa9ldu5v3yt5jU/kmSutLKakr4d2yd9lRtaPPZCrT\nm0lmfCZZ8Vldk6m0iUxMnUhibOIIP4mISPiWL1/OSy+9hNfr5eyzz+YnP/kJ8+bN46abbuJvf/sb\nU6dO5frrr2fhwoWsWbMG6Nk7tWLFCl544QVmzJjB4sWLWbJkCcuXL2fNmjVERESwYcMGCgt77195\n7LHHWLt2LY8++ijz5s0D4KOPPuLiiy9m5cqVnH766dx9993Mnz+fTZs2BZOh7lauXMmKFSt44okn\nuPfee1mwYAFbtmwhMrLr0OnIyEjuvfdeTjrpJHbv3s0XvvAFHnjgAb71rW8Fr3nuuedYv3491dXV\nzJw5k3POOYczzzyTv/zlL/zsZz/j2Wef5ZhjjuFnP/sZixYt4rXXXjvgr3934SRZN1trnwo9YYy5\n0Fr7x+5FLHqxBwhNCfNwc7NCXQ58DsBa+4YxxmOMybDWVnS/2dKlS4P7c+fOZe7cuWGELyJycDo6\nXDJUXe2KP2zb1vtaTmVlLsHq6Bj8Z0ydCikprqWnu0QpM7MzccrIcMP1xow5cuY5HQxfm4/i2mLe\nL3+fzRWb2VG9g53VO9lVs4sdVTtoaut7Ya1UTyrHZR7HrJxZzMqdxcS0iUxJn0KyJ3kEn0BEjiTm\nlqEbSmd/NKgac0HXXHMNOTk5ACxZsoRrrrmGkpISLr/8co4//ngAbr/9dlJTUykqKiI/P5/u9ezO\nP/98Zs6cCcAll1zC9ddf3zW2MCbwhl7z1FNPcfbZZwfnaN1www3cd999vP7665x22mm9vn/mzJmc\nd955AFx33XX8/Oc/54033uCUU07pct2JJ54Y3M/Pz+cb3/gGa9as6ZJk3XjjjSQmJpKYmMi8efN4\n5513OPPMM3nooYe48cYbmTx5MgDf//73+elPf8ru3bsZN25cv8+3evVqVq9ePeDXIZwk6/vAU93O\n3YgbKjiQdcAxxpgCoBRYiOu5CrULN0Twd/7CF7G9JVjQNckSETkQHR2wfz/U17tWW+uSo9LSzjlO\ngVZR4RKrmprBJU6BJCnQsrPdsLysLLdNT4fk5M55TzExw/e8hwtrLQ2tDVQ1VQUX0K32VQf3RfmX\n4AAAIABJREFU99TuYUf1DopqithVs4uKxl7/mQhK9aRyfPbxTB8znbykPLISspiWOY0pGVNIiEkY\noacSERk5eXl5wf2CggJKSkooLS0NJk0A8fHxpKenU1xc3OvQuOzs7OC+1+ulvr6+z8/74he/yNq1\nazHG8OCDD7JoUfdf8aGkpISCgoLgsTGGcePGUVxczPLly7niiiswxjBnzhyee+45gC5JjjGGvLw8\nSkq699HAli1buO6663jrrbdoamqira2ty7MCZGVl9fo8u3bt4tprrw0mkdZajDEUFxcPmGR17+i5\n5ZZber2uzyTLGPMF4ItArjHmf0JeSgLCWkLSWttujLkaeJHOEu6bjDG3AOustc8CNwAPG2O+gyuC\n8eVw7i0iEtDU5BKnmhqXNFVVuSF6e/a4tnu3Oy4vd0P0BjOnKSAx0fUyjRnjikMEKuiFJlOB3qcj\ndWHccAV6map8Vexv2t+lBdaDCiycW+2rDiZWbR3hr04cFRFFTmIOE1MnMj1rOoUphYxPGR9s6pUS\nkZF0oL1PQ2n37s4yCEVFReTm5pKTk8POnTuD5xsaGqisrOySkB2oVatW9TjXffhhTk4OGzdu7BFn\nbm4up512GhdffHGPe4Q+h7WWPXv2kJub2+O6K6+8khNPPJEnn3wSr9fLfffdx5/+9KewYh83bhw3\n33xzr4nhUOmvJ6sEeAs4B1gfcr4O+E64H2Ct/T9gSrdzPwrZ3wScGu79ROTI19HhepJ27YKdO10r\nK3MJVGDYXnm5S6wqK12SNRgpKa4nKT7eFYbIyuqsnheY55SV5Ybopaa664+WwhChOmwHtc21VPuq\nqfZVU9FYQUldCfUt9dQ111HfUk+Vr4qyhjKqmlxCta1qG7XNBzDRDIiLiiM1LpVUT2pwm+JJIdWT\nypj4MUxKn0RBcoErb56QpUV0RURC/PKXv+Sss84iLi6O2267jYULFzJv3jwWLVrEJZdcwpQpU7jp\npps4+eSTB+yt6U12djbbt2/vt4R74JrA8MCLLrqIO+64g5dffpk5c+Zw77334vF4mD17dp/3WL9+\nPX/5y1+YP38+9913Hx6Ph09+8pM9rqurqyMpKQmv18uHH37IsmXLGDNmTFjP8s1vfpMf/OAHHH/8\n8UydOpWamhpeeuklLrjggrDeH44+f22w1r4LvGuMecJaG/5/L4qI9KO9vbNq3pYtbn5TRYVbCLe8\nvDO5Crf0OLjhdmlpLnEKtNxc1/LyOreBxOloG57X2NpIeUM5ZQ1llNSVBJOmgVptcy22R62igUVH\nRNPa0cqktEnkJ+eT7k0nzZNGWlya249LI9ObSVpcGqlxnYlUbJQmm4mIHKiLL76YM888k9LSUhYs\nWMCSJUvweDzceuutnH/++VRXVzN79mxWrFgRfM9gyrIvXbqUxYsX4/P5eOihh3pNSL7//e9zzTXX\n8N3vfpebb76Z6667jt///vdcffXVweqCzzzzTJ9FLwDOPfdcnnzySRYvXsykSZN4+umng0UvQuO9\n6667+MY3vsGdd97JjBkzWLhwIf/4xz/6fLbQ4wULFtDQ0MDChQspKioiOTmZz372s0OaZJm+JrAZ\nY56y1l5kjNlAz4qAWGt71lIcRsYYG85kOxEZeW1tnYlT9xZaFGIwhSEyM12p8fHjXcvJcfOXEhNd\nEjVmjEus0tJcb9ShuHxHh+2gvqWehpYGmtqaaGptCm4bWxupba6lub2Z1vZW2jraaO3wb3s59rX5\naG5vxtfm67Hva/PR3NbtOOT1lvZBZKzdJMcmk+JJIcWTQrInmbykPJJikkiMTSQhJoGk2CSyE7Jd\nwuRJpSClgExvptZTEZEjijEmrKIPo+VIWQT4lltuYdu2bTz22GOjHUoPff0Z8J/v8Y9efwNgrvVv\nzx6i2ETkMBPodSot7SwMEdgPHO/Y4baD+bcnI6OzCMT06S6hyshwydOUKTBhghvKdyA6bAet7a20\ntLf0aM3tzdS31NPY2oivzdcl6QlsfW2+LucaWhtobmvu9X6h9+3t/GDmGA2nmMgYxsSPYUz8GHIS\nc0iLSyMlNiWYPPXVkmKTiIyIHPgDREREpIv+hguW+re7Ri4cERkJ1roiEYHCEMXFXZOo0HNdep0i\n2iCqCaKbIMrn9iNbILuN5NR20jPaSE1vIyWtjeTUzpaY3EZ8UgsR3hqiPT6s6dpLU9/RRlVHK/ub\n9rNyq4/I7ZHBnplAj0xzW3OfycyhmNgEJMQkEB8dT1x0HHFRccGtN9pLQkwCcdFxREdEExUR1bmN\n7DwO7HuiPHiiPMRGxgb3PVEeYqO6HXd73RPlISYyRj1LIiJHMP0df+jpb7hgHb0ME8QtMGyttUnD\nGVgv8Wi4oBzVrLW023Za2luCPTWtHa3B49rmWsoby2lua6aqrpniMh97y5spr26isq6BveU+9tc2\nU9fko6G5mQ7T7BKlyGaI6mM/ugkT04SJ8mGjmrDmAMryjYLoiGhiImN6tNioWBJiEvBGe4mLisMT\n5elMfkISoNDz8THxwUSlx/0iY3s9H/isSBOpf/hERI4Ah/pwQRl+gx0u2GeSdahRkiWHKmstja2N\nNLY20tzeHOxxCd12H5LW17aiqYLa5trgPJ76lnoaWhuCQ9xGW4SJCCYjnigPcVFxREdG9+iB6avF\nR8eTEJPQa49N4Li1vZWEmATS4tJ69NYEEpvoyN6TqJjIGKIjopXYiIjIkFKSJUM2J8sYk2StrTXG\npPX2urV2/0FFKjLKmtuae6zjU95Q3qW6Wk1zTZf9hpaGHglUS3vLAVVgOyA2EtpioD0aOqKhPWS/\n1Qv12dDmIaLDQ4InlkRvLIlxHhI9XjJTvORmxZKZ5iEjJZbk+M6hZbFRsV32A8POQpMpT5SH6Mij\nfAEoERERkTD0V/hiOa7oxXrcsMHQDM0CfRfJFxkB1lp8bT7qWuqo8dX0SJgCydH+pv3B1wJr+VT5\nqoa0Z8gT5SEhJoHYyNhgwhIYMhaapPQ2NC2KOBqq46ipjKOuPJWqklR2bY1ny/sJtDUkQGs8tMS7\nrXXrAkVEwLhxMG0aFBa66nsFBZ3V+DIzD81qeyIiIiJHAw0XlENGfUs9RTVF7Kndw+6a3eyu3U1p\nXSkVTRXBBCkwfK6hpYGG1gY6bBi1wPsQFREVLDsdWK8nsHZPiiclWLo62ZMcPI6PiQ8mUoHenpjI\nmAErsDU2uip8O3fC5s3w4YdujaitW12Rib5kZ8Mxx8CMGZ1V9z72Mbdo7tG4OK6IiMho0HBBGcoS\n7qFvPh84FdeDtdZa+5eDDVSOTNZaKpsq2Vm9k5K6Euqa62hobaCxtTGYGNW31FPlq6KysZLyxnL2\nNeyjqqmKupa6QX9eTGQMCTEJpHhSSItLC7ZUTyqpnlSSPcldzgWSqbS4NOKj44d87k5HBxQVwQcf\nwPr1sG4dbNjgkqu+REW55GnSJJdQTZoExx4LM2dCSsqQhiciIiIHoKCgQPN9j3IFBQWDun7Anixj\nzAPAMcAf/Ke+BGyz1l51IAEeKPVkjTxfm6/L8LvQoXYVjRWU1pd2OVfjq2F/034aWhsO6POiI6IZ\nnzKevKQ88pLyyE/OJzcxlwxvRrB3KTE2kfjoeOJj4omPjh+1OUKtra7E+TvvwPvvw/btrlfq7beh\nvr7n9ca4RCqQTE2ZApMnu/2CAvVKiYiIiByODri6oDHmQ+C4QIZjjIkA3rfWHjcskfYdh5Ksg9TS\n3kJZfRmVTZXUNtdS46sJzlnaU7sneL6soYyt+7eyt37vAX1OUmxSMFlKik1ySVFIYhQfEx/sVUr3\nppMVn0W6N52k2CQiTMQQP/XBaWtzw/o2bIDnn4eqKnjlFaiu7nvx3exs1xM1YwacdJLbFhZCbOzI\nxi4iIiIiw+tghgtuBfKBwKLE4/znZARZa2lobaC2uTbYanw11DbXBgs8VPmqulTG635usIUeoiKi\nSI9L7xxu5x9ml+Zx+zmJOaTHpZMa54bmpXhSgnOYDjcdHbBrlxvm99FHbt7U5s3w1lu990wBZGW5\nwhMnnggTJ7pEavp0N19KRERERI5e/ZVwfwY3BysR2GSMedN//EngzZEJ78gUSJiqfdVUNVVR5aui\nqqmKyqZKKhorqGisoKyhjMrGymDp8L31e6lorDioz400kaTGpTI2YSzJnuRgYYdUj0uYxsSPISk2\niaTYJCanTyY/OX/Agg6Ho7o6l0xt3AjvvefmTr33njvfm4ICV2wiUHBi3jw31M/jGdm4RUREROTw\n0F9P1l0jFsURJLAwbW1zLTuqd7B1/1a2V21nV80udtfspqimiKKaIprbmwd9b0+Uh+TYZJJik0iM\nTSQ5NplkT3KXXqTQ/eC5OHduOAo9HMra2tw8qXffdXOnNm50ra8iFBkZridqypTONnUq5OePaNgi\nIiIicphTCfcw1TXXsad2T7AV1xWzu2Y35Y3lVDRWBHuh9jftp62jbcD7xUXFBZOfQGKU4c0g05tJ\nhjeDdG86Y+LHBBOltLg0chNzj6okaTCamuCNN1zhiTfecD1VW7a4AhXdxcTAcce5nqlp01wVv6lT\nITdXa0uJiIiISPgOeE6WMeZk4BfAcUAMEAk0WGuThjzKUWKtpamtibL6MkrrSymqKWJT+SY2V25m\nw74N7KndQ21zbdj3i4uKIyk2iZzEHI7NOJbClELGp4wnPzmfccnjyE/OJyEmYRif6MjX2Ahvvgkv\nvQR//jNs2tT7dXl5cPzxbt7U9OkusTrmGFXzExEREZHhE86vmvcDC4E/Ap8AFgOThzOo4dLW0cam\n8k2sL13Pe2XvsbvWDd/buG/jgEUhPFEexiWNIy8pj9ykXHITXRubONb1PMWlB0uNx0apjNxQamtz\ni/e+9prrqdq40RWkaGnpet348a5H6rzzXO/U5MkQHz8qIYuIiIjIUSys/8+31m41xkRaa9uB3xhj\n/g3cOLyhHbyKxgpe3PYiKzauoLyxnHf3vktTW1Ov18ZGxjImfgxjE8eSk5jDcRnHMSF1AjOyZ1CY\nWkiqJ1VD9UZAWxv8/e+ulZa60umbNvVMqMD1Ss2dC5/7HMyeDWlpIx6uiIiIiEgP4SRZjcaYGOAd\nY8ydQClwaC1m1M3e+r0sW7eM+/51HzXNNV1em5A6gZljZzIjewbjU8aTm5TLtMxppHvTRynao9vW\nrfD66669/bYrm17by8jM8ePh5JPhk5+Ej3/cJVhZWSMeroiIiIjIgMJZjLgAKMPNx/oOkAw8YK0d\n0bWywi188dT7T3H5ysupb3GLG80eN5svHvNFpmRM4YzCM0iNSx3uUGUAdXXwpz/Bgw+6IhXdTZ4M\nZ53lyqXPnu2SqqQjZgagiIiIiBwp+ip8EVZ1QX9P1rG4dbI2W2t7Gbw1vMJJsu755z1c9+J1AJw1\n6Syu+9R1zBs/T8P8RpnP55Kp1avhhRdg3Tpob3evxcfDZz/reqlmzXJl08eOVZU/ERERETn0HXCS\nZYw5C/gVsA0wQCFwhbX2+eEItJ84+k2yHn/3cRb/ZTEAP/30T7lpzk0jFZp0U1Hhhv+99ppr69Z1\nnVMVGekSqq9+FRYuhAQVWhQRERGRw9DBJFkfAmcHhgcaYyYCz1lrjx2WSPuOo88ka0vlFmb9ehbV\nvmp+8YVfcPWsq0cytKOatbBtmytUsW6dS6o+/LDrNca4OVRz5sDnP++KVSQmjkq4IiIiIiJD5oDX\nyQLqus2/2g7UDVlkB6m9o52L/vciqn3VnDPlHK466arRDumIV1UFa9e64X9//jPs3Nn1dY/HFag4\n5RTXPvUpSNVUOBERERE5SvSZZBljzvfvvmWMWQU8hZuTdSGwLtwPMMZ8HrgXV5HwEWvtHb1ccxHw\nI6ADeNdae2m49//jB3/knb3vMC5pHL8/7/eafzXEWlvdulT/+AesXw8ffADvved6sALS0+HTn3bJ\n1OzZMGMGxMSMXswiIiIiIqOpv56s+SH7ZcDp/v1ywBPOzY0xEbjFjM8ASoB1xpi/Wms/DLnmGOB7\nwKestbXGmIxBxM9/v/7fACyZs4TEWI1BO1jNzfDKK7Bqleut2rjRnQsVHe16qubNgzPOcMMAIw7p\nov4iIiIiIiOnzyTLWnvZENx/FrDFWrsLwBizAjgXCJ2183Xgl9baWv/nVoR78y2VW3i79G2SYpP4\n8glfHoJwjz4tLW59qtdeg5dfhuee63nNxIkwc6abS3X88XDCCeD1jnioIiIiIiKHhQHnZBlj8oBf\nAKfghgu+Clxrrd0Txv1zgd0hx3twiVeoyf7PeRU3pPAWa+0LYdybpzc9DcD8yfPxRIXVuXbU8/ng\n3Xfd8L9HHoHiYncu1JgxcPHFcO65buhfcvLoxCoiIiIicjgKp/DFb4DluLlYAJf6z302jPf2NkGq\ne4nAKOAY4DQgH1hrjJkW6Nnqz582/QmA/zjuP8II5ei1Zw88+aSrAPj3v3ctpw5w3HFw6qmuSMVn\nPgO5uaMTp4iIiIjIkSCcJCvTWvubkOPfGmO+Heb99+ASp4A83Nys7tf801rbAew0xmwGJgHru99s\n6dKlwf3jPnEc60rW4Y328rljPhdmOEeHxkbYscMlVE895YYCBhjjkqo5c1yxitNPh+zs0YtVRERE\nRORwsXr1alavXj3gdeGsk/U34LfAH/ynFgGXWWvPGPDmxkQCm3GFL0qBN4FF1tpNIdd8zn/uK/6i\nF+uBE6y1Vd3u1WWdrIfXP8w3nv0G5x17Hk9/6ekBH/RItW+fq/i3c6cbBvj001BU1PUajwfOOssN\n//v0p9VTJSIiIiIyFA5mnayv4ioE3oMb6ve6/9yArLXtxpirgRfpLOG+yRhzC7DOWvustfYFY8yZ\nxpj3gTbghu4JVm9e3f0qAHPHzw0nlCNKQwP86U+ul+r556Gjo+c18fHwuc/BhRfC2WdDQsLIxyki\nIiIicjTqtyfL3xP1LWvtPSMXUp+xBHuyrLUU3lfIrppd/PuKf3NC9gmjHN3IqKmBX/4S7rkHKvw1\nGKOj4aSTYMIEmDQJTjsNZs1S9T8RERERkeF2QD1Z/p6oRbherEPGR5UfsatmFxneDD4+5uOjHc6w\nq6iAe++F++93iRa4xGrxYvjSlyAzc3TjExERERGRTuEMF3zNGHM/8CTQEDhprX172KIawLtl7wJw\nct7JREZEjlYYw66mBn79a/jxj6HWX2tx7lxYssQtAmx6q90oIiIiIiKjKpwkKzAW78ch5yzw6aEP\nJzxvFr8JwIzsGaMVwrCprXXFK1avhj/+0VUKBDjzTPjRj2D27FENT0REREREBjBgkmWtnTcSgQzG\nv4r/BcCn8j41ypEMnZ07Ydky+N3voKys8/zcufCd78D8+eq5EhERERE5HAyYZBlj0oEfAafierBe\nBX5sra0c5th61d7RztulbqTiSbknjUYIQ6q6Gm66CR55pHOR4E98AhYtcuXWTzg6anqIiIiIiBwx\nwhkuuAJ4BfgP//EluPlZnxmuoPqzo3oHja2N5CXlkeHNGI0QhsQ//gF33+22TU3u3MKF8M1vuoWC\nIyJGNz4RERERETkw4SRZY621t4Yc/8QY86XhCmggmys2A3BsxrGjFcJBefttuOIKeOutznNz5rjS\n7B8/8gslioiIiIgc8cLpL3nRGLPQGBPhbxcBLwx3YH35qPIjACalTRqtEA5IaSl87WtuKOBbb7nF\ngf/rv2D3bnjlFSVYIiIiIiJHinB6sr4OfBt43H8cCTQYY64ArLU2abiC683GfRsBOC7juJH82AO2\nb5+bc/W730FbG0RFwdVXw623ukRLRERERESOLOFUF0wciUDCtb16O3DoDxdsbobbb4fbboPWVnfu\nvPPgZz+DyZNHNzYRERERERk+4fRkHVL21O4BIC8pb5Qj6duWLa464Pr17njuXJdcffKToxqWiIiI\niIiMgMMuydrXsA+ArISsUY6kp9pa+J//gR/+EKyFcePgscdckiUiIiIiIkeHwyrJqmuuo7a5Fk+U\nh1RP6miH08Wrr8I550BVlTueP9/Nw0o9tMIUEREREZFhFtZqTMaYU40xl/n3M40xhcMbVu+K64oB\nyE3MxRgzGiH0YC38/Odu4eCqKjj5ZHjhBVi5UgmWiIiIiMjRaMCeLGPMj4BPAFOA3wDRwO+BU4Y3\ntJ7K6ssAGJs4dqQ/uleVlfDVr7qECuCqq+C++yAycnTjEhERERGR0RPOcMHzgBnA2wDW2hJjzKhU\nHKxprgEgxZMyGh/fxSuvwIUXuhLtKSnw29/CueeOdlQiIiIiIjLawhku2GKttYAFMMbED29Ifav2\nVQOjm2RZC488Ap/9rEuwTj0V3nxTCZaIiIiIiDjhJFlPGWMeBFKMMV8H/gY8PLxh9S6QZCXHJo/G\nx9PYCP/5n/C1r0FLi1tUePVqmDRpVMIREREREZFDUDiLEd9ljPksUIubl/VDa+1Lwx5ZL2p8ozdc\ncMcOt/bVv/4FcXHwq1+5hOsQqb8hIiIiIiKHiHAKX3wH+ONoJVahRmO4YGMj3H03/PSn4PNBQQE8\n8wx8/OMjFoKIiIiIiBxGwhkumAS8YIxZa4y5yhgzaqsABwpfjNRwwbffdnOufvADl2AFerKUYImI\niIiISF8GTLKstbdYa6cBVwE5wBpjzN+GPbJejGRP1hNPwKc+Bf/+N+TkwKpVsHw5ZI1aiikiIiIi\nIoeDsBYj9tsH7AUqgTHDE07/gj1ZnuHrydq7F84/Hy691BW3+NrX4IMP4AtfGLaPFBERERGRI0g4\nc7KuBL4EZAL/C3zdWvvBcAfWm+HuyXrnHViwAHbtAo8Hbr8drr1WxS1ERERERCR84SxGXAB821r7\nznAHM5DhSrKshWXL4NvfhtZWmDUL/vxnN0xQRERERERkMPocLmiMSfLv3gkUGWPSQlu4H2CM+bwx\n5kNjzEfGmO/1c90FxpgOY8yJfV0TKOE+lIUvqqvh8svhqqtcgnXFFbBmjRIsERERERE5MP31ZC0H\nzgbWAxYIHTRngQkD3dwYEwHcD5wBlADrjDF/tdZ+2O26BOAa4I3+7hdcjHiI5mQ984xLsMrL3dpX\nv/41XHzxkNxaRERERESOUn0mWdbas/3bwoO4/yxgi7V2F4AxZgVwLvBht+tuBe4A/qu/m7V2tBIb\nGYsnynMQITlPPukWE25thdmz3XDB6dMP+rYiIiIiInKUG7C6oDHm7+Gc60MusDvkeI//XOi9TgDy\nrLWrwrnhwc7HshYeeAAuucQlWNdeC6+8ogRLRERERESGRp89WcYYD+AFMowxqXQOF0zCrZcVjt7q\n8tmQzzDAPcCXB3hP0MEkWS0tcP31cP/97vi734Wf/UzVA0VEREREZOj0NyfrCuDbuIRqPZ3JTy3w\nyzDvvwfIDznOw83NCkgEpgGr/QlXNvBXY8w51tq3e9ztZahLqmNpxVLmzp3L3LlzwwzDlWU/91x4\n912IjnbDA7/6VSVYIiIiIiISntWrV7N69eoBrzPW2v4vMOYaa+0vDiQIY0wksBlX+KIUeBNYZK3d\n1Mf1LwPXWWv/3ctrlqVw5sQzeeHSFwYVxwcfwJlnQnExTJgAjz/u5mGJiIiIiIgcKGMM1toe3TYD\nrpNlrf2FMeZjwFTAE3L+sTDe226MuRp4ETf/6xFr7SZjzC3AOmvts93fwgDDBQdbvn3lSli4EJqa\nYM4cd5wyPGsZi4iIiIiIDJxkGWN+BMzFJVmrgC8ArwIDJlkA1tr/A6Z0O/ejPq799ED3S4pNGuiS\noI8+gi99CXw+OP9814Pl9Yb9dhERERERkUEbsLogcAFuuN9ea+1lwPHA0K0GPEje6PCypPZ2+PrX\nXYJ14YXwv/+rBEtERERERIZfOElWk7W2A2gzxiQB+4BxwxtW38JNsp54wpVmHzPGFblQgQsRERER\nERkJAw4XBN4yxqQAD+OqDNYD/xzWqPoRFxU34DXV1fC977n9//5vSE8f5qBERERERET8wil88f/8\nu78yxvwfkGStfW94w+pbXPTASdaNN8Leva6C4KWXjkBQIiIiIiIifv0tRnxif6/1uo7VCIiJjOn3\n9e3b4eGHITISHnoIIsIZECkiIiIiIjJE+uvJ+nk/r1lgwEqAwyE6Irrf1+++2xW9WLwYpk0boaBE\nRERERET8+kyyrLXzRjKQcEVH9p1kNTXBY/7C8tdfP0IBiYiIiIiIhAhnnazFvZ0PZzHi4dBfT9bz\nz0NdHcycCdOnj2BQIiIiIiIifuFUFzwpZN+DWzPrbcJcjHio9deT9eSTbvulL41QMCIiIiIiIt2E\nU13wmtBjY0wy8OSwRTSAvnqyGhrg2Wfd/kUXjWBAIiIiIiIiIQ6k9l4jUDjUgYSrr56sVaugsRE+\n+UkoKBjhoERERERERPzCmZP1DK6aILikbCrw1HAG1Z++erL+8Ae31VBBEREREREZTeHMyborZL8N\n2GWt3TNM8QwoKqJnyK2t8NJLbv/CC0c4IBERERERkRDhzMlaA2CMSQpcb4xJs9buH+bYetXbcME3\n34T6epgyBfLyRiEoERERERERv3CGC34DuBVoAjoAgxs+OGF4Q+tdb8MF16xx20+PyvLIIiIiIiIi\nncIZLvhfwDRrbcVwBxOO3nqyVq1y2zPOGOFgREREREREugmnuuA2XEXBQ0L3OVn798M//wnR0XDm\nmaMUlIiIiIiIiF84PVk3Aq8bY/4FNAdOWmu/NWxR9aP7cMF//Qs6OmD2bEhMHI2IREREREREOoWT\nZD0I/APYgJuTNaq692S9/bbbzpw5CsGIiIiIiIh0E06SFW2tvW7YIwlT9zlZ69e77Sc+MQrBiIiI\niIiIdBPOnKznjTHfMMaMNcakBdqwR9aH7sMF33rLbdWTJSIiIiIih4JwerIW+bc3hpwbtRLuocMF\ny8pg925ISIDJk0cjGhERERERka7CWYy4cCQCCVfocMGNG932hBMgMnKUAhIREREREQkESKinAAAN\n90lEQVQRzmLEi3s7b619bOjDGVhoT9bOnW47fvxoRCIiIiIiItJTOHOyTgppc4ClwDnhfoAx5vPG\nmA+NMR8ZY77Xy+vfMca8b4x5xxjzkjFmXH/3C52TtWmT206ZEm40IiIiIiIiwyuc4YLXhB4bY5KB\nJ8O5uTEmArgfOAMoAdYZY/5qrf0w5LK3gZnWWp8x5pvAfwML+ww4pCfrnXfcdvr0cKIREREREREZ\nfuH0ZHXXCIQ7T2sWsMVau8ta2wqsAM4NvcBau8Za6/MfvgHk9nfD0CTrgw/c9mMfCzMaERERERGR\nYRbOnKxncNUEwSVlU4Gnwrx/LrA75HgPLvHqy+XA8/3dMFD4oqYGSkvB44GCgjCjERERERERGWbh\nlHC/K2S/Ddhlrd0T5v1NL+dsL+cwxlwKzARO7++GkcaVEQydj6XKgiIiIiIicqjoM8kyxhzD/2/v\n/oPlKus7jr8/CUn4keGHpSAlQpQfZbAChh8itBRHOmJbZbAwFmkbqWM7FgecTtXa2iItQ6N2BkVa\nGVtQoFWE0io/pKMVrpSiAQIUhJDSihQsUCWk8psYvv1jz4XNsnvvhezu3b15v2YyOXvOs8/5Zp9z\nn5vvPs85D+xcVd/q2H94kkVV9V8zqP8BYLe210to3ZvVea6jaK3DdUQzrbB7TBPh9DodgCeeOBI4\nkn33nUEUkiRJkrSJJiYmmJiYmLZcqroOLJHkSuAjVXVHx/7XAWdW1dumrTyZD6yh9eCLB4EbgROq\nanVbmdcDlwJvmSpxS1JbnbEVT/7xkwCceiqcfTasWAEfftEzCyVJkiRpsJJQVS+avTfVgy927kyw\nAJp9S2dy0qraALwf+DpwJ3BxVa1OcnqSX22KfQLYBrg0ya1JvtKrvvaHXtzdPJ9wn31mEokkSZIk\nDcdU92RtP8WxrWZ6gqr6Z+BnO/ad1rb9SzOtqz3J+t73Wn/vtddM3y1JkiRJgzfVSNbNSd7buTPJ\ne4BVgwupt8knC27YAPfd19q3dOlsRCJJkiRJ3U01kvUB4J+SnMgLSdVBwELg2EEH1s2Cea0k6777\nYP162HVX2Hrr2YhEkiRJkrrrmWRV1cPAYUneBEwu93tVVV0zlMi6mBzJmpwquMcesxWJJEmSJHU3\n7TpZVXUtcO0QYpnW5D1Z997bev2a18xiMJIkSZLUxVT3ZI2cyemCkyNZJlmSJEmSRs14JVnzTbIk\nSZIkjbbxSrIcyZIkSZI04sYryXIkS5IkSdKIG68ka94C1q2DtWtbj27faafZjkiSJEmSNjZeSdb8\nBRs9WTCZ3XgkSZIkqdN4JVnzFjw/VfDVr57dWCRJkiSpm/FKsuYv8H4sSZIkSSNtvJKseSZZkiRJ\nkkbbeCVZjmRJkiRJGnHjlWTNW8CaNa3tPfec3VgkSZIkqZuxSrJSW3D//TBvniNZkiRJkkbTWCVZ\nzzy1gOeeg912g4ULZzsaSZIkSXqxsUqynnp8AQC77z7LgUiSJElSD2OVZD3ZJFmukSVJkiRpVI1V\nkvXYulaStXTp7MYhSZIkSb2MVZL1f4+2kqy9957lQCRJkiSph7FKstY90kqyfHy7JEmSpFE1VknW\n2h9tAZhkSZIkSRpdY5Vk/eSprdlxR9hhh9mORJIkSZK6G6ski2e3Yb/9ZjsISZIkSept4ElWkqOT\n3J3kP5J8uMvxhUkuTnJPkm8n2a1nZc8u5rDDBhquJEmSJG2SgSZZSeYB5wBvAV4LnJBkn45i7wHW\nVtVewKeAT/SscP02HHvsgILVyJuYmJjtEDSLbH95DchrYPNm+2ucroFBj2QdAtxTVfdV1XrgYuCY\njjLHABc02/8AvLlXZYcdtJhlywYSp8bAOP1gqf9sf3kNyGtg82b7a5yugUEnWbsC97e9fqDZ17VM\nVW0A1iV5RbfKPvB7iwcRoyRJkiT1zaCTrHTZV9OUSZcyAOz9yiX9iEmSJEmSBiZVXfOZ/lSeHAp8\nrKqObl7/IVBV9fG2Mlc3ZVYmmQ88WFU7dalrcIFKkiRJ0stQVS8aWNpiwOe8Cdgzye7Ag8CvAyd0\nlLkCWA6sBI4HrulWUbfgJUmSJGnUDDTJqqoNSd4PfJ3W1MTzqmp1ktOBm6rqSuA84KIk9wCP0ErE\nJEmSJGksDXS6oCRJkiRtbga+GPFL1dfFizV2ZtD+y5P8b5Jbmj+/PRtxanCSnJfk4SS3T1Hm7KYP\nuC3JAcOMT4M1Xfsn+cUk69r6gI8OO0YNVpIlSa5JcleSO5Kc0qOc/cAcNJP2tx+Y25IsSrIyya3N\nNXBalzIjnw+MVJLV98WLNVZm2P4AF1fVsubP+UMNUsPweVrXQFdJ3grs0fQBvwucO6zANBRTtn/j\nurY+4IxhBKWh+gnw+1W1L/BG4OTO3wX2A3PatO3fsB+Yo6rqGeBNVfV64ADgrUkO6Sg28vnASCVZ\n9HnxYo2dmbQ/dF8aQHNEVV0PPDpFkWOAC5uyK4Htkuw8jNg0eDNof7APmNOq6qGquq3ZfhxYzYvX\n2LQfmKNm2P5gPzCnVdWTzeYiWs+Q6Ly/aeTzgVFLsvq6eLHGzkzaH+AdzfSQS5K4eNrmp/M6+QHd\nrxPNXYc200iuSrLvbAejwUmylNY32Ss7DtkPbAamaH+wH5jTksxLcivwEPCNqrqpo8jI5wOjlmT1\ndfFijZ2ZtP/lwNKqOgD4Ji98i6HNx0yuE81dq4Ddm2kk5wBfmeV4NCBJFtP6hvrUZkRjo8Nd3mI/\nMIdM0/72A3NcVT3XtO8S4A1dEumRzwdGLcl6AGi/cW0J8D8dZe4HXgXQLF68bVVNN7VE42Ha9q+q\nR5uphAB/Axw4pNg0Oh6g6QMa3foJzVFV9fjkNJKquhpYMGrfXmrTJdmC1n+wL6qqr3YpYj8wh03X\n/vYDm4+q+jEwARzdcWjk84FRS7KeX7w4yUJaa2Zd3lFmcvFimGLxYo2lads/ySvbXh4D3DXE+DQ8\nofd8+8uB3wJIciiwrqoeHlZgGoqe7d9+301zI3Sqau2wAtPQnA/cVVWf7nHcfmBum7L97QfmtiQ7\nJtmu2d4KOAq4u6PYyOcDA12M+KVy8eLN2wzb/5QkbwfWA2uBd89awBqIJF8EjgR+Ksl/A6cBC4Gq\nqs9V1deS/HKS/wSeAE6avWjVb9O1P3BckvfR6gOeAt45W7FqMJIcDpwI3NHck1HAHwG7Yz8w582k\n/bEfmOt2AS5onjo9D/hy8zM/VvmAixFLkiRJUh+N2nRBSZIkSRprJlmSJEmS1EcmWZIkSZLURyZZ\nkiRJktRHJlmSJEmS1EcmWZIkSZLURyZZkqSukmxIckuSW5u/PzTbMW2qJMs7FjWfUbkkn0uyT59i\nOCbJRzexjmuTLGu2vzG5cKckaTSM1GLEkqSR8kRVLZuqQJJ5VfVc2+v5VbVhuopnWu7l6Iypw7uB\n7wIPTVPNRuWq6nf6FR/wIeBtnTs34TO5EDgZOHNTA5Mk9YcjWZKkXtJ1Z3JvkhVJbgaOa0ZVzkpy\nI3BKkt2S/EuS25pRliXN+z6f5LNJvgN8vKPORUnOT3J7klVJjmz2L09yWZKrk6xJ8vHOeHrEtH+S\nbzcxXJZk+yS/BhwE/F0zMrcoyZ8kWdmc99ymrs5yW3aMHJ3QlL89yYq2GB5LckZzzhuS/HSXOPcC\nnq6qtd0+kyQHJ/m35jO4vilPE8OXktyZ5B+BLduqvQI4YeqmlCQNk0mWJKmXrTqmCx7fduxHVXVQ\nVV3SvF5QVYdU1VnAOcAXquoA4IvAZ9ret2tVHVpVf9BxrpOBqqr9gHcBFyRZ2BzbHzge2A94Z5Jd\ne8TbHtOFwAebGL4L/GlVXQbcDLyrqpZV1TPAZ6rqDc15t07yK13KPT15giS7ACuAI4EDgIOTvL05\nvA1wQ3POfwXe2yXGw4FbOva1fyargV+oqgOB04C/aMq8j9bI4mub/QdNvrmq1gELk+zQ43ORJA2Z\n0wUlSb08OcV0wS9P8fqNwLHN9kVsPGp1aY/6fh44G6Cq1iT5PrB3c+ybVfU4QJK7gN2BH/SKKcm2\nwHZVdX2z/wLgkrZy7SN0b07yQWBrYAdaCdlVXcpNOhi4tm0k6u+BI4DLgWer6mtNuVXAUV3evwvw\nw4597Z/J9sCFzQhW8cLv6SOATwNU1R1J/r2jjh8CPwM82uWckqQhcyRLkvRyPDHF6+o4Vj3KtetM\naNpfP9O2vYHeXxD2qrv7CZNFwF8B72hGsv6Wjafh9Yqz6zRKYP0M4nyqyzna4/5z4Jqqeh2t+7ba\ny7Z/jp0xbNnULUkaASZZkqReeiUT07mBF+4R+g3g+inKTroOOBEgyd7Aq4A1L+fkVfVj4NEkhze7\nfhP4VrP9GLBts70lrcTlkSSLgePaqmkv124lcESSVySZT+vfOfESwlsN7DXF8W15YZTupLb919H6\nLEnyc7SmTrbbGfj+S4hDkjRAJlmSpF627Lgna/LpdVONVAGcCpyU5DZaidOpPcq1+2tgiyS3A18C\nllfV+i7letXRuX858JdNDPsDf9bs/wJwbpJbgKdpjV7dCVwN3Nj2/ufLJZlMxqiqh4CP0EqsbgVW\nVdWVM/j3TbqO1r1cveL+JLAiySo2/h39WWBxkjuBj9G6ZwyAJAcC35niiYqSpCFL1Ux+J0iSpH5I\nchZwRVVd06f6PgV8taqu7Ud9kqRN50iWJEnDdSatB230yx0mWJI0WhzJkiRJkqQ+ciRLkiRJkvrI\nJEuSJEmS+sgkS5IkSZL6yCRLkiRJkvrIJEuSJEmS+sgkS5IkSZL66P8Bio8AfyxfJKkAAAAASUVO\nRK5CYII=\n", - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "fig = plt.figure(figsize=(12,6))\n", - "\n", - "\n", - "\n", - "ax1 = fig.add_subplot(211)\n", - "for name in solution_names:\n", - " data = plot_data[name].error_trans.sort(inplace=False).values\n", - " cum_prob = np.linspace(0, 1., len(data))\n", - " ax1.plot(data, cum_prob,\n", - " '-', lw=2 \n", - " );\n", - "ax1.set_xlabel('Error on translation (m)')\n", - "ax1.set_ylabel('Cumulative probability')\n", - "ax1.set_xlim([0., data.max()])\n", - "ax1.set_ylim([0., 1.01])\n", - "ax1.legend(solution_names)\n", - "\n", - "ax2 = fig.add_subplot(212)\n", - "for name in solution_names:\n", - " data = plot_data[name].error_rot.sort(inplace=False).values\n", - " cum_prob = np.linspace(0, 1., len(data))\n", - " ax2.plot(data, cum_prob,\n", - " '-', lw=2 \n", - " );\n", - "\n", - "ax2.set_xlabel('Error on rotation (rad)')\n", - "ax2.set_ylabel('Cumulative probability')\n", - "ax2.set_xlim([0., data.max()])\n", - "ax2.set_ylim([0., 1.01])\n", - "ax2.legend(solution_names)\n", - "\n", - "fig.tight_layout()" - ] - }, - { - "cell_type": "code", - "execution_count": 216, - "metadata": { - "collapsed": false - }, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAjkAAAI6CAYAAADFf1nDAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nRU5ErkJggg==\n", - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "fig = plt.figure(figsize=(8,8))\n", - "ax1 = fig.add_subplot(111)\n", - "ax1.hexbin(plot_data.validation.perturbation_trans.unique(), plot_data.validation.perturbation_rot.unique(), \n", - " gridsize=30);\n", - "ax1.set_xlabel('Translation (m)')\n", - "ax1.set_ylabel('Rotation (rad)')\n", - "fig.tight_layout()" - ] - }, - { - "cell_type": "code", - "execution_count": 234, - "metadata": { - "collapsed": false - }, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAeYAAAHhCAYAAAC7lh13AAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nyP8Pl+quvPNPwEoAAAAASUVORK5CYII=\n", - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "fig = plt.figure(figsize=(8,8))\n", - "ax1 = fig.add_subplot(111)\n", - "ax1.violinplot(plot_data[[('point-to-point', 'error_trans'), ('point-to-plane', 'error_trans')]].values)\n", - "ax1.set_yscale('log')" - ] - }, - { - "cell_type": "code", - "execution_count": 237, - "metadata": { - "collapsed": false - }, - "outputs": [ - { - "data": { - "text/plain": [ - "point-to-point error_rot 0\n", - "dtype: float64" - ] - }, - "execution_count": 237, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "np.min(plot_data[[('point-to-point', 'error_rot')]])" - ] - }, - { - "cell_type": "code", - "execution_count": 211, - "metadata": { - "collapsed": false - }, - "outputs": [ - { - "data": { - "text/plain": [ - "array([ 2.3344, 2.9928, 5.9257, ..., 3.8618, 2.7754, 2.2971])" - ] - }, - "execution_count": 211, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "plot_data['point-to-point', 'time'].values" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "collapsed": true - }, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 2", - "language": "python", - "name": "python2" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 2 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython2", - "version": "2.7.6" - } - }, - "nbformat": 4, - "nbformat_minor": 0 -} diff --git a/thirdparty/libpointmatcher/evaluations/official_solutions/Besl92_pt2point.yaml b/thirdparty/libpointmatcher/evaluations/official_solutions/Besl92_pt2point.yaml deleted file mode 100644 index a42f47c..0000000 --- a/thirdparty/libpointmatcher/evaluations/official_solutions/Besl92_pt2point.yaml +++ /dev/null @@ -1,45 +0,0 @@ -# Solution based on: -# P Besl and H McKay, 1992. A method for registration of 3-D shapes. -# Pattern Analysis and Machine Intelligence, IEEE Transactions on, 14, pp. 239 - 256. -# - and - -# Chetverikov, D and Svirko, D and Stepanov, D and Krsek, P, 2002. The Trimmed Iterative Closest -# Point algorithm. Pattern Recognition, 2002. Proceedings. 16th International Conference on, 3, pp. 2724 - 2729. -readingDataPointsFilters: - - MinDistDataPointsFilter: - minDist: 1.0 - - RandomSamplingDataPointsFilter: - prob: 0.05 - -referenceDataPointsFilters: - - MinDistDataPointsFilter: - minDist: 1.0 - - RandomSamplingDataPointsFilter: - prob: 0.05 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 3.16 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPointErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 150 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - PerformanceInspector - -logger: -# FileLogger - NullLogger - diff --git a/thirdparty/libpointmatcher/evaluations/official_solutions/Chen91_pt2plane.yaml b/thirdparty/libpointmatcher/evaluations/official_solutions/Chen91_pt2plane.yaml deleted file mode 100644 index a862ca3..0000000 --- a/thirdparty/libpointmatcher/evaluations/official_solutions/Chen91_pt2plane.yaml +++ /dev/null @@ -1,47 +0,0 @@ -# Solution based on: -# Y Chen and G Medioni, 1991. Object modeling by registration of multiple range images. Robotics and -# Automation. Proc. of IEEE International Conf. on, 3, pp. 2724 - 2729. -# - and - -# Chetverikov, D and Svirko, D and Stepanov, D and Krsek, P, 2002. The Trimmed Iterative Closest -# Point algorithm. Pattern Recognition, 2002. Proceedings. 16th International Conference on, 3, pp. 2724 - 2729. -readingDataPointsFilters: - - MinDistDataPointsFilter: - minDist: 1.0 - - RandomSamplingDataPointsFilter: - prob: 0.05 - -referenceDataPointsFilters: - - MinDistDataPointsFilter: - minDist: 1.0 - - SamplingSurfaceNormalDataPointsFilter: - knn: 7 - samplingMethod: 1 - ratio: 0.1 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 3.16 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.7 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 150 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - PerformanceInspector - -logger: -# FileLogger - NullLogger - diff --git a/thirdparty/libpointmatcher/examples/CMakeLists.txt b/thirdparty/libpointmatcher/examples/CMakeLists.txt deleted file mode 100644 index b79b786..0000000 --- a/thirdparty/libpointmatcher/examples/CMakeLists.txt +++ /dev/null @@ -1,24 +0,0 @@ -add_executable(pmicp icp.cpp) -target_link_libraries(pmicp pointmatcher) -install(TARGETS pmicp RUNTIME DESTINATION bin) - -add_executable(icp_simple icp_simple.cpp) -target_link_libraries(icp_simple pointmatcher) - -add_executable(align_sequence align_sequence.cpp) -target_link_libraries(align_sequence pointmatcher) - -add_executable(list_modules list_modules.cpp) -target_link_libraries(list_modules pointmatcher) - -add_executable(build_map build_map.cpp) -target_link_libraries(build_map pointmatcher) - -add_executable(compute_overlap compute_overlap.cpp) -target_link_libraries(compute_overlap pointmatcher) - -add_executable(icp_advance_api icp_advance_api.cpp) -target_link_libraries(icp_advance_api pointmatcher) - -add_executable(icp_customized icp_customized.cpp) -target_link_libraries(icp_customized pointmatcher) diff --git a/thirdparty/libpointmatcher/examples/align_sequence.cpp b/thirdparty/libpointmatcher/examples/align_sequence.cpp deleted file mode 100644 index 9ea020f..0000000 --- a/thirdparty/libpointmatcher/examples/align_sequence.cpp +++ /dev/null @@ -1,171 +0,0 @@ -// kate: replace-tabs off; indent-width 4; indent-mode normal -// vim: ts=4:sw=4:noexpandtab -/* - -Copyright (c) 2010--2012, -François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland -You can contact the authors at and - - -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 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 ETH-ASL 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. - -*/ - -#include "pointmatcher/PointMatcher.h" -#include "pointmatcher/IO.h" -#include -#include -#include -#include -#include -#include - - -using namespace std; -using namespace PointMatcherSupport; - -void validateArgs(int argc, char *argv[]); - -/** - * Code example for ICP taking a sequence of point clouds relatively close - * and build a map with them. - * It assumes that: 3D point clouds are used, they were recorded in sequence - * and they are express in sensor frame. - */ -int main(int argc, char *argv[]) -{ - validateArgs(argc, argv); - - typedef PointMatcher PM; - typedef PointMatcherIO PMIO; - typedef PM::TransformationParameters TP; - typedef PM::DataPoints DP; - - string outputFileName(argv[0]); - - // Rigid transformation - std::shared_ptr rigidTrans; - rigidTrans = PM::get().REG(Transformation).create("RigidTransformation"); - - // Create filters manually to clean the global map - std::shared_ptr densityFilter = - PM::get().DataPointsFilterRegistrar.create( - "SurfaceNormalDataPointsFilter", - { - {"knn", "10"}, - {"epsilon", "5"}, - {"keepNormals", "0"}, - {"keepDensities", "1"} - } - ); - - std::shared_ptr maxDensitySubsample = - PM::get().DataPointsFilterRegistrar.create( - "MaxDensityDataPointsFilter", - {{"maxDensity", toParam(30)}} - ); - // Main algorithm definition - PM::ICP icp; - - // load YAML config - ifstream ifs(argv[1]); - validateFile(argv[1]); - icp.loadFromYaml(ifs); - - PMIO::FileInfoVector list(argv[2]); - - PM::DataPoints mapPointCloud, newCloud; - TP T_to_map_from_new = TP::Identity(4,4); // assumes 3D - - for(unsigned i=0; i < list.size(); i++) - { - cout << "---------------------\nLoading: " << list[i].readingFileName << endl; - - // It is assume that the point cloud is express in sensor frame - newCloud = DP::load(list[i].readingFileName); - - if(mapPointCloud.getNbPoints() == 0) - { - mapPointCloud = newCloud; - continue; - } - - // call ICP - try - { - // We use the last transformation as a prior - // this assumes that the point clouds were recorded in - // sequence. - const TP prior = T_to_map_from_new; - - T_to_map_from_new = icp(newCloud, mapPointCloud, prior); - } - catch (PM::ConvergenceError& error) - { - cout << "ERROR PM::ICP failed to converge: " << endl; - cout << " " << error.what() << endl; - continue; - } - - // This is not necessary in this example, but could be - // useful if the same matrix is composed in the loop. - T_to_map_from_new = rigidTrans->correctParameters(T_to_map_from_new); - - // Move the new point cloud in the map reference - newCloud = rigidTrans->compute(newCloud, T_to_map_from_new); - - // Merge point clouds to map - mapPointCloud.concatenate(newCloud); - - // Clean the map - mapPointCloud = densityFilter->filter(mapPointCloud); - mapPointCloud = maxDensitySubsample->filter(mapPointCloud); - - // Save the map at each iteration - stringstream outputFileNameIter; - outputFileNameIter << outputFileName << "_" << i << ".vtk"; - - cout << "outputFileName: " << outputFileNameIter.str() << endl; - mapPointCloud.save(outputFileNameIter.str()); - } - - return 0; -} - -void validateArgs(int argc, char *argv[]) -{ - if (!(argc == 3)) - { - cerr << "Error in command line, usage " << argv[0] << " icpConfiguration.yaml listOfFiles.csv" << endl; - cerr << endl << "Example:" << endl; - cerr << argv[0] << " ../examples/data/default.yaml ../examples/data/carCloudList.csv" << endl; - cerr << endl << " - or - " << endl << endl; - cerr << argv[0] << " ../examples/data/default.yaml ../examples/data/cloudList.csv" << endl << endl; - - abort(); - } -} - - diff --git a/thirdparty/libpointmatcher/examples/build_map.cpp b/thirdparty/libpointmatcher/examples/build_map.cpp deleted file mode 100644 index 939ce44..0000000 --- a/thirdparty/libpointmatcher/examples/build_map.cpp +++ /dev/null @@ -1,261 +0,0 @@ -// kate: replace-tabs off; indent-width 4; indent-mode normal -// vim: ts=4:sw=4:noexpandtab -/* - -Copyright (c) 2010--2012, -François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland -You can contact the authors at and - - -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 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 ETH-ASL 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. - -*/ - -#include "pointmatcher/PointMatcher.h" -#include "pointmatcher/IO.h" -#include -#include -#include -#include -#include -#include -#include - -using namespace std; -using namespace PointMatcherSupport; - -void validateArgs(int argc, char *argv[]); -void setupArgs(int argc, char *argv[], unsigned int& startId, unsigned int& endId, string& extension); -vector loadYamlFile(string listFileName); - -/** - * Code example for DataFilter taking a sequence of point clouds with - * their global coordinates and build a map with a fix (manageable) number of points. - * The example shows how to generate filters in the source code. - * For an example generating filters using yaml configuration, see demo_cmake/convert.cpp - * For an example with a registration solution, see icp.cpp - */ -int main(int argc, char *argv[]) -{ - validateArgs(argc, argv); - - typedef PointMatcher PM; - typedef PointMatcherIO PMIO; - typedef PM::TransformationParameters TP; - typedef PM::DataPoints DP; - - // Process arguments - PMIO::FileInfoVector list(argv[1]); - const unsigned totalPointCount = boost::lexical_cast(argv[2]); - string outputFileName(argv[3]); - - - setLogger(PM::get().LoggerRegistrar.create("FileLogger")); - - PM::DataPoints mapCloud; - - PM::DataPoints lastCloud, newCloud; - TP T = TP::Identity(4,4); - - // Define transformation chain - std::shared_ptr transformation; - transformation = PM::get().REG(Transformation).create("RigidTransformation"); - - // This filter will remove a sphere of 1 m radius. Easy way to remove the sensor self-scanning. - std::shared_ptr removeScanner = - PM::get().DataPointsFilterRegistrar.create( - "MinDistDataPointsFilter", - {{"minDist", "1.0"}} - ); - - // This filter will randomly remove 35% of the points. - std::shared_ptr randSubsample = - PM::get().DataPointsFilterRegistrar.create( - "RandomSamplingDataPointsFilter", - {{"prob", toParam(0.65)}} - ); - - // For a complete description of filter, see - // https://github.com/ethz-asl/libpointmatcher/blob/master/doc/Datafilters.md - std::shared_ptr normalFilter = - PM::get().DataPointsFilterRegistrar.create( - "SurfaceNormalDataPointsFilter", - { - {"knn", toParam(10)}, - {"epsilon", toParam(5)}, - {"keepNormals",toParam(1)}, - {"keepDensities",toParam(0)} - } - ); - - std::shared_ptr densityFilter = - PM::get().DataPointsFilterRegistrar.create( - "SurfaceNormalDataPointsFilter", - { - {"knn", "10"}, - {"epsilon", "5"}, - {"keepDensities","1"}, - {"keepNormals","0"} - } - ); - - std::shared_ptr observationDirectionFilter = - PM::get().DataPointsFilterRegistrar.create( - "ObservationDirectionDataPointsFilter" - ); - - std::shared_ptr orientNormalFilter = - PM::get().DataPointsFilterRegistrar.create( - "OrientNormalsDataPointsFilter", - {{"towardCenter", "1"}} - ); - - std::shared_ptr uniformSubsample = - PM::get().DataPointsFilterRegistrar.create( - "MaxDensityDataPointsFilter", - {{"maxDensity", toParam(30)}} - ); - - std::shared_ptr shadowFilter = - PM::get().DataPointsFilterRegistrar.create( - "ShadowDataPointsFilter" - ); - - for(unsigned i=0; i < list.size(); i++) - { - cout << endl << "-----------------------------" << endl; - cout << "Loading " << list[i].readingFileName; - newCloud = DP::load(list[i].readingFileName); - - cout << " found " << newCloud.getNbPoints() << " points. " << endl; - - - if(list[i].groundTruthTransformation.rows() != 0) - T = list[i].groundTruthTransformation; - else - { - cout << "ERROR: the field gTXX (ground truth) is required" << endl; - abort(); - } - - PM::Parameters params; - - // Remove the scanner - newCloud = removeScanner->filter(newCloud); - - - // Accelerate the process and dissolve lines - newCloud = randSubsample->filter(newCloud); - - // Build filter to remove shadow points and down-sample - newCloud = normalFilter->filter(newCloud); - newCloud = observationDirectionFilter->filter(newCloud); - newCloud = orientNormalFilter->filter(newCloud); - newCloud = shadowFilter->filter(newCloud); - - // Transforme pointCloud - cout << "Transformation matrix: " << endl << T << endl; - newCloud = transformation->compute(newCloud, T); - - if(i==0) - { - mapCloud = newCloud; - } - else - { - mapCloud.concatenate(newCloud); - - // Control point cloud size - double probToKeep = totalPointCount/(double)mapCloud.features.cols(); - if(probToKeep < 1) - { - - mapCloud = densityFilter->filter(mapCloud); - mapCloud = uniformSubsample->filter(mapCloud); - - probToKeep = totalPointCount/(double)mapCloud.features.cols(); - - if(probToKeep < 1) - { - cout << "Randomly keep " << probToKeep*100 << "\% points" << endl; - randSubsample = PM::get().DataPointsFilterRegistrar.create( - "RandomSamplingDataPointsFilter", - {{"prob", toParam(probToKeep)}} - ); - mapCloud = randSubsample->filter(mapCloud); - } - } - } - - stringstream outputFileNameIter; - outputFileNameIter << boost::filesystem::path(outputFileName).stem().c_str() << "_" << i << ".vtk"; - - mapCloud.save(outputFileNameIter.str()); - } - - mapCloud = densityFilter->filter(mapCloud); - mapCloud = uniformSubsample->filter(mapCloud); - - mapCloud = densityFilter->filter(mapCloud); - - cout << endl ; - cout << "-----------------------------" << endl; - cout << "-----------------------------" << endl; - cout << "Final number of points in the map: " << mapCloud.getNbPoints() << endl; - mapCloud.save(outputFileName); - cout << endl ; - - return 0; -} - -void validateArgs(int argc, char *argv[]) -{ - if (!(argc == 4)) - { - cerr << endl; - cerr << "Error in command line, usage " << argv[0] << " listOfFiles.csv maxPoint outputFileName.{vtk,csv,ply}" << endl; - cerr << endl; - cerr << " example using file from example/data: " << endl; - cerr << " " << argv[0] << " carCloudList.csv 30000 test.vtk" << endl; - cerr << endl; - cerr << "Note: the file listOfFiles.csv need to include a serialize transformation matrix. For example:" << endl; - cerr << " fileName1.vtk, T00, T01, T02, T03, T10, T11, T12, T13, T20, T21, T22, T23, T30, T31, T32" << endl; - cerr << endl; - cerr << "Where Txy would be a 4x4 transformation matrix:" << endl; - cerr << " [T00 T01 T02 T03] " << endl; - cerr << " [T10 T11 T12 T13] " << endl; - cerr << " [T20 T21 T22 T23] " << endl; - cerr << " [T30 T31 T32 T33] (i.e., 0,0,0,1)" << endl; - cerr << endl; - cerr << "For more data visit:" << endl; - cerr << " http://projects.asl.ethz.ch/datasets/doku.php?id=laserregistration:laserregistration" << endl; - cerr << endl; - - abort(); - } -} - - - diff --git a/thirdparty/libpointmatcher/examples/compute_overlap.cpp b/thirdparty/libpointmatcher/examples/compute_overlap.cpp deleted file mode 100644 index a7fe923..0000000 --- a/thirdparty/libpointmatcher/examples/compute_overlap.cpp +++ /dev/null @@ -1,287 +0,0 @@ -// kate: replace-tabs off; indent-width 4; indent-mode normal -// vim: ts=4:sw=4:noexpandtab -/* - -Copyright (c) 2010--2012, -François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland -You can contact the authors at and - - -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 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 ETH-ASL 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. - -*/ - -#include "pointmatcher/PointMatcher.h" -#include "pointmatcher/IO.h" -#include -#include -#include -#include -#include -#include -#include -#include - -using namespace std; -using namespace PointMatcherSupport; - -void validateArgs(int argc, char *argv[]); -void setupArgs(int argc, char *argv[], unsigned int& startId, unsigned int& endId, string& extension); - -/** - * Code example for DataFilter taking a sequence of point clouds with - * their global coordinates and build a map with a fix (manageable) number of points - */ -int main(int argc, char *argv[]) -{ - validateArgs(argc, argv); - - typedef PointMatcher PM; - typedef PointMatcherIO PMIO; - typedef PM::Matrix Matrix; - typedef PM::TransformationParameters TP; - typedef PM::DataPoints DP; - typedef PM::Matches Matches; - - // Process arguments - PMIO::FileInfoVector list(argv[1]); - bool debugMode = false; - if (argc == 4) - debugMode = true; - - if(debugMode) - setLogger(PM::get().LoggerRegistrar.create("FileLogger")); - - // Prepare transformation chain for maps - std::shared_ptr rigidTransform; - rigidTransform = PM::get().TransformationRegistrar.create("RigidTransformation"); - - PM::Transformations transformations; - transformations.push_back(rigidTransform); - - DP reading, reference; - TP Tread = TP::Identity(4,4); - DP mapCloud; - TP Tref = TP::Identity(4,4); - - unsigned startingI = 0; - unsigned listSizeI = list.size(); - unsigned listSizeJ = list.size(); - if(debugMode) - { - startingI = boost::lexical_cast(argv[2]); - listSizeI = startingI + 1; - } - - PM::Matrix overlapResults = PM::Matrix::Ones(listSizeJ, listSizeI); - - for(unsigned i = startingI; i < listSizeI; i++) - { - unsigned startingJ = i+1; - if(debugMode) - { - startingJ = boost::lexical_cast(argv[3]); - listSizeJ = startingJ + 1; - } - for(unsigned j = startingJ; j < listSizeJ; j++) - { - // Load point clouds - reading = DP::load(list[i].readingFileName); - reference = DP::load(list[j].readingFileName); - - cout << "Point cloud loaded" << endl; - - // Load transformation matrices - if(list[i].groundTruthTransformation.rows() != 0) - { - Tread = list[i].groundTruthTransformation; - Tref = list[j].groundTruthTransformation; - } - else - { - cout << "ERROR: fields gTXX (i.e., ground truth matrix) is required" << endl; - abort(); - } - - // Move point cloud in global frame - transformations.apply(reading, Tread); - transformations.apply(reference, Tref); - - // Preprare filters - std::shared_ptr subSample = - PM::get().DataPointsFilterRegistrar.create( - "RandomSamplingDataPointsFilter", - {{"prob", "0.5"}} - ); - - std::shared_ptr maxDensity = - PM::get().DataPointsFilterRegistrar.create( - "MaxDensityDataPointsFilter" - ); - - /*std::shared_ptr cutInHalf; - cutInHalf = PM::get().DataPointsFilterRegistrar.create( - "MinDistDataPointsFilter", PM::Parameters({ - {"dim", "1"}, - {"minDist", "0"} - }));*/ - - std::shared_ptr computeDensity = - PM::get().DataPointsFilterRegistrar.create( - "SurfaceNormalDataPointsFilter", - { - {"knn", "20"}, - {"keepDensities", "1"} - } - ); - - reading = subSample->filter(reading); - reading = computeDensity->filter(reading); - reading = maxDensity->filter(reading); - //reading = cutInHalf->filter(reading); - const Matrix inliersRead = Matrix::Zero(1, reading.features.cols()); - reading.addDescriptor("inliers", inliersRead); - - reference = subSample->filter(reference); - reference = computeDensity->filter(reference); - reference = maxDensity->filter(reference); - const Matrix inliersRef = Matrix::Zero(1, reference.features.cols()); - reference.addDescriptor("inliers", inliersRef); - - //TODO: reverse self and target - DP self = reading; - DP target = reference; - - for(int l = 0; l < 2; l++) - { - const int selfPtsCount = self.features.cols(); - const int targetPtsCount = target.features.cols(); - - // Build kd-tree - int knn = 20; - int knnAll = 50; - std::shared_ptr matcherSelf = - PM::get().MatcherRegistrar.create( - "KDTreeMatcher", - {{"knn", toParam(knn)}} - ); - - std::shared_ptr matcherTarget = - PM::get().MatcherRegistrar.create( - "KDTreeVarDistMatcher", - { - {"knn", toParam(knnAll)}, - {"maxDistField", "maxSearchDist"} - } - ); - - matcherSelf->init(self); - matcherTarget->init(target); - - Matches selfMatches(knn, selfPtsCount); - selfMatches = matcherSelf->findClosests(self); - - const Matrix maxSearchDist = selfMatches.dists.colwise().maxCoeff().cwiseSqrt(); - self.addDescriptor("maxSearchDist", maxSearchDist); - - Matches targetMatches(knnAll, targetPtsCount); - targetMatches = matcherTarget->findClosests(self); - - BOOST_AUTO(inlierSelf, self.getDescriptorViewByName("inliers")); - BOOST_AUTO(inlierTarget, target.getDescriptorViewByName("inliers")); - for(int i = 0; i < selfPtsCount; i++) - { - for(int k = 0; k < knnAll; k++) - { - if (targetMatches.dists(k, i) != Matches::InvalidDist) - { - inlierSelf(0,i) = 1.0; - inlierTarget(0,targetMatches.ids(k, i)) = 1.0; - } - } - } - - // Swap point clouds - PM::swapDataPoints(self, target); - } - - const BOOST_AUTO(finalInlierSelf, self.getDescriptorViewByName("inliers")); - const BOOST_AUTO(finalInlierTarget, target.getDescriptorViewByName("inliers")); - const double selfRatio = (finalInlierSelf.array() > 0).count()/(double)finalInlierSelf.cols(); - const double targetRatio = (finalInlierTarget.array() > 0).count()/(double)finalInlierTarget.cols(); - - cout << i << " -> " << j << ": " << selfRatio << endl; - cout << j << " -> " << i << ": " << targetRatio << endl; - - if(debugMode) - { - self.save("scan_i.vtk"); - target.save("scan_j.vtk"); - } - else - { - overlapResults(j,i) = selfRatio; - overlapResults(i,j) = targetRatio; - } - } - } - - - // write results in a file - std::fstream outFile; - outFile.open("overlapResults.csv", fstream::out); - for(int x=0; x < overlapResults.rows(); x++) - { - for(int y=0; y < overlapResults.cols(); y++) - { - outFile << overlapResults(x, y) << ", "; - } - - outFile << endl; - } - - outFile.close(); - - return 0; -} - -void validateArgs(int argc, char *argv[]) -{ - if (!(argc == 2 || argc == 4)) - { - cerr << endl; - cerr << " ERROR in command line" << endl << endl; - cerr << " Usage: " << argv[0] << " listOfFiles.csv " << endl; - cerr << " Note: 'i' and 'j' are optional arguments. If used, only compute the overlap for those 2 point cloud ids and dump VTK files for visual inspection." << endl; - cerr << endl; - cerr << " Example: " << endl; - cerr << " $ " << argv[0] << " ../example/data/carCloudList.csv" << endl; - cerr << endl; - abort(); - } -} - - - diff --git a/thirdparty/libpointmatcher/examples/data/2D_oneBox.csv b/thirdparty/libpointmatcher/examples/data/2D_oneBox.csv deleted file mode 100644 index 79b8bb7..0000000 --- a/thirdparty/libpointmatcher/examples/data/2D_oneBox.csv +++ /dev/null @@ -1,361 +0,0 @@ -0.533677 , 1.01599 -0.542156 , 1.01961 -0.550897 , 1.02412 -0.558934 , 1.02467 -0.566163 , 1.02128 -0.573775 , 1.01976 -0.581372 , 1.01818 -0.588489 , 1.01461 -0.597726 , 1.01961 -0.607562 , 1.02643 -0.615728 , 1.02647 -0.624442 , 1.02833 -0.632655 , 1.02822 -0.640034 , 1.02518 -0.647085 , 1.02113 -0.654682 , 1.01891 -0.662874 , 1.01851 -0.669813 , 1.01428 -0.67702 , 1.01093 -0.683856 , 1.00659 -0.692 , 1.00592 -0.701199 , 1.00795 -0.70867 , 1.00526 -0.716116 , 1.00252 -0.723164 , 0.998783 -0.733981 , 1.00415 -0.740634 , 0.999355 -0.749214 , 0.999057 -0.754978 , 0.992333 -0.765607 , 0.996403 -0.773807 , 0.994959 -0.779435 , 0.988065 -0.791084 , 0.993621 -0.801525 , 0.996376 -0.808876 , 0.992825 -0.816195 , 0.98921 -0.823949 , 0.986408 -0.830734 , 0.981789 -0.841815 , 0.984933 -0.849059 , 0.981033 -0.860749 , 0.984814 -0.867483 , 0.979894 -0.875191 , 0.976624 -0.886519 , 0.979216 -0.893705 , 0.974929 -0.900316 , 0.969741 -0.9085 , 0.967003 -0.919973 , 0.969162 -0.932077 , 0.97201 -0.939756 , 0.968151 -0.94512 , 0.960957 -0.958498 , 0.965079 -0.964375 , 0.958559 -0.971365 , 0.953599 -0.983705 , 0.955739 -0.995518 , 0.956935 -1.00249 , 0.951706 -1.01499 , 0.953437 -1.02318 , 0.949589 -1.03515 , 0.950276 -1.0427 , 0.945469 -1.05409 , 0.945143 -1.06225 , 0.940914 -1.07501 , 0.941835 -1.08583 , 0.940371 -1.09331 , 0.935097 -1.10483 , 0.934136 -1.11363 , 0.930135 -1.12658 , 0.930355 -1.13748 , 0.92827 -1.15051 , 0.928177 -1.15791 , 0.922308 -1.16885 , 0.919845 -1.18196 , 0.919316 -1.19585 , 0.919302 -1.20613 , 0.915722 -1.21418 , 0.910013 -1.22816 , 0.909531 -1.23843 , 0.905578 -1.25324 , 0.90541 -1.26581 , 0.903109 -1.27995 , 0.901923 -1.29025 , 0.897392 -1.30522 , 0.896488 -1.31789 , 0.893526 -1.33136 , 0.891013 -1.34007 , 0.884694 -1.35195 , 0.88067 -1.36705 , 0.87886 -1.37895 , 0.874506 -1.39328 , 0.871734 -1.4101 , 0.870477 -1.42863 , 0.870112 -1.43974 , 0.864473 -1.45334 , 0.860344 -1.47198 , 0.859284 -1.48476 , 0.854211 -1.49754 , 0.84897 -1.51628 , 0.847202 -1.53678 , 0.846187 -1.54872 , 0.839816 -1.56843 , 0.837771 -1.58819 , 0.835438 -1.60712 , 0.832331 -1.62344 , 0.827521 -1.63711 , 0.821075 -1.65786 , 0.818126 -1.67687 , 0.813962 -1.69678 , 0.809965 -1.71672 , 0.805673 -1.7439 , 0.804524 -1.76571 , 0.800422 -1.78664 , 0.795576 -1.81489 , 0.793669 -1.82761 , 0.784544 -1.61019 , 0.677532 -1.47696 , 0.609913 -1.46318 , 0.59337 -1.45011 , 0.577465 -1.44059 , 0.56325 -1.42154 , 0.545717 -1.41824 , 0.534371 -1.40163 , 0.51842 -1.3867 , 0.503435 -1.37729 , 0.490643 -1.37247 , 0.479591 -1.35992 , 0.466224 -1.34817 , 0.45339 -1.3334 , 0.439922 -1.32711 , 0.429228 -1.3207 , 0.418661 -1.30261 , 0.405089 -1.29789 , 0.395386 -1.29404 , 0.386025 -1.2765 , 0.373441 -1.27147 , 0.364135 -1.26731 , 0.35515 -1.27283 , 0.348363 -1.27633 , 0.341088 -1.26215 , 0.330267 -1.28218 , 0.32621 -1.29237 , 0.320044 -1.30253 , 0.313712 -1.31165 , 0.307057 -1.3217 , 0.300405 -1.32974 , 0.293303 -1.33969 , 0.286343 -1.34761 , 0.278964 -1.35844 , 0.271812 -1.35633 , 0.263057 -1.37696 , 0.256666 -1.38463 , 0.248725 -1.3982 , 0.241159 -1.39481 , 0.232085 -1.39929 , 0.223608 -1.41763 , 0.21587 -1.41998 , 0.207026 -1.54772 , 0.203298 -2.29199 , 0.217374 -2.2932 , 0.200911 -2.2863 , 0.184306 -2.28523 , 0.167858 -2.27605 , 0.151443 -2.27569 , 0.135087 -2.27519 , 0.118732 -2.26658 , 0.102603 -2.26578 , 0.086324 -2.26386 , 0.0700958 -2.26377 , 0.053783 -2.25461 , 0.0380214 -2.25226 , 0.0219105 -2.24976 , 0.00582605 -2.24911 , -0.0104044 -2.24832 , -0.02664 -2.2365 , -0.0417238 -2.23444 , -0.0577572 -2.23224 , -0.073775 -2.2299 , -0.0897744 -2.22742 , -0.105755 -2.2248 , -0.121716 -2.22301 , -0.137812 -2.22011 , -0.153738 -2.20826 , -0.168084 -2.20509 , -0.183886 -2.20276 , -0.199851 -2.19931 , -0.215609 -2.20252 , -0.232786 -2.19974 , -0.248759 -2.1862 , -0.262259 -2.19088 , -0.279967 -2.18576 , -0.295389 -2.18147 , -0.31101 -2.18567 , -0.328906 -2.17248 , -0.342141 -2.16778 , -0.357651 -2.1715 , -0.375657 -2.1665 , -0.391161 -2.16987 , -0.409308 -2.1627 , -0.424189 -2.15915 , -0.440251 -2.15265 , -0.455332 -2.14789 , -0.471013 -2.14206 , -0.486322 -2.14443 , -0.504705 -2.1383 , -0.519989 -2.13112 , -0.534858 -2.12564 , -0.5504 -2.12642 , -0.568556 -2.11973 , -0.58369 -2.12015 , -0.601924 -2.11227 , -0.616605 -2.11235 , -0.634904 -2.10597 , -0.650341 -2.10658 , -0.66914 -2.09812 , -0.683678 -2.09837 , -0.702551 -2.08962 , -0.717007 -2.08863 , -0.73549 -2.08222 , -0.751244 -2.07999 , -0.769315 -2.08016 , -0.788862 -2.06982 , -0.802644 -2.07132 , -0.823243 -2.06748 , -0.840935 -2.0584 , -0.855588 -2.05675 , -0.874809 -2.05572 , -0.894608 -2.04699 , -0.909695 -2.04391 , -0.928482 -2.04145 , -0.947846 -2.03877 , -0.967255 -2.03587 , -0.986707 -2.0255 , -1.0011 -2.02943 , -1.02573 -2.01553 , -1.03775 -1.8182 , -0.91332 -1.77634 , -0.901457 -1.74182 , -0.894364 -1.69748 , -0.878851 -1.66814 , -0.87433 -1.62906 , -0.861303 -1.60624 , -0.860869 -1.57149 , -0.849963 -1.54973 , -0.849435 -1.51845 , -0.840189 -1.48303 , -0.826553 -1.4647 , -0.827573 -1.43777 , -0.820349 -1.41106 , -0.812733 -1.39026 , -0.810167 -1.37029 , -0.808002 -1.34276 , -0.797956 -1.32311 , -0.795184 -1.2981 , -0.786513 -1.27808 , -0.782452 -1.25484 , -0.774538 -1.24048 , -0.775675 -1.22221 , -0.772271 -1.20407 , -0.768623 -1.1893 , -0.768427 -1.16948 , -0.76209 -1.15048 , -0.75623 -1.13164 , -0.750113 -1.11856 , -0.75059 -1.10062 , -0.744777 -1.08163 , -0.737179 -1.06944 , -0.737872 -1.05551 , -0.736076 -1.04167 , -0.734106 -1.02213 , -0.724037 -1.01369 , -0.728859 -1.00239 , -0.729589 -0.984998 , -0.721304 -0.971108 , -0.717662 -0.958416 , -0.715483 -0.947954 , -0.71644 -0.933825 , -0.711494 -0.921393 , -0.708864 -0.910593 , -0.708596 -0.897314 , -0.704003 -0.884658 , -0.700091 -0.873586 , -0.698575 -0.863065 , -0.697787 -0.851173 , -0.694308 -0.837979 , -0.688102 -0.830914 , -0.692996 -0.819279 , -0.689127 -0.804636 , -0.679 -0.793704 , -0.675712 -0.786297 , -0.679356 -0.775491 , -0.675849 -0.765193 , -0.673107 -0.757004 , -0.674718 -0.746036 , -0.669972 -0.735185 , -0.665099 -0.725213 , -0.661909 -0.7157 , -0.659517 -0.708449 , -0.662487 -0.69796 , -0.657169 -0.687593 , -0.651731 -0.678371 , -0.648936 -0.668892 , -0.64512 -0.659831 , -0.642128 -0.654324 , -0.64926 -0.642248 , -0.636787 -0.633114 , -0.632579 -0.625823 , -0.633897 -0.619097 , -0.637028 -0.609315 , -0.629737 -0.603144 , -0.634621 -0.592265 , -0.622408 -0.584615 , -0.62146 -0.57724 , -0.621391 -0.568489 , -0.615531 -0.561877 , -0.618181 -0.555017 , -0.619821 -0.546487 , -0.613719 -0.540067 , -0.617148 -0.53322 , -0.618599 -0.524909 , -0.612265 -0.518454 , -0.615519 -0.510146 , -0.608064 -0.503852 , -0.612166 -0.495878 , -0.605529 -0.488725 , -0.603678 -0.480966 , -0.596888 -0.475401 , -0.606607 -0.467869 , -0.600662 -0.46118 , -0.601488 -0.45439 , -0.601276 -0.446656 , -0.59023 -0.440298 , -0.593813 -0.433813 , -0.596363 -0.427108 , -0.595912 -0.419999 , -0.587542 -0.413565 , -0.590903 -0.406936 , -0.590275 -0.40035 , -0.590575 -0.393623 , -0.582941 -0.387129 , -0.586079 -0.380584 , -0.582267 -0.374115 , -0.577413 -0.367561 , -0.582353 -0.361077 , -0.581326 -0.354821 , -0.574336 -0.348211 , -0.578121 -0.341742 , -0.577913 -0.335154 , -0.579615 -0.329021 , -0.574377 -0.321884 , -0.582849 -0.315378 , -0.582413 -0.309546 , -0.575049 -0.30311 , -0.574507 -0.296906 , -0.571948 -0.290015 , -0.575213 -0.284231 , -0.56961 -0.277849 , -0.568848 -0.271473 , -0.568031 -0.264951 , -0.568134 -0.258255 , -0.569153 -0.252746 , -0.563305 diff --git a/thirdparty/libpointmatcher/examples/data/2D_twoBoxes.csv b/thirdparty/libpointmatcher/examples/data/2D_twoBoxes.csv deleted file mode 100644 index 41506ad..0000000 --- a/thirdparty/libpointmatcher/examples/data/2D_twoBoxes.csv +++ /dev/null @@ -1,361 +0,0 @@ - 2.8600000e-01 8.8600000e-01 - 2.9377500e-01 8.9096600e-01 - 3.0169000e-01 8.9886300e-01 - 3.0953300e-01 8.9869200e-01 - 3.1737500e-01 8.9845200e-01 - 3.2521400e-01 8.9814400e-01 - 3.3252700e-01 8.8778200e-01 - 3.4082200e-01 8.9632500e-01 - 3.4919900e-01 9.0379300e-01 - 3.5755500e-01 9.0918900e-01 - 3.6566000e-01 9.1052200e-01 - 3.7341100e-01 9.0780100e-01 - 3.8133000e-01 9.0700400e-01 - 3.8912800e-01 9.0514400e-01 - 3.9702300e-01 9.0421000e-01 - 4.0556200e-01 9.0816400e-01 - 4.1264800e-01 9.0114400e-01 - 4.2168900e-01 9.0791700e-01 - 4.2945000e-01 9.0571000e-01 - 4.3685400e-01 9.0146500e-01 - 4.4506200e-01 9.0208400e-01 - 4.5238100e-01 8.9771200e-01 - 4.6001800e-01 8.9524400e-01 - 4.6961800e-01 9.0251100e-01 - 4.7727900e-01 8.9989600e-01 - 4.8534100e-01 8.9916900e-01 - 4.9228000e-01 8.9349700e-01 - 5.0263700e-01 9.0235900e-01 - 5.1002000e-01 8.9849400e-01 - 5.1760200e-01 8.9553700e-01 - 5.2773700e-01 9.0217500e-01 - 5.3533300e-01 8.9906700e-01 - 5.4289400e-01 8.9589600e-01 - 5.5325800e-01 9.0224900e-01 - 5.6112200e-01 8.9988300e-01 - 5.6836300e-01 8.9554000e-01 - 5.7925700e-01 9.0255300e-01 - 5.8680500e-01 8.9901100e-01 - 5.9463900e-01 8.9635200e-01 - 6.0244900e-01 8.9362400e-01 - 6.1297100e-01 8.9834600e-01 - 6.2079800e-01 8.9545900e-01 - 6.2860000e-01 8.9250300e-01 - 6.3967400e-01 8.9785300e-01 - 6.5049200e-01 9.0215000e-01 - 6.5835100e-01 8.9893500e-01 - 6.6657200e-01 8.9657200e-01 - 6.7438200e-01 8.9321700e-01 - 6.8582200e-01 8.9801500e-01 - 6.9364400e-01 8.9449200e-01 - 7.0481500e-01 8.9815100e-01 - 7.1306700e-01 8.9536500e-01 - 7.1998700e-01 8.8980600e-01 - 7.3175200e-01 8.9404000e-01 - 7.3953700e-01 8.9011600e-01 - 7.5098100e-01 8.9322000e-01 - 7.6298300e-01 8.9707500e-01 - 7.7079300e-01 8.9287800e-01 - 7.7953600e-01 8.9036300e-01 - 7.9024200e-01 8.9124400e-01 - 8.0400000e-01 8.9720200e-01 - 8.1079500e-01 8.9092500e-01 - 8.2318500e-01 8.9402600e-01 - 8.3148900e-01 8.9015600e-01 - 8.4347500e-01 8.9214700e-01 - 8.5661200e-01 8.9568200e-01 - 8.6713000e-01 8.9486200e-01 - 8.7602100e-01 8.9142400e-01 - 8.8936900e-01 8.9453200e-01 - 8.9998400e-01 8.9335300e-01 - 9.0775700e-01 8.8796100e-01 - 9.2245000e-01 8.9227100e-01 - 9.3315200e-01 8.9072800e-01 - 9.4565900e-01 8.9147700e-01 - 9.5401500e-01 8.8648500e-01 - 9.6537800e-01 8.8538200e-01 - 9.7985100e-01 8.8808800e-01 - 9.9379900e-01 8.8982600e-01 - 1.0053130e+00 8.8827800e-01 - 1.0193980e+00 8.8968300e-01 - 1.0329190e+00 8.9014400e-01 - 1.0400090e+00 8.8283100e-01 - 1.0575250e+00 8.8753800e-01 - 1.0672290e+00 8.8301900e-01 - 1.0856110e+00 8.8805800e-01 - 1.0940060e+00 8.8178400e-01 - 1.1037160e+00 8.7689300e-01 - 1.1230390e+00 8.8205500e-01 - 1.1376510e+00 8.8191100e-01 - 1.1509220e+00 8.8015100e-01 - 1.1642270e+00 8.7822700e-01 - 1.1811290e+00 8.7964100e-01 - 1.1930880e+00 8.7596400e-01 - 1.2065000e+00 8.7352200e-01 - 1.2199390e+00 8.7091200e-01 - 1.2385620e+00 8.7286300e-01 - 1.2580340e+00 8.7522300e-01 - 1.2708770e+00 8.7134500e-01 - 1.2912730e+00 8.7387100e-01 - 1.3049440e+00 8.7026000e-01 - 1.3247560e+00 8.7162000e-01 - 1.3377240e+00 8.6697500e-01 - 1.3576840e+00 8.6783300e-01 - 1.3769560e+00 8.6778500e-01 - 1.3947310e+00 8.6623600e-01 - 1.2872120e+00 7.6825700e-01 - 1.2667240e+00 7.3902900e-01 - 1.2546480e+00 7.1676100e-01 - 1.2406400e+00 6.9358700e-01 - 1.2214190e+00 6.6722800e-01 - 1.2059080e+00 6.4412600e-01 - 1.1917150e+00 6.2248100e-01 - 1.1763860e+00 6.0057300e-01 - 1.1615800e+00 5.7953400e-01 - 1.1540240e+00 5.6370100e-01 - 1.1454160e+00 5.4750800e-01 - 1.1357440e+00 5.3097900e-01 - 1.1215870e+00 5.1204900e-01 - 1.1285950e+00 5.0628200e-01 - 1.1191950e+00 4.9079000e-01 - 1.1338390e+00 4.8950000e-01 - 1.1311150e+00 4.7814300e-01 - 1.1413780e+00 4.7414400e-01 - 1.1525140e+00 4.7047900e-01 - 1.1574690e+00 4.6336800e-01 - 1.1597060e+00 4.5482200e-01 - 1.1716610e+00 4.5126700e-01 - 1.1818290e+00 4.4664400e-01 - 1.1937820e+00 4.4275500e-01 - 1.1976110e+00 4.3481600e-01 - 1.2013710e+00 4.2684400e-01 - 1.2114310e+00 4.2174300e-01 - 1.2223840e+00 4.1690500e-01 - 1.2351570e+00 4.1270500e-01 - 1.2460870e+00 4.0753300e-01 - 1.2486820e+00 3.9875600e-01 - 1.2595430e+00 3.9333700e-01 - 1.2694510e+00 3.8739200e-01 - 1.2811970e+00 3.8202000e-01 - 1.2919860e+00 3.7612300e-01 - 1.3008680e+00 3.6938200e-01 - 1.3210200e+00 3.6652000e-01 - 1.3241790e+00 3.5747400e-01 - 1.3509680e+00 3.5633300e-01 - 2.1367560e+00 6.0134700e-01 - 2.1791280e+00 5.9690100e-01 - 2.1842650e+00 5.8035800e-01 - 2.1806280e+00 5.6121400e-01 - 2.1768020e+00 5.4217900e-01 - 2.1814610e+00 5.2565800e-01 - 2.1772830e+00 5.0676800e-01 - 2.1816330e+00 4.9024400e-01 - 2.1771070e+00 4.7150600e-01 - 2.1723980e+00 4.5288400e-01 - 2.1772520e+00 4.3663000e-01 - 2.1712280e+00 4.1794500e-01 - 2.1757810e+00 4.0168500e-01 - 2.1703950e+00 3.8338500e-01 - 2.1746510e+00 3.6711700e-01 - 2.1777830e+00 3.5062100e-01 - 2.1728920e+00 3.3271000e-01 - 2.1737510e+00 3.1590100e-01 - 2.1685340e+00 2.9816400e-01 - 2.1710640e+00 2.8172500e-01 - 2.1734510e+00 2.6526400e-01 - 2.1667710e+00 2.4760800e-01 - 2.1688600e+00 2.3118600e-01 - 2.1717990e+00 2.1486000e-01 - 2.1656470e+00 1.9755900e-01 - 2.1682940e+00 1.8124400e-01 - 2.1598420e+00 1.6394000e-01 - 2.1621990e+00 1.4766000e-01 - 2.1614210e+00 1.3114200e-01 - 2.1634920e+00 1.1483200e-01 - 2.1554350e+00 9.7973000e-02 - 2.1652100e+00 8.2048000e-02 - 2.1568600e+00 6.5332000e-02 - 2.1563590e+00 4.8977000e-02 - 2.1667130e+00 3.2828000e-02 - 2.1579290e+00 1.6336000e-02 - 2.1680000e+00 0.0000000e+00 - 2.1579290e+00 -1.6336000e-02 - 2.1587150e+00 -3.2688000e-02 - 2.1583580e+00 -4.9029000e-02 - 2.1588590e+00 -6.5402000e-02 - 2.1572180e+00 -8.1699000e-02 - 2.1554350e+00 -9.7973000e-02 - 2.1565050e+00 -1.1440500e-01 - 2.1624180e+00 -1.3121200e-01 - 2.1512320e+00 -1.4679700e-01 - 2.1598420e+00 -1.6394000e-01 - 2.1583400e+00 -1.8028600e-01 - 2.1557010e+00 -1.9651400e-01 - 2.1529220e+00 -2.1270900e-01 - 2.1509940e+00 -2.2899300e-01 - 2.1489250e+00 -2.4525900e-01 - 2.1556260e+00 -2.6275900e-01 - 2.1542510e+00 -2.7921200e-01 - 2.1497680e+00 -2.9519200e-01 - 2.1490940e+00 -3.1177500e-01 - 2.1453170e+00 -3.2784800e-01 - 2.1423850e+00 -3.4406100e-01 - 2.1461840e+00 -3.6158300e-01 - 2.1439370e+00 -3.7800200e-01 - 2.1483930e+00 -3.9586400e-01 - 2.1458440e+00 -4.1231700e-01 - 2.1421750e+00 -4.2853200e-01 - 2.1461440e+00 -4.4658100e-01 - 2.1421760e+00 -4.6279700e-01 - 1.8756990e+00 -4.1112400e-01 - 1.6923880e+00 -3.7684100e-01 - 1.6659190e+00 -3.8268500e-01 - 1.6471470e+00 -3.9030300e-01 - 1.6283480e+00 -3.9762200e-01 - 1.6028320e+00 -4.0259600e-01 - 1.5782870e+00 -4.0745600e-01 - 1.5585140e+00 -4.1346500e-01 - 1.5415810e+00 -4.2011100e-01 - 1.5217930e+00 -4.2551800e-01 - 1.5029500e+00 -4.3094500e-01 - 1.4859880e+00 -4.3676000e-01 - 1.4662070e+00 -4.4126100e-01 - 1.4529760e+00 -4.4796000e-01 - 1.4415790e+00 -4.5519500e-01 - 1.4199460e+00 -4.5814400e-01 - 1.4094380e+00 -4.6534300e-01 - 1.3896850e+00 -4.6848700e-01 - 1.3717990e+00 -4.7211900e-01 - 1.3685510e+00 -4.8198300e-01 - 1.3688540e+00 -4.9348500e-01 - 1.3590680e+00 -5.0038000e-01 - 1.3763230e+00 -5.2005700e-01 - 1.3789340e+00 -5.3305900e-01 - 1.3876640e+00 -5.4927000e-01 - 1.3899570e+00 -5.6249400e-01 - 1.3921030e+00 -5.7580100e-01 - 1.3940990e+00 -5.8918700e-01 - 1.4020980e+00 -6.0599200e-01 - 1.4037640e+00 -6.1958700e-01 - 1.4061480e+00 -6.3374900e-01 - 1.4187610e+00 -6.5400000e-01 - 1.4121490e+00 -6.6335300e-01 - 1.4208900e+00 -6.8191000e-01 - 1.4097800e+00 -6.8865300e-01 - 1.5869060e+00 -8.1289600e-01 - 1.5527740e+00 -8.0702400e-01 - 1.5297480e+00 -8.0770000e-01 - 1.5076430e+00 -8.0858800e-01 - 1.4798140e+00 -8.0523800e-01 - 1.4595560e+00 -8.0656200e-01 - 1.4328130e+00 -8.0300700e-01 - 1.4176210e+00 -8.0717700e-01 - 1.3838360e+00 -7.9762500e-01 - 1.3575410e+00 -7.9289900e-01 - 1.3433940e+00 -7.9680300e-01 - 1.3165660e+00 -7.9078100e-01 - 1.2985940e+00 -7.9112500e-01 - 1.2783470e+00 -7.8934900e-01 - 1.2652040e+00 -7.9294400e-01 - 1.2451290e+00 -7.9064500e-01 - 1.2312990e+00 -7.9320000e-01 - 1.2114140e+00 -7.9037800e-01 - 1.1924060e+00 -7.8792700e-01 - 1.1720150e+00 -7.8388000e-01 - 1.1591950e+00 -7.8622900e-01 - 1.1397670e+00 -7.8233400e-01 - 1.1270570e+00 -7.8429800e-01 - 1.1071240e+00 -7.7921700e-01 - 1.0895030e+00 -7.7593300e-01 - 1.0769950e+00 -7.7730800e-01 - 1.0694740e+00 -7.8347400e-01 - 1.0506920e+00 -7.7815600e-01 - 1.0397040e+00 -7.8048400e-01 - 1.0266700e+00 -7.8050300e-01 - 1.0116460e+00 -7.7816000e-01 - 9.9537000e-01 -7.7414100e-01 - 9.8858700e-01 -7.8030200e-01 - 9.7512500e-01 -7.7891400e-01 - 9.6239700e-01 -7.7810600e-01 - 9.4908600e-01 -7.7637500e-01 - 9.3200200e-01 -7.6987500e-01 - 9.2525900e-01 -7.7548300e-01 - 9.0965700e-01 -7.7015200e-01 - 9.0229000e-01 -7.7478200e-01 - 8.8811700e-01 -7.7067500e-01 - 8.7528100e-01 -7.6796600e-01 - 8.6374200e-01 -7.6669000e-01 - 8.5405600e-01 -7.6768300e-01 - 8.4204500e-01 -7.6533000e-01 - 8.3592600e-01 -7.7096700e-01 - 8.2344100e-01 -7.6754600e-01 - 8.1219100e-01 -7.6561300e-01 - 8.0157600e-01 -7.6437300e-01 - 7.9378200e-01 -7.6717500e-01 - 7.8216600e-01 -7.6402900e-01 - 7.7118200e-01 -7.6158200e-01 - 7.5974800e-01 -7.5815500e-01 - 7.5050100e-01 -7.5799700e-01 - 7.3923400e-01 -7.5430700e-01 - 7.3364900e-01 -7.5995700e-01 - 7.2200000e-01 -7.5517400e-01 - 7.1342400e-01 -7.5546900e-01 - 7.0245100e-01 -7.5129800e-01 - 6.9492500e-01 -7.5314600e-01 - 6.8411200e-01 -7.4874000e-01 - 6.7433100e-01 -7.4597600e-01 - 6.6826000e-01 -7.5022800e-01 - 6.5768300e-01 -7.4548000e-01 - 6.5116300e-01 -7.4869500e-01 - 6.4203300e-01 -7.4643800e-01 - 6.3550500e-01 -7.4951700e-01 - 6.2521900e-01 -7.4434800e-01 - 6.1830400e-01 -7.4636700e-01 - 6.1177800e-01 -7.4923800e-01 - 6.0522700e-01 -7.5205200e-01 - 5.9214700e-01 -7.3910400e-01 - 5.8568500e-01 -7.4174700e-01 - 5.7700200e-01 -7.3875200e-01 - 5.7090300e-01 -7.4219600e-01 - 5.6441500e-01 -7.4465400e-01 - 5.5448600e-01 -7.3765900e-01 - 5.4803800e-01 -7.3997400e-01 - 5.4059400e-01 -7.3939600e-01 - 5.3635300e-01 -7.4822700e-01 - 5.2703300e-01 -7.4182400e-01 - 5.2085100e-01 -7.4485300e-01 - 5.1463500e-01 -7.4783000e-01 - 5.0554400e-01 -7.4116800e-01 - 4.9906800e-01 -7.4305500e-01 - 4.9257500e-01 -7.4488600e-01 - 4.8322000e-01 -7.3603600e-01 - 4.7679000e-01 -7.3772900e-01 - 4.7107000e-01 -7.4227600e-01 - 4.6271800e-01 -7.3608400e-01 - 4.5583800e-01 -7.3564900e-01 - 4.5006100e-01 -7.4003200e-01 - 4.4359700e-01 -7.4143600e-01 - 4.3532700e-01 -7.3396400e-01 - 4.2891600e-01 -7.3523900e-01 - 4.2140100e-01 -7.3055800e-01 - 4.1554200e-01 -7.3466700e-01 - 4.0896000e-01 -7.3478300e-01 - 4.0160500e-01 -7.2990200e-01 - 3.9670900e-01 -7.4077300e-01 - 3.8940600e-01 -7.3576900e-01 - 3.8311200e-01 -7.3763500e-01 - 3.7728000e-01 -7.4341700e-01 - 3.7056300e-01 -7.4219800e-01 - 3.6366500e-01 -7.3893000e-01 - 3.5692600e-01 -7.3659300e-01 - 3.5084400e-01 -7.4116900e-01 - 3.4445200e-01 -7.4270300e-01 - 3.3782900e-01 -7.4119000e-01 - 3.3148100e-01 -7.4361100e-01 - 3.2509500e-01 -7.4597600e-01 - 3.1832200e-01 -7.4029500e-01 - 3.1182600e-01 -7.3954900e-01 - 3.0537100e-01 -7.3974600e-01 - 2.9893200e-01 -7.4088700e-01 - 2.9244000e-01 -7.3797200e-01 - 2.8600000e-01 -7.4200000e-01 diff --git a/thirdparty/libpointmatcher/examples/data/carCloudList.csv b/thirdparty/libpointmatcher/examples/data/carCloudList.csv deleted file mode 100644 index 089378c..0000000 --- a/thirdparty/libpointmatcher/examples/data/carCloudList.csv +++ /dev/null @@ -1,3 +0,0 @@ -reading, gT00, gT01, gT02, gT03, gT10, gT11, gT12, gT13, gT20, gT21, gT22, gT23, gT30, gT31, gT32, gT33 -car_cloud400.csv, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1 -car_cloud401.csv, 0.981715, 0.169605, -0.0864239, 0.0614127, -0.152902, 0.973034, 0.172703, 0.191433, 0.113385, -0.15633, 0.981175, -0.0338571, 0, 0, 0, 1 diff --git a/thirdparty/libpointmatcher/examples/data/car_cloud400.csv b/thirdparty/libpointmatcher/examples/data/car_cloud400.csv deleted file mode 100644 index 598102a..0000000 --- a/thirdparty/libpointmatcher/examples/data/car_cloud400.csv +++ /dev/null @@ -1,24990 +0,0 @@ -x,y,z,nx,ny,nz --3.5376 , 0.639553 , -1.37678 , -0.060181,0.173729,0.982953 --3.70695 , 0.66904 , -1.38125 , -0.0626123,0.160174,0.985101 --3.94686 , 0.705947 , -1.41908 , -0.0976163,0.166735,0.981158 --4.1806 , 0.744893 , -1.44477 , -0.0784408,0.157429,0.98441 --4.4161 , 0.784772 , -1.463 , -0.0725446,0.160107,0.98443 --4.70664 , 0.831313 , -1.49967 , -0.0670886,0.157903,0.985173 --5.00006 , 0.879487 , -1.52686 , 0.0957914,-0.162661,-0.982021 --5.39542 , 0.941408 , -1.58932 , -0.101123,0.170577,0.980142 --5.79491 , 1.00601 , -1.63871 , 0.0732289,-0.166511,-0.983317 --6.18709 , 1.07131 , -1.67095 , -0.0791607,0.163702,0.983329 --6.71279 , 1.15567 , -1.74048 , -0.0879112,0.159616,0.983257 --7.25076 , 1.24392 , -1.79576 , -0.0868382,0.160392,0.983226 --7.93297 , 1.35316 , -1.88164 , -0.093464,0.151249,0.984067 --8.67705 , 1.47447 , -1.96303 , -0.0854969,0.152165,0.98465 --9.57677 , 1.62141 , -2.06632 , -0.0799285,0.154929,0.984687 --10.5859 , 1.78721 , -2.16888 , -0.074619,0.15217,0.985534 --11.8598 , 1.99545 , -2.30721 , -0.0867539,0.146827,0.985351 --13.3608 , 2.2428 , -2.45753 , -0.0827772,0.143029,0.986251 --15.4283 , 2.58044 , -2.6873 , 0.0809063,-0.138219,-0.987092 --38.5584 , 6.34831 , -5.28178 , 0.00900988,0.0803953,0.996722 --37.2452 , 6.25228 , -4.39823 , -0.0437685,0.0813806,0.995722 --12.9643 , 2.99068 , 2.65653 , -0.0133044,0.38658,0.92216 --13.4139 , 3.12087 , 2.95988 , 0.0883472,0.238177,0.967195 --9.20758 , 2.29478 , 2.55445 , 0.10192,0.116325,0.987968 --8.82818 , 2.24355 , 2.66459 , -0.340129,0.0884919,0.936206 --8.68759 , 2.24164 , 2.80819 , 0.418616,-0.248391,-0.873535 --8.44078 , 2.21527 , 2.92535 , -0.396641,0.170746,0.901954 --8.25898 , 2.20233 , 3.04985 , -0.504488,0.144277,0.851279 --8.00964 , 2.17434 , 3.15205 , -0.150985,0.291481,0.944586 --3.99202 , 1.30138 , 2.23938 , -0.870361,0.455486,0.187096 --3.93962 , 1.30316 , 2.31062 , -0.713415,0.510021,0.480539 --4.97006 , 1.55345 , 2.71162 , -0.285023,-0.932145,0.223312 --4.89081 , 1.55175 , 2.79305 , -0.285023,-0.932145,0.223312 --8.10492 , 2.3283 , 4.00865 , -0.929065,0.362877,0.07183 --8.02913 , 2.33753 , 4.15386 , -0.929065,0.362877,0.0718299 --4.74821 , 1.56912 , 3.06248 , 0.516439,0.477784,-0.710643 --4.60971 , 1.55299 , 3.11478 , -0.663889,0.414625,0.622365 --4.48953 , 1.54005 , 3.17065 , 0.240654,-0.924009,-0.297141 --6.44052 , 2.05054 , 4.1518 , -0.0500453,-0.729169,0.682501 --6.55002 , 2.10263 , 4.35318 , 0.684482,-0.72216,-0.0998501 --4.40757 , 1.57125 , 3.45454 , -0.563814,0.82588,0.00603979 --6.49295 , 2.1379 , 4.63707 , -0.15692,-0.911667,0.379788 --5.79935 , 1.97766 , 4.42479 , -0.859463,-0.0156872,0.510957 --6.36488 , 2.15409 , 4.88852 , -0.105936,-0.949351,0.295822 --6.68859 , 2.26954 , 5.24074 , -0.821478,-0.0509287,0.567961 --4.2333 , 1.61437 , 3.92146 , 0.747978,-0.635314,-0.192105 --4.08154 , 1.58967 , 3.94317 , -0.155983,0.570213,0.806552 --3.29725 , 1.38371 , 3.54281 , 0.269366,0.961912,0.0465567 --3.42004 , 1.43525 , 3.72565 , 0.468996,0.748423,0.468942 --3.79833 , 1.56349 , 4.0997 , -0.107864,0.340076,0.934192 --2.97646 , 1.33698 , 3.60964 , -0.697255,-0.500412,0.513249 --3.37631 , 1.47386 , 4.01478 , -0.479822,-0.675067,-0.560406 --2.94992 , 1.36086 , 3.78693 , -0.913399,-0.128346,0.386302 --2.95951 , 1.37995 , 3.89795 , -0.960344,0.25931,0.102457 --2.98867 , 1.40601 , 4.02927 , 0.183539,0.676847,0.712876 --3.88683 , 1.71387 , 4.93696 , -0.741774,-0.617273,0.262193 --5.88941 , 2.3944 , 6.92472 , -0.26106,0.397609,0.879634 --3.01935 , 1.47174 , 4.40079 , -0.846256,-0.131633,-0.51626 --2.95829 , 1.47071 , 4.46375 , -0.809746,0.462272,-0.361409 --2.96474 , 1.49222 , 4.59522 , -0.962362,-0.0909194,0.256113 --2.8678 , 1.47895 , 4.62178 , -0.711791,-0.646186,0.275313 --2.94044 , 1.52609 , 4.8332 , -0.562183,-0.796607,0.222187 --2.84046 , 1.51176 , 4.85827 , 0.827306,0.399436,-0.394988 --2.77777 , 1.51123 , 4.92556 , 0.614805,0.702632,-0.358222 --2.7814 , 1.53676 , 5.07473 , -0.638481,-0.651202,0.410216 --2.6668 , 1.51681 , 5.08007 , -0.540736,-0.771499,0.335253 --2.67153 , 1.54233 , 5.238 , -0.636418,-0.638298,0.433067 --2.62986 , 1.55154 , 5.34233 , -0.636418,-0.638298,0.433067 --1.22329 , 1.00191 , 3.50149 , 0.0967838,-0.0447865,0.994297 --1.16897 , 0.994694 , 3.51642 , -0.407007,0.121583,0.905297 --1.08714 , 0.976123 , 3.48919 , 0.553947,0.0675277,-0.829809 --1.08458 , 0.989959 , 3.58432 , -0.723882,-0.279676,0.630695 --1.06936 , 1.00039 , 3.66296 , -0.708364,-0.351418,0.612149 --1.17366 , 1.06546 , 3.95339 , -0.704955,-0.434662,0.560453 --0.91493 , 0.963352 , 3.60811 , 0.764246,-0.268042,0.586584 --0.868481 , 0.959283 , 3.63387 , 0.989745,-0.0592647,0.129968 --1.0259 , 1.05602 , 4.05914 , 0.450743,-0.309392,0.837321 --0.946432 , 1.03747 , 4.0343 , 0.575444,-0.302012,0.760035 --0.967384 , 1.07072 , 4.22022 , 0.785982,0.510232,-0.349136 --2.3172 , 1.83085 , 7.43787 , -0.256291,-0.531859,-0.807119 --2.17719 , 1.80424 , 7.42625 , 0.0313578,0.435129,0.899822 --1.01736 , 1.18146 , 4.8516 , 0.604669,0.443098,-0.661846 --0.960629 , 1.17995 , 4.90705 , 0.5075,0.754153,0.416769 --0.866374 , 1.1553 , 4.86033 , 0.000149641,0.102888,0.994693 --0.74221 , 1.10988 , 4.71876 , -0.156969,-0.862646,0.480835 --0.635691 , 1.07378 , 4.6112 , 0.21494,-0.482436,0.84915 --0.519916 , 1.02824 , 4.45393 , -0.974897,0.159471,0.155388 --0.514845 , 1.06155 , 4.67127 , -0.0558169,-0.959745,0.27527 --0.388987 , 1.00405 , 4.45321 , -0.508102,-0.279123,0.814815 --0.793681 , 1.38644 , 6.3861 , 0.381336,-0.902343,-0.200898 --0.742632 , 1.41227 , 6.60209 , -0.241912,0.830534,0.50169 --0.358401 , 1.12316 , 5.23137 , -0.267022,0.458404,0.847682 --0.285385 , 1.11267 , 5.24781 , -0.272082,0.543048,0.794399 --0.21757 , 1.10917 , 5.30186 , -0.255001,-0.15462,0.954499 --0.0862824 , 1.02615 , 4.93682 , -0.194531,0.658782,-0.726749 --0.212479 , 1.28542 , 6.41121 , -0.639639,-0.15021,-0.753856 --0.137581 , 1.30113 , 6.59168 , -0.372291,0.281455,-0.884411 --0.048097 , 1.30001 , 6.68309 , -0.853459,-0.496822,0.157401 --3.43464 , 0.74495 , -1.39414 , -0.046603,0.162806,0.985557 --3.60167 , 0.778452 , -1.40182 , -0.0529197,0.163832,0.985068 --3.80574 , 0.818061 , -1.42432 , -0.0856848,0.180198,0.979891 --4.04506 , 0.863784 , -1.45947 , -0.0772477,0.177641,0.981059 --4.28736 , 0.909793 , -1.48668 , -0.0731044,0.184944,0.980026 --4.54043 , 0.96013 , -1.51094 , -0.0650408,0.189826,0.979661 --4.82196 , 1.01447 , -1.53976 , -0.0804394,0.193191,0.977858 --5.17795 , 1.08219 , -1.59309 , 0.102991,-0.180755,-0.978121 --5.56373 , 1.15519 , -1.64644 , -0.078779,0.168378,0.98257 --5.93464 , 1.22773 , -1.67915 , 0.0716674,-0.163173,-0.983991 --6.39976 , 1.31739 , -1.73682 , 0.0874837,-0.167881,-0.981918 --6.91505 , 1.41694 , -1.79667 , 0.0831242,-0.162994,-0.983119 --7.51686 , 1.53314 , -1.86949 , 0.08995,-0.163877,-0.982371 --8.24413 , 1.67181 , -1.96363 , 0.0903297,-0.155201,-0.983745 --9.07043 , 1.83068 , -2.06353 , 0.0864151,-0.157092,-0.983796 --9.98657 , 2.00913 , -2.16119 , -0.0718534,0.154967,0.985303 --11.0884 , 2.22307 , -2.27915 , -0.0788311,0.156867,0.984469 --12.4815 , 2.49281 , -2.43574 , -0.0770106,0.152212,0.985343 --14.2079 , 2.82779 , -2.62541 , -0.0788707,0.141487,0.986793 --16.3829 , 3.25154 , -2.85735 , -0.0776827,0.141744,0.986851 --36.4854 , 7.19219 , -4.82105 , -0.0214249,0.0236366,0.999491 --41.7682 , 8.29641 , -4.90339 , 0.159231,0.103443,0.981807 --12.6156 , 3.29045 , 2.44613 , -0.115631,0.252603,0.960636 --12.0312 , 3.19297 , 2.60872 , -0.14068,-0.0254555,0.989728 --11.7635 , 3.16572 , 2.79722 , -0.00145616,-0.257265,0.96634 --9.57116 , 2.68134 , 2.6663 , -0.289771,-0.6084,0.738838 --9.61213 , 2.72079 , 2.85827 , -0.318103,-0.302559,0.898481 --9.47801 , 2.71761 , 3.01843 , -0.318103,-0.30256,0.898481 --8.58143 , 2.52616 , 3.00974 , -0.366355,-0.190394,0.910788 --4.07549 , 1.43347 , 2.11781 , -0.521813,0.470461,0.711602 --3.93086 , 1.41114 , 2.16775 , 0.986091,-0.15107,0.069297 --3.85267 , 1.40385 , 2.23114 , 0.986091,-0.15107,0.0692968 --3.99656 , 1.45418 , 2.35759 , -0.875862,0.114534,-0.468773 --4.30399 , 1.54858 , 2.54166 , -0.375072,0.182434,-0.908867 --4.16437 , 1.52617 , 2.59032 , 0.109109,0.773399,-0.624459 --7.45324 , 2.41949 , 3.84378 , -0.469844,-0.809011,0.353197 --4.7287 , 1.70885 , 2.9893 , 0.564844,-0.119418,-0.816511 --4.6913 , 1.71572 , 3.08233 , -0.387574,0.19624,0.900709 --4.54456 , 1.69245 , 3.13028 , 0.584984,-0.522826,-0.620037 --3.70543 , 1.47398 , 2.87199 , 0.450132,-0.836771,-0.311762 --4.28791 , 1.65345 , 3.22872 , 0.347924,-0.937401,0.0151314 --3.86263 , 1.54754 , 3.13004 , 0.34709,-0.881167,0.321051 --4.32438 , 1.69774 , 3.45951 , 0.709226,-0.704981,-0.000997805 --11.2216 , 3.74278 , 7.18536 , 0.271154,-0.613541,0.741649 --3.91012 , 1.60872 , 3.45445 , 0.586744,0.727492,-0.355648 --11.0474 , 3.77616 , 7.63556 , -0.271154,0.613541,-0.741649 --4.15957 , 1.71885 , 3.81403 , 0.171461,0.4145,0.893751 --4.07549 , 1.71005 , 3.87717 , 0.171461,0.4145,0.893751 --3.52762 , 1.55745 , 3.63905 , 0.385138,0.90467,-0.182321 --3.18259 , 1.46445 , 3.51174 , 0.269366,0.961912,0.0465567 --3.20842 , 1.48755 , 3.62774 , 0.269366,0.961912,0.0465566 --3.68512 , 1.65944 , 4.07434 , 0.294279,0.239067,0.925336 --4.52606 , 1.95502 , 4.82398 , -0.831297,-0.207944,0.515465 --5.65375 , 2.35461 , 5.84896 , -0.872297,0.411901,-0.263505 --2.98219 , 1.47738 , 3.86429 , -0.913399,-0.128346,0.386302 --2.92304 , 1.47338 , 3.92078 , -0.972601,0.0656136,0.22303 --3.86928 , 1.82042 , 4.85346 , -0.741774,-0.617273,0.262193 --3.97954 , 1.88192 , 5.09428 , -0.700281,-0.652028,0.290631 --3.94098 , 1.89177 , 5.2081 , 0.676207,0.535365,-0.506092 --2.83283 , 1.51144 , 4.28309 , 0.436543,-0.197844,0.877661 --2.74678 , 1.49897 , 4.31565 , 0.254644,0.750098,0.610336 --2.80795 , 1.54085 , 4.50022 , -0.49046,0.866374,-0.0940493 --3.10023 , 1.67279 , 4.94419 , -0.436417,-0.774509,0.457903 --2.86964 , 1.6053 , 4.8285 , 0.632943,0.731455,-0.253684 --2.82716 , 1.61037 , 4.91891 , 0.774421,0.568556,-0.277517 --2.88706 , 1.6576 , 5.13588 , -0.615399,-0.720632,0.319333 --1.28533 , 1.02616 , 3.28078 , 0.385581,-0.258915,-0.885602 --2.69211 , 1.62597 , 5.19609 , -0.636418,-0.638298,0.433067 --2.61818 , 1.61965 , 5.25401 , -0.636418,-0.638298,0.433067 --2.57694 , 1.62685 , 5.35825 , -0.636418,-0.638298,0.433067 --1.18797 , 1.04063 , 3.50237 , -0.0640318,0.295101,-0.953318 --1.15453 , 1.04104 , 3.54938 , 0.144672,0.599221,-0.787404 --1.28165 , 1.11598 , 3.85006 , 0.754308,-0.562103,0.339204 --1.26227 , 1.12408 , 3.93252 , 0.643392,0.0734406,-0.762006 --1.01907 , 1.02683 , 3.63772 , -0.906449,0.395683,-0.147599 --1.02097 , 1.04438 , 3.75048 , -0.104206,0.0245212,0.994253 --0.861855 , 0.982855 , 3.57302 , 0.989745,-0.0592647,0.129968 --1.05391 , 1.10019 , 4.05623 , 0.509055,0.697527,-0.504301 --1.18136 , 1.18959 , 4.45157 , -0.516125,0.502619,0.693534 --1.08832 , 1.16361 , 4.41215 , 0.179948,-0.979836,-0.0868331 --0.960659 , 1.11727 , 4.29059 , 0.741228,0.665428,-0.0882462 --1.00271 , 1.16696 , 4.55089 , 0.629082,-0.38605,-0.674701 --1.05941 , 1.22887 , 4.86777 , -0.499061,-0.532823,0.683402 --1.01614 , 1.23425 , 4.96065 , -0.267936,-0.508062,0.818586 --0.876814 , 1.17933 , 4.79646 , -0.592232,0.804551,-0.0442619 --0.743318 , 1.12406 , 4.62872 , -0.554689,-0.706322,-0.439807 --0.689425 , 1.12132 , 4.67992 , -0.307838,-0.58986,0.746526 --0.536425 , 1.04688 , 4.41261 , -0.974897,0.159471,0.155388 --0.504933 , 1.05743 , 4.52647 , -0.278944,-0.945253,0.169373 --0.484936 , 1.08044 , 4.69678 , 0.155893,0.917717,-0.365366 --0.809525 , 1.39567 , 6.26473 , 0.589402,-0.804537,0.0729795 --0.764761 , 1.42195 , 6.49053 , 0.787329,0.567464,-0.241035 --0.68378 , 1.41982 , 6.58215 , -0.679078,-0.374052,-0.631616 --0.315753 , 1.12672 , 5.21843 , -0.267022,0.458403,0.847682 --0.241465 , 1.11176 , 5.22498 , -0.110989,-0.00149758,0.993821 --0.129244 , 1.05249 , 4.99726 , -0.510933,0.481988,-0.711783 --0.266338 , 1.31212 , 6.46037 , -0.50621,-0.177964,-0.843849 --0.190521 , 1.32171 , 6.62256 , 0.659786,-0.337884,0.671206 --0.083733 , 1.28735 , 6.54905 , -0.927835,0.242068,-0.283771 --2.99361 , 0.771721 , -1.36631 , -0.0969432,0.0930884,0.990927 --3.14794 , 0.806677 , -1.3822 , -0.0829157,0.104623,0.99105 --3.31201 , 0.843938 , -1.39863 , 0.0803087,-0.135865,-0.987467 --3.47767 , 0.881605 , -1.40992 , -0.0747512,0.159824,0.984311 --3.66131 , 0.923741 , -1.42623 , -0.0615462,0.183346,0.98112 --3.89027 , 0.974255 , -1.46137 , -0.0869116,0.184026,0.979071 --4.121 , 1.0257 , -1.48905 , -0.0821101,0.180071,0.980221 --4.37938 , 1.08372 , -1.52315 , -0.0739496,0.193863,0.978238 --4.64058 , 1.14316 , -1.54874 , -0.0684915,0.191711,0.979059 --4.95722 , 1.21277 , -1.59154 , -0.097803,0.197801,0.975351 --5.33028 , 1.29442 , -1.64877 , -0.0955373,0.176439,0.979664 --5.71568 , 1.38084 , -1.69772 , -0.0713301,0.161926,0.984222 --6.11276 , 1.47101 , -1.73749 , -0.0783676,0.16673,0.982883 --6.60395 , 1.5797 , -1.80048 , -0.0879513,0.167315,0.981973 --7.15327 , 1.7029 , -1.868 , -0.0852281,0.165468,0.982526 --7.80027 , 1.84725 , -1.95034 , -0.0892775,0.166459,0.981998 --8.55294 , 2.01515 , -2.04536 , -0.0888757,0.159522,0.983186 --9.48813 , 2.2218 , -2.17168 , -0.0773702,0.158344,0.984348 --10.4298 , 2.43566 , -2.26598 , 0.0719471,-0.153897,-0.985464 --11.6782 , 2.71655 , -2.41368 , 0.0791929,-0.153359,-0.984992 --13.1986 , 3.05823 , -2.58828 , -0.0772042,0.152495,0.985284 --15.0976 , 3.48579 , -2.80134 , -0.0796574,0.142543,0.986578 --17.397 , 4.00677 , -3.03748 , 0.0891181,-0.148694,-0.984859 --37.8853 , 8.5796 , -5.60646 , -0.0437685,0.0813806,0.995722 --47.205 , 11.1201 , -3.80044 , 0.525351,-0.714073,0.462717 --13.2307 , 3.8278 , 2.33589 , 0.997204,0.0724442,-0.0183108 --11.8027 , 3.49514 , 2.42336 , -0.204688,-0.115219,0.972022 --12.038 , 3.59148 , 2.67764 , 0.262114,0.204803,-0.943055 --11.0244 , 3.35752 , 2.75582 , 0.189166,0.0726343,-0.979255 --10.1179 , 3.14741 , 2.81603 , 0.381835,0.496794,-0.779357 --10.2026 , 3.2009 , 3.02839 , 0.316837,0.475408,-0.820732 --9.26138 , 2.97332 , 3.03572 , -0.315819,-0.600024,0.735003 --9.4732 , 3.06013 , 3.26707 , 0.381835,0.496795,-0.779357 --3.89521 , 1.52681 , 2.1043 , 0.763329,-0.299812,-0.572225 --3.81726 , 1.51862 , 2.16808 , 0.772722,0.36901,0.516461 --3.95209 , 1.56991 , 2.28974 , -0.841763,-0.393692,-0.36938 --4.03813 , 1.60836 , 2.40272 , -0.943116,-0.0103327,-0.332304 --4.29574 , 1.69744 , 2.57505 , 0.137886,-0.0784284,0.987338 --4.06428 , 1.64377 , 2.5929 , 0.164883,-0.877342,0.45065 --5.00297 , 1.93855 , 3.0242 , -0.598575,-0.200236,0.775637 --3.91285 , 1.62667 , 2.72184 , 0.656732,-0.33687,-0.674702 --3.88959 , 1.63388 , 2.80469 , -0.613429,0.103679,0.782915 --3.77579 , 1.61394 , 2.84963 , -0.613429,0.103679,0.782915 --3.77694 , 1.62816 , 2.94214 , 0.729635,-0.674122,-0.114859 --4.08003 , 1.73848 , 3.17772 , -0.382553,-0.490346,0.78308 --3.92777 , 1.7054 , 3.20527 , -0.90633,-0.248849,-0.341526 --4.09241 , 1.77402 , 3.39008 , -0.391719,-0.898511,0.198078 --3.89568 , 1.72654 , 3.3912 , -0.909567,-0.334985,0.245912 --3.92757 , 1.75332 , 3.5126 , 0.567781,0.745843,-0.348342 --4.16405 , 1.8479 , 3.757 , 0.703684,-0.556829,-0.441329 --3.83457 , 1.75484 , 3.67162 , -0.346715,-0.889234,0.298414 --3.68813 , 1.722 , 3.6883 , -0.536414,-0.690064,0.485871 --3.26204 , 1.59214 , 3.51563 , 0.269366,0.961912,0.0465568 --3.24084 , 1.60015 , 3.59989 , 0.269366,0.961912,0.0465568 --3.5848 , 1.73727 , 3.94623 , -0.848375,-0.522797,0.0833224 --4.37496 , 2.03658 , 4.64279 , 0.93869,-0.340752,-0.0524405 --4.4767 , 2.09525 , 4.85982 , -0.892212,-0.0387967,0.449948 --4.42938 , 2.09971 , 4.96831 , 0.699523,-0.0196994,-0.714339 --4.28378 , 2.06944 , 4.99638 , 0.233648,0.131665,-0.963366 --4.04488 , 2.00258 , 4.93923 , -0.700281,-0.652028,0.290632 --4.02439 , 2.01761 , 5.06657 , -0.618907,-0.295628,0.727708 --4.36914 , 2.17267 , 5.53399 , -0.862913,-0.333144,0.379996 --3.02896 , 1.67533 , 4.41833 , -0.832125,-0.527166,-0.172232 --2.7432 , 1.58091 , 4.25897 , -0.256979,0.884537,-0.389302 --2.66509 , 1.56845 , 4.29731 , 0.254644,0.750098,0.610336 --2.94255 , 1.70041 , 4.71349 , -0.756898,-0.651631,-0.0498277 --3.10905 , 1.79023 , 5.03378 , 0.474524,0.643426,-0.600691 --3.03194 , 1.78018 , 5.09267 , 0.474524,0.643426,-0.600691 --2.87191 , 1.73565 , 5.05401 , -0.509622,-0.753366,0.415601 --1.9447 , 1.35625 , 4.05908 , -0.680923,0.0748196,0.728523 --1.25509 , 1.06997 , 3.29 , 0.484223,0.340788,0.805848 --1.38934 , 1.14325 , 3.55382 , -0.626721,-0.678491,-0.383238 --1.32758 , 1.13027 , 3.56506 , -0.54149,-0.837082,0.0779896 --1.28238 , 1.12501 , 3.5988 , -0.330654,-0.707905,0.62413 --1.21594 , 1.10871 , 3.59962 , 0.117535,0.827346,-0.549257 --1.17534 , 1.10484 , 3.6396 , 0.262705,0.95518,-0.136447 --1.1347 , 1.10081 , 3.6789 , 0.214236,-0.233227,-0.948529 --1.19228 , 1.14707 , 3.88382 , 0.192448,0.976488,-0.097137 --0.998088 , 1.06573 , 3.66287 , -0.147239,0.612736,0.77645 --0.877204 , 1.01965 , 3.55472 , 0.199926,-0.0873944,0.975906 --1.11202 , 1.16315 , 4.11302 , -0.496292,-0.722092,0.481951 --1.03647 , 1.14272 , 4.09973 , 0.685822,0.68554,-0.244302 --1.10846 , 1.20526 , 4.39128 , -0.480426,0.876777,-0.0212923 --1.07446 , 1.20989 , 4.47448 , 0.551026,-0.59164,-0.5885 --1.01428 , 1.20004 , 4.50401 , -0.574811,0.557091,0.599367 --0.97176 , 1.2006 , 4.57777 , 0.647514,-0.264419,-0.714709 --0.914073 , 1.19285 , 4.61445 , -0.62517,0.474718,0.61952 --0.875005 , 1.19677 , 4.70538 , -0.388108,0.815335,0.429653 --0.80132 , 1.17926 , 4.70393 , -0.521538,-0.808543,-0.272501 --0.724885 , 1.15885 , 4.69183 , 0.443564,0.340703,0.828958 --0.570008 , 1.08023 , 4.42684 , -0.966572,0.0334815,0.254201 --0.494541 , 1.05625 , 4.39131 , -0.340544,-0.341961,0.875838 --0.541186 , 1.12894 , 4.78741 , -0.382259,-0.710706,0.590573 --0.470868 , 1.1118 , 4.78881 , -0.00217993,-0.854596,0.519288 --0.788815 , 1.43807 , 6.39763 , -0.415098,-0.906848,-0.0729453 --0.686908 , 1.41123 , 6.38496 , 0.716929,0.696393,-0.0323906 --0.342751 , 1.14099 , 5.17897 , -0.267022,0.458403,0.847682 --0.278858 , 1.13455 , 5.23442 , -0.163822,0.0891714,0.982451 --0.181601 , 1.09097 , 5.10503 , 0.779148,-0.346788,0.522176 --0.0828027 , 1.0406 , 4.93464 , 0.0772675,-0.630122,0.772642 --0.208268 , 1.29765 , 6.3992 , -0.639639,-0.15021,-0.753856 --0.136457 , 1.31 , 6.59017 , -0.372291,0.281455,-0.884411 --0.0517363 , 1.30999 , 6.72178 , -0.706597,-0.672914,0.21888 --2.73121 , 0.818734 , -1.34288 , -0.094916,0.158099,0.982851 --2.84981 , 0.851111 , -1.34371 , 0.0820324,-0.13534,-0.987397 --3.01833 , 0.892797 , -1.37452 , -0.0981821,0.149803,0.983829 --3.17164 , 0.932994 , -1.38927 , -0.0847433,0.123813,0.98868 --3.35129 , 0.978474 , -1.41508 , 0.0885875,-0.145384,-0.985401 --3.55018 , 1.0278 , -1.44535 , -0.0691963,0.173506,0.982399 --3.7505 , 1.07878 , -1.46933 , -0.0824619,0.183248,0.979602 --3.96991 , 1.13483 , -1.49679 , -0.0872168,0.171083,0.981389 --4.22614 , 1.19965 , -1.53607 , 0.0930449,-0.171465,-0.980787 --4.48421 , 1.26565 , -1.56681 , -0.0673216,0.182376,0.980921 --4.77103 , 1.33881 , -1.60244 , -0.0891576,0.185768,0.97854 --5.11296 , 1.42444 , -1.65393 , -0.0911545,0.169751,0.981262 --5.45865 , 1.51331 , -1.69431 , -0.0817694,0.163499,0.983149 --5.8422 , 1.61077 , -1.73852 , -0.0743576,0.16209,0.983971 --6.29132 , 1.7258 , -1.79662 , -0.088565,0.163245,0.982602 --6.80794 , 1.85656 , -1.86464 , -0.0875661,0.16176,0.982937 --7.40138 , 2.00739 , -1.94292 , -0.0893745,0.163498,0.982487 --8.08173 , 2.17997 , -2.03032 , -0.0900623,0.159245,0.983123 --8.91524 , 2.39123 , -2.14465 , -0.089622,0.151558,0.984377 --9.81856 , 2.62251 , -2.25092 , -0.07148,0.151963,0.985798 --10.905 , 2.89992 , -2.37899 , -0.0779898,0.153838,0.985014 --12.269 , 3.24858 , -2.54588 , -0.0786092,0.1509,0.985419 --13.9321 , 3.67485 , -2.74159 , -0.0770378,0.147394,0.986073 --16.1054 , 4.23018 , -3.00096 , -0.0828049,0.155483,0.984362 --38.0831 , 9.97412 , -4.81431 , -0.308069,0.000157603,0.951364 --38.17 , 10.102 , -4.12931 , -0.451973,-0.0805946,0.888383 --43.702 , 11.6257 , -4.07292 , 0.349079,-0.73522,0.58103 --44.1766 , 11.8688 , -3.32577 , 0.478986,-0.801306,0.358442 --46.5616 , 12.7433 , -1.87346 , 0.257951,-0.860016,0.440265 --45.7022 , 12.6412 , -0.994084 , 0.209198,-0.967402,0.142722 --45.7272 , 12.7734 , -0.168746 , 0.351752,-0.925434,0.140861 --49.0076 , 13.7943 , 0.631072 , 0.432753,-0.72121,0.540907 --49.3679 , 14.0283 , 1.5211 , -0.0733615,-0.932057,0.354807 --49.0675 , 14.0798 , 2.40739 , 0.19001,-0.636208,0.747754 --46.0972 , 13.3816 , 3.16319 , 0.19001,-0.636208,0.747754 --12.8258 , 4.07457 , 1.88643 , -0.941758,-0.184442,0.2812 --12.8094 , 4.10658 , 2.12629 , -0.941758,-0.184442,0.2812 --12.6459 , 4.09599 , 2.35179 , -0.941758,-0.184442,0.2812 --12.7078 , 4.15107 , 2.59911 , 0.718126,0.383677,-0.580592 --12.8785 , 4.23804 , 2.86514 , -0.648089,-0.0377599,0.760628 --12.0975 , 4.04325 , 2.99107 , -0.210817,-0.221614,0.952073 --10.0977 , 3.47795 , 2.87836 , -0.275382,-0.133984,0.951952 --10.1792 , 3.53314 , 3.09264 , -0.225863,0.0451396,0.973113 --9.51725 , 3.36085 , 3.15434 , 0.381835,0.496794,-0.779357 --3.99458 , 1.68488 , 2.07374 , -0.922923,0.0591094,-0.38042 --3.94545 , 1.68279 , 2.14777 , -0.758255,0.195048,-0.622098 --4.03377 , 1.72333 , 2.25795 , -0.965481,-0.149786,-0.213097 --4.1564 , 1.77531 , 2.38231 , -0.797125,-0.073233,-0.599357 --4.29327 , 1.83403 , 2.51705 , 0.491392,-0.691068,-0.530055 --4.00066 , 1.75317 , 2.51743 , -0.907736,-0.146604,0.393093 --4.07987 , 1.79332 , 2.6366 , -0.257198,0.50144,0.826079 --3.86114 , 1.73555 , 2.64991 , 0.547971,-0.495269,-0.674119 --3.95466 , 1.78097 , 2.77741 , -0.704329,-0.0767004,0.705718 --3.7706 , 1.73303 , 2.79661 , 0.673754,-0.304512,-0.673296 --3.64134 , 1.70312 , 2.83221 , -0.00943229,-0.143798,0.989562 --3.69403 , 1.73472 , 2.94696 , -0.773913,0.561683,-0.292525 --4.1922 , 1.92157 , 3.27788 , -0.237344,0.670772,-0.702661 --3.69673 , 1.76433 , 3.13722 , 0.698509,-0.475853,0.534461 --4.17373 , 1.94798 , 3.48308 , 0.644591,-0.755076,0.119847 --3.94383 , 1.88252 , 3.46751 , 0.836435,0.512614,-0.193913 --4.07301 , 1.94557 , 3.64758 , 0.343245,0.807914,-0.479019 --4.06574 , 1.95982 , 3.7554 , 0.42409,-0.308581,-0.851426 --3.91793 , 1.9227 , 3.77839 , -0.55716,-0.511515,0.65416 --3.97159 , 1.95935 , 3.92646 , 0.375869,-0.391306,-0.840001 --3.72096 , 1.88339 , 3.87492 , 0.610226,0.517122,-0.600174 --3.66912 , 1.88126 , 3.95194 , -0.913832,-0.268504,0.304658 --4.5657 , 2.24248 , 4.71848 , -0.238835,0.484158,-0.841754 --4.71275 , 2.32205 , 4.97202 , -0.564602,-0.310735,0.764636 --4.51301 , 2.26635 , 4.96751 , -0.50518,-0.276582,0.817494 --4.36781 , 2.23166 , 4.99912 , 0.533053,-0.074865,-0.842763 --4.26734 , 2.21386 , 5.06376 , 0.453719,-0.0111018,-0.891076 --4.00803 , 2.13066 , 4.98768 , -0.466499,-0.383894,0.796871 --4.05663 , 2.17314 , 5.18004 , 0.617741,0.328628,-0.714423 --3.18833 , 1.83488 , 4.51577 , -0.896863,-0.415156,-0.152585 --3.01665 , 1.78211 , 4.47665 , -0.780207,-0.526119,0.338343 --2.8071 , 1.71149 , 4.39164 , -0.447534,0.0897823,-0.889749 --3.25591 , 1.92518 , 4.98702 , -0.593375,-0.80414,-0.035566 --3.12052 , 1.8882 , 4.98572 , -0.700558,-0.672367,0.239043 --3.11309 , 1.90678 , 5.12475 , -0.700558,-0.672367,0.239043 --2.94703 , 1.85471 , 5.08227 , -0.474524,-0.643426,0.600691 --2.08296 , 1.48122 , 4.18224 , -0.405218,-0.013724,0.914117 --1.43017 , 1.19533 , 3.47745 , 0.18319,0.891952,0.413357 --1.39299 , 1.19199 , 3.52096 , 0.149673,0.90056,0.408154 --1.14915 , 1.08897 , 3.28527 , -0.0485575,0.550564,0.83338 --1.08769 , 1.07251 , 3.28442 , -0.0971805,0.30165,0.948453 --1.0585 , 1.07159 , 3.33008 , -0.252449,-0.13998,0.957431 --1.13456 , 1.12381 , 3.53659 , 0.369775,-0.698738,0.612398 --1.09056 , 1.11613 , 3.5673 , -0.633839,0.621092,-0.46097 --1.05104 , 1.1111 , 3.60551 , 0.439691,-0.403487,-0.802415 --1.13245 , 1.17079 , 3.85177 , 0.315791,-0.94659,0.0651471 --0.931916 , 1.07987 , 3.61249 , -0.333989,0.342747,-0.878053 --0.873786 , 1.06367 , 3.61401 , -0.807227,-0.343259,0.480165 --1.12377 , 1.22444 , 4.21713 , 0.629683,0.765275,-0.133617 --0.991493 , 1.16876 , 4.09154 , 0.685821,0.68554,-0.244302 --1.0946 , 1.25153 , 4.45361 , 0.523954,-0.433781,-0.733012 --0.97219 , 1.20126 , 4.3423 , 0.799029,-0.414388,0.4357 --0.986215 , 1.23529 , 4.54028 , -0.690109,0.136797,0.710659 --0.936463 , 1.23027 , 4.5958 , 0.475035,-0.139459,-0.868846 --0.878234 , 1.22027 , 4.63241 , -0.643107,0.500423,0.579647 --0.831924 , 1.21857 , 4.7049 , 0.415848,0.908362,-0.0441463 --0.854491 , 1.26638 , 4.97941 , -0.235793,0.796058,-0.557398 --0.740787 , 1.218 , 4.86683 , -0.210902,0.878369,-0.428938 --0.526207 , 1.08923 , 4.40607 , -0.966572,0.0334816,0.254201 --0.518989 , 1.11709 , 4.60477 , -0.927688,-0.360866,0.095763 --0.500424 , 1.13944 , 4.7854 , 0.650841,0.731598,-0.202905 --0.802256 , 1.4488 , 6.2762 , 0.527191,-0.848608,0.0439846 --0.703024 , 1.41963 , 6.26428 , -0.379204,-0.711198,0.591947 --0.260604 , 1.05013 , 4.63122 , -0.627396,-0.778687,0.00452451 --0.208517 , 1.04619 , 4.69479 , 0.424409,-0.875619,-0.230583 --0.23805 , 1.13535 , 5.23131 , -0.526793,0.369102,0.765671 --0.122646 , 1.0652 , 4.97524 , -0.510933,0.481988,-0.711783 --0.25974 , 1.32484 , 6.43836 , -0.639639,-0.150211,-0.753856 --0.194721 , 1.34399 , 6.6794 , 0.71698,-0.68807,-0.111801 --0.0876326 , 1.30145 , 6.59718 , -0.536179,-0.430306,0.726188 --2.62784 , 0.897986 , -1.34393 , -0.069229,0.187814,0.979762 --2.75253 , 0.935369 , -1.35323 , -0.0768755,0.198123,0.977158 --2.90243 , 0.977338 , -1.37563 , -0.0894985,0.172841,0.980875 --3.05439 , 1.02179 , -1.3936 , -0.0774728,0.163008,0.983579 --3.22353 , 1.0693 , -1.41734 , -0.0875036,0.162427,0.982833 --3.41958 , 1.12441 , -1.45179 , 0.0984224,-0.14995,-0.983783 --3.60984 , 1.17939 , -1.47489 , -0.0909901,0.164666,0.982144 --3.83484 , 1.24227 , -1.5115 , -0.0827517,0.173693,0.981317 --4.05291 , 1.30592 , -1.53616 , -0.0911546,0.173258,0.980649 --4.3255 , 1.38194 , -1.58155 , -0.0805456,0.171543,0.981879 --4.58301 , 1.45686 , -1.60913 , -0.0761504,0.16479,0.983385 --4.87659 , 1.54101 , -1.64548 , -0.0903467,0.156794,0.98349 --5.23508 , 1.64238 , -1.70166 , -0.0930208,0.147831,0.984628 --5.59641 , 1.74694 , -1.74592 , -0.0779367,0.155022,0.984832 --5.99521 , 1.86222 , -1.79334 , -0.0810615,0.15305,0.984888 --6.47015 , 1.99721 , -1.85705 , -0.0880512,0.156031,0.98382 --7.00226 , 2.15045 , -1.92637 , -0.0931578,0.152229,0.983945 --7.65609 , 2.33588 , -2.02148 , 0.0945339,-0.136569,-0.98611 --8.37847 , 2.54247 , -2.11672 , -0.112157,0.11496,0.987018 --9.26263 , 2.79496 , -2.23971 , -0.0833644,0.146846,0.98564 --10.1974 , 3.06552 , -2.3463 , -0.0983057,0.111643,0.988874 --11.3887 , 3.40776 , -2.49477 , -0.0935089,0.118518,0.988539 --12.8374 , 3.8248 , -2.67139 , -0.0880943,0.121367,0.988691 --14.6319 , 4.34206 , -2.88438 , -0.0919798,0.11278,0.989354 --17.1663 , 5.06976 , -3.2103 , -0.0828048,0.155483,0.984362 --43.6092 , 12.8202 , -5.50429 , -0.326962,0.749237,-0.575969 --44.529 , 13.3255 , -4.0051 , -0.306791,0.79567,-0.522292 --44.7834 , 13.521 , -3.21413 , 0.370743,-0.702488,0.607504 --46.545 , 14.2883 , -1.68069 , 0.350225,-0.826994,0.4398 --44.3659 , 13.7613 , -0.745507 , -0.34654,0.908978,0.231666 --42.8245 , 13.4153 , 0.0973001 , 0.569791,-0.820656,0.043157 --47.7332 , 15.1616 , 1.73364 , 0.19001,-0.636208,0.747754 --47.7444 , 15.2952 , 2.60779 , -0.547396,0.420694,0.723446 --47.322 , 15.2932 , 3.46264 , -0.279309,0.310351,0.908663 --40.3016 , 13.2026 , 3.85033 , 0.732799,-0.664948,-0.144395 --13.1111 , 4.63912 , 2.2255 , -0.896647,-0.221634,0.383278 --12.927 , 4.61717 , 2.45623 , -0.947915,-0.153953,0.278847 --12.7025 , 4.58089 , 2.67635 , -0.781648,0.00788346,0.623671 --11.0803 , 4.08711 , 2.6903 , -0.0828849,0.00884947,0.99652 --11.3148 , 4.19588 , 2.9446 , 0.0134013,0.0438118,0.99895 --3.85476 , 1.74645 , 1.82325 , -0.921533,-0.249698,-0.297367 --3.79133 , 1.73686 , 1.89336 , -0.906426,-0.260194,-0.332701 --5.8417 , 2.44313 , 2.42273 , -0.0556311,0.58287,0.810659 --4.53844 , 2.01717 , 2.2355 , -0.470013,-0.537203,-0.700358 --3.91571 , 1.81745 , 2.17384 , 0.732307,-0.129875,-0.668475 --4.07589 , 1.88541 , 2.30506 , 0.634719,-0.644047,0.427008 --3.72306 , 1.7752 , 2.29158 , -0.772329,0.345917,-0.532775 --4.01443 , 1.89149 , 2.46862 , 0.78762,-0.605065,0.116408 --4.08438 , 1.92972 , 2.58459 , -0.880858,-0.400101,0.253 --4.37584 , 2.0484 , 2.78318 , 0.325477,0.813786,0.481473 --4.4747 , 2.09972 , 2.92262 , -0.185172,-0.981274,-0.053026 --4.72811 , 2.20862 , 3.12965 , 0.333629,-0.727267,0.599811 --4.57493 , 2.16804 , 3.17787 , 0.472574,-0.562305,0.678592 --3.51291 , 1.79024 , 2.81799 , -0.773913,0.561683,-0.292525 --3.64188 , 1.85118 , 2.96782 , -0.773913,0.561683,-0.292525 --3.69041 , 1.88439 , 3.08519 , -0.901097,-0.2708,0.338661 --3.93963 , 1.99357 , 3.3087 , 0.0284172,0.586829,0.809212 --4.33086 , 2.15982 , 3.62253 , -0.576209,-0.288135,0.764828 --4.24984 , 2.14592 , 3.69287 , 0.508077,0.377191,-0.774329 --4.03747 , 2.08005 , 3.68481 , 0.405245,-0.67043,-0.621531 --3.93983 , 2.05765 , 3.73909 , 0.486859,-0.806402,-0.335683 --3.92258 , 2.06722 , 3.84131 , 0.359721,-0.853631,-0.376717 --3.79978 , 2.03554 , 3.8759 , -0.661442,-0.178443,0.728459 --4.01361 , 2.13969 , 4.13773 , -0.161068,-0.838354,0.520788 --3.72533 , 2.03972 , 4.05597 , -0.192595,-0.787233,0.585809 --4.25726 , 2.27904 , 4.56915 , -0.800943,0.583621,-0.133704 --4.42623 , 2.37015 , 4.83695 , -0.8269,-0.0603706,0.559099 --4.32034 , 2.34724 , 4.89864 , -0.457946,0.00292297,0.888975 --4.35367 , 2.38324 , 5.07294 , 0.572468,0.367283,-0.733064 --4.14355 , 2.31494 , 5.04543 , -0.479213,-0.389642,0.78647 --4.09372 , 2.31499 , 5.15079 , -0.417052,-0.549809,0.723725 --4.01237 , 2.30278 , 5.22971 , 0.654609,0.442549,-0.612892 --3.14981 , 1.93754 , 4.55517 , -0.697555,-0.708024,-0.110084 --3.20114 , 1.98074 , 4.73761 , 0.777719,0.627154,0.0427848 --1.58736 , 1.25837 , 3.20337 , -0.706442,-0.160533,0.689325 --1.55572 , 1.25486 , 3.24959 , -0.706442,-0.160533,0.689325 --1.50364 , 1.24279 , 3.27387 , 0.608506,0.230171,-0.759436 --3.70588 , 2.30846 , 5.90212 , -0.467475,0.218736,0.856517 --1.41749 , 1.22693 , 3.34092 , 0.345051,-0.687434,-0.639041 --1.40102 , 1.23128 , 3.40695 , 0.0596025,0.868615,0.49189 --1.24223 , 1.16586 , 3.2914 , -0.161809,-0.955558,-0.246427 --1.27691 , 1.19568 , 3.42413 , -0.216074,-0.890447,-0.40052 --1.15086 , 1.1451 , 3.34103 , -0.356626,-0.407363,0.840758 --1.04035 , 1.1008 , 3.26963 , -0.6325,0.663731,0.399256 --1.02707 , 1.10664 , 3.339 , 0.819119,0.137465,-0.556909 --1.00806 , 1.11044 , 3.4003 , -0.874706,-0.193129,0.444513 --1.03241 , 1.13718 , 3.53563 , -0.438066,0.600452,0.668996 --1.0279 , 1.15059 , 3.631 , -0.492257,0.49676,0.714781 --0.949119 , 1.12184 , 3.60173 , 0.274555,0.343379,0.89817 --0.900576 , 1.10959 , 3.62097 , -0.847262,-0.323408,0.421373 --0.891168 , 1.12174 , 3.71616 , -0.470542,-0.653346,0.593068 --0.831492 , 1.10297 , 3.71724 , 0.545987,0.482188,-0.685123 --0.785387 , 1.09267 , 3.74294 , -0.029505,-0.367916,0.929391 --1.03451 , 1.2705 , 4.41926 , -0.787619,0.508037,0.348647 --0.995626 , 1.26891 , 4.49354 , -0.845173,0.300326,0.442139 --0.949963 , 1.26479 , 4.55863 , -0.551037,0.296063,0.780196 --0.893204 , 1.25319 , 4.5959 , 0.569175,-0.421444,-0.705992 --0.848357 , 1.24987 , 4.66896 , -0.576191,0.515961,0.633867 --0.831555 , 1.26834 , 4.82372 , -0.610813,0.165929,0.774193 --0.76616 , 1.25235 , 4.85009 , -0.0582043,-0.713201,-0.698539 --0.698036 , 1.23353 , 4.8661 , 0.208452,0.967177,-0.145316 --0.598545 , 1.19057 , 4.77785 , -0.549076,-0.833435,-0.0624568 --0.555731 , 1.19174 , 4.87524 , -0.399718,-0.805531,0.437431 --1.02754 , 1.65092 , 6.98664 , -0.768737,-0.238808,-0.593308 --0.802705 , 1.50994 , 6.50463 , 0.0127905,0.998606,0.0512063 --0.303016 , 1.08601 , 4.6877 , 0.0821665,-0.442149,0.89317 --0.219131 , 1.0468 , 4.59888 , -0.134018,-0.387764,0.911964 --0.272316 , 1.15744 , 5.23097 , -0.281284,0.12453,0.95151 --0.17791 , 1.11144 , 5.11189 , -0.811297,0.422232,-0.404372 --0.0821986 , 1.05771 , 4.95199 , 0.276944,-0.686084,0.672748 --0.210318 , 1.31842 , 6.43609 , -0.639639,-0.150211,-0.753856 --0.136049 , 1.32209 , 6.60844 , 0.045659,-0.542139,0.839047 --0.0563362 , 1.32121 , 6.7704 , -0.612586,-0.763046,0.206155 --2.66217 , 1.01431 , -1.36628 , -0.069229,0.187814,0.979762 --2.80261 , 1.05876 , -1.38566 , -0.0779468,0.189224,0.978835 --2.96066 , 1.10822 , -1.41209 , -0.0684574,0.178798,0.981501 --3.1119 , 1.15713 , -1.42793 , -0.053062,0.16572,0.984744 --3.28084 , 1.21129 , -1.44977 , -0.0770299,0.154374,0.985005 --3.46753 , 1.27089 , -1.47673 , -0.0981316,0.145846,0.984428 --3.66409 , 1.33317 , -1.50256 , -0.0958669,0.153505,0.983487 --3.8795 , 1.4015 , -1.53188 , -0.0815961,0.165648,0.982804 --4.11384 , 1.47608 , -1.56382 , -0.092789,0.153852,0.983727 --4.38463 , 1.56163 , -1.6067 , -0.088044,0.151059,0.984596 --4.6663 , 1.65188 , -1.64499 , -0.0937433,0.154773,0.983493 --4.99313 , 1.75503 , -1.6953 , 0.0900727,-0.131581,-0.987205 --5.33222 , 1.86268 , -1.73861 , -0.096561,0.134428,0.986207 --5.71725 , 1.98616 , -1.79086 , -0.0798097,0.150348,0.985407 --6.14179 , 2.12113 , -1.84506 , -0.0906735,0.145912,0.985134 --6.63972 , 2.27956 , -1.91444 , -0.0913414,0.144149,0.985331 --7.21352 , 2.46185 , -1.99486 , -0.0949255,0.127233,0.98732 --7.87281 , 2.67158 , -2.08569 , -0.0954111,0.0942123,0.99097 --8.65421 , 2.92029 , -2.19535 , -0.122376,0.0780376,0.989411 --9.5501 , 3.20602 , -2.31398 , -0.0859865,0.0932349,0.991924 --10.5983 , 3.54117 , -2.44731 , -0.113046,0.0552798,0.992051 --11.8735 , 3.94884 , -2.60868 , -0.112186,0.0889781,0.989696 --13.4884 , 4.46467 , -2.8166 , -0.0963449,0.0849434,0.991717 --15.5394 , 5.11984 , -3.07666 , 0.102132,-0.143274,-0.984399 --29.329 , 9.51323 , -4.93534 , 0.0252173,0.0851688,0.996047 --40.1981 , 13.092 , -5.60501 , -0.253388,0.966274,-0.045918 --40.5821 , 13.3226 , -4.91169 , 0.19016,-0.800355,0.568569 --41.2375 , 13.6429 , -4.24119 , -0.24901,0.765972,-0.59269 --51.5864 , 17.0916 , -4.59745 , -0.526513,-0.84202,0.117419 --42.5721 , 14.2999 , -2.83583 , -0.337411,0.910216,-0.240128 --42.6715 , 14.447 , -2.05775 , -0.61039,0.787434,-0.0858623 --43.1648 , 14.7248 , -1.29762 , -0.61039,0.787434,-0.0858622 --41.8911 , 14.4173 , -0.457439 , -0.61039,0.787434,-0.0858623 --42.7576 , 14.8207 , 0.300176 , -0.511072,0.201781,-0.835518 --45.3708 , 15.8208 , 1.09222 , -0.352415,0.512888,-0.782783 --47.1801 , 16.5607 , 1.96552 , 0.578999,-0.738135,0.346291 --13.0774 , 5.03694 , 2.0507 , -0.690883,0.597844,0.406527 --12.9065 , 5.01396 , 2.28602 , -0.390826,0.77439,0.49757 --12.7322 , 4.98898 , 2.51577 , 0.390827,-0.774389,-0.49757 --12.3112 , 4.87414 , 2.70845 , -0.224215,0.375822,0.899158 --10.3515 , 4.20435 , 2.65705 , -0.0702851,0.239486,0.968352 --7.16642 , 3.0785 , 2.32722 , 0.0667014,0.700853,0.71018 --3.88126 , 1.89808 , 1.85888 , -0.939756,-0.25461,-0.228105 --4.12113 , 1.99894 , 1.99266 , -0.961119,-0.178761,-0.210465 --4.40384 , 2.11758 , 2.14576 , 0.418934,-0.575211,0.702586 --4.89178 , 2.31374 , 2.36155 , -0.529848,-0.844897,0.073549 --4.42874 , 2.15462 , 2.34533 , -0.889409,0.34764,0.296814 --3.84205 , 1.94659 , 2.27649 , 0.90297,0.293981,0.313402 --3.85288 , 1.96293 , 2.36769 , 0.728566,0.49104,0.477569 --4.58545 , 2.25865 , 2.6951 , 0.249426,-0.565673,-0.786003 --4.18032 , 2.11629 , 2.6601 , -0.92512,-0.379644,-0.00487864 --4.21871 , 2.14597 , 2.77254 , -0.756239,-0.131529,-0.640939 --4.36853 , 2.22021 , 2.93118 , -0.902204,0.39272,-0.178323 --4.28045 , 2.20003 , 2.99996 , -0.824993,0.246088,-0.508751 --4.43236 , 2.27621 , 3.17054 , -0.531742,0.584572,-0.612801 --3.61517 , 1.96156 , 2.9087 , 0.866255,-0.076627,0.493691 --3.84165 , 2.06793 , 3.11039 , -0.402779,-0.820513,0.40562 --3.78642 , 2.05977 , 3.18264 , -0.2432,-0.436993,0.865963 --3.70491 , 2.04104 , 3.24043 , 0.160001,-0.402232,0.901448 --3.5569 , 1.99373 , 3.26019 , -0.648553,-0.22505,0.727139 --4.24907 , 2.30052 , 3.75514 , -0.599889,-0.42751,0.67629 --3.81278 , 2.13131 , 3.61268 , 0.47413,-0.862101,-0.178838 --3.74164 , 2.11678 , 3.67831 , 0.463148,-0.883957,-0.0641372 --3.74859 , 2.13602 , 3.79319 , -0.799447,0.541451,0.260221 --4.25098 , 2.37232 , 4.24605 , -0.122908,-0.991992,0.0290886 --3.7542 , 2.17221 , 4.02688 , -0.687289,0.698319,-0.199963 --3.73831 , 2.18315 , 4.13413 , 0.790693,-0.438926,0.426789 --4.65711 , 2.61338 , 4.95344 , 0.0173164,-0.347352,0.937575 --4.50538 , 2.56677 , 4.98606 , 0.551424,0.201566,-0.809508 --4.36868 , 2.52652 , 5.02631 , -0.89384,-0.109463,0.43482 --4.35472 , 2.54271 , 5.16667 , -0.657816,-0.532259,0.532896 --5.63293 , 3.16252 , 6.45037 , -0.0238431,0.179646,0.983442 --4.16454 , 2.49899 , 5.30984 , 0.654512,0.549017,-0.519802 --5.25366 , 3.04183 , 6.50413 , -0.0983761,0.00548474,0.995134 --5.37225 , 3.12936 , 6.82501 , -0.730229,0.373222,-0.572251 --1.60237 , 1.32218 , 3.18907 , 0.680623,0.0275716,-0.732115 --1.57099 , 1.31781 , 3.23588 , -0.706442,-0.160533,0.689325 --1.53198 , 1.31101 , 3.27506 , -0.672956,-0.160611,0.722035 --1.48676 , 1.30004 , 3.30661 , 0.598235,0.196363,-0.776889 --1.43407 , 1.28551 , 3.32995 , -0.251587,0.357213,0.899502 --1.28568 , 1.22151 , 3.23417 , 0.286194,-0.0167748,0.958025 --1.19455 , 1.18573 , 3.20093 , 0.104415,0.878426,0.466332 --1.05956 , 1.12589 , 3.10414 , 0.362319,-0.424902,-0.829568 --1.04563 , 1.12979 , 3.16494 , -0.860193,0.0316599,0.508985 --1.14543 , 1.19694 , 3.38975 , -0.0823842,-0.919369,0.384674 --1.01915 , 1.14068 , 3.29469 , 0.495816,-0.486025,-0.719685 --0.979396 , 1.13164 , 3.32395 , 0.618059,-0.719082,-0.317686 --0.960823 , 1.1334 , 3.38507 , -0.530799,0.755704,-0.38362 --1.0331 , 1.19006 , 3.60227 , -0.0496777,-0.138342,0.989138 --0.969395 , 1.16829 , 3.59878 , 0.130838,-0.626636,-0.768251 --0.939518 , 1.16573 , 3.65257 , -0.655792,0.286075,0.69864 --0.89858 , 1.15687 , 3.68917 , 0.835331,0.214058,-0.50636 --1.1568 , 1.33643 , 4.31735 , -0.909129,-0.123233,0.397867 --0.786152 , 1.12065 , 3.69956 , -0.029505,-0.367916,0.929391 --1.02327 , 1.29386 , 4.33753 , -0.644942,0.0807526,0.759953 --0.998306 , 1.30014 , 4.43819 , -0.778929,0.496234,0.383435 --0.985031 , 1.31568 , 4.57464 , -0.852569,0.144955,0.50211 --0.916795 , 1.29486 , 4.58617 , -0.463408,0.010632,0.886081 --0.855893 , 1.27826 , 4.6144 , 0.56647,-0.384794,-0.728729 --0.735832 , 1.21695 , 4.47745 , 0.602894,0.716942,0.350019 --0.69925 , 1.21796 , 4.5666 , 0.513307,-0.799413,-0.312177 --0.716204 , 1.26236 , 4.8314 , -0.0747969,-0.878601,0.471663 --0.640313 , 1.23467 , 4.81895 , 0.398008,0.905499,0.147176 --0.621359 , 1.25523 , 5.00156 , -0.247747,-0.750065,0.613208 --1.10884 , 1.72956 , 7.11669 , -0.934765,-0.0404768,-0.352954 --1.0594 , 1.74948 , 7.36812 , -0.924879,-0.0379527,-0.378363 --0.836626 , 1.60478 , 6.89605 , -0.604372,0.422555,-0.675412 --0.26132 , 1.08473 , 4.6655 , -0.222603,-0.307823,0.925037 --0.207506 , 1.07435 , 4.72027 , -0.758118,0.0274491,0.651539 --0.234383 , 1.1609 , 5.2474 , -0.630274,0.325957,0.704633 --0.122302 , 1.08644 , 5.00203 , 0.748158,-0.379645,0.544177 --0.0482288 , 1.05669 , 4.96739 , -0.0320306,0.616358,-0.786814 --0.194573 , 1.36021 , 6.7071 , -0.276031,0.0265245,0.960783 --0.0912963 , 1.3165 , 6.6451 , -0.600034,-0.751763,0.273518 --2.85641 , 1.19042 , -1.4232 , -0.089528,0.139117,0.986221 --2.99718 , 1.2415 , -1.43638 , -0.0635627,0.134512,0.988871 --3.14768 , 1.29481 , -1.45039 , -0.0621598,0.140042,0.988193 --3.30745 , 1.35238 , -1.46511 , 0.0829158,-0.138688,-0.986859 --3.50114 , 1.42035 , -1.49551 , -0.109331,0.149136,0.982754 --3.73831 , 1.5005 , -1.54454 , 0.106771,-0.160824,-0.981191 --3.96037 , 1.57946 , -1.57614 , 0.082557,-0.154487,-0.98454 --4.2026 , 1.66407 , -1.6097 , 0.0879516,-0.148107,-0.985053 --4.45466 , 1.7529 , -1.6397 , 0.0849302,-0.140631,-0.986413 --4.75933 , 1.85939 , -1.68799 , -0.0864924,0.142964,0.985941 --5.05044 , 1.9633 , -1.71731 , -0.0943842,0.134382,0.986425 --5.44773 , 2.10103 , -1.78645 , -0.100507,0.1323,0.986101 --5.82972 , 2.23637 , -1.83365 , -0.0857069,0.0888211,0.992353 --6.29474 , 2.39941 , -1.90224 , -0.125651,0.0424422,0.991166 --6.79909 , 2.57674 , -1.96917 , -0.124942,0.0586918,0.990427 --7.39513 , 2.78685 , -2.05353 , -0.0980693,0.0380575,0.994452 --8.1207 , 3.04061 , -2.16335 , -0.0928261,0.0137908,0.995587 --8.95961 , 3.33457 , -2.28566 , -0.128645,0.0269146,0.991325 --9.88554 , 3.66122 , -2.40508 , -0.10605,0.0431743,0.993423 --11.0436 , 4.06902 , -2.56258 , -0.107825,0.0569017,0.99254 --12.4637 , 4.56955 , -2.75347 , 0.0411112,0.0160971,-0.999025 --14.1026 , 5.15024 , -2.951 , -0.243273,0.0110224,0.969895 --16.91 , 6.13137 , -3.3844 , 0.102132,-0.143274,-0.984399 --26.5215 , 9.49897 , -4.80068 , -0.0788197,0.217925,0.972778 --26.5447 , 9.57973 , -4.29704 , -0.0788197,0.217925,0.972778 --37.8712 , 13.5703 , -5.81309 , -0.414156,0.504833,0.757376 --37.9082 , 13.6856 , -5.10385 , -0.414157,0.504834,0.757375 --38.0645 , 13.8434 , -4.41292 , -0.414156,0.504833,0.757376 --38.0874 , 13.9535 , -3.70158 , -0.0230718,0.323431,0.94597 --41.0712 , 15.2296 , -2.53362 , -0.710727,0.546937,-0.44241 --41.4635 , 15.4812 , -1.79428 , -0.766435,0.574457,-0.287361 --41.995 , 15.8974 , -0.265472 , -0.738267,0.635377,-0.226405 --44.5523 , 16.9551 , 0.486273 , 0.549253,0.0902758,0.830766 --44.5902 , 17.0886 , 1.31766 , 0.549253,0.0902758,0.830766 --44.6617 , 17.2353 , 2.15279 , 0.618285,0.0895393,0.780837 --45.3453 , 17.6129 , 3.01941 , 0.79243,-0.35438,0.496457 --12.392 , 5.2007 , 1.83525 , -0.624752,0.776758,0.0795725 --12.2822 , 5.19316 , 2.06695 , -0.750452,0.630946,0.196795 --12.3453 , 5.2514 , 2.31285 , -0.837677,0.540924,0.0754926 --11.6998 , 5.03542 , 2.47869 , -0.193096,0.283944,0.939196 --11.58 , 5.02188 , 2.69348 , 0.302093,-0.17708,-0.936687 --3.98056 , 2.06158 , 1.73808 , -0.918907,0.0203196,-0.39395 --3.90969 , 2.04561 , 1.81162 , -0.918907,0.0203196,-0.39395 --3.92873 , 2.06566 , 1.90076 , -0.942084,0.151174,-0.299372 --3.93739 , 2.08087 , 1.98908 , -0.914404,0.186503,-0.35928 --3.93518 , 2.09305 , 2.07582 , 0.972016,0.154477,0.176979 --4.05792 , 2.15555 , 2.19502 , -0.828604,0.0417399,-0.558277 --4.348 , 2.28809 , 2.36581 , -0.626564,0.77147,-0.110685 --4.23256 , 2.2539 , 2.43014 , 0.534506,-0.745438,0.398279 --4.39875 , 2.3377 , 2.57984 , 0.499838,-0.807432,0.313395 --4.39506 , 2.35026 , 2.68027 , -0.29726,0.71683,0.630706 --4.4247 , 2.37793 , 2.79352 , -0.598017,0.642711,0.478851 --4.21627 , 2.30446 , 2.82009 , -0.884928,-0.416329,-0.208742 --4.18204 , 2.30382 , 2.90861 , 0.348186,0.301532,0.887607 --4.78842 , 2.58093 , 3.26669 , -0.726086,-0.0868324,0.682099 --4.44913 , 2.45012 , 3.23404 , -0.836748,0.525651,0.15344 --4.45817 , 2.47023 , 3.35063 , -0.882361,0.396827,-0.252917 --3.99788 , 2.28267 , 3.23958 , -0.284685,-0.345128,0.894339 --4.44512 , 2.4966 , 3.57445 , -0.726776,0.373715,0.57631 --3.71734 , 2.18736 , 3.30277 , -0.34386,0.684221,-0.643118 --3.5943 , 2.14708 , 3.33666 , -0.854894,-0.466553,0.226901 --3.69688 , 2.20818 , 3.49859 , -0.516234,0.852222,0.0849695 --3.50943 , 2.13691 , 3.49042 , -0.692056,-0.463064,0.553743 --3.51179 , 2.15311 , 3.59616 , 0.072674,-0.993101,0.0920258 --3.69014 , 2.25244 , 3.82142 , -0.850525,0.524422,0.0398649 --5.28961 , 3.0205 , 5.04071 , 0.0117799,-0.154815,0.987873 --5.11136 , 2.9591 , 5.07423 , 0.0117799,-0.154815,0.987873 --4.06674 , 2.48221 , 4.4539 , 0.640955,-0.513551,0.570475 --4.94197 , 2.92484 , 5.26861 , 0.287188,0.759806,-0.583282 --4.67747 , 2.81965 , 5.21936 , 0.22711,0.735355,-0.638493 --4.32375 , 2.66809 , 5.08361 , -0.839029,-0.25519,0.48053 --4.3298 , 2.6932 , 5.24308 , 0.774435,0.392722,-0.496005 --4.27639 , 2.68933 , 5.35412 , 0.573579,0.431512,-0.696279 --4.19923 , 2.67439 , 5.44526 , 0.573579,0.431512,-0.696279 --5.2527 , 3.23584 , 6.63503 , -0.546492,-0.383446,0.744524 --5.08131 , 3.17784 , 6.67169 , 0.442621,-0.429789,0.786999 --1.58975 , 1.38709 , 3.22829 , 0.693696,-0.042865,-0.718991 --1.55126 , 1.37854 , 3.26855 , 0.650839,-0.0938589,-0.753392 --1.51271 , 1.3698 , 3.30793 , 0.588202,-0.153036,-0.794102 --1.46697 , 1.35666 , 3.3398 , 0.0487609,0.521213,0.852032 --1.36041 , 1.31099 , 3.29761 , 0.470622,0.194854,0.86055 --1.13334 , 1.19829 , 3.09648 , 0.220215,0.732805,0.643819 --1.18935 , 1.24055 , 3.24856 , -0.118056,-0.989088,-0.0881306 --1.123 , 1.21562 , 3.2431 , 0.25355,-0.936692,-0.241497 --1.06298 , 1.19352 , 3.24372 , -0.815294,-0.254749,0.519998 --1.04641 , 1.19593 , 3.30557 , -0.931338,-0.211507,0.296435 --1.04864 , 1.21069 , 3.39941 , -0.841125,-0.519612,0.15004 --1.0492 , 1.22415 , 3.49408 , 0.543421,-0.831652,-0.114232 --1.05593 , 1.24274 , 3.60605 , 0.469712,-0.529696,-0.706253 --0.978419 , 1.20952 , 3.57903 , 0.0853042,0.408136,0.908927 --0.92612 , 1.19177 , 3.59146 , -0.845934,0.420108,0.328491 --0.908852 , 1.19749 , 3.67008 , 0.552511,-0.758068,-0.346503 --0.898982 , 1.20764 , 3.76628 , 0.532794,0.335859,-0.776743 --0.840264 , 1.18511 , 3.76834 , -0.266942,-0.449898,0.852252 --0.77643 , 1.16129 , 3.76018 , 0.183062,-0.333107,0.924948 --1.02229 , 1.34859 , 4.43543 , -0.692597,0.707725,0.139408 --0.979314 , 1.34217 , 4.50144 , 0.834438,-0.223581,-0.503711 --0.928129 , 1.32992 , 4.54914 , -0.704688,-0.0160374,0.709336 --0.868696 , 1.31172 , 4.57803 , -0.310104,0.160187,0.93711 --0.878821 , 1.34693 , 4.79649 , -0.888536,-0.132978,0.439113 --0.675104 , 1.21776 , 4.42218 , 0.275533,0.616382,0.737668 --0.808888 , 1.35419 , 5.0266 , -0.158281,-0.813615,0.559445 --0.623157 , 1.23493 , 4.67349 , 0.333307,-0.931598,0.145026 --0.597464 , 1.24595 , 4.81815 , -0.461978,-0.874374,-0.14848 --0.569789 , 1.25746 , 4.97262 , -0.309013,0.75084,-0.583738 --1.12556 , 1.81782 , 7.44119 , -0.850637,0.0176081,-0.525458 --0.904058 , 1.67072 , 6.99157 , -0.768737,-0.238807,-0.593309 --0.280841 , 1.1004 , 4.62648 , 0.0821665,-0.442149,0.89317 --0.21838 , 1.07908 , 4.63379 , -0.161251,-0.482731,0.860796 --0.239734 , 1.15222 , 5.09273 , -0.901816,-0.202362,-0.381808 --0.195434 , 1.15901 , 5.25443 , 0.511794,-0.849716,-0.126685 --0.0803969 , 1.07558 , 4.96937 , 0.141721,-0.69754,0.702391 --0.00963603 , 1.04543 , 4.94403 , 0.0479572,-0.624407,0.779625 --0.14094 , 1.34253 , 6.67582 , 0.371509,-0.810076,0.453605 --0.0520282 , 1.3192 , 6.74055 , 0.618924,0.76353,-0.184272 --2.59898 , 1.21021 , -1.40017 , -0.0654352,0.128425,0.989558 --2.72845 , 1.26032 , -1.41465 , 0.0850866,-0.1133,-0.989911 --2.86617 , 1.31424 , -1.43072 , -0.0846289,0.109995,0.990323 --3.01432 , 1.37152 , -1.44811 , -0.0757993,0.121686,0.98967 --3.18692 , 1.43773 , -1.47705 , -0.078464,0.134447,0.987809 --3.36212 , 1.50471 , -1.5003 , 0.0922558,-0.142188,-0.985531 --3.56287 , 1.58126 , -1.53326 , 0.118292,-0.149319,-0.981688 --3.78226 , 1.66486 , -1.56972 , 0.0933932,-0.156924,-0.983185 --4.01118 , 1.75344 , -1.6037 , -0.0816044,0.137616,0.987118 --4.25911 , 1.84853 , -1.63912 , -0.0849213,0.124838,0.988536 --4.52564 , 1.95223 , -1.67551 , -0.0907541,0.118438,0.988806 --4.82956 , 2.06871 , -1.72035 , -0.0826571,0.102655,0.991277 --5.13427 , 2.18758 , -1.75458 , -0.105802,0.0963406,0.989709 --5.54558 , 2.34379 , -1.82739 , -0.106339,0.068022,0.992 --5.93452 , 2.49462 , -1.87408 , -0.0514805,-0.0282711,0.998274 --6.41321 , 2.67845 , -1.94489 , 0.143865,0.0447773,-0.988584 --6.93918 , 2.88113 , -2.0168 , -0.15444,-0.0242663,0.987704 --7.53909 , 3.11287 , -2.09779 , -0.124654,-0.0190388,0.992018 --7.88379 , 3.25828 , -2.06195 , -0.117239,-0.0193438,0.992915 --8.56982 , 3.52607 , -2.13284 , -0.151752,0.026172,0.988072 --9.56557 , 3.90843 , -2.27991 , 0.137231,-0.0469865,-0.989424 --10.8282 , 4.39279 , -2.47196 , -0.10708,0.0481463,0.993084 --12.3413 , 4.97603 , -2.68926 , 0.0323491,-0.166638,0.985487 --13.8805 , 5.5762 , -2.85623 , -0.206268,-0.211353,0.955397 --24.6496 , 9.66499 , -4.80335 , -0.129011,0.293683,0.947157 --25.4989 , 10.051 , -4.50451 , -0.0882368,0.154216,0.984089 --37.9304 , 14.9202 , -5.69888 , -0.697268,0.330788,0.635922 --38.1009 , 15.087 , -5.00218 , -0.697268,0.330788,0.635922 --13.0415 , 5.5568 , -0.573618 , 0.988194,0.152904,0.00961787 --13.0443 , 5.59308 , -0.320937 , 0.988162,0.152716,0.0145869 --40.5713 , 16.4642 , -2.31698 , 0.722534,-0.654765,0.221873 --13.0742 , 5.67541 , 0.182149 , 0.988008,0.153468,0.0169487 --41.6762 , 17.1198 , -0.836043 , -0.885873,0.443358,-0.13661 --45.0109 , 18.5696 , -0.136399 , -0.59843,-0.0207459,-0.800906 --40.6519 , 16.9266 , 0.743708 , -0.892349,0.433396,-0.12602 --40.4649 , 16.9583 , 1.5102 , -0.919357,0.376252,0.114965 --12.384 , 5.57036 , 1.42796 , 0.987401,-0.03634,-0.154006 --12.2801 , 5.56221 , 1.6648 , 0.996427,0.0280793,-0.0796561 --12.2752 , 5.59399 , 1.9051 , 0.996427,0.0280793,-0.0796561 --12.2559 , 5.6201 , 2.14517 , 0.99315,-0.0861566,-0.0789309 --12.2884 , 5.6676 , 2.39115 , -0.972226,0.110934,0.206082 --12.2255 , 5.67478 , 2.62765 , 0.973419,-0.141507,-0.180085 --5.22609 , 2.73162 , 1.8638 , 0.0168381,0.300937,0.953495 --5.13373 , 2.70855 , 1.95925 , -0.420835,-0.0898936,0.902672 --5.01256 , 2.67153 , 2.04715 , -0.420834,-0.0898932,0.902672 --3.87164 , 2.19197 , 1.92438 , -0.94145,0.308119,-0.136875 --4.3463 , 2.41148 , 2.11656 , 0.577203,-0.6918,0.433877 --4.10045 , 2.31726 , 2.15369 , 0.568422,0.0902606,0.817771 --4.13089 , 2.3436 , 2.25443 , 0.241754,0.690028,0.682214 --4.23821 , 2.40455 , 2.37955 , -0.16051,0.986693,0.0259656 --4.11477 , 2.36228 , 2.43982 , 0.605616,-0.710722,0.357917 --4.23512 , 2.4307 , 2.57524 , 0.490413,-0.840555,0.230136 --4.28294 , 2.46675 , 2.69192 , -0.513529,0.816501,-0.263846 --4.24223 , 2.4622 , 2.77944 , -0.705025,0.703276,0.0913332 --4.32879 , 2.51618 , 2.91602 , -0.530176,0.532663,-0.659685 --4.34415 , 2.53809 , 3.02864 , -0.501012,0.815733,-0.289079 --4.48362 , 2.61817 , 3.19742 , -0.950561,0.189293,-0.246176 --4.25029 , 2.525 , 3.20439 , -0.475906,0.827645,0.297518 --4.22658 , 2.52902 , 3.3028 , -0.475906,0.827645,0.297518 --3.88832 , 2.38363 , 3.24417 , 0.525491,0.29071,-0.799592 --3.51399 , 2.21917 , 3.15193 , -0.0985331,-0.475084,0.874406 --3.6928 , 2.31899 , 3.34857 , -0.640999,-0.167615,0.749016 --3.68211 , 2.32938 , 3.44693 , -0.946268,0.256861,0.196467 --3.56705 , 2.28759 , 3.48427 , 0.809709,-0.0467891,-0.584963 --3.59365 , 2.31525 , 3.60617 , -0.803315,-0.574753,0.156025 --3.39299 , 2.23037 , 3.58365 , -0.84912,-0.0739814,0.522994 --3.59149 , 2.34529 , 3.82455 , -0.542144,0.839664,-0.0323253 --3.44371 , 2.2864 , 3.83375 , 0.155783,-0.753066,0.639237 --3.62393 , 2.39368 , 4.0799 , 0.783239,-0.569169,0.250168 --3.65825 , 2.42843 , 4.22676 , -0.79477,0.347621,-0.497494 --4.44295 , 2.85201 , 4.97666 , 0.586512,-0.535151,0.607962 --6.10386 , 3.73899 , 6.50342 , -0.582668,0.337008,-0.739542 --4.42875 , 2.88831 , 5.27511 , 0.637951,0.629042,-0.444212 --4.34035 , 2.86366 , 5.35819 , 0.637951,0.629042,-0.444212 --4.21051 , 2.81727 , 5.40116 , -0.446871,-0.39739,0.801491 --5.10191 , 3.3214 , 6.42208 , -0.492903,-0.28617,0.821677 --3.93661 , 2.71514 , 5.46406 , 0.148777,0.365893,-0.918688 --1.60016 , 1.45285 , 3.21369 , 0.693696,-0.0428649,-0.718991 --1.5371 , 1.4285 , 3.22738 , 0.281384,-0.142772,-0.948915 --1.49337 , 1.41602 , 3.25998 , -0.0410804,0.609474,0.791741 --1.39954 , 1.37399 , 3.23535 , 0.16397,0.549408,0.819308 --1.37363 , 1.3709 , 3.2869 , 0.16397,0.549408,0.819308 --1.09349 , 1.22052 , 3.02329 , 0.362319,-0.424903,-0.829568 --1.10505 , 1.23803 , 3.11417 , -0.966164,-0.250696,-0.0606601 --1.21003 , 1.31185 , 3.33453 , -0.573684,-0.696896,-0.430375 --1.04997 , 1.22741 , 3.19972 , -0.215578,-0.937409,-0.273477 --1.01271 , 1.21716 , 3.2303 , -0.289017,-0.757957,0.584782 --0.953957 , 1.19284 , 3.22887 , -0.118492,0.967993,0.221244 --0.942792 , 1.198 , 3.2975 , 0.834592,-0.177345,-0.521541 --0.978328 , 1.23372 , 3.44755 , 0.278164,-0.848427,0.450329 --0.904137 , 1.19907 , 3.41979 , -0.880427,0.47347,-0.0259746 --0.919619 , 1.22406 , 3.54713 , -0.70812,0.673324,0.212607 --0.909069 , 1.23214 , 3.63418 , 0.465011,-0.792025,-0.395551 --0.966147 , 1.28627 , 3.85741 , 0.152587,-0.679529,0.717605 --0.820168 , 1.20385 , 3.69016 , -0.638656,0.142117,0.756255 --0.800407 , 1.20684 , 3.76877 , -0.84114,-0.394326,0.370122 --0.706576 , 1.15788 , 3.6904 , 0.13441,-0.133907,0.981836 --1.0455 , 1.42223 , 4.59551 , -0.533939,-0.675423,0.508638 --0.945206 , 1.37212 , 4.5295 , 0.561241,-0.664888,-0.492882 --0.915083 , 1.3741 , 4.63079 , 0.244076,-0.190198,-0.950921 --0.749729 , 1.27166 , 4.38008 , -0.433158,-0.555416,-0.709851 --0.690595 , 1.24998 , 4.39689 , -0.35927,-0.429163,-0.828701 --0.618643 , 1.21833 , 4.37589 , 0.379858,0.101089,0.919505 --0.548514 , 1.18676 , 4.35309 , 0.409863,0.32533,0.852158 --0.681348 , 1.33227 , 5.00744 , -0.121591,-0.634992,0.76289 --0.609923 , 1.30433 , 5.01383 , -0.219502,-0.671522,0.707726 --0.529498 , 1.26711 , 4.98115 , -0.333657,0.605315,-0.72268 --0.943529 , 1.71424 , 6.97181 , -0.768737,-0.238808,-0.593308 --0.314092 , 1.13318 , 4.65361 , 0.11874,-0.583338,0.803503 --0.252146 , 1.11009 , 4.66189 , -0.000667572,-0.59491,0.803792 --0.197339 , 1.09441 , 4.70755 , -0.390731,-0.816984,-0.424107 --0.228289 , 1.18287 , 5.2542 , -0.630273,0.325957,0.704633 --0.127024 , 1.11592 , 5.06759 , -0.71501,0.328571,-0.617091 --0.052193 , 1.07993 , 5.02404 , -0.530925,-0.697311,0.481535 --0.202869 , 1.39053 , 6.80283 , -0.592217,-0.789528,0.161011 --0.108688 , 1.35606 , 6.83028 , 0.416487,0.889926,-0.185932 --2.4796 , 1.27373 , -1.39205 , -0.0650882,0.0999971,0.992857 --2.59886 , 1.32509 , -1.40349 , -0.0650882,0.0999971,0.992857 --2.73545 , 1.38227 , -1.42278 , -0.0886854,0.104141,0.990601 --2.8803 , 1.44333 , -1.44335 , -0.0878424,0.123689,0.988425 --3.0426 , 1.51055 , -1.47031 , 0.0955954,-0.128189,-0.987132 --3.21424 , 1.58217 , -1.49732 , 0.0874595,-0.142194,-0.985967 --3.39524 , 1.65828 , -1.52399 , 0.109303,-0.132849,-0.985091 --3.61876 , 1.75035 , -1.57017 , 0.118912,-0.128277,-0.984584 --3.82786 , 1.83829 , -1.59872 , -0.0878266,0.101006,0.991002 --4.06366 , 1.93657 , -1.63468 , -0.100171,0.0736035,0.992244 --4.31707 , 2.04316 , -1.67188 , -0.114611,0.0842269,0.989833 --4.59909 , 2.16209 , -1.7142 , -0.107114,0.0827683,0.990796 --4.90739 , 2.29113 , -1.75942 , -0.0998279,0.084666,0.991396 --5.24454 , 2.43321 , -1.80666 , -0.113029,0.0545904,0.992091 --5.60893 , 2.58724 , -1.8542 , 0.0720194,0.0216412,-0.997168 --5.83884 , 2.692 , -1.82653 , -0.027166,-0.0227734,0.999371 --6.14643 , 2.8275 , -1.82454 , -0.0866766,-0.0716317,0.993658 --6.63032 , 3.03197 , -1.88313 , -0.149704,-0.0309244,0.988247 --7.23945 , 3.28747 , -1.97203 , 0.13933,-0.0161952,-0.990114 --8.00256 , 3.60678 , -2.09441 , 0.108373,-0.0418395,-0.99323 --8.80561 , 3.94553 , -2.20114 , -0.121917,0.0590732,0.990781 --9.87008 , 4.39126 , -2.36292 , 0.128825,-0.0789873,-0.988517 --11.1642 , 4.93396 , -2.55455 , -0.12161,0.0820767,0.989179 --12.7165 , 5.58703 , -2.77092 , 0.109028,-0.0939835,0.989586 --12.9597 , 5.75674 , -2.31414 , 0.109028,-0.0939835,0.989586 --12.9983 , 5.80809 , -2.06198 , -0.149955,-0.982351,0.111805 --13.034 , 5.85884 , -1.80927 , 0.69095,0.722781,0.0132496 --38.0346 , 16.2352 , -6.32885 , -0.697268,0.330788,0.635922 --38.0932 , 16.3604 , -5.6026 , -0.697268,0.330788,0.635922 --14.0825 , 6.40402 , -1.19364 , 0.6493,0.701484,-0.29382 --13.1058 , 6.03102 , -0.786038 , 0.987565,0.156346,0.0164678 --13.1194 , 6.07176 , -0.529824 , 0.987361,0.158421,0.00470288 --13.1208 , 6.10758 , -0.272618 , 0.987944,0.154418,0.0110861 --13.1361 , 6.14975 , -0.0166482 , 0.987102,0.159328,0.0156282 --13.1375 , 6.18557 , 0.240558 , 0.987146,0.158788,0.0181248 --13.1631 , 6.23245 , 0.49675 , 0.987146,0.158788,0.0181248 --44.4271 , 20.0459 , 0.955371 , -0.27239,0.107186,0.956198 --40.8922 , 18.7073 , 2.53135 , 0.950319,-0.240944,-0.197077 --12.4057 , 6.07122 , 1.74956 , -0.935172,0.354123,-0.00701509 --12.3619 , 6.08461 , 1.9932 , -0.978632,-0.0124724,0.20524 --12.1596 , 6.02709 , 2.22119 , 0.975077,-0.0924186,-0.201703 --10.8858 , 5.48107 , 2.32181 , -0.617873,0.751146,-0.232406 --12.0356 , 6.03776 , 2.69447 , -0.551111,0.327536,0.767461 --11.1491 , 5.66328 , 2.8047 , 0.376182,-0.411943,0.829934 --11.0803 , 5.66291 , 3.02196 , -0.478548,0.522304,-0.705826 --3.91785 , 2.35563 , 1.88295 , -0.570638,0.317199,-0.757468 --3.93513 , 2.37578 , 1.97466 , 0.53631,-0.48272,0.692353 --3.88834 , 2.36579 , 2.05338 , 0.53631,-0.48272,0.692353 --4.0701 , 2.46402 , 2.18818 , 0.773634,-0.356761,0.523652 --4.97538 , 2.90921 , 2.52828 , 0.988876,0.0587001,-0.136671 --8.71049 , 4.71799 , 3.73539 , 0.324298,-0.400587,0.856948 --8.53523 , 4.66015 , 3.87375 , 0.352447,-0.528344,0.772421 --8.84164 , 4.83498 , 4.16812 , -0.0909381,0.473641,-0.87601 --4.84454 , 2.90948 , 2.94439 , -0.763326,-0.45456,0.459031 --4.08552 , 2.5515 , 2.77403 , -0.845953,0.416562,-0.332926 --4.16175 , 2.60307 , 2.90627 , 0.740958,-0.433976,0.512491 --4.30268 , 2.68776 , 3.07019 , 0.983328,0.161869,0.0828549 --4.25567 , 2.67983 , 3.15905 , -0.821545,-0.494841,-0.283189 --4.15874 , 2.64608 , 3.22365 , -0.885761,-0.452821,0.101889 --4.36301 , 2.76457 , 3.43432 , 0.969499,0.216018,0.115796 --4.12459 , 2.65898 , 3.42803 , 0.163185,0.855919,-0.490687 --3.90511 , 2.56132 , 3.42214 , 0.550502,0.691667,-0.467488 --3.63145 , 2.43479 , 3.37725 , -0.946268,0.256861,0.196467 --3.51811 , 2.39046 , 3.41555 , 0.761766,0.331676,-0.55651 --3.58424 , 2.43908 , 3.56081 , -0.9304,0.362441,-0.0547004 --3.66166 , 2.49533 , 3.71924 , -0.732363,-0.389265,0.558675 --3.58407 , 2.46971 , 3.77963 , -0.708821,-0.508887,0.488474 --3.38454 , 2.37824 , 3.75441 , 0.573189,0.685751,-0.448553 --3.4037 , 2.4035 , 3.87864 , -0.861681,-0.46225,0.209357 --3.52878 , 2.4873 , 4.08763 , -0.90501,-0.166892,-0.391285 --3.46831 , 2.47064 , 4.16066 , -0.858104,-0.000640195,-0.513475 --4.13268 , 2.85418 , 4.82588 , 0.728808,-0.11477,0.675031 --5.85588 , 3.83274 , 6.43596 , -0.112891,-0.62706,0.770747 --6.1974 , 4.05331 , 6.94444 , -0.121536,0.902537,-0.413105 --6.16247 , 4.06386 , 7.13842 , -0.097291,0.810274,-0.577919 --8.50837 , 5.43404 , 9.59879 , 0.0748753,-0.27088,0.959697 --8.20199 , 5.30163 , 9.62037 , 0.0748753,-0.27088,0.959697 --3.84327 , 2.81713 , 5.48467 , -0.0239302,0.0742915,0.996949 --3.58914 , 2.69068 , 5.38137 , 0.375935,0.282635,0.882491 --8.50587 , 5.61893 , 10.9596 , -0.126804,-0.48236,0.866747 --3.19856 , 2.50429 , 5.26867 , -0.454108,0.405283,0.79343 --1.33629 , 1.40319 , 3.21866 , 0.195256,0.431395,0.88078 --1.31056 , 1.399 , 3.26973 , 0.195256,0.431394,0.88078 --1.08747 , 1.27396 , 3.07026 , 0.36232,-0.424902,-0.829568 --1.07055 , 1.27363 , 3.12433 , -0.00532166,0.995009,0.0996434 --0.996287 , 1.23813 , 3.10273 , -0.881715,-0.0506623,0.469054 --0.945223 , 1.2164 , 3.10969 , -0.693949,0.187952,0.69506 --1.02002 , 1.27602 , 3.30271 , -0.157705,-0.987137,-0.0262459 --1.75063 , 1.76426 , 4.52031 , -0.77433,-0.578518,0.256378 --1.62173 , 1.69851 , 4.45359 , 0.884778,0.335244,-0.323697 --0.90907 , 1.24045 , 3.40062 , 0.140182,0.511391,-0.847838 --0.873707 , 1.22988 , 3.43751 , -0.979516,0.0111861,0.201055 --0.879391 , 1.248 , 3.54852 , 0.623373,-0.714498,-0.317645 --1.05527 , 1.38597 , 3.9884 , 0.973976,-0.10261,0.202095 --0.820885 , 1.23668 , 3.65504 , -0.195262,0.867441,0.457622 --1.15082 , 1.49166 , 4.4548 , -0.810198,-0.357601,0.464436 --0.801465 , 1.25566 , 3.85593 , -0.351581,0.7002,-0.621379 --1.0443 , 1.45652 , 4.53934 , -0.693466,-0.621579,0.364342 --1.01908 , 1.4608 , 4.65095 , -0.0869887,-0.369286,0.925236 --0.916808 , 1.40515 , 4.57575 , -0.50556,0.774776,0.379646 --0.813425 , 1.34778 , 4.48859 , 0.556319,-0.815621,-0.158971 --0.709914 , 1.28897 , 4.38952 , 0.249363,0.263729,0.931808 --0.648567 , 1.2627 , 4.39694 , 0.132946,0.196819,0.971384 --0.56645 , 1.21868 , 4.33858 , 0.475812,0.099869,0.873859 --0.56554 , 1.24599 , 4.53724 , -0.965701,0.213997,0.147062 --0.641383 , 1.34624 , 5.02628 , -0.219502,-0.671523,0.707726 --0.567723 , 1.31364 , 5.023 , -0.26382,0.736313,-0.623091 --1.03478 , 1.81339 , 7.16855 , 0.718092,0.683113,0.133044 --0.850754 , 1.68747 , 6.8421 , -0.825283,0.145312,-0.545703 --0.278185 , 1.13629 , 4.66082 , -0.0671466,-0.261003,0.963 --0.21328 , 1.10633 , 4.64971 , 0.013193,-0.828344,0.560065 --0.171193 , 1.1035 , 4.76234 , -0.897679,0.117009,0.424832 --0.194879 , 1.18627 , 5.29025 , 0.511794,-0.849716,-0.126684 --0.0769014 , 1.09104 , 4.97713 , 0.0814276,-0.530197,0.843956 --0.00634468 , 1.05484 , 4.94267 , -0.0838298,-0.761808,0.642356 --0.142935 , 1.36025 , 6.72337 , -0.313565,0.155471,0.936753 -0.0158419 , 1.19794 , 6.0545 , -0.0173761,-0.817288,0.575967 --2.38346 , 1.33963 , -1.40028 , -0.0519616,0.109397,0.992639 --2.48608 , 1.38789 , -1.40166 , -0.0519616,0.109397,0.992639 --2.61939 , 1.44892 , -1.42384 , -0.0930675,0.124094,0.987896 --2.7612 , 1.51285 , -1.4472 , -0.0980163,0.133215,0.986228 --2.91325 , 1.58121 , -1.4716 , -0.0833544,0.144109,0.986045 --3.06641 , 1.6519 , -1.49116 , -0.0926026,0.141607,0.985582 --3.23611 , 1.72872 , -1.51612 , -0.0785977,0.105539,0.991304 --3.4239 , 1.81423 , -1.54613 , -0.138797,0.0871522,0.986479 --3.65306 , 1.9166 , -1.59496 , -0.137004,0.0744762,0.987767 --3.87579 , 2.01795 , -1.63094 , 0.0837679,-0.0379975,-0.995761 --4.08528 , 2.11434 , -1.64961 , -0.118096,0.0266178,0.992646 --4.34512 , 2.2326 , -1.68889 , -0.129741,0.0301784,0.991089 --4.60662 , 2.35315 , -1.71915 , -0.120743,0.0214088,0.992453 --4.90389 , 2.4893 , -1.75745 , -0.113765,0.0246801,0.993201 --5.21121 , 2.63035 , -1.78918 , -0.106312,-0.00639462,0.994312 --5.52912 , 2.77856 , -1.81427 , 0.0594568,0.0234259,-0.997956 --5.84908 , 2.92861 , -1.8279 , 0.0456957,0.0425992,-0.998047 --6.23924 , 3.11014 , -1.85972 , 0.103948,0.00112008,-0.994582 --6.75263 , 3.34436 , -1.92671 , -0.119052,-0.00639881,0.992867 --7.4156 , 3.64549 , -2.03219 , 0.11891,-0.0479635,-0.991746 --8.15221 , 3.98147 , -2.13879 , -0.101715,0.0588789,0.99307 --9.07806 , 4.40193 , -2.28206 , -0.096638,0.13392,0.986269 --10.272 , 4.94327 , -2.47703 , 0.11832,-0.108345,-0.987047 --11.711 , 5.59624 , -2.70035 , 0.103253,-0.0239696,0.994366 --13.2455 , 6.29975 , -2.89544 , -0.253535,0.375845,0.891325 --21.4187 , 9.98471 , -4.36628 , -0.0625117,-0.39705,0.915666 --21.507 , 10.0821 , -3.95665 , -0.0625117,-0.39705,0.915666 --38.1477 , 17.6827 , -6.22908 , 0.91563,0.132476,0.379568 --14.0493 , 6.87924 , -1.4165 , 0.59079,0.756403,-0.280751 --14.0536 , 6.91938 , -1.13684 , 0.731619,0.450994,-0.511212 --13.1958 , 6.5641 , -0.745385 , 0.736587,0.456205,-0.499316 --13.208 , 6.60453 , -0.483965 , 0.985039,0.172056,0.00973512 --13.2164 , 6.64404 , -0.222354 , 0.985298,0.170257,0.0141674 --13.2304 , 6.68593 , 0.0389193 , 0.985298,0.170257,0.0141674 --13.239 , 6.72459 , 0.301214 , 0.985298,0.170257,0.0141674 --40.151 , 19.4205 , -0.36492 , 0.865869,-0.472861,0.163321 --45.1925 , 22.027 , 1.21177 , -0.419361,-0.139991,0.896961 --40.3381 , 19.8235 , 1.97814 , -0.942471,0.333535,-0.0224353 --39.5382 , 19.5449 , 2.73095 , -0.943594,0.302121,0.135475 --39.2646 , 19.7238 , 5.03511 , 0.871175,-0.366226,0.327005 --10.8484 , 5.87087 , 2.40154 , 0.607333,-0.173172,0.775344 --10.4039 , 5.68179 , 2.56329 , -0.591287,0.801457,-0.0897008 --5.41052 , 3.23176 , 1.98246 , 0.401204,-0.400265,0.823907 --5.35353 , 3.21899 , 2.09032 , 0.662231,-0.512991,0.546159 --3.71993 , 2.41462 , 1.88201 , 0.649781,-0.326491,0.686432 --3.7283 , 2.4306 , 1.96936 , 0.528163,-0.427243,0.733831 --3.97041 , 2.5648 , 2.11426 , 0.55118,-0.0546039,0.832598 --3.89542 , 2.53933 , 2.18747 , 0.55118,-0.0546038,0.832598 --10.3014 , 5.83678 , 4.0869 , 0.792629,-0.21941,-0.568857 --8.60989 , 4.99487 , 3.80226 , -0.231392,0.547538,-0.804151 --9.78404 , 5.63021 , 4.37809 , -0.436796,-0.279239,0.855123 --5.24356 , 3.29272 , 3.02834 , 0.584332,-0.811063,-0.0270786 --4.03537 , 2.6759 , 2.70918 , 0.801035,-0.310999,0.51149 --4.32938 , 2.84402 , 2.92519 , 0.826311,-0.200283,0.526401 --4.74158 , 3.07766 , 3.20445 , -0.664505,-0.542633,0.513792 --4.33052 , 2.87421 , 3.14545 , -0.9574,-0.276486,-0.0833111 --5.32883 , 3.42499 , 3.71626 , 0.197969,-0.965348,0.170033 --4.43741 , 2.9626 , 3.42363 , 0.635904,0.654103,-0.409604 --3.83136 , 2.6494 , 3.23567 , -0.466717,-0.579062,0.668477 --4.13327 , 2.82891 , 3.50228 , -0.262095,-0.679395,0.685368 --4.33297 , 2.95384 , 3.72921 , 0.781238,0.509955,-0.360017 --3.94119 , 2.75411 , 3.62455 , -0.7312,-0.502608,0.461228 --3.82579 , 2.70445 , 3.66996 , -0.584589,-0.741753,0.328721 --3.848 , 2.73245 , 3.79869 , -0.509922,-0.634801,0.580523 --3.90438 , 2.77979 , 3.95453 , 0.512352,0.615703,-0.59867 --3.57709 , 2.61102 , 3.85113 , -0.866928,-0.165796,0.470052 --3.53496 , 2.60261 , 3.93696 , 0.982631,0.113455,-0.146847 --3.44012 , 2.56371 , 3.98437 , 0.998729,0.0503983,-0.000182288 --3.64004 , 2.69519 , 4.25781 , -0.933894,0.140899,-0.328618 --3.93858 , 2.88653 , 4.62602 , -0.27726,0.723539,-0.632154 --4.12762 , 3.01649 , 4.92538 , 0.666397,-0.281654,0.690352 --6.28347 , 4.31349 , 6.95595 , -0.121536,0.902537,-0.413105 --5.97784 , 4.16137 , 6.907 , -0.097291,0.810274,-0.577919 --5.91755 , 4.15478 , 7.07394 , -0.0134829,-0.891644,0.452537 --8.87308 , 5.97664 , 10.1881 , -0.0254712,-0.25226,0.967324 --5.29484 , 3.83719 , 6.91011 , 0.186695,-0.146011,0.971507 --5.22641 , 3.82494 , 7.05951 , 0.186695,-0.146011,0.971507 --3.30455 , 2.66143 , 5.19024 , -0.454108,0.405283,0.79343 --3.20269 , 2.61862 , 5.23227 , -0.454108,0.405283,0.79343 --3.15022 , 2.60654 , 5.32792 , -0.454108,0.405283,0.79343 --2.00135 , 1.89491 , 4.09047 , 0.579145,0.433653,-0.690316 --1.97279 , 1.89177 , 4.1703 , 0.657692,0.197483,-0.72694 --1.82445 , 1.81094 , 4.09466 , 0.350859,0.935423,0.0433866 --1.81684 , 1.82186 , 4.20202 , -0.682578,0.532497,0.500533 --1.80755 , 1.83149 , 4.31022 , 0.845634,-0.212057,-0.489831 --1.75275 , 1.8119 , 4.35727 , -0.932337,-0.264188,0.246885 --1.72811 , 1.81251 , 4.45045 , -0.86153,-0.393016,0.32141 --1.73083 , 1.83297 , 4.59148 , -0.845781,-0.50698,0.166211 --0.922566 , 1.28935 , 3.39731 , -0.850232,-0.263621,0.455641 --0.916113 , 1.2973 , 3.48388 , 0.930815,0.113417,-0.347449 --1.32142 , 1.60129 , 4.31331 , -0.534916,-0.834747,-0.130623 --1.23204 , 1.55522 , 4.28412 , -0.534916,-0.834747,-0.130623 --0.806028 , 1.26041 , 3.59467 , 0.686675,-0.311641,-0.656778 --1.14932 , 1.53172 , 4.4065 , -0.769709,-0.395587,0.501057 --1.11396 , 1.52538 , 4.48406 , -0.771808,0.181419,0.609426 --0.756988 , 1.27034 , 3.84812 , -0.517168,0.510857,-0.686705 --0.653698 , 1.2072 , 3.74313 , 0.465989,0.0260852,0.884406 --0.984961 , 1.49178 , 4.68905 , -0.911433,0.0268756,0.410569 --0.838691 , 1.3968 , 4.49712 , -0.274086,0.950561,0.145983 --0.801983 , 1.39015 , 4.57988 , 0.645063,-0.0142733,0.763996 --0.664526 , 1.298 , 4.38089 , 0.081907,0.227817,0.970253 --0.598075 , 1.26547 , 4.36934 , -0.373064,-0.122004,-0.919749 --0.531758 , 1.23169 , 4.35663 , 0.511272,-0.433458,0.742102 --0.681967 , 1.40008 , 5.07524 , -0.28213,-0.415255,0.86485 --1.18093 , 1.91448 , 7.14686 , 0.782176,0.615307,0.0979672 --1.04772 , 1.83881 , 7.05268 , -0.726478,-0.663583,-0.178569 --0.505394 , 1.33689 , 5.23495 , -0.926736,-0.334116,-0.171834 --0.320601 , 1.18219 , 4.73518 , 0.853895,0.474273,-0.214308 --0.24633 , 1.14123 , 4.68726 , -0.499376,-0.121053,0.857887 --0.188118 , 1.11568 , 4.70456 , -0.978066,-0.0506982,-0.202031 --0.146465 , 1.11188 , 4.82725 , 0.898748,-0.352475,-0.260795 --0.120165 , 1.13162 , 5.06538 , -0.775411,0.241651,-0.583389 --0.0404728 , 1.08134 , 4.97392 , -0.0827923,-0.888916,0.450526 --0.211157 , 1.42188 , 6.90861 , -0.565858,-0.821325,0.0723171 --0.137155 , 1.41542 , 7.12301 , -0.359071,-0.890909,0.278118 --2.38599 , 1.45273 , -1.41029 , -0.0769166,0.102719,0.991732 --2.50168 , 1.51038 , -1.42258 , -0.059262,0.118336,0.991204 --2.63423 , 1.57574 , -1.4432 , -0.079035,0.134431,0.987766 --2.77504 , 1.645 , -1.46502 , -0.0837108,0.148445,0.985371 --2.91719 , 1.71558 , -1.48209 , -0.0863895,0.14091,0.986246 --3.09225 , 1.80018 , -1.5165 , -0.110383,0.0837221,0.990357 --3.25183 , 1.88021 , -1.53413 , -0.102949,0.0563534,0.993089 --3.45343 , 1.97797 , -1.57226 , -0.153904,0.042865,0.987156 --3.66428 , 2.08157 , -1.60848 , -0.124062,0.00201775,0.992272 --3.83736 , 2.16879 , -1.6127 , 0.115906,0.0328924,-0.992715 --4.05121 , 2.27605 , -1.63487 , -0.146854,-0.0129996,0.989073 --4.3403 , 2.416 , -1.69069 , -0.158229,-0.0104273,0.987347 --4.63188 , 2.55972 , -1.73634 , -0.146752,-0.0178523,0.989012 --4.9335 , 2.70835 , -1.77542 , -0.127776,-0.0267455,0.991442 --5.23764 , 2.86082 , -1.80404 , -0.0860841,-0.0311136,0.995802 --5.53501 , 3.01058 , -1.81736 , -0.051663,-0.0208382,0.998447 --5.86697 , 3.17845 , -1.83539 , -0.0730187,0.0386281,0.996582 --6.31195 , 3.39858 , -1.88855 , -0.0941968,0.09261,0.991237 --6.87805 , 3.67771 , -1.97423 , 0.101623,-0.114283,-0.988237 --7.56723 , 4.01576 , -2.08507 , -0.106495,0.113172,0.987852 --8.41696 , 4.4313 , -2.22701 , -0.0901869,0.129024,0.987532 --9.46003 , 4.94243 , -2.40257 , -0.0942767,0.137311,0.986031 --10.5796 , 5.49486 , -2.56161 , -0.0933762,0.135381,0.986384 --12.2277 , 6.30124 , -2.83732 , 0.300407,0.206746,0.931135 --22.9555 , 11.4868 , -5.15776 , -0.144977,0.15163,0.977747 --29.6911 , 14.9353 , -5.13822 , -0.0606889,0.837023,-0.543792 --30.1245 , 15.2239 , -4.6244 , -0.0606889,0.837022,-0.543793 --39.8178 , 20.2587 , -4.0537 , -0.861191,-0.50575,-0.0506739 --39.5651 , 20.235 , -3.24247 , -0.809376,-0.581809,0.0800565 --38.4347 , 19.772 , -2.36562 , -0.925301,-0.364482,-0.10474 --38.9322 , 20.1207 , -1.64371 , 0.94456,0.296131,-0.141822 --39.4451 , 20.4801 , -0.903387 , -0.991671,-0.0173539,-0.127626 --49.1611 , 25.6414 , 0.554147 , 0.892368,0.299026,0.338029 --39.8641 , 21.1032 , 2.21874 , -0.736745,0.300249,-0.605853 --11.7481 , 6.64139 , 1.63638 , 0.841483,-0.423876,-0.335015 --41.1214 , 22.0722 , 4.70959 , -0.924014,0.22518,-0.309018 --11.4798 , 6.59532 , 2.33284 , 0.420383,-0.657426,-0.625356 --10.3734 , 6.04178 , 2.43019 , 0.413531,-0.126557,0.901651 --10.3041 , 6.03402 , 2.63786 , 0.712666,-0.339619,0.613813 --11.2078 , 6.54503 , 3.00833 , 0.354202,-0.385254,-0.852127 --5.07811 , 3.28848 , 2.09073 , 0.465503,-0.869718,0.164007 --10.7251 , 6.34708 , 3.38585 , 0.582157,-0.592732,-0.556563 --4.06502 , 2.76982 , 2.08773 , 0.22041,-0.0497454,0.974138 --3.90576 , 2.6956 , 2.14319 , -0.555405,0.108975,-0.824409 --8.3456 , 5.1375 , 3.44272 , 0.183172,-0.160148,0.969949 --5.10666 , 3.38036 , 2.68212 , -0.667818,0.743097,0.0427214 --5.0402 , 3.35943 , 2.78225 , -0.744817,0.65117,-0.145687 --4.98119 , 3.34263 , 2.88326 , 0.418912,-0.907213,-0.0384423 --5.00442 , 3.371 , 3.01255 , 0.473235,-0.880771,0.0170559 --5.0575 , 3.41711 , 3.15627 , 0.436744,-0.898607,0.0419466 --5.00138 , 3.40257 , 3.25963 , -0.467156,0.860466,0.203379 --4.97618 , 3.40464 , 3.37576 , 0.141008,-0.979192,0.145946 --4.8198 , 3.33266 , 3.43347 , -0.564669,-0.777047,0.278112 --4.4951 , 3.16248 , 3.40636 , 0.553208,0.388339,-0.73699 --4.53975 , 3.20423 , 3.54923 , 0.342787,0.333421,-0.878253 --4.4152 , 3.14783 , 3.60856 , 0.606812,0.360986,-0.708145 --4.24446 , 3.06436 , 3.63818 , 0.227265,-0.0545069,0.972306 --4.22908 , 3.07123 , 3.75053 , 0.0671143,0.994507,0.080325 --4.21875 , 3.0815 , 3.86811 , -0.531853,0.836026,0.13488 --4.25259 , 3.11814 , 4.01448 , -0.128819,-0.627413,0.767957 --3.93762 , 2.94659 , 3.93874 , 0.401304,0.492925,-0.771998 --3.85731 , 2.91468 , 4.00754 , -0.315329,-0.381243,0.869035 --3.48372 , 2.70564 , 3.86663 , 0.833353,0.271532,-0.481449 --3.55771 , 2.7657 , 4.0374 , -0.874131,-0.325302,0.360658 --3.54815 , 2.77556 , 4.15214 , -0.978966,-0.133896,-0.153938 --4.48685 , 3.37042 , 5.02704 , 0.581553,-0.00959193,0.813452 --4.08532 , 3.14187 , 4.85078 , -0.989397,0.144201,0.0173352 --5.60043 , 4.10764 , 6.30841 , 0.451341,-0.818154,-0.356252 --9.51564 , 6.59674 , 10.0234 , 0.184822,-0.241912,0.952533 --8.70574 , 6.12931 , 9.61414 , 0.185874,-0.262338,0.946905 --5.56756 , 4.16909 , 6.90755 , 0.233019,0.953301,0.192145 --5.35214 , 4.06044 , 6.91473 , 0.134372,0.402777,0.905381 --5.2276 , 4.00889 , 7.0076 , 0.134372,0.402777,0.905381 --3.25216 , 2.74809 , 5.09809 , 0.420492,-0.509376,-0.750815 --3.17239 , 2.7151 , 5.16103 , 0.420491,-0.509375,-0.750815 --3.10906 , 2.69334 , 5.24334 , -0.454108,0.405283,0.793431 --1.9777 , 1.95636 , 4.03498 , 0.579145,0.433653,-0.690316 --1.96791 , 1.96447 , 4.13646 , 0.674783,0.153162,-0.721949 --1.88754 , 1.92544 , 4.15075 , -0.353341,-0.390893,0.849913 --1.81942 , 1.89417 , 4.17769 , -0.599293,-0.181455,0.779693 --2.49904 , 2.3833 , 5.25273 , 0.0823179,0.889887,0.448693 --1.7673 , 1.89055 , 4.34921 , -0.985458,0.0537786,0.161184 --1.8463 , 1.96289 , 4.59856 , -0.8862,-0.404378,0.226113 --1.69733 , 1.87515 , 4.50551 , -0.845781,-0.50698,0.166211 --0.962959 , 1.36005 , 3.44165 , 0.964047,-0.0374632,-0.263079 --0.933667 , 1.35094 , 3.48844 , 0.737679,0.289922,-0.609733 --1.26201 , 1.60903 , 4.17332 , -0.567967,-0.794464,-0.215036 --0.893305 , 1.34772 , 3.62251 , -0.633678,0.350961,0.689404 --0.932701 , 1.39242 , 3.81126 , -0.672495,-0.648657,-0.356363 --1.05159 , 1.50086 , 4.1718 , -0.847294,-0.494945,-0.192671 --1.09449 , 1.55284 , 4.4016 , -0.911394,-0.234699,0.33805 --1.62061 , 1.99351 , 5.71528 , 0.267432,0.603653,0.751055 --0.651592 , 1.23464 , 3.7006 , -0.641977,-0.104654,-0.759548 --0.564019 , 1.17936 , 3.6198 , 0.70253,0.097822,0.704898 --0.820002 , 1.41164 , 4.39843 , 0.657958,0.224878,0.718694 --0.816454 , 1.43095 , 4.56168 , -0.623223,-0.350778,-0.698963 --0.688654 , 1.34402 , 4.39152 , -0.161674,0.337665,0.927278 --0.610459 , 1.29812 , 4.34471 , 0.844443,-0.493046,-0.209338 --0.562443 , 1.27836 , 4.3879 , 0.0364323,-0.116441,0.992529 --0.45927 , 1.20741 , 4.24509 , 0.578843,0.13528,0.804139 --1.2918 , 2.04638 , 7.40206 , -0.549021,0.059808,-0.833666 --0.568061 , 1.37438 , 5.09251 , -0.0654373,-0.881264,0.468073 --0.531865 , 1.3729 , 5.22999 , 0.844103,0.43745,0.310045 --0.812108 , 1.71853 , 6.7695 , -0.904942,-0.26947,-0.329342 --0.293842 , 1.19441 , 4.79064 , 0.495982,0.863233,0.0939697 --0.209851 , 1.13699 , 4.68508 , -0.0205256,-0.265941,0.963771 --0.144834 , 1.1017 , 4.66356 , 0.816991,-0.570598,-0.0833287 --0.167292 , 1.17908 , 5.17202 , 0.726631,-0.615433,0.305368 --0.0750839 , 1.10992 , 5.00446 , 0.628549,0.599902,-0.495019 --0.0114823 , 1.07936 , 5.01928 , 0.44023,0.486073,-0.754938 --0.137461 , 1.36409 , 6.70287 , -0.4025,0.775771,-0.485977 -0.0225598 , 1.1903 , 5.99526 , 0.77041,0.543667,-0.333008 --2.27828 , 1.51 , -1.41078 , -0.0575795,0.0999082,0.993329 --2.39216 , 1.56988 , -1.42539 , -0.0806081,0.100939,0.991622 --2.50705 , 1.63178 , -1.43652 , -0.0755019,0.116679,0.990296 --2.63785 , 1.70123 , -1.45557 , -0.111225,0.133892,0.984734 --2.7993 , 1.78499 , -1.49299 , -0.0854188,0.0557849,0.994782 --2.95517 , 1.86755 , -1.51934 , -0.1011,0.0389431,0.994114 --3.11242 , 1.95156 , -1.54037 , -0.104928,0.0205542,0.994267 --3.24083 , 2.0224 , -1.53469 , -0.10544,0.0132859,0.994337 --3.41557 , 2.11602 , -1.55559 , -0.153831,0.021914,0.987854 --3.62422 , 2.22566 , -1.59045 , -0.137564,-0.043658,0.98953 --3.82566 , 2.33296 , -1.61283 , -0.121293,-0.0465238,0.991526 --4.05293 , 2.45461 , -1.64244 , -0.151442,-0.050161,0.987193 --4.29786 , 2.58471 , -1.67269 , 0.173667,0.0762751,-0.981846 --4.57686 , 2.73299 , -1.71176 , 0.182908,0.0668436,-0.980855 --4.89034 , 2.89896 , -1.75738 , -0.156421,-0.047226,0.986561 --5.20637 , 3.06891 , -1.79196 , -0.120422,-0.0609422,0.99085 --5.49997 , 3.22773 , -1.80273 , -0.0808165,-0.00380861,0.996722 --5.90232 , 3.44236 , -1.85168 , 0.0883653,-0.0422568,-0.995191 --6.43278 , 3.7227 , -1.93961 , 0.10334,-0.110711,-0.988465 --7.05919 , 4.05362 , -2.04529 , 0.10345,-0.122133,-0.987108 --7.80804 , 4.44819 , -2.17282 , -0.0986247,0.135091,0.985913 --8.7566 , 4.94644 , -2.34316 , -0.0944392,0.143357,0.985155 --9.8217 , 5.50891 , -2.51542 , -0.0818983,0.139794,0.986788 --11.2518 , 6.26278 , -2.76343 , 0.0792399,-0.173428,-0.981654 --18.6804 , 10.135 , -4.37723 , -0.0852728,0.52354,-0.847723 --19.4942 , 10.6036 , -4.19976 , -0.0852728,0.52354,-0.847723 --27.6596 , 14.8863 , -5.76904 , -0.083922,0.919602,-0.383784 --27.7823 , 15.0223 , -5.22957 , 0.083922,-0.919602,0.383783 --28.1592 , 15.2921 , -4.73905 , -0.0821306,0.852563,-0.516131 --28.1524 , 15.3609 , -4.16603 , -0.0606889,0.837022,-0.543792 --38.7622 , 21.0391 , -5.31262 , 0.926784,0.372517,0.0479888 --46.2274 , 25.1 , -5.59367 , -0.504586,-0.730875,-0.459582 --40.369 , 22.0942 , -3.95415 , -0.861191,-0.50575,-0.0506738 --40.5718 , 22.3054 , -3.16793 , -0.87678,-0.473716,-0.0827599 --38.4709 , 21.2773 , -2.18406 , -0.94456,-0.296131,0.141823 --38.6489 , 21.472 , -1.42712 , -0.943271,-0.0281653,0.330826 --39.3182 , 22.2355 , 1.67714 , -0.865498,0.435732,-0.247085 --38.3152 , 21.7808 , 2.43182 , 0.921408,-0.37047,0.117299 --11.5698 , 7.00806 , 1.71209 , 0.610487,-0.465616,-0.640708 --11.5185 , 7.00993 , 1.94964 , 0.567251,-0.474788,-0.672906 --10.1165 , 6.25478 , 2.05657 , -0.525501,0.0943258,-0.845548 --10.2002 , 6.32935 , 2.28071 , -0.5255,0.0943256,-0.845548 --10.6874 , 6.63191 , 2.56442 , 0.160763,-0.235761,0.958422 --10.7101 , 6.67413 , 2.7967 , -0.587102,-0.643611,-0.490995 --4.98859 , 3.43396 , 2.01243 , 0.563194,-0.804782,0.187453 --10.0356 , 6.34616 , 3.12608 , -0.913889,-0.124847,-0.386291 --5.07989 , 3.5155 , 2.26104 , -0.507786,0.857881,-0.0787045 --5.00275 , 3.48651 , 2.3604 , 0.37021,-0.92847,-0.0298182 --4.93417 , 3.46065 , 2.45954 , -0.451741,0.884231,0.118599 --4.89717 , 3.45462 , 2.56593 , -0.62825,0.777039,0.0389041 --4.88307 , 3.461 , 2.67943 , 0.8183,-0.568769,0.0829835 --4.92575 , 3.50116 , 2.81191 , -0.850063,0.522557,-0.0657807 --4.95806 , 3.53649 , 2.94368 , 0.690895,-0.706508,-0.15333 --5.64172 , 3.95971 , 3.32108 , -0.764357,-0.576869,0.288064 --4.76231 , 3.4499 , 3.11483 , -0.445757,0.88719,0.119141 --4.86092 , 3.52502 , 3.27811 , 0.557115,-0.829502,0.039353 --4.81961 , 3.51619 , 3.38628 , -0.549244,0.802166,0.234223 --4.89602 , 3.57938 , 3.54897 , 0.466929,-0.779244,-0.418038 --4.70146 , 3.47661 , 3.58493 , -0.0815295,0.590417,0.80297 --4.56189 , 3.40762 , 3.64205 , 0.751155,0.0767553,-0.655648 --4.35349 , 3.29497 , 3.65702 , 0.519464,0.246199,-0.818256 --4.13088 , 3.17233 , 3.65607 , -0.325059,0.554757,0.765886 --3.94027 , 3.06914 , 3.665 , -0.834722,-0.351067,0.424255 --4.46476 , 3.41387 , 4.10755 , -0.921694,-0.288655,0.259148 --4.00289 , 3.13963 , 3.94528 , -0.054872,0.0807974,0.995219 --4.04755 , 3.18413 , 4.1014 , 0.220814,-0.840831,0.494211 --3.65428 , 2.94909 , 3.95497 , -0.322137,0.0538302,0.945161 --3.49646 , 2.86397 , 3.96118 , -0.87413,-0.325302,0.360658 --3.54587 , 2.91091 , 4.11835 , -0.660062,-0.750109,0.0406782 --3.444 , 2.8602 , 4.16278 , 0.968058,0.194323,0.158436 --4.17694 , 3.35564 , 4.89034 , -0.81613,0.568654,0.102779 --4.17231 , 3.37166 , 5.03899 , -0.299868,0.0846875,-0.950214 --4.04519 , 3.30793 , 5.08125 , -0.914719,0.336738,-0.223378 --3.54844 , 2.99601 , 4.77899 , -0.853837,0.50144,-0.139714 --3.47266 , 2.9636 , 4.85013 , -0.853837,0.50144,-0.139714 --5.31285 , 4.22617 , 6.82842 , 0.0768132,0.959845,0.269809 --5.10337 , 4.11189 , 6.83181 , 0.0768132,0.959845,0.269809 --3.43831 , 2.99806 , 5.26511 , 0.608941,0.331615,0.720571 --3.21654 , 2.86515 , 5.17813 , 0.206982,-0.120135,-0.970941 --3.07634 , 2.78731 , 5.17305 , 0.420491,-0.509375,-0.750815 --3.02573 , 2.77148 , 5.26869 , -0.420491,0.509376,0.750815 --1.97101 , 2.04625 , 4.11663 , 0.732365,-0.120492,-0.670166 --1.90899 , 2.01655 , 4.15396 , -0.60803,-0.152721,0.779086 --1.88512 , 2.01508 , 4.24129 , 0.455324,0.356121,-0.816001 --1.76351 , 1.94158 , 4.19438 , 0.682635,-0.293995,-0.669012 --2.42028 , 2.43924 , 5.26693 , 0.104646,0.809643,0.577519 --1.80296 , 2.00306 , 4.50452 , 0.978109,0.208023,-0.00542949 --0.977247 , 1.40245 , 3.35032 , -0.892667,-0.0977055,0.439999 --1.6844 , 1.94998 , 4.59298 , -0.845781,-0.50698,0.166211 --0.953303 , 1.40878 , 3.50064 , 0.877151,-0.137784,-0.460024 --0.923285 , 1.39852 , 3.54785 , 0.877151,-0.137784,-0.460024 --0.86428 , 1.36556 , 3.54561 , 0.845547,0.15449,-0.511061 --1.02822 , 1.50912 , 3.96589 , -0.716066,0.160757,-0.679269 --1.05795 , 1.5484 , 4.1502 , 0.696022,0.699252,0.163096 --1.74999 , 2.13082 , 5.73117 , -0.267432,-0.603653,-0.751055 --0.731828 , 1.31572 , 3.72709 , 0.450678,0.585125,0.67418 --0.677494 , 1.28664 , 3.72783 , -0.44486,-0.219179,-0.868367 --0.57582 , 1.21568 , 3.61359 , 0.70253,0.097822,0.704899 --0.869703 , 1.48756 , 4.47708 , 0.847909,0.183575,0.497343 --0.791528 , 1.44049 , 4.44492 , 0.657958,0.224877,0.718694 --0.672876 , 1.35557 , 4.29378 , 0.651832,0.569034,0.501314 --0.60238 , 1.31334 , 4.2656 , -0.00826812,0.777673,0.628615 --0.586139 , 1.32245 , 4.39992 , -0.0320719,0.604865,0.795682 --0.479625 , 1.24393 , 4.24992 , 0.578843,0.13528,0.804139 --0.73048 , 1.5184 , 5.31925 , 0.729252,0.651442,-0.20932 --0.637591 , 1.45879 , 5.25431 , -0.704919,-0.576379,-0.413372 --0.53037 , 1.38357 , 5.1211 , -0.913446,0.274347,0.300583 --0.396982 , 1.27592 , 4.85263 , -0.844533,-0.535413,0.00983035 --0.305653 , 1.21032 , 4.73159 , -0.702763,-0.302848,-0.643745 --0.271142 , 1.2085 , 4.86542 , 0.766838,-0.194257,-0.611739 --0.168283 , 1.12549 , 4.65397 , 0.113085,-0.73171,0.67217 --0.170027 , 1.17291 , 5.01739 , -0.755598,-0.649983,0.081202 --0.101969 , 1.13263 , 4.99568 , -0.497322,-0.0852798,0.863365 --0.0364726 , 1.09466 , 4.9821 , 0.459864,0.569046,-0.681698 --0.206188 , 1.43498 , 6.91692 , -0.565858,-0.821325,0.0723171 --0.115038 , 1.38698 , 6.9363 , -0.615523,-0.76548,-0.187542 --2.25347 , 1.61294 , -1.40165 , -0.0163685,0.0342636,0.999279 --2.38663 , 1.6876 , -1.43388 , 0.0818988,-0.117454,-0.989695 --2.52231 , 1.7628 , -1.46149 , -0.105154,0.0317007,0.993951 --2.66582 , 1.84387 , -1.49038 , -0.117796,0.0194508,0.992847 --2.79622 , 1.9188 , -1.50284 , -0.116791,-0.000126352,0.993156 --2.88331 , 1.97293 , -1.47766 , 0.117717,0.0439723,-0.992073 --3.05976 , 2.07314 , -1.51447 , -0.112144,0.00366314,0.993685 --3.22338 , 2.16634 , -1.53424 , -0.101452,0.00332264,0.994835 --3.41166 , 2.2731 , -1.56374 , -0.133303,-0.038929,0.990311 --3.59343 , 2.37854 , -1.58167 , 0.122297,0.0644236,-0.9904 --3.78468 , 2.48883 , -1.5977 , -0.14779,-0.0739668,0.986249 --4.00006 , 2.61208 , -1.62061 , -0.146283,-0.0862904,0.985472 --4.21773 , 2.73851 , -1.63598 , -0.167204,-0.0926511,0.981559 --4.49215 , 2.89439 , -1.67344 , 0.187692,0.0901469,-0.978083 --4.79252 , 3.06667 , -1.71355 , -0.169299,-0.0842346,0.981958 --5.13512 , 3.26229 , -1.76249 , 0.16322,0.08719,-0.982729 --5.52207 , 3.4823 , -1.81778 , -0.129617,0.0202288,0.991358 --5.97617 , 3.74003 , -1.88802 , -0.12114,0.084313,0.989048 --6.5644 , 4.07324 , -1.99785 , -0.102645,0.120493,0.987393 --7.26513 , 4.46883 , -2.12881 , -0.106392,0.131516,0.985588 --8.12031 , 4.95098 , -2.29051 , -0.0963057,0.141821,0.985196 --9.02261 , 5.4632 , -2.43446 , 0.0893658,-0.144935,-0.985397 --10.2232 , 6.14292 , -2.64411 , -0.080073,0.18524,0.979426 --11.9705 , 7.12829 , -2.981 , -0.0151151,0.289352,0.957104 --17.5221 , 10.2167 , -4.39275 , 0.0450921,0.361285,-0.931365 --25.9485 , 14.9896 , -5.83552 , 0.0663644,-0.943331,0.32515 --19.7967 , 11.6244 , -3.82026 , 0.135064,-0.592733,0.793993 --26.3917 , 15.3734 , -4.84931 , 0.0663644,-0.943331,0.32515 --26.6194 , 15.5686 , -4.34738 , 0.0722263,-0.935085,0.346987 --38.9411 , 22.6066 , -5.995 , -0.926562,-0.373477,0.0446875 --28.1444 , 16.6431 , -2.91442 , -0.022546,-0.852179,0.522764 --28.4022 , 16.8621 , -2.36903 , -0.0225459,-0.852179,0.522764 --38.2692 , 23.0973 , 1.13728 , -0.885282,0.420861,-0.19787 --39.0452 , 23.653 , 1.93673 , 0.786352,-0.375779,0.490348 --37.7875 , 23.0061 , 2.68233 , 0.918761,-0.294228,0.263263 --39.0964 , 23.8819 , 3.54197 , 0.786352,-0.375779,0.490348 --11.6435 , 7.56061 , 2.05371 , 0.52114,-0.494986,-0.695271 --9.88838 , 6.5371 , 2.11969 , -0.833406,-0.34691,-0.430218 --10.0628 , 6.66914 , 2.35533 , -0.833406,-0.34691,-0.430218 --10.4202 , 6.91265 , 2.62607 , -0.833406,-0.34691,-0.430218 --4.83391 , 3.54253 , 1.92522 , 0.605859,-0.793895,0.0516383 --4.79726 , 3.53421 , 2.03025 , 0.605859,-0.793895,0.0516382 --4.77557 , 3.53436 , 2.13801 , 0.664935,-0.742648,0.079599 --4.77695 , 3.54973 , 2.251 , -0.712282,0.682848,-0.162396 --4.79346 , 3.57406 , 2.36886 , 0.750668,-0.647227,0.132647 --4.80834 , 3.59721 , 2.48803 , -0.80248,0.582937,-0.127324 --4.83746 , 3.62938 , 2.61345 , -0.809547,0.583732,-0.062373 --4.88065 , 3.6717 , 2.74561 , -0.899547,0.40492,-0.163877 --5.85594 , 4.30151 , 3.19801 , -0.875353,0.346536,-0.33715 --5.78305 , 4.2733 , 3.3163 , -0.875353,0.346536,-0.33715 --5.66011 , 4.21268 , 3.41419 , -0.875353,0.346536,-0.33715 --4.74013 , 3.64331 , 3.18207 , -0.305267,0.950438,0.0589916 --4.64597 , 3.59839 , 3.26553 , 0.359821,-0.933001,0.00616355 --4.55827 , 3.55737 , 3.34989 , 0.305188,-0.903997,-0.299417 --4.61032 , 3.60642 , 3.49888 , -0.0784695,0.898616,0.431662 --4.46623 , 3.52841 , 3.55334 , -0.0968499,0.486134,0.868501 --4.35327 , 3.46992 , 3.61916 , 0.407351,-0.680665,-0.608901 --4.05002 , 3.28697 , 3.57576 , -0.197362,0.295609,0.9347 --4.33585 , 3.48981 , 3.86256 , 0.491632,-0.868826,0.0586422 --4.3321 , 3.50367 , 3.98963 , 0.894812,-0.442908,-0.056073 --3.98017 , 3.28491 , 3.89761 , -0.780061,0.227249,0.582978 --3.94508 , 3.27753 , 4.00026 , -0.687851,0.281942,0.668857 --3.7654 , 3.17253 , 4.00262 , 0.544638,0.182053,-0.818673 --4.22669 , 3.49974 , 4.46154 , 0.765599,-0.336391,-0.54836 --3.8601 , 3.26753 , 4.32729 , -0.209863,-0.629106,0.748454 --4.08878 , 3.44076 , 4.64096 , -0.770396,0.427086,0.473379 --4.0412 , 3.42698 , 4.74794 , -0.816619,0.522382,0.245459 --4.04009 , 3.44446 , 4.89435 , -0.81613,0.568654,0.102779 --3.92971 , 3.38625 , 4.94831 , -0.81613,0.568654,0.102779 --3.4061 , 3.03731 , 4.62125 , 0.923656,-0.341777,0.173345 --3.39209 , 3.04503 , 4.74616 , 0.923656,-0.341777,0.173345 --3.41342 , 3.07791 , 4.90963 , -0.819504,0.53568,-0.203617 --8.69465 , 6.87311 , 10.4775 , 0.699027,-0.124029,-0.704257 --4.94891 , 4.22047 , 6.84572 , 0.384077,-0.760808,-0.523122 --3.26123 , 3.02474 , 5.20002 , 0.821454,0.563495,0.0876791 --3.06271 , 2.89908 , 5.13032 , -0.640736,-0.363886,-0.676051 --2.69424 , 2.64684 , 4.84594 , -0.575925,0.109505,0.810135 --2.58051 , 2.58071 , 4.85053 , -0.575925,0.109505,0.810135 --2.07746 , 2.22295 , 4.34992 , 0.200066,-0.478049,0.855244 --1.88234 , 2.09202 , 4.21528 , -0.691294,0.344145,0.635356 --1.79285 , 2.03923 , 4.21464 , -0.242626,-0.250154,0.937313 --1.72156 , 1.99924 , 4.23371 , -0.363693,0.12403,0.923225 --1.02091 , 1.47267 , 3.3124 , -0.628753,-0.00286355,0.7776 --2.14178 , 2.35884 , 5.14117 , 0.172281,0.930331,0.323732 --2.47995 , 2.64633 , 5.84961 , 0.291368,0.852493,-0.434006 --0.938328 , 1.44215 , 3.4565 , -0.845535,0.0364809,0.532672 --0.899724 , 1.42431 , 3.48756 , 0.877151,-0.137784,-0.460024 --0.847436 , 1.39372 , 3.49374 , 0.877151,-0.137784,-0.460024 --1.54907 , 1.98458 , 4.92664 , -0.267691,-0.185297,0.945519 --1.83026 , 2.23858 , 5.64812 , 0.267432,0.603653,0.751055 --0.766424 , 1.36629 , 3.65594 , 0.274874,-0.758722,-0.590581 --0.725102 , 1.34504 , 3.68396 , -0.359906,-0.665755,-0.653635 --0.679164 , 1.32069 , 3.70254 , -0.407452,-0.600306,-0.688197 --0.61134 , 1.27673 , 3.66788 , 0.771717,0.360086,0.524205 --0.935917 , 1.5827 , 4.59827 , -0.789568,0.226063,-0.570507 --0.79443 , 1.47678 , 4.40865 , 0.807157,-0.00289609,0.59033 --0.761565 , 1.46695 , 4.49175 , -0.68472,0.707166,0.176279 --0.607761 , 1.34442 , 4.23166 , 0.123884,0.663586,0.737772 --0.578801 , 1.33886 , 4.32059 , -0.60558,0.727939,0.321524 --0.779072 , 1.55878 , 5.15181 , -0.953852,-0.290262,0.0769089 --0.44559 , 1.25393 , 4.26788 , 0.550194,-0.0558952,0.833164 --0.652441 , 1.49302 , 5.21916 , -0.361365,-0.919185,-0.156572 --0.567904 , 1.43801 , 5.17148 , -0.753653,-0.54834,-0.362395 --0.364658 , 1.25076 , 4.62298 , 0.962137,0.243641,-0.12219 --0.343985 , 1.25928 , 4.79517 , 0.644507,0.426311,0.63472 --0.275978 , 1.21581 , 4.76822 , 0.542597,-0.148061,0.826841 --0.203537 , 1.16602 , 4.71096 , -0.551306,-0.254629,0.794497 --0.157059 , 1.14803 , 4.78622 , 0.839395,0.0587828,-0.540334 --0.145007 , 1.17919 , 5.09277 , -0.733654,0.633578,-0.245623 --0.073022 , 1.13078 , 5.04163 , 0.285116,0.300638,0.910124 --0.248641 , 1.46526 , 6.90579 , -0.565858,-0.821325,0.0723171 --0.124024 , 1.35697 , 6.62376 , -0.679173,0.715296,-0.164547 -0.0316963 , 1.17804 , 5.91668 , 0.587588,-0.784641,0.197682 --2.1715 , 1.67595 , -1.4255 , -0.0465786,-0.0095738,0.998869 --2.26816 , 1.73599 , -1.42889 , -0.0318886,-0.000761283,0.999491 --2.3852 , 1.80747 , -1.44707 , -0.130477,-0.00165547,0.99145 --2.50425 , 1.88126 , -1.46161 , -0.151215,-0.0199928,0.988299 --2.58847 , 1.93548 , -1.44271 , -0.140183,-0.000604846,0.990125 --2.738 , 2.02636 , -1.47202 , -0.104789,-0.0130018,0.99441 --2.88914 , 2.11772 , -1.49589 , -0.112274,0.00319974,0.993672 --3.04916 , 2.21548 , -1.51982 , 0.0941313,0.0136692,-0.995466 --3.20284 , 2.31077 , -1.53285 , -0.121766,-0.0370078,0.991869 --3.38022 , 2.41942 , -1.55539 , -0.134134,-0.0632773,0.988941 --3.53597 , 2.51662 , -1.55666 , 0.135035,0.0806725,-0.987551 --3.7396 , 2.64086 , -1.58098 , -0.134554,-0.0725984,0.988243 --3.94355 , 2.76777 , -1.59791 , -0.134118,-0.0859666,0.987229 --4.1571 , 2.89986 , -1.61148 , 0.146303,0.0766196,-0.986268 --4.43455 , 3.06861 , -1.65134 , 0.161274,0.0532418,-0.985473 --4.73898 , 3.25412 , -1.69331 , 0.150336,0.0419972,-0.987743 --5.01216 , 3.42395 , -1.70761 , 0.158566,0.0412625,-0.986486 --5.51942 , 3.72874 , -1.82225 , 0.17115,-0.0218998,-0.985002 --6.0879 , 4.07062 , -1.94264 , -0.131666,0.1062,0.985589 --6.65998 , 4.41799 , -2.04089 , 0.102937,-0.129958,-0.986162 --7.43179 , 4.88385 , -2.19672 , -0.0995544,0.154588,0.98295 --8.20829 , 5.35513 , -2.32184 , -0.0895072,0.154544,0.983923 --9.35173 , 6.04554 , -2.54846 , -0.0691763,0.186583,0.980001 --11.0384 , 7.06045 , -2.91371 , -0.0819699,0.25648,0.963068 --16.3575 , 10.221 , -4.37386 , -0.0862818,-0.315763,0.944907 --24.6854 , 15.3789 , -4.92676 , 0.0477008,-0.94505,0.323426 --25.1137 , 15.6994 , -4.49633 , 0.0423548,-0.936007,0.349424 --24.8091 , 15.58 , -3.90744 , 0.036878,-0.931276,0.362444 --25.5375 , 16.1486 , -2.97857 , 0.102126,-0.903087,0.417137 --25.8103 , 16.3792 , -2.48153 , -0.023201,-0.879612,0.475125 --37.7391 , 24.2366 , 0.610986 , -0.885282,0.420861,-0.19787 --37.897 , 24.5255 , 2.18528 , 0.786352,-0.375779,0.490348 --4.69621 , 3.58905 , 1.30063 , 0.62836,-0.769107,0.116781 --4.68554 , 3.59493 , 1.40761 , -0.603609,0.786297,-0.131883 --4.69025 , 3.61117 , 1.51574 , 0.630114,-0.761048,0.15415 --4.67686 , 3.61532 , 1.6227 , 0.719163,-0.692041,0.0623235 --4.66971 , 3.62433 , 1.73046 , 0.743961,-0.657727,0.117974 --4.66085 , 3.63192 , 1.83846 , 0.762943,-0.639691,0.0933491 --4.65949 , 3.6438 , 1.94803 , -0.835742,0.518755,-0.180079 --4.67197 , 3.66515 , 2.06141 , -0.866775,0.491442,-0.0847661 --4.69911 , 3.69735 , 2.17916 , -0.887684,0.45732,-0.0536248 --4.72487 , 3.7275 , 2.29882 , -0.923072,0.353669,-0.151182 --10.5304 , 7.5679 , 3.94109 , 0.296548,0.809094,0.507372 --10.5223 , 7.59206 , 4.18386 , -0.296548,-0.809094,-0.507372 --10.4448 , 7.56995 , 4.40812 , 0.530014,0.328941,-0.78159 --7.90217 , 5.90381 , 3.81653 , -0.00230384,-0.332766,0.943007 --7.92201 , 5.94078 , 4.0167 , 0.0656689,-0.305767,0.949839 --5.71277 , 4.47734 , 3.38082 , -0.875353,0.346537,-0.33715 --4.45106 , 3.64258 , 3.02235 , -0.288352,0.948101,0.134006 --4.48596 , 3.68092 , 3.1554 , 0.368757,-0.929281,0.0213364 --8.10482 , 6.16204 , 4.90062 , 0.081574,-0.214105,0.973399 --6.47656 , 5.07202 , 4.34228 , -0.331034,-0.86062,0.386975 --4.40555 , 3.67055 , 3.48526 , 0.524199,-0.673458,-0.52122 --4.18172 , 3.53055 , 3.49326 , -0.468125,-0.486099,-0.737947 --4.12419 , 3.50553 , 3.58327 , 0.978247,-0.0614965,0.198117 --4.22111 , 3.58763 , 3.76195 , 0.686888,-0.671436,-0.278135 --4.15244 , 3.55484 , 3.84807 , -0.272713,0.940863,0.201008 --4.00978 , 3.47071 , 3.88654 , -0.488309,0.00654372,0.872646 --3.85444 , 3.37522 , 3.91074 , 0.491384,0.235294,0.838557 --3.84853 , 3.38631 , 4.03212 , 0.687865,-0.278194,-0.67041 --4.02342 , 3.52636 , 4.28555 , -0.740852,-0.487384,-0.462164 --3.76109 , 3.35435 , 4.22573 , -0.0151928,-0.879358,0.475918 --4.07784 , 3.59965 , 4.60435 , -0.95636,0.148912,0.251396 --5.92828 , 4.9583 , 6.24821 , 0.398636,0.508142,0.763467 --3.92545 , 3.52367 , 4.76978 , -0.453158,0.821387,0.346368 --3.93626 , 3.54962 , 4.92757 , -0.453158,0.821387,0.346368 --3.39234 , 3.16717 , 4.58483 , -0.922135,0.324745,-0.210258 --3.2959 , 3.11204 , 4.63191 , 0.504795,-0.239973,0.829213 --3.38206 , 3.19344 , 4.85555 , -0.919483,0.384344,-0.0826493 --3.37015 , 3.20145 , 4.98948 , -0.92316,0.294012,0.247655 --3.39124 , 3.23633 , 5.1629 , -0.988445,-0.0341068,0.147692 --2.97214 , 2.93579 , 4.85814 , 0.454513,0.817355,0.354047 --2.74587 , 2.78057 , 4.74497 , -0.704086,0.173743,0.688532 --2.68071 , 2.74707 , 4.80827 , 0.575925,-0.109505,-0.810135 --2.56897 , 2.6776 , 4.81461 , 0.575925,-0.109505,-0.810135 --2.50329 , 2.64419 , 4.87392 , -0.575925,0.109505,0.810135 --1.99625 , 2.26232 , 4.348 , 0.124828,-0.39565,0.909879 --1.86371 , 2.17275 , 4.29238 , 0.0818289,-0.527682,0.845491 --1.78013 , 2.12093 , 4.29952 , -0.17575,-0.115421,0.977645 --1.67837 , 2.05359 , 4.27379 , 0.0443719,-0.269279,0.96204 --2.10944 , 2.42029 , 5.06566 , -0.262136,-0.921258,-0.287349 --2.05608 , 2.39491 , 5.13879 , 0.117324,0.792773,0.598119 --3.29339 , 3.4395 , 7.36427 , -0.175135,0.813433,0.554666 --1.73242 , 2.16521 , 4.91463 , -0.859529,-0.0423296,-0.509331 --1.78391 , 2.2281 , 5.16652 , -0.616793,0.594352,-0.516053 --1.87272 , 2.32431 , 5.504 , -0.422843,0.753473,0.50347 --1.79425 , 2.27982 , 5.54035 , 0.422843,-0.753473,-0.50347 --2.81117 , 3.19154 , 7.81421 , -0.480776,0.721204,0.498718 --2.68171 , 3.11388 , 7.8377 , -0.795618,0.227359,0.561515 --0.668374 , 1.34526 , 3.65144 , -0.359906,-0.665755,-0.653635 --0.616871 , 1.31265 , 3.65206 , -0.638371,-0.398309,-0.658659 --0.936599 , 1.62331 , 4.56016 , -0.21503,0.774618,0.594751 --0.799959 , 1.51558 , 4.38138 , -0.563909,0.0295989,-0.825306 --0.745517 , 1.48435 , 4.40226 , 0.857024,-0.282909,0.430666 --0.626808 , 1.39031 , 4.2427 , 0.470863,0.46076,-0.752322 --0.593074 , 1.37784 , 4.31412 , 0.444187,0.815856,-0.370239 --0.527992 , 1.33447 , 4.29423 , -0.300049,0.911885,0.280067 --0.502775 , 1.33149 , 4.40121 , 0.664259,-0.57991,-0.471661 --0.417308 , 1.26715 , 4.30462 , -0.877803,0.121691,-0.463306 --0.629027 , 1.52161 , 5.31405 , -0.776647,-0.42767,-0.462513 --0.466325 , 1.37482 , 4.94766 , -0.685041,0.265696,-0.678325 --0.354815 , 1.27993 , 4.74499 , -0.916819,-0.313063,-0.247859 --0.30203 , 1.25205 , 4.78513 , -0.955472,-0.144075,0.257519 --0.220687 , 1.18827 , 4.68122 , -0.0371567,-0.294424,0.954952 --0.160006 , 1.14901 , 4.67086 , -0.392493,-0.570625,0.721344 --0.156188 , 1.18607 , 4.99602 , -0.539138,-0.827132,0.158691 --0.0917143 , 1.14454 , 4.9843 , -0.955403,-0.0317993,0.293589 --0.0317393 , 1.10681 , 4.99061 , -0.549236,-0.422303,0.72111 --0.237382 , 1.5061 , 7.22766 , 0.24594,0.518482,0.818957 --0.105925 , 1.38085 , 6.8771 , 0.597507,0.801523,0.023365 --2.06803 , 1.72627 , -1.42916 , -0.0572209,-0.0758898,0.995473 --2.14757 , 1.78112 , -1.42188 , -0.0242854,-0.0297261,0.999263 --2.2218 , 1.83226 , -1.40586 , -0.0919494,-0.108229,0.989865 --2.32381 , 1.89947 , -1.41147 , -0.104203,-0.0172512,0.994406 --2.44679 , 1.98049 , -1.43132 , -0.110578,0.00639569,0.993847 --2.59323 , 2.07413 , -1.4639 , -0.105692,0.0327711,0.993859 --2.73332 , 2.16532 , -1.48557 , -0.0990972,0.0295765,0.994638 --2.88131 , 2.26259 , -1.50757 , -0.0937649,-0.00318273,0.995589 --3.02414 , 2.3566 , -1.51888 , -0.0839782,-0.0253183,0.996146 --3.16832 , 2.45201 , -1.52507 , -0.0935359,-0.0587756,0.99388 --3.3129 , 2.5486 , -1.52599 , -0.118854,-0.0865307,0.989134 --3.50312 , 2.67262 , -1.5506 , -0.143819,-0.0752353,0.98674 --3.68024 , 2.79046 , -1.55895 , 0.128345,0.0508581,-0.990425 --3.88884 , 2.9274 , -1.57869 , -0.0973878,-0.0442669,0.994262 --4.10585 , 3.07031 , -1.59486 , 0.135567,0.0370042,-0.990077 --4.37049 , 3.24454 , -1.62844 , -0.126027,0.0202256,0.991821 --4.70771 , 3.46283 , -1.68836 , -0.115836,-0.00887673,0.993229 --4.96856 , 3.63629 , -1.69578 , -0.127212,0.0311948,0.991385 --5.54715 , 4.00544 , -1.84374 , 0.173492,-0.106947,-0.979011 --6.21663 , 4.43468 , -2.00824 , -0.101535,0.140657,0.984838 --6.80369 , 4.81589 , -2.10816 , -0.0725162,0.182165,0.98059 --7.61086 , 5.33597 , -2.2728 , -0.069285,0.167803,0.983383 --8.64063 , 6.00034 , -2.48918 , 0.0732066,-0.197531,-0.977559 --10.0654 , 6.91642 , -2.8051 , -0.0711741,0.203278,0.976531 --17.1198 , 11.4706 , -4.22021 , -0.0389003,-0.511717,0.858273 --23.0804 , 15.3094 , -5.4926 , -0.0666469,0.849335,-0.523629 --23.1958 , 15.4415 , -5.01873 , -0.143291,0.867884,-0.475653 --23.5429 , 15.7232 , -4.59714 , -0.176814,0.848139,-0.499396 --23.4791 , 15.741 , -4.07537 , 0.170418,-0.855508,0.488942 --19.0132 , 12.9126 , -2.71236 , 0.949843,0.23133,0.21044 --19.092 , 13.0121 , -2.3166 , -0.980714,-0.193574,-0.0270132 --19.1082 , 13.0701 , -1.90918 , 0.906054,0.108339,0.409059 --4.53687 , 3.67636 , 1.12154 , -0.581924,0.808851,-0.0844133 --4.52062 , 3.67834 , 1.22653 , -0.582311,0.796132,-0.164582 --4.50359 , 3.67903 , 1.33125 , 0.58046,-0.796538,0.169094 --4.53446 , 3.71225 , 1.43935 , -0.674768,0.70893,-0.205199 --4.54657 , 3.73246 , 1.54767 , -0.767461,0.603308,-0.216848 --4.56573 , 3.75894 , 1.65754 , -0.813959,0.556152,-0.167827 --4.57429 , 3.7776 , 1.76771 , -0.889231,0.402462,-0.217466 --4.59862 , 3.80615 , 1.88136 , -0.903992,0.394242,-0.165445 --4.66019 , 3.86259 , 2.00392 , -0.895788,0.400754,-0.192251 --11.1191 , 8.35419 , 3.46648 , 0.658302,0.745307,0.105622 --10.6411 , 8.0517 , 3.61296 , -0.496344,-0.598999,-0.628365 --10.8468 , 8.22381 , 3.91339 , 0.850071,0.464556,0.248127 --10.9898 , 8.3541 , 4.20851 , 0.747919,0.40198,-0.528232 --9.37139 , 7.24595 , 3.98677 , 0.260325,0.766114,-0.587622 --9.55223 , 7.40042 , 4.27227 , 0.113359,0.813396,0.570558 --9.61741 , 7.47401 , 4.52894 , 0.366434,0.92238,-0.122233 --9.39003 , 7.33938 , 4.6836 , 0.260325,0.766114,-0.587623 --6.87447 , 5.56921 , 3.9331 , 0.247575,0.92904,0.27494 --4.32239 , 3.75793 , 3.04823 , -0.196689,0.950413,0.240892 --4.17984 , 3.66897 , 3.10382 , -0.143002,0.971115,0.191015 --4.30243 , 3.77221 , 3.27777 , 0.174756,-0.968253,0.178733 --4.12762 , 3.65968 , 3.31405 , 0.85723,0.443424,0.261786 --4.28238 , 3.78562 , 3.51337 , -0.587786,0.808013,0.0402768 --4.2107 , 3.74792 , 3.59969 , -0.630065,0.666172,0.39904 --4.17471 , 3.73661 , 3.70473 , 0.707101,-0.527461,-0.470949 --4.16538 , 3.7449 , 3.8268 , 0.173638,-0.669543,-0.722192 --3.72442 , 3.43186 , 3.68047 , 0.567025,-0.710781,0.416262 --3.89984 , 3.57761 , 3.9152 , -0.36527,0.147732,0.919105 --4.24654 , 3.85131 , 4.27839 , -0.955471,-0.22525,0.190625 --4.19912 , 3.83243 , 4.38589 , -0.895008,-0.230958,-0.381601 --3.95223 , 3.66183 , 4.34485 , 0.582614,0.587784,0.561312 --3.69453 , 3.48233 , 4.28392 , 0.0565295,0.564029,0.823818 --3.56775 , 3.40175 , 4.31547 , -0.15265,0.712201,0.685177 --5.57721 , 4.95826 , 6.13047 , 0.0572611,0.645874,0.761294 --5.22042 , 4.70698 , 6.02426 , -0.0492758,0.659795,0.749828 --5.11501 , 4.64822 , 6.12536 , -0.0885555,0.648041,0.756439 --3.39278 , 3.32967 , 4.70403 , -0.920578,0.376186,-0.104976 --3.32771 , 3.29523 , 4.78295 , 0.968938,-0.229553,0.0920072 --2.99759 , 3.05299 , 4.59223 , -0.335487,0.704386,0.62553 --2.83263 , 2.938 , 4.55412 , -0.0606498,0.635795,0.769471 --2.7652 , 2.89912 , 4.61448 , 0.832161,-0.199447,-0.517425 --2.70826 , 2.87043 , 4.68606 , -0.775599,0.240406,0.583654 --2.65665 , 2.8443 , 4.76364 , -0.704086,0.173743,0.688533 --2.60896 , 2.82245 , 4.84706 , -0.575925,0.109505,0.810135 --2.54932 , 2.79042 , 4.91589 , -0.575925,0.109505,0.810135 --3.13299 , 3.28803 , 5.83232 , 0.768867,0.488687,-0.412344 --1.79668 , 2.20147 , 4.18666 , -0.156191,0.135365,0.978407 --1.72669 , 2.1571 , 4.20837 , 0.285257,-0.116543,-0.951339 --1.71793 , 2.16499 , 4.31774 , -0.00304062,0.99591,0.090303 --1.60752 , 2.08594 , 4.27628 , 0.627548,-0.662173,0.409523 --2.04183 , 2.47156 , 5.09468 , 0.115044,0.939435,0.32284 --2.02655 , 2.47693 , 5.23008 , 0.268261,0.956099,-0.117943 --2.27024 , 2.70866 , 5.81806 , 0.25986,-0.136688,0.955923 --1.84692 , 2.36069 , 5.2542 , 0.234314,0.959457,-0.156652 --1.61667 , 2.17601 , 4.99863 , 0.105799,-0.0632967,0.992371 --1.80197 , 2.36137 , 5.52403 , -0.422843,0.753473,0.50347 --1.70431 , 2.29602 , 5.51821 , 0.422843,-0.753473,-0.50347 --1.38127 , 2.02223 , 5.03003 , 0.235452,0.0386133,-0.971119 --0.666659 , 1.38055 , 3.62602 , -0.420067,-0.648246,-0.635076 --1.23327 , 1.92661 , 5.05494 , 0.227341,-0.450061,-0.863575 --1.16869 , 1.88668 , 5.08655 , -0.900714,0.0949073,0.423919 --0.840744 , 1.59353 , 4.45007 , 0.673362,-0.0871419,0.734159 --0.759453 , 1.53291 , 4.40187 , -0.905371,-0.114058,-0.409015 --0.645134 , 1.43901 , 4.25294 , 0.434141,0.349759,-0.830175 --0.627298 , 1.44102 , 4.37008 , 0.654874,-0.468622,-0.592903 --0.536043 , 1.36819 , 4.26987 , -0.328689,0.944253,0.0187163 --0.562112 , 1.41739 , 4.54185 , -0.88959,0.287472,0.354949 --0.673661 , 1.56148 , 5.1388 , -0.427103,-0.776938,0.462548 --0.646764 , 1.56247 , 5.29734 , 0.996354,0.0836011,-0.0170171 --0.517125 , 1.4483 , 5.06389 , 0.673255,-0.450456,0.58636 --0.382995 , 1.32551 , 4.77906 , -0.825022,-0.50785,-0.247844 --0.306846 , 1.26536 , 4.70673 , 0.658268,0.730186,0.183062 --0.242425 , 1.2196 , 4.67962 , 0.178512,-0.124883,0.97598 --0.228096 , 1.23629 , 4.90901 , -0.582167,-0.0174985,0.812881 --0.176288 , 1.2091 , 4.9665 , 0.620409,0.747792,0.23643 --0.134777 , 1.19618 , 5.09062 , -0.397439,0.220662,0.890702 --0.0615536 , 1.13734 , 5.01099 , -0.469927,-0.476586,0.74299 --0.236936 , 1.47278 , 6.87495 , -0.565858,-0.821325,0.0723171 --0.112523 , 1.35133 , 6.55456 , -0.876698,-0.231551,-0.421645 -0.0364932 , 1.17289 , 5.87729 , 0.6021,-0.778879,0.175568 --2.01531 , 1.81277 , -1.40005 , -0.0665993,-0.107264,0.991997 --2.09442 , 1.86965 , -1.39258 , -0.0912778,-0.0580183,0.994134 --2.2133 , 1.95145 , -1.41899 , -0.0896541,0.0460237,0.994909 --2.32028 , 2.0263 , -1.42916 , -0.0974079,0.0551323,0.993716 --2.44923 , 2.11529 , -1.45311 , -0.0926461,0.0777722,0.992657 --2.57202 , 2.20076 , -1.46645 , -0.0484076,0.0514474,0.997502 --2.70265 , 2.29213 , -1.48099 , -0.09982,0.0399937,0.994201 --2.84888 , 2.39348 , -1.50151 , -0.0843621,-0.00601467,0.996417 --2.96693 , 2.47861 , -1.49561 , -0.0471695,-0.0436431,0.997933 --3.11589 , 2.58276 , -1.50587 , -0.0521364,-0.0496935,0.997403 --3.26405 , 2.68891 , -1.51066 , -0.0880697,-0.0492453,0.994896 --3.4214 , 2.80067 , -1.51453 , -0.0977635,-0.00627219,0.99519 --3.64702 , 2.95657 , -1.55442 , -0.088132,0.0192545,0.995923 --3.84373 , 3.09512 , -1.56737 , 0.0758961,-0.0265157,-0.996763 --4.11002 , 3.27907 , -1.61179 , 0.117111,-0.0837424,-0.989582 --4.38567 , 3.47085 , -1.64994 , -0.0847371,0.0758415,0.993513 --4.67833 , 3.67579 , -1.68545 , -0.0692882,0.0523009,0.996225 --4.99619 , 3.89756 , -1.72067 , -0.137815,0.116523,0.98358 --5.66522 , 4.35196 , -1.91024 , -0.156079,0.16938,0.973113 --6.37079 , 4.83493 , -2.08679 , -0.0494782,0.189703,0.980594 --7.02586 , 5.28693 , -2.21043 , -0.0470891,0.225031,0.973213 --7.92933 , 5.90826 , -2.40737 , 0.0667378,-0.214686,-0.9744 --9.32194 , 6.85955 , -2.75321 , -0.0664256,0.210246,0.975389 --12.2982 , 8.88062 , -3.61373 , -0.103389,0.18504,0.977277 --14.6785 , 10.5154 , -4.14011 , 0.00338578,-0.354869,0.93491 --15.1497 , 10.8724 , -3.95438 , -0.066432,-0.176579,0.982042 --15.1847 , 10.9346 , -3.62052 , 0.135038,0.216601,-0.966876 --21.8093 , 15.4824 , -5.10014 , 0.0477123,-0.881258,0.47022 --22.103 , 15.738 , -4.68965 , 0.014354,-0.841211,0.540517 --22.3906 , 15.9904 , -4.26749 , 0.058129,-0.825001,0.562134 --22.8996 , 16.3963 , -3.88159 , -0.0681206,0.856791,-0.511144 --23.0788 , 16.5767 , -3.41342 , -0.129385,0.849179,-0.51201 --23.0142 , 16.5896 , -2.89862 , -0.129385,0.849179,-0.51201 --47.7553 , 34.0793 , -3.95764 , 0.569199,0.82214,0.00986706 --4.41359 , 3.78517 , 0.947236 , -0.580843,0.813218,-0.036033 --4.36837 , 3.76415 , 1.05197 , -0.580843,0.813218,-0.036033 --4.35323 , 3.76511 , 1.15578 , 0.582961,-0.800038,0.141759 --4.37822 , 3.79518 , 1.26081 , -0.678997,0.686109,-0.261185 --4.41698 , 3.8345 , 1.36858 , -0.771067,0.527071,-0.357284 --4.46308 , 3.87931 , 1.47889 , 0.829924,-0.46143,0.313544 --4.49022 , 3.91213 , 1.58951 , 0.836457,-0.47789,0.268256 --11.8034 , 9.2384 , 2.66579 , -0.756357,0.324353,0.568084 --11.387 , 8.96564 , 2.87178 , -0.875503,-0.461823,0.142179 --10.7783 , 8.55058 , 3.02701 , 0.0823729,0.701429,0.707963 --11.0143 , 8.75179 , 3.32498 , -0.970349,-0.217457,0.105528 --10.3002 , 8.25523 , 3.42588 , 0.527558,0.58087,0.619898 --10.8761 , 8.70788 , 3.81052 , -0.826837,-0.557263,-0.0761503 --10.8131 , 8.69126 , 4.05394 , 0.677939,0.645439,-0.351863 --11.0373 , 8.88691 , 4.37974 , -0.896446,-0.364697,0.251754 --10.0574 , 8.18542 , 4.34228 , -0.123445,0.650956,0.749011 --8.12667 , 6.76623 , 3.94166 , -0.400742,-0.591079,0.700022 --8.96433 , 7.4197 , 4.44966 , 0.390908,0.736309,0.552305 --5.56205 , 4.876 , 3.37016 , -0.76131,0.494268,-0.419651 --5.52078 , 4.86154 , 3.5018 , -0.846441,0.395242,-0.356821 --5.55276 , 4.90238 , 3.66555 , -0.872492,0.361065,-0.329227 --4.01428 , 3.74516 , 3.11169 , -0.190007,0.981776,-0.00351989 --4.43009 , 4.07696 , 3.42916 , 0.658286,-0.721293,-0.215395 --6.38017 , 5.59215 , 4.55341 , 0.00751186,-0.301206,0.95353 --4.13582 , 3.8789 , 3.53025 , 0.303317,-0.952269,-0.0343822 --4.02264 , 3.80458 , 3.59093 , -0.427579,0.750265,0.504261 --3.98022 , 3.7862 , 3.68983 , -0.0269711,0.793878,0.607478 --3.70258 , 3.58372 , 3.64327 , 0.253277,0.40276,0.879565 --3.73623 , 3.6237 , 3.78572 , -0.898199,-0.26411,-0.351404 --3.86478 , 3.73914 , 3.99614 , -0.666913,-0.694798,-0.269226 --3.74867 , 3.6614 , 4.04383 , 0.989893,0.0851448,-0.113408 --4.23531 , 4.06304 , 4.53237 , -0.962702,-0.258223,-0.0807852 --4.15251 , 4.01368 , 4.61629 , -0.93126,-0.339401,0.132519 --4.28689 , 4.13802 , 4.87279 , 0.926144,0.330777,-0.181229 --3.34452 , 3.39572 , 4.24403 , 0.117817,0.99224,0.0397509 --3.30637 , 3.37996 , 4.34037 , 0.302503,-0.95085,0.0661573 --3.19686 , 3.30604 , 4.37324 , -0.0564992,-0.708279,0.703668 --2.97461 , 3.1395 , 4.29698 , 0.420457,0.880688,0.218186 --2.89233 , 3.08586 , 4.34441 , -0.205924,0.78106,0.589526 --2.8408 , 3.05828 , 4.41996 , -0.233845,0.778735,0.582141 --2.78747 , 3.02903 , 4.49468 , -0.335486,0.704387,0.62553 --2.7579 , 3.01813 , 4.59401 , -0.0204078,0.716391,0.697401 --2.7313 , 3.01142 , 4.69988 , -0.795671,0.180878,0.578093 --3.47607 , 3.65652 , 5.71439 , -0.737207,-0.512774,0.439987 --3.41541 , 3.62502 , 5.8174 , 0.809476,0.445505,-0.382458 --1.60524 , 2.0978 , 3.70782 , -0.338638,-0.293674,0.893913 --1.50545 , 2.02374 , 3.67771 , 0.670078,0.2199,-0.708971 --2.14925 , 2.59227 , 4.65649 , -0.317284,-0.90831,-0.272589 --2.08365 , 2.55077 , 4.70199 , -0.428926,-0.849433,-0.307385 --2.02315 , 2.51281 , 4.75341 , 0.515398,0.802348,0.301004 --1.62594 , 2.17876 , 4.29136 , 0.633072,-0.429615,0.643934 --1.62946 , 2.19562 , 4.42421 , -0.887476,0.449113,-0.103363 --3.09126 , 3.52399 , 6.96935 , -0.241829,0.680981,0.691219 --3.04293 , 3.50702 , 7.12264 , -0.480776,0.721204,0.498718 --1.69222 , 2.30082 , 4.95782 , -0.19021,-0.0910384,0.977513 --1.62482 , 2.2566 , 4.99236 , -0.348801,-0.241917,0.905436 --1.79338 , 2.43263 , 5.48267 , -0.295217,0.927425,0.229631 --1.69338 , 2.36004 , 5.47002 , -0.295217,0.927425,0.229631 --1.40875 , 2.11118 , 5.06124 , 0.150492,0.309788,-0.93882 --0.659645 , 1.41172 , 3.59216 , -0.420067,-0.648246,-0.635076 --1.23165 , 1.98022 , 5.02147 , -0.0856349,0.338988,0.936885 --0.550675 , 1.33143 , 3.56836 , 0.696387,0.352709,0.625013 --0.862774 , 1.65652 , 4.47408 , -0.726568,0.0802647,-0.68239 --0.76497 , 1.57668 , 4.38335 , 0.475762,0.00477042,0.879561 --0.673992 , 1.50181 , 4.29829 , 0.768818,0.22331,-0.59921 --0.629035 , 1.47422 , 4.33552 , 0.588528,0.123067,-0.799055 --0.606352 , 1.47014 , 4.44431 , -0.590181,0.721657,0.361799 --0.485691 , 1.36185 , 4.24371 , -0.293332,-0.0159535,-0.955877 --0.479236 , 1.3749 , 4.4056 , -0.718969,0.632999,-0.287047 --0.604746 , 1.53909 , 5.06759 , -0.527198,-0.193324,-0.827459 --0.451992 , 1.39279 , 4.7322 , -0.30931,0.190025,0.931782 --0.445155 , 1.4127 , 4.95291 , 0.353849,0.917865,0.179764 --0.319615 , 1.2925 , 4.67539 , -0.901029,-0.3067,0.306728 --0.282716 , 1.27617 , 4.77249 , -0.56098,-0.474104,-0.678621 --0.21703 , 1.22596 , 4.73558 , -0.406777,0.365527,-0.837211 --0.160902 , 1.18673 , 4.74523 , -0.965872,-0.0908536,0.242563 --0.129317 , 1.18211 , 4.89757 , -0.59963,-0.551744,-0.579674 --0.0858076 , 1.16252 , 5.00206 , 0.966349,0.0452362,-0.253227 --0.263944 , 1.49135 , 6.78528 , -0.854695,-0.519129,0.00160515 --0.120754 , 1.33431 , 6.30051 , 0.766054,0.629177,0.131519 --0.0982607 , 1.37912 , 6.83736 , -0.389046,-0.904546,0.174471 --1.89124 , 1.84247 , -1.3822 , -0.0929958,-0.0139546,0.995569 --1.97427 , 1.9049 , -1.38306 , -0.0804425,-0.0205833,0.996547 --2.07694 , 1.98153 , -1.39979 , -0.0928014,0.0624416,0.993725 --2.19406 , 2.06737 , -1.42482 , -0.0937328,0.0993618,0.990627 --2.306 , 2.14986 , -1.43956 , -0.103122,0.0980025,0.989829 --2.44622 , 2.25221 , -1.47343 , -0.0767795,0.0708081,0.994531 --2.55304 , 2.33326 , -1.47379 , -0.0472735,0.0478273,0.997736 --2.6742 , 2.42481 , -1.48119 , -0.0478184,0.0406259,0.99803 --2.81095 , 2.5263 , -1.49476 , -0.0446139,0.0270331,0.998639 --2.94809 , 2.62898 , -1.50309 , -0.00664414,0.0147377,0.999869 --3.06496 , 2.71826 , -1.49095 , -0.0134037,0.0454909,0.998875 --3.23963 , 2.84823 , -1.51389 , -0.0460233,0.0344389,0.998347 --3.41578 , 2.97997 , -1.53004 , -0.0836012,0.0689327,0.994112 --3.63715 , 3.14283 , -1.56676 , -0.0325018,0.073489,0.996766 --3.78602 , 3.25776 , -1.55026 , -0.0756126,0.0930202,0.992789 --4.1358 , 3.51212 , -1.64383 , -0.109844,-0.0286437,0.993536 --4.40685 , 3.71311 , -1.67766 , 0.237918,0.0928379,-0.966838 --4.74612 , 3.96474 , -1.73633 , -0.0507243,0.0919136,0.994474 --5.23266 , 4.31956 , -1.85353 , -0.142743,0.169841,0.975079 --5.98143 , 4.86175 , -2.07484 , -0.0877921,0.206681,0.974462 --6.6742 , 5.36874 , -2.23684 , -0.0525084,0.226219,0.97266 --7.40395 , 5.90393 , -2.38308 , -0.0479895,0.238853,0.969869 --8.58503 , 6.76516 , -2.68233 , -0.0643453,0.219212,0.973553 --11.2885 , 8.71887 , -3.51637 , -0.0589463,0.24418,0.967937 --13.8075 , 10.5546 , -4.16159 , 0.0886793,0.363735,-0.927272 --14.1196 , 10.815 , -3.94269 , -0.0162862,-0.513858,0.857721 --14.1163 , 10.8482 , -3.61137 , -0.0594184,-0.542225,0.83813 --20.5729 , 15.5614 , -5.19259 , -0.0460716,0.901408,-0.430513 --20.7679 , 15.7539 , -4.77601 , -0.0460716,0.901408,-0.430513 --21.131 , 16.0699 , -4.39565 , 0.0317079,-0.893469,0.448004 --21.1235 , 16.1169 , -3.91674 , -0.00324708,-0.865802,0.500377 --30.6348 , 23.1499 , -5.41184 , 0.214842,-0.955437,0.202446 --30.7404 , 23.3018 , -4.74961 , 0.214842,-0.955437,0.202446 --30.8933 , 23.4886 , -4.09241 , 0.214842,-0.955436,0.202446 --31.0126 , 23.6513 , -3.42539 , 0.214842,-0.955436,0.202446 --31.1057 , 23.7962 , -2.7514 , 0.173532,-0.958546,0.226001 --31.1975 , 23.9396 , -2.07386 , 0.173532,-0.958546,0.226001 --31.28 , 24.0762 , -1.39187 , 0.173532,-0.958546,0.226001 --31.4015 , 24.2428 , -0.708529 , 0.173532,-0.958546,0.226001 --4.24852 , 3.8735 , 0.881302 , 0.589516,-0.807691,-0.0102951 --4.21234 , 3.85769 , 0.985115 , 0.579811,-0.809266,0.0943782 --4.231 , 3.88264 , 1.08818 , 0.646849,-0.711706,0.273972 --4.25595 , 3.91258 , 1.19262 , -0.666178,0.655742,-0.35526 --4.31104 , 3.96635 , 1.29993 , 0.675096,-0.63236,0.379955 --11.6191 , 9.56736 , 1.96382 , 0.474304,-0.780879,-0.406528 --11.6458 , 9.61748 , 2.23441 , 0.474303,-0.780878,-0.406528 --11.6051 , 9.61511 , 2.49968 , 0.475624,-0.531829,-0.700671 --10.971 , 9.15581 , 2.67953 , -0.242523,0.414255,0.877254 --11.0823 , 9.2701 , 2.95586 , -0.874758,-0.440879,0.20106 --11.2437 , 9.42338 , 3.24873 , -0.918685,-0.300406,0.256465 --11.3992 , 9.57477 , 3.54955 , -0.918685,-0.300406,0.256465 --10.0555 , 8.55332 , 3.50876 , 0.287138,0.953033,0.0963374 --13.2762 , 11.1075 , 4.58235 , -0.671148,-0.741322,0.00154692 --13.5003 , 11.3188 , 4.96817 , 0.642876,0.765041,-0.0377226 --11.3894 , 9.68749 , 4.65714 , 0.919309,0.362625,-0.152882 --10.6091 , 9.10068 , 4.68592 , 0.613748,0.729405,-0.302129 --5.36769 , 4.9625 , 3.10741 , -0.732646,0.6004,-0.320545 --5.2938 , 4.91883 , 3.2233 , -0.776028,0.515513,-0.363354 --3.95117 , 3.86091 , 2.82804 , -0.198202,0.959019,0.202479 --5.37823 , 5.01887 , 3.54904 , 0.739911,-0.544015,0.395701 --6.49583 , 5.93528 , 4.20488 , -0.24208,0.809431,0.534994 --5.57492 , 5.21083 , 3.94567 , 0.654346,-0.674206,0.34246 --5.56242 , 5.21856 , 4.09925 , 0.210416,-0.901045,0.379266 --5.71241 , 5.35743 , 4.34133 , -0.332701,-0.885822,0.323464 --3.90306 , 3.89682 , 3.49955 , 0.0019813,-0.987194,0.159511 --5.53103 , 5.24669 , 4.57649 , -0.384445,0.643358,-0.662037 --3.83494 , 3.86775 , 3.70433 , 0.272528,0.915712,0.295298 --3.62553 , 3.70882 , 3.69498 , 0.247074,0.295118,0.922962 --3.43299 , 3.56261 , 3.68632 , 0.0269266,0.803154,0.595162 --3.36411 , 3.51689 , 3.75595 , 0.549016,-0.618822,-0.56182 --3.30695 , 3.48298 , 3.83303 , -0.65684,0.427554,0.621095 --3.25647 , 3.45359 , 3.91384 , -0.355463,0.775643,0.521559 --3.19834 , 3.41781 , 3.98813 , 0.518885,-0.543909,-0.659486 --3.12599 , 3.36973 , 4.05053 , 0.547652,-0.454654,-0.702401 --3.04761 , 3.31641 , 4.10501 , 0.552981,-0.391357,-0.735562 --2.98055 , 3.27305 , 4.16862 , 0.609616,-0.317709,-0.726243 --2.92018 , 3.23424 , 4.23605 , 0.725422,-0.221783,-0.651594 --2.87024 , 3.20543 , 4.31391 , 0.822074,-0.0983309,-0.560825 --2.83198 , 3.18601 , 4.40287 , -0.14717,0.854491,0.498184 --2.80448 , 3.17594 , 4.50371 , -0.308797,0.778495,0.546434 --7.92829 , 7.67452 , 10.2107 , -0.0675887,-0.679866,0.730215 --3.57388 , 3.8825 , 5.64322 , 0.556881,0.630014,-0.541264 --3.45913 , 3.79947 , 5.68408 , -0.737207,-0.512774,0.439987 --1.65845 , 2.21752 , 3.66911 , -0.338638,-0.293674,0.893913 --1.59677 , 2.17322 , 3.69142 , -0.338638,-0.293674,0.893913 --7.71059 , 7.68413 , 11.8094 , -0.176882,-0.580056,0.795141 --1.46952 , 2.08105 , 3.72336 , 0.670078,0.2199,-0.708971 --1.82767 , 2.41809 , 4.33268 , 0.188074,-0.106737,0.976338 --1.80364 , 2.40992 , 4.42338 , -0.226163,0.409352,0.883901 --1.59195 , 2.22821 , 4.23092 , -0.891827,0.244695,-0.380484 --1.66854 , 2.31389 , 4.47651 , 0.427672,0.78482,0.448502 --1.60403 , 2.26689 , 4.50437 , 0.464906,-0.844184,0.266865 --1.5339 , 2.21652 , 4.52261 , 0.464905,-0.844184,0.266865 --2.79763 , 3.43247 , 6.90941 , -0.312074,0.698527,0.643948 --1.61142 , 2.32296 , 4.95339 , -0.19021,-0.0910384,0.977513 --1.66411 , 2.39013 , 5.2143 , -0.157439,0.543704,0.824378 --1.68767 , 2.43293 , 5.43816 , -0.239425,-0.958556,-0.154425 --1.50792 , 2.27672 , 5.24939 , -0.224454,-0.50927,-0.830821 --1.32383 , 2.11278 , 5.02856 , 0.00320611,0.0854467,0.996338 --1.23934 , 2.04758 , 5.01278 , 0.0284588,0.290198,0.956543 --1.17772 , 2.00454 , 5.04611 , -0.256587,0.310545,0.915273 --1.13638 , 1.9823 , 5.13017 , -0.900714,0.0949073,0.423919 --0.765908 , 1.61746 , 4.35588 , 0.475762,0.00477065,0.879561 --0.733563 , 1.60087 , 4.43111 , 0.475762,0.00477042,0.879561 --0.637959 , 1.51787 , 4.32756 , -0.348794,-0.047838,0.935978 --0.58165 , 1.47475 , 4.32885 , -0.224724,0.15317,0.962309 --0.50288 , 1.40755 , 4.25605 , 0.34921,-0.891456,0.288719 --0.453843 , 1.37242 , 4.27196 , -0.580302,-0.111668,0.806709 --0.68195 , 1.65499 , 5.28081 , 0.792074,-0.429202,-0.434055 --0.442507 , 1.40375 , 4.63422 , 0.65292,0.738481,-0.168347 --0.508506 , 1.50805 , 5.13429 , 0.686274,0.444596,0.575641 --0.378193 , 1.37806 , 4.8507 , -0.741792,0.646083,-0.17978 --0.297187 , 1.30575 , 4.75085 , 0.52186,0.796669,0.304928 --0.233221 , 1.25303 , 4.715 , -0.273718,0.698461,-0.661234 --0.257738 , 1.31987 , 5.15497 , 0.845351,0.481696,0.230978 --0.174528 , 1.24421 , 5.03148 , 0.686333,-0.571875,-0.44934 --0.118014 , 1.20258 , 5.05033 , -0.284517,0.898831,-0.333395 --0.052488 , 1.14953 , 5.00963 , -0.463225,-0.472207,0.749962 --0.19651 , 1.43317 , 6.62079 , 0.783408,0.521292,0.338418 --0.104143 , 1.35348 , 6.52427 , 0.734057,0.433699,0.522557 -0.037202 , 1.1768 , 5.88684 , 0.6021,-0.778879,0.175567 --1.78132 , 1.87651 , -1.37553 , -0.0667123,0.0435478,0.996822 --1.86827 , 1.94449 , -1.38472 , -0.104991,0.0544638,0.992981 --1.9617 , 2.01868 , -1.39713 , -0.051022,0.0701207,0.996233 --2.05636 , 2.09386 , -1.40616 , 0.0861182,-0.0881362,-0.992379 --2.17174 , 2.18378 , -1.42971 , -0.104637,0.0963925,0.989828 --2.29394 , 2.2793 , -1.45474 , -0.122336,0.0928461,0.988136 --2.42473 , 2.38194 , -1.48098 , -0.0574476,0.049884,0.997101 --2.53003 , 2.46609 , -1.47977 , -0.0136442,0.030229,0.99945 --2.64847 , 2.56152 , -1.48547 , -0.0544272,0.0368525,0.997837 --2.78252 , 2.66694 , -1.49717 , -0.0312436,0.0511718,0.998201 --2.91674 , 2.77451 , -1.50371 , 0.0011728,0.0563135,0.998412 --3.05888 , 2.88829 , -1.51009 , -0.0104864,0.0699492,0.997495 --3.2307 , 3.0234 , -1.53017 , -0.040903,0.108225,0.993285 --3.44603 , 3.19217 , -1.57168 , -0.0272441,0.123883,0.991923 --3.66299 , 3.36316 , -1.60447 , -0.0290827,0.113801,0.993078 --3.92496 , 3.56795 , -1.65471 , -0.0939618,0.0939542,0.991133 --4.19609 , 3.78163 , -1.6984 , -0.153423,-0.249609,0.956115 --4.39648 , 3.94334 , -1.69023 , 0.277416,0.301459,-0.91223 --4.78095 , 4.24349 , -1.77166 , -0.198251,0.0582311,0.97842 --5.49516 , 4.792 , -2.0023 , -0.131905,0.201397,0.970588 --6.30429 , 5.41707 , -2.24579 , -0.0550409,0.235093,0.970413 --6.96252 , 5.93132 , -2.38218 , -0.0284285,0.23984,0.970396 --7.92642 , 6.67976 , -2.62118 , -0.054577,0.229361,0.97181 --8.98793 , 7.50685 , -2.85601 , -0.061079,0.221039,0.973351 --12.7461 , 10.3955 , -4.08575 , -0.156091,0.0293664,0.987306 --14.0815 , 11.4489 , -4.26115 , 0.0162862,0.513858,-0.85772 --19.4031 , 15.6159 , -5.27452 , 0.0907632,-0.836425,0.540513 --19.5249 , 15.7584 , -4.85486 , 0.0907632,-0.836425,0.540513 --19.8433 , 16.0516 , -4.48514 , 0.0907632,-0.836425,0.540514 --19.7833 , 16.0544 , -4.0098 , -0.120871,0.839604,-0.529581 --29.4949 , 23.6694 , -5.75026 , 0.214842,-0.955436,0.202446 --29.5098 , 23.7512 , -5.07962 , 0.214842,-0.955436,0.202446 --20.3627 , 16.7012 , -2.28265 , -0.0805643,0.92745,-0.365166 --29.3594 , 23.8439 , -3.0493 , 0.214842,-0.955437,0.202446 --4.69206 , 4.40426 , 0.442636 , 0.434668,0.842925,0.317081 --4.61511 , 4.35493 , 0.565281 , 0.462469,0.832348,0.305483 --4.13027 , 3.98163 , 0.712948 , -0.573383,0.816118,0.0719982 --4.10497 , 3.9728 , 0.817149 , 0.571016,-0.815797,-0.0917401 --4.08674 , 3.96861 , 0.920083 , 0.597264,-0.801992,0.00921059 --4.08234 , 3.97611 , 1.02233 , 0.599542,-0.796417,0.0791727 --4.11586 , 4.01316 , 1.12546 , -0.41707,0.890657,-0.181059 --11.3641 , 9.87614 , 1.52783 , 0.474304,-0.780878,-0.406528 --11.3115 , 9.86095 , 1.79102 , 0.474304,-0.780878,-0.406528 --11.301 , 9.88084 , 2.05662 , 0.474303,-0.780879,-0.406528 --11.2953 , 9.90326 , 2.32365 , 0.474303,-0.780878,-0.406528 --11.3629 , 9.98703 , 2.60118 , -0.64615,0.676864,0.352627 --5.74956 , 5.41708 , 2.00515 , 0.656024,0.754403,-0.0225448 --5.77356 , 5.45279 , 2.15369 , 0.656024,0.754403,-0.0225449 --5.81953 , 5.50472 , 2.30865 , 0.656024,0.754403,-0.0225449 --5.86907 , 5.56163 , 2.46809 , 0.656024,0.754403,-0.0225449 --5.93246 , 5.62964 , 2.63415 , 0.656024,0.754403,-0.0225448 --5.98434 , 5.68986 , 2.80171 , 0.712447,0.694572,0.0999469 --6.07191 , 5.77873 , 2.98367 , 0.786919,0.616152,0.0333973 --5.13597 , 5.01221 , 2.84363 , -0.214816,-0.831752,-0.511901 --5.09586 , 4.99353 , 2.96873 , -0.0134635,0.983369,0.181118 --3.78852 , 3.90772 , 2.62483 , -0.19459,0.962868,0.187137 --3.71737 , 3.85935 , 2.70468 , -0.193174,0.959618,0.204491 --3.68874 , 3.8469 , 2.80049 , -0.0615859,0.986268,0.153243 --3.69587 , 3.86336 , 2.91188 , 0.0501401,-0.981606,-0.184219 --3.67191 , 3.85479 , 3.01068 , -0.0854185,0.968264,0.23488 --3.58222 , 3.78969 , 3.0776 , 0.268447,-0.815749,-0.512338 --3.53526 , 3.76112 , 3.1632 , -0.43086,0.682535,0.590344 --3.47999 , 3.72523 , 3.24367 , 0.353432,-0.847251,-0.39655 --3.43012 , 3.69436 , 3.32672 , -0.488625,0.776047,0.398743 --3.38037 , 3.66219 , 3.40842 , 0.580104,-0.709369,-0.400344 --3.34233 , 3.64178 , 3.49737 , -0.600568,0.713245,0.361385 --3.29696 , 3.61426 , 3.58108 , 0.54447,-0.722054,-0.426838 --3.25075 , 3.58527 , 3.66374 , -0.615651,0.624387,0.480744 --3.21003 , 3.56157 , 3.75014 , -0.665392,0.542307,0.512988 --3.17503 , 3.54223 , 3.84058 , 0.71959,-0.38291,-0.579284 --3.13149 , 3.51646 , 3.9255 , 0.796683,-0.180143,-0.576927 --3.08031 , 3.48435 , 4.0041 , 0.754627,-0.177621,-0.631656 --3.02269 , 3.44509 , 4.07626 , -0.843989,-0.135744,0.518899 --2.98863 , 3.42753 , 4.1691 , -0.941578,-0.2395,0.236792 --3.0755 , 3.51914 , 4.37527 , -0.751489,0.659745,0.000728057 --3.06773 , 3.5261 , 4.49917 , -0.814261,0.540537,0.211656 --3.05092 , 3.52456 , 4.61826 , 0.613168,-0.773906,-0.15841 --3.03219 , 3.52261 , 4.73768 , -0.51785,0.830276,0.206088 --8.14368 , 8.22395 , 10.4337 , -0.0675887,-0.679866,0.730215 --7.91211 , 8.04962 , 10.5337 , -0.0675889,-0.679866,0.730215 --7.73254 , 7.92093 , 10.6852 , -0.0675886,-0.679866,0.730215 --6.88454 , 7.17044 , 10.0207 , 0.241179,-0.776647,0.581938 --7.05793 , 7.36842 , 10.5806 , -0.0759901,-0.694231,0.71573 --1.56323 , 2.23794 , 3.74457 , -0.338638,-0.293674,0.893913 --2.08106 , 2.73877 , 4.55252 , -0.712258,0.164465,-0.682378 --1.82197 , 2.50661 , 4.32041 , -0.32783,-0.574971,-0.749624 --1.72912 , 2.43103 , 4.31017 , 0.351158,0.837201,0.419264 --1.62352 , 2.34278 , 4.27434 , -0.915791,0.140475,-0.37629 --1.50938 , 2.24542 , 4.22003 , 0.0283671,-0.0647919,0.997496 --1.58406 , 2.33074 , 4.46615 , -0.941855,0.28322,0.180818 --1.58427 , 2.34512 , 4.60114 , 0.761205,-0.628996,-0.157897 --1.58517 , 2.36157 , 4.74527 , -0.670678,0.713986,-0.201037 --1.66908 , 2.46125 , 5.04964 , -0.68956,0.704975,-0.165883 --1.53605 , 2.34398 , 4.95735 , 0.836014,-0.234196,-0.496219 --1.55383 , 2.37852 , 5.15329 , -0.106666,0.839506,0.532777 --1.49843 , 2.3401 , 5.21162 , -0.0630695,0.727153,0.683572 --1.43096 , 2.29005 , 5.24348 , 0.155849,0.60217,0.783008 --2.43023 , 3.34896 , 7.69582 , 0.220396,-0.848751,-0.480673 --1.17631 , 2.06212 , 5.02139 , -0.35086,0.0212675,0.936186 --1.1861 , 2.09132 , 5.22653 , -0.830387,-0.493007,0.259618 --1.06916 , 1.98672 , 5.1203 , -0.900714,0.0949075,0.423919 --0.898025 , 1.82137 , 4.85185 , 0.575535,-0.0109138,0.817704 --0.660804 , 1.57938 , 4.36378 , 0.393726,-0.399722,0.827769 --0.58987 , 1.51732 , 4.32161 , -0.276589,0.201127,0.939706 --0.546503 , 1.48683 , 4.35814 , 0.529064,-0.748095,-0.400557 --0.453222 , 1.39831 , 4.23028 , -0.512885,-0.223819,0.828767 --0.424118 , 1.38338 , 4.30963 , -0.950014,0.0528918,0.307694 --0.478805 , 1.46988 , 4.71208 , -0.963729,0.0279775,-0.265412 --0.390317 , 1.38561 , 4.58886 , -0.884263,-0.314903,0.344841 --0.360302 , 1.37215 , 4.69662 , 0.686078,0.025275,0.727089 --0.331671 , 1.36287 , 4.82296 , -0.217601,-0.272186,0.937318 --0.321799 , 1.37886 , 5.05372 , 0.310078,0.922998,0.227874 --0.189465 , 1.23307 , 4.6761 , -0.44457,-0.280696,0.850628 --0.183522 , 1.25763 , 4.95367 , 0.367261,0.828642,0.422459 --0.112081 , 1.19148 , 4.86703 , 0.9984,-0.00630959,-0.0561934 --0.0789246 , 1.18027 , 5.01984 , -0.615671,-0.602379,0.508025 --0.0234703 , 1.13747 , 5.03682 , -0.284859,-0.597177,0.749823 --0.100085 , 1.31949 , 6.18277 , -0.588174,-0.764404,0.264079 --0.0204638 , 1.24954 , 6.12309 , 0.0844212,-0.770626,0.631671 --1.59963 , 1.84499 , -1.36608 , -0.0831281,0.0127424,0.996457 --1.6707 , 1.90553 , -1.36686 , -0.0825776,0.0172266,0.996436 --1.74941 , 1.97136 , -1.37155 , -0.098247,0.060264,0.993336 --1.85177 , 2.05723 , -1.39909 , 0.0766571,-0.0732558,-0.994363 --1.93839 , 2.12922 , -1.40381 , -0.0669295,0.074408,0.994979 --2.04328 , 2.2173 , -1.4237 , -0.0947933,0.0837021,0.991972 --2.14295 , 2.30193 , -1.43369 , -0.099853,0.0954153,0.990417 --2.26341 , 2.40154 , -1.45715 , -0.123202,0.0770249,0.989388 --2.38496 , 2.50339 , -1.47615 , -0.0635131,0.0588976,0.996242 --2.50058 , 2.60072 , -1.48454 , -0.00378854,0.0476788,0.998856 --2.62381 , 2.70496 , -1.49404 , -0.0266764,0.0668317,0.997408 --2.75495 , 2.81532 , -1.50375 , -0.0303947,0.0793961,0.99638 --2.90668 , 2.94337 , -1.52373 , 0.0159641,0.0852438,0.996232 --3.03959 , 3.05641 , -1.52267 , -0.0123827,0.0841628,0.996375 --3.22786 , 3.21314 , -1.55441 , 0.0663389,-0.136126,-0.988468 --3.44631 , 3.39501 , -1.59727 , -0.00245139,0.104231,0.99455 --3.58163 , 3.51261 , -1.57707 , 0.0283504,-0.127879,-0.991385 --3.8305 , 3.71976 , -1.6206 , -0.031182,-0.385741,0.92208 --3.95304 , 3.82823 , -1.57847 , 0.0897782,0.640364,-0.762807 --4.01782 , 3.89221 , -1.49938 , 0.165752,0.837816,-0.520183 --4.13927 , 4.00115 , -1.44864 , 0.189398,0.883362,-0.428719 --4.14493 , 4.01691 , -1.3338 , 0.254971,0.863131,-0.435885 --6.54866 , 5.95879 , -2.38346 , -0.0310209,0.241621,0.969875 --7.32495 , 6.60294 , -2.56662 , -0.0438592,0.242708,0.969108 --8.277 , 7.39072 , -2.78926 , -0.0614543,0.231762,0.970829 --10.9136 , 9.55007 , -3.66146 , -0.0144855,0.200691,0.979547 --12.5446 , 10.9039 , -4.01852 , -0.104307,0.0408144,0.993707 --12.5361 , 10.9282 , -3.70361 , -0.104307,0.0408144,0.993707 --12.6953 , 11.0889 , -3.44823 , -0.156091,0.0293663,0.987306 --18.8026 , 16.175 , -4.61771 , 0.0907633,-0.836425,0.540513 --18.9294 , 16.3251 , -4.20242 , 0.14755,-0.851246,0.503597 --19.3072 , 16.683 , -3.84535 , -0.179364,0.898965,-0.399612 --4.31375 , 4.29071 , -0.0379326 , 0.332733,0.940558,0.0681099 --4.29925 , 4.28964 , 0.075633 , -0.334083,-0.929187,-0.158114 --4.22229 , 4.23633 , 0.199383 , 0.262488,0.937068,0.230225 --4.04458 , 4.09949 , 0.3347 , 0.122116,0.973673,0.192481 --4.00201 , 4.07381 , 0.444198 , -0.292852,0.954326,0.059158 --3.98143 , 4.06732 , 0.54896 , -0.313969,0.945853,0.082377 --3.96692 , 4.06518 , 0.652284 , 0.400969,-0.915008,-0.044556 --3.97384 , 4.0816 , 0.753623 , -0.39168,0.917419,0.0702112 --3.9568 , 4.07663 , 0.856439 , 0.430763,-0.902399,0.0109181 --3.93775 , 4.07101 , 0.958525 , 0.287739,-0.950087,-0.120589 --3.95607 , 4.09663 , 1.06013 , -0.143513,0.978927,0.145276 --3.84385 , 4.01153 , 1.15894 , -0.0423185,0.879131,0.474699 --3.69221 , 3.89116 , 1.25128 , 0.249557,-0.950802,-0.183566 --3.68388 , 3.89429 , 1.3473 , 0.280173,-0.955967,-0.0873496 --3.69773 , 3.91494 , 1.44553 , -0.500674,0.859143,-0.105824 --3.70871 , 3.93508 , 1.5447 , -0.487344,0.86749,-0.0997901 --3.70421 , 3.94062 , 1.64266 , -0.505074,0.86194,-0.0442596 --3.69072 , 3.93945 , 1.73932 , -0.533647,0.845625,-0.0117849 --3.68351 , 3.94326 , 1.83726 , -0.57032,0.821422,-0.00116779 --3.66751 , 3.93933 , 1.9337 , -0.618209,0.785912,0.0126417 --3.66488 , 3.94678 , 2.03356 , -0.665041,0.745715,0.0403632 --3.65324 , 3.94743 , 2.13173 , 0.709156,-0.702652,-0.0581155 --3.63397 , 3.93948 , 2.22788 , -0.715234,0.695612,0.0675683 --3.61982 , 3.93739 , 2.32593 , -0.765049,0.63754,0.0907872 --3.61204 , 3.94054 , 2.42642 , 0.601089,-0.798998,-0.0171409 --3.5809 , 3.92366 , 2.5191 , 0.592864,-0.799244,-0.0985935 --3.56943 , 3.92482 , 2.6195 , 0.732893,-0.647165,-0.209869 --3.53671 , 3.90527 , 2.71126 , 0.608733,-0.723497,-0.325571 --3.50196 , 3.88501 , 2.80209 , -0.719001,0.566275,0.402952 --3.4726 , 3.86976 , 2.8954 , 0.638648,-0.647932,-0.415106 --3.436 , 3.84767 , 2.98463 , 0.682163,-0.633711,-0.364779 --3.3976 , 3.82391 , 3.07304 , -0.707814,0.594167,0.382054 --3.35912 , 3.79988 , 3.16027 , -0.852327,0.384396,0.354652 --3.33256 , 3.7866 , 3.25467 , 0.721922,-0.507737,-0.47014 --3.30424 , 3.77176 , 3.34874 , 0.786728,-0.420402,-0.452019 --3.27489 , 3.75656 , 3.44224 , 0.743814,-0.5373,-0.397556 --3.25129 , 3.74573 , 3.53988 , 0.878959,-0.314959,-0.358095 --3.2332 , 3.74031 , 3.64175 , 0.974685,0.0393459,-0.220094 --3.21896 , 3.73898 , 3.74867 , 0.972514,0.106832,-0.206892 --3.21684 , 3.74902 , 3.86549 , 0.953916,0.164787,-0.250777 --3.19265 , 3.73914 , 3.96841 , -0.912879,-0.0633092,0.40329 --3.13583 , 3.699 , 4.04543 , -0.893083,-0.179922,0.412349 --3.06037 , 3.64011 , 4.10506 , 0.899369,0.232637,-0.370154 --3.07013 , 3.66182 , 4.23861 , -0.964302,-0.248191,0.0923221 --3.0228 , 3.62985 , 4.32346 , -0.95422,-0.270795,0.127023 --2.9859 , 3.60791 , 4.41885 , 0.897898,-0.411963,-0.155133 --2.95949 , 3.59617 , 4.52553 , -0.635961,0.751069,0.177339 --2.92547 , 3.57811 , 4.6261 , 0.544999,-0.818153,-0.183306 --2.90714 , 3.57406 , 4.74504 , -0.498027,0.830979,0.247876 --2.88711 , 3.56863 , 4.86442 , -0.504082,0.815074,0.285581 --8.09317 , 8.63287 , 11.1128 , -0.176882,-0.580056,0.795141 --8.00696 , 8.58733 , 11.3915 , -0.176882,-0.580056,0.79514 --1.5854 , 2.3508 , 3.77582 , -0.709187,-0.311952,0.632249 --1.4846 , 2.26121 , 3.74302 , 0.676926,0.246685,-0.693483 --3.43062 , 4.20584 , 6.59323 , -0.922358,-0.272933,0.273429 --1.76543 , 2.56255 , 4.3638 , -0.32783,-0.574971,-0.749624 --1.59723 , 2.40712 , 4.23597 , 0.967026,-0.201643,0.155569 --3.04273 , 3.88059 , 6.64388 , 0.870728,-0.014464,-0.491552 --1.52454 , 2.35753 , 4.3675 , -0.927256,0.306048,-0.215709 --1.38711 , 2.23053 , 4.26396 , -0.231255,0.908295,-0.348598 --1.51682 , 2.37671 , 4.62123 , 0.761205,-0.628996,-0.157896 --1.60762 , 2.48549 , 4.93085 , -0.878489,0.470281,-0.0842174 --1.56988 , 2.461 , 5.01495 , 0.83487,0.316159,-0.450594 --1.48929 , 2.39324 , 5.01765 , -0.815641,0.313472,0.486277 --1.48434 , 2.40541 , 5.17346 , -0.79258,0.416065,0.445767 --1.44204 , 2.37739 , 5.25612 , 0.25025,0.464769,0.849332 --2.51741 , 3.55587 , 7.86976 , -0.316794,0.8096,0.494155 --1.28027 , 2.2384 , 5.25054 , -0.436023,-0.845164,0.309163 --1.107 , 2.06732 , 5.01273 , -0.264688,0.234276,0.935444 --0.971127 , 1.93492 , 4.84584 , -0.745142,-0.207192,-0.633904 --0.880418 , 1.8501 , 4.77832 , 0.389767,0.241283,0.888743 --0.654311 , 1.61169 , 4.31955 , -0.268785,-0.054145,-0.961677 --0.608172 , 1.57595 , 4.34935 , -0.0274578,0.283198,0.958668 --0.559548 , 1.53647 , 4.36909 , 0.320261,-0.879667,-0.351594 --0.527686 , 1.51634 , 4.44189 , -0.264034,0.836451,0.480246 --0.446871 , 1.43839 , 4.35009 , -0.973588,-0.226014,0.0323079 --0.433398 , 1.4409 , 4.49484 , -0.612077,-0.761164,-0.214457 --0.470985 , 1.50974 , 4.8528 , 0.977805,-0.117104,-0.173734 --0.383161 , 1.42248 , 4.7296 , -0.0326686,-0.213735,0.976345 --0.302933 , 1.34253 , 4.62237 , -0.858349,-0.0228288,0.512558 --0.343027 , 1.42197 , 5.06903 , 0.308409,0.919348,0.244299 --0.242112 , 1.3147 , 4.8548 , 0.968705,-0.116497,0.219178 --0.231624 , 1.33032 , 5.10481 , 0.694746,0.713547,0.0904393 --0.187006 , 1.30176 , 5.1927 , 0.245641,0.645081,0.723554 --0.0901428 , 1.19332 , 4.94267 , -0.798449,0.529048,0.287381 --0.0537895 , 1.17725 , 5.08602 , -0.363572,-0.598947,0.713497 --0.145939 , 1.37703 , 6.28888 , -0.645223,-0.741969,-0.182123 --0.0993698 , 1.36156 , 6.53349 , 0.75754,0.41908,0.500505 -0.0379108 , 1.1807 , 5.89639 , 0.6021,-0.778879,0.175567 --1.48754 , 1.8632 , -1.34704 , 0.0675703,-0.00703158,-0.99769 --1.56229 , 1.9302 , -1.35654 , -0.0894631,0.0365011,0.995321 --1.64371 , 2.00229 , -1.36974 , -0.0564974,0.0294652,0.997968 --1.71987 , 2.07084 , -1.37342 , 0.0965239,-0.0874072,-0.991485 --1.81519 , 2.15549 , -1.39337 , -0.0742654,0.0918979,0.992995 --1.90454 , 2.23548 , -1.40329 , -0.0642002,0.0789515,0.994809 --2.01415 , 2.33213 , -1.42804 , -0.0951487,0.0902988,0.991359 --2.12432 , 2.42884 , -1.44812 , -0.0876865,0.0936763,0.991734 --2.24185 , 2.53333 , -1.46989 , -0.0974789,0.0957181,0.990624 --2.3607 , 2.63913 , -1.48691 , -0.0513882,0.0797435,0.99549 --2.46707 , 2.73564 , -1.48816 , -0.00695278,0.0836094,0.996474 --2.60048 , 2.85426 , -1.50638 , -0.0293921,0.0835703,0.996068 --2.74159 , 2.98007 , -1.52444 , -0.0302635,0.0807893,0.996272 --2.87777 , 3.10166 , -1.53163 , 0.00763494,0.0774064,0.99697 --3.02073 , 3.23035 , -1.53804 , -0.0399752,0.10812,0.993334 --3.22502 , 3.41077 , -1.58115 , -0.0268946,0.12211,0.992152 --3.43191 , 3.59361 , -1.61566 , -0.0303456,0.0453649,0.998509 --3.66057 , 3.79668 , -1.65471 , -0.0499044,-0.263947,0.963245 --3.7383 , 3.87359 , -1.58957 , -0.0018765,-0.871855,0.48976 --3.74701 , 3.89105 , -1.48028 , 0.0156753,-0.912683,0.408367 --3.75277 , 3.90775 , -1.3712 , 0.021544,-0.979891,0.198369 --3.76443 , 3.92825 , -1.266 , -0.0890378,0.970814,-0.222695 --3.77533 , 3.94752 , -1.16077 , -0.13515,0.962696,-0.234416 --3.79169 , 3.97261 , -1.05931 , -0.164806,0.959831,-0.227076 --3.80561 , 3.99516 , -0.957104 , -0.183221,0.957832,-0.221331 --3.81207 , 4.01125 , -0.85175 , -0.188808,0.95624,-0.223512 --3.8245 , 4.03138 , -0.749293 , -0.195705,0.952403,-0.233727 --3.84149 , 4.05733 , -0.64952 , -0.205692,0.949332,-0.237613 --3.85897 , 4.0814 , -0.549255 , -0.196484,0.957793,-0.209828 --3.86604 , 4.09829 , -0.445873 , -0.172834,0.9673,-0.185631 --3.87987 , 4.12057 , -0.344831 , 0.151085,-0.971449,0.182923 --3.88544 , 4.13502 , -0.241299 , -0.149085,0.978027,-0.145728 --3.8966 , 4.15568 , -0.139794 , 0.17436,-0.979815,0.0977841 --3.8768 , 4.14822 , -0.0304543 , 0.228853,-0.97322,0.0216502 --3.86276 , 4.14584 , 0.0761805 , 0.311981,-0.948508,-0.0547766 --3.8325 , 4.12934 , 0.184846 , -0.314349,0.948348,0.042682 --3.80824 , 4.11699 , 0.291101 , 0.365047,-0.930597,-0.0270217 --3.79811 , 4.11786 , 0.393524 , -0.472369,0.881184,-0.0195849 --3.80073 , 4.12987 , 0.493919 , -0.453171,0.891328,0.0130501 --3.8026 , 4.14065 , 0.594339 , 0.466271,-0.880995,-0.0802449 --3.78032 , 4.13111 , 0.696624 , 0.398501,-0.892569,-0.210991 --3.74955 , 4.11308 , 0.798479 , -0.440121,0.854326,0.276444 --3.70235 , 4.0803 , 0.899544 , -0.442571,0.836862,0.32217 --3.66192 , 4.05294 , 0.998367 , -0.596047,0.738613,0.314925 --3.62735 , 4.03094 , 1.09575 , -0.683691,0.624072,0.378286 --3.58493 , 4.00134 , 1.19122 , -0.895573,0.390973,0.212342 --3.56286 , 3.99139 , 1.28618 , -0.882994,0.458941,0.098462 --3.54697 , 3.98614 , 1.38116 , -0.816507,0.577203,-0.0123995 --3.55981 , 4.00644 , 1.47892 , -0.807205,0.58666,-0.0651866 --3.55597 , 4.01292 , 1.5756 , -0.836048,0.547593,-0.0341378 --3.55065 , 4.01701 , 1.67262 , -0.809433,0.579676,0.0937796 --3.55213 , 4.02828 , 1.7708 , -0.533647,0.845625,-0.0117849 --3.55215 , 4.03724 , 1.86971 , -0.57032,0.821422,-0.00116798 --3.55023 , 4.04577 , 1.96887 , -0.618209,0.785912,0.0126416 --3.54074 , 4.04583 , 2.0667 , -0.665041,0.745715,0.0403632 --3.53638 , 4.05179 , 2.16651 , 0.709157,-0.702652,-0.0581154 --3.53031 , 4.05637 , 2.26677 , -0.765049,0.63754,0.0907872 --3.52351 , 4.05975 , 2.36724 , 0.813384,-0.5723,-0.104302 --3.515 , 4.06173 , 2.46806 , -0.855213,0.497776,0.144328 --3.50573 , 4.06251 , 2.569 , -0.880073,0.425113,0.211544 --3.49476 , 4.06187 , 2.67028 , -0.880751,0.396492,0.258981 --3.46751 , 4.04756 , 2.76559 , -0.882794,0.324884,0.3393 --3.43327 , 4.02549 , 2.8572 , 0.892349,-0.281962,-0.352435 --3.40441 , 4.00843 , 2.9513 , -0.93138,0.191333,0.309714 --3.38196 , 3.99671 , 3.04833 , -0.886866,0.390538,0.246876 --3.38367 , 4.00974 , 3.15977 , -0.922002,0.280684,0.266699 --3.35873 , 3.99532 , 3.25688 , -0.812484,0.403818,0.420477 --4.25026 , 4.86321 , 3.90845 , -0.963394,0.26291,-0.0524467 --3.57765 , 4.22876 , 3.62429 , 0.561961,-0.808982,0.172473 --3.49956 , 4.16556 , 3.6966 , 0.375775,0.00924048,0.926665 --3.42129 , 4.10175 , 3.76628 , -0.211402,-0.0070429,0.977374 --3.26679 , 3.96286 , 3.77781 , -0.903108,-0.414822,0.110988 --4.27029 , 4.95387 , 4.6612 , -0.819284,0.532921,-0.211588 --4.29125 , 4.99002 , 4.83577 , 0.734109,-0.658632,0.165189 --4.27851 , 4.99309 , 4.98744 , -0.585143,0.795924,-0.155282 --4.29404 , 5.02352 , 5.16628 , -0.744167,0.654496,-0.133606 --4.30603 , 5.05242 , 5.34706 , -0.787701,0.593044,-0.166814 --4.33278 , 5.09522 , 5.54684 , 0.634654,-0.750767,0.183202 --4.36092 , 5.14122 , 5.75525 , 0.991307,-0.123307,0.0458791 --4.34464 , 5.14321 , 5.92623 , -0.931254,0.360543,-0.0526814 --4.33158 , 5.14848 , 6.10404 , -0.939104,0.310829,0.146526 --2.85666 , 3.68047 , 4.69517 , 0.490583,-0.841201,-0.227395 --2.79379 , 3.63102 , 4.76498 , -0.474904,0.82503,0.306253 --2.7626 , 3.61277 , 4.87134 , -0.558936,0.708319,0.431132 --2.73439 , 3.59871 , 4.98423 , 0.509652,-0.77408,-0.375572 --4.34913 , 5.26691 , 7.17613 , -0.880754,0.466265,-0.082885 --1.53244 , 2.39054 , 3.71148 , -0.914004,0.377263,0.149229 --1.56574 , 2.43447 , 3.85819 , -0.78767,-0.348384,0.508138 --3.4524 , 4.40453 , 6.63338 , 0.864864,0.253529,-0.433282 --3.29217 , 4.2581 , 6.61035 , -0.845084,-0.2776,0.456915 --1.40779 , 2.30113 , 3.95126 , 0.726028,0.434113,-0.53332 --1.4049 , 2.30881 , 4.05767 , 0.82756,0.423105,-0.368953 --1.55393 , 2.4776 , 4.41981 , -0.488375,0.840617,0.234206 --1.35644 , 2.2796 , 4.21291 , -0.347095,0.924341,0.15849 --1.33866 , 2.27241 , 4.3059 , 0.434446,-0.891647,0.127365 --1.40404 , 2.35509 , 4.55547 , -0.854439,0.519123,0.0210984 --1.81377 , 2.81503 , 5.48298 , 0.359738,-0.049801,0.931723 --1.51189 , 2.50117 , 5.06005 , 0.722438,-0.166635,-0.671056 --1.49146 , 2.4956 , 5.18432 , 0.243057,-0.888545,-0.389116 --1.3134 , 2.31388 , 4.97189 , -0.146143,-0.017856,0.989102 --1.30041 , 2.31513 , 5.11 , 0.651724,0.679079,0.337798 --1.20953 , 2.22903 , 5.07198 , -0.609956,-0.116385,-0.783842 --1.2278 , 2.26714 , 5.29472 , -0.436023,-0.845164,0.309163 --1.16979 , 2.21896 , 5.33953 , -0.109012,-0.57895,0.808043 --0.898056 , 1.92293 , 4.80949 , -0.745141,-0.207192,-0.633905 --0.834404 , 1.86645 , 4.81085 , -0.346631,0.731663,-0.586955 --0.600967 , 1.60716 , 4.30573 , -0.370278,-0.474898,-0.798352 --0.542987 , 1.55276 , 4.29006 , 0.187789,0.475531,0.859422 --0.518117 , 1.53916 , 4.38092 , 0.239993,-0.917175,-0.318109 --0.476583 , 1.50483 , 4.41705 , 0.493128,0.800727,0.34009 --0.403166 , 1.4313 , 4.34281 , 0.995795,0.0906291,-0.0133375 --0.528722 , 1.60957 , 5.02197 , -0.944724,-0.0220833,-0.327121 --0.428425 , 1.50279 , 4.85497 , 0.940781,-0.0106372,0.338849 --0.338605 , 1.40887 , 4.71214 , -0.356354,-0.0429117,0.933365 --0.329257 , 1.421 , 4.9237 , 0.100523,-0.823168,0.558829 --0.279782 , 1.37877 , 4.95655 , 0.703867,0.656424,0.271438 --0.176132 , 1.26154 , 4.70263 , -0.44457,-0.280696,0.850628 --0.157619 , 1.26205 , 4.89447 , -0.384288,0.922571,-0.0344321 --0.0957993 , 1.20206 , 4.84632 , 0.662285,-0.319377,-0.677773 --0.0734911 , 1.20241 , 5.05708 , 0.733113,-0.589549,0.339083 --0.0148691 , 1.14773 , 5.03577 , -0.517002,-0.607267,0.603271 --0.0888134 , 1.31998 , 6.1429 , 0.525139,0.774343,0.353017 --0.0267649 , 1.27031 , 6.21064 , -0.237148,-0.921143,0.308636 --1.33099 , 1.83377 , -1.34744 , 0.0361819,-0.0241083,-0.999054 --1.39214 , 1.89311 , -1.34721 , -0.035182,0.0353941,0.998754 --1.45369 , 1.95199 , -1.34463 , -0.0412616,0.0431828,0.998215 --1.53233 , 2.02613 , -1.35984 , 0.0752105,-0.083176,-0.993693 --1.61218 , 2.10121 , -1.37195 , -0.0877014,0.0953402,0.991574 --1.70925 , 2.19193 , -1.40018 , -0.0897939,0.110522,0.989809 --1.79059 , 2.26878 , -1.40551 , -0.0333526,0.0876381,0.995594 --1.88467 , 2.35737 , -1.42019 , -0.0753476,0.101339,0.991995 --1.98529 , 2.45236 , -1.43711 , -0.0744275,0.100656,0.992134 --2.08721 , 2.54854 , -1.44988 , -0.0649684,0.113857,0.991371 --2.20201 , 2.65689 , -1.47005 , -0.0755289,0.106303,0.991461 --2.33631 , 2.78233 , -1.50202 , -0.0325623,0.0954913,0.994898 --2.45285 , 2.89322 , -1.512 , 0.00450775,0.0692581,0.997589 --2.5705 , 3.0064 , -1.51734 , -0.0154942,0.0741049,0.99713 --2.70894 , 3.13624 , -1.53303 , -0.0246741,0.0806919,0.996434 --2.8476 , 3.26841 , -1.54288 , -0.0166132,0.0968766,0.995158 --3.03315 , 3.44312 , -1.58095 , -0.042018,0.138406,0.989484 --3.21319 , 3.61291 , -1.60578 , -0.00716658,0.0545001,0.998488 --3.40829 , 3.79768 , -1.63213 , 0.0963267,0.518144,-0.849852 --3.45038 , 3.84532 , -1.54899 , 0.0833473,-0.705667,0.703625 --3.49158 , 3.89299 , -1.46467 , 0.117077,-0.891472,0.437689 --3.51214 , 3.92053 , -1.36655 , 0.193574,-0.89421,0.40363 --3.53076 , 3.94765 , -1.26818 , -0.265301,0.891356,-0.367559 --3.54768 , 3.97338 , -1.16938 , -0.339399,0.865322,-0.368817 --3.57033 , 4.00408 , -1.07378 , 0.319123,-0.901478,0.292401 --3.59226 , 4.03367 , -0.977557 , 0.345908,-0.902972,0.25493 --3.59857 , 4.0493 , -0.874246 , -0.384439,0.895623,-0.223753 --3.61061 , 4.06992 , -0.774029 , -0.404459,0.885378,-0.229169 --3.62842 , 4.09562 , -0.67642 , -0.39512,0.890934,-0.223867 --3.6455 , 4.12019 , -0.578396 , -0.366579,0.911568,-0.186182 --3.65316 , 4.13778 , -0.477375 , -0.342553,0.928661,-0.142286 --3.65374 , 4.14679 , -0.373789 , 0.325467,-0.938432,0.115829 --3.65891 , 4.16168 , -0.272692 , -0.387585,0.906693,-0.166393 --3.66356 , 4.17439 , -0.171371 , 0.393924,-0.9035,0.168855 --3.66624 , 4.18658 , -0.0701985 , -0.477394,0.866867,-0.143656 --3.66817 , 4.19753 , 0.0310005 , -0.440106,0.894831,-0.0747287 --3.66835 , 4.20699 , 0.132152 , 0.533225,-0.843234,0.068024 --3.66778 , 4.21522 , 0.23333 , 0.623952,-0.778476,0.068254 --3.67187 , 4.22957 , 0.333088 , -0.666634,0.744793,-0.0297084 --3.6688 , 4.23505 , 0.434148 , -0.656424,0.754375,-0.00502749 --3.6571 , 4.23325 , 0.535747 , 0.646795,-0.762241,-0.0253985 --3.6503 , 4.23666 , 0.63632 , -0.641459,0.760858,0.0981147 --3.6284 , 4.22494 , 0.737735 , -0.772223,0.630279,0.080125 --3.61333 , 4.21883 , 0.837783 , -0.78445,0.567394,0.250405 --3.60319 , 4.218 , 0.937095 , -0.841962,0.442801,0.308266 --3.57763 , 4.20274 , 1.03598 , -0.922232,0.316883,0.221528 --3.55797 , 4.193 , 1.13411 , -0.973571,0.164553,0.158372 --3.54424 , 4.18883 , 1.23177 , -0.97441,0.126156,0.186039 --3.55194 , 4.2049 , 1.33046 , 0.999815,-0.00513618,-0.0185186 --3.55698 , 4.21942 , 1.4299 , 0.995519,0.0664898,0.067234 --3.57607 , 4.24628 , 1.53158 , 0.991452,0.114715,0.0621635 --3.60711 , 4.28626 , 1.63659 , 0.995541,-0.094181,-0.00533749 --3.94247 , 4.62205 , 1.79583 , -0.669025,0.689348,-0.277859 --4.06986 , 4.75631 , 1.93117 , -0.376783,0.892113,-0.249338 --4.06703 , 4.76355 , 2.04548 , 0.314148,-0.912634,0.261554 --4.06933 , 4.7767 , 2.16188 , -0.30213,0.946001,-0.117474 --4.06993 , 4.78849 , 2.27882 , -0.354816,0.926983,-0.121686 --4.06297 , 4.79182 , 2.39443 , 0.399414,-0.907178,0.132273 --4.06042 , 4.79994 , 2.51264 , 0.472064,-0.87126,0.134393 --4.07116 , 4.82085 , 2.63612 , 0.507713,-0.855091,0.105104 --4.06502 , 4.82729 , 2.75559 , 0.612307,-0.780927,0.12342 --4.06552 , 4.83815 , 2.8783 , -0.717549,0.687456,-0.111928 --4.06337 , 4.84747 , 3.00185 , -0.824234,0.559374,-0.0879741 --4.05954 , 4.85549 , 3.12614 , -0.895455,0.416245,-0.157802 --4.06046 , 4.86762 , 3.25449 , -0.920823,0.376688,-0.100949 --4.06666 , 4.8861 , 3.38687 , -0.971237,0.207992,-0.115923 --4.07672 , 4.90871 , 3.52441 , 0.990505,-0.124238,0.0588566 --4.07912 , 4.92261 , 3.65955 , -0.958053,0.252665,-0.135262 --4.08516 , 4.94164 , 3.79983 , -0.949751,0.304386,-0.0729479 --4.06376 , 4.93189 , 3.92533 , -0.963394,0.26291,-0.0524467 --3.40514 , 4.2743 , 3.62942 , -0.878936,-0.474295,0.0501625 --4.08534 , 4.97928 , 4.22437 , -0.866509,0.488435,-0.10292 --4.08884 , 4.99651 , 4.37419 , -0.941061,0.315435,-0.122086 --4.08973 , 5.01234 , 4.52546 , -0.931979,0.351928,-0.0869544 --4.08847 , 5.02479 , 4.67826 , -0.834574,0.539921,-0.109414 --4.10961 , 5.05981 , 4.85225 , -0.764379,0.644732,-0.00679817 --4.10895 , 5.07411 , 5.01322 , -0.774569,0.592655,-0.220912 --4.11129 , 5.09266 , 5.18093 , -0.8087,0.542998,-0.226182 --4.12811 , 5.12592 , 5.36685 , 0.809624,-0.573009,0.127157 --4.14283 , 5.15599 , 5.55508 , 0.741704,-0.666216,0.077665 --4.15891 , 5.18915 , 5.75146 , 0.986315,-0.0446246,-0.158716 --4.15404 , 5.2014 , 5.93294 , -0.959325,0.282285,-0.00323479 --4.15809 , 5.22285 , 6.12782 , -0.950312,0.21074,0.229122 --4.15784 , 5.24154 , 6.32467 , -0.93698,0.302144,0.175434 --1.78253 , 2.7298 , 3.73094 , 0.231212,0.911944,0.338967 --2.65779 , 3.67552 , 4.90393 , -0.500934,0.751904,0.428609 --2.61563 , 3.64334 , 4.99678 , -0.513319,0.763334,0.392205 --2.58137 , 3.62 , 5.10256 , -0.518366,0.71461,0.469712 --4.05861 , 5.23238 , 7.27578 , -0.914044,-0.352843,0.200063 --1.70379 , 2.69412 , 4.16989 , 0.696029,-0.67565,0.242982 --1.48837 , 2.47046 , 3.97218 , 0.690093,0.27842,-0.668023 --1.40638 , 2.39056 , 3.95851 , -0.670565,-0.442087,0.595736 --1.36222 , 2.35248 , 4 , -0.679395,-0.266946,0.683492 --1.47981 , 2.49263 , 4.30722 , 0.182459,0.665546,0.723711 --1.29977 , 2.30401 , 4.12466 , 0.307924,-0.905627,-0.291585 --1.31415 , 2.33047 , 4.27057 , -0.70755,0.660266,-0.251837 --1.43432 , 2.47784 , 4.61965 , -0.856454,0.503175,-0.115333 --1.81199 , 2.91848 , 5.4873 , 0.775931,-0.0799664,0.625729 --1.73702 , 2.84899 , 5.51546 , -0.684478,0.0620973,-0.726384 --1.64614 , 2.76208 , 5.50907 , -0.222369,0.0232386,-0.974686 --1.38655 , 2.47876 , 5.13221 , 0.481578,0.785743,0.388189 --1.25908 , 2.34639 , 5.01619 , -0.747573,-0.500625,-0.436474 --1.36289 , 2.48329 , 5.43063 , -0.664317,-0.0614645,0.74492 --1.2639 , 2.38376 , 5.37815 , -0.626511,-0.668,0.401573 --0.950137 , 2.02677 , 4.76653 , -0.938667,0.330167,0.0994719 --0.92934 , 2.01841 , 4.88283 , -0.847797,0.309778,0.43044 --0.866711 , 1.95837 , 4.88605 , -0.00259981,-0.236838,0.971546 --0.589419 , 1.63442 , 4.25336 , -0.115732,-0.260698,0.958459 --0.564161 , 1.61798 , 4.33605 , 0.481008,0.467906,-0.741414 --0.503975 , 1.55901 , 4.31109 , -0.0488096,0.524893,0.849767 --0.472089 , 1.53381 , 4.37466 , 0.512394,0.783506,0.351525 --0.653056 , 1.78393 , 5.21242 , 0.149754,0.633131,0.75942 --0.589818 , 1.72204 , 5.20747 , 0.108827,0.673654,0.73099 --0.407363 , 1.50316 , 4.71975 , -0.293608,0.544059,0.785999 --0.35929 , 1.45973 , 4.74516 , -0.545486,0.198914,0.814173 --0.298818 , 1.39822 , 4.7134 , -0.315623,-0.000851548,0.948884 --0.283885 , 1.40097 , 4.89655 , -0.971133,0.126344,-0.20233 --0.239899 , 1.36282 , 4.9476 , -0.444976,-0.824718,0.349051 --0.185448 , 1.31201 , 4.95008 , -0.606533,0.0261903,-0.794627 --0.133794 , 1.26256 , 4.96088 , -0.422592,-0.60017,-0.679126 --0.071678 , 1.19834 , 4.90282 , -0.879744,0.430646,0.201481 --0.195856 , 1.4367 , 6.20785 , -0.592102,-0.80461,0.0449177 --0.127199 , 1.37077 , 6.21018 , -0.226096,-0.966073,0.124834 --0.0885714 , 1.35911 , 6.48387 , -0.905502,-0.172156,-0.387851 -0.0393444 , 1.18241 , 5.89622 , 0.6021,-0.778879,0.175567 --1.23409 , 1.85277 , -1.33763 , -0.0603778,0.0151652,0.99806 --1.29296 , 1.91233 , -1.33871 , -0.0368482,0.0453246,0.998293 --1.3582 , 1.97771 , -1.34466 , -0.0355973,0.0422714,0.998472 --1.42886 , 2.04882 , -1.35478 , -0.0394793,0.0772451,0.99623 --1.50618 , 2.12502 , -1.36861 , -0.0539071,0.0969197,0.993831 --1.58351 , 2.2029 , -1.37942 , -0.0930811,0.122072,0.988147 --1.67259 , 2.2922 , -1.39985 , -0.0663683,0.1289,0.989434 --1.76388 , 2.38279 , -1.41673 , -0.0350296,0.0854671,0.995725 --1.8492 , 2.46873 , -1.42358 , -0.0657946,0.0979913,0.99301 --1.96494 , 2.58404 , -1.45691 , -0.0847342,0.13163,0.987671 --2.07696 , 2.69437 , -1.47938 , -0.055114,0.109461,0.992462 --2.17651 , 2.7955 , -1.48568 , -0.0562925,0.111395,0.992181 --2.30161 , 2.92027 , -1.50992 , -0.0141636,0.0921978,0.99564 --2.40913 , 3.02939 , -1.51256 , 0.0115527,0.069967,0.997482 --2.53063 , 3.15125 , -1.52118 , -0.0242266,0.0820375,0.996335 --2.67765 , 3.29836 , -1.545 , -0.00669967,0.0988936,0.995076 --2.81881 , 3.44115 , -1.55724 , 0.0509209,-0.125471,-0.99079 --3.01847 , 3.63916 , -1.60625 , 0.0248978,0.0852662,0.996047 --3.18151 , 3.80416 , -1.61865 , 0.24443,-0.206334,0.94746 --3.262 , 3.88979 , -1.56546 , 0.398373,-0.29842,0.86732 --3.28929 , 3.92493 , -1.47428 , 0.626198,-0.570424,0.531501 --3.32207 , 3.96595 , -1.38659 , -0.751734,0.498678,-0.431529 --3.36059 , 4.01198 , -1.3019 , -0.726061,0.478667,-0.493673 --3.39201 , 4.05099 , -1.21211 , 0.711687,-0.527523,0.46392 --3.41436 , 4.08246 , -1.11748 , 0.697775,-0.595045,0.398787 --3.4432 , 4.12015 , -1.02597 , 0.684617,-0.641078,0.34687 --3.45692 , 4.14208 , -0.926482 , 0.683806,-0.668353,0.292771 --3.47616 , 4.17001 , -0.829996 , 0.669969,-0.701264,0.243662 --3.48721 , 4.19034 , -0.72995 , 0.646126,-0.72887,0.226428 --3.49123 , 4.20221 , -0.626852 , 0.629497,-0.756985,0.175233 --3.4998 , 4.21987 , -0.526633 , 0.617015,-0.774352,0.140254 --3.50012 , 4.22972 , -0.42373 , 0.637185,-0.749294,0.180428 --3.50621 , 4.24468 , -0.323435 , 0.643511,-0.743942,0.180122 --3.52467 , 4.27131 , -0.227215 , 0.645163,-0.740375,0.188704 --3.52927 , 4.28388 , -0.126478 , 0.650454,-0.737067,0.183414 --3.5385 , 4.30246 , -0.0276471 , 0.676026,-0.720343,0.155227 --3.54626 , 4.3187 , 0.0718198 , -0.7071,0.696068,-0.124496 --3.55305 , 4.33473 , 0.171408 , -0.689927,0.719653,-0.0781005 --3.5451 , 4.3351 , 0.273884 , 0.604672,-0.796122,0.0236946 --3.5494 , 4.34843 , 0.373547 , 0.490795,-0.869937,-0.0482652 --3.53892 , 4.34596 , 0.475516 , 0.420182,-0.907417,-0.00649489 --3.52644 , 4.34286 , 0.57685 , 0.479936,-0.871798,0.0981371 --3.54849 , 4.37281 , 0.674625 , -0.675211,0.735894,-0.050509 --3.58301 , 4.41639 , 0.772604 , -0.903874,0.371542,-0.212056 --3.63774 , 4.48089 , 0.871242 , -0.781531,0.155147,-0.604267 --3.69791 , 4.55052 , 0.972942 , 0.878422,0.0817526,0.47084 --3.74983 , 4.6124 , 1.07752 , -0.967238,-0.0205183,-0.253039 --3.77927 , 4.65131 , 1.18434 , 0.978649,-0.105822,0.176207 --3.80034 , 4.68207 , 1.29228 , -0.95606,0.250595,-0.152153 --3.81228 , 4.70343 , 1.40128 , -0.928299,0.339463,-0.151743 --3.83103 , 4.73199 , 1.51153 , -0.893837,0.406078,-0.190147 --3.84062 , 4.75107 , 1.62246 , -0.887208,0.423659,-0.182691 --3.85533 , 4.77601 , 1.73527 , -0.891948,0.420883,-0.165188 --3.86255 , 4.79273 , 1.84783 , -0.803333,0.550581,-0.226973 --3.8681 , 4.80816 , 1.96121 , -0.682637,0.718215,-0.134809 --3.87196 , 4.82226 , 2.07523 , -0.743751,0.650496,-0.153917 --3.87438 , 4.8341 , 2.19027 , -0.788984,0.59118,-0.167364 --3.88883 , 4.8593 , 2.30973 , -0.73498,0.675118,-0.0634131 --3.89477 , 4.87592 , 2.42836 , -0.852649,0.515633,-0.0843375 --3.90518 , 4.8975 , 2.55038 , -0.825163,0.55785,-0.0889351 --3.91515 , 4.91711 , 2.67359 , 0.55659,-0.813282,0.169648 --3.92942 , 4.9428 , 2.80066 , -0.647999,0.741893,-0.172314 --3.96229 , 4.98771 , 2.93742 , 0.80905,-0.566268,0.157413 --3.97257 , 5.00995 , 3.06783 , -0.895455,0.416245,-0.157802 --3.99459 , 5.04404 , 3.20589 , -0.954441,0.248621,-0.165018 --4.02647 , 5.08973 , 3.35262 , -0.971237,0.207992,-0.115923 --4.07045 , 5.14669 , 3.50885 , -0.989058,0.109952,-0.0983564 --5.30418 , 6.47048 , 4.34845 , -0.947001,-0.0218691,-0.320485 --5.21799 , 6.39398 , 4.47278 , -0.896074,0.373837,-0.23937 --5.1306 , 6.31657 , 4.59412 , 0.623303,0.600359,0.501061 --9.56999 , 11.0868 , 7.71111 , 0.219317,0.895649,-0.386929 --5.68128 , 6.93723 , 5.33257 , 0.364487,0.317373,0.875456 --4.077 , 5.22773 , 4.36819 , -0.931979,0.351928,-0.0869545 --4.07294 , 5.23654 , 4.51688 , -0.931979,0.351928,-0.0869544 --4.06017 , 5.23618 , 4.66213 , -0.923865,0.380839,-0.0378756 --4.05129 , 5.24004 , 4.81301 , -0.944845,0.303236,-0.123756 --4.05167 , 5.25478 , 4.97484 , -0.951361,0.26738,-0.15304 --4.11378 , 5.33588 , 5.1954 , -0.926767,0.317861,-0.200168 --4.1134 , 5.35042 , 5.3673 , -0.923229,0.373405,-0.0906497 --4.28527 , 5.55463 , 5.71079 , -0.863479,0.257033,0.43398 --4.23829 , 5.51948 , 5.85082 , -0.752242,0.248614,0.610183 --4.16744 , 5.45774 , 5.96718 , -0.968439,0.192667,0.158134 --1.5269 , 2.54544 , 3.264 , -0.934412,0.123825,0.33398 --1.53877 , 2.5672 , 3.3649 , -0.945343,0.136109,0.296313 --1.54454 , 2.58121 , 3.46101 , -0.945343,0.136109,0.296313 --1.44044 , 2.47233 , 3.42531 , -0.945343,0.136109,0.296313 --2.57416 , 3.75529 , 4.96286 , -0.513319,0.763334,0.392205 --2.5022 , 3.68658 , 5.01653 , -0.537408,0.734249,0.414814 --1.55876 , 2.63073 , 3.8703 , -0.79339,-0.198349,0.575491 --1.5453 , 2.62464 , 3.95841 , -0.79339,-0.198349,0.575491 --6.35624 , 8.12749 , 11.1877 , -0.0941889,0.690839,-0.716847 --1.42101 , 2.50231 , 3.99344 , 0.813158,0.324848,-0.482958 --1.41468 , 2.50382 , 4.09441 , 0.624759,0.33252,-0.706475 --1.36958 , 2.46166 , 4.13761 , -0.535211,-0.199264,0.820879 --1.25094 , 2.33474 , 4.05249 , 0.690542,-0.327747,-0.644774 --1.242 , 2.33316 , 4.15188 , 0.504082,-0.852788,-0.136577 --1.20134 , 2.29588 , 4.19807 , -0.465752,0.878481,-0.106514 --1.4757 , 2.63077 , 4.85154 , -0.701705,0.487693,-0.51939 --1.51266 , 2.68897 , 5.07791 , -0.513339,0.772046,0.374737 --1.63752 , 2.85161 , 5.50008 , 0.550436,0.0100847,0.834817 --1.16089 , 2.29421 , 4.6488 , 0.46127,0.783816,0.415767 --1.24162 , 2.40513 , 4.98079 , -0.693909,-0.342034,-0.633643 --1.10969 , 2.25847 , 4.83666 , 0.16483,0.932613,0.321035 --0.952155 , 2.07909 , 4.61097 , -0.890731,-0.246745,-0.381726 --1.04194 , 2.20385 , 4.99887 , -0.271192,0.715973,0.643302 --0.898684 , 2.04025 , 4.79168 , -0.848444,0.374845,0.373676 --0.840642 , 1.98322 , 4.80395 , 0.780952,0.348423,0.518378 --0.625639 , 1.72548 , 4.35015 , -0.86442,0.469312,0.180343 --0.586028 , 1.68926 , 4.39007 , -0.864421,0.469312,0.180343 --0.548979 , 1.65535 , 4.4381 , -0.834092,-0.166762,0.525814 --0.460832 , 1.55529 , 4.31432 , -0.544703,-0.653725,-0.525302 --0.634806 , 1.80071 , 5.11244 , -0.40278,-0.80643,-0.432942 --0.450152 , 1.57317 , 4.64134 , 0.516138,-0.157235,-0.841949 --0.453308 , 1.59447 , 4.86191 , 0.481612,0.263322,-0.83589 --0.358735 , 1.48476 , 4.69422 , -0.0988648,0.0934813,0.9907 --0.329425 , 1.46343 , 4.79363 , 0.589388,-0.0853199,-0.803332 --0.274456 , 1.40605 , 4.78026 , -0.161324,0.788763,0.593151 --0.227599 , 1.36025 , 4.80293 , -0.235128,-0.594917,-0.768628 --0.164721 , 1.29145 , 4.73887 , -0.0340859,-0.56126,0.826938 --0.135807 , 1.27343 , 4.86392 , 0.676391,0.315601,0.665501 --0.0843397 , 1.22182 , 4.86409 , 0.662285,-0.319377,-0.677773 --0.0656305 , 1.22097 , 5.08503 , 0.697155,-0.481193,-0.53144 --0.194058 , 1.47461 , 6.50934 , -0.315613,-0.732224,0.603521 --0.0806767 , 1.32832 , 6.14213 , 0.525139,0.774344,0.353016 --0.0132961 , 1.25809 , 6.12221 , 0.0844212,-0.770626,0.631671 --1.14241 , 1.87294 , -1.3335 , -0.0784729,0.0295473,0.996478 --1.19975 , 1.9339 , -1.33612 , -0.0616064,0.0363791,0.997437 --1.26674 , 2.00537 , -1.35027 , -0.0578315,0.0595618,0.996548 --1.33065 , 2.07279 , -1.35494 , -0.0172209,0.0977046,0.995066 --1.39878 , 2.14668 , -1.36385 , -0.0517379,0.0885687,0.994725 --1.46833 , 2.22047 , -1.36987 , -0.0714293,0.110407,0.991316 --1.56085 , 2.31722 , -1.39902 , -0.101748,0.120165,0.987526 --1.6484 , 2.40965 , -1.41779 , -0.047306,0.087735,0.99502 --1.73073 , 2.49861 , -1.42674 , -0.0324743,0.0949279,0.994954 --1.81982 , 2.59296 , -1.43804 , -0.0824808,0.124872,0.988739 --1.93286 , 2.7122 , -1.46948 , -0.0675789,0.124038,0.989974 --2.03493 , 2.82066 , -1.484 , -0.0476523,0.114274,0.992306 --2.15599 , 2.94804 , -1.5111 , -0.0315147,0.0993495,0.994553 --2.26678 , 3.06572 , -1.52198 , 0.012688,0.0867267,0.996151 --2.38306 , 3.19099 , -1.53324 , 0.0174459,0.0998791,0.994847 --2.51337 , 3.32918 , -1.54969 , -0.00813268,0.104592,0.994482 --2.64413 , 3.46872 , -1.56011 , -0.0210096,0.12015,0.992534 --2.82528 , 3.66008 , -1.60388 , -0.064387,0.135485,0.988685 --3.01343 , 3.85924 , -1.64375 , 0.066035,0.123993,0.990083 --3.16636 , 4.02352 , -1.64754 , -0.484773,-0.0343012,-0.873967 --3.25724 , 4.1242 , -1.60006 , -0.844352,0.134041,-0.518751 --3.28972 , 4.16765 , -1.51043 , -0.868731,0.261495,-0.420626 --3.31012 , 4.19637 , -1.41153 , -0.907862,0.36444,-0.207294 --3.31498 , 4.21139 , -1.30438 , -0.864842,0.472119,-0.170738 --3.33195 , 4.2373 , -1.2048 , -0.831177,0.530903,-0.165189 --3.33527 , 4.24974 , -1.09808 , -0.804479,0.558665,-0.201761 --3.34978 , 4.27299 , -0.998227 , -0.799609,0.571374,-0.184816 --3.35609 , 4.28865 , -0.894819 , -0.80346,0.567643,-0.179534 --3.36187 , 4.30205 , -0.791479 , -0.80461,0.569126,-0.169409 --3.37195 , 4.32217 , -0.691313 , -0.820985,0.554214,-0.137226 --3.38152 , 4.34013 , -0.590825 , -0.847748,0.516583,-0.120274 --3.38283 , 4.35029 , -0.487654 , -0.876661,0.469137,-0.106655 --3.38992 , 4.36554 , -0.387091 , -0.886714,0.436675,-0.151834 --3.40258 , 4.38697 , -0.288749 , -0.89878,0.425954,-0.103724 --3.39965 , 4.3929 , -0.185744 , -0.902309,0.419249,-0.100339 --3.40985 , 4.41171 , -0.0869366 , -0.896873,0.40515,-0.177406 --3.41931 , 4.42934 , 0.0120915 , -0.894727,0.423648,-0.141374 --3.43345 , 4.45312 , 0.109895 , -0.897586,0.433356,0.0808823 --3.41275 , 4.43841 , 0.215698 , 0.69026,-0.712991,-0.12323 --3.38338 , 4.41628 , 0.321459 , -0.536844,0.790527,0.294731 --3.34672 , 4.38489 , 0.426769 , -0.349316,0.920992,0.17249 --3.32867 , 4.37399 , 0.527506 , 0.300457,-0.953658,0.0161573 --3.35107 , 4.40561 , 0.62282 , 0.171651,-0.969662,0.174042 --3.41341 , 4.47928 , 0.716045 , 0.170815,-0.802291,0.571972 --3.50057 , 4.58151 , 0.81094 , -0.692185,0.206774,-0.691466 --3.71703 , 4.82204 , 0.906291 , 0.911031,0.0314357,0.411138 --3.72714 , 4.84164 , 1.01407 , -0.978627,0.00796623,-0.205488 --3.72884 , 4.85297 , 1.1224 , -0.967458,0.228555,-0.108575 --3.73004 , 4.86215 , 1.23115 , -0.95606,0.250595,-0.152153 --3.73604 , 4.87791 , 1.34052 , -0.928299,0.339463,-0.151743 --3.74156 , 4.8916 , 1.4506 , -0.907617,0.384958,-0.167449 --3.75194 , 4.91202 , 1.56198 , -0.897284,0.407868,-0.168892 --3.76745 , 4.9383 , 1.67525 , -0.898347,0.406879,-0.165597 --3.77474 , 4.95522 , 1.78868 , -0.911715,0.381193,-0.15319 --3.79399 , 4.9853 , 1.90565 , -0.933677,0.329243,-0.140877 --3.80574 , 5.00717 , 2.02236 , -0.949672,0.276432,-0.14734 --3.82879 , 5.04119 , 2.14371 , -0.973087,0.15239,-0.172853 --3.84337 , 5.06679 , 2.26492 , -0.9234,0.34084,-0.176523 --3.90244 , 5.14232 , 2.40144 , -0.903466,0.401602,-0.149883 --5.72859 , 7.16541 , 3.13806 , -0.71695,-0.566022,0.406943 --5.70269 , 7.1509 , 3.30177 , -0.811108,0.568388,0.137983 --5.53216 , 6.97537 , 3.40921 , -0.774841,-0.543516,0.322818 --4.76864 , 6.14228 , 3.25892 , 0.181591,0.953,0.242521 --5.77351 , 7.27211 , 3.86242 , -0.811108,0.568387,0.137983 --5.02635 , 6.45369 , 3.68734 , 0.804909,-0.414988,0.424154 --5.06957 , 6.51653 , 3.87283 , -0.327345,-0.887757,-0.323625 --5.06742 , 6.52613 , 4.03827 , -0.393426,0.918205,-0.0459858 --5.11755 , 6.59754 , 4.23652 , -0.947001,-0.0218691,-0.320485 --5.28892 , 6.80346 , 4.51286 , 0.99893,-0.0125753,0.0445124 --9.08647 , 11.0949 , 7.09147 , 0.813743,0.538758,0.218087 --5.70056 , 7.29769 , 5.15238 , -0.626977,-0.0940629,-0.773338 --5.43995 , 7.01866 , 5.17242 , 0.658374,0.700714,0.274853 --5.53273 , 7.13953 , 5.43661 , 0.626978,0.0940631,0.773338 --5.09483 , 6.65942 , 5.30702 , 0.819412,0.242842,0.519223 --4.94369 , 6.5025 , 5.37962 , -0.792488,-0.609809,0.00975809 --1.87087 , 3.00755 , 3.01365 , 0.637122,-0.403909,-0.656455 --4.06056 , 5.52182 , 5.00021 , 0.989901,-0.102847,0.0975648 --4.36898 , 5.88964 , 5.44747 , 0.894937,-0.436078,0.0944663 --4.26545 , 5.78626 , 5.53383 , 0.993366,0.0666138,-0.0937413 --4.2455 , 5.77744 , 5.69756 , -0.837378,0.300491,0.456621 --4.14009 , 5.67044 , 5.77891 , -0.837378,0.300491,0.456621 --4.90977 , 6.57945 , 6.78449 , -0.693563,-0.531622,-0.486157 --4.99308 , 6.69459 , 7.1033 , -0.418236,-0.462977,-0.781492 --1.49399 , 2.62724 , 3.32785 , -0.836849,0.469207,0.282007 --1.49507 , 2.63562 , 3.41766 , -0.831692,0.426476,0.355536 --1.44877 , 2.58924 , 3.45204 , -0.94655,0.135796,0.29258 --1.44741 , 2.59505 , 3.54252 , -0.921955,-0.212933,0.323511 --1.60157 , 2.78478 , 3.8424 , -0.00559148,0.905218,0.424911 --2.4168 , 3.76082 , 5.07623 , -0.537409,0.734249,0.414814 --1.56662 , 2.76113 , 4.00833 , 0.433269,0.892384,-0.126211 --1.47368 , 2.65782 , 3.98102 , -0.685623,-0.327134,0.650311 --1.46249 , 2.65485 , 4.07637 , 0.743874,0.295183,-0.599598 --1.39294 , 2.57939 , 4.07938 , -0.810867,-0.239233,0.5341 --1.38117 , 2.57406 , 4.17417 , -0.720873,-0.33575,-0.606312 --1.26787 , 2.44744 , 4.09937 , 0.021662,0.0160819,0.999636 --1.19623 , 2.36835 , 4.08742 , 0.755056,-0.389575,-0.527372 --1.20727 , 2.39122 , 4.22503 , 0.981496,-0.185712,-0.046653 --1.199 , 2.39167 , 4.33337 , -0.839941,0.410222,-0.355272 --1.41815 , 2.67391 , 4.90539 , -0.425196,0.829617,0.361861 --1.63957 , 2.96184 , 5.52242 , 0.0135427,0.800105,0.599707 --1.14723 , 2.35961 , 4.63084 , -0.0573591,-0.382386,0.92222 --1.10605 , 2.31952 , 4.68438 , 0.46127,0.783816,0.415767 --1.08463 , 2.30594 , 4.78639 , -0.402419,-0.795146,-0.453654 --0.997321 , 2.20747 , 4.73012 , -0.580811,-0.715487,-0.388249 --0.898571 , 2.09322 , 4.63675 , 0.991727,0.018667,0.126997 --0.889103 , 2.09426 , 4.76961 , 0.977777,0.124287,0.168835 --0.867584 , 2.07976 , 4.87748 , 0.988066,-0.00669563,-0.153885 --0.761001 , 1.95371 , 4.74162 , 0.179425,0.254011,0.950413 --0.835915 , 2.0668 , 5.14673 , -0.560401,0.269946,-0.782994 --0.531422 , 1.67635 , 4.36775 , -0.814239,-0.442319,0.375991 --0.630523 , 1.82436 , 4.87183 , 0.516816,0.772127,-0.369758 --0.644715 , 1.85857 , 5.12115 , 0.160994,0.800422,0.577413 --0.554803 , 1.75404 , 5.00837 , -0.927081,-0.369489,0.063238 --0.543584 , 1.75549 , 5.18588 , 0.114539,0.723937,0.680291 --0.364923 , 1.52328 , 4.68003 , -0.377344,0.220979,0.899322 --0.324549 , 1.48353 , 4.72408 , -0.458624,0.11888,0.880643 --0.273463 , 1.42808 , 4.72047 , 0.340615,0.793653,-0.50408 --0.277585 , 1.45321 , 4.98873 , 0.854977,-0.402936,0.326583 --0.19808 , 1.35667 , 4.8412 , 0.0465669,-0.901661,-0.429928 --0.151564 , 1.30857 , 4.86252 , 0.0261662,0.600115,0.799486 --0.104961 , 1.26021 , 4.88267 , 0.114108,0.0140967,0.993368 --0.0807337 , 1.24807 , 5.05579 , 0.728627,-0.591631,-0.345072 --0.180038 , 1.44536 , 6.18744 , -0.592102,-0.80461,0.0449178 --0.108459 , 1.36452 , 6.13148 , 0.194163,-0.89625,0.398793 --0.0560634 , 1.31717 , 6.23941 , 0.746175,0.639706,0.184391 -0.0400532 , 1.18632 , 5.90577 , 0.598426,-0.778429,0.189563 --1.10753 , 1.9518 , -1.33216 , -0.0761023,0.0381406,0.99637 --1.16255 , 2.01449 , -1.33377 , -0.0761023,0.0381406,0.99637 --1.22819 , 2.08794 , -1.34692 , 0.0758437,-0.108068,-0.991246 --1.29477 , 2.16319 , -1.35757 , -0.0538525,0.0962338,0.993901 --1.36681 , 2.24426 , -1.372 , -0.0164768,0.0940802,0.995428 --1.44006 , 2.32627 , -1.38333 , -0.0732401,0.137549,0.987783 --1.52889 , 2.42665 , -1.41087 , -0.0633433,0.121588,0.990557 --1.60362 , 2.51044 , -1.41542 , -0.042858,0.104193,0.993633 --1.68967 , 2.60771 , -1.42931 , -0.041273,0.10897,0.993188 --1.79267 , 2.72309 , -1.45718 , -0.0659733,0.120514,0.990517 --1.8907 , 2.83416 , -1.47456 , -0.0777219,0.121329,0.989565 --2.00144 , 2.95851 , -1.49887 , -0.0548963,0.118889,0.991389 --2.11352 , 3.08423 , -1.51814 , -0.042357,0.117389,0.992182 --2.23209 , 3.2178 , -1.53771 , 0.0109381,0.103118,0.994609 --2.33961 , 3.34041 , -1.54124 , 0.0205611,0.117529,0.992857 --2.48388 , 3.50145 , -1.57057 , 0.0207464,0.110697,0.993638 --2.5993 , 3.6335 , -1.56839 , -0.0208421,0.130053,0.991288 --2.7931 , 3.84984 , -1.62337 , -0.0672113,0.166302,0.983782 --2.99376 , 4.07517 , -1.67358 , 0.145058,0.0751698,0.986564 --3.11806 , 4.21798 , -1.65548 , 0.534666,-0.228457,0.813597 --3.18234 , 4.29619 , -1.5883 , 0.761297,-0.512915,0.396667 --3.19638 , 4.31909 , -1.48453 , -0.778898,0.537773,-0.322675 --3.19583 , 4.32844 , -1.37292 , -0.831426,0.532894,-0.157338 --3.20737 , 4.34856 , -1.26937 , -0.85971,0.491095,-0.140443 --3.21717 , 4.36722 , -1.16577 , -0.845445,0.498758,-0.190954 --3.22598 , 4.3856 , -1.06234 , -0.88553,0.425733,-0.185978 --3.25225 , 4.42202 , -0.968804 , -0.935222,0.304839,-0.180094 --3.26509 , 4.444 , -0.86803 , -0.831409,0.509115,-0.222624 --3.28248 , 4.47176 , -0.770135 , -0.871395,0.42086,-0.252085 --3.29915 , 4.49843 , -0.671629 , -0.912551,0.342958,-0.22278 --3.32163 , 4.53027 , -0.575342 , -0.932979,0.292775,-0.209362 --3.3359 , 4.55447 , -0.475691 , -0.954433,0.2436,-0.172387 --3.3487 , 4.57634 , -0.375403 , -0.966484,0.198246,-0.163116 --3.36054 , 4.59802 , -0.274897 , 0.977881,-0.1735,0.11682 --3.37189 , 4.61758 , -0.173876 , 0.981142,-0.165188,0.100363 --3.38129 , 4.6367 , -0.0726128 , 0.991084,-0.0842297,0.103239 --3.38286 , 4.64596 , 0.0309503 , 0.990804,-0.131517,-0.0317792 --3.38981 , 4.66247 , 0.132678 , 0.993141,-0.0997785,-0.0609473 --3.33087 , 4.60251 , 0.248465 , 0.848312,-0.322667,-0.419824 --3.2493 , 4.51912 , 0.364447 , -0.536986,0.746815,0.392319 --3.18712 , 4.45585 , 0.473205 , 0.444628,-0.831546,-0.332923 --3.15611 , 4.42919 , 0.574254 , -0.391655,0.861885,0.32212 --3.1309 , 4.40774 , 0.673278 , -0.347554,0.901064,0.259405 --3.12445 , 4.4072 , 0.769578 , 0.0545774,-0.99829,-0.0209264 --3.13016 , 4.42101 , 0.864814 , 0.00297403,0.999272,0.0380407 --3.17376 , 4.47778 , 0.959757 , -0.0679835,-0.990002,0.123594 --10.1102 , 12.3881 , 1.09176 , -0.35784,0.613785,0.703717 --9.814 , 12.0714 , 1.36327 , 0.250151,0.736492,0.628494 --9.25911 , 11.4575 , 1.60483 , 0.750394,0.659168,-0.0490663 --9.10326 , 11.2987 , 1.85161 , 0.750394,0.659167,-0.0490669 --8.71645 , 10.8741 , 2.06514 , -0.828462,-0.498664,0.25492 --9.00813 , 11.2278 , 2.35289 , -0.811219,-0.512542,0.281469 --8.30367 , 10.436 , 2.49333 , 0.793481,0.58907,-0.152919 --8.27684 , 10.4232 , 2.72723 , -0.722602,-0.669662,0.17146 --8.32578 , 10.4967 , 2.97763 , -0.668014,-0.71738,0.197798 --8.31847 , 10.5071 , 3.21902 , 0.754857,0.621423,-0.209821 --8.19312 , 10.3809 , 3.42904 , -0.713142,-0.656389,0.246133 --8.38649 , 10.6227 , 3.73057 , 0.244551,0.958355,0.14748 --5.54208 , 7.33206 , 3.03959 , -0.811108,0.568387,0.137983 --7.93295 , 10.1333 , 4.07162 , 0.128329,0.976202,0.174818 --8.07749 , 10.3194 , 4.37066 , 0.168029,-0.97624,-0.136827 --7.91001 , 10.1428 , 4.55028 , 0.168029,-0.97624,-0.136827 --5.44818 , 7.27401 , 3.69792 , -0.811108,0.568387,0.137983 --4.92214 , 6.66904 , 3.62396 , 0.21724,0.944899,0.244893 --5.30375 , 7.13099 , 3.9816 , -0.851132,0.0600244,0.521509 --5.03135 , 6.82293 , 4.01257 , 0.720285,0.376052,0.582902 --4.83309 , 6.60111 , 4.07179 , -0.3012,-0.944006,-0.134653 --4.54514 , 6.2734 , 4.06714 , 0.180762,0.900856,0.394695 --10.1676 , 12.9576 , 7.7829 , 0.0764241,0.922688,-0.377897 --5.27304 , 7.16295 , 4.87679 , -0.377829,0.818958,-0.431917 --5.26258 , 7.16501 , 5.06141 , -0.425942,-0.599001,-0.678065 --5.82547 , 7.85168 , 5.66769 , -0.288038,0.350528,-0.891159 --1.99451 , 3.28486 , 2.95137 , 0.552568,-0.150018,-0.819855 --1.9186 , 3.20006 , 2.97782 , 0.60501,-0.117438,-0.78751 --1.87087 , 3.14855 , 3.02466 , -0.680516,0.00985995,0.732667 --1.83978 , 3.11746 , 3.08416 , 0.785208,-0.0271705,-0.618636 --1.79157 , 3.06617 , 3.12761 , 0.781091,-0.0430613,-0.622931 --1.77567 , 3.05316 , 3.20039 , -0.708816,-0.109849,0.696788 --4.10131 , 5.88176 , 5.5875 , -0.720263,0.567363,0.39915 --4.07004 , 5.85736 , 5.74028 , -0.720263,0.567363,0.39915 --5.24904 , 7.30976 , 7.18942 , 0.00995921,0.829749,0.558048 --1.51039 , 2.75745 , 3.27738 , -0.853904,0.421448,0.305336 --1.47755 , 2.72375 , 3.3264 , -0.663859,0.540736,0.51662 --1.54944 , 2.81883 , 3.50134 , -0.95903,-0.196517,0.204066 --1.42944 , 2.67788 , 3.44652 , 0.765454,-0.607695,-0.211631 --1.48749 , 2.75625 , 3.61311 , -0.764624,-0.219644,0.605893 --1.41688 , 2.67635 , 3.61627 , -0.971969,0.10638,0.209666 --4.11283 , 6.03667 , 7.47103 , -0.934089,-0.355473,0.0334194 --4.03803 , 5.9608 , 7.60506 , -0.503265,-0.334863,0.796612 --2.27549 , 3.77414 , 5.20802 , 0.0731096,-0.777443,0.62469 --1.46451 , 2.76669 , 4.10143 , -0.70093,-0.413326,0.581256 --1.43109 , 2.73336 , 4.16305 , -0.648959,-0.303099,0.697842 --1.33236 , 2.61715 , 4.11596 , -0.34003,-0.26448,0.902458 --1.29871 , 2.58311 , 4.17447 , 0.369348,0.688745,-0.623869 --1.21127 , 2.48076 , 4.13512 , -0.963091,-0.26915,-0.00372217 --1.2176 , 2.49796 , 4.26624 , -0.913479,-0.406307,0.0216895 --1.13156 , 2.39606 , 4.22228 , 0.987437,-0.112458,-0.110998 --2.43838 , 4.09306 , 6.99205 , -0.185581,0.727262,0.660795 --1.33124 , 2.67475 , 4.89677 , -0.422027,0.900858,-0.101729 --1.26957 , 2.60578 , 4.91663 , -0.214278,0.300819,0.929297 --1.08043 , 2.36968 , 4.64269 , -0.057359,-0.382386,0.922221 --1.00524 , 2.283 , 4.61359 , -0.410508,-0.735265,-0.539322 --0.962942 , 2.23725 , 4.65637 , 0.75094,0.568396,0.336177 --0.93563 , 2.21214 , 4.74024 , 0.706947,-0.0791868,-0.702819 --0.872055 , 2.13968 , 4.7303 , -0.056499,0.327765,0.943069 --0.895183 , 2.18224 , 4.95857 , 0.390911,-0.312053,0.865917 --0.821827 , 2.09629 , 4.92064 , -0.168967,-0.500027,0.849367 --0.706515 , 1.95222 , 4.74889 , 0.219947,0.930698,-0.292275 --0.695597 , 1.95036 , 4.88981 , -0.867995,-0.334163,0.367314 --0.652632 , 1.90364 , 4.93379 , -0.836064,-0.251565,0.487558 --0.618965 , 1.87166 , 5.01238 , -0.94464,-0.177765,-0.27578 --0.525473 , 1.75446 , 4.87314 , 0.525887,0.126123,0.841152 --0.537883 , 1.78809 , 5.13197 , -0.033303,0.644406,0.763958 --0.489493 , 1.7352 , 5.16283 , 0.0520081,0.58978,0.805888 --0.337506 , 1.53063 , 4.73807 , -0.509374,0.482553,0.712517 --0.286936 , 1.47341 , 4.73544 , -0.266049,-0.262233,0.927606 --0.255359 , 1.44232 , 4.81584 , -0.666394,-0.680355,-0.305017 --0.211858 , 1.39625 , 4.8484 , -0.623312,-0.104218,-0.774997 --0.177465 , 1.36313 , 4.92741 , 0.307835,-0.89647,0.318715 --0.119289 , 1.29208 , 4.87224 , -0.0793809,0.521883,0.849316 --0.0738406 , 1.24283 , 4.89179 , -0.820161,0.144577,0.553564 --0.0526885 , 1.23229 , 5.08416 , -0.863585,0.305313,0.401255 --0.156254 , 1.44173 , 6.30475 , 0.625144,0.763618,0.161501 --0.0754301 , 1.33936 , 6.1611 , -0.0199795,0.896589,0.442412 --0.012839 , 1.26715 , 6.15124 , -0.222458,0.974196,0.0381368 --1.06858 , 2.03088 , -1.32996 , -0.0210959,0.107615,0.993969 --1.12649 , 2.10039 , -1.33763 , -0.0796785,0.0928925,0.992483 --1.20504 , 2.19292 , -1.37045 , -0.0558886,0.113992,0.991909 --1.26007 , 2.25897 , -1.36603 , -0.0281633,0.102954,0.994287 --1.32959 , 2.34284 , -1.37915 , -0.0142738,0.119703,0.992707 --1.40535 , 2.43386 , -1.39569 , -0.0619856,0.151455,0.986519 --1.48664 , 2.53092 , -1.41503 , 0.0601271,-0.135179,-0.988995 --1.5805 , 2.64083 , -1.44315 , -0.0372579,0.119255,0.992164 --1.65783 , 2.73554 , -1.44882 , -0.0461136,0.132107,0.990162 --1.75837 , 2.85392 , -1.47451 , -0.0765241,0.115458,0.99036 --1.85977 , 2.97553 , -1.49576 , -0.0641067,0.124482,0.990149 --1.96686 , 3.10368 , -1.51767 , -0.0583439,0.135204,0.989098 --2.0865 , 3.24628 , -1.54563 , -0.00383674,0.122535,0.992457 --2.20146 , 3.38376 , -1.56232 , 0.013149,0.117644,0.992969 --2.30634 , 3.51047 , -1.56319 , 0.0124475,0.148025,0.988905 --2.44045 , 3.67066 , -1.58448 , 0.0469293,0.142368,0.988701 --2.5699 , 3.82579 , -1.59421 , 0.00550392,0.138675,0.990323 --2.79149 , 4.0891 , -1.67379 , -0.0281955,0.17712,0.983785 --2.97549 , 4.30902 , -1.70993 , -0.444878,-0.103115,-0.889635 --3.04963 , 4.40236 , -1.65255 , 0.623452,-0.0190065,0.78163 --3.06964 , 4.43322 , -1.55298 , -0.824493,0.365666,-0.431855 --3.10128 , 4.47685 , -1.46148 , -0.920492,0.307692,-0.240872 --3.12484 , 4.51322 , -1.36496 , -0.902684,0.340253,-0.263418 --3.15414 , 4.55459 , -1.27143 , -0.937173,0.13065,-0.323476 --3.18802 , 4.60181 , -1.18049 , -0.954857,0.117804,-0.272708 --3.23273 , 4.66211 , -1.09517 , -0.970725,0.0701109,-0.229733 --8.26458 , 10.5612 , -3.70739 , -0.224056,-0.0134206,0.974484 --9.8351 , 12.4211 , -4.25286 , 0.191661,-0.193369,-0.962224 --12.9035 , 16.0736 , -5.04415 , 0.000515438,-0.927751,0.373201 --13.0321 , 16.2517 , -4.71414 , -0.0142378,-0.925595,0.378248 --13.2381 , 16.5213 , -4.41046 , 0.0412943,-0.826879,0.560862 --13.2786 , 16.5952 , -4.03669 , 0.109705,-0.665688,0.738122 --13.3513 , 16.7083 , -3.67429 , 0.109705,-0.665688,0.738122 --3.43289 , 4.96552 , -0.190601 , 0.995924,0.0789821,-0.043567 --3.38467 , 4.91705 , -0.0677218 , 0.996811,0.0596307,-0.0530283 --3.3676 , 4.90348 , 0.0443377 , 0.993594,-0.0424917,-0.104715 --3.36223 , 4.90455 , 0.152218 , 0.98934,-0.066632,-0.129484 --3.36814 , 4.91835 , 0.257309 , -0.984367,0.0791206,0.157356 --3.37874 , 4.93837 , 0.361467 , -0.970769,0.00964545,0.239822 --3.06949 , 4.57576 , 0.512963 , -0.739026,0.355595,0.572182 --3.00149 , 4.49994 , 0.618823 , -0.371383,0.870409,0.323207 --2.95803 , 4.45411 , 0.718344 , -0.324048,0.911765,0.252343 --2.91913 , 4.41413 , 0.815277 , 0.264736,-0.921659,-0.283652 --2.91172 , 4.41173 , 0.908879 , 0.176041,-0.96399,-0.19933 --2.91554 , 4.42359 , 1.00202 , 0.0140123,0.99982,-0.0128125 --2.93186 , 4.44918 , 1.09576 , 0.0996466,0.995008,0.00549092 --2.95207 , 4.48128 , 1.19093 , 0.0506962,0.994445,0.0922461 --3.91248 , 5.65288 , 1.35474 , -0.949859,-0.271499,-0.1551 --3.98057 , 5.7437 , 1.48324 , -0.955894,-0.281088,-0.0851897 --4.03434 , 5.81679 , 1.61434 , 0.166434,-0.813866,0.556707 --4.08563 , 5.88888 , 1.74862 , 0.166435,-0.813866,0.556707 --4.14246 , 5.96641 , 1.88733 , 0.166434,-0.813866,0.556707 --4.2095 , 6.05722 , 2.03225 , 0.157972,-0.829985,0.534948 --4.29342 , 6.16975 , 2.18571 , 0.182062,-0.840754,0.509889 --8.11925 , 10.8721 , 3.34704 , 0.754857,0.621423,-0.209821 --8.86608 , 11.8061 , 3.81652 , -0.83684,-0.504865,0.211684 --7.66378 , 10.3451 , 3.69682 , 0.119347,0.958453,0.259085 --7.84022 , 10.5796 , 3.99849 , 0.118545,0.925621,0.359406 --7.61477 , 10.3183 , 4.15828 , 0.168029,-0.97624,-0.136827 --7.60776 , 10.3264 , 4.39783 , 0.168029,-0.97624,-0.136827 --4.72448 , 6.77049 , 3.36127 , -0.402008,0.874806,-0.270377 --5.40823 , 7.63006 , 3.846 , -0.811108,0.568387,0.137983 --5.32248 , 7.53684 , 3.98548 , -0.864286,0.116541,0.489313 --4.57724 , 6.62073 , 3.76777 , 0.120473,0.879344,0.460696 --4.38205 , 6.3894 , 3.81801 , 0.207691,0.897573,0.388879 --4.44529 , 6.47924 , 4.01349 , -0.0576504,-0.450367,0.890981 --4.27853 , 6.28155 , 4.07036 , 0.224778,0.854782,0.467785 --4.9079 , 7.0809 , 4.64901 , 0.313129,-0.834101,0.454121 --5.48922 , 7.82465 , 5.23989 , -0.288038,0.350528,-0.891159 --4.98872 , 7.2089 , 5.07838 , -0.447019,0.81661,-0.365132 --1.94554 , 3.38401 , 2.92553 , -0.61939,0.123232,0.775351 --1.8714 , 3.29687 , 2.95371 , 0.598773,-0.085143,-0.796381 --1.79873 , 3.21038 , 2.97825 , 0.757621,-0.159666,-0.632864 --1.85614 , 3.28861 , 3.1146 , -0.843623,0.125303,0.52211 --1.73915 , 3.14558 , 3.09682 , -0.820684,-0.0539493,0.568829 --1.71352 , 3.11969 , 3.15967 , -0.820684,-0.0539493,0.568829 --1.68171 , 3.08579 , 3.21667 , -0.708816,-0.109849,0.696788 --6.34049 , 9.05326 , 8.14013 , -0.750316,-0.581349,-0.314736 --4.03064 , 6.11026 , 5.93258 , -0.752813,0.434945,0.49406 --1.44846 , 2.8045 , 3.22861 , -0.853904,0.421448,0.305336 --1.43136 , 2.78889 , 3.29539 , -0.942183,0.335062,-0.00485848 --1.39004 , 2.74005 , 3.33222 , -0.886598,0.353417,0.298396 --4.31263 , 6.5313 , 7.09877 , -0.832517,-0.428193,-0.35152 --1.52023 , 2.92151 , 3.68169 , 0.802083,0.059476,-0.594244 --1.43141 , 2.81359 , 3.66272 , -0.843376,-0.289663,0.452562 --1.38651 , 2.76145 , 3.69809 , 0.783553,0.0958685,-0.613884 --1.32732 , 2.69183 , 3.71185 , -0.435145,-0.606953,0.665024 --6.00468 , 8.83818 , 10.8997 , 0.0390716,-0.662474,0.748065 --1.92476 , 3.49228 , 4.85592 , -0.404509,0.136103,0.90435 --1.81994 , 3.3626 , 4.82713 , 0.314438,-0.167843,-0.934322 --1.77508 , 3.31373 , 4.89342 , -0.390079,0.476353,0.787989 --1.74574 , 3.28505 , 4.98781 , -0.444712,0.076297,0.892418 --1.16943 , 2.5253 , 4.08573 , -0.8068,-0.590609,-0.0159838 --1.1287 , 2.48054 , 4.12632 , -0.940292,0.30342,0.154232 --1.19782 , 2.58048 , 4.3787 , -0.816679,-0.268301,0.510931 --1.52136 , 3.02637 , 5.16912 , -0.121379,0.64606,0.753574 --1.31035 , 2.75188 , 4.88317 , -0.142814,0.0967498,0.98501 --1.45299 , 2.95624 , 5.34845 , 0.336321,0.560286,0.756947 --1.10443 , 2.49184 , 4.72165 , -0.681584,0.663729,-0.30807 --1.00999 , 2.37295 , 4.64637 , -0.399262,-0.034219,-0.916198 --0.92901 , 2.27005 , 4.59156 , 0.608847,0.463508,0.64379 --0.858632 , 2.18269 , 4.55846 , -0.77109,0.010754,-0.636635 --0.83939 , 2.16693 , 4.65751 , 0.927393,-0.194232,-0.319712 --0.918402 , 2.2896 , 5.03805 , -0.814215,-0.563146,-0.141136 --0.919276 , 2.30293 , 5.21784 , 0.157404,0.958059,0.239472 --0.698208 , 2.00175 , 4.72907 , 0.0730217,-0.905297,0.418456 --0.70751 , 2.02718 , 4.93181 , -0.183848,-0.179675,0.966394 --0.641989 , 1.94487 , 4.897 , 0.243507,0.243368,-0.93887 --0.60812 , 1.90895 , 4.96695 , -0.895966,-0.176013,0.407756 --0.572712 , 1.87047 , 5.03656 , -0.793605,-0.466066,-0.391119 --0.466379 , 1.72823 , 4.83248 , -0.144111,-0.0619713,0.987619 --0.495632 , 1.78752 , 5.16454 , 0.168789,0.50552,0.846144 --0.370461 , 1.61418 , 4.85325 , -0.0710144,-0.262171,0.962405 --0.332982 , 1.57214 , 4.9082 , -0.22393,-0.178229,0.95817 --0.287203 , 1.51795 , 4.92456 , -0.595135,0.433174,0.676886 --0.2266 , 1.44104 , 4.86432 , -0.927928,-0.154021,-0.339451 --0.167583 , 1.36517 , 4.80208 , -0.332318,-0.587248,-0.738041 --0.123943 , 1.31262 , 4.8137 , -0.31848,-0.569108,-0.758081 --0.079247 , 1.2596 , 4.82428 , -0.782542,-0.436006,-0.444439 --0.0641829 , 1.25557 , 5.03569 , -0.807798,0.49266,0.32365 --0.0456246 , 1.25062 , 5.26711 , -0.213963,0.969954,0.115796 --0.101527 , 1.37923 , 6.16002 , -0.550741,-0.693246,0.46486 --0.0539285 , 1.32992 , 6.27811 , 0.731744,0.526601,0.432715 -0.0333034 , 1.20617 , 6.00357 , 0.688538,-0.200711,-0.696872 --1.22656 , 2.36021 , -1.38003 , -0.00414965,0.133243,0.991075 --1.29883 , 2.45216 , -1.39805 , -0.0293185,0.157226,0.987127 --1.37737 , 2.55129 , -1.4193 , -0.0465815,0.141641,0.988822 --1.45187 , 2.64622 , -1.43067 , -0.0210675,0.13048,0.991227 --1.52665 , 2.74196 , -1.43844 , -0.0273824,0.126831,0.991546 --1.61809 , 2.85668 , -1.46078 , -0.0358666,0.119462,0.992191 --1.70965 , 2.9734 , -1.47864 , -0.0516569,0.126353,0.99064 --1.8127 , 3.10411 , -1.50361 , -0.0536653,0.136765,0.989149 --1.92221 , 3.24263 , -1.52907 , -0.0385972,0.142084,0.989102 --2.0331 , 3.38261 , -1.54911 , -0.0212507,0.142234,0.989605 --2.16053 , 3.54448 , -1.57964 , 0.025287,0.166773,0.985671 --2.28844 , 3.70785 , -1.60355 , 0.0571988,0.151994,0.986725 --2.41879 , 3.87314 , -1.62109 , 0.0852214,0.157043,0.983908 --2.54963 , 4.0399 , -1.63212 , 0.0073546,0.181261,0.983408 --2.78636 , 4.33879 , -1.72548 , 0.148733,0.0965008,0.984158 --2.95936 , 4.558 , -1.7519 , 0.529678,0.162626,0.832463 --3.03756 , 4.66063 , -1.69507 , -0.77261,0.0292043,-0.634208 --3.41092 , 5.13011 , -1.8538 , -0.00902034,0.239206,0.970927 --3.81133 , 5.63341 , -2.0085 , -0.0445885,0.304975,0.951316 --4.51041 , 6.50921 , -2.3405 , -0.0563113,0.278106,0.958899 --5.14697 , 7.30899 , -2.58932 , -0.0760869,0.26008,0.962585 --6.0766 , 8.47596 , -2.97866 , -0.0775756,0.230691,0.96993 --7.0668 , 9.72108 , -3.34731 , -0.109155,0.21076,0.971424 --8.7212 , 11.7998 , -4.02206 , 0.231231,-0.0294958,-0.972452 --9.46808 , 12.7502 , -4.12757 , 0.191661,-0.193369,-0.962224 --9.32882 , 12.5947 , -3.75839 , 0.191662,-0.193369,-0.962224 --12.3595 , 16.4341 , -4.46985 , -0.00685831,-0.939534,0.342388 --12.4489 , 16.5686 , -4.12594 , -0.0509857,-0.774286,0.630778 --12.4244 , 16.5621 , -3.7378 , -0.0236395,-0.798774,0.601167 --18.711 , 24.5421 , -4.94547 , -0.384145,-0.860446,0.334761 --24.263 , 31.5927 , -5.96157 , -0.0901222,-0.0965113,0.991243 --20.1602 , 26.4453 , -4.20971 , -0.511793,-0.755363,0.409261 --3.39264 , 5.23216 , 0.160147 , -0.968624,0.168732,0.182474 --3.30564 , 5.12891 , 0.288213 , -0.932603,0.174219,0.316067 --3.27907 , 5.10256 , 0.40068 , -0.879362,0.173453,0.443437 --3.26996 , 5.09758 , 0.509177 , -0.810571,0.0695062,0.581501 --3.05005 , 4.82339 , 0.640731 , 0.627188,0.101738,-0.772195 --2.82874 , 4.54831 , 0.759534 , -0.848515,0.303822,0.43326 --2.78572 , 4.49883 , 0.856145 , -0.727992,0.560775,0.394409 --2.74729 , 4.45525 , 0.950362 , 0.295072,-0.915181,-0.274547 --2.71421 , 4.41883 , 1.04236 , 0.267284,-0.896656,-0.352942 --2.68676 , 4.38875 , 1.13281 , -0.256834,0.826934,0.500217 --2.65193 , 4.34913 , 1.22155 , -0.393025,0.720719,0.571047 --2.62807 , 4.32466 , 1.30944 , -0.219984,0.80656,0.548697 --2.59126 , 4.28282 , 1.39492 , -0.0391319,0.803557,0.593941 --2.54774 , 4.23242 , 1.47759 , 0.0766018,0.844383,0.530236 --2.50988 , 4.18845 , 1.55911 , -0.116745,0.793115,0.597779 --2.47673 , 4.15079 , 1.64008 , -0.233238,0.65357,0.720032 --4.02766 , 6.16719 , 2.08562 , 0.182062,-0.840754,0.509889 --4.06566 , 6.22526 , 2.22899 , 0.182062,-0.840754,0.509889 --4.11484 , 6.29682 , 2.37846 , 0.270584,-0.84027,0.469819 --4.14949 , 6.35002 , 2.52771 , 0.26759,-0.850272,0.453248 --4.18848 , 6.40942 , 2.6814 , 0.493111,0.814608,-0.305377 --2.25159 , 3.89133 , 2.08713 , 0.0669107,0.929016,0.363939 --4.27741 , 6.54377 , 3.00502 , -0.0781988,-0.964858,0.250868 --4.34596 , 6.64187 , 3.18333 , -0.142407,-0.989785,0.0067794 --7.37731 , 10.6264 , 4.77235 , 0.168029,-0.97624,-0.136827 --5.08744 , 7.63536 , 3.86479 , -0.814769,-0.0913161,0.572549 --3.86535 , 6.03968 , 3.38773 , 0.809777,0.578224,0.099588 --3.68736 , 5.81377 , 3.42836 , -0.378258,0.0583564,0.923859 --3.73118 , 5.88089 , 3.59321 , 0.809777,0.578224,0.099588 --4.05942 , 6.32416 , 3.94477 , -0.255024,-0.925306,-0.280664 --4.14106 , 6.44156 , 4.15486 , 0.279262,0.651194,-0.705662 --4.72386 , 7.22377 , 4.72677 , 0.201198,-0.769158,0.60656 --3.89809 , 6.13915 , 4.29954 , -0.181131,-0.644091,0.743195 --1.90908 , 3.50358 , 2.91224 , -0.61939,0.123232,0.775351 --1.88082 , 3.47227 , 2.97744 , -0.61939,0.123232,0.775351 --1.7991 , 3.3677 , 2.99655 , 0.714706,-0.0592973,-0.696907 --1.78638 , 3.35614 , 3.07258 , -0.790087,-0.118033,0.601524 --2.09668 , 3.77811 , 3.44929 , -0.799598,-0.45304,0.394206 --1.73745 , 3.30201 , 3.2045 , 0.751845,-0.0487836,-0.657533 --4.02828 , 6.3873 , 5.60407 , 0.762003,-0.486896,-0.426947 --3.79785 , 6.08884 , 5.55008 , 0.749615,-0.614298,-0.246405 --2.19249 , 3.93308 , 3.98072 , 0.756054,0.647164,-0.0977784 --2.13336 , 3.86061 , 4.0313 , 0.0438801,-0.467214,0.883055 --1.63226 , 3.18828 , 3.55718 , -0.033481,0.1876,0.981675 --1.6309 , 3.1935 , 3.65488 , -0.529557,0.109621,0.841161 --4.35244 , 6.90378 , 7.22065 , 0.483606,0.617506,0.620332 --1.36982 , 2.84943 , 3.51388 , -0.989628,0.135211,0.0485134 --1.40529 , 2.90466 , 3.65675 , -0.945954,-0.00482227,0.324264 --1.3619 , 2.85106 , 3.69336 , -0.564503,-0.0824554,0.821302 --1.34408 , 2.8337 , 3.76779 , -0.684819,0.195074,0.702117 --1.33495 , 2.82655 , 3.8557 , -0.684819,0.195074,0.702117 --1.16106 , 2.59349 , 3.68467 , -0.140151,0.169002,0.9756 --1.12233 , 2.546 , 3.71987 , -0.2913,0.526428,0.79876 --1.10033 , 2.52187 , 3.78185 , -0.2913,0.526428,0.79876 --1.08157 , 2.50108 , 3.85095 , -0.194092,0.968853,0.153794 --1.24024 , 2.73009 , 4.24872 , 0.693621,0.0944896,-0.714116 --1.21916 , 2.70815 , 4.33029 , -0.71278,-0.236518,0.660306 --1.56274 , 3.19793 , 5.13613 , -0.925253,-0.200915,-0.321777 --1.50094 , 3.12174 , 5.16689 , -0.301284,0.457501,0.836613 --1.28037 , 2.81924 , 4.85364 , -0.142814,0.0967496,0.98501 --1.24151 , 2.77288 , 4.9147 , -0.142814,0.0967497,0.98501 --1.2078 , 2.73514 , 4.9909 , 0.822895,-0.268908,-0.500532 --1.04262 , 2.50783 , 4.75101 , 0.61174,-0.737803,-0.285345 --0.886201 , 2.29211 , 4.51093 , 0.660808,-0.212591,0.719818 --0.805574 , 2.1859 , 4.44482 , -0.181988,0.235615,-0.954655 --0.885732 , 2.30949 , 4.80307 , -0.0247068,-0.99224,0.121862 --0.864606 , 2.28952 , 4.90434 , -0.912789,-0.39065,-0.1192 --1.11785 , 2.67143 , 5.81991 , -0.673151,0.733508,-0.0939853 --1.16595 , 2.75507 , 6.18094 , 0.810676,0.527965,-0.253097 --0.696562 , 2.07415 , 4.9028 , -0.0344529,-0.192621,0.980668 --0.660904 , 2.03325 , 4.96609 , 0.142477,0.104317,-0.984286 --0.608075 , 1.96446 , 4.96613 , 0.51251,-0.231472,-0.826894 --0.58572 , 1.94394 , 5.08139 , -0.709573,0.674617,0.203466 --0.490526 , 1.81035 , 4.91585 , -0.557584,-0.122249,-0.821069 --0.489444 , 1.82303 , 5.12018 , 0.145484,0.5283,0.836501 --0.44489 , 1.76694 , 5.15128 , 0.154938,0.597428,0.786812 --0.332661 , 1.60621 , 4.87524 , -0.22393,-0.178229,0.95817 --0.26591 , 1.51428 , 4.7803 , 0.617629,0.562401,-0.549764 --0.215715 , 1.44881 , 4.75771 , 0.179482,0.282318,-0.942381 --0.175097 , 1.39832 , 4.78067 , 0.0742974,0.686698,0.723136 --0.154684 , 1.38141 , 4.92622 , 0.475591,-0.756808,0.448391 --0.101802 , 1.31051 , 4.88069 , -0.245911,0.412608,0.877087 --0.0601898 , 1.25806 , 4.90047 , 0.701325,0.0312719,-0.712155 --0.0445836 , 1.25283 , 5.12196 , 0.855225,-0.45959,-0.239514 --0.0119569 , 1.21823 , 5.23735 , 0.509632,0.858574,-0.0559042 --0.0709011 , 1.35257 , 6.1897 , 0.739861,0.482475,-0.468853 --0.00394579 , 1.26108 , 6.10218 , -0.168888,0.905733,-0.388748 --1.26358 , 2.56371 , -1.416 , -0.00671181,0.163239,0.986564 --1.33458 , 2.65952 , -1.42905 , 0.0142998,0.149174,0.988708 --1.41067 , 2.76334 , -1.44501 , -0.0128962,0.146647,0.989105 --1.49308 , 2.87458 , -1.46322 , -0.000250309,0.136094,0.990696 --1.57073 , 2.9804 , -1.47142 , -0.00660581,0.116666,0.993149 --1.66999 , 3.11281 , -1.49885 , 0.0398925,-0.151646,-0.98763 --1.7796 , 3.26013 , -1.53268 , -0.0408203,0.151564,0.987604 --1.89549 , 3.41637 , -1.56642 , -0.0252815,0.141724,0.989583 --2.00257 , 3.5613 , -1.58339 , 0.00750114,0.164041,0.986425 --2.1306 , 3.73351 , -1.61548 , 0.0379186,0.177642,0.983365 --2.26062 , 3.90961 , -1.64129 , 0.080282,0.163128,0.983333 --2.37615 , 4.06566 , -1.64516 , -0.0756271,-0.186295,-0.979579 --2.54482 , 4.29343 , -1.69097 , 0.00329946,0.202691,0.979237 --2.7581 , 4.57911 , -1.76429 , 0.0727919,0.181349,0.980721 --2.95741 , 4.84859 , -1.81286 , 0.0498793,0.241898,0.969019 --3.16893 , 5.13421 , -1.859 , 0.0161285,0.232403,0.972486 --3.44361 , 5.50199 , -1.93919 , -0.0202551,0.287546,0.957553 --4.09606 , 6.37167 , -2.27538 , -0.051224,0.288217,0.956194 --4.68314 , 7.15699 , -2.52465 , -0.0665599,0.266019,0.961667 --5.52741 , 8.28566 , -2.90546 , -0.0814701,0.239776,0.967404 --6.32432 , 9.35359 , -3.20324 , -0.0848702,0.224245,0.97083 --7.59704 , 11.0579 , -3.73261 , -0.111904,0.12045,0.986392 --8.95531 , 12.8783 , -4.22992 , 0.22009,0.0244385,-0.975173 --10.3407 , 14.7407 , -4.65847 , 0.168061,0.158799,0.972902 --11.4655 , 16.2601 , -4.87398 , 0.455079,-0.866583,0.204783 --11.5383 , 16.3777 , -4.53562 , 0.639573,-0.0467362,0.767309 --11.5967 , 16.4766 , -4.18948 , 0.672397,-0.1832,0.717161 --11.64 , 16.5543 , -3.8362 , 0.672397,-0.1832,0.717161 --12.2338 , 17.3703 , -3.68718 , -0.694277,0.200947,-0.691085 --12.7091 , 18.0313 , -3.46464 , 0.398768,-0.433228,0.808268 --13.026 , 18.4777 , -3.16567 , 0.349001,-0.316869,0.881925 --17.4799 , 24.4946 , -4.01208 , 0.0412309,-0.987062,0.154949 --17.5517 , 24.6198 , -3.49435 , 0.0307553,-0.984024,0.175358 --17.6289 , 24.7538 , -2.97572 , 0.0684076,-0.970618,0.230695 --17.6892 , 24.865 , -2.45088 , 0.0797057,-0.970034,0.229525 --3.20145 , 5.30525 , 0.437057 , -0.847513,0.239766,0.473534 --3.13954 , 5.22702 , 0.554417 , -0.796614,0.101737,0.595866 --3.09379 , 5.17059 , 0.66637 , 0.678827,0.00205266,-0.734296 --2.79821 , 4.77491 , 0.794096 , -0.569847,-0.0248031,0.821377 --2.80879 , 4.79547 , 0.890734 , -0.569847,-0.0248031,0.821377 --2.77205 , 4.75097 , 0.988631 , 0.755723,-0.336092,-0.562072 --2.60992 , 4.53486 , 1.08292 , -0.779159,0.158251,0.606521 --2.56533 , 4.47937 , 1.17268 , -0.459495,0.693786,0.55455 --2.50772 , 4.40633 , 1.25926 , -0.194394,0.752718,0.628989 --2.43167 , 4.30669 , 1.34098 , -0.244044,0.795326,0.554887 --2.38469 , 4.24775 , 1.42203 , -0.155309,0.799715,0.579944 --2.34334 , 4.19516 , 1.50164 , 0.242466,-0.773081,-0.586136 --2.29988 , 4.14159 , 1.57906 , -0.266123,0.651964,0.710015 --2.26305 , 4.09469 , 1.65541 , -0.304142,0.582846,0.753517 --2.2251 , 4.04715 , 1.72993 , -0.45486,0.601033,0.657162 --2.19756 , 4.01405 , 1.80596 , -0.282384,0.745138,0.604177 --2.15858 , 3.96443 , 1.87681 , -0.0209796,0.863374,0.504128 --2.12983 , 3.9304 , 1.94975 , 0.0414179,0.884316,0.465048 --2.10119 , 3.89506 , 2.02133 , -0.117226,-0.920561,-0.372593 --2.08804 , 3.8816 , 2.09884 , 0.151268,0.896295,0.416862 --2.08078 , 3.87526 , 2.17832 , 0.176226,0.91107,0.372687 --4.16854 , 6.77679 , 3.25037 , 0.402728,0.913643,0.0553785 --3.85499 , 6.35009 , 3.2449 , -0.610433,-0.0985018,0.785919 --3.8565 , 6.35947 , 3.38966 , -0.842603,-0.47196,0.259373 --3.65049 , 6.08103 , 3.41824 , 0.809777,0.578224,0.099588 --3.63917 , 6.07233 , 3.552 , 0.809777,0.578224,0.099588 --3.87608 , 6.41188 , 3.84703 , -0.465384,-0.884729,-0.0259197 --4.24359 , 6.93411 , 4.24865 , 0.74567,0.0572645,-0.66385 --4.2058 , 6.8911 , 4.39048 , 0.780574,-0.372503,0.501942 --4.09794 , 6.74831 , 4.47949 , -0.612602,-0.151849,0.775668 --4.43739 , 7.235 , 4.91558 , 0.310557,-0.698771,0.644417 --4.64885 , 7.54359 , 5.27418 , 0.214176,-0.535511,0.816919 --2.1653 , 4.05491 , 3.33377 , -0.851185,-0.441483,0.283861 --2.10285 , 3.97262 , 3.38157 , -0.851185,-0.441483,0.28386 --2.06087 , 3.91875 , 3.44559 , -0.658251,0.118941,0.743343 --1.67257 , 3.37407 , 3.16839 , -0.451512,-0.0540241,0.890628 --3.74467 , 6.31751 , 5.3734 , -0.771016,0.469231,0.43053 --1.78565 , 3.54571 , 3.47068 , 0.609081,-0.690447,0.390262 --1.80124 , 3.57391 , 3.58804 , -0.617311,-0.774113,-0.140275 --1.7926 , 3.56656 , 3.67946 , -0.617311,-0.774113,-0.140275 --1.78692 , 3.56336 , 3.77723 , -0.617311,-0.774113,-0.140274 --1.75095 , 3.51923 , 3.84055 , 0.707208,0.672196,-0.219112 --1.725 , 3.48719 , 3.91468 , 0.772041,0.498164,-0.394697 --1.4158 , 3.0502 , 3.61117 , -0.894653,0.119598,-0.430455 --1.40108 , 3.0341 , 3.68796 , -0.965788,-0.0199515,0.258566 --1.41195 , 3.05433 , 3.80294 , -0.941899,0.313709,0.120055 --1.39853 , 3.04111 , 3.887 , 0.753072,0.108377,-0.648951 --1.27354 , 2.86682 , 3.79897 , 0.425791,-0.817884,-0.387 --1.15958 , 2.70725 , 3.71809 , -0.168876,-0.0461964,0.984554 --1.08905 , 2.61033 , 3.69991 , -0.2913,0.526428,0.79876 --1.03965 , 2.54315 , 3.71372 , -0.291299,0.526428,0.79876 --1.0299 , 2.53579 , 3.79629 , -0.2913,0.526428,0.798761 --1.23326 , 2.83852 , 4.27821 , 0.602752,-0.537139,-0.590061 --1.60148 , 3.38647 , 5.11215 , -0.341078,0.620852,0.705839 --1.45373 , 3.17584 , 4.96731 , -0.0252801,0.443739,0.8958 --1.49064 , 3.23948 , 5.19462 , 0.385074,0.0979828,0.917669 --1.28909 , 2.95006 , 4.91657 , -0.149443,-0.369623,0.917085 --1.17051 , 2.78193 , 4.79994 , 0.421451,-0.0649454,0.904523 --1.32405 , 3.01893 , 5.30319 , 0.290728,0.432957,0.853244 --0.940478 , 2.4546 , 4.5404 , 0.703254,-0.579797,-0.411423 --0.847666 , 2.3229 , 4.44702 , 0.170503,0.152772,0.973442 --0.817816 , 2.28555 , 4.50528 , 0.441615,-0.259714,0.858793 --0.863033 , 2.36139 , 4.77135 , 0.827957,-0.361968,-0.428329 --0.795936 , 2.26853 , 4.73822 , -0.876422,0.414088,-0.245797 --1.11238 , 2.76048 , 5.83526 , -0.673151,0.733508,-0.0939853 --1.14779 , 2.82563 , 6.15269 , 0.810676,0.527965,-0.253097 --0.703583 , 2.1537 , 4.94352 , 0.0473233,0.0297532,0.998437 --0.649237 , 2.07909 , 4.93758 , 0.129524,0.0788534,0.988436 --0.541847 , 1.92393 , 4.74339 , -0.0701238,0.614385,0.785884 --0.543798 , 1.93552 , 4.92873 , -0.421197,0.902619,0.088723 --0.472247 , 1.83416 , 4.84471 , 0.293875,0.223863,0.929259 --0.432139 , 1.78127 , 4.87578 , -0.0248112,0.104634,0.994201 --0.440167 , 1.80584 , 5.11643 , 0.346908,0.376384,0.859064 --0.347045 , 1.66658 , 4.91604 , 0.379514,0.0361786,-0.924479 --0.293617 , 1.59387 , 4.88772 , -0.22393,-0.178229,0.95817 --0.245882 , 1.52814 , 4.87611 , 0.984675,0.101123,-0.142087 --0.178002 , 1.42839 , 4.74992 , -0.0672864,0.401534,0.913369 --0.143597 , 1.38418 , 4.80081 , -0.0986526,0.638706,0.763101 --0.110814 , 1.34216 , 4.86033 , -0.85309,0.237833,0.464406 --0.0576306 , 1.26596 , 4.79465 , -0.959905,0.0187813,-0.279696 --0.0490668 , 1.26741 , 5.03486 , 0.666195,-0.680221,-0.305751 --0.0218022 , 1.23818 , 5.16972 , 0.731104,-0.645253,-0.221664 --0.0962811 , 1.39739 , 6.20822 , 0.794148,0.567589,-0.217194 --0.0392535 , 1.31949 , 6.19974 , 0.822785,0.563698,-0.0725907 -0.0364307 , 1.20547 , 5.99379 , 0.831242,0.0420475,-0.554319 --0.658286 , 1.86459 , -1.29175 , -0.107583,0.0742247,0.991421 --0.712389 , 1.9409 , -1.31784 , -0.151541,0.0980629,0.983575 --0.762709 , 2.01207 , -1.33376 , -0.175969,0.0892726,0.980339 --0.816967 , 2.09052 , -1.3548 , -0.150445,0.0917814,0.984349 --0.864167 , 2.15919 , -1.35882 , -0.114531,0.0852693,0.989754 --1.29711 , 2.77937 , -1.44993 , 0.00655891,0.15571,0.987781 --1.37988 , 2.89849 , -1.47612 , 0.00339366,0.136009,0.990702 --1.45478 , 3.00643 , -1.48603 , 0.00729218,0.119559,0.9928 --1.53505 , 3.12161 , -1.49787 , -0.0183585,0.151469,0.988292 --1.63044 , 3.25879 , -1.52301 , -0.0428047,0.145692,0.988404 --1.73134 , 3.40359 , -1.54843 , -0.0987026,0.104247,0.989642 --1.84264 , 3.56348 , -1.57937 , 0.128463,-0.146051,-0.980901 --1.97127 , 3.74661 , -1.62034 , -0.0147356,0.170701,0.985213 --2.09016 , 3.91831 , -1.64392 , 0.0422507,0.16518,0.985358 --2.22991 , 4.11871 , -1.68078 , 0.0790189,0.185347,0.979491 --2.36186 , 4.30811 , -1.70049 , 0.0819063,0.201454,0.976067 --2.51953 , 4.53522 , -1.7364 , 0.0118473,0.180768,0.983454 --2.7355 , 4.84395 , -1.81327 , 0.0302669,0.207992,0.977662 --2.94393 , 5.1425 , -1.86939 , 0.0048259,0.170785,0.985297 --3.14829 , 5.43609 , -1.90909 , 0.00288502,0.237832,0.971302 --3.72932 , 6.26144 , -2.22666 , -0.0539158,0.302946,0.951481 --4.27395 , 7.03682 , -2.47823 , -0.0623191,0.256075,0.964646 --5.00106 , 8.07269 , -2.82185 , -0.0794048,0.250713,0.964799 --5.76167 , 9.15789 , -3.13995 , -0.0816409,0.207598,0.974802 --6.7361 , 10.5474 , -3.54342 , -0.108014,0.206081,0.972555 --7.8762 , 12.1744 , -3.98315 , -0.183018,-0.136875,0.973535 --7.78714 , 12.0628 , -3.65447 , -0.183018,-0.136875,0.973535 --7.84934 , 12.1637 , -3.41454 , -0.183018,-0.136875,0.973535 --11.2516 , 17.017 , -4.84499 , 0.307769,-0.092913,0.946913 --11.567 , 17.484 , -4.61223 , -0.860995,0.00736177,-0.508561 --11.7808 , 17.8061 , -4.31783 , 0.76024,-0.134011,0.63567 --11.8459 , 17.9179 , -3.9529 , -0.772649,0.0534035,-0.632584 --11.7445 , 17.7924 , -3.52446 , -0.767301,-0.0545778,-0.638961 --12.0947 , 18.3116 , -3.25862 , 0.336389,-0.314519,0.887649 --12.5387 , 18.9657 , -3.00204 , 0.619028,-0.262749,0.740113 --12.6522 , 19.1482 , -2.6276 , 0.619028,-0.262749,0.740113 --16.574 , 24.7925 , -3.19079 , 0.0721766,-0.970896,0.228367 --16.6408 , 24.9144 , -2.67769 , 0.0719687,-0.970466,0.230254 --16.6748 , 24.989 , -2.15599 , 0.0719687,-0.970466,0.230254 --16.7491 , 25.1208 , -1.63953 , 0.0719687,-0.970466,0.230254 --3.07538 , 5.4492 , 0.592688 , -0.905272,-0.0390632,0.423032 --2.59255 , 4.75947 , 0.747532 , -0.0139087,-0.996563,0.0816607 --2.59844 , 4.77215 , 0.842187 , -0.0139087,-0.996563,0.0816607 --2.60335 , 4.78459 , 0.936865 , -0.00357816,-0.997158,0.075259 --2.6133 , 4.80264 , 1.03227 , -0.119836,0.894488,0.430733 --2.98558 , 5.34679 , 1.13861 , -0.56773,0.777443,-0.270674 --2.99341 , 5.36265 , 1.24628 , 0.595004,-0.743724,0.304705 --3.01699 , 5.40181 , 1.35625 , 0.595005,-0.743723,0.304705 --3.05569 , 5.46337 , 1.47001 , 0.578725,-0.767297,0.276283 --3.08821 , 5.51634 , 1.58523 , 0.556453,-0.761515,0.332348 --2.2743 , 4.33686 , 1.54787 , -0.27485,0.761215,0.587375 --2.21595 , 4.25595 , 1.6227 , -0.354763,0.608115,0.710169 --2.14585 , 4.15922 , 1.69109 , -0.489391,0.481761,0.726913 --2.09824 , 4.09276 , 1.76197 , -0.331945,0.632638,0.699702 --2.05584 , 4.0347 , 1.83169 , -0.42385,0.635662,0.645201 --2.01253 , 3.97493 , 1.8993 , -0.350345,0.68965,0.633751 --1.97471 , 3.92277 , 1.96662 , 0.261491,-0.7396,-0.620173 --1.94145 , 3.87807 , 2.03409 , -0.222526,0.672246,0.706093 --1.90139 , 3.82456 , 2.09757 , 0.0587594,0.842823,0.534974 --1.87853 , 3.79434 , 2.16664 , 0.0673395,0.803289,0.591771 --1.85388 , 3.76246 , 2.23498 , 0.0956427,0.91307,0.396429 --1.82913 , 3.73031 , 2.30206 , -0.0273021,0.899716,0.435621 --1.82005 , 3.72056 , 2.37741 , 0.243696,0.902772,0.354423 --1.8102 , 3.70956 , 2.45268 , 0.143088,0.882012,0.448977 --3.39623 , 6.05595 , 3.56064 , 0.322588,0.171796,0.930818 --4.17342 , 7.21271 , 4.23166 , -0.638046,0.272497,-0.720169 --4.08582 , 7.09143 , 4.33938 , -0.638046,0.272498,-0.720169 --3.94127 , 6.88432 , 4.40031 , -0.97437,-0.224848,0.00681712 --4.33821 , 7.48215 , 4.88298 , 0.32636,-0.761688,0.55975 --2.13976 , 4.22317 , 3.23816 , -0.160111,0.650759,0.742211 --2.10543 , 4.17734 , 3.3116 , -0.160111,0.650759,0.742211 --2.03554 , 4.07808 , 3.35228 , -0.851185,-0.441483,0.283861 --2.03084 , 4.07511 , 3.45003 , -0.851185,-0.441483,0.28386 --3.86373 , 6.81956 , 5.37665 , -0.938659,-0.22986,0.257069 --1.64005 , 3.50129 , 3.25823 , 0.142753,-0.858412,0.492696 --1.7117 , 3.61309 , 3.42787 , -0.110351,-0.94898,0.295398 --4.25179 , 7.42835 , 6.37885 , 0.813504,-0.541422,-0.212305 --1.79943 , 3.75395 , 3.72862 , -0.61731,-0.774113,-0.140275 --1.96322 , 4.00629 , 4.03513 , 0.0438797,-0.467214,0.883055 --1.68705 , 3.59547 , 3.80311 , 0.361305,0.931289,0.0464658 --1.50123 , 3.31931 , 3.66655 , 0.100796,-0.949541,-0.297006 --1.43752 , 3.22884 , 3.68145 , 0.316331,0.404932,0.857884 --1.40111 , 3.17839 , 3.72999 , -0.950768,0.2946,0.0961808 --1.40314 , 3.18572 , 3.83385 , 0.890087,-0.0825295,-0.448257 --1.3442 , 3.1017 , 3.84879 , -0.670558,0.355742,0.650999 --1.22265 , 2.92241 , 3.76297 , -0.438712,0.821003,0.365357 --1.19822 , 2.89014 , 3.82408 , 0.558082,-0.817975,0.139504 --1.77145 , 3.77008 , 4.89896 , -0.0663051,0.0200346,0.997598 --1.00968 , 2.61101 , 3.70176 , -0.291299,0.526428,0.79876 --1.01324 , 2.62089 , 3.80596 , -0.2913,0.526428,0.79876 --1.57292 , 3.48494 , 4.96736 , 0.496897,0.477152,0.724858 --1.51278 , 3.40044 , 4.99668 , 0.0214512,0.73325,0.679621 --1.46841 , 3.33914 , 5.05309 , 0.982993,0.14869,0.107773 --1.43364 , 3.29303 , 5.13075 , -0.948255,0.0229837,0.316678 --1.38474 , 3.22328 , 5.17718 , -0.106445,0.184342,0.977081 --1.30047 , 3.10096 , 5.14417 , 0.799272,0.600914,0.00818306 --0.909274 , 2.49771 , 4.3751 , 0.84577,-0.492481,-0.20527 --0.890857 , 2.47507 , 4.46022 , 0.78034,-0.492468,-0.385417 --1.13721 , 2.86796 , 5.22416 , -0.444229,-0.810067,0.382691 --0.823504 , 2.38166 , 4.55654 , -0.302128,-0.211142,0.92959 --0.774971 , 2.31273 , 4.56595 , 0.30041,-0.328801,0.895345 --1.44185 , 3.375 , 6.62601 , -0.899318,-0.43725,-0.00624186 --1.38701 , 3.29946 , 6.69722 , -0.929452,-0.368782,-0.0108612 --1.12045 , 2.88618 , 6.10744 , 0.810676,0.527965,-0.253097 --1.06108 , 2.80129 , 6.13391 , -0.313267,-0.908026,0.278124 --1.01934 , 2.74463 , 6.21971 , -0.313267,-0.908026,0.278124 --0.587691 , 2.05799 , 4.91949 , -0.258133,-0.333397,-0.90676 --0.507404 , 1.93631 , 4.80371 , -0.543493,-0.205813,-0.813791 --0.471044 , 1.88661 , 4.8457 , 0.580282,0.354244,0.733337 --0.430008 , 1.82863 , 4.86853 , 0.124144,0.233148,0.964485 --0.439759 , 1.85465 , 5.10903 , -0.268136,0.851555,0.450508 --0.384811 , 1.77216 , 5.07594 , 0.0231925,0.592133,0.805507 --0.359202 , 1.741 , 5.17925 , -0.425666,0.87906,0.214621 --0.24922 , 1.56619 , 4.86305 , -0.292453,-0.138874,-0.946143 --0.229691 , 1.54484 , 4.99123 , -0.896274,0.0557046,0.439989 --0.146035 , 1.41117 , 4.76082 , -0.37605,0.30538,0.874831 --0.142525 , 1.41722 , 4.99181 , 0.0240966,-0.345969,0.937936 --0.0480445 , 1.26617 , 4.66015 , 0.571361,-0.814629,0.099632 --0.0503997 , 1.28227 , 4.94784 , 0.53602,-0.831341,0.146817 --0.0398505 , 1.27921 , 5.18892 , 0.708645,0.689716,0.148709 --0.00839707 , 1.23878 , 5.29506 , -0.213963,0.969954,0.115796 --0.0670882 , 1.36902 , 6.23808 , -0.732795,-0.670263,0.1173 -0.00664856 , 1.25257 , 6.04343 , -0.861913,-0.141947,-0.486783 --0.546803 , 1.82018 , -1.29664 , -0.107583,0.0742248,0.991422 --0.590343 , 1.88592 , -1.31041 , -0.107583,0.0742247,0.991422 --0.622645 , 1.93721 , -1.29932 , -0.107583,0.0742247,0.991421 --0.669484 , 2.00933 , -1.31664 , -0.126991,0.0868126,0.988098 --0.718214 , 2.08341 , -1.33186 , -0.17842,0.103166,0.978531 --0.770157 , 2.16362 , -1.35178 , -0.155223,0.103959,0.982394 --0.816232 , 2.23326 , -1.35481 , -0.114787,0.0889088,0.989403 --0.866489 , 2.30925 , -1.36266 , -0.0801359,0.127884,0.988546 --0.936619 , 2.41713 , -1.40263 , -0.0920068,0.153327,0.983883 --1.11637 , 2.69235 , -1.44066 , 0.00407646,0.173428,0.984838 --1.18621 , 2.7992 , -1.45992 , 0.0293263,0.124362,0.991804 --1.25225 , 2.90085 , -1.4693 , 0.00100483,0.109803,0.993953 --1.31953 , 3.00355 , -1.4751 , -0.0122654,0.117525,0.992994 --1.39991 , 3.12752 , -1.49531 , -0.00342083,0.123703,0.992313 --1.48667 , 3.2591 , -1.51689 , -0.0210174,0.135805,0.990513 --1.57867 , 3.39916 , -1.53934 , -0.0437679,0.0716837,0.996467 --1.68472 , 3.56236 , -1.57341 , -0.161561,0.090869,0.98267 --1.80125 , 3.74085 , -1.61213 , 0.128918,-0.175881,-0.975933 --1.92906 , 3.93604 , -1.65473 , -0.0575068,0.168048,0.9841 --2.06234 , 4.14043 , -1.69499 , 0.0224303,0.188344,0.981847 --2.20308 , 4.35459 , -1.73257 , 0.05451,0.19088,0.980099 --2.34443 , 4.57061 , -1.76187 , 0.0468886,0.184762,0.981664 --2.4963 , 4.80373 , -1.79222 , 0.0152456,0.17923,0.983689 --2.67486 , 5.07641 , -1.83607 , 0.00281793,0.182765,0.983153 --2.88926 , 5.40431 , -1.89968 , 0.0106972,0.240509,0.970588 --3.37175 , 6.13709 , -2.17091 , 0.0460356,-0.30582,-0.950976 --3.81948 , 6.81937 , -2.38056 , -0.0645946,0.256714,0.964326 --4.37387 , 7.66294 , -2.63931 , -0.0704475,0.257935,0.96359 --5.05675 , 8.70164 , -2.9519 , -0.0836059,0.219444,0.972036 --5.79781 , 9.83084 , -3.25741 , 0.088327,-0.215509,-0.972499 --6.72629 , 11.2471 , -3.6344 , -0.0169143,0.123432,0.992209 --7.75725 , 12.8202 , -4.01077 , 0.25334,-0.42103,-0.870949 --7.72607 , 12.7832 , -3.70582 , -0.25334,0.421029,0.870949 --7.68099 , 12.7264 , -3.39864 , -0.368621,-0.00838082,0.929542 --7.6644 , 12.7115 , -3.11126 , -0.368621,-0.00838078,0.929542 --11.2158 , 18.1275 , -4.52018 , 0.432414,-0.191655,0.881071 --11.6338 , 18.7788 , -4.31152 , -0.772958,0.0564013,-0.631945 --11.8843 , 19.1767 , -4.00992 , 0.914357,0.0991957,0.39257 --11.9879 , 19.3507 , -3.63929 , -0.883429,0.0986578,-0.45806 --11.8834 , 19.2071 , -3.19318 , 0.774808,-0.130989,0.618477 --11.9578 , 19.3373 , -2.81151 , 0.710388,-0.518035,0.476434 --15.5293 , 24.8152 , -3.39346 , -0.0555816,0.974541,-0.217212 --15.571 , 24.8996 , -2.8844 , 0.0555816,-0.974541,0.217212 --15.6399 , 25.0254 , -2.38017 , -0.0555816,0.974541,-0.217212 --15.7257 , 25.1775 , -1.87603 , -0.0563138,0.974867,-0.215554 --8.29117 , 13.7905 , -0.258578 , 0.854112,-0.499201,0.145912 --8.16171 , 13.6014 , 0.0383107 , -0.29886,0.60631,0.736934 --2.40064 , 4.75876 , 0.796115 , 0.0761713,0.986811,-0.142834 --2.40638 , 4.77098 , 0.888727 , 0.0670363,0.987812,-0.140473 --2.41041 , 4.78184 , 0.981876 , 0.0506181,0.987421,-0.149795 --2.41469 , 4.79174 , 1.07522 , 0.0506181,0.987421,-0.149795 --2.88527 , 5.52071 , 1.19006 , -0.611044,0.714743,-0.340246 --2.88159 , 5.51919 , 1.29861 , 0.595004,-0.743723,0.304705 --2.88709 , 5.53281 , 1.4084 , -0.614442,0.730708,-0.297535 --2.90838 , 5.56984 , 1.52097 , 0.574318,-0.75851,0.30793 --2.91197 , 5.57916 , 1.63259 , -0.524525,0.787227,-0.324263 --2.93655 , 5.62196 , 1.74876 , -0.481018,0.807999,-0.340234 --2.98103 , 5.69534 , 1.87206 , -0.465413,0.792162,-0.394804 --3.01322 , 5.75001 , 1.99587 , 0.237798,-0.860958,0.449669 --3.05535 , 5.81882 , 2.12531 , 0.339836,-0.839419,0.424131 --3.095 , 5.88661 , 2.25784 , -0.277718,0.877935,-0.390004 --5.40921 , 9.4889 , 3.24068 , -0.594077,-0.0784207,-0.800577 --1.904 , 4.04182 , 2.01706 , -0.22893,0.736509,0.63651 --1.84122 , 3.94608 , 2.07132 , -0.577819,0.359462,0.732743 --1.78739 , 3.8665 , 2.12691 , 0.411447,-0.633224,-0.655545 --1.74403 , 3.80159 , 2.18499 , 0.398493,-0.596516,-0.696687 --1.71073 , 3.75345 , 2.24604 , 0.193489,-0.624339,-0.756811 --1.6718 , 3.69565 , 2.3027 , -0.111635,0.742081,0.660949 --1.64801 , 3.66198 , 2.36645 , 0.126788,0.858339,0.497172 --1.6234 , 3.62689 , 2.42935 , 0.103153,0.849176,0.517939 --1.59893 , 3.59056 , 2.49118 , -0.389765,0.726168,0.56636 --1.58903 , 3.57773 , 2.56276 , -0.121543,0.850528,0.511692 --1.56751 , 3.54781 , 2.62663 , 0.234378,0.831459,0.503729 --1.551 , 3.52503 , 2.69365 , -0.362984,-0.831895,-0.419754 --1.49477 , 3.43923 , 2.72719 , -0.265747,-0.860544,-0.434561 --1.51147 , 3.46826 , 2.82186 , 0.435929,0.85161,0.291076 --1.46905 , 3.40468 , 2.86498 , 0.335144,0.887934,0.315043 --1.45491 , 3.38596 , 2.93348 , 0.540123,0.832758,0.121576 --1.4349 , 3.35846 , 2.9971 , 0.588879,0.784178,0.195669 --1.46167 , 3.40306 , 3.1092 , 0.557982,0.800446,0.218957 --1.36725 , 3.25629 , 3.09202 , -0.548412,-0.778193,-0.306039 --3.96051 , 7.3712 , 6.1423 , -0.37287,-0.417183,0.82881 --1.54991 , 3.55347 , 3.48073 , 0.597179,0.798416,0.0768662 --3.49025 , 6.64187 , 5.97972 , 0.500714,-0.329667,0.800378 --1.83282 , 4.01235 , 4.04285 , -0.140447,0.447383,-0.883246 --1.38278 , 3.29882 , 3.55728 , -0.0684963,0.00409891,0.997643 --1.32758 , 3.21466 , 3.57721 , 0.057861,0.220811,0.973599 --1.33079 , 3.2251 , 3.67946 , 0.38749,0.875117,0.289864 --1.49616 , 3.49222 , 4.02495 , 0.622757,0.709504,-0.329815 --1.30218 , 3.18646 , 3.83648 , 0.258705,0.749803,0.608989 --1.16183 , 2.96448 , 3.71421 , 0.207411,0.273698,0.939186 --1.11859 , 2.90069 , 3.74211 , -0.322991,0.0349364,-0.945757 --1.18583 , 3.01133 , 3.95706 , -0.550888,-0.558822,0.619872 --1.14483 , 2.95058 , 3.99183 , -0.696616,0.58974,-0.408574 --1.60474 , 3.69732 , 4.95515 , 0.382627,0.466372,0.797555 --1.51085 , 3.55065 , 4.91757 , -0.488095,-0.472246,-0.733994 --1.45058 , 3.4585 , 4.9405 , -0.0168304,0.882804,0.469441 --2.64552 , 5.40203 , 7.55808 , 0.370242,0.566009,-0.736584 --1.40433 , 3.39489 , 5.13501 , 0.287883,-0.640103,-0.712315 --1.52735 , 3.60121 , 5.56225 , -0.00725394,-0.987742,0.155927 --0.863404 , 2.52493 , 4.19629 , 0.284881,-0.91527,-0.284823 --0.845547 , 2.49959 , 4.27283 , -0.650901,0.66757,0.361494 --1.49083 , 3.56298 , 6.00429 , -0.229814,-0.942145,-0.244025 --1.09147 , 2.91445 , 5.16352 , -0.474393,-0.782435,0.40342 --0.878305 , 2.57053 , 4.7531 , 0.0990953,0.804645,0.585429 --0.774443 , 2.40467 , 4.60958 , 0.675584,-0.430748,0.598366 --0.699797 , 2.28571 , 4.53562 , -0.0471572,-0.576954,0.815414 --1.27441 , 3.24663 , 6.41996 , -0.899383,-0.424397,-0.104872 --1.50093 , 3.63042 , 7.35632 , -0.261691,-0.964286,-0.0408636 --1.04361 , 2.87893 , 6.12374 , -0.313267,-0.908026,0.278124 --0.986802 , 2.79137 , 6.1495 , -0.313267,-0.908026,0.278124 --0.582016 , 2.12005 , 4.92656 , -0.160432,0.703891,0.691953 --0.510458 , 2.00744 , 4.83901 , -0.96546,-0.245982,0.0859055 --0.508328 , 2.00922 , 5.00724 , 0.575662,-0.0857882,-0.813175 --0.48038 , 1.97036 , 5.08635 , 0.218737,-0.37999,-0.898755 --0.428719 , 1.88906 , 5.06518 , 0.142489,0.487284,0.86154 --0.389975 , 1.8303 , 5.09676 , -0.552417,0.103438,0.827125 --0.369713 , 1.80446 , 5.21933 , -0.526714,0.072588,0.846938 --0.25954 , 1.6218 , 4.89587 , -0.356532,-0.249563,0.900335 --0.228695 , 1.57793 , 4.95937 , -0.848813,0.0486724,0.526449 --0.187853 , 1.51448 , 4.96575 , 0.0283707,0.49458,0.868669 --0.117428 , 1.39868 , 4.79054 , 0.297214,-0.214636,-0.930374 --0.0718002 , 1.32845 , 4.75471 , 0.695446,0.339463,0.63334 --0.0505047 , 1.29886 , 4.87059 , -0.799962,-0.176246,0.573584 --0.0395126 , 1.29067 , 5.08244 , -0.845785,0.532008,0.040197 --0.00351851 , 1.23814 , 5.13059 , -0.908007,0.364383,0.206755 -0.0774723 , 1.09898 , 4.77931 , -0.115437,-0.908813,0.400916 --0.0255391 , 1.3103 , 6.13129 , 0.528604,0.173309,0.830988 -0.0421967 , 1.2001 , 5.95452 , -0.200353,-0.926294,0.319122 --0.5834 , 2.00812 , -1.30573 , -0.126991,0.0868126,0.988098 --0.625883 , 2.07671 , -1.31463 , -0.154119,0.0675359,0.985741 --0.67229 , 2.15253 , -1.32883 , -0.165762,0.0862841,0.982384 --0.725918 , 2.24028 , -1.35491 , 0.094368,-0.112386,-0.989173 --0.777458 , 2.32426 , -1.37134 , -0.0801359,0.127884,0.988546 --0.825428 , 2.4021 , -1.37769 , -0.107439,0.160415,0.981185 --0.901131 , 2.52464 , -1.42961 , -0.106787,0.139232,0.984485 --0.938387 , 2.58628 , -1.41002 , -0.086725,0.137643,0.986678 --1.01135 , 2.70581 , -1.4479 , -0.0458335,0.145607,0.98828 --1.06958 , 2.8016 , -1.45589 , -0.025372,0.13395,0.990663 --1.13309 , 2.90438 , -1.46697 , 0.0209482,0.0984045,0.994926 --1.19663 , 3.00889 , -1.47475 , -0.00353932,0.101233,0.994857 --1.27348 , 3.1337 , -1.49685 , -0.00595905,0.14763,0.989025 --1.35141 , 3.26072 , -1.51469 , 0.000198754,0.137844,0.990454 --1.42967 , 3.38874 , -1.52805 , 0.039692,0.0545698,0.997721 --1.52192 , 3.53973 , -1.55381 , 0.0153558,0.000958576,0.999882 --1.55718 , 3.59997 , -1.50312 , 0.0153558,0.000958568,0.999882 --1.73631 , 3.88898 , -1.6209 , 0.308369,-0.0447257,-0.950215 --1.87605 , 4.11815 , -1.68112 , -0.0708811,0.183754,0.980413 --2.01839 , 4.34978 , -1.73263 , 0.00979309,0.182951,0.983073 --2.15743 , 4.57606 , -1.77055 , 0.0454306,0.180387,0.982546 --2.30182 , 4.81285 , -1.80467 , 0.0217272,0.190014,0.981541 --2.47166 , 5.08982 , -1.85284 , 0.00807277,0.190067,0.981738 --2.67611 , 5.42267 , -1.92125 , 0.0184517,0.236958,0.971345 --3.0057 , 5.95963 , -2.08742 , -0.0373049,0.306025,0.951292 --3.42133 , 6.63506 , -2.30187 , -0.061084,0.258227,0.964151 --3.9036 , 7.41976 , -2.54041 , -0.066575,0.251928,0.965453 --4.51372 , 8.41115 , -2.84214 , -0.0873841,0.232976,0.968548 --5.13838 , 9.42971 , -3.11132 , -0.0869018,0.213066,0.973166 --5.99186 , 10.8176 , -3.49462 , -0.0933886,0.211584,0.972888 --6.97186 , 12.4129 , -3.90088 , -0.192198,-0.260275,-0.946212 --8.34337 , 14.6468 , -4.4826 , -0.0776601,0.230487,0.969972 --9.57113 , 16.6494 , -4.88276 , -0.0316491,-0.227474,0.97327 --9.93589 , 17.2535 , -4.72175 , -0.0379843,-0.235307,0.971179 --10.3256 , 17.8994 , -4.55098 , 0.000632291,-0.275131,0.961406 --10.7307 , 18.5695 , -4.36287 , -0.122573,0.188237,-0.974445 --11.8385 , 20.384 , -4.46255 , 0.988289,0.0945699,0.119759 --12.0852 , 20.8001 , -4.13446 , -0.915463,-0.115076,-0.385596 --12.1092 , 20.8525 , -3.70803 , -0.915463,-0.115076,-0.385596 --12.726 , 21.8713 , -3.48514 , -0.97898,-0.0401522,-0.199963 --12.5679 , 21.6281 , -2.98415 , -0.97898,-0.0401522,-0.199963 --14.5819 , 24.9301 , -3.09033 , 0.0583717,-0.970409,0.234304 --14.6468 , 25.0512 , -2.59427 , -0.0583717,0.97041,-0.234304 --14.6753 , 25.1138 , -2.08817 , 0.0614244,-0.971956,0.227 --21.5049 , 36.3024 , -2.75344 , -0.114824,-0.049292,0.992162 --21.5725 , 36.436 , -2.02287 , -0.09595,0.0182439,0.995219 --2.20222 , 4.72709 , 0.753908 , 0.110396,0.984938,-0.133077 --2.20854 , 4.74002 , 0.844159 , 0.110396,0.984938,-0.133077 --2.21843 , 4.76019 , 0.934665 , 0.109787,0.973224,-0.201947 --2.22883 , 4.77855 , 1.02595 , 0.0945304,0.974292,-0.204499 --2.24286 , 4.80428 , 1.11808 , -0.256344,-0.964781,-0.0590416 --2.10996 , 4.59011 , 1.20195 , 0.182088,0.923498,0.337633 --2.18477 , 4.71564 , 1.29723 , 0.548211,0.836125,-0.0189642 --2.2378 , 4.80577 , 1.39483 , -0.549714,-0.811237,0.19927 --2.79144 , 5.71989 , 1.57854 , -0.606428,0.745013,-0.277851 --2.80069 , 5.73735 , 1.69222 , 0.747643,-0.604441,0.275103 --2.8029 , 5.74461 , 1.80564 , -0.68887,0.632855,-0.353486 --2.81442 , 5.76742 , 1.92215 , 0.690429,-0.641462,0.334416 --2.85007 , 5.83064 , 2.04758 , 0.596145,-0.702423,0.388862 --2.87454 , 5.87416 , 2.17243 , 0.432712,-0.859496,0.272079 --2.90308 , 5.92472 , 2.30105 , 0.329507,-0.892653,0.307564 --2.93028 , 5.97334 , 2.43204 , 0.218083,-0.901337,0.374207 --2.96085 , 6.02795 , 2.56761 , -0.129202,0.906294,-0.402416 --3.00997 , 6.11283 , 2.71551 , 0.223777,-0.897812,0.379286 --3.04291 , 6.17082 , 2.85949 , 0.162215,-0.92039,0.355764 --1.67294 , 3.90371 , 2.23537 , -0.342618,0.578191,0.740478 --1.63085 , 3.83658 , 2.29139 , 0.516246,-0.406108,-0.754033 --1.57903 , 3.75265 , 2.33878 , -0.623646,0.298693,0.722391 --1.54134 , 3.69252 , 2.39289 , -0.615201,0.424706,0.664193 --1.50828 , 3.64012 , 2.4483 , 0.456239,-0.612068,-0.645925 --1.48494 , 3.60281 , 2.50914 , -0.342027,0.713049,0.612028 --1.45066 , 3.54945 , 2.56137 , -0.161372,0.671685,0.723048 --1.41746 , 3.49493 , 2.61182 , 0.0102281,0.70847,0.705667 --1.39185 , 3.45621 , 2.66852 , -0.303585,0.670775,0.676681 --1.36736 , 3.41648 , 2.72414 , -0.312367,0.678548,0.664831 --1.34083 , 3.37603 , 2.77873 , -0.0681865,0.789573,0.609856 --1.31541 , 3.33455 , 2.83203 , -0.0236869,0.758505,0.651236 --1.29307 , 3.29984 , 2.88902 , 0.208385,0.817222,0.53733 --1.27065 , 3.2649 , 2.94494 , 0.0945859,0.841468,0.531964 --1.24303 , 3.22219 , 2.99499 , 0.145474,0.83301,0.53379 --1.22068 , 3.18581 , 3.04896 , 0.181209,0.813365,0.552812 --1.20073 , 3.15517 , 3.10753 , -0.351625,0.750761,0.559212 --1.17631 , 3.11792 , 3.1598 , -0.262343,0.797834,0.542805 --1.16508 , 3.09987 , 3.22803 , 0.0402861,0.918656,0.392999 --1.14843 , 3.075 , 3.29019 , 0.0513816,0.863111,0.502394 --1.14312 , 3.06916 , 3.36972 , -0.408288,-0.877852,-0.250352 --1.15793 , 3.09666 , 3.47958 , -0.290125,-0.952555,0.0920165 --1.20718 , 3.18237 , 3.64651 , 0.663425,0.718064,0.210362 --1.17491 , 3.13024 , 3.69214 , 0.766351,0.587202,0.260577 --1.1108 , 3.02461 , 3.6851 , 0.506588,0.592133,0.626696 --1.0933 , 2.99762 , 3.75325 , -0.663504,-0.145309,-0.733926 --1.19958 , 3.18244 , 4.04105 , -0.396482,-0.914392,-0.0817902 --1.56567 , 3.80675 , 4.82008 , 0.546426,0.533259,0.645796 --1.3548 , 3.45214 , 4.55807 , 0.136027,0.975837,0.170994 --1.41186 , 3.55276 , 4.79773 , 0.136027,0.975837,0.170994 --1.39424 , 3.52632 , 4.89906 , -0.0140258,0.955895,0.293374 --1.3685 , 3.48642 , 4.98574 , -0.106617,0.906169,0.409257 --1.36519 , 3.48585 , 5.12375 , 0.258608,-0.776863,-0.574113 --0.83857 , 2.59041 , 4.08057 , -0.254093,0.964088,0.0772728 --0.83959 , 2.59451 , 4.19541 , -0.613085,0.790014,-0.00198769 --1.38809 , 3.5403 , 5.65289 , -0.137339,0.9876,-0.076048 --0.611683 , 2.21135 , 3.86176 , 0.28415,0.122183,-0.950963 --1.38381 , 3.54317 , 5.99618 , -0.229814,-0.942145,-0.244025 --0.786859 , 2.52022 , 4.55902 , 0.365059,-0.879022,-0.306678 --0.705509 , 2.38271 , 4.46446 , 0.0162472,-0.141129,0.989858 --0.664368 , 2.31714 , 4.4812 , -0.113158,0.366874,-0.923363 --0.627204 , 2.25606 , 4.50476 , 0.354216,-0.12509,-0.92676 --1.40929 , 3.62123 , 7.14279 , -0.341338,-0.939455,-0.0302108 --1.46887 , 3.73168 , 7.59405 , 0.251757,0.967738,0.0100864 --0.622187 , 2.26167 , 4.93815 , 0.475569,0.0894367,0.87512 --0.562123 , 2.16107 , 4.88969 , -0.435961,0.564983,0.700523 --0.512264 , 2.07918 , 4.87366 , -0.970322,0.175047,0.166834 --0.495024 , 2.05388 , 4.98005 , -0.856236,0.190091,0.480339 --0.41676 , 1.92123 , 4.84439 , 0.224039,0.373413,0.900205 --0.410671 , 1.9169 , 5.00309 , 0.0820183,0.885055,0.458204 --0.340359 , 1.79717 , 4.87975 , 0.243213,0.212648,0.946377 --0.366937 , 1.84986 , 5.20342 , -0.61741,-0.00856161,0.786595 --0.315487 , 1.76482 , 5.16901 , 0.778059,-0.395061,-0.488418 --0.226479 , 1.6117 , 4.92724 , 0.983739,0.0411086,-0.174836 --0.214434 , 1.5961 , 5.0843 , 0.0143784,0.261414,0.96512 --0.115036 , 1.42359 , 4.7412 , 0.37605,-0.30538,-0.874831 --0.103534 , 1.40963 , 4.90556 , -0.359519,0.845114,0.395637 --0.0358445 , 1.29185 , 4.70737 , 0.735531,0.508641,-0.447525 --0.0386715 , 1.30606 , 4.99546 , -0.364258,0.73763,0.568523 --0.0116629 , 1.26276 , 5.08249 , -0.663639,0.672482,0.327645 -0.0125496 , 1.229 , 5.21722 , -0.572017,-0.817109,-0.0716146 --0.0519245 , 1.36255 , 6.17941 , 0.777875,0.624661,-0.0686239 -0.0172271 , 1.24306 , 5.97472 , -0.942886,-0.322455,-0.0835963 --0.729895 , 2.40857 , -1.37923 , -0.107439,0.160415,0.981185 --0.779122 , 2.49599 , -1.39154 , -0.0951841,0.132579,0.986592 --0.833809 , 2.58923 , -1.40763 , -0.126613,0.126505,0.983852 --0.887287 , 2.68486 , -1.42088 , -0.0810392,0.123924,0.988977 --0.961831 , 2.81329 , -1.46335 , -0.0425673,0.147608,0.98813 --1.02163 , 2.91796 , -1.47602 , 0.017948,0.109245,0.993853 --1.07784 , 3.01644 , -1.47881 , 0.0465654,0.146399,0.988129 --1.14685 , 3.13699 , -1.49689 , 0.0420924,0.15629,0.986814 --1.21618 , 3.25848 , -1.51079 , 0.0396856,0.135624,0.989965 --1.29456 , 3.39537 , -1.53223 , 0.0149597,0.138553,0.990242 --1.3772 , 3.5405 , -1.55451 , -0.0979256,-0.0246999,-0.994887 --1.46194 , 3.68821 , -1.57188 , 0.125226,0.0357676,0.991483 --1.47459 , 3.7131 , -1.4923 , 0.126964,-0.0642719,0.989823 --1.65323 , 4.02366 , -1.61707 , -0.291803,-0.29853,0.908698 --1.81749 , 4.30996 , -1.7099 , -0.516083,0.00807482,0.8565 --1.95789 , 4.55461 , -1.76215 , -0.0132485,0.168014,0.985696 --2.1039 , 4.80893 , -1.81001 , 0.0248681,0.173467,0.984526 --2.26007 , 5.08256 , -1.85795 , 0.0240263,0.179509,0.983463 --2.43588 , 5.3889 , -1.91351 , 0.0273765,0.230619,0.972659 --2.71189 , 5.87085 , -2.05289 , -0.0256669,0.283724,0.958562 --3.06808 , 6.49212 , -2.24461 , -0.062203,0.258231,0.964079 --3.48397 , 7.21673 , -2.46042 , -0.0683552,0.252277,0.965238 --4.00982 , 8.13266 , -2.73647 , -0.0897465,0.237771,0.967166 --4.63292 , 9.22141 , -3.05046 , -0.0960966,0.206195,0.973781 --5.33769 , 10.4506 , -3.378 , -0.0985297,0.211668,0.972362 --6.04976 , 11.6926 , -3.65727 , -0.0390254,0.171621,0.98439 --7.35233 , 13.9651 , -4.28452 , 0.146216,0.336781,0.930161 --8.69964 , 16.3167 , -4.8424 , -0.0790771,-0.0277403,0.996482 --9.12821 , 17.0698 , -4.74848 , -0.0136369,-0.229799,0.973142 --9.49951 , 17.7247 , -4.59348 , -0.00593668,-0.252309,0.967628 --9.86569 , 18.3713 , -4.41145 , -0.00673495,-0.265715,0.964028 --10.2509 , 19.052 , -4.21459 , 0.0202262,-0.310672,0.950302 --12.0481 , 22.1953 , -4.62964 , -0.94622,-0.100893,-0.30739 --12.1891 , 22.45 , -4.22874 , -0.953977,-0.0808612,-0.288774 --12.0336 , 22.1873 , -3.70834 , -0.97898,-0.0401522,-0.199963 --12.264 , 22.6004 , -3.33447 , 0.988568,0.0313856,0.147471 --13.592 , 24.9308 , -3.28253 , -0.0732761,0.96997,-0.231926 --12.1964 , 22.4999 , -2.40024 , 0.988568,0.0313856,0.147471 --13.7282 , 25.1897 , -2.30796 , -0.0790174,0.970807,-0.226472 --13.7809 , 25.2907 , -1.81294 , 0.0829105,-0.97148,0.222155 --13.8282 , 25.3847 , -1.31502 , 0.0676194,-0.973572,0.218142 --13.8861 , 25.4973 , -0.816198 , 0.0680189,-0.974606,0.213346 --2.02731 , 4.72829 , 0.801514 , 0.116691,0.982231,-0.146987 --2.02295 , 4.72365 , 0.89077 , 0.131493,0.983724,-0.122459 --2.02766 , 4.73383 , 0.979809 , 0.129601,0.970933,-0.201228 --2.05164 , 4.77828 , 1.06923 , 0.0494824,0.977315,0.205931 --7.08886 , 13.6196 , 1.39797 , -0.32126,0.553337,0.768512 --1.94491 , 4.59296 , 1.24063 , -0.0304467,0.970852,0.237737 --1.95155 , 4.60747 , 1.32804 , 0.164736,-0.985836,-0.0314423 --1.97279 , 4.64618 , 1.41834 , -0.00447372,-0.991065,0.133302 --1.99265 , 4.68281 , 1.51045 , 0.277597,0.953323,-0.118803 --2.00184 , 4.7019 , 1.60167 , 0.277597,0.953323,-0.118803 --2.73625 , 5.99529 , 1.88299 , 0.696265,-0.662608,0.275982 --2.73227 , 5.98997 , 1.99889 , 0.78756,-0.579623,0.209253 --2.72729 , 5.98434 , 2.11453 , 0.588066,-0.784697,0.196034 --2.73658 , 6.00129 , 2.23582 , 0.673948,-0.693938,0.253465 --2.73407 , 5.99997 , 2.3541 , 0.578867,-0.751299,0.316958 --2.75487 , 6.03929 , 2.48336 , -0.581766,0.759786,-0.290299 --2.77901 , 6.08453 , 2.61689 , 0.477353,-0.848169,0.229658 --2.80277 , 6.128 , 2.7525 , 0.293407,-0.915593,0.274958 --2.82895 , 6.1773 , 2.89308 , 0.208945,-0.928225,0.3078 --2.85855 , 6.23272 , 3.03882 , 0.165351,-0.933358,0.318594 --2.88608 , 6.28508 , 3.18745 , 0.307026,-0.902743,0.301313 --5.71196 , 11.2836 , 5.22372 , -0.0996021,-0.593342,0.798765 --1.48485 , 3.81034 , 2.4559 , -0.61555,0.310876,0.724193 --1.44369 , 3.73997 , 2.50529 , -0.596077,0.341333,0.726763 --1.40234 , 3.66905 , 2.55224 , 0.380127,-0.39322,-0.837187 --1.36082 , 3.5976 , 2.59686 , -0.773081,0.127583,0.621344 --1.32877 , 3.54221 , 2.64681 , -0.787644,0.170083,0.59219 --1.30555 , 3.50194 , 2.70337 , 0.326779,-0.669359,-0.667214 --1.28149 , 3.4602 , 2.7589 , -0.555377,0.532494,0.638754 --1.26124 , 3.42637 , 2.81759 , -0.52312,0.536026,0.662587 --1.23213 , 3.37565 , 2.86626 , -0.488933,0.56282,0.666467 --1.20194 , 3.32439 , 2.9136 , -0.38742,0.610318,0.690954 --1.18068 , 3.28857 , 2.96901 , -0.29346,0.682068,0.669824 --1.15028 , 3.23665 , 3.01343 , -0.658344,0.453668,0.60064 --1.12908 , 3.19936 , 3.06671 , -0.416126,0.64694,0.63899 --1.10192 , 3.15305 , 3.11403 , -0.434513,0.6025,0.669472 --1.07959 , 3.11504 , 3.16519 , -0.386345,0.618719,0.68405 --1.05668 , 3.07466 , 3.2158 , -0.127688,0.767478,0.62823 --1.03248 , 3.03478 , 3.26525 , -0.186497,0.640729,0.744772 --1.00844 , 2.99371 , 3.31384 , -0.111231,0.653984,0.748286 --0.984326 , 2.9524 , 3.36135 , 0.515658,-0.530638,-0.672696 --0.967125 , 2.9236 , 3.42043 , -0.27931,0.758275,0.589071 --0.949873 , 2.89465 , 3.47882 , -0.215348,0.741235,0.635764 --0.93535 , 2.87081 , 3.54337 , -0.407985,-0.880119,-0.242774 --0.960736 , 2.9171 , 3.68048 , 0.574714,0.790562,0.211461 --0.904956 , 2.81949 , 3.67173 , 0.552126,0.652999,0.518411 --1.36005 , 3.63714 , 4.64829 , -0.77739,-0.585501,-0.2299 --0.819304 , 2.66945 , 3.69421 , 0.40067,0.734651,0.547495 --1.3049 , 3.54377 , 4.80115 , 0.0261733,0.974666,0.222128 --1.26549 , 3.47496 , 4.85087 , -0.00110113,0.925487,0.378777 --3.5583 , 7.60519 , 10.1129 , -0.278047,0.889682,-0.362155 --0.793492 , 2.63209 , 4.04152 , 0.0241731,0.992065,0.123381 --2.45119 , 5.62297 , 8.13107 , 0.0264062,-0.701133,0.712541 --0.626319 , 2.33302 , 3.8482 , -0.28722,-0.0739522,0.955006 --1.29372 , 3.54181 , 5.67664 , 0.18991,0.980432,0.0518318 --1.26476 , 3.49348 , 5.77215 , -0.18991,-0.980432,-0.0518318 --0.743623 , 2.55371 , 4.50359 , 0.0221731,-0.995572,0.0913547 --0.710581 , 2.49529 , 4.54011 , 0.182578,0.0519861,0.981816 --0.723324 , 2.5221 , 4.71494 , 0.150372,0.960569,-0.23387 --0.913138 , 2.86967 , 5.44954 , -0.551148,-0.797949,-0.243954 --0.733238 , 2.54689 , 5.04564 , -0.159201,-0.18046,0.970613 --0.645257 , 2.38896 , 4.91117 , -0.918457,-0.177214,-0.353599 --0.559477 , 2.2368 , 4.77154 , 0.563361,-0.672696,-0.479693 --0.529461 , 2.18439 , 4.81819 , -0.68904,0.254191,0.678683 --0.498631 , 2.13057 , 4.8641 , 0.749113,-0.12909,-0.649743 --0.502843 , 2.1419 , 5.05056 , -0.918584,0.308881,0.246567 --0.491367 , 2.12486 , 5.18478 , 0.534848,-0.364045,0.762502 --0.356212 , 1.87876 , 4.78798 , 0.148354,0.562607,0.813304 --0.332944 , 1.84046 , 4.86425 , -0.172652,0.59406,0.785674 --0.280884 , 1.74751 , 4.80257 , -0.503648,-0.537134,-0.676628 --0.318993 , 1.82171 , 5.19084 , 0.780483,-0.429154,-0.454613 --0.228106 , 1.65834 , 4.93231 , 0.0507468,-0.300365,0.952473 --0.177913 , 1.56788 , 4.86521 , 0.139107,0.847915,0.511556 --0.128819 , 1.48031 , 4.79551 , -0.613501,-0.213082,0.760403 --0.0958298 , 1.42327 , 4.81836 , 0.769004,0.353981,-0.532288 --0.0571976 , 1.35563 , 4.80187 , -0.806631,-0.148019,0.572221 --0.0392654 , 1.32579 , 4.92774 , -0.923451,0.317734,0.215138 --0.0229301 , 1.30019 , 5.08224 , -0.981638,0.148764,-0.119403 -0.000514301 , 1.26164 , 5.19805 , -0.572017,-0.81711,-0.0716147 -0.0849172 , 1.10547 , 4.78909 , -0.115437,-0.908813,0.400916 --0.0168818 , 1.31039 , 6.11167 , 0.39105,0.13383,0.910588 -0.045324 , 1.1994 , 5.94474 , 0.145853,-0.944868,0.293174 --1.03712 , 3.16279 , -1.52003 , 0.0704454,0.154061,0.985547 --1.09597 , 3.27232 , -1.52336 , 0.0500259,0.160242,0.985809 --1.16576 , 3.40374 , -1.54066 , 0.0433475,0.143706,0.988671 --1.23687 , 3.5364 , -1.55351 , 0.0293873,0.161138,0.986494 --1.31979 , 3.69255 , -1.57871 , 0.129808,0.0757287,0.988643 --1.40386 , 3.85112 , -1.59869 , 0.373186,-0.220485,0.901176 --1.44095 , 3.92102 , -1.54919 , 0.364579,-0.236206,0.900716 --1.4784 , 3.99038 , -1.49765 , 0.266087,0.66409,-0.698701 --1.52664 , 4.0828 , -1.45931 , 0.381277,0.67935,-0.626987 --1.56762 , 4.15922 , -1.40839 , 0.401244,0.803466,-0.439826 --1.62068 , 4.25826 , -1.36923 , 0.441469,0.861296,-0.251545 --1.57261 , 4.1696 , -1.21735 , 0.42775,0.88926,-0.16201 --1.58142 , 4.18753 , -1.13129 , 0.224788,0.969584,-0.0968365 --2.74379 , 6.35924 , -2.19373 , -0.0630319,0.256312,0.964537 --3.10057 , 7.02735 , -2.38836 , -0.0693965,0.243966,0.967298 --3.54908 , 7.86583 , -2.63633 , 0.0744377,-0.23388,-0.969412 --4.03589 , 8.77941 , -2.88211 , -0.0856562,0.214631,0.972932 --4.58142 , 9.80044 , -3.13597 , 0.0900149,-0.214586,-0.972548 --5.4649 , 11.4535 , -3.60936 , -0.0871783,0.208684,0.97409 --6.56059 , 13.5059 , -4.16911 , 0.0248679,0.325977,0.945051 --7.6273 , 15.5031 , -4.6209 , -0.0430916,0.149416,0.987835 --8.3879 , 16.9285 , -4.78846 , -0.0556812,-0.103638,0.993055 --8.71807 , 17.55 , -4.63384 , -0.0195072,-0.235462,0.971688 --9.07589 , 18.2229 , -4.47204 , -0.000236453,-0.255416,0.966831 --9.43765 , 18.9046 , -4.28785 , 0.00304909,-0.256821,0.966454 --12.0838 , 23.8634 , -5.21288 , -0.465537,-0.0662167,-0.882548 --12.2928 , 24.2585 , -4.81936 , -0.929423,-0.183316,-0.320263 --12.2952 , 24.2687 , -4.32701 , -0.948989,-0.196783,-0.246368 --12.6185 , 24.878 , -3.95954 , -0.0100265,-0.916407,0.400121 --12.6737 , 24.9872 , -3.4789 , 0.0210011,-0.929265,0.368816 --12.7207 , 25.0804 , -2.99404 , 0.0319008,-0.94319,0.33072 --12.7921 , 25.2186 , -2.51446 , 0.0737787,-0.971097,0.226997 --12.8358 , 25.3057 , -2.02519 , 0.0941544,-0.968103,0.232187 --7.34588 , 15.0151 , -0.470572 , 0.501325,-0.69059,-0.521304 --7.57643 , 15.4503 , -0.21333 , 0.501325,-0.69059,-0.521304 --1.84999 , 4.70965 , 0.761373 , 0.35676,0.927824,-0.108924 --1.83716 , 4.68699 , 0.849883 , 0.341318,0.937471,-0.0681905 --1.8475 , 4.70747 , 0.936277 , 0.299824,0.945965,-0.123515 --1.85208 , 4.71725 , 1.02356 , 0.229345,0.947637,-0.222227 --1.8803 , 4.76987 , 1.11185 , 0.089961,0.987573,0.128869 --1.86024 , 4.73255 , 1.19907 , -0.193732,-0.886804,-0.419579 --1.82446 , 4.66913 , 1.54416 , -0.144382,0.986004,-0.0833616 --1.84261 , 4.70436 , 1.63661 , 0.17462,-0.980845,0.0863241 --4.19627 , 9.12935 , 2.41438 , -0.185885,-0.0838928,0.978983 --2.84218 , 6.58563 , 2.14522 , -0.944844,-0.19756,0.261228 --2.81367 , 6.5335 , 2.26242 , -0.950447,-0.103146,0.293276 --2.72837 , 6.37508 , 2.35553 , -0.968466,-0.0394722,0.245999 --2.65724 , 6.24125 , 2.44893 , -0.95941,0.281998,0.00312462 --2.64472 , 6.21937 , 2.56612 , -0.811683,0.583509,0.0262437 --2.64534 , 6.22106 , 2.69007 , -0.854127,0.492773,-0.16626 --2.64827 , 6.22823 , 2.81744 , -0.657484,0.70609,-0.262968 --2.65975 , 6.25136 , 2.95074 , 0.658047,-0.710797,0.248479 --2.68387 , 6.29758 , 3.09413 , 0.583953,-0.761531,0.281193 --2.70591 , 6.34066 , 3.24002 , 0.488806,-0.844435,0.219087 --2.72301 , 6.37285 , 3.38494 , 0.487723,-0.822382,0.292941 --2.77274 , 6.46957 , 3.5588 , -0.261974,0.84314,-0.469557 --2.83901 , 6.59532 , 3.7515 , 0.261974,-0.84314,0.469557 --2.87692 , 6.66752 , 3.92767 , 0.261974,-0.84314,0.469557 --1.66905 , 4.39131 , 2.98989 , 0.600195,0.650784,-0.465022 --1.30554 , 3.70569 , 2.74329 , -0.9146,-0.0360874,0.402745 --1.31148 , 3.71915 , 2.8315 , 0.804179,0.328185,-0.495572 --1.39779 , 3.88233 , 3.00335 , -0.892151,-0.290193,-0.3462 --1.43511 , 3.95411 , 3.13258 , -0.951946,-0.259211,-0.163124 --1.45042 , 3.98373 , 3.24193 , -0.953882,0.300113,-0.00640509 --1.40765 , 3.90332 , 3.28538 , -0.953882,0.300113,-0.00640508 --1.41686 , 3.92125 , 3.39124 , -0.950148,0.0556666,0.306791 --1.45315 , 3.99141 , 3.53417 , -0.854742,0.479807,0.197993 --1.09028 , 3.30647 , 3.15323 , 0.67776,-0.305684,-0.66873 --1.04465 , 3.22179 , 3.17442 , 0.510845,-0.407417,-0.756999 --1.01142 , 3.15885 , 3.20961 , -0.484305,0.342461,0.80509 --0.989464 , 3.11864 , 3.2599 , -0.223723,0.58168,0.782047 --0.963455 , 3.06977 , 3.30361 , -0.598071,0.369023,0.711431 --0.93312 , 3.01306 , 3.34006 , 0.527906,-0.431719,-0.731392 --0.90594 , 2.96335 , 3.38117 , 0.433798,-0.563028,-0.703433 --0.883132 , 2.91995 , 3.4272 , -0.274177,0.624789,0.731071 --0.862781 , 2.8825 , 3.4787 , -0.097877,0.671277,0.734716 --0.838845 , 2.83841 , 3.52272 , 0.0328451,0.70876,0.704685 --0.818592 , 2.79958 , 3.57257 , -0.312397,-0.790154,-0.527319 --0.800832 , 2.76682 , 3.62837 , 0.184063,0.651964,0.73557 --0.778746 , 2.72622 , 3.67691 , -0.0964367,0.607171,0.788697 --0.723548 , 2.62265 , 3.65394 , -0.138228,0.728316,0.671155 --0.73718 , 2.64976 , 3.77848 , 0.0641067,0.949816,0.30617 --0.73048 , 2.63785 , 3.86082 , 0.164867,0.823752,0.54245 --0.669009 , 2.52326 , 3.81757 , -0.121317,0.275544,0.953603 --0.637515 , 2.46304 , 3.83845 , -0.896253,0.406791,0.176782 --0.661926 , 2.51059 , 4.0031 , 0.366575,0.926898,-0.0805149 --0.766506 , 2.7108 , 4.38746 , 0.467273,0.371085,0.802466 --1.20406 , 3.54504 , 5.70818 , -0.18991,-0.980432,-0.0518318 --0.673899 , 2.53647 , 4.3771 , -0.612985,-0.597284,-0.517205 --0.678563 , 2.54784 , 4.51757 , 0.0197807,-0.965272,-0.260496 --0.639757 , 2.47328 , 4.52877 , 0.0365617,-0.292846,0.95546 --0.775127 , 2.73299 , 5.09228 , -0.155325,-0.804655,0.573066 --0.61395 , 2.42798 , 4.72122 , 0.0668389,0.936545,0.344116 --0.568856 , 2.34237 , 4.71194 , 0.706997,0.507482,0.492562 --0.499894 , 2.21263 , 4.61471 , -0.424213,0.878756,0.218703 --0.516701 , 2.2457 , 4.82503 , 0.579961,-0.386564,-0.717087 --0.490259 , 2.19595 , 4.88028 , 0.547098,-0.449016,-0.706447 --0.465166 , 2.14924 , 4.94347 , -0.838171,0.434419,0.329772 --0.440475 , 2.10542 , 5.01503 , 0.65868,-0.416496,-0.626635 --0.346797 , 1.92643 , 4.7808 , 0.144927,0.827505,0.542432 --0.317536 , 1.87192 , 4.8215 , 0.765689,0.595927,0.242055 --0.286745 , 1.81382 , 4.85182 , 0.48428,0.72591,0.488393 --0.319831 , 1.88096 , 5.21204 , 0.635888,-0.744309,0.204087 --0.228507 , 1.70566 , 4.93701 , -0.198159,0.303038,0.932149 --0.172797 , 1.60103 , 4.83353 , -0.25095,-0.678078,-0.690822 --0.146217 , 1.55087 , 4.88693 , -0.507952,-0.759756,-0.405902 --0.123183 , 1.50934 , 4.96761 , -0.292834,-0.153196,-0.943811 --0.0787748 , 1.42341 , 4.90532 , -0.759813,-0.592398,-0.267862 --0.0495142 , 1.3689 , 4.94602 , -0.326758,0.523449,0.786912 --0.031773 , 1.33904 , 5.08165 , -0.93337,-0.0152478,-0.358593 -0.0252382 , 1.22912 , 4.90864 , 0.972188,-0.158447,-0.172468 -0.0530731 , 1.17621 , 4.95535 , 0.712366,0.587771,-0.383483 --0.035799 , 1.35589 , 6.12095 , 0.546607,-0.452906,0.704342 -0.0251756 , 1.23924 , 5.94554 , -0.914287,-0.27506,-0.297357 --1.18253 , 3.70037 , -1.58978 , 0.152793,0.12655,0.980122 --1.26187 , 3.86049 , -1.61181 , 0.110456,-0.254325,0.96079 --1.30136 , 3.93906 , -1.56898 , -0.117956,-0.468079,0.875779 --1.3287 , 3.99421 , -1.50802 , -0.102915,-0.742633,0.661743 --1.36281 , 4.06493 , -1.45612 , 0.0736462,0.691082,-0.719015 --1.37447 , 4.08728 , -1.37241 , -0.0305306,-0.832564,0.553088 --1.38539 , 4.10842 , -1.28857 , 0.270972,-0.92035,0.282012 --1.39156 , 4.12093 , -1.20017 , 0.373373,-0.907422,0.192817 --1.40496 , 4.14703 , -1.12072 , 0.158478,-0.960877,0.227157 --1.40886 , 4.15582 , -1.03233 , 0.338788,-0.930538,0.139 --1.42075 , 4.17948 , -0.952734 , 0.350462,-0.932931,0.082562 --1.42432 , 4.18498 , -0.86461 , 0.590316,-0.785243,0.186871 --1.43471 , 4.20619 , -0.78486 , 0.556931,-0.812895,0.170379 --1.44437 , 4.22624 , -0.704793 , 0.532888,-0.822922,0.197053 --1.44968 , 4.23551 , -0.620836 , 0.508224,-0.841288,0.184234 --1.45807 , 4.25216 , -0.540422 , -0.47853,0.85226,-0.211335 --1.46572 , 4.26763 , -0.459787 , -0.451903,0.854621,-0.255748 --1.47261 , 4.28186 , -0.379125 , -0.437813,0.863437,-0.250591 --1.48749 , 4.31262 , -0.304332 , 0.398001,-0.882601,0.250222 --1.49801 , 4.33257 , -0.225747 , 0.368867,-0.898267,0.23886 --1.50365 , 4.34345 , -0.144544 , -0.32043,0.926611,-0.196764 --1.51269 , 4.36103 , -0.0655176 , -0.305512,0.930368,-0.202679 --1.5161 , 4.36833 , 0.0162509 , -0.305123,0.928609,-0.21115 --1.52858 , 4.39271 , 0.0935866 , 0.303739,-0.929726,0.208214 --1.53543 , 4.40679 , 0.173567 , -0.271785,0.940914,-0.202025 --1.54154 , 4.4197 , 0.253866 , 0.219601,-0.94838,0.228804 --1.55185 , 4.4407 , 0.332642 , 0.155452,-0.960624,0.230296 --1.56569 , 4.46876 , 0.410896 , -0.106374,0.963617,-0.245207 --1.57482 , 4.48661 , 0.491089 , 0.046219,-0.974826,0.218125 --1.58324 , 4.50335 , 0.571893 , -0.00571978,-0.975607,0.219452 --1.59617 , 4.52744 , 0.652345 , 0.0355877,0.972024,-0.232169 --1.6072 , 4.55121 , 0.733524 , 0.0574064,0.972925,-0.223876 --1.61874 , 4.57317 , 0.815488 , 0.250748,0.945297,-0.208659 --1.62452 , 4.58449 , 0.898637 , -0.262034,-0.946668,0.187502 --1.63895 , 4.61268 , 0.981855 , -0.323381,-0.901237,0.288438 --1.65271 , 4.63988 , 1.06617 , -0.356549,-0.922272,0.149288 --1.70926 , 4.7551 , 1.15383 , -0.268949,-0.9458,-0.182014 --1.63697 , 4.60987 , 1.23416 , 0.313317,0.900494,0.301569 --3.97037 , 9.30892 , 2.51143 , -0.185885,-0.0838928,0.978983 --4.02482 , 9.41742 , 2.71106 , -0.183684,-0.019129,0.982799 --2.82972 , 7.01044 , 2.40452 , -0.9353,-0.194769,0.295432 --2.85383 , 7.05831 , 2.55082 , -0.934279,-0.211988,0.286679 --6.4556 , 14.3139 , 4.45886 , 0.492155,-0.662838,-0.564296 --6.41983 , 14.2397 , 4.72701 , -0.542134,0.338021,0.769306 --2.59926 , 6.54349 , 2.8202 , -0.863143,0.499765,-0.0722449 --2.56739 , 6.47979 , 2.93121 , -0.921157,0.387118,-0.0401142 --2.55649 , 6.45844 , 3.05413 , -0.792053,0.609666,-0.0309831 --2.54981 , 6.44292 , 3.17983 , -0.593555,0.793891,-0.132019 --2.5619 , 6.4679 , 3.32131 , 0.688345,-0.6905,0.22224 --2.56518 , 6.47387 , 3.45766 , 0.510556,-0.772805,0.376968 --2.62936 , 6.60266 , 3.64725 , 0.408817,-0.787297,0.461555 --2.67483 , 6.69449 , 3.82798 , 0.509894,-0.708989,0.487179 --1.43125 , 4.18866 , 2.82395 , 0.807521,0.576882,0.122951 --1.35921 , 4.0457 , 2.84403 , -0.868806,-0.312702,-0.383919 --1.42235 , 4.17152 , 2.99521 , -0.965196,0.107438,-0.238442 --1.41155 , 4.14853 , 3.0746 , 0.98631,-0.135349,0.0942014 --1.23586 , 3.79472 , 2.97209 , 0.519136,0.249207,-0.817554 --1.48584 , 4.29709 , 3.34747 , 0.998697,-0.0472027,-0.0193834 --1.39649 , 4.11885 , 3.3397 , 0.992323,-0.115336,0.0446352 --3.25633 , 7.86024 , 5.78469 , 0.0535848,-0.639571,0.766863 --3.63419 , 8.61972 , 6.4767 , -0.751437,-0.545198,0.37162 --3.5302 , 8.41152 , 6.5548 , -0.751437,-0.545198,0.37162 --3.46078 , 8.271 , 6.67476 , 0.823989,0.565307,-0.0383353 --3.38709 , 8.1212 , 6.78542 , 0.738158,0.376088,-0.560072 --1.34603 , 4.01453 , 3.875 , -0.071915,0.981686,-0.17641 --1.37495 , 4.07231 , 4.02786 , -0.0715911,0.985959,-0.150864 --0.94951 , 3.21703 , 3.4375 , -0.254607,-0.952957,-0.164465 --0.874039 , 3.06491 , 3.3972 , 0.385447,-0.460568,-0.799567 --0.841524 , 2.99976 , 3.42595 , -0.536898,0.496423,0.682133 --0.812384 , 2.94061 , 3.45936 , -0.581908,0.542238,0.606103 --0.787388 , 2.88875 , 3.49761 , 0.625908,-0.319065,-0.711644 --0.764606 , 2.84377 , 3.54102 , 0.480711,-0.452543,-0.75108 --0.738453 , 2.79112 , 3.57686 , -0.250863,0.647378,0.719701 --0.718305 , 2.75095 , 3.62515 , -0.181271,0.56307,0.806284 --0.698321 , 2.70961 , 3.67267 , -0.251812,0.423894,0.870003 --0.680852 , 2.6744 , 3.72644 , -0.0785826,0.774033,0.62825 --0.668742 , 2.65075 , 3.79414 , -0.273019,-0.697267,-0.662781 --0.647836 , 2.60768 , 3.83945 , 0.164867,0.823752,0.54245 --1.15318 , 3.62224 , 5.2139 , -0.696846,0.703176,0.141244 --0.777463 , 2.86814 , 4.38308 , -0.644784,-0.0898665,0.759064 --0.717585 , 2.74673 , 4.34044 , -0.620566,-0.517142,0.589459 --2.13533 , 5.59232 , 8.43175 , -0.275929,0.639643,-0.71744 --0.633463 , 2.57633 , 4.33893 , -0.957249,-0.243263,-0.156515 --0.567601 , 2.44433 , 4.26254 , 0.539804,0.826925,0.157503 --0.602264 , 2.5139 , 4.49073 , -0.0427248,-0.99784,-0.0498975 --0.590144 , 2.49007 , 4.58285 , 0.36328,-0.891165,-0.271758 --0.584666 , 2.47837 , 4.7002 , 0.41089,-0.362473,-0.83653 --0.544913 , 2.397 , 4.69995 , -0.8209,-0.559589,-0.113945 --0.481059 , 2.26852 , 4.61284 , -0.0640168,-0.934227,0.350888 --0.498379 , 2.30376 , 4.82284 , 0.4199,-0.403639,-0.812871 --0.473185 , 2.25341 , 4.87875 , 0.330143,-0.552496,-0.765345 --0.441653 , 2.18851 , 4.90757 , -0.59145,0.545097,0.594185 --0.463195 , 2.23155 , 5.16535 , 0.624068,0.100877,0.774831 --0.487375 , 2.27925 , 5.45261 , 0.497988,-0.691408,0.523414 --0.367913 , 2.03972 , 5.09407 , -0.104536,0.318237,0.94223 --0.294996 , 1.8936 , 4.92765 , -0.672714,-0.715087,0.190016 --0.535674 , 2.3746 , 6.34117 , 0.434259,0.791029,0.43092 --0.272113 , 1.84683 , 5.19062 , 0.491067,-0.271925,0.827593 --0.164278 , 1.63036 , 4.79259 , 0.169225,0.593426,0.786898 --0.135313 , 1.57069 , 4.8182 , -0.325503,-0.596452,-0.733685 --0.105056 , 1.5115 , 4.84256 , 0.81378,0.183731,-0.551367 --0.0788261 , 1.458 , 4.88455 , -0.911807,0.0283078,0.409642 --0.0447547 , 1.38935 , 4.87803 , -0.428738,-0.838117,-0.33726 --0.0396251 , 1.37761 , 5.08089 , 0.693503,-0.418823,0.586209 -0.00163383 , 1.29472 , 5.02446 , -0.384266,0.908909,0.161939 -0.0466007 , 1.2056 , 4.92716 , -0.933624,-0.105242,-0.342449 -0.0819792 , 1.1336 , 4.89589 , 0.897106,0.406488,0.173113 -0.00431548 , 1.2873 , 5.97497 , -0.942446,0.329932,0.0542229 -0.0484513 , 1.1987 , 5.93495 , 0.145853,-0.944868,0.293174 --1.27996 , 4.20422 , -1.3594 , -0.722352,0.632758,-0.278971 --1.2872 , 4.21723 , -1.26985 , 0.704388,-0.682949,0.193438 --1.29269 , 4.2287 , -1.18055 , -0.694548,0.696297,-0.181037 --1.29836 , 4.23907 , -1.09173 , 0.661059,-0.725808,0.190275 --1.30631 , 4.25544 , -1.0071 , -0.641366,0.746079,-0.178928 --1.31372 , 4.26957 , -0.92245 , 0.609969,-0.774229,0.168839 --1.3173 , 4.27509 , -0.834229 , 0.590316,-0.785243,0.186871 --1.32293 , 4.28763 , -0.75011 , 0.556931,-0.812895,0.170379 --1.33284 , 4.30677 , -0.66965 , 0.532888,-0.822922,0.197053 --1.33335 , 4.30721 , -0.582005 , 0.506647,-0.841913,0.185718 --1.34583 , 4.33159 , -0.504669 , -0.483615,0.847987,-0.216875 --1.34864 , 4.33814 , -0.420734 , 0.449278,-0.86625,0.218542 --1.35965 , 4.36017 , -0.34286 , -0.415138,0.879451,-0.232868 --1.36604 , 4.37226 , -0.26178 , 0.364602,-0.907966,0.206552 --1.37144 , 4.38407 , -0.180871 , 0.332947,-0.9244,0.186096 --1.37728 , 4.39391 , -0.0998595 , 0.329186,-0.925856,0.185547 --1.38557 , 4.41026 , -0.020807 , 0.636637,-0.717612,0.282358 --1.39386 , 4.42661 , 0.0582455 , 0.657569,-0.715325,0.23646 --1.40068 , 4.44062 , 0.137934 , 0.636669,-0.740696,0.21453 --1.40749 , 4.45461 , 0.217526 , 0.594857,-0.776413,0.208154 --1.40983 , 4.45742 , 0.299255 , 0.573101,-0.801601,0.170268 --1.41938 , 4.47714 , 0.377863 , -0.479269,0.836717,-0.264964 --1.42421 , 4.48662 , 0.458315 , 0.63477,-0.757519,0.152419 --1.43328 , 4.5043 , 0.537827 , 0.609899,-0.779607,0.142253 --1.43663 , 4.5114 , 0.61872 , -0.535368,0.826263,-0.175128 --1.44853 , 4.53508 , 0.698417 , -0.442632,0.870144,-0.216626 --1.45543 , 4.54934 , 0.779176 , 0.330882,-0.919316,0.213014 --1.46591 , 4.57084 , 0.86019 , 0.291419,-0.933811,0.207537 --1.47161 , 4.58187 , 0.942074 , 0.432642,-0.871882,0.229441 --1.4809 , 4.60022 , 1.02451 , 0.383505,-0.862985,0.328908 --1.48105 , 4.59956 , 1.10729 , 0.478829,-0.826293,0.296585 --1.5599 , 4.75839 , 1.89042 , 0.283592,-0.943018,0.174046 --1.57098 , 4.77941 , 1.98363 , -0.497563,0.833105,-0.241594 --1.58838 , 4.81676 , 2.08213 , -0.497563,0.833105,-0.241594 --1.59736 , 4.83462 , 2.17775 , -0.475058,0.847522,-0.236698 --1.61039 , 4.85944 , 2.27684 , 0.416943,-0.886078,0.202543 --1.62177 , 4.88307 , 2.37715 , -0.375892,0.904126,-0.20313 --1.63175 , 4.90453 , 2.47887 , 0.321261,-0.924499,0.205165 --1.64226 , 4.92427 , 2.58176 , -0.307344,0.929862,-0.20223 --1.65134 , 4.94181 , 2.68587 , 0.280595,-0.942704,0.180485 --1.66355 , 4.96628 , 2.79435 , 0.24111,-0.951156,0.192792 --1.21463 , 3.99857 , 2.51082 , -0.658843,0.659153,-0.362551 --1.21621 , 4.00013 , 2.59248 , -0.749863,0.611641,-0.252192 --1.69756 , 5.03531 , 3.13219 , -0.972727,-0.106095,0.206269 --1.26299 , 4.09865 , 2.80388 , 0.430243,-0.780264,0.45396 --1.27361 , 4.11934 , 2.9011 , -0.886812,0.0745577,-0.456076 --1.45904 , 4.5169 , 3.19282 , 0.347799,0.0482644,-0.936326 --1.34481 , 4.2696 , 3.16046 , -0.866481,-0.316954,0.385682 --1.13405 , 3.81455 , 3.00192 , -0.368757,-0.257788,0.893064 --1.32491 , 4.22436 , 3.32593 , 0.590616,-0.0775057,0.803222 --1.27561 , 4.11577 , 3.35783 , 0.594158,0.0740252,0.800935 --2.65361 , 7.07356 , 5.32649 , -0.0770321,-0.469202,0.879725 --3.3049 , 8.46746 , 6.41988 , -0.751437,-0.545198,0.37162 --3.00353 , 7.81886 , 6.19133 , -0.794567,-0.317291,0.517677 --1.23725 , 4.02695 , 3.69498 , 0.0552549,-0.998471,-0.00157554 --1.23528 , 4.02182 , 3.79424 , 0.122036,-0.989709,0.07472 --2.92698 , 7.64406 , 6.68149 , 0.772904,0.435131,-0.461824 --2.85844 , 7.49415 , 6.77534 , -0.494262,-0.513537,0.701416 --2.96 , 7.70624 , 7.16485 , -0.627901,-0.433686,0.646264 --0.771599 , 3.0213 , 3.37521 , -0.543642,0.41337,0.730464 --0.764494 , 3.00483 , 3.44617 , 0.61837,-0.453269,-0.642001 --0.763423 , 3.00092 , 3.52998 , -0.657233,0.427775,0.620527 --0.738899 , 2.94716 , 3.56862 , -0.65223,0.257697,0.712874 --0.703936 , 2.87275 , 3.58607 , 0.713783,-0.108156,-0.691966 --0.680163 , 2.81854 , 3.62167 , -0.62066,0.240833,0.746177 --0.651786 , 2.75732 , 3.64923 , -0.407694,0.513204,0.755253 --0.629186 , 2.70955 , 3.68914 , -0.223549,0.692546,0.685862 --0.610298 , 2.66715 , 3.73528 , -0.0765331,0.559068,0.825582 --0.58801 , 2.61699 , 3.77345 , -0.0569979,-0.670829,-0.739419 --0.573433 , 2.58571 , 3.83259 , -0.00536829,0.777901,0.628364 --0.567324 , 2.57059 , 3.91396 , -0.0933345,0.933376,0.346551 --0.612888 , 2.66465 , 4.14074 , -0.385465,-0.848067,0.363592 --0.649749 , 2.74061 , 4.35654 , -0.853379,-0.511854,-0.0987437 --0.614611 , 2.66567 , 4.37166 , -0.0932563,-0.209897,0.973266 --0.556731 , 2.54048 , 4.31348 , 0.114974,-0.531195,0.839412 --0.535164 , 2.49417 , 4.3643 , 0.0795138,0.982311,-0.16954 --0.543344 , 2.50803 , 4.51258 , 0.199248,-0.97316,0.11515 --0.559168 , 2.53934 , 4.69532 , 0.446796,-0.664463,-0.599051 --0.539091 , 2.49589 , 4.76316 , -0.722378,0.348431,0.597299 --0.457867 , 2.32044 , 4.60202 , -0.433553,-0.66331,0.60996 --0.444513 , 2.29164 , 4.69196 , 0.270769,0.953604,-0.131616 --0.448626 , 2.29723 , 4.85084 , -0.204104,0.494022,0.845153 --0.418343 , 2.23173 , 4.88033 , -0.0582757,0.680319,0.730596 --0.411289 , 2.21281 , 5.00529 , 0.541598,-0.761208,-0.3567 --0.612404 , 2.63215 , 6.0826 , -0.343087,-0.911895,-0.225255 --0.360622 , 2.10171 , 5.11289 , -0.0404006,0.383143,0.922805 --0.314784 , 2.00279 , 5.06567 , 0.155522,0.527292,0.83533 --0.279662 , 1.92685 , 5.07084 , 0.125136,0.366729,0.921873 --0.273907 , 1.91231 , 5.23058 , 0.305214,0.287325,0.907903 --0.158151 , 1.66923 , 4.77955 , -0.636346,-0.0276947,-0.770906 --0.131404 , 1.60917 , 4.80569 , 0.098482,0.547968,0.830682 --0.107952 , 1.55865 , 4.85873 , -0.278954,-0.606997,-0.744137 --0.0815126 , 1.50119 , 4.89197 , 0.775246,0.457177,0.43587 --0.0499019 , 1.43123 , 4.88628 , -0.00812747,0.0525044,0.998588 --0.0278749 , 1.38336 , 4.95547 , -0.597047,0.232336,0.767825 --0.0741989 , 1.47332 , 5.5619 , 0.99556,0.0315522,-0.0886789 -0.0466663 , 1.22333 , 4.85059 , -0.680375,0.241336,-0.691988 -0.067033 , 1.17717 , 4.93613 , 0.712366,0.587771,-0.383483 -0.114285 , 1.0769 , 4.76751 , 0.396009,-0.679062,0.618103 -0.0314302 , 1.23784 , 5.92597 , -0.817182,-0.387567,-0.42662 --1.88113 , 5.9922 , -2.06096 , -0.0365805,0.249293,0.967737 --2.09133 , 6.49012 , -2.1865 , -0.0419988,0.234561,0.971194 --2.36434 , 7.13555 , -2.36504 , -0.0631973,0.235889,0.969723 --2.69015 , 7.90611 , -2.57599 , 0.0689789,-0.238733,-0.968632 --3.05478 , 8.77034 , -2.7971 , -0.0644261,0.211001,0.975361 --3.46053 , 9.72984 , -3.02357 , -0.0794317,0.206446,0.975229 --4.03404 , 11.0868 , -3.37348 , -0.0902852,0.210032,0.973517 --4.84004 , 12.9951 , -3.88137 , -0.0846834,0.217109,0.972467 --5.7653 , 15.1843 , -4.41409 , -0.0781577,0.151509,0.985361 --6.55603 , 17.0506 , -4.74678 , -0.0231525,-0.241849,0.970038 --6.81407 , 17.6515 , -4.5948 , -0.0231525,-0.241849,0.970038 --7.08818 , 18.288 , -4.43272 , -0.0166928,-0.266091,0.963803 --7.35728 , 18.9148 , -4.24526 , -0.0176056,-0.266945,0.963551 --9.73202 , 24.5072 , -4.86185 , 0.123089,-0.312343,0.941961 --1.32847 , 4.62491 , 0.0690045 , -0.934523,0.333307,-0.12479 --1.33152 , 4.63049 , 0.15304 , -0.935454,0.339691,-0.0976481 --1.33477 , 4.63502 , 0.236883 , -0.928455,0.360001,-0.0914912 --1.3445 , 4.65529 , 0.317923 , -0.922394,0.373275,-0.0992716 --1.34247 , 4.64728 , 0.403347 , -0.913963,0.393912,-0.0974942 --1.35146 , 4.66636 , 0.484608 , -0.905223,0.414617,-0.0930855 --1.35594 , 4.67415 , 0.567521 , -0.890685,0.446081,-0.0877007 --1.35586 , 4.67055 , 0.651598 , -0.856176,0.511518,-0.0728789 --1.35981 , 4.67612 , 0.73454 , -0.832013,0.548452,-0.0833955 --1.3539 , 4.66162 , 0.818635 , -0.79764,0.572819,-0.188808 --1.36876 , 4.69173 , 0.900462 , 0.804135,-0.559743,0.200136 --1.38919 , 4.73919 , 0.9833 , -0.591962,0.777088,-0.213809 --1.39476 , 4.74757 , 1.06775 , 0.46135,-0.814493,0.351791 --1.45088 , 4.8517 , 1.94366 , -0.497563,0.833105,-0.241594 --1.46455 , 4.88135 , 2.03987 , -0.497563,0.833105,-0.241594 --1.47427 , 4.90037 , 2.13517 , -0.475058,0.847522,-0.236698 --1.47905 , 4.90848 , 2.2294 , 0.457057,-0.862364,0.217778 --1.48688 , 4.92329 , 2.32692 , 0.396573,-0.894885,0.204721 --1.49401 , 4.93702 , 2.42515 , 0.349169,-0.912248,0.214208 --1.50424 , 4.95758 , 2.52727 , 0.321261,-0.924499,0.205165 --1.51378 , 4.9771 , 2.63028 , -0.307344,0.929862,-0.20223 --1.52214 , 4.99352 , 2.73491 , 0.280595,-0.942704,0.180485 --1.13011 , 4.08174 , 2.4859 , -0.591345,0.73104,-0.340429 --1.53366 , 5.01235 , 2.9437 , -0.543047,0.815185,-0.201428 --1.11795 , 4.04896 , 2.63626 , -0.796884,0.208657,-0.566955 --1.55969 , 5.06675 , 3.17493 , -0.972727,-0.106095,0.206269 --1.56748 , 5.08186 , 3.28915 , 0.975884,0.123754,-0.179818 --1.4295 , 4.75997 , 3.23973 , 0.123559,0.29625,0.947085 --0.930222 , 3.60386 , 2.74645 , -0.198721,0.803559,0.561073 --1.32932 , 4.5215 , 3.31935 , -0.169969,-0.0959148,-0.980771 --0.882573 , 3.48935 , 2.83908 , 0.81403,0.567951,0.1216 --0.933937 , 3.60487 , 2.98504 , 0.562386,0.573963,-0.595221 --1.64759 , 5.24406 , 4.07184 , 0.810379,-0.563985,0.158765 --1.66214 , 5.27335 , 4.21596 , 0.718551,-0.673573,0.173158 --0.795915 , 3.27946 , 3.02009 , -0.746236,0.0208443,0.665355 --0.751678 , 3.17673 , 3.0286 , 0.536036,0.224462,0.813807 --1.09679 , 3.96304 , 3.67125 , -0.285498,-0.944353,0.163368 --1.15439 , 4.09429 , 3.87044 , 0.122036,-0.989709,0.0747201 --1.73671 , 5.42326 , 5.00677 , 0.430901,-0.885322,0.174726 --1.7559 , 5.46115 , 5.18684 , 0.4309,-0.885322,0.174726 --1.15488 , 4.08242 , 4.19266 , 0.148568,-0.988706,0.0197009 --1.79404 , 5.54 , 5.56707 , -0.151765,0.970294,-0.188409 --1.82256 , 5.60001 , 5.78688 , -0.553396,-0.772473,0.311509 --1.84599 , 5.64865 , 6.00357 , -0.509888,-0.726073,0.461337 --1.14313 , 4.04162 , 4.63837 , 0.485123,-0.482955,-0.728979 --1.1305 , 4.00941 , 4.73632 , 0.485123,-0.482955,-0.728979 --0.639632 , 2.89096 , 3.71524 , 0.698714,0.0245259,-0.71498 --0.593213 , 2.78161 , 3.69446 , -0.61067,0.0273808,0.791411 --0.566865 , 2.71943 , 3.72003 , 0.605187,-0.191169,-0.772789 --0.543002 , 2.66328 , 3.75145 , -0.333992,0.403744,0.851728 --0.517406 , 2.60065 , 3.77397 , -0.0705705,0.673576,0.735742 --0.50682 , 2.57391 , 3.84011 , -0.0908519,0.797583,0.596328 --0.490745 , 2.5352 , 3.89055 , -0.294293,-0.768536,-0.568106 --0.479575 , 2.50608 , 3.95604 , -0.326768,-0.787502,-0.522555 --0.497296 , 2.54347 , 4.11515 , 0.593132,0.804952,0.0157106 --0.566433 , 2.69469 , 4.4425 , 0.911426,0.408445,-0.049762 --0.494503 , 2.53108 , 4.32733 , -0.438876,-0.85804,0.26675 --0.517729 , 2.57865 , 4.52393 , 0.753179,-0.500077,-0.427369 --0.891704 , 3.40918 , 5.97368 , -0.713906,-0.584902,-0.385005 --0.591512 , 2.73237 , 5.05029 , 0.356948,-0.611758,0.705932 --0.491335 , 2.50497 , 4.81842 , -0.650315,0.16531,0.74146 --0.420358 , 2.34335 , 4.68136 , 0.394885,0.746771,-0.535163 --0.394989 , 2.28414 , 4.72006 , -0.665179,0.0278161,0.746166 --0.381312 , 2.24709 , 4.80099 , -0.281747,-0.921339,-0.267867 --0.373569 , 2.22608 , 4.9167 , -0.0457135,0.929694,0.365485 --0.439139 , 2.3664 , 5.37814 , 0.490082,-0.744759,0.452939 --0.340542 , 2.14489 , 5.08665 , 0.025054,0.444297,0.895529 --0.298601 , 2.04795 , 5.04938 , 0.379927,0.414475,0.826962 --0.28042 , 2.00191 , 5.12784 , 0.0146604,0.504498,0.863288 --0.252735 , 1.93551 , 5.16 , 0.406962,0.528664,0.744913 --0.168436 , 1.74684 , 4.86784 , 0.471148,0.739666,-0.480536 --0.122397 , 1.64141 , 4.77431 , 0.098482,0.547968,0.830682 --0.101156 , 1.59049 , 4.82779 , 0.129152,0.521679,0.84331 --0.0754759 , 1.52927 , 4.85216 , 0.254674,0.528394,0.809902 --0.107283 , 1.58977 , 5.27308 , -0.890751,-0.423979,-0.16372 --0.0185202 , 1.39472 , 4.85924 , 0.718446,0.598732,-0.354055 --0.0666024 , 1.48911 , 5.45457 , 0.992196,0.091205,0.0850248 -0.0242755 , 1.2907 , 4.97638 , -0.0503315,-0.801428,0.59597 -0.0663509 , 1.19612 , 4.85944 , -0.52759,-0.827829,-0.19065 -0.0973959 , 1.12303 , 4.82789 , 0.904341,-0.421635,-0.0662783 -0.00935784 , 1.29229 , 5.98481 , -0.961638,0.188843,0.198973 -0.0556667 , 1.18894 , 5.87623 , 0.6021,-0.778879,0.175567 --1.80474 , 6.33379 , -2.13159 , -0.0419988,0.234561,0.971194 --2.0205 , 6.89077 , -2.27294 , -0.0505728,0.226946,0.972593 --2.28226 , 7.56572 , -2.44775 , -0.0619379,0.242052,0.968284 --2.63863 , 8.48708 , -2.70788 , -0.0755739,0.228835,0.970527 --3.02715 , 9.48854 , -2.96475 , -0.0673804,0.207527,0.975906 --3.48585 , 10.6745 , -3.2572 , -0.0658311,0.211647,0.975127 --4.02536 , 12.064 , -3.58191 , -0.0951743,0.199639,0.975236 --4.84596 , 14.1817 , -4.12132 , 0.104204,-0.198027,-0.974642 --5.83006 , 16.718 , -4.72254 , -0.124139,-0.020374,0.992056 --6.11554 , 17.4399 , -4.62354 , -0.0231525,-0.241849,0.970038 --6.36069 , 18.0556 , -4.46583 , -0.0158082,-0.263694,0.964477 --6.60537 , 18.6715 , -4.28673 , -0.0157167,-0.267034,0.963559 --6.87878 , 19.3591 , -4.10559 , -0.0157167,-0.267034,0.963559 --8.77157 , 24.2226 , -4.94464 , 0.0772876,-0.182107,0.980237 --9.14478 , 25.161 , -4.69142 , 0.123089,-0.312343,0.941961 --9.55057 , 26.1803 , -4.42197 , -0.205602,0.280181,-0.937671 --9.94849 , 27.1786 , -4.11226 , -0.29688,0.239284,-0.924449 --11.4957 , 31.1286 , -4.27583 , -0.487974,0.0386746,-0.872001 --5.60219 , 15.9679 , -1.36295 , 0.649018,-0.758958,0.0525189 --11.654 , 31.4448 , -2.55006 , 0.538071,-0.256521,0.802918 --5.72348 , 16.2333 , -0.496462 , 0.649018,-0.758958,0.0525189 --5.69323 , 16.1425 , -0.188965 , -0.967728,0.246456,-0.0525575 --5.58969 , 15.8605 , 0.125538 , -0.991062,0.0481248,0.124419 --5.40947 , 15.3874 , 0.436577 , -0.0734971,0.509488,0.857333 --5.14009 , 14.6856 , 0.734371 , -0.073498,0.509487,0.857334 --2.93079 , 8.94548 , 2.99464 , 0.630405,0.16627,-0.75825 --2.79887 , 8.60281 , 3.08103 , 0.688168,-0.0160846,-0.725373 --2.74445 , 8.45907 , 3.20801 , 0.688168,-0.0160844,-0.725373 --2.66087 , 8.24189 , 3.30964 , 0.688168,-0.0160845,-0.725373 --2.69558 , 8.31921 , 3.49404 , 0.688168,-0.0160845,-0.725373 --2.15283 , 6.95233 , 3.21205 , 0.707843,-0.694373,-0.129635 --2.12004 , 6.8622 , 3.31832 , 0.687869,-0.717242,-0.11136 --2.13474 , 6.89358 , 3.4673 , 0.589967,-0.807351,-0.0111356 --4.12374 , 11.8558 , 5.53834 , -0.0736607,-0.873494,0.481229 --1.06058 , 4.19869 , 2.64136 , 0.453693,-0.759821,0.465655 --1.4802 , 5.23966 , 3.17634 , -0.972727,-0.106095,0.206269 --1.49463 , 5.27206 , 3.30013 , -0.972727,-0.106095,0.206269 --0.874997 , 3.72315 , 2.67316 , 0.977556,-0.20406,0.0523892 --0.858681 , 3.67916 , 2.72882 , 0.876636,-0.449322,-0.1721 --0.794834 , 3.51699 , 2.7225 , -0.686073,-0.531275,-0.497042 --1.0851 , 4.23332 , 3.18955 , -0.34521,0.417244,-0.840677 --0.933447 , 3.85294 , 3.06699 , 0.213545,0.122935,-0.969167 --0.777265 , 3.46138 , 2.92129 , -0.82096,-0.364404,0.439584 --0.723065 , 3.32596 , 2.91582 , -0.746236,0.0208443,0.665355 --0.728481 , 3.33388 , 2.99823 , -0.746236,0.0208442,0.665355 --0.678532 , 3.20667 , 2.99182 , -0.746236,0.0208442,0.665355 --1.58977 , 5.44658 , 4.631 , -0.543293,0.816836,-0.193938 --1.59975 , 5.46378 , 4.78312 , -0.543293,0.816836,-0.193937 --1.61083 , 5.48495 , 4.9429 , 0.4309,-0.885322,0.174726 --1.624 , 5.51032 , 5.11032 , 0.4309,-0.885322,0.174726 --1.63951 , 5.53901 , 5.28585 , 0.37632,-0.904909,0.198805 --1.65544 , 5.57065 , 5.47004 , 0.208083,-0.959034,0.192238 --1.66721 , 5.59098 , 5.65032 , -0.301544,-0.941178,0.152495 --1.68521 , 5.62785 , 5.85219 , -0.509889,-0.726073,0.461337 --1.07814 , 4.14289 , 4.63679 , 0.485122,-0.482955,-0.728979 --1.04787 , 4.06211 , 4.68884 , 0.485123,-0.482955,-0.728979 --1.01136 , 3.96814 , 4.72532 , 0.485123,-0.482955,-0.728979 --0.980563 , 3.88741 , 4.77319 , 0.485123,-0.482955,-0.728979 --0.542844 , 2.82293 , 3.76135 , 0.648622,0.140145,-0.748097 --0.512755 , 2.74636 , 3.77266 , -0.630144,0.0197266,0.776228 --0.486092 , 2.67594 , 3.78932 , -0.653505,0.0559506,0.754851 --0.455507 , 2.59953 , 3.79693 , -0.476448,0.322794,0.817803 --0.439011 , 2.55393 , 3.84001 , -0.206848,0.51813,0.829913 --0.418629 , 2.50244 , 3.87454 , -0.00699405,0.633702,0.773546 --0.401247 , 2.45522 , 3.9159 , 0.247049,0.713178,0.656007 --0.398532 , 2.44222 , 4.00343 , -0.374768,-0.753317,-0.540429 --0.389579 , 2.41604 , 4.07538 , -0.485865,-0.801645,-0.348282 --0.437017 , 2.5235 , 4.34936 , -0.260224,-0.95274,0.156748 --0.490508 , 2.64342 , 4.66099 , 0.754659,-0.637892,-0.153567 --0.456947 , 2.55888 , 4.66337 , 0.711916,-0.616622,-0.336084 --0.522007 , 2.70542 , 5.04901 , 0.235505,-0.630287,0.739781 --0.427743 , 2.47794 , 4.81477 , -0.129107,0.340519,0.931332 --0.394825 , 2.39263 , 4.81265 , 0.421275,-0.462332,0.780241 --0.349046 , 2.27933 , 4.75684 , 0.602312,0.321911,-0.730475 --0.323794 , 2.2138 , 4.78524 , 0.0571623,0.97381,0.220058 --0.353031 , 2.27338 , 5.068 , -0.490954,-0.72644,-0.480883 --0.308385 , 2.16141 , 5.00709 , -0.443903,-0.533996,-0.719582 --0.27925 , 2.08833 , 5.02402 , -0.430269,-0.298407,-0.851952 --0.261836 , 2.03857 , 5.0937 , 0.13005,0.722733,0.678781 --0.234689 , 1.96941 , 5.117 , 0.125136,0.366729,0.921874 --0.206701 , 1.89876 , 5.13915 , -0.236842,-0.561741,-0.792687 --0.13947 , 1.73871 , 4.91902 , -0.0469849,-0.0219364,0.998655 --0.0921712 , 1.6228 , 4.79669 , -0.497637,0.282959,0.819934 --0.0873206 , 1.60161 , 4.94359 , -0.882837,0.428715,0.191837 --0.0487706 , 1.50817 , 4.87351 , 0.408215,0.418096,0.811515 --0.0386667 , 1.47634 , 5.00069 , 0.0869862,-0.0585903,0.994485 -0.00248906 , 1.37666 , 4.8986 , 0.781127,-0.297378,-0.549005 -0.0171189 , 1.33427 , 4.9955 , 0.466308,-0.446566,-0.763634 -0.0536137 , 1.24617 , 4.91831 , -0.941202,0.119745,0.31591 -0.0838991 , 1.16932 , 4.87789 , -0.794835,-0.587806,-0.150738 -0.112332 , 1.09871 , 4.85515 , -0.870292,0.469523,-0.148794 -0.0369602 , 1.23863 , 5.91613 , 0.898146,0.359072,0.253772 --1.55441 , 6.24536 , -2.11188 , -0.0419988,0.234562,0.971194 --1.74077 , 6.7729 , -2.24347 , -0.0505728,0.226946,0.972593 --1.94766 , 7.35782 , -2.38142 , -0.0615508,0.244479,0.967699 --2.2982 , 8.3546 , -2.68642 , -0.0714522,0.230584,0.970426 --2.57489 , 9.13737 , -2.85575 , -0.0626136,0.208895,0.975932 --2.91403 , 10.094 , -3.06706 , -0.0632468,0.214393,0.974698 --3.4109 , 11.5018 , -3.41976 , -0.0781722,0.213616,0.973785 --4.02895 , 13.2524 , -3.84554 , -0.0983975,0.205538,0.97369 --4.82389 , 15.5025 , -4.37973 , -0.103881,0.126555,0.986505 --5.46045 , 17.2959 , -4.67173 , -0.0231525,-0.241849,0.970038 --5.67213 , 17.8735 , -4.51093 , -0.0212692,-0.245378,0.969194 --5.8996 , 18.4953 , -4.3435 , -0.0147368,-0.267797,0.963363 --6.14768 , 19.1719 , -4.16992 , -0.0157167,-0.267034,0.963559 --8.21415 , 24.9668 , -4.80436 , 0.123089,-0.312343,0.941961 --5.13243 , 16.134 , -1.20143 , 0.649018,-0.758958,0.0525189 --5.2343 , 16.4002 , -0.936512 , 0.649018,-0.758958,0.0525189 --5.24799 , 16.4185 , -0.636883 , 0.649018,-0.758958,0.0525189 --5.26367 , 16.4412 , -0.338016 , 0.649018,-0.758958,0.0525189 --5.27449 , 16.4494 , -0.0380489 , -0.967728,0.246456,-0.0525575 --5.21673 , 16.2648 , 0.270879 , -0.967728,0.246456,-0.0525575 --4.63613 , 14.6254 , 0.615704 , 0.192556,-0.382777,-0.903551 --3.05354 , 10.0286 , 3.31751 , 0.569339,0.301824,-0.764693 --2.55243 , 8.64476 , 3.15725 , 0.688168,-0.0160846,-0.725373 --1.96739 , 7.00004 , 3.41543 , -0.588306,0.799798,0.119246 --1.97549 , 7.01198 , 3.55963 , -0.588306,0.799798,0.119246 --3.6782 , 11.6102 , 5.52494 , -0.100818,-0.795321,0.597746 --3.69809 , 11.6464 , 5.78212 , -0.186427,-0.917616,0.351035 --0.778499 , 3.75436 , 2.55889 , 0.929776,0.235334,-0.283081 --0.767816 , 3.72004 , 2.61904 , 0.977556,-0.20406,0.0523892 --3.10789 , 10.0095 , 5.7396 , -0.779931,-0.39389,-0.486373 --1.07901 , 4.54541 , 3.19157 , -0.150713,-0.129713,-0.980031 --1.07469 , 4.52572 , 3.27919 , -0.150713,-0.129713,-0.980031 --0.869573 , 3.97169 , 3.07237 , -0.177894,-0.4673,0.866016 --0.822158 , 3.83823 , 3.08343 , -0.464087,-0.264122,0.845496 --2.01953 , 7.02567 , 5.0882 , 0.0407868,-0.979976,0.194893 --0.688715 , 3.46871 , 3.02696 , -0.943221,0.167708,0.286718 --0.701722 , 3.49908 , 3.12747 , -0.962698,0.220161,0.157299 --0.803678 , 3.76387 , 3.39054 , 0.844565,0.369634,0.387402 --0.779273 , 3.69302 , 3.43283 , 0.684578,0.115746,0.719691 --0.696526 , 3.46725 , 3.36026 , -0.0123196,-0.950435,0.310679 --2.56647 , 8.39904 , 7.19548 , 0.513999,0.257681,-0.818172 --2.76498 , 8.90484 , 7.82627 , -0.88146,-0.47212,-0.0114449 --2.389 , 7.89915 , 7.25725 , -0.500871,0.00572783,0.865503 --2.76486 , 8.87088 , 8.3113 , 0.794167,0.506307,0.336083 --1.68079 , 6.01343 , 6.06475 , 0.137551,-0.339473,0.930504 --1.54356 , 5.64397 , 5.91173 , -0.509888,-0.726073,0.461337 --0.958305 , 4.10555 , 4.63544 , 0.485123,-0.482955,-0.728979 --2.32995 , 7.66491 , 8.24561 , -0.364647,0.786941,0.497752 --0.913274 , 3.97032 , 4.76184 , 0.485122,-0.482955,-0.728979 --0.913193 , 3.96136 , 4.88598 , 0.760037,-0.5648,-0.321472 --0.929489 , 3.99533 , 5.06068 , 0.777167,-0.520546,-0.353614 --0.460743 , 2.77753 , 3.83312 , 0.66818,0.119041,-0.734415 --0.432904 , 2.699 , 3.84245 , 0.598628,-0.0275196,-0.800554 --0.407294 , 2.62739 , 3.85714 , -0.563381,0.00121581,0.826196 --0.379685 , 2.55016 , 3.86235 , -0.56894,0.200293,0.797615 --0.361669 , 2.49707 , 3.89644 , -0.184542,0.613553,0.767787 --0.345221 , 2.44995 , 3.93719 , -0.189491,0.55412,0.810583 --0.327274 , 2.3954 , 3.96925 , 0.104781,0.622784,0.775346 --0.314704 , 2.35748 , 4.02439 , 0.466467,0.694008,0.548417 --0.312546 , 2.34617 , 4.11941 , 0.54059,0.756764,0.367519 --0.360207 , 2.4587 , 4.41248 , 0.460476,0.871072,0.170867 --0.426129 , 2.61302 , 4.79405 , 0.617374,-0.457376,-0.640044 --0.44506 , 2.65102 , 5.00536 , 0.238747,-0.728303,0.64232 --0.378969 , 2.47772 , 4.86183 , -0.268537,-0.463725,0.844303 --0.33593 , 2.36228 , 4.80765 , 0.0363068,-0.152714,0.987603 --0.29611 , 2.25404 , 4.75899 , 0.0571624,0.97381,0.220058 --0.291481 , 2.23264 , 4.87416 , 0.144925,0.98205,0.120722 --0.268982 , 2.16835 , 4.91029 , -0.0089708,0.698351,0.7157 --0.265901 , 2.14997 , 5.04326 , -0.142159,0.134073,-0.980722 --0.232869 , 2.05992 , 5.02351 , 0.277222,0.497725,0.821838 --0.215401 , 2.00499 , 5.08357 , 0.511222,0.60034,0.615016 --0.184078 , 1.91967 , 5.0694 , 0.137887,0.451597,0.881503 --0.164009 , 1.86064 , 5.11784 , -0.0768806,0.525956,0.84703 --0.081944 , 1.65679 , 4.77518 , -0.497637,0.282959,0.819934 --0.0619064 , 1.59907 , 4.80965 , -0.745249,0.339176,0.574077 --0.0603927 , 1.58255 , 4.97508 , 0.923989,-0.133651,-0.358303 --0.0888156 , 1.63429 , 5.37809 , -0.827551,-0.382244,0.411156 --0.00340595 , 1.42685 , 4.93596 , 0.66212,0.659402,-0.35607 --0.0306682 , 1.47202 , 5.35935 , 0.887132,0.452084,-0.0928341 -0.0360439 , 1.31042 , 5.02471 , 0.0541576,0.815136,0.576732 -0.082981 , 1.19443 , 4.83063 , -0.417494,-0.274682,-0.866169 -0.108236 , 1.12467 , 4.81835 , 0.782759,-0.472802,0.404655 -0.0238127 , 1.28192 , 5.91658 , -0.520349,0.330718,-0.787314 -0.0563913 , 1.19385 , 5.89573 , 0.6021,-0.778879,0.175567 --2.69857 , 9.76748 , 4.27644 , 0.220938,-0.373199,0.90106 --1.80901 , 7.12165 , 3.51211 , -0.588306,0.799798,0.119246 --1.81407 , 7.12301 , 3.65451 , -0.559083,0.817816,0.136393 --3.29699 , 11.4718 , 5.55643 , -0.100818,-0.795321,0.597746 --3.28343 , 11.4106 , 5.76913 , -0.100818,-0.795321,0.597746 --3.59602 , 12.305 , 6.40972 , 0.711222,0.527629,-0.464512 --1.63206 , 6.53869 , 3.9683 , -0.142988,0.463763,0.874344 --1.63694 , 6.53951 , 4.10826 , -0.0303116,0.463195,0.885738 --3.49242 , 11.9304 , 7.02237 , -0.852336,-0.407483,0.327842 --0.747212 , 3.92869 , 2.99098 , -0.251982,-0.0641649,0.965602 --0.723993 , 3.85311 , 3.03435 , -0.303364,-0.0845424,0.949117 --0.686102 , 3.73584 , 3.05132 , 0.612533,-0.0823253,-0.786146 --0.670926 , 3.6853 , 3.10447 , 0.75609,0.102692,-0.646361 --0.602411 , 3.48016 , 3.05866 , -0.932642,-0.00738301,0.360728 --0.631821 , 3.55702 , 3.19145 , 0.730816,-0.666787,-0.145956 --0.630743 , 3.54416 , 3.26751 , -0.59657,0.792466,0.126891 --0.627956 , 3.52989 , 3.34392 , -0.59657,0.792466,0.126891 --0.627655 , 3.52165 , 3.42619 , 0.41837,-0.134677,0.898237 --2.57546 , 9.05733 , 7.76956 , 0.686937,0.22487,0.69105 --2.24786 , 8.10612 , 7.26347 , -0.721408,-0.046121,0.690973 --1.68779 , 6.49839 , 6.16512 , 0.576206,-0.37042,0.728544 --1.91734 , 7.12911 , 6.895 , -0.454861,-0.820703,0.345757 --2.19927 , 7.9042 , 7.79724 , -0.884411,0.0613628,-0.462658 --2.12771 , 7.6828 , 7.8388 , -0.879858,-0.396057,-0.26266 --1.32837 , 5.4241 , 5.92962 , 0.379791,0.917878,-0.115149 --2.09018 , 7.53295 , 8.18977 , -0.0397175,0.981075,0.189509 --0.846524 , 4.05009 , 4.88171 , 0.777167,-0.520546,-0.353614 --0.853743 , 4.05815 , 5.02849 , -0.777167,0.520546,0.353614 --0.578137 , 3.28519 , 4.32152 , 0.432648,-0.307611,-0.847462 --0.589251 , 3.306 , 4.46432 , 0.602524,0.781655,-0.161184 --0.379212 , 2.71992 , 3.896 , 0.664817,0.140784,-0.73362 --0.351741 , 2.63417 , 3.89541 , -0.639387,-0.0469054,0.767453 --0.330754 , 2.56796 , 3.91542 , -0.611988,0.00451054,0.790855 --0.307775 , 2.49616 , 3.92605 , 0.560901,-0.187085,-0.806467 --0.286328 , 2.43022 , 3.94285 , -0.266745,0.437687,0.858648 --0.271197 , 2.38104 , 3.98222 , -0.176012,0.474563,0.862444 --0.256956 , 2.33183 , 4.0204 , -0.0357263,0.550866,0.833829 --0.243813 , 2.28656 , 4.06614 , 0.50741,0.749305,0.425532 --0.2461 , 2.28284 , 4.17721 , -0.574333,-0.763234,-0.296 --0.293522 , 2.39842 , 4.49037 , 0.274083,0.771314,0.574416 --0.371654 , 2.59419 , 4.96096 , -0.343458,-0.711956,0.612499 --0.313166 , 2.42716 , 4.82337 , 0.128762,0.166596,-0.977582 --0.271976 , 2.30688 , 4.75883 , 0.051808,-0.179071,0.982471 --0.26836 , 2.28582 , 4.87446 , 0.860062,-0.0599705,-0.506652 --0.25578 , 2.23876 , 4.94636 , -0.208722,0.854417,0.475823 --0.241425 , 2.1901 , 5.01773 , -0.343439,0.608218,0.715626 --0.210854 , 2.09873 , 4.9988 , -0.0982313,-0.154284,0.983131 --0.19174 , 2.03654 , 5.041 , 0.359018,0.653672,0.666198 --0.175427 , 1.98072 , 5.10046 , 0.136784,0.678422,0.721827 --0.151298 , 1.90587 , 5.11299 , 0.494238,0.0537752,-0.867662 --0.107243 , 1.78208 , 4.99437 , -0.623566,-0.596328,0.505528 --0.0647645 , 1.66322 , 4.87235 , -0.817062,0.512362,0.264376 --0.056521 , 1.6272 , 4.98214 , 0.799374,-0.129129,-0.586794 --0.096593 , 1.7058 , 5.46024 , -0.844824,-0.289169,0.45017 --0.0330032 , 1.5379 , 5.17253 , -0.914453,-0.391869,0.101063 -0.0183452 , 1.40154 , 4.95645 , 0.559506,-0.423468,-0.71248 -0.0395318 , 1.33639 , 4.97675 , -0.310541,0.155367,0.937777 -0.0675734 , 1.25424 , 4.92832 , -0.149647,-0.230263,0.961553 -0.100049 , 1.1647 , 4.83944 , -0.935111,-0.346416,-0.0745848 -0.128969 , 1.08277 , 4.76779 , 0.396009,-0.679062,0.618103 -0.040569 , 1.24191 , 5.92615 , 0.882261,0.306735,0.357111 --0.209545 , 2.64032 , 1.58149 , 0.850358,-0.428153,0.305903 --0.211194 , 2.63954 , 1.62646 , 0.850358,-0.428153,0.305903 --0.215409 , 2.64732 , 1.67414 , 0.850358,-0.428153,0.305903 --0.210688 , 2.62614 , 1.71443 , 0.850358,-0.428153,0.305903 --2.21214 , 9.14112 , 3.7784 , -0.413842,0.524596,-0.743999 --2.18695 , 9.03735 , 3.9213 , -0.413842,0.524596,-0.743999 --2.57472 , 10.273 , 4.53085 , -0.940746,-0.338509,-0.0202171 --1.63841 , 7.22147 , 3.60445 , 0.513329,-0.849161,-0.124172 --1.63538 , 7.19368 , 3.73759 , -0.513329,0.849161,0.124172 --2.91257 , 11.2869 , 5.57039 , 0.298603,0.0588384,0.952562 --3.03384 , 11.6482 , 5.96172 , -0.32212,-0.935882,0.142704 --3.49682 , 13.1031 , 6.86984 , -0.777171,-0.510878,0.367436 --1.44423 , 6.51369 , 4.00634 , 0.169446,0.980234,-0.102123 --1.44659 , 6.5044 , 4.14117 , 0.169446,0.980234,-0.102123 --3.47988 , 12.9472 , 7.64845 , -0.946744,-0.313838,0.0719752 --2.98986 , 11.3607 , 7.0755 , 0.621537,0.747391,-0.234731 --3.76924 , 13.7944 , 8.72227 , -0.782544,-0.584799,0.213621 --0.640093 , 3.89608 , 3.17459 , 0.75081,-0.600191,-0.275781 --0.659918 , 3.94928 , 3.29596 , 0.448095,0.400272,0.799371 --0.609523 , 3.78084 , 3.27875 , -0.199631,-0.430309,0.88033 --0.59721 , 3.73414 , 3.33688 , 0.295043,0.245522,0.923401 --0.547479 , 3.56727 , 3.31126 , 0.0503691,0.282242,0.95802 --2.26227 , 8.87874 , 7.23202 , 0.59873,-0.00885295,0.800902 --3.18759 , 11.7166 , 9.59391 , 0.836434,0.525538,-0.155523 --1.70408 , 7.10299 , 6.32966 , 0.436381,-0.891843,0.119107 --1.75236 , 7.23086 , 6.63011 , 0.348161,0.265426,0.899073 --1.63384 , 6.84424 , 6.5139 , -0.288202,-0.675438,0.678766 --2.0287 , 8.0265 , 7.73947 , -0.831632,-0.11206,0.543904 --1.8837 , 7.5576 , 7.56219 , -0.449362,-0.786024,0.424546 --1.86284 , 7.46731 , 7.71427 , -0.354137,-0.87291,0.33558 --1.17747 , 5.37183 , 5.93396 , -0.46804,-0.880543,0.0747137 --1.92032 , 7.58813 , 8.32441 , 0.163219,-0.943017,-0.289963 --0.773114 , 4.11979 , 4.99642 , -0.777167,0.520547,0.353614 --0.752971 , 4.04581 , 5.05904 , -0.777167,0.520547,0.353614 --0.722157 , 3.93822 , 5.08378 , -0.777167,0.520547,0.353614 --2.27172 , 8.50586 , 10.4852 , -0.604136,0.52284,-0.60138 --0.300894 , 2.6516 , 3.94902 , 0.658873,0.0761992,-0.748385 --0.281319 , 2.58362 , 3.96892 , -0.762221,0.0440898,0.645814 --0.257862 , 2.50475 , 3.97141 , -0.681662,-0.124405,0.721013 --0.234282 , 2.42552 , 3.97225 , -0.342254,0.291468,0.893257 --0.219384 , 2.37038 , 4.00288 , 0.149622,-0.521042,-0.840315 --0.201776 , 2.30852 , 4.02464 , -0.053874,0.443487,0.89466 --0.190521 , 2.26353 , 4.06946 , 0.0450961,0.589493,0.806514 --0.178467 , 2.21718 , 4.11371 , 0.189804,0.642831,0.74212 --0.184265 , 2.22093 , 4.24143 , 0.67711,0.727071,0.11353 --0.279312 , 2.47169 , 4.80494 , 0.128762,0.166596,-0.977582 --0.249716 , 2.37495 , 4.78428 , 0.414106,0.324163,-0.85055 --0.21542 , 2.26484 , 4.73522 , 0.328265,-0.653421,0.682116 --0.203106 , 2.21587 , 4.79757 , 0.0583205,0.980286,0.188782 --0.201282 , 2.19586 , 4.92115 , -0.114932,0.76516,0.633498 --0.201818 , 2.18028 , 5.06329 , -0.184007,-0.281111,0.94187 --0.169747 , 2.07542 , 5.01659 , 0.0830877,0.221839,0.971537 --0.145271 , 1.99286 , 5.01259 , -0.549082,-0.25828,-0.794858 --0.152087 , 1.99315 , 5.20855 , -0.135976,-0.756119,0.640152 --0.115821 , 1.87935 , 5.12882 , -0.362121,0.397783,0.842993 --0.100723 , 1.82116 , 5.18554 , -0.346127,0.325296,0.879988 --0.0381087 , 1.64332 , 4.90453 , -0.954842,0.268526,0.127162 --0.0886189 , 1.74845 , 5.4474 , -0.932132,-0.00176392,0.362116 --0.0737227 , 1.68965 , 5.5212 , 0.920803,0.380219,0.0869265 --0.0347495 , 1.57159 , 5.40388 , -0.879656,-0.320348,0.351542 --0.00633307 , 1.47981 , 5.36012 , 0.887132,0.452084,-0.0928341 --0.0172515 , 1.47871 , 5.66103 , -0.97266,0.0946545,0.212069 -0.0860775 , 1.22121 , 4.92801 , -0.208483,-0.134179,0.968778 -0.120525 , 1.12192 , 4.78936 , -0.497073,0.508896,-0.702811 -0.0288709 , 1.28792 , 5.93637 , 0.745573,-0.232602,0.624514 -0.0551789 , 1.20025 , 5.92513 , 0.220483,-0.954649,0.20008 --0.176028 , 2.77625 , 1.58782 , 0.850358,-0.428153,0.305903 --0.180366 , 2.7844 , 1.63716 , 0.850358,-0.428153,0.305903 --0.176789 , 2.76396 , 1.67966 , 0.850358,-0.428153,0.305903 --2.45709 , 11.0087 , 4.02839 , -0.856635,0.43841,0.27198 --1.84808 , 8.77789 , 3.57179 , -0.242269,0.939804,-0.240986 --2.04977 , 9.47849 , 3.96244 , 0.804567,-0.567328,0.175531 --1.94291 , 9.06929 , 4.00721 , 0.0592335,-0.596193,0.800653 --2.48539 , 10.9823 , 4.87079 , -0.0155405,-0.702279,0.711732 --1.47326 , 7.34102 , 3.7094 , 0.419625,-0.903211,-0.0901319 --1.45639 , 7.25724 , 3.82219 , 0.419625,-0.903211,-0.0901321 --1.46868 , 7.27996 , 3.97783 , 0.415216,-0.897991,-0.145629 --2.14678 , 9.65346 , 5.17671 , -0.93196,-0.330309,0.149491 --2.10279 , 9.4659 , 5.29275 , -0.344523,-0.936455,-0.0660074 --1.26011 , 6.48117 , 4.04426 , 0.169446,0.980234,-0.102123 --1.26335 , 6.47183 , 4.1778 , 0.169446,0.980234,-0.102123 --2.77156 , 11.7067 , 7.09945 , -0.863092,-0.444613,0.239565 --0.583715 , 4.06948 , 3.13048 , 0.479068,-0.623591,-0.61776 --0.550274 , 3.94025 , 3.1453 , -0.402817,-0.360199,-0.841425 --0.523764 , 3.83709 , 3.17109 , -0.129833,-0.452367,-0.882331 --0.493039 , 3.71748 , 3.18343 , 0.244886,0.461368,0.852743 --0.497067 , 3.72104 , 3.27175 , -0.00822872,0.418341,0.908253 --0.470762 , 3.61744 , 3.29012 , -0.134535,0.293012,0.946596 --0.448793 , 3.53126 , 3.31636 , 0.525367,-0.691955,-0.495164 --1.70134 , 7.75499 , 6.49211 , 0.652396,-0.170341,0.738488 --1.44686 , 6.86927 , 6.02694 , -0.846983,0.192265,-0.495634 --1.55026 , 7.18854 , 6.46488 , -0.190354,0.763464,0.617161 --1.51243 , 7.03398 , 6.54012 , -0.190354,0.763464,0.617161 --1.8606 , 8.16704 , 7.70082 , 0.751811,0.589023,-0.296364 --1.69703 , 7.5896 , 7.43792 , -0.367216,-0.845028,0.38869 --1.81136 , 7.93386 , 7.98329 , -0.26468,0.667808,0.695685 --1.78364 , 7.80708 , 8.11452 , -0.46167,0.759403,0.458441 --1.03875 , 5.33607 , 5.95771 , 0.510604,0.83529,-0.203899 --1.75958 , 7.65647 , 8.4812 , 0.427073,-0.870651,-0.244083 --1.73914 , 7.55559 , 8.64252 , 0.805758,-0.165373,-0.568688 --1.87071 , 7.94199 , 9.33497 , -0.941181,0.290991,-0.171764 --1.83241 , 7.78006 , 9.45128 , -0.590775,0.747476,-0.303751 --2.73057 , 10.5404 , 13.403 , 0.471428,-0.865991,0.166778 --0.416177 , 3.19276 , 4.66231 , -0.855121,-0.502187,0.12875 --0.388448 , 3.08879 , 4.66032 , -0.0808532,-0.995948,0.0393725 --0.221905 , 2.55148 , 4.07249 , -0.777335,-0.198891,0.596819 --0.186278 , 2.42552 , 4.00934 , -0.347808,0.235095,0.907612 --0.168997 , 2.35799 , 4.02362 , -0.181347,0.351241,0.918555 --0.153512 , 2.29545 , 4.04465 , -0.0603624,0.395643,0.916419 --0.139602 , 2.23892 , 4.07243 , 0.0153949,0.581893,0.81312 --0.130622 , 2.19704 , 4.1245 , 0.0801765,0.610273,0.788124 --0.119657 , 2.1496 , 4.16728 , -0.551789,-0.710976,-0.435938 --0.136635 , 2.18335 , 4.35533 , -0.665534,-0.745891,0.0266724 --0.212606 , 2.38786 , 4.86554 , -0.506162,0.20829,0.836908 --0.171068 , 2.24819 , 4.76367 , -0.0625276,-0.959515,0.274628 --0.177707 , 2.24705 , 4.92255 , -0.114932,0.765161,0.633498 --0.173228 , 2.21549 , 5.0291 , 0.31773,-0.813543,-0.487027 --0.154223 , 2.13863 , 5.04602 , 0.0736736,-0.202805,0.976444 --0.128602 , 2.04698 , 5.02495 , -0.0752255,-0.138653,0.98748 --0.109869 , 1.97155 , 5.03834 , 0.379879,-0.769592,-0.513245 --0.111811 , 1.95463 , 5.19764 , 0.602124,0.405077,-0.688011 --0.0868405 , 1.86223 , 5.17216 , -0.354275,0.226635,0.907263 --0.066849 , 1.78571 , 5.18178 , 0.268596,0.0671829,-0.960907 --0.0390064 , 1.689 , 5.13385 , 0.99901,0.0418152,0.0151627 --0.0616626 , 1.72036 , 5.47086 , -0.844824,-0.289169,0.45017 --0.0440343 , 1.64767 , 5.50627 , 0.927022,0.363707,-0.0913685 --0.0292046 , 1.58241 , 5.56909 , -0.955574,0.156754,0.249614 -0.0217837 , 1.4317 , 5.31377 , 0.999913,-0.0129062,0.00290359 -0.0839674 , 1.25871 , 4.92894 , 0.683243,-0.286133,0.671794 -0.105816 , 1.18172 , 4.898 , -0.78498,-0.558036,-0.269076 -0.135957 , 1.08732 , 4.77777 , 0.396009,-0.679062,0.618103 -0.0393723 , 1.25643 , 5.99473 , 0.68583,0.0895885,-0.722227 --1.75454 , 10.8144 , -3.16342 , -0.0140586,-0.0581759,0.998207 --2.31013 , 13.29 , -3.62688 , 0.206002,-0.320264,-0.924659 --2.85583 , 15.7393 , -4.19984 , -0.127388,0.187599,0.97395 --7.82993 , 36.6693 , -2.4573 , -0.87841,0.441942,-0.181887 --3.1587 , 16.2223 , -0.205554 , 0.0623155,0.987279,0.146275 --7.81676 , 36.3445 , -1.12984 , -0.878411,0.441941,-0.181887 --3.15893 , 16.1034 , 0.371004 , 0.107555,-0.519521,-0.847661 --3.16455 , 16.0701 , 0.654908 , -0.0473852,0.395599,0.9172 --0.102248 , 2.77939 , 1.56445 , 0.850358,-0.428153,0.305903 --0.092729 , 2.73088 , 1.60037 , 0.850358,-0.428153,0.305903 --0.0954125 , 2.73052 , 1.64609 , 0.850358,-0.428153,0.305903 --1.75242 , 9.44608 , 3.4977 , -0.433117,-0.0899765,-0.896835 --1.95989 , 10.2518 , 3.90674 , -0.0847616,0.818586,0.568096 --1.79941 , 9.56655 , 3.89069 , -0.827274,0.172802,-0.534562 --1.88345 , 9.86636 , 4.17175 , -0.102095,0.713485,0.693193 --1.83401 , 9.63538 , 4.28259 , -0.21023,-0.248882,0.945442 --1.84662 , 9.65039 , 4.47675 , -0.0641928,0.995034,0.0760757 --2.35521 , 11.6307 , 5.43661 , 0.211325,-0.419794,0.882675 --1.27879 , 7.33351 , 3.91574 , 0.414782,-0.898002,-0.146794 --1.28895 , 7.34566 , 4.06858 , 0.368398,-0.922513,-0.115125 --1.84856 , 9.5111 , 5.19633 , -0.344523,-0.936455,-0.0660073 --1.81199 , 9.33151 , 5.31157 , -0.32319,-0.945641,0.036203 --1.07461 , 6.4264 , 4.07281 , 0.189979,0.97755,-0.0911275 --1.10052 , 6.50215 , 4.25 , 0.174582,0.803254,-0.569477 --0.482351 , 4.09511 , 3.09144 , -0.0339818,0.272193,0.961642 --0.459739 , 3.99059 , 3.12125 , -0.0339818,0.272193,0.961642 --0.441384 , 3.90326 , 3.15786 , 0.189797,0.402379,0.895583 --0.424376 , 3.82517 , 3.19691 , -0.206378,0.835085,0.509943 --0.412427 , 3.76169 , 3.24462 , -0.334845,0.494858,0.80187 --1.25741 , 6.93172 , 5.42954 , 0.842396,0.010859,0.538749 --1.69558 , 8.54504 , 6.71067 , 0.425509,-0.395725,0.813845 --1.36438 , 7.26844 , 6.01828 , 0.599062,-0.729474,0.330141 --1.51904 , 7.80969 , 6.60887 , -0.285678,0.0762439,-0.955288 --1.19454 , 6.5729 , 5.86732 , 0.400006,0.853693,0.333472 --1.1429 , 6.35151 , 5.86997 , -0.149581,-0.71913,0.678585 --1.30343 , 6.9074 , 6.50893 , 0.188476,0.722058,0.665665 --1.35211 , 7.05043 , 6.83133 , 0.387867,0.89828,-0.206522 --1.43568 , 7.31507 , 7.27784 , -0.123004,-0.860174,0.494945 --1.42752 , 7.24971 , 7.44369 , -0.208583,-0.859691,0.466289 --1.5527 , 7.65599 , 8.06233 , 0.457683,-0.888761,0.0251155 --1.55759 , 7.63208 , 8.29083 , 0.427072,-0.870651,-0.244083 --1.60214 , 7.74555 , 8.66821 , -0.969159,0.194075,0.151872 --1.74019 , 8.1856 , 9.40891 , -0.834921,0.537712,0.117362 --1.65467 , 7.83598 , 9.32526 , -0.590775,0.747476,-0.303751 --1.4392 , 7.03706 , 8.71516 , -0.754515,-0.20488,0.623483 --2.4664 , 10.5334 , 13.1172 , 0.471428,-0.865991,0.166778 --0.393164 , 3.36404 , 4.79104 , -0.859312,-0.511235,-0.0148599 --0.32867 , 3.12281 , 4.62214 , 0.0844122,0.975904,0.201213 --0.309879 , 3.03704 , 4.64147 , 0.271571,0.710502,0.649181 --0.353158 , 3.16111 , 4.9448 , -0.685858,-0.60906,0.398302 --0.155066 , 2.47907 , 4.12754 , 0.710271,0.377237,-0.594313 --0.119282 , 2.34263 , 4.04446 , -0.443315,0.139656,0.88542 --0.103787 , 2.27507 , 4.05645 , -0.302019,0.188795,0.93442 --0.0910382 , 2.21766 , 4.08373 , -0.0816195,0.465614,0.881216 --0.0810907 , 2.16558 , 4.11813 , 0.17471,0.632466,0.754628 --0.0734352 , 2.12167 , 4.16891 , 0.164633,0.631271,0.757887 --0.0760156 , 2.11156 , 4.27924 , 0.602912,0.788239,0.123193 --0.118857 , 2.22442 , 4.62532 , 0.658927,-0.264932,0.704007 --0.146397 , 2.28553 , 4.89718 , -0.890366,-0.451078,-0.0614582 --0.182843 , 2.37168 , 5.24371 , -0.407225,-0.584392,0.701893 --0.115299 , 2.14369 , 4.94972 , -0.770245,0.0845467,0.632119 --0.102729 , 2.07999 , 4.99208 , -0.415748,-0.0832066,0.905666 --0.083556 , 1.99656 , 4.98768 , 0.096522,0.431734,0.896822 --0.0857716 , 1.97774 , 5.13752 , -0.499979,-0.852041,0.155071 --0.0739019 , 1.9145 , 5.1863 , 0.201492,0.110583,0.973228 --0.0534695 , 1.82998 , 5.17813 , -0.354275,0.226635,0.907263 --0.419399 , 2.79162 , 8.14645 , -0.345567,0.140618,0.927799 --0.0558653 , 1.77462 , 5.49615 , -0.348241,0.237143,0.906913 --0.0368283 , 1.69265 , 5.50374 , 0.920803,0.380218,0.0869267 --0.0169652 , 1.60819 , 5.50024 , -0.965716,-0.136643,0.220728 -0.014866 , 1.49438 , 5.38986 , -0.851151,-0.399497,0.340505 -0.00154504 , 1.49179 , 5.69083 , -0.984356,0.078025,0.157974 -0.0901503 , 1.24776 , 5.02542 , 0.826254,0.561389,0.0463409 -0.129451 , 1.12603 , 4.79958 , -0.636887,0.392251,-0.663713 -0.0308015 , 1.30174 , 5.99517 , 0.651124,-0.235323,-0.721568 -0.0583148 , 1.20058 , 5.92539 , 0.0864923,-0.981865,0.168704 --0.795704 , 7.47412 , -2.01977 , -0.580372,-0.404841,-0.706592 --0.808023 , 7.49647 , -1.88112 , -0.580372,-0.404841,-0.706592 --0.822152 , 7.53464 , -1.74945 , -0.580372,-0.404841,-0.706592 --0.843367 , 7.56696 , -1.47197 , 0.580372,0.404841,0.706592 --0.860299 , 7.61729 , -1.34583 , 0.580372,0.404841,0.706592 --6.45862 , 36.687 , -7.35147 , -0.790265,0.574164,-0.214047 --6.52212 , 36.8281 , -6.70657 , -0.790265,0.574164,-0.214047 --6.59362 , 37.0166 , -6.07022 , -0.790265,0.574164,-0.214047 --6.6696 , 37.222 , -5.4342 , -0.790265,0.574165,-0.214047 --6.73147 , 37.3597 , -4.78367 , -0.790265,0.574165,-0.214047 --6.79756 , 37.5149 , -4.13416 , -0.790265,0.574164,-0.214047 --6.85047 , 37.6009 , -3.47357 , 0.873269,-0.450846,0.184768 --6.91867 , 37.7628 , -2.82025 , -0.876512,0.44502,-0.183531 --6.97984 , 37.8948 , -2.16058 , -0.87841,0.441942,-0.181887 --2.69656 , 16.293 , -0.0370171 , 0.231538,-0.167694,-0.958263 --2.67855 , 16.1297 , 0.256222 , 0.579672,0.0215252,-0.814566 --7.19465 , 38.4277 , -0.166558 , -0.87841,0.441942,-0.181887 --7.25729 , 38.5625 , 0.509938 , -0.87841,0.441942,-0.181887 --0.0911527 , 3.06775 , 1.59996 , 0.592431,-0.106963,0.798489 --1.39997 , 9.13345 , 2.99418 , 0.12756,-0.870853,0.474703 --1.39257 , 9.05932 , 3.14222 , -0.341502,-0.932686,0.116077 --1.50796 , 9.55025 , 3.43575 , 0.413249,-0.113639,0.903499 --1.59024 , 9.88397 , 3.70507 , -0.957674,-0.281022,-0.0623466 --1.48004 , 9.33802 , 3.72783 , 0.333919,0.894581,0.297022 --1.45805 , 9.19485 , 3.85935 , 0.102653,0.990871,0.0873891 --1.57722 , 9.69161 , 4.20186 , -0.168641,0.848153,0.502191 --1.49672 , 9.28321 , 4.24428 , -0.669108,-0.705206,0.234478 --1.78768 , 10.5446 , 4.90126 , -0.672776,-0.445801,0.590452 --1.8122 , 10.6021 , 5.13426 , -0.533226,0.204468,0.820891 --1.09924 , 7.39415 , 4.00721 , 0.368398,-0.922512,-0.115125 --1.10145 , 7.36867 , 4.14519 , 0.351716,-0.935737,-0.0262936 --1.58757 , 9.4644 , 5.26281 , -0.0101354,-0.940302,0.34019 --1.63384 , 9.61881 , 5.53656 , -0.107637,0.787073,-0.607396 --0.896461 , 6.3732 , 4.10519 , 0.195121,0.973795,-0.116839 --1.11789 , 7.29744 , 4.72971 , -0.723841,0.644603,0.246052 --1.01956 , 6.83766 , 4.63694 , -0.982192,0.161433,-0.0961202 --0.320541 , 3.81453 , 3.05688 , -0.245883,-0.85887,-0.449315 --0.338022 , 3.87168 , 3.17475 , 0.404619,0.780011,0.477352 --0.324299 , 3.79205 , 3.21257 , 0.460554,-0.886263,0.0492717 --0.331575 , 3.80289 , 3.30682 , 0.458427,-0.51122,-0.726979 --1.11899 , 7.07698 , 5.59608 , 0.55021,-0.718719,0.425103 --1.17281 , 7.26205 , 5.90222 , -0.692659,0.640413,-0.331806 --1.59439 , 8.96315 , 7.32243 , 0.633462,0.527655,0.565955 --1.20776 , 7.32389 , 6.32589 , 0.349231,0.84055,0.414141 --0.979473 , 6.34859 , 5.76234 , -0.0136721,0.776958,0.629404 --1.18137 , 7.12804 , 6.56842 , 0.365526,0.825839,0.429397 --1.17527 , 7.06135 , 6.7153 , 0.441497,0.882647,0.161292 --1.27582 , 7.42121 , 7.23576 , 0.763554,0.619493,0.182247 --1.15124 , 6.87447 , 6.96785 , 0.608,0.435184,0.664042 --1.05982 , 6.46875 , 6.80315 , 0.497175,0.469065,0.729928 --1.55429 , 8.36907 , 8.84857 , -0.927886,0.313832,-0.20134 --1.50744 , 8.12812 , 8.88798 , -0.927886,0.313832,-0.20134 --1.42867 , 7.76537 , 8.79373 , -0.925057,0.379807,0.00400668 --1.57493 , 8.2676 , 9.61168 , 0.55521,-0.152195,-0.817667 --1.52269 , 8.00605 , 9.6291 , 0.799556,-0.600429,-0.013971 --1.01761 , 6.03722 , 7.66635 , -0.296851,-0.862359,-0.410141 --0.273048 , 3.20285 , 4.51713 , 0.467283,0.490943,0.73527 --0.258955 , 3.12437 , 4.54577 , 0.255094,0.669258,0.697868 --0.250594 , 3.06921 , 4.60398 , 0.11615,0.786314,0.606811 --0.280158 , 3.14922 , 4.84294 , -0.297795,-0.935494,0.190181 --0.25775 , 3.04276 , 4.83782 , 0.394401,0.848355,-0.353189 --0.10347 , 2.46346 , 4.1494 , -0.707198,-0.327339,0.626674 --0.0800028 , 2.35896 , 4.11442 , 0.669173,0.279099,-0.688703 --0.0592897 , 2.26358 , 4.08467 , -0.279414,0.0973788,0.95522 --0.0467597 , 2.20018 , 4.103 , 0.272533,-0.221509,-0.936301 --0.0370308 , 2.14209 , 4.12846 , 0.062845,0.58968,0.805188 --0.0303009 , 2.09826 , 4.17854 , 0.112187,0.682652,0.722081 --0.0280615 , 2.06715 , 4.25419 , 0.464381,0.769821,0.437865 --0.0540909 , 2.12762 , 4.50451 , -0.85147,-0.456724,0.257685 --0.141166 , 2.38489 , 5.16468 , 0.356197,0.62673,-0.69306 --0.110999 , 2.25809 , 5.08589 , -0.325133,-0.528892,0.78394 --0.0881564 , 2.15442 , 5.04913 , -0.676172,-0.287355,0.678394 --0.0707249 , 2.06855 , 5.04607 , 0.230432,0.176725,-0.956906 --0.717654 , 4.00095 , 9.82074 , -0.799913,0.528505,-0.284291 --0.0534436 , 1.95198 , 5.16342 , -0.153498,-0.418437,0.895181 --0.0366794 , 1.87041 , 5.16511 , 0.227295,0.0387517,0.973055 --0.0529641 , 1.88351 , 5.42675 , -0.731144,0.553686,0.398573 --0.360641 , 2.70591 , 8.07705 , 0.345567,-0.140618,-0.927799 --0.222351 , 2.26647 , 7.13682 , -0.460345,0.425392,-0.779182 --0.00784868 , 1.64676 , 5.47926 , 0.907633,0.34414,-0.240355 --0.0213329 , 1.6415 , 5.75194 , -0.478923,0.877837,-0.00598422 -0.0722879 , 1.36466 , 5.04579 , 0.771296,-0.215237,0.598979 -0.0955244 , 1.2724 , 4.96824 , 0.787683,0.540003,-0.296566 -0.125369 , 1.16617 , 4.82105 , 0.670159,-0.290987,0.682798 -0.0183928 , 1.36412 , 6.07338 , -5.48247e-05,0.922602,0.385753 -0.0405783 , 1.26533 , 6.03403 , -0.202134,0.0567352,-0.977713 -0.109495 , 2.95148 , -0.109431 , -0.983929,-0.168841,-0.0581116 -0.103624 , 2.97005 , -0.0623599 , -0.983929,-0.168841,-0.0581116 -0.100815 , 2.96946 , -0.00775234 , -0.983929,-0.168841,-0.0581116 -0.0947226 , 2.98704 , 0.0393211 , -0.983929,-0.168841,-0.0581116 -0.0876681 , 3.0127 , 0.0836753 , -0.983929,-0.168841,-0.0581116 --1.3774 , 12.3287 , -2.49024 , 0.697437,0.402933,-0.592643 -0.0595728 , 3.05588 , 0.435701 , -0.982542,-0.177136,-0.0568641 -0.058081 , 3.04613 , 0.488261 , -0.982542,-0.177136,-0.0568641 -0.0522248 , 3.06466 , 0.535137 , 0.996977,-0.00221416,0.0776612 -0.0494912 , 3.06218 , 0.585759 , 0.997264,-0.00179516,0.0739024 -0.0486055 , 3.04998 , 0.637375 , 0.997264,-0.00179516,0.0739024 -0.0485038 , 3.03646 , 0.688628 , 0.997264,-0.00179516,0.0739024 --1.15405 , 9.26949 , 2.77856 , -0.0294039,-0.752247,0.658225 --1.62055 , 11.7285 , 3.46684 , 0.461405,0.047816,0.8859 --1.14974 , 9.14326 , 3.08214 , 0.207584,0.867023,-0.452969 --1.20083 , 9.36253 , 3.30306 , -0.769505,0.634857,0.0694177 --1.33602 , 10.0234 , 3.65244 , 0.998843,0.0395958,-0.0273002 --1.19792 , 9.23782 , 3.61226 , -0.248569,0.958367,0.140523 --1.1879 , 9.13422 , 3.75307 , 0.491516,-0.835245,0.246532 --1.33237 , 9.83321 , 4.15368 , -0.141652,0.957128,0.252669 --1.29607 , 9.5905 , 4.25808 , 0.290227,-0.630005,-0.72032 --1.48322 , 10.4922 , 4.77449 , 0.0388866,-0.8647,0.500781 --1.24667 , 9.2228 , 4.49004 , -0.211826,0.596143,0.774431 --1.23239 , 9.09637 , 4.62214 , 0.163484,-0.986495,-0.0100664 --0.924944 , 7.49411 , 4.11984 , 0.378052,-0.917835,-0.121062 --0.921391 , 7.43048 , 4.24292 , 0.378052,-0.917835,-0.121062 --0.934748 , 7.45309 , 4.40693 , 0.379531,-0.91486,-0.137796 --0.73332 , 6.41295 , 4.05101 , 0.00547292,-0.0914118,0.995798 --0.726474 , 6.34145 , 4.15021 , 0.167958,0.250659,0.953394 --0.233663 , 3.893 , 2.97152 , -0.549973,-0.51099,-0.66062 --0.27176 , 4.05629 , 3.14581 , -0.2769,-0.600896,0.749833 --0.229006 , 3.82252 , 3.09838 , -0.177436,-0.974798,-0.135225 --0.254088 , 3.92065 , 3.24262 , -0.413839,-0.228499,-0.881207 --0.928117 , 7.10232 , 5.34339 , 0.563841,-0.716506,0.410734 --1.00406 , 7.4122 , 5.71816 , -0.761718,0.41982,-0.493494 --1.00174 , 7.35398 , 5.86079 , -0.800805,0.512133,-0.310532 --0.993121 , 7.25994 , 5.98012 , -0.567473,0.773188,-0.283118 --1.05161 , 7.48177 , 6.33126 , -0.973753,0.220712,0.055598 --0.8568 , 6.53538 , 5.80628 , 0.00829593,-0.748222,0.663397 --0.95405 , 6.93012 , 6.29619 , -0.704087,-0.629195,-0.329205 --0.870388 , 6.50249 , 6.13823 , 0.0795571,-0.897137,0.434531 --0.953368 , 6.82477 , 6.59983 , -0.134926,0.171645,0.975876 --0.929988 , 6.66816 , 6.66315 , 0.694522,0.17548,0.697743 --0.906332 , 6.51072 , 6.72278 , -0.363685,0.0686016,-0.928992 --1.34889 , 8.39494 , 8.71207 , 0.309187,-0.699988,0.643755 --1.50598 , 9.00651 , 9.58818 , -0.173563,-0.0116643,0.984754 --1.40744 , 8.5035 , 9.38349 , 0.853361,-0.244377,-0.460494 --0.596705 , 4.97808 , 5.97097 , -0.157946,-0.186251,0.969724 --1.32894 , 8.02124 , 9.46773 , 0.799556,-0.600429,-0.013971 --0.902297 , 6.16571 , 7.67377 , 0.28698,0.753974,0.590903 --0.853918 , 5.90773 , 7.6126 , 0.28698,0.753974,0.590903 --0.195018 , 3.15439 , 4.5085 , 0.255094,0.669258,0.697868 --0.193573 , 3.11842 , 4.59013 , -0.101039,-0.794366,-0.598978 --0.211817 , 3.15784 , 4.77362 , 0.12897,-0.97435,0.184417 --0.17632 , 2.98693 , 4.68113 , 0.467943,-0.42152,-0.776757 --0.16401 , 2.90675 , 4.70448 , 0.584995,0.0371848,-0.810184 --0.148003 , 2.81459 , 4.70994 , 0.813609,0.278806,-0.510203 --0.0419098 , 2.3795 , 4.1931 , 0.739307,0.409999,-0.534159 --0.0171542 , 2.25548 , 4.12129 , -0.442027,0.199515,0.874532 --0.00390012 , 2.18093 , 4.12226 , -0.41139,0.129946,0.902149 -0.00466726 , 2.12198 , 4.14721 , 0.119883,-0.531792,-0.838347 -0.00925939 , 2.07752 , 4.19676 , 0.247949,0.769788,0.588173 -0.0136782 , 2.03692 , 4.25457 , 0.299428,0.719636,0.626472 --0.00536187 , 2.07192 , 4.46141 , -0.714723,-0.698621,0.0331619 --0.172977 , 2.62215 , 5.71837 , -0.354939,0.929956,0.0959196 --0.0836299 , 2.27586 , 5.20428 , -0.793175,-0.593668,0.13576 --0.0568866 , 2.1502 , 5.12189 , -0.80087,-0.237039,0.549927 --0.0336298 , 2.03589 , 5.05457 , -0.930564,0.137444,0.339352 --0.401837 , 3.17173 , 8.00373 , 0.31277,-0.132155,-0.94059 --0.016486 , 1.90702 , 5.14282 , -0.201492,-0.110583,-0.973228 --0.0236124 , 1.89098 , 5.32045 , -0.898266,0.401732,0.178127 --0.342685 , 2.79297 , 8.1129 , -0.345567,0.140618,0.927799 --0.328925 , 2.68257 , 8.19498 , -0.345567,0.140618,0.927799 --0.180101 , 2.19786 , 7.08958 , -0.462949,0.438738,-0.770186 --0.00159232 , 1.65648 , 5.64508 , 0.602257,-0.794933,-0.0732689 -0.0825654 , 1.38805 , 4.98844 , -0.0311143,0.654228,0.755657 -0.0259132 , 1.48842 , 5.66319 , 0.977032,-0.107006,-0.184277 -0.124207 , 1.20458 , 4.83254 , 0.0939319,0.337712,0.936551 -0.130398 , 1.14722 , 4.88769 , -0.92635,0.263529,-0.269125 -0.0375534 , 1.30533 , 6.00534 , -0.79917,0.282232,0.530728 -0.0530302 , 1.21704 , 6.01369 , 0.428424,-0.902554,0.0429933 --0.345037 , 7.60804 , -2.16816 , -0.580371,-0.404841,-0.706592 --0.563773 , 9.38594 , -2.76021 , -0.0652647,0.195129,0.978604 --0.684149 , 10.3082 , -2.9417 , -0.0976421,0.187522,0.977395 --0.83303 , 11.4434 , -3.16919 , -0.179061,0.028903,0.983413 --0.961077 , 12.3824 , -3.28411 , -0.291435,-0.11001,-0.950244 --1.18697 , 14.1001 , -3.62801 , 0.178803,-0.250558,-0.951446 --1.5323 , 16.7599 , -4.20829 , -0.0843199,0.193697,0.977431 --1.8941 , 19.4993 , -4.71341 , -0.0710559,0.155716,0.985243 -0.0644982 , 3.61854 , 0.413221 , 0.997264,-0.00179516,0.0739024 -0.0618824 , 3.60887 , 0.474931 , 0.997264,-0.00179516,0.0739024 --1.52872 , 14.48 , 0.89197 , 0.779883,-0.600569,0.176352 --1.52968 , 14.3785 , 1.14107 , 0.779883,-0.600569,0.176352 --1.55014 , 14.412 , 1.38986 , 0.779883,-0.600569,0.176352 --1.24815 , 11.6247 , 2.9352 , 0.345285,0.0196891,0.938291 --1.16934 , 11.0346 , 3.0317 , -0.370914,-0.0154037,-0.92854 --1.17665 , 11.0066 , 3.22269 , 0.117293,-0.0636778,0.991054 --1.11623 , 10.5414 , 3.31664 , 0.897684,-0.352277,-0.264698 --0.981733 , 9.62425 , 3.28638 , -0.0868308,-0.83502,0.543325 --0.940083 , 9.29519 , 3.37613 , 0.35423,-0.835267,0.420535 --0.983985 , 9.4993 , 3.60347 , 0.472283,-0.87932,0.0611952 --1.0216 , 9.66018 , 3.82758 , 0.870991,0.0089098,0.491218 --1.10159 , 10.0804 , 4.14158 , -0.527725,0.584411,0.616416 --1.0816 , 9.88276 , 4.26664 , -0.194333,0.222809,0.955296 --1.37021 , 11.5458 , 5.04895 , 0.0787856,0.268386,0.960084 --1.00518 , 9.28226 , 4.42183 , -0.073263,-0.569265,-0.818883 --1.04686 , 9.45959 , 4.6747 , 0.362333,-0.927862,-0.0882471 --1.05073 , 9.41151 , 4.84367 , -0.641524,0.757305,-0.122214 --1.28709 , 10.7182 , 5.60695 , 0.280236,-0.279056,-0.918474 --0.749076 , 7.53038 , 4.36301 , 0.679829,-0.564216,-0.468501 --0.748335 , 7.47043 , 4.49039 , 0.506205,-0.849358,-0.149492 --0.561783 , 6.3489 , 4.08401 , 0.0553365,0.187835,0.980641 --0.137405 , 3.90699 , 2.93616 , 0.582794,0.673747,0.454331 --0.136212 , 3.87362 , 2.9996 , 0.277427,0.813131,0.511715 --0.141682 , 3.87215 , 3.08227 , -0.425723,-0.869907,-0.24904 --0.131076 , 3.78486 , 3.1149 , 0.197339,0.810912,0.550889 --0.874595 , 7.81435 , 5.69383 , -0.89651,0.381853,-0.224628 --0.829993 , 7.50656 , 5.68186 , -0.761718,0.41982,-0.493494 --0.812462 , 7.35013 , 5.75931 , -0.761718,0.41982,-0.493494 --0.931912 , 7.92373 , 6.34028 , 0.204527,-0.978828,-0.00797297 --0.925209 , 7.82157 , 6.4688 , -0.0148059,-0.335102,0.942066 --0.692773 , 6.53834 , 5.71258 , 0.0795571,-0.897137,0.434531 --0.711247 , 6.58058 , 5.91947 , 0.079557,-0.897136,0.434531 --0.706083 , 6.49401 , 6.03017 , 0.324086,-0.934523,0.14709 --0.801093 , 6.91406 , 6.56377 , -0.632509,-0.757299,-0.162577 --0.775199 , 6.7189 , 6.5962 , 0.049594,-0.0998632,0.993764 --1.52524 , 10.3911 , 10.0895 , -0.989067,0.0865725,-0.119382 --1.46974 , 10.0139 , 10.0652 , -0.939516,-0.341957,0.0193651 --1.32978 , 9.23413 , 9.63964 , -0.180346,-0.328682,0.927062 --1.55095 , 10.2038 , 10.9144 , 0.52648,-0.384485,0.758281 --1.22347 , 8.53583 , 9.54644 , -0.307745,-0.0288892,0.95103 --0.474717 , 4.91205 , 5.97575 , -0.157948,-0.186253,0.969723 --0.7348 , 6.07223 , 7.43837 , 0.275551,0.696545,0.662493 --0.72297 , 5.94646 , 7.52511 , 0.28698,0.753974,0.590903 --0.127533 , 3.16894 , 4.45659 , 0.199691,0.84249,0.500334 --0.124738 , 3.12098 , 4.52262 , 0.168009,0.787066,0.593549 --0.121879 , 3.07283 , 4.58777 , 0.172255,0.752235,0.63598 --0.126916 , 3.05745 , 4.70014 , -0.717251,-0.119443,0.686502 --0.1086 , 2.94084 , 4.67665 , -0.867657,0.0639031,0.493039 --0.112339 , 2.91697 , 4.78003 , 0.775419,0.190556,-0.602007 --0.0923261 , 2.79628 , 4.74392 , -0.802447,-0.265765,0.534274 --0.0349048 , 2.52109 , 4.46364 , 0.324681,0.806828,-0.49357 -0.025474 , 2.24028 , 4.14959 , -0.746526,-0.191473,0.637211 -0.0365976 , 2.16508 , 4.14993 , 0.354965,-0.271015,-0.894735 -0.0439845 , 2.10031 , 4.16573 , -0.189938,0.411107,0.89158 -0.0485938 , 2.0508 , 4.20613 , 0.294293,0.673038,0.678536 -0.0508893 , 2.00952 , 4.26322 , 0.318053,0.666641,0.674116 -0.0393175 , 2.02094 , 4.42609 , -0.763243,-0.645904,-0.0163642 --0.0480028 , 2.30546 , 5.1616 , -0.833823,-0.552019,-0.00379413 --0.0246965 , 2.17873 , 5.08002 , -0.536616,-0.298173,0.789389 --0.0359753 , 2.17227 , 5.25836 , -0.879466,-0.299793,0.369682 --0.533035 , 3.82128 , 9.35239 , -0.186625,-0.897368,0.399878 --0.360005 , 3.15889 , 8.13371 , -0.337474,0.202472,0.919302 --0.334326 , 2.99975 , 8.09129 , -0.337474,0.202472,0.919302 --0.00978777 , 1.9053 , 5.46688 , -0.377652,0.620864,0.686954 --0.302285 , 2.74358 , 8.15615 , -0.345567,0.140618,0.927798 --0.207532 , 2.38656 , 7.48023 , -0.511133,-0.84339,0.165637 -0.00922381 , 1.69868 , 5.63347 , -0.866671,0.398123,0.300633 -0.00228443 , 1.66569 , 5.8208 , 0.749114,-0.662356,0.010616 -0.114093 , 1.31477 , 4.84504 , 0.99576,-0.0314395,0.0864451 -0.123541 , 1.24587 , 4.85349 , -0.51385,0.124267,-0.848832 -0.134043 , 1.17544 , 4.85075 , 0.0199872,0.910004,0.414117 -0.036008 , 1.349 , 5.99619 , -0.770716,0.327245,-0.546725 -0.0410597 , 1.27643 , 6.08305 , 0.500627,-0.85686,0.123145 --0.0777129 , 7.36384 , -2.25591 , -0.295307,-0.42675,-0.854797 --0.14605 , 8.06564 , -2.41971 , 0.0985576,0.278941,0.955237 --0.236453 , 8.99588 , -2.6536 , -0.0523333,0.202067,0.977972 --0.314751 , 9.75947 , -2.7847 , -0.068354,0.186903,0.979998 --0.424833 , 10.8658 , -3.01892 , -0.0716643,0.167618,0.983244 --0.513607 , 11.7007 , -3.11293 , 0.0653034,-0.248783,0.966355 --0.647156 , 13.0039 , -3.33806 , 0.0559194,-0.391743,-0.918374 --0.839919 , 14.914 , -3.71258 , -0.0607693,0.269219,0.96116 --1.13209 , 17.8404 , -4.32731 , 0.0818934,-0.153856,-0.984694 --1.42009 , 20.6471 , -4.79949 , 0.00669806,-0.262766,0.964836 --1.05879 , 14.2599 , 0.554532 , 0.501273,-0.832569,0.2357 --1.0829 , 14.1751 , 1.044 , 0.501273,-0.832569,0.2357 --1.09297 , 14.1217 , 1.28628 , -0.911591,-0.396574,0.108307 --1.11912 , 14.2022 , 1.53195 , -0.904272,-0.4181,0.0865186 --1.20561 , 14.7948 , 1.80768 , -0.802293,0.596382,-0.0256051 --1.19583 , 14.5591 , 2.04633 , 0.839713,-0.540159,-0.0557693 --0.989433 , 12.2123 , 2.94101 , -0.452382,-0.454459,-0.767345 --0.899019 , 11.3843 , 3.00923 , -0.182941,0.323911,0.928232 --0.608746 , 9.00098 , 2.74363 , -0.121547,-0.914515,0.385861 --0.615469 , 8.9681 , 2.89631 , -0.121547,-0.914515,0.385861 --0.631015 , 9.00145 , 3.0639 , 0.0417983,-0.869734,0.491747 --0.644285 , 9.02152 , 3.23096 , 0.0684099,0.880121,-0.469795 --0.71941 , 9.49804 , 3.52345 , 0.261646,0.860771,-0.436595 --0.727724 , 9.4706 , 3.69031 , -0.296428,0.163645,-0.940931 --0.861036 , 10.37 , 4.14312 , 0.119566,0.0930368,-0.988457 --0.822224 , 9.98359 , 4.21149 , -0.306533,0.135659,0.942143 --0.799568 , 9.72892 , 4.31293 , 0.117438,0.516351,0.848287 --0.778491 , 9.48316 , 4.40979 , -0.354957,0.767757,-0.533438 --0.745722 , 9.16291 , 4.47058 , 0.358428,-0.767884,0.530926 --0.858013 , 9.86222 , 4.93653 , -0.467147,0.883518,-0.0342029 --0.818222 , 9.49153 , 4.97531 , -0.45159,0.820716,-0.349989 --0.819088 , 9.40158 , 5.12837 , 0.597693,-0.746834,0.291553 --0.918189 , 9.99166 , 5.60023 , -0.0106412,-0.492982,0.869975 --0.56925 , 7.53521 , 4.60125 , 0.705094,-0.384902,-0.59556 --0.393777 , 6.28967 , 4.1208 , 0.116871,0.499874,0.858176 --0.358606 , 5.99901 , 4.09912 , 0.0502104,0.521163,0.851979 --0.356958 , 5.92693 , 4.18933 , 0.230943,-0.462385,-0.856076 --0.0362412 , 3.78984 , 3.0749 , -0.425724,-0.869907,-0.24904 --0.0311847 , 3.71925 , 3.11558 , -0.197339,-0.810912,-0.550889 --0.330302 , 5.58501 , 4.37646 , 0.948825,0.00871314,-0.315682 --0.400901 , 5.96418 , 4.75727 , -0.290658,-0.922941,0.252383 --0.745617 , 8.04446 , 6.31908 , 0.864358,-0.318122,-0.389466 --1.33722 , 11.5921 , 9.03131 , -0.027223,-0.607735,0.793673 --0.746107 , 7.87823 , 6.60646 , -0.520662,0.164997,0.837668 --0.744384 , 7.77921 , 6.73915 , 0.293694,0.743641,0.600617 --0.528117 , 6.41007 , 5.86853 , 0.324086,-0.934523,0.14709 --0.602255 , 6.77659 , 6.34628 , -0.800033,-0.479727,0.360292 --0.653996 , 7.00019 , 6.72919 , 0.564149,-0.0339789,-0.824974 --0.587487 , 6.53479 , 6.52565 , 0.559108,0.699846,-0.444538 --0.574687 , 6.38591 , 6.58829 , 0.35532,-0.933261,0.0526468 --0.883768 , 8.03269 , 8.34214 , -0.195695,-0.404873,0.893186 --1.10463 , 9.15152 , 9.69789 , -0.173563,-0.0116643,0.984754 --1.05798 , 8.78205 , 9.63422 , -0.173563,-0.0116643,0.984754 --1.0593 , 8.67859 , 9.83305 , -0.173563,-0.0116643,0.984754 --0.353485 , 4.82938 , 5.96521 , -0.125342,-0.14017,0.982162 --0.597721 , 6.03962 , 7.5058 , -0.047456,-0.768242,-0.638398 --0.59962 , 5.96418 , 7.65159 , 0.0916641,0.644822,0.758816 --0.590196 , 5.83527 , 7.73547 , 0.281761,0.908429,0.308815 --0.605087 , 5.82232 , 7.96435 , -0.160328,-0.953909,-0.253679 --0.769103 , 6.54165 , 9.15419 , 0.00603299,-0.383798,0.923397 --0.0709409 , 3.06884 , 4.77636 , 0.626059,-0.388718,-0.675979 --0.0717346 , 3.02693 , 4.8571 , -0.396637,0.473234,0.786593 --0.0417605 , 2.84144 , 4.73327 , -0.69782,0.227092,0.679321 --0.0354495 , 2.76477 , 4.76133 , -0.647042,-0.497738,0.577576 --0.0214423 , 2.65656 , 4.73768 , 0.542762,0.37102,-0.753495 -0.0543167 , 2.28041 , 4.27116 , -0.786712,-0.439614,0.433387 -0.0756691 , 2.14748 , 4.17768 , -0.324608,0.372227,0.869527 -0.0821303 , 2.0828 , 4.19277 , -0.246815,0.279268,0.927951 -0.0867595 , 2.02323 , 4.2151 , -0.198367,-0.598469,-0.776199 -0.0878863 , 1.98111 , 4.27178 , 0.215896,0.619162,0.755001 -0.0804301 , 1.97261 , 4.39926 , -0.77045,-0.626585,-0.117464 --0.00328469 , 2.25648 , 5.14608 , -0.879466,-0.299793,0.369682 -0.0034578 , 2.18018 , 5.17132 , -0.879466,-0.299793,0.369682 --0.0625878 , 2.37416 , 5.81498 , -0.0136386,0.308494,0.951128 --0.494703 , 3.85494 , 9.62641 , -0.775343,0.550141,-0.310143 --0.299995 , 3.07362 , 8.08816 , 0.337474,-0.202472,-0.919302 --0.285829 , 2.93988 , 8.10883 , 0.32886,-0.117805,-0.937002 -0.0180995 , 1.86712 , 5.47316 , -0.361317,0.544754,0.756765 --0.25335 , 2.66088 , 8.10468 , -0.345567,0.140618,0.927798 --0.176407 , 2.33972 , 7.51964 , 0.400211,0.912745,-0.0820242 -0.0251841 , 1.67487 , 5.69482 , -0.670421,0.721647,0.172515 -0.0115359 , 1.65238 , 5.92985 , 0.790076,-0.565286,-0.237132 -0.126771 , 1.28518 , 4.86448 , -0.715502,-0.0935176,-0.692324 -0.149331 , 1.17864 , 4.71723 , -0.64346,0.16431,-0.747637 -0.133053 , 1.16595 , 4.96599 , 0.370927,0.791026,-0.486508 -0.04262 , 1.31236 , 6.03517 , -0.786214,-0.372217,-0.493276 -0.0561575 , 1.21634 , 6.0039 , 0.428424,-0.902554,0.0429935 -0.164968 , 7.02322 , -2.14384 , 0.0856921,0.237196,0.967675 -0.126206 , 7.5778 , -2.25245 , 0.0530573,0.263509,0.963197 -0.0592208 , 8.62313 , -2.55201 , -0.0572536,0.204902,0.977107 -0.00551919 , 9.37689 , -2.69099 , 0.0597591,-0.176471,-0.98249 --0.0579436 , 10.2675 , -2.85554 , -0.0708707,0.185514,0.980083 --0.140892 , 11.4472 , -3.09412 , -0.00407717,-0.0980889,0.995169 --0.197624 , 12.1287 , -3.114 , -0.0516863,0.0459037,0.997608 --0.296975 , 13.4864 , -3.3342 , -0.116404,0.234249,0.965183 --0.318734 , 13.5398 , -3.09759 , -0.116404,0.234249,0.965183 --0.254439 , 12.2297 , -2.46162 , -0.181707,-0.86573,0.466362 --1.29915 , 27.5012 , -5.92155 , 0.061067,0.253677,0.965359 --1.19919 , 23.6297 , -2.80715 , 0.194224,0.0612411,0.979044 --1.23774 , 23.7197 , -2.40369 , 0.194224,0.0612411,0.979044 --0.910562 , 16.487 , 1.50258 , 0.742151,0.622338,0.248812 --0.942969 , 16.6244 , 1.79219 , -0.760927,-0.647064,-0.0479331 --0.624847 , 12.8495 , 1.8381 , 0.293701,0.224596,0.929138 --0.639463 , 12.8324 , 2.05735 , -0.76672,0.130874,0.628501 --0.682328 , 13.1186 , 2.30663 , -0.58851,0.615936,0.523716 --0.624106 , 12.312 , 2.43938 , 0.602127,0.478745,0.638942 --0.622967 , 12.1357 , 2.62955 , -0.511697,-0.352607,-0.783476 --0.59485 , 11.6821 , 2.7717 , 0.269715,0.608352,0.746433 --0.578827 , 11.3647 , 2.9221 , 0.345937,-0.830292,0.43697 --0.593816 , 11.3679 , 3.12273 , -0.345937,0.830292,-0.436971 --0.646712 , 11.7471 , 3.4028 , 0.61915,0.620925,-0.480734 --0.384749 , 9.01397 , 2.99801 , -0.147874,0.867283,-0.475346 --0.413152 , 9.18055 , 3.19973 , 0.173618,-0.830008,0.530042 --0.432661 , 9.24641 , 3.3825 , 0.159334,-0.752606,0.638903 --0.458096 , 9.36605 , 3.58445 , -0.232887,0.604118,-0.762106 --0.756209 , 12.0255 , 4.55381 , 0.28867,0.79275,0.536859 --0.720819 , 11.5531 , 4.62881 , -0.500398,-0.531803,-0.683218 --0.631874 , 10.5926 , 4.52242 , 0.34152,-0.830375,0.440275 --0.518243 , 9.44381 , 4.31318 , 0.470878,-0.501758,-0.725613 --0.517567 , 9.31824 , 4.44838 , 0.115062,-0.551558,0.826162 --0.559105 , 9.56185 , 4.72711 , -0.323596,0.868265,-0.376034 --0.712468 , 10.7606 , 5.41868 , 0.351701,0.28445,0.891849 --0.430597 , 8.23338 , 4.52544 , 0.668563,-0.480069,-0.567942 --0.627466 , 9.77802 , 5.40402 , 0.136261,-0.812016,0.567506 --0.408157 , 7.83574 , 4.67201 , 0.6867,-0.434214,-0.583011 --0.389908 , 7.59298 , 4.71412 , -0.560016,0.646884,0.517613 --0.214897 , 6.084 , 4.08272 , 0.0792653,0.548503,0.832383 --0.374088 , 7.27612 , 4.86724 , 0.673913,0.119003,-0.729163 --0.393599 , 7.32787 , 5.05803 , 0.412725,-0.901919,-0.127283 --0.232216 , 5.98344 , 4.4234 , -0.777423,0.551084,0.303183 --0.206814 , 5.7205 , 4.397 , -0.856137,0.463454,0.228562 --0.243728 , 5.91943 , 4.65841 , 0.273031,-0.950944,0.145463 --0.239959 , 5.81331 , 4.72891 , 0.213102,-0.958909,0.187299 --0.297837 , 6.16399 , 5.11422 , 0.290889,0.945163,-0.148495 --0.547362 , 7.8808 , 6.5067 , 0.0371688,0.578513,0.814826 --0.555508 , 7.83146 , 6.6746 , 0.293695,0.743641,0.600617 --0.851219 , 9.79641 , 8.40776 , 0.81555,0.57482,-0.0667913 --0.527558 , 7.41923 , 6.76753 , 0.113102,0.370705,0.921838 --0.549439 , 7.46285 , 7.0125 , -0.881532,-0.289918,0.372625 --0.526031 , 7.19929 , 7.001 , -0.889172,0.0236614,0.456962 --0.477975 , 6.77492 , 6.83646 , 0.762745,0.28,-0.582941 --0.480579 , 6.6939 , 6.96968 , 0.799793,0.221495,-0.557917 --0.869341 , 9.083 , 9.47639 , 0.287483,-0.398701,0.870857 --0.703154 , 7.89833 , 8.59933 , 0.0257876,-0.372567,0.927647 --0.854268 , 8.70558 , 9.70151 , 0.098191,-0.369409,0.924065 --0.461133 , 6.17333 , 7.31042 , 0.146833,0.56711,0.810448 --0.24258 , 4.76306 , 5.97561 , 0.493933,0.853121,-0.167974 --0.459695 , 5.96276 , 7.52819 , -0.141995,-0.691242,-0.708535 --0.461356 , 5.87433 , 7.6572 , -0.0523627,0.678059,0.73314 --0.445759 , 5.68226 , 7.66186 , -0.0138884,0.684503,0.728878 --0.0208119 , 3.21602 , 4.76052 , -0.522804,-0.273871,0.807261 --0.011299 , 3.10766 , 4.7561 , 0.398374,-0.152332,-0.904485 --0.00912341 , 3.04264 , 4.80497 , 0.215291,0.853486,0.474565 --0.00967916 , 2.98773 , 4.86893 , -0.0976219,0.644533,0.758319 --0.00449007 , 2.9028 , 4.89128 , 0.579223,-0.0651845,-0.812559 -0.00391265 , 2.80796 , 4.89502 , -0.583875,-0.342391,0.736111 -0.0340042 , 2.60334 , 4.71961 , -0.720918,-0.652203,0.234324 -0.0909992 , 2.27628 , 4.3255 , -0.765553,-0.492125,0.414418 -0.113553 , 2.1241 , 4.19637 , 0.401672,-0.243468,-0.882827 -0.117883 , 2.05877 , 4.21083 , 0.358695,-0.207958,-0.909996 -0.121344 , 1.99835 , 4.23275 , 0.0577749,0.56803,0.820978 -0.122502 , 1.95113 , 4.2801 , 0.199041,0.672027,0.713276 -0.120111 , 1.91651 , 4.35352 , 0.608435,0.71767,0.338758 -0.104307 , 1.93365 , 4.54398 , -0.789343,-0.608303,-0.0830992 -0.0289637 , 2.18421 , 5.27192 , 0.832848,0.535936,-0.138333 --0.0182391 , 2.30797 , 5.77176 , -0.941382,-0.304684,0.144802 --0.260058 , 3.1441 , 8.07542 , -0.337474,0.202472,0.919302 -0.0351757 , 1.98055 , 5.42229 , 0.0988981,0.337006,0.936294 -0.0389727 , 1.90772 , 5.46081 , 0.287361,-0.618258,-0.731561 --0.237357 , 2.76766 , 8.20797 , -0.345567,0.140618,0.927799 --0.162182 , 2.4231 , 7.57886 , 0.536242,0.823685,-0.184354 -0.0369606 , 1.72294 , 5.70253 , 0.553867,0.421497,-0.718033 -0.140977 , 1.35309 , 4.72244 , 0.223396,0.738857,0.635755 -0.138486 , 1.30633 , 4.80816 , -0.936886,0.0840998,-0.339369 -0.14601 , 1.2307 , 4.78694 , -0.855647,0.45481,0.247013 -0.153368 , 1.15891 , 4.7739 , 0.762509,-0.607185,0.223398 -0.0480771 , 1.3463 , 5.97734 , -0.270664,0.426976,0.862805 -0.0422743 , 1.28637 , 6.1324 , -0.204594,0.977022,0.0597456 -0.436874 , 4.02728 , -0.753552 , 0.76643,0.298789,0.568604 -0.423823 , 4.34843 , -0.821915 , -0.728095,-0.0986802,-0.678337 -0.414668 , 4.48026 , -0.795118 , -0.724445,-0.0855865,-0.683999 -0.404443 , 4.64022 , -0.775883 , 0.748977,0.067119,0.659188 -0.393417 , 4.81111 , -0.755578 , 0.748977,0.067119,0.659188 -0.382994 , 4.9254 , -0.708467 , -0.78481,-0.065954,-0.616218 -0.187665 , 11.7604 , -3.06112 , 0.0936179,-0.00183194,0.995607 -0.133952 , 12.9946 , -3.25486 , 0.165217,0.245425,0.955233 -0.0615803 , 14.7427 , -3.56757 , -0.057771,0.321351,0.945196 -0.0871558 , 13.2588 , -2.84755 , -0.572054,0.432261,0.697068 --0.206566 , 21.4164 , -4.89464 , 0.0496907,-0.319383,0.946322 -0.0564434 , 12.5392 , -1.94569 , -0.943461,0.316729,-0.0977966 -0.0360747 , 12.5985 , -1.73447 , -0.973413,0.228241,-0.0192948 -0.0168291 , 12.6335 , -1.51768 , 0.468232,-0.853285,0.229485 --0.00189051 , 12.6664 , -1.30076 , 0.468232,-0.853285,0.229485 --0.0221966 , 12.7137 , -1.08662 , 0.468231,-0.853286,0.229485 --0.0412796 , 12.7578 , -0.871557 , 0.46823,-0.853286,0.229485 --0.062422 , 12.828 , -0.659665 , 0.468231,-0.853286,0.229485 --0.0821255 , 12.8745 , -0.443459 , -0.797468,-0.60056,0.0580785 --0.101589 , 12.9181 , -0.226248 , -0.797468,-0.60056,0.0580785 --0.364873 , 16.14 , 0.836293 , -0.78651,-0.547125,-0.286453 --0.387685 , 16.1503 , 1.11226 , -0.78651,-0.547125,-0.286453 --0.376784 , 15.576 , 1.3761 , 0.758703,0.616808,0.209566 --0.406342 , 15.726 , 1.64868 , 0.758703,0.616808,0.209566 --0.418141 , 15.5632 , 1.90875 , 0.637702,-0.769739,-0.0289355 --0.270877 , 12.8371 , 1.97295 , 0.66445,0.258974,-0.701027 --0.2416 , 12.092 , 2.12469 , -0.531858,-0.42834,-0.730515 --0.257455 , 12.0906 , 2.33228 , -0.531858,-0.42834,-0.730515 --0.260545 , 11.8866 , 2.51515 , 0.547588,0.515802,0.658859 --0.245363 , 11.424 , 2.65386 , 0.0664353,0.733244,0.676712 --0.257647 , 11.3632 , 2.84295 , -0.495877,-0.51055,-0.702457 --0.275246 , 11.3887 , 3.04608 , -0.568258,-0.804301,-0.173732 --0.293332 , 11.4291 , 3.25496 , -0.568258,-0.804301,-0.173732 --0.389066 , 12.5182 , 3.69455 , -0.915025,0.402582,-0.0256188 --0.167006 , 9.29502 , 3.15911 , 0.173618,-0.830007,0.530042 --0.374319 , 11.8553 , 3.97673 , -0.975174,-0.186798,-0.118918 --0.237003 , 9.85822 , 3.64765 , 0.675095,-0.733968,0.0744195 --0.252615 , 9.86751 , 3.83085 , 0.742597,-0.0648549,0.666591 --0.298859 , 10.274 , 4.13945 , 0.247036,0.748106,0.615882 --0.289831 , 9.97144 , 4.23179 , -0.138003,0.754056,0.642148 --0.308451 , 10.0164 , 4.43642 , -0.205518,0.648354,0.733075 --0.283833 , 9.55321 , 4.45703 , 0.591897,-0.428857,-0.682451 --0.311692 , 9.70431 , 4.70134 , -0.661659,0.561665,0.496729 --0.404693 , 10.579 , 5.25032 , 0.512288,0.203644,0.83432 --0.181959 , 7.92182 , 4.3186 , -0.69912,0.387256,0.601052 --0.379139 , 9.93332 , 5.3855 , -0.0849473,-0.0287445,-0.995971 --0.398177 , 9.9727 , 5.60841 , 0.0835659,0.409011,0.908695 --0.681813 , 12.7851 , 7.20606 , -0.740459,0.671996,-0.0118764 --0.0673434 , 6.20127 , 4.0847 , 0.0267705,0.981177,-0.191247 --0.0733127 , 6.15567 , 4.1921 , -0.225702,0.967751,0.111882 --0.595102 , 11.2604 , 7.18888 , -0.980678,0.00166248,-0.195623 --0.140603 , 6.60052 , 4.72134 , -0.131641,-0.987191,0.0901339 --0.0637702 , 5.75096 , 4.35504 , 0.24219,-0.902851,0.355251 --0.0992136 , 5.9862 , 4.63621 , -0.502786,0.785648,0.360505 --0.0968273 , 5.86367 , 4.69685 , 0.205695,-0.951984,-0.226751 --0.106189 , 5.84034 , 4.82148 , -0.280737,-0.91188,0.299434 --0.133851 , 5.9919 , 5.07331 , -0.303208,-0.944758,0.124493 --0.149458 , 6.02483 , 5.2489 , 0.294921,0.891758,0.343203 --0.151577 , 5.93417 , 5.33624 , 0.00697667,0.846977,0.531584 --0.340887 , 7.42739 , 6.67526 , 0.113104,0.370705,0.921838 --0.348988 , 7.35837 , 6.82428 , -0.889172,0.0236615,0.456962 --0.351945 , 7.24764 , 6.94055 , 0.940025,0.100183,-0.326063 --0.322626 , 6.8814 , 6.83118 , -0.6732,0.163681,0.721118 --0.353096 , 6.99188 , 7.13997 , 0.718158,0.0392359,-0.694773 --0.350442 , 6.83304 , 7.20832 , -0.692554,-0.0999152,0.714413 --0.579398 , 8.42574 , 8.98467 , 0.396598,0.833871,-0.383888 --0.582928 , 8.28459 , 9.12586 , -0.512746,0.51238,-0.688882 --0.531523 , 7.74987 , 8.85379 , -0.30586,0.859546,-0.409426 --0.326567 , 6.1479 , 7.39423 , 0.158706,0.571808,0.80489 --0.130799 , 4.67392 , 5.96315 , -0.496641,-0.823761,0.273433 --0.326296 , 5.89632 , 7.56486 , 0.150649,0.692012,0.705991 --0.324774 , 5.76791 , 7.6468 , 0.153408,0.778716,0.608331 --0.342249 , 5.75629 , 7.87395 , -0.163257,-0.970047,-0.179877 -0.0406208 , 3.2116 , 4.82274 , -0.156541,0.333203,0.929769 -0.0556539 , 3.04995 , 4.74534 , -0.403233,-0.915086,-0.00453112 -0.0590175 , 2.96677 , 4.7689 , -0.596419,-0.700256,-0.392334 -0.0509717 , 2.94673 , 4.88055 , -0.360898,0.494857,0.790487 -0.00953255 , 3.11612 , 5.28295 , -0.162952,-0.486463,0.858371 -0.0829935 , 2.63328 , 4.6945 , -0.408013,-0.582521,0.70299 -0.0757277 , 2.61026 , 4.80287 , -0.720918,-0.652203,0.234324 -0.119622 , 2.31647 , 4.45722 , -0.790129,0.611065,0.0479025 -0.150022 , 2.10396 , 4.22389 , -0.477507,0.153251,0.86516 -0.153423 , 2.03372 , 4.2288 , 0.448459,-0.126003,-0.884877 -0.155722 , 1.97243 , 4.25021 , -0.0458832,0.512223,0.857626 -0.153773 , 1.9248 , 4.2969 , 0.337676,0.743644,0.577034 -0.150213 , 1.88933 , 4.36992 , -0.379528,-0.72479,-0.575012 -0.14311 , 1.86748 , 4.47907 , -0.76287,-0.637069,-0.110329 -0.00696077 , 2.38407 , 5.82933 , -0.0816328,-0.521969,-0.849049 --0.469158 , 4.23907 , 10.5362 , 0.920519,-0.0634323,0.385515 -0.0599952 , 2.02508 , 5.4184 , 0.244034,0.109019,0.963619 -0.0613315 , 1.95094 , 5.45776 , -0.0629916,0.387231,0.919828 -0.0576826 , 1.89375 , 5.54246 , 0.205618,-0.860735,-0.465679 -0.0332986 , 1.90657 , 5.84374 , -0.996552,-0.0124301,0.0820409 -0.0482759 , 1.78014 , 5.73845 , 0.561254,-0.265262,0.783984 -0.0451823 , 1.71504 , 5.82118 , -0.680571,0.701886,0.210188 -0.149978 , 1.33254 , 4.77092 , 0.530162,0.509972,0.67739 -0.153353 , 1.26404 , 4.77914 , 0.911854,0.270119,0.309124 -0.158494 , 1.19187 , 4.76663 , 0.80583,-0.395896,0.440345 -0.0540605 , 1.38516 , 5.94887 , 0.998409,0.0556112,0.00931767 -0.0604784 , 1.29105 , 5.92845 , 0.432516,-0.826153,0.36111 -0.057371 , 1.21811 , 6.01387 , 0.428424,-0.902554,0.0429933 -0.591972 , 6.55908 , -2.01687 , 0.0645146,0.203009,0.977049 -0.586105 , 7.0102 , -2.09349 , 0.0478674,0.210375,0.976448 -0.585664 , 8.06837 , -2.42389 , -0.016997,0.233836,0.972127 -0.577617 , 8.75376 , -2.5542 , -0.0685198,0.185185,0.980312 -0.569601 , 9.53809 , -2.69894 , -0.0629474,0.173785,0.98277 -0.558604 , 10.535 , -2.89644 , -0.0713861,0.185292,0.980087 -0.545899 , 11.6548 , -3.10146 , -0.0291102,0.140656,0.989631 -0.529107 , 12.3775 , -3.12829 , 0.253379,0.0665709,0.965074 -0.510275 , 13.9689 , -3.41273 , -0.0838797,-0.241466,-0.966777 -0.484018 , 17.3046 , -4.17339 , 0.0702144,-0.166152,-0.983597 -0.451315 , 19.5264 , -4.49033 , 0.0657317,-0.163728,-0.984313 -0.104236 , 15.2101 , 1.01299 , -0.906103,0.216274,0.363597 -0.0671601 , 15.7373 , 1.28075 , 0.758703,0.616808,0.209566 -0.0346549 , 15.3187 , 1.79769 , -0.860437,-0.509556,-9.92276e-05 -0.00714314 , 15.4926 , 2.0717 , 0.788353,0.586564,-0.185587 -0.0983354 , 12.1557 , 2.05239 , 0.0616708,-0.322965,-0.944399 --0.047956 , 15.7935 , 2.6358 , 0.750537,0.626354,-0.210657 -0.0310856 , 13.0344 , 2.57594 , 0.674263,-0.365333,-0.641796 -0.0180779 , 12.8662 , 2.77813 , 0.637747,-0.120346,-0.760786 -3.98771e-05 , 12.8536 , 2.99971 , 0.695532,-0.659161,-0.285906 -0.0684795 , 10.7594 , 2.85982 , -0.83831,-0.518977,0.167027 -0.0553119 , 10.6863 , 3.03404 , -0.899495,-0.0113439,-0.436785 -0.0439118 , 10.6005 , 3.2044 , 0.976231,0.190093,0.104101 -0.0150392 , 10.8817 , 3.45686 , -0.953722,-0.275058,-0.121476 -0.0279394 , 10.2453 , 3.49475 , 0.500014,0.627155,0.597213 -0.00631296 , 10.3839 , 3.71636 , -0.607937,-0.728475,-0.315811 --0.00882629 , 10.3737 , 3.90245 , -0.297841,-0.954158,-0.0295484 --0.00704136 , 10.0252 , 3.98766 , 0.318729,-0.603088,0.73123 --0.0427191 , 10.3993 , 4.2945 , -0.598432,0.586752,-0.545529 --0.0831965 , 10.8325 , 4.63759 , 0.207895,-0.947493,0.242977 --0.100283 , 10.8232 , 4.84091 , -0.245725,0.963607,0.105264 --0.117107 , 10.8108 , 5.04494 , 0.0829933,0.948726,0.305011 --0.125263 , 10.6464 , 5.19011 , 0.514947,0.384651,0.766077 --0.105729 , 10.0466 , 5.1489 , 0.334565,0.305419,-0.891508 --0.0989585 , 9.6812 , 5.18876 , -0.12113,-0.906117,0.405314 --0.128248 , 9.87863 , 5.47739 , -0.0932674,0.354643,-0.930339 --0.239671 , 11.2628 , 6.35325 , -0.0610376,0.962707,-0.263571 -0.0917747 , 6.21701 , 4.03657 , -0.162982,-0.9784,0.127167 -0.086969 , 6.11905 , 4.1159 , 0.356088,0.929752,-0.0936099 --0.0378756 , 7.67255 , 5.103 , -0.61441,0.220588,0.757523 -0.0601184 , 6.18062 , 4.41617 , -0.0405074,0.968279,0.246568 -0.0520484 , 6.1376 , 4.52848 , -0.226365,0.8951,0.384128 -0.0530361 , 5.97293 , 4.56668 , -0.142316,0.790855,0.595227 -0.0380991 , 6.01899 , 4.73545 , 0.503622,-0.819638,-0.273052 -0.0273806 , 5.99538 , 4.8622 , 0.49384,-0.869369,-0.0179072 -0.0130063 , 6.01669 , 5.02376 , -0.144863,0.984504,-0.0988256 -0.00861487 , 5.92975 , 5.11111 , -0.214536,-0.964262,-0.155475 --0.00611058 , 5.95378 , 5.28036 , 0.00697667,0.846977,0.531584 --0.0101831 , 5.85466 , 5.36 , -0.0778548,0.786646,0.612476 --0.0154132 , 5.76193 , 5.44377 , -0.0778548,0.786646,0.612476 --0.625064 , 11.8913 , 10.7224 , -0.661716,-0.69434,-0.282885 --0.216044 , 7.50418 , 7.27583 , 0.871159,-0.4198,-0.254657 --0.205523 , 7.2158 , 7.2407 , 0.357702,-0.0679036,-0.931364 --0.365984 , 8.56746 , 8.71704 , -0.166291,0.974447,0.151 --0.251113 , 7.28885 , 7.76147 , 0.978625,-0.0115338,-0.20533 --0.180207 , 6.46317 , 7.17893 , 0.0250034,0.376558,0.926056 --0.319932 , 7.53413 , 8.50219 , -0.710506,0.42402,-0.561594 --0.152777 , 5.91025 , 7.03366 , -0.637309,-0.0789931,-0.766549 --0.18105 , 5.99085 , 7.33786 , 0.486654,0.790143,0.372616 --0.0288252 , 4.60789 , 5.9795 , -0.496641,-0.823761,0.273433 --0.214023 , 5.94601 , 7.74609 , 0.0807041,0.753127,0.652907 --0.208419 , 5.7464 , 7.74297 , 0.108879,0.78877,0.604968 -0.130782 , 3.06953 , 4.57486 , -0.53523,-0.667938,-0.517096 -0.129726 , 2.99448 , 4.60695 , 0.611281,0.612397,0.501304 -0.127636 , 2.93211 , 4.65336 , -0.609647,-0.608616,-0.507856 -0.108621 , 2.9822 , 4.86204 , -0.133134,0.738471,0.661011 -0.0677796 , 3.17205 , 5.28781 , -0.113887,0.53829,0.835029 -0.067388 , 3.08648 , 5.32068 , -0.111874,-0.604418,0.788773 -0.121186 , 2.66668 , 4.82013 , 0.72913,0.592986,-0.341668 -0.129284 , 2.53838 , 4.75844 , -0.829676,-0.539205,0.144553 -0.116398 , 2.53712 , 4.90927 , -0.739847,-0.570801,0.356109 -0.18411 , 2.08225 , 4.25117 , 0.652277,-0.0346939,-0.757186 -0.186342 , 2.01117 , 4.25567 , 0.331234,-0.217959,-0.918029 -0.185777 , 1.95039 , 4.27614 , -0.117534,0.477837,0.87055 -0.183861 , 1.89766 , 4.3135 , -0.381993,-0.691912,-0.61265 -0.179131 , 1.86135 , 4.38611 , -0.427339,-0.687575,-0.587046 -0.170853 , 1.83868 , 4.49494 , -0.769669,-0.619038,-0.156211 --0.291549 , 3.82979 , 9.34256 , 0.360047,-0.837484,0.411081 -0.0860642 , 2.07128 , 5.42399 , 0.66811,0.196175,0.717735 -0.0866207 , 1.98739 , 5.43568 , 0.244495,0.265124,0.932701 -0.0846262 , 1.91684 , 5.48333 , 0.363679,-0.633051,-0.683362 -0.0677041 , 1.90083 , 5.68993 , 0.989879,-0.140239,-0.0217561 -0.0622744 , 1.84069 , 5.78369 , -0.961178,0.098875,-0.257607 -0.0659267 , 1.74287 , 5.76227 , 0.445275,-0.381468,0.81007 -0.147448 , 1.40642 , 4.90628 , -0.474059,0.509678,-0.717981 -0.162405 , 1.29493 , 4.76153 , -0.686997,-0.0239259,-0.726267 -0.160979 , 1.2345 , 4.79779 , -0.855647,0.45481,0.247013 -0.164721 , 1.15945 , 4.77483 , 0.762509,-0.607185,0.223397 -0.0575077 , 1.34827 , 5.98798 , -0.270664,0.426976,0.862805 -0.0458988 , 1.29066 , 6.15236 , -0.205705,0.959088,-0.194515 -0.796977 , 6.5981 , -2.08534 , 0.0720076,0.200227,0.9771 -0.812542 , 7.2201 , -2.2448 , 0.0241334,0.227847,0.973398 -0.822725 , 7.75955 , -2.34254 , -0.00901112,0.209616,0.977742 -0.835764 , 8.40437 , -2.46593 , -0.0794996,0.191313,0.978304 -0.851467 , 9.19458 , -2.62492 , -0.0639093,0.184742,0.980707 -0.866854 , 10.0391 , -2.77566 , -0.0654034,0.177969,0.98186 -0.883911 , 11.0045 , -2.93988 , -0.0623431,0.162825,0.984683 -0.910313 , 12.3359 , -3.1976 , -0.0179843,0.160294,0.986905 -0.938609 , 13.878 , -3.47613 , 0.0838798,0.241466,0.966777 -0.979074 , 15.968 , -3.8697 , -0.0424212,0.21088,0.976591 -1.02537 , 18.5164 , -4.32153 , -0.0631416,0.164635,0.984332 -1.27244 , 32.8256 , -6.71258 , -0.0807923,0.162344,0.983421 -1.22716 , 33.1816 , -6.19535 , -0.0807923,0.162344,0.983421 -0.438709 , 13.8428 , 2.11147 , 0.700211,-0.542633,-0.463955 -0.403917 , 12.9623 , 2.48637 , -0.903513,0.356289,0.238165 -0.37662 , 13.7581 , 2.81485 , 0.700211,-0.542633,-0.463955 -0.33216 , 15.8119 , 3.3609 , -0.916004,-0.318329,0.244138 -0.311618 , 15.5119 , 3.58747 , -0.920104,-0.219147,0.324628 -0.362825 , 10.166 , 2.86878 , 0.755364,0.600424,0.262519 -0.349912 , 9.96645 , 3.0061 , -0.722004,-0.666506,-0.185689 -0.315657 , 11.0336 , 3.41834 , -0.0683682,-0.60581,0.792666 -0.31454 , 10.1832 , 3.4111 , -0.733996,-0.633103,-0.245825 -0.297458 , 10.2077 , 3.6001 , -0.286642,0.9084,-0.304378 -0.287346 , 9.92995 , 3.70803 , -0.48737,-0.866502,-0.107914 -0.269146 , 9.98712 , 3.90623 , 0.650919,0.435367,0.6219 -0.250569 , 10.1071 , 4.12834 , -0.28747,0.735056,-0.614047 -0.208426 , 10.9994 , 4.61525 , -0.49452,0.722617,-0.482985 -0.119887 , 13.4138 , 5.67725 , 0.522018,-0.799214,0.297915 -0.181666 , 10.6622 , 4.90815 , -0.316533,-0.807732,-0.497369 -0.155495 , 10.8808 , 5.20118 , -0.316533,-0.807732,-0.497369 -0.182271 , 9.55986 , 4.86882 , 0.296217,0.748379,-0.593451 -0.147538 , 10.0596 , 5.27605 , -0.100524,-0.789084,0.606004 -0.149982 , 9.52888 , 5.23831 , -0.21099,-0.75739,0.617935 -0.0793925 , 10.8433 , 6.05968 , -0.903834,-0.316167,0.288308 -0.0621001 , 10.7634 , 6.24646 , -0.852936,-0.301994,0.425792 -0.246903 , 6.10365 , 4.05543 , 0.334226,0.574357,0.747266 -0.234239 , 6.11977 , 4.19403 , 0.560395,0.827253,0.0401353 -0.236755 , 5.83721 , 4.16727 , 0.399761,0.318649,0.85945 -0.208978 , 6.15286 , 4.4805 , -0.417308,0.906813,-0.0595389 -0.202778 , 6.03124 , 4.54544 , 0.0540854,0.908033,0.415392 -0.185984 , 6.12115 , 4.74097 , 0.500127,-0.863622,-0.0634883 -0.162547 , 6.29656 , 5.0014 , 0.653791,-0.739414,-0.1607 -0.170105 , 5.94639 , 4.91309 , 0.376186,-0.855792,-0.355111 -0.168807 , 5.74803 , 4.91791 , 0.325665,0.90553,-0.271951 -0.13818 , 6.02456 , 5.2671 , -0.013244,0.9177,0.397053 -0.134087 , 5.88578 , 5.31767 , -0.116265,0.859087,0.49845 -0.12372 , 5.82579 , 5.42645 , -0.116265,0.859087,0.49845 --0.0810787 , 8.50896 , 7.79236 , -0.54542,0.368665,-0.752731 --0.0281286 , 7.50007 , 7.17656 , -0.698558,-0.37704,0.608159 --0.0615106 , 7.67653 , 7.55175 , -0.357754,-0.450749,0.817825 --0.0267035 , 6.97865 , 7.14703 , -0.133048,-0.128565,0.982736 --0.0464993 , 6.97939 , 7.36515 , 0.133048,0.128565,-0.982736 --0.0322308 , 6.57566 , 7.19384 , -0.0182975,-0.13424,0.99078 --0.0392061 , 6.43168 , 7.26654 , 0.211239,-0.0178676,0.977271 --0.0168137 , 5.97116 , 7.00341 , 0.255378,0.0530642,0.965384 --0.238283 , 8.09984 , 9.5337 , -0.674001,-0.728217,0.124187 --0.0545197 , 5.95677 , 7.42107 , 0.429627,0.815882,0.386986 -0.069606 , 4.53944 , 5.99509 , 0.457682,0.802439,-0.382908 --0.0714724 , 5.72401 , 7.6061 , 0.40165,-0.0599515,0.913829 -0.200102 , 3.05713 , 4.50162 , 0.434749,0.63371,0.639848 -0.19387 , 3.00871 , 4.56472 , 0.434749,0.63371,0.639848 -0.184067 , 2.99416 , 4.67541 , -0.541452,-0.629154,-0.557669 -0.167587 , 3.02807 , 4.85977 , -0.121351,0.849095,0.514113 -0.162442 , 2.96618 , 4.91499 , -0.198173,0.827251,0.525722 -0.158099 , 2.89792 , 4.96072 , 0.251934,-0.877813,-0.407399 -0.145195 , 2.89838 , 5.11476 , 0.515074,-0.756197,-0.403565 -0.140301 , 2.83179 , 5.16788 , -0.0588742,-0.93751,0.342941 -0.17952 , 2.46506 , 4.71326 , 0.66715,0.217954,0.712325 -0.172128 , 2.42576 , 4.79364 , 0.77828,0.504765,0.373487 -0.217749 , 2.05857 , 4.27855 , 0.674773,0.00182269,-0.738023 -0.218317 , 1.98375 , 4.27319 , -0.341277,0.275212,0.89877 -0.215615 , 1.92235 , 4.29312 , -0.144493,0.452296,0.880085 -0.212536 , 1.86875 , 4.32998 , 0.370632,0.683308,0.629065 -0.205662 , 1.83183 , 4.40215 , 0.556176,0.729997,0.397206 -0.197897 , 1.80093 , 4.49222 , 0.685432,0.700912,0.197245 --0.353906 , 4.31927 , 10.7314 , 0.921878,0.0616299,0.382547 -0.110726 , 2.04514 , 5.46935 , -0.0875056,0.394112,0.914887 -0.112078 , 1.94884 , 5.45255 , -0.0365654,0.621593,0.782486 -0.107707 , 1.88172 , 5.50881 , 0.0117583,0.953742,0.300398 -0.0656452 , 1.95197 , 5.9797 , 0.439292,-0.898173,0.0175651 -0.0837827 , 1.79051 , 5.77011 , 0.561253,-0.265262,0.783984 -0.0848373 , 1.69511 , 5.7573 , -0.00965261,-0.711381,0.70274 -0.163976 , 1.35683 , 4.85919 , -0.4423,0.533902,-0.720638 -0.171474 , 1.26206 , 4.77097 , -0.565373,0.0542775,-0.823047 -0.165254 , 1.21071 , 4.84531 , 0.411997,0.217278,0.8849 -0.0719357 , 1.37303 , 5.89147 , -0.966421,-0.221065,-0.130999 -0.0701449 , 1.28686 , 5.90967 , -0.120331,0.631313,-0.766136 -0.0605068 , 1.21844 , 6.01414 , 0.407144,-0.913213,0.0166171 -0.974849 , 6.12173 , -2.02628 , 0.0313102,0.189632,0.981356 -0.992128 , 6.49598 , -2.08608 , 0.0257628,0.182124,0.982938 -1.01227 , 6.9266 , -2.15953 , 0.0243934,0.196384,0.980224 -1.03912 , 7.46242 , -2.26497 , 0.00817676,0.210492,0.977561 -1.063 , 7.98541 , -2.34461 , -0.0604135,0.181707,0.981495 -1.10012 , 8.71598 , -2.49194 , -0.0594868,0.199732,0.978043 -1.14042 , 9.52776 , -2.64421 , -0.060483,0.184082,0.981048 -1.1876 , 10.5055 , -2.82943 , -0.0630729,0.181671,0.981335 -1.24161 , 11.6148 , -3.02538 , -0.0416982,0.162229,0.985872 -1.30852 , 12.999 , -3.27392 , -0.0168872,0.179452,0.983622 -1.39163 , 14.7373 , -3.58486 , -0.0227904,0.186247,0.982239 -1.50799 , 17.1113 , -4.02354 , -0.0700682,0.174981,0.982075 -1.65431 , 20.1575 , -4.56504 , -0.061365,0.17127,0.983311 -2.22145 , 32.8958 , -6.34474 , -0.137598,0.168488,0.976053 -0.716143 , 11.2573 , 2.41683 , 0.0129768,0.944428,0.328462 -0.743342 , 13.8242 , 2.97916 , 0.700211,-0.542633,-0.463955 -0.713235 , 13.3943 , 3.15029 , -0.176312,0.653355,0.736235 -0.654159 , 10.8262 , 2.92453 , -0.192437,0.981029,0.0234681 -0.626575 , 10.0273 , 2.95633 , 0.80799,-0.3084,-0.502038 -0.609025 , 9.93377 , 3.11265 , 0.807989,-0.3084,-0.502039 -0.594353 , 10.1692 , 3.34333 , 0.689409,0.71225,-0.131966 -0.573282 , 9.70103 , 3.40709 , -0.185234,0.951937,0.243934 -0.557059 , 9.73583 , 3.59096 , 0.640668,0.412458,0.647629 -0.54392 , 10.4881 , 3.985 , -0.178128,0.905478,-0.385202 -0.525525 , 10.5021 , 4.18225 , 0.297746,-0.85462,0.425408 -0.507492 , 11.2256 , 4.6139 , 0.665164,-0.249993,0.703606 -0.488201 , 10.7458 , 4.65924 , -0.740071,0.038387,-0.671432 -0.469698 , 10.4931 , 4.77147 , -0.700024,-0.714115,-0.0024172 -0.452871 , 9.98902 , 4.77859 , 0.166861,-0.275625,0.946672 -0.438259 , 9.4496 , 4.7546 , 0.54624,-0.305938,0.779759 -0.420963 , 9.41139 , 4.92466 , 0.415138,-0.35861,0.836098 -0.397485 , 9.94503 , 5.35159 , -0.0285929,0.978231,0.205537 -0.380105 , 9.80442 , 5.48895 , 0.0939448,-0.924726,0.368858 -0.359888 , 9.88726 , 5.73249 , 0.0939448,-0.924726,0.368858 -0.404744 , 6.06505 , 3.987 , -0.27514,-0.164035,-0.947307 -0.393667 , 6.00343 , 4.08201 , -0.240548,-0.968214,-0.0685413 -0.381985 , 5.98457 , 4.20011 , 0.315741,0.909649,-0.2699 -0.367604 , 6.09338 , 4.39341 , -0.314053,0.922562,-0.224165 -0.348076 , 6.34243 , 4.67912 , 0.690617,-0.689786,0.217357 -0.344135 , 5.98928 , 4.60327 , 0.126394,0.938826,0.32036 -0.323418 , 6.23633 , 4.90323 , -0.833306,0.202852,0.51425 -0.308337 , 6.28388 , 5.08409 , -0.86582,0.317498,0.386718 -0.306248 , 5.92679 , 4.98635 , 0.375504,-0.277722,-0.884233 -0.290432 , 5.98612 , 5.17756 , -0.2492,0.966739,0.0575834 -0.0554082 , 11.4984 , 9.48894 , -0.935787,0.334056,0.112733 -0.263798 , 5.90906 , 5.42785 , 0.277355,0.71758,0.638869 -0.130406 , 8.50996 , 7.69523 , -0.490779,0.559421,-0.66797 -0.111694 , 8.43844 , 7.87527 , -0.490779,0.559421,-0.66797 --0.0348805 , 10.859 , 10.2253 , -0.924936,0.353568,0.139584 -0.138239 , 7.07371 , 7.14381 , 0.426067,0.782352,-0.454304 -0.133903 , 6.79075 , 7.09679 , 0.709705,-0.0117871,0.704401 -0.106278 , 6.9141 , 7.43054 , 0.525577,-0.0859621,-0.846392 -0.114424 , 6.4406 , 7.18408 , -0.0487527,-0.0416199,-0.997943 -0.11732 , 6.09689 , 7.04534 , -0.363782,-0.0843659,0.927656 -0.103988 , 5.99056 , 7.14505 , -0.430634,0.294356,0.853176 -0.104179 , 5.71009 , 7.0496 , -0.456336,0.226749,0.860431 -0.0905839 , 5.62972 , 7.17281 , 0.632441,-0.48843,-0.601211 -0.0537376 , 5.82379 , 7.62373 , 0.47363,-0.104615,0.874489 -0.0587237 , 5.50012 , 7.46254 , 0.785542,0.138364,0.603141 -0.0575419 , 5.27036 , 7.4022 , -0.167225,0.407306,0.897851 -0.251865 , 2.97031 , 4.58573 , 0.434749,0.63371,0.639848 -0.244993 , 2.91383 , 4.63961 , 0.434749,0.63371,0.639848 -0.225536 , 2.97087 , 4.85593 , -0.0130165,0.945384,0.325699 -0.215551 , 2.94232 , 4.9597 , 0.251934,-0.877813,-0.407399 -0.0288693 , 4.45124 , 7.43159 , -0.642768,0.519438,-0.563057 -0.196606 , 2.85695 , 5.1335 , 0.739927,-0.665849,-0.0956694 -0.218293 , 2.55874 , 4.80086 , -0.270977,-0.610521,0.744201 -0.220018 , 2.43237 , 4.73579 , -0.559904,-0.555134,-0.615088 -0.214553 , 2.37268 , 4.78093 , 0.0394931,0.936846,0.347506 -0.245889 , 2.05295 , 4.34082 , -0.797253,-0.15534,0.583316 -0.247897 , 1.95482 , 4.29066 , -0.201059,0.461545,0.864032 -0.243076 , 1.89773 , 4.31872 , 0.233655,-0.430192,-0.871975 -0.23906 , 1.83925 , 4.34612 , -0.312382,-0.659813,-0.683421 -0.231491 , 1.79837 , 4.40855 , 0.346784,0.680247,0.645759 -0.219425 , 1.77735 , 4.52587 , -0.679993,-0.719005,-0.14367 -0.153736 , 2.02326 , 5.30882 , 0.492834,0.602871,0.627424 -0.143185 , 1.97293 , 5.40318 , 0.209183,0.621684,0.754819 -0.135871 , 1.90657 , 5.45956 , 0.278221,0.515562,0.810426 -0.121144 , 1.86784 , 5.5998 , -0.36347,-0.913203,-0.184254 -0.085432 , 1.90534 , 5.98626 , -0.46952,-0.592631,0.654477 -0.106788 , 1.72473 , 5.70845 , -0.259256,-0.404317,0.877106 -0.0819633 , 1.70889 , 5.96222 , 0.905441,-0.25003,-0.343018 -0.177626 , 1.3078 , 4.81136 , -0.893886,-0.313711,0.320239 -0.173545 , 1.24391 , 4.83792 , -0.851914,0.522356,-0.0372341 -0.179706 , 1.15002 , 4.73716 , -0.64346,0.16431,-0.747637 -0.0686162 , 1.34682 , 5.97906 , -0.678986,0.367997,0.63526 -0.0524223 , 1.28616 , 6.13341 , -0.330498,0.941053,0.0720419 -0.820848 , 1.80591 , -1.22576 , -0.0751089,0.0437343,0.996216 -0.82616 , 1.87318 , -1.23963 , -0.00748956,0.0339753,0.999395 -0.829243 , 1.93099 , -1.23591 , -0.00748957,0.0339753,0.999395 -1.09534 , 5.28466 , -1.8595 , -0.0439158,0.168201,0.984774 -1.1166 , 5.56992 , -1.90281 , -0.028852,0.167774,0.985403 -1.14072 , 5.88394 , -1.95097 , -0.0336331,0.183905,0.982368 -1.16844 , 6.23741 , -2.00735 , -0.0284763,0.175116,0.984136 -1.20281 , 6.67484 , -2.09176 , -0.0130934,0.18483,0.982683 -1.24166 , 7.16128 , -2.1828 , -0.0379654,0.192779,0.980507 -1.29048 , 7.76244 , -2.30671 , -0.0377684,0.179692,0.982998 -1.33856 , 8.37872 , -2.41435 , -0.0406011,0.190179,0.980909 -1.39955 , 9.13989 , -2.55787 , -0.0450719,0.188877,0.980966 -1.46604 , 9.99186 , -2.70801 , -0.0478485,0.184089,0.981744 -1.54927 , 11.0482 , -2.90163 , -0.0485076,0.177235,0.982973 -1.64393 , 12.2556 , -3.10826 , -0.0388758,0.181682,0.982589 -1.76687 , 13.8232 , -3.3886 , -0.0345426,0.180327,0.983 -1.93043 , 15.8994 , -3.76791 , -0.0595417,0.185034,0.980927 -2.13242 , 18.4812 , -4.21722 , -0.0690202,0.164893,0.983894 -3.65058 , 38.596 , -7.1855 , 0.00525864,0.140935,0.990005 -1.06632 , 11.0623 , 1.95052 , -0.333993,0.873874,-0.35326 -1.04551 , 11.0259 , 2.13561 , -0.15456,-0.98792,-0.0112309 -1.02717 , 11.0459 , 2.32667 , -0.440238,0.811893,0.383432 -1.00806 , 11.0329 , 2.51475 , -0.137575,0.922151,0.36154 -0.972691 , 10.6702 , 2.64922 , -0.342781,0.930341,0.130257 -0.965013 , 10.917 , 2.87714 , -0.236677,0.970929,-0.0357945 -0.949107 , 10.9928 , 3.08188 , -0.30127,0.950446,-0.0767411 -0.9274 , 10.9469 , 3.26537 , -0.0356064,0.991218,-0.127351 -0.901995 , 10.7806 , 3.42139 , -0.835387,0.532323,0.136971 -0.862438 , 10.214 , 3.47457 , -0.768468,0.250449,0.58884 -0.832677 , 9.87174 , 3.56733 , 0.198855,-0.959817,0.198012 -0.838392 , 10.5962 , 3.95088 , 0.255682,-0.0753863,0.963817 -0.808199 , 10.2671 , 4.04567 , 0.0881535,-0.594859,0.798981 -0.886951 , 13.6408 , 5.317 , 0.663594,0.6315,0.401062 -0.873419 , 14.1053 , 5.73131 , 0.663594,0.6315,0.401062 -0.842726 , 13.9467 , 5.94348 , 0.663593,0.631501,0.401062 -0.817084 , 14.0096 , 6.23645 , -0.598427,-0.226837,-0.768394 -0.689833 , 9.22858 , 4.60268 , -0.501599,-0.130701,-0.85517 -0.668886 , 9.05545 , 4.71073 , -0.501599,-0.130701,-0.85517 -0.66483 , 9.88745 , 5.25664 , -0.271611,-0.867782,-0.416151 -0.645861 , 9.96756 , 5.4936 , 0.0821453,0.303964,0.949135 -0.623668 , 9.8352 , 5.63459 , 0.0821454,0.303964,0.949135 -0.563038 , 6.03901 , 3.92902 , 0.378308,0.893487,-0.242 -0.549892 , 5.9435 , 4.00512 , 0.164809,0.378506,0.910808 -0.539885 , 6.35633 , 4.35714 , 0.633797,-0.591991,0.497844 -0.524854 , 6.0975 , 4.34786 , 0.267602,0.954539,0.13132 -0.512964 , 6.7019 , 4.84098 , -0.807205,0.286451,-0.516106 -0.497622 , 6.93277 , 5.13523 , 0.889316,-0.44973,-0.082827 -0.479389 , 7.48318 , 5.64932 , 0.300436,0.382905,-0.873568 -0.468453 , 6.27915 , 5.02462 , -0.0397162,0.655765,0.75392 -0.454332 , 6.20843 , 5.12784 , 0.438746,-0.0172749,-0.898445 -0.442299 , 5.93429 , 5.08381 , -0.418573,0.357701,-0.834774 -0.427722 , 5.83873 , 5.163 , -0.243233,0.924588,-0.293216 -0.331588 , 10.881 , 9.20356 , -0.348627,-0.920479,0.176571 -0.29966 , 10.9642 , 9.56652 , 0.348627,0.920479,-0.176571 -0.26215 , 11.2922 , 10.1453 , -0.878161,0.382651,0.287074 -0.238447 , 10.9114 , 10.1457 , -0.924936,0.353568,0.139584 -0.287371 , 8.02364 , 7.90433 , 0.337742,-0.303966,0.890806 -0.30264 , 6.74773 , 6.97445 , 0.454471,0.201602,-0.867648 -0.278926 , 6.83161 , 7.26447 , -0.438556,-0.860561,0.259042 -0.270034 , 6.46625 , 7.12379 , 0.487849,0.0107582,-0.872862 -0.26048 , 6.19126 , 7.05834 , -0.377797,-0.0352567,0.925217 -0.246867 , 6.0244 , 7.09388 , -0.432306,0.431279,0.791903 -0.232267 , 5.87736 , 7.14779 , 0.602638,-0.248136,-0.758457 -0.21512 , 5.79626 , 7.27337 , -0.795543,0.140664,0.589343 -0.190433 , 5.8361 , 7.54243 , -0.536485,-0.264259,-0.801468 -0.184838 , 5.5385 , 7.41321 , -0.382118,0.421458,0.822411 -0.172436 , 5.37691 , 7.44014 , -0.0670258,0.286641,0.955691 -0.31535 , 2.98654 , 4.55236 , 0.434749,0.63371,0.639848 -0.308989 , 2.90062 , 4.56626 , 0.434749,0.63371,0.639848 -0.168322 , 4.51376 , 6.96223 , 0.901539,-0.0724916,0.426581 -0.258138 , 3.18854 , 5.2553 , -0.0025384,0.590859,0.806771 -0.246033 , 3.14308 , 5.34597 , -0.0633088,0.546523,0.835048 -0.238189 , 3.05105 , 5.36916 , 0.0404456,0.482501,0.874961 -0.273405 , 2.53691 , 4.70064 , 0.253424,-0.236095,0.938102 -0.27056 , 2.43244 , 4.66985 , 0.0818894,0.466693,0.88062 -0.256039 , 2.42736 , 4.81043 , -0.0170756,0.980517,0.19569 -0.249374 , 2.35692 , 4.83776 , 0.729604,0.224397,-0.646006 -0.274989 , 2.03714 , 4.38551 , -0.795769,-0.286943,0.533306 -0.2751 , 1.92932 , 4.31674 , -0.240861,0.44149,0.864334 -0.269341 , 1.86735 , 4.33535 , -0.245951,0.388368,0.888076 -0.262224 , 1.81344 , 4.37094 , -0.192806,-0.694524,-0.693154 -0.254694 , 1.76744 , 4.42394 , 0.283825,0.686853,0.669086 -0.241213 , 1.74965 , 4.55009 , -0.691534,-0.716024,-0.0953445 -0.172143 , 2.01354 , 5.40048 , 0.600743,0.725664,0.335439 -0.158729 , 1.96477 , 5.50403 , -0.499366,-0.354534,-0.790531 -0.157032 , 1.86077 , 5.45657 , -0.386339,-0.484342,-0.784956 -0.105279 , 1.9695 , 6.04068 , -0.359197,-0.701246,0.615818 -0.121742 , 1.78617 , 5.76415 , 0.683195,-0.0122608,0.730133 -0.119647 , 1.68338 , 5.72204 , 0.259256,0.404317,-0.877106 -0.0881048 , 1.68413 , 6.04269 , -0.633549,0.0763606,0.769925 -0.181133 , 1.28634 , 4.86919 , 0.497571,0.032289,0.866822 -0.179759 , 1.20547 , 4.82723 , 0.117297,0.48517,0.866517 -0.183536 , 1.11503 , 4.73517 , 0.620793,0.0302176,0.783392 -0.0708791 , 1.30098 , 5.97859 , -0.86378,-0.136492,-0.48503 -0.061713 , 1.22023 , 6.0242 , 0.407144,-0.913213,0.0166175 -0.876355 , 1.78678 , -1.24156 , -0.076006,0.0647999,0.995 -0.880103 , 1.8374 , -1.23113 , 0.0462549,-0.0694184,-0.996515 -0.886343 , 1.90003 , -1.23587 , -0.00748957,0.0339753,0.999395 -0.890344 , 1.95778 , -1.23134 , -0.0287381,0.0633441,0.997578 -1.18557 , 4.63903 , -1.73822 , -0.0689399,0.182222,0.980838 -1.21024 , 4.87315 , -1.77579 , -0.0553187,0.17456,0.983091 -1.23823 , 5.13629 , -1.82141 , -0.0497165,0.172172,0.983812 -1.26655 , 5.40117 , -1.85826 , -0.0383111,0.168405,0.984973 -1.29865 , 5.7049 , -1.90596 , -0.014633,0.178618,0.98381 -1.34292 , 6.09905 , -1.98962 , -0.0345818,0.190467,0.981084 -1.3886 , 6.51576 , -2.06923 , 0.0261496,-0.192921,-0.980866 -1.43718 , 6.96447 , -2.14814 , -0.019665,0.190192,0.98155 -1.49953 , 7.52556 , -2.26158 , -0.0262417,0.183531,0.982664 -1.56093 , 8.09287 , -2.35635 , -0.0284278,0.183584,0.982593 -1.64115 , 8.82153 , -2.49685 , -0.0318313,0.187365,0.981775 -1.72812 , 9.62187 , -2.63833 , -0.0410341,0.179563,0.98289 -1.83336 , 10.5886 , -2.81213 , -0.0520404,0.18442,0.981469 -1.9483 , 11.6667 , -2.98959 , -0.0560937,0.174937,0.98298 -2.10908 , 13.1409 , -3.25978 , -0.06229,0.182976,0.981142 -2.30783 , 14.968 , -3.58679 , -0.0598087,0.190877,0.97979 -2.58064 , 17.4682 , -4.04592 , -0.0740876,0.17144,0.982405 -2.87242 , 20.1996 , -4.47721 , -0.0702866,0.172752,0.982454 -4.55869 , 36.1342 , -6.89306 , -0.0807924,0.162344,0.983421 -4.60822 , 37.1988 , -6.45386 , -0.0295974,0.179288,0.983351 -1.40185 , 11.0672 , 1.70139 , -0.197025,0.930372,-0.309175 -1.378 , 11.0168 , 1.88565 , -0.197025,0.930372,-0.309175 -1.3691 , 11.15 , 2.08678 , 0.197025,-0.930372,0.309175 -1.37446 , 11.469 , 2.31404 , 0.513379,-0.852689,-0.0967679 -1.32865 , 11.15 , 2.46932 , -0.429394,0.858146,0.281438 -1.2974 , 10.9974 , 2.63868 , -0.377359,0.808638,0.451336 -1.27712 , 10.9892 , 2.82806 , 0.130242,-0.968418,-0.212613 -1.25169 , 10.919 , 3.00648 , -0.125094,0.990974,-0.0481901 -1.23002 , 10.8937 , 3.19323 , -0.00129247,0.98558,0.169205 -1.28244 , 11.987 , 3.62729 , 0.839439,-0.445782,0.310838 -1.23066 , 11.534 , 3.73262 , -0.802361,0.545738,-0.241635 -1.18149 , 11.0905 , 3.82544 , -0.828741,0.548131,-0.112871 -1.17259 , 11.2919 , 4.08188 , 0.816442,-0.445411,0.367465 -1.08095 , 10.0999 , 3.93578 , 0.541271,0.604846,-0.584113 -1.47939 , 17.4409 , 6.43029 , -0.938062,0.140904,0.316521 -1.25032 , 13.8989 , 5.57688 , 0.663594,0.6315,0.401062 -0.990777 , 9.52455 , 4.29666 , -0.419652,0.731434,-0.537491 -0.969815 , 9.48656 , 4.46341 , -0.184413,0.871027,-0.455306 -0.948675 , 9.43622 , 4.62615 , -0.187772,0.975929,-0.110925 -0.966188 , 10.2236 , 5.13482 , 0.182546,0.748921,0.63702 -0.789583 , 6.75021 , 3.83359 , -0.0626323,0.997707,0.0256438 -0.776088 , 6.73807 , 3.96165 , 0.201785,-0.951578,-0.231912 -0.870856 , 9.45817 , 5.38899 , 0.113334,0.685726,-0.718982 -0.737747 , 6.49919 , 4.11697 , 0.700941,-0.621662,-0.349598 -0.711271 , 6.16218 , 4.07681 , -0.867263,0.27771,-0.413197 -0.685384 , 5.79262 , 4.00704 , -0.532257,-0.297547,0.792571 -0.675782 , 5.87933 , 4.1806 , 0.722635,0.651727,-0.230327 -0.687427 , 6.79139 , 4.84251 , 0.907324,-0.217246,0.359953 -0.667111 , 6.61335 , 4.88706 , -0.840008,0.456943,0.292558 -0.793616 , 12.6621 , 8.86791 , 0.814614,-0.36962,-0.446972 -0.760352 , 12.5838 , 9.11953 , -0.945451,0.317138,0.0744675 -0.605581 , 5.89379 , 4.86069 , -0.512155,-0.469947,-0.718921 -0.591392 , 5.99063 , 5.07253 , 0.575215,-0.335267,0.746139 -0.580024 , 6.28339 , 5.43686 , 0.457402,-0.861916,-0.218823 -0.583633 , 8.37015 , 7.18773 , 0.00958721,-0.435863,0.899962 -0.585178 , 11.9209 , 10.2135 , -0.878161,0.382651,0.287074 -0.548723 , 11.4197 , 10.1347 , -0.878161,0.382651,0.287074 -0.514007 , 11.2838 , 10.3451 , -0.878161,0.382651,0.287074 -0.479799 , 11.1815 , 10.5864 , 0.313344,-0.597738,0.737919 -0.44523 , 11.0518 , 10.8067 , 0.313344,-0.597738,0.737919 -0.443623 , 7.05641 , 7.39496 , 0.289526,-0.556346,-0.77888 -0.423191 , 6.8234 , 7.3922 , -0.222263,-0.014333,0.974881 -0.400692 , 6.74035 , 7.53242 , -0.413413,0.0638578,0.908302 -0.382814 , 6.44032 , 7.44775 , 0.623199,0.11204,-0.773996 -0.36757 , 6.06971 , 7.27416 , 0.365229,-0.335173,-0.868486 -0.350305 , 5.86786 , 7.2684 , -0.311913,0.403248,0.860291 -0.330228 , 5.77853 , 7.38628 , -0.222449,-0.695745,-0.682975 -0.313123 , 5.59075 , 7.38773 , -0.0040926,0.32873,0.944415 -0.294708 , 5.44833 , 7.43909 , 0.187004,-0.00142402,0.982358 -0.278813 , 5.25688 , 7.4243 , -0.40144,-0.503397,-0.765139 -0.289543 , 4.54573 , 6.70892 , -0.337492,0.819783,-0.462661 -0.260257 , 4.68729 , 7.11326 , -0.214853,0.975898,0.0382364 -0.323585 , 3.24942 , 5.27747 , 0.0521226,0.61382,0.787724 -0.312922 , 3.16443 , 5.31098 , 0.0719927,0.553662,0.829624 -0.299109 , 3.10643 , 5.38473 , 0.196491,0.438854,0.876811 -0.197932 , 4.17083 , 7.26463 , 0.843685,0.408117,0.348764 -0.19074 , 3.95345 , 7.15037 , 0.654816,0.50799,0.559609 -0.307484 , 2.40242 , 4.70097 , -0.22161,-0.367926,-0.903061 -0.287542 , 2.44516 , 4.92881 , -0.616029,-0.0437334,0.786509 -0.2818 , 2.33964 , 4.89455 , 0.691749,0.335725,-0.639353 -0.302653 , 2.00963 , 4.4126 , 0.777671,0.315168,-0.543964 -0.300884 , 1.90206 , 4.34281 , 0.566557,-0.135778,-0.81276 -0.293224 , 1.84041 , 4.36068 , -0.204751,0.394563,0.895766 -0.284204 , 1.78682 , 4.39555 , 0.0867717,0.646769,0.757734 -0.274062 , 1.7433 , 4.45736 , 0.292749,0.794411,0.532174 -0.257463 , 1.73618 , 4.61098 , 0.746796,0.647253,0.152839 -0.194445 , 1.96972 , 5.40844 , -0.654764,-0.547337,-0.521255 -0.183261 , 1.9042 , 5.46424 , 0.386339,0.484342,0.784956 -0.148424 , 1.9436 , 5.83049 , 0.799642,0.548014,-0.245468 -0.130169 , 1.89346 , 5.96216 , -0.98029,-0.192455,-0.0446406 -0.13797 , 1.73505 , 5.74987 , 0.445275,-0.381468,0.81007 -0.21034 , 1.35295 , 4.72866 , -0.211933,0.596714,-0.773962 -0.106152 , 1.61098 , 5.94975 , -0.932042,-0.335353,0.137242 -0.191682 , 1.23582 , 4.81047 , -0.0552196,0.834035,0.548941 -0.183576 , 1.17157 , 4.83558 , 0.0267445,-0.796217,0.604419 -0.077079 , 1.35006 , 5.99973 , 0.66847,-0.672413,-0.317819 -0.0678538 , 1.26132 , 6.00674 , 0.114252,0.959599,-0.257131 -0.931851 , 1.80117 , -1.22238 , 0.0982216,-0.0915935,-0.990941 -0.94223 , 1.86836 , -1.23565 , -0.0819535,0.0493558,0.995413 -0.949609 , 1.93192 , -1.23959 , -0.0496011,0.097315,0.994017 -1.27976 , 4.2956 , -1.66515 , -0.0889989,0.197458,0.976263 -1.31277 , 4.52455 , -1.71255 , -0.0774298,0.192779,0.978183 -1.34332 , 4.74929 , -1.74777 , -0.0658589,0.181334,0.981214 -1.37633 , 4.99277 , -1.78591 , 0.0493623,-0.179563,-0.982507 -1.4173 , 5.28123 , -1.84091 , -0.0442495,0.182024,0.982298 -1.46003 , 5.59122 , -1.89643 , -0.0269267,0.177643,0.983727 -1.5077 , 5.93073 , -1.95568 , -0.0215607,0.179778,0.983471 -1.56277 , 6.3271 , -2.03092 , -0.0235752,0.191978,0.981116 -1.62851 , 6.78978 , -2.12332 , -0.0224569,0.18393,0.982683 -1.69642 , 7.27544 , -2.20872 , -0.0342153,0.185036,0.982136 -1.77362 , 7.82886 , -2.30596 , -0.0394107,0.177387,0.983352 -1.86466 , 8.47973 , -2.42346 , -0.0421581,0.185008,0.981832 -1.97473 , 9.26478 , -2.57056 , -0.0429121,0.175705,0.983507 -2.09653 , 10.1414 , -2.72299 , -0.0584853,0.18053,0.981829 -2.24112 , 11.1843 , -2.90304 , -0.0656387,0.16917,0.983399 -2.41648 , 12.4513 , -3.12113 , -0.0616656,0.181529,0.98145 -2.64169 , 14.0685 , -3.40514 , -0.0600078,0.179845,0.981863 -2.96755 , 16.3917 , -3.84356 , -0.0707962,0.18057,0.981011 -3.27352 , 18.6391 , -4.17456 , -0.0761924,0.174383,0.981726 -4.56435 , 28.3407 , -5.35526 , -0.476016,0.0291861,0.878953 -4.48125 , 28.1529 , -4.79963 , -0.169395,0.144372,0.974916 -1.70074 , 11.03 , 1.82838 , 0.0551103,-0.955559,0.289602 -1.65547 , 11.1882 , 2.41547 , -0.632729,0.756813,-0.163977 -1.63863 , 11.2338 , 2.61525 , -0.679767,0.640914,0.356575 -1.63805 , 11.4432 , 2.8438 , -0.677816,0.721694,-0.140438 -1.55464 , 10.8243 , 2.93233 , 0.488389,-0.845494,-0.21591 -1.61316 , 11.6326 , 3.28165 , -0.558827,0.715441,-0.419353 -1.62317 , 11.9739 , 3.56087 , 0.777632,-0.441632,0.447493 -1.56649 , 11.6198 , 3.69139 , -0.829809,0.460786,-0.314792 -1.39561 , 10.2377 , 3.73465 , 0.126042,0.875763,0.465996 -1.35641 , 10.0186 , 3.85759 , -0.153453,0.642203,0.751018 -1.33404 , 9.99899 , 4.0352 , 0.201442,0.655525,0.72781 -1.25167 , 9.25589 , 3.97682 , 0.550396,-0.717269,0.427305 -1.22837 , 9.20561 , 4.13219 , -0.237257,0.845337,-0.478659 -1.20673 , 9.17089 , 4.29363 , -0.237257,0.845337,-0.478659 -1.20628 , 9.41278 , 4.56255 , -0.108474,-0.916292,0.385542 -0.973476 , 6.57915 , 3.59338 , 0.0274674,-0.998929,-0.0372351 -0.962119 , 6.61814 , 3.7374 , 0.0274674,-0.998929,-0.0372351 -0.954595 , 6.70794 , 3.90805 , 0.0274674,-0.998929,-0.037235 -0.943032 , 6.75816 , 4.06545 , 0.201785,-0.951578,-0.231912 -0.915044 , 6.56248 , 4.10704 , 0.201785,-0.951578,-0.231912 -0.904658 , 6.64263 , 4.28347 , 0.159367,-0.978861,0.128192 -0.903714 , 6.86813 , 4.54371 , -0.301232,0.93419,-0.191177 -0.815451 , 5.64684 , 4.01193 , -0.753826,-0.625075,0.202556 -0.81091 , 5.79398 , 4.2194 , 0.76024,0.521144,-0.387871 -0.802855 , 5.91056 , 4.41717 , 0.832752,0.427339,-0.352001 -0.797429 , 6.08888 , 4.66245 , -0.819983,-0.515941,0.247857 -0.776791 , 6.00096 , 4.74594 , 0.860437,-0.26519,0.435113 -0.773164 , 6.25976 , 5.06219 , 0.493126,-0.557096,0.668185 -0.764532 , 6.43552 , 5.3369 , -0.219946,0.96228,0.160129 -0.70867 , 5.48746 , 4.80832 , 0.741445,-0.254102,-0.621041 -0.720479 , 6.229 , 5.50463 , -0.149639,0.883037,0.444808 -0.700767 , 6.16722 , 5.61898 , 0.250767,-0.436276,-0.864164 -0.680793 , 6.11185 , 5.73854 , 0.284215,-0.295851,-0.911973 -0.725458 , 8.41442 , 7.83422 , -0.537332,0.52289,-0.66171 -0.631628 , 5.62892 , 5.66191 , 0.355926,-0.00763084,-0.934483 -0.656534 , 7.70693 , 7.68996 , -0.459547,-0.0909838,0.883481 -0.588296 , 5.24046 , 5.63221 , -0.687318,0.246249,0.683341 -0.594662 , 7.00533 , 7.49134 , -0.515579,-0.0137132,0.856732 -0.568551 , 6.83685 , 7.54975 , -0.445451,-0.0205397,0.895071 -0.54121 , 6.50752 , 7.43913 , -0.60742,-0.225934,0.761574 -0.515504 , 6.08167 , 7.20971 , -0.25137,0.424532,0.869819 -0.492059 , 5.928 , 7.25654 , -0.263196,0.334103,0.905043 -0.468982 , 5.78716 , 7.315 , -0.144981,0.325287,0.934435 -0.445595 , 5.63892 , 7.36278 , -0.0936786,0.367686,0.92522 -0.441061 , 4.3406 , 5.99716 , 0.167394,0.825548,-0.538934 -0.402129 , 5.27542 , 7.36207 , 0.322452,0.527986,0.785656 -0.39532 , 4.54826 , 6.63472 , 0.403618,-0.899328,0.168232 -0.34635 , 5.40364 , 8.0049 , 0.905892,0.423384,0.0102394 -0.395564 , 3.25668 , 5.2262 , 0.0678346,0.436886,0.896955 -0.381561 , 3.18926 , 5.28469 , -0.0634789,-0.562334,-0.82447 -0.367801 , 3.09882 , 5.30851 , 0.163596,0.450196,0.877815 -0.276931 , 4.42362 , 7.56958 , 0.713709,-0.206513,-0.669307 -0.365326 , 2.52873 , 4.71026 , 0.0240246,-0.920542,0.389905 -0.349061 , 2.53516 , 4.86877 , 0.602708,0.728553,0.325506 -0.339056 , 2.44 , 4.85405 , -0.856626,0.48291,-0.18163 -0.323544 , 2.41126 , 4.96043 , 0.771864,0.00357455,-0.635778 -0.317564 , 2.27874 , 4.8717 , 0.720874,0.630989,-0.286692 -0.331764 , 1.95878 , 4.39479 , -0.7301,-0.274633,0.625724 -0.325953 , 1.87092 , 4.35942 , -0.229024,0.373546,0.898895 -0.316169 , 1.80859 , 4.37657 , 0.125465,-0.482856,-0.866665 -0.305742 , 1.75821 , 4.42017 , 0.129199,0.717212,0.684773 -0.292001 , 1.72243 , 4.49979 , -0.471871,-0.791376,-0.388667 -0.273502 , 1.71669 , 4.66284 , 0.773785,0.555519,0.304393 -0.169315 , 2.19008 , 6.12679 , -0.954126,0.0454602,0.295934 -0.201056 , 1.86316 , 5.48018 , 0.563151,0.583799,0.584842 -0.151724 , 1.96228 , 6.036 , -0.359197,-0.701246,0.615818 -0.142987 , 1.85434 , 5.99662 , 0.181518,-0.318285,0.930455 -0.216301 , 1.42894 , 4.87415 , 0.682854,-0.477222,0.553146 -0.220588 , 1.30879 , 4.70024 , 0.660129,-0.016528,0.750971 -0.208709 , 1.25281 , 4.74551 , -0.00747815,-0.327387,0.944861 -0.202488 , 1.17907 , 4.72202 , 0.483092,-0.363156,0.796706 -0.0833149 , 1.40615 , 6.04961 , 0.164284,-0.965974,0.199764 -0.0868151 , 1.28111 , 5.88158 , -0.20998,-0.740085,0.638892 -0.0629264 , 1.22199 , 6.03417 , 0.407144,-0.913213,0.0166175 -0.982135 , 1.76331 , -1.21306 , 0.150858,-0.0914791,-0.984314 -0.991398 , 1.82494 , -1.219 , -0.107318,0.131412,0.985502 -1.00152 , 1.88669 , -1.22335 , -0.0945114,0.130984,0.986869 -1.01292 , 1.95519 , -1.23416 , 0.0516401,-0.106277,-0.992995 -1.02441 , 2.02505 , -1.24333 , -0.0958211,0.163869,0.981817 -1.03925 , 2.10705 , -1.26599 , -0.0903476,0.188075,0.97799 -1.3297 , 3.81475 , -1.57277 , -0.0971031,0.181515,0.978582 -1.35848 , 3.98875 , -1.60139 , -0.0909998,0.185218,0.978475 -1.38948 , 4.17267 , -1.63014 , -0.0808679,0.1947,0.977524 -1.42572 , 4.38359 , -1.66942 , -0.0797378,0.206604,0.97517 -1.46615 , 4.622 , -1.71809 , -0.0604483,0.186687,0.980558 -1.50743 , 4.86388 , -1.75916 , -0.0534952,0.179264,0.982345 -1.55249 , 5.13279 , -1.80728 , -0.0428195,0.177766,0.983141 -1.60387 , 5.43145 , -1.86145 , -0.0393697,0.177542,0.983325 -1.66161 , 5.76769 , -1.92445 , -0.0434382,0.178302,0.983017 -1.71644 , 6.09942 , -1.97216 , -0.0559998,0.186026,0.980948 -1.78988 , 6.53128 , -2.05703 , -0.0582962,0.197152,0.978638 -1.87062 , 7.00385 , -2.14458 , -0.0608521,0.18873,0.980142 -1.95982 , 7.52596 , -2.23653 , -0.0627974,0.187654,0.980226 -2.06066 , 8.12537 , -2.34219 , 0.0633872,-0.186492,-0.98041 -2.18607 , 8.85912 , -2.48016 , -0.0600595,0.187504,0.980426 -2.32208 , 9.66378 , -2.61825 , -0.0684168,0.174295,0.982314 -2.486 , 10.6328 , -2.78695 , -0.0713162,0.174291,0.982108 -2.66267 , 11.6862 , -2.94889 , -0.0672281,0.172883,0.982645 -2.91725 , 13.1874 , -3.21984 , -0.0627053,0.180078,0.981652 -3.22785 , 15.0212 , -3.53828 , -0.0678996,0.185766,0.980245 -4.13732 , 20.4175 , -4.44339 , 0.231013,-0.19534,-0.95314 -4.64916 , 23.5339 , -4.85344 , -0.0172227,-0.0145624,0.999746 -4.87164 , 25.0785 , -4.78124 , -0.0262147,0.0764171,0.996731 -4.71897 , 24.5089 , -4.19834 , -0.301683,0.1069,0.947397 -2.01116 , 11.6275 , 2.61277 , 0.552853,-0.794812,0.250257 -2.00341 , 11.739 , 2.83226 , -0.600921,0.654818,-0.458375 -2.07784 , 12.5011 , 3.17028 , -0.72016,0.461467,-0.518091 -2.08011 , 12.7188 , 3.43222 , 0.678193,-0.489144,0.548445 -2.06115 , 12.7759 , 3.66945 , 0.72191,-0.488059,0.490555 -1.93006 , 11.9195 , 3.70076 , -0.757126,0.403746,-0.513565 -2.07603 , 13.3404 , 4.26587 , 0.592062,-0.78991,0.159701 -2.04174 , 13.2857 , 4.49327 , -0.825765,-0.563324,0.0278947 -1.59932 , 9.90279 , 3.95427 , -0.161634,-0.748283,-0.643387 -1.56341 , 9.7683 , 4.09391 , -0.178351,0.718322,0.672461 -1.51989 , 9.56611 , 4.20715 , 0.824136,-0.528219,-0.204412 -1.48216 , 9.40986 , 4.3309 , -0.80859,0.551401,0.205279 -1.47805 , 9.5678 , 4.57071 , -0.00268357,0.927746,0.373201 -1.44868 , 9.48923 , 4.72431 , 0.112769,0.979375,0.167652 -1.42347 , 9.45324 , 4.89564 , -0.408181,-0.899995,0.152961 -1.39981 , 9.43314 , 5.07449 , -0.659992,-0.738949,0.13552 -1.37692 , 9.41905 , 5.2579 , -0.150967,-0.963046,0.223052 -1.0968 , 6.65559 , 4.11446 , 0.476762,-0.871482,-0.114964 -1.07903 , 6.63824 , 4.24267 , 0.460252,-0.873457,0.158873 -1.20899 , 8.2861 , 5.24943 , -0.819097,-0.0606729,0.570437 -1.05123 , 6.6842 , 4.54763 , -0.445144,0.857161,-0.25908 -0.942824 , 5.58505 , 4.06385 , 0.73337,0.630683,-0.253785 -0.925395 , 5.54212 , 4.16033 , -0.73337,-0.630683,0.253785 -0.953347 , 6.0831 , 4.61822 , -0.109232,0.870905,0.479159 -0.926963 , 5.95427 , 4.67495 , -0.541261,-0.432014,-0.721388 -0.912471 , 5.97487 , 4.82793 , 0.786315,0.124838,0.605082 -0.877503 , 5.70431 , 4.78384 , 0.0224753,0.186863,0.982129 -0.845663 , 5.46215 , 4.74869 , -0.524589,0.398672,0.752242 -0.82131 , 5.33384 , 4.79004 , 0.764329,-0.308146,-0.566435 -0.791842 , 5.10343 , 4.7485 , 0.754141,-0.131684,-0.643374 -0.782201 , 5.21132 , 4.96836 , 0.754141,-0.131684,-0.643374 -0.804668 , 5.92107 , 5.6964 , -0.104031,0.167672,0.980339 -0.773114 , 5.68199 , 5.65615 , 0.125015,-0.0758197,-0.989254 -0.755686 , 5.69921 , 5.83495 , -0.145046,0.265341,0.953182 -0.720264 , 5.34426 , 5.6773 , 0.586978,-0.347859,-0.731062 -0.696091 , 5.20646 , 5.70857 , 0.487931,0.0579959,-0.870954 -0.740282 , 6.95707 , 7.59481 , -0.445451,-0.0205399,0.895071 -0.700908 , 6.57121 , 7.43037 , -0.194187,-0.424198,0.884504 -0.674796 , 6.55688 , 7.63919 , -0.244232,-0.212697,0.946103 -0.636393 , 6.0376 , 7.30381 , -0.238099,0.271841,0.932422 -0.607283 , 5.86354 , 7.32666 , -0.342655,0.35696,0.869003 -0.58031 , 5.70967 , 7.36834 , -0.292167,0.313393,0.903562 -0.550678 , 5.35216 , 7.15969 , -0.440599,-0.859759,-0.258239 -0.522174 , 4.48567 , 6.29196 , -0.821706,0.542727,-0.173917 -0.499462 , 4.75534 , 6.83037 , 0.0152155,0.973048,-0.230102 -0.472733 , 5.1854 , 7.62048 , 0.572136,0.819121,-0.0412572 -0.454934 , 4.36722 , 6.71982 , -0.354082,0.0178841,-0.935043 -0.451003 , 3.21771 , 5.26668 , -0.127375,-0.454038,-0.881831 -0.403725 , 4.41854 , 7.23039 , -0.385043,0.919864,-0.0747748 -0.418619 , 3.03297 , 5.30507 , 0.183139,0.305858,0.934297 -0.419303 , 2.512 , 4.62822 , 0.356946,0.461299,0.812276 -0.405272 , 2.47044 , 4.69988 , 0.130012,0.482021,0.86646 -0.390765 , 2.40699 , 4.73636 , -0.764777,-0.0752209,-0.639889 -0.378467 , 2.31895 , 4.72788 , 0.159514,0.723936,0.671172 -0.362562 , 2.30201 , 4.85017 , 0.628276,0.751735,0.200411 -0.314488 , 2.66373 , 5.73121 , 0.677158,-0.662767,0.319681 -0.355867 , 1.9389 , 4.43921 , 0.759855,0.312331,-0.570149 -0.347671 , 1.83843 , 4.37567 , -0.205606,0.402228,0.892154 -0.336954 , 1.7762 , 4.39222 , -0.152003,0.564688,0.811186 -0.324387 , 1.7302 , 4.44422 , 0.168674,0.766775,0.619359 -0.309478 , 1.69358 , 4.52344 , 0.36558,0.81995,0.440493 -0.290286 , 1.67888 , 4.6678 , -0.783309,-0.50439,-0.363342 -0.252261 , 1.77205 , 5.1223 , -0.0665691,-0.40547,0.911681 -0.18373 , 1.99636 , 6.00551 , -0.677122,0.73573,-0.0144059 -0.160634 , 1.94334 , 6.13777 , 0.482213,-0.862322,0.154504 -0.22641 , 1.49779 , 4.9902 , 0.32964,-0.93952,0.0929521 -0.234055 , 1.34974 , 4.73136 , 0.759354,-0.357344,0.543771 -0.224316 , 1.28122 , 4.72884 , -0.565395,0.44695,0.693227 -0.212246 , 1.21704 , 4.74449 , -0.408951,-0.51967,0.750135 -0.196158 , 1.16777 , 4.8272 , 0.0677411,-0.883726,0.463077 -0.0870056 , 1.34886 , 6.00074 , 0.328154,0.687492,-0.647819 -0.0731794 , 1.26318 , 6.017 , 0.114252,0.959599,-0.257131 -1.04125 , 1.78508 , -1.20977 , -0.102046,0.0984231,0.989899 -1.05336 , 1.84624 , -1.21456 , -0.101576,0.119452,0.98763 -1.06676 , 1.91411 , -1.22601 , 0.0867106,-0.144282,-0.98573 -1.0779 , 1.97716 , -1.22791 , -0.0707882,0.171458,0.982645 -1.09572 , 2.05827 , -1.25128 , -0.0651653,0.172607,0.982833 -1.10683 , 2.12309 , -1.24977 , -0.0918209,0.171853,0.980834 -1.12457 , 2.20613 , -1.26905 , -0.110469,0.172614,0.978775 -1.13931 , 2.28555 , -1.2789 , -0.0742511,0.212284,0.974383 -1.1585 , 2.37812 , -1.30116 , -0.0912232,0.217517,0.971784 -1.18003 , 2.47861 , -1.328 , -0.110158,0.212473,0.970938 -1.2878 , 3.01194 , -1.4248 , 0.107676,-0.21518,-0.97062 -1.30812 , 3.12171 , -1.43369 , -0.107314,0.200458,0.973807 -1.33683 , 3.26164 , -1.46449 , -0.0850995,0.182841,0.979453 -1.36421 , 3.39669 , -1.48493 , -0.091466,0.189139,0.977681 -1.39444 , 3.54929 , -1.51365 , -0.0822281,0.194733,0.977404 -1.42286 , 3.69513 , -1.53152 , 0.0920462,-0.192459,-0.976978 -1.45768 , 3.86713 , -1.56252 , -0.084537,0.184769,0.979139 -1.49353 , 4.04832 , -1.59358 , -0.0755519,0.177746,0.981172 -1.53179 , 4.24051 , -1.62447 , -0.0760022,0.19261,0.978328 -1.58026 , 4.4763 , -1.67617 , -0.0618398,0.214599,0.974743 -1.63075 , 4.72266 , -1.72517 , -0.0584069,0.189526,0.980137 -1.68272 , 4.9818 , -1.7716 , -0.0516537,0.184385,0.981496 -1.738 , 5.25982 , -1.81927 , -0.0603345,0.174014,0.982893 -1.79796 , 5.55866 , -1.8674 , -0.063449,0.181971,0.981255 -1.86681 , 5.90407 , -1.92866 , -0.0574274,0.180066,0.981977 -1.94399 , 6.28813 , -1.99629 , 0.0542059,-0.188825,-0.980514 -2.03477 , 6.73781 , -2.0809 , 0.0663902,-0.187163,-0.980083 -2.13374 , 7.22826 , -2.16693 , -0.0687101,0.188903,0.979589 -2.25143 , 7.81332 , -2.276 , -0.070178,0.182408,0.980715 -2.37284 , 8.4221 , -2.37269 , -0.0812119,0.178822,0.980524 -2.53087 , 9.21033 , -2.51807 , -0.0783051,0.182539,0.980075 -2.696 , 10.0426 , -2.65016 , -0.0775871,0.177187,0.981114 -2.90108 , 11.0664 , -2.81964 , -0.0738136,0.173912,0.981991 -3.15541 , 12.3415 , -3.03594 , -0.0639335,0.18398,0.980849 -3.47768 , 13.9542 , -3.312 , -0.0667754,0.180935,0.981226 -3.89704 , 16.0497 , -3.6725 , -0.0964435,0.177507,0.979383 -4.40171 , 18.5874 , -4.07884 , 0.257618,-0.128587,-0.957653 -5.39599 , 23.7577 , -4.63467 , -0.0308335,0.0224929,0.999271 -5.44323 , 24.2444 , -4.3041 , -0.0262147,0.0764171,0.996731 -5.46652 , 24.6206 , -3.93671 , -0.0262147,0.0764171,0.996731 -2.38484 , 11.8306 , 2.58426 , 0.685152,-0.668828,0.288506 -2.04816 , 9.89267 , 2.49596 , 0.00785641,-0.974677,0.22348 -1.99623 , 9.69463 , 2.63436 , -0.0589714,-0.991662,0.114584 -2.01372 , 9.941 , 2.85005 , -0.62064,0.771286,0.141154 -1.98351 , 9.88246 , 3.01305 , 0.0131238,0.995109,-0.0979125 -1.96222 , 9.87972 , 3.18723 , -0.203787,-0.978944,0.0117732 -1.96525 , 10.0369 , 3.40153 , 0.739504,0.67176,0.0432702 -1.9357 , 9.98863 , 3.56924 , 0.0169168,-0.967348,0.252888 -1.92969 , 10.0993 , 3.78135 , 0.185869,-0.975027,-0.121552 -1.88785 , 9.95853 , 3.92432 , 0.315197,-0.898644,-0.305108 -2.27593 , 12.8675 , 5.03204 , -0.0277242,-0.878829,0.476331 -1.82538 , 9.83261 , 4.25092 , -0.263342,0.846291,0.463079 -2.16614 , 12.4973 , 5.38603 , 0.851716,0.512819,-0.107684 -1.86875 , 10.493 , 4.87232 , -0.493924,-0.869121,0.0258426 -1.82374 , 10.3369 , 5.01329 , 0.488523,0.842654,0.22645 -1.65877 , 9.24298 , 4.76094 , -0.562946,-0.810382,-0.1624 -1.64534 , 9.3172 , 4.97609 , -0.468736,-0.860463,0.199724 -1.65947 , 9.61273 , 5.29812 , 0.038176,-0.925759,0.376181 -1.62551 , 9.52265 , 5.45151 , 0.149327,-0.813321,0.562326 -1.28362 , 6.85135 , 4.3138 , -0.36384,0.93137,0.0130283 -1.34392 , 7.51935 , 4.80461 , -0.0551881,-0.642396,0.764384 -1.35352 , 7.77071 , 5.10082 , 0.998273,0.0509442,0.0292399 -1.15639 , 6.18565 , 4.37233 , 0.383278,-0.556533,-0.737136 -1.06974 , 5.5286 , 4.12069 , 0.738543,0.672177,0.052276 -1.0397 , 5.39164 , 4.15915 , 0.623923,0.736703,0.260746 -1.32493 , 8.31395 , 6.14059 , -0.0548664,0.207615,0.976671 -1.11159 , 6.40679 , 5.07599 , 0.327203,0.83721,-0.438198 -1.13756 , 6.87234 , 5.54788 , 0.453798,0.0146966,-0.890983 -0.99878 , 5.59373 , 4.80603 , 0.554451,-0.323016,-0.766971 -0.977349 , 5.54582 , 4.9092 , -0.524589,0.398672,0.752242 -0.950568 , 5.43231 , 4.96327 , 0.535236,-0.450493,-0.714548 -0.920314 , 5.27144 , 4.97741 , 0.756354,-0.255201,-0.60233 -0.893257 , 5.15771 , 5.02503 , 0.756354,-0.255201,-0.60233 -1.30622 , 10.7447 , 9.90869 , 0.116692,0.96751,-0.224294 -0.891682 , 5.59828 , 5.69828 , -0.328151,0.120173,0.93695 -0.869477 , 5.56272 , 5.82965 , -0.519654,0.601029,0.607226 -0.836873 , 5.3717 , 5.81721 , 0.741858,-0.436554,-0.508986 -0.813044 , 5.31939 , 5.93179 , -0.76736,0.100872,0.633233 -0.782099 , 5.14395 , 5.92552 , 0.634616,-0.238027,-0.735259 -0.839879 , 6.59603 , 7.60976 , 0.0130615,-0.235915,0.971686 -0.785199 , 6.04903 , 7.24796 , 0.524275,-0.387049,-0.758504 -0.757371 , 6.01552 , 7.4281 , -0.380361,0.163806,0.910216 -0.705094 , 5.37046 , 6.90546 , 0.63763,0.753201,-0.161603 -0.659236 , 4.78278 , 6.40868 , -0.671192,0.741263,0.00551145 -0.63199 , 4.64006 , 6.42275 , 0.827454,-0.400086,0.394018 -0.608205 , 4.60929 , 6.57532 , -0.84832,0.528286,-0.0355792 -0.583632 , 4.59318 , 6.75208 , 0.233752,0.850813,-0.470613 -0.564021 , 4.96495 , 7.47231 , -0.330922,-0.382455,-0.862681 -0.523609 , 3.23745 , 5.24091 , 0.126476,0.44073,0.888685 -0.504761 , 3.17111 , 5.29879 , -0.0444805,-0.375014,-0.925951 -0.485213 , 3.08688 , 5.33044 , 0.124249,0.301787,0.945244 -0.442209 , 4.84439 , 8.30116 , -0.966791,-0.237718,0.0938378 -0.457343 , 2.46405 , 4.635 , 0.409853,0.21219,0.887128 -0.4412 , 2.42677 , 4.71468 , 0.64215,0.202897,0.73924 -0.428052 , 2.31526 , 4.66292 , 0.105144,0.280676,0.954026 -0.391799 , 2.69642 , 5.52514 , -0.978725,-0.185583,-0.0875043 -0.372735 , 2.61906 , 5.56514 , -0.978725,-0.185583,-0.0875045 -0.355213 , 2.52808 , 5.57678 , -0.615689,0.777599,-0.12754 -0.379254 , 1.90013 , 4.44745 , 0.780656,0.212244,-0.587818 -0.369175 , 1.80492 , 4.39183 , 0.532206,-0.272859,-0.801439 -0.35511 , 1.75135 , 4.42581 , -0.138403,0.623219,0.769703 -0.340643 , 1.70066 , 4.46814 , 0.205351,0.806073,0.555048 -0.323838 , 1.67039 , 4.56562 , 0.169894,0.772025,0.612465 -0.306858 , 1.63399 , 4.65357 , -0.728872,-0.488553,-0.479648 -0.289717 , 1.5914 , 4.73181 , 0.622671,0.66782,0.407795 -0.19844 , 1.9459 , 6.01286 , -0.359197,-0.701246,0.615818 -0.188255 , 1.82207 , 5.91539 , -0.927367,0.33805,-0.160355 -0.247534 , 1.40276 , 4.80046 , 0.791656,-0.455053,0.407685 -0.238251 , 1.31908 , 4.75073 , 0.694094,0.668606,0.266832 -0.224443 , 1.25745 , 4.77657 , -0.920939,0.388361,0.0323608 -0.217009 , 1.17483 , 4.71388 , -0.238145,-0.218233,0.946394 -0.0840744 , 1.43758 , 6.20713 , 0.314503,-0.781954,0.538179 -0.0907011 , 1.28945 , 5.93148 , 0.198297,0.962916,-0.182953 -0.0648732 , 1.22259 , 6.04446 , -0.934537,0.246129,0.257025 -1.08867 , 1.7438 , -1.2001 , -0.127099,0.150113,0.980465 -1.1018 , 1.80457 , -1.20555 , -0.124287,0.108553,0.986291 -1.11603 , 1.86643 , -1.20952 , -0.117155,0.149915,0.981733 -1.13343 , 1.93928 , -1.22766 , -0.0734977,0.152631,0.985546 -1.14667 , 2.00307 , -1.22854 , 0.0623448,-0.184884,-0.980781 -1.16636 , 2.084 , -1.25059 , -0.109604,0.146354,0.983142 -1.18167 , 2.15485 , -1.25548 , -0.074912,0.129427,0.988755 -1.19916 , 2.23242 , -1.26594 , -0.0745571,0.204148,0.976097 -1.22135 , 2.32408 , -1.289 , -0.0665478,0.190945,0.979342 -1.24128 , 2.41094 , -1.3024 , 0.123992,-0.197575,-0.972415 -1.2633 , 2.50476 , -1.3203 , -0.132905,0.211255,0.968353 -1.28536 , 2.60017 , -1.33558 , -0.121503,0.196702,0.972906 -1.30744 , 2.69714 , -1.34834 , -0.0920348,0.175596,0.980151 -1.32931 , 2.79477 , -1.35817 , -0.0682892,0.17209,0.982711 -1.35746 , 2.91565 , -1.38522 , -0.0779427,0.20878,0.974852 -1.38877 , 3.04466 , -1.4149 , -0.0805584,0.205698,0.975294 -1.41681 , 3.16918 , -1.43467 , -0.0910064,0.191172,0.977329 -1.44554 , 3.29436 , -1.45042 , -0.0678571,0.182143,0.980928 -1.47836 , 3.43771 , -1.475 , -0.0755783,0.1862,0.979601 -1.51814 , 3.60498 , -1.51279 , -0.0636911,0.18734,0.980228 -1.55534 , 3.76676 , -1.53957 , -0.0706535,0.181416,0.980865 -1.59479 , 3.93837 , -1.56696 , -0.0605851,0.186137,0.980654 -1.64148 , 4.13634 , -1.60552 , -0.0518742,0.186663,0.981054 -1.68935 , 4.3447 , -1.64326 , -0.0477859,0.207612,0.977043 -1.74786 , 4.58848 , -1.69508 , -0.0549708,0.199214,0.978413 -1.80268 , 4.82743 , -1.73407 , -0.0544869,0.182512,0.981693 -1.86466 , 5.09467 , -1.78015 , -0.0543845,0.17505,0.983056 -1.92757 , 5.37302 , -1.82219 , -0.053337,0.17494,0.983133 -2.00492 , 5.70591 , -1.88297 , -0.0484968,0.184469,0.981641 -2.08931 , 6.06914 , -1.94618 , -0.0397843,0.179672,0.982922 -2.18426 , 6.47929 , -2.01878 , -0.0552617,0.182302,0.981688 -2.29078 , 6.93769 , -2.09824 , -0.0668039,0.186428,0.980195 -2.41656 , 7.48058 , -2.19832 , 0.0675127,-0.185415,-0.980338 -2.54261 , 8.03037 , -2.28 , -0.077593,0.172281,0.981987 -2.70191 , 8.71889 , -2.39793 , -0.079819,0.189187,0.978692 -2.89238 , 9.54248 , -2.54179 , 0.0762255,-0.183336,-0.980091 -3.10926 , 10.4832 , -2.69729 , -0.0768021,0.181579,0.980373 -3.36831 , 11.6074 , -2.88089 , -0.0633813,0.180632,0.981506 -3.70949 , 13.0838 , -3.13732 , -0.0651468,0.179271,0.981641 -4.1336 , 14.9174 , -3.44787 , -0.0843331,0.174131,0.981105 -4.64594 , 17.1503 , -3.80454 , -0.10663,0.178173,0.978205 -2.92442 , 12.9717 , 2.90402 , 0.119465,-0.716257,0.687535 -2.38122 , 10.247 , 2.6819 , -0.256038,-0.932209,-0.255795 -2.30577 , 9.95999 , 2.80924 , -0.256037,-0.932209,-0.255795 -2.27482 , 9.91381 , 2.97524 , 0.367125,0.878552,0.305557 -2.24039 , 9.84428 , 3.13599 , -0.322656,-0.85994,-0.39547 -2.20674 , 9.78296 , 3.29668 , 0.57007,0.803015,0.173747 -2.21217 , 9.93771 , 3.51222 , 0.0606276,0.927712,-0.36834 -2.13281 , 9.61256 , 3.60287 , -0.26693,-0.94503,0.188857 -2.19597 , 10.1103 , 3.92492 , -0.0232863,-0.982234,-0.186212 -2.15648 , 10.0161 , 4.08222 , -0.0292917,0.865499,0.500054 -2.11368 , 9.90193 , 4.23043 , -0.00401447,0.839199,0.54381 -2.08048 , 9.84031 , 4.39534 , 0.00839261,0.866907,0.498399 -1.94966 , 9.18211 , 4.33874 , -0.361446,0.63166,0.68583 -1.92637 , 9.17441 , 4.51194 , -0.0653745,0.939761,0.335524 -1.90361 , 9.17172 , 4.6897 , 0.532168,0.825474,0.188123 -1.88997 , 9.23038 , 4.89541 , 0.516094,0.796595,0.314776 -1.85478 , 9.15707 , 5.04718 , -0.258434,0.238198,0.936202 -1.57674 , 7.46067 , 4.43002 , 0.352982,-0.475841,0.805593 -1.51141 , 7.14633 , 4.42738 , -0.555961,0.10853,0.824093 -1.50805 , 7.24877 , 4.62848 , -0.118336,-0.0681782,0.99063 -1.54232 , 7.62623 , 4.98449 , 0.803746,0.568931,-0.174101 -1.32348 , 6.20049 , 4.34967 , -0.456392,0.468989,0.756145 -1.54509 , 7.95588 , 5.50817 , -0.953046,0.259344,0.156346 -1.17131 , 5.31519 , 4.08466 , 0.631578,0.686063,0.361145 -1.15397 , 5.29779 , 4.19287 , 0.631578,0.686063,0.361145 -1.37794 , 7.18388 , 5.54857 , 0.00469841,-0.0297274,0.999547 -1.35533 , 7.17409 , 5.71253 , 0.00469831,-0.0297271,0.999547 -1.24503 , 6.44472 , 5.37278 , -0.615425,0.226992,0.754802 -1.20607 , 6.28331 , 5.41445 , -0.482664,0.527845,0.698867 -1.09697 , 5.50303 , 4.98267 , 0.678217,-0.0668376,-0.731816 -1.1582 , 6.21285 , 5.6813 , -0.0828258,0.697644,0.711641 -1.11904 , 6.04202 , 5.70771 , -0.441324,0.401724,0.802404 -0.994476 , 5.04015 , 5.03013 , -0.682666,0.441904,0.581969 -1.03866 , 5.66497 , 5.71411 , 0.351259,0.109451,0.929859 -1.00024 , 5.48193 , 5.71291 , 0.233332,-0.254047,0.938625 -0.983947 , 5.51965 , 5.91081 , -0.979286,-0.00990933,-0.202238 -0.962374 , 5.524 , 6.08337 , 0.820342,-0.0728199,-0.567217 -0.913476 , 5.20483 , 5.94027 , -0.74194,0.00173317,0.670464 -0.98373 , 6.35092 , 7.29397 , 0.121006,-0.39534,0.910529 -0.95222 , 6.29979 , 7.45571 , 0.121006,-0.395341,0.910529 -0.820868 , 4.82425 , 6.04677 , -0.737293,-0.566574,-0.367959 -0.79453 , 4.76577 , 6.15391 , -0.799166,0.34382,-0.493074 -0.801718 , 5.24594 , 6.90193 , -0.910926,-0.119419,0.394908 -0.776439 , 5.26653 , 7.13314 , -0.415715,-0.886895,-0.20149 -0.748478 , 5.24964 , 7.3274 , 0.166508,0.914676,0.368298 -0.689835 , 4.56199 , 6.64749 , -0.171703,0.858211,0.483727 -0.6661 , 4.59061 , 6.88893 , -0.615404,-0.782125,0.0977663 -0.644739 , 4.76887 , 7.35301 , 0.330914,-0.512903,0.792103 -0.575325 , 3.17266 , 5.2487 , -0.0444805,-0.375014,-0.925951 -0.554334 , 3.10069 , 5.29721 , 0.0444805,0.375014,0.925951 -0.555761 , 5.10728 , 8.62008 , -0.966791,-0.237718,0.0938378 -0.518632 , 5.01425 , 8.76054 , -0.957753,-0.241824,0.155661 -0.493027 , 2.41945 , 4.65009 , 0.64215,0.202897,0.73924 -0.474971 , 2.37753 , 4.7203 , 0.303021,0.305703,0.902621 -0.424311 , 3.78553 , 7.46102 , -0.226674,-0.165154,0.959866 -0.427313 , 2.65778 , 5.56879 , -0.978725,-0.185583,-0.0875045 -0.407273 , 2.5496 , 5.54516 , -0.615689,0.777599,-0.12754 -0.383855 , 2.51561 , 5.67249 , -0.615689,0.777599,-0.12754 -0.40097 , 1.85765 , 4.44592 , -0.718804,-0.208514,0.663207 -0.387081 , 1.77915 , 4.42581 , 0.454887,-0.401688,-0.794811 -0.370878 , 1.72495 , 4.45926 , -0.0628361,0.682621,0.728066 -0.354751 , 1.68157 , 4.51966 , 0.143374,0.870243,0.471296 -0.336774 , 1.63941 , 4.58879 , 0.335216,0.800946,0.496101 -0.318625 , 1.60216 , 4.67634 , -0.595034,-0.588169,-0.547715 -0.299094 , 1.56305 , 4.76338 , 0.652042,0.653086,0.385124 -0.14599 , 2.24786 , 7.11234 , 0.673635,-0.439462,0.594213 -0.273892 , 1.40324 , 4.69747 , 0.705378,-0.575468,0.413857 -0.261168 , 1.32955 , 4.67658 , -0.503748,-0.0758255,-0.860517 -0.237631 , 1.29758 , 4.80847 , -0.576764,-0.358443,-0.734073 -0.227255 , 1.21677 , 4.75605 , -0.206322,-0.53812,0.817226 -0.216719 , 1.13977 , 4.71171 , 0.593,-0.385934,0.706686 -0.0954841 , 1.35311 , 6.03135 , -0.764925,-0.0465784,0.642434 -0.0763395 , 1.26555 , 6.03726 , -0.401152,-0.545941,-0.735544 -1.13173 , 1.69695 , -1.182 , -0.135833,0.160484,0.977647 -1.14999 , 1.76202 , -1.19605 , -0.134266,0.14921,0.979647 -1.16501 , 1.82253 , -1.20048 , -0.131801,0.127125,0.983091 -1.18015 , 1.88435 , -1.20355 , -0.0910093,0.192666,0.977035 -1.19965 , 1.95794 , -1.22067 , -0.0550277,0.193402,0.979575 -1.2202 , 2.03275 , -1.23572 , 0.0831408,-0.157974,-0.983937 -1.23729 , 2.102 , -1.24115 , -0.0634813,0.139595,0.988172 -1.25447 , 2.17263 , -1.24492 , -0.0883632,0.160119,0.983135 -1.27943 , 2.26238 , -1.26878 , -0.0559135,0.204172,0.977337 -1.30212 , 2.34736 , -1.28289 , -0.102903,0.152762,0.982891 -1.3239 , 2.43406 , -1.29489 , 0.102862,-0.171852,-0.979738 -1.34897 , 2.52847 , -1.31136 , 0.0994134,-0.204793,-0.973744 -1.37612 , 2.62994 , -1.33185 , -0.0594185,0.164541,0.984579 -1.4035 , 2.73402 , -1.34961 , -0.0609755,0.176333,0.98244 -1.43066 , 2.8388 , -1.36426 , -0.0553175,0.18095,0.981935 -1.46029 , 2.95272 , -1.38254 , -0.0568178,0.213775,0.975229 -1.49557 , 3.08226 , -1.40999 , -0.0607906,0.205844,0.976695 -1.53227 , 3.22142 , -1.44002 , -0.0657728,0.184163,0.980693 -1.56716 , 3.3538 , -1.4593 , -0.0490582,0.174933,0.983357 -1.60464 , 3.49665 , -1.48075 , -0.0566594,0.185818,0.980949 -1.64688 , 3.65676 , -1.50956 , -0.0554342,0.187081,0.980779 -1.69378 , 3.83436 , -1.54473 , -0.0461752,0.182291,0.98216 -1.74387 , 4.02173 , -1.57972 , -0.044527,0.183941,0.981928 -1.79277 , 4.21164 , -1.60889 , -0.0410044,0.19059,0.980813 -1.85573 , 4.44433 , -1.65819 , -0.0426791,0.205813,0.97766 -1.91761 , 4.68092 , -1.70013 , -0.0479076,0.186527,0.981281 -1.98741 , 4.94457 , -1.74913 , -0.0434665,0.182203,0.9823 -2.0601 , 5.21885 , -1.79404 , -0.0411417,0.171422,0.984338 -2.13906 , 5.52304 , -1.84432 , -0.0348841,0.18065,0.982929 -2.23172 , 5.8728 , -1.90685 , -0.0381828,0.182629,0.98244 -2.33366 , 6.26109 , -1.97513 , -0.0444941,0.177866,0.983048 -2.44667 , 6.68794 , -2.04697 , -0.0570684,0.175229,0.982872 -2.56792 , 7.15543 , -2.1208 , 0.0610806,-0.185438,-0.980756 -2.72393 , 7.74172 , -2.22885 , 0.0712889,-0.174687,-0.98204 -2.86972 , 8.30857 , -2.30602 , -0.0743725,0.170366,0.98257 -3.07051 , 9.06892 , -2.43842 , 0.0738926,-0.189,-0.979193 -3.30557 , 9.96249 , -2.59189 , 0.0737675,-0.179418,-0.981003 -3.58316 , 11.0202 , -2.76939 , -0.059324,0.182705,0.981376 -3.9344 , 12.3527 , -2.99872 , -0.0592652,0.184458,0.981052 -4.35163 , 13.946 , -3.25983 , -0.066542,0.178351,0.981714 -4.86573 , 15.9146 , -3.57167 , -0.105459,0.162504,0.981056 -5.48101 , 18.2815 , -3.91937 , -0.313523,0.0753161,0.946589 -19.0429 , 71.0901 , -10.4585 , 0.0667103,0.259503,0.963435 -13.1222 , 50.787 , -2.57276 , -0.52857,0.615029,-0.58511 -13.016 , 50.8387 , -1.66973 , -0.558404,-0.822748,0.10616 -2.59042 , 9.81 , 2.56808 , -0.247591,0.415555,0.875222 -2.55171 , 9.73921 , 2.72776 , -0.653963,-0.601609,-0.458693 -2.54428 , 9.81007 , 2.9136 , 0.551814,0.759824,0.343756 -2.48298 , 9.62839 , 3.04874 , -0.318996,-0.946921,-0.0397796 -2.46357 , 9.64451 , 3.22487 , 0.199225,0.939516,-0.278602 -2.51497 , 10.0006 , 3.4882 , 0.315457,0.823375,-0.471743 -2.49479 , 10.0191 , 3.67474 , -0.304089,-0.926527,0.221534 -2.48712 , 10.1006 , 3.88147 , -0.322378,-0.935477,-0.144761 -2.4421 , 9.99895 , 4.03676 , 0.0897562,0.875286,0.475203 -2.38068 , 9.81097 , 4.1616 , 0.199861,0.759181,0.619435 -2.35008 , 9.77996 , 4.33531 , -0.257017,-0.828733,-0.497135 -2.30584 , 9.67201 , 4.48149 , 0.286307,0.946377,0.149664 -2.26985 , 9.61628 , 4.64609 , -0.333953,-0.942588,0.00185575 -2.29449 , 9.87805 , 4.93952 , 0.333953,0.942588,-0.00185579 -2.22923 , 9.66006 , 5.04176 , -0.758974,0.515378,0.397924 -2.07432 , 8.94709 , 4.91525 , 0.584094,-0.461156,-0.667959 -2.01004 , 8.72338 , 4.99111 , -0.371225,0.345017,0.862064 -1.97665 , 8.66749 , 5.14288 , -0.371226,0.345017,0.862064 -1.73735 , 7.42137 , 4.68583 , -0.315443,-0.463845,0.827855 -1.62612 , 6.89081 , 4.5587 , -0.670997,-0.221657,0.707553 -1.58519 , 6.76341 , 4.6353 , 0.720672,0.401916,-0.564886 -1.78209 , 8.07535 , 5.5415 , -0.878582,0.465482,-0.106867 -1.30702 , 5.27695 , 4.03711 , 0.448353,0.593013,0.668816 -1.27713 , 5.18548 , 4.09748 , 0.407779,0.912893,-0.0185292 -1.54408 , 7.00636 , 5.39793 , -0.336655,0.764524,-0.549697 -1.49803 , 6.85177 , 5.45891 , -0.184252,0.0958322,-0.978196 -1.47958 , 6.86771 , 5.63536 , 0.00469841,-0.0297274,0.999547 -1.41804 , 6.59903 , 5.60912 , -0.637354,0.259968,0.725394 -1.36203 , 6.35629 , 5.59296 , -0.914683,0.394938,0.0859042 -1.2494 , 5.70057 , 5.24575 , -0.856534,0.467843,0.217881 -1.29307 , 6.17177 , 5.77618 , -0.679346,-0.68637,-0.259587 -1.26101 , 6.09353 , 5.87749 , -0.291839,0.253538,0.922252 -1.19158 , 5.72604 , 5.73021 , -0.0261417,-0.0892654,0.995665 -1.12453 , 5.35073 , 5.55824 , 0.513204,-0.110417,0.851135 -1.06776 , 5.04926 , 5.43533 , -0.568919,0.819864,0.0644598 -1.03776 , 4.96146 , 5.50309 , 0.421312,0.489216,0.763652 -1.01996 , 4.98602 , 5.68134 , -0.968119,-0.122254,-0.218629 -1.01338 , 5.11702 , 5.97577 , 0.744489,0.179754,-0.642981 -0.974301 , 4.95235 , 5.97119 , -0.604997,-0.478756,-0.636216 -0.938204 , 4.8153 , 5.99185 , -0.543585,0.00245313,-0.839351 -0.913855 , 4.7914 , 6.13635 , 0.764233,-0.313536,0.563599 -0.894626 , 4.84198 , 6.37245 , -0.551903,0.803887,-0.221741 -0.884126 , 5.00653 , 6.7581 , -0.971818,-0.166275,-0.167102 -0.878273 , 5.28365 , 7.30698 , 0.166508,0.914676,0.368298 -0.782921 , 4.32557 , 6.28258 , 0.538517,0.813713,-0.218793 -0.782332 , 4.70778 , 6.98471 , -0.524108,0.00757511,0.851618 -0.744966 , 4.54958 , 6.97788 , 0.559201,-0.729921,-0.393078 -0.712659 , 4.47209 , 7.0825 , -0.451915,0.886395,-0.100382 -0.666251 , 4.08753 , 6.72843 , 0.318577,0.885103,0.339265 -0.632948 , 3.9164 , 6.67424 , 0.720365,0.0437855,0.692212 -0.604301 , 3.92614 , 6.90488 , 0.351993,0.863609,0.360945 -0.596302 , 5.015 , 8.95837 , -0.957753,-0.241824,0.155661 -0.548586 , 4.44837 , 8.28217 , -0.850839,-0.39046,0.351588 -0.509738 , 3.81424 , 7.42287 , -0.124972,-0.778555,0.615008 -0.481355 , 2.94795 , 6.04949 , 0.000396946,0.902575,0.430533 -0.455669 , 2.88644 , 6.13774 , -0.152696,0.878402,0.452874 -0.433877 , 2.62936 , 5.82979 , -0.981361,0.188493,0.0374345 -0.399793 , 2.77164 , 6.34843 , -0.857817,0.4556,0.237863 -0.420057 , 1.82269 , 4.46233 , 0.705702,0.145995,-0.693304 -0.40428 , 1.74447 , 4.4413 , 0.32842,-0.524616,-0.785442 -0.386176 , 1.69059 , 4.47401 , -0.106105,0.798781,0.592192 -0.367427 , 1.65471 , 4.55226 , 0.100901,0.746568,0.657614 -0.348274 , 1.61173 , 4.62108 , -0.354815,-0.805485,-0.474659 -0.327987 , 1.57385 , 4.7081 , 0.563532,0.708453,0.424882 -0.226017 , 2.03982 , 6.33147 , -0.0999809,-0.822222,0.560316 -0.239378 , 1.73994 , 5.6818 , 0.045227,-0.449954,0.891906 -0.275632 , 1.38337 , 4.75575 , 0.705379,-0.575467,0.413857 -0.262708 , 1.3015 , 4.70533 , -0.532813,-0.697965,-0.478492 -0.240673 , 1.25892 , 4.798 , -0.579605,0.269961,-0.768882 -0.217758 , 1.21129 , 4.88045 , -0.337517,-0.24783,0.908109 -0.0961763 , 1.43795 , 6.21833 , 0.188386,-0.72602,0.661367 -0.0967599 , 1.29014 , 5.94205 , 0.540146,0.774993,0.328067 -0.0680162 , 1.2229 , 6.04463 , -0.934537,0.246129,0.257025 -1.15749 , 1.5956 , -1.16356 , -0.113879,0.186495,0.975834 -1.17475 , 1.65478 , -1.17174 , -0.111849,0.17352,0.978458 -1.19165 , 1.71337 , -1.17816 , -0.124149,0.183328,0.975181 -1.20867 , 1.77325 , -1.18322 , 0.0925335,-0.161599,-0.982509 -1.22795 , 1.83963 , -1.19482 , -0.0792915,0.172712,0.981776 -1.2502 , 1.9114 , -1.21235 , -0.0755798,0.190631,0.978748 -1.26943 , 1.97959 , -1.22036 , -0.0540615,0.168111,0.984285 -1.2895 , 2.04798 , -1.2264 , -0.079705,0.187372,0.97905 -1.31433 , 2.13024 , -1.246 , -0.0514631,0.122781,0.991099 -1.33336 , 2.2007 , -1.24837 , -0.0561835,0.17525,0.98292 -1.36113 , 2.29012 , -1.2705 , -0.0838388,0.178082,0.980438 -1.38359 , 2.36957 , -1.27608 , -0.0876381,0.163484,0.982646 -1.40819 , 2.45588 , -1.28655 , -0.0800395,0.186935,0.979106 -1.43836 , 2.55636 , -1.30823 , -0.0332029,0.208361,0.977488 -1.46854 , 2.65846 , -1.32709 , -0.0430552,0.190865,0.980672 -1.50195 , 2.76848 , -1.34955 , 0.041856,-0.163688,-0.985624 -1.53534 , 2.88026 , -1.3686 , -0.0232372,0.203971,0.978701 -1.57366 , 3.00874 , -1.39754 , -0.0493556,0.199773,0.978598 -1.60921 , 3.13063 , -1.41594 , -0.0590242,0.178318,0.982201 -1.65058 , 3.26924 , -1.44304 , -0.0493314,0.182504,0.981967 -1.69209 , 3.41077 , -1.46605 , -0.0430073,0.174036,0.9838 -1.73909 , 3.56837 , -1.49619 , -0.0460592,0.181928,0.982233 -1.78595 , 3.72807 , -1.52146 , -0.0499552,0.178538,0.982664 -1.83603 , 3.89739 , -1.54714 , -0.0443932,0.189526,0.980872 -1.89337 , 4.09306 , -1.58407 , -0.0475282,0.183622,0.981847 -1.95477 , 4.2985 , -1.61973 , -0.0364083,0.204488,0.978192 -2.02683 , 4.53936 , -1.66948 , -0.0431249,0.194337,0.979987 -2.09851 , 4.78301 , -1.71125 , -0.0398639,0.186838,0.981582 -2.17928 , 5.05458 , -1.75958 , -0.0398206,0.180186,0.982826 -2.26473 , 5.34693 , -1.80855 , -0.0379873,0.179875,0.982956 -2.36468 , 5.68349 , -1.87022 , -0.0435531,0.185727,0.981636 -2.47006 , 6.04132 , -1.92931 , -0.0507874,0.176648,0.982963 -2.58081 , 6.4206 , -1.98493 , -0.0581148,0.175571,0.98275 -2.71441 , 6.87314 , -2.06032 , 0.0622246,-0.181114,-0.981492 -2.8696 , 7.40005 , -2.15162 , 0.0705589,-0.185747,-0.980061 -3.03655 , 7.96778 , -2.23975 , -0.0700303,0.172287,0.982554 -3.23077 , 8.63043 , -2.34441 , -0.0609742,0.184376,0.980963 -3.4753 , 9.46063 , -2.4881 , -0.0725836,0.181363,0.980734 -3.74808 , 10.3882 , -2.63532 , -0.064396,0.182074,0.981174 -4.11574 , 11.6322 , -2.8559 , -0.0582324,0.184102,0.981181 -4.54216 , 13.0797 , -3.0943 , -0.0594634,0.176723,0.982463 -5.04424 , 14.7972 , -3.35966 , -0.112395,0.147086,0.982717 -5.40519 , 16.0859 , -3.4385 , -0.116658,0.157979,0.980527 -6.14442 , 19.1069 , -2.84571 , -0.105482,0.162411,0.981069 -19.1339 , 62.9551 , -10.719 , -0.179445,0.152996,0.971798 -17.3634 , 57.4943 , -8.62519 , -0.567245,-0.260762,-0.781176 -14.4246 , 49.6268 , -2.76948 , -0.520801,-0.79955,0.299142 -14.2958 , 51.4027 , 1.69254 , -0.169701,-0.981974,-0.0832433 -2.79233 , 9.63155 , 2.84082 , -0.371017,-0.928086,-0.0316644 -3.56857 , 12.9275 , 3.70926 , 0.287662,-0.894054,0.343391 -3.56498 , 13.0489 , 3.97083 , -0.287662,0.894054,-0.343391 -2.77194 , 9.84653 , 3.41221 , 0.199539,0.885888,-0.418793 -2.74342 , 9.82985 , 3.58654 , -0.513675,-0.841118,-0.169289 -2.70332 , 9.76281 , 3.74743 , 0.662239,0.747634,0.0498279 -2.73728 , 10.0193 , 4.00645 , -0.69145,-0.681099,-0.240836 -2.68669 , 9.90868 , 4.15729 , 0.373871,0.695392,0.613719 -2.6126 , 9.69398 , 4.26995 , -0.483307,-0.782504,-0.392558 -2.57489 , 9.63409 , 4.43269 , -0.408137,-0.767779,-0.493903 -2.54581 , 9.61742 , 4.6115 , -0.241656,-0.968903,0.0531896 -2.55287 , 9.77024 , 4.86018 , -0.205393,-0.978211,0.0302909 -2.49646 , 9.6278 , 4.99279 , -0.972386,-0.0445875,-0.229081 -2.35993 , 9.10705 , 4.95365 , 0.413514,-0.246599,-0.876468 -2.34982 , 9.17875 , 5.17075 , -0.279278,0.120313,0.952643 -2.26308 , 8.88258 , 5.21494 , -0.371226,0.345017,0.862064 -1.9287 , 7.35009 , 4.62152 , -0.0951263,0.625786,0.774173 -1.87643 , 7.1974 , 4.69436 , 0.385586,-0.288434,-0.87643 -1.80023 , 6.91305 , 4.69164 , 0.362998,0.127668,-0.923002 -1.71017 , 6.55484 , 4.63539 , 0.672806,0.486785,0.557111 -1.76451 , 6.94652 , 5.01301 , -0.411117,0.911533,-0.00947165 -1.40701 , 5.14462 , 4.0506 , 0.293557,0.955941,-0.000409885 -1.40089 , 5.19592 , 4.19942 , 0.293557,0.955941,-0.000409992 -1.5704 , 6.22917 , 5.01111 , 0.749822,0.24657,0.613979 -1.50309 , 5.96059 , 4.97342 , 0.577228,0.270979,0.77031 -1.47028 , 5.88813 , 5.06618 , 0.830321,-0.372121,-0.414841 -1.56476 , 6.56137 , 5.71439 , 0.714489,-0.590194,-0.375736 -1.44228 , 5.96694 , 5.42291 , -0.964163,-0.200215,-0.174082 -1.33542 , 5.43771 , 5.15539 , -0.373376,-0.429423,0.822306 -1.28758 , 5.25601 , 5.14938 , 0.401598,-0.804953,-0.436771 -1.366 , 5.89643 , 5.84307 , -0.391349,0.0280047,0.919816 -1.26848 , 5.40161 , 5.57022 , 0.483888,-0.379109,0.788751 -1.21318 , 5.1654 , 5.51039 , 0.816562,-0.209924,0.537734 -1.18305 , 5.09921 , 5.60111 , -0.787247,0.312925,-0.531338 -1.14244 , 4.95994 , 5.62091 , -0.987698,0.0117827,-0.155929 -1.1725 , 5.35146 , 6.17653 , 0.285735,-0.189385,-0.939409 -1.2674 , 6.28308 , 7.33125 , 0.284434,-0.0658688,0.95643 -1.05902 , 4.82957 , 5.96689 , -0.0355613,-0.264073,0.963847 -1.0122 , 4.6287 , 5.9102 , 0.369016,-0.357919,0.857742 -0.974814 , 4.49573 , 5.92367 , -0.786848,0.616849,0.0191772 -1.08188 , 5.71558 , 7.56051 , -0.367667,-0.0806833,0.926451 -0.907844 , 4.30717 , 6.03404 , -0.966331,-0.123935,-0.225485 -0.966065 , 5.17306 , 7.32462 , 0.835921,0.293198,0.463973 -0.891798 , 4.67258 , 6.87994 , -0.0924371,-0.932958,0.347914 -0.84739 , 4.48773 , 6.83245 , -0.5319,-0.843689,0.0726009 -0.814697 , 4.43096 , 6.96052 , 0.371231,-0.0592439,0.926649 -0.761296 , 4.07582 , 6.64873 , 0.118042,0.0295403,0.992569 -0.72551 , 3.95466 , 6.67034 , 0.330449,-0.0255817,0.943477 -0.698165 , 3.99878 , 6.9518 , 0.0180136,0.999794,-0.00932766 -0.666432 , 3.97183 , 7.13355 , -0.488311,0.813908,0.314811 -0.651933 , 4.46738 , 8.2237 , 0.833647,0.454584,-0.313666 -0.593633 , 3.72322 , 7.17544 , 0.724843,-0.128336,0.676855 -0.547251 , 2.99065 , 6.06048 , 0.000396949,0.902575,0.430533 -0.517826 , 2.91125 , 6.11374 , 0.235079,-0.901448,-0.363495 -0.488237 , 2.94218 , 6.38969 , -0.449153,0.739621,-0.501221 -0.458725 , 2.82638 , 6.3788 , -0.659961,0.596042,-0.457368 -0.429368 , 2.72011 , 6.38365 , -0.786124,0.317755,0.530133 -0.437715 , 1.77496 , 4.45089 , 0.576334,-0.203579,-0.791451 -0.418356 , 1.71443 , 4.46527 , -0.40134,0.556351,0.727599 -0.39884 , 1.67482 , 4.53474 , 0.0707083,-0.795929,-0.601246 -0.378683 , 1.6261 , 4.58485 , -0.210239,-0.743411,-0.634933 -0.35714 , 1.58659 , 4.66247 , 0.394732,0.724141,0.565515 -0.332774 , 1.56063 , 4.78689 , -0.649988,-0.653463,-0.387946 -0.196619 , 2.23868 , 7.12857 , 0.673635,-0.439462,0.594213 -0.248144 , 1.68132 , 5.64779 , -0.215162,-0.655375,0.724009 -0.281518 , 1.33215 , 4.70834 , -0.379189,-0.643893,0.664543 -0.260165 , 1.28039 , 4.76264 , -0.777094,-0.577971,-0.249149 -0.239861 , 1.22212 , 4.7969 , -0.669106,-0.538825,-0.511824 -0.112116 , 1.4908 , 6.25908 , -0.0884203,0.828785,-0.552538 -0.102765 , 1.3566 , 6.06194 , -0.805902,0.0177658,-0.591783 -0.0828702 , 1.26103 , 6.01821 , -0.351097,0.156574,-0.923155 -1.17841 , 1.497 , -1.14272 , -0.124472,0.125598,0.984242 -1.1973 , 1.55335 , -1.15249 , -0.109606,0.162103,0.980668 -1.21316 , 1.60613 , -1.15265 , -0.119377,0.192226,0.974063 -1.23423 , 1.66919 , -1.16799 , 0.092653,-0.165759,-0.981804 -1.25302 , 1.72752 , -1.17339 , -0.094296,0.164664,0.981832 -1.27527 , 1.79306 , -1.18551 , -0.0796428,0.188579,0.978823 -1.29641 , 1.85923 , -1.19589 , -0.0374543,0.170993,0.98456 -1.31742 , 1.92581 , -1.20443 , 0.0737765,-0.177357,-0.981377 -1.34162 , 1.99878 , -1.21891 , -0.0496681,0.173946,0.983502 -1.36709 , 2.07395 , -1.23141 , -0.067485,0.14686,0.986853 -1.3879 , 2.14279 , -1.23441 , -0.0702178,0.137936,0.987949 -1.41562 , 2.22614 , -1.25035 , -0.0755703,0.162901,0.983744 -1.44292 , 2.3091 , -1.26366 , -0.0729219,0.173685,0.982098 -1.4728 , 2.40088 , -1.28196 , -0.0433604,0.195508,0.979743 -1.50345 , 2.49307 , -1.29741 , -0.0135618,0.196414,0.980427 -1.53988 , 2.60046 , -1.32388 , -0.0313587,0.18085,0.983011 -1.57055 , 2.69589 , -1.3338 , -0.0630136,0.152655,0.986269 -1.60351 , 2.79943 , -1.34753 , -0.0296635,0.202501,0.978833 -1.64906 , 2.93292 , -1.38415 , -0.0330722,0.194055,0.980433 -1.6827 , 3.03878 , -1.39096 , -0.0579632,0.167238,0.984211 -1.72468 , 3.16871 , -1.41358 , -0.0618581,0.194382,0.978974 -1.77318 , 3.31432 , -1.44398 , -0.0543476,0.189813,0.980315 -1.81937 , 3.4553 , -1.46405 , -0.0515707,0.188034,0.980808 -1.86764 , 3.60495 , -1.48542 , -0.0528097,0.186225,0.981087 -1.92834 , 3.78672 , -1.52451 , -0.0475772,0.187475,0.981116 -1.98907 , 3.97178 , -1.55788 , -0.0566088,0.190523,0.980049 -2.05292 , 4.16674 , -1.59047 , -0.0344301,0.192806,0.980633 -2.12941 , 4.39655 , -1.6375 , -0.0353939,0.202583,0.978625 -2.2089 , 4.63668 , -1.6819 , -0.0412223,0.189197,0.981074 -2.29416 , 4.89701 , -1.72838 , -0.0456539,0.18727,0.981247 -2.38561 , 5.17569 , -1.77526 , -0.0528342,0.176991,0.982793 -2.48365 , 5.47483 , -1.82205 , -0.052116,0.184694,0.981413 -2.59661 , 5.82024 , -1.88126 , -0.0577591,0.182614,0.981487 -2.7215 , 6.20262 , -1.94557 , 0.0653415,-0.176914,-0.982055 -2.85591 , 6.61433 , -2.00911 , -0.0704215,0.177472,0.981603 -3.00846 , 7.08359 , -2.08255 , -0.248847,0.217938,0.943704 -3.18865 , 7.6348 , -2.17378 , -0.0706567,0.171779,0.982598 -3.37823 , 8.219 , -2.25685 , -0.0656014,0.177473,0.981937 -3.63542 , 9.00179 , -2.39608 , -0.0654818,0.184447,0.980659 -3.90817 , 9.83767 , -2.52425 , -0.0649991,0.179072,0.981687 -4.26979 , 10.9413 , -2.71469 , -0.0609368,0.183319,0.981163 -4.70527 , 12.271 , -2.93754 , -0.0589015,0.181216,0.981678 -5.21732 , 13.8397 , -3.18357 , -0.0791923,0.164361,0.983216 -5.63592 , 15.1674 , -3.2994 , -0.105945,0.144633,0.983797 -15.9353 , 50.0457 , -1.26975 , -0.52857,0.615028,-0.58511 -16.1078 , 51.4554 , 0.519758 , -0.169701,-0.981974,-0.0832434 -3.0883 , 9.91931 , 3.39632 , -0.0918635,-0.896455,-0.433509 -3.00878 , 9.71639 , 3.5238 , -0.0918636,-0.896455,-0.43351 -2.97794 , 9.69797 , 3.69711 , 0.0772818,0.882389,0.46413 -2.93049 , 9.61231 , 3.85066 , 0.120795,0.907844,0.401531 -2.89315 , 9.5698 , 4.0166 , -0.260346,-0.937043,-0.232746 -2.83789 , 9.45072 , 4.15676 , 0.48135,0.852581,0.203489 -2.84848 , 9.59601 , 4.38859 , -0.488814,-0.775268,-0.400025 -2.37809 , 7.81453 , 3.89647 , -0.374649,0.888415,-0.265247 -2.34968 , 7.78871 , 4.037 , 0.794633,-0.549755,0.257543 -2.34741 , 7.86877 , 4.22268 , 0.794633,-0.549755,0.257543 -2.24901 , 7.55072 , 4.23867 , 0.819685,0.123682,0.559303 -2.19396 , 7.41222 , 4.32598 , -0.63395,-0.0841561,-0.768782 -2.51004 , 8.85007 , 5.17089 , -0.112633,-0.306635,-0.945139 -1.89615 , 6.31026 , 4.07356 , 0.364898,-0.82112,0.438875 -1.90568 , 6.43604 , 4.27087 , 0.533552,-0.604839,0.591178 -1.92928 , 6.6261 , 4.51114 , 0.59359,0.411256,0.691751 -1.87413 , 6.46792 , 4.56424 , -0.523921,-0.780701,0.340606 -2.22598 , 8.1698 , 5.71667 , 0.18815,0.398884,0.897492 -1.55605 , 5.18248 , 4.05655 , -0.137967,0.743814,0.653992 -1.52739 , 5.12637 , 4.13688 , -0.0470517,0.936666,0.347048 -1.86983 , 6.84843 , 5.40072 , 0.286273,0.58777,0.756687 -1.90388 , 7.12709 , 5.75641 , 0.498578,0.0556584,0.865056 -1.47934 , 5.14176 , 4.50839 , -0.619307,-0.760903,0.193612 -1.48816 , 5.27575 , 4.73432 , -0.728022,0.670467,0.143029 -1.54222 , 5.65507 , 5.1584 , 0.848522,0.287023,0.444555 -1.49995 , 5.54267 , 5.21456 , -0.0215188,-0.0688214,0.997397 -1.48345 , 5.56663 , 5.38132 , 0.501967,-0.190345,0.843681 -1.53339 , 5.95614 , 5.86488 , -0.740706,-0.262783,0.618305 -1.49102 , 5.85573 , 5.94319 , 0.740706,0.262783,-0.618304 -1.42439 , 5.60708 , 5.88584 , 0.634044,-0.672208,-0.382262 -1.20476 , 4.45274 , 4.9625 , 0.696584,-0.168061,-0.697514 -1.17861 , 4.4101 , 5.05499 , 0.696584,-0.168061,-0.697514 -1.13829 , 4.27511 , 5.05523 , -0.663106,0.118403,0.739102 -1.40047 , 6.10086 , 7.0981 , -0.0440774,0.3393,0.939645 -1.17052 , 4.75772 , 5.85503 , -0.884035,-0.361688,-0.296082 -1.15333 , 4.79817 , 6.06499 , -0.490274,0.0038882,0.87156 -1.07282 , 4.39712 , 5.77305 , 0.723683,-0.302679,0.620217 -1.04061 , 4.33239 , 5.85825 , 0.800693,-0.0044505,0.599059 -1.02018 , 4.35328 , 6.05111 , 0.761606,-0.631161,-0.146942 -0.99162 , 4.32624 , 6.19067 , 0.744057,-0.623545,-0.239938 -0.992741 , 4.56006 , 6.68098 , -0.115137,0.602711,0.78961 -0.971671 , 4.63227 , 6.97866 , -0.0924371,-0.932958,0.347914 -0.942388 , 4.63788 , 7.19878 , 0.477669,-0.631388,0.610886 -0.855585 , 4.04746 , 6.55371 , 0.0497602,0.10832,0.99287 -0.818169 , 3.9514 , 6.60829 , 0.0807871,0.0841818,0.99317 -0.777253 , 3.80051 , 6.57672 , 0.0448083,0.120238,0.991733 -0.741462 , 3.71891 , 6.6523 , -0.205735,0.621886,0.7556 -0.740231 , 4.20874 , 7.70032 , -0.198853,0.704033,-0.681759 -0.685579 , 3.85728 , 7.33888 , 0.263437,-0.802583,0.535221 -0.643248 , 3.69129 , 7.28348 , 0.618202,-0.309041,0.722717 -0.582891 , 2.92041 , 6.06338 , 0.000396936,0.902575,0.430533 -0.552352 , 2.86 , 6.15112 , 0.235079,-0.901449,-0.363495 -0.52093 , 2.91815 , 6.49026 , 0.168539,-0.647888,-0.742857 -0.488024 , 2.76903 , 6.40585 , -0.653292,0.208056,0.727958 -0.472425 , 1.82807 , 4.51538 , 0.656544,0.0302571,-0.75368 -0.451789 , 1.75097 , 4.49394 , -0.708375,0.202909,0.676042 -0.431016 , 1.69368 , 4.51716 , 0.273374,-0.737457,-0.617595 -0.410082 , 1.64626 , 4.56753 , 0.0246089,0.688051,0.725245 -0.387535 , 1.601 , 4.62643 , -0.16665,-0.795926,-0.582005 -0.364335 , 1.55773 , 4.69409 , 0.230113,0.728832,0.644866 -0.341705 , 1.51212 , 4.7613 , 0.608665,0.672735,0.42066 -0.268207 , 1.77706 , 5.83951 , -0.318391,-0.838656,0.441909 -0.299379 , 1.38217 , 4.77835 , -0.251592,-0.547534,0.798065 -0.284525 , 1.28754 , 4.67927 , -0.137268,0.497341,0.856627 -0.261505 , 1.23705 , 4.73265 , 0.340812,-0.102776,0.934497 -0.233264 , 1.20073 , 4.85315 , 0.106089,0.922465,0.371219 -0.111682 , 1.4274 , 6.19103 , 0.183163,-0.778738,0.600015 -0.0926984 , 1.31757 , 6.08974 , -0.520143,0.795322,0.311309 -0.0697186 , 1.22152 , 6.04507 , -0.934537,0.246129,0.257025 -1.23174 , 1.50584 , -1.13262 , -0.110166,0.121597,0.986447 -1.25155 , 1.56211 , -1.14169 , -0.113823,0.15013,0.982092 -1.27438 , 1.62363 , -1.15728 , 0.107258,-0.204515,-0.972969 -1.29539 , 1.6823 , -1.16341 , 0.0861047,-0.130106,-0.987754 -1.31844 , 1.74648 , -1.17609 , 0.0971128,-0.187319,-0.977487 -1.34232 , 1.81085 , -1.18679 , 0.0830069,-0.200345,-0.976203 -1.36534 , 1.87681 , -1.19596 , 0.0730789,-0.180579,-0.980842 -1.39154 , 1.94915 , -1.21107 , 0.0765865,-0.179566,-0.98076 -1.41878 , 2.02272 , -1.22411 , -0.110108,0.147401,0.982929 -1.4449 , 2.09698 , -1.23514 , -0.10873,0.152405,0.982319 -1.46877 , 2.16638 , -1.2368 , 0.0788589,-0.158516,-0.984202 -1.49809 , 2.24865 , -1.25104 , 0.0720647,-0.186204,-0.979865 -1.52516 , 2.32607 , -1.25581 , -0.0505283,0.199642,0.978565 -1.56439 , 2.42981 , -1.28639 , -0.0325877,0.221528,0.974609 -1.60131 , 2.52887 , -1.30684 , -0.0371301,0.19018,0.981047 -1.63403 , 2.62356 , -1.31787 , -0.0582132,0.165733,0.984451 -1.67074 , 2.72493 , -1.33248 , -0.0478219,0.187264,0.981145 -1.71316 , 2.84172 , -1.35714 , -0.0455447,0.19514,0.979717 -1.75328 , 2.95378 , -1.37185 , -0.0679407,0.178034,0.981676 -1.79905 , 3.08148 , -1.39564 , -0.064816,0.17301,0.982785 -1.84571 , 3.21084 , -1.41541 , -0.0593177,0.189392,0.980108 -1.89888 , 3.35591 , -1.44288 , -0.0624493,0.194188,0.978975 -1.95873 , 3.51786 , -1.47726 , -0.0521311,0.18277,0.981773 -2.0109 , 3.66824 , -1.49551 , -0.0488415,0.185602,0.98141 -2.07741 , 3.85042 , -1.53078 , -0.0535365,0.187436,0.980817 -2.14371 , 4.03491 , -1.56021 , -0.0474125,0.199881,0.978672 -2.22343 , 4.25294 , -1.60443 , -0.0348261,0.206341,0.97786 -2.30713 , 4.48101 , -1.64621 , -0.0508218,0.193818,0.97972 -2.39665 , 4.72917 , -1.69055 , -0.0507402,0.193039,0.979878 -2.49263 , 4.9965 , -1.73607 , -0.063506,0.178366,0.981913 -2.59244 , 5.27435 , -1.77699 , -0.064987,0.183439,0.980881 -2.70917 , 5.59782 , -1.83107 , -0.0677086,0.186006,0.980213 -2.83538 , 5.94907 , -1.88681 , -0.0759832,0.181568,0.980438 -2.97493 , 6.33909 , -1.94744 , 0.193206,-0.162795,-0.967558 -3.12815 , 6.76627 , -2.01019 , 0.271942,-0.0515844,-0.96093 -3.31158 , 7.27635 , -2.09312 , -0.452731,0.332486,0.827338 -3.51844 , 7.85054 , -2.18354 , -0.0700601,0.174614,0.982141 -3.76177 , 8.52741 , -2.29269 , -0.0623689,0.183483,0.981042 -4.04903 , 9.32588 , -2.42171 , -0.0643459,0.181444,0.981294 -4.39616 , 10.2896 , -2.57957 , -0.0644571,0.18259,0.981074 -4.81003 , 11.4414 , -2.76385 , -0.061553,0.183585,0.981075 -5.33805 , 12.9085 , -3.00435 , -0.0696462,0.177021,0.98174 -5.93167 , 14.5682 , -3.24586 , -0.109034,0.149602,0.982716 -6.45514 , 16.0701 , -3.37954 , -0.126545,0.164994,0.978143 -8.43378 , 21.4778 , -4.47245 , 0.018297,0.129417,0.991421 -17.9169 , 47.9097 , -8.56297 , -0.806942,0.23865,-0.540269 -16.2438 , 49.6181 , 6.57961 , 0.504563,0.85048,-0.148659 -16.2749 , 52.8779 , 13.7513 , -0.504563,-0.85048,0.148659 -3.30244 , 9.71622 , 3.49391 , -0.0132128,-0.941545,-0.336629 -3.29294 , 9.77378 , 3.68917 , -0.100709,0.87606,0.471569 -3.22779 , 9.64399 , 3.83174 , 0.0763684,-0.952741,-0.294029 -3.15698 , 9.49255 , 3.96448 , -0.090465,0.913195,0.397355 -3.15773 , 9.58661 , 4.1757 , -0.0654045,0.982466,0.174593 -2.60529 , 7.73006 , 3.69483 , 0.0221288,-0.990279,0.137323 -2.58205 , 7.72632 , 3.84155 , 0.0221288,-0.990279,0.137323 -2.5361 , 7.63961 , 3.95638 , -0.374649,0.888415,-0.265247 -2.5829 , 7.89095 , 4.21075 , -0.374649,0.888415,-0.265247 -2.52281 , 7.75351 , 4.30732 , -0.830823,-0.094152,-0.548515 -2.32999 , 7.12073 , 4.17252 , -0.971158,-0.238017,-0.0141386 -2.32844 , 7.19631 , 4.35269 , -0.758395,-0.481832,-0.438948 -2.22019 , 6.8665 , 4.33564 , -0.858856,0.364939,-0.359424 -2.09917 , 6.47848 , 4.27601 , -0.415655,0.687273,-0.595723 -2.22078 , 7.03695 , 4.71739 , 0.635131,0.76617,-0.097939 -2.2166 , 7.10718 , 4.90916 , 0.208092,0.974779,0.0806484 -2.20317 , 7.14787 , 5.08934 , -0.315423,-0.857967,-0.405463 -1.71873 , 5.26636 , 4.09299 , 0.364873,-0.850936,-0.377856 -1.68445 , 5.19412 , 4.16483 , -0.247899,0.904108,0.348044 -1.64676 , 5.11177 , 4.22945 , 0.531428,-0.619853,-0.577379 -1.63608 , 5.14248 , 4.36983 , -0.0641124,0.914966,0.398406 -1.6655 , 5.34623 , 4.63746 , 0.74014,-0.67234,0.0123286 -1.62017 , 5.23389 , 4.68515 , -0.718677,-0.0215852,0.695009 -1.6155 , 5.30121 , 4.86737 , 0.513828,-0.665458,-0.54143 -1.56908 , 5.17884 , 4.90594 , 0.613375,0.789719,0.0107515 -1.54715 , 5.17109 , 5.03495 , -0.638446,-0.473562,-0.606733 -1.57212 , 5.38502 , 5.35648 , 0.663413,0.550675,0.506598 -1.63436 , 5.79948 , 5.86862 , -0.923368,-0.358123,0.138349 -1.46233 , 5.06322 , 5.36609 , 0.722905,0.154893,0.673362 -1.34858 , 4.59723 , 5.07606 , 0.622552,-0.197444,-0.757262 -1.31803 , 4.54641 , 5.16441 , -0.633273,0.27381,0.723873 -1.26542 , 4.37526 , 5.13264 , -0.680235,0.0676535,0.729865 -1.22965 , 4.28816 , 5.18171 , 0.55364,-0.0335756,-0.832079 -1.17433 , 4.09309 , 5.11249 , 0.626732,-0.196542,-0.754042 -1.2923 , 4.90571 , 6.15168 , 0.836273,0.312019,-0.450879 -1.19493 , 4.47034 , 5.82615 , -0.336872,0.0168236,-0.9414 -1.1759 , 4.50199 , 6.02697 , 0.0314352,-0.999496,0.00435423 -1.14873 , 4.49077 , 6.18361 , -0.850728,0.343137,0.398143 -1.11039 , 4.4137 , 6.26282 , 0.411743,-0.808713,-0.420061 -1.05882 , 4.23773 , 6.21412 , 0.917107,0.025617,-0.397816 -1.00638 , 4.04168 , 6.12837 , -0.80734,-0.590019,-0.00889685 -1.02924 , 4.43814 , 6.86644 , 0.196019,0.56036,0.804719 -0.980393 , 4.28101 , 6.84597 , -0.977338,-0.207716,-0.0408087 -0.917003 , 3.9997 , 6.62993 , 0.0497601,0.10832,0.99287 -0.877471 , 3.90294 , 6.68368 , -0.156648,0.0428128,0.986726 -0.832044 , 3.75878 , 6.65889 , 0.0448082,0.120238,0.991733 -0.892688 , 4.82924 , 8.67529 , -0.937173,-0.297984,0.181421 -0.780333 , 3.931 , 7.39713 , -0.239937,0.906531,-0.347322 -0.722873 , 3.62004 , 7.0807 , -0.662641,0.34793,-0.663214 -0.649232 , 2.93615 , 6.03105 , 0.0374708,0.912546,0.407255 -0.640294 , 3.43007 , 7.20616 , 0.72517,-0.185658,0.663068 -0.583369 , 2.84227 , 6.25981 , 0.23409,-0.893999,-0.382057 -0.556997 , 3.17578 , 7.19797 , 0.359045,-0.0227767,0.933042 -0.513488 , 2.70242 , 6.41406 , 0.0752767,-0.992477,-0.0965568 -0.48767 , 1.78387 , 4.51303 , 0.661444,-0.00361177,-0.749986 -0.464662 , 1.71518 , 4.50905 , -0.447097,0.510479,0.734517 -0.442236 , 1.66518 , 4.55023 , 0.0766539,0.595167,0.799938 -0.418677 , 1.61421 , 4.59051 , -0.145846,-0.761172,-0.631938 -0.394715 , 1.57219 , 4.65825 , -0.0861904,0.853967,0.513139 -0.370347 , 1.52807 , 4.7255 , 0.230132,0.702495,0.673454 -0.343151 , 1.49147 , 4.82055 , 0.643041,0.720156,0.260527 -0.279897 , 1.6743 , 5.66202 , -0.215162,-0.655374,0.72401 -0.277638 , 1.46076 , 5.19213 , -0.00277774,-0.996124,0.0879202 -0.279311 , 1.27513 , 4.76525 , 0.581655,-0.282826,0.762684 -0.257305 , 1.21113 , 4.76985 , -0.219769,-0.832768,-0.508133 -0.147449 , 1.42391 , 5.98891 , -0.510729,0.302895,-0.804618 -0.11029 , 1.36207 , 6.10238 , -0.781072,0.119227,-0.612953 -0.086755 , 1.2612 , 6.02874 , 0.488524,0.430444,0.758988 -1.27202 , 1.47066 , -1.1376 , -0.0640254,0.110592,0.991801 -1.28871 , 1.51743 , -1.13027 , -0.0808713,0.134709,0.98758 -1.3104 , 1.57346 , -1.13823 , -0.0803267,0.174094,0.981447 -1.33511 , 1.63471 , -1.15289 , -0.0755127,0.187862,0.979288 -1.35801 , 1.69313 , -1.15801 , 0.0818069,-0.121378,-0.98923 -1.37958 , 1.75116 , -1.16149 , -0.0964078,0.193475,0.976357 -1.41082 , 1.8264 , -1.18705 , 0.0727491,-0.19815,-0.977468 -1.43357 , 1.88691 , -1.1873 , 0.0867085,-0.176861,-0.980409 -1.46261 , 1.95883 , -1.20107 , 0.0813889,-0.17648,-0.980934 -1.48744 , 2.02637 , -1.20553 , -0.1004,0.162539,0.981581 -1.51641 , 2.10016 , -1.21542 , -0.0887744,0.147549,0.985063 -1.54851 , 2.18052 , -1.23045 , -0.0796828,0.164638,0.98313 -1.58416 , 2.26947 , -1.25046 , -0.0400596,0.187669,0.981415 -1.61732 , 2.35268 , -1.26061 , -0.0537013,0.206424,0.976988 -1.65607 , 2.44998 , -1.28227 , -0.0483948,0.218129,0.974719 -1.69579 , 2.54872 , -1.30089 , 0.0758168,-0.182026,-0.980367 -1.73107 , 2.64212 , -1.31 , -0.0609871,0.171552,0.983286 -1.7775 , 2.75766 , -1.33593 , -0.0471002,0.198935,0.97888 -1.82462 , 2.87381 , -1.35803 , -0.0650213,0.195265,0.978593 -1.87072 , 2.99199 , -1.37666 , -0.050823,0.188009,0.980852 -1.92116 , 3.11912 , -1.39761 , -0.0440409,0.188856,0.981017 -1.97495 , 3.25548 , -1.4207 , -0.0671373,0.170778,0.98302 -2.0284 , 3.39288 , -1.43921 , -0.0588381,0.198929,0.978246 -2.08975 , 3.54782 , -1.46501 , -0.0458274,0.191986,0.980327 -2.15748 , 3.71887 , -1.49675 , -0.0480473,0.180556,0.982391 -2.22597 , 3.892 , -1.52262 , -0.0475465,0.19337,0.979973 -2.3125 , 4.10677 , -1.56941 , -0.0308681,0.209055,0.977417 -2.40206 , 4.33175 , -1.61396 , -0.0479515,0.190987,0.980421 -2.49151 , 4.5604 , -1.65112 , -0.0551777,0.188355,0.98055 -2.59274 , 4.81526 , -1.69477 , -0.0646012,0.180771,0.981401 -2.69686 , 5.08076 , -1.73433 , -0.0691102,0.179377,0.98135 -2.81967 , 5.3903 , -1.78748 , -0.0674836,0.184919,0.980434 -2.94895 , 5.72069 , -1.8388 , -0.0802987,0.179378,0.980498 -3.08959 , 6.07859 , -1.89085 , 0.308399,-0.213201,-0.927058 -3.24776 , 6.48302 , -1.95098 , -0.301898,0.0301554,0.952863 -3.41725 , 6.91672 , -2.00845 , -0.79942,-0.00212579,0.60077 -3.40363 , 6.93862 , -1.86845 , -0.88161,-0.138232,0.451282 -3.39629 , 6.97525 , -1.73604 , 0.977259,0.0120431,-0.211706 -3.38481 , 7.00006 , -1.59972 , 0.998027,0.0626376,-0.00442523 -3.41634 , 7.12696 , -1.50248 , 0.998027,0.0626376,-0.00442524 -3.38847 , 7.11346 , -1.35257 , 0.988858,-0.0625743,-0.13507 -3.40779 , 7.21149 , -1.2419 , 0.984776,-0.0973637,-0.144002 -6.54084 , 14.8934 , -3.17441 , -0.109034,0.149602,0.982716 -8.47894 , 19.7238 , -4.17563 , -0.0447423,0.201999,0.978363 -18.0918 , 44.4491 , -7.32988 , 0.779828,-0.0180027,0.625735 -21.3635 , 53.0543 , -7.94353 , 0.407023,0.148332,0.901293 -21.2854 , 53.2526 , -6.96379 , 0.229927,0.467261,0.853698 -21.1724 , 53.3613 , -5.97154 , 0.229926,0.467262,0.853698 -18.2858 , 46.2934 , -4.1691 , 0.660387,0.663974,-0.350753 -18.6065 , 48.1955 , -1.69814 , -0.520802,-0.79955,0.299142 -17.3377 , 50.518 , 12.0894 , 0.997698,-0.0239023,-0.0634574 -3.65812 , 9.79105 , 3.30687 , 0.272669,0.895915,0.350696 -3.53005 , 9.65512 , 3.81083 , -0.181428,-0.949739,-0.255109 -3.49524 , 9.63387 , 3.98603 , 0.233108,0.888553,0.395139 -2.88395 , 7.79434 , 3.55234 , 0.0332996,-0.994601,0.0982887 -2.83835 , 7.72278 , 3.67478 , -0.0332996,0.994601,-0.0982886 -3.22285 , 9.03276 , 4.31427 , 0.704498,0.490406,0.513015 -3.25251 , 9.21788 , 4.5633 , 0.704498,0.490406,0.513015 -3.1821 , 9.07707 , 4.68699 , 0.697463,-0.715701,0.0362825 -3.1059 , 8.9173 , 4.7985 , -0.981512,0.12191,-0.147551 -2.56614 , 7.20247 , 4.19519 , -0.164965,-0.114435,-0.979638 -2.36767 , 6.60702 , 4.05627 , -0.203151,0.0562205,0.977532 -2.31757 , 6.50929 , 4.14337 , -0.0746095,-0.107703,0.99138 -2.28074 , 6.45432 , 4.24987 , 0.152708,-0.743336,-0.651254 -2.37552 , 6.85766 , 4.60536 , -0.813555,-0.579049,0.0531962 -2.3895 , 6.98959 , 4.82751 , -0.808185,-0.587853,0.0355771 -2.36401 , 6.98161 , 4.97646 , 0.467211,-0.337674,0.817123 -2.19814 , 6.46498 , 4.81569 , -0.182858,0.073876,0.98036 -1.84298 , 5.23936 , 4.18225 , -0.286566,0.880049,0.378673 -1.83151 , 5.26413 , 4.31837 , -0.309761,0.662142,0.682361 -1.76687 , 5.09206 , 4.32354 , -0.416958,0.652839,0.632414 -1.70847 , 4.93756 , 4.33475 , 0.292593,-0.938089,-0.185415 -1.81577 , 5.43134 , 4.81702 , -0.443776,0.773467,0.452561 -1.77805 , 5.36471 , 4.90163 , -0.871383,0.47925,0.10493 -1.68383 , 5.06586 , 4.80237 , 0.755841,0.578517,0.306631 -1.73047 , 5.34172 , 5.15963 , -0.934164,-0.331095,-0.133091 -1.66604 , 5.16401 , 5.15303 , -0.955093,0.0517782,-0.291748 -1.58159 , 4.90039 , 5.06298 , -0.585542,-0.270982,-0.764009 -1.55146 , 4.85828 , 5.16348 , -0.78282,-0.35313,-0.512339 -1.51298 , 4.78624 , 5.23629 , -0.850225,-0.0796235,0.520363 -1.49089 , 4.78396 , 5.37629 , -0.857735,-0.138495,0.495086 -1.4025 , 4.47747 , 5.2167 , 0.262308,-0.274163,-0.925219 -1.32192 , 4.19876 , 5.06868 , 0.389947,-0.323186,-0.86226 -1.29495 , 4.16812 , 5.17247 , -0.552239,0.0820569,0.829638 -1.31794 , 4.38892 , 5.55521 , 0.232665,-0.892589,0.386201 -1.30062 , 4.42204 , 5.74492 , -0.235272,0.888648,-0.393639 -1.39408 , 5.05293 , 6.6488 , 0.449132,-0.421742,-0.787664 -1.32499 , 4.83177 , 6.56902 , -0.700197,0.375659,0.607128 -1.28534 , 4.77433 , 6.68553 , 0.632193,-0.475926,-0.611414 -1.23408 , 4.64801 , 6.71446 , -0.462177,0.726895,0.507953 -1.1489 , 4.30797 , 6.45269 , -0.974706,0.18476,0.125743 -1.0978 , 4.16345 , 6.43969 , -0.746375,0.630473,0.213137 -1.05759 , 4.0933 , 6.52973 , 0.656318,-0.753826,-0.0314957 -1.02378 , 4.06071 , 6.67673 , -0.468673,0.85987,0.20241 -0.973683 , 3.91647 , 6.65613 , -0.143097,0.300229,0.943073 -0.960688 , 4.0737 , 7.11499 , -0.832362,0.546234,-0.0938191 -0.901571 , 3.85776 , 6.98112 , -0.258227,-0.00521351,0.96607 -0.88477 , 4.03592 , 7.51607 , -0.469504,0.440946,-0.76494 -0.806086 , 3.59653 , 6.97555 , 0.55113,-0.401869,0.731271 -0.75983 , 3.46777 , 6.96829 , -0.946729,-0.219658,-0.23549 -0.68608 , 2.94208 , 6.18479 , 0.224574,-0.97394,-0.0317572 -0.65071 , 2.89876 , 6.3086 , -0.400323,0.795788,0.454381 -0.614974 , 2.86427 , 6.45938 , -0.354535,-0.732891,-0.580668 -0.58474 , 3.0621 , 7.12889 , 0.53844,-0.275637,0.796308 -0.540711 , 2.88342 , 6.98999 , -0.0752957,-0.911944,0.403346 -0.500289 , 1.74219 , 4.51969 , 0.522908,-0.214613,-0.82493 -0.475878 , 1.6817 , 4.53328 , -0.217704,0.481978,0.848706 -0.451062 , 1.6291 , 4.56417 , 0.0862665,0.641605,0.762169 -0.426331 , 1.58836 , 4.63208 , 0.086961,-0.871792,-0.482097 -0.400705 , 1.5426 , 4.68994 , -0.127242,0.676374,0.725484 -0.37323 , 1.49807 , 4.75654 , 0.354519,0.798036,0.487294 -0.308956 , 1.72654 , 5.72064 , -0.384957,-0.779715,0.493815 -0.279975 , 1.63674 , 5.69384 , 0.215162,0.655375,-0.724009 -0.302953 , 1.29157 , 4.72075 , -0.397993,0.428154,0.811348 -0.277271 , 1.2366 , 4.75438 , 0.514867,-0.0734026,0.854122 -0.248533 , 1.18923 , 4.82605 , -0.0971896,0.988511,0.115759 -0.135151 , 1.39164 , 6.04667 , 0.562324,0.47782,0.674893 -0.102632 , 1.30923 , 6.06142 , -0.882112,0.441649,0.163781 -0.0808091 , 1.20273 , 5.94745 , 0.605814,0.787657,-0.112188 -1.30206 , 1.42226 , -1.11714 , 0.039915,-0.131506,-0.990512 -1.32562 , 1.47641 , -1.12689 , -0.0393954,0.112346,0.992888 -1.34929 , 1.53185 , -1.13529 , -0.0953225,0.072934,0.992771 -1.36972 , 1.58274 , -1.13405 , -0.0551269,0.195187,0.979216 -1.39967 , 1.64964 , -1.15577 , -0.0660496,0.149547,0.986546 -1.42012 , 1.70214 , -1.15182 , 0.0650872,-0.119843,-0.990657 -1.44788 , 1.76563 , -1.16213 , -0.0414535,0.20024,0.978869 -1.47788 , 1.83568 , -1.1787 , -0.0597044,0.196337,0.978717 -1.50869 , 1.906 , -1.19301 , -0.0787439,0.163109,0.983461 -1.53626 , 1.97173 , -1.19778 , -0.0641368,0.143279,0.987602 -1.57054 , 2.05091 , -1.21588 , -0.069902,0.148996,0.986364 -1.59806 , 2.11851 , -1.21687 , -0.0629645,0.144627,0.987481 -1.6332 , 2.19947 , -1.23038 , -0.0421661,0.20777,0.977268 -1.67142 , 2.28714 , -1.24846 , -0.0200854,0.172277,0.984844 -1.70642 , 2.3702 , -1.25711 , -0.0574871,0.201319,0.977837 -1.75218 , 2.47318 , -1.28354 , -0.0431533,0.188189,0.981184 -1.79373 , 2.57185 , -1.30036 , -0.0608974,0.178256,0.982098 -1.83624 , 2.67197 , -1.31405 , 0.0538842,-0.175231,-0.983052 -1.88294 , 2.77981 , -1.33112 , -0.0607775,0.194455,0.979027 -1.93283 , 2.89573 , -1.35102 , 0.0554326,-0.17887,-0.98231 -1.98266 , 3.01349 , -1.36722 , -0.0425395,0.180882,0.982584 -2.04027 , 3.14751 , -1.39196 , -0.0596339,0.176336,0.982522 -2.09851 , 3.28233 , -1.41211 , -0.0576964,0.185513,0.980946 -2.17121 , 3.44858 , -1.45092 , -0.0503545,0.195994,0.979311 -2.23695 , 3.60218 , -1.4729 , -0.0306847,0.183784,0.982488 -2.31026 , 3.77265 , -1.5008 , -0.0318056,0.172478,0.9845 -2.3913 , 3.96117 , -1.53374 , -0.0270592,0.19467,0.980496 -2.48409 , 4.17435 , -1.57559 , -0.0449564,0.196034,0.979566 -2.5768 , 4.39113 , -1.61034 , -0.0500387,0.189464,0.980612 -2.68466 , 4.64161 , -1.65703 , -0.0556567,0.181238,0.981863 -2.7888 , 4.88736 , -1.69048 , -0.0678828,0.171282,0.982881 -2.90888 , 5.16714 , -1.73332 , -0.0621761,0.17995,0.981709 -3.04428 , 5.48347 , -1.78429 , -0.0718864,0.175381,0.981873 -3.18782 , 5.81936 , -1.8326 , -0.21866,0.25895,0.940815 -3.35415 , 6.20897 , -1.8936 , -0.174179,0.0160493,0.984583 -3.46868 , 6.49454 , -1.88984 , -0.972433,-0.106348,0.207521 -3.43123 , 6.46478 , -1.73348 , -0.963574,-0.248529,0.0987856 -3.44842 , 6.54928 , -1.62978 , 0.542603,0.78866,-0.289134 -3.44184 , 6.58135 , -1.50328 , 0.977375,0.189146,0.0946717 -3.41739 , 6.57747 , -1.36371 , 0.998356,0.0474505,0.0321447 -3.39676 , 6.57914 , -1.2283 , 0.998849,-0.0470933,-0.00913404 -3.3987 , 6.6302 , -1.11151 , 0.986626,-0.0719612,-0.146259 -3.42006 , 6.72417 , -1.00789 , 0.981973,-0.0463853,-0.183241 -3.49096 , 6.9307 , -0.935673 , 0.972317,-0.0560151,-0.226854 -3.54568 , 7.10167 , -0.846554 , 0.972317,-0.0560151,-0.226854 -9.46775 , 20.4949 , -4.14517 , 0.00279295,0.146329,0.989232 -18.3107 , 41.3025 , -7.03311 , -0.92453,0.0348837,-0.37951 -27.5541 , 63.499 , -8.93772 , -0.179445,0.152996,0.971798 -27.5221 , 63.8831 , -7.77253 , -0.179445,0.152996,0.971798 -15.0234 , 34.9669 , -2.44175 , -0.827753,-0.560525,0.0252246 -14.9283 , 34.9897 , -1.78698 , 0.821045,0.569438,0.0403231 -14.935 , 35.2609 , -1.15031 , 0.764009,0.641134,-0.0723663 -14.8956 , 35.42 , -0.501016 , 0.742863,0.633715,-0.215776 -14.6623 , 35.105 , 0.163932 , -0.761943,-0.559645,0.325946 -14.64 , 35.3079 , 0.811709 , -0.775387,-0.521339,0.356344 -15.0738 , 36.6514 , 1.47937 , -0.922889,-0.353275,0.153206 -15.05 , 36.8618 , 2.16122 , -0.882065,-0.449573,0.140872 -3.87399 , 9.61229 , 3.4174 , -0.27027,-0.937783,-0.217983 -3.82805 , 9.56343 , 3.58299 , 0.258205,0.93055,0.259628 -3.79992 , 9.56572 , 3.76314 , 0.360953,0.858809,0.363538 -3.62487 , 9.3131 , 4.22088 , 0.172762,0.647448,0.742269 -3.46141 , 8.92143 , 4.25512 , -0.384597,0.917508,-0.101314 -3.41573 , 8.86682 , 4.40846 , -0.434804,0.895871,-0.0914418 -3.46332 , 9.09254 , 4.67711 , -0.137386,0.986693,0.0869654 -3.38132 , 8.9357 , 4.79071 , -0.981512,0.12191,-0.147551 -3.17074 , 8.3849 , 4.72087 , -0.957282,-0.0906763,-0.274569 -3.30965 , 8.89459 , 5.13519 , -0.83192,0.119121,0.54196 -2.55277 , 6.64211 , 4.19843 , 0.256363,0.871704,-0.417624 -2.49947 , 6.54427 , 4.28624 , 0.588403,-0.681498,-0.435134 -2.54196 , 6.75061 , 4.53638 , 0.638741,0.738273,-0.216709 -2.51617 , 6.7408 , 4.67615 , -0.811919,-0.16301,-0.560549 -2.37297 , 6.35299 , 4.59611 , -0.362405,0.846048,0.39098 -2.29104 , 6.15943 , 4.61892 , -0.88609,-0.297946,-0.355067 -2.10965 , 5.63191 , 4.42255 , -0.394368,-0.793283,0.463871 -1.96835 , 5.22396 , 4.28316 , -0.258756,0.867755,0.42432 -2.0361 , 5.52017 , 4.60667 , -0.411465,-0.8999,-0.144484 -2.04714 , 5.6327 , 4.81787 , -0.301713,0.191169,0.934036 -2.24389 , 6.40066 , 5.51799 , 0.812959,0.289736,0.505125 -2.18149 , 6.27011 , 5.57911 , 0.373705,0.387535,0.842711 -1.8163 , 5.04155 , 4.7725 , 0.742109,0.63743,0.207261 -1.81289 , 5.10551 , 4.95525 , -0.931239,-0.318422,-0.177206 -1.74102 , 4.91796 , 4.93285 , -0.848942,-0.142493,-0.508914 -1.73698 , 4.98379 , 5.12387 , -0.685638,-0.163099,-0.709436 -1.80587 , 5.33683 , 5.58089 , 0.756529,0.504607,-0.415976 -1.64335 , 4.79194 , 5.22704 , -0.220222,0.874411,0.432328 -1.59578 , 4.6911 , 5.27176 , 0.823741,-0.299585,-0.481352 -1.52294 , 4.48604 , 5.20944 , -0.0124613,0.173734,0.984714 -1.48346 , 4.41491 , 5.2753 , 0.120819,0.483435,0.867002 -1.42516 , 4.26088 , 5.25342 , 0.462719,-0.0165062,-0.886351 -1.4308 , 4.38811 , 5.53419 , 0.160988,-0.914315,0.371634 -1.37255 , 4.23226 , 5.50862 , -0.792461,-0.539325,-0.284841 -1.39534 , 4.45184 , 5.91567 , 0.0621765,-0.980507,0.186386 -1.49515 , 5.05675 , 6.81335 , -0.0211689,0.139388,0.990012 -1.40816 , 4.78008 , 6.66244 , 0.463915,-0.702465,-0.539747 -1.37497 , 4.76393 , 6.83373 , -0.512854,0.630958,0.582129 -1.31381 , 4.60753 , 6.82235 , -0.399852,0.708117,0.58197 -1.1684 , 3.98151 , 6.15352 , -0.893033,-0.445328,-0.0646191 -1.14565 , 4.01504 , 6.37922 , -0.949368,-0.314101,-0.00638908 -1.13334 , 4.12475 , 6.73138 , 0.166964,-0.96821,0.186257 -1.09691 , 4.09966 , 6.89623 , -0.910234,-0.382098,-0.15961 -1.09024 , 4.28237 , 7.39935 , 0.732869,-0.585626,0.346331 -1.01339 , 4.00103 , 7.16709 , -0.847213,0.525814,-0.0758254 -0.97762 , 4.00875 , 7.40989 , 0.547143,-0.278053,0.789507 -0.906149 , 3.72654 , 7.14945 , -0.621292,0.77325,0.126809 -0.839683 , 3.46294 , 6.89855 , -0.85826,0.489343,0.154706 -0.750396 , 2.90351 , 6.05542 , 0.0147625,0.954216,0.298755 -0.719508 , 2.92688 , 6.30347 , 0.471399,-0.577754,-0.666321 -0.679512 , 2.85064 , 6.36438 , 0.23299,-0.791002,-0.565714 -0.641131 , 2.80766 , 6.49642 , -0.381983,-0.617055,-0.687991 -0.59943 , 2.7322 , 6.56412 , 0.449612,0.811741,-0.372728 -0.537167 , 1.78084 , 4.5576 , -0.655121,-0.0735921,0.751931 -0.510514 , 1.70898 , 4.54409 , -0.495859,0.304581,0.813237 -0.484437 , 1.64976 , 4.55675 , -0.0973229,0.520853,0.84808 -0.458694 , 1.60331 , 4.60603 , -0.0676552,0.907633,0.414276 -0.430367 , 1.5653 , 4.68281 , 0.295431,-0.731753,-0.614213 -0.403574 , 1.51264 , 4.72118 , -0.0380725,0.684295,0.72821 -0.374196 , 1.47448 , 4.80614 , 0.488807,0.792679,0.364318 -0.310457 , 1.67967 , 5.72445 , -0.761765,-0.474675,0.440906 -0.282987 , 1.56606 , 5.61002 , -0.767234,-0.523942,0.369914 -0.298954 , 1.26065 , 4.73915 , 0.426079,-0.148722,0.892378 -0.27259 , 1.20063 , 4.7527 , 0.55923,0.489694,0.668926 -0.171424 , 1.38707 , 5.85511 , 0.226526,0.635944,0.737741 -0.122644 , 1.35018 , 6.06487 , -0.582606,0.22663,-0.780519 -0.0930499 , 1.25573 , 6.00989 , -0.638752,0.439933,-0.631233 -1.3613 , 1.43469 , -1.12324 , -0.0417303,0.105985,0.993492 -1.38285 , 1.48492 , -1.12383 , -0.0667776,0.0922652,0.993493 -1.40527 , 1.53523 , -1.12304 , -0.0593584,0.108008,0.992376 -1.43386 , 1.59561 , -1.13722 , -0.0742079,0.197678,0.977454 -1.46255 , 1.65737 , -1.14975 , -0.0759503,0.142815,0.986831 -1.48799 , 1.71457 , -1.15265 , 0.0448555,-0.160956,-0.985942 -1.52073 , 1.78282 , -1.16953 , -0.0377471,0.192744,0.980523 -1.54616 , 1.84172 , -1.16932 , -0.052905,0.185726,0.981176 -1.58289 , 1.91665 , -1.18978 , -0.0323471,0.182348,0.982702 -1.61564 , 1.98819 , -1.20093 , -0.051706,0.147672,0.987684 -1.64516 , 2.05513 , -1.20264 , 0.0483356,-0.140647,-0.988879 -1.68306 , 2.13424 , -1.21676 , -0.0472734,0.167432,0.98475 -1.72308 , 2.22024 , -1.23567 , -0.0389726,0.185227,0.981923 -1.76107 , 2.30239 , -1.24512 , -0.0402914,0.175215,0.983705 -1.80636 , 2.39726 , -1.26564 , -0.0151027,0.192223,0.981235 -1.84744 , 2.48778 , -1.27665 , -0.0561425,0.197468,0.9787 -1.89598 , 2.59217 , -1.29805 , -0.0464397,0.161028,0.985857 -1.94202 , 2.69083 , -1.3095 , -0.0558816,0.195329,0.979145 -1.99913 , 2.8118 , -1.33699 , -0.0473846,0.184615,0.981668 -2.05274 , 2.92732 , -1.35436 , -0.0404973,0.197026,0.979562 -2.11389 , 3.05817 , -1.38007 , -0.0466324,0.163597,0.985425 -2.16834 , 3.17721 , -1.38964 , -0.0613437,0.164217,0.984515 -2.23368 , 3.3191 , -1.41281 , -0.0278504,0.200514,0.979295 -2.30763 , 3.47746 , -1.44255 , -0.018769,0.194457,0.980731 -2.38988 , 3.65156 , -1.4777 , -0.0118738,0.182887,0.983062 -2.47214 , 3.82895 , -1.50711 , -0.0152973,0.172098,0.984961 -2.5674 , 4.03159 , -1.54619 , -0.0309951,0.189535,0.981385 -2.66667 , 4.24419 , -1.58311 , -0.0389916,0.182309,0.982468 -2.76993 , 4.46682 , -1.61757 , -0.0391239,0.175688,0.983668 -2.88594 , 4.71543 , -1.6585 , -0.0543555,0.166196,0.984594 -3.00605 , 4.97541 , -1.69542 , -0.052941,0.168364,0.984302 -3.13777 , 5.26213 , -1.73648 , -0.0589849,0.168416,0.98395 -3.28221 , 5.57664 , -1.78041 , 0.191769,-0.144284,-0.970777 -3.45197 , 5.94203 , -1.83754 , -0.166238,0.170625,0.971212 -3.64309 , 6.35324 , -1.90157 , 0.614532,0.433273,-0.65926 -3.58311 , 6.28352 , -1.72666 , -0.95223,-0.0857409,-0.293097 -3.4639 , 6.09425 , -1.50479 , -0.983632,-0.0550659,-0.171566 -3.43593 , 6.08229 , -1.36788 , 0.977867,-0.00463274,0.209175 -3.42851 , 6.11082 , -1.24927 , 0.998305,0.0266867,0.0517281 -3.41503 , 6.12792 , -1.12719 , 0.999435,0.0325259,0.00845121 -3.41432 , 6.1693 , -1.01468 , 0.998012,0.0507307,-0.0374007 -3.44233 , 6.26898 , -0.921111 , 0.967351,0.034441,-0.25109 -3.5796 , 6.68306 , -0.655639 , 0.95162,-0.0533529,-0.30261 -14.9761 , 31.2013 , -4.66298 , -0.11324,-0.873872,0.472784 -15.8168 , 33.9301 , -2.54032 , -0.76294,-0.637573,-0.106877 -15.8048 , 34.14 , -1.91258 , -0.827753,-0.560525,0.0252246 -15.5411 , 33.7937 , -1.2422 , -0.827753,-0.560525,0.0252246 -15.6498 , 34.2745 , -0.628412 , -0.786518,-0.605684,0.120567 -15.7711 , 35.0358 , 0.648854 , -0.795663,-0.508789,0.328716 -15.9081 , 35.5998 , 1.30754 , -0.882065,-0.449573,0.140872 -15.1086 , 34.5028 , 3.22608 , -0.865904,-0.477624,-0.148612 -15.7854 , 37.1652 , 6.16539 , -0.951647,0.210268,-0.223956 -15.0789 , 36.0015 , 7.35155 , -0.817031,-0.06144,-0.573311 -15.094 , 36.3171 , 8.09086 , -0.817031,-0.06144,-0.573311 -4.23678 , 9.58584 , 3.03431 , 0.525544,0.850685,-0.0118137 -4.20819 , 9.66358 , 3.41046 , -0.213376,-0.976857,0.0148582 -4.0995 , 9.46348 , 3.53698 , -0.247593,-0.924007,-0.291391 -4.1097 , 9.56629 , 3.7459 , -0.176937,-0.851858,-0.492982 -4.04874 , 9.48682 , 3.903 , 0.172733,0.749283,0.639327 -3.88457 , 9.21443 , 4.17205 , 0.245725,0.590077,0.769044 -3.83563 , 9.1632 , 4.33272 , 0.410539,0.341063,0.845656 -3.51081 , 8.37071 , 4.20247 , 0.756155,0.108658,0.645308 -3.27353 , 7.80262 , 4.13393 , -0.715554,0.35551,-0.601328 -3.26355 , 7.84665 , 4.30898 , -0.711009,0.319479,-0.626418 -3.36151 , 8.19028 , 4.62362 , 0.698801,0.69753,-0.15852 -3.35569 , 8.25153 , 4.82079 , 0.554977,0.744409,-0.371289 -2.86635 , 6.95239 , 4.3464 , -0.331816,0.457866,0.824777 -2.73006 , 6.63425 , 4.32679 , -0.455145,-0.3912,0.799879 -2.66681 , 6.51915 , 4.40563 , 0.724429,0.650176,-0.229071 -2.64674 , 6.52912 , 4.55134 , -0.696557,0.712239,0.0867376 -2.56921 , 6.37054 , 4.60111 , -0.917071,0.136634,-0.374582 -2.55621 , 6.40162 , 4.76078 , -0.592497,0.061897,-0.803191 -2.43574 , 6.11123 , 4.72158 , 0.395202,0.0171162,0.918435 -2.13285 , 5.25956 , 4.30177 , -0.165346,-0.173936,0.970777 -2.31123 , 5.87399 , 4.84267 , 0.504281,-0.00106935,0.863539 -2.15389 , 5.45382 , 4.68594 , 0.619302,0.755662,-0.213167 -2.14894 , 5.50972 , 4.85837 , 0.605055,0.777671,0.170695 -2.36631 , 6.28006 , 5.57943 , -0.697402,-0.681253,-0.222543 -2.22971 , 5.92197 , 5.45801 , -0.912385,0.320852,-0.254181 -1.89658 , 4.90328 , 4.78452 , -0.394558,-0.310673,-0.864758 -1.85834 , 4.84674 , 4.8665 , 0.786822,0.111439,0.607036 -1.84572 , 4.87833 , 5.02402 , 0.664582,-0.0838055,0.742501 -1.75368 , 4.63607 , 4.94174 , 0.744155,0.147035,0.651625 -1.91112 , 5.2725 , 5.66504 , 0.146849,-0.616754,0.773337 -1.77416 , 4.8696 , 5.43356 , 0.615692,0.391225,0.684008 -1.6917 , 4.65694 , 5.36865 , 0.130632,-0.322278,0.937589 -1.5817 , 4.33708 , 5.18466 , 0.489683,0.462024,0.739422 -1.54828 , 4.29408 , 5.27689 , 0.584181,0.534156,0.611072 -1.50766 , 4.22927 , 5.34658 , 0.679743,0.561816,0.4715 -1.55055 , 4.49603 , 5.79226 , 0.0223196,-0.93458,0.355053 -1.7022 , 5.22615 , 6.80337 , -0.0897191,0.0668415,0.993722 -1.62248 , 5.02395 , 6.75161 , -0.0897191,0.0668415,0.993722 -1.56431 , 4.9112 , 6.80224 , 0.253809,0.185246,0.94935 -1.49873 , 4.76062 , 6.80351 , 0.276051,-0.643022,-0.714366 -1.45227 , 4.69581 , 6.91182 , -0.0805931,0.664625,0.742818 -1.39742 , 4.59343 , 6.97084 , -0.0533696,0.574729,0.816601 -1.3571 , 4.56363 , 7.13368 , -0.641258,0.666204,0.380737 -1.28247 , 4.35702 , 7.04147 , 0.997421,-0.0583229,0.0418209 -1.24696 , 4.35686 , 7.25163 , 0.623942,0.12546,0.771334 -1.18102 , 4.19026 , 7.21065 , 0.73319,-0.553259,0.395395 -1.10352 , 3.94378 , 7.02916 , 0.804658,-0.521501,-0.283834 -1.04923 , 3.8303 , 7.05558 , 0.788481,-0.608375,-0.0904336 -1.01182 , 3.82923 , 7.27937 , -0.822402,0.341292,-0.455164 -0.942417 , 3.60741 , 7.10988 , 0.666677,-0.676094,0.313749 -0.820235 , 2.92226 , 6.04179 , 0.210898,0.863934,-0.457319 -0.792279 , 2.9649 , 6.32549 , 0.202832,0.924018,0.324113 -0.843336 , 3.87702 , 8.41826 , -0.893333,0.409429,-0.185268 -0.703208 , 2.77666 , 6.36538 , -0.682973,-0.568277,-0.458922 -0.668669 , 2.83154 , 6.71541 , -0.419515,-0.907644,0.0137535 -0.613183 , 2.54103 , 6.2871 , 0.276247,0.701277,-0.65719 -0.548588 , 1.7384 , 4.56423 , -0.44324,0.367333,0.817682 -0.520037 , 1.67185 , 4.55884 , -0.517208,0.341379,0.784829 -0.492065 , 1.61293 , 4.57068 , 0.166485,-0.680354,-0.713723 -0.462971 , 1.5933 , 4.69464 , 0.476508,-0.697154,-0.535647 -0.433709 , 1.53829 , 4.7238 , 0.244067,-0.575341,-0.78065 -0.405014 , 1.48595 , 4.76144 , 0.187719,0.773229,0.605704 -0.369371 , 1.48451 , 4.97034 , -0.569551,-0.808836,-0.146274 -0.31054 , 1.61682 , 5.66978 , -0.687289,-0.449834,0.570337 -0.321879 , 1.28638 , 4.73351 , 0.62195,0.112773,-0.774893 -0.294251 , 1.22474 , 4.73776 , -0.457005,-0.0661375,-0.887002 -0.26285 , 1.17895 , 4.80878 , 0.100552,0.983686,0.149166 -0.146324 , 1.38817 , 6.05847 , 0.660003,0.454139,0.598459 -0.106779 , 1.31344 , 6.1019 , 0.732137,-0.249906,0.633658 -0.0837163 , 1.20208 , 5.94781 , -0.63574,-0.764753,0.104825 -1.39091 , 1.38884 , -1.1113 , -0.0329202,0.0662594,0.997259 -1.41833 , 1.44217 , -1.12037 , -0.0553137,0.0367001,0.997794 -1.44153 , 1.49117 , -1.11985 , -0.086728,0.0483971,0.995056 -1.468 , 1.5463 , -1.12642 , -0.0354683,0.151063,0.987888 -1.49534 , 1.60155 , -1.13141 , -0.0721999,0.181761,0.980689 -1.52566 , 1.66212 , -1.14263 , -0.0381268,0.152025,0.987641 -1.55706 , 1.7238 , -1.15226 , -0.0180029,0.187219,0.982153 -1.59166 , 1.79186 , -1.16783 , -0.0724663,0.162065,0.984116 -1.62325 , 1.8563 , -1.17407 , 0.054927,-0.171585,-0.983637 -1.65779 , 1.92622 , -1.18585 , -0.050223,0.143325,0.988401 -1.69336 , 1.99738 , -1.19547 , -0.0631845,0.145686,0.987311 -1.72878 , 2.069 , -1.20304 , -0.0275753,0.154248,0.987647 -1.76852 , 2.14797 , -1.21565 , -0.0415633,0.190516,0.980804 -1.81559 , 2.23953 , -1.23982 , -0.0645431,0.166074,0.983999 -1.85094 , 2.31471 , -1.24049 , -0.00978698,0.211754,0.977274 -1.90748 , 2.4212 , -1.27256 , -0.0498424,0.18533,0.981411 -1.94713 , 2.50544 , -1.27506 , -0.0736775,0.165741,0.983413 -1.99918 , 2.60841 , -1.29403 , -0.0605898,0.182416,0.981353 -2.05242 , 2.71383 , -1.30987 , -0.0447826,0.189969,0.980768 -2.10885 , 2.82732 , -1.32862 , -0.0378431,0.199143,0.979239 -2.17477 , 2.95566 , -1.35567 , -0.0437082,0.183681,0.982014 -2.23181 , 3.07166 , -1.36662 , -0.054069,0.165723,0.984689 -2.30193 , 3.21102 , -1.39123 , -0.0174049,0.183037,0.982952 -2.38045 , 3.36583 , -1.4225 , -0.0158666,0.204126,0.978816 -2.4675 , 3.53731 , -1.45947 , -0.0126799,0.193478,0.981023 -2.55119 , 3.70459 , -1.48526 , -0.0305985,0.172658,0.984506 -2.63877 , 3.88051 , -1.51035 , -0.0320146,0.169397,0.985028 -2.73934 , 4.08174 , -1.54481 , -0.0380847,0.194199,0.980223 -2.85351 , 4.30745 , -1.58686 , -0.0371948,0.188212,0.981424 -2.96851 , 4.53671 , -1.62093 , -0.0542118,0.173458,0.983348 -3.0917 , 4.78368 , -1.65612 , -0.0486758,0.174185,0.983509 -3.23203 , 5.06546 , -1.70056 , -0.0501945,0.170023,0.984161 -3.38134 , 5.36532 , -1.74339 , 0.171659,-0.243441,-0.954604 -3.54426 , 5.69297 , -1.78798 , -0.0057464,0.271752,0.96235 -3.73362 , 6.07251 , -1.84469 , 0.453856,0.170629,0.874586 -3.50146 , 5.69777 , -1.52716 , 0.993632,0.106904,0.0355958 -3.47352 , 5.688 , -1.39485 , 0.986005,0.0815941,0.145386 -3.44079 , 5.66726 , -1.26032 , 0.99272,0.0638906,0.102106 -3.44319 , 5.70965 , -1.15438 , 0.998604,0.0185289,0.049466 -3.43995 , 5.74264 , -1.04479 , 0.998707,0.033421,-0.0382954 -3.43968 , 5.78269 , -0.938118 , 0.993408,0.0599286,-0.0977156 -3.47085 , 5.87931 , -0.85051 , -0.950319,-0.0139363,0.310966 -3.65128 , 6.38858 , -0.505158 , -0.904223,0.0287248,0.426094 -18.7002 , 36.2444 , -5.86329 , -0.665267,-0.259894,-0.699911 -26.8754 , 53.1133 , -6.99003 , -0.236076,0.345362,0.908291 -16.4671 , 32.933 , -2.00015 , 0.681473,0.699408,0.215462 -16.4132 , 33.0455 , -1.37522 , 0.75386,0.65078,0.0904469 -16.3754 , 33.8837 , 1.14176 , 0.855632,0.517482,-0.0103028 -16.4043 , 34.1819 , 1.78818 , 0.618278,0.641051,0.454737 -15.6565 , 33.0458 , 3.00757 , -0.410501,-0.840945,-0.352562 -15.5432 , 33.0324 , 3.62815 , 0.722832,0.680997,0.117291 -15.5749 , 33.3361 , 4.27908 , -0.834492,-0.477315,0.275307 -16.124 , 34.7883 , 5.07654 , -0.925791,0.345443,0.153559 -16.0555 , 34.8884 , 5.74604 , -0.860916,0.245916,-0.445363 -15.9541 , 34.9154 , 6.40904 , 0.731805,0.144084,0.666109 -15.2708 , 33.6306 , 6.84627 , -0.972401,-0.153796,-0.17545 -15.235 , 33.7998 , 7.51763 , 0.946249,0.322639,-0.0227396 -4.44836 , 9.40524 , 3.15109 , 0.717167,0.671404,0.186783 -4.41113 , 9.39045 , 3.32414 , -0.697416,-0.680472,-0.224875 -4.44182 , 9.5338 , 3.54023 , 0.603298,0.773644,0.193669 -4.40565 , 9.52184 , 3.71806 , -0.464781,-0.753691,-0.464681 -4.25618 , 9.24126 , 3.81315 , -0.410923,-0.638922,-0.650324 -4.2477 , 9.29452 , 4.00916 , 0.337368,0.528731,0.778863 -4.10299 , 9.01995 , 4.09328 , -0.40324,-0.510066,-0.759757 -4.04918 , 8.96259 , 4.24901 , -0.340724,-0.409545,-0.846274 -3.70166 , 8.18026 , 4.12032 , -0.417553,-0.830212,0.369319 -3.59405 , 7.98325 , 4.20223 , -0.223238,-0.0709246,0.97218 -3.55304 , 7.95008 , 4.348 , -0.384707,0.920309,0.0709369 -3.50797 , 7.90545 , 4.48937 , 0.103979,-0.990309,0.0920714 -3.45815 , 7.85039 , 4.62545 , 0.342228,0.87471,-0.343166 -3.81085 , 8.8334 , 5.27701 , 0.770925,0.0360689,-0.635904 -2.83355 , 6.37171 , 4.1879 , 0.757683,0.506621,0.411402 -2.7811 , 6.29477 , 4.28124 , 0.711131,0.406237,0.573815 -2.88754 , 6.63825 , 4.61032 , -0.101619,0.58427,0.805172 -2.55031 , 5.79882 , 4.26422 , 0.104127,-0.439036,0.892415 -2.61355 , 6.03023 , 4.53336 , -0.246086,-0.553031,0.795989 -2.53335 , 5.87613 , 4.57113 , -0.487727,-0.870036,0.0718278 -2.30443 , 5.30502 , 4.3308 , 0.289569,0.661356,-0.691924 -2.28393 , 5.30522 , 4.45422 , 0.0991004,0.924078,-0.369133 -2.31695 , 5.4603 , 4.68911 , -0.377005,-0.909715,0.17403 -2.3049 , 5.49349 , 4.84488 , 0.567487,0.638068,0.520411 -2.21278 , 5.2921 , 4.82789 , -0.689053,-0.639701,-0.340572 -2.21954 , 5.38095 , 5.03127 , -0.60314,-0.780524,-0.164331 -2.18449 , 5.34513 , 5.14098 , 0.250016,0.632828,0.732818 -1.97482 , 4.78033 , 4.80712 , 0.561111,-0.240273,0.7921 -1.9273 , 4.70283 , 4.86816 , -0.818897,-0.0525464,-0.57153 -1.86866 , 4.58835 , 4.89468 , -0.900891,-0.161915,-0.402714 -1.8389 , 4.56694 , 5.0042 , 0.254515,0.189965,0.948228 -1.80231 , 4.52205 , 5.09364 , 0.0950219,0.504877,0.857945 -1.74416 , 4.40605 , 5.11345 , -0.694542,-0.0240532,-0.71905 -1.67881 , 4.26328 , 5.10197 , -0.785807,-0.409526,-0.463461 -1.65743 , 4.26949 , 5.24319 , -0.529767,-0.517992,-0.671588 -1.62851 , 4.25329 , 5.36362 , 0.350669,0.524913,0.775563 -1.57532 , 4.14877 , 5.38892 , -0.538537,-0.630289,-0.559208 -1.63923 , 4.47473 , 5.91212 , 0.0223195,-0.93458,0.355053 -1.74215 , 4.96745 , 6.66783 , 0.666782,-0.0179851,0.745035 -1.69995 , 4.93183 , 6.81046 , -0.313397,-0.291416,-0.903802 -1.62407 , 4.75965 , 6.78141 , 0.220535,-0.511416,-0.830553 -1.57488 , 4.69661 , 6.88994 , -0.123625,-0.649518,-0.750229 -1.5198 , 4.60721 , 6.96564 , 0.308817,0.730282,0.609361 -1.30183 , 3.80423 , 6.02567 , 0.744823,0.597318,0.297406 -1.39083 , 4.34124 , 6.98845 , -0.823683,0.114011,-0.555471 -1.35855 , 4.36006 , 7.22304 , 0.201898,0.474321,0.856888 -1.19797 , 3.74819 , 6.47762 , -0.270601,-0.246011,-0.930727 -1.21596 , 4.01834 , 7.11259 , 0.983581,-0.15166,0.0978176 -1.14397 , 3.8283 , 7.01221 , 0.671043,-0.677708,-0.300688 -1.10951 , 3.85038 , 7.27005 , -0.851991,0.435967,-0.289902 -1.05603 , 3.76884 , 7.3552 , 0.642666,-0.488042,0.590589 -0.892571 , 2.94327 , 6.03698 , -0.180213,-0.918929,0.350847 -0.854639 , 2.90682 , 6.16049 , 0.2399,0.970294,0.0312585 -0.820551 , 2.91506 , 6.38244 , -0.573548,-0.0146427,0.819041 -0.772493 , 2.82375 , 6.40667 , -0.300177,0.314896,0.900408 -0.724812 , 2.72797 , 6.41992 , 0.126355,0.185304,0.974524 -0.668867 , 2.51368 , 6.15589 , 0.279944,0.713487,-0.642314 -0.588163 , 1.78644 , 4.63034 , 0.291132,-0.134948,-0.947117 -0.556877 , 1.70062 , 4.57944 , -0.409826,0.260998,0.874027 -0.526193 , 1.63842 , 4.58237 , 0.517133,-0.545412,-0.65962 -0.497051 , 1.60683 , 4.66884 , -0.342503,0.912787,0.22251 -0.466049 , 1.55937 , 4.71713 , 0.488708,-0.621966,-0.611819 -0.435374 , 1.50153 , 4.73603 , -0.0878812,0.575285,0.813218 -0.404294 , 1.4587 , 4.80146 , -0.388055,-0.748105,-0.538286 -0.339837 , 1.67923 , 5.77772 , -0.761765,-0.474675,0.440906 -0.346284 , 1.31578 , 4.74739 , 0.120379,-0.247559,0.961366 -0.317155 , 1.25054 , 4.73241 , -0.469406,0.0871346,-0.878673 -0.287151 , 1.19233 , 4.74527 , -0.464241,-0.387138,-0.796621 -0.186709 , 1.37657 , 5.83796 , -0.888727,-0.423552,-0.175407 -0.13428 , 1.34046 , 6.03699 , -0.630499,-0.0049317,-0.776175 -0.0986285 , 1.25349 , 6.01081 , -0.638752,0.439933,-0.631233 -1.45454 , 1.4028 , -1.12503 , 0.0572376,-0.0362705,-0.997702 -1.47269 , 1.44273 , -1.10843 , -0.0298306,0.0245884,0.999253 -1.50092 , 1.4963 , -1.11535 , -0.0753322,0.128432,0.988853 -1.53314 , 1.55492 , -1.12865 , -0.0496847,0.141344,0.988713 -1.56234 , 1.60995 , -1.13243 , -0.0452659,0.158259,0.986359 -1.59454 , 1.67027 , -1.14262 , -0.0135804,0.202438,0.979201 -1.63188 , 1.73652 , -1.15861 , -0.0715491,0.142753,0.987169 -1.66021 , 1.79481 , -1.15784 , -0.076282,0.154903,0.98498 -1.70154 , 1.86772 , -1.1775 , -0.0615367,0.195993,0.978673 -1.73485 , 1.93241 , -1.18048 , -0.0625415,0.181026,0.981488 -1.77632 , 2.00825 , -1.19596 , -0.035939,0.166671,0.985357 -1.81784 , 2.08561 , -1.2091 , -0.0582033,0.149202,0.987092 -1.85614 , 2.15833 , -1.21301 , -0.0678529,0.19247,0.978954 -1.90177 , 2.24365 , -1.22847 , -0.0444023,0.217671,0.975012 -1.95686 , 2.34227 , -1.25465 , 0.0641856,-0.192582,-0.97918 -1.99904 , 2.42365 , -1.25776 , -0.0852866,0.167431,0.982188 -2.0551 , 2.52538 , -1.2779 , -0.0866929,0.184769,0.978951 -2.10573 , 2.62204 , -1.28845 , 0.0638434,-0.207807,-0.976084 -2.17012 , 2.7394 , -1.31448 , -0.0446167,0.207756,0.977163 -2.231 , 2.85133 , -1.33039 , -0.0551833,0.198774,0.978491 -2.30063 , 2.97931 , -1.35472 , -0.0653084,0.179887,0.981517 -2.3648 , 3.10232 , -1.36898 , -0.0337687,0.180602,0.982976 -2.44884 , 3.25338 , -1.40157 , -0.0144666,0.20086,0.979513 -2.53196 , 3.40782 , -1.42913 , -0.0287629,0.20439,0.978467 -2.62968 , 3.58481 , -1.46737 , -0.0431138,0.183969,0.981986 -2.71774 , 3.7508 , -1.48905 , -0.0482217,0.185544,0.981452 -2.81955 , 3.94081 , -1.52037 , -0.0474318,0.19577,0.979502 -2.93574 , 4.15403 , -1.55945 , -0.0459615,0.193494,0.980024 -3.05732 , 4.37905 , -1.59597 , -0.0614149,0.176201,0.982436 -3.17829 , 4.60592 , -1.62432 , -0.0627109,0.181603,0.98137 -3.31842 , 4.86693 , -1.66276 , -0.270671,0.0687502,0.960214 -3.47184 , 5.15338 , -1.70451 , -0.120938,0.0376006,0.991948 -3.63017 , 5.45144 , -1.74019 , 0.0235544,0.118999,0.992615 -3.82549 , 5.81575 , -1.79733 , 0.713051,0.165067,0.681404 -3.51088 , 5.32927 , -1.42288 , 0.987116,0.0925161,0.130548 -3.49198 , 5.33461 , -1.30318 , 0.990414,0.0925904,0.102509 -3.47714 , 5.34642 , -1.18792 , 0.994358,0.0869661,0.0607394 -3.46168 , 5.35514 , -1.07315 , 0.999305,0.0320675,-0.0189823 -3.46302 , 5.3947 , -0.971997 , 0.994372,0.0291825,-0.101849 -3.46923 , 5.44097 , -0.873232 , -0.975368,-0.0439521,0.216163 -3.50275 , 5.5359 , -0.790929 , -0.952005,-0.045224,0.302723 -3.65676 , 5.9579 , -0.446955 , -0.903688,0.0205294,0.427699 -19.0419 , 34.2648 , -5.74772 , -0.952507,-0.165926,-0.255341 -18.9564 , 34.3369 , -5.06607 , -0.935389,-0.251921,-0.248159 -17.5897 , 32.4578 , -2.78764 , 0.269341,0.962759,0.0234752 -17.348 , 32.2147 , -2.12539 , 0.269342,0.962759,0.0234754 -17.3141 , 32.367 , -1.50794 , 0.257124,0.948054,0.187299 -17.2714 , 32.5001 , -0.886628 , 0.00509386,0.997873,0.0649837 -16.9148 , 32.0292 , -0.238737 , 0.216554,0.974844,0.0527565 -16.8726 , 32.1608 , 0.375567 , 0.206703,0.950895,-0.230374 -16.855 , 32.3446 , 0.992848 , -0.0673685,-0.848641,0.524662 -17.0515 , 33.1748 , 2.2612 , -0.238833,-0.970598,0.0299671 -10.0455 , 19.5172 , 2.49312 , 0.652375,-0.738511,-0.17032 -16.28 , 32.2983 , 4.07538 , -0.689019,-0.72473,0.00439714 -16.4455 , 32.8627 , 4.7549 , -0.864201,-0.497976,0.0719445 -17.5749 , 35.4159 , 5.72221 , -0.860977,-0.0922232,-0.500214 -16.1667 , 32.983 , 6.65893 , -0.987523,-0.0533027,-0.148181 -16.1358 , 33.1572 , 7.32509 , -0.94414,-0.329447,0.00806257 -4.68964 , 9.16019 , 2.90649 , -0.59099,-0.762091,-0.264475 -4.70813 , 9.26585 , 3.10366 , -0.586487,-0.773306,-0.240898 -4.62489 , 9.15539 , 3.25192 , -0.526055,-0.850237,0.0190469 -4.56252 , 9.08762 , 3.40802 , 0.499381,0.864676,0.0543598 -4.56327 , 9.15819 , 3.60224 , -0.70974,-0.682862,-0.173116 -4.59415 , 9.29475 , 3.82132 , 0.624018,0.708197,0.33024 -4.47634 , 9.10462 , 3.93936 , 0.675454,0.180348,0.715008 -3.72446 , 7.49619 , 3.55504 , -0.35549,-0.743659,0.566214 -3.69229 , 7.48209 , 3.69695 , 0.025887,-0.860206,0.50929 -3.71534 , 7.59606 , 3.88889 , -0.149034,-0.87118,0.467797 -3.76604 , 7.77414 , 4.11395 , -0.549085,-0.614143,0.566864 -3.64372 , 7.55574 , 4.17646 , -0.683224,-0.725936,0.0788842 -3.81999 , 8.03231 , 4.54667 , 0.0735086,0.912989,0.401308 -3.753 , 7.94435 , 4.67081 , -0.274811,-0.929746,0.245052 -3.67892 , 7.83699 , 4.7842 , 0.830928,-0.168702,0.530187 -3.76009 , 8.10378 , 5.08832 , -0.591341,-0.794328,0.13914 -2.97559 , 6.28018 , 4.2761 , 0.920035,0.351911,-0.17232 -3.10759 , 6.66292 , 4.62741 , 0.236804,-0.471374,-0.849547 -2.80822 , 5.98741 , 4.37714 , 0.607847,-0.585064,-0.536863 -2.67549 , 5.71503 , 4.34428 , -0.982452,0.157137,0.100476 -2.76073 , 5.98996 , 4.64686 , 0.158748,-0.344941,0.925103 -2.49563 , 5.37622 , 4.38067 , -0.358461,-0.900839,0.244939 -2.42489 , 5.25162 , 4.41999 , 0.182995,0.955199,-0.232612 -2.47139 , 5.42973 , 4.67052 , 0.231197,0.972061,-0.0405683 -2.40721 , 5.32445 , 4.72467 , 0.0849073,0.739754,0.667498 -2.37872 , 5.31026 , 4.84519 , -0.36204,0.654644,0.663603 -2.31893 , 5.21152 , 4.90066 , 0.566166,0.771762,0.289549 -2.18732 , 4.91756 , 4.79545 , 0.2356,-0.232688,0.943583 -2.0366 , 4.56115 , 4.62471 , 0.279521,-0.251081,0.926729 -1.98824 , 4.48742 , 4.68268 , -0.644692,0.12124,-0.754767 -1.90989 , 4.32686 , 4.66109 , 0.64076,-0.0410378,0.766644 -1.84675 , 4.20404 , 4.66737 , -0.773106,-0.0684941,-0.630568 -1.87051 , 4.34069 , 4.91889 , -0.901994,0.0825392,-0.423785 -1.82037 , 4.25629 , 4.96382 , -0.864795,0.136974,-0.483082 -1.76078 , 4.14484 , 4.97849 , -0.896612,-0.127849,-0.423959 -1.77646 , 4.2684 , 5.23832 , -0.667603,-0.357537,-0.653049 -1.70621 , 4.12022 , 5.21516 , -0.871564,-0.116998,-0.476117 -1.63194 , 3.96165 , 5.17256 , -0.930628,-0.163412,-0.327457 -1.76308 , 4.47659 , 5.90695 , 0.356708,-0.934172,0.00905807 -1.82632 , 4.78719 , 6.44139 , -0.794079,0.118089,-0.596233 -1.75745 , 4.65856 , 6.45842 , 0.0764994,-0.989575,0.122022 -1.75518 , 4.76584 , 6.77539 , -0.365475,-0.461017,-0.808635 -1.70422 , 4.7044 , 6.88445 , 0.125813,0.387944,0.913056 -1.63861 , 4.5874 , 6.92089 , -0.349163,-0.742651,-0.57145 -1.605 , 4.59646 , 7.1322 , 0.319723,0.673027,0.666943 -1.45848 , 4.15342 , 6.69064 , 0.0150608,-0.765294,0.643504 -1.4157 , 4.1185 , 6.83092 , 0.117699,-0.601778,0.789943 -1.28934 , 3.72703 , 6.4189 , 0.559544,0.166513,0.811902 -1.22924 , 3.60437 , 6.40933 , -0.543209,0.290578,-0.787711 -1.19299 , 3.59994 , 6.59296 , -0.508537,0.178073,-0.842425 -1.12776 , 3.45091 , 6.53624 , 0.487123,-0.372234,0.790034 -1.06171 , 3.29059 , 6.44942 , -0.49701,0.47678,-0.725026 -1.00774 , 3.19027 , 6.46364 , -0.903035,0.26999,-0.334116 -0.902728 , 2.77056 , 5.85483 , 0.259678,-0.740477,0.619888 -0.903206 , 3.00245 , 6.51245 , 0.747274,-0.187957,-0.63738 -0.843012 , 2.84649 , 6.40299 , -0.266191,0.488441,0.831004 -0.793324 , 2.75635 , 6.42581 , -0.149364,0.0624333,0.986809 -0.740833 , 2.64548 , 6.40109 , 0.00340608,0.0603405,0.998172 -0.683302 , 2.44722 , 6.16179 , 0.219524,-0.613164,0.758841 -0.595695 , 1.72384 , 4.59086 , -0.186021,0.15854,0.969671 -0.563994 , 1.67306 , 4.62228 , 0.499506,-0.621249,-0.603774 -0.531408 , 1.61118 , 4.62447 , -0.476578,0.834503,0.276545 -0.49988 , 1.58909 , 4.73874 , 0.735115,-0.501142,-0.456577 -0.467218 , 1.52578 , 4.73899 , 0.534408,-0.456795,-0.711158 -0.435122 , 1.47119 , 4.76681 , -0.0589867,0.685796,0.725399 -0.400208 , 1.44226 , 4.87949 , 0.561161,0.746086,0.358405 -0.281501 , 2.06906 , 7.32934 , 0.473777,0.880485,0.0167505 -0.341783 , 1.27488 , 4.7272 , 0.341936,-0.248529,0.906263 -0.311246 , 1.21284 , 4.72095 , -0.578651,0.0221738,-0.815274 -0.272329 , 1.18499 , 4.85941 , -0.249227,0.964528,0.087011 -0.161356 , 1.37466 , 6.02142 , -0.884138,-0.0453018,-0.465024 -0.12659 , 1.27744 , 5.93676 , 0.193664,0.0919524,0.976749 -0.0863793 , 1.19946 , 5.93832 , -0.655589,-0.754746,-0.023717 -1.50869 , 1.40235 , -1.11318 , -0.0731705,-0.00116128,0.997319 -1.53455 , 1.44978 , -1.11199 , -0.083054,0.00304831,0.99654 -1.56466 , 1.50312 , -1.11779 , -0.077985,0.106078,0.991295 -1.59465 , 1.55681 , -1.12203 , -0.0484304,0.173785,0.983592 -1.62982 , 1.6163 , -1.13264 , -0.0372699,0.195535,0.979988 -1.66796 , 1.68117 , -1.14928 , -0.0926826,0.158399,0.983016 -1.69495 , 1.73289 , -1.14127 , -0.1005,0.159133,0.982129 -1.73401 , 1.79936 , -1.15409 , 0.0780751,-0.194274,-0.977835 -1.77745 , 1.87303 , -1.17263 , -0.0918171,0.213188,0.972687 -1.81641 , 1.94145 , -1.18127 , -0.0743696,0.17063,0.982525 -1.85667 , 2.01202 , -1.18815 , -0.0801807,0.181539,0.98011 -1.89556 , 2.08236 , -1.19271 , 0.066611,-0.161676,-0.984593 -1.94494 , 2.16553 , -1.20895 , -0.0744446,0.190594,0.978842 -1.99761 , 2.25647 , -1.22946 , -0.043583,0.207832,0.977193 -2.04681 , 2.34189 , -1.24016 , -0.0921039,0.188423,0.97776 -2.09602 , 2.42891 , -1.24823 , -0.0959001,0.180062,0.978969 -2.15463 , 2.5294 , -1.26625 , -0.0817289,0.200904,0.976196 -2.21765 , 2.63864 , -1.28746 , 0.0682567,-0.226374,-0.971646 -2.28553 , 2.75464 , -1.31086 , 0.0608426,-0.199069,-0.978095 -2.34917 , 2.86638 , -1.32437 , 0.0802241,-0.203547,-0.975773 -2.42325 , 2.99279 , -1.34586 , -0.0445446,0.192116,0.980361 -2.50575 , 3.13457 , -1.3744 , -0.0348769,0.198747,0.97943 -2.59345 , 3.28541 , -1.40368 , -0.048544,0.198054,0.978988 -2.68171 , 3.43729 , -1.4273 , -0.0663162,0.203499,0.976827 -2.77439 , 3.59956 , -1.45129 , -0.0710034,0.19791,0.977645 -2.88277 , 3.7854 , -1.48477 , -0.066507,0.185753,0.980343 -2.99064 , 3.97277 , -1.51145 , -0.0665126,0.201136,0.977303 -3.11765 , 4.19266 , -1.55103 , -0.0762123,0.192002,0.978431 -3.24526 , 4.41515 , -1.58241 , -0.0799278,0.1889,0.978738 -3.39255 , 4.66958 , -1.62376 , -0.301975,0.178088,0.936534 -3.54056 , 4.92787 , -1.65576 , 0.0935321,-0.147849,-0.984577 -3.70732 , 5.21986 , -1.6954 , 0.188069,0.324134,0.927128 -3.8894 , 5.53828 , -1.73628 , 0.508828,0.115407,0.853097 -3.52434 , 5.0067 , -1.33556 , 0.994636,0.0698698,0.0762665 -3.51023 , 5.01965 , -1.22411 , 0.994232,0.0753158,0.0763598 -3.49549 , 5.0295 , -1.11313 , 0.997428,0.0575549,0.0427199 -3.48921 , 5.05459 , -1.00979 , 0.997836,0.0468876,-0.046103 -3.48765 , 5.08521 , -0.909617 , 0.992578,0.0502432,-0.110746 -3.49936 , 5.13801 , -0.818395 , 0.98536,0.0331693,-0.167229 -3.52663 , 5.21476 , -0.734918 , -0.957901,-0.0252248,0.285987 -3.57133 , 5.3232 , -0.66028 , -0.940295,0.000875813,0.340361 -3.60073 , 5.40625 , -0.574365 , -0.923746,0.0554563,0.37897 -3.62948 , 5.48792 , -0.48572 , -0.914822,0.0177737,0.403467 -3.74853 , 5.75892 , -0.328881 , -0.907079,0.0185002,0.420553 -19.0808 , 31.985 , -5.55075 , 0.993478,0.0771933,0.083925 -19.0189 , 32.0892 , -4.90934 , -0.960853,-0.212196,-0.17814 -18.7309 , 32.2202 , -2.96977 , -0.334529,-0.942375,0.00448634 -18.6365 , 32.266 , -2.32961 , 0.279309,0.939664,-0.19753 -18.6702 , 32.5373 , -1.71099 , 0.185475,0.98123,-0.0527886 -18.3214 , 32.128 , -1.04065 , 0.0264018,-0.972744,0.230372 -18.6211 , 33.0941 , 0.195948 , -0.247582,0.938102,-0.242214 -18.2637 , 32.6615 , 0.844501 , 0.0908867,-0.911136,0.401959 -18.3974 , 33.1219 , 1.48614 , -0.325434,-0.912306,0.248578 -15.2999 , 27.6228 , 1.94618 , 0.859563,-0.15922,-0.485593 -15.2565 , 27.7254 , 2.48552 , 0.908339,-0.211666,-0.360718 -10.8102 , 19.5905 , 2.43261 , 0.654485,-0.725997,-0.211135 -17.7652 , 32.8284 , 4.02354 , -0.464097,-0.857669,-0.221401 -15.9156 , 29.5425 , 4.29215 , 0.998886,0.0233731,-0.0409922 -15.8739 , 29.6649 , 4.87813 , 0.997635,-0.027365,0.0630511 -15.8349 , 29.7943 , 5.47105 , -0.991387,0.125318,-0.0380511 -15.7081 , 29.757 , 6.04144 , 0.993574,-0.10252,-0.0479602 -14.0399 , 26.7098 , 6.04145 , 0.778736,0.489383,-0.392524 -5.00138 , 9.13556 , 2.88665 , 0.297505,0.94878,-0.106333 -4.84962 , 8.90072 , 3.00702 , 0.297505,0.948781,-0.106333 -4.97954 , 9.22204 , 3.25732 , -0.0289654,-0.997689,0.0614608 -16.9553 , 33.3453 , 9.911 , -0.965101,-0.254074,0.0634557 -4.88565 , 9.16655 , 3.59713 , -0.248287,-0.961565,-0.117247 -3.94528 , 7.42541 , 3.52837 , -0.348945,-0.805527,0.47892 -3.83894 , 7.25928 , 3.61368 , -0.348945,-0.805526,0.47892 -4.04412 , 7.74873 , 3.9488 , 0.149632,0.875293,-0.459861 -3.97046 , 7.65463 , 4.06581 , -0.13932,-0.872845,0.467687 -3.89659 , 7.55787 , 4.17981 , -0.296084,-0.955162,-0.000492168 -3.98645 , 7.81241 , 4.45044 , -0.401146,-0.873029,0.277312 -3.94354 , 7.7868 , 4.60001 , -0.269786,0.386485,0.881955 -3.75321 , 7.43437 , 4.58865 , -0.924112,-0.320079,0.208725 -3.71037 , 7.40524 , 4.73142 , -0.281097,-0.103396,0.954093 -3.42244 , 6.82552 , 4.57662 , -0.200525,0.356398,0.912562 -3.338 , 6.69732 , 4.65315 , -0.149002,0.330061,0.932126 -3.0136 , 6.02071 , 4.40311 , 0.769537,-0.448619,-0.454481 -2.8024 , 5.59252 , 4.27512 , -0.971893,0.132628,0.194509 -2.98963 , 6.0811 , 4.71127 , 0.260548,-0.323679,-0.909586 -2.80864 , 5.7164 , 4.61137 , -0.828204,-0.0824109,0.554335 -2.58955 , 5.25476 , 4.42918 , 0.403336,0.899259,-0.169273 -2.67212 , 5.50987 , 4.73439 , 0.14321,0.36353,0.920509 -2.55183 , 5.27628 , 4.69565 , 0.658928,0.225346,0.717658 -2.57421 , 5.39271 , 4.91391 , -0.462158,-0.673038,-0.577433 -2.52496 , 5.33168 , 5.00163 , -0.573842,-0.642354,-0.508022 -2.42521 , 5.14284 , 4.98535 , -0.209981,-0.888017,0.409065 -2.17784 , 4.57491 , 4.64199 , 0.213546,-0.316147,0.924364 -2.11035 , 4.45941 , 4.66315 , 0.226893,-0.0421129,0.973009 -2.02727 , 4.30121 , 4.64222 , 0.18504,0.0242889,0.982431 -2.00496 , 4.29981 , 4.76083 , -0.704062,0.617971,-0.349868 -2.06 , 4.51257 , 5.08733 , -0.697346,-0.165937,0.697261 -1.96697 , 4.32382 , 5.03391 , 0.165571,-0.619525,0.767316 -1.85264 , 4.07107 , 4.90485 , 0.99827,0.057991,-0.00966191 -1.79536 , 3.97595 , 4.93009 , -0.82856,-0.180071,-0.530153 -1.81377 , 4.09774 , 5.18971 , -0.94981,0.0511917,0.308612 -1.75843 , 4.0055 , 5.22101 , -0.902882,-0.398554,0.161119 -1.73356 , 4.00913 , 5.3608 , -0.675792,-0.736079,-0.0386263 -1.93991 , 4.72321 , 6.35987 , 0.357395,-0.839336,0.409614 -1.92919 , 4.7937 , 6.62109 , -0.921715,-0.157663,-0.354378 -1.51373 , 3.55852 , 5.22078 , 0.00335531,0.674746,0.738043 -1.46179 , 3.4737 , 5.24634 , 0.00335533,0.674746,0.738043 -1.76302 , 4.58756 , 6.90823 , 0.157266,0.373296,0.914285 -1.68912 , 4.45559 , 6.91834 , 0.516454,0.332186,0.789258 -1.52282 , 3.98415 , 6.42766 , -0.575566,-0.279569,0.768482 -1.51825 , 4.09612 , 6.77968 , -0.0220214,-0.708939,0.704926 -1.39246 , 3.75015 , 6.43575 , -0.0250915,0.220341,0.9751 -1.33087 , 3.63993 , 6.44382 , -0.534515,0.133593,-0.834534 -1.26947 , 3.52914 , 6.44936 , -0.551449,0.358325,-0.753331 -1.2023 , 3.39449 , 6.40898 , 0.494562,-0.305994,0.813497 -1.12463 , 3.19839 , 6.25229 , 0.456371,-0.359914,0.813749 -1.0264 , 2.89033 , 5.87071 , 0.0255804,-0.815111,0.578739 -0.960518 , 2.71756 , 5.71897 , 0.155724,-0.914991,0.372212 -0.933052 , 2.74994 , 5.96391 , -0.335545,-0.883089,0.327969 -0.907404 , 2.81875 , 6.30057 , -0.950551,-0.298432,-0.0859738 -0.862373 , 2.77749 , 6.42279 , -0.00752512,0.0963015,0.995324 -0.808603 , 2.68111 , 6.42585 , 0.00340608,0.0603405,0.998172 -0.757185 , 2.59576 , 6.45455 , -0.0843018,0.0875703,0.992585 -0.635018 , 1.73887 , 4.58362 , 0.311814,-0.0497665,-0.948839 -0.601817 , 1.68552 , 4.60594 , -0.150416,0.744815,0.650096 -0.602258 , 2.3286 , 6.5014 , -0.825337,0.0791312,0.559068 -0.54892 , 2.16974 , 6.31518 , -0.991292,-0.0719295,-0.110305 -0.501512 , 1.5706 , 4.80862 , 0.798361,-0.17246,-0.576954 -0.467197 , 1.49141 , 4.76073 , 0.443793,-0.460556,-0.768724 -0.431984 , 1.44144 , 4.79694 , 0.18907,0.740899,0.644455 -0.395412 , 1.41481 , 4.91874 , 0.788763,0.556458,0.261167 -0.316778 , 1.67316 , 6.10095 , -0.799014,0.189145,-0.57079 -0.335616 , 1.2363 , 4.71624 , 0.435482,-0.114689,0.892861 -0.30172 , 1.18506 , 4.7479 , -0.526021,-0.157012,-0.835852 -0.201026 , 1.36629 , 5.82069 , 0.943065,0.264854,0.201196 -0.146406 , 1.32759 , 5.99958 , 0.192506,-0.785316,0.588404 -0.103245 , 1.25144 , 6.01151 , -0.638752,0.439933,-0.631233 -1.57131 , 1.40814 , -1.11681 , 0.0581904,-0.0491152,-0.997097 -1.5901 , 1.44719 , -1.09864 , -0.0882318,0.0462918,0.995024 -1.62596 , 1.50397 , -1.11136 , -0.0791346,0.155058,0.984731 -1.66193 , 1.5621 , -1.12253 , -0.0420974,0.16887,0.984739 -1.69465 , 1.61567 , -1.12407 , -0.0569916,0.20724,0.976629 -1.73466 , 1.68033 , -1.13949 , 0.112823,-0.157006,-0.981132 -1.76737 , 1.73562 , -1.13783 , -0.0978369,0.137918,0.9856 -1.80829 , 1.80189 , -1.14944 , -0.0886145,0.198889,0.976008 -1.85027 , 1.86935 , -1.15908 , -0.073512,0.228172,0.970842 -1.89635 , 1.94317 , -1.17375 , -0.0791718,0.177976,0.980845 -1.94224 , 2.01753 , -1.186 , -0.0773074,0.185678,0.979565 -1.98819 , 2.09339 , -1.19601 , -0.0670801,0.169275,0.983283 -2.03517 , 2.17054 , -1.20366 , -0.0751295,0.212226,0.974328 -2.09138 , 2.25997 , -1.22214 , -0.0882242,0.180188,0.979668 -2.14337 , 2.34508 , -1.23101 , -0.0806104,0.165009,0.982992 -2.19937 , 2.43682 , -1.24365 , -0.0912132,0.185671,0.978369 -2.25656 , 2.531 , -1.25326 , -0.0567603,0.214051,0.975172 -2.33243 , 2.65076 , -1.28442 , 0.0756664,-0.22004,-0.972552 -2.39963 , 2.75927 , -1.29909 , 0.0787789,-0.202063,-0.976199 -2.47631 , 2.88265 , -1.32196 , -0.0670322,0.213884,0.974557 -2.55825 , 3.01492 , -1.34635 , -0.0437829,0.207448,0.977266 -2.64517 , 3.15525 , -1.37156 , -0.0466761,0.200538,0.978573 -2.73291 , 3.29747 , -1.3917 , -0.0652498,0.197897,0.978049 -2.83527 , 3.46217 , -1.42281 , 0.0762562,-0.20203,-0.976406 -2.93861 , 3.62994 , -1.44807 , 0.0771543,-0.200191,-0.976714 -3.05209 , 3.81333 , -1.47713 , 0.0729283,-0.192648,-0.978554 -3.17586 , 4.0135 , -1.50921 , -0.0766993,0.195875,0.977625 -3.30458 , 4.22349 , -1.53872 , -0.0806265,0.19197,0.978083 -3.44874 , 4.45786 , -1.57413 , -0.206749,0.310621,0.927777 -3.60417 , 4.71044 , -1.60962 , -0.149427,0.19623,0.969105 -3.7696 , 4.9807 , -1.64415 , 0.239995,0.265397,0.933791 -3.92405 , 5.23959 , -1.66048 , 0.0600924,0.129657,0.989736 -3.53709 , 4.71285 , -1.25756 , -0.906015,-0.142939,-0.398378 -3.52305 , 4.72392 , -1.14999 , 0.994187,0.0815759,0.0702668 -3.51403 , 4.74126 , -1.04675 , 0.997138,0.0678659,0.0333081 -3.50264 , 4.75702 , -0.94385 , 0.997505,0.0704554,0.00443769 -3.51173 , 4.80169 , -0.85438 , 0.995785,0.0414048,-0.0818365 -3.51022 , 4.83048 , -0.757897 , 0.995748,0.0394114,-0.0832671 -3.54373 , 4.91256 , -0.68184 , 0.99446,0.0297305,-0.100828 -3.71903 , 5.34582 , -0.273346 , -0.911734,0.0314448,0.409577 -18.8394 , 29.4672 , -5.27587 , -0.870758,-0.0763294,0.485751 -19.226 , 30.2787 , -4.81269 , -0.927779,-0.249749,0.277221 -19.5427 , 31.3873 , -3.07682 , 0.581307,0.760518,-0.289299 -19.5748 , 31.6429 , -2.46485 , 0.279309,0.939664,-0.19753 -19.5796 , 31.8558 , -1.84281 , 0.279309,0.939664,-0.19753 -19.681 , 32.2304 , -1.22758 , -0.212671,-0.926186,0.311369 -14.8869 , 24.4037 , -0.184583 , 0.640374,0.663601,-0.386723 -14.9284 , 24.6313 , 0.29359 , 0.640374,0.663601,-0.386723 -14.8882 , 24.7233 , 0.780268 , 0.116965,0.976014,-0.183619 -14.864 , 24.8422 , 1.26905 , 0.116965,0.976014,-0.183619 -14.9103 , 25.0828 , 1.76489 , -0.297275,-0.941886,0.156456 -14.8052 , 25.0667 , 2.25604 , -0.313198,-0.939919,0.135861 -14.7668 , 25.1637 , 2.75375 , -0.476535,-0.878818,0.0243581 -14.6732 , 25.1671 , 3.24608 , 0.66073,0.750399,-0.0183582 -14.6542 , 25.301 , 3.75262 , -0.702331,-0.701424,0.121387 -14.5918 , 25.3576 , 4.2548 , -0.692765,-0.704474,0.154252 -14.6293 , 25.5972 , 4.78638 , 0.833454,0.523393,-0.177242 -14.6813 , 25.8637 , 5.33262 , -0.816677,-0.541719,0.198948 -14.7394 , 26.1474 , 5.89361 , -0.774862,-0.591539,0.222869 -14.73 , 26.3108 , 6.44202 , 0.798811,0.423892,-0.426869 -15.7996 , 28.4651 , 7.45159 , -0.858669,0.278823,0.430054 -15.7441 , 28.5642 , 8.04047 , 0.935357,-0.122274,-0.331897 -15.5078 , 28.3272 , 8.54612 , -0.910044,-0.137957,0.390882 -5.19566 , 9.12761 , 3.58225 , -0.0435954,-0.986745,0.156314 -4.13242 , 7.39193 , 3.81353 , -0.348945,-0.805526,0.47892 -4.12984 , 7.4438 , 3.98458 , 0.447413,0.722076,-0.527662 -4.93935 , 9.10798 , 4.85862 , 0.0127626,0.587969,0.808783 -4.46242 , 8.22591 , 4.64671 , 0.282148,0.0760681,-0.956351 -4.40712 , 8.18278 , 4.79829 , 0.176463,-0.22907,-0.957281 -4.15395 , 7.735 , 4.74868 , -0.341121,-0.904997,-0.2542 -3.99354 , 7.46935 , 4.77596 , 0.582863,-0.127081,-0.802572 -4.01358 , 7.5762 , 4.9959 , -0.285624,0.776712,0.561371 -3.55091 , 6.67471 , 4.6516 , -0.252205,0.319616,0.913366 -3.4097 , 6.43806 , 4.65927 , 0.190759,-0.333899,-0.923105 -3.37919 , 6.4306 , 4.79971 , -0.951813,-0.276284,-0.133113 -3.24464 , 6.20134 , 4.80025 , 0.286152,-0.945104,0.157783 -3.33045 , 6.4486 , 5.10696 , -0.405494,-0.899582,0.162254 -3.24217 , 6.31843 , 5.16936 , -0.405494,-0.899582,0.162254 -2.70976 , 5.19982 , 4.52589 , 0.201283,0.962202,0.183447 -2.7184 , 5.27509 , 4.70658 , 0.707685,0.501254,0.497923 -2.63606 , 5.14403 , 4.73631 , -0.474657,-0.876651,-0.07863 -2.60899 , 5.13888 , 4.86158 , 0.478234,-0.180542,0.859475 -2.39412 , 4.69811 , 4.63305 , -0.281667,-0.338886,0.897675 -2.26654 , 4.45269 , 4.54885 , 0.115318,-0.187361,0.975499 -2.28724 , 4.55589 , 4.75702 , 0.282112,0.385925,-0.878336 -2.13046 , 4.23577 , 4.59191 , -0.277922,-0.041396,-0.959711 -2.11144 , 4.24316 , 4.71628 , 0.238452,-0.0894105,0.96703 -2.29838 , 4.76678 , 5.34134 , -0.673621,0.482399,-0.559934 -2.13997 , 4.43451 , 5.15111 , 0.109848,0.752102,0.649828 -2.11274 , 4.4315 , 5.28143 , -0.246241,0.461527,0.852267 -1.90557 , 3.96028 , 4.92035 , 0.965336,0.194597,0.173947 -1.86156 , 3.90608 , 4.98647 , -0.868922,-0.284546,-0.40498 -1.80209 , 3.81274 , 5.00754 , -0.868922,-0.284545,-0.40498 -1.87458 , 4.07933 , 5.44725 , 0.471882,-0.612152,-0.634506 -1.80771 , 3.96817 , 5.45462 , -0.934743,-0.329166,-0.133811 -1.74983 , 3.88046 , 5.48955 , -0.216996,-0.107277,0.97026 -1.60264 , 3.52855 , 5.18257 , 0.133174,0.394555,0.90917 -1.57295 , 3.51759 , 5.30197 , 0.00335533,0.674746,0.738043 -1.51311 , 3.41598 , 5.30298 , -0.0665212,0.776238,0.62692 -1.83328 , 4.52051 , 7.00333 , -0.770005,-0.309461,-0.557967 -1.73561 , 4.32344 , 6.91434 , 0.06146,-0.260821,0.963429 -1.69797 , 4.32716 , 7.11535 , -0.502613,-0.603244,-0.619255 -1.5515 , 3.95156 , 6.73556 , -0.0321229,-0.681333,0.731269 -1.42754 , 3.63903 , 6.4283 , 0.491329,0.323998,-0.808469 -1.34183 , 3.45429 , 6.30668 , 0.131647,-0.248771,0.959574 -1.29051 , 3.39305 , 6.38587 , 0.089831,-0.261757,0.960944 -1.22149 , 3.2575 , 6.33384 , 0.36498,-0.447216,0.816571 -1.1455 , 3.09131 , 6.21697 , 0.304843,-0.0602924,0.950492 -1.01467 , 2.65742 , 5.5748 , 0.155724,-0.914991,0.372212 -1.00664 , 2.77864 , 5.98758 , 0.234364,0.833268,-0.500737 -1.01787 , 3.03503 , 6.71027 , -0.908596,-0.19351,0.370145 -0.940529 , 2.8343 , 6.5013 , 0.484661,-0.291857,-0.824574 -0.874431 , 2.68112 , 6.37792 , 0.143643,0.280843,0.948944 -0.819051 , 2.59084 , 6.38822 , 0.168525,-0.27138,0.947603 -0.677554 , 1.7661 , 4.61373 , -0.138768,0.028051,0.989928 -0.640654 , 1.69868 , 4.59928 , -0.272517,0.656636,0.703252 -0.607009 , 1.6644 , 4.66742 , -0.309921,0.680818,0.663653 -0.601066 , 2.17267 , 6.24974 , -0.991292,-0.0719295,-0.110305 -0.549042 , 2.07555 , 6.22093 , -0.991292,-0.0719296,-0.110305 -0.50026 , 1.52346 , 4.79265 , -0.814452,0.20697,0.542062 -0.464519 , 1.45859 , 4.78171 , -0.118323,0.696851,0.707388 -0.428143 , 1.41381 , 4.8365 , 0.322218,0.792694,0.517505 -0.300984 , 2.21775 , 7.94293 , 0.808884,0.535031,-0.24382 -0.236792 , 2.10179 , 7.92024 , 0.774065,0.171986,-0.609298 -0.327273 , 1.20221 , 4.71417 , -0.578651,0.0221738,-0.815274 -0.280856 , 1.19332 , 4.93001 , 0.0234848,0.998327,-0.05284 -0.174948 , 1.35946 , 5.98464 , -0.85165,-0.0484177,-0.52187 -0.132909 , 1.27401 , 5.9379 , 0.193664,0.0919531,0.976749 -0.0866479 , 1.20348 , 5.96817 , -0.63574,-0.764753,0.104825 -1.6264 , 1.4036 , -1.10326 , -0.0960668,0.0377594,0.994658 -1.65507 , 1.4507 , -1.10035 , -0.115108,0.0555681,0.991798 -1.6887 , 1.50256 , -1.104 , -0.0475967,0.16179,0.985677 -1.72632 , 1.55948 , -1.11395 , -0.0623353,0.180094,0.981672 -1.76403 , 1.61777 , -1.12225 , -0.0837394,0.168039,0.982217 -1.8028 , 1.67722 , -1.12878 , -0.0797981,0.134707,0.987667 -1.84121 , 1.73613 , -1.13326 , -0.071344,0.128981,0.989077 -1.87994 , 1.79736 , -1.13629 , 0.0597655,-0.182857,-0.981321 -1.93186 , 1.87435 , -1.15906 , -0.0570754,0.196059,0.97893 -1.97127 , 1.93629 , -1.15788 , -0.0605189,0.191931,0.979541 -2.02402 , 2.01516 , -1.17567 , -0.0527425,0.167637,0.984437 -2.07279 , 2.09064 , -1.18415 , 0.0880835,-0.178751,-0.979944 -2.13178 , 2.17815 , -1.20353 , -0.0614092,0.221884,0.973137 -2.18535 , 2.26057 , -1.21332 , -0.0685743,0.174156,0.982327 -2.23992 , 2.34437 , -1.22037 , -0.0756333,0.156883,0.984717 -2.30388 , 2.44165 , -1.23737 , -0.0573869,0.177999,0.982356 -2.36878 , 2.54045 , -1.25094 , -0.038717,0.2025,0.978517 -2.44396 , 2.65277 , -1.27318 , -0.0644007,0.194429,0.9788 -2.51393 , 2.76104 , -1.28573 , -0.0473968,0.198108,0.979034 -2.60459 , 2.89591 , -1.31756 , -0.0348555,0.2079,0.977529 -2.69608 , 3.03268 , -1.3443 , -0.0401759,0.209571,0.976968 -2.78742 , 3.17157 , -1.36609 , -0.0576243,0.183074,0.981409 -2.88467 , 3.3184 , -1.3881 , -0.0611158,0.183523,0.981114 -2.9873 , 3.47545 , -1.41017 , -0.0523074,0.185749,0.981204 -3.10517 , 3.65412 , -1.44153 , -0.0642935,0.180757,0.981424 -3.21869 , 3.82888 , -1.46144 , -0.0564933,0.183888,0.981322 -3.3538 , 4.03357 , -1.4937 , -0.0521264,0.182309,0.981859 -3.50007 , 4.25515 , -1.5274 , 0.196255,-0.174182,-0.964959 -3.65646 , 4.49406 , -1.56179 , 0.119187,-0.107051,-0.987084 -3.82933 , 4.75856 , -1.60001 , 0.24802,0.347698,0.904208 -3.75869 , 4.69635 , -1.44218 , 0.765896,0.36573,0.528815 -3.56206 , 4.45966 , -1.19687 , -0.967006,-0.130557,-0.218755 -3.53687 , 4.45549 , -1.08495 , -0.962433,-0.112006,-0.247342 -3.53331 , 4.47945 , -0.988863 , 0.994174,0.0706598,0.0813911 -3.5276 , 4.50283 , -0.893115 , 0.998191,0.0600006,0.00374546 -3.52217 , 4.52306 , -0.796946 , 0.99774,0.0661134,-0.012037 -3.53127 , 4.56602 , -0.710684 , -0.963311,-0.0694291,-0.259251 -3.36947 , 4.36607 , -0.530387 , 0.833689,0.247283,0.493775 -3.73353 , 5.03894 , -0.240887 , -0.888654,-0.0157883,0.458307 -19.5179 , 28.7613 , -4.75704 , -0.919851,-0.0532418,0.388639 -19.4254 , 28.806 , -4.1507 , -0.928617,-0.132419,0.346605 -27.6978 , 41.8036 , -4.74868 , -0.222647,0.0174888,0.974742 -27.7186 , 42.1026 , -3.91082 , -0.222647,0.0174889,0.974742 -17.6833 , 26.8574 , -1.55129 , -0.628043,0.0259096,-0.777748 -17.5076 , 26.7562 , -0.992433 , -0.728086,0.0192839,-0.685214 -17.8985 , 27.5389 , -0.490673 , -0.628043,0.0259097,-0.777748 -16.6581 , 25.7591 , 0.131674 , -0.530556,-0.440218,-0.724375 -15.9875 , 24.86 , 0.665196 , 0.285025,-0.715056,-0.638323 -15.6986 , 24.5588 , 1.16315 , -0.594173,-0.789193,0.155349 -15.7356 , 24.7767 , 1.66014 , -0.600707,-0.785278,-0.149964 -15.562 , 24.6552 , 2.14921 , 0.665036,0.746449,0.0232752 -16.6943 , 26.8322 , 3.31755 , -0.471776,0.300974,0.828759 -16.4079 , 26.5354 , 3.81962 , -0.0819617,0.602648,0.793787 -15.2215 , 24.7396 , 4.12067 , 0.64698,0.760442,-0.0560771 -15.1705 , 24.8198 , 4.6234 , 0.650564,0.727401,-0.218301 -15.2143 , 25.228 , 5.68662 , -0.753063,-0.641814,0.144811 -15.0868 , 25.1823 , 6.18042 , -0.776785,-0.623636,0.087655 -15.1385 , 25.4428 , 6.74311 , 0.811591,0.554018,-0.185429 -15.7541 , 26.6851 , 7.56074 , 0.777084,0.131127,-0.615586 -16.6816 , 28.4891 , 8.58118 , 0.377052,0.872828,0.309844 -15.9856 , 27.4698 , 8.86458 , -0.910044,-0.137957,0.390882 -15.8389 , 27.6084 , 10.0316 , -0.764342,-0.644726,0.0104828 -16.9884 , 29.8738 , 11.3932 , -0.978718,0.00636323,0.20511 -4.45029 , 7.59939 , 4.2158 , 0.24328,0.904771,-0.349578 -4.41683 , 7.59712 , 4.37263 , -0.302014,-0.912568,0.275693 -4.39912 , 7.62369 , 4.54549 , -0.132852,-0.942717,0.305997 -4.40928 , 7.70419 , 4.74814 , -0.108503,0.988801,0.102464 -4.12145 , 7.21812 , 4.65999 , 0.0589489,0.210857,0.975738 -4.30344 , 7.62955 , 5.04215 , 0.210503,-0.929375,-0.303233 -4.30244 , 7.69314 , 5.24624 , 0.210503,-0.929375,-0.303234 -3.73183 , 6.64076 , 4.79538 , -0.28193,0.300707,0.911093 -3.52464 , 6.28847 , 4.72906 , 0.455756,-0.583249,-0.672389 -3.49249 , 6.2822 , 4.86819 , 0.253915,0.962663,0.0938479 -3.50105 , 6.35648 , 5.06431 , 0.381932,0.922991,0.0470702 -3.49427 , 6.40565 , 5.24769 , 0.393648,0.907281,0.147925 -3.00843 , 5.46576 , 4.73107 , -0.100254,0.167551,0.980753 -2.87269 , 5.23874 , 4.69545 , 0.315422,-0.334104,-0.888191 -2.81065 , 5.16156 , 4.76602 , 0.0670712,0.793255,0.605184 -3.06544 , 5.76077 , 5.37043 , -0.617856,-0.48261,-0.620759 -2.99645 , 5.67541 , 5.44902 , -0.617856,-0.48261,-0.620759 -2.94985 , 5.63909 , 5.56784 , -0.617856,-0.48261,-0.620759 -2.32555 , 4.32569 , 4.56949 , -0.460905,0.235971,-0.855503 -2.26199 , 4.2366 , 4.60615 , -0.460905,0.235971,-0.855503 -2.34097 , 4.4679 , 4.93919 , -0.837456,0.538959,-0.0904977 -2.58789 , 5.09477 , 5.67265 , 0.95883,-0.171618,0.226258 -2.2422 , 4.42088 , 5.28361 , -0.914122,0.342047,0.217682 -2.16358 , 4.2975 , 5.28896 , 0.861578,0.391073,-0.323643 -2.10228 , 4.21366 , 5.33334 , 0.159524,-0.0391113,0.986419 -1.93902 , 3.87386 , 5.08586 , -0.935457,-0.352951,-0.0186103 -2.34787 , 4.97779 , 6.50412 , 0.252713,-0.864493,0.434496 -1.88399 , 3.86686 , 5.34103 , 0.56277,0.710111,0.423122 -1.84294 , 3.83247 , 5.43527 , -0.117191,-0.0721351,0.990486 -1.75195 , 3.6639 , 5.35997 , 0.115183,-0.497416,0.859832 -1.67669 , 3.53368 , 5.32621 , -0.677589,0.44783,0.583371 -1.60184 , 3.39886 , 5.28088 , 0.00335532,0.674746,0.738043 -1.57085 , 3.39077 , 5.40754 , -0.248724,0.705505,0.663626 -1.84167 , 4.28006 , 6.84714 , -0.683712,0.0298829,0.72914 -1.58988 , 3.62663 , 6.05579 , -0.976512,-0.140634,-0.163237 -1.87597 , 4.63772 , 7.79691 , -0.461795,-0.782629,0.417418 -1.60909 , 3.91209 , 6.8573 , 0.527842,-0.788566,0.315511 -1.4353 , 3.45824 , 6.30063 , 0.273733,-0.306243,0.911749 -1.38642 , 3.41337 , 6.4059 , -0.385065,-0.257211,0.886323 -1.3033 , 3.24581 , 6.29416 , 0.0951215,-0.408708,0.907695 -1.23743 , 3.13783 , 6.28259 , -0.324586,0.192895,-0.925978 -1.09672 , 2.71771 , 5.66967 , 0.103926,-0.899603,0.424162 -1.04528 , 2.6426 , 5.69195 , 0.155724,-0.914991,0.372212 -1.09362 , 3.02823 , 6.66164 , -0.797504,-0.564487,0.212937 -1.04599 , 3.00713 , 6.83235 , -0.139072,-0.369613,0.918719 -1.01836 , 3.10389 , 7.27603 , -0.700757,0.0433053,-0.712084 -0.904506 , 2.72426 , 6.65226 , 0.0405896,-0.881849,0.469783 -0.814162 , 2.4249 , 6.16497 , -0.29008,-0.356954,0.88794 -0.681206 , 1.71543 , 4.60181 , -0.262209,0.511192,0.818492 -0.645337 , 1.67472 , 4.6515 , -0.14429,0.763055,0.630022 -0.66302 , 2.30393 , 6.5412 , 0.436232,0.137204,-0.889313 -0.602391 , 2.13767 , 6.32579 , -0.991292,-0.0719295,-0.110305 -0.548234 , 2.0449 , 6.30529 , -0.991292,-0.0719295,-0.110305 -0.49709 , 1.48275 , 4.79524 , -0.648447,0.284869,0.705951 -0.459207 , 1.42831 , 4.8118 , -0.0939938,0.759042,0.64422 -0.420202 , 1.39211 , 4.89467 , -0.56647,-0.72152,-0.398148 -0.341336 , 1.68295 , 6.20285 , -0.96314,0.261554,0.0628617 -0.352132 , 1.22252 , 4.69992 , -0.578653,0.112862,-0.807727 -0.240901 , 1.52092 , 6.19845 , -0.825347,0.468985,-0.314413 -0.210049 , 1.37144 , 5.88166 , -0.444357,-0.844397,-0.299234 -0.152986 , 1.32821 , 6.03067 , 0.244888,0.852216,0.462341 -0.109777 , 1.24086 , 5.97337 , 0.840578,-0.488109,0.234901 -1.68585 , 1.40067 , -1.09703 , -0.0742084,0.0993211,0.992284 -1.71641 , 1.44748 , -1.0932 , -0.0565828,0.100469,0.99333 -1.76085 , 1.50733 , -1.11132 , -0.0644104,0.18369,0.980872 -1.79526 , 1.55954 , -1.11232 , -0.0390235,0.158419,0.986601 -1.83581 , 1.61741 , -1.11929 , -0.0960721,0.141261,0.9853 -1.87622 , 1.67569 , -1.12441 , -0.0743466,0.139251,0.987462 -1.92055 , 1.7392 , -1.13514 , -0.0544428,0.126868,0.990424 -1.96091 , 1.79929 , -1.13666 , -0.035869,0.198673,0.979409 -2.0166 , 1.87573 , -1.15758 , -0.0593096,0.184712,0.981001 -2.06188 , 1.94241 , -1.16197 , -0.0637778,0.171666,0.983089 -2.11318 , 2.01506 , -1.17096 , -0.0888732,0.149242,0.984799 -2.15932 , 2.08351 , -1.17085 , -0.0496683,0.193511,0.97984 -2.23031 , 2.18142 , -1.20176 , -0.0536076,0.190894,0.980146 -2.28765 , 2.26333 , -1.20951 , -0.0880127,0.166329,0.982135 -2.3438 , 2.3461 , -1.21456 , -0.0527123,0.187996,0.980754 -2.41668 , 2.44873 , -1.2356 , -0.0167982,0.193345,0.980987 -2.48927 , 2.55222 , -1.25285 , -0.0313578,0.188944,0.981487 -2.56279 , 2.65731 , -1.26637 , -0.0273287,0.170747,0.984936 -2.64652 , 2.77609 , -1.28779 , -0.0384646,0.193179,0.980409 -2.73624 , 2.9026 , -1.31039 , -0.0413634,0.207251,0.977413 -2.84261 , 3.05084 , -1.3451 , -0.042521,0.193698,0.980139 -2.93302 , 3.18132 , -1.35786 , -0.0596398,0.182648,0.981368 -3.04001 , 3.33378 , -1.38165 , -0.0468291,0.180659,0.98243 -3.15307 , 3.49536 , -1.40489 , -0.0559076,0.185237,0.981102 -3.28231 , 3.67847 , -1.43671 , 0.0496658,-0.18054,-0.982313 -3.41774 , 3.87202 , -1.46653 , 0.277693,-0.0745461,-0.957773 -3.57037 , 4.08839 , -1.50259 , -0.142383,-0.0168192,0.989669 -3.71733 , 4.30041 , -1.52585 , -0.030548,0.219565,0.975119 -3.88687 , 4.54381 , -1.55833 , 0.0376981,0.2507,0.96733 -3.66726 , 4.29778 , -1.29433 , -0.975722,-0.0638418,-0.2095 -3.57517 , 4.20979 , -1.13443 , -0.967876,-0.0785681,-0.238838 -3.55043 , 4.20589 , -1.02571 , 0.987967,0.0899027,0.125853 -3.54094 , 4.22193 , -0.92931 , 0.997818,0.0546558,0.0370423 -3.53623 , 4.24334 , -0.836747 , 0.997958,0.0527417,-0.0360416 -3.54165 , 4.27868 , -0.751093 , 0.980814,0.0916433,0.172065 -3.55271 , 4.31948 , -0.667797 , -0.902871,-0.135759,-0.407913 -3.43562 , 4.19269 , -0.517138 , -0.892669,-0.297877,-0.338247 -3.43907 , 4.22293 , -0.433051 , -0.870027,-0.481982,-0.103665 -3.75113 , 4.75783 , -0.212169 , 0.786784,0.0656565,-0.613727 -19.6598 , 27.1293 , -4.66322 , -0.830331,-0.0411951,0.555746 -19.6435 , 27.2798 , -4.09866 , -0.968339,-0.198185,-0.151798 -20.8306 , 29.1387 , -3.82111 , -0.339699,0.0616202,0.938514 -28.1979 , 39.8442 , -4.7666 , -0.242932,0.100464,0.964827 -28.059 , 39.8972 , -3.92209 , -0.242932,0.100464,0.964827 -18.1422 , 25.8082 , -1.61258 , 0.500422,0.283879,0.817918 -17.4286 , 24.9321 , -0.999169 , -0.902426,-0.10528,-0.417784 -17.6314 , 25.3872 , -0.508233 , -0.902426,-0.10528,-0.417784 -17.788 , 25.7788 , 0.00139369 , -0.964903,-0.0418646,-0.259249 -15.9757 , 23.2546 , 0.582324 , 0.629643,0.471256,0.61763 -16.1606 , 23.6765 , 1.05916 , 0.244476,0.962916,0.114127 -16.1989 , 23.8858 , 1.54658 , -0.825029,-0.540737,0.164104 -16.017 , 23.7636 , 2.02707 , -0.371458,-0.923263,0.097997 -16.0018 , 23.8911 , 2.51725 , 0.155071,0.986713,0.0484769 -16.0895 , 24.1805 , 3.02448 , -0.111965,-0.977551,0.178487 -15.933 , 24.094 , 3.50449 , -0.245447,-0.968663,-0.0380406 -15.9542 , 24.2849 , 4.01461 , -0.475886,-0.832045,-0.285015 -16.6384 , 25.6811 , 5.22558 , 0.241861,0.815481,0.525827 -15.9456 , 24.7543 , 5.57345 , -0.921144,-0.112777,-0.372526 -15.8433 , 24.7565 , 6.07525 , -0.821539,-0.215916,-0.527688 -15.6889 , 24.6766 , 6.55945 , -0.946775,-0.319459,0.0395407 -15.7985 , 25.0214 , 7.14698 , -0.946775,-0.319459,0.0395407 -15.7518 , 25.117 , 7.68366 , -0.899407,-0.193181,0.392107 -17.0531 , 27.426 , 8.8647 , -0.397077,-0.716683,-0.573319 -17.0403 , 27.5995 , 9.48362 , 0.643218,0.662344,0.38415 -16.8462 , 27.474 , 10.0144 , -0.79162,-0.608786,-0.0521226 -16.8787 , 27.7272 , 10.6763 , -0.914126,-0.306453,0.265444 -16.5815 , 27.4288 , 11.1473 , -0.743737,-0.465332,0.479918 -4.71718 , 7.57181 , 4.2194 , -0.0558428,-0.881255,0.46933 -4.53039 , 7.30412 , 4.25597 , 0.151546,0.965501,-0.21176 -4.72954 , 7.70995 , 4.60634 , -0.0917557,-0.988497,0.120229 -4.55926 , 7.47049 , 4.65185 , -0.60968,0.790701,-0.0555208 -4.63685 , 7.66723 , 4.91796 , -0.42244,-0.87467,-0.23769 -4.36217 , 7.23781 , 4.85006 , 0.306015,-0.951964,0.0109323 -4.45082 , 7.45946 , 5.138 , 0.457264,0.877264,0.146007 -4.41102 , 7.45052 , 5.30069 , -0.0874741,0.984677,-0.150866 -3.85537 , 6.48901 , 4.87514 , -0.142148,0.374503,0.916265 -3.75856 , 6.36686 , 4.94577 , 0.176931,0.435686,0.882538 -3.63387 , 6.18981 , 4.97678 , -0.306237,-0.948274,0.0836404 -3.58633 , 6.15693 , 5.10093 , -0.414934,-0.0885274,-0.905535 -3.31188 , 5.68881 , 4.91258 , -0.279319,0.619413,-0.733695 -3.05584 , 5.24754 , 4.72365 , -0.163601,0.282667,0.945164 -2.95276 , 5.09869 , 4.73911 , 0.138923,-0.399419,-0.906181 -2.8953 , 5.03805 , 4.81893 , 0.0268536,-0.46897,-0.882806 -3.18238 , 5.66773 , 5.46697 , 0.268136,0.376525,0.886754 -3.06764 , 5.49746 , 5.47159 , -0.617856,-0.48261,-0.620759 -2.99535 , 5.41288 , 5.54492 , -0.678791,-0.58385,-0.445379 -2.98405 , 5.45199 , 5.73013 , 0.590434,0.650433,0.477832 -2.77266 , 5.07491 , 5.52911 , 0.438394,0.026391,0.898395 -2.85523 , 5.31604 , 5.90882 , -0.700037,0.683954,-0.205314 -2.85884 , 5.39428 , 6.14345 , 0.83897,-0.477011,0.261896 -2.84027 , 5.4262 , 6.34105 , -0.854922,0.46836,-0.223042 -2.80338 , 5.42218 , 6.50563 , 0.859925,-0.477295,0.180879 -2.20281 , 4.14479 , 5.27344 , -0.79757,-0.135195,-0.587881 -2.61164 , 5.14968 , 6.54857 , -0.831386,0.531233,-0.163059 -2.54411 , 5.07656 , 6.63725 , -0.78863,0.540974,-0.292252 -2.44519 , 4.92722 , 6.63503 , -0.430729,0.79654,-0.424259 -1.93358 , 3.77423 , 5.37428 , -0.0241132,-0.104107,0.994274 -1.87688 , 3.70356 , 5.42179 , -0.106067,-0.164996,0.980575 -1.75789 , 3.47515 , 5.25759 , -0.531668,-0.833857,-0.148365 -1.69881 , 3.3952 , 5.28286 , 0.560325,0.821544,0.105362 -1.68097 , 3.42219 , 5.45758 , -0.390113,0.699373,0.598907 -1.62287 , 3.34531 , 5.4887 , -0.261546,-0.772638,-0.578468 -1.58653 , 3.32753 , 5.60781 , -0.547974,-0.506156,-0.665981 -1.53761 , 3.27627 , 5.67721 , 0.839181,0.277156,0.467931 -1.50148 , 3.26393 , 5.81268 , -0.832233,-0.377548,-0.406012 -1.74401 , 4.11417 , 7.3849 , -0.476161,-0.497337,-0.725208 -1.50883 , 3.50415 , 6.55415 , -0.704661,-0.0947877,0.703184 -1.42222 , 3.35066 , 6.47063 , -0.101298,-0.565812,0.818288 -1.32171 , 3.13846 , 6.26982 , -0.324586,0.192895,-0.925978 -1.21356 , 2.88553 , 5.97495 , -0.0196796,0.919194,0.393312 -1.19281 , 2.9466 , 6.27507 , -0.56502,-0.0449803,-0.823851 -1.14137 , 2.89967 , 6.3724 , -0.989498,0.119726,-0.0809941 -1.10235 , 2.91425 , 6.60384 , 0.588908,0.72266,-0.361869 -1.05308 , 2.88932 , 6.7643 , -0.105065,0.54381,-0.832606 -0.959808 , 2.64974 , 6.44009 , -0.0556748,-0.467823,0.882067 -0.880715 , 2.46194 , 6.21028 , -0.408994,-0.336044,0.84841 -0.723754 , 1.73262 , 4.61394 , -0.230552,0.388818,0.892001 -0.685648 , 1.68553 , 4.64538 , -0.143046,0.623666,0.768491 -0.696688 , 2.08792 , 5.89456 , 0.749108,-0.624864,-0.21996 -0.651637 , 2.102 , 6.15692 , 0.901195,0.00701467,0.433358 -0.601813 , 2.10905 , 6.4202 , -0.949438,-0.0585203,0.308452 -0.532602 , 1.51827 , 4.8468 , 0.787863,-0.0383615,-0.614654 -0.491758 , 1.44647 , 4.80652 , -0.390792,0.590712,0.705932 -0.452223 , 1.40038 , 4.8512 , -0.187776,-0.800668,-0.568921 -0.410346 , 1.37789 , 4.98154 , -0.710487,-0.700556,-0.066549 -0.347278 , 1.48882 , 5.64376 , -0.495603,-0.855767,-0.148465 -0.27854 , 1.53821 , 6.13424 , 0.589624,-0.435543,0.680181 -0.241336 , 1.40254 , 5.87646 , -0.621779,-0.761072,-0.184826 -0.185396 , 1.35107 , 5.97694 , -0.701075,0.440343,-0.560884 -0.141395 , 1.26401 , 5.90996 , -0.600274,0.590469,-0.539461 -0.0897839 , 1.19669 , 5.9392 , -0.655589,-0.754746,-0.0237172 -1.71469 , 1.35111 , -1.09376 , -0.105769,0.0992966,0.989421 -1.74603 , 1.39661 , -1.0903 , 0.0892196,-0.156606,-0.983623 -1.78233 , 1.44689 , -1.09329 , -0.0818334,0.164107,0.983042 -1.81948 , 1.49731 , -1.09461 , -0.0531133,0.181716,0.981916 -1.86565 , 1.55736 , -1.10967 , -0.0822944,0.136211,0.987256 -1.90182 , 1.60971 , -1.10791 , -0.0843805,0.137207,0.986942 -1.94914 , 1.67233 , -1.11934 , 0.0531711,-0.167505,-0.984436 -1.99127 , 1.73082 , -1.1214 , -0.0382692,0.148246,0.98821 -2.04329 , 1.79901 , -1.1358 , -0.0492994,0.186172,0.98128 -2.09656 , 1.86946 , -1.14795 , -0.0650321,0.188463,0.979925 -2.14868 , 1.94068 , -1.15779 , -0.0918174,0.157872,0.983182 -2.20183 , 2.01318 , -1.16527 , -0.0740278,0.170997,0.982487 -2.26096 , 2.09178 , -1.17676 , -0.0608325,0.21361,0.975023 -2.3189 , 2.17122 , -1.18556 , -0.0901541,0.182233,0.979114 -2.384 , 2.25761 , -1.19796 , -0.0845034,0.185868,0.978934 -2.45427 , 2.35148 , -1.21371 , -0.0449076,0.207583,0.977186 -2.5346 , 2.45785 , -1.23823 , -0.0160678,0.180813,0.983386 -2.61068 , 2.55998 , -1.25275 , -0.0280673,0.191677,0.981057 -2.69892 , 2.67537 , -1.27501 , -0.0295606,0.169954,0.985009 -2.78098 , 2.78695 , -1.28752 , -0.0538223,0.189292,0.980445 -2.88049 , 2.91891 , -1.31268 , -0.0457916,0.221762,0.974025 -2.98591 , 3.05882 , -1.33807 , -0.07111,0.189566,0.97929 -3.09117 , 3.2009 , -1.35821 , -0.0534779,0.195525,0.97924 -3.21367 , 3.364 , -1.38818 , -0.0629416,0.185539,0.980619 -3.32577 , 3.51726 , -1.402 , 0.0589481,-0.192444,-0.979536 -3.47261 , 3.71179 , -1.4388 , 0.302195,-0.165695,-0.938735 -3.62007 , 3.90884 , -1.46779 , -0.0752244,0.144366,0.986661 -3.77245 , 4.11579 , -1.49383 , -0.0195683,0.0266835,0.999452 -3.93763 , 4.33843 , -1.52009 , 0.29695,0.142544,0.944194 -3.6053 , 3.97495 , -1.18183 , 0.990796,0.0922568,0.0990559 -3.57992 , 3.97193 , -1.0747 , 0.98787,0.0940176,0.123586 -3.57203 , 3.98919 , -0.980614 , 0.987494,0.0983225,0.123245 -3.55753 , 3.99727 , -0.882991 , 0.994207,0.0836895,0.0674442 -3.55326 , 4.019 , -0.793446 , 0.997799,0.0640259,-0.0172528 -3.55348 , 4.04527 , -0.707057 , 0.992431,0.0906599,0.082829 -3.57116 , 4.09356 , -0.630407 , -0.957318,-0.163711,-0.238203 -3.49291 , 4.02161 , -0.503322 , -0.940703,-0.293949,-0.169329 -3.50874 , 4.06612 , -0.426879 , -0.911494,-0.356371,0.205373 -3.71171 , 4.40221 , -0.256184 , 0.520803,0.0373038,-0.852862 -3.76482 , 4.49907 , -0.186834 , -0.41873,-0.0293663,0.907636 -3.93728 , 4.74975 , -0.155359 , -0.384233,0.0159637,0.923098 -16.9764 , 21.938 , -3.76441 , -0.271005,0.830745,-0.48623 -16.9983 , 22.1073 , -3.3074 , 0.343878,-0.779795,0.523132 -16.9797 , 22.2218 , -2.83809 , 0.0316522,-0.881508,0.471108 -20.2095 , 26.8559 , -2.48162 , 0.73125,0.157878,0.663587 -19.1863 , 25.6374 , -1.76614 , 0.367384,0.379561,0.849095 -17.7971 , 23.9029 , -1.06213 , -0.277684,-0.682675,-0.675905 -17.6446 , 23.8432 , -0.54944 , -0.438821,-0.762292,-0.475759 -17.4871 , 23.7761 , -0.0422752 , 0.976877,0.148909,0.153418 -17.5009 , 23.9449 , 0.453407 , 0.0879803,-0.986239,0.139975 -17.543 , 24.1548 , 0.953595 , -0.088674,0.987024,-0.133868 -17.5276 , 24.2855 , 1.45907 , -0.090037,0.982137,-0.16523 -17.2761 , 24.0819 , 1.95534 , -0.0574315,0.970975,0.232182 -17.2041 , 24.1322 , 2.45648 , -0.0184592,0.999804,-0.00709687 -17.1948 , 24.2738 , 2.96571 , 0.219846,0.960553,-0.170312 -17.1014 , 24.2928 , 3.46788 , 0.12408,0.892105,-0.434456 -17.5548 , 25.1097 , 4.06692 , -0.945941,-0.31578,0.0740143 -17.4807 , 25.1632 , 4.59111 , 0.828715,0.0959188,0.55139 -16.2776 , 23.554 , 4.84486 , -0.750176,-0.63365,-0.189005 -16.0176 , 23.3233 , 5.28649 , -0.790026,-0.562762,-0.243222 -15.8926 , 23.2906 , 5.75965 , -0.799822,-0.550241,-0.239832 -15.785 , 23.284 , 6.23798 , -0.767936,-0.632676,0.099978 -15.8342 , 23.5148 , 6.77624 , -0.906319,-0.395619,0.148563 -15.8173 , 23.6485 , 7.29932 , 0.890939,0.40433,-0.206749 -17.91 , 27.0241 , 8.76704 , -0.778462,-0.0886367,0.621402 -17.4068 , 26.6205 , 9.76648 , 0.716183,0.630145,0.299999 -16.9801 , 26.1415 , 10.1597 , -0.929098,-0.367943,-0.0373471 -17.033 , 26.414 , 10.8172 , 0.776319,0.509086,0.371699 -17.8937 , 27.9763 , 12.0013 , -0.854135,-0.280744,0.437762 -4.92645 , 7.38883 , 4.00269 , -0.11645,-0.857559,0.501031 -4.88964 , 7.38354 , 4.15615 , -0.116449,-0.857559,0.501031 -4.99239 , 7.60633 , 4.41579 , 0.0474572,-0.896506,0.440483 -4.88325 , 7.48481 , 4.52031 , 0.0274899,-0.916461,0.399178 -4.22311 , 6.45104 , 4.15859 , -0.894722,0.0280057,-0.445746 -4.2476 , 6.54199 , 4.34771 , -0.868732,-0.309749,-0.386472 -4.23258 , 6.56811 , 4.50639 , 0.99825,-0.00701011,-0.0587103 -4.06946 , 6.34528 , 4.52411 , -0.750843,-0.496936,-0.435075 -4.26588 , 6.7353 , 4.90139 , -0.572977,0.315715,0.756321 -4.00081 , 6.3334 , 4.80538 , -0.198147,-0.979446,-0.0377175 -3.96132 , 6.32139 , 4.9435 , 0.107297,0.971754,0.210193 -3.84871 , 6.17844 , 4.99628 , 0.279033,0.0534553,0.958793 -3.70683 , 5.98265 , 5.00762 , 0.0988913,-0.0637249,0.993056 -3.51328 , 5.69235 , 4.94231 , 0.337057,-0.203599,0.919206 -3.25212 , 5.27315 , 4.76754 , 0.27074,-0.177369,-0.946172 -3.17505 , 5.18444 , 4.83045 , -0.349249,0.342289,0.872275 -3.07554 , 5.0525 , 4.85572 , -0.311165,0.473411,0.82405 -2.97373 , 4.91373 , 4.87063 , -0.152642,0.498538,0.853323 -3.21947 , 5.43071 , 5.44267 , -0.398384,-0.542502,-0.739582 -3.15509 , 5.36907 , 5.53475 , 0.404603,0.801577,0.440193 -3.13764 , 5.39656 , 5.70722 , -0.367643,-0.824834,-0.42952 -3.09625 , 5.37925 , 5.84291 , 0.193447,0.918208,0.345648 -2.873 , 5.00273 , 5.63039 , 0.481139,0.495168,0.723404 -2.79251 , 4.90456 , 5.67905 , -0.426431,-0.23043,-0.874676 -2.88016 , 5.1477 , 6.07954 , -0.886198,0.354033,-0.298853 -2.324 , 4.06628 , 5.08023 , -0.494769,-0.156407,-0.854834 -2.26306 , 3.9959 , 5.1292 , -0.634757,-0.27488,-0.722166 -2.60528 , 4.78706 , 6.16066 , -0.752808,0.528434,-0.392476 -2.74113 , 5.15613 , 6.75473 , -0.768387,0.628322,-0.121625 -2.60188 , 4.93481 , 6.66637 , -0.78863,0.540974,-0.292252 -2.05885 , 3.79663 , 5.41915 , 0.171935,0.0850285,0.981432 -2.00186 , 3.73412 , 5.47528 , 0.327773,0.116621,0.937531 -1.83774 , 3.41968 , 5.19702 , 0.140726,0.969752,-0.199442 -1.76921 , 3.32555 , 5.19838 , 0.450016,-0.00734532,0.89299 -1.76678 , 3.38786 , 5.41992 , -0.820472,-0.385758,-0.42192 -1.72905 , 3.36885 , 5.53149 , -0.208987,-0.790537,-0.575652 -1.65344 , 3.25484 , 5.50453 , -0.319302,-0.708158,-0.629729 -1.62982 , 3.27511 , 5.68044 , 0.57767,0.722983,0.378937 -1.56687 , 3.19266 , 5.6992 , -0.816248,-0.225962,-0.531677 -1.53524 , 3.19588 , 5.85934 , -0.843836,-0.493809,-0.209987 -1.48467 , 3.15024 , 5.94369 , -0.960313,-0.111932,-0.25548 -1.45172 , 3.15748 , 6.12164 , -0.768764,-0.0558118,-0.637093 -1.40014 , 3.11657 , 6.22253 , 0.387023,-0.242174,0.889699 -1.28136 , 2.85257 , 5.90213 , -0.0672366,0.954637,0.290083 -1.22636 , 2.79175 , 5.95361 , -0.0196796,0.919194,0.393312 -1.18108 , 2.76807 , 6.08427 , -0.0938448,0.965465,0.243044 -1.14572 , 2.78367 , 6.30476 , -0.949424,-0.0605721,-0.308101 -1.09571 , 2.75283 , 6.43577 , 0.359563,0.718638,0.59521 -1.04705 , 2.7394 , 6.61187 , 0.00942045,-0.836932,0.547225 -0.954406 , 2.51518 , 6.30171 , 0.0807633,0.733402,-0.67498 -0.76754 , 1.74545 , 4.61667 , -0.181994,0.437156,0.88078 -0.727926 , 1.69582 , 4.63911 , -0.0811885,0.553891,0.828622 -0.746507 , 2.07519 , 5.81162 , 0.457645,0.263246,-0.849272 -0.688963 , 1.97257 , 5.7345 , 0.96285,-0.145818,-0.227283 -0.653975 , 2.11299 , 6.36471 , -0.991292,-0.0719295,-0.110305 -0.594455 , 2.01742 , 6.3243 , -0.991292,-0.0719295,-0.110305 -0.527008 , 1.46901 , 4.82051 , -0.699437,0.230973,0.676342 -0.485476 , 1.41641 , 4.83649 , -0.231088,0.644119,0.729183 -0.443313 , 1.3789 , 4.90925 , -0.562323,-0.739673,-0.369697 -0.383094 , 1.51147 , 5.62857 , 0.548281,0.527536,-0.648917 -0.250712 , 2.01067 , 7.9029 , -0.955781,0.292561,-0.0298417 -0.266146 , 1.46856 , 6.02683 , -0.49096,0.774208,-0.399449 -0.207974 , 1.41674 , 6.12804 , 0.107191,-0.898274,0.426163 -0.158606 , 1.33006 , 6.07168 , -0.79504,0.16151,-0.584659 -0.115599 , 1.23243 , 5.94477 , 0.810054,-0.489912,0.322178 -1.76449 , 1.33714 , -1.07117 , 0.100479,-0.112132,-0.9886 -1.80764 , 1.3903 , -1.08253 , -0.0868782,0.125607,0.988269 -1.84559 , 1.43936 , -1.08441 , -0.0772878,0.188389,0.979049 -1.89352 , 1.49783 , -1.09991 , -0.0671247,0.145635,0.987059 -1.93146 , 1.5486 , -1.09858 , -0.126483,0.132209,0.983119 -1.97528 , 1.6041 , -1.10291 , 0.0978009,-0.186459,-0.977583 -2.02924 , 1.67019 , -1.12009 , -0.0797184,0.195549,0.977449 -2.07324 , 1.72847 , -1.12093 , -0.0596868,0.172355,0.983225 -2.12186 , 1.79091 , -1.12658 , -0.0751921,0.204593,0.975955 -2.17676 , 1.86022 , -1.13722 , -0.0950908,0.178773,0.979284 -2.23243 , 1.92989 , -1.1452 , -0.0923365,0.19135,0.977169 -2.2924 , 2.00699 , -1.15784 , -0.0714668,0.203075,0.976552 -2.35906 , 2.08908 , -1.17388 , -0.101593,0.187698,0.976959 -2.41462 , 2.16243 , -1.17438 , -0.0944715,0.189746,0.977278 -2.48746 , 2.25335 , -1.19114 , -0.0469947,0.211534,0.97624 -2.56617 , 2.35067 , -1.21054 , -0.0243948,0.221449,0.974867 -2.6512 , 2.45643 , -1.23241 , -0.0408164,0.183918,0.982094 -2.73592 , 2.56308 , -1.25029 , -0.0549234,0.184537,0.98129 -2.81544 , 2.6657 , -1.25839 , -0.0603622,0.186675,0.980566 -2.91317 , 2.78742 , -1.27932 , -0.0593038,0.207704,0.976393 -3.02198 , 2.92297 , -1.30645 , -0.0771717,0.213263,0.973942 -3.11945 , 3.04883 , -1.31785 , 0.0681182,-0.208824,-0.975578 -3.24731 , 3.20701 , -1.34991 , -0.076081,0.204251,0.975958 -3.3638 , 3.35559 , -1.36584 , -0.0787606,0.195569,0.977522 -3.50349 , 3.53134 , -1.39533 , -0.0741522,0.199311,0.977127 -3.65011 , 3.71638 , -1.4224 , -0.0318447,0.266409,0.963334 -3.81586 , 3.9238 , -1.45556 , 0.149723,0.227399,0.962223 -3.97498 , 4.12709 , -1.47595 , 0.00928152,0.0717843,0.997377 -3.61309 , 3.7535 , -1.12548 , 0.987183,0.0882343,0.132981 -3.59959 , 3.76521 , -1.02943 , 0.987183,0.0882343,0.132981 -3.58568 , 3.77482 , -0.933853 , 0.988898,0.0892143,0.118837 -3.57039 , 3.78256 , -0.838783 , 0.99415,0.0828641,0.0692755 -3.56729 , 3.80346 , -0.751841 , 0.997987,0.0625333,-0.0105218 -3.57411 , 3.83728 , -0.671807 , 0.993588,0.0761497,-0.0835742 -3.58045 , 3.86925 , -0.591183 , 0.969687,0.24258,-0.0293752 -3.56811 , 3.87849 , -0.50055 , -0.906662,-0.343537,0.24484 -3.55955 , 3.89339 , -0.413585 , -0.856123,-0.432855,0.282293 -3.69032 , 4.09829 , -0.303028 , -0.653254,-0.0744692,0.753467 -3.73561 , 4.17795 , -0.234695 , -0.55314,-0.0211317,0.83282 -3.92284 , 4.45619 , -0.123644 , -0.41873,-0.0293663,0.907636 -20.9637 , 25.6777 , -4.25635 , 0.122897,0.202148,0.971613 -20.0656 , 24.7197 , -3.49353 , -0.868036,-0.00692856,-0.496454 -23.5317 , 29.2309 , -3.67011 , -0.215131,0.111038,0.970252 -28.2738 , 35.4121 , -3.88199 , -0.991708,-0.099937,-0.0807916 -28.2373 , 35.5895 , -3.11572 , -0.991708,-0.099937,-0.0807914 -19.3317 , 24.4087 , -1.26351 , -0.361177,-0.491237,-0.792614 -19.1497 , 24.328 , -0.725346 , -0.124172,-0.838862,-0.529993 -18.6101 , 23.7802 , -0.170245 , 0.21641,0.925692,0.310261 -18.4872 , 23.7697 , 0.341744 , 0.335682,0.884053,-0.325221 -17.3482 , 22.4216 , 0.861396 , -0.193895,0.460698,0.866119 -17.3461 , 22.5603 , 1.34036 , 0.584,-0.196148,-0.7877 -18.318 , 23.9948 , 1.86864 , 0.0509973,0.584838,0.809545 -19.0833 , 25.1705 , 2.44216 , -0.119525,-0.983153,0.138292 -17.4368 , 23.1122 , 2.81282 , 0.558032,0.793193,0.243814 -17.3404 , 23.1279 , 3.30001 , -0.570389,-0.647759,-0.50504 -18.0036 , 24.1811 , 3.91155 , -0.704092,-0.408189,0.581065 -17.1908 , 23.2194 , 4.2824 , 0.64329,0.422943,0.638198 -16.9743 , 23.0704 , 4.74408 , -0.603203,-0.749379,-0.273086 -16.9268 , 23.1551 , 5.24256 , 0.454186,0.887109,0.0821813 -16.644 , 22.9108 , 5.67774 , -0.295351,-0.939072,-0.175818 -16.9965 , 23.5588 , 6.30502 , -0.0803949,-0.996763,-0.000656204 -16.4118 , 22.8848 , 6.63314 , 0.411847,0.89649,-0.163363 -16.5109 , 23.1817 , 7.19493 , -0.218554,-0.947406,0.233785 -16.553 , 23.3984 , 7.74788 , -0.218554,-0.947406,0.233785 -17.4392 , 25.0166 , 9.28249 , -0.394877,-0.765068,0.508668 -18.2417 , 26.3718 , 10.2999 , -0.46304,-0.730806,-0.501515 -17.9565 , 26.1374 , 10.78 , 0.33222,0.850435,0.407911 -17.4301 , 25.5406 , 11.1091 , -0.576486,-0.747182,0.330733 -6.29587 , 9.00011 , 4.70302 , 0.717114,-0.534529,-0.447243 -5.16011 , 7.34644 , 4.16371 , -0.032627,-0.927303,0.372886 -5.61723 , 8.09609 , 4.6712 , 0.258388,-0.743517,0.616781 -4.3788 , 6.25314 , 3.94784 , 0.571766,0.755878,0.318956 -4.37454 , 6.29406 , 4.10459 , 0.855452,0.512033,0.0776136 -4.49111 , 6.5243 , 4.36595 , -0.883213,-0.462285,0.0789135 -4.2669 , 6.22204 , 4.34319 , -0.715854,-0.61739,-0.326164 -4.2714 , 6.2788 , 4.51583 , 0.806054,0.589075,-0.0571604 -4.22032 , 6.2491 , 4.64095 , -0.466784,-0.870212,-0.157622 -4.40145 , 6.59309 , 5.00096 , 0.042538,-0.0749772,0.996278 -4.16713 , 6.26694 , 4.94214 , -0.268378,-0.962188,-0.0465561 -4.18877 , 6.35654 , 5.15171 , 0.0947531,0.0285153,-0.995092 -3.81712 , 5.79756 , 4.91076 , 0.231158,-0.266201,0.93579 -3.647 , 5.5637 , 4.88213 , 0.329013,-0.19093,0.924822 -3.60337 , 5.54169 , 5.00257 , -0.385673,0.053823,-0.921064 -3.4694 , 5.36737 , 5.00524 , -0.712715,0.12658,-0.689938 -3.30982 , 5.14457 , 4.96144 , 0.427979,-0.746599,-0.509337 -3.32239 , 5.21759 , 5.15629 , -0.106059,-0.912171,0.395848 -3.3785 , 5.37115 , 5.42665 , -0.700726,-0.668797,-0.248384 -3.35509 , 5.38807 , 5.58668 , 0.404603,0.801578,0.440193 -3.09287 , 4.9726 , 5.35261 , -0.592569,-0.127037,-0.795439 -3.06231 , 4.97484 , 5.49414 , 0.677378,0.152159,0.719727 -2.87197 , 4.68179 , 5.34848 , -0.963052,0.188471,-0.192378 -2.83117 , 4.66164 , 5.46604 , -0.905972,-0.390674,-0.163057 -2.87426 , 4.80293 , 5.7529 , 0.643695,-0.229069,0.730195 -2.78689 , 4.69989 , 5.79012 , 0.896235,0.0525508,0.440457 -2.38144 , 3.9704 , 5.12744 , 0.274313,0.366581,0.889028 -2.30813 , 3.8826 , 5.15363 , 0.120658,0.434712,0.89245 -2.24199 , 3.80605 , 5.19189 , 0.352442,0.342969,0.870722 -2.22677 , 3.8328 , 5.35339 , -0.462801,-0.388121,-0.79698 -2.11916 , 3.67166 , 5.28391 , -0.507023,0.0596864,-0.859863 -2.10088 , 3.69391 , 5.44538 , -0.466066,-0.24804,-0.849269 -2.00366 , 3.5514 , 5.392 , -0.461037,-0.438051,0.771723 -1.88496 , 3.35398 , 5.25588 , -0.152217,0.817057,0.5561 -1.84141 , 3.32294 , 5.34301 , 0.314506,0.0905617,-0.944926 -1.76791 , 3.22359 , 5.33355 , 0.92098,0.119953,0.370685 -1.75536 , 3.26478 , 5.53239 , 0.478819,-0.598535,-0.642252 -1.70097 , 3.21214 , 5.59357 , 0.101186,0.769932,0.630052 -1.64644 , 3.15821 , 5.65349 , -0.427411,-0.634472,-0.644022 -1.58633 , 3.08761 , 5.68716 , -0.135735,0.568566,0.811363 -1.5308 , 3.03231 , 5.74434 , -0.313307,0.499848,0.80746 -1.46776 , 2.95576 , 5.76608 , 0.141043,0.382419,0.913161 -1.40903 , 2.88868 , 5.80317 , 0.231379,0.278077,0.932275 -1.35339 , 2.83042 , 5.85607 , 0.301656,0.668497,0.67979 -1.3429 , 2.91488 , 6.19001 , 0.444194,6.25824e-05,0.895931 -1.25574 , 2.76339 , 6.06478 , 0.261239,-0.880412,-0.395764 -1.2029 , 2.72252 , 6.1593 , 0.27315,-0.96191,0.010846 -1.1676 , 2.74898 , 6.40684 , -0.767873,0.107586,0.631503 -1.10516 , 2.68105 , 6.45567 , 0.245412,-0.941725,0.230058 -1.02619 , 2.54272 , 6.33784 , -0.0174617,-0.673985,0.738539 -0.813551 , 1.7597 , 4.62891 , -0.198126,0.33147,0.922428 -0.770723 , 1.70393 , 4.63307 , -0.102736,0.573331,0.812857 -0.745091 , 1.75725 , 4.92543 , 0.0596179,0.979982,-0.18995 -0.742429 , 2.00328 , 5.77421 , 0.457645,0.263246,-0.849272 -0.686414 , 1.92526 , 5.76175 , 0.785625,-0.354609,-0.506997 -0.64318 , 1.99 , 6.17429 , -0.881394,-0.170146,-0.440677 -0.566921 , 1.56809 , 5.08244 , 0.103948,0.989541,-0.100014 -0.519989 , 1.43513 , 4.84131 , 0.508809,-0.534797,-0.674615 -0.477043 , 1.38576 , 4.86611 , -0.00111462,0.745914,0.666042 -0.429838 , 1.38776 , 5.08283 , 0.794317,0.606627,-0.0326308 -0.368207 , 1.47405 , 5.64825 , 0.490931,0.847757,0.200735 -0.297766 , 1.52482 , 6.13828 , 0.589624,-0.435543,0.680181 -0.248209 , 1.42344 , 6.01584 , -0.0178619,-0.20989,0.977562 -0.198759 , 1.3349 , 5.94026 , -0.901595,0.200113,-0.383511 -0.148203 , 1.25743 , 5.90157 , 0.65506,-0.451886,0.605554 -0.0924625 , 1.19507 , 5.93966 , -0.655589,-0.754746,-0.0237171 -1.91341 , 1.43451 , -1.08248 , -0.0460044,0.149062,0.987757 -1.95793 , 1.48727 , -1.08902 , -0.121704,0.147029,0.981616 -1.99775 , 1.53779 , -1.08667 , -0.11286,0.100878,0.988477 -2.04321 , 1.59209 , -1.08979 , 0.087268,-0.17127,-0.981352 -2.09379 , 1.65238 , -1.09841 , -0.0799847,0.224845,0.971106 -2.15542 , 1.7232 , -1.11906 , -0.0830472,0.16196,0.983297 -2.2009 , 1.78078 , -1.11645 , -0.0945871,0.176909,0.979672 -2.25838 , 1.84875 , -1.12536 , -0.0920818,0.189258,0.9776 -2.31471 , 1.9175 , -1.13196 , -0.0953932,0.188526,0.977424 -2.37823 , 1.99305 , -1.14275 , -0.0774337,0.22434,0.97143 -2.44747 , 2.07383 , -1.15696 , 0.0813219,-0.17003,-0.982078 -2.51079 , 2.15165 , -1.16211 , -0.0776523,0.193569,0.978009 -2.59209 , 2.24598 , -1.1827 , -0.0158163,0.233354,0.972263 -2.6856 , 2.35338 , -1.21182 , -0.0504653,0.202608,0.977959 -2.76164 , 2.44549 , -1.21904 , -0.0635909,0.196117,0.978516 -2.85597 , 2.55647 , -1.24005 , -0.0690675,0.195203,0.978328 -2.94485 , 2.66248 , -1.251 , -0.0717007,0.181679,0.98074 -3.04509 , 2.78313 , -1.26904 , -0.0651713,0.207408,0.976081 -3.15298 , 2.91023 , -1.28734 , 0.0671465,-0.210513,-0.975282 -3.27914 , 3.05795 , -1.31613 , -0.0760619,0.207925,0.975183 -3.39298 , 3.19623 , -1.32912 , -0.0851496,0.201707,0.975738 -3.53177 , 3.36016 , -1.3559 , -0.0728895,0.199847,0.977112 -3.67149 , 3.52733 , -1.37605 , 0.0438511,0.332646,0.942032 -3.83644 , 3.72265 , -1.40767 , 0.197054,0.293883,0.935309 -4.00701 , 3.92677 , -1.43572 , -0.0889663,0.194827,0.976795 -3.621 , 3.55139 , -1.07709 , 0.989024,0.0815257,0.123231 -3.60864 , 3.56238 , -0.983151 , 0.989024,0.0815257,0.123231 -3.60111 , 3.57855 , -0.893928 , 0.990941,0.0916009,0.0982096 -3.58501 , 3.586 , -0.801216 , 0.994192,0.0882484,0.0615972 -3.58208 , 3.60639 , -0.716512 , 0.996158,0.0855934,0.018544 -3.58366 , 3.63128 , -0.635158 , 0.983908,0.0212036,-0.177412 -3.58524 , 3.65617 , -0.553805 , 0.96288,0.0323881,-0.267979 -3.62911 , 3.72907 , -0.494432 , -0.92553,-0.189289,0.32797 -3.63482 , 3.75791 , -0.414384 , -0.865531,-0.184493,0.465638 -3.67795 , 3.82973 , -0.351017 , -0.843656,-0.144309,0.517125 -3.69432 , 3.872 , -0.274546 , -0.843553,-0.0935338,0.528838 -3.74158 , 3.94945 , -0.209471 , -0.704828,-0.0877296,0.703932 -3.96878 , 4.25823 , -0.116219 , -0.394468,-0.0357086,0.918216 -4.14213 , 4.48361 , -0.0789651 , -0.31441,0.00720253,0.94926 -19.793 , 22.7796 , -3.87568 , -0.915277,-0.379409,-0.135337 -20.2797 , 23.4961 , -3.48228 , -0.915277,-0.379409,-0.135337 -20.247 , 23.6069 , -2.95692 , -0.87193,-0.46011,-0.167446 -20.1136 , 23.7454 , -1.89595 , 0.817607,0.510701,0.265901 -19.8594 , 23.5885 , -1.34465 , -0.845249,-0.396504,-0.358244 -20.1154 , 24.0462 , -0.853532 , 0.688632,0.393337,0.609156 -19.1652 , 23.0403 , -0.262139 , -0.714082,-0.642133,-0.278841 -19.1567 , 23.1731 , 0.241329 , 0.633974,0.706521,-0.314492 -19.1738 , 23.3389 , 0.747257 , -0.654902,-0.737663,0.164189 -19.4911 , 23.8807 , 1.26105 , -0.3433,-0.929177,0.13702 -18.8513 , 23.2304 , 1.75908 , -0.210404,-0.967735,-0.138632 -18.7945 , 23.3053 , 2.26504 , 0.141899,0.950097,0.277815 -18.5331 , 23.1224 , 2.75322 , -0.224745,-0.870272,-0.43831 -18.4172 , 23.1206 , 3.24958 , 0.497917,0.836552,0.228601 -18.3325 , 23.1591 , 3.74935 , 0.43534,0.68292,0.586599 -17.5902 , 22.3492 , 4.13114 , 0.357588,0.863311,0.356125 -17.6188 , 22.5302 , 4.6378 , -0.276318,-0.952715,-0.126424 -18.4439 , 23.9102 , 5.88267 , -0.534585,-0.844942,0.017077 -17.9545 , 23.4176 , 6.28257 , 0.157694,0.986163,-0.0511448 -17.2113 , 22.5824 , 6.5762 , -0.0180553,-0.992319,0.122383 -17.8574 , 23.599 , 7.33523 , 0.0964016,-0.942004,0.321459 -17.1759 , 22.8371 , 7.62039 , -0.13819,-0.931911,0.33533 -18.4554 , 24.735 , 8.70854 , 0.0123463,-0.742192,0.670074 -18.17 , 24.5127 , 9.17023 , -0.197243,-0.760102,0.619145 -18.6238 , 25.3109 , 9.98925 , -0.0383343,-0.855385,0.516572 -18.8653 , 25.8248 , 10.7389 , -0.0382156,0.718479,0.694498 -6.49555 , 8.68678 , 4.41389 , 0.811515,-0.339082,-0.475885 -5.93504 , 7.95765 , 4.29227 , -0.458081,0.802379,-0.382557 -5.82086 , 7.8534 , 4.41832 , -0.458081,0.802379,-0.382557 -6.01659 , 8.19079 , 4.74874 , 0.762822,-0.584997,-0.275465 -4.57872 , 6.17614 , 3.93706 , 0.31756,0.819322,0.477355 -4.5393 , 6.16451 , 4.06698 , 0.476919,0.797045,0.370495 -4.50782 , 6.16518 , 4.20489 , -0.558042,-0.758151,-0.337337 -4.44018 , 6.11195 , 4.31333 , 0.616958,0.721507,0.314309 -4.44175 , 6.16213 , 4.48117 , -0.568842,-0.81557,0.106135 -4.4788 , 6.26828 , 4.68763 , 0.336086,0.931468,-0.139336 -4.40159 , 6.20167 , 4.79108 , -0.429863,-0.900775,-0.0618261 -4.40463 , 6.25784 , 4.97433 , -0.198615,-0.886366,0.41822 -4.30005 , 6.15037 , 5.05073 , 0.241976,0.964396,-0.106711 -3.83501 , 5.47987 , 4.72286 , -0.0408989,-0.305052,0.951457 -3.59117 , 5.14617 , 4.61117 , 0.504549,-0.567617,0.65057 -3.60447 , 5.21363 , 4.79017 , 0.637092,-0.478376,0.604375 -3.56091 , 5.19368 , 4.90543 , -0.332092,-0.943098,-0.0167797 -3.50017 , 5.14377 , 4.99759 , 0.185488,0.864271,0.467578 -3.43736 , 5.09299 , 5.08815 , -0.059856,0.920616,0.385854 -3.36538 , 5.02598 , 5.16545 , -0.353105,0.88996,0.288597 -2.96493 , 4.40858 , 4.74518 , 0.686735,-0.408835,0.601041 -2.93534 , 4.40683 , 4.86353 , -0.963001,0.236591,-0.129054 -3.01399 , 4.58882 , 5.16112 , -0.108245,-0.96035,0.256927 -3.15249 , 4.88275 , 5.58354 , 0.589374,0.171539,0.789438 -3.01488 , 4.69872 , 5.54012 , 0.292064,-0.24402,-0.924745 -2.90549 , 4.5624 , 5.53747 , -0.647853,-0.665772,-0.370181 -2.84332 , 4.50971 , 5.61957 , 0.84871,0.525288,0.0613613 -2.50014 , 3.94167 , 5.12571 , -0.0694699,0.2617,0.962646 -2.40728 , 3.82518 , 5.11683 , 0.259243,0.539093,0.801356 -2.38419 , 3.83672 , 5.25641 , 0.377918,0.633199,0.675453 -2.29989 , 3.73167 , 5.2572 , 0.0155091,0.533602,0.845594 -2.22805 , 3.65107 , 5.28434 , -0.222197,0.891842,0.394013 -2.15985 , 3.57591 , 5.31679 , 0.69229,-0.714113,0.103813 -2.05219 , 3.41949 , 5.23956 , -0.448322,0.54976,-0.70482 -2.01821 , 3.41289 , 5.35971 , -0.303875,0.861524,-0.406739 -1.86195 , 3.14902 , 5.11677 , 0.799257,0.0553036,0.59844 -1.82947 , 3.14228 , 5.23295 , -0.899628,-0.0331544,-0.435398 -1.88641 , 3.33496 , 5.65746 , 0.403119,-0.755387,-0.51661 -1.81333 , 3.24599 , 5.66306 , 0.468827,-0.726914,-0.501793 -1.75133 , 3.18233 , 5.70767 , 0.396963,-0.597511,-0.696707 -1.68843 , 3.11366 , 5.74223 , -0.276807,0.672043,0.686831 -1.63609 , 3.07355 , 5.82582 , 0.671716,0.697915,0.248421 -1.5989 , 3.07003 , 5.97721 , -0.927481,-0.189321,-0.322392 -1.5063 , 2.92747 , 5.87844 , 0.110105,0.289159,0.950928 -1.47842 , 2.95292 , 6.08945 , 0.312951,0.448524,0.83719 -1.42283 , 2.91056 , 6.17854 , -0.240328,-0.72772,-0.642392 -1.34399 , 2.80001 , 6.13401 , -0.475033,0.878324,-0.0537586 -1.28468 , 2.743 , 6.19366 , 0.0672377,-0.966994,-0.245769 -1.27018 , 2.83738 , 6.58581 , -0.13401,-0.501173,0.854907 -1.20399 , 2.77262 , 6.64546 , 0.125499,-0.619968,0.774525 -1.08428 , 2.50545 , 6.22755 , 0.612178,-0.766891,0.192656 -0.859601 , 1.76884 , 4.63171 , 0.114279,-0.168805,-0.979002 -0.814777 , 1.71367 , 4.63641 , -0.0893736,0.465674,0.880432 -0.772976 , 1.67355 , 4.67679 , 0.103556,-0.530071,-0.841606 -0.800322 , 2.04191 , 5.84216 , -0.565495,-0.234876,0.7906 -0.740832 , 1.96186 , 5.82086 , 0.58698,-0.664269,-0.462819 -0.68683 , 1.92346 , 5.92079 , -0.962165,0.16231,0.218847 -0.633655 , 1.91388 , 6.11511 , 0.98551,0.0885566,-0.144665 -0.555749 , 1.46157 , 4.8747 , 0.645024,-0.25225,-0.721327 -0.511289 , 1.40256 , 4.86138 , -0.311516,0.517848,0.796738 -0.46596 , 1.35664 , 4.89489 , 0.25948,0.697649,0.6678 -0.40671 , 1.489 , 5.61433 , 0.235665,0.797824,0.554922 -0.334017 , 1.57082 , 6.21087 , -0.940242,0.332916,-0.0714983 -0.278116 , 1.48323 , 6.14734 , -0.756002,-0.0925957,-0.647987 -0.218226 , 1.41756 , 6.17971 , 0.255697,-0.545213,0.79835 -0.175323 , 1.29783 , 5.94637 , 0.352713,-0.641977,0.680778 -0.124068 , 1.22037 , 5.89673 , 0.747497,-0.438387,0.499063 -1.98244 , 1.42644 , -1.07942 , -0.104421,0.142659,0.984248 -2.02883 , 1.47899 , -1.08475 , 0.099876,-0.13172,-0.986243 -2.07029 , 1.52831 , -1.08118 , -0.0844766,0.120486,0.989114 -2.1224 , 1.58605 , -1.09014 , -0.0713737,0.174136,0.982132 -2.17483 , 1.64617 , -1.09734 , -0.0553145,0.20488,0.977223 -2.22783 , 1.70562 , -1.10209 , -0.0684482,0.181931,0.980926 -2.28711 , 1.77193 , -1.11183 , -0.0937408,0.16084,0.982519 -2.34619 , 1.83881 , -1.11904 , -0.0597101,0.177887,0.982238 -2.4051 , 1.90624 , -1.12381 , -0.0662702,0.189113,0.979717 -2.47615 , 1.98529 , -1.13915 , -0.0542336,0.198248,0.97865 -2.54202 , 2.06023 , -1.145 , -0.0627887,0.180882,0.981498 -2.61997 , 2.14698 , -1.16053 , -0.0168852,0.201031,0.979439 -2.71068 , 2.24458 , -1.18455 , -0.0203118,0.207836,0.977953 -2.79542 , 2.33934 , -1.19892 , -0.0549188,0.196003,0.979064 -2.88011 , 2.43594 , -1.2096 , -0.0591003,0.189099,0.980178 -2.9777 , 2.54462 , -1.22769 , -0.0578082,0.178215,0.982292 -3.07006 , 2.64929 , -1.23592 , -0.0542808,0.188131,0.980643 -3.18668 , 2.77901 , -1.26157 , 0.0572663,-0.195521,-0.979026 -3.29801 , 2.90489 , -1.27656 , -0.0561222,0.189891,0.9802 -3.42205 , 3.04344 , -1.29635 , -0.069614,0.193609,0.978606 -3.55313 , 3.1909 , -1.31547 , -0.0587037,0.194785,0.979088 -3.71031 , 3.36494 , -1.34749 , 0.0922133,0.378649,0.920935 -3.8609 , 3.53472 , -1.36741 , -0.0945774,0.194942,0.976244 -4.03162 , 3.72656 , -1.3937 , -0.0976617,0.208436,0.973148 -3.63394 , 3.36346 , -1.03543 , 0.989255,0.0817025,0.121242 -3.62172 , 3.37398 , -0.943533 , 0.989255,0.0817025,0.121242 -3.6074 , 3.38379 , -0.852557 , 0.992199,0.0693571,0.103587 -3.6058 , 3.40453 , -0.769681 , 0.996215,0.0606088,0.0623018 -3.59587 , 3.41754 , -0.683318 , 0.997814,0.0609455,0.0255531 -3.59785 , 3.44288 , -0.6044 , 0.980504,0.0213243,-0.195337 -3.5932 , 3.45909 , -0.521653 , -0.942953,-0.0556792,0.328238 -3.65914 , 3.55031 , -0.474232 , -0.925963,-0.0421702,0.375253 -3.6662 , 3.57945 , -0.396206 , -0.903851,-0.0195289,0.427401 -3.69115 , 3.62871 , -0.326528 , -0.934842,-0.0520291,0.351231 -3.73459 , 3.69729 , -0.26313 , -0.926406,-0.0353801,0.374859 -4.52238 , 4.55456 , -0.478328 , -0.579849,-0.369409,-0.726162 -4.5984 , 4.66474 , -0.403496 , -0.579849,-0.369409,-0.726163 -4.12185 , 4.20719 , -0.0526858 , -0.303437,-0.0775198,0.949693 -20.9443 , 22.8268 , -3.57433 , -0.220908,-0.429957,0.875407 -21.2539 , 23.3155 , -3.11799 , -0.248572,-0.400067,0.882133 -23.6968 , 26.1904 , -3.01758 , 0.652462,-0.198635,-0.731326 -28.6785 , 31.9546 , -3.17046 , -0.99006,-0.106452,-0.0919179 -20.3425 , 22.7306 , -1.41751 , -0.905737,-0.396501,-0.14976 -20.1124 , 22.6113 , -0.884811 , -0.68759,-0.656967,-0.309217 -20.0081 , 22.6344 , -0.370815 , 0.582787,0.799215,0.147018 -19.8071 , 22.5443 , 0.145326 , 0.610508,0.789228,-0.0663309 -19.8553 , 22.7419 , 0.648869 , -0.603802,-0.777682,0.175026 -19.8971 , 22.9328 , 1.15857 , 0.633268,0.561092,-0.533055 -20.3207 , 23.5753 , 1.68654 , -0.577556,-0.563389,0.59078 -20.3284 , 23.8824 , 2.7513 , 0.485425,0.743553,-0.459882 -19.3692 , 22.8853 , 3.18194 , -0.596691,-0.724744,-0.344538 -18.744 , 22.2772 , 3.61232 , -0.621492,-0.757136,-0.20123 -18.7312 , 22.4051 , 4.11709 , 0.422575,0.89839,0.119695 -18.7512 , 22.5713 , 4.63353 , 0.412945,0.905603,-0.0967446 -18.7004 , 22.6555 , 5.14121 , 0.251232,0.945346,-0.207853 -18.7241 , 22.8322 , 5.67171 , -0.682163,-0.731073,0.0136294 -18.5442 , 22.7569 , 6.15257 , 0.453488,0.890381,-0.039639 -18.4137 , 22.7434 , 6.64616 , 0.271595,0.945012,-0.182179 -18.5331 , 23.0442 , 7.22575 , -0.0708033,-0.860371,0.504727 -19.1188 , 23.9434 , 7.99509 , 0.00377098,-0.730276,0.683142 -19.2212 , 24.2366 , 8.61419 , 0.0836377,-0.777693,0.623056 -20.1465 , 25.7707 , 10.2405 , 0.0713415,-0.996748,0.0374683 -20.4726 , 26.3773 , 11.0471 , -0.27676,0.918306,0.28305 -19.3718 , 25.1163 , 11.1254 , 0.141825,-0.86439,-0.482406 -19.15 , 25.002 , 11.6421 , 0.141825,-0.86439,-0.482406 -6.46288 , 8.24989 , 4.6347 , 0.811515,-0.339083,-0.475885 -6.51357 , 8.37841 , 4.87917 , 0.717114,-0.534529,-0.447243 -6.64247 , 8.61482 , 5.18507 , 0.717114,-0.534529,-0.447243 -6.53634 , 8.53415 , 5.33816 , 0.717114,-0.534529,-0.447243 -4.72511 , 6.10466 , 4.20823 , 0.26778,0.813113,0.516857 -4.5908 , 5.96532 , 4.26772 , -0.62243,-0.706415,-0.336985 -4.55188 , 5.95718 , 4.39988 , 0.731335,0.673372,0.108255 -4.59956 , 6.0706 , 4.60847 , 0.786091,0.612188,-0.0853607 -4.56666 , 6.07283 , 4.7522 , 0.701034,0.636474,-0.32164 -4.64163 , 6.23007 , 5.00206 , -0.57896,-0.744883,0.331595 -3.5013 , 4.63281 , 4.0452 , -0.621336,-0.743954,-0.245913 -3.44327 , 4.58799 , 4.12459 , -0.621337,-0.743954,-0.245914 -3.60075 , 4.85997 , 4.43847 , -0.954687,0.297437,0.0102035 -3.68401 , 5.02674 , 4.68844 , 0.6305,-0.674816,0.383526 -3.30482 , 4.50343 , 4.39765 , 0.389713,0.870527,0.300511 -3.32617 , 4.57783 , 4.57414 , -0.151824,0.968505,-0.197352 -3.269 , 4.53315 , 4.65521 , 0.763037,0.268783,0.587818 -3.18347 , 4.44679 , 4.69908 , -0.565341,0.118889,-0.816244 -3.16377 , 4.46018 , 4.83129 , 0.410893,-0.906362,-0.098357 -3.02885 , 4.29303 , 4.79649 , 0.782052,-0.309428,0.540971 -3.06336 , 4.39518 , 5.01611 , 0.876846,-0.351807,-0.327678 -2.91806 , 4.20831 , 4.95488 , -0.970901,-0.160301,0.177916 -3.12337 , 4.59323 , 5.4753 , -0.401232,0.125164,0.907384 -3.01805 , 4.47334 , 5.4858 , 0.0185066,0.599752,0.799972 -2.97247 , 4.45406 , 5.60188 , 0.0123481,0.0903746,0.995831 -2.70965 , 4.06227 , 5.29889 , 0.494141,0.83958,-0.225679 -2.50878 , 3.76879 , 5.08789 , -0.00520336,0.609036,0.793125 -2.47314 , 3.75846 , 5.19817 , 0.200423,0.674312,0.710728 -2.43234 , 3.73953 , 5.30137 , -0.221455,0.927003,0.302692 -2.35997 , 3.66614 , 5.33733 , -0.353255,0.831691,0.428371 -2.33859 , 3.68462 , 5.49212 , -0.029199,0.794101,0.607085 -2.10906 , 3.3147 , 5.12654 , 0.142506,-0.640125,0.754938 -2.17906 , 3.50562 , 5.51768 , 0.250144,-0.473121,0.844739 -1.92459 , 3.07323 , 5.03392 , -0.774208,-0.263169,-0.575626 -1.85036 , 2.98289 , 5.02145 , 0.658768,0.204225,0.724098 -1.82818 , 2.99776 , 5.16795 , 0.942358,0.0979259,0.319958 -1.81075 , 3.02517 , 5.34013 , 0.867862,0.385242,-0.313696 -1.87776 , 3.23832 , 5.81966 , 0.423968,-0.706228,-0.567004 -1.78936 , 3.12497 , 5.7806 , -0.591645,0.553756,0.585927 -2.05146 , 3.80003 , 7.09905 , 0.428828,0.656474,-0.620603 -1.64663 , 2.96437 , 5.80347 , 0.0848196,0.259408,0.962036 -1.56316 , 2.85421 , 5.75531 , 0.042477,0.0911834,0.994928 -1.51114 , 2.81813 , 5.84346 , 0.16352,0.214628,0.96291 -1.48432 , 2.8481 , 6.06237 , -0.298491,-0.901727,-0.312718 -1.42414 , 2.79771 , 6.13259 , 0.00479476,0.856839,0.515562 -1.36873 , 2.75981 , 6.22819 , -0.310431,0.334773,0.889696 -1.34215 , 2.81433 , 6.53028 , 0.513721,-0.335207,0.789764 -1.27491 , 2.74898 , 6.58074 , -0.122384,-0.581044,0.804618 -1.1755 , 2.58107 , 6.39211 , -0.441354,-0.46904,0.764989 -0.907877 , 1.7794 , 4.64403 , -0.223695,-0.321134,0.920236 -0.859832 , 1.7181 , 4.63055 , -0.0931998,0.253615,0.962805 -0.816285 , 1.67949 , 4.67107 , 0.00294075,0.522328,0.85274 -0.854845 , 2.05108 , 5.835 , -0.467411,-0.881404,-0.0682274 -0.83604 , 2.221 , 6.5204 , -0.030639,-0.788538,0.614222 -0.737087 , 1.93089 , 5.8951 , -0.466983,0.828069,0.310208 -0.685816 , 1.9381 , 6.13717 , 0.98551,0.0885566,-0.144665 -0.622711 , 1.85812 , 6.11188 , -0.874926,0.220689,-0.431045 -0.546542 , 1.42009 , 4.86642 , -0.512861,0.407243,0.755729 -0.500186 , 1.36745 , 4.87136 , -0.163212,0.651394,0.740978 -0.452716 , 1.34013 , 4.97174 , 0.585991,0.762564,0.274063 -0.388915 , 1.45934 , 5.66288 , 0.490931,0.847757,0.200735 -0.315796 , 1.51173 , 6.15245 , 0.589624,-0.435543,0.680181 -0.252452 , 1.45714 , 6.22399 , -0.838118,0.534682,-0.108049 -0.205371 , 1.33752 , 5.99125 , -0.218337,0.87811,-0.425736 -0.156459 , 1.2454 , 5.86358 , -0.589674,0.339929,-0.73262 -0.0941648 , 1.19369 , 5.9401 , -0.655589,-0.754746,-0.023717 -2.04087 , 1.40751 , -1.06031 , -0.11524,0.159427,0.980461 -2.09395 , 1.46338 , -1.07206 , 0.0979549,-0.159041,-0.982401 -2.14304 , 1.51589 , -1.0744 , 0.0746609,-0.146868,-0.986334 -2.19103 , 1.56902 , -1.07501 , -0.0422261,0.160889,0.986069 -2.25682 , 1.63586 , -1.09466 , -0.0542346,0.168804,0.984157 -2.3057 , 1.69068 , -1.09117 , 0.0902163,-0.170413,-0.981234 -2.3666 , 1.75585 , -1.0994 , -0.0526241,0.17412,0.983317 -2.43422 , 1.82593 , -1.11142 , -0.0755962,0.166967,0.98306 -2.49571 , 1.89205 , -1.11437 , -0.0321085,0.174943,0.984055 -2.57526 , 1.97439 , -1.13403 , -0.0498796,0.173242,0.983615 -2.64369 , 2.04807 , -1.13786 , -0.0209984,0.177858,0.983832 -2.73009 , 2.13826 , -1.15714 , -0.00114807,0.206593,0.978426 -2.82331 , 2.23472 , -1.17856 , -0.0457051,0.203496,0.978008 -2.91156 , 2.32809 , -1.1904 , -0.044424,0.175441,0.983487 -3.00563 , 2.42804 , -1.20411 , -0.0437589,0.17903,0.98287 -3.10645 , 2.53446 , -1.2191 , -0.0523064,0.17081,0.983915 -3.21446 , 2.64936 , -1.23525 , -0.0433262,0.183729,0.982022 -3.32893 , 2.76998 , -1.2516 , 0.0548285,-0.185498,-0.981114 -3.45052 , 2.89929 , -1.26825 , -0.0517976,0.185287,0.981318 -3.58597 , 3.04213 , -1.28919 , -0.219683,0.130627,0.966786 -3.73498 , 3.19774 , -1.31344 , -0.0713514,0.598279,0.798104 -3.88998 , 3.36277 , -1.33577 , -0.132279,0.310449,0.941341 -4.00641 , 3.49394 , -1.32424 , -0.105198,0.202659,0.973582 -3.65167 , 3.19264 , -1.0018 , -0.936551,-0.23146,-0.263244 -3.63165 , 3.19715 , -0.907687 , -0.975803,-0.191476,-0.105575 -3.61125 , 3.19949 , -0.814348 , 0.965571,0.165865,0.200405 -3.60982 , 3.21974 , -0.733612 , 0.979261,0.120225,0.163078 -3.60003 , 3.2323 , -0.649292 , 0.998223,0.0224966,-0.0551719 -3.60315 , 3.25691 , -0.57249 , 0.975099,-0.00258775,-0.221757 -3.62503 , 3.30003 , -0.505664 , -0.933059,-0.0300968,0.358462 -3.6675 , 3.36157 , -0.447016 , -0.915015,-0.0585622,0.399146 -3.68776 , 3.40354 , -0.377484 , -0.903109,-0.0275312,0.428528 -3.70061 , 3.43769 , -0.303859 , -0.907388,-0.0374982,0.418617 -4.62787 , 4.40523 , -0.489576 , -0.663863,-0.294154,-0.687575 -4.19693 , 4.04987 , -0.0577139 , 0.284227,0.0638188,-0.956631 -21.1535 , 21.7027 , -3.5705 , -0.422041,-0.0362978,0.90585 -22.5754 , 23.3254 , -3.34547 , -0.164953,-0.0400404,0.985488 -23.7892 , 24.7497 , -3.01331 , -0.75472,0.300238,0.583313 -28.8625 , 30.2685 , -3.19566 , 0.994347,0.0782714,0.0717529 -20.8063 , 21.8923 , -1.49008 , -0.785417,-0.538036,-0.306002 -20.8596 , 22.0878 , -0.990604 , -0.770215,-0.607933,-0.192836 -20.6818 , 22.0352 , -0.468772 , 0.686074,0.717533,0.120205 -20.579 , 22.0637 , 0.0426778 , -0.597927,-0.801526,0.00631814 -20.5058 , 22.1222 , 0.551433 , -0.631221,-0.769241,0.099134 -20.5735 , 22.3359 , 1.05977 , -0.502581,-0.660568,0.55773 -20.5876 , 22.4926 , 1.57361 , 0.589908,0.534908,-0.604882 -21.1488 , 23.2593 , 2.12096 , 0.578213,0.596194,-0.556976 -21.181 , 23.442 , 2.66009 , -0.571579,-0.768478,0.287644 -19.7008 , 21.924 , 3.04755 , 0.177389,0.852714,0.491338 -19.6853 , 22.0455 , 3.55398 , -0.070573,-0.99601,-0.0546293 -19.5456 , 22.0264 , 4.04506 , 0.54619,0.835057,0.0660021 -19.51 , 22.1281 , 4.55344 , -0.368157,-0.918003,0.147412 -19.4561 , 22.208 , 5.06196 , -0.405162,-0.897154,0.175951 -19.5104 , 22.4155 , 5.60022 , -0.40894,-0.906661,0.10361 -19.4744 , 22.5193 , 6.1239 , -0.362699,-0.927916,0.0861514 -19.4821 , 22.677 , 6.6656 , -0.362698,-0.927916,0.0861516 -19.1355 , 22.4149 , 7.10047 , -0.516402,-0.85573,0.032486 -20.5126 , 24.2112 , 8.13466 , 0.0338401,-0.825833,0.562898 -21.1775 , 25.174 , 8.98571 , 0.0803946,-0.7901,0.607683 -22.5177 , 26.9699 , 10.1667 , 0.3899,-0.839172,0.379167 -21.7197 , 26.1827 , 10.4892 , -0.332492,0.900584,-0.279994 -20.9043 , 25.7228 , 12.0811 , 0.224759,-0.973987,-0.0288691 -20.9098 , 25.9164 , 12.7625 , 0.224759,-0.973987,-0.0288691 -20.9622 , 26.1735 , 13.4874 , 0.224759,-0.973987,-0.0288691 -6.814 , 8.4 , 5.32212 , 0.717114,-0.534529,-0.447243 -4.94529 , 6.04521 , 4.21514 , 0.180124,0.816365,0.548729 -4.7677 , 5.85845 , 4.24758 , -0.29634,-0.761324,-0.576688 -4.76759 , 5.90268 , 4.41006 , -0.413676,-0.792252,-0.448564 -4.68812 , 5.84371 , 4.51213 , -0.811061,-0.551761,-0.194267 -4.64049 , 5.82626 , 4.63967 , -0.357677,-0.898369,0.254952 -4.76895 , 6.04674 , 4.92899 , 0.442339,0.739817,-0.506959 -3.6636 , 4.5938 , 4.05613 , 0.854243,0.517492,0.0497063 -3.55435 , 4.481 , 4.08601 , 0.233548,0.857416,0.458578 -4.16466 , 5.36509 , 4.86235 , -0.143525,-0.120091,0.982333 -4.05901 , 5.26558 , 4.92013 , -0.0902864,-0.0985824,0.991025 -3.42426 , 4.41634 , 4.36876 , 0.403069,0.833695,0.377476 -3.85071 , 5.06457 , 5.02453 , 0.154882,-0.784199,0.600869 -3.28147 , 4.2935 , 4.49256 , -0.813856,-0.227274,-0.534775 -3.30188 , 4.36407 , 4.66974 , 0.59221,-0.105373,0.798865 -3.1527 , 4.18807 , 4.6259 , -0.706626,-0.00250934,-0.707583 -3.35227 , 4.52904 , 5.06435 , -0.208389,-0.977588,-0.0299402 -3.28799 , 4.47957 , 5.14423 , 0.287708,-0.837783,0.464052 -3.08855 , 4.22494 , 5.01583 , 0.378135,0.497455,0.780739 -3.03733 , 4.19475 , 5.10806 , 0.906132,0.390476,0.162647 -3.21791 , 4.52503 , 5.58882 , 0.093517,-0.0402136,0.994805 -3.10449 , 4.40125 , 5.59116 , 0.0123481,0.0903745,0.995831 -2.76085 , 3.90617 , 5.16476 , 0.469455,0.245162,-0.848238 -2.69721 , 3.85534 , 5.22875 , 0.390445,-0.844598,-0.366342 -2.77796 , 4.03943 , 5.57948 , 0.615088,-0.718478,0.324742 -2.62254 , 3.83615 , 5.4625 , 0.651508,-0.750349,-0.111866 -2.5735 , 3.80984 , 5.56079 , -0.589436,0.70598,0.39263 -2.45306 , 3.66116 , 5.5006 , 0.574254,-0.602738,-0.554021 -2.13612 , 3.16278 , 4.95338 , 0.103575,-0.556519,0.824353 -2.03154 , 3.0293 , 4.88405 , 0.85034,0.000206709,0.526234 -2.02928 , 3.07673 , 5.0695 , 0.560563,0.627473,0.540414 -1.96449 , 3.01459 , 5.09783 , 0.100482,0.753914,0.649243 -1.91172 , 2.9726 , 5.15662 , -0.162093,0.825786,0.540188 -1.83926 , 2.89298 , 5.15738 , -0.85789,-0.428515,-0.283549 -1.80157 , 2.88008 , 5.26295 , -0.896688,-0.392176,0.205301 -2.36757 , 4.10324 , 7.45417 , -0.417846,-0.510594,0.751464 -2.12147 , 3.69215 , 6.94124 , -0.917458,0.315533,-0.2423 -1.72775 , 2.94229 , 5.78386 , -0.166546,0.128716,0.977597 -1.65781 , 2.87154 , 5.80502 , 0.258354,0.0129646,0.965963 -1.58504 , 2.79121 , 5.80704 , 0.0957079,0.0145011,0.995304 -1.56458 , 2.83656 , 6.05194 , -0.84114,-0.507922,-0.185737 -1.52402 , 2.84112 , 6.22818 , 0.260039,0.706872,0.657808 -1.5194 , 2.94232 , 6.61943 , 0.213809,-0.350667,0.911767 -1.4262 , 2.82112 , 6.54693 , -0.0699408,0.491872,-0.867854 -1.35105 , 2.74192 , 6.56169 , 0.253541,-0.383284,0.88815 -1.2724 , 2.65412 , 6.55613 , 0.126192,-0.711901,0.690849 -0.964028 , 1.80997 , 4.71161 , -0.103613,-0.313025,0.944076 -0.906881 , 1.72798 , 4.64323 , -0.0263253,0.132532,0.990829 -0.859626 , 1.68034 , 4.65602 , 0.0445144,0.395141,0.917541 -0.957989 , 2.25844 , 6.37034 , 0.684568,0.556478,0.470849 -0.900061 , 2.24194 , 6.54079 , -0.40441,0.666302,0.626494 -0.797868 , 1.9871 , 6.02087 , -0.483591,0.868944,0.105242 -0.735324 , 1.92359 , 6.04526 , -0.692398,0.610169,-0.385071 -0.671195 , 1.85504 , 6.04856 , 0.71734,0.465003,0.51884 -0.58548 , 1.46701 , 4.97703 , -0.911513,-0.209025,0.354193 -0.535661 , 1.38703 , 4.88654 , 0.343951,-0.469313,-0.813291 -0.487409 , 1.34075 , 4.90974 , 0.124323,0.656376,0.74412 -0.427434 , 1.4753 , 5.63891 , 0.235666,0.797824,0.554922 -0.357389 , 1.53215 , 6.12832 , -0.482601,0.646711,-0.590645 -0.293963 , 1.46859 , 6.15142 , -0.756002,-0.0925957,-0.647987 -0.232819 , 1.39705 , 6.13372 , 0.287438,-0.8855,0.365061 -0.18384 , 1.28985 , 5.93833 , 0.352713,-0.641977,0.680778 -0.127487 , 1.21756 , 5.89742 , 0.624497,-0.531849,0.571962 -2.06682 , 1.34897 , -1.05821 , 0.112806,-0.13439,-0.984487 -2.11084 , 1.39536 , -1.05554 , -0.0520635,0.170277,0.98402 -2.16555 , 1.45007 , -1.06587 , -0.0670739,0.168709,0.983381 -2.22106 , 1.50507 , -1.07385 , -0.0688168,0.147419,0.986677 -2.27188 , 1.5578 , -1.07303 , -0.0555689,0.195552,0.979118 -2.33427 , 1.61889 , -1.08393 , -0.0878818,0.140801,0.98613 -2.39074 , 1.67703 , -1.08576 , -0.083622,0.156453,0.984139 -2.45994 , 1.74444 , -1.0986 , -0.0800099,0.17696,0.980961 -2.52321 , 1.80892 , -1.10228 , -0.0474461,0.183012,0.981965 -2.5984 , 1.88403 , -1.11642 , -0.054386,0.17868,0.982403 -2.66249 , 1.95043 , -1.11493 , -0.0338684,0.171275,0.984641 -2.75835 , 2.04207 , -1.14123 , 0.00604072,0.191643,0.981446 -2.84801 , 2.12993 , -1.15768 , -0.0267159,0.196223,0.980195 -2.93786 , 2.22056 , -1.17073 , -0.0494705,0.191042,0.980335 -3.03524 , 2.31635 , -1.18532 , -0.0429634,0.189801,0.980882 -3.13279 , 2.41497 , -1.19621 , -0.0578209,0.176609,0.982581 -3.23709 , 2.52009 , -1.20828 , -0.0522873,0.173778,0.983396 -3.35516 , 2.63735 , -1.22638 , -0.0573962,0.187811,0.980527 -3.48084 , 2.76118 , -1.24426 , -0.215683,0.117254,0.969398 -3.61266 , 2.89399 , -1.26217 , -0.146177,0.271184,0.951363 -3.75201 , 3.03361 , -1.2788 , 0.333605,-0.275691,-0.9015 -3.87908 , 3.1637 , -1.28001 , -0.19274,0.275213,0.941865 -3.7748 , 3.09804 , -1.12329 , -0.946758,0.15168,-0.283975 -3.6543 , 3.01721 , -0.962806 , 0.98014,-0.0324213,0.195639 -3.69639 , 3.07491 , -0.907944 , 0.977342,0.155739,0.143345 -3.70333 , 3.10275 , -0.831277 , -0.947296,-0.29681,-0.120556 -3.60518 , 3.03836 , -0.696589 , -0.916159,-0.212897,-0.339601 -3.60964 , 3.06327 , -0.62181 , -0.960015,-0.13699,-0.24414 -3.61363 , 3.08627 , -0.546636 , 0.974751,-0.0140281,-0.222853 -3.6295 , 3.12173 , -0.478323 , -0.942703,0.0200706,0.333029 -3.67314 , 3.18246 , -0.422181 , -0.90052,0.0444338,0.432539 -3.69527 , 3.22255 , -0.354447 , -0.903904,0.00178354,0.427733 -3.73721 , 3.28236 , -0.294626 , -0.903904,0.00178349,0.427733 -4.73598 , 4.23268 , -0.604549 , 0.710677,0.264544,0.651885 -4.73536 , 4.25922 , -0.50266 , 0.710677,0.264544,0.651885 -4.36431 , 3.98576 , -0.0907941 , -0.497939,-0.508451,-0.70252 -4.40832 , 4.05246 , -0.0104805 , -0.497939,-0.508451,-0.70252 -21.8548 , 21.2474 , -3.16964 , -0.576055,0.0720515,0.814229 -22.6687 , 22.1879 , -2.80028 , -0.194848,0.242413,0.950405 -23.9801 , 23.6348 , -2.46535 , -0.905671,0.246853,0.344708 -28.964 , 28.7733 , -2.5257 , 0.996258,0.0556779,0.0661049 -28.9394 , 28.9327 , -1.83742 , 0.995843,0.0594149,0.0690455 -28.7377 , 28.9121 , -1.13373 , 0.995699,0.0603258,0.0703229 -23.8754 , 24.1375 , -0.191708 , 0.431775,-0.880068,-0.197612 -23.9356 , 24.3521 , 0.377863 , -0.479987,0.870592,0.108085 -23.3069 , 23.8574 , 0.955957 , 0.020473,0.872401,0.488362 -21.7696 , 22.5533 , 2.01757 , -0.574959,-0.69924,0.424837 -21.5663 , 22.4824 , 2.53732 , -0.574959,-0.69924,0.424837 -21.7477 , 22.8186 , 3.08824 , -0.571579,-0.768478,0.287643 -21.2594 , 22.443 , 3.5718 , -0.0818465,0.874167,0.478679 -25.4678 , 27.1059 , 4.72972 , -0.0372331,0.445135,0.894689 -22.5018 , 24.0752 , 4.8647 , 0.350971,-0.898674,0.263067 -21.9543 , 23.6348 , 5.33524 , 0.420232,-0.870965,0.254607 -22.0648 , 23.91 , 5.9326 , -0.407418,0.88224,-0.23593 -22.1917 , 24.3656 , 7.14099 , -0.264496,-0.954521,0.13759 -21.7181 , 23.9984 , 7.59669 , 0.0484269,-0.959115,0.278844 -21.8333 , 24.2888 , 8.23269 , 0.0690433,-0.946002,0.316722 -21.9886 , 24.6283 , 8.89966 , 0.207495,-0.710565,0.672341 -24.3979 , 27.5432 , 10.4754 , -0.276424,0.761566,-0.586179 -23.5051 , 26.7078 , 10.8022 , -0.490468,0.815653,-0.306842 -22.275 , 25.6504 , 11.6013 , 0.318258,-0.944634,0.0798702 -5.19444 , 6.14586 , 4.75503 , 0.307758,0.94888,-0.0700899 -4.99262 , 5.94101 , 4.76755 , 0.215175,0.871259,-0.441144 -4.94592 , 5.92846 , 4.90464 , 0.259497,0.693363,-0.672242 -4.23727 , 5.20264 , 4.92593 , -0.269816,0.027916,0.962507 -3.59652 , 4.43843 , 4.54939 , 0.457131,0.842564,-0.284812 -3.63336 , 4.52898 , 4.7463 , -0.462733,-0.851871,-0.245346 -3.29849 , 4.11499 , 4.49333 , 0.148862,0.332486,0.931286 -3.3379 , 4.20986 , 4.69388 , 0.339398,0.0820644,0.937056 -3.18525 , 4.03911 , 4.64583 , -0.0800041,0.554228,0.828511 -3.11124 , 3.9769 , 4.69826 , 0.0550481,0.741189,0.669035 -3.04692 , 3.92711 , 4.76135 , -0.362854,-0.931783,0.0108274 -3.1073 , 4.0568 , 5.01296 , -0.793791,-0.553692,-0.251635 -3.05925 , 4.03414 , 5.10978 , -0.892704,-0.394582,-0.217679 -3.06014 , 4.08243 , 5.28797 , 0.996205,0.0677516,0.0546408 -3.08486 , 4.16902 , 5.51715 , -0.565165,0.405292,-0.718559 -2.83563 , 3.84296 , 5.26355 , -0.42384,-0.882955,-0.201867 -2.84506 , 3.90882 , 5.47079 , 0.640929,0.63577,0.430124 -2.76982 , 3.84428 , 5.52067 , -0.216803,0.940339,-0.262219 -2.71174 , 3.80693 , 5.60557 , 0.529623,-0.611914,0.587419 -2.55511 , 3.61145 , 5.47914 , 0.497574,-0.839865,-0.216904 -2.2253 , 3.12564 , 4.94169 , -0.302261,-0.573662,0.761282 -2.105 , 2.97397 , 4.84189 , -0.357851,0.494959,-0.791807 -2.04112 , 2.91575 , 4.86991 , -0.359751,-0.922437,0.140318 -2.04759 , 2.97848 , 5.07877 , 0.383986,0.865671,0.3212 -2.07466 , 3.0832 , 5.36272 , 0.303941,0.837607,-0.45391 -1.95253 , 2.92226 , 5.2363 , 0.0145165,0.785678,0.618466 -2.12813 , 3.31059 , 6.00116 , -0.273605,0.709485,0.64944 -2.36868 , 3.84275 , 7.05578 , 0.777963,-0.582036,0.236659 -2.39659 , 3.98988 , 7.49962 , -0.417846,-0.510594,0.751465 -2.07697 , 3.45414 , 6.73358 , -0.917458,0.315533,-0.2423 -2.02793 , 3.44867 , 6.902 , -0.917458,0.315533,-0.2423 -1.66811 , 2.78369 , 5.81432 , 0.402176,-0.0569551,0.913789 -1.59518 , 2.71109 , 5.82302 , 0.854575,0.469422,0.222134 -1.59247 , 2.7977 , 6.15634 , -0.950402,-0.290107,0.11213 -1.53353 , 2.76293 , 6.25272 , -0.127249,0.385113,0.914055 -1.46216 , 2.6971 , 6.28581 , 0.674743,0.439669,0.592801 -1.40322 , 2.66675 , 6.39836 , -0.398539,-0.899976,-0.176662 -1.34117 , 2.63094 , 6.50122 , 0.0138587,-0.749532,0.661823 -1.01065 , 1.80177 , 4.68723 , 0.120247,-0.251864,0.960263 -0.952989 , 1.728 , 4.63761 , -0.00300981,0.183228,0.983066 -0.90495 , 1.68168 , 4.65077 , 0.030621,-0.247298,-0.968456 -0.866545 , 1.67594 , 4.77481 , -0.0891066,0.947607,0.30676 -0.965602 , 2.25539 , 6.5522 , -0.194605,0.601036,0.775167 -0.841629 , 1.93656 , 5.84467 , 0.385056,-0.673528,-0.630945 -0.785371 , 1.91894 , 5.99144 , -0.437946,0.886424,-0.149851 -0.730432 , 1.92199 , 6.21413 , 0.958826,-0.0260582,0.282796 -0.658805 , 1.81472 , 6.09272 , 0.832094,-0.342778,0.436031 -0.571418 , 1.40242 , 4.892 , 0.482945,-0.317376,-0.816111 -0.522619 , 1.35235 , 4.89628 , -0.1396,0.609668,0.780267 -0.472707 , 1.3276 , 4.996 , 0.557862,0.783062,0.274961 -0.40625 , 1.46363 , 5.75499 , -0.37324,-0.816525,-0.440431 -0.334802 , 1.48418 , 6.10818 , 0.784959,-0.229127,0.575622 -0.269243 , 1.43208 , 6.16882 , -0.59846,0.516522,-0.612414 -0.218978 , 1.31517 , 5.92505 , -0.919488,0.0661265,-0.387516 -0.162307 , 1.24007 , 5.86512 , 0.583632,-0.388245,0.71319 -0.0965991 , 1.19009 , 5.93072 , -0.655589,-0.754746,-0.0237171 -2.03912 , 1.24313 , -1.04932 , -0.185401,0.103875,0.977157 -2.07802 , 1.28352 , -1.04115 , 0.205625,-0.128749,-0.970125 -2.1296 , 1.33167 , -1.04633 , -0.0784063,0.135448,0.987677 -2.18008 , 1.38045 , -1.04979 , 0.081535,-0.154206,-0.984669 -2.23738 , 1.4338 , -1.05849 , 0.106633,-0.148663,-0.983122 -2.28877 , 1.48417 , -1.05823 , -0.0762896,0.175261,0.981562 -2.35869 , 1.54711 , -1.07659 , 0.089933,-0.201011,-0.975452 -2.40525 , 1.59565 , -1.06558 , -0.0897917,0.165658,0.982087 -2.47504 , 1.66063 , -1.07927 , -0.0804549,0.175173,0.981245 -2.53394 , 1.71792 , -1.07723 , -0.0702415,0.204092,0.976429 -2.61859 , 1.79447 , -1.09849 , -0.032059,0.190214,0.981219 -2.69634 , 1.86834 , -1.11052 , -0.0461717,0.188503,0.980987 -2.77483 , 1.9427 , -1.1193 , -0.0141081,0.18691,0.982276 -2.86706 , 2.02759 , -1.13685 , -0.0289007,0.20368,0.978611 -2.95336 , 2.10962 , -1.14494 , -0.0526226,0.188018,0.980755 -3.05334 , 2.20236 , -1.161 , -0.0604221,0.19876,0.978184 -3.16009 , 2.30155 , -1.17843 , -0.0682605,0.194742,0.978476 -3.26088 , 2.39789 , -1.18631 , -0.0721528,0.187491,0.979613 -3.37524 , 2.50534 , -1.20041 , -0.0664942,0.192876,0.978968 -3.48948 , 2.61482 , -1.20994 , -0.250878,0.141292,0.957652 -3.63245 , 2.74768 , -1.23454 , -0.324014,0.290365,0.900391 -3.75535 , 2.86665 , -1.23868 , 0.720341,-0.29161,-0.629342 -3.6777 , 2.82593 , -1.10216 , 0.996742,0.0394007,0.0703812 -3.66067 , 2.8335 , -1.00996 , 0.988303,0.0435651,0.146146 -3.65551 , 2.85186 , -0.927632 , 0.999699,-0.00110578,0.0245047 -3.63574 , 2.85562 , -0.836828 , 0.921787,-0.181055,-0.342823 -3.67872 , 2.91169 , -0.783691 , -0.971675,0.0979623,-0.21506 -3.74889 , 2.98973 , -0.744078 , -0.917478,-0.306232,-0.253882 -3.61232 , 2.89618 , -0.593228 , 0.990545,0.104101,0.0893538 -3.61573 , 2.91991 , -0.520318 , 0.973624,0.0228184,-0.227014 -3.63369 , 2.95448 , -0.453806 , -0.939005,-0.0011725,0.343901 -3.66419 , 3.0005 , -0.393059 , -0.871566,0.030559,0.489324 -3.69437 , 3.04585 , -0.330849 , -0.834701,0.0283739,0.549973 -3.74509 , 3.10979 , -0.276136 , -0.839688,0.0160968,0.542831 -4.78521 , 4.09222 , -0.396988 , 0.710677,0.264544,0.651885 -4.42405 , 3.84422 , -0.00257221 , -0.41684,-0.731297,-0.539861 -21.5997 , 19.7741 , -3.09367 , 0.636284,-0.0381012,-0.770514 -22.6894 , 20.9151 , -2.79128 , -0.403901,0.0815658,0.911159 -22.6812 , 21.0434 , -2.27361 , -0.403901,0.0815659,0.911159 -29.0236 , 27.1519 , -2.55533 , 0.993299,0.0560795,0.101054 -28.9694 , 27.2765 , -1.88227 , 0.993299,0.0560795,0.101054 -28.9351 , 27.42 , -1.21097 , 0.996127,0.0577844,0.0662761 -28.7987 , 27.4652 , -0.532692 , 0.996803,0.0578716,0.0550901 -28.8768 , 27.7179 , 0.135379 , 0.997326,0.0659298,0.031544 -23.5337 , 22.6977 , 0.854446 , -0.178404,0.892327,0.414639 -24.1095 , 23.4081 , 1.41573 , -0.178403,0.892326,0.414639 -28.7616 , 28.1425 , 2.17208 , 0.99877,0.0376525,0.0322688 -24.1993 , 23.7977 , 2.56552 , -0.0671063,0.911217,0.406424 -22.8016 , 22.5552 , 3.022 , -0.200508,0.978531,-0.0476863 -28.6712 , 28.5991 , 4.24053 , 0.998155,0.0377688,0.0475388 -28.6268 , 28.7389 , 4.9375 , 0.997687,0.042532,0.0530267 -28.573 , 28.8712 , 5.63754 , 0.997766,0.0456771,0.0487447 -28.5173 , 29.0017 , 6.34214 , 0.998389,0.0377478,0.0423716 -28.4991 , 29.174 , 7.05994 , 0.998703,0.0410776,0.0300782 -28.4991 , 29.3653 , 7.78991 , 0.99621,0.0630325,0.0599427 -28.4395 , 29.4985 , 8.51334 , 0.99621,0.0630325,0.0599427 -28.256 , 29.5028 , 9.20671 , 0.994618,0.0695828,0.0767672 -22.4872 , 23.5886 , 8.10559 , -0.264496,-0.954521,0.13759 -5.0945 , 5.77862 , 4.86136 , 0.215175,0.871259,-0.441144 -3.75818 , 4.36022 , 4.42121 , 0.808879,0.574386,-0.125677 -3.6983 , 4.32283 , 4.50383 , -0.816189,-0.279684,0.505581 -3.58584 , 4.22009 , 4.5277 , 0.284265,-0.786779,-0.54788 -3.51547 , 4.16836 , 4.59448 , 0.305759,-0.799203,-0.517481 -3.61013 , 4.33202 , 4.86337 , -0.897068,-0.328762,0.29527 -3.57272 , 4.3266 , 4.98002 , 0.724851,0.436594,0.532895 -3.28178 , 3.9838 , 4.75803 , -0.352673,0.689381,0.632753 -3.16387 , 3.86791 , 4.75249 , 0.16278,0.964837,0.206379 -3.22819 , 3.99654 , 5.00371 , 0.660512,0.678917,0.320617 -3.14071 , 3.92085 , 5.04091 , -0.644231,-0.574844,-0.504501 -3.13935 , 3.96387 , 5.21128 , -0.920903,-0.2767,-0.274544 -3.10898 , 3.9701 , 5.34185 , 0.00636458,0.536342,0.843977 -2.98241 , 3.83867 , 5.31184 , 0.471896,-0.0131756,0.881556 -2.91829 , 3.79492 , 5.38407 , -0.0348864,-0.985825,0.164112 -2.58253 , 3.35232 , 4.94651 , -0.372731,-0.440133,-0.816918 -2.47605 , 3.23917 , 4.91212 , -0.121712,0.480134,0.86871 -2.46222 , 3.26504 , 5.06087 , -0.121712,0.480134,0.86871 -2.36081 , 3.15739 , 5.0287 , -0.250183,0.145123,0.95726 -2.1848 , 2.93243 , 4.82309 , 0.145875,0.0998712,-0.984249 -2.1303 , 2.89254 , 4.87471 , 0.159704,0.969197,0.18749 -2.10622 , 2.90331 , 5.00431 , 0.295076,0.953591,-0.0599551 -2.10425 , 2.95259 , 5.19902 , -0.324029,-0.940502,0.102281 -2.08842 , 2.98284 , 5.37161 , -0.457345,0.323429,-0.828389 -2.01247 , 2.91124 , 5.38151 , 0.124398,0.18183,0.97543 -1.92012 , 2.81082 , 5.33923 , 0.755037,0.631943,0.174833 -2.25728 , 3.48708 , 6.66197 , -0.917458,0.315533,-0.2423 -2.27249 , 3.6023 , 7.0432 , -0.917459,0.315533,-0.2423 -2.17423 , 3.50871 , 7.05218 , -0.917458,0.315533,-0.2423 -2.11882 , 3.49899 , 7.22283 , -0.917459,0.315533,-0.2423 -1.67308 , 2.69398 , 5.81336 , -0.569861,-0.228041,-0.789466 -1.50334 , 2.42154 , 5.40658 , -0.921849,-0.378733,0.0821966 -1.57546 , 2.66533 , 6.06532 , 0.875486,0.477231,0.0759917 -1.5144 , 2.62884 , 6.15083 , 0.655946,0.617758,0.433715 -1.48975 , 2.6819 , 6.44311 , -0.215564,-0.911687,0.349798 -1.40044 , 2.58102 , 6.39212 , -0.134216,0.967934,-0.212342 -1.05168 , 1.77584 , 4.62645 , 0.106965,-0.0694342,0.991835 -1.00157 , 1.73037 , 4.64121 , 0.0367904,-0.0824506,0.995916 -0.950066 , 1.68198 , 4.64532 , -0.0753241,0.181474,0.980507 -0.883757 , 1.58071 , 4.50846 , 0.830156,-0.137627,0.540278 -0.847102 , 1.57738 , 4.63106 , 0.697082,-0.178645,0.69438 -0.903238 , 1.97526 , 5.93262 , 0.570581,-0.786136,-0.237543 -0.729375 , 1.38964 , 4.35529 , -0.939257,0.144184,0.311461 -0.772662 , 1.85975 , 5.97971 , -0.862353,0.339153,-0.375929 -0.700239 , 1.75779 , 5.85755 , 0.990372,0.118157,0.0721292 -0.615729 , 1.47739 , 5.10882 , -0.831839,0.488808,-0.262889 -0.558355 , 1.3678 , 4.90203 , 0.459958,-0.409376,-0.78794 -0.50766 , 1.32409 , 4.92457 , -0.0907236,0.681571,0.726106 -0.44793 , 1.46774 , 5.69282 , -0.64192,-0.742251,-0.192359 -0.377862 , 1.49515 , 6.05546 , -0.183744,0.821772,-0.539379 -0.304516 , 1.48255 , 6.28206 , 0.846686,-0.519186,0.116486 -0.248861 , 1.36503 , 6.03905 , 0.426388,-0.895752,0.125782 -0.192602 , 1.27673 , 5.9109 , 0.311728,-0.612504,0.726405 -0.133318 , 1.21017 , 5.87886 , 0.576426,-0.630435,0.519889 -2.06496 , 1.18947 , -1.05419 , 0.173358,-0.136652,-0.975332 -2.08822 , 1.2184 , -1.02373 , 0.173358,-0.136652,-0.975332 -2.14616 , 1.26756 , -1.03669 , -0.144445,0.148321,0.978333 -2.20418 , 1.31811 , -1.04789 , 0.104407,-0.191626,-0.975899 -2.24474 , 1.35893 , -1.03569 , 0.0799573,-0.193846,-0.977768 -2.30967 , 1.4155 , -1.05021 , -0.107255,0.176066,0.978518 -2.35671 , 1.46029 , -1.0415 , 0.099052,-0.202255,-0.974311 -2.42826 , 1.52206 , -1.05845 , -0.0879014,0.193064,0.977241 -2.48792 , 1.57644 , -1.0594 , -0.101846,0.171458,0.979913 -2.55457 , 1.63658 , -1.06473 , -0.0625344,0.18204,0.981301 -2.62795 , 1.70159 , -1.07404 , -0.0474304,0.189697,0.980696 -2.70208 , 1.76701 , -1.08042 , -0.0353285,0.20591,0.977933 -2.78907 , 1.843 , -1.09655 , -0.0145466,0.19951,0.979788 -2.88291 , 1.92514 , -1.1153 , -0.0309464,0.20876,0.977477 -2.97841 , 2.00769 , -1.13012 , -0.0688375,0.204819,0.976376 -3.06725 , 2.08852 , -1.1359 , -0.0722879,0.184537,0.980164 -3.16267 , 2.17464 , -1.14372 , -0.0730363,0.200025,0.977065 -3.27268 , 2.27149 , -1.15842 , -0.0789213,0.206865,0.975181 -3.38357 , 2.37008 , -1.16873 , -0.0769299,0.195963,0.977589 -3.50823 , 2.4808 , -1.18516 , -0.133311,0.169503,0.976472 -3.63347 , 2.59249 , -1.19623 , 0.473622,-0.22278,-0.852087 -3.72389 , 2.67999 , -1.17801 , 0.990503,-0.0562363,0.125466 -3.65891 , 2.65264 , -1.05312 , 0.997322,0.0289657,0.0671607 -3.65506 , 2.67142 , -0.972229 , 0.998519,0.0482937,0.0250538 -3.6585 , 2.69279 , -0.895493 , 0.994356,0.106077,0.00184333 -3.66699 , 2.72033 , -0.823475 , 0.998351,0.0379828,-0.0430457 -3.65336 , 2.7297 , -0.738826 , 0.986207,-0.0107115,-0.165172 -3.81236 , 2.87314 , -0.748994 , -0.77005,-0.418838,0.481245 -3.62916 , 2.74962 , -0.575423 , 0.951526,0.171629,0.255227 -3.63461 , 2.77262 , -0.503633 , 0.974365,0.0190969,-0.224162 -3.63763 , 2.79416 , -0.431593 , 0.942197,0.000845876,-0.335058 -3.67715 , 2.84528 , -0.376054 , -0.879606,0.0021456,0.475698 -3.7082 , 2.88903 , -0.315472 , -0.79149,0.038295,0.609982 -3.78337 , 2.96889 , -0.271272 , -0.801813,0.00801937,0.597521 -4.78529 , 3.86192 , -0.377348 , 0.415205,0.651798,0.634637 -18.0729 , 15.4431 , -2.77965 , -0.100445,0.186039,0.977395 -21.5352 , 18.5514 , -3.05659 , -0.561368,-0.0693611,0.824655 -22.256 , 19.3044 , -2.70463 , 0.284329,0.141764,-0.948188 -22.753 , 19.8681 , -2.28571 , -0.441661,-0.0694049,0.894494 -22.9065 , 20.1347 , -1.79998 , -0.480384,0.00576722,0.877039 -29.0364 , 25.731 , -1.92696 , 0.997028,0.0530644,0.0558577 -29.0017 , 25.868 , -1.27241 , 0.995756,0.065539,0.0646165 -28.9502 , 25.9906 , -0.616169 , 0.996457,0.0691831,0.0478279 -28.9205 , 26.1319 , 0.0401159 , 0.997454,0.0624379,0.0344516 -28.9027 , 26.2864 , 0.697933 , 0.998119,0.0552882,0.0264784 -24.5375 , 22.4362 , 1.30972 , -0.178403,0.892326,0.41464 -28.8349 , 26.5662 , 2.02176 , 0.997666,0.0546523,0.0409488 -28.7685 , 26.6774 , 2.68616 , 0.997674,0.0542235,0.0413089 -28.7302 , 26.815 , 3.35468 , 0.997766,0.0554167,0.037303 -28.7403 , 26.9992 , 4.03211 , 0.99827,0.0505665,0.029994 -28.7049 , 27.1413 , 4.71023 , 0.99809,0.0449236,0.0423991 -28.6604 , 27.2767 , 5.39142 , 0.997675,0.0467245,0.0496058 -28.5986 , 27.3959 , 6.07469 , 0.997778,0.0494149,0.0446908 -28.5914 , 27.5699 , 6.7734 , 0.99829,0.0479705,0.0334073 -28.5595 , 27.7221 , 7.47426 , 0.998828,0.0368402,0.0314041 -28.5255 , 27.873 , 8.18143 , 0.99771,0.0393475,0.0550184 -28.4937 , 28.0292 , 8.89691 , 0.994936,0.0621135,0.0790279 -28.3966 , 28.1215 , 9.60059 , 0.994936,0.0621135,0.0790278 -3.75994 , 4.23747 , 4.71827 , 0.301627,0.952798,0.0345986 -3.68531 , 4.18609 , 4.78671 , -0.46142,-0.86975,0.175003 -3.61922 , 4.14624 , 4.8652 , 0.724593,0.688907,-0.0192927 -3.38703 , 3.8983 , 4.72998 , -0.454761,0.636832,0.622605 -3.34821 , 3.88836 , 4.83325 , 0.181157,0.976296,0.118438 -3.29676 , 3.86511 , 4.92317 , -0.327612,-0.92206,-0.206097 -3.25416 , 3.8518 , 5.026 , -0.835735,-0.0838261,-0.542697 -3.20492 , 3.8323 , 5.1214 , -0.872802,-0.131032,-0.470158 -3.14151 , 3.79306 , 5.19595 , 0.224536,0.930823,0.288361 -3.12023 , 3.81021 , 5.33933 , 0.482261,0.243665,0.841458 -3.02485 , 3.72833 , 5.36264 , -0.115152,-0.824398,-0.554174 -3.56942 , 4.52947 , 6.52697 , -0.492058,-0.857884,0.148035 -2.59682 , 3.229 , 4.95168 , 0.372731,0.440133,0.816918 -2.51396 , 3.15702 , 4.9667 , -0.0609527,0.114184,0.991588 -2.47677 , 3.14986 , 5.07018 , 0.0659978,0.272881,0.959781 -2.32726 , 2.97717 , 4.93544 , 0.663275,0.0425579,-0.747164 -2.28912 , 2.96853 , 5.03569 , 0.526163,0.120155,0.841852 -2.22693 , 2.92287 , 5.08073 , -0.376189,-0.84809,-0.373129 -2.24199 , 2.9974 , 5.31624 , -0.758125,-0.586772,-0.28451 -2.15994 , 2.92296 , 5.32036 , 0.204874,-0.38464,0.900044 -2.02458 , 2.76127 , 5.17452 , 0.392118,-0.0717762,0.917111 -1.96365 , 2.71785 , 5.22172 , 0.583553,-0.476806,0.65736 -1.95226 , 2.7583 , 5.41835 , -0.971354,0.107856,-0.211751 -1.88878 , 2.71215 , 5.46454 , -0.82676,-0.0467242,-0.560611 -1.8173 , 2.65186 , 5.48362 , -0.774299,-0.365518,-0.516583 -1.79448 , 2.67907 , 5.67375 , -0.771049,-0.337269,-0.540123 -1.62745 , 2.43768 , 5.33376 , -0.644716,0.764361,-0.00966861 -1.56402 , 2.38702 , 5.36329 , -0.928591,-0.331289,0.16723 -1.64842 , 2.63959 , 6.03853 , -0.818475,-0.551423,-0.161345 -1.61381 , 2.66244 , 6.24922 , -0.97876,-0.163477,0.123713 -1.57561 , 2.68408 , 6.47009 , -0.502965,-0.857073,0.11159 -1.51271 , 2.65483 , 6.58323 , -0.295173,-0.623249,0.724178 -1.10401 , 1.7771 , 4.63932 , 0.122767,0.275407,0.953456 -1.04822 , 1.72313 , 4.62659 , -0.111166,0.596852,0.794613 -1.00059 , 1.68994 , 4.66805 , -0.0186336,0.363436,0.931433 -1.12927 , 2.19181 , 6.15238 , 0.441595,0.510155,-0.738062 -0.887276 , 1.568 , 4.59834 , -0.500756,-0.6775,-0.538737 -0.83845 , 1.53134 , 4.62673 , 0.837081,0.127263,0.532072 -0.777023 , 1.4401 , 4.49341 , 0.204688,-0.154531,0.966552 -0.732761 , 1.41594 , 4.55713 , 0.986458,-0.153345,-0.0581975 -0.743172 , 1.7237 , 5.70902 , 0.9971,0.0394542,-0.0650799 -0.696394 , 1.79918 , 6.16913 , -0.874926,0.220689,-0.431045 -0.596325 , 1.38571 , 4.92733 , -0.628512,0.313762,0.711707 -0.543375 , 1.33355 , 4.91153 , -0.0011744,0.46473,0.885451 -0.491029 , 1.30529 , 4.99141 , 0.551272,0.771892,0.316673 -0.422647 , 1.47728 , 5.89611 , 0.520812,-0.760366,0.38807 -0.354289 , 1.44533 , 6.0151 , -0.564104,0.737634,-0.371057 -0.282174 , 1.41705 , 6.16249 , 0.670048,-0.700427,0.245843 -0.231372 , 1.2921 , 5.85903 , -0.73242,0.423258,-0.533304 -0.165507 , 1.23837 , 5.88609 , 0.478535,-0.426772,0.767379 -0.0973409 , 1.18995 , 5.94108 , -0.655589,-0.754746,-0.0237171 -2.10708 , 1.16065 , -1.02121 , -0.203315,0.100357,0.973957 -2.15423 , 1.20176 , -1.01999 , -0.174851,0.129144,0.976089 -2.20704 , 1.24662 , -1.02434 , -0.133407,0.195371,0.971614 -2.25516 , 1.28922 , -1.01989 , -0.114144,0.211038,0.970791 -2.32141 , 1.34221 , -1.03484 , -0.116877,0.171173,0.978284 -2.37525 , 1.39001 , -1.03391 , -0.126398,0.162866,0.978518 -2.43662 , 1.44131 , -1.03753 , -0.0980842,0.206781,0.973458 -2.49808 , 1.49401 , -1.03931 , -0.0634163,0.175548,0.982426 -2.57202 , 1.55503 , -1.052 , -0.0683867,0.185872,0.980191 -2.64028 , 1.61405 , -1.05572 , -0.0350035,0.184498,0.982209 -2.7229 , 1.68115 , -1.06924 , -0.0249681,0.185964,0.982239 -2.80553 , 1.7499 , -1.07985 , -0.0395614,0.19744,0.979516 -2.89481 , 1.82375 , -1.09337 , -0.0495272,0.201583,0.978218 -2.97817 , 1.89467 , -1.09773 , 0.0479195,-0.215023,-0.975433 -3.0831 , 1.98044 , -1.11617 , -0.0585083,0.195971,0.978863 -3.17401 , 2.05813 , -1.11934 , -0.076595,0.177715,0.981097 -3.27978 , 2.14739 , -1.13007 , -0.0701257,0.198155,0.977659 -3.39208 , 2.24213 , -1.14207 , 0.0679216,-0.191972,-0.979047 -3.51304 , 2.34301 , -1.15461 , -0.136879,0.177365,0.97458 -3.64069 , 2.45057 , -1.16754 , 0.557982,-0.135764,-0.818672 -3.69829 , 2.50996 , -1.1265 , 0.985857,-0.0362775,-0.163616 -3.67508 , 2.51434 , -1.03178 , 0.984053,0.122609,-0.128865 -3.68703 , 2.54287 , -0.960962 , 0.969124,0.246556,-0.002964 -3.6758 , 2.55376 , -0.876271 , 0.977419,0.209519,0.0274495 -3.67042 , 2.56946 , -0.796857 , 0.988244,0.125824,0.0868482 -3.6718 , 2.58994 , -0.721819 , 0.996801,0.0640928,0.047756 -3.66384 , 2.60304 , -0.642832 , 0.99295,-0.0999231,0.063757 -3.8121 , 2.73103 , -0.644041 , -0.434809,0.900371,-0.0165583 -3.63772 , 2.62166 , -0.482878 , 0.997599,0.0241926,-0.0648972 -3.64183 , 2.64264 , -0.412273 , -0.926695,0.0455807,0.373041 -3.67531 , 2.68614 , -0.355052 , -0.874997,0.0524913,0.481275 -3.71536 , 2.73503 , -0.299484 , 0.786541,-0.0638584,-0.614228 -3.77767 , 2.80105 , -0.251266 , 0.777901,-0.0766491,-0.623695 -4.6929 , 3.66689 , 0.0413685 , 0.43662,0.654355,0.6174 -22.3723 , 18.2599 , -2.71665 , 0.237487,0.290729,-0.926864 -24.051 , 19.7701 , -2.48417 , 0.196073,0.775735,-0.599825 -23.9368 , 19.8075 , -1.94835 , 0.356256,0.933793,-0.0333372 -24.1527 , 20.1199 , -1.45095 , 0.356257,0.933793,-0.0333371 -29.0882 , 24.4191 , -1.33459 , 0.773957,0.428613,0.466134 -29.0738 , 24.5689 , -0.695599 , 0.773957,0.428614,0.466135 -29.0042 , 24.6722 , -0.052595 , 0.994812,0.0974739,0.0291314 -28.9867 , 24.8192 , 0.589765 , 0.994802,0.0945582,0.0377951 -28.9461 , 24.9471 , 1.2343 , 0.996191,0.0824974,0.0282472 -28.9106 , 25.0806 , 1.88095 , -0.922505,-0.300573,0.242156 -28.8966 , 25.2337 , 2.53134 , 0.955782,0.248255,0.157643 -28.8656 , 25.3726 , 3.1844 , 0.996058,0.0852378,0.0245726 -28.8178 , 25.4972 , 3.83963 , 0.995922,0.0863091,0.0262725 -28.7988 , 25.6486 , 4.50155 , 0.996027,0.0817124,0.0354108 -28.7467 , 25.7716 , 5.16401 , 0.995198,0.0811734,0.0546972 -28.7081 , 25.9082 , 5.83254 , -0.9437,-0.289965,-0.159219 -28.6676 , 26.0432 , 6.50601 , 0.997132,0.0717297,0.024136 -28.6243 , 26.1778 , 7.1843 , 0.995941,0.0899799,0.00248916 -28.6068 , 26.338 , 7.87498 , 0.993987,0.104841,0.0316054 -28.5499 , 26.4633 , 8.5631 , 0.994253,0.100064,0.0380558 -28.5261 , 26.6214 , 9.26702 , 0.992432,0.101249,0.0694849 -28.4768 , 26.7577 , 9.97162 , 0.992432,0.101249,0.0694849 -3.87213 , 4.13651 , 4.68981 , 0.50152,-0.261528,0.82467 -3.79118 , 4.08127 , 4.75238 , 0.653888,-0.109169,0.748674 -3.84308 , 4.18202 , 4.97083 , 0.242875,0.82388,0.512088 -3.69851 , 4.05326 , 4.95758 , -0.251058,0.68396,0.684959 -3.64922 , 4.03722 , 5.0595 , -0.0229832,0.350353,0.936336 -3.4974 , 3.8964 , 5.025 , -0.167477,0.341552,0.924821 -3.39456 , 3.81475 , 5.05058 , -0.0304226,-0.105308,-0.993974 -3.22354 , 3.64645 , 4.97214 , -0.834637,-0.188521,-0.517534 -3.38884 , 3.89442 , 5.3874 , 0.148187,0.93984,-0.307801 -3.28042 , 3.80443 , 5.4016 , 0.146412,-0.926337,-0.347077 -2.80889 , 3.24811 , 4.81587 , 0.253183,0.965842,-0.0552063 -2.51666 , 2.91067 , 4.48135 , 0.611001,0.790479,0.0426743 -2.4435 , 2.85167 , 4.49961 , -0.914613,-0.0142732,-0.404077 -2.61755 , 3.12306 , 4.97746 , -0.37273,-0.440133,-0.816918 -2.57633 , 3.11224 , 5.07366 , 0.241664,-0.14947,0.958779 -2.40496 , 2.92201 , 4.90928 , -0.404147,-0.77892,-0.47953 -2.33149 , 2.86395 , 4.93172 , 0.798857,0.591911,0.107092 -2.2971 , 2.86207 , 5.03864 , -0.719459,-0.329821,-0.611226 -2.25662 , 2.85174 , 5.13807 , -0.2866,-0.667392,-0.687348 -2.20778 , 2.83163 , 5.2209 , 0.0729209,0.316859,0.945665 -2.11968 , 2.75146 , 5.20541 , -0.586056,0.796623,-0.148089 -2.02977 , 2.66635 , 5.17908 , 0.320912,-0.488507,0.811404 -2.01783 , 2.70404 , 5.36682 , 0.788857,0.264576,0.554711 -1.89484 , 2.56435 , 5.23544 , -0.902136,0.426884,0.0626106 -1.92895 , 2.6821 , 5.58553 , -0.119105,0.920227,0.372823 -2.23011 , 3.26804 , 6.87059 , -0.917458,0.315533,-0.2423 -1.92534 , 2.82062 , 6.14276 , -0.218742,-0.291996,0.931069 -1.73151 , 2.54921 , 5.73241 , 0.0237944,-0.246971,0.968731 -1.62676 , 2.42945 , 5.62265 , 0.611735,-0.456561,0.646013 -1.54309 , 2.34966 , 5.5889 , 0.295818,0.940778,0.165617 -1.6328 , 2.62045 , 6.35324 , -0.603653,-0.784818,-0.140225 -1.5429 , 2.53697 , 6.32973 , -0.185603,-0.982625,-6.21897e-05 -1.1554 , 1.77352 , 4.64293 , 0.0345378,0.499556,0.865593 -1.09835 , 1.72395 , 4.6398 , 0.123975,-0.484279,-0.866085 -1.04773 , 1.68561 , 4.66298 , -0.125222,0.558557,0.81996 -1.20407 , 2.21864 , 6.22929 , -0.614837,-0.544576,0.57045 -0.923091 , 1.54655 , 4.53771 , 0.703506,0.34054,-0.623788 -0.874716 , 1.51186 , 4.56599 , -0.728419,-0.0474052,-0.68349 -0.834953 , 1.50812 , 4.68794 , -0.866295,0.380875,0.323216 -0.769664 , 1.41058 , 4.52471 , 0.154626,0.238906,0.958653 -0.727386 , 1.40402 , 4.64526 , -0.804624,0.552165,0.21839 -0.739308 , 1.74593 , 5.95349 , -0.967079,0.219923,-0.128035 -0.645036 , 1.47684 , 5.21217 , -0.357884,0.205335,0.91091 -0.580584 , 1.34665 , 4.91782 , -0.439868,0.249924,0.862586 -0.52647 , 1.30574 , 4.93967 , 0.38098,0.755752,0.532628 -0.467222 , 1.43204 , 5.64003 , 0.485245,0.747267,0.454015 -0.399778 , 1.43244 , 5.87555 , 0.755791,-0.554524,0.348257 -0.329516 , 1.39976 , 5.98367 , -0.503375,0.795588,-0.337126 -0.270439 , 1.30428 , 5.80738 , -0.69888,0.540236,-0.468734 -0.203774 , 1.25798 , 5.85409 , 0.531639,-0.839077,0.115367 -0.139629 , 1.1986 , 5.84072 , -0.6495,0.658715,-0.379795 -2.16588 , 1.13891 , -1.01017 , -0.181866,0.131272,0.974522 -2.21468 , 1.17881 , -1.00774 , -0.133223,0.175914,0.975349 -2.26915 , 1.22244 , -1.01096 , -0.0836086,0.163881,0.982931 -2.33044 , 1.27065 , -1.01944 , -0.0772816,0.180096,0.980609 -2.38582 , 1.31588 , -1.01895 , -0.0802784,0.191418,0.97822 -2.44801 , 1.36574 , -1.02342 , -0.0425767,0.170366,0.984461 -2.51773 , 1.41913 , -1.03234 , -0.0602778,0.14321,0.987855 -2.58079 , 1.47074 , -1.03241 , -0.0769783,0.16248,0.983705 -2.65708 , 1.52949 , -1.04308 , -0.0517777,0.183474,0.98166 -2.73363 , 1.59078 , -1.05132 , -0.0241166,0.19014,0.981461 -2.81784 , 1.65684 , -1.06285 , -0.0471464,0.154927,0.9868 -2.8959 , 1.719 , -1.06511 , -0.0516414,0.191676,0.980099 -2.99559 , 1.79579 , -1.08242 , -0.0521011,0.201283,0.978147 -3.08127 , 1.86451 , -1.08447 , -0.0499213,0.198162,0.978897 -3.18849 , 1.94814 , -1.1003 , -0.0456307,0.189436,0.980832 -3.29541 , 2.03271 , -1.11205 , -0.067876,0.177463,0.981784 -3.39736 , 2.11416 , -1.11432 , 0.0579644,-0.177459,-0.98242 -3.51974 , 2.21119 , -1.12856 , -0.1186,0.168831,0.978484 -3.65172 , 2.31422 , -1.14292 , -0.605727,0.221898,0.764105 -3.6808 , 2.3529 , -1.08381 , -0.963455,0.0300253,0.26618 -3.68704 , 2.37623 , -1.00946 , -0.973668,-0.0247803,0.226621 -3.72137 , 2.41821 , -0.95348 , 0.997516,0.0456608,-0.0536361 -3.72516 , 2.44016 , -0.878595 , 0.996792,0.0766474,0.0230207 -3.68287 , 2.43154 , -0.778142 , 0.986632,0.0669826,0.14856 -3.66941 , 2.44038 , -0.695827 , 0.994384,0.0596933,-0.0873962 -3.66276 , 2.45389 , -0.618376 , 0.988899,0.0855084,0.121518 -3.92085 , 2.65037 , -0.674976 , -0.239382,0.080688,0.967567 -3.62916 , 2.46719 , -0.457571 , 0.988286,0.122346,0.0912224 -3.64898 , 2.49824 , -0.395676 , -0.928282,0.00826766,0.371786 -3.67566 , 2.5354 , -0.336605 , -0.88117,0.0328108,0.471659 -3.70969 , 2.57665 , -0.279452 , 0.786802,-0.0660471,-0.613662 -3.7884 , 2.65166 , -0.239236 , 0.685638,-0.0375859,-0.726972 -4.95984 , 3.68387 , 0.0825005 , -0.505472,-0.574248,-0.644001 -18.3648 , 13.9734 , -2.40779 , 0.111429,-0.17929,-0.977465 -23.1496 , 17.7586 , -2.84206 , -0.237487,-0.290729,0.926864 -25.1794 , 19.4566 , -2.65702 , -0.0324318,-0.397126,0.917191 -25.3097 , 19.6922 , -2.14053 , -0.0324318,-0.397126,0.917191 -25.3081 , 19.8241 , -1.60293 , 0.137364,0.671418,-0.728237 -30.7294 , 24.4195 , -0.86601 , 0.773957,0.428613,0.466134 -29.2135 , 23.3657 , -0.143015 , 0.989118,0.136171,0.0557108 -29.0933 , 23.4257 , 0.489243 , 0.99148,0.122905,0.0431397 -29.1746 , 23.6488 , 1.12003 , 0.991349,0.131224,0.00259635 -30.635 , 25.1714 , 2.4645 , 0.986781,0.149782,0.0618691 -28.93 , 24.0828 , 3.6654 , 0.991091,0.123933,0.048778 -29.002 , 24.3062 , 4.32175 , 0.993111,0.116442,-0.013095 -30.4748 , 25.8915 , 5.87686 , -0.9437,-0.289965,-0.15922 -28.7247 , 24.7277 , 6.92506 , 0.991528,0.129003,0.0151656 -28.8429 , 24.9999 , 7.62901 , 0.991886,0.119058,-0.044584 -28.8612 , 25.1873 , 8.32115 , 0.988582,0.148327,-0.0265396 -28.7111 , 25.4029 , 9.67791 , 0.97977,0.162858,0.116313 -28.5603 , 25.4441 , 10.34 , 0.97977,0.162858,0.116313 -4.27386 , 4.08929 , 3.94901 , 0.0813344,0.318453,0.944443 -4.15483 , 4.00132 , 3.9856 , 0.0503439,0.382089,0.922753 -4.02468 , 3.90152 , 4.00759 , -0.101684,0.57915,0.808854 -4.03729 , 4.05065 , 4.56948 , 0.210494,0.12585,0.969461 -3.99906 , 4.04726 , 4.67975 , 0.180219,0.0725807,0.980945 -3.88336 , 3.95967 , 4.70694 , -0.295882,-0.0500807,-0.953911 -3.75782 , 3.8607 , 4.7182 , -0.0549611,0.169979,0.983914 -3.86983 , 4.02353 , 5.00379 , 0.731898,0.411399,0.543209 -3.74284 , 3.92125 , 5.01249 , -0.779416,0.520439,-0.34879 -3.63145 , 3.83707 , 5.03595 , 0.359549,0.277163,0.891014 -4.03196 , 4.33663 , 5.73436 , -0.749862,0.490589,0.443881 -3.61135 , 3.89829 , 5.3477 , -0.105268,-0.950919,-0.290983 -3.52269 , 3.83966 , 5.39987 , -0.0381575,-0.997835,-0.0535677 -3.25853 , 3.57065 , 5.18562 , 0.880746,-0.0381284,0.472052 -2.79512 , 3.05619 , 4.63411 , -0.87015,0.336753,-0.359774 -2.51815 , 2.75578 , 4.3342 , -0.597636,0.0875097,-0.796978 -2.48695 , 2.75364 , 4.42343 , -0.792035,-0.0170408,-0.610238 -2.45081 , 2.74392 , 4.50568 , -0.914157,-0.128969,-0.384296 -2.43641 , 2.76439 , 4.63279 , 0.775223,0.497111,0.389757 -2.39221 , 2.74672 , 4.70759 , 0.806346,0.0861641,0.585134 -2.26614 , 2.62198 , 4.61927 , -0.695375,-0.30278,-0.65175 -2.281 , 2.68336 , 4.81641 , -0.269074,-0.901835,0.338072 -2.2693 , 2.71155 , 4.9688 , -0.695444,-0.630563,0.344598 -2.3052 , 2.809 , 5.24344 , 0.200143,-0.462463,0.863754 -2.21754 , 2.73584 , 5.23689 , -0.251807,0.401021,0.880781 -2.12733 , 2.65891 , 5.21927 , -0.195,0.319728,0.927227 -2.04245 , 2.5861 , 5.2076 , 0.839249,-0.49699,-0.220594 -1.94613 , 2.49697 , 5.15929 , -0.902136,0.426884,0.0626107 -1.94961 , 2.55815 , 5.39767 , -0.936083,-0.285439,-0.205603 -2.13699 , 2.9226 , 6.24897 , -0.0810138,0.200401,0.976359 -2.0566 , 2.8669 , 6.28969 , 0.169649,0.129632,0.976942 -1.79279 , 2.49831 , 5.67169 , -0.34109,0.0392506,-0.939211 -1.75144 , 2.50106 , 5.81795 , 0.617539,-0.418537,0.665937 -1.63621 , 2.37373 , 5.67942 , -0.551085,0.591612,0.588473 -1.58867 , 2.36556 , 5.80621 , -0.715066,0.00835951,0.699007 -1.64377 , 2.56933 , 6.4391 , 0.613439,0.772665,-0.163345 -1.20536 , 1.7632 , 4.63767 , 0.233907,0.119141,0.964931 -1.14947 , 1.71949 , 4.6439 , 0.135156,0.304818,0.942772 -1.10446 , 1.69989 , 4.71353 , -0.0316233,0.387076,0.921506 -1.37552 , 2.47252 , 6.92871 , -0.919267,0.0104229,0.393496 -1.17646 , 2.10773 , 6.11249 , -0.524074,-0.448571,0.723968 -0.921008 , 1.52009 , 4.59009 , 0.352113,0.292485,0.889083 -0.867058 , 1.47658 , 4.58942 , 0.662962,0.103701,0.741436 -0.824169 , 1.46643 , 4.69192 , -0.840715,0.371777,0.393674 -0.764283 , 1.39868 , 4.61293 , 0.834261,0.265133,-0.483439 -0.774713 , 1.67321 , 5.68063 , 0.9971,0.0394542,-0.0650799 -0.652089 , 1.25944 , 4.42057 , -0.831077,0.541531,0.126714 -0.620271 , 1.37024 , 4.97259 , 0.794059,0.0487583,-0.605883 -0.563178 , 1.31598 , 4.9366 , -0.0496282,0.557105,0.828958 -0.508137 , 1.28833 , 5.00607 , 0.551272,0.771892,0.316673 -0.443367 , 1.40775 , 5.69709 , 0.293896,0.553673,0.779148 -0.377141 , 1.36511 , 5.7468 , 0.176253,-0.559004,0.810215 -0.305471 , 1.34171 , 5.88274 , 0.676278,-0.248954,0.693303 -0.241615 , 1.27661 , 5.83204 , 0.471714,-0.703713,0.531295 -0.171117 , 1.23103 , 5.87768 , 0.583632,-0.388245,0.71319 -0.0990504 , 1.18855 , 5.94142 , -0.655589,-0.754746,-0.0237171 -2.2242 , 1.11533 , -0.998444 , -0.0928427,0.157677,0.983117 -2.27464 , 1.15402 , -0.994792 , -0.104796,0.155168,0.982314 -2.33075 , 1.19645 , -0.996802 , -0.0515602,0.164345,0.985054 -2.39345 , 1.2425 , -1.00387 , 0.0823314,-0.167021,-0.98251 -2.45047 , 1.28654 , -1.00206 , -0.0401652,0.172027,0.984273 -2.53444 , 1.34499 , -1.02525 , -0.0432792,0.152821,0.987306 -2.59138 , 1.39095 , -1.01936 , -0.0860066,0.132106,0.987497 -2.66253 , 1.44377 , -1.02424 , -0.0809623,0.170244,0.982071 -2.7347 , 1.49787 , -1.02676 , -0.0186751,0.188827,0.981833 -2.82718 , 1.56461 , -1.04543 , -0.0220631,0.173632,0.984563 -2.90705 , 1.62503 , -1.04881 , -0.0643142,0.164451,0.984286 -2.99337 , 1.68956 , -1.0551 , -0.0459244,0.191627,0.980393 -3.09537 , 1.76417 , -1.07001 , -0.0317772,0.190578,0.981158 -3.19807 , 1.83943 , -1.081 , -0.0417259,0.180761,0.982642 -3.30072 , 1.91647 , -1.08849 , -0.0586522,0.173374,0.983108 -3.4109 , 1.99871 , -1.09742 , -0.0515951,0.173334,0.983511 -3.52978 , 2.08697 , -1.10746 , -0.120172,0.158564,0.980008 -3.65611 , 2.18061 , -1.11807 , 0.60556,-0.169711,-0.777493 -3.69285 , 2.22241 , -1.06516 , -0.94294,-0.0745809,0.324502 -3.69236 , 2.24084 , -0.987021 , 0.974691,0.114522,-0.191994 -3.69749 , 2.26315 , -0.913867 , 0.997083,0.0736879,0.0198912 -3.69464 , 2.27995 , -0.836259 , 0.983843,0.0691612,0.165133 -3.69039 , 2.29495 , -0.758863 , 0.993306,0.0884456,0.0742993 -3.67628 , 2.30472 , -0.677937 , 0.99822,0.0483573,-0.0349111 -3.6697 , 2.31801 , -0.601458 , 0.997766,0.0506275,0.0435913 -3.74661 , 2.38576 , -0.567962 , 0.988125,0.108167,0.109126 -3.64417 , 2.33651 , -0.446469 , 0.990424,0.0848228,0.108932 -3.65737 , 2.36232 , -0.38224 , -0.924647,-0.054098,0.376964 -3.67701 , 2.39224 , -0.320927 , -0.884561,-0.0241041,0.465801 -3.71978 , 2.4377 , -0.268493 , -0.815015,0.0147119,0.579253 -3.77771 , 2.49322 , -0.220389 , 0.67792,-0.0704439,-0.731753 -4.97048 , 3.48199 , 0.0845851 , -0.667033,-0.445576,-0.597101 -24.6683 , 17.9045 , -2.58866 , -0.0561847,-0.378556,0.923872 -26.7964 , 19.591 , -2.35196 , -0.0372566,-0.334099,0.941801 -26.7903 , 19.7228 , -1.79455 , 0.0486944,-0.561059,0.826342 -27.0567 , 20.0567 , -1.25968 , 0.0203197,-0.624408,0.780834 -29.4637 , 21.9985 , -0.851927 , 0.995885,0.0561752,0.0711217 -29.4439 , 22.1359 , -0.233265 , 0.994138,0.0634993,0.087513 -29.2168 , 22.1148 , 0.391876 , 0.992969,0.0827286,0.0846697 -29.2763 , 22.3112 , 1.0097 , 0.99787,0.0638192,0.0135448 -29.2461 , 22.4403 , 1.63141 , 0.998956,0.0217223,-0.0401966 -29.3184 , 22.6493 , 2.25957 , 0.999567,0.0193844,0.0221555 -29.3098 , 22.7969 , 2.88972 , 0.994833,0.0537767,0.0861161 -29.1416 , 22.8201 , 3.51027 , 0.994579,0.0598364,0.0850418 -29.0451 , 22.8991 , 4.13568 , 0.997258,0.0638437,0.0374206 -29.1022 , 23.101 , 4.7823 , 0.99904,0.0370751,-0.0233347 -29.1563 , 23.3032 , 5.43676 , 0.999803,0.0196667,0.00280056 -29.1237 , 23.4362 , 6.08455 , 0.99453,0.0589392,0.0862299 -29.0346 , 23.5251 , 6.72635 , 0.993185,0.0687043,0.0941453 -28.8683 , 23.5514 , 7.35375 , 0.997281,0.066882,0.0309392 -28.9275 , 23.7646 , 8.03664 , 0.997671,0.052621,-0.0433895 -29.0061 , 23.9952 , 8.73593 , 0.999922,0.011003,-0.00590101 -28.9904 , 24.1504 , 9.41985 , 0.99515,0.0475404,0.0861171 -28.8591 , 24.2107 , 10.0759 , 0.988728,0.0662371,0.134272 -28.6524 , 24.2073 , 10.7092 , -0.975593,-0.218559,-0.0212117 -13.8908 , 12.0946 , 7.38317 , -0.654926,-0.667433,0.354409 -4.34079 , 3.96304 , 4.02331 , 0.0813345,0.318453,0.944443 -4.1873 , 3.84849 , 4.0324 , 0.050344,0.382089,0.922753 -4.14668 , 3.84086 , 4.12947 , 0.0159719,0.570793,0.820938 -5.18997 , 4.98637 , 5.5488 , -0.103916,0.226432,0.968468 -4.08334 , 3.91495 , 4.62895 , -0.010818,0.138246,0.990339 -3.94827 , 3.81372 , 4.63815 , -0.0123104,0.322824,0.946379 -3.83183 , 3.72957 , 4.66081 , 0.0281445,0.230906,0.972569 -3.74328 , 3.67456 , 4.71033 , 0.0350192,0.345582,0.937735 -3.66594 , 3.62945 , 4.77026 , 0.70062,-0.61043,0.369469 -3.5617 , 3.55554 , 4.79604 , 0.688555,-0.338918,0.641114 -4.09409 , 4.16866 , 5.6321 , -0.869026,0.306882,0.388094 -3.68179 , 3.76437 , 5.27259 , 0.561901,0.82092,0.101774 -3.34154 , 3.43209 , 4.97651 , -0.705052,-0.579059,-0.409381 -2.75877 , 2.82002 , 4.29815 , -0.0132085,-0.758458,0.651588 -2.67337 , 2.75546 , 4.30534 , -0.0132087,-0.758459,0.651587 -2.61606 , 2.72379 , 4.35273 , 0.330868,-0.380845,0.863414 -2.59353 , 2.73214 , 4.4573 , 0.0481415,-0.980926,-0.188327 -2.50333 , 2.66184 , 4.45135 , 0.640238,0.567279,0.517967 -2.63494 , 2.85557 , 4.83338 , 0.238386,-0.757425,0.607848 -2.4263 , 2.64317 , 4.61387 , -0.696192,-0.367708,-0.616529 -2.38146 , 2.62641 , 4.6872 , -0.695375,-0.30278,-0.65175 -2.45108 , 2.75496 , 4.99505 , -0.450815,-0.780795,-0.43258 -2.4043 , 2.73966 , 5.07818 , -0.611811,-0.790585,-0.0257525 -2.38414 , 2.75946 , 5.22556 , 0.54263,0.749078,0.380046 -2.32218 , 2.72707 , 5.28418 , 0.619079,0.657275,0.429804 -2.60487 , 3.16522 , 6.18925 , -0.375577,0.64824,-0.662365 -2.21515 , 2.68566 , 5.44817 , 0.483927,0.859959,0.162126 -2.18092 , 2.69376 , 5.58821 , 0.0355701,0.988601,0.146295 -2.02191 , 2.52089 , 5.38043 , -0.967563,-0.250174,-0.035137 -2.0599 , 2.63881 , 5.74106 , 0.223223,-0.322037,-0.920035 -1.95051 , 2.53554 , 5.66475 , 0.0858817,0.122288,0.988772 -1.86914 , 2.47526 , 5.67209 , -0.0117043,-0.999429,0.0317141 -1.76429 , 2.37477 , 5.58923 , -0.348265,0.450878,0.82184 -1.78986 , 2.49294 , 5.99194 , -0.441018,-0.801212,0.404428 -1.62802 , 2.29139 , 5.67294 , -0.467085,0.444277,0.764493 -1.7344 , 2.57112 , 6.48512 , 0.613439,0.772665,-0.163345 -1.64988 , 2.51434 , 6.5157 , 0.613439,0.772665,-0.163345 -1.19649 , 1.70491 , 4.62982 , 0.311617,0.233374,0.921103 -1.1458 , 1.67678 , 4.67177 , 0.345217,0.334451,0.876908 -1.45512 , 2.47069 , 6.94914 , -0.919267,0.0104229,0.393496 -1.31509 , 2.28263 , 6.61988 , -0.947504,0.0717601,0.311586 -0.963933 , 1.51598 , 4.58609 , 0.449479,0.737027,0.504737 -0.898692 , 1.44313 , 4.4913 , -0.751751,0.257329,-0.607167 -0.864319 , 1.46317 , 4.67859 , 0.60213,-0.624154,-0.497866 -0.809745 , 1.42049 , 4.67614 , 0.648257,-0.117406,-0.752315 -0.751851 , 1.3632 , 4.62464 , -0.929188,0.126416,0.347318 -0.69063 , 1.28317 , 4.48479 , -0.818178,0.150113,0.555024 -0.646564 , 1.28975 , 4.65137 , -0.795527,0.586432,-0.152429 -0.601861 , 1.32672 , 4.94343 , 0.66744,-0.4021,-0.62677 -0.545304 , 1.28838 , 4.96463 , -0.266688,-0.787142,-0.556134 -0.485338 , 1.42397 , 5.70385 , -0.577289,-0.584424,-0.57025 -0.416145 , 1.40244 , 5.83153 , 0.775177,0.431531,-0.461391 -0.34849 , 1.34069 , 5.79243 , 0.490671,-0.582049,0.648429 -0.282385 , 1.2803 , 5.7516 , 0.582082,-0.428441,0.6911 -0.210614 , 1.24631 , 5.83637 , -0.530279,0.760731,-0.37429 -0.144245 , 1.18943 , 5.8122 , -0.580029,0.691528,-0.430529 -2.23345 , 1.05095 , -0.988665 , -0.0841788,0.149502,0.985172 -2.28349 , 1.08755 , -0.985493 , -0.0960094,0.137463,0.985843 -2.34714 , 1.13177 , -0.995159 , 0.0749825,-0.166347,-0.983212 -2.40584 , 1.17285 , -0.995539 , -0.0881287,0.16939,0.981601 -2.47015 , 1.21778 , -1.001 , -0.0252414,0.181937,0.982986 -2.53551 , 1.26393 , -1.00439 , -0.0208321,0.174273,0.984477 -2.60743 , 1.31381 , -1.01236 , -0.106956,0.166646,0.980199 -2.66673 , 1.35744 , -1.00474 , 0.10521,-0.145938,-0.983683 -2.74643 , 1.4134 , -1.01463 , -0.0333137,0.187657,0.98167 -2.83357 , 1.47315 , -1.0278 , -0.00986165,0.185719,0.982554 -2.92145 , 1.53336 , -1.03783 , -0.0685512,0.170886,0.982903 -3.00365 , 1.59158 , -1.03889 , -0.0594152,0.163597,0.984737 -3.09917 , 1.65831 , -1.0489 , -0.0474212,0.203108,0.978007 -3.20347 , 1.7308 , -1.0612 , -0.0310194,0.195227,0.980268 -3.30846 , 1.80392 , -1.06959 , -0.0617303,0.184327,0.980924 -3.40656 , 1.87433 , -1.06893 , -0.0617877,0.178925,0.981921 -3.53442 , 1.96213 , -1.08561 , -0.111324,0.169283,0.97926 -3.65655 , 2.04811 , -1.09264 , -0.583946,0.185521,0.790309 -3.70168 , 2.09184 , -1.0457 , -0.878997,0.0646631,0.472422 -3.70127 , 2.11005 , -0.968537 , 0.984601,-0.0476745,-0.16819 -3.78483 , 2.17564 , -0.942588 , 0.999084,0.0314196,-0.0290681 -3.70466 , 2.14848 , -0.819697 , 0.992507,0.0373143,0.116354 -3.70071 , 2.16424 , -0.743375 , 0.990322,0.135811,0.0285944 -3.69536 , 2.1782 , -0.667265 , 0.986698,0.157759,0.0392391 -3.68113 , 2.18666 , -0.587698 , 0.973449,0.216531,0.0742386 -3.6968 , 2.21377 , -0.524401 , 0.979002,0.201312,0.0320782 -3.66365 , 2.21043 , -0.438232 , 0.987512,0.155543,0.0250265 -3.66925 , 2.23129 , -0.371498 , 0.983263,0.0333826,-0.179108 -3.68972 , 2.25976 , -0.311131 , 0.896989,-0.00441015,-0.442032 -3.72567 , 2.29892 , -0.256653 , -0.758008,0.0573229,0.649721 -3.77683 , 2.34802 , -0.207087 , 0.610699,-0.0989418,-0.785657 -3.8844 , 2.43195 , -0.175475 , 0.524142,-0.0263972,-0.851222 -5.00826 , 3.30168 , 0.0812488 , 0.542338,0.346026,0.765595 -22.0638 , 15.0023 , -2.20251 , -0.0955529,0.200033,0.975119 -26.6296 , 18.247 , -2.34784 , -0.141579,-0.391808,0.909089 -29.4468 , 20.3267 , -2.11303 , 0.863848,0.463682,-0.196891 -29.4437 , 20.4689 , -1.5119 , -0.884626,-0.458489,0.0850057 -29.4147 , 20.594 , -0.907887 , -0.861782,-0.496184,0.105516 -29.3942 , 20.7244 , -0.303636 , -0.930781,-0.364546,-0.0274349 -29.3488 , 20.8371 , 0.302446 , -0.906039,-0.422712,-0.0202044 -29.3183 , 20.961 , 0.908966 , -0.88825,-0.458758,0.0235368 -29.2864 , 21.0845 , 1.51702 , -0.896972,-0.442037,0.00669909 -29.263 , 21.2148 , 2.12717 , -0.908013,-0.418478,0.0197134 -29.222 , 21.3319 , 2.73917 , -0.921805,-0.387653,0.000871639 -29.2032 , 21.4674 , 3.35494 , -0.903129,-0.429361,-0.00258058 -29.1604 , 21.5839 , 3.97218 , -0.87149,-0.489639,0.0275423 -29.1397 , 21.7193 , 4.59493 , -0.871127,-0.489083,0.0439988 -29.1014 , 21.8415 , 5.21964 , -0.893951,-0.446249,0.0413926 -29.0691 , 21.9706 , 5.84932 , -0.90324,-0.4283,0.0267725 -29.0433 , 22.1047 , 6.48515 , -0.894751,-0.445913,0.0241489 -29.0075 , 22.2324 , 7.12432 , -0.861362,-0.50627,0.0417913 -28.9689 , 22.3598 , 7.76851 , -0.847148,-0.525943,0.0756553 -28.9443 , 22.4994 , 8.42209 , -0.825785,-0.56377,-0.0155698 -28.901 , 22.6261 , 9.07761 , -0.858236,-0.512244,-0.0322021 -28.8619 , 22.7576 , 9.74138 , -0.87674,-0.47877,0.0458955 -28.8354 , 22.9011 , 10.4167 , -0.881689,-0.463207,0.089798 -28.7533 , 23.0014 , 11.0807 , -0.881689,-0.463207,0.089798 -14.5146 , 11.9008 , 7.44732 , -0.654926,-0.667433,0.354409 -4.45112 , 3.84421 , 4.00276 , 0.211165,0.346872,0.913832 -4.3842 , 3.81536 , 4.08261 , 0.207055,0.310775,0.927657 -4.20943 , 3.68752 , 4.07318 , 0.37015,0.707558,0.601956 -4.14291 , 3.65743 , 4.14759 , 0.467359,0.750422,0.467378 -4.19191 , 3.73546 , 4.32398 , -0.54216,-0.767258,-0.342605 -5.33493 , 4.84434 , 5.52363 , 0.189372,0.364307,0.911822 -4.24133 , 3.85051 , 4.65404 , -0.961261,-0.198996,-0.190731 -4.19676 , 3.84334 , 4.75872 , 0.313236,0.148281,0.938028 -4.04046 , 3.72869 , 4.74882 , -0.446789,0.167357,-0.878847 -3.96007 , 3.68633 , 4.81335 , -0.209294,0.376389,0.902512 -3.8731 , 3.63758 , 4.86958 , 0.228318,0.676029,0.700612 -3.59671 , 3.39855 , 4.69914 , 0.550649,0.256149,0.794464 -3.73195 , 3.57129 , 5.01465 , -0.873912,0.405673,-0.267783 -3.89879 , 3.78154 , 5.39178 , 0.666447,0.670879,0.325223 -3.42411 , 3.33087 , 4.93675 , -0.608485,-0.622333,-0.492389 -3.32958 , 3.26992 , 4.96568 , 0.243711,0.565411,0.787982 -2.7487 , 2.69018 , 4.28838 , 0.334412,-0.142298,0.931622 -2.77666 , 2.75238 , 4.46462 , -0.740258,-0.572507,-0.352498 -3.0628 , 3.10091 , 5.05819 , -0.145846,0.662127,0.735063 -2.67169 , 2.70764 , 4.58964 , -0.153579,0.697883,0.699552 -2.61435 , 2.67939 , 4.64334 , 0.238623,0.446176,0.862547 -2.50022 , 2.58568 , 4.59731 , 0.137823,0.7519,0.64471 -2.42205 , 2.53282 , 4.60877 , 0.302735,0.792476,0.529464 -2.6381 , 2.82758 , 5.1887 , 0.632874,-0.232127,0.738639 -2.50914 , 2.7174 , 5.1164 , -0.191474,-0.976338,0.100507 -2.41755 , 2.65086 , 5.11176 , -0.14404,-0.981842,0.123443 -2.73212 , 3.09135 , 6.00542 , -0.43357,0.482382,-0.761134 -2.6492 , 3.04347 , 6.05549 , -0.433571,0.482382,-0.761134 -2.28217 , 2.62458 , 5.406 , -0.898025,-0.392025,-0.199667 -2.47091 , 2.93009 , 6.11664 , 0.383975,-0.655947,0.649844 -2.20976 , 2.63687 , 5.67773 , 0.313975,-0.819342,-0.479686 -2.12828 , 2.58358 , 5.69839 , 0.0746726,0.00482674,0.997196 -1.99027 , 2.44711 , 5.54429 , -0.19032,-0.929672,-0.315419 -1.96081 , 2.46708 , 5.71685 , 0.221454,0.975034,0.0163362 -1.86203 , 2.38617 , 5.66979 , -0.231297,0.96634,-0.112644 -1.8079 , 2.3712 , 5.77111 , 0.118396,-0.691867,0.712251 -1.70499 , 2.27755 , 5.69311 , -0.12869,0.489683,0.862351 -1.61329 , 2.20152 , 5.64763 , -0.926538,-0.343219,0.154042 -1.72652 , 2.48769 , 6.49906 , -0.579727,-0.801953,0.144179 -1.24403 , 1.68814 , 4.61588 , 0.381581,0.232899,0.894513 -1.18938 , 1.65509 , 4.63952 , -0.398486,-0.346917,-0.849033 -1.52962 , 2.44797 , 6.92354 , 0.86466,0.493724,-0.0927354 -1.38878 , 2.27739 , 6.632 , 0.971153,-0.23668,-0.0290496 -0.983665 , 1.45217 , 4.41346 , 0.896922,0.441793,0.0187019 -0.954806 , 1.4791 , 4.61019 , -0.134244,0.457028,0.879263 -0.893507 , 1.42125 , 4.55188 , -0.629906,0.00784378,0.776632 -0.856717 , 1.43983 , 4.73941 , 0.136954,-0.936012,-0.32423 -0.785609 , 1.34649 , 4.56411 , 0.0628638,-0.281543,0.957487 -0.730675 , 1.2984 , 4.53008 , 0.690942,-0.461828,-0.55616 -0.66826 , 1.20837 , 4.34059 , -0.350428,0.58692,0.72988 -0.635468 , 1.29912 , 4.81505 , -0.784892,-0.145993,-0.602188 -0.582021 , 1.28647 , 4.92329 , 0.0496282,-0.557105,-0.828958 -0.524307 , 1.2736 , 5.04052 , -0.53408,-0.7924,-0.29472 -0.45953 , 1.38593 , 5.7024 , -0.619938,-0.492742,-0.610641 -0.393477 , 1.31782 , 5.61428 , 0.832611,-0.552238,0.0423311 -0.320569 , 1.30483 , 5.77872 , 0.475897,-0.508391,0.717677 -0.246558 , 1.27658 , 5.8834 , 0.570473,-0.73856,0.35929 -0.176492 , 1.22274 , 5.86947 , 0.72514,-0.688593,0.00352561 -0.100524 , 1.18619 , 5.94196 , -0.655589,-0.754746,-0.0237171 -2.28987 , 1.02374 , -0.976465 , -0.0865226,0.132107,0.987452 -2.3483 , 1.06227 , -0.979272 , -0.0867664,0.141052,0.986193 -2.40107 , 1.09877 , -0.973305 , 0.1151,-0.179999,-0.97691 -2.46597 , 1.1413 , -0.979514 , 0.0766293,-0.210375,-0.974613 -2.53963 , 1.18803 , -0.990441 , -0.0560967,0.187564,0.980649 -2.61212 , 1.23556 , -0.998959 , -0.112964,0.186733,0.975894 -2.67991 , 1.28084 , -0.998584 , -0.098122,0.17336,0.979958 -2.74658 , 1.32681 , -0.99619 , -0.0706351,0.18354,0.980471 -2.83627 , 1.38366 , -1.01016 , -0.00354551,0.196032,0.980591 -2.92572 , 1.4412 , -1.02101 , -0.0564694,0.184406,0.981227 -3.00853 , 1.49696 , -1.02312 , -0.0750927,0.189621,0.978982 -3.09875 , 1.5566 , -1.02802 , -0.071577,0.193385,0.978509 -3.19755 , 1.62094 , -1.0355 , -0.0440058,0.225378,0.973277 -3.31177 , 1.69455 , -1.05081 , -0.0635396,0.193874,0.978967 -3.41906 , 1.76552 , -1.05668 , -0.0631856,0.179441,0.981737 -3.53388 , 1.84169 , -1.064 , -0.114108,0.16635,0.979442 -3.65034 , 1.91835 , -1.06698 , 0.550314,-0.210089,-0.808095 -3.71287 , 1.96911 , -1.03123 , 0.960928,0.0288664,-0.275289 -3.70498 , 1.98367 , -0.950203 , 0.987773,0.0422505,-0.150067 -3.71099 , 2.00433 , -0.878871 , 0.995568,0.084895,-0.0404579 -3.70828 , 2.02071 , -0.803111 , 0.990847,0.108866,-0.0798096 -3.71312 , 2.04055 , -0.732092 , 0.998329,0.0540412,-0.0204572 -3.74747 , 2.07688 , -0.678018 , 0.994385,0.098917,0.0376016 -3.7016 , 2.06819 , -0.582133 , 0.99608,0.0482135,-0.0741598 -3.68529 , 2.07585 , -0.503875 , 0.991133,0.127215,0.0383609 -3.74222 , 2.12441 , -0.460132 , -0.953896,-0.296082,-0.0491799 -3.65913 , 2.09356 , -0.353481 , 0.997867,0.0366661,-0.0540024 -3.69699 , 2.13073 , -0.301288 , -0.906947,0.0646228,0.416259 -3.7175 , 2.15906 , -0.241505 , -0.804482,0.075829,0.589117 -3.76165 , 2.2008 , -0.190183 , 0.678171,-0.114831,-0.725878 -3.87089 , 2.28177 , -0.160756 , 0.518959,-0.148007,-0.841888 -5.02018 , 3.11382 , 0.0814967 , -0.171147,-0.0445633,0.984237 -14.5918 , 9.15342 , -1.65941 , -0.0733668,0.183195,0.980335 -18.6368 , 11.7837 , -2.06528 , 0.108699,-0.185765,-0.976563 -30.0348 , 19.4312 , -2.21627 , 0.759362,0.610107,-0.226139 -30.2707 , 19.7274 , -1.6364 , 0.759362,0.610107,-0.226139 -30.2641 , 19.8665 , -1.02897 , 0.684373,0.70526,-0.185044 -30.2317 , 19.9885 , -0.418967 , 0.635147,0.759716,-0.139354 -30.1982 , 20.1107 , 0.191309 , 0.627642,0.765872,-0.139659 -30.2059 , 20.2607 , 0.802284 , 0.618422,0.773458,-0.138986 -30.1792 , 20.3872 , 1.4159 , 0.605335,0.78156,-0.150775 -30.1514 , 20.5143 , 2.03114 , 0.594421,0.789643,-0.152075 -30.1547 , 20.663 , 2.65052 , 0.585472,0.796778,-0.149558 -30.125 , 20.7896 , 3.27129 , 0.574816,0.805295,-0.145212 -30.1013 , 20.9218 , 3.89567 , 0.562677,0.813652,-0.146169 -30.0771 , 21.0538 , 4.52354 , 0.555553,0.818089,-0.148633 -30.0671 , 21.1972 , 5.15751 , 0.545855,0.82376,-0.153175 -30.047 , 21.3344 , 5.795 , 0.542807,0.826857,-0.147203 -30.0242 , 21.4712 , 6.43723 , 0.530963,0.834103,-0.149502 -29.9757 , 21.5902 , 7.0797 , 0.520119,0.839597,-0.156696 -29.9815 , 21.7496 , 7.73917 , 0.510049,0.845371,-0.158737 -29.9752 , 21.9037 , 8.4034 , 0.500247,0.851197,-0.158797 -29.943 , 22.039 , 9.06846 , 0.483168,0.860653,-0.160701 -29.9077 , 22.1734 , 9.73981 , 0.465449,0.871442,-0.154748 -29.9157 , 22.3423 , 10.4323 , 0.741155,0.665466,-0.088567 -29.8806 , 22.4821 , 11.1203 , 0.796659,0.587198,-0.143295 -4.47601 , 3.68637 , 4.05177 , -0.426198,-0.531715,-0.73187 -4.36197 , 3.61934 , 4.09398 , -0.0133014,0.709547,0.704533 -4.31402 , 3.60818 , 4.18554 , -0.2491,-0.899469,-0.359032 -4.36467 , 3.68498 , 4.36305 , 0.72221,0.371439,0.583478 -4.2307 , 3.59937 , 4.383 , 0.748607,0.203257,0.63109 -4.16576 , 3.5739 , 4.46131 , 0.537536,0.146129,0.830483 -4.11758 , 3.56344 , 4.55598 , 0.809654,-0.155985,0.5658 -4.00241 , 3.49274 , 4.58414 , -0.66935,0.393883,-0.629942 -3.97562 , 3.50251 , 4.70061 , -0.822227,-0.000790361,-0.56916 -3.76418 , 3.34009 , 4.61741 , -0.218379,0.789146,0.574073 -3.68556 , 3.30071 , 4.67307 , 0.258646,0.609932,0.749056 -3.63462 , 3.28713 , 4.75951 , -0.145448,-0.872895,-0.465724 -3.56029 , 3.2506 , 4.81886 , -0.16009,-0.961405,-0.223766 -3.62289 , 3.34764 , 5.05252 , -0.828841,-0.357091,0.430708 -3.54521 , 3.30977 , 5.11151 , 0.607492,0.741213,-0.285582 -2.84758 , 2.64841 , 4.30652 , -0.740258,-0.572507,-0.352497 -2.7488 , 2.57963 , 4.29763 , 0.334412,-0.142298,0.931622 -3.22618 , 3.10575 , 5.1552 , 0.316292,0.0893059,0.944449 -3.56528 , 3.50013 , 5.86087 , -0.188257,0.659119,0.728094 -2.66601 , 2.59328 , 4.58883 , 0.492038,-0.595001,-0.63551 -2.58915 , 2.54746 , 4.61051 , -0.0931429,0.413452,0.905749 -2.53527 , 2.52358 , 4.66915 , -0.0675481,0.251486,0.965501 -2.618 , 2.65449 , 4.98371 , -0.975432,-0.00625754,-0.220212 -2.96744 , 3.09258 , 5.84156 , 0.421164,-0.693319,0.584747 -3.01478 , 3.20016 , 6.15845 , 0.140458,-0.851892,0.504531 -3.07567 , 3.32914 , 6.52887 , -0.352464,0.818236,-0.454158 -2.67629 , 2.90937 , 5.89732 , 0.479234,-0.429759,0.765273 -2.36805 , 2.58806 , 5.41366 , -0.773489,-0.126612,-0.621035 -2.38659 , 2.66275 , 5.6794 , -0.369959,-0.882969,-0.288955 -2.3291 , 2.64543 , 5.77041 , -0.22548,0.0719179,0.97159 -2.22782 , 2.5727 , 5.74969 , -0.0490516,-0.0849667,0.995176 -2.0843 , 2.43993 , 5.59671 , -0.479888,-0.277811,0.832183 -1.99247 , 2.37367 , 5.5779 , -0.317762,-0.824574,-0.468086 -1.96675 , 2.40153 , 5.76766 , 0.191683,0.973174,0.127242 -2.00648 , 2.5293 , 6.19815 , -0.939044,-0.3404,0.0482146 -1.70487 , 2.14641 , 5.43563 , 0.828278,0.546247,-0.124778 -1.64826 , 2.12641 , 5.51477 , 0.887191,0.4609,0.0215225 -1.78804 , 2.43669 , 6.428 , -0.503221,-0.764145,-0.403548 -1.29308 , 1.67392 , 4.61102 , 0.26586,0.220086,0.938552 -1.23593 , 1.63859 , 4.62574 , -0.367095,-0.301434,-0.879988 -1.18721 , 1.61996 , 4.68543 , -0.474107,-0.348634,-0.808503 -1.54231 , 2.43299 , 7.1097 , 0.682746,0.649356,-0.334955 -1.01785 , 1.429 , 4.36286 , -0.824053,-0.560882,-0.0796797 -0.995301 , 1.46752 , 4.58756 , -0.813515,-0.569538,0.117556 -0.950813 , 1.45905 , 4.68103 , -0.280648,-0.912062,-0.298964 -0.902989 , 1.44919 , 4.77395 , -0.0696483,0.913021,0.401923 -0.834502 , 1.37757 , 4.66599 , -0.790215,0.103053,0.604104 -0.770261 , 1.31063 , 4.56542 , -0.339193,0.40603,-0.84858 -0.723661 , 1.30689 , 4.68428 , -0.903772,0.398837,-0.155324 -0.672269 , 1.29302 , 4.77384 , -0.31988,0.924254,-0.208403 -0.617062 , 1.2677 , 4.82396 , -0.679614,-0.701308,-0.215158 -0.561239 , 1.26559 , 4.97004 , 0.315706,0.801055,0.508567 -0.502479 , 1.39585 , 5.6901 , 0.472851,0.645934,0.599318 -0.43108 , 1.37073 , 5.78769 , -0.0161097,-0.614531,0.788728 -0.362162 , 1.31025 , 5.72786 , 0.350126,-0.0664431,0.934343 -0.291691 , 1.26809 , 5.75454 , 0.582082,-0.428441,0.6911 -0.218903 , 1.23024 , 5.79919 , -0.653344,0.510046,-0.559459 -0.146461 , 1.18694 , 5.8231 , -0.6495,0.658715,-0.379795 -2.35424 , 0.996441 , -0.970335 , -0.115313,0.102805,0.987995 -2.41311 , 1.03305 , -0.971751 , 0.123447,-0.160779,-0.97924 -2.46654 , 1.06858 , -0.964591 , -0.0875798,0.187089,0.978431 -2.54078 , 1.11294 , -0.97617 , -0.0440196,0.213871,0.97587 -2.60812 , 1.15459 , -0.978608 , -0.0941691,0.189782,0.9773 -2.67003 , 1.19515 , -0.972568 , -0.0876287,0.211196,0.973508 -2.7524 , 1.24391 , -0.98361 , -0.0841741,0.176598,0.980677 -2.82834 , 1.29186 , -0.985906 , -0.0394096,0.196136,0.979784 -2.9194 , 1.34668 , -0.997876 , -0.0541925,0.201626,0.977962 -3.00355 , 1.3988 , -1.0007 , -0.0848293,0.198718,0.976379 -3.09537 , 1.4557 , -1.00682 , -0.0846196,0.192052,0.97773 -3.18792 , 1.5131 , -1.0096 , -0.0641926,0.202372,0.977202 -3.29592 , 1.57966 , -1.0207 , -0.0421425,0.215089,0.975685 -3.40437 , 1.64592 , -1.02768 , -0.0535221,0.209433,0.976357 -3.52157 , 1.71806 , -1.03637 , -0.0909056,0.164967,0.982101 -3.63942 , 1.7909 , -1.04086 , 0.452703,-0.197291,-0.869561 -3.71893 , 1.84668 , -1.01639 , -0.941094,0.0274275,0.337031 -3.70353 , 1.85764 , -0.931303 , 0.982651,-0.023305,-0.183994 -3.74996 , 1.89789 , -0.884409 , 0.99624,0.0604554,-0.0620609 -3.72422 , 1.90177 , -0.795106 , 0.99759,0.0673475,-0.0167024 -3.72136 , 1.91694 , -0.720316 , 0.998432,0.00782361,0.0554327 -3.71636 , 1.9315 , -0.64596 , 0.993762,-0.0133186,0.110724 -3.70246 , 1.94063 , -0.567855 , 0.999954,-0.00574641,-0.00766836 -3.69513 , 1.95345 , -0.494514 , 0.999541,0.0267632,0.0142282 -3.76881 , 2.00766 , -0.459227 , 0.993503,0.0718963,0.0882214 -3.67677 , 1.97552 , -0.349252 , 0.995228,0.0569647,0.0792185 -3.69935 , 2.003 , -0.291075 , -0.871616,0.010266,0.490081 -3.71205 , 2.02534 , -0.228979 , -0.872212,0.000320578,0.489128 -3.76591 , 2.07107 , -0.182256 , -0.732986,0.0337801,0.679405 -3.84403 , 2.12937 , -0.142217 , 0.458938,-0.114353,-0.881079 -3.98021 , 2.22131 , -0.118915 , -0.318321,0.12176,0.940131 -5.06881 , 2.95197 , 0.0736711 , -0.171147,-0.0445632,0.984237 -14.2467 , 8.35771 , -1.59124 , -0.0693754,0.180813,0.981068 -22.2599 , 13.3618 , -1.82131 , -0.127518,0.204883,0.970444 -30.5493 , 18.4791 , -2.31104 , -0.0927642,-0.752165,0.652414 -32.5492 , 19.8385 , -1.89387 , 0.100149,-0.923311,0.370767 -32.521 , 19.9705 , -1.25076 , -0.0612395,0.974791,-0.214553 -32.5085 , 20.1121 , -0.608246 , -0.0649965,0.975994,-0.207872 -32.4863 , 20.248 , 0.0357534 , -0.0678861,0.97575,-0.208097 -32.4625 , 20.3825 , 0.681194 , -0.0662204,0.975834,-0.208237 -32.4283 , 20.5124 , 1.32771 , 0.0648585,-0.975928,0.208223 -32.4103 , 20.6515 , 1.97666 , 0.0498102,-0.975728,0.213245 -32.3909 , 20.7903 , 2.62802 , -0.0641003,0.974554,-0.214791 -32.3858 , 20.94 , 3.28322 , -0.0634341,0.974468,-0.21538 -32.3876 , 21.0954 , 3.94303 , -0.0650831,0.974771,-0.213508 -32.3624 , 21.2325 , 4.60482 , 0.0316371,-0.977104,0.210396 -32.3431 , 21.3755 , 5.27128 , -0.0389255,0.977008,-0.209618 -32.3044 , 21.5069 , 5.93965 , -0.0402764,0.975612,-0.215776 -32.3138 , 21.671 , 6.62064 , 0.0691023,-0.974501,0.21348 -32.2779 , 21.8071 , 7.29986 , 0.0330254,-0.978141,0.205306 -32.2969 , 21.9816 , 7.99651 , 0.00446176,-0.978017,0.208477 -32.2561 , 22.116 , 8.68726 , 0.00183751,-0.977322,0.211753 -32.2196 , 22.2552 , 9.38558 , 0.0174851,-0.977262,0.211313 -32.1955 , 22.405 , 10.0944 , 0.033831,-0.977991,0.205889 -32.1837 , 22.5658 , 10.8151 , -0.0338309,0.977991,-0.205889 -4.4795 , 3.54449 , 4.21811 , -0.649603,-0.579612,-0.492002 -4.36932 , 3.4862 , 4.26141 , -0.556784,-0.614976,-0.558387 -4.33724 , 3.49007 , 4.36844 , 0.496509,0.3106,0.810559 -4.22718 , 3.42975 , 4.40716 , -0.589388,0.0563056,-0.805886 -4.17419 , 3.41694 , 4.49492 , 0.606794,-0.134911,0.783326 -4.05124 , 3.34469 , 4.51647 , -0.680659,0.418845,-0.601059 -4.08648 , 3.40722 , 4.69287 , -0.600362,0.787673,0.138334 -4.16312 , 3.50935 , 4.9222 , -0.720433,-0.210943,0.660666 -3.89962 , 3.31135 , 4.78766 , 0.245002,-0.822472,-0.513336 -3.82902 , 3.28339 , 4.85728 , 0.208156,-0.890476,-0.404629 -3.70726 , 3.20919 , 4.86579 , -0.0992448,0.914388,0.392485 -3.62571 , 3.16882 , 4.91827 , -0.414034,-0.907299,-0.0733818 -3.92091 , 3.48047 , 5.45629 , 0.512647,0.361413,-0.778828 -3.67909 , 3.29469 , 5.31032 , 0.691196,-0.712126,0.122978 -3.43396 , 3.09975 , 5.1415 , -0.311353,0.88845,0.337219 -3.34454 , 3.05316 , 5.1799 , 0.124915,0.515952,0.84746 -4.41184 , 4.14372 , 6.97103 , 0.499456,-0.35831,0.78877 -3.55312 , 3.34358 , 5.86171 , -0.466058,0.84605,-0.258823 -3.34426 , 3.17914 , 5.72118 , -0.593569,0.656342,-0.465716 -2.62349 , 2.48253 , 4.68304 , -0.4134,0.360134,0.836304 -2.55849 , 2.45071 , 4.72557 , -0.474094,0.242895,0.846308 -3.00632 , 2.96693 , 5.72811 , -0.461456,0.490365,-0.739324 -3.7248 , 3.79667 , 7.34463 , -0.683376,0.348223,-0.641668 -2.82033 , 2.86134 , 5.78209 , -0.446971,0.419518,-0.790078 -2.77695 , 2.86433 , 5.91191 , -0.479234,0.429759,-0.765273 -2.66046 , 2.7846 , 5.88485 , 0.170878,-0.726255,0.665849 -2.33662 , 2.45885 , 5.36115 , -0.654807,0.207562,-0.726736 -2.28659 , 2.45023 , 5.45743 , -0.901934,0.0481926,-0.429176 -2.32348 , 2.54875 , 5.78401 , -0.281436,-0.0144975,0.959471 -2.17742 , 2.42385 , 5.64058 , 0.481516,-0.062207,-0.874227 -2.12124 , 2.41024 , 5.73588 , -0.200821,-0.834064,-0.513818 -2.07253 , 2.40747 , 5.85684 , 0.543046,0.782849,0.303726 -2.06524 , 2.46661 , 6.12828 , 0.560054,0.826681,-0.0541968 -2.0125 , 2.46561 , 6.26818 , -0.418508,-0.781541,-0.46265 -1.70317 , 2.08513 , 5.47257 , 0.887191,0.460899,0.021523 -1.70405 , 2.15844 , 5.78655 , 0.604666,-0.643952,0.468728 -2.00662 , 2.73142 , 7.42637 , 0.690571,-0.665928,0.282228 -1.28449 , 1.62252 , 4.62148 , 0.334174,0.25458,0.907478 -1.23008 , 1.59539 , 4.65367 , -0.451401,-0.319928,-0.832996 -1.59779 , 2.36969 , 6.98227 , 0.267141,0.206315,0.941313 -1.39333 , 2.09419 , 6.35198 , -0.876619,-0.335589,0.344846 -1.26884 , 1.9588 , 6.10778 , 0.810078,0.423761,-0.405217 -1.00134 , 1.47018 , 4.73429 , -0.248513,-0.964069,-0.0938684 -0.965922 , 1.49671 , 4.94151 , 0.938348,0.279388,-0.203582 -0.861973 , 1.33707 , 4.53904 , -0.0115479,-0.0303621,0.999472 -0.834278 , 1.39165 , 4.85018 , -0.857501,0.293608,0.422476 -0.751764 , 1.26737 , 4.53742 , 0.879611,0.0776019,-0.46932 -0.701547 , 1.25326 , 4.61714 , -0.49954,0.695636,-0.516285 -0.64628 , 1.21891 , 4.61852 , -0.433639,0.545557,-0.717164 -0.588165 , 1.15762 , 4.51199 , -0.318372,0.935573,-0.152783 -0.53999 , 1.24884 , 5.03618 , -0.424825,-0.835985,-0.347351 -0.474969 , 1.3663 , 5.71744 , 0.38768,0.658198,0.645353 -0.405015 , 1.30413 , 5.63807 , -0.902379,0.345686,0.257319 -0.332058 , 1.27995 , 5.73328 , -0.175901,-0.206752,-0.962451 -0.258715 , 1.24439 , 5.7782 , -0.56643,0.726332,-0.389358 -0.178739 , 1.22227 , 5.90027 , 0.481542,-0.474556,0.736826 --0.0238356 , 1.4629 , 7.48234 , -0.211292,-0.907431,0.363214 -2.4104 , 0.964405 , -0.956347 , -0.131008,0.138826,0.981613 -2.4644 , 0.997599 , -0.949644 , 0.126751,-0.135438,-0.982645 -2.53249 , 1.03637 , -0.954972 , -0.0691849,0.196298,0.978101 -2.60066 , 1.07657 , -0.958356 , -0.0574678,0.19046,0.980011 -2.67732 , 1.12008 , -0.966068 , -0.0806559,0.170535,0.982045 -2.74612 , 1.16107 , -0.964857 , -0.081131,0.182313,0.979888 -2.82339 , 1.20544 , -0.967681 , -0.0303853,0.183762,0.982501 -2.91603 , 1.25757 , -0.980571 , -0.0220811,0.209319,0.977598 -3.00821 , 1.30944 , -0.990248 , -0.0748,0.182153,0.980421 -3.0873 , 1.35708 , -0.985248 , -0.0770199,0.179217,0.98079 -3.18144 , 1.41175 , -0.989143 , -0.0575211,0.186452,0.980779 -3.28297 , 1.47039 , -0.995541 , -0.0349316,0.197656,0.979649 -3.40161 , 1.53693 , -1.00923 , -0.0439503,0.203554,0.978077 -3.52019 , 1.60532 , -1.01914 , -0.0740376,0.188508,0.979277 -3.63943 , 1.67442 , -1.02483 , -0.363463,0.177891,0.914467 -3.72809 , 1.73088 , -1.00641 , -0.906066,-0.0742034,0.416579 -3.72126 , 1.74494 , -0.926526 , -0.939446,-0.0636195,0.336739 -3.72081 , 1.76156 , -0.851987 , 0.996799,0.0683643,-0.0414537 -3.73547 , 1.78508 , -0.786928 , 0.997727,0.0459219,0.0493233 -3.73169 , 1.80033 , -0.712843 , 0.998403,0.0440007,0.0354227 -3.71147 , 1.80666 , -0.630464 , 0.987082,0.144231,0.0697616 -3.70537 , 1.82015 , -0.557491 , 0.985668,0.158893,0.056669 -3.69907 , 1.83258 , -0.484807 , 0.961307,0.235882,0.142297 -3.73261 , 1.86471 , -0.431694 , 0.988946,-0.0345912,0.144186 -3.67262 , 1.85179 , -0.337653 , 0.999406,0.0336963,0.00726786 -3.69604 , 1.8778 , -0.28052 , 0.964123,0.00814706,-0.26533 -3.7261 , 1.90893 , -0.226208 , -0.854943,0.0200044,0.518336 -3.7729 , 1.94746 , -0.177048 , 0.712581,-0.034998,-0.700717 -3.83561 , 1.99482 , -0.132191 , 0.561494,-0.099058,-0.821531 -3.94072 , 2.06394 , -0.0989579 , -0.352099,0.126436,0.927384 -5.08425 , 2.77842 , 0.0711535 , -0.989275,-0.143331,-0.0281132 -13.4407 , 7.36495 , -1.43798 , -0.0615174,0.181164,0.981527 -15.3049 , 8.45091 , -1.50375 , -0.0733668,0.183195,0.980335 -18.8397 , 10.4809 , -1.75057 , -0.129607,0.195709,0.97206 -22.3711 , 12.5405 , -1.85839 , -0.121965,0.205126,0.971107 -25.3593 , 14.3254 , -1.76627 , -0.47351,0.39034,0.789572 -34.9327 , 20.0391 , -1.49353 , -0.00444475,-0.965021,0.262135 -34.9585 , 20.2098 , -0.817007 , -0.00444475,-0.965021,0.262135 -34.9564 , 20.364 , -0.136778 , -0.0762419,-0.987216,0.139968 -34.9271 , 20.5033 , 0.545693 , -0.165989,-0.981232,0.0981428 -34.8345 , 20.6049 , 1.2291 , 0.10561,0.992066,-0.068211 -34.7317 , 20.7015 , 1.91125 , -0.136925,-0.990135,0.0297411 -34.9446 , 20.9864 , 2.60715 , -0.125206,-0.972489,0.196439 -39.233 , 23.9217 , 4.3683 , -0.382941,0.886822,-0.258655 -34.6693 , 21.2971 , 4.67339 , -0.149267,-0.968664,0.198517 -34.5399 , 21.3779 , 5.35936 , -0.0943597,-0.981682,0.165518 -39.4758 , 24.6199 , 6.7937 , -0.47987,0.859353,-0.176741 -39.0177 , 24.5185 , 7.53118 , -0.37366,0.924969,0.0693568 -34.3491 , 21.9112 , 8.17937 , -0.171114,-0.974814,0.143028 -34.3386 , 22.0718 , 8.90563 , -0.186708,-0.964512,0.186698 -5.81271 , 4.3734 , 5.15658 , 0.0392283,-0.482494,0.875021 -5.59666 , 4.24621 , 5.15666 , 0.331376,-0.492287,0.804887 -4.4858 , 3.41515 , 4.39252 , 0.331483,0.521662,0.786122 -4.37316 , 3.35784 , 4.43253 , 0.132457,0.23752,0.962309 -4.17264 , 3.22913 , 4.38807 , 0.26317,-0.29573,0.918306 -3.98083 , 3.10636 , 4.3422 , -0.251812,0.250559,-0.934779 -3.90439 , 3.07309 , 4.39953 , -0.251812,0.250559,-0.934778 -4.18326 , 3.33416 , 4.82111 , -0.554802,-0.16635,0.815183 -4.24677 , 3.42281 , 5.0407 , -0.639006,-0.767132,0.0563933 -4.03134 , 3.27678 , 4.9608 , 0.383256,-0.914288,-0.131122 -4.14573 , 3.41021 , 5.2494 , 0.211687,0.965048,-0.154504 -3.82578 , 3.17257 , 5.03357 , -0.2312,0.941017,-0.247049 -3.66954 , 3.0714 , 4.9975 , 0.142257,0.918755,0.368311 -4.65741 , 3.98555 , 6.44101 , 0.102934,-0.961476,0.254888 -4.33414 , 3.7448 , 6.22142 , -0.824565,0.204644,-0.52746 -4.29588 , 3.75862 , 6.37919 , -0.651362,0.699717,-0.293467 -4.40511 , 3.90981 , 6.75734 , 0.499456,-0.35831,0.78877 -3.76708 , 3.36439 , 6.02014 , 0.0580998,0.749232,0.659754 -3.40713 , 3.06821 , 5.65666 , 0.659221,-0.593003,0.462359 -2.59926 , 2.32938 , 4.51353 , 0.56037,0.102841,0.821833 -2.5904 , 2.35502 , 4.64687 , 0.986941,-0.126651,-0.0995355 -2.53442 , 2.33431 , 4.70309 , -0.958629,0.277715,0.0624805 -3.92823 , 3.79535 , 7.49021 , -0.683376,0.348223,-0.641668 -2.98529 , 2.88058 , 5.9251 , 0.356183,-0.68296,0.63773 -2.43639 , 2.34982 , 5.02049 , 0.462743,-0.734923,0.49574 -2.47004 , 2.4291 , 5.28087 , -0.618415,0.278033,-0.735024 -2.37068 , 2.36556 , 5.2611 , -0.733902,0.232444,-0.638246 -2.28656 , 2.31834 , 5.27238 , -0.731358,-0.283771,-0.620153 -2.26452 , 2.34277 , 5.43482 , 0.979706,0.0469779,0.194858 -2.28145 , 2.41567 , 5.71031 , 0.024317,-0.217193,0.975826 -2.18603 , 2.35775 , 5.7021 , 0.129758,-0.623919,-0.770641 -2.09765 , 2.30755 , 5.70911 , -0.20438,-0.242394,-0.948406 -2.0933 , 2.36491 , 5.97038 , -0.217732,-0.852594,0.475053 -1.84286 , 2.09726 , 5.44971 , -0.36569,-0.370345,0.853883 -2.00284 , 2.38485 , 6.29289 , -0.418508,-0.781541,-0.46265 -1.92939 , 2.36174 , 6.37744 , 0.390045,0.778507,0.491723 -2.13453 , 2.75834 , 7.58236 , 0.690571,-0.665928,0.282228 -1.33163 , 1.60469 , 4.6172 , 0.20962,0.103609,0.972278 -1.27228 , 1.57289 , 4.63106 , 0.411129,0.207819,0.887572 -1.80344 , 2.57503 , 7.63548 , -0.569855,0.817342,-0.0849559 -1.64234 , 2.41808 , 7.36515 , 0.911483,0.199131,-0.359924 -1.32859 , 1.94103 , 6.09353 , -0.84577,-0.398631,0.354637 -1.02402 , 1.41664 , 4.58937 , 0.815004,0.0893128,0.572531 -0.985156 , 1.42791 , 4.73914 , 0.733032,-0.06577,0.677007 -0.905577 , 1.34407 , 4.57421 , 0.226773,0.0858066,-0.970161 -0.847328 , 1.30619 , 4.56013 , -0.0690494,0.000903478,0.997613 -0.802352 , 1.31131 , 4.6983 , -0.25908,0.332833,0.906697 -0.746479 , 1.28757 , 4.74 , -0.181082,-0.982178,-0.0503646 -0.677981 , 1.20087 , 4.53903 , 0.261798,-0.858269,0.441403 -0.622259 , 1.16138 , 4.51008 , -0.252433,0.951502,-0.175846 -0.569079 , 1.15248 , 4.60629 , -0.155254,0.985104,-0.0739297 -0.517698 , 1.36917 , 5.68605 , 0.284344,0.755503,0.590224 -0.44384 , 1.34561 , 5.77304 , -0.0747767,0.834004,0.546668 -0.372471 , 1.29378 , 5.73173 , -0.078434,0.268011,0.960218 -0.297848 , 1.26271 , 5.78664 , 0.306119,-0.415614,0.856479 -0.225491 , 1.2166 , 5.77172 , 0.633293,-0.2207,0.741776 -0.147234 , 1.18882 , 5.85337 , -0.6495,0.658715,-0.379795 -2.41851 , 0.899723 , -0.954497 , -0.132346,0.158255,0.978489 -2.46678 , 0.929387 , -0.941256 , -0.126178,0.161719,0.978737 -2.53544 , 0.965817 , -0.947042 , -0.048261,0.161788,0.985645 -2.60515 , 1.00347 , -0.950763 , -0.0599143,0.196276,0.978716 -2.67567 , 1.04136 , -0.95232 , -0.0568624,0.151915,0.986757 -2.74529 , 1.08093 , -0.951958 , -0.0561567,0.142592,0.988187 -2.82413 , 1.12268 , -0.95541 , -0.050855,0.157697,0.986177 -2.90947 , 1.16831 , -0.962751 , -0.0377504,0.189929,0.981072 -2.99679 , 1.21508 , -0.967323 , -0.0367557,0.190069,0.981083 -3.08389 , 1.26249 , -0.969074 , -0.0608083,0.172247,0.983175 -3.17842 , 1.31372 , -0.97391 , -0.0587273,0.173813,0.983026 -3.28251 , 1.36943 , -0.981205 , -0.0356287,0.17779,0.983423 -3.39491 , 1.429 , -0.990395 , -0.0454971,0.191659,0.980407 -3.49944 , 1.48608 , -0.990564 , 0.0442781,-0.197791,-0.979244 -3.62864 , 1.55449 , -1.00287 , -0.268811,0.112971,0.956545 -3.72648 , 1.61158 , -0.990689 , -0.852753,0.0723783,0.517275 -3.73579 , 1.63206 , -0.921332 , -0.951258,-0.0789092,0.29813 -3.76777 , 1.66286 , -0.866389 , 0.997158,0.0476987,-0.0583155 -3.73404 , 1.66521 , -0.773737 , 0.996898,0.0383587,0.0687276 -3.73129 , 1.68007 , -0.700309 , 0.996515,0.0117293,-0.0825849 -3.72736 , 1.69408 , -0.627292 , 0.99842,0.028372,0.0485102 -3.79731 , 1.74083 , -0.591933 , 0.99275,0.0675242,0.0994366 -3.71623 , 1.72054 , -0.482586 , 0.991995,0.00911965,0.125946 -3.73342 , 1.74349 , -0.422347 , 0.984832,0.0425766,0.168208 -3.66525 , 1.72798 , -0.325246 , 0.99672,0.0378991,0.0715104 -3.70585 , 1.7617 , -0.276284 , -0.930202,0.0487857,0.363792 -3.71966 , 1.78338 , -0.216013 , -0.883534,0.121205,0.452413 -3.7673 , 1.82042 , -0.167994 , -0.729603,0.148894,0.667466 -3.81458 , 1.85687 , -0.118124 , 0.613892,-0.163941,-0.772179 -3.90436 , 1.9148 , -0.0811426 , -0.385509,0.145594,0.911145 -4.07946 , 2.01401 , -0.0674772 , -0.171578,0.120173,0.977814 -5.10355 , 2.60801 , 0.0681118 , -0.975958,-0.129491,0.175326 -12.8106 , 6.537 , -1.31859 , -0.0553634,0.184744,0.981226 -14.5042 , 7.4567 , -1.37134 , -0.0733668,0.183195,0.980335 -22.4851 , 11.8267 , -1.46985 , -0.549914,0.308478,0.776167 -36.8293 , 19.6667 , -1.70158 , 0.0608255,0.983343,-0.17128 -43.0366 , 23.1632 , -1.3462 , -0.0382919,-0.976476,0.212199 -35.6686 , 19.8206 , 1.80861 , 0.137551,0.989193,-0.0507604 -35.6113 , 19.9452 , 2.49809 , -0.239593,-0.963278,0.121207 -43.1887 , 24.3755 , 3.65753 , 0.0853548,-0.980707,0.175865 -23.7594 , 13.519 , 2.92801 , 0.839083,-0.10678,0.533421 -42.8347 , 24.5578 , 5.32483 , 0.0440787,-0.992228,0.116368 -35.5862 , 20.5625 , 5.29799 , -0.183958,-0.965315,0.185277 -42.9277 , 24.9978 , 7.05094 , 0.149047,-0.96726,0.20541 -41.1093 , 24.3163 , 8.46309 , -0.343975,0.935703,0.0783644 -35.6898 , 21.2765 , 8.20592 , -0.215063,-0.965491,0.146886 -35.5319 , 21.3475 , 8.91174 , -0.18694,-0.973641,0.130677 -5.71704 , 4.12691 , 5.30297 , 0.331376,-0.492287,0.804887 -4.54574 , 3.29774 , 4.48075 , 0.13922,0.82673,0.545102 -4.23589 , 3.09547 , 4.34619 , -0.280018,0.0897679,0.955788 -4.00861 , 2.95435 , 4.27078 , -0.178688,0.0860488,-0.980136 -4.02013 , 2.99222 , 4.41141 , -0.189729,0.185941,0.964069 -4.36947 , 3.29374 , 4.89438 , 0.649941,0.752043,-0.109581 -4.33155 , 3.29837 , 5.0082 , 0.727148,0.686201,-0.0196069 -4.48938 , 3.4584 , 5.33505 , -0.421731,-0.899507,0.114153 -4.2432 , 3.29892 , 5.22958 , 0.754502,0.640128,-0.144784 -4.29586 , 3.38034 , 5.45708 , 0.0432651,0.967078,0.250775 -4.32069 , 3.43975 , 5.66178 , 0.299832,0.758015,0.579236 -4.67592 , 3.77698 , 6.29357 , 0.724918,0.169209,-0.66773 -4.8165 , 3.94377 , 6.68812 , 0.608219,-0.57147,0.550901 -4.72449 , 3.91607 , 6.78918 , 0.553316,-0.223925,0.802308 -4.48023 , 3.75681 , 6.67692 , 0.0284551,-0.195166,0.980357 -4.37823 , 3.71882 , 6.75695 , 0.237432,0.0266844,0.971038 -4.2274 , 3.63592 , 6.75971 , 0.1792,0.0363184,0.983142 -4.06669 , 3.54407 , 6.74299 , 0.680403,-0.420785,-0.599994 -3.15302 , 2.75193 , 5.45959 , 0.750529,0.171406,0.638221 -2.66784 , 2.33707 , 4.80492 , -0.656952,0.295927,0.693427 -2.52113 , 2.23245 , 4.7028 , 0.476933,0.361929,0.800964 -2.6197 , 2.36705 , 5.0541 , -0.195712,-0.978802,-0.0603666 -2.51188 , 2.29968 , 5.02099 , 0.746172,-0.0046832,0.665737 -2.46856 , 2.29765 , 5.11649 , 0.899792,-0.241667,0.363279 -2.43868 , 2.30969 , 5.24527 , -0.850694,0.042177,-0.523966 -2.39749 , 2.31271 , 5.35757 , 0.507412,0.459464,0.72899 -2.27291 , 2.22544 , 5.27436 , -0.469561,-0.696412,-0.5427 -2.2847 , 2.28762 , 5.52238 , 0.847543,0.466109,0.253797 -2.26519 , 2.32027 , 5.71224 , 0.277117,0.309886,0.909493 -2.20088 , 2.30184 , 5.78973 , -0.295433,0.540166,0.787998 -2.12215 , 2.26792 , 5.8311 , 0.708441,0.123075,0.694956 -2.0519 , 2.24447 , 5.89757 , -0.833298,0.242246,-0.496922 -2.09876 , 2.37451 , 6.35767 , 0.865401,0.48989,0.105307 -2.02988 , 2.35948 , 6.4613 , -0.423108,-0.680225,-0.59856 -2.08309 , 2.51836 , 7.03768 , 0.265402,-0.744583,0.612501 -1.37757 , 1.58112 , 4.60405 , 0.252699,0.0741244,0.964702 -1.31499 , 1.5482 , 4.60867 , -0.403396,-0.157478,-0.901373 -1.26524 , 1.53391 , 4.66781 , 0.42959,0.242545,0.869841 -1.6445 , 2.25946 , 6.95761 , 0.61844,0.202403,0.759319 -1.4268 , 1.99007 , 6.29535 , -0.878201,-0.338698,0.337707 -1.04331 , 1.36188 , 4.44467 , 0.984732,0.171859,0.0277172 -1.01321 , 1.38714 , 4.63182 , -0.959827,-0.103566,-0.26078 -0.953369 , 1.35304 , 4.62899 , 0.638309,-0.746113,0.18941 -0.887017 , 1.30312 , 4.56738 , -0.0785951,0.0642083,0.994837 -0.819044 , 1.24115 , 4.45595 , 0.0272034,-0.736741,0.675627 -0.77655 , 1.25464 , 4.62221 , 0.574377,0.762586,-0.297581 -0.710443 , 1.18869 , 4.48869 , -0.637822,0.240163,0.731782 -0.654685 , 1.15538 , 4.47932 , -0.0797769,0.754657,0.651252 -0.604373 , 1.15806 , 4.61455 , -0.155254,0.985104,-0.0739297 -0.553033 , 1.23481 , 5.0804 , -0.452007,-0.833027,-0.318992 -0.48702 , 1.34439 , 5.72246 , -0.249186,-0.778557,-0.575983 -0.414142 , 1.30319 , 5.72048 , -0.183891,-0.364485,0.912872 -0.339924 , 1.26606 , 5.73649 , -0.0606683,0.40099,0.914071 -0.264847 , 1.22986 , 5.76107 , 0.382064,-0.354836,0.853299 -0.0715143 , 1.53176 , 7.56856 , -0.467553,-0.160274,0.869314 --0.0192502 , 1.45172 , 7.43392 , 0.211292,0.907431,-0.363214 -2.46551 , 0.863031 , -0.933354 , -0.114321,0.133856,0.984385 -2.52847 , 0.895865 , -0.932893 , -0.113845,0.150276,0.982068 -2.59226 , 0.928901 , -0.930463 , -0.0560393,0.188706,0.980433 -2.66986 , 0.966669 , -0.939379 , -0.0172716,0.181079,0.983317 -2.74848 , 1.00572 , -0.945939 , -0.0691304,0.164705,0.983917 -2.82046 , 1.04298 , -0.94375 , 0.0687005,-0.148071,-0.986588 -2.89971 , 1.08288 , -0.945519 , -0.0505385,0.160662,0.985715 -2.98739 , 1.12625 , -0.950838 , -0.032295,0.196211,0.98003 -3.08371 , 1.17416 , -0.959416 , -0.060002,0.172288,0.983217 -3.17218 , 1.21954 , -0.959168 , -0.0709098,0.162087,0.984226 -3.26903 , 1.26858 , -0.961692 , 0.053539,-0.176832,-0.982784 -3.37519 , 1.32116 , -0.966378 , -0.0412573,0.192011,0.980525 -3.48894 , 1.37874 , -0.973375 , -0.0490534,0.198029,0.978968 -3.6117 , 1.43914 , -0.981365 , 0.203586,-0.144595,-0.968321 -3.73463 , 1.50234 , -0.985761 , -0.761793,0.0856999,0.642127 -3.73642 , 1.5193 , -0.911956 , 0.945188,0.0778379,-0.317112 -3.73703 , 1.53544 , -0.838464 , 0.998495,0.0450839,0.0312245 -3.74425 , 1.55518 , -0.770124 , 0.996291,0.0402377,0.0760604 -3.734 , 1.56644 , -0.692638 , 0.995864,0.062422,0.066018 -3.73035 , 1.58127 , -0.620402 , 0.996226,0.0571762,0.0653014 -3.7253 , 1.59431 , -0.548378 , 0.997106,0.057862,0.0493083 -3.71932 , 1.60745 , -0.476961 , 0.991672,0.125965,-0.0268362 -3.72039 , 1.62218 , -0.409695 , 0.986487,0.152914,0.0588339 -3.70362 , 1.63019 , -0.335355 , -0.980529,-0.11949,-0.155834 -3.68451 , 1.63652 , -0.261834 , 0.992933,-0.0211451,-0.11678 -3.69939 , 1.6577 , -0.202706 , 0.939487,-0.086987,-0.331357 -3.73948 , 1.68963 , -0.152864 , -0.88028,0.14567,0.451539 -3.77826 , 1.7211 , -0.10168 , 0.623171,-0.184162,-0.760094 -3.9042 , 1.79049 , -0.0777478 , -0.415722,0.12987,0.900172 -4.02141 , 1.85723 , -0.0465702 , -0.170572,0.179958,0.968773 -5.1326 , 2.45103 , 0.0603998 , 0.992244,0.12229,0.022293 -12.1403 , 5.76168 , -1.1962 , -0.0482326,0.191294,0.980347 -13.9304 , 6.65986 , -1.28306 , 0.073171,-0.186607,-0.979706 -19.0818 , 9.259 , -1.4646 , -0.173344,0.17615,0.968981 -22.5121 , 11.0072 , -1.50735 , -0.139781,0.263133,0.95458 -25.0687 , 12.3565 , -1.33536 , -0.523964,0.4867,0.698989 -46.7726 , 23.4032 , -1.66789 , 0.158405,0.92816,-0.336788 -46.737 , 23.582 , -0.782424 , 0.158405,0.92816,-0.336788 -46.7503 , 23.7854 , 0.102664 , 0.156489,0.95298,-0.259502 -46.6782 , 23.9454 , 0.990975 , 0.156489,0.95298,-0.259502 -46.6889 , 24.1494 , 1.88088 , -0.231649,-0.972086,0.0372524 -24.8891 , 12.9951 , 1.95508 , -0.590542,0.421275,-0.688322 -24.5711 , 12.9341 , 2.41091 , 0.938274,-0.19142,0.288099 -24.0107 , 12.7414 , 2.83844 , -0.792065,0.452351,-0.409891 -24.1312 , 12.9085 , 3.3121 , 0.80615,0.193372,0.559223 -23.5418 , 12.6949 , 3.71134 , -0.927714,0.369211,-0.0550517 -23.4988 , 12.7744 , 4.16457 , -0.825775,0.563856,0.0127245 -23.2058 , 12.7158 , 4.5809 , -0.937958,0.306237,0.162646 -44.9227 , 24.7973 , 8.869 , 0.113747,-0.979911,0.163819 -48.6753 , 27.0861 , 10.5154 , 0.112691,-0.978036,0.175347 -4.96285 , 3.40163 , 4.73023 , -0.0858866,-0.831577,0.548729 -4.68743 , 3.24167 , 4.64325 , -0.449256,-0.304754,0.839818 -4.1349 , 2.88041 , 4.29318 , -0.427089,0.04312,0.903181 -4.08906 , 2.87622 , 4.38035 , -0.427089,0.04312,0.903181 -4.00341 , 2.8436 , 4.42985 , -0.00162771,0.164462,0.986382 -4.35533 , 3.13199 , 4.91845 , 0.900288,-0.00544682,-0.43526 -4.40873 , 3.20618 , 5.12718 , -0.968624,-0.180241,0.171114 -4.47507 , 3.29154 , 5.35964 , -0.505381,-0.849613,0.150823 -4.43953 , 3.30211 , 5.48977 , -0.778614,-0.4488,-0.438565 -4.32008 , 3.24863 , 5.52492 , 0.755795,0.451201,0.474543 -4.27599 , 3.25335 , 5.647 , -0.78365,0.03367,0.620289 -4.67275 , 3.60842 , 6.33336 , 0.549242,-0.312299,-0.775115 -5.30181 , 4.1635 , 7.37505 , 0.58621,0.118798,-0.801402 -4.65566 , 3.69106 , 6.74185 , 0.0498103,0.0177755,0.998601 -4.37554 , 3.5098 , 6.57186 , -0.922595,-0.385056,-0.0234468 -4.36579 , 3.55175 , 6.78276 , -0.0886584,-0.134295,-0.986967 -3.28719 , 2.68125 , 5.35008 , 0.249163,0.334214,0.908966 -3.23686 , 2.67749 , 5.44914 , -0.419504,-0.397664,0.816014 -3.18017 , 2.66835 , 5.54001 , -0.308331,-0.626337,0.715985 -2.70071 , 2.27884 , 4.89278 , -0.0452136,0.616118,-0.786355 -2.53798 , 2.1665 , 4.76469 , -0.227601,0.388352,0.892962 -2.44978 , 2.12032 , 4.76094 , 0.732954,-0.0984276,-0.67312 -2.55895 , 2.26317 , 5.14951 , -0.114694,0.92571,0.360425 -2.44915 , 2.19863 , 5.11243 , 0.419604,0.830932,0.365357 -2.45784 , 2.2499 , 5.32445 , 0.293757,0.692562,0.658836 -2.38532 , 2.22245 , 5.36893 , 0.123975,0.837067,0.532869 -2.32649 , 2.20997 , 5.4462 , -0.579608,-0.806234,-0.118499 -2.31706 , 2.25095 , 5.65282 , -0.735856,-0.542759,-0.404881 -2.31208 , 2.29976 , 5.8873 , -0.209258,0.685787,0.697071 -2.17147 , 2.20043 , 5.76224 , -0.106202,0.343687,0.93306 -2.06648 , 2.13718 , 5.72193 , 0.720635,-0.310908,0.619695 -2.01625 , 2.14024 , 5.84897 , 0.720635,-0.310908,0.619695 -2.11008 , 2.32717 , 6.47231 , -0.790613,-0.472987,0.388863 -2.1844 , 2.5047 , 7.103 , 0.732858,-0.536207,0.41881 -1.42503 , 1.56005 , 4.5997 , 0.297749,0.0261318,0.954286 -1.36167 , 1.52845 , 4.60469 , 0.263539,0.0384606,0.963882 -1.30549 , 1.50685 , 4.63611 , -0.41631,-0.112042,-0.902293 -1.79856 , 2.36118 , 7.34339 , 0.785239,0.494247,-0.372987 -1.79242 , 2.48008 , 7.89416 , -0.569855,0.817342,-0.0849559 -1.36576 , 1.86098 , 6.09146 , -0.84577,-0.398631,0.354637 -1.04497 , 1.3565 , 4.56257 , -0.876164,0.0129072,-0.481841 -0.984596 , 1.32461 , 4.55962 , 0.0560637,-0.455279,0.888582 -0.926019 , 1.29606 , 4.56479 , -0.0937168,0.286573,0.953464 -0.867027 , 1.26438 , 4.55943 , -0.174252,-0.225278,0.958586 -0.806162 , 1.22582 , 4.52372 , -0.083153,-0.594469,0.799808 -0.752954 , 1.20945 , 4.57372 , -0.185707,0.879087,-0.438998 -0.693971 , 1.17502 , 4.5551 , 0.261798,-0.858269,0.441403 -0.636532 , 1.14302 , 4.545 , -0.318372,0.935573,-0.152783 -0.590981 , 1.22962 , 5.0399 , -0.309629,-0.830249,-0.463484 -0.531757 , 1.37218 , 5.81871 , 0.0234036,0.958843,0.28297 -0.455158 , 1.32487 , 5.77774 , 0.544287,0.25563,-0.799002 -0.380133 , 1.28095 , 5.75504 , 0.139549,-0.270197,-0.952638 -0.304011 , 1.2502 , 5.78941 , -0.12412,0.194946,-0.972929 -0.230401 , 1.20639 , 5.76381 , 0.633293,-0.2207,0.741776 -0.0238698 , 1.49791 , 7.55107 , -0.275485,-0.292135,0.915841 -2.91013 , 0.819317 , -1.78842 , 0.41663,-0.887909,0.195034 -2.52025 , 0.825286 , -0.918182 , -0.129555,0.160248,0.978538 -2.59112 , 0.858194 , -0.92311 , -0.0930494,0.154002,0.983679 -2.65534 , 0.88931 , -0.919289 , -0.0206921,0.182747,0.982942 -2.74178 , 0.927046 , -0.932986 , -0.0504093,0.19478,0.979551 -2.81532 , 0.961711 , -0.931328 , -0.0875635,0.177735,0.980175 -2.89538 , 1.00017 , -0.933947 , -0.0782579,0.155599,0.984716 -2.96858 , 1.03585 , -0.927814 , -0.0416543,0.182852,0.982258 -3.07368 , 1.08227 , -0.943215 , -0.0308562,0.193886,0.980539 -3.16372 , 1.12499 , -0.94379 , -0.0654007,0.175254,0.982349 -3.25356 , 1.16835 , -0.941544 , -0.0723477,0.178635,0.981252 -3.36012 , 1.21744 , -0.947366 , -0.0544642,0.187674,0.98072 -3.46763 , 1.26805 , -0.94986 , -0.05582,0.19831,0.978549 -3.58346 , 1.3225 , -0.954249 , -0.121277,0.18891,0.974477 -3.70828 , 1.37979 , -0.959534 , 0.597865,-0.227215,-0.76872 -3.75168 , 1.41152 , -0.911763 , 0.910239,0.00848982,-0.413996 -3.76915 , 1.43301 , -0.84809 , 0.990237,0.0312877,-0.135834 -3.75201 , 1.4438 , -0.765872 , 0.997201,0.0719783,0.0202535 -3.74179 , 1.45496 , -0.688775 , 0.994252,0.0908202,0.0566937 -3.73914 , 1.46947 , -0.616904 , 0.976139,0.171589,-0.133076 -3.73437 , 1.48335 , -0.545564 , -0.97738,-0.211431,0.00497693 -3.72842 , 1.49638 , -0.474634 , -0.979136,-0.195969,0.0537425 -3.7213 , 1.50856 , -0.404114 , 0.986787,0.135377,0.0890182 -3.78235 , 1.54595 , -0.363707 , -0.973633,-0.158579,-0.163985 -3.67729 , 1.52015 , -0.253874 , 0.992757,0.0301585,0.116294 -3.70141 , 1.54343 , -0.19895 , 0.886993,-0.00660499,-0.461735 -3.7339 , 1.5704 , -0.146602 , -0.878365,0.0299881,0.47705 -3.7651 , 1.59686 , -0.0932051 , -0.671018,0.0674549,0.738366 -3.86629 , 1.65182 , -0.0619998 , -0.435616,0.131246,0.890513 -3.98494 , 1.71464 , -0.03281 , -0.301452,0.134538,0.943942 -4.26408 , 1.84456 , -0.0456738 , -0.0919044,0.184542,0.978518 -5.14921 , 2.28622 , 0.055791 , -0.994083,-0.103355,0.0334246 -11.6279 , 5.10918 , -1.10366 , -0.0528061,0.18919,0.98052 -13.2182 , 5.84904 , -1.16914 , -0.058459,0.190947,0.979858 -14.9707 , 6.67446 , -1.20063 , -0.0779719,0.189986,0.978686 -22.9096 , 10.4521 , -1.16489 , -0.272301,0.358396,0.892975 -49.4385 , 23.0813 , -1.01184 , 0.34888,0.921825,-0.168881 -49.4131 , 23.2718 , -0.0880714 , -0.34888,-0.921825,0.168881 -49.3898 , 23.4632 , 0.837101 , 0.34888,0.921825,-0.168881 -24.0122 , 11.5342 , 1.38773 , -0.447263,0.0636044,-0.892138 -23.8121 , 11.5355 , 1.8286 , 0.539213,0.422166,0.728715 -22.8685 , 11.1746 , 2.22423 , -0.739427,0.441806,-0.507991 -23.097 , 11.3808 , 2.6706 , -0.424558,0.855496,-0.296441 -22.7899 , 11.3241 , 3.07919 , -0.968193,-0.176599,0.17724 -23.4735 , 11.7605 , 3.58846 , -0.801135,-0.299181,0.518336 -23.1709 , 11.7062 , 3.99869 , -0.894205,-0.121927,0.430733 -23.1619 , 11.7998 , 4.44447 , -0.924349,-0.208933,0.31926 -24.053 , 12.3544 , 5.04675 , -0.951212,-0.300946,0.0680311 -23.841 , 12.3484 , 5.47892 , 0.939855,0.329425,-0.0902887 -48.8458 , 25.4769 , 11.215 , 0.113747,-0.979911,0.163819 -4.99072 , 3.18681 , 4.51316 , 0.633419,-0.0153303,0.773657 -4.98175 , 3.21279 , 4.64796 , 0.484916,0.125216,0.865551 -4.84722 , 3.15524 , 4.68095 , 0.22568,-0.0374239,0.973482 -5.0366 , 3.31357 , 4.99172 , -0.596925,-0.620519,0.508564 -4.12244 , 2.73249 , 4.32011 , -0.656297,0.117553,0.745289 -4.21278 , 2.82289 , 4.53462 , 0.815501,-0.0479186,-0.576768 -3.91219 , 2.64526 , 4.37791 , 0.103647,0.0203197,0.994407 -3.87752 , 2.64941 , 4.47306 , -0.105262,0.28958,0.951348 -4.42815 , 3.06811 , 5.189 , 0.984781,-0.0977718,-0.143692 -4.24455 , 2.97199 , 5.14965 , -0.867845,-0.0620165,-0.49295 -4.55803 , 3.23399 , 5.66776 , 0.793259,0.458141,0.401057 -4.44038 , 3.1878 , 5.70982 , -0.783648,0.0336722,0.620291 -4.27799 , 3.10683 , 5.69288 , -0.78365,0.0336702,0.620289 -4.63738 , 3.41805 , 6.33599 , -0.962944,0.0765645,-0.258605 -4.47315 , 3.33827 , 6.32759 , 0.725095,-0.591583,0.352516 -4.56145 , 3.4539 , 6.66134 , -0.496115,-0.161866,-0.853035 -4.46302 , 3.42554 , 6.74645 , 0.248545,0.0469566,0.967481 -4.40453 , 3.42896 , 6.89067 , -0.529975,-0.812827,-0.24174 -2.79282 , 2.16575 , 4.61466 , 0.636899,0.520406,0.568804 -2.74517 , 2.15887 , 4.68667 , 0.74746,0.391432,0.536735 -2.80824 , 2.24582 , 4.94823 , 0.589391,0.266388,-0.762664 -2.68654 , 2.178 , 4.90144 , 0.595027,-0.176137,-0.784167 -2.56233 , 2.10629 , 4.84301 , 0.679551,0.0566928,-0.731434 -2.67964 , 2.24896 , 5.24045 , 0.263697,0.855302,0.446008 -2.62042 , 2.2366 , 5.31274 , 0.0974104,0.880017,0.464845 -2.53955 , 2.20496 , 5.34223 , 0.113599,0.796197,0.594278 -2.45091 , 2.16511 , 5.35326 , -0.296579,-0.712358,-0.636072 -2.41077 , 2.17266 , 5.47345 , 0.449082,0.861548,0.236771 -2.46642 , 2.27818 , 5.83593 , 0.307675,0.950892,0.0337667 -2.32752 , 2.18909 , 5.73192 , -0.127173,0.80829,-0.574886 -2.27428 , 2.18868 , 5.84368 , -0.466191,-0.853291,0.233582 -2.16552 , 2.12766 , 5.80454 , 0.186912,-0.473383,0.860797 -2.04387 , 2.0515 , 5.7176 , -0.11502,-0.30749,0.944574 -2.14684 , 2.23692 , 6.3395 , 0.789624,-0.164341,0.591173 -2.10104 , 2.25497 , 6.52381 , -0.790613,-0.472987,0.388863 -2.10395 , 2.34057 , 6.90968 , 0.789277,-0.595636,0.1492 -1.40594 , 1.50219 , 4.59182 , 0.310006,-0.00964788,0.950686 -1.34899 , 1.48187 , 4.62341 , -0.433644,-0.0772288,-0.897769 -1.79029 , 2.19802 , 6.93691 , 0.702615,0.191348,0.68536 -1.80546 , 2.33556 , 7.53214 , 0.858184,-0.508726,0.06869 -1.60062 , 2.13058 , 7.03874 , 0.454766,0.00645537,0.890588 -1.34954 , 1.81623 , 6.15021 , 0.977216,0.211409,0.0188536 -1.00803 , 1.28093 , 4.44285 , 0.861763,-0.49174,-0.124723 -0.965045 , 1.28394 , 4.55296 , 0.155732,0.152578,0.975944 -0.922876 , 1.29871 , 4.71064 , -0.70089,-0.513211,-0.495347 -0.845097 , 1.22503 , 4.54109 , -0.347858,0.816844,-0.460174 -0.789404 , 1.20529 , 4.57192 , -0.00566789,-0.120087,0.992747 -0.725238 , 1.15602 , 4.48566 , 0.361843,-0.883671,0.296978 -0.669453 , 1.13384 , 4.5046 , -0.252433,0.951502,-0.175846 -0.629463 , 1.22931 , 5.02865 , 0.248097,0.710535,0.658474 -0.566092 , 1.22179 , 5.13458 , 0.624963,0.755427,0.196853 -0.49911 , 1.33158 , 5.77652 , 0.0640488,-0.791381,0.607959 -0.423522 , 1.28999 , 5.75417 , -0.185877,-0.434913,0.881079 -0.346837 , 1.25338 , 5.74953 , -0.338423,0.372952,0.863931 -0.270986 , 1.21531 , 5.74385 , -0.310633,0.441601,-0.841722 -0.0757153 , 1.52475 , 7.58033 , -0.467553,-0.160274,0.869314 -0.0026855 , 1.40399 , 7.18946 , -0.842883,-0.50957,0.17288 -2.52333 , 0.760596 , -0.917323 , -0.0745358,0.180163,0.980809 -2.58077 , 0.786984 , -0.90893 , -0.0868135,0.176961,0.980382 -2.65303 , 0.817756 , -0.912346 , 0.0331497,-0.179038,-0.983284 -2.73283 , 0.852024 , -0.920307 , -0.0569874,0.20095,0.977943 -2.79853 , 0.882439 , -0.913031 , -0.0643169,0.207828,0.976049 -2.87994 , 0.917287 , -0.916276 , -0.0540605,0.201671,0.97796 -2.96956 , 0.954618 , -0.923066 , -0.0696071,0.174404,0.982211 -3.05179 , 0.991367 , -0.921232 , -0.042586,0.196043,0.97967 -3.15083 , 1.03359 , -0.928632 , 0.0658849,-0.185023,-0.980523 -3.24201 , 1.07331 , -0.927109 , -0.0852037,0.173889,0.981072 -3.34157 , 1.11669 , -0.928357 , -0.0602604,0.187614,0.980393 -3.44948 , 1.1638 , -0.931986 , -0.0473565,0.189867,0.980667 -3.56668 , 1.21455 , -0.93739 , -0.0819862,0.184318,0.979441 -3.68456 , 1.26593 , -0.938976 , 0.444925,-0.180202,-0.877251 -3.74519 , 1.2996 , -0.901771 , -0.936947,-0.00927237,0.349349 -3.74708 , 1.31626 , -0.829328 , 0.974232,0.00922604,-0.225359 -3.75512 , 1.33457 , -0.761838 , 0.996091,0.084916,-0.0243284 -3.76196 , 1.35212 , -0.694368 , 0.996541,0.0819418,-0.0138379 -3.75106 , 1.36425 , -0.618465 , 0.996639,0.0360834,-0.0735475 -3.75553 , 1.38022 , -0.551328 , 0.996768,-0.00998414,0.0797071 -3.81142 , 1.41404 , -0.508959 , 0.997794,0.0583959,0.0315906 -3.73523 , 1.40272 , -0.406308 , 0.99024,-0.101318,0.095701 -3.7625 , 1.42626 , -0.351414 , 0.965477,-0.00185187,0.260481 -3.68325 , 1.41271 , -0.253011 , 0.988776,0.0854313,0.122571 -3.70839 , 1.43562 , -0.198648 , -0.914188,-0.0324512,0.403989 -3.72289 , 1.45461 , -0.14039 , -0.880732,0.0434624,0.471617 -3.77271 , 1.48654 , -0.0941384 , -0.776113,0.102876,0.622145 -3.84932 , 1.52822 , -0.0549813 , 0.519299,-0.163503,-0.838806 -3.95163 , 1.58022 , -0.0214832 , 0.346408,-0.16216,-0.923962 -4.09008 , 1.64704 , 0.00508899 , 0.129557,-0.222514,-0.966283 -5.168 , 2.12979 , 0.0486279 , -0.993467,-0.0968668,0.0603341 -11.1594 , 4.5276 , -1.02201 , -0.0559189,0.186427,0.980876 -12.4769 , 5.0995 , -1.05282 , -0.0482327,0.191294,0.980347 -14.1702 , 5.83366 , -1.09361 , -0.0755189,0.185799,0.979681 -19.2709 , 8.05185 , -1.19124 , -0.140025,0.169581,0.975518 -21.6476 , 9.11876 , -1.08091 , -0.673843,0.262726,0.690587 -24.3034 , 10.3223 , -0.905305 , -0.431377,0.497217,0.752788 -50.4042 , 21.9168 , -0.253305 , -0.34888,-0.921825,0.168881 -50.4716 , 22.1477 , 0.676896 , -0.34888,-0.921825,0.168881 -25.5131 , 11.3342 , 1.32526 , 0.128937,0.257132,0.957736 -24.2623 , 10.8783 , 1.75688 , 0.79561,-0.424001,-0.432697 -23.7653 , 10.7509 , 2.18034 , 0.539213,0.422166,0.728715 -22.9631 , 10.4822 , 2.56601 , 0.55979,0.518855,0.646085 -22.8194 , 10.5093 , 2.9808 , -0.943616,-0.213012,0.253408 -24.2878 , 11.2783 , 3.56408 , 0.800733,-0.0671963,0.595241 -24.1804 , 11.3277 , 4.0086 , -0.844034,-0.359416,-0.398027 -23.4552 , 11.086 , 4.36296 , -0.943173,-0.290467,0.161412 -23.864 , 11.3764 , 4.87887 , -0.909563,-0.259074,0.324923 -23.7624 , 11.4271 , 5.32087 , -0.931348,-0.219506,0.290531 -23.8845 , 11.5862 , 5.80839 , -0.931348,-0.219506,0.290531 -23.548 , 11.5233 , 6.2026 , -0.931348,-0.219506,0.290531 -25.0558 , 12.3655 , 7.03873 , 0.0345518,0.999265,0.0166218 -5.20658 , 3.09578 , 4.44876 , -0.572704,-0.25517,-0.779037 -5.10713 , 3.0657 , 4.51423 , -0.729866,-0.375571,-0.571177 -4.98548 , 3.0224 , 4.56038 , 0.668219,0.403167,0.625251 -4.97001 , 3.04342 , 4.68883 , 0.736299,0.352873,0.577359 -4.04141 , 2.49709 , 4.04592 , 0.639829,-0.498093,0.585255 -4.00747 , 2.50068 , 4.13417 , -0.368998,-0.924035,0.100004 -4.15068 , 2.61859 , 4.38741 , -0.572653,-0.111026,0.812245 -4.20811 , 2.68375 , 4.57258 , -0.969599,-0.112753,-0.217175 -3.8862 , 2.50313 , 4.39121 , 0.561939,0.285927,0.77619 -4.45226 , 2.90575 , 5.10381 , -0.949677,0.20858,0.233682 -4.32895 , 2.85764 , 5.12985 , -0.867845,-0.0620165,-0.49295 -4.25586 , 2.84132 , 5.20703 , 0.993093,-0.034976,-0.111997 -4.43803 , 3.00152 , 5.57903 , 0.993521,0.0967652,0.0596077 -4.47435 , 3.06541 , 5.79879 , 0.113043,0.818239,0.563654 -4.61821 , 3.20754 , 6.16451 , -0.907325,0.406529,0.107219 -4.77978 , 3.36602 , 6.57452 , -0.905771,0.421054,-0.0478865 -4.64323 , 3.31477 , 6.61015 , -0.0828481,-0.975049,0.205952 -4.62014 , 3.3451 , 6.79976 , -0.481297,-0.115405,-0.868928 -3.513 , 2.5622 , 5.42092 , -0.270102,-0.149664,0.951129 -3.45704 , 2.5575 , 5.51382 , -0.0799285,-0.153339,0.984936 -3.33415 , 2.50103 , 5.50508 , -0.310077,-0.351964,0.883161 -2.74146 , 2.07186 , 4.71879 , -0.863759,-0.0717379,-0.498773 -2.69194 , 2.06519 , 4.78959 , -0.742762,-0.36908,-0.558645 -2.64922 , 2.06531 , 4.87591 , 0.835528,0.492242,0.24411 -2.60927 , 2.0685 , 4.97027 , -0.655868,-0.0906878,0.749408 -2.69437 , 2.17947 , 5.31316 , -0.393316,-0.60008,-0.696568 -2.65374 , 2.18581 , 5.42691 , 0.496624,0.708003,0.502092 -2.54969 , 2.1374 , 5.41374 , -0.167983,-0.938533,-0.301557 -2.52898 , 2.16388 , 5.57747 , -0.0959422,-0.995238,-0.0172097 -2.52043 , 2.20491 , 5.78537 , -0.408435,-0.911876,0.0407725 -2.4002 , 2.14095 , 5.73361 , -0.420665,-0.906598,0.0334943 -2.39126 , 2.1859 , 5.95992 , 0.47379,0.480214,0.738185 -2.33903 , 2.19122 , 6.09041 , 0.653765,-0.573148,0.494057 -2.12494 , 2.02472 , 5.75631 , -0.215811,0.579021,-0.786232 -2.19914 , 2.16856 , 6.27002 , 0.773554,0.0139398,0.633578 -2.11915 , 2.14742 , 6.33596 , 0.836946,-0.0555235,0.544461 -2.04764 , 2.1378 , 6.43724 , -0.904827,-0.327842,0.271677 -1.45 , 1.47492 , 4.57885 , 0.3544,-0.0297369,0.934621 -1.38982 , 1.45351 , 4.6013 , 0.355664,-0.0272817,0.934216 -1.83791 , 2.12828 , 6.81971 , -0.0522523,-0.754082,0.654698 -1.75826 , 2.11867 , 6.93662 , 0.677254,-0.240832,0.695217 -1.7703 , 2.25193 , 7.53278 , 0.663172,0.643883,-0.381598 -1.56405 , 2.05093 , 7.01639 , 0.539393,0.0257664,0.84166 -1.35904 , 1.82547 , 6.38853 , 0.977216,0.211409,0.0188537 -1.00998 , 1.28341 , 4.58891 , -0.318793,0.374075,0.870884 -1.19264 , 1.78235 , 6.52906 , 0.688468,-0.59799,-0.41039 -0.887981 , 1.23027 , 4.5872 , 0.341028,0.310575,0.887267 -0.839075 , 1.2343 , 4.70527 , 0.686973,0.573432,-0.446367 -0.890957 , 1.58221 , 6.2169 , 0.564118,0.529806,-0.633306 -0.744479 , 1.29479 , 5.18288 , -0.753,-0.414269,0.511247 -0.668715 , 1.22877 , 5.02738 , -0.00614117,0.708768,0.705415 -0.603805 , 1.20853 , 5.06504 , -0.28943,-0.703556,-0.649029 -0.543833 , 1.33097 , 5.75604 , 0.427485,-0.781558,-0.454338 -0.465538 , 1.30635 , 5.80223 , -0.794649,-0.400023,0.456635 -0.388999 , 1.26175 , 5.74904 , -0.0625985,0.25723,0.96432 -0.312105 , 1.22911 , 5.75314 , -0.133656,0.394865,-0.908965 -0.234358 , 1.19739 , 5.76572 , 0.400939,0.271322,0.875004 -0.0263455 , 1.49129 , 7.55255 , -0.275485,-0.292135,0.915841 -2.5677 , 0.717481 , -0.894823 , -0.0707093,0.172729,0.982428 -2.64056 , 0.745871 , -0.898891 , -0.0853577,0.161754,0.983133 -2.70601 , 0.77368 , -0.894333 , -0.0575408,0.214688,0.974986 -2.78795 , 0.804646 , -0.900464 , -0.0697018,0.189059,0.979489 -2.86176 , 0.836174 , -0.898385 , -0.0738306,0.196307,0.977759 -2.95176 , 0.870106 , -0.905923 , -0.0426813,0.197971,0.979278 -3.03556 , 0.904192 , -0.904911 , -0.0470373,0.170208,0.984285 -3.12659 , 0.94102 , -0.907371 , -0.0420534,0.194443,0.980012 -3.22677 , 0.980247 , -0.912673 , -0.0531769,0.177864,0.982617 -3.31932 , 1.01794 , -0.909152 , -0.0654978,0.169358,0.983376 -3.4286 , 1.06135 , -0.913797 , -0.0543525,0.187625,0.980736 -3.53858 , 1.10534 , -0.914818 , -0.0448555,0.181018,0.982456 -3.65786 , 1.15297 , -0.917613 , 0.311607,-0.175508,-0.933862 -3.76094 , 1.19593 , -0.90648 , -0.816727,-0.0085576,0.576961 -3.76285 , 1.21255 , -0.834232 , -0.917074,-0.131305,0.376475 -3.79701 , 1.23823 , -0.781056 , 0.991777,0.111636,-0.0625795 -3.76313 , 1.24332 , -0.690575 , 0.993252,0.086594,0.0771476 -3.76054 , 1.25767 , -0.619386 , 0.991152,0.0989414,-0.0884763 -3.73077 , 1.26346 , -0.535848 , 0.978891,0.153702,0.134713 -3.72587 , 1.27603 , -0.465867 , 0.979169,0.126993,0.158431 -3.72828 , 1.29113 , -0.400331 , 0.995227,0.0431005,-0.0875543 -3.73894 , 1.3086 , -0.338828 , 0.997456,0.0596664,0.0390053 -3.70368 , 1.31077 , -0.258996 , -0.96649,-0.178861,-0.184137 -3.711 , 1.32685 , -0.198045 , -0.95124,0.0215802,0.307695 -3.71832 , 1.34293 , -0.137093 , -0.917281,0.0252751,0.397437 -3.75957 , 1.37012 , -0.088457 , -0.869914,0.0773108,0.487107 -3.79136 , 1.39422 , -0.0356145 , 0.60402,-0.155054,-0.78174 -3.90447 , 1.44569 , -0.00694851 , 0.396802,-0.183775,-0.899319 -4.04413 , 1.50762 , 0.0177359 , -0.274115,0.16233,0.947898 -4.31203 , 1.61465 , 0.0128038 , -0.0976332,0.211494,0.972491 -5.16379 , 1.96532 , 0.0460923 , -0.992611,-0.0930493,0.0778844 -5.19204 , 1.9941 , 0.127422 , -0.992611,-0.0930493,0.0778845 -11.7878 , 4.42674 , -0.944813 , -0.0559189,0.186427,0.980876 -13.539 , 5.11906 , -1.01172 , -0.0605282,0.181804,0.98147 -15.1963 , 5.78965 , -1.00167 , -0.0811258,0.187088,0.978988 -22.0366 , 8.59928 , -0.76449 , 0.55477,-0.0531898,-0.830302 -22.4804 , 8.85633 , -0.398268 , 0.547338,-0.0803325,-0.833048 -23.9128 , 9.78095 , 1.23171 , -0.951695,0.111634,0.286031 -24.4662 , 10.0993 , 1.68004 , -0.960719,-0.0259349,0.276309 -24.2073 , 10.0874 , 2.11356 , 0.157828,-0.981588,0.107592 -24.3016 , 10.2201 , 2.56211 , -0.513312,-0.814309,-0.270946 -24.6532 , 10.4627 , 3.03768 , -0.917079,0.349309,-0.192222 -23.5113 , 10.0742 , 3.37699 , -0.359972,-0.911686,0.198111 -23.8584 , 10.3164 , 3.8552 , 0.417158,-0.848769,0.324915 -23.5397 , 10.2727 , 4.25689 , -0.841361,0.471102,0.264904 -23.9129 , 10.5304 , 4.75957 , -0.949074,0.297222,-0.104491 -24.4298 , 10.855 , 5.30583 , 0.983503,-0.162304,0.0798699 -25.8063 , 11.568 , 6.04622 , 0.281073,0.893878,-0.349256 -25.7388 , 11.6433 , 6.53126 , 0.521802,0.599479,-0.606916 -25.9114 , 11.829 , 7.07572 , -0.637459,-0.6812,0.360019 -26.1715 , 12.057 , 7.6548 , 0.306154,0.951139,-0.0400644 -25.4859 , 11.8513 , 7.98741 , 0.0225833,0.921964,0.386617 -22.5064 , 11.7323 , 13.0853 , 0.55,-0.832231,-0.0699385 -5.3927 , 2.97355 , 4.36051 , 0.514533,0.237844,0.823824 -5.25561 , 2.92786 , 4.40204 , -0.526305,-0.248647,-0.813128 -5.17076 , 2.90891 , 4.47781 , 0.647218,0.27239,0.711978 -5.12793 , 2.91539 , 4.58458 , 0.699229,0.315367,0.641578 -5.09098 , 2.92374 , 4.69722 , -0.704287,-0.239341,-0.668353 -4.28439 , 2.48764 , 4.17419 , -0.671749,-0.672003,0.311713 -4.1374 , 2.42763 , 4.17032 , 0.56359,0.803719,0.190791 -4.13391 , 2.45122 , 4.29003 , -0.792677,-0.607998,-0.0447479 -4.15549 , 2.49083 , 4.43584 , 0.998614,-0.0316213,-0.0420641 -4.00059 , 2.42469 , 4.41827 , 0.189256,0.809882,0.555224 -3.84942 , 2.35877 , 4.3961 , 0.550247,0.549538,0.628678 -4.01023 , 2.48778 , 4.69348 , -0.340771,-0.931022,-0.130662 -4.31883 , 2.71245 , 5.16764 , -0.984568,0.174593,0.0119522 -3.86569 , 2.45468 , 4.81723 , -0.77416,0.407583,-0.484306 -3.8276 , 2.46102 , 4.91883 , 0.542964,0.758602,0.360157 -3.71746 , 2.42022 , 4.93505 , -0.785545,0.463922,-0.409507 -3.61875 , 2.38638 , 4.96299 , -0.914329,0.347587,0.207811 -4.40149 , 2.95272 , 6.14126 , -0.946039,0.319515,0.054033 -4.26732 , 2.90258 , 6.15975 , -0.670053,0.554848,0.493126 -3.64178 , 2.50554 , 5.47898 , -0.375093,-0.250315,0.892551 -3.52658 , 2.46147 , 5.48857 , -0.375092,-0.250315,0.892551 -3.27022 , 2.31311 , 5.27757 , -0.533445,-0.20114,0.821571 -3.02365 , 2.16684 , 5.05798 , -0.384181,0.73053,0.564563 -2.7269 , 1.97781 , 4.73432 , -0.760297,-0.0720064,-0.645572 -2.7233 , 2.00884 , 4.88472 , 0.75507,-0.316004,0.574465 -2.56939 , 1.92336 , 4.77507 , 0.0738482,0.241489,0.96759 -2.78102 , 2.12861 , 5.33871 , 0.467032,0.547327,0.694489 -2.70943 , 2.11165 , 5.39435 , -0.39333,-0.404595,-0.825588 -2.73236 , 2.17334 , 5.64321 , -0.786301,-0.526657,-0.323054 -2.62856 , 2.13088 , 5.6387 , 0.819834,0.223394,0.527225 -2.53847 , 2.09828 , 5.65764 , 0.635813,0.358889,0.683331 -2.53512 , 2.1449 , 5.88349 , -0.448495,-0.867331,-0.215847 -2.44822 , 2.11689 , 5.91818 , 0.0460289,0.856655,0.513831 -2.36047 , 2.08871 , 5.95111 , 0.585111,-0.594792,-0.551242 -2.30212 , 2.08852 , 6.06285 , -0.880515,0.283985,-0.379534 -2.25496 , 2.10315 , 6.21895 , 0.809268,-0.0748778,0.582649 -2.25875 , 2.17456 , 6.54755 , -0.651962,-0.730416,0.203563 -2.07754 , 2.04825 , 6.29451 , 0.478201,-0.538991,0.693406 -1.49068 , 1.44141 , 4.55707 , 0.347618,0.0526418,0.936157 -1.42997 , 1.42222 , 4.57949 , -0.556617,-0.533214,-0.637071 -1.91625 , 2.09889 , 6.84256 , -0.874874,-0.410633,0.256858 -1.78847 , 2.02622 , 6.74482 , -0.633113,0.730069,-0.257229 -1.69345 , 1.99709 , 6.78471 , 0.836045,-0.446154,0.319335 -1.60542 , 1.97794 , 6.8608 , 0.830366,-0.245199,0.500369 -1.41888 , 1.79951 , 6.37542 , 0.991469,-0.12672,-0.0305327 -1.04078 , 1.25399 , 4.52949 , 0.532233,0.725468,0.436378 -0.989471 , 1.24897 , 4.60102 , -0.354423,-0.0332522,0.934494 -0.916967 , 1.20046 , 4.50851 , -0.506282,-0.554126,0.660774 -0.885857 , 1.24572 , 4.7808 , -0.218828,-0.550547,0.805613 -0.945527 , 1.57653 , 6.2243 , -0.459841,-0.624836,0.630973 -0.845207 , 1.49794 , 6.04473 , 0.512605,0.551757,-0.657876 -0.688919 , 1.13951 , 4.65659 , -0.36987,0.896359,-0.24441 -0.642555 , 1.20513 , 5.05441 , 0.123734,0.680106,0.722597 -0.578205 , 1.20997 , 5.19849 , 0.799477,0.59981,0.0326297 -0.509995 , 1.31093 , 5.80142 , 0.141533,-0.976623,-0.161792 -0.431925 , 1.26174 , 5.71924 , -0.0150424,-0.0657823,0.997721 -0.353514 , 1.23976 , 5.76277 , 0.0138817,0.408158,0.912806 -0.277133 , 1.20073 , 5.72652 , -0.150167,0.328002,-0.932665 -0.0803967 , 1.51356 , 7.57251 , -0.208667,-0.656438,0.724946 -0.00488387 , 1.39944 , 7.18027 , -0.842883,-0.50957,0.17288 -2.62559 , 0.676689 , -0.885512 , -0.0807074,0.124371,0.988948 -2.69887 , 0.703181 , -0.888091 , -0.0711308,0.151821,0.985845 -2.77415 , 0.730699 , -0.888389 , -0.0609056,0.18413,0.981013 -2.84832 , 0.758894 , -0.886765 , -0.0443503,0.153043,0.987224 -2.9317 , 0.789247 , -0.889053 , -0.0596452,0.170811,0.983497 -3.01587 , 0.819956 , -0.88869 , 0.0578239,-0.189781,-0.980122 -3.10728 , 0.853362 , -0.891994 , -0.0362656,0.168421,0.985048 -3.2088 , 0.888975 , -0.897922 , -0.0356988,0.166566,0.985384 -3.30195 , 0.924199 , -0.895442 , -0.0760987,0.166492,0.983102 -3.40423 , 0.961911 , -0.895415 , -0.0637972,0.161604,0.984791 -3.51462 , 1.00239 , -0.897669 , -0.0485943,0.180163,0.982436 -3.63527 , 1.04629 , -0.901576 , 0.226714,-0.153196,-0.961838 -3.74707 , 1.08794 , -0.896487 , -0.728105,0.133223,0.672394 -3.76663 , 1.10854 , -0.834615 , -0.853591,0.050252,0.518515 -3.79327 , 1.13068 , -0.777089 , 0.997301,-0.026379,-0.0685262 -3.76794 , 1.13892 , -0.691616 , 0.994362,-0.0268117,0.102594 -3.76634 , 1.15299 , -0.620598 , 0.997668,0.0318465,-0.0603678 -3.75433 , 1.16413 , -0.545785 , 0.995199,0.0386252,0.0899231 -3.83758 , 1.20199 , -0.517091 , 0.987101,0.0839919,0.136296 -3.74383 , 1.19036 , -0.406531 , -0.963149,-0.0602868,0.262126 -3.73683 , 1.20219 , -0.337567 , 0.978127,0.118208,-0.171157 -3.80897 , 1.23589 , -0.301669 , -0.973954,-0.189812,-0.124035 -3.70097 , 1.21874 , -0.194213 , 0.995361,0.0361845,-0.0891515 -3.71752 , 1.23695 , -0.137271 , -0.87482,0.00165451,0.484446 -3.742 , 1.25687 , -0.0828986 , -0.872629,0.00968279,0.488288 -3.79216 , 1.28548 , -0.0370042 , -0.704925,0.0318758,0.708565 -3.87898 , 1.32508 , -0.000728002 , 0.447801,-0.113319,-0.886923 -3.99318 , 1.37369 , 0.03062 , -0.257181,0.166926,0.951837 -4.15313 , 1.43754 , 0.0532995 , 0.147841,-0.187616,-0.971053 -5.1825 , 1.83277 , 0.123572 , -0.818294,-0.0116319,0.574683 -11.3116 , 3.8865 , -0.875863 , -0.0641611,0.181884,0.981225 -12.7907 , 4.42545 , -0.912877 , -0.0413584,0.187698,0.981356 -14.3926 , 5.01713 , -0.913699 , -0.0834602,0.178637,0.980369 -19.4538 , 6.88162 , -0.934808 , -0.138832,0.177876,0.97421 -21.8589 , 7.79896 , -0.797216 , -0.553234,0.0389139,0.832116 -22.2642 , 8.02342 , -0.436576 , -0.597409,-0.0448716,0.80068 -23.5466 , 8.56672 , -0.104898 , -0.703385,-0.00850547,0.710759 -23.148 , 8.51015 , 0.326648 , -0.703385,-0.0085054,0.710759 -23.8039 , 8.83696 , 0.730327 , 0.801314,-0.0530927,-0.595884 -23.9881 , 9.26559 , 2.44985 , -0.181772,-0.971795,0.150246 -28.5561 , 11.1186 , 3.24372 , -0.617021,0.575814,-0.536399 -28.7395 , 11.2997 , 3.78349 , -0.617021,0.575814,-0.536399 -28.1729 , 11.1872 , 4.24619 , -0.617021,0.575814,-0.536399 -27.9614 , 11.2125 , 4.73866 , -0.441603,0.861155,-0.251793 -27.1264 , 10.9859 , 5.13108 , 0.300978,-0.58459,0.753437 -28.8506 , 11.7914 , 5.93784 , 0.100506,-0.957588,0.270044 -28.3638 , 11.7075 , 6.39048 , -0.577432,0.808378,0.114445 -29.4326 , 12.2628 , 7.15825 , 0.0803081,0.840937,0.535141 -27.1275 , 11.529 , 7.72118 , 0.461879,0.850144,-0.252828 -27.0852 , 11.6226 , 8.24363 , 0.157023,0.793629,0.58779 -26.741 , 11.5877 , 8.68237 , 0.157023,0.793629,0.58779 -26.2234 , 11.4758 , 9.05967 , 0.157023,0.793629,0.587789 -29.2409 , 12.9124 , 10.5986 , -0.286195,0.870886,-0.399562 -28.5011 , 12.7111 , 10.9429 , 0.428872,-0.865391,0.259168 -23.8178 , 11.2876 , 12.402 , 0.204656,0.88251,0.423428 -19.2258 , 9.21504 , 10.6071 , -0.931819,-0.0665197,-0.356776 -24.6311 , 11.9119 , 13.9522 , 0.0125389,-0.996793,0.0790302 -22.7985 , 11.1449 , 13.5209 , -0.439568,0.849599,0.29148 -22.1051 , 10.9213 , 13.6766 , 0.766527,0.311691,0.561502 -24.0552 , 12.0077 , 15.4234 , -0.36876,0.926628,-0.0733334 -23.1052 , 11.66 , 15.4387 , 0.203767,-0.924421,0.322374 -23.0389 , 11.7538 , 16.0046 , -0.0121856,-0.353267,0.935443 -21.6737 , 11.1826 , 15.6829 , -0.825514,0.560778,0.0636765 -5.31007 , 2.79598 , 4.50012 , -0.51024,-0.259346,-0.819997 -5.15625 , 2.74475 , 4.52531 , 0.673873,0.217656,0.70606 -5.09866 , 2.74289 , 4.61981 , -0.69465,-0.363687,-0.620639 -4.16525 , 2.31888 , 4.24166 , -0.89783,-0.33253,-0.288662 -4.18884 , 2.35781 , 4.38665 , 0.66356,0.394215,0.635833 -4.17457 , 2.37685 , 4.50196 , -0.836029,-0.159674,-0.524938 -4.11751 , 2.37231 , 4.57912 , -0.889426,-0.0951637,-0.447062 -4.03447 , 2.3518 , 4.62927 , -0.309413,-0.949811,-0.0460783 -3.87934 , 2.28927 , 4.60346 , -0.294183,0.929967,0.220496 -3.90269 , 2.33168 , 4.76492 , -0.641588,0.451117,-0.620369 -3.7799 , 2.28714 , 4.7683 , -0.558928,0.459641,-0.690167 -3.66577 , 2.24651 , 4.77545 , -0.784898,0.135586,-0.604609 -3.79806 , 2.35934 , 5.08237 , -0.118424,0.852564,0.509029 -4.43811 , 2.79964 , 6.055 , -0.670053,0.554848,0.493126 -4.32607 , 2.76793 , 6.10264 , -0.670053,0.554848,0.493126 -4.24657 , 2.75801 , 6.19291 , -0.670052,0.554848,0.493126 -3.50247 , 2.30278 , 5.33307 , 0.335246,0.327844,-0.883249 -3.50948 , 2.34435 , 5.51653 , 0.100341,-0.280826,0.954499 -3.13629 , 2.12345 , 5.12016 , 0.747925,-0.151633,-0.646232 -3.10386 , 2.13564 , 5.23649 , -0.681432,0.498808,0.535575 -2.89496 , 2.02211 , 5.06268 , 0.586368,-0.393695,-0.707938 -2.67098 , 1.89304 , 4.8415 , -0.855122,-0.348051,-0.384223 -2.8522 , 2.06381 , 5.33932 , -0.625292,-0.346342,-0.699327 -2.75901 , 2.03305 , 5.3533 , -0.625292,-0.346342,-0.699326 -2.69662 , 2.02442 , 5.42461 , -0.773692,-0.276482,-0.570052 -2.68078 , 2.0547 , 5.5973 , -0.921499,0.120933,-0.369073 -2.64795 , 2.07356 , 5.74529 , 0.807011,-0.141065,0.57344 -2.57049 , 2.05644 , 5.79817 , 0.828976,-0.0147855,0.559089 -2.56714 , 2.10408 , 6.03406 , 0.129823,0.988836,-0.0731343 -2.48789 , 2.08798 , 6.0948 , -0.408351,0.790824,0.455902 -2.33687 , 2.00543 , 5.96723 , -0.392373,0.776204,0.493509 -2.26776 , 1.99686 , 6.05108 , 0.641924,-0.662112,0.386706 -2.16628 , 1.9584 , 6.04337 , 0.847642,-0.183385,0.497868 -1.59473 , 1.42991 , 4.5297 , -0.300022,-0.488524,-0.819348 -1.53167 , 1.40967 , 4.54427 , -0.450637,-0.389231,-0.803384 -1.47408 , 1.39585 , 4.57599 , 0.609921,0.58518,0.534379 -1.85407 , 1.90019 , 6.31685 , -0.821363,0.338573,-0.459055 -1.83663 , 1.96529 , 6.65557 , 0.284409,-0.697419,-0.657813 -1.79006 , 2.00157 , 6.91167 , -0.940222,0.324338,-0.103867 -1.70708 , 1.99451 , 7.02673 , 0.550505,0.252573,0.795708 -1.60612 , 1.96539 , 7.06464 , 0.833331,0.355481,-0.423312 -1.08163 , 1.24222 , 4.53674 , 0.0604802,0.378952,0.923438 -1.03345 , 1.2436 , 4.62771 , 0.00783831,0.998196,0.0595289 -0.963831 , 1.20664 , 4.57403 , -0.225705,-0.020678,0.973976 -0.885498 , 1.14524 , 4.42253 , -0.801389,-0.597216,-0.0332893 -0.991847 , 1.54545 , 6.14504 , -0.459841,-0.624835,0.630973 -0.903194 , 1.50974 , 6.13036 , -0.459841,-0.624836,0.630973 -0.753708 , 1.24115 , 5.11263 , 0.568946,0.303968,-0.764136 -0.682319 , 1.20243 , 5.05346 , -0.222118,0.569294,0.791561 -0.61495 , 1.18376 , 5.08051 , 0.169807,0.726984,0.665327 -0.554978 , 1.30619 , 5.77151 , -0.411008,0.879077,0.241444 -0.475407 , 1.27578 , 5.76793 , -0.792325,0.0969664,0.602344 -0.396417 , 1.23982 , 5.73326 , -0.355832,-0.260669,-0.897461 -0.318513 , 1.21147 , 5.73654 , -0.0592913,-0.430718,0.900537 -0.236629 , 1.19185 , 5.78729 , 0.749553,0.36946,0.549245 -0.0290644 , 1.48561 , 7.55372 , -0.275485,-0.292135,0.915841 -2.61567 , 0.608116 , -0.87837 , -0.0695681,0.142964,0.98728 -2.68975 , 0.633221 , -0.881605 , -0.0850206,0.145138,0.985752 -2.74995 , 0.655469 , -0.869604 , 0.0592644,-0.122979,-0.990638 -2.84109 , 0.683048 , -0.88107 , -0.0397577,0.158548,0.986551 -2.91663 , 0.709174 , -0.877642 , -0.0550936,0.163135,0.985064 -3.00139 , 0.737457 , -0.878126 , 0.0573699,-0.180366,-0.981925 -3.09437 , 0.768244 , -0.882058 , -0.0195056,0.175742,0.984243 -3.18811 , 0.799432 , -0.883146 , -0.0437085,0.18118,0.982478 -3.28978 , 0.832305 , -0.886902 , -0.0818692,0.180935,0.980082 -3.38429 , 0.865525 , -0.882327 , -0.07603,0.15722,0.984633 -3.48769 , 0.900281 , -0.880007 , 0.0456116,-0.172923,-0.983879 -3.6085 , 0.939721 , -0.88495 , 0.140774,-0.15123,-0.978423 -3.73025 , 0.980733 , -0.886273 , -0.584044,0.129791,0.801278 -3.76701 , 1.00336 , -0.834577 , -0.946079,-0.0567459,0.318929 -3.76877 , 1.01876 , -0.763299 , -0.949987,-0.127692,0.284991 -3.77764 , 1.03559 , -0.696852 , 0.994419,0.07219,0.0769317 -3.75972 , 1.04605 , -0.617188 , 0.997396,0.0234983,0.06818 -3.75698 , 1.05919 , -0.546968 , 0.993549,0.0647778,0.0930819 -3.7533 , 1.07243 , -0.477355 , 0.995617,0.0754277,0.05529 -3.73001 , 1.08054 , -0.400232 , 0.99485,0.0894328,-0.047692 -3.75094 , 1.09973 , -0.343493 , 0.982488,-0.0485039,-0.179902 -3.77861 , 1.11978 , -0.289734 , 0.990553,-0.112028,0.0790869 -3.69693 , 1.11271 , -0.193388 , 0.990456,0.0934755,0.101285 -3.72345 , 1.1319 , -0.140137 , -0.906169,-0.0419377,0.420831 -3.75713 , 1.15402 , -0.0894819 , -0.869017,-0.00039448,0.494783 -3.79075 , 1.17634 , -0.0379516 , -0.797543,0.0403586,0.601911 -3.84136 , 1.20297 , 0.00904198 , 0.534233,-0.110813,-0.838043 -3.95698 , 1.24774 , 0.0387914 , -0.344377,0.120064,0.931122 -4.09965 , 1.30083 , 0.0649774 , 0.22374,-0.150097,-0.963022 -4.58184 , 1.4673 , 0.0859174 , -0.0597245,0.183198,0.98126 -5.19694 , 1.67924 , 0.115021 , -0.802413,-0.0118255,0.596651 -10.9577 , 3.41668 , -0.827774 , -0.0686179,0.187496,0.979866 -12.0831 , 3.79653 , -0.818312 , -0.0496398,0.186661,0.981169 -13.8344 , 4.37481 , -0.857301 , -0.0713354,0.1866,0.979843 -15.4431 , 4.92307 , -0.81615 , -0.0617378,0.191272,0.979594 -21.8461 , 7.0656 , -0.842023 , 0.510738,-0.0462107,-0.858493 -22.2967 , 7.28972 , -0.489649 , -0.510739,0.0462107,0.858493 -22.8554 , 7.55129 , -0.126475 , -0.569512,-0.0247726,0.82161 -23.407 , 7.81568 , 0.257019 , -0.888956,0.114122,0.443546 -23.4668 , 7.92094 , 0.668795 , -0.94349,0.193107,0.269327 -23.5285 , 8.02733 , 1.08334 , -0.978689,-0.0390576,0.201601 -67.1525 , 22.925 , 2.37425 , -0.0580557,-0.973499,0.221198 -29.7214 , 10.7677 , 4.29737 , 0.420705,-0.773519,0.473999 -27.8936 , 10.2174 , 4.6026 , 0.585224,-0.0233407,0.810536 -27.2588 , 10.195 , 5.52492 , 0.710094,-0.34108,0.61598 -21.8628 , 8.2825 , 5.0256 , 0.649894,-0.755976,-0.0783487 -22.4476 , 8.58791 , 5.55535 , 0.85643,-0.515901,0.0193474 -29.7109 , 11.4489 , 7.61525 , -0.478429,-0.563677,-0.67333 -26.5518 , 10.3477 , 7.41265 , -0.747211,-0.56484,0.350187 -28.0486 , 11.0376 , 8.32233 , 0.075669,-0.607748,0.790517 -27.6557 , 10.9967 , 8.76043 , -0.146396,-0.691133,0.707746 -26.0333 , 10.4633 , 8.81472 , 0.097565,0.710373,0.69703 -20.762 , 8.44987 , 7.62342 , 0.6787,-0.330355,0.655921 -20.7044 , 8.51243 , 8.02345 , 0.677631,0.319388,0.662425 -24.3527 , 10.0997 , 9.78615 , 0.5906,-0.804919,-0.0574105 -22.7827 , 9.55266 , 9.68562 , 0.134161,-0.932066,-0.336532 -26.1701 , 11.0756 , 11.556 , -0.447173,0.860874,-0.242759 -25.6344 , 10.9644 , 11.8896 , -0.888494,0.37931,-0.258267 -25.0538 , 10.8319 , 12.1885 , 0.33941,-0.698737,0.629736 -19.8158 , 8.67419 , 10.2499 , -0.959201,0.0294016,-0.281194 -19.2359 , 8.51229 , 10.4079 , -0.959201,0.0294016,-0.281194 -19.2843 , 8.62579 , 10.8762 , 0.968382,-0.168755,0.183734 -19.469 , 8.80221 , 11.4308 , -0.940689,-0.16254,-0.297799 -19.0672 , 8.7156 , 11.6681 , 0.983763,0.138716,0.113881 -23.2563 , 10.7347 , 14.6392 , -0.802029,-0.178497,0.56999 -22.2942 , 10.4091 , 14.6255 , -0.377063,-0.763048,-0.524958 -21.4671 , 10.1394 , 14.6622 , 0.790006,0.185415,0.58439 -21.6176 , 10.3279 , 15.3305 , 0.790006,0.185415,0.58439 -5.37974 , 2.63997 , 4.47466 , -0.416156,-0.484082,-0.769727 -5.2702 , 2.61613 , 4.53284 , 0.510901,0.430098,0.744309 -5.16793 , 2.5943 , 4.59419 , 0.510901,0.430098,0.744309 -4.42231 , 2.27685 , 4.26517 , 0.13935,0.457865,0.878032 -4.35602 , 2.26747 , 4.33327 , 0.73596,0.0757667,0.672772 -4.23213 , 2.23023 , 4.35023 , 0.486305,0.00348271,0.873782 -4.17868 , 2.22792 , 4.42726 , -0.873595,0.130297,-0.468887 -4.08904 , 2.20669 , 4.47112 , -0.909716,0.162923,-0.381934 -4.07992 , 2.22874 , 4.59189 , -0.841516,-0.487575,-0.232638 -4.15146 , 2.29635 , 4.80068 , 0.808233,0.516696,-0.282462 -4.17287 , 2.33689 , 4.96601 , 0.149319,0.890984,0.428778 -3.86993 , 2.19662 , 4.7789 , -0.446851,-0.00361596,-0.894601 -3.77771 , 2.17339 , 4.8151 , -0.784898,0.135586,-0.604609 -3.9082 , 2.27894 , 5.11521 , 0.0865929,0.846922,0.524619 -3.70568 , 2.19168 , 5.01992 , -0.816545,0.569895,0.0920501 -4.56983 , 2.74441 , 6.29068 , -0.482042,-0.194408,-0.854307 -4.36391 , 2.65971 , 6.21892 , -0.482042,-0.194408,-0.854307 -3.614 , 2.23485 , 5.37698 , 0.295784,-0.509172,0.808242 -3.5414 , 2.22492 , 5.44504 , -0.887909,0.320477,-0.330018 -3.37973 , 2.15666 , 5.37872 , -0.413679,-0.0780467,0.907072 -3.16568 , 2.05181 , 5.22035 , -0.666605,0.0479124,0.743869 -2.95912 , 1.94894 , 5.0551 , -0.125101,-0.376793,-0.917811 -2.87832 , 1.92832 , 5.08714 , -0.684617,0.13948,-0.715434 -2.85759 , 1.94936 , 5.22465 , -0.845898,0.394494,-0.35893 -2.86438 , 1.99263 , 5.42116 , 0.68013,0.189119,0.708278 -2.75243 , 1.95099 , 5.40074 , 0.749873,-0.113694,0.65174 -2.67971 , 1.93703 , 5.45429 , -0.920026,0.0968773,-0.379693 -2.65526 , 1.9606 , 5.60966 , -0.8458,0.247431,-0.472652 -2.59456 , 1.95891 , 5.69618 , -0.600059,0.419832,-0.680933 -2.50536 , 1.93363 , 5.72104 , 0.0556417,-0.453918,0.889305 -2.62855 , 2.08737 , 6.26505 , 0.211064,0.96991,0.121352 -2.55425 , 2.08093 , 6.35296 , 0.211064,0.96991,0.121352 -2.35029 , 1.95822 , 6.09011 , 0.641924,-0.662112,0.386706 -2.2721 , 1.94495 , 6.15564 , 0.823119,-0.230893,0.518811 -2.21838 , 1.95706 , 6.30185 , 0.462969,0.841858,-0.277371 -1.57317 , 1.37576 , 4.53168 , 0.065496,0.759483,0.647221 -1.51578 , 1.36299 , 4.5637 , -0.484212,-0.560266,-0.672043 -1.47421 , 1.36903 , 4.65966 , -0.496859,-0.724234,-0.478138 -1.97832 , 2.01121 , 6.95004 , -0.96544,0.00681805,0.260536 -1.90493 , 2.01835 , 7.10454 , -0.537403,0.63189,0.558492 -1.73363 , 1.90286 , 6.8243 , -0.243525,-0.879423,-0.409037 -1.65536 , 1.90347 , 6.95668 , 0.51222,0.663803,0.544974 -1.12425 , 1.22994 , 4.55379 , 0.214135,0.692858,0.688545 -1.07384 , 1.22992 , 4.63535 , 0.405363,0.696142,0.592509 -0.99926 , 1.18725 , 4.55329 , -0.161279,0.373784,0.913387 -0.921841 , 1.13686 , 4.43063 , -0.85558,-0.479266,0.195669 -0.884378 , 1.16643 , 4.63485 , -0.794348,-0.130524,-0.593275 -0.955852 , 1.50046 , 6.13843 , -0.459841,-0.624836,0.630973 -0.86136 , 1.44977 , 6.04458 , 0.512606,0.551756,-0.657876 -0.723592 , 1.20438 , 5.08179 , 0.399672,-0.12025,-0.908737 -0.654205 , 1.17821 , 5.0703 , 0.192715,0.68819,0.699468 -0.590601 , 1.20924 , 5.32128 , -0.808362,-0.588162,-0.0248162 -0.519698 , 1.29764 , 5.86548 , -0.519606,0.822955,0.229682 -0.440342 , 1.24162 , 5.72349 , -0.399751,0.317113,0.860022 -0.359717 , 1.22318 , 5.76625 , -0.0484418,0.231854,0.971544 -0.280153 , 1.19503 , 5.75836 , 0.429172,-0.0969897,0.898 -0.0819433 , 1.51021 , 7.60381 , -0.467553,-0.160274,0.869314 -0.0145324 , 1.37791 , 7.07279 , -0.627353,-0.225825,0.745272 -2.67794 , 0.564947 , -0.875289 , -0.100308,0.176455,0.979184 -2.74593 , 0.585944 , -0.870134 , -0.108105,0.152547,0.982366 -2.81499 , 0.608117 , -0.86311 , -0.049245,0.208245,0.976836 -2.89931 , 0.632733 , -0.866602 , -0.0641836,0.181568,0.981282 -2.97649 , 0.657674 , -0.861859 , -0.083442,0.167706,0.982299 -3.06143 , 0.683151 , -0.860463 , -0.0336137,0.192553,0.980711 -3.16298 , 0.713066 , -0.868494 , -0.046709,0.199208,0.978844 -3.26624 , 0.743231 , -0.873267 , -0.0710474,0.19688,0.97785 -3.35372 , 0.770816 , -0.863728 , -0.066635,0.19122,0.979283 -3.46587 , 0.80415 , -0.867938 , -0.0704095,0.187599,0.979719 -3.57062 , 0.836902 , -0.863523 , -0.0453972,0.182451,0.982166 -3.70065 , 0.874588 , -0.870981 , 0.373293,-0.184597,-0.909162 -3.78135 , 0.904151 , -0.844818 , -0.85587,0.0226284,0.516696 -3.77502 , 0.918325 , -0.768829 , -0.885669,-0.0743779,0.458321 -3.84621 , 0.946609 , -0.734863 , 0.997523,0.0697569,-0.00907685 -3.76696 , 0.945334 , -0.622889 , 0.98578,0.0639724,0.155385 -3.76544 , 0.959166 , -0.55294 , 0.996428,0.0774916,0.0335725 -3.77079 , 0.973507 , -0.487529 , 0.993153,0.0928658,0.0708696 -3.75695 , 0.984743 , -0.414417 , 0.996124,0.0847596,0.0235059 -3.75118 , 0.997224 , -0.345919 , -0.953441,-0.086008,0.289057 -3.76146 , 1.0125 , -0.285286 , 0.98754,0.0999243,-0.121576 -3.726 , 1.01757 , -0.206945 , -0.96042,-0.224779,-0.164524 -3.72496 , 1.02993 , -0.143515 , -0.93755,0.00617632,0.347795 -3.74132 , 1.04707 , -0.0869586 , -0.908479,0.0328822,0.416634 -3.77551 , 1.06705 , -0.0358858 , -0.85568,0.0688815,0.5129 -3.81781 , 1.08984 , 0.0131001 , 0.659612,-0.12946,-0.740373 -3.92469 , 1.12869 , 0.0443609 , 0.410369,-0.155495,-0.898565 -4.04141 , 1.17057 , 0.0766951 , -0.227351,0.170986,0.958684 -4.23243 , 1.23187 , 0.0938366 , -0.187385,0.167955,0.967821 -5.2141 , 1.53187 , 0.103945 , -0.05318,0.0480955,0.997426 -10.5283 , 2.96175 , -0.767812 , -0.0684103,0.190088,0.979381 -11.5964 , 3.2871 , -0.760177 , -0.0642158,0.180157,0.98154 -13.0956 , 3.73708 , -0.776636 , -0.0446036,0.18797,0.981161 -14.7088 , 4.22986 , -0.754385 , -0.0849186,0.180123,0.979972 -17.1366 , 4.96306 , -0.76305 , -0.0507679,0.184652,0.981492 -19.6206 , 5.72965 , -0.690584 , -0.0911533,0.178858,0.979643 -22.0526 , 6.49983 , -0.526075 , 0.495903,-0.0648851,-0.86595 -22.9265 , 6.83228 , -0.189348 , -0.470284,-0.0325268,0.881916 -23.4781 , 7.07594 , 0.190499 , -0.840633,-0.439213,0.316905 -23.6859 , 7.30605 , 1.01127 , -0.933997,-0.273519,-0.229863 -23.2385 , 7.25351 , 1.41915 , -0.933997,-0.273519,-0.229863 -28.5592 , 9.39917 , 4.04725 , 0.585223,-0.0233407,0.810536 -22.3428 , 7.46417 , 3.78164 , -0.191872,0.693387,-0.69455 -26.9631 , 9.07977 , 4.85105 , 0.798668,0.50158,0.332486 -20.3934 , 6.97347 , 4.27475 , -0.8235,0.557264,-0.106324 -21.8732 , 7.55209 , 4.91627 , 0.682766,-0.720011,-0.124154 -21.1509 , 7.38655 , 5.17543 , 0.680961,-0.54092,-0.493657 -22.1658 , 7.81883 , 5.79214 , -0.922826,0.385195,0.0041286 -27.9229 , 9.92657 , 7.58329 , -0.525393,-0.833955,0.168767 -22.0472 , 7.94746 , 6.6001 , -0.939767,0.154592,-0.30486 -28.401 , 10.3166 , 8.78885 , 0.00961754,-0.45508,0.890398 -18.9223 , 6.98652 , 6.52203 , -0.887614,-0.429283,0.166906 -19.0326 , 7.10221 , 6.92791 , 0.978317,0.189302,-0.0840233 -19.026 , 7.17657 , 7.3039 , -0.982058,-0.137358,0.12921 -20.1579 , 7.67971 , 8.0931 , 0.571105,-0.557045,-0.602942 -20.0854 , 7.73643 , 8.47762 , -0.53996,-0.376006,-0.753036 -22.7498 , 8.84501 , 9.96377 , -0.208322,-0.133728,0.968875 -23.3956 , 9.1934 , 10.718 , -0.973144,0.0954594,-0.209472 -19.8415 , 7.89931 , 9.64039 , 0.744787,-0.476831,0.466823 -19.8422 , 7.98787 , 10.0734 , 0.715527,0.299713,0.631026 -19.1423 , 7.79485 , 10.171 , -0.846325,0.391856,-0.360809 -19.3328 , 7.96059 , 10.7012 , 0.986442,0.0703458,0.148269 -19.4193 , 8.0874 , 11.1932 , 0.99339,0.109968,-0.0329079 -19.0189 , 8.01311 , 11.4256 , 0.984374,0.124265,0.124767 -22.8172 , 9.70851 , 14.1069 , 0.55986,-0.215116,-0.800176 -23.4268 , 10.0833 , 15.0416 , 0.538531,-0.383345,-0.750354 -24.2311 , 10.5511 , 16.1451 , -0.842574,0.44641,-0.301309 -21.8466 , 9.63589 , 15.1913 , -0.611909,-0.291911,-0.735089 -5.35161 , 2.50001 , 4.65805 , 0.510901,0.430098,0.744309 -5.24687 , 2.48084 , 4.71913 , -0.660437,-0.358539,-0.659751 -4.26401 , 2.09897 , 4.30773 , 0.486305,0.00348281,0.873782 -4.1689 , 2.07799 , 4.34629 , 0.826933,0.0116366,0.56218 -4.10782 , 2.0737 , 4.41477 , -0.932038,0.0254216,-0.361468 -4.14781 , 2.11921 , 4.58067 , -0.94657,-0.0336357,-0.32074 -4.11593 , 2.13034 , 4.68237 , 0.85695,-0.284096,0.43003 -4.29725 , 2.25189 , 5.00887 , 0.73319,0.679049,0.0364032 -4.1741 , 2.21742 , 5.02485 , -0.100561,-0.994352,-0.0339452 -4.13933 , 2.2302 , 5.13614 , 0.0616754,0.910312,0.409303 -4.02155 , 2.19806 , 5.15456 , -0.57261,-0.407221,-0.711539 -4.00146 , 2.21886 , 5.28662 , 0.0174626,0.611622,0.790957 -3.93704 , 2.21591 , 5.3677 , 0.405041,-0.481305,-0.77736 -3.64065 , 2.08183 , 5.1473 , 0.0540166,0.677337,0.733687 -3.57289 , 2.07476 , 5.21467 , -0.11291,0.362701,-0.92504 -3.4538 , 2.03843 , 5.21133 , -0.612886,0.103887,-0.783312 -3.44299 , 2.06498 , 5.3619 , -0.616554,0.424606,-0.663001 -3.4024 , 2.07514 , 5.47386 , -0.861616,0.47766,-0.171637 -3.42394 , 2.1262 , 5.69007 , 0.972465,-0.172984,-0.15617 -3.11587 , 1.9685 , 5.37227 , 0.203455,0.434065,0.877607 -2.9054 , 1.8678 , 5.19256 , -0.241997,-0.3141,-0.91803 -2.80395 , 1.83655 , 5.18918 , 0.687328,-0.346549,0.638345 -2.74373 , 1.83237 , 5.25924 , -0.814408,0.483243,-0.321273 -2.74691 , 1.87339 , 5.45579 , -0.890047,0.0661425,-0.451045 -2.70684 , 1.88638 , 5.57692 , -0.829072,-0.0243711,-0.55861 -2.59869 , 1.84971 , 5.55967 , -0.781315,0.177229,-0.598445 -2.52994 , 1.84292 , 5.62721 , 0.534957,-0.24708,0.807943 -2.73161 , 2.04848 , 6.33753 , 0.211064,0.96991,0.121352 -2.65278 , 2.0405 , 6.41764 , -0.178215,-0.979461,-0.0943211 -2.58195 , 2.04109 , 6.52335 , -0.347247,-0.92584,-0.149134 -2.43713 , 1.97774 , 6.42994 , 0.0836141,0.996496,0.00183738 -2.4165 , 2.02467 , 6.68731 , 0.434822,0.688523,0.580401 -1.64054 , 1.36513 , 4.6015 , -0.296765,0.817171,0.494128 -1.55534 , 1.32955 , 4.55107 , 0.145661,0.773969,0.616242 -1.51249 , 1.334 , 4.63784 , -0.367897,-0.874845,-0.315116 -1.88452 , 1.78825 , 6.32024 , 0.674024,-0.364763,0.64237 -1.9549 , 1.95179 , 7.01558 , 0.989982,0.116408,-0.0799077 -1.82811 , 1.89777 , 6.94309 , 0.208535,0.965171,0.15798 -1.72378 , 1.87085 , 6.96226 , 0.0451823,0.852977,0.51999 -1.16251 , 1.21057 , 4.55176 , 0.214135,0.692858,0.688545 -1.11204 , 1.20968 , 4.62396 , -0.638111,0.00616348,-0.76992 -1.04304 , 1.1819 , 4.58994 , 0.185672,0.412084,-0.892027 -0.94549 , 1.10023 , 4.33294 , -0.872727,0.222977,0.434315 -0.916315 , 1.14296 , 4.58518 , 0.440744,0.271707,0.855524 -0.863228 , 1.14394 , 4.67341 , -0.754735,-0.126717,-0.643675 -0.914736 , 1.44648 , 6.08239 , 0.512606,0.551757,-0.657876 -0.76492 , 1.20117 , 5.1005 , 0.430421,-0.0763957,-0.899389 -0.693756 , 1.17555 , 5.07939 , -0.14521,0.553112,0.820354 -0.625393 , 1.16216 , 5.11556 , 0.285918,0.751446,0.594626 -0.565208 , 1.29886 , 5.87507 , -0.202054,0.922264,0.329551 -0.482707 , 1.28233 , 5.91974 , -0.932134,0.278613,0.231303 -0.402645 , 1.22528 , 5.75675 , -0.145527,-0.623975,-0.767774 -0.322274 , 1.19746 , 5.73936 , -0.0344774,-0.423951,0.905029 -0.241066 , 1.17868 , 5.76962 , -0.54639,-0.512726,-0.662246 -0.0322648 , 1.4768 , 7.54547 , -0.130313,-0.681324,0.720289 -2.71823 , 0.513764 , -0.850962 , -0.0945725,0.204536,0.97428 -2.78691 , 0.533748 , -0.844809 , 0.0851912,-0.210222,-0.973935 -2.87906 , 0.557047 , -0.855438 , -0.0556479,0.204062,0.977375 -2.95658 , 0.578654 , -0.85115 , -0.0639847,0.184777,0.980695 -3.04211 , 0.601728 , -0.850503 , -0.0604825,0.19754,0.978427 -3.13684 , 0.627046 , -0.853378 , -0.0496127,0.202918,0.977938 -3.22393 , 0.650831 , -0.847431 , -0.0557129,0.209554,0.976209 -3.31921 , 0.677165 , -0.844738 , -0.0649763,0.197627,0.978121 -3.43273 , 0.706797 , -0.849963 , -0.0628099,0.208558,0.975991 -3.54599 , 0.737197 , -0.851782 , -0.0508143,0.192482,0.979984 -3.66094 , 0.767937 , -0.849956 , 0.253502,-0.157794,-0.954378 -3.7668 , 0.799454 , -0.840039 , -0.827712,0.171404,0.534334 -3.77862 , 0.815512 , -0.773814 , 0.970614,-0.0565349,-0.233905 -3.8066 , 0.834039 , -0.716913 , 0.974147,-0.209998,-0.0833014 -3.78082 , 0.844222 , -0.632735 , 0.997803,-0.00463182,0.0660945 -3.77028 , 0.856958 , -0.558585 , 0.989037,0.0912941,-0.116067 -3.7676 , 0.869921 , -0.489144 , 0.990615,0.136667,0.00181934 -3.76278 , 0.882253 , -0.420233 , 0.988315,0.100111,0.114941 -3.758 , 0.894476 , -0.351809 , 0.974365,-0.0239541,-0.223695 -3.76029 , 0.908247 , -0.28773 , 0.988886,0.0959514,-0.113568 -3.8251 , 0.933904 , -0.248711 , 0.976278,0.0915655,0.196207 -3.72405 , 0.926562 , -0.146448 , 0.98447,0.045587,0.169529 -3.74119 , 0.942395 , -0.0901575 , -0.917959,0.0353399,0.395099 -3.76625 , 0.959913 , -0.0365349 , -0.88695,0.0648611,0.457288 -3.80935 , 0.981322 , 0.0117963 , -0.781825,0.136377,0.6084 -3.87041 , 1.00686 , 0.0559062 , 0.481006,-0.184747,-0.857031 -3.99744 , 1.04638 , 0.0840947 , -0.274547,0.174169,0.945669 -4.15247 , 1.09405 , 0.109035 , -0.204033,0.179117,0.962438 -4.74809 , 1.2551 , 0.112718 , -0.0322514,0.138849,0.989788 -5.23819 , 1.38257 , 0.0918663 , -0.0470408,0.0453109,0.997865 -10.1208 , 2.5386 , -0.71083 , -0.0570696,0.188169,0.980477 -11.1212 , 2.81053 , -0.702237 , -0.0682691,0.190533,0.979304 -12.3331 , 3.1402 , -0.689492 , -0.0470161,0.18796,0.981051 -14.0471 , 3.6005 , -0.698234 , -0.0727106,0.18569,0.979915 -15.6264 , 4.03941 , -0.631808 , -0.0618301,0.191938,0.979457 -19.4548 , 5.05557 , -0.718551 , -0.0912999,0.166379,0.981826 -22.5738 , 5.99474 , -0.225574 , 0.50535,-0.106359,-0.856335 -24.0316 , 6.45489 , 0.107319 , -0.762085,-0.187954,0.619596 -23.84 , 6.48775 , 0.528225 , -0.897367,-0.284293,0.337506 -23.863 , 6.57726 , 0.941746 , -0.93819,-0.306269,-0.161242 -24.1192 , 6.72976 , 1.36006 , 0.865129,0.107555,0.489881 -23.1256 , 6.53968 , 1.74916 , 0.781804,-0.231723,0.578867 -19.9346 , 5.72864 , 1.99578 , 0.906746,-0.403177,0.123532 -20.3297 , 5.91019 , 2.37038 , 0.676171,-0.734008,0.0634402 -20.4391 , 6.01356 , 2.73613 , 0.676171,-0.734008,0.0634403 -20.7329 , 6.17098 , 3.12673 , -0.633581,-0.735236,0.24084 -20.1903 , 6.08532 , 3.4283 , -0.695036,0.715576,-0.0698256 -20.4993 , 6.24887 , 3.8313 , -0.875359,0.432944,-0.215191 -20.0893 , 6.19896 , 4.13437 , -0.918966,0.390935,-0.0516815 -20.6851 , 6.45416 , 4.60238 , -0.848823,0.511556,0.133457 -20.011 , 6.32111 , 4.84771 , -0.915507,0.399202,0.0498516 -29.874 , 9.47913 , 7.32685 , -0.675121,0.708032,0.207128 -21.5831 , 6.9666 , 5.9524 , 0.855199,-0.477531,-0.20149 -22.0501 , 7.19776 , 6.47494 , 0.779394,-0.570139,-0.259783 -19.2539 , 6.37494 , 6.13319 , -0.963348,-0.24017,0.119495 -19.2748 , 6.4557 , 6.507 , -0.926357,-0.369395,-0.0735502 -19.1797 , 6.49888 , 6.84993 , -0.926357,-0.369395,-0.0735502 -19.1861 , 6.57668 , 7.22754 , 0.958054,0.283101,0.044567 -19.455 , 6.74413 , 7.70273 , -0.951447,-0.215208,0.220076 -20.7122 , 7.25595 , 8.5619 , -0.682431,-0.258044,-0.683887 -19.6141 , 6.95787 , 8.55369 , -0.704831,0.68808,-0.172509 -19.8774 , 7.13202 , 9.0696 , 0.510991,0.269988,0.816085 -19.2843 , 7.00426 , 9.22942 , 0.978388,0.0541745,0.199553 -19.1141 , 7.02563 , 9.56489 , -0.89567,-0.124872,-0.426828 -20.4636 , 7.60339 , 10.6293 , -0.625202,-0.62035,-0.473591 -19.1835 , 7.22043 , 10.4402 , -0.880528,0.465962,-0.0868866 -19.649 , 7.4813 , 11.1193 , 0.403587,0.810396,0.424707 -19.2977 , 7.43947 , 11.3795 , -0.886163,0.411146,-0.213713 -21.8799 , 8.52448 , 13.3176 , 0.234521,-0.578784,0.781031 -23.6885 , 9.33528 , 14.9296 , 0.467922,-0.744571,-0.476092 -18.3655 , 7.35043 , 12.1925 , 0.476512,0.092298,0.87431 -19.856 , 8.03973 , 13.6238 , 0.57435,0.00937534,0.818556 -21.8093 , 8.93456 , 15.459 , 0.130333,0.574759,0.807877 -21.8341 , 9.06047 , 16.0553 , 0.130332,0.574759,0.807877 -5.24174 , 2.44571 , 5.38483 , 0.212726,-0.494149,0.84295 -5.03802 , 2.38481 , 5.35442 , -0.806174,-0.0946086,-0.584065 -4.96539 , 2.38268 , 5.44488 , -0.517678,-0.565435,-0.6421 -4.9577 , 2.41296 , 5.60193 , -0.482263,-0.836326,-0.260732 -4.82949 , 2.38456 , 5.63611 , 0.624266,0.749724,0.219558 -4.22201 , 2.12108 , 5.1395 , -0.691079,-0.613977,-0.381368 -4.81124 , 2.44609 , 5.96674 , -0.755824,-0.645143,-0.111895 -4.18275 , 2.16424 , 5.40713 , 0.399623,0.590071,0.701511 -3.92373 , 2.06428 , 5.25407 , -0.122096,0.468684,0.874887 -3.78942 , 2.02491 , 5.24319 , 0.239725,0.0550527,-0.969279 -3.71883 , 2.01994 , 5.31224 , -0.112579,0.516829,0.848654 -3.52445 , 1.94718 , 5.21047 , 0.147351,0.403498,0.903038 -3.49345 , 1.96278 , 5.32973 , 0.527057,-0.216746,0.821725 -3.347 , 1.91375 , 5.28313 , 0.143096,0.233455,0.961781 -3.1218 , 1.81687 , 5.10424 , -0.213558,-0.413244,0.885224 -3.09889 , 1.83803 , 5.23467 , -0.4037,-0.35442,0.843453 -2.93124 , 1.77127 , 5.12789 , -0.0679814,-0.207157,0.975943 -2.7502 , 1.69259 , 4.98313 , 0.254608,-0.144999,0.956112 -2.72517 , 1.71142 , 5.10991 , 0.256037,-0.799887,0.542794 -2.74594 , 1.76146 , 5.33041 , 0.97832,0.206144,-0.0198562 -2.69993 , 1.77005 , 5.43338 , -0.916267,-0.193851,-0.350539 -2.67203 , 1.7915 , 5.57951 , -0.411957,-0.367265,-0.833911 -2.57951 , 1.76935 , 5.5952 , 0.183766,0.101922,0.977672 -2.73956 , 1.93189 , 6.19023 , 0.772512,0.588989,-0.237314 -2.73641 , 1.98275 , 6.44689 , -0.178215,-0.979461,-0.094321 -2.07967 , 1.52651 , 5.05826 , 0.411164,0.658996,-0.629816 -2.0117 , 1.51693 , 5.09802 , 0.771008,-0.0721029,-0.63273 -1.95957 , 1.52001 , 5.18235 , 0.771008,-0.0721027,-0.63273 -1.72006 , 1.36016 , 4.70804 , -0.228385,0.87304,0.430862 -1.63207 , 1.32653 , 4.65861 , -0.20604,0.920223,0.332772 -1.56851 , 1.3134 , 4.68151 , -0.0221458,0.977359,0.210424 -1.92129 , 1.71799 , 6.22301 , -0.937638,-0.00162911,-0.347611 -2.07834 , 1.96191 , 7.22714 , 0.182901,0.175655,0.967312 -1.89279 , 1.85169 , 6.92995 , 0.346015,-0.0878893,0.934104 -1.81878 , 1.86463 , 7.09142 , 0.402465,-0.372733,0.836117 -1.71082 , 1.83949 , 7.10971 , -0.538174,0.277552,0.795822 -1.14588 , 1.18238 , 4.59358 , -0.535457,-0.513785,-0.670306 -1.0761 , 1.1559 , 4.55983 , -0.298111,0.0936837,0.949923 -1.03676 , 1.17921 , 4.72658 , 0.223131,-0.290515,0.930491 -0.950738 , 1.1239 , 4.56481 , -0.433775,0.00473696,-0.901009 -0.895151 , 1.12051 , 4.62393 , -0.727769,0.00053083,-0.685822 -0.974281 , 1.45172 , 6.1687 , -0.459841,-0.624836,0.630973 -0.819265 , 1.23429 , 5.29473 , -0.597638,-0.800644,-0.0423997 -0.734085 , 1.17264 , 5.09837 , 0.285485,-0.117787,-0.951117 -0.663939 , 1.15271 , 5.0958 , 0.30902,0.694995,0.649221 -0.615213 , 1.3294 , 6.0416 , 0.59922,0.299948,-0.742271 -0.528739 , 1.3048 , 6.03753 , 0.535361,-0.186887,0.823688 -0.445862 , 1.22317 , 5.73742 , -0.306112,0.603541,0.736229 -0.364235 , 1.20899 , 5.77925 , 0.477354,0.055463,-0.876959 -0.284126 , 1.17993 , 5.74099 , -0.298382,0.168759,-0.939409 -0.0861446 , 1.49609 , 7.58634 , -0.14836,-0.633375,0.75949 -0.0157776 , 1.37458 , 7.07342 , -0.627353,-0.225825,0.745272 -2.69455 , 0.446517 , -0.83867 , -0.0995394,0.166067,0.981078 -2.77925 , 0.466035 , -0.846019 , -0.0603726,0.178125,0.982154 -2.84015 , 0.483271 , -0.832012 , -0.0634473,0.195245,0.9787 -2.92623 , 0.502395 , -0.834543 , -0.0538585,0.20142,0.978023 -3.01237 , 0.52302 , -0.83484 , -0.077308,0.171378,0.982168 -3.09832 , 0.544195 , -0.832705 , -0.0582547,0.191869,0.97969 -3.19443 , 0.567444 , -0.833777 , -0.0435806,0.191081,0.980606 -3.29823 , 0.591404 , -0.837417 , -0.058355,0.20057,0.97794 -3.39585 , 0.615497 , -0.832604 , -0.0701861,0.174785,0.982102 -3.49325 , 0.640249 , -0.824873 , -0.0672963,0.20688,0.976049 -3.61577 , 0.668764 , -0.829792 , 0.146772,-0.169602,-0.974522 -3.73994 , 0.697705 , -0.830675 , -0.556937,0.133199,0.819804 -3.77804 , 0.716718 , -0.779606 , -0.83054,-0.0761066,0.551735 -3.7625 , 0.728734 , -0.699705 , 0.986707,0.0955447,-0.131456 -3.7722 , 0.744095 , -0.634302 , 0.987489,0.0945329,0.12621 -3.77974 , 0.758913 , -0.569041 , 0.991244,0.0174824,-0.130879 -3.77827 , 0.772591 , -0.499774 , 0.980051,0.0896501,-0.177376 -3.81993 , 0.792312 , -0.451168 , 0.989194,0.146499,-0.00575732 -3.75164 , 0.794606 , -0.3545 , 0.968585,0.180751,0.170799 -3.76295 , 0.809495 , -0.294524 , -0.933129,0.0991272,0.345606 -3.78322 , 0.825656 , -0.237971 , 0.987267,-0.026364,-0.156871 -3.72815 , 0.829476 , -0.153613 , -0.958511,-0.135765,-0.250648 -3.7371 , 0.842739 , -0.0941659 , -0.932364,0.0654728,0.355542 -3.74411 , 0.856454 , -0.0348627 , -0.910219,0.0722385,0.407777 -3.78779 , 0.875503 , 0.0129139 , 0.859768,-0.0857619,-0.503433 -3.82172 , 0.8946 , 0.0644758 , -0.616013,0.163036,0.770679 -3.94895 , 0.929548 , 0.0911423 , 0.36004,-0.193889,-0.912567 -4.0761 , 0.966391 , 0.121795 , -0.218226,0.169578,0.961052 -4.26056 , 1.01444 , 0.143188 , -0.177317,0.177674,0.967983 -5.15917 , 1.22051 , 0.0977061 , -0.0752192,0.107603,0.991344 -5.24809 , 1.25448 , 0.165114 , -0.0752192,0.107603,0.991344 -10.6343 , 2.37875 , -0.6449 , -0.0681408,0.184468,0.980474 -11.6518 , 2.62763 , -0.615544 , -0.0607618,0.18966,0.979968 -13.2125 , 2.99829 , -0.62163 , -0.0454791,0.187716,0.98117 -14.7355 , 3.37161 , -0.568734 , -0.0809615,0.185706,0.979264 -17.0648 , 3.93321 , -0.539512 , 0.0394749,-0.191215,-0.980754 -19.7623 , 4.59316 , -0.457482 , -0.109586,0.171204,0.979122 -22.2237 , 5.2176 , -0.266404 , -0.972388,-0.132627,0.192023 -23.1118 , 5.49762 , 0.0777791 , 0.480311,-0.0790743,-0.873527 -24.1588 , 5.82066 , 0.449366 , -0.871957,-0.199628,0.447034 -23.9912 , 5.86264 , 0.867027 , -0.871957,-0.199628,0.447034 -23.5729 , 5.84423 , 1.27656 , 0.597079,-0.167751,0.784446 -22.3915 , 5.63666 , 1.6508 , 0.78606,-0.458629,0.41445 -22.5063 , 5.74216 , 2.04339 , -0.771626,0.102091,-0.62783 -22.6323 , 5.85042 , 2.44236 , 0.783868,-0.611567,-0.107406 -22.7233 , 5.95115 , 2.84422 , -0.129389,0.942888,0.306953 -19.4906 , 5.19621 , 2.92129 , 0.79478,-0.582804,0.169307 -19.5069 , 5.26764 , 3.26501 , -0.746795,0.65817,0.0954474 -23.093 , 6.28679 , 4.09378 , 0.917978,0.391917,-0.0609628 -20.0479 , 5.54922 , 4.03792 , -0.817252,0.548037,0.178195 -20.0061 , 5.60924 , 4.38892 , -0.90413,0.427202,0.00690079 -19.8827 , 5.6466 , 4.7256 , 0.954968,-0.232888,-0.183845 -20.1779 , 5.80082 , 5.14818 , -0.882329,0.397192,0.252454 -20.3704 , 5.92823 , 5.56175 , 0.777754,0.623607,0.0788183 -21.629 , 6.36413 , 6.24915 , 0.795912,-0.559845,-0.230428 -26.8779 , 7.97223 , 8.04888 , 0.562694,-0.210988,0.799287 -20.7454 , 6.26461 , 6.81113 , 0.121942,0.876834,0.465072 -19.762 , 6.04923 , 6.908 , 0.0956778,0.790861,0.60447 -19.2214 , 5.96121 , 7.11446 , 0.975992,0.0945777,-0.196201 -19.1808 , 6.0232 , 7.47631 , 0.963655,0.0281514,-0.265662 -19.2591 , 6.12223 , 7.88533 , -0.882535,-0.462034,-0.087499 -20.9225 , 6.723 , 8.914 , 0.14107,0.566826,0.81167 -25.0931 , 8.13704 , 11.0382 , -0.704053,0.0102908,0.710073 -19.732 , 6.5092 , 9.26758 , -0.947731,-0.278771,-0.155221 -19.7556 , 6.59917 , 9.69409 , -0.935939,-0.281825,-0.211169 -19.6736 , 6.65534 , 10.0798 , 0.77846,0.299947,0.551391 -24.427 , 8.33787 , 12.8575 , -0.910854,-0.281726,-0.301623 -18.6052 , 6.46317 , 10.3947 , 0.723062,0.54083,0.429749 -18.8218 , 6.62102 , 10.9333 , -0.710464,0.656308,-0.253969 -19.3748 , 6.90059 , 11.6806 , 0.00643503,0.219614,0.975566 -18.4224 , 6.65311 , 11.5786 , -0.92565,-0.341182,0.163606 -18.5657 , 6.79309 , 12.1107 , -0.938812,-0.217327,-0.267209 -20.1851 , 7.47472 , 13.6034 , -0.979973,0.188971,-0.0627853 -20.284 , 7.61193 , 14.1805 , -0.912476,-0.154893,-0.378676 -22.0814 , 8.39081 , 15.9495 , 0.999073,0.0422128,0.00841479 -21.2517 , 8.19167 , 15.9435 , -0.921418,0.212622,0.32524 -21.2572 , 8.30877 , 16.53 , 0.999073,0.0422128,0.00841478 -5.38851 , 2.33016 , 5.43379 , 0.057464,-0.308024,0.949641 -5.17579 , 2.27263 , 5.39876 , -0.0745922,0.173077,-0.98208 -5.11654 , 2.27866 , 5.504 , -0.351336,-0.626643,-0.695616 -5.06144 , 2.28803 , 5.61506 , -0.585533,-0.757164,-0.289576 -4.91789 , 2.2576 , 5.63632 , 0.599042,0.749749,0.281114 -4.95154 , 2.30689 , 5.84324 , 0.641501,0.742067,0.194456 -4.85803 , 2.29922 , 5.91746 , 0.641501,0.742067,0.194456 -4.23899 , 2.04508 , 5.38118 , -0.276813,0.393214,0.876788 -4.00103 , 1.96403 , 5.25831 , 0.0430231,0.41876,0.907077 -3.92494 , 1.95941 , 5.32245 , 0.294803,0.0452396,-0.954487 -3.71898 , 1.8891 , 5.21866 , -0.17016,0.127255,0.977165 -3.65495 , 1.88892 , 5.29328 , 0.282911,-0.170146,0.943934 -3.52835 , 1.85584 , 5.28145 , 0.226879,0.120415,0.96645 -3.41983 , 1.83196 , 5.28996 , 0.304306,0.202279,0.93085 -3.3326 , 1.81841 , 5.32816 , 0.0370018,-0.130626,0.990741 -3.58952 , 1.99461 , 5.90717 , -0.788275,-0.540049,0.294905 -2.94846 , 1.67303 , 5.05484 , -0.239267,0.112027,0.964469 -2.88655 , 1.6708 , 5.11703 , 0.316537,0.247026,0.915851 -2.7715 , 1.63723 , 5.08623 , -0.0609356,0.232452,0.970697 -2.72642 , 1.64464 , 5.17957 , 0.992023,0.0143069,0.125239 -2.77073 , 1.70913 , 5.45231 , 0.574178,0.532921,0.621543 -2.74772 , 1.73439 , 5.6074 , -0.622588,-0.724976,-0.294608 -2.62989 , 1.69937 , 5.57138 , 0.215708,0.457586,0.862604 -2.55621 , 1.69287 , 5.62934 , 0.462762,0.191723,0.865502 -2.61905 , 1.78261 , 6.00538 , 0.982876,0.103352,-0.152553 -2.19756 , 1.5273 , 5.2232 , -0.715974,-0.626641,0.307736 -2.06146 , 1.469 , 5.09363 , 0.771008,-0.0721029,-0.63273 -2.02899 , 1.48902 , 5.23245 , 0.771008,-0.0721025,-0.63273 -1.79475 , 1.34621 , 4.79591 , -0.206013,0.778798,0.59248 -1.70174 , 1.31315 , 4.73816 , -0.266569,0.835979,0.479666 -1.63664 , 1.3026 , 4.76149 , -0.113291,0.921974,0.37031 -2.20284 , 1.88004 , 7.00143 , 0.394209,0.734719,-0.552076 -1.9335 , 1.70048 , 6.41669 , 0.835234,0.503216,-0.221714 -1.95139 , 1.79995 , 6.89748 , -0.656723,0.0144004,-0.753994 -1.87389 , 1.80989 , 7.04025 , 0.664491,0.538298,0.518351 -1.78055 , 1.80442 , 7.1253 , -0.0581939,0.533615,0.843723 -1.65426 , 1.75845 , 7.04661 , 0.783455,-0.469256,-0.407427 -1.11629 , 1.14219 , 4.57723 , -0.719979,0.600901,-0.347202 -1.06613 , 1.14806 , 4.66724 , -0.543038,0.6619,-0.516719 -0.993518 , 1.1199 , 4.61186 , -0.270071,-0.204414,0.940891 -0.924419 , 1.09362 , 4.56475 , -0.681065,0.208304,-0.701969 -0.874014 , 1.10403 , 4.68138 , 0.640329,-0.290877,0.710894 -0.921418 , 1.37724 , 6.00479 , -0.398257,-0.602689,0.691489 -0.77446 , 1.1646 , 5.10782 , -0.295386,0.134416,0.945875 -0.702539 , 1.14522 , 5.09564 , -0.0328349,0.3656,0.930193 -0.633663 , 1.14005 , 5.15057 , 0.39169,0.768694,0.505656 -0.575982 , 1.30561 , 6.05732 , 0.469706,-0.822264,0.321339 -0.488983 , 1.25659 , 5.91461 , -0.837052,0.395456,0.378099 -0.406951 , 1.21218 , 5.78994 , 0.421456,-0.515474,-0.746098 -0.326995 , 1.18221 , 5.73226 , -0.18689,-0.283047,0.940721 -0.24381 , 1.16792 , 5.76157 , -0.702272,-0.172405,-0.690717 -0.0340145 , 1.47133 , 7.54653 , -0.130313,-0.681324,0.720289 -2.82362 , 0.411721 , -0.826849 , -0.0774152,0.174545,0.981601 -2.90136 , 0.428758 , -0.824083 , 0.0840703,-0.192744,-0.977641 -2.98784 , 0.44605 , -0.824835 , -0.0547936,0.171092,0.98373 -3.06719 , 0.463646 , -0.81745 , -0.0544614,0.182263,0.98174 -3.16269 , 0.483711 , -0.819389 , -0.0494158,0.176888,0.98299 -3.25896 , 0.504175 , -0.818483 , -0.0458966,0.167989,0.98472 -3.3639 , 0.525136 , -0.820025 , -0.0678249,0.169476,0.983198 -3.46168 , 0.546467 , -0.813138 , -0.0837786,0.185611,0.979045 -3.57744 , 0.570188 , -0.813777 , -0.0433786,0.194739,0.979895 -3.69294 , 0.5947 , -0.810914 , 0.296477,-0.151735,-0.942909 -3.80129 , 0.61956 , -0.79972 , -0.901896,-0.0162636,0.431646 -3.79501 , 0.633601 , -0.724314 , -0.901896,-0.0162635,0.431646 -3.84065 , 0.652132 , -0.676685 , -0.946222,-0.316921,0.0649996 -3.76993 , 0.658005 , -0.570727 , 0.991003,0.0353697,0.129085 -3.7863 , 0.672836 , -0.510053 , 0.980435,-0.0974462,-0.171029 -3.77464 , 0.684571 , -0.436994 , 0.998127,-0.0467771,0.0394154 -3.82485 , 0.703485 , -0.392195 , 0.991112,-0.0391643,0.127138 -3.76416 , 0.709077 , -0.300947 , 0.990117,0.0191875,-0.138926 -3.77524 , 0.722971 , -0.240969 , 0.976555,0.112407,-0.183587 -3.83213 , 0.742988 , -0.198081 , 0.954503,0.100138,0.280886 -3.72065 , 0.740619 , -0.0944275 , 0.988473,0.0384246,0.146439 -3.74633 , 0.755689 , -0.0417487 , -0.875925,0.0140934,0.482242 -3.78209 , 0.773009 , 0.00850106 , -0.844813,0.062032,0.531453 -3.81561 , 0.790028 , 0.0596794 , -0.762508,0.0664014,0.643563 -3.87772 , 0.811157 , 0.104042 , -0.448478,0.150622,0.881011 -4.02506 , 0.846847 , 0.127928 , -0.226014,0.196882,0.954021 -4.18288 , 0.884697 , 0.15447 , -0.197044,0.168967,0.965725 -4.56082 , 0.959747 , 0.136999 , -0.00839009,0.17435,0.984648 -4.95055 , 1.03842 , 0.130792 , -0.0625077,0.185278,0.980696 -5.25361 , 1.10578 , 0.153985 , -0.0914213,0.184089,0.978649 -10.2413 , 1.99028 , -0.601042 , -0.0576944,0.188804,0.980318 -11.2159 , 2.19753 , -0.575342 , -0.0702403,0.184664,0.980288 -12.4741 , 2.46192 , -0.553453 , -0.0479829,0.189235,0.980759 -14.1633 , 2.81476 , -0.537515 , -0.078516,0.18695,0.979227 -15.8518 , 3.1789 , -0.462815 , -0.0619134,0.186889,0.980428 -19.6455 , 3.95582 , -0.498116 , -0.0622228,0.18988,0.979834 -22.7283 , 4.69722 , 0.0317984 , 0.368715,-0.123794,-0.921262 -24.315 , 5.09314 , 0.376147 , -0.398666,0.0840068,0.913241 -24.2676 , 5.16503 , 0.792928 , 0.559185,0.156806,-0.814079 -25.7531 , 5.72809 , 2.1061 , 0.303242,0.503721,-0.808894 -26.1037 , 5.89125 , 2.57211 , -0.115589,-0.405598,-0.906713 -21.605 , 5.12694 , 3.42688 , 0.247838,0.423475,0.871347 -18.9086 , 4.57398 , 3.45172 , 0.954923,-0.290739,-0.0599483 -18.6875 , 4.58677 , 3.75069 , 0.954923,-0.290739,-0.0599483 -19.3838 , 4.81787 , 4.19729 , 0.796515,-0.466596,-0.384516 -19.6764 , 4.95643 , 4.5969 , -0.915623,0.354071,0.190442 -20.008 , 5.10659 , 5.01807 , 0.759801,-0.649567,0.0276478 -20.0733 , 5.19388 , 5.39536 , 0.446946,-0.893696,-0.0393181 -20.972 , 5.49368 , 5.97937 , 0.836966,-0.516722,-0.180237 -19.3484 , 5.15111 , 5.94431 , -0.623565,0.700429,-0.347227 -19.3774 , 5.22885 , 6.31335 , -0.878482,0.461101,-0.12512 -19.345 , 5.29166 , 6.66874 , -0.898414,0.436945,-0.0439519 -18.9448 , 5.25602 , 6.91042 , -0.960063,0.261075,-0.100592 -19.891 , 5.58514 , 7.59629 , 0.982542,-0.0206145,-0.184895 -24.8346 , 7.02957 , 9.75715 , -0.580448,0.031528,-0.813687 -19.4984 , 5.62824 , 8.23181 , -0.949418,-0.0636518,0.307495 -19.5183 , 5.71063 , 8.63262 , -0.933882,-0.340902,0.107935 -19.7714 , 5.86097 , 9.13815 , 0.999871,0.015983,-0.00135629 -19.6939 , 5.91837 , 9.51484 , -0.978891,-0.132115,0.155945 -19.6701 , 5.99253 , 9.92012 , 0.735814,0.190717,0.649772 -20.7936 , 6.41401 , 10.8882 , -0.801568,-0.577001,0.156712 -20.6817 , 6.46894 , 11.2879 , -0.494825,-0.767376,-0.407777 -20.2394 , 6.42185 , 11.5153 , 0.339888,0.758626,0.555844 -18.9615 , 6.10933 , 11.2682 , -0.184306,0.907982,0.376297 -19.6854 , 6.4265 , 12.1273 , 0.143499,0.908383,0.392744 -20.5003 , 6.78161 , 13.0855 , -0.965344,0.257978,-0.039472 -21.7833 , 7.30137 , 14.3888 , -0.657221,0.753639,-0.00945944 -20.0408 , 6.82497 , 13.7944 , -0.979973,0.188971,-0.0627852 -20.065 , 6.93253 , 14.3217 , -0.877057,-0.281914,-0.388966 -19.6995 , 6.9091 , 14.5878 , 0.887666,0.0304991,0.459477 -21.9077 , 7.78444 , 16.7352 , 0.999556,-0.0286358,-0.00827195 -5.10636 , 2.06983 , 5.25509 , -0.655535,-0.129136,0.744041 -5.21011 , 2.14112 , 5.51006 , 0.76959,-0.151423,0.620324 -4.65543 , 1.95261 , 5.12894 , -0.0949509,0.984906,0.14472 -4.46632 , 1.90464 , 5.08714 , 0.30533,0.523357,0.795532 -4.41207 , 1.91201 , 5.17949 , -0.30533,-0.523356,-0.795532 -4.28543 , 1.88844 , 5.19317 , -0.642277,-0.431493,-0.633478 -4.2734 , 1.91326 , 5.33396 , 0.0122152,-0.997461,0.0701594 -4.10171 , 1.86935 , 5.29203 , 0.137157,0.441845,0.886544 -4.06693 , 1.88549 , 5.40934 , -0.0240184,0.537007,0.843236 -3.94673 , 1.86206 , 5.4213 , 0.284155,0.689944,0.665758 -3.66961 , 1.7666 , 5.2227 , 0.175039,0.10719,0.978709 -3.55464 , 1.74322 , 5.22589 , 0.0928883,0.0787347,0.992559 -3.54505 , 1.77046 , 5.37619 , 0.293243,0.139683,0.945778 -3.13838 , 1.60203 , 4.94451 , 0.12395,-0.223185,0.966864 -3.15244 , 1.63957 , 5.1221 , 0.480124,0.389473,-0.785997 -2.97644 , 1.58151 , 5.00677 , 0.443213,0.340125,0.829384 -2.90533 , 1.57495 , 5.0523 , -0.103839,0.374831,0.921259 -3.05016 , 1.68724 , 5.47293 , 0.368187,0.918922,0.141496 -2.94694 , 1.6665 , 5.47763 , 0.55209,-0.270127,0.788814 -2.8451 , 1.646 , 5.48002 , -0.851715,-0.365574,-0.375417 -2.82674 , 1.67408 , 5.64418 , 0.50271,0.51164,0.696784 -2.71945 , 1.65042 , 5.63495 , 0.177648,0.156607,-0.971553 -2.59676 , 1.6155 , 5.58847 , 0.373415,-0.314944,0.872566 -2.52754 , 1.61469 , 5.6539 , 0.788267,-0.0896206,0.608772 -2.47593 , 1.62497 , 5.76338 , 0.944812,0.0646133,0.321178 -2.16285 , 1.45518 , 5.22416 , -0.109504,-0.317354,0.941963 -2.04478 , 1.41395 , 5.13761 , -0.0581136,-0.463379,0.884253 -1.84787 , 1.31065 , 4.81971 , -0.163548,0.742835,0.64919 -1.76537 , 1.29007 , 4.7992 , -0.255037,0.786743,0.562131 -2.07676 , 1.59158 , 6.01717 , -0.734606,-0.361581,-0.57412 -2.2509 , 1.80638 , 6.9317 , 0.10664,0.480613,-0.870425 -1.9593 , 1.62078 , 6.29127 , -0.836076,-0.494596,-0.237383 -2.02482 , 1.75937 , 6.93144 , 0.856397,0.0471564,0.51416 -1.95115 , 1.77358 , 7.08422 , -0.606427,-0.603115,-0.518168 -1.82142 , 1.73216 , 7.00816 , 0.594011,-0.164298,0.787501 -1.72006 , 1.71941 , 7.05354 , -0.595578,-0.536291,0.598063 -1.59136 , 1.67377 , 6.95332 , -0.237906,-0.568837,0.78729 -1.47631 , 1.64141 , 6.90807 , -0.785648,-0.0657345,0.615171 -1.02313 , 1.09076 , 4.56247 , 0.208035,-0.310344,0.927582 -0.966705 , 1.08779 , 4.61249 , 0.50912,-0.0940853,0.855538 -0.905959 , 1.08159 , 4.64175 , 0.640329,-0.290877,0.710894 -0.840887 , 1.06611 , 4.63125 , -0.796738,0.288584,-0.530969 -0.820754 , 1.17128 , 5.19538 , -0.825226,-0.401689,0.397049 -0.741916 , 1.13747 , 5.10536 , -0.102428,0.344804,0.93307 -0.6715 , 1.12669 , 5.12125 , 0.325933,0.640117,0.695714 -0.625271 , 1.31804 , 6.15593 , 0.404751,-0.864987,-0.296604 -0.534812 , 1.28118 , 6.06264 , 0.535361,-0.186887,0.823688 -0.450932 , 1.21092 , 5.79082 , 0.392948,-0.722147,-0.569294 -0.368729 , 1.18671 , 5.75317 , -0.363182,-0.334013,0.86979 -0.287138 , 1.16608 , 5.73355 , 0.350605,-0.374243,0.858498 -0.0896125 , 1.48313 , 7.56856 , 0.521137,0.299947,-0.79903 -0.0194169 , 1.36461 , 7.03473 , -0.923476,0.382173,-0.0337181 -2.80462 , 0.34283 , -0.821957 , -0.115309,0.181231,0.976657 -2.86677 , 0.356737 , -0.807311 , -0.0719416,0.168659,0.983046 -2.95386 , 0.371581 , -0.809006 , -0.0259391,0.203952,0.978637 -3.04871 , 0.386939 , -0.814145 , -0.0497351,0.19443,0.979655 -3.1364 , 0.40271 , -0.81066 , -0.0448644,0.170362,0.98436 -3.23304 , 0.419775 , -0.810501 , -0.0471183,0.175621,0.98333 -3.32155 , 0.437426 , -0.802035 , -0.0514563,0.171063,0.983916 -3.42785 , 0.456361 , -0.801578 , -0.0929167,0.182576,0.978791 -3.52701 , 0.475622 , -0.792887 , -0.0582819,0.17482,0.982874 -3.65177 , 0.496572 , -0.796136 , -0.159217,0.158312,0.974468 -3.77746 , 0.519071 , -0.795862 , -0.724122,0.14137,0.675027 -3.79794 , 0.534014 , -0.734805 , -0.884278,0.183013,0.429602 -3.78264 , 0.546938 , -0.655296 , 0.999433,-0.0105917,0.031978 -3.89972 , 0.569817 , -0.643209 , 0.999433,-0.0105917,0.0319781 -3.79141 , 0.573771 , -0.5205 , 0.990593,0.136509,0.00948307 -3.77096 , 0.585361 , -0.443437 , 0.997352,-0.0722598,-0.00815285 -3.78518 , 0.599583 , -0.383197 , 0.986305,0.149544,-0.0695715 -3.76147 , 0.609586 , -0.307562 , 0.993319,0.0758218,-0.0870015 -3.76456 , 0.621993 , -0.24404 , 0.989211,0.0816705,0.121619 -3.8123 , 0.63961 , -0.19831 , 0.992351,-0.0939125,0.0801208 -3.72815 , 0.643092 , -0.104736 , 0.986721,0.0426482,0.156725 -3.74586 , 0.656565 , -0.0489998 , -0.933905,-0.0235787,0.356742 -3.75364 , 0.669003 , 0.0101351 , -0.887281,0.07677,0.454795 -3.81669 , 0.688329 , 0.0519944 , 0.787651,-0.0586599,-0.613323 -3.84101 , 0.703102 , 0.106695 , -0.611089,0.129186,0.780949 -3.96089 , 0.730071 , 0.136774 , -0.338577,0.185914,0.922389 -4.1187 , 0.762311 , 0.161602 , -0.182721,0.193849,0.963865 -4.29583 , 0.798357 , 0.187318 , -0.0720472,0.186468,0.979816 -4.76447 , 0.875931 , 0.158662 , 0.0348637,-0.208625,-0.977374 -5.19554 , 0.950873 , 0.153499 , -0.102193,0.216585,0.9709 -9.76595 , 1.61977 , -0.543629 , -0.0613479,0.190971,0.979677 -10.7453 , 1.795 , -0.529878 , -0.0582992,0.189656,0.980118 -11.7847 , 1.98588 , -0.490411 , -0.0593398,0.18703,0.98056 -13.3447 , 2.26212 , -0.47636 , -0.0491193,0.185786,0.981362 -14.8667 , 2.54398 , -0.404528 , -0.0770364,0.184998,0.979715 -17.3217 , 2.98453 , -0.35772 , 0.039247,-0.186981,-0.981579 -19.8851 , 3.45962 , -0.232827 , 0.107772,-0.19265,-0.975331 -22.4062 , 3.94409 , -0.016893 , -0.3315,0.117202,0.936147 -23.1274 , 4.14029 , 0.341801 , -0.296488,0.129555,0.946208 -27.0251 , 4.89074 , 0.683276 , -0.0148576,-0.318823,0.947698 -25.1609 , 4.65041 , 1.13749 , 0.710829,-0.0818152,-0.69859 -27.0108 , 5.06587 , 1.60692 , 0.456087,-0.451433,0.766938 -26.9916 , 5.15073 , 2.06923 , 0.456087,-0.451433,0.766938 -26.9939 , 5.24005 , 2.53305 , 0.456086,-0.451433,0.766938 -20.138 , 4.02697 , 2.49105 , -0.771016,-0.615359,-0.163911 -19.4342 , 3.95716 , 2.77272 , -0.68437,-0.477924,-0.550659 -23.3306 , 4.78864 , 3.53378 , 0.96759,0.221253,0.121726 -23.6798 , 4.93634 , 3.98425 , 0.851659,0.358408,0.382388 -19.2749 , 4.11945 , 3.7602 , -0.654965,-0.0768017,-0.751746 -19.5132 , 4.23313 , 4.13712 , 0.727135,0.237906,-0.643954 -22.9529 , 5.02411 , 5.10458 , -0.978729,-0.00657085,0.205053 -22.9811 , 5.18912 , 5.93397 , 0.678238,0.687172,0.260361 -23.4114 , 5.3646 , 6.45329 , -0.686461,-0.712387,0.145861 -18.9456 , 4.44215 , 5.74364 , 0.758518,-0.59182,0.272763 -18.4633 , 4.39967 , 5.96071 , -0.895387,0.424397,-0.134792 -18.7301 , 4.52721 , 6.38267 , 0.872403,-0.474809,0.116061 -18.865 , 4.62722 , 6.7779 , -0.914114,0.402436,0.0494094 -19.3249 , 4.8066 , 7.29053 , -0.834171,0.51859,0.18768 -19.0918 , 4.82183 , 7.58199 , -0.866376,0.268513,0.421063 -19.9766 , 5.11206 , 8.28564 , -0.938934,-0.195422,0.283221 -22.1019 , 5.72241 , 9.51719 , 0.593678,-0.354622,-0.72235 -21.2001 , 5.57888 , 9.59189 , -0.00617567,0.0915661,0.99578 -18.4472 , 4.94866 , 8.83192 , 0.431935,-0.158814,0.887812 -19.5991 , 5.32551 , 9.74046 , -0.970058,-0.18103,0.161911 -17.5645 , 4.86117 , 9.18443 , -0.754123,0.531317,-0.386007 -17.827 , 5.00467 , 9.69354 , 0.79298,-0.582553,0.178368 -28.7088 , 8.08588 , 15.7667 , -0.646744,-0.485955,-0.587852 -24.9609 , 7.15879 , 14.3724 , -0.750899,-0.311014,-0.582599 -20.4487 , 5.98201 , 12.381 , -0.101911,0.978016,0.181932 -20.1024 , 5.97413 , 12.6538 , -0.68002,0.715716,-0.159131 -19.1004 , 5.77143 , 12.5159 , -0.862697,0.255343,0.436525 -19.4251 , 5.95797 , 13.1904 , -0.815835,0.576071,-0.0505586 -20.3103 , 6.32041 , 14.268 , -0.872081,-0.316476,-0.373253 -19.7941 , 6.26136 , 14.4304 , -0.859542,0.37561,0.346562 -19.8362 , 6.37468 , 14.9816 , 0.0476671,0.412813,0.909568 -21.9976 , 7.16848 , 17.1359 , -0.968539,-0.199204,-0.149163 -5.26544 , 1.95672 , 5.32548 , -0.713265,0.114397,-0.691496 -5.17346 , 1.9544 , 5.39696 , -0.713265,0.114397,-0.691496 -4.97519 , 1.91302 , 5.36584 , -0.376796,0.594141,0.710648 -4.65703 , 1.82625 , 5.2057 , 0.185896,-0.771906,-0.607951 -4.46651 , 1.78436 , 5.16109 , 0.0132833,0.98604,0.165976 -4.36529 , 1.77512 , 5.20333 , 0.203461,0.787605,0.58162 -4.3542 , 1.79981 , 5.34463 , -0.0564033,-0.981236,0.184375 -4.37134 , 1.83786 , 5.52326 , -0.00860764,0.98194,0.188999 -4.09736 , 1.75877 , 5.3617 , -0.0957579,-0.108392,-0.989486 -4.23714 , 1.84749 , 5.69816 , -0.286078,0.755437,0.58947 -3.95195 , 1.76034 , 5.50459 , -0.989186,0.0567496,0.135246 -3.6749 , 1.67255 , 5.30252 , 0.515581,0.0497358,0.855396 -3.52989 , 1.63978 , 5.26509 , -0.0963438,0.190319,0.976983 -3.23367 , 1.53748 , 5.00052 , -0.684493,-0.225076,0.693405 -3.14087 , 1.52407 , 5.0175 , 0.216681,0.943834,-0.249453 -3.19419 , 1.58029 , 5.26112 , 0.106948,0.985354,0.132811 -3.0023 , 1.5197 , 5.11969 , 0.202093,-0.00595764,0.979348 -2.93889 , 1.51991 , 5.18173 , 0.255504,0.16819,0.952066 -2.79802 , 1.48065 , 5.10784 , 0.165576,-0.375136,0.912062 -2.86758 , 1.55208 , 5.41379 , 0.547834,-0.796583,0.255604 -2.74106 , 1.52016 , 5.36203 , -0.294624,0.789156,0.538915 -2.72751 , 1.55061 , 5.5332 , -0.199013,0.885445,-0.419977 -2.62674 , 1.53184 , 5.53004 , 0.0688332,-0.264711,0.961868 -2.51822 , 1.50873 , 5.50682 , -0.347639,0.296929,-0.889371 -2.50065 , 1.53988 , 5.68668 , 0.822752,-0.218532,0.524713 -2.43579 , 1.5445 , 5.76828 , 0.98385,0.167482,0.0631615 -2.04215 , 1.32861 , 5.00672 , -0.692655,-0.491068,0.528281 -1.90497 , 1.27496 , 4.85269 , 0.497818,0.49469,-0.712361 -1.8362 , 1.26797 , 4.87865 , -0.163548,0.742836,0.649189 -2.08621 , 1.50287 , 5.87437 , -0.313603,-0.440842,0.841018 -2.30715 , 1.73948 , 6.8993 , -0.248691,-0.755408,0.606227 -2.22727 , 1.74802 , 7.01734 , 0.132714,-0.561684,0.816638 -1.90598 , 1.54355 , 6.25037 , -0.982848,-0.0615498,-0.173843 -1.96984 , 1.6805 , 6.90096 , 0.748942,0.0879131,0.656778 -1.91661 , 1.71854 , 7.14743 , 0.0761038,0.464056,0.882531 -1.7722 , 1.66548 , 7.00279 , 0.356043,-0.282357,0.890791 -1.6954 , 1.68373 , 7.17129 , -0.0842116,0.271414,0.958772 -1.57975 , 1.66088 , 7.15601 , 0.806602,-0.586664,0.0722408 -1.0589 , 1.07016 , 4.56167 , -0.433309,0.524493,-0.732906 -0.991405 , 1.05281 , 4.53414 , 0.120709,-0.452938,0.883333 -0.929128 , 1.04203 , 4.53441 , 0.304538,-0.413795,0.857922 -0.902476 , 1.10433 , 4.88407 , 0.985895,-0.0137047,-0.166801 -0.931812 , 1.3273 , 6.01458 , -0.520082,-0.584925,0.622396 -0.782063 , 1.12845 , 5.11491 , -0.22971,0.207678,0.950844 -0.71036 , 1.11507 , 5.11166 , 0.253954,0.491184,0.833214 -0.643208 , 1.1298 , 5.25443 , -0.795173,-0.603392,-0.0601422 -0.581094 , 1.269 , 6.03389 , -0.24001,0.285424,-0.927862 -0.493424 , 1.26786 , 6.10605 , 0.60643,-0.0715886,0.791908 -0.410523 , 1.19314 , 5.79358 , -0.454903,0.0875485,0.886227 -0.330275 , 1.16421 , 5.71529 , 0.292819,-0.487295,0.822679 -0.244151 , 1.16383 , 5.79294 , 0.792196,0.233587,0.563793 -0.0362532 , 1.46271 , 7.53805 , -0.143286,-0.506744,0.850105 -2.70486 , 0.263531 , -0.816825 , -0.134322,0.217463,0.966782 -2.7677 , 0.274704 , -0.804388 , -0.13054,0.16926,0.976888 -2.83742 , 0.286365 , -0.796584 , -0.100494,0.178239,0.978842 -2.92414 , 0.29902 , -0.79915 , -0.0856503,0.176156,0.980629 -3.0114 , 0.311058 , -0.798965 , -0.0690291,0.210092,0.975242 -3.09175 , 0.324395 , -0.790646 , -0.0393972,0.19406,0.980198 -3.1878 , 0.338254 , -0.791452 , -0.0403951,0.217237,0.975283 -3.29374 , 0.353302 , -0.794975 , -0.0618001,0.182171,0.981323 -3.39227 , 0.367791 , -0.789776 , -0.0867164,0.172622,0.981164 -3.49083 , 0.383889 , -0.781855 , -0.0815449,0.177286,0.980775 -3.60713 , 0.401405 , -0.781361 , -0.0394169,0.198659,0.979276 -3.733 , 0.419443 , -0.782122 , -0.373813,0.187086,0.90844 -3.80703 , 0.436038 , -0.750443 , 0.991444,0.0671154,-0.11196 -3.79172 , 0.449005 , -0.67074 , 0.969204,0.06799,-0.236689 -3.78432 , 0.462046 , -0.596425 , 0.993328,0.0924332,-0.0689602 -3.8469 , 0.477814 , -0.557087 , 0.988049,-0.121947,0.0942756 -3.78194 , 0.487108 , -0.458153 , 0.990638,0.114938,0.0736623 -3.77934 , 0.499808 , -0.389879 , 0.99449,0.0939036,0.0466107 -3.88512 , 0.51912 , -0.367961 , 0.99449,0.0939036,0.0466107 -3.78668 , 0.525533 , -0.262134 , -0.960777,-0.101467,0.258092 -3.7888 , 0.538154 , -0.198733 , -0.973588,-0.224439,-0.0418747 -3.75238 , 0.547329 , -0.122007 , 0.90519,0.149611,0.397804 -3.73351 , 0.556859 , -0.0529961 , 0.976714,-0.0280645,-0.212702 -3.75027 , 0.570503 , 0.00242427 , 0.976714,-0.0280645,-0.212702 -3.78537 , 0.584837 , 0.0526823 , 0.821057,-0.0925597,-0.563293 -3.83897 , 0.601032 , 0.0985535 , -0.727643,0.117746,0.675774 -3.89245 , 0.617599 , 0.146079 , 0.483726,-0.166706,-0.859196 -4.02211 , 0.642132 , 0.1761 , 0.244893,-0.211143,-0.94628 -4.21901 , 0.674966 , 0.194763 , -0.167302,0.188996,0.967621 -4.57246 , 0.724631 , 0.187779 , -0.0183987,0.243659,0.969687 -4.89773 , 0.77336 , 0.198334 , -0.0600591,0.253468,0.965478 -5.24278 , 0.827173 , 0.216512 , -0.100307,0.226578,0.968814 -10.3197 , 1.42938 , -0.490725 , -0.0549928,0.190945,0.980059 -11.3051 , 1.57944 , -0.454292 , -0.0689081,0.187556,0.979834 -12.5665 , 1.76942 , -0.417407 , -0.0468955,0.183181,0.98196 -14.2717 , 2.02332 , -0.383073 , -0.0799791,0.180652,0.98029 -16.0374 , 2.29646 , -0.295123 , -0.060289,0.181991,0.98145 -19.5428 , 2.8105 , -0.265296 , -0.0637422,0.202289,0.977249 -22.9551 , 3.40818 , 0.27958 , -0.380322,0.0822709,0.921188 -24.0535 , 3.6374 , 0.650495 , -0.506381,0.123144,0.853472 -24.5006 , 3.77945 , 1.05897 , 0.52252,-0.126143,-0.843244 -24.9411 , 3.92426 , 1.48309 , -0.800401,-0.209536,0.561652 -24.4651 , 4.0909 , 2.7262 , -0.622096,-0.677657,-0.392146 -22.9362 , 3.92267 , 3.01159 , 0.284697,0.193505,0.938884 -20.0708 , 3.52439 , 3.10382 , 0.120177,0.912039,0.392101 -20.2178 , 3.61489 , 3.46767 , 0.120177,0.912039,0.392101 -20.8174 , 3.78448 , 3.90235 , -0.385865,0.475284,-0.790705 -18.9542 , 3.52665 , 3.96938 , 0.257639,0.192361,0.9469 -22.984 , 4.30923 , 5.01384 , 0.985647,-0.162987,0.0439943 -28.224 , 5.33924 , 6.44279 , -0.921427,0.227492,0.314991 -27.5535 , 5.31165 , 6.8057 , 0.236192,-0.96801,0.0846761 -23.3421 , 4.69039 , 6.75273 , 0.519608,0.249525,0.817156 -20.665 , 4.24678 , 6.46136 , -0.335142,-0.77753,-0.532096 -18.7361 , 3.93439 , 6.2881 , -0.955074,0.178292,0.236739 -18.7829 , 4.00983 , 6.65198 , 0.942167,-0.155876,-0.296689 -29.577 , 6.30981 , 10.5305 , 0.641423,-0.194177,0.742207 -18.7703 , 4.14217 , 7.36123 , -0.516508,0.853911,0.063688 -17.6816 , 3.97803 , 7.32593 , -0.149523,-0.593958,0.790479 -17.9708 , 4.10656 , 7.7846 , -0.444667,-0.432928,0.78412 -17.0252 , 3.9643 , 7.75738 , -0.983119,0.138973,-0.119008 -18.2201 , 4.29928 , 8.61156 , 0.449588,0.476389,0.755595 -19.933 , 4.76426 , 9.75415 , -0.666125,0.0417354,0.744672 -17.378 , 4.24501 , 8.97018 , 0.816434,-0.309075,0.487758 -17.3776 , 4.31517 , 9.33843 , -0.943382,0.190551,0.271516 -17.351 , 4.38003 , 9.70047 , -0.924344,0.309653,0.222943 -17.6013 , 4.51444 , 10.217 , 0.794187,-0.425794,-0.43355 -25.723 , 6.62771 , 15.16 , 0.0728617,0.0130773,-0.997256 -23.8729 , 6.26818 , 14.6762 , 0.304377,0.193347,0.932723 -18.8218 , 5.06159 , 12.1705 , -0.93784,0.22682,0.262694 -18.9863 , 5.18973 , 12.7266 , 0.807834,-0.456153,-0.373268 -18.9811 , 5.27761 , 13.1898 , 0.807834,-0.456153,-0.373268 -20.5756 , 5.8055 , 14.7576 , 0.0686115,0.259502,0.963302 -20.1869 , 5.79738 , 15.014 , 0.0686115,0.259502,0.963302 -19.2702 , 5.63816 , 14.8736 , 0.145372,0.205848,0.967726 -18.6666 , 5.56232 , 14.9368 , 0.150869,0.211155,0.965739 -18.3883 , 5.57918 , 15.2378 , 0.150869,0.211155,0.965739 -6.14527 , 2.06008 , 6.03427 , -0.297693,0.815373,-0.496533 -5.20021 , 1.79309 , 5.35038 , 0.404633,0.00162794,0.914478 -5.16426 , 1.81173 , 5.47332 , 0.404633,0.00162787,0.914478 -5.02747 , 1.7967 , 5.50085 , 0.171969,0.171223,0.970108 -4.88536 , 1.77978 , 5.51803 , -0.289993,0.817297,0.497926 -5.49154 , 2.02057 , 6.32424 , 0.0724393,0.787947,-0.611468 -5.34288 , 2.00489 , 6.35473 , -0.0346611,-0.760268,0.648684 -4.05836 , 1.57823 , 5.08812 , -0.876173,0.324384,-0.356506 -3.98586 , 1.57982 , 5.15102 , 0.812183,-0.0653233,0.579734 -3.96043 , 1.59881 , 5.27301 , -0.870942,0.390623,-0.298118 -4.13572 , 1.69665 , 5.65529 , 0.303124,-0.788079,-0.535768 -4.04672 , 1.69471 , 5.7119 , 0.516429,-0.679787,-0.52076 -3.59494 , 1.54628 , 5.27204 , 0.208933,0.0965639,0.973151 -3.56345 , 1.56397 , 5.39069 , -0.414029,0.300161,0.85935 -3.36023 , 1.50945 , 5.25989 , -0.101006,-0.438185,-0.893192 -3.10343 , 1.42947 , 5.03351 , -0.364064,0.0769317,-0.928191 -3.26402 , 1.53194 , 5.45096 , -0.343574,-0.853197,-0.392443 -2.8536 , 1.37735 , 4.94978 , 0.0927293,-0.168766,0.981285 -2.85155 , 1.40686 , 5.10989 , 0.0239764,-0.326731,0.944813 -3.08438 , 1.55356 , 5.70539 , -0.271346,-0.953028,-0.134569 -2.84625 , 1.47221 , 5.45923 , -0.355549,0.830801,0.428199 -2.83732 , 1.50561 , 5.64005 , -0.974997,-0.0803679,-0.207175 -2.72134 , 1.48333 , 5.61187 , -0.295082,0.3697,0.88105 -2.58602 , 1.4498 , 5.53679 , 0.429935,0.439263,0.788799 -2.52915 , 1.45862 , 5.62791 , -0.817357,-0.378288,-0.434541 -2.19817 , 1.30548 , 5.07157 , -0.835276,-0.293032,0.465238 -2.04965 , 1.25355 , 4.91219 , 0.571901,-0.227768,-0.788068 -1.96713 , 1.23969 , 4.90383 , 0.454669,0.787389,-0.416287 -1.97711 , 1.28838 , 5.15055 , -0.619872,0.0303516,-0.784115 -2.20403 , 1.49415 , 6.06438 , -0.660977,-0.661939,0.353477 -2.28402 , 1.6117 , 6.62547 , 0.243975,-0.840211,0.484274 -2.27984 , 1.67805 , 6.9759 , -0.645823,0.168355,-0.744694 -1.95541 , 1.48888 , 6.22826 , -0.990378,-0.137845,0.0122303 -2.00674 , 1.60587 , 6.80307 , 0.399124,-0.110821,0.910175 -1.93161 , 1.62134 , 6.94498 , -0.723039,-0.0956434,-0.684155 -1.86099 , 1.64553 , 7.12421 , 0.47989,-0.561683,-0.673956 -1.75932 , 1.64099 , 7.17841 , -0.158942,0.285405,0.945136 -1.60604 , 1.57731 , 6.96181 , 0.614056,-0.312837,-0.724616 -1.48333 , 1.54381 , 6.87657 , 0.70899,0.183288,-0.680984 -1.34339 , 1.48073 , 6.65343 , -0.741861,0.0182975,0.670304 -0.967783 , 1.03297 , 4.57243 , 0.304538,-0.413795,0.857922 -0.903574 , 1.02155 , 4.56221 , 0.416052,-0.620128,0.665088 -0.846316 , 1.02339 , 4.6192 , -0.567605,0.442461,-0.694301 -0.822523 , 1.11726 , 5.13463 , 0.642351,0.181184,-0.744686 -0.747572 , 1.10073 , 5.10215 , -0.0588646,0.298767,0.952509 -0.677872 , 1.10095 , 5.15673 , 0.504682,0.69768,0.508467 -0.630682 , 1.28643 , 6.17211 , 0.404751,-0.864987,-0.296604 -0.539907 , 1.24963 , 6.04836 , 0.60643,-0.0715886,0.791908 -0.454293 , 1.19296 , 5.81466 , -0.416731,0.67333,0.610706 -0.371797 , 1.1698 , 5.75639 , -0.292923,-0.628285,0.720732 -0.29015 , 1.15223 , 5.72611 , 0.18133,-0.517507,0.836245 -0.0945371 , 1.46576 , 7.53122 , -0.500398,-0.819149,0.280352 -0.0237738 , 1.35245 , 6.98641 , -0.972536,0.171686,-0.157153 -2.68181 , 0.199961 , -0.81138 , -0.130917,0.216598,0.967443 -2.74448 , 0.209985 , -0.799621 , -0.133908,0.209818,0.968527 -2.82275 , 0.219184 , -0.79854 , -0.110685,0.173742,0.978551 -2.8929 , 0.228946 , -0.789249 , -0.0731737,0.167144,0.983213 -2.96485 , 0.238696 , -0.777868 , -0.0654793,0.171219,0.983055 -3.05254 , 0.248813 , -0.776292 , -0.0593107,0.190495,0.979895 -3.15713 , 0.260233 , -0.783722 , 0.0509975,-0.221127,-0.973911 -3.24638 , 0.271084 , -0.776748 , -0.0245685,0.209533,0.977493 -3.35248 , 0.28337 , -0.778197 , -0.0670962,0.168494,0.983416 -3.44255 , 0.296145 , -0.766047 , -0.100019,0.182327,0.978138 -3.55112 , 0.309103 , -0.761296 , 0.0697166,-0.176898,-0.981757 -3.66854 , 0.323664 , -0.758509 , 0.17493,-0.191779,-0.965723 -3.80316 , 0.338001 , -0.761586 , -0.785133,0.0954598,0.611926 -3.79788 , 0.351739 , -0.686448 , -0.924212,0.0112737,0.381713 -3.80932 , 0.365631 , -0.620996 , 0.985491,0.0878706,-0.145212 -3.79095 , 0.378028 , -0.542625 , 0.982651,0.185318,-0.00729842 -3.82664 , 0.391613 , -0.4902 , 0.982651,0.185318,-0.00729842 -3.80642 , 0.404199 , -0.413141 , 0.953986,0.294756,-0.0550352 -3.77508 , 0.414926 , -0.332995 , 0.974849,0.222709,0.00839307 -3.78814 , 0.428279 , -0.273261 , -0.96546,-0.195861,0.171832 -3.791 , 0.439734 , -0.209543 , 0.995979,0.0846605,0.0292918 -3.84872 , 0.454321 , -0.166496 , 0.95262,0.131029,0.274493 -3.72646 , 0.460324 , -0.0607064 , 0.952135,0.109911,0.285233 -3.75366 , 0.472863 , -0.00826694 , -0.879992,0.0415221,0.473171 -3.76049 , 0.485429 , 0.050358 , -0.879992,0.0415221,0.473171 -3.82457 , 0.50043 , 0.0928591 , -0.798308,0.0864949,0.596006 -3.84943 , 0.512976 , 0.147589 , -0.600174,0.134226,0.788527 -3.96963 , 0.532722 , 0.178707 , 0.355305,-0.170954,-0.918985 -4.11866 , 0.555274 , 0.207124 , -0.167162,0.197838,0.965876 -4.31685 , 0.582369 , 0.230057 , -0.0643182,0.207823,0.97605 -4.74066 , 0.628886 , 0.215972 , -0.041372,0.258853,0.96503 -5.01792 , 0.665449 , 0.242247 , -0.0713943,0.272668,0.959456 -9.86181 , 1.09279 , -0.446559 , -0.0709003,0.200061,0.977215 -10.7812 , 1.2052 , -0.411982 , -0.056713,0.194636,0.979235 -11.8585 , 1.33772 , -0.365566 , -0.0554281,0.188651,0.980479 -13.4219 , 1.52325 , -0.333755 , -0.0483124,0.191321,0.980338 -14.8973 , 1.70975 , -0.240257 , -0.075842,0.187408,0.97935 -19.9577 , 2.33262 , -0.0162675 , -0.101837,0.198537,0.974788 -22.559 , 2.67611 , 0.223815 , 0.550889,-0.156396,-0.819794 -23.9436 , 2.90124 , 0.57739 , -0.4878,0.17117,0.856009 -24.7045 , 3.06417 , 0.980272 , -0.12402,0.0542708,0.990795 -24.6338 , 3.13354 , 1.39753 , 0.552812,0.486652,-0.676438 -26.3715 , 3.42208 , 1.87081 , -0.202072,-0.0845919,0.975711 -25.4161 , 3.4682 , 2.70476 , -0.941582,0.101551,-0.321109 -24.8208 , 3.47053 , 3.08893 , -0.974688,0.221334,-0.031541 -24.9687 , 3.5704 , 3.52935 , 0.391085,-0.0492126,0.919038 -22.8065 , 3.35378 , 3.7012 , -0.977527,0.0515117,0.204422 -20.3639 , 3.08447 , 3.76024 , 0.120177,0.912039,0.392101 -19.0341 , 2.959 , 3.907 , 0.433476,0.0308251,0.900638 -18.2321 , 2.90347 , 4.0996 , -0.451949,-0.0789503,-0.888543 -17.9552 , 2.92116 , 4.36577 , -0.854066,0.505154,-0.124061 -18.2751 , 3.02952 , 4.74874 , -0.330309,-0.920613,0.208248 -18.6238 , 3.14458 , 5.15279 , 0.688673,0.724281,-0.0338624 -17.899 , 3.09071 , 5.30883 , 0.151564,0.988441,0.0036643 -17.5478 , 3.09322 , 5.53969 , 0.171415,-0.946723,0.27264 -18.3387 , 3.34932 , 6.42259 , -0.28113,0.426927,0.859476 -17.4269 , 3.2536 , 6.47259 , 0.7373,0.640668,0.214322 -17.3318 , 3.29872 , 6.76914 , -0.936089,0.169418,0.308277 -17.1297 , 3.32361 , 7.02763 , 0.80388,0.27921,-0.525185 -17.8715 , 3.5235 , 7.64163 , 0.646189,0.232564,-0.726879 -18.9164 , 3.78679 , 8.41181 , 0.781733,-0.0952871,-0.616291 -19.0763 , 3.88795 , 8.85757 , -0.233397,6.71736e-05,0.972382 -20.3059 , 4.20392 , 9.78831 , -0.77702,0.465112,0.424159 -23.0512 , 4.8348 , 11.4799 , 0.998663,-0.0247013,0.0454087 -17.3332 , 3.75114 , 9.19556 , 0.957669,-0.210611,-0.196249 -17.3477 , 3.82357 , 9.57232 , -0.965337,0.178758,0.190182 -17.8223 , 3.99491 , 10.2006 , 0.7759,-0.432716,-0.459059 -18.1765 , 4.14624 , 10.7912 , -0.0604496,0.463339,0.884117 -21.4426 , 4.94869 , 13.0811 , 0.989407,0.100699,0.104565 -19.0297 , 4.49489 , 12.134 , 0.994238,-0.0461641,0.0967473 -23.1799 , 5.53886 , 15.1706 , -0.329478,0.565839,0.755824 -19.5931 , 4.7975 , 13.4102 , 0.846934,-0.0836046,-0.525083 -18.4786 , 4.62055 , 13.1454 , -0.945853,0.159948,0.282451 -21.5895 , 5.47208 , 15.7907 , 0.444191,0.306142,-0.842004 -19.4152 , 5.03231 , 14.7758 , 0.273293,0.171393,0.946539 -6.75446 , 1.89344 , 5.75105 , 0.397671,0.190691,0.897494 -18.774 , 5.06195 , 15.3281 , 0.169874,0.0094867,0.98542 -6.397 , 1.86487 , 5.81948 , -0.517204,-0.0700953,-0.852987 -4.53339 , 1.39104 , 4.42889 , -0.627601,0.100422,-0.772031 -4.46442 , 1.3951 , 4.49273 , -0.627601,0.100422,-0.772031 -6.10008 , 1.88256 , 6.09721 , -0.461161,0.73438,-0.498013 -6.05816 , 1.90506 , 6.24175 , -0.483467,0.736801,-0.472635 -5.96299 , 1.912 , 6.33886 , -0.302761,0.92111,-0.244727 -6.00546 , 1.96055 , 6.57302 , -0.0267529,0.987257,0.156872 -5.49199 , 1.83984 , 6.23876 , -0.0241603,-0.656977,0.753523 -4.65294 , 1.60921 , 5.52249 , -0.130368,0.911405,0.390315 -4.10376 , 1.46137 , 5.0704 , 0.627796,0.38897,0.674221 -3.999 , 1.45486 , 5.09624 , 0.812183,-0.0653233,0.579734 -3.95657 , 1.46802 , 5.19516 , 0.812183,-0.0653234,0.579734 -3.93042 , 1.48814 , 5.31664 , -0.513262,-0.170092,-0.841208 -4.1097 , 1.58188 , 5.70929 , -0.524902,0.263187,0.809451 -4.00782 , 1.57754 , 5.74904 , -0.524902,0.263187,0.809451 -3.75179 , 1.51504 , 5.57242 , -0.513384,0.529381,0.675421 -3.48218 , 1.44351 , 5.35623 , -0.559298,-0.297293,-0.773823 -3.33426 , 1.41654 , 5.30278 , -0.436009,-0.795723,-0.420383 -3.32067 , 1.44334 , 5.45124 , 0.343791,0.865414,0.364509 -3.28206 , 1.46022 , 5.56759 , 0.357429,0.932735,-0.0474324 -3.14603 , 1.43655 , 5.52395 , -0.614408,0.56927,-0.546292 -3.20478 , 1.49853 , 5.81704 , -0.298456,0.948519,0.106004 -3.23077 , 1.54892 , 6.07084 , 0.40508,-0.275282,-0.871854 -3.05077 , 1.50454 , 5.94575 , 0.342614,-0.804438,-0.485278 -2.90616 , 1.47465 , 5.87707 , 0.487655,-0.696346,-0.526588 -2.79041 , 1.45834 , 5.85774 , 0.303758,-0.937587,-0.169296 -2.86558 , 1.54089 , 6.25441 , 0.582935,-0.125223,0.802811 -2.60237 , 1.44467 , 5.9015 , -0.388645,-0.547153,-0.741336 -2.11393 , 1.21333 , 4.96235 , 0.386714,0.919135,-0.075124 -2.07251 , 1.22783 , 5.06382 , 0.714002,0.608582,-0.346163 -2.33906 , 1.43446 , 6.00887 , 0.119791,-0.673877,0.729068 -2.33824 , 1.48686 , 6.29096 , 0.507994,0.853926,-0.112931 -2.23503 , 1.47565 , 6.29597 , -0.412096,-0.87874,-0.240817 -2.28576 , 1.5748 , 6.79418 , 0.137608,-0.769664,0.623443 -2.2056 , 1.58539 , 6.90146 , 0.387887,-0.75512,0.528524 -2.06042 , 1.54696 , 6.7808 , -0.164925,0.835348,-0.524397 -1.98447 , 1.56279 , 6.91332 , -0.90634,0.0966377,-0.411349 -1.93392 , 1.60421 , 7.16919 , -0.577722,0.250937,-0.776703 -1.81889 , 1.59114 , 7.16635 , 0.385947,0.0416226,0.921582 -1.67729 , 1.54897 , 7.02687 , -0.716899,0.0546958,0.695028 -1.54932 , 1.51402 , 6.92326 , -0.36027,-0.28842,0.887141 -1.5098 , 1.589 , 7.34908 , -0.372268,0.76769,-0.521602 -0.992499 , 0.999001 , 4.50403 , -0.21602,0.592476,-0.776085 -0.939021 , 1.00527 , 4.57171 , -0.459663,0.588743,-0.6649 -0.860867 , 0.970777 , 4.43358 , -0.772829,0.304995,0.556518 -0.874552 , 1.13256 , 5.29088 , -0.798973,-0.462028,0.384931 -0.787262 , 1.09081 , 5.12205 , -0.172106,0.31726,0.932591 -0.716015 , 1.08544 , 5.13769 , 0.494204,0.619314,0.610092 -0.647358 , 1.1005 , 5.26002 , -0.81966,-0.564068,-0.0999198 -0.58623 , 1.2405 , 6.04955 , 0.24001,-0.285424,0.927862 -0.497297 , 1.24063 , 6.10097 , 0.60643,-0.0715885,0.791908 -0.415726 , 1.15237 , 5.67921 , 0.531062,0.778324,-0.334942 -0.334256 , 1.14304 , 5.67874 , -0.266941,0.730098,-0.629046 -0.244981 , 1.15554 , 5.80464 , -0.99255,-0.121784,0.0035577 -0.0560307 , 1.40836 , 7.27427 , -0.97399,-0.148426,-0.171214 -2.70332 , 0.146097 , -0.781886 , -0.0557938,0.231162,0.971314 -2.78121 , 0.153108 , -0.781675 , -0.0873237,0.194816,0.976945 -2.85195 , 0.160466 , -0.773133 , 0.067606,-0.217812,-0.973646 -2.94739 , 0.167832 , -0.780637 , -0.0734283,0.182328,0.980492 -3.01879 , 0.17592 , -0.767791 , 0.0887819,-0.196187,-0.976539 -3.10787 , 0.183967 , -0.764412 , -0.0768814,0.201046,0.97656 -3.18786 , 0.192771 , -0.75304 , 0.0278956,-0.203971,-0.978579 -3.30325 , 0.201385 , -0.761087 , -0.0157998,0.198808,0.979911 -3.41049 , 0.210671 , -0.760438 , -0.0828978,0.197448,0.976802 -3.50959 , 0.220565 , -0.751384 , -0.0936356,0.18168,0.97889 -3.61831 , 0.230783 , -0.744461 , 0.0600964,-0.187119,-0.980497 -3.73565 , 0.241673 , -0.739207 , 0.376362,-0.172851,-0.910205 -3.82742 , 0.254119 , -0.716473 , 0.970997,-0.0612598,-0.231112 -3.80328 , 0.267073 , -0.632182 , 0.91664,0.0247325,-0.398948 -3.84975 , 0.280196 , -0.584298 , 0.967255,0.145539,-0.207933 -3.79518 , 0.292494 , -0.488866 , 0.99361,0.102074,-0.0481734 -3.86679 , 0.30538 , -0.452624 , 0.977684,0.194714,-0.0788665 -3.79095 , 0.317722 , -0.352003 , 0.988283,0.0885737,0.124305 -3.86904 , 0.33065 , -0.31796 , -0.931482,-0.208883,-0.29784 -3.79905 , 0.342192 , -0.224329 , 0.998394,0.0514291,0.0237722 -3.81066 , 0.35388 , -0.164224 , 0.981051,0.0948346,0.168953 -3.7638 , 0.36416 , -0.0845169 , 0.972942,0.0936046,0.211239 -3.74445 , 0.375764 , -0.016216 , 0.970082,0.0198079,-0.241968 -3.76172 , 0.387246 , 0.0395253 , 0.970082,0.0198079,-0.241968 -3.79733 , 0.399418 , 0.0901042 , -0.83323,0.0655126,0.549032 -3.84156 , 0.41224 , 0.138917 , -0.736497,0.0925865,0.670075 -3.90499 , 0.425865 , 0.184148 , 0.472777,-0.155873,-0.867286 -4.03497 , 0.443196 , 0.215306 , -0.208448,0.186748,0.960039 -4.22431 , 0.463058 , 0.238391 , 0.13248,-0.200191,-0.970759 -4.47205 , 0.487276 , 0.256004 , -0.0408079,0.232205,0.971811 -4.84732 , 0.519944 , 0.259006 , -0.0535564,0.237305,0.969958 -9.51227 , 0.789049 , -0.418495 , -0.100833,0.188559,0.976872 -10.2164 , 0.859564 , -0.361922 , -0.0609236,0.193035,0.979299 -11.3063 , 0.957508 , -0.330184 , -0.0693607,0.186743,0.979957 -12.635 , 1.07741 , -0.287264 , -0.0422735,0.18906,0.981055 -14.2736 , 1.22704 , -0.227248 , -0.0755404,0.180119,0.98074 -16.0006 , 1.39337 , -0.11786 , -0.0628172,0.180762,0.981519 -23.0939 , 2.1104 , 0.521963 , 0.65612,-0.2083,-0.72534 -25.3554 , 2.37091 , 0.898345 , -0.317731,0.0327247,0.947616 -25.9356 , 2.50014 , 1.3332 , -0.353834,-0.269834,0.895539 -23.8485 , 2.39389 , 1.71154 , -0.838286,0.527523,0.137828 -24.486 , 2.67986 , 2.97582 , 0.856113,-0.175798,-0.485969 -23.7885 , 2.68555 , 3.32499 , -0.456425,-0.435192,-0.77607 -22.7211 , 2.64745 , 3.60869 , -0.526435,-0.461766,-0.71389 -22.9917 , 2.74868 , 4.03513 , -0.526435,-0.461766,-0.71389 -23.1057 , 2.83473 , 4.44953 , -0.781499,0.245055,-0.573766 -18.5787 , 2.3852 , 4.08747 , 0.473979,0.257292,0.842107 -17.5796 , 2.32598 , 4.22428 , 0.74795,-0.405901,-0.525182 -17.9734 , 2.43076 , 4.61243 , -0.689256,0.523578,0.500792 -18.3193 , 2.53189 , 5.00667 , -0.952265,-0.0342475,0.303345 -18.7825 , 2.65179 , 5.44428 , -0.784556,-0.617588,-0.0552826 -17.8219 , 2.64628 , 5.85573 , 0.74692,0.661079,0.0713093 -18.2522 , 2.76623 , 6.30988 , -0.140844,-0.985092,-0.0987765 -19.0392 , 2.9409 , 6.89687 , 0.32418,0.303395,0.896024 -20.7129 , 3.25142 , 7.81516 , -0.60207,-0.422738,-0.677351 -17.9528 , 2.91047 , 7.23036 , 0.961503,0.274783,-0.00246841 -18.0302 , 2.98571 , 7.60459 , 0.693544,0.137407,-0.707189 -18.6432 , 3.14702 , 8.19787 , -0.712245,0.364621,0.599798 -19.4689 , 3.3474 , 8.9094 , 0.716025,-0.532551,-0.45133 -18.8862 , 3.32392 , 9.04736 , -0.831412,0.551624,0.066824 -20.4811 , 3.66408 , 10.1614 , -0.78808,0.459952,0.409114 -17.1733 , 3.17151 , 9.00681 , 0.740373,0.451698,0.497812 -17.3172 , 3.26364 , 9.44056 , -0.853046,-0.342266,-0.393913 -20.3575 , 3.88087 , 11.3986 , -0.933517,-0.18282,-0.308419 -17.1916 , 3.3785 , 10.123 , -0.956742,0.269672,0.109191 -17.402 , 3.48842 , 10.6259 , -0.847998,0.391676,0.357057 -17.1317 , 3.50997 , 10.8628 , -0.635054,0.282303,0.719035 -21.2608 , 4.39877 , 13.8 , 0.199556,-0.958576,-0.203248 -20.1456 , 4.26716 , 13.596 , -0.487379,0.831974,-0.265105 -19.1764 , 4.15767 , 13.445 , 0.686042,-0.162571,-0.709166 -20.1249 , 4.44682 , 14.5794 , 0.647841,-0.556074,0.520657 -20.1101 , 4.53861 , 15.0854 , 0.741688,0.00094317,0.670745 -6.85501 , 1.70149 , 5.7615 , 0.397671,0.190691,0.897494 -6.62084 , 1.6809 , 5.75734 , 0.397671,0.190691,0.897494 -6.5193 , 1.68973 , 5.85088 , -0.397671,-0.190691,-0.897494 -6.39429 , 1.69274 , 5.92373 , -0.517204,-0.0700953,-0.852987 -4.47828 , 1.2599 , 4.45533 , -0.627602,0.100422,-0.772031 -4.40889 , 1.26584 , 4.51758 , -0.627601,0.100422,-0.772031 -4.31608 , 1.2658 , 4.55847 , -0.566382,0.349812,-0.74622 -5.68769 , 1.64654 , 5.99665 , -0.135702,0.708513,-0.692528 -5.71616 , 1.68671 , 6.20411 , -0.135702,0.708513,-0.692527 -5.39598 , 1.63368 , 6.06231 , -0.109898,-0.70748,0.698136 -5.65564 , 1.73974 , 6.51922 , -0.0724393,-0.787947,0.611468 -4.92313 , 1.56596 , 5.9105 , 0.261261,-0.905648,-0.333982 -5.02913 , 1.62993 , 6.20882 , -0.17058,-0.899594,0.402037 -4.00476 , 1.35419 , 5.18529 , -0.587835,-0.444419,-0.675975 -3.9551 , 1.36752 , 5.27634 , -0.513262,-0.170092,-0.841208 -3.84244 , 1.36044 , 5.29 , -0.497028,-0.340831,-0.797996 -3.72998 , 1.35279 , 5.30113 , -0.0255499,0.262257,0.96466 -3.55468 , 1.32319 , 5.22249 , -0.62453,0.201921,-0.754447 -3.51351 , 1.33861 , 5.32367 , 0.596714,0.800912,-0.0497346 -3.47466 , 1.35514 , 5.43298 , 0.681482,0.719457,0.134029 -3.41699 , 1.36595 , 5.51752 , 0.326414,0.799807,0.503749 -3.25362 , 1.33684 , 5.43525 , 0.318301,-0.00366908,0.947983 -3.07359 , 1.29979 , 5.31508 , -0.52435,0.233719,-0.818799 -3.08977 , 1.33953 , 5.521 , 0.753619,-0.655137,0.0534247 -3.26159 , 1.44576 , 6.02068 , 0.566666,-0.339613,-0.750702 -3.09435 , 1.41308 , 5.92165 , 0.268646,-0.361816,-0.892703 -3.01992 , 1.42006 , 5.99306 , 0.436855,0.00075809,-0.899531 -2.78158 , 1.35072 , 5.72854 , -0.418458,0.3668,0.830874 -2.66002 , 1.3336 , 5.6882 , -0.21117,0.497464,0.84139 -2.57344 , 1.33159 , 5.71694 , 0.701181,0.689986,0.179625 -2.29167 , 1.22748 , 5.28354 , 0.789695,0.215869,-0.574267 -2.12451 , 1.17778 , 5.08732 , 0.714002,0.608582,-0.346163 -2.3934 , 1.3705 , 6.0137 , 0.789885,0.246194,0.561668 -2.2688 , 1.34729 , 5.94541 , 0.119791,-0.673877,0.729068 -2.23158 , 1.37794 , 6.12475 , 0.159131,-0.951245,0.264217 -2.33256 , 1.50206 , 6.75273 , -0.243975,0.840211,-0.484274 -2.19058 , 1.47147 , 6.65347 , -0.127037,0.950071,-0.285004 -2.01605 , 1.41354 , 6.41888 , 0.422746,0.660589,-0.620409 -2.02022 , 1.48833 , 6.82507 , 0.668485,-0.18535,0.72026 -1.9475 , 1.51027 , 6.97567 , 0.100237,0.448956,0.887914 -1.88006 , 1.5407 , 7.17356 , 0.613158,-0.465187,0.638466 -1.75747 , 1.52227 , 7.13077 , -0.0994538,0.877757,-0.468669 -1.64707 , 1.51547 , 7.1434 , 0.272287,-0.354521,-0.894525 -1.50614 , 1.47143 , 6.97037 , 0.976623,0.206756,0.0588164 -1.43896 , 1.51575 , 7.24059 , -0.523433,0.598365,-0.606611 -1.34321 , 1.53049 , 7.36447 , -0.500331,0.793522,-0.346399 -1.06706 , 1.24786 , 5.95533 , -0.508381,-0.737055,0.445307 -0.838046 , 0.960624 , 4.49924 , 0.134898,-0.877726,0.459783 -0.827258 , 1.07769 , 5.14207 , -0.303771,0.171716,0.937143 -0.75277 , 1.06914 , 5.12838 , 0.218562,0.490256,0.84373 -0.683526 , 1.07737 , 5.20185 , -0.726092,-0.645972,-0.235609 -0.63514 , 1.25603 , 6.19811 , 0.313117,-0.920721,-0.232873 -0.543071 , 1.21849 , 6.03373 , 0.0672927,-0.606966,0.791874 -0.456692 , 1.1752 , 5.83828 , -0.288119,0.750678,0.594534 -0.375801 , 1.1425 , 5.70046 , 0.00506475,-0.791946,0.61057 -0.292193 , 1.1386 , 5.71855 , -0.569578,0.543891,-0.616249 -0.0984769 , 1.4476 , 7.48381 , -0.532357,-0.846293,-0.0195954 -0.0250103 , 1.34809 , 6.977 , -0.972536,0.171686,-0.157154 -2.67589 , 0.0855281 , -0.777342 , 0.0860591,-0.197663,-0.976485 -2.74637 , 0.0903461 , -0.771227 , -0.0516257,0.168593,0.984333 -2.8334 , 0.0941679 , -0.775474 , -0.0762436,0.189851,0.978848 -2.89586 , 0.100896 , -0.759595 , -0.0587431,0.191221,0.979788 -2.98353 , 0.105491 , -0.759344 , -0.0976223,0.175581,0.979613 -3.06428 , 0.111386 , -0.750959 , -0.106589,0.199493,0.974085 -3.15257 , 0.116821 , -0.745917 , -0.0369175,0.180474,0.982887 -3.25944 , 0.122198 , -0.749345 , -0.0158824,0.194876,0.980699 -3.36609 , 0.128278 , -0.74966 , -0.0834018,0.190034,0.978229 -3.45693 , 0.135821 , -0.736476 , -0.0813462,0.190867,0.97824 -3.56507 , 0.142789 , -0.730713 , -0.0715194,0.185274,0.980081 -3.68257 , 0.149241 , -0.726397 , 0.204152,-0.178082,-0.962605 -3.80102 , 0.157198 , -0.718753 , -0.773551,-0.00322233,0.633725 -3.81319 , 0.169923 , -0.652982 , 0.917744,0.135325,-0.373408 -3.79719 , 0.183925 , -0.57418 , 0.995786,-0.0170893,0.0901013 -3.87895 , 0.193276 , -0.54286 , 0.995786,-0.0170893,0.0901013 -3.80556 , 0.208635 , -0.439962 , 0.999209,-0.0329678,-0.0222281 -3.87643 , 0.218755 , -0.402739 , 0.992868,-0.106309,0.0539612 -3.79039 , 0.233109 , -0.299528 , 0.961644,-0.0637291,0.266796 -3.79422 , 0.244349 , -0.235689 , 0.965911,-0.0404682,-0.255692 -3.79732 , 0.256712 , -0.172362 , -0.97578,-0.124544,0.179841 -3.87356 , 0.267527 , -0.135513 , 0.951794,0.085368,0.294621 -3.742 , 0.279481 , -0.0273401 , 0.99569,0.0661856,0.0649686 -3.75928 , 0.290919 , 0.0282066 , -0.90388,0.0296606,0.426756 -3.77631 , 0.301494 , 0.0843398 , -0.90388,0.0296606,0.426756 -3.831 , 0.313166 , 0.129977 , -0.811976,0.0790636,0.578311 -3.85563 , 0.324716 , 0.18471 , -0.609848,0.139078,0.78022 -3.97713 , 0.337046 , 0.217085 , 0.351833,-0.170083,-0.920481 -4.12699 , 0.350257 , 0.247057 , -0.171933,0.187642,0.967073 -4.32554 , 0.366086 , 0.271842 , -0.0973133,0.187234,0.977483 -4.60383 , 0.383751 , 0.289305 , -0.0272654,0.215179,0.976194 -9.87792 , 0.558354 , -0.343881 , -0.102686,0.184877,0.977382 -10.8114 , 0.617477 , -0.301262 , -0.0557534,0.195118,0.979194 -11.8348 , 0.685102 , -0.236797 , -0.0602199,0.186439,0.980619 -13.3954 , 0.779056 , -0.188723 , -0.0491095,0.188491,0.980846 -14.9968 , 0.884881 , -0.090441 , 0.0746698,-0.182347,-0.980395 -17.3756 , 1.034 , 0.0156856 , -0.063909,0.192623,0.979189 -20.0528 , 1.21266 , 0.190096 , -0.107518,0.193654,0.975161 -22.7073 , 1.40665 , 0.457014 , -0.527189,0.142606,0.837696 -24.158 , 1.55239 , 0.826042 , 0.339739,-0.0810952,-0.937017 -25.4522 , 1.69963 , 1.24342 , -0.172867,0.502588,0.847067 -27.2366 , 1.88337 , 1.71816 , -0.475386,0.522084,0.708122 -24.0853 , 1.76951 , 2.04453 , -0.723052,-0.613589,0.31734 -24.6035 , 1.95295 , 2.89978 , 0.757651,0.603639,-0.248163 -24.8115 , 2.04373 , 3.3379 , -0.774755,-0.622807,0.108929 -22.8999 , 1.97767 , 3.54714 , -0.594709,-0.316639,-0.738959 -23.1353 , 2.06684 , 3.96968 , -0.51135,-0.359715,-0.780465 -23.47 , 2.16599 , 4.41699 , -0.428593,-0.449464,-0.783767 -22.1545 , 2.1288 , 4.60624 , -0.83584,-0.0548382,-0.546228 -18.6834 , 1.89301 , 4.35784 , -0.58302,-0.191868,-0.789478 -17.4853 , 1.84306 , 4.4434 , -0.514386,-0.0190392,0.857347 -17.9939 , 1.94655 , 4.86105 , -0.190337,0.308279,0.93206 -18.4044 , 2.04445 , 5.27657 , -0.952922,0.0233044,0.302318 -21.3908 , 2.40575 , 6.36681 , -0.808951,0.144398,-0.569866 -21.923 , 2.53145 , 6.89951 , -0.952861,0.0820563,-0.292102 -19.0819 , 2.2984 , 6.46964 , 0.961109,-0.145538,-0.234709 -19.2357 , 2.37886 , 6.86915 , 0.997933,0.0410067,-0.0494827 -17.9188 , 2.29312 , 6.79226 , -0.914415,-0.369741,-0.16473 -17.5764 , 2.31381 , 7.0098 , -0.82327,-0.530318,-0.20246 -17.4281 , 2.3561 , 7.28985 , -0.977738,-0.0352669,0.206846 -17.7654 , 2.45986 , 7.75749 , 0.548226,-0.522008,-0.653419 -19.1011 , 2.69487 , 8.65275 , -0.919167,0.375727,0.118155 -18.3957 , 2.67024 , 8.72972 , 0.668762,-0.604098,0.433386 -18.5795 , 2.76312 , 9.18437 , 0.995068,0.0186629,-0.0974218 -18.3664 , 2.80279 , 9.46565 , -0.575059,0.801167,0.165648 -18.7799 , 2.93159 , 10.0539 , 0.724976,-0.616053,-0.30804 -19.0374 , 3.04228 , 10.5863 , 0.742352,0.23209,0.628529 -17.3527 , 2.8606 , 10.0936 , -0.835276,-0.528834,0.150493 -17.8 , 2.99991 , 10.7273 , -0.727158,-0.565413,0.389293 -17.1783 , 2.97277 , 10.7656 , -0.727158,-0.565413,0.389293 -19.1335 , 3.36685 , 12.3473 , -0.424392,-0.263049,-0.866427 -18.7847 , 3.38974 , 12.578 , -0.974338,0.193338,0.115264 -18.6662 , 3.45156 , 12.9523 , 0.979075,-0.0500995,0.197238 -22.0792 , 4.14383 , 15.738 , -0.250138,0.437475,0.86374 -19.1229 , 3.70379 , 14.2078 , -0.759681,0.44142,0.477527 -19.6572 , 3.89422 , 15.0956 , -0.961703,0.247447,-0.117887 -6.8967 , 1.52878 , 5.90589 , -0.397671,-0.190691,-0.897494 -6.58372 , 1.49886 , 5.83855 , -0.397671,-0.190691,-0.897494 -4.5848 , 1.1252 , 4.37907 , 0.637331,0.028899,0.770048 -4.44953 , 1.11908 , 4.38549 , -0.415758,0.343085,-0.842282 -4.43293 , 1.13701 , 4.49265 , 0.426197,-0.355096,0.832024 -4.37865 , 1.148 , 4.56692 , 0.426197,-0.355096,0.832024 -5.82916 , 1.49794 , 6.06233 , -0.211469,0.813135,-0.542303 -4.63112 , 1.25312 , 5.07151 , 0.204493,-0.757786,0.619631 -4.5504 , 1.26013 , 5.13556 , 0.204493,-0.757786,0.619631 -4.46326 , 1.26588 , 5.19088 , 0.204493,-0.757786,0.619631 -4.2612 , 1.24165 , 5.12137 , 0.13802,0.653619,-0.744132 -4.18794 , 1.25008 , 5.18596 , 0.167767,0.800646,-0.57517 -4.24826 , 1.29249 , 5.40681 , -0.111171,-0.980109,0.164401 -4.02487 , 1.26089 , 5.29657 , 0.382317,0.477499,0.791094 -4.21949 , 1.34383 , 5.69599 , 0.647422,0.455734,-0.610861 -3.99747 , 1.3108 , 5.58052 , 0.444936,0.735633,-0.51076 -3.59289 , 1.2209 , 5.20568 , -0.584877,0.26599,-0.766269 -3.56388 , 1.23983 , 5.3231 , -0.87074,0.429712,-0.239081 -3.57648 , 1.2735 , 5.50557 , -0.970384,0.136803,-0.199098 -3.52914 , 1.28961 , 5.60777 , 0.795615,-0.586779,0.15062 -3.45208 , 1.29703 , 5.66799 , 0.669368,0.445996,0.594167 -3.19979 , 1.24228 , 5.442 , -0.204132,-0.183674,0.961558 -3.04566 , 1.21859 , 5.36145 , -0.348365,0.131537,0.928084 -3.08492 , 1.26582 , 5.61078 , -0.808683,0.414308,0.417589 -3.19951 , 1.34612 , 6.0184 , 0.566665,-0.339613,-0.750702 -3.0338 , 1.31878 , 5.91654 , 0.330317,-0.391832,-0.858696 -2.86809 , 1.28875 , 5.80171 , -0.568363,-0.248553,0.784337 -2.72833 , 1.26795 , 5.72692 , 0.345097,0.348829,-0.871336 -2.61547 , 1.25725 , 5.70263 , 0.0404802,0.240816,0.969726 -2.3644 , 1.17933 , 5.35112 , 0.664179,0.742575,-0.0863097 -2.20549 , 1.14079 , 5.18311 , 0.488558,0.853395,-0.181735 -2.40018 , 1.28096 , 5.89915 , -0.862276,-0.272831,0.426665 -2.27207 , 1.25979 , 5.82131 , 0.102452,-0.497068,0.861642 -2.23236 , 1.2871 , 5.98158 , 0.218137,-0.783633,0.581666 -2.13507 , 1.28216 , 5.98336 , 0.497124,-0.620055,0.606959 -2.05269 , 1.28604 , 6.03031 , -0.50551,0.584869,-0.63434 -1.97165 , 1.2913 , 6.08548 , -0.304021,0.663668,-0.683459 -2.1345 , 1.47306 , 7.04004 , 0.423434,-0.817441,0.390505 -1.69041 , 1.21255 , 5.73447 , -0.0813888,0.774369,0.627478 -1.91622 , 1.46725 , 7.07546 , 0.307921,-0.653906,0.691079 -1.7901 , 1.44988 , 7.01325 , -0.0353932,-0.842597,0.537381 -1.73339 , 1.49635 , 7.28613 , -0.048335,0.258321,0.964849 -1.55133 , 1.41845 , 6.91077 , -0.396171,-0.39578,0.828497 -1.48261 , 1.4582 , 7.1521 , -0.925579,-0.0113893,-0.378382 -1.40664 , 1.49756 , 7.39298 , 0.500331,-0.793522,0.346399 -1.12885 , 1.24411 , 6.08207 , 0.36608,0.928962,0.0549208 -0.860956 , 0.926236 , 4.41147 , -0.777519,0.570593,0.264365 -0.867306 , 1.06547 , 5.17156 , -0.316494,0.079971,0.945217 -0.791516 , 1.05437 , 5.13892 , -0.16745,0.280535,0.945125 -0.719763 , 1.0572 , 5.17323 , 0.53124,0.686423,0.496597 -0.668908 , 1.16955 , 5.80623 , -0.525131,-0.230287,-0.819271 -0.587228 , 1.20276 , 6.0157 , 0.503851,0.469518,-0.725043 -0.499398 , 1.18943 , 5.96807 , -0.649507,-0.332822,0.683645 -0.418085 , 1.13155 , 5.67288 , 0.195565,0.967901,-0.157866 -0.336331 , 1.12431 , 5.66185 , -0.105648,-0.684819,0.721014 -0.14653 , 1.47634 , 7.65451 , -0.84158,-0.310757,0.441784 -0.0630651 , 1.38642 , 7.18703 , -0.869169,-0.48756,0.0826514 -2.70953 , 0.0281907 , -0.760242 , -0.0347302,0.162134,0.986157 -2.78843 , 0.0309209 , -0.759195 , -0.058584,0.175466,0.982741 -2.8592 , 0.0342358 , -0.74984 , -0.0925563,0.163244,0.982235 -2.9465 , 0.0366425 , -0.750459 , -0.0812936,0.182369,0.979864 -3.01892 , 0.040406 , -0.736971 , -0.0788433,0.181933,0.980145 -3.10683 , 0.0436302 , -0.732897 , -0.0509936,0.162588,0.985375 -3.20422 , 0.0460081 , -0.73173 , -0.0192006,0.157314,0.987362 -3.31125 , 0.0486232 , -0.733083 , -0.0525114,0.188715,0.980627 -3.4015 , 0.0529596 , -0.720864 , 0.0874563,-0.183772,-0.979071 -3.51004 , 0.0564627 , -0.716138 , 0.0862363,-0.19562,-0.976881 -3.62697 , 0.0596422 , -0.713079 , -0.0601091,0.190005,0.979941 -3.74582 , 0.064112 , -0.706571 , 0.312823,-0.102033,-0.944315 -3.84673 , 0.069391 , -0.687191 , 0.985725,0.15133,-0.0737995 -3.83164 , 0.0833538 , -0.60749 , -0.969239,-0.0574668,0.239317 -3.79729 , 0.0983869 , -0.520318 , 0.998505,0.0167532,0.0520345 -3.80516 , 0.109915 , -0.455317 , 0.995396,-0.0908083,0.0306573 -3.84016 , 0.120601 , -0.402495 , 0.991843,-0.0694192,0.1069 -3.80069 , 0.134192 , -0.318256 , 0.9955,0.0827675,0.0461494 -3.79596 , 0.146261 , -0.250513 , 0.990848,0.0725398,-0.113834 -3.79882 , 0.157694 , -0.186891 , 0.990848,0.0725397,-0.113834 -3.82965 , 0.168465 , -0.133577 , 0.975764,0.105841,-0.191528 -3.7643 , 0.18245 , -0.0479635 , -0.973934,-0.125293,-0.189088 -3.76412 , 0.193291 , 0.0142284 , 0.978488,0.0422972,-0.201919 -3.77146 , 0.203716 , 0.0732715 , -0.936345,0.000496214,0.35108 -3.7979 , 0.213555 , 0.126984 , -0.869183,0.0670902,0.489919 -3.85208 , 0.223456 , 0.1736 , -0.758924,0.114025,0.641118 -3.90516 , 0.233946 , 0.221748 , 0.478818,-0.169101,-0.861474 -4.0362 , 0.242909 , 0.254361 , -0.258074,0.176766,0.949817 -4.21554 , 0.252347 , 0.281112 , 0.133322,-0.191959,-0.972305 -4.46393 , 0.262163 , 0.300998 , -0.0667169,0.177938,0.981777 -9.47087 , 0.275586 , -0.313839 , -0.129638,0.190357,0.973118 -10.1269 , 0.304001 , -0.244148 , -0.0614437,0.187927,0.980259 -11.2999 , 0.339354 , -0.212231 , -0.071076,0.183923,0.980367 -12.5142 , 0.381423 , -0.144111 , -0.046318,0.187774,0.98112 -14.2067 , 0.435838 , -0.0733802 , -0.0726621,0.180873,0.980819 -15.9892 , 0.501848 , 0.049337 , -0.0633621,0.188299,0.980066 -23.125 , 0.805117 , 0.761721 , -0.291976,0.371943,0.881141 -24.8842 , 0.920211 , 1.15911 , -0.632563,0.485972,0.603071 -25.2461 , 1.00529 , 1.58634 , 0.752503,-0.554872,-0.354763 -24.9212 , 1.0706 , 1.99945 , 0.687047,-0.603791,0.404232 -25.2283 , 1.15681 , 2.43766 , -0.921532,0.325734,-0.211369 -25.1282 , 1.22973 , 2.85716 , 0.638447,0.734225,-0.230868 -25.0703 , 1.3031 , 3.27858 , 0.801952,0.571141,-0.175135 -24.9056 , 1.37199 , 3.68761 , -0.853464,-0.502627,0.137714 -25.5668 , 1.47973 , 4.19666 , -0.510876,-0.855175,0.0876467 -25.0798 , 1.53411 , 4.56604 , 0.623814,0.759828,0.183079 -19.5991 , 1.31744 , 4.11601 , 0.720195,-0.0376885,-0.692747 -19.0883 , 1.34922 , 4.36311 , 0.457146,0.534631,0.710765 -18.5839 , 1.37843 , 4.59544 , 0.684268,0.586507,0.433344 -17.9218 , 1.39443 , 4.77819 , 0.305863,0.737882,0.601646 -20.0868 , 1.59421 , 5.59764 , 0.13291,-0.913482,0.384559 -20.96 , 1.71913 , 6.17443 , -0.403039,0.508238,0.761087 -18.8899 , 1.63561 , 5.99343 , -0.787662,0.60435,-0.119791 -18.4716 , 1.66544 , 6.21507 , -0.766807,0.608006,-0.205757 -18.9094 , 1.75997 , 6.68745 , -0.757487,0.652188,0.029418 -18.4545 , 1.78525 , 6.88889 , -0.694738,0.640683,0.3269 -18.9588 , 1.88989 , 7.40845 , -0.964347,0.236884,-0.117983 -18.5518 , 1.91786 , 7.61932 , 0.0587861,-0.987379,0.147063 -18.6358 , 1.98913 , 8.00769 , -0.0998499,-0.907286,0.408487 -18.8868 , 2.07886 , 8.47176 , -0.797387,0.49453,-0.345854 -17.7336 , 2.02942 , 8.35507 , -0.883955,0.325,0.336152 -18.2911 , 2.15089 , 8.95846 , -0.834008,0.137902,0.534241 -19.0129 , 2.29551 , 9.66723 , -0.94881,-0.0851421,0.304155 -18.9627 , 2.36046 , 10.0369 , -0.715135,-0.137047,0.685419 -17.8241 , 2.29957 , 9.85713 , 0.803919,-0.196155,0.56146 -18.1375 , 2.40612 , 10.4059 , -0.146586,-0.973569,0.175148 -17.1409 , 2.35298 , 10.2509 , -0.847182,-0.501196,0.176311 -17.8614 , 2.51304 , 11.0476 , -0.0971225,-0.581781,0.807526 -19.9978 , 2.86744 , 12.7357 , 0.742401,0.647141,-0.173346 -18.6569 , 2.76879 , 12.3651 , 0.953293,-0.00723771,0.301962 -18.9601 , 2.89061 , 13.0058 , -0.798617,0.58434,-0.144074 -18.9415 , 2.97056 , 13.4552 , 0.877167,0.251374,-0.409133 -19.3595 , 3.11708 , 14.2205 , 0.692284,0.472832,-0.545136 -18.4151 , 3.06064 , 14.0307 , -0.949582,-0.136124,0.282425 -18.5692 , 3.17087 , 14.6299 , -0.923628,0.344087,0.168867 -19.4503 , 3.40478 , 15.8177 , -0.779675,0.0583468,0.62346 -18.9675 , 3.41995 , 15.9675 , 0.816073,0.306248,-0.49014 -4.51428 , 0.995567 , 4.3994 , 0.1813,-0.23997,0.953701 -4.31901 , 0.981455 , 4.35134 , -0.0314971,-0.476338,0.878698 -4.17082 , 0.975311 , 4.33717 , 0.159601,0.210365,-0.964507 -4.70548 , 1.09879 , 4.9534 , 0.188335,0.97905,-0.0774063 -3.90176 , 0.96537 , 4.31731 , 0.532554,-0.273498,0.80099 -4.50832 , 1.10993 , 5.04002 , -0.131036,0.708306,-0.693637 -4.41494 , 1.11553 , 5.0872 , -0.131036,0.708306,-0.693637 -3.88372 , 1.02667 , 4.66229 , 0.262342,-0.962368,0.0708785 -4.06415 , 1.09027 , 4.99204 , 0.45204,-0.829145,0.328905 -4.10962 , 1.1258 , 5.18733 , -0.475971,0.701093,-0.530962 -3.85792 , 1.09289 , 5.03694 , -0.453422,0.75913,-0.467044 -3.85407 , 1.11801 , 5.17879 , 0.51556,-0.632284,-0.578286 -3.92559 , 1.16352 , 5.4229 , -0.646734,-0.593316,0.479283 -3.5806 , 1.10239 , 5.12628 , -0.808697,0.263885,-0.525714 -3.52968 , 1.11573 , 5.21085 , -0.865709,0.167836,-0.471571 -3.50119 , 1.13643 , 5.32729 , -0.810665,0.474339,-0.343256 -3.51261 , 1.16928 , 5.50945 , -0.872215,0.369342,-0.320666 -3.37383 , 1.15866 , 5.46974 , -0.393511,-0.567598,0.723175 -3.39331 , 1.19595 , 5.67791 , 0.7393,-0.629659,0.238675 -3.31567 , 1.20407 , 5.73577 , -0.22047,0.360169,-0.906461 -3.01481 , 1.13807 , 5.40756 , 0.748847,-0.635531,-0.187958 -3.04171 , 1.18071 , 5.64025 , 0.546847,-0.293999,0.783915 -3.13526 , 1.24988 , 6.01469 , 0.0811899,0.00700727,-0.996674 -2.97978 , 1.23045 , 5.92773 , 0.53505,-0.441007,-0.720579 -2.78888 , 1.19508 , 5.75704 , -0.345383,0.217034,-0.913021 -2.83793 , 1.25455 , 6.08215 , 0.184923,0.768856,0.612098 -2.38579 , 1.10388 , 5.30171 , -0.54086,-0.811331,0.22184 -2.28263 , 1.09559 , 5.2702 , 0.757741,0.140002,-0.63736 -2.43395 , 1.20612 , 5.86749 , -0.83766,-0.544014,0.04872 -2.37284 , 1.22251 , 5.96469 , -0.905222,-0.268261,0.329561 -2.37451 , 1.27218 , 6.24675 , -0.662035,-0.686912,0.299768 -2.04116 , 1.14298 , 5.56992 , -0.591936,-0.371506,-0.715259 -1.9489 , 1.13929 , 5.55843 , 0.135467,-0.987037,0.0860652 -2.00454 , 1.2255 , 6.03556 , 0.422534,-0.784003,0.454757 -1.94693 , 1.24868 , 6.17477 , 0.446334,-0.622424,0.642942 -1.73612 , 1.16705 , 5.74199 , -0.574119,-0.543818,-0.612086 -1.93647 , 1.38365 , 6.92964 , -0.383586,0.859293,0.338345 -1.84443 , 1.39611 , 7.01145 , -0.173285,0.841478,-0.511748 -1.70852 , 1.37088 , 6.88954 , 0.168335,0.223082,-0.960155 -1.5971 , 1.36523 , 6.871 , 0.867951,0.418031,0.268162 -1.54352 , 1.41854 , 7.1806 , -0.625254,-0.634252,-0.454733 -1.44145 , 1.4281 , 7.24659 , 0.118016,-0.382314,0.916465 -1.17357 , 1.21304 , 6.08193 , -0.401555,-0.88226,-0.245707 -1.22129 , 1.42983 , 7.28572 , -0.675449,0.593011,-0.4383 -0.915516 , 1.06541 , 5.28967 , -0.778442,-0.417953,0.468341 -0.827622 , 1.0361 , 5.13957 , -0.176825,0.133459,0.975152 -0.755787 , 1.03706 , 5.15466 , -0.479135,-0.575841,-0.662448 -0.686526 , 1.05034 , 5.23726 , -0.756411,-0.600619,-0.259035 -0.638409 , 1.23303 , 6.26338 , -0.885503,0.000897233,0.464633 -0.54255 , 1.17402 , 5.9504 , -0.778238,-0.399112,0.484826 -0.456446 , 1.16212 , 5.89148 , 0.945026,0.0495823,-0.323215 -0.378325 , 1.11046 , 5.61486 , 0.162031,-0.509916,0.844826 -0.293014 , 1.12217 , 5.69097 , -0.701502,0.338241,-0.627286 -0.0980855 , 1.43756 , 7.48564 , -0.720129,-0.612713,-0.325573 -0.02431 , 1.34522 , 6.97749 , -0.972536,0.171686,-0.157153 -2.67942 , -0.0307373 , -0.756064 , -0.0636789,0.168806,0.98359 -2.75769 , -0.0311035 , -0.755495 , -0.0778377,0.161134,0.983858 -2.82806 , -0.0299113 , -0.746718 , -0.112975,0.201562,0.972939 -2.89927 , -0.0285168 , -0.735972 , 0.055329,-0.13927,-0.988708 -2.98675 , -0.0289602 , -0.734906 , 0.0793706,-0.165716,-0.982974 -3.06754 , -0.0271308 , -0.725805 , -0.0703345,0.126663,0.989449 -3.17298 , -0.0290735 , -0.730771 , -0.0531814,0.156676,0.986217 -3.25439 , -0.0263826 , -0.716782 , -0.0405857,0.203407,0.978253 -3.37001 , -0.0286177 , -0.721129 , -0.0718843,0.204168,0.976293 -3.46065 , -0.0260918 , -0.707032 , -0.0899862,0.197207,0.976223 -3.56934 , -0.025329 , -0.700135 , -0.0744766,0.193077,0.978353 -3.67876 , -0.0240562 , -0.689906 , -0.0540417,0.193134,0.979683 -3.80614 , -0.0242827 , -0.68571 , -0.571523,0.121206,0.811585 -3.86228 , -0.0165543 , -0.642158 , 0.922337,-0.0449031,-0.383768 -3.82023 , -0.000577901 , -0.549503 , 0.995248,0.0754431,0.0615673 -3.85694 , 0.00870437 , -0.496339 , -0.970352,-0.211235,0.117463 -3.81021 , 0.0252292 , -0.406622 , 0.993498,0.113683,-0.00622224 -4.1207 , 0.013195 , -0.468555 , 0.524422,0.684215,0.506786 -3.80359 , 0.0489187 , -0.269898 , 0.984906,0.168995,0.0374367 -3.81714 , 0.0601759 , -0.209552 , 0.953403,0.00220094,-0.301692 -3.81124 , 0.0714203 , -0.142121 , -0.924024,-0.0251162,0.381509 -3.89795 , 0.0770874 , -0.107441 , 0.941342,0.124006,0.313845 -3.76509 , 0.0964794 , -0.000427576 , 0.99533,0.0601222,0.0755224 -3.77363 , 0.107641 , 0.058539 , 0.968384,-0.0266014,-0.248041 -3.78097 , 0.118067 , 0.117582 , -0.919033,0.0352776,0.392598 -3.82602 , 0.125502 , 0.166748 , -0.829774,0.049676,0.555884 -3.85986 , 0.13532 , 0.219063 , -0.639869,0.122966,0.758583 -3.97226 , 0.141186 , 0.254995 , -0.351219,0.164553,0.92172 -4.13161 , 0.145574 , 0.284172 , 0.162869,-0.192238,-0.967739 -4.34062 , 0.148409 , 0.309484 , -0.100281,0.182242,0.978127 -4.65896 , 0.149044 , 0.323086 , -0.0438262,0.169837,0.984497 -9.3033 , 0.0139811 , -0.321205 , -0.127617,0.194657,0.972534 -9.87089 , 0.0248008 , -0.244359 , -0.112973,0.180232,0.977115 -10.8054 , 0.028935 , -0.19202 , -0.0477464,0.179581,0.982584 -11.8506 , 0.0371484 , -0.11929 , -0.0643175,0.184067,0.980807 -13.3642 , 0.0419688 , -0.0505872 , -0.0465345,0.187625,0.981138 -15.0868 , 0.0521343 , 0.0556124 , -0.0756429,0.185403,0.979747 -17.2 , 0.0682561 , 0.201283 , -0.0649635,0.192628,0.979119 -20.1502 , 0.0869337 , 0.391774 , -0.134691,0.195818,0.971346 -22.8588 , 0.126291 , 0.687047 , 0.383988,-0.43697,-0.813394 -23.5825 , 0.190789 , 1.07249 , -0.474083,0.18676,0.860445 -24.1887 , 0.259662 , 1.48057 , -0.485785,0.337024,0.806491 -24.417 , 0.331322 , 1.89624 , -0.751907,0.131065,0.64611 -27.1982 , 0.5788 , 3.37825 , 0.460546,0.881176,0.106897 -27.1141 , 0.659187 , 3.83252 , -0.484739,-0.713219,0.506307 -25.7305 , 0.718382 , 4.12651 , -0.403043,-0.906771,0.123787 -27.6631 , 0.833615 , 4.83827 , 0.618257,0.747505,-0.242887 -27.088 , 0.905032 , 5.22499 , 0.335649,0.829347,0.446681 -19.3094 , 0.784713 , 4.33263 , 0.605899,0.474395,0.638619 -19.2195 , 0.841226 , 4.6497 , 0.793096,0.333032,0.509988 -19.0355 , 0.894668 , 4.94596 , 0.793096,0.333032,0.509988 -18.8466 , 0.946183 , 5.23715 , 0.736039,0.411362,0.537613 -19.0127 , 1.01209 , 5.61157 , 0.724766,-0.389336,0.568447 -18.2525 , 1.03994 , 5.74949 , -0.568158,0.40416,-0.716834 -18.0328 , 1.0876 , 6.01572 , -0.568158,0.40416,-0.716834 -18.1139 , 1.14903 , 6.36837 , -0.49198,0.62745,-0.603541 -20.9365 , 1.35402 , 7.60876 , 0.903074,-0.302097,0.305278 -19.002 , 1.3165 , 7.34042 , -0.937004,-0.239959,-0.253858 -25.3135 , 1.74894 , 9.97081 , -0.921808,0.209589,-0.326103 -23.8456 , 1.74387 , 9.8997 , -0.868104,-0.34266,0.359136 -17.6412 , 1.41892 , 7.88516 , 0.600958,0.549568,0.580366 -17.9221 , 1.49897 , 8.34851 , -0.924682,0.367316,-0.10021 -18.1103 , 1.57489 , 8.78747 , 0.852865,-0.111845,-0.510012 -18.125 , 1.64108 , 9.15969 , -0.906374,-0.212658,0.365051 -18.8319 , 1.76294 , 9.8727 , 0.796411,0.12442,-0.591819 -19.3412 , 1.87449 , 10.5226 , 0.797241,0.276414,-0.536659 -19.8671 , 1.99407 , 11.2108 , 0.660591,0.748695,0.0554587 -19.614 , 2.0461 , 11.5039 , 0.813635,0.5455,0.201064 -19.8853 , 2.14819 , 12.0924 , 0.592705,-0.465763,0.657089 -19.6526 , 2.20413 , 12.4033 , 0.0106916,-0.657465,0.753409 -18.5926 , 2.17399 , 12.2022 , 0.118661,-0.456337,0.881859 -18.6686 , 2.25921 , 12.6887 , -0.929639,-0.359779,0.0795629 -19.8182 , 2.468 , 13.904 , -0.801534,-0.574618,-0.165399 -18.5485 , 2.40568 , 13.5151 , 0.793069,0.464394,-0.394184 -19.5937 , 2.61482 , 14.7338 , -0.933809,-0.335196,0.12508 -19.2534 , 2.66156 , 14.9884 , 0.813832,0.570679,-0.109559 -20.1136 , 2.86467 , 16.1648 , 0.856911,0.423302,-0.29414 -4.63417 , 0.857225 , 4.34182 , -0.072481,-0.301815,0.950607 -4.5911 , 0.872517 , 4.42489 , 0.0853537,-0.371547,0.924482 -4.42482 , 0.869473 , 4.40404 , 0.0763918,0.270625,-0.959649 -4.13457 , 0.846639 , 4.26629 , 0.227707,-0.492776,0.839834 -4.19315 , 0.87569 , 4.43585 , 0.365215,-0.83975,0.401794 -3.91688 , 0.852546 , 4.29304 , -0.634373,-0.261529,-0.727443 -4.1768 , 0.916766 , 4.66506 , -0.536762,0.707688,-0.459416 -3.84133 , 0.879889 , 4.45114 , -0.893739,-0.275249,-0.354215 -3.82158 , 0.898159 , 4.55111 , 0.995118,0.0515598,0.0841535 -3.75231 , 0.906626 , 4.60036 , 0.995118,0.0515598,0.0841535 -3.90509 , 0.959496 , 4.90108 , -0.895364,0.435309,-0.0939677 -4.04119 , 1.01103 , 5.20075 , 0.615103,-0.788403,0.00825987 -3.8168 , 0.990525 , 5.07693 , -0.880902,0.308802,-0.358682 -3.89188 , 1.03276 , 5.31968 , 0.745983,-0.551592,-0.37317 -3.66571 , 1.0095 , 5.18042 , -0.229152,0.209883,-0.950494 -3.53289 , 1.00547 , 5.15427 , -0.448051,0.215665,-0.867605 -3.52857 , 1.03204 , 5.30254 , 0.759257,-0.490006,0.428278 -3.50238 , 1.05392 , 5.42743 , 0.68372,-0.594359,0.423395 -3.30978 , 1.0331 , 5.30461 , -0.00234733,-0.430813,0.902438 -3.18632 , 1.02855 , 5.27701 , 0.062987,-0.537096,0.841166 -3.16741 , 1.05349 , 5.41521 , -0.856456,-0.476005,-0.199756 -3.09465 , 1.0627 , 5.46897 , 0.567729,0.0851249,0.818802 -2.89493 , 1.03351 , 5.29725 , 0.162709,-0.563537,0.809909 -2.88424 , 1.06243 , 5.45942 , -0.6549,0.74705,-0.114116 -2.8463 , 1.08394 , 5.57858 , -0.582605,0.424073,-0.693349 -2.79629 , 1.10165 , 5.68022 , 0.465631,-0.296399,0.833868 -2.68049 , 1.09624 , 5.64753 , 0.651763,-0.101068,0.751658 -2.4439 , 1.04422 , 5.34192 , 0.54086,0.811331,-0.22184 -2.4022 , 1.06458 , 5.45612 , 0.349296,0.732559,0.584251 -2.64892 , 1.20855 , 6.28311 , 0.0596054,0.918688,0.39046 -2.55283 , 1.21376 , 6.30993 , -0.687143,-0.582835,0.433749 -2.3594 , 1.17321 , 6.07577 , -0.882529,-0.457647,-0.108171 -2.07814 , 1.08385 , 5.55704 , -0.591936,-0.371506,-0.715259 -1.95844 , 1.06745 , 5.46158 , 0.0731296,0.188866,0.979276 -1.94386 , 1.10858 , 5.69317 , 0.611159,0.614244,0.499188 -1.96332 , 1.17406 , 6.06765 , 0.49214,-0.753298,0.436281 -1.79819 , 1.1302 , 5.81589 , 0.240739,0.818367,0.521843 -1.70606 , 1.12948 , 5.80867 , 0.106909,0.802174,0.587441 -1.64453 , 1.14987 , 5.92468 , -0.0813889,0.774369,0.627478 -1.63424 , 1.21658 , 6.29996 , -0.173907,0.97134,-0.162035 -1.56749 , 1.24402 , 6.45387 , 0.512646,-0.683735,0.519327 -1.44679 , 1.22414 , 6.33537 , -0.220719,0.972908,0.0687957 -1.297 , 1.16555 , 6.0005 , -0.338174,-0.788927,0.513062 -1.21881 , 1.17973 , 6.08183 , -0.468975,-0.845408,-0.255632 -1.30385 , 1.42983 , 7.50094 , 0.566931,0.394096,0.723379 -1.02079 , 1.15358 , 5.92682 , -0.501762,-0.692167,0.518786 -0.865749 , 1.01926 , 5.15968 , -0.245087,0.157085,0.956691 -0.791627 , 1.01688 , 5.14575 , 0.0928771,0.496234,0.863207 -0.722543 , 1.03023 , 5.21879 , -0.646667,-0.644474,-0.408014 -0.668499 , 1.13319 , 5.8027 , -0.535743,-0.0505899,-0.842864 -0.587488 , 1.16725 , 5.99177 , 0.643042,0.460385,-0.611999 -0.499309 , 1.14381 , 5.8544 , -0.348128,0.417551,0.83932 -0.414703 , 1.13342 , 5.79443 , -0.840465,-0.295513,0.454192 -0.335964 , 1.1092 , 5.65444 , 0.0155961,-0.718561,0.695289 -0.248522 , 1.12737 , 5.75916 , 0.876891,-0.0935193,0.471505 -0.0698393 , 1.3615 , 7.08 , -0.691891,-0.655356,0.302979 -2.71747 , -0.0905612 , -0.74568 , -0.069526,0.189187,0.979477 -2.78745 , -0.0915137 , -0.737579 , -0.075398,0.188964,0.979085 -2.86697 , -0.0935541 , -0.733455 , -0.0596205,0.163433,0.984751 -2.95382 , -0.0970939 , -0.732866 , -0.0715366,0.184229,0.980277 -3.03399 , -0.0983607 , -0.724244 , -0.0789417,0.171478,0.98202 -3.11496 , -0.0993593 , -0.71336 , -0.059822,0.173992,0.982928 -3.20347 , -0.100796 , -0.705723 , -0.0913779,0.187206,0.978061 -3.30239 , -0.10325 , -0.700677 , -0.0376405,0.221026,0.974541 -3.40975 , -0.106181 , -0.697979 , -0.0874017,0.195112,0.976879 -3.50057 , -0.106483 , -0.682098 , -0.0894753,0.207194,0.9742 -3.61783 , -0.110505 , -0.677903 , -0.059652,0.190096,0.979952 -3.73603 , -0.113021 , -0.670379 , -0.219658,0.161249,0.962159 -3.86355 , -0.115943 , -0.663816 , 0.981072,0.141636,-0.132047 -3.83125 , -0.100037 , -0.575043 , -0.925521,0.136926,0.353075 -3.81429 , -0.0858422 , -0.49646 , 0.993466,0.0374225,0.107818 -3.91368 , -0.0842662 , -0.471423 , -0.962192,-0.150907,0.226745 -3.81168 , -0.0617541 , -0.358087 , -0.990201,-0.0570043,-0.127482 -3.86402 , -0.0556856 , -0.311873 , -0.938354,-0.297163,-0.176594 -3.81362 , -0.0388934 , -0.225266 , 0.998111,0.0560154,-0.0252231 -3.80793 , -0.0266536 , -0.157838 , 0.995599,0.0790136,0.050402 -3.84753 , -0.0196274 , -0.107034 , 0.981707,0.0784948,-0.173465 -3.77338 , -0.00180957 , -0.0185214 , -0.976925,-0.0767963,-0.1993 -3.77221 , 0.00929079 , 0.0437443 , 0.98681,0.0111655,-0.161497 -3.78051 , 0.0195229 , 0.103006 , -0.949448,0.0122783,0.313683 -3.80673 , 0.0284097 , 0.156915 , -0.894494,0.0345117,0.445746 -3.86092 , 0.0343115 , 0.204538 , -0.782486,0.0684921,0.61889 -3.89423 , 0.042402 , 0.258026 , -0.513912,0.139652,0.8464 -4.035 , 0.0434723 , 0.289549 , 0.273764,-0.16574,-0.947409 -4.20531 , 0.0423138 , 0.320281 , -0.123552,0.190214,0.973937 -4.47308 , 0.0366071 , 0.339154 , 0.0521816,-0.170571,-0.983963 -9.42876 , -0.232196 , -0.218125 , -0.112003,0.191473,0.975086 -10.2337 , -0.250588 , -0.160579 , -0.0568652,0.184694,0.98115 -11.3269 , -0.279075 , -0.106322 , -0.0630703,0.189624,0.979829 -12.5304 , -0.306098 , -0.0245369 , -0.0492551,0.182531,0.981965 -14.1927 , -0.348355 , 0.065989 , -0.0687067,0.185391,0.98026 -15.9748 , -0.385664 , 0.206868 , -0.0711275,0.190646,0.979079 -22.829 , -0.487116 , 0.992553 , -0.878617,-0.128242,-0.459985 -22.8584 , -0.422002 , 1.37722 , -0.771118,-0.592989,-0.231821 -22.7011 , -0.350505 , 1.75691 , 0.935513,0.210304,0.283881 -22.6574 , -0.282871 , 2.13719 , -0.673836,0.738687,-0.0169541 -22.6168 , -0.215151 , 2.51667 , 0.85287,0.522068,0.0076092 -22.5904 , -0.148671 , 2.89687 , -0.856148,-0.5165,0.0154749 -22.5661 , -0.0816049 , 3.27739 , -0.860011,-0.509779,0.0225016 -22.5355 , -0.0151064 , 3.65779 , -0.879036,-0.469078,-0.0852177 -22.5071 , 0.0520448 , 4.03881 , -0.948239,-0.315663,-0.0346482 -22.4928 , 0.119434 , 4.42268 , -0.95234,-0.304459,-0.018785 -22.4812 , 0.186596 , 4.80876 , -0.950205,0.199328,-0.239539 -22.4626 , 0.254531 , 5.19517 , -0.950205,0.199328,-0.239539 -22.4568 , 0.322364 , 5.58625 , 0.996965,0.0605518,0.0489275 -18.7555 , 0.37436 , 5.14797 , -0.922153,0.365677,-0.126149 -18.7209 , 0.431932 , 5.47036 , -0.847874,0.264215,-0.459674 -18.3514 , 0.485358 , 5.70696 , -0.587594,-0.0392716,-0.808202 -18.1619 , 0.540174 , 5.98308 , -0.653673,0.26923,-0.707267 -20.0756 , 0.629872 , 6.8836 , 0.389421,-0.80518,0.447254 -20.3241 , 0.698868 , 7.33089 , -0.0402977,-0.191441,0.980676 -20.8372 , 0.776123 , 7.88082 , -0.916312,-0.222417,0.333022 -18.6424 , 0.785436 , 7.49164 , -0.651621,-0.181565,-0.736495 -25.6495 , 1.05868 , 10.4747 , 0.991823,-0.0594861,-0.11291 -18.4814 , 0.903049 , 8.14002 , -0.843093,-0.529664,-0.0930012 -17.7545 , 0.938723 , 8.19838 , 0.794509,0.493928,-0.353256 -17.8282 , 1.00198 , 8.58131 , -0.849405,-0.355339,0.390186 -18.3764 , 1.08866 , 9.18837 , 0.557256,0.817893,0.143238 -18.9253 , 1.18025 , 9.82479 , 0.030488,-0.419647,0.907175 -18.3037 , 1.21599 , 9.90795 , 0.084701,0.547662,0.832401 -17.8357 , 1.25652 , 10.0508 , 0.323842,0.209895,0.922535 -23.0922 , 1.63487 , 13.2828 , -0.0637412,-0.982999,0.172195 -19.5712 , 1.50081 , 11.8032 , -0.572309,-0.796339,-0.195721 -19.6974 , 1.58526 , 12.3155 , 0.647562,0.695478,0.311406 -20.8169 , 1.74262 , 13.4496 , -0.00290135,-0.47989,0.877324 -20.4959 , 1.80296 , 13.7318 , -0.483469,-0.735167,-0.475171 -19.3871 , 1.79966 , 13.4903 , 0.609262,0.765808,-0.205764 -19.6351 , 1.90202 , 14.1333 , -0.916525,-0.39836,0.0359362 -19.8002 , 2.00204 , 14.7421 , 0.7517,0.658963,0.0267467 -19.7663 , 2.08732 , 15.2242 , -0.916809,-0.321787,0.236463 -20.0522 , 2.20547 , 15.9635 , 0.789901,0.451652,-0.41481 -4.27877 , 0.701521 , 4.13414 , 0.123286,-0.276732,0.953006 -4.20881 , 0.712678 , 4.18541 , -0.438363,-0.206168,-0.874833 -4.19034 , 0.729788 , 4.28131 , -0.438363,-0.206168,-0.874833 -4.05195 , 0.732384 , 4.27031 , -0.414982,-0.216611,-0.883669 -3.99471 , 0.745378 , 4.33044 , 0.57276,0.264212,0.775975 -3.90699 , 0.753659 , 4.36181 , -0.746242,-0.380387,-0.546287 -3.86956 , 0.768812 , 4.44081 , 0.857607,0.346954,0.379649 -3.82996 , 0.783401 , 4.51958 , -0.89279,-0.319378,-0.317684 -3.82226 , 0.803854 , 4.63434 , -0.925836,-0.376909,-0.0276976 -3.82438 , 0.826165 , 4.76473 , 0.984922,-0.0870348,-0.149513 -3.83649 , 0.851462 , 4.91132 , -0.831446,0.330084,-0.446925 -3.82463 , 0.87303 , 5.03662 , -0.824645,0.371893,-0.426211 -3.89025 , 0.910076 , 5.26329 , 0.643176,-0.694782,-0.321872 -3.7181 , 0.904869 , 5.19459 , 0.13844,0.943067,0.302422 -3.56119 , 0.900386 , 5.13746 , 0.274135,0.0231387,0.961413 -3.48805 , 0.911368 , 5.18914 , -0.679859,0.140792,-0.719701 -3.43146 , 0.926188 , 5.26391 , -0.528313,0.0551475,-0.847257 -3.37844 , 0.942725 , 5.34617 , -0.0938157,0.453267,-0.886424 -3.25385 , 0.942831 , 5.31939 , -0.0802684,-0.297691,0.951282 -3.09439 , 0.932436 , 5.23071 , -0.0563056,-0.269345,0.961396 -3.20798 , 0.990302 , 5.58977 , -0.368763,0.197449,-0.90831 -2.94027 , 0.950928 , 5.30797 , 0.337463,0.941282,0.0103861 -2.83148 , 0.951677 , 5.28798 , 0.161643,0.968822,-0.187766 -2.75115 , 0.95996 , 5.31806 , 0.0534568,-0.623106,0.780308 -2.66646 , 0.96617 , 5.33799 , -0.0149865,-0.799999,0.599815 -2.59055 , 0.974651 , 5.37431 , 0.360442,0.771556,0.524197 -2.50512 , 0.980395 , 5.39112 , 0.224671,0.566644,0.79274 -2.61104 , 1.05487 , 5.84134 , -0.533935,0.0531273,-0.843855 -2.6674 , 1.11816 , 6.21393 , -0.698652,-0.714979,-0.0262528 -2.62337 , 1.1466 , 6.36941 , 0.0596054,0.918688,0.39046 -2.3196 , 1.06679 , 5.84952 , -0.639025,0.101613,0.762445 -2.12408 , 1.0252 , 5.57237 , 0.715644,-0.411905,-0.564081 -2.01539 , 1.01918 , 5.51475 , 0.0731296,0.188866,0.979276 -1.95417 , 1.03546 , 5.59615 , -0.797402,0.0777982,-0.598413 -1.89329 , 1.05345 , 5.68612 , 0.644378,0.559488,0.521296 -1.86698 , 1.09248 , 5.90878 , 0.272493,0.0107826,0.962097 -1.75333 , 1.08243 , 5.8258 , -0.426129,-0.809971,-0.40294 -1.67993 , 1.09691 , 5.89405 , -0.114244,-0.00442866,0.993443 -1.64969 , 1.14452 , 6.16351 , 0.105229,-0.926744,0.360655 -1.69993 , 1.2646 , 6.86849 , 0.304671,-0.750786,-0.586085 -1.63835 , 1.30906 , 7.11063 , 0.643919,0.164779,0.747138 -1.34463 , 1.13136 , 6.02935 , 0.242275,-0.62139,0.745102 -1.26586 , 1.14684 , 6.10109 , 0.468975,0.845408,0.255632 -1.17692 , 1.1534 , 6.12269 , -0.468975,-0.845408,-0.255632 -1.24045 , 1.38456 , 7.46533 , -0.675449,0.593011,-0.4383 -0.904167 , 0.999259 , 5.18011 , 0.339501,-0.108103,-0.934373 -0.828504 , 0.998378 , 5.15638 , -0.130131,0.265245,0.955359 -0.756896 , 1.00638 , 5.19045 , 0.515059,0.622665,0.589068 -0.771814 , 1.35883 , 7.22201 , 0.290429,0.954234,0.0713266 -0.631518 , 1.15552 , 6.02329 , -0.377848,-0.662125,0.647164 -0.542304 , 1.1396 , 5.91591 , 0.580238,0.606745,-0.54331 -0.455939 , 1.13894 , 5.89565 , -0.168024,0.262982,0.950057 -0.377273 , 1.09348 , 5.6179 , 0.366057,-0.131606,0.921239 -0.293852 , 1.10779 , 5.68349 , -0.712456,0.509331,-0.482688 -0.0955358 , 1.43513 , 7.5266 , 0.532357,0.846293,0.0195953 -0.0243344 , 1.34014 , 6.96826 , -0.965549,0.199249,-0.167379 -2.74532 , -0.150629 , -0.728394 , -0.0634094,0.195086,0.978734 -2.81574 , -0.153524 , -0.719 , -0.0551851,0.185901,0.981018 -2.9032 , -0.159511 , -0.719355 , -0.0789781,0.193474,0.977922 -2.97429 , -0.161721 , -0.70585 , -0.0725231,0.229353,0.970638 -3.07106 , -0.168115 , -0.707167 , -0.0661972,0.20157,0.977235 -3.16016 , -0.171955 , -0.700279 , 0.0856433,-0.222454,-0.971174 -3.24115 , -0.175277 , -0.685375 , -0.070386,0.191536,0.978958 -3.34793 , -0.181458 , -0.683835 , -0.0421378,0.216982,0.975266 -3.43818 , -0.184989 , -0.669017 , -0.0789707,0.199994,0.97661 -3.55486 , -0.192282 , -0.666078 , -0.0511312,0.198195,0.978828 -3.67249 , -0.19807 , -0.65981 , -0.0439294,0.184172,0.981912 -3.79922 , -0.205238 , -0.654404 , -0.313169,0.043827,0.948685 -3.90106 , -0.207953 , -0.631915 , -0.975575,-0.1814,-0.123886 -3.84054 , -0.186661 , -0.530633 , 0.995485,0.0867205,0.0385977 -3.83217 , -0.173382 , -0.456342 , 0.995477,-0.0136537,0.0940159 -3.82263 , -0.160972 , -0.382558 , 0.993682,0.0971095,-0.0562638 -3.96735 , -0.168697 , -0.373526 , 0.975632,-0.171718,0.136586 -3.81596 , -0.137151 , -0.245249 , 0.998224,0.0526553,0.0278566 -3.82073 , -0.126038 , -0.1809 , -0.917482,-0.0440842,0.395327 -3.83282 , -0.116403 , -0.119988 , -0.917482,-0.0440841,0.395327 -3.90982 , -0.114753 , -0.0808066 , 0.978891,0.020247,0.203379 -3.76813 , -0.0874626 , 0.0283899 , 0.989425,0.0893307,0.114276 -3.78686 , -0.0782918 , 0.0848647 , 0.970393,-0.0090196,-0.241363 -3.78449 , -0.0679498 , 0.14711 , -0.953892,-0.0127163,0.29988 -3.82907 , -0.0624169 , 0.19667 , -0.849959,0.0416558,0.525199 -3.87259 , -0.0563832 , 0.247374 , -0.709745,0.117019,0.694672 -3.95535 , -0.0541715 , 0.291072 , 0.401013,-0.179047,-0.898405 -4.10516 , -0.0582612 , 0.323714 , 0.167513,-0.188432,-0.967695 -4.31358 , -0.0665204 , 0.350563 , -0.0955918,0.189735,0.977171 -4.65111 , -0.0864475 , 0.363968 , -0.0253723,0.169092,0.985274 -9.24634 , -0.483417 , -0.228634 , -0.140325,0.196712,0.970368 -9.74426 , -0.499739 , -0.137898 , -0.107238,0.197628,0.974394 -10.7266 , -0.553309 , -0.0836611 , -0.0544341,0.190434,0.98019 -11.7387 , -0.603716 , 0.00128012 , -0.0624104,0.190477,0.979706 -13.2793 , -0.689385 , 0.0814312 , -0.045887,0.183073,0.982028 -14.8888 , -0.771515 , 0.210431 , -0.0731835,0.189928,0.979067 -16.6889 , -0.856373 , 0.386828 , -0.0724053,0.186993,0.979689 -20.1817 , -1.04712 , 0.586 , -0.248811,0.154566,0.956139 -23.0443 , -1.17676 , 0.909228 , 0.839349,0.355263,-0.411439 -23.6261 , -1.14651 , 1.30447 , 0.610611,0.304282,-0.731141 -23.931 , -1.09663 , 1.71186 , 0.556786,-0.128453,-0.820664 -24.4196 , -1.05466 , 2.13843 , 0.56697,-0.0906338,-0.818737 -27.4504 , -1.06667 , 3.20959 , 0.0792345,-0.102847,0.991536 -23.039 , -0.777177 , 3.24522 , 0.979413,0.19884,0.0348307 -22.8718 , -0.702552 , 3.61813 , -0.909338,-0.108007,-0.401795 -22.9163 , -0.637645 , 4.01465 , -0.880697,0.0300714,-0.472725 -22.3015 , -0.546873 , 4.3155 , -0.958655,0.106869,-0.263741 -28.7293 , -0.709959 , 5.77923 , -0.943066,-0.293562,0.156358 -28.2734 , -0.610539 , 6.19512 , 0.95189,0.19862,-0.233359 -24.9119 , -0.426075 , 6.00624 , 0.0610682,0.740556,0.669214 -18.461 , -0.180126 , 5.01588 , 0.765778,-0.0903157,-0.636732 -18.5175 , -0.126035 , 5.35437 , -0.650493,-0.309636,0.69353 -19.0814 , -0.0813305 , 5.82827 , -0.743404,0.00935501,0.668778 -19.489 , -0.0303091 , 6.28284 , 0.724087,-0.0392965,-0.688588 -20.5671 , 0.0149012 , 6.95323 , 0.543951,0.379506,-0.748393 -20.4437 , 0.0808712 , 7.29106 , 0.593338,0.200691,-0.779534 -19.1479 , 0.154677 , 7.23839 , -0.710906,-0.405031,-0.574946 -19.2377 , 0.215204 , 7.62746 , 0.690151,0.382366,0.6144 -18.4651 , 0.278688 , 7.70451 , 0.653024,0.467036,0.596186 -18.6002 , 0.338812 , 8.1103 , 0.653024,0.467036,0.596186 -18.2817 , 0.399201 , 8.33997 , 0.757188,0.65295,0.0179652 -19.0802 , 0.468055 , 9.04361 , -0.824508,-0.367007,0.430689 -11.7852 , 0.439606 , 6.13173 , -0.0135141,0.480982,0.876626 -19.2545 , 0.601235 , 9.89416 , -0.879485,-0.471974,-0.0612155 -18.4616 , 0.653959 , 9.90007 , -0.231543,-0.640025,-0.732637 -17.9065 , 0.706302 , 10.0009 , 0.251784,0.628578,0.735863 -17.5368 , 0.761382 , 10.1843 , 0.57916,0.25763,0.773434 -21.974 , 0.964443 , 13.0463 , -0.354153,0.754857,-0.552056 -21.6764 , 1.03751 , 13.3621 , -0.48496,-0.770839,0.413064 -19.3042 , 1.02941 , 12.4187 , -0.94724,-0.241488,0.210758 -21.1855 , 1.18683 , 14.0478 , -0.754983,-0.474168,-0.452953 -19.7679 , 1.20542 , 13.6239 , -0.785039,-0.27842,0.55335 -21.6054 , 1.38178 , 15.3479 , 0.729692,-0.496505,0.470141 -21.0668 , 1.44291 , 15.5057 , -0.162817,-0.676469,0.718248 -20.5298 , 1.50277 , 15.6491 , -0.563511,-0.613004,0.553789 -4.44011 , 0.587893 , 4.23514 , 0.0400272,-0.487381,0.872272 -4.32281 , 0.598107 , 4.25061 , -0.0747118,0.568398,-0.819354 -4.19819 , 0.607068 , 4.25637 , -0.288299,-0.554375,-0.780739 -4.08915 , 0.617376 , 4.27202 , 0.512133,-0.180217,0.839786 -4.03209 , 0.631497 , 4.33273 , -0.899266,-0.107372,-0.424018 -3.96734 , 0.643833 , 4.38577 , -0.706758,-0.383579,-0.59444 -3.92255 , 0.659477 , 4.45835 , -0.798344,-0.410748,-0.440378 -3.8962 , 0.677028 , 4.55203 , -0.770986,-0.205318,-0.602847 -3.82146 , 0.689687 , 4.59469 , -0.902255,-0.100381,-0.419357 -3.89897 , 0.720631 , 4.80614 , 0.998305,-0.0570584,0.0114919 -3.83845 , 0.735413 , 4.87097 , -0.787991,0.409361,-0.459886 -3.78353 , 0.751218 , 4.94235 , 0.872175,-0.318251,0.37152 -3.68994 , 0.76159 , 4.96665 , 0.757473,-0.491437,0.429796 -3.72469 , 0.790704 , 5.15364 , -0.917761,-0.121056,-0.378233 -3.80185 , 0.829213 , 5.40623 , 0.927127,-0.374174,-0.0207196 -3.79583 , 0.854882 , 5.55828 , 0.624571,0.177644,0.760496 -3.49813 , 0.830769 , 5.3041 , 0.750517,0.0401172,0.659633 -3.39567 , 0.839133 , 5.31318 , -0.273285,-0.292151,-0.916495 -3.27075 , 0.842507 , 5.28657 , -0.12909,0.182203,0.97475 -3.20098 , 0.856424 , 5.34124 , -0.125572,0.399096,0.90827 -3.07958 , 0.858961 , 5.30972 , -0.0178181,0.380565,0.924582 -2.97355 , 0.864534 , 5.30108 , 0.502397,0.781307,0.370346 -2.98089 , 0.896574 , 5.48969 , 0.523531,0.762462,0.38022 -2.83189 , 0.89064 , 5.39955 , 0.19829,0.977592,0.0706709 -2.82322 , 0.919923 , 5.57094 , -0.781978,-0.0888788,-0.616936 -2.89169 , 0.973752 , 5.91233 , -0.855373,0.121792,0.503492 -2.69131 , 0.951889 , 5.70931 , -0.57698,0.157146,-0.801498 -2.63377 , 0.971242 , 5.79974 , -0.643406,0.460155,-0.61179 -2.81808 , 1.07277 , 6.46401 , -0.685934,-0.72714,0.0276132 -2.61395 , 1.04764 , 6.23564 , -0.706215,-0.499027,0.502228 -2.4192 , 1.0202 , 6.00233 , -0.565704,-0.186731,0.803188 -2.24598 , 0.996199 , 5.80119 , -0.167031,0.28925,0.942568 -2.06849 , 0.966685 , 5.55822 , 0.0612652,0.0596511,0.996338 -2.04372 , 1.00166 , 5.75302 , -0.116202,-0.939108,-0.323379 -1.91641 , 0.990027 , 5.63597 , -0.932325,0.0606766,-0.356496 -1.87995 , 1.02172 , 5.81112 , -0.881234,-0.314925,-0.352491 -1.82338 , 1.04737 , 5.93813 , 0.107166,-0.0943988,0.98975 -1.71812 , 1.04411 , 5.88271 , 0.206344,0.0499889,0.977202 -1.61866 , 1.04395 , 5.84419 , -0.1067,0.518166,-0.848598 -1.52942 , 1.04991 , 5.84227 , 0.0628022,-0.597021,0.799764 -1.71233 , 1.27467 , 7.22577 , 0.920845,-0.301964,0.246704 -1.60972 , 1.29104 , 7.2834 , 0.00842708,-0.0475621,0.998833 -1.30881 , 1.10778 , 6.10088 , -0.612158,-0.780338,0.127805 -1.24164 , 1.1415 , 6.26937 , -0.0238924,0.996842,0.0757295 -1.14781 , 1.14714 , 6.27056 , 0.497451,0.859296,0.118964 -0.943635 , 0.98091 , 5.21988 , 0.425074,-0.0278682,-0.90473 -0.86349 , 0.975172 , 5.15724 , 0.0149427,0.322613,0.946413 -0.792279 , 0.984243 , 5.18175 , -0.401921,-0.653958,-0.640936 -0.723163 , 1.00269 , 5.26412 , 0.648324,0.642247,0.408896 -0.673608 , 1.12894 , 5.98597 , -0.288963,-0.719261,0.631795 -0.586847 , 1.14204 , 6.02651 , 0.343226,0.579997,-0.738783 -0.498597 , 1.12064 , 5.86852 , -0.207265,-0.0135428,0.978191 -0.413487 , 1.12767 , 5.87673 , 0.720809,0.64385,-0.256694 -0.335376 , 1.0931 , 5.64704 , 0.218979,-0.23444,0.947146 -0.248129 , 1.11628 , 5.75084 , -0.773841,0.0549055,-0.630996 -0.0667763 , 1.36017 , 7.11049 , 0.984119,0.153523,-0.0891071 -3.04753 , -0.383966 , -1.57345 , 0.41638,0.0829981,-0.905394 -2.70168 , -0.207279 , -0.719263 , -0.0542096,0.187902,0.980691 -2.77923 , -0.214389 , -0.716608 , -0.0587334,0.18357,0.98125 -2.85855 , -0.221446 , -0.711571 , -0.0770108,0.20699,0.975307 -2.92926 , -0.225822 , -0.69884 , -0.115732,0.201467,0.972634 -3.00948 , -0.23122 , -0.689793 , 0.067716,-0.200941,-0.97726 -3.09775 , -0.239219 , -0.683672 , -0.0533976,0.204716,0.977364 -3.19451 , -0.247848 , -0.68058 , 0.0799773,-0.202718,-0.975966 -3.28362 , -0.253989 , -0.669574 , -0.0633479,0.193977,0.978959 -3.39056 , -0.262932 , -0.665959 , -0.0763074,0.191235,0.978574 -3.48962 , -0.270339 , -0.654235 , -0.0646159,0.180026,0.981537 -3.60621 , -0.281303 , -0.648829 , -0.0645112,0.183472,0.980906 -3.71537 , -0.288804 , -0.63561 , -0.0584575,0.194212,0.979216 -3.84298 , -0.299879 , -0.627713 , -0.577671,0.0311506,0.815675 -3.90817 , -0.299031 , -0.58625 , 0.986804,0.00477568,-0.161847 -3.83859 , -0.274792 , -0.481579 , 0.971475,0.188553,0.143817 -3.83857 , -0.263382 , -0.411383 , 0.995321,0.0886666,0.038392 -3.82734 , -0.249611 , -0.338135 , 0.999117,0.0368173,0.0202668 -3.8528 , -0.241771 , -0.280037 , 0.997416,0.0639289,0.032765 -3.82994 , -0.22772 , -0.204121 , 0.994516,0.0663394,-0.0808565 -3.82422 , -0.21537 , -0.136206 , -0.931216,0.0300419,0.363229 -3.8643 , -0.210396 , -0.0845945 , 0.971615,0.0976135,-0.21549 -3.79007 , -0.188403 , 0.0036887 , -0.970257,-0.0657973,-0.232964 -3.7794 , -0.176347 , 0.069348 , 0.983064,0.0379531,-0.179287 -3.79667 , -0.168776 , 0.126486 , 0.956959,0.025372,-0.289114 -3.81413 , -0.160166 , 0.183815 , -0.901013,0.0236187,0.433149 -3.85819 , -0.15636 , 0.234549 , -0.829457,0.0217007,0.558149 -3.88281 , -0.148722 , 0.290678 , -0.602225,0.119733,0.789297 -4.01208 , -0.155611 , 0.325814 , 0.295616,-0.168279,-0.940369 -4.2008 , -0.168144 , 0.354114 , -0.107588,0.166133,0.980217 -4.46872 , -0.190068 , 0.376044 , 0.0434979,-0.168574,-0.984729 -9.35715 , -0.735559 , -0.126224 , 0.12483,-0.185166,-0.974747 -10.158 , -0.800817 , -0.0613798 , -0.0541236,0.192591,0.979785 -11.1881 , -0.886054 , 0.00870532 , -0.0612795,0.191561,0.979566 -12.328 , -0.977209 , 0.105582 , -0.0481442,0.18672,0.981233 -14.0528 , -1.12339 , 0.205421 , -0.0632842,0.189138,0.979909 -15.7493 , -1.25627 , 0.365929 , 0.0795114,-0.188953,-0.978762 -20.4401 , -1.6177 , 0.849546 , -0.241906,0.151659,0.958374 -23.1833 , -1.81499 , 1.21565 , -0.584884,-0.042775,0.809989 -23.8507 , -1.80944 , 1.62459 , -0.642187,-0.0975173,0.76032 -23.7138 , -1.72876 , 2.02233 , 0.615882,0.102113,-0.781193 -24.9223 , -1.76394 , 2.49642 , 0.768887,0.123899,-0.627266 -28.5866 , -1.99095 , 3.20191 , -0.507864,-0.052625,0.859828 -27.4387 , -1.73953 , 4.0507 , -0.954652,-0.0887713,0.284182 -22.4524 , -1.29844 , 3.87688 , 0.52106,-0.194154,0.831144 -22.1583 , -1.21345 , 4.21897 , 0.385264,-0.119374,0.915053 -19.9881 , -1.00458 , 4.24386 , 0.385759,0.600582,0.700351 -19.6486 , -0.924675 , 4.52739 , -0.552705,-0.496293,-0.669485 -27.4794 , -1.34238 , 6.43508 , 0.855603,0.517388,-0.0159296 -18.0125 , -0.714866 , 4.85561 , 0.00978476,-0.525205,0.850919 -18.7734 , -0.703868 , 5.35191 , 0.00978481,-0.525205,0.850919 -18.6516 , -0.641572 , 5.65368 , 0.718348,0.0464912,-0.694129 -20.3939 , -0.66933 , 6.46199 , 0.752853,0.614662,-0.235377 -20.8088 , -0.626489 , 6.95163 , -0.97144,-0.130974,-0.197865 -21.2604 , -0.582212 , 7.47185 , -0.884029,-0.0613952,0.463382 -19.6597 , -0.453853 , 7.3381 , 0.496001,0.72759,0.473914 -21.3156 , -0.451288 , 8.28063 , -0.940084,-0.214251,0.265214 -19.4832 , -0.323274 , 8.01015 , 0.473549,0.696472,0.539145 -20.873 , -0.301528 , 8.91968 , -0.304712,0.945367,-0.115894 -18.0792 , -0.161273 , 8.18761 , 0.374956,0.0283118,0.92661 -18.5521 , -0.112764 , 8.74351 , 0.462338,-0.489903,-0.73908 -19.4962 , -0.0692773 , 9.53423 , -0.953973,-0.212121,0.211992 -11.6143 , 0.120671 , 6.23924 , -0.0135136,0.480983,0.876626 -19.0788 , 0.0692319 , 10.124 , -0.756981,-0.463121,-0.460976 -19.054 , 0.136424 , 10.5094 , 0.188924,0.300316,0.934943 -21.5199 , 0.192347 , 12.2264 , 0.210683,-0.720115,0.661096 -21.5619 , 0.270841 , 12.7159 , -0.509524,0.719153,-0.472445 -21.4451 , 0.350979 , 13.125 , 0.822229,-0.279949,0.495548 -20.4117 , 0.425269 , 12.9879 , -0.168794,-0.0336446,-0.985077 -23.2408 , 0.534082 , 15.2217 , -0.134441,0.986872,0.0894957 -21.1556 , 0.595306 , 14.4182 , -0.672401,0.703672,-0.229614 -20.6156 , 0.670925 , 14.5632 , -0.739623,0.475615,-0.47618 -20.839 , 0.761316 , 15.2255 , 0.475984,-0.603378,0.639824 -20.4616 , 0.838785 , 15.4773 , 0.379991,-0.619324,0.687055 -20.2976 , 0.922417 , 15.8823 , -0.390153,-0.450026,0.803279 -4.29463 , 0.45104 , 4.09054 , -0.0169844,-0.662347,0.749005 -4.13396 , 0.461465 , 4.06532 , 0.0942925,-0.810441,0.578182 -3.97483 , 0.471571 , 4.03535 , -0.806024,0.554055,-0.208203 -4.20588 , 0.502085 , 4.34715 , 0.292871,0.586407,0.755218 -3.95689 , 0.506566 , 4.23334 , -0.880432,0.441352,-0.173343 -4.00229 , 0.528523 , 4.38841 , -0.775713,0.484046,-0.40493 -3.98561 , 0.54732 , 4.48951 , -0.80927,0.332534,-0.484256 -4.21855 , 0.585097 , 4.84874 , -0.676002,-0.0624295,-0.73425 -3.85697 , 0.577693 , 4.59878 , -0.80957,0.240504,-0.535494 -3.74841 , 0.588807 , 4.6037 , -0.964038,0.186534,-0.189301 -3.78465 , 0.613395 , 4.77066 , -0.932412,0.351247,-0.0850551 -3.80284 , 0.637663 , 4.92462 , 0.870125,0.0201431,0.49242 -3.6969 , 0.649011 , 4.9338 , -0.850391,-0.131275,-0.509511 -3.72813 , 0.676232 , 5.11253 , -0.967045,-0.19337,-0.165625 -3.6022 , 0.684961 , 5.09532 , -0.144758,-0.893988,-0.424063 -3.50742 , 0.696809 , 5.11518 , 0.285716,0.183403,0.940601 -3.39484 , 0.706495 , 5.10841 , 0.650573,-0.0988108,0.752988 -3.61702 , 0.765832 , 5.58408 , 0.347268,-0.477409,-0.807147 -3.38272 , 0.756979 , 5.40324 , 0.711581,0.30001,0.635331 -3.3337 , 0.777267 , 5.49317 , 0.110285,0.603713,0.789536 -3.08896 , 0.761934 , 5.26861 , 0.124876,0.469424,0.874098 -3.09051 , 0.790815 , 5.44013 , -0.846981,-0.450487,-0.282286 -3.05702 , 0.814708 , 5.56093 , 0.773016,-0.510489,0.376626 -2.95405 , 0.82416 , 5.55945 , -0.510025,-0.816724,-0.269881 -2.96145 , 0.858129 , 5.76757 , 0.661969,0.731445,-0.163662 -2.82992 , 0.860979 , 5.71025 , -0.222609,-0.919335,0.324452 -2.69636 , 0.861816 , 5.6408 , -0.223827,-0.103293,-0.96914 -2.62837 , 0.879139 , 5.70388 , -0.279018,0.571603,-0.771634 -2.55082 , 0.893812 , 5.74783 , 0.463558,-0.577766,0.671789 -2.49815 , 0.916407 , 5.85465 , 0.374162,-0.802034,0.465559 -2.66419 , 1.0131 , 6.52441 , -0.797871,-0.600566,0.0521737 -2.3075 , 0.935837 , 5.86237 , 0.0924675,0.261146,0.96086 -2.21882 , 0.947214 , 5.88218 , 0.0924674,0.261146,0.96086 -2.12182 , 0.955494 , 5.87205 , -0.0423805,0.531295,0.846126 -1.93244 , 0.921361 , 5.56726 , 0.766751,0.145017,0.62535 -1.91692 , 0.963671 , 5.80848 , -0.629811,0.397452,-0.667361 -1.83093 , 0.974009 , 5.82143 , 0.0552789,-0.551509,0.832335 -1.99025 , 1.12007 , 6.78205 , -0.40502,-0.191484,-0.894032 -1.71547 , 1.02856 , 6.08328 , -0.122407,-0.89564,0.427604 -1.55963 , 0.99633 , 5.80245 , 0.550125,0.0565178,-0.833167 -1.74461 , 1.20316 , 7.13743 , -0.715092,0.617074,-0.328425 -1.60647 , 1.19128 , 6.99106 , -0.648725,-0.724578,-0.232685 -1.53833 , 1.23717 , 7.2221 , -0.04423,-0.492696,0.869077 -1.34734 , 1.16571 , 6.68982 , -0.750687,0.643002,-0.151717 -1.21429 , 1.13687 , 6.44744 , 0.194384,-0.971582,-0.13507 -0.990792 , 0.970704 , 5.32839 , 0.747615,0.412274,-0.520674 -0.900473 , 0.953464 , 5.17785 , -0.32259,0.0812917,0.943042 -0.827243 , 0.961103 , 5.1829 , -0.249223,-0.630703,-0.734916 -0.757059 , 0.976896 , 5.23598 , 0.617025,0.662526,0.424665 -0.736129 , 1.18468 , 6.46125 , -0.843292,-0.474511,0.252384 -0.626916 , 1.10586 , 5.93035 , -0.213413,-0.842656,0.494355 -0.540418 , 1.11771 , 5.95001 , -0.33166,-0.478316,0.813152 -0.454462 , 1.11492 , 5.88955 , 0.351925,0.481538,0.802665 -0.374575 , 1.08906 , 5.68962 , 0.634808,0.0507205,-0.771004 -0.295389 , 1.08813 , 5.63613 , 0.120513,-0.519933,0.845663 -0.0941912 , 1.42632 , 7.53825 , -0.721231,-0.682559,-0.118061 -0.0246032 , 1.33705 , 6.96887 , -0.965549,0.199249,-0.167379 -2.73368 , -0.270719 , -0.708204 , -0.0727141,0.185922,0.97987 -2.81262 , -0.279943 , -0.70394 , -0.0833603,0.18046,0.980044 -2.88294 , -0.286464 , -0.691884 , 0.0762416,-0.196863,-0.977462 -2.96158 , -0.294765 , -0.683534 , -0.100963,0.169808,0.980292 -3.04947 , -0.304973 , -0.678381 , -0.0971371,0.213441,0.972115 -3.12972 , -0.312694 , -0.665314 , -0.0582457,0.18779,0.980481 -3.22666 , -0.324151 , -0.660438 , -0.0519657,0.188851,0.98063 -3.32436 , -0.335187 , -0.65262 , -0.0568756,0.195806,0.978992 -3.42306 , -0.34487 , -0.642155 , -0.0740451,0.183661,0.980197 -3.53069 , -0.357105 , -0.633326 , 0.0573959,-0.173351,-0.983186 -3.64745 , -0.370831 , -0.625845 , -0.0699898,0.191518,0.97899 -3.76514 , -0.383029 , -0.614939 , -0.226076,0.175193,0.958226 -3.89169 , -0.397536 , -0.604599 , 0.975922,0.163736,-0.144109 -3.88609 , -0.38453 , -0.528292 , 0.975922,0.163736,-0.144109 -3.85998 , -0.367102 , -0.445055 , 0.980592,0.108572,0.16325 -3.84133 , -0.351547 , -0.367008 , 0.996154,0.0469707,0.0739691 -3.8301 , -0.337777 , -0.29376 , 0.99981,0.0158235,0.0114126 -3.82602 , -0.326655 , -0.224726 , 0.99733,0.00147324,-0.0730062 -3.83053 , -0.316406 , -0.15979 , -0.946997,-0.101312,0.304848 -3.85281 , -0.308784 , -0.101467 , -0.920196,-0.0718792,0.384802 -3.92033 , -0.310155 , -0.0577874 , 0.980478,0.0858992,0.176876 -3.77026 , -0.273042 , 0.0532951 , 0.984808,0.0330014,-0.170481 -3.79771 , -0.267484 , 0.107844 , 0.974247,0.0111863,-0.225206 -3.80453 , -0.258808 , 0.167963 , -0.914779,-0.0153977,0.40366 -3.83094 , -0.252793 , 0.223461 , -0.895384,0.0110897,0.445158 -3.88388 , -0.251451 , 0.272946 , -0.799151,0.0538753,0.598711 -3.93672 , -0.249758 , 0.323988 , 0.4676,-0.121157,-0.875598 -4.07624 , -0.261114 , 0.359972 , 0.188436,-0.16986,-0.967285 -4.28383 , -0.281398 , 0.388653 , -0.0969694,0.167523,0.981088 -4.64825 , -0.325109 , 0.400593 , -0.0363712,0.169221,0.984907 -9.18051 , -0.977816 , -0.142336 , -0.167044,0.190042,0.967461 -9.65519 , -1.02057 , -0.0446875 , -0.118888,0.185854,0.975358 -10.6026 , -1.12714 , 0.0213842 , -0.0507021,0.189741,0.980524 -11.619 , -1.23793 , 0.114108 , -0.0659646,0.189737,0.979617 -13.1209 , -1.40947 , 0.210365 , -0.0422988,0.188291,0.981202 -14.683 , -1.57954 , 0.355392 , -0.0746357,0.188847,0.979166 -16.6797 , -1.79643 , 0.540588 , -0.0679555,0.185102,0.980367 -19.896 , -2.15645 , 0.778655 , -0.0938111,0.183029,0.978621 -24.0363 , -2.54553 , 1.54019 , 0.510577,0.0375703,-0.859011 -24.7663 , -2.56346 , 1.97657 , -0.823348,-0.181084,0.537872 -24.6454 , -2.48012 , 2.39105 , -0.770205,-0.289373,0.568373 -24.7455 , -2.42164 , 2.81804 , -0.770205,-0.289373,0.568373 -25.0364 , -2.38387 , 3.2668 , 0.852099,0.0814244,-0.517009 -28.0765 , -2.63663 , 4.02443 , -0.557508,0.722778,-0.408384 -22.4134 , -1.971 , 3.7949 , -0.263319,-0.28349,-0.922115 -21.2867 , -1.79358 , 4.01842 , -0.250501,-0.126916,-0.959761 -21.3172 , -1.7356 , 4.39018 , -0.335677,-0.0924616,-0.937428 -20.3602 , -1.58441 , 4.58858 , 0.385759,0.600582,0.700351 -19.725 , -1.46766 , 4.81801 , -0.182751,0.507944,0.841781 -20.4128 , -1.47186 , 5.31076 , -0.655227,0.423831,0.625336 -20.7491 , -1.44021 , 5.74876 , -0.728833,-0.578204,0.366719 -20.7772 , -1.38186 , 6.12447 , -0.924638,-0.359505,0.125704 -24.052 , -1.58147 , 7.3784 , 0.274754,-0.923903,-0.266294 -20.8106 , -1.26139 , 6.88218 , -0.949153,0.131046,-0.286245 -23.5258 , -1.3983 , 8.09382 , 0.0925769,-0.961945,-0.257084 -20.5509 , -1.11621 , 7.56066 , -0.0608771,0.118685,-0.991064 -24.8375 , -1.34128 , 9.41963 , -0.867871,0.472529,-0.153347 -19.3767 , -0.913866 , 7.9033 , -0.732406,-0.566157,-0.378217 -17.1894 , -0.720175 , 7.43418 , -0.02817,-0.599607,0.799798 -19.554 , -0.801604 , 8.71737 , 0.994683,-0.0980312,0.0315533 -17.7393 , -0.639835 , 8.33184 , 0.867366,-0.457899,-0.194949 -18.8754 , -0.639198 , 9.18602 , 0.967856,-0.132473,-0.213789 -19.6873 , -0.615262 , 9.94242 , 0.998608,-0.0513384,0.0121264 -19.8943 , -0.558048 , 10.4454 , 0.761269,-0.199293,-0.617051 -20.7585 , -0.524327 , 11.2963 , 0.194331,0.980383,-0.0329225 -20.5734 , -0.445411 , 11.6381 , 0.0212799,-0.996206,-0.0843832 -19.8746 , -0.348329 , 11.6967 , -0.864998,0.469723,-0.176463 -19.6916 , -0.271138 , 12.0276 , 0.765874,0.442416,0.466589 -19.5621 , -0.195217 , 12.3909 , 0.979682,-0.185245,-0.0768589 -9.12308 , 0.107321 , 6.37469 , 0.0405622,0.384092,0.922403 -19.8974 , -0.0519278 , 13.5079 , 0.995892,-0.0864367,-0.0269717 -21.0379 , 0.0108018 , 14.7429 , -0.649111,0.720165,-0.244985 -20.201 , 0.103656 , 14.6768 , 0.498583,-0.807451,0.315338 -20.079 , 0.18771 , 15.0934 , -0.438782,0.667208,-0.601917 -4.24055 , 0.307337 , 3.92079 , 0.00260391,-0.696502,0.71755 -4.21355 , 0.324717 , 4.00274 , 0.0881383,-0.700259,0.708427 -3.97728 , 0.339374 , 3.91265 , 0.743354,-0.153304,0.651094 -4.00379 , 0.356426 , 4.03669 , -0.797688,0.581827,-0.158654 -3.82458 , 0.369787 , 3.98321 , 0.964506,-0.0911941,0.247815 -3.98021 , 0.390529 , 4.22869 , -0.907079,0.267961,-0.324661 -3.92517 , 0.407912 , 4.28728 , -0.764174,0.506296,-0.399628 -3.89669 , 0.425412 , 4.37309 , -0.694482,0.642023,-0.324809 -3.8386 , 0.442203 , 4.43025 , -0.614929,0.655348,-0.438613 -3.84868 , 0.462178 , 4.55888 , 0.620687,-0.615741,0.485397 -3.73329 , 0.475554 , 4.55641 , -0.943816,0.253788,-0.211669 -3.78509 , 0.499275 , 4.73777 , -0.985037,-0.11143,0.131476 -3.83157 , 0.523823 , 4.92184 , 0.928557,0.320547,0.187169 -3.75082 , 0.540644 , 4.96219 , -0.9464,-0.17218,-0.273278 -3.76377 , 0.56552 , 5.11788 , -0.901758,-0.306426,-0.304853 -3.74797 , 0.588146 , 5.24358 , 0.990452,0.136319,-0.0205305 -3.64524 , 0.602911 , 5.25787 , -0.434166,-0.700649,-0.566208 -3.5015 , 0.613454 , 5.21292 , 0.658598,0.649959,0.379212 -3.49146 , 0.637673 , 5.35318 , -0.478149,0.014034,-0.878167 -3.366 , 0.648885 , 5.32824 , 0.546959,-0.126859,0.827492 -3.31298 , 0.669377 , 5.4093 , 0.0665074,-0.611338,0.78857 -3.30015 , 0.694942 , 5.55778 , -0.139482,-0.555614,0.819657 -3.12981 , 0.698988 , 5.44971 , -0.771003,-0.595665,0.22525 -3.34973 , 0.764253 , 6.01207 , -0.978085,0.0666061,0.197265 -3.15204 , 0.763465 , 5.85814 , 0.577072,-0.67615,-0.458048 -3.15184 , 0.797017 , 6.06023 , 0.0994143,-0.98841,0.114729 -2.87138 , 0.775327 , 5.72179 , 0.43628,0.769262,0.466793 -3.04581 , 0.847647 , 6.28913 , 0.782827,0.105022,0.613312 -2.92426 , 0.859565 , 6.26721 , 0.782827,0.105022,0.613312 -2.71218 , 0.846911 , 6.03379 , -0.706305,0.421274,0.568913 -2.4746 , 0.823347 , 5.71222 , 0.475814,-0.67068,0.569025 -2.50341 , 0.870754 , 6.02087 , -0.180021,0.927435,0.327808 -2.34915 , 0.866444 , 5.87652 , 0.195776,-0.122262,0.972997 -2.24501 , 0.875223 , 5.85012 , -0.550211,-0.27892,-0.787065 -2.16352 , 0.891557 , 5.88724 , 0.00614503,0.544261,0.838893 -1.95964 , 0.859641 , 5.5454 , 0.419769,0.115912,0.900199 -1.93298 , 0.894917 , 5.73938 , 0.545084,-0.367344,0.753619 -1.87776 , 0.921465 , 5.85714 , 0.219647,-0.595618,0.772654 -1.78611 , 0.932139 , 5.84975 , -0.330661,0.603813,-0.725309 -1.96475 , 1.08739 , 6.92845 , 0.519641,0.519366,0.678405 -1.60394 , 0.951155 , 5.83014 , 0.550125,0.0565178,-0.833167 -1.50701 , 0.956058 , 5.78861 , 0.0296386,-0.793126,0.608336 -1.40353 , 0.954223 , 5.69661 , -0.115075,-0.501778,0.857308 -1.35089 , 0.989729 , 5.87586 , -0.282471,0.790251,-0.543795 -1.26906 , 1.00606 , 5.9075 , 0.46267,-0.620221,0.633453 -1.3035 , 1.14404 , 6.77111 , 0.858908,-0.474109,-0.193642 -1.05896 , 0.981504 , 5.60383 , 0.148202,0.980905,0.125941 -0.93606 , 0.929937 , 5.19814 , -0.279267,0.0964459,0.955358 -0.860787 , 0.936208 , 5.18403 , 0.0987492,0.514369,0.851865 -0.79078 , 0.952076 , 5.22755 , -0.569213,-0.626388,-0.532574 -0.73027 , 0.999947 , 5.46714 , -0.622194,-0.663213,-0.415961 -0.664597 , 1.06814 , 5.83406 , 0.713402,-0.104548,0.692912 -0.582238 , 1.09846 , 5.95275 , -0.301599,-0.750556,0.587966 -0.495955 , 1.09893 , 5.89245 , 0.204921,0.147969,0.967529 -0.414316 , 1.08277 , 5.73214 , -0.920909,-0.109834,0.373984 -0.334787 , 1.07699 , 5.63963 , 0.0534388,0.0437198,0.997614 -0.247981 , 1.10718 , 5.75237 , -0.782999,0.0972664,-0.614372 -0.0670768 , 1.35198 , 7.10178 , -0.877047,-0.440992,-0.190563 -2.88957 , -0.515819 , -1.68351 , 0.41638,0.0829981,-0.905394 -3.105 , -0.525436 , -1.53321 , 0.41638,0.0829981,-0.905394 -2.75671 , -0.33371 , -0.690515 , -0.072784,0.201875,0.976703 -2.82641 , -0.343371 , -0.679132 , -0.0654737,0.194939,0.978628 -2.9216 , -0.358301 , -0.682956 , -0.0968705,0.167599,0.981084 -2.99219 , -0.36628 , -0.667466 , -0.0917765,0.190809,0.977328 -3.08028 , -0.379317 , -0.660529 , -0.0731855,0.196741,0.97772 -3.16817 , -0.391805 , -0.65116 , -0.0578271,0.217853,0.974267 -3.26552 , -0.405095 , -0.644504 , -0.0462986,0.208874,0.976846 -3.37084 , -0.420765 , -0.639801 , -0.0693182,0.192533,0.978839 -3.46947 , -0.434162 , -0.627063 , -0.045318,0.179739,0.98267 -3.58563 , -0.451116 , -0.620644 , -0.0631491,0.189653,0.979818 -3.69414 , -0.465559 , -0.606215 , -0.0817816,0.176554,0.980888 -3.81078 , -0.481234 , -0.59306 , -0.265637,0.0867454,0.960163 -3.9468 , -0.500565 , -0.584523 , -0.934129,-0.0790906,-0.348062 -3.86017 , -0.469256 , -0.471206 , 0.994966,0.0175774,0.0986616 -3.86009 , -0.457669 , -0.400232 , 0.982613,0.0863451,0.164367 -3.84144 , -0.442136 , -0.322282 , 0.989402,0.109454,0.0954112 -3.82924 , -0.428173 , -0.249253 , 0.995805,0.0911891,-0.00756003 -3.85226 , -0.421717 , -0.190612 , 0.989063,0.0746677,-0.127201 -3.84722 , -0.41038 , -0.121698 , 0.942833,-0.0354172,-0.331377 -3.87752 , -0.40527 , -0.0659117 , 0.993159,0.0843988,-0.0806922 -3.7947 , -0.378405 , 0.0254622 , -0.960514,-0.129054,-0.246493 -3.79444 , -0.367322 , 0.0887243 , 0.972915,0.0946194,-0.210911 -3.81239 , -0.360786 , 0.146764 , 0.966106,0.0439313,-0.254379 -3.82837 , -0.353732 , 0.204951 , -0.928924,-0.0378917,0.368327 -3.85353 , -0.3483 , 0.261207 , -0.890203,0.0227975,0.454993 -3.88758 , -0.345354 , 0.316117 , -0.676139,0.131893,0.724873 -4.00699 , -0.357475 , 0.354785 , 0.343606,-0.17392,-0.922869 -4.16565 , -0.375718 , 0.390563 , 0.11651,-0.16516,-0.979361 -4.43084 , -0.413302 , 0.414798 , -0.0448596,0.167882,0.984786 -9.29392 , -1.2386 , -0.0430228 , 0.128347,-0.197365,-0.971892 -10.0213 , -1.33827 , 0.0366603 , -0.0590299,0.187777,0.980436 -11.0239 , -1.48072 , 0.117315 , -0.0575698,0.187712,0.980536 -12.1653 , -1.63979 , 0.222848 , -0.0519505,0.180878,0.982133 -13.8485 , -1.88048 , 0.339184 , 0.064064,-0.185406,-0.980572 -15.5516 , -2.11515 , 0.513412 , -0.0707851,0.18268,0.980621 -20.456 , -2.78775 , 1.03902 , 0.121771,-0.187908,-0.974609 -23.3281 , -3.16698 , 1.43701 , 0.420739,-0.0302849,-0.906676 -24.6817 , -3.30406 , 1.88201 , 0.52888,0.232133,-0.816333 -24.5644 , -3.21828 , 2.29732 , -0.648761,-0.327156,0.68708 -25.1218 , -3.22976 , 2.75609 , -0.837989,-0.466689,0.282799 -28.2759 , -3.60252 , 3.46153 , -0.106161,-0.0657821,0.992171 -25.9645 , -3.20491 , 3.70577 , -0.785838,-0.336644,-0.518776 -23.0622 , -2.74176 , 3.79806 , 0.75079,0.574874,0.325323 -22.9911 , -2.66791 , 4.1857 , 0.75079,0.574874,0.325323 -21.4722 , -2.40676 , 4.34413 , 0.132057,0.219683,0.966592 -22.4168 , -2.46511 , 4.88262 , -0.5974,-0.657541,-0.459078 -20.0164 , -2.10682 , 4.81057 , -0.627316,0.0572685,-0.776656 -19.5871 , -1.99799 , 5.0706 , -0.0264985,0.42356,0.905481 -19.609 , -1.94441 , 5.42102 , 0.723274,-0.111767,0.681456 -21.0228 , -2.04914 , 6.11935 , -0.96084,-0.0792271,-0.265538 -21.4684 , -2.03689 , 6.61469 , -0.853509,0.0314508,-0.520128 -20.5155 , -1.87094 , 6.73204 , -0.836525,0.0158099,-0.547701 -20.4698 , -1.80489 , 7.09219 , -0.858638,0.110454,-0.50054 -20.2645 , -1.72312 , 7.40328 , -0.56371,0.0545723,-0.824168 -22.9668 , -1.92919 , 8.70195 , -0.208855,0.288488,0.934427 -18.0888 , -1.39105 , 7.37712 , -0.799254,-0.185506,0.571647 -17.5454 , -1.28476 , 7.51379 , -0.39347,-0.803473,0.446781 -17.1134 , -1.19099 , 7.67773 , -0.39347,-0.803473,0.446781 -16.6525 , -1.09728 , 7.81691 , -0.865309,-0.20945,0.455379 -17.5331 , -1.11677 , 8.53222 , 0.128541,-0.511975,0.849329 -18.9833 , -1.1756 , 9.55099 , -0.85225,0.486574,-0.192132 -21.8683 , -1.33223 , 11.3267 , -0.199996,-0.67932,0.706063 -18.9394 , -1.04552 , 10.3083 , -0.843897,0.100803,0.52695 -25.2354 , -1.41634 , 14.0081 , -0.723409,-0.68014,0.118699 -21.3718 , -1.07483 , 12.4407 , -0.568385,0.71552,0.406165 -20.1187 , -0.921194 , 12.1956 , 0.550416,0.64928,0.524859 -19.9721 , -0.839454 , 12.5565 , -0.883967,-0.357758,-0.301017 -20.1077 , -0.77331 , 13.0933 , 0.97653,-0.174265,0.12657 -19.6415 , -0.673337 , 13.2614 , -0.959458,0.265588,-0.0943591 -19.8001 , -0.606042 , 13.8312 , 0.781684,-0.57722,0.236194 -19.6888 , -0.523348 , 14.2338 , 0.783046,-0.584567,0.212414 -4.31917 , 0.148435 , 3.76035 , 0.426169,-0.617129,0.661462 -4.22381 , 0.167651 , 3.78971 , -0.382674,0.688403,-0.616167 -4.16172 , 0.186279 , 3.8408 , 0.30508,-0.563857,0.767458 -4.05837 , 0.205234 , 3.85935 , 0.660069,0.0219926,0.750883 -3.98701 , 0.223084 , 3.90068 , -0.767706,-0.0519425,-0.638694 -3.97615 , 0.239515 , 3.99227 , -0.931416,0.104081,-0.348756 -3.96331 , 0.256486 , 4.0841 , -0.973003,-0.035094,-0.22811 -3.91777 , 0.273966 , 4.14943 , -0.93286,0.0593534,-0.355315 -3.88617 , 0.291718 , 4.22766 , 0.9433,0.148816,0.296714 -3.83875 , 0.309429 , 4.29188 , 0.809089,-0.303139,0.503469 -3.839 , 0.327568 , 4.40498 , 0.620075,0.232029,0.749447 -3.76033 , 0.34582 , 4.4395 , -0.827775,0.350201,-0.438347 -3.7702 , 0.364734 , 4.56784 , -0.938048,0.190206,-0.289633 -3.87526 , 0.387648 , 4.80896 , -0.947951,-0.30995,0.0729342 -3.81059 , 0.407006 , 4.86556 , -0.813328,-0.520607,-0.259744 -3.80919 , 0.428477 , 4.99783 , -0.842331,-0.444355,-0.305003 -3.75323 , 0.44865 , 5.06877 , -0.902528,-0.313734,-0.294982 -3.70164 , 0.469198 , 5.14673 , 0.874871,-0.00548987,0.484325 -3.78716 , 0.498981 , 5.40776 , -0.702028,-0.7051,0.0999504 -3.55896 , 0.508569 , 5.2522 , -0.704759,-0.439221,-0.557135 -3.70994 , 0.545798 , 5.6223 , -0.0412826,-0.157421,-0.986668 -3.47367 , 0.552616 , 5.44373 , -0.680653,-0.659992,-0.317998 -3.30505 , 0.563554 , 5.35068 , -0.0814189,-0.241855,0.966891 -3.22516 , 0.582769 , 5.38839 , 0.242202,-0.548138,0.800551 -3.10926 , 0.596181 , 5.36522 , -0.34301,-0.3516,0.871047 -2.89398 , 0.597752 , 5.16617 , 0.769009,-0.205246,-0.605392 -2.85637 , 0.619493 , 5.26659 , 0.679925,-0.485655,-0.5494 -2.96225 , 0.664245 , 5.63935 , 0.734323,0.550552,0.397067 -2.96393 , 0.695866 , 5.83945 , 0.352013,-0.139951,-0.925473 -3.04407 , 0.744551 , 6.21053 , -0.649339,-0.478656,-0.590972 -2.99587 , 0.773251 , 6.342 , -0.649339,-0.478656,-0.590972 -2.86342 , 0.785125 , 6.29162 , 0.641681,0.633486,-0.432366 -2.50116 , 0.744474 , 5.69809 , -0.601008,0.718147,-0.350791 -2.35632 , 0.747164 , 5.57342 , -0.186025,-0.518876,0.834363 -2.32754 , 0.776909 , 5.73313 , -0.721743,-0.68252,0.115124 -2.29184 , 0.807504 , 5.88361 , -0.550211,-0.278921,-0.787065 -2.21075 , 0.825982 , 5.92139 , -0.550211,-0.27892,-0.787065 -2.02894 , 0.810665 , 5.65557 , -0.661849,-0.673742,-0.328675 -1.92465 , 0.818381 , 5.60361 , -0.781983,-0.439796,0.44168 -1.87061 , 0.8447 , 5.71154 , -0.25288,-0.753155,0.607297 -1.77595 , 0.854222 , 5.68486 , -0.0801805,-0.794952,0.601351 -2.0176 , 1.02505 , 6.96466 , 0.566396,0.440543,0.696504 -1.66169 , 0.911355 , 5.92514 , 0.282592,0.910691,-0.301303 -1.52864 , 0.898583 , 5.71973 , -0.491371,-0.000973079,0.87095 -1.45291 , 0.917111 , 5.76418 , -0.124632,-0.133156,0.983228 -1.36129 , 0.926216 , 5.72898 , -0.580133,-0.0669328,-0.811767 -1.40672 , 1.04616 , 6.51371 , -0.840979,0.014617,-0.54087 -1.30988 , 1.06232 , 6.51642 , -0.906056,-0.407,0.115819 -1.2937 , 1.16544 , 7.1362 , -0.514272,0.720696,-0.464889 -0.969747 , 0.901722 , 5.20877 , -0.210824,0.107986,0.971541 -0.894865 , 0.909086 , 5.18519 , 0.164972,0.509989,0.844213 -0.825279 , 0.927011 , 5.229 , -0.549303,-0.636927,-0.540916 -0.761733 , 0.963526 , 5.38993 , -0.558969,-0.811076,-0.172362 -0.703126 , 1.04131 , 5.81657 , -0.429188,-0.149037,-0.890835 -0.621125 , 1.06253 , 5.86652 , -0.186185,0.65803,-0.729611 -0.5365 , 1.07598 , 5.86571 , -0.536357,-0.354459,-0.765951 -0.453134 , 1.07156 , 5.76501 , -0.9346,0.0224934,0.35499 -0.374703 , 1.06261 , 5.63321 , 0.345402,0.307788,0.886546 -0.294287 , 1.07314 , 5.61826 , -0.508084,-0.05865,0.859308 -0.0911612 , 1.42095 , 7.56956 , -0.372172,-0.508787,0.776289 -0.0239101 , 1.33415 , 6.96927 , -0.965549,0.199249,-0.167379 -2.85498 , -0.575844 , -1.69504 , -0.410882,-0.0763641,0.908485 -3.15881 , -0.607332 , -1.53949 , 0.41638,0.0829981,-0.905394 -2.71624 , -0.38954 , -0.688836 , -0.0729699,0.191765,0.978725 -2.79305 , -0.40335 , -0.683901 , -0.0483995,0.19687,0.979234 -2.86341 , -0.413958 , -0.671226 , -0.0284105,0.19644,0.980104 -2.94185 , -0.427276 , -0.661963 , -0.12874,0.193173,0.972682 -3.01288 , -0.437198 , -0.64518 , 0.118087,-0.192455,-0.974175 -3.10767 , -0.454831 , -0.642256 , -0.0752255,0.188749,0.97914 -3.19599 , -0.469195 , -0.631302 , -0.0619088,0.197139,0.978419 -3.29254 , -0.485098 , -0.622984 , 0.0417683,-0.197093,-0.979495 -3.38963 , -0.50153 , -0.611526 , -0.0470214,0.191042,0.980455 -3.5134 , -0.524751 , -0.61104 , 0.0589695,-0.19961,-0.978099 -3.61221 , -0.539322 , -0.593604 , 0.064709,-0.189138,-0.979816 -3.73741 , -0.561413 , -0.585969 , -0.0698159,0.183018,0.980627 -3.8633 , -0.582885 , -0.574516 , 0.311978,0.0831953,-0.94644 -3.9631 , -0.596662 , -0.54701 , 0.928196,0.316188,0.196157 -3.86691 , -0.560287 , -0.43082 , -0.969637,-0.183464,-0.161697 -3.86658 , -0.549609 , -0.359455 , 0.98942,0.117229,0.0854714 -3.85625 , -0.535856 , -0.285211 , 0.983557,0.157814,0.0878106 -3.84404 , -0.521827 , -0.211889 , 0.9936,0.0971484,-0.0576381 -3.84848 , -0.51138 , -0.146077 , 0.955944,0.0591341,-0.28753 -3.86075 , -0.504573 , -0.0833827 , 0.990768,-0.0343939,-0.13113 -3.91828 , -0.506847 , -0.0357201 , -0.96626,-0.0654967,-0.249104 -3.80771 , -0.470414 , 0.0635543 , -0.948437,-0.154483,-0.276771 -3.80718 , -0.460194 , 0.127403 , 0.979389,0.0291092,-0.199873 -3.82389 , -0.454285 , 0.186005 , 0.962615,0.00485962,-0.270831 -3.83961 , -0.448095 , 0.244779 , -0.917773,0.0791251,0.389143 -3.87368 , -0.445192 , 0.299495 , -0.888562,0.066169,0.45396 -3.90646 , -0.442784 , 0.355358 , 0.521576,-0.155289,-0.838954 -4.05523 , -0.463893 , 0.390841 , -0.302239,0.196485,0.932762 -4.26967 , -0.49938 , 0.420279 , 0.113498,-0.177186,-0.977611 -9.12383 , -1.47317 , -0.0649049 , -0.139401,0.193037,0.971238 -9.55577 , -1.53601 , 0.0419058 , -0.124219,0.190464,0.973804 -10.4552 , -1.68914 , 0.12006 , -0.0527294,0.189625,0.98044 -11.5023 , -1.86728 , 0.21867 , -0.0641842,0.187947,0.98008 -12.8633 , -2.09945 , 0.335598 , -0.0448185,0.187674,0.981208 -14.5583 , -2.38835 , 0.486927 , 0.0702476,-0.189595,-0.979346 -16.5769 , -2.72881 , 0.690254 , -0.0743316,0.183134,0.980274 -23.8079 , -3.89271 , 1.75928 , 0.685402,-0.273638,-0.674794 -25.6625 , -4.15555 , 2.25746 , 0.316463,-0.118493,-0.941175 -25.9256 , -4.13092 , 2.71596 , -0.853554,-0.103955,0.510529 -26.1801 , -4.10235 , 3.18331 , 0.868103,0.263043,0.420957 -25.4262 , -3.90379 , 3.55893 , -0.482296,0.873872,-0.0611472 -23.137 , -3.45402 , 3.72643 , 0.814432,0.411332,0.409276 -23.0883 , -3.38236 , 4.12024 , 0.943973,0.329974,0.00565189 -22.5838 , -3.23757 , 4.44354 , 0.675804,0.714462,0.181197 -20.5548 , -2.85572 , 4.48819 , 0.406494,0.117053,0.906124 -23.3193 , -3.22406 , 5.37248 , -0.971704,-0.234066,0.0317054 -19.717 , -2.61355 , 5.03469 , -0.770336,-0.177643,-0.612393 -19.6926 , -2.55423 , 5.37769 , 0.693732,0.136505,0.707179 -21.0762 , -2.69872 , 6.06599 , -0.80875,0.529687,-0.255645 -20.709 , -2.58602 , 6.34797 , -0.736314,0.208697,-0.643651 -20.6428 , -2.51678 , 6.70412 , -0.736314,0.208697,-0.643651 -20.617 , -2.45373 , 7.07352 , -0.715005,0.197139,-0.670748 -21.673 , -2.53329 , 7.78987 , 0.725975,-0.0489372,-0.685978 -16.9466 , -1.85205 , 6.59645 , -0.193012,-0.572524,0.796845 -17.2204 , -1.83598 , 7.01132 , -0.833671,-0.196285,0.516203 -17.1684 , -1.77736 , 7.31799 , -0.267969,-0.756062,0.597129 -17.4441 , -1.75798 , 7.75621 , 0.594094,0.70291,-0.391114 -17.2783 , -1.68409 , 8.02587 , 0.594095,0.70291,-0.391114 -24.4893 , -2.45759 , 11.5159 , -0.333666,0.940042,-0.0706303 -18.8148 , -1.74657 , 9.41391 , 0.843265,-0.515259,0.153013 -18.5045 , -1.59045 , 10.029 , -0.790858,0.551792,-0.264706 -19.6523 , -1.64419 , 11.0151 , -0.846887,0.457268,0.271456 -19.5297 , -1.56579 , 11.3682 , -0.843889,0.446505,0.297463 -20.9267 , -1.62872 , 12.5825 , -0.354989,0.886054,0.298146 -19.6506 , -1.439 , 12.2964 , 0.961128,-0.276102,0.0010495 -21.2318 , -1.5059 , 13.7066 , 0.687413,0.686467,0.237122 -19.9237 , -1.31839 , 13.3667 , -0.786857,0.53335,-0.310474 -19.1745 , -1.18399 , 13.3421 , -0.786857,0.53335,-0.310474 -19.3376 , -1.12246 , 13.9149 , -0.839513,0.429213,-0.333158 -4.15111 , 0.0359161 , 3.62502 , 0.552199,-0.561527,0.61625 -4.14804 , 0.0504941 , 3.71699 , 0.581297,-0.641162,0.501005 -4.10222 , 0.0694543 , 3.77898 , -0.629287,0.473779,-0.616061 -4.07951 , 0.0863974 , 3.85888 , 0.718451,-0.459606,0.522102 -3.99264 , 0.106659 , 3.88823 , -0.757268,0.22795,-0.612032 -4.02067 , 0.121201 , 4.01213 , 0.947268,0.0896093,0.307658 -3.89536 , 0.143644 , 4.00605 , 0.983146,0.062772,0.171707 -3.99289 , 0.15608 , 4.19779 , 0.962099,0.266633,0.0572012 -3.9173 , 0.176491 , 4.23627 , -0.907838,-0.351679,-0.228368 -3.94893 , 0.193715 , 4.37741 , -0.829931,-0.405959,-0.382637 -3.90699 , 0.212867 , 4.45003 , -0.785028,-0.232794,-0.574053 -3.78569 , 0.234031 , 4.44258 , -0.819065,-0.200388,-0.537566 -3.7347 , 0.253379 , 4.50534 , -0.87743,-0.0193548,-0.479315 -3.94357 , 0.271334 , 4.85677 , 0.9904,0.0802317,0.112567 -3.93027 , 0.291816 , 4.97512 , -0.871183,-0.458267,-0.176157 -3.89541 , 0.313997 , 5.07081 , -0.870942,-0.443082,-0.212459 -3.75083 , 0.334955 , 5.03454 , -0.825469,-0.459444,-0.327891 -3.75701 , 0.357962 , 5.18327 , -0.554865,-0.572889,-0.60326 -3.87287 , 0.384384 , 5.48464 , -0.866435,-0.401282,0.297092 -3.85 , 0.409395 , 5.61338 , -0.455284,-0.887334,0.0731742 -3.70292 , 0.429747 , 5.5712 , 0.136285,0.912056,0.386757 -3.50713 , 0.446993 , 5.45076 , 0.683308,0.728424,0.0498882 -3.48564 , 0.471567 , 5.58412 , -0.157006,0.5839,0.796498 -3.19949 , 0.480196 , 5.30398 , -0.169371,-0.176588,0.969603 -2.99152 , 0.489725 , 5.1267 , 0.517508,0.369381,-0.771844 -2.79008 , 0.497465 , 4.94353 , -0.71615,-0.550239,0.429379 -2.77166 , 0.521534 , 5.06799 , -0.71615,-0.550239,0.429379 -2.77393 , 0.547616 , 5.23701 , -0.647931,-0.633026,-0.423632 -3.00001 , 0.603975 , 5.84994 , 0.629155,-0.670769,-0.392725 -3.0551 , 0.644641 , 6.16762 , 0.693548,0.322915,0.643986 -3.02272 , 0.676067 , 6.32606 , 0.536513,0.186717,0.822977 -2.93206 , 0.699632 , 6.36682 , 0.41821,-0.310087,0.853784 -2.49008 , 0.658833 , 5.60128 , -0.47479,-0.606786,0.637483 -2.38479 , 0.672934 , 5.56877 , 0.082414,0.766446,-0.636999 -2.28388 , 0.687366 , 5.54309 , -0.0375446,0.921595,0.386334 -2.19248 , 0.702903 , 5.53411 , 0.0396295,0.583061,0.811462 -2.11161 , 0.72025 , 5.55151 , -0.228436,-0.470452,-0.852345 -2.04668 , 0.742054 , 5.61452 , -0.624708,-0.61653,-0.479198 -1.98852 , 0.767854 , 5.70489 , 0.674921,0.298973,0.674609 -1.88819 , 0.779454 , 5.66118 , -0.29159,-0.253402,0.922368 -1.77615 , 0.784682 , 5.56767 , 0.0454826,-0.758492,0.650094 -1.68028 , 0.795318 , 5.51958 , 0.499336,-0.493011,-0.712463 -1.59492 , 0.808883 , 5.50831 , 0.169804,0.922418,-0.346859 -1.49362 , 0.813157 , 5.41798 , 0.154996,0.985662,-0.0666867 -1.40181 , 0.819676 , 5.35488 , 0.229988,0.921231,-0.313749 -1.31429 , 0.826768 , 5.29968 , 0.222377,0.927885,-0.299295 -1.26189 , 0.858993 , 5.43806 , -0.18643,-0.971568,-0.145945 -1.26182 , 0.939632 , 5.93831 , -0.956857,-0.118349,-0.265363 -1.27146 , 1.04934 , 6.63593 , -0.0201683,-0.998093,-0.0583407 -1.00422 , 0.873239 , 5.22918 , -0.104507,0.247832,0.96315 -0.92779 , 0.882126 , 5.19589 , -0.040675,0.399586,0.915793 -0.857382 , 0.899376 , 5.22026 , 0.461709,0.581225,0.670077 -0.795973 , 0.936522 , 5.38172 , -0.681507,-0.72829,-0.0717083 -0.724833 , 0.965659 , 5.48281 , 0.819294,0.429397,0.379969 -0.661357 , 1.04248 , 5.88885 , -0.43403,0.64738,-0.626512 -0.57639 , 1.05107 , 5.84902 , 0.0762519,0.568018,0.819476 -0.492792 , 1.07125 , 5.87678 , -0.152805,-0.00637556,-0.988236 -0.413215 , 1.04644 , 5.62658 , -0.381588,0.279091,0.881192 -0.33323 , 1.06111 , 5.63211 , 0.123887,0.151811,0.980615 -0.245667 , 1.09858 , 5.7639 , -0.84771,0.0896237,-0.522834 -0.0690468 , 1.33935 , 7.06346 , 0.735721,0.615766,-0.282042 -2.86588 , -0.639317 , -1.66376 , -0.412121,-0.0535364,0.909555 -3.15561 , -0.689806 , -1.58626 , 0.402977,0.0862518,-0.911137 -2.65826 , -0.438548 , -0.6752 , -0.0474695,0.183191,0.981931 -2.72717 , -0.452498 , -0.665168 , -0.0826814,0.199712,0.97636 -2.80346 , -0.468058 , -0.659157 , 0.0473278,-0.222893,-0.973693 -2.89725 , -0.488741 , -0.661992 , -0.0715717,0.177748,0.98147 -2.96789 , -0.500808 , -0.645883 , -0.108694,0.207196,0.972242 -3.04637 , -0.516514 , -0.632892 , -0.0975354,0.183529,0.978164 -3.12492 , -0.530764 , -0.61786 , -0.0753239,0.139793,0.987312 -3.22089 , -0.549873 , -0.610507 , -0.0534455,0.17322,0.983432 -3.33399 , -0.574639 , -0.609953 , -0.0581754,0.163535,0.984821 -3.43146 , -0.59286 , -0.59652 , -0.0554686,0.188752,0.980457 -3.53762 , -0.614606 , -0.584625 , -0.0477066,0.206599,0.977262 -3.66129 , -0.639776 , -0.578465 , 0.062207,-0.186793,-0.980428 -3.77727 , -0.662392 , -0.564099 , -0.356066,0.157226,0.921139 -3.89374 , -0.685406 , -0.546011 , -0.561524,-0.172082,0.809369 -3.97626 , -0.697043 , -0.508557 , -0.95234,-0.168254,-0.254439 -3.87053 , -0.655603 , -0.389495 , -0.964835,-0.165975,-0.203826 -3.87852 , -0.646705 , -0.321835 , 0.994461,0.103284,0.0194945 -3.85814 , -0.629724 , -0.244032 , 0.987091,0.151737,0.0512546 -3.86424 , -0.620527 , -0.177198 , 0.992579,0.116781,-0.033916 -3.86841 , -0.610944 , -0.1108 , 0.97872,0.00591404,-0.205114 -3.87967 , -0.60379 , -0.0476419 , 0.995538,0.0416708,-0.0846645 -3.83543 , -0.581477 , 0.0324214 , -0.960244,-0.000270177,-0.279164 -3.80762 , -0.563719 , 0.105075 , 0.996072,0.0599148,-0.065204 -3.82505 , -0.558933 , 0.16419 , 0.995698,0.0726688,-0.0574846 -3.83177 , -0.549971 , 0.225574 , 0.954586,-0.0386806,-0.295415 -3.83825 , -0.541961 , 0.287155 , -0.917473,0.0723279,0.391168 -3.88994 , -0.545135 , 0.338697 , -0.777861,0.0600792,0.625558 -3.9705 , -0.555201 , 0.386443 , 0.415739,-0.145303,-0.897802 -4.12684 , -0.58307 , 0.423708 , 0.215771,-0.194381,-0.956901 -4.38951 , -0.635317 , 0.450246 , 0.069468,-0.166894,-0.983525 -9.19181 , -1.73664 , 0.0381056 , -0.124782,0.20634,0.970491 -9.83391 , -1.85957 , 0.131693 , -0.0846987,0.201742,0.97577 -10.8258 , -2.05977 , 0.220072 , -0.0507424,0.190381,0.980398 -11.973 , -2.29014 , 0.333411 , -0.0572093,0.191122,0.979898 -13.5806 , -2.61572 , 0.466878 , -0.0556378,0.185678,0.981034 -15.2848 , -2.95412 , 0.654133 , -0.0689194,0.187406,0.979862 -20.4395 , -3.97588 , 1.2242 , -0.132472,0.184372,0.973888 -23.466 , -4.56057 , 1.65717 , 0.64225,-0.377196,-0.667262 -23.9934 , -4.60769 , 2.08567 , 0.846644,-0.462304,-0.263569 -24.0532 , -4.55474 , 2.50361 , -0.86442,0.43799,0.246866 -24.0969 , -4.49858 , 2.92302 , 0.910004,-0.168113,-0.378987 -24.1621 , -4.44585 , 3.34645 , 0.270335,-0.957822,-0.0974441 -24.8239 , -4.51028 , 3.84191 , -0.469425,0.871489,0.14194 -24.9227 , -4.46132 , 4.2873 , 0.392439,-0.883075,0.257235 -24.5163 , -4.31553 , 4.66166 , -0.541691,0.581019,-0.607444 -23.6211 , -4.07789 , 4.94033 , -0.834173,-0.49996,-0.2328 -19.8893 , -3.31734 , 4.65932 , -0.758072,-0.273551,-0.592028 -19.8926 , -3.26314 , 5.01079 , -0.758072,-0.273551,-0.592028 -20.3316 , -3.28691 , 5.46146 , -0.636293,0.545384,0.545607 -19.4301 , -3.06902 , 5.60689 , 0.448741,0.314961,0.83632 -18.9201 , -2.92501 , 5.82357 , 0.829458,-0.33373,0.447911 -20.6323 , -3.16586 , 6.6427 , -0.914156,0.40534,0.00422388 -20.3261 , -3.05474 , 6.92917 , -0.856935,0.0629229,-0.511569 -18.8576 , -2.75228 , 6.84016 , 0.538797,-0.752238,0.379257 -18.2875 , -2.60417 , 6.99973 , 0.64566,0.491365,-0.584538 -18.7512 , -2.62432 , 7.50744 , -0.817404,-0.532325,0.220182 -17.8554 , -2.37405 , 7.8716 , 0.65662,0.591402,0.468075 -21.5158 , -2.87111 , 9.73312 , -0.628456,0.664005,-0.405143 -18.2107 , -2.31674 , 8.72461 , -0.84467,0.356251,0.399521 -18.7713 , -2.34002 , 9.34324 , -0.662973,-0.343119,0.665384 -18.1967 , -2.19943 , 9.45103 , -0.778829,0.534838,-0.327679 -17.8269 , -2.08915 , 9.64218 , -0.633678,0.758993,-0.149606 -18.1707 , -2.07694 , 10.193 , 0.622049,-0.782192,-0.035068 -18.1248 , -2.0105 , 10.5549 , -0.825649,0.52804,0.198691 -18.9817 , -2.05741 , 11.4288 , -0.632846,0.620851,0.462654 -19.6593 , -2.07516 , 12.2443 , -0.889155,0.305937,0.340302 -19.4912 , -1.986 , 12.5848 , 0.946964,-0.106651,-0.303126 -4.35605 , -0.153642 , 3.47279 , 0.614569,-0.11407,0.780572 -4.25723 , -0.127575 , 3.50066 , 0.61457,-0.11407,0.780572 -22.5887 , -2.10692 , 16.0637 , 0.378258,-0.159559,-0.911845 -20.9707 , -1.8505 , 15.4777 , 0.446206,-0.0759451,-0.891702 -4.09071 , -0.0664113 , 3.66244 , -0.851456,0.252522,-0.459625 -4.08692 , -0.0507105 , 3.7539 , 0.754399,0.241229,0.610485 -4.02567 , -0.029602 , 3.80274 , -0.815663,0.234425,-0.528903 -3.97163 , -0.0102436 , 3.85684 , 0.810263,-0.311405,0.496488 -3.95465 , 0.00732681 , 3.94155 , 0.995703,0.0592009,0.0712078 -4.0042 , 0.0186476 , 4.08576 , 0.996318,-0.0822472,-0.0242011 -3.93826 , 0.0403483 , 4.13187 , -0.920867,0.0800628,-0.381569 -4.01004 , 0.0523545 , 4.30596 , 0.737282,-0.349488,0.578164 -3.9412 , 0.0746787 , 4.3516 , 0.711981,-0.498432,0.49462 -3.82137 , 0.0991202 , 4.34651 , -0.650116,0.30765,-0.694767 -3.75913 , 0.12051 , 4.39553 , -0.507296,0.43273,-0.745249 -3.81154 , 0.136775 , 4.567 , 0.97528,-0.178283,-0.130556 -3.90637 , 0.151774 , 4.79322 , -0.961409,0.208559,0.179432 -3.88903 , 0.172569 , 4.90317 , 0.978777,-0.193178,0.0683964 -3.8489 , 0.194372 , 4.99075 , -0.943429,0.23786,-0.231008 -3.89638 , 0.215758 , 5.18609 , -0.656139,-0.590226,-0.470228 -3.78912 , 0.240197 , 5.19602 , 0.431641,0.528808,0.730786 -3.70684 , 0.263483 , 5.23531 , -0.439941,-0.35284,-0.825806 -3.63548 , 0.288018 , 5.28859 , -0.518992,-0.254999,-0.815857 -3.88199 , 0.312843 , 5.78908 , 0.407067,0.10212,0.907672 -4.06765 , 0.343065 , 6.23273 , -0.458444,0.8567,0.236421 -3.57076 , 0.362103 , 5.6749 , -0.351809,0.426674,0.833174 -3.21739 , 0.379417 , 5.29549 , 0.135722,0.29473,-0.945893 -3.08755 , 0.399392 , 5.24677 , 0.202039,-0.0403956,-0.978544 -2.89907 , 0.41598 , 5.09135 , -0.700052,-0.643951,0.308633 -2.7415 , 0.430804 , 4.9745 , -0.71615,-0.550238,0.429379 -2.76046 , 0.458005 , 5.16887 , -0.716151,-0.550238,0.429379 -3.23287 , 0.52433 , 6.24082 , 0.562508,0.125993,0.817135 -2.96524 , 0.533229 , 5.92839 , -0.672399,0.469551,0.572191 -2.69877 , 0.537582 , 5.59035 , 0.47449,0.808558,-0.347985 -2.71306 , 0.571218 , 5.82537 , -0.352918,0.754438,0.553418 -2.46644 , 0.571517 , 5.48644 , -0.0292302,-0.389635,0.920505 -2.54961 , 0.61776 , 5.89499 , -0.751898,-0.45151,-0.480405 -2.41824 , 0.632123 , 5.80723 , 0.581086,-0.341037,-0.738941 -2.2474 , 0.636683 , 5.60475 , -0.272504,0.594482,0.756527 -2.16616 , 0.657408 , 5.6228 , 0.16307,0.686641,0.708472 -2.05165 , 0.669677 , 5.5451 , -0.227204,0.632787,0.740243 -1.96546 , 0.688026 , 5.5407 , 0.409115,0.667019,0.622664 -1.873 , 0.703635 , 5.51559 , -0.132984,0.363841,-0.921919 -1.77964 , 0.718166 , 5.47914 , 0.0556244,0.950703,0.305075 -1.68838 , 0.731782 , 5.44079 , 0.559264,-0.141663,-0.816796 -1.60045 , 0.746186 , 5.41023 , 0.234818,0.946537,-0.221197 -1.5146 , 0.759742 , 5.37805 , 0.185882,0.979042,-0.0832185 -1.42667 , 0.771439 , 5.33442 , -0.285118,0.505067,0.814626 -1.34201 , 0.783025 , 5.28911 , 0.212315,-0.707733,-0.673822 -1.26686 , 0.798938 , 5.29123 , -0.227644,0.0953065,0.969069 -1.19525 , 0.817709 , 5.31136 , -0.317946,0.164648,0.933703 -1.14469 , 0.855249 , 5.47756 , 0.612928,0.766854,-0.190409 -1.03703 , 0.841021 , 5.23973 , -0.0966616,0.160966,0.982215 -0.961036 , 0.852973 , 5.21667 , -0.127581,0.287116,0.949362 -0.888569 , 0.867847 , 5.21192 , 0.34093,0.622024,0.704878 -0.832296 , 0.914985 , 5.43277 , 0.79916,0.546179,0.251062 -0.758579 , 0.935766 , 5.46514 , 0.622194,0.663213,0.415961 -0.687498 , 0.972893 , 5.60482 , 0.687695,0.529713,0.496467 -0.621247 , 1.07263 , 6.14846 , -0.859963,0.499375,-0.105299 -0.53218 , 1.05058 , 5.87996 , -0.451519,-0.214096,-0.866195 -0.449694 , 1.04593 , 5.73867 , -0.9346,0.0224935,0.35499 -0.371468 , 1.04304 , 5.61601 , 0.264923,0.0896105,0.960097 -0.291754 , 1.0646 , 5.63994 , -0.521073,0.0747349,0.850234 --0.031328 , 1.73607 , 9.4697 , 0.288677,-0.94473,-0.155407 -0.0239346 , 1.32908 , 6.96004 , -0.945507,0.247155,-0.211967 -2.8471 , -0.705835 , -1.69783 , -0.412121,-0.0535366,0.909555 -2.89523 , -0.71077 , -1.65397 , -0.412121,-0.0535366,0.909555 -2.68233 , -0.505327 , -0.66439 , -0.0621348,0.191298,0.979563 -2.75918 , -0.523225 , -0.658836 , -0.0771402,0.193403,0.978082 -2.82015 , -0.535463 , -0.639915 , -0.0514347,0.171748,0.983797 -2.90494 , -0.555653 , -0.635925 , -0.0544757,0.201834,0.977904 -2.9915 , -0.575724 , -0.629261 , -0.0870137,0.218279,0.971999 -3.07763 , -0.596198 , -0.619968 , 0.0707693,-0.158786,-0.984773 -3.17202 , -0.618232 , -0.613408 , 0.0732996,-0.169676,-0.98277 -3.25995 , -0.637041 , -0.599011 , -0.0539289,0.166385,0.984585 -3.35564 , -0.659249 , -0.586661 , -0.0573536,0.167318,0.984233 -3.46146 , -0.683293 , -0.576122 , -0.0878117,0.195033,0.976858 -3.57497 , -0.710516 , -0.566657 , -0.0525029,0.182095,0.981878 -3.6904 , -0.736448 , -0.553743 , -0.0652761,0.194298,0.978768 -3.8063 , -0.762756 , -0.537008 , 0.208911,-0.200755,-0.957107 -3.9394 , -0.793243 , -0.524936 , -0.895718,0.0843837,0.436543 -3.95901 , -0.788559 , -0.458645 , -0.966815,-0.255374,-0.0072643 -3.87145 , -0.749277 , -0.348534 , -0.963749,-0.155361,-0.216913 -3.88727 , -0.743997 , -0.283894 , 0.997098,0.0761075,0.00191016 -3.88522 , -0.731892 , -0.212773 , 0.99409,0.0921227,0.0574268 -3.87199 , -0.717494 , -0.138891 , 0.994958,0.0475692,-0.0882943 -3.86614 , -0.704749 , -0.0692258 , -0.981591,-0.0798531,0.173502 -3.90538 , -0.706212 , -0.0141659 , -0.973717,-0.213337,-0.079761 -3.81417 , -0.669458 , 0.0793859 , 0.955089,0.104745,0.27719 -3.83157 , -0.664561 , 0.138988 , 0.998046,0.00310871,-0.0624134 -3.83001 , -0.653951 , 0.203494 , 0.98181,0.0237281,-0.188376 -3.83647 , -0.645853 , 0.265464 , -0.951738,-0.0148969,0.306551 -3.87076 , -0.64591 , 0.321379 , -0.876062,-0.0219231,0.4817 -3.91295 , -0.648106 , 0.376412 , -0.689763,0.0656774,0.72105 -4.00187 , -0.662363 , 0.424083 , -0.382149,0.15091,0.911696 -4.20559 , -0.707129 , 0.456771 , -0.112016,0.165052,0.979903 -9.40613 , -2.04143 , 0.126917 , -0.12476,0.200793,0.971657 -10.2271 , -2.22913 , 0.218238 , -0.0540559,0.194418,0.979428 -11.3278 , -2.48507 , 0.319906 , -0.0576391,0.187002,0.980667 -12.5164 , -2.75773 , 0.456161 , -0.0478725,0.192745,0.98008 -14.2871 , -3.16967 , 0.616564 , -0.0687401,0.185961,0.98015 -16.1838 , -3.60334 , 0.837815 , -0.0864555,0.209101,0.974065 -23.7318 , -5.28798 , 1.97909 , 0.927909,-0.326169,-0.18055 -25.2424 , -5.58379 , 2.47976 , -0.297729,0.450528,0.841654 -27.2492 , -5.9868 , 3.07182 , -0.346831,0.356468,0.867548 -26.8486 , -5.82077 , 3.5102 , -0.0843002,0.409439,0.908434 -24.7942 , -5.27645 , 3.75042 , 0.707954,0.705037,-0.0415174 -23.9561 , -5.02006 , 4.07628 , 0.494161,-0.662794,0.562591 -23.713 , -4.90004 , 4.46072 , 0.706039,-0.596024,0.382445 -22.9715 , -4.67186 , 4.75585 , -0.534282,0.630062,-0.563529 -23.1588 , -4.65002 , 5.19648 , 0.534282,-0.630062,0.563529 -23.4348 , -4.64574 , 5.66362 , 0.473022,-0.337666,0.813776 -19.9426 , -3.83886 , 5.31465 , -0.746257,-0.312264,-0.58787 -20.0218 , -3.80043 , 5.69097 , -0.784225,-0.419622,-0.457065 -18.9454 , -3.5213 , 5.77571 , -0.571565,-0.217061,-0.791327 -18.7685 , -3.43196 , 6.07107 , 0.789016,-0.185219,0.585788 -18.5966 , -3.34438 , 6.36402 , 0.789016,-0.185218,0.585788 -17.6608 , -3.10623 , 6.41424 , -0.698678,-0.655107,-0.287549 -21.7391 , -3.85185 , 8.09854 , -0.902136,0.19823,0.383217 -21.5254 , -3.74712 , 8.43436 , -0.432816,0.732795,-0.525055 -18.003 , -3.01694 , 7.53749 , -0.279687,-0.95798,-0.0636339 -19.6431 , -3.26905 , 8.52536 , -0.913565,0.0801238,0.398723 -17.1355 , -2.75035 , 7.87736 , 0.393195,0.558794,0.730169 -16.7273 , -2.62517 , 8.03875 , 0.607501,0.355477,0.710337 -19.4123 , -3.04857 , 9.58627 , 0.80243,0.393517,0.44861 -19.1406 , -2.87897 , 10.2466 , -0.798392,-0.211051,-0.563939 -17.6376 , -2.56614 , 9.87262 , -0.964546,0.247233,0.0923435 -18.1222 , -2.58816 , 10.5077 , -0.943007,0.0422896,0.330073 -18.2369 , -2.54523 , 10.9634 , 0.893528,-0.114335,-0.434206 -18.0577 , -2.45593 , 11.2608 , 0.728777,-0.402253,-0.554144 -19.2738 , -2.57959 , 12.4019 , -0.793673,0.214786,0.569166 -19.9361 , -2.60997 , 13.2598 , 0.77827,-0.374664,-0.503907 -4.24286 , -0.25008 , 3.48059 , 0.59475,-0.131933,0.793011 -20.7214 , -2.5764 , 14.7353 , -0.920521,0.370658,-0.123506 -4.1448 , -0.207841 , 3.59747 , 0.745035,-0.261467,0.613644 -4.08677 , -0.185014 , 3.64833 , -0.869501,0.284714,-0.403615 -4.1231 , -0.176119 , 3.77011 , -0.96052,0.0830194,-0.265536 -4.12537 , -0.161404 , 3.86913 , -0.742318,0.13132,-0.657053 -3.9931 , -0.129017 , 3.86214 , -0.600969,0.0721275,-0.796011 -3.95401 , -0.109754 , 3.92857 , -0.974526,0.18026,-0.133438 -3.98157 , -0.097115 , 4.05287 , 0.97381,-0.141842,0.177695 -3.99874 , -0.082922 , 4.17223 , 0.994799,-0.0451172,0.0913263 -3.82969 , -0.0490236 , 4.12351 , 0.784324,-0.374763,0.494356 -3.85761 , -0.0347757 , 4.256 , -0.858747,0.318798,-0.401149 -3.81817 , -0.0144366 , 4.3272 , -0.686287,0.21184,-0.695797 -3.77681 , 0.00626689 , 4.39787 , -0.686287,0.21184,-0.695797 -3.72746 , 0.0283642 , 4.46064 , 0.994341,-0.100631,0.034067 -3.85868 , 0.0363535 , 4.72189 , -0.932195,0.313627,0.180696 -3.73115 , 0.0652434 , 4.7037 , -0.904445,0.362709,0.224549 -3.81922 , 0.0794255 , 4.93309 , -0.931536,0.342472,-0.12228 -3.9381 , 0.0932242 , 5.21266 , -0.973137,-0.19581,-0.121089 -3.79957 , 0.122762 , 5.18447 , 0.531435,0.466266,0.70723 -3.87018 , 0.141935 , 5.42212 , 0.990618,-0.111588,0.0788909 -3.63018 , 0.174924 , 5.25381 , -0.526459,-0.0949291,-0.844884 -3.54686 , 0.200924 , 5.28973 , -0.0820247,-0.681027,-0.72765 -3.39583 , 0.228162 , 5.22536 , 0.258473,0.721554,0.642302 -3.33129 , 0.252735 , 5.28191 , 0.254189,0.66685,0.700499 -3.27111 , 0.277704 , 5.34559 , 0.198399,0.54604,0.813927 -3.13513 , 0.302883 , 5.28928 , -0.0653148,0.492512,0.867851 -3.01255 , 0.326586 , 5.24694 , -0.162854,0.738653,0.654118 -2.92611 , 0.350109 , 5.26211 , 0.0129121,-0.701933,-0.712126 -2.89312 , 0.374765 , 5.37199 , -0.518837,-0.362108,-0.774394 -2.88607 , 0.401856 , 5.53474 , -0.785453,-0.512858,-0.346468 -3.13598 , 0.445249 , 6.21497 , 0.721799,0.553859,-0.415025 -2.67209 , 0.44675 , 5.48532 , -0.245437,-0.804782,0.540451 -2.56707 , 0.468958 , 5.45676 , -0.429751,-0.651057,0.625651 -2.51637 , 0.494517 , 5.54476 , 0.666083,0.727151,-0.166086 -2.53078 , 0.528854 , 5.78836 , 0.194163,-0.484233,-0.853123 -2.55985 , 0.568206 , 6.08888 , 0.406724,0.909978,0.0807173 -2.29676 , 0.567632 , 5.66524 , -0.648761,0.394293,0.650878 -2.34582 , 0.613231 , 6.04005 , 0.727662,0.639444,0.248232 -2.34999 , 0.656202 , 6.32319 , 0.19621,0.879847,0.432864 -2.03503 , 0.632474 , 5.67016 , 0.4848,0.533796,0.692843 -1.959 , 0.657085 , 5.70303 , 0.459128,-0.0328318,0.887763 -1.90237 , 0.68534 , 5.80201 , 0.542385,0.0697431,0.83723 -1.76525 , 0.691302 , 5.62125 , 0.756503,-0.402057,-0.515803 -1.65719 , 0.703228 , 5.52427 , -0.499336,0.49301,0.712464 -1.55321 , 0.713678 , 5.42505 , 0.159877,0.986936,-0.0199005 -1.49626 , 0.741848 , 5.51816 , 0.0455092,0.998603,-0.0268656 -1.39351 , 0.750218 , 5.40531 , -0.0421576,0.963123,0.26574 -1.30641 , 0.763343 , 5.34929 , 0.222377,0.927885,-0.299295 -1.22116 , 0.774647 , 5.29177 , -0.186128,0.0499731,0.981254 -1.14586 , 0.792205 , 5.28137 , -0.36427,-0.0064234,0.931271 -1.06623 , 0.805519 , 5.24026 , 0.203019,-0.15111,-0.967445 -0.992847 , 0.821057 , 5.22748 , -0.0609356,0.213806,0.974974 -0.921053 , 0.839949 , 5.23277 , -0.375184,-0.485647,-0.789547 -0.85281 , 0.863803 , 5.27636 , -0.534603,-0.598389,-0.596766 -0.81221 , 0.950672 , 5.77342 , 0.5077,0.484659,-0.712282 -0.718466 , 0.933582 , 5.51816 , -0.827627,-0.384168,-0.409205 -0.650965 , 0.996145 , 5.81517 , -0.498725,0.606115,-0.619595 -0.569683 , 1.02519 , 5.87328 , 0.144334,0.464728,0.873611 -0.487503 , 1.05317 , 5.92014 , -0.0292474,0.0255952,0.999245 -0.408107 , 1.03343 , 5.66922 , 0.89678,-0.00250702,-0.44247 -0.328538 , 1.05305 , 5.66369 , -0.0520847,0.309076,0.94961 -0.242629 , 1.09218 , 5.78516 , -0.944164,-0.0746158,-0.320915 -0.0717487 , 1.32449 , 7.01531 , 0.563494,0.825961,0.0162315 -2.8743 , -0.777874 , -1.68837 , -0.387778,-0.0236897,0.921448 -2.62941 , -0.553814 , -0.657381 , -0.044024,0.16157,0.985879 -2.70492 , -0.573685 , -0.652819 , -0.0862535,0.165246,0.982473 -2.77373 , -0.591261 , -0.640125 , -0.0862501,0.155389,0.984081 -2.85814 , -0.613596 , -0.63681 , -0.0703056,0.210265,0.975113 -2.9194 , -0.627337 , -0.61465 , -0.0702266,0.171283,0.982716 -3.01242 , -0.652956 , -0.611802 , -0.0311583,0.160518,0.986541 -3.10621 , -0.678196 , -0.606206 , 0.0880308,-0.174603,-0.980696 -3.18438 , -0.696913 , -0.58783 , 0.057487,-0.173203,-0.983207 -3.30403 , -0.731423 , -0.59096 , -0.0356025,0.195975,0.979963 -3.39194 , -0.752423 , -0.571959 , -0.0802346,0.186178,0.979235 -3.48855 , -0.776971 , -0.554593 , -0.0566004,0.180537,0.981938 -3.61036 , -0.809863 , -0.54734 , -0.0569544,0.193758,0.979395 -3.72473 , -0.83925 , -0.53208 , -0.0731535,0.183252,0.98034 -3.84794 , -0.870947 , -0.517386 , 0.271059,-0.232575,-0.934043 -3.98166 , -0.906204 , -0.502237 , 0.829638,-0.173533,-0.530648 -3.93051 , -0.877605 , -0.405195 , 0.982246,-0.069729,0.174157 -3.87685 , -0.847871 , -0.310756 , 0.991429,0.0833353,0.100617 -3.89264 , -0.842502 , -0.245727 , 0.998304,0.0517018,0.0267476 -3.88031 , -0.828143 , -0.170946 , 0.996799,0.0460685,0.0653348 -3.86731 , -0.812772 , -0.0971644 , 0.984955,0.00181946,-0.172804 -3.88827 , -0.809468 , -0.0359093 , 0.972207,-0.0143193,-0.233685 -3.93622 , -0.814477 , 0.0175163 , 0.970209,0.120627,0.210105 -3.81677 , -0.766081 , 0.118259 , -0.92255,-0.168112,-0.347334 -3.8339 , -0.762048 , 0.178447 , 0.987778,0.0283175,-0.153275 -3.83231 , -0.75135 , 0.243342 , 0.959386,0.0175988,-0.281547 -3.85739 , -0.749653 , 0.301772 , -0.895072,0.00477607,0.445897 -3.90928 , -0.755699 , 0.354903 , -0.784645,0.0736147,0.615559 -3.9323 , -0.753177 , 0.414843 , 0.572021,-0.0783842,-0.816485 -4.0863 , -0.790628 , 0.45379 , 0.284397,-0.165793,-0.944262 -4.32571 , -0.851812 , 0.485444 , -0.095617,0.157684,0.98285 -9.05124 , -2.22366 , 0.116246 , -0.124456,0.207512,0.970283 -9.67446 , -2.38157 , 0.216223 , -0.094418,0.192717,0.976701 -10.633 , -2.63353 , 0.314218 , -0.0479164,0.191504,0.980322 -11.7068 , -2.91351 , 0.440073 , -0.0643452,0.192925,0.979102 -13.2522 , -3.3207 , 0.58714 , -0.0406831,0.190184,0.980905 -14.9612 , -3.76599 , 0.786548 , -0.0835326,0.211058,0.973898 -20.4175 , -5.19079 , 1.40546 , 0.0947421,0.615024,0.782796 -23.2067 , -5.83536 , 2.26948 , -0.990113,0.138051,0.0248783 -23.3141 , -5.80234 , 2.68375 , -0.970814,0.239665,0.00897477 -23.2984 , -5.73703 , 3.09143 , 0.988576,-0.145515,0.039282 -25.7203 , -6.30858 , 3.76214 , 0.165938,0.433461,0.885763 -27.4749 , -6.69493 , 4.43711 , -0.3124,0.478956,0.82037 -23.105 , -5.50058 , 4.29439 , 0.3471,-0.803655,0.483385 -23.4357 , -5.52225 , 4.75738 , 0.631015,0.030557,0.775169 -22.2577 , -5.16367 , 4.96197 , 0.423936,-0.861862,0.278339 -20.0866 , -4.56424 , 4.92819 , -0.974199,-0.171892,0.14625 -22.35 , -5.06543 , 5.77914 , 0.556395,-0.825742,0.092597 -19.6762 , -4.35598 , 5.55345 , 0.744688,0.477732,0.46606 -20.0344 , -4.38765 , 6.00111 , 0.974623,0.216023,-0.0586808 -20.0931 , -4.34611 , 6.383 , 0.993729,-0.111029,0.0132573 -18.5232 , -3.92267 , 6.2952 , -0.728381,-0.203918,-0.654125 -20.2156 , -4.26177 , 7.16425 , -0.916162,0.177142,0.359539 -18.4434 , -3.74671 , 7.3068 , 0.993691,0.0958923,0.058166 -21.0747 , -4.27805 , 8.62944 , -0.432816,0.732795,-0.525055 -21.0023 , -4.2002 , 9.0095 , 0.488408,-0.793766,0.362481 -18.9269 , -3.68922 , 8.57234 , -0.352584,-0.302411,0.885569 -19.9448 , -3.84991 , 9.38394 , 0.343397,0.488092,0.802399 -17.897 , -3.35893 , 8.86312 , 0.721691,-0.115595,0.682495 -21.0014 , -3.9455 , 10.6876 , -0.330011,0.92373,0.194463 -18.0065 , -3.27041 , 9.64892 , 0.969988,-0.191026,-0.150439 -17.4227 , -3.09607 , 9.72589 , 0.99492,-0.0791164,0.0622514 -18.5001 , -3.25192 , 10.6726 , 0.525138,-0.281312,0.803177 -17.7345 , -3.04346 , 10.6462 , 0.837008,-0.286741,-0.466045 -18.3572 , -3.10295 , 11.3975 , -0.219941,-0.301732,0.927677 -19.6452 , -3.28083 , 12.586 , -0.948389,0.043442,0.31412 -19.4427 , -3.17527 , 12.9087 , -0.931752,0.214392,0.293044 -4.27388 , -0.382432 , 3.49264 , -0.662837,0.290952,-0.689923 -4.17649 , -0.350677 , 3.51923 , -0.662837,0.290952,-0.689923 -20.1158 , -3.08083 , 14.7716 , -0.876954,0.447301,0.17571 -4.09478 , -0.308391 , 3.64575 , -0.71595,0.15493,-0.680744 -4.00501 , -0.279595 , 3.67223 , 0.780768,-0.253753,0.570973 -3.94885 , -0.241874 , 3.81741 , -0.633053,0.525355,-0.568547 -3.92646 , -0.224221 , 3.89605 , -0.939575,0.137343,-0.313585 -3.9928 , -0.218751 , 4.05239 , 0.970594,-0.231035,0.0676087 -3.86897 , -0.185165 , 4.04607 , -0.942475,0.26244,-0.207042 -3.90039 , -0.173966 , 4.17817 , 0.750566,-0.311253,0.582899 -3.96367 , -0.166315 , 4.34644 , -0.567763,-0.59835,-0.565351 -3.81064 , -0.12908 , 4.30761 , -0.816658,-0.458524,-0.350464 -3.77047 , -0.107596 , 4.3784 , -0.745797,-0.409879,-0.525154 -3.72935 , -0.0859631 , 4.44878 , -0.969601,-0.205264,-0.133194 -3.78688 , -0.0744895 , 4.62861 , 0.982264,-0.0321539,-0.184725 -3.85361 , -0.062643 , 4.8263 , 0.885645,-0.463948,0.0196257 -3.84256 , -0.0418371 , 4.94382 , -0.916532,0.392242,-0.0781968 -3.8735 , -0.0243546 , 5.11579 , -0.974194,0.0316484,0.223483 -3.89942 , -0.00522503 , 5.28968 , -0.890872,-0.00852614,-0.454176 -3.83542 , 0.0220836 , 5.35501 , 0.626506,-0.050462,0.777781 -3.72189 , 0.0543801 , 5.35478 , 0.262258,0.477813,0.838401 -3.59703 , 0.0856283 , 5.33596 , 0.766983,-0.024968,0.641181 -3.55425 , 0.112293 , 5.42861 , 0.62988,0.0905709,0.771393 -3.48679 , 0.139232 , 5.48801 , 0.840175,0.455982,0.293575 -3.36987 , 0.169842 , 5.47054 , 0.465523,0.875516,0.129456 -3.41192 , 0.193286 , 5.70479 , 0.528901,0.837468,0.137519 -3.25132 , 0.224108 , 5.61587 , 0.212791,0.969504,-0.121581 -3.15012 , 0.252765 , 5.61789 , -0.0933427,0.99173,-0.0880796 -3.22421 , 0.279653 , 5.93238 , -0.377638,-0.893053,0.244634 -3.3129 , 0.310679 , 6.29442 , -0.889372,-0.426414,-0.164892 -2.75871 , 0.333519 , 5.43306 , 0.71974,0.650329,0.242996 -2.66339 , 0.359636 , 5.42479 , 0.331287,-0.261902,0.906453 -2.64536 , 0.387331 , 5.57734 , 0.595357,0.783772,0.17678 -2.63882 , 0.417718 , 5.76673 , -0.606754,-0.498212,-0.619383 -2.75383 , 0.459102 , 6.2507 , 0.964135,0.117551,0.237962 -2.68963 , 0.490807 , 6.34206 , -0.440656,0.424553,0.790934 -2.34802 , 0.493724 , 5.73499 , 0.257084,0.825982,0.501659 -2.41593 , 0.53918 , 6.15697 , -0.601836,-0.668056,-0.437602 -2.34715 , 0.570118 , 6.23408 , -0.7388,-0.615736,-0.27394 -2.06561 , 0.565002 , 5.68541 , -0.464779,0.606849,-0.644759 -1.9724 , 0.587432 , 5.66189 , -0.889398,-0.0173952,-0.456802 -1.91422 , 0.617209 , 5.75116 , 0.498987,-0.597851,0.627364 -1.83461 , 0.642404 , 5.77243 , -0.331102,0.670386,0.664043 -1.70168 , 0.65217 , 5.58969 , 0.227235,0.928051,0.295101 -2.07599 , 0.82887 , 7.44657 , -0.943022,-0.131858,0.305487 -1.91325 , 0.841402 , 7.22635 , -0.959078,-0.270202,0.084619 -1.48662 , 0.730698 , 5.71638 , -0.879881,-0.237284,-0.411711 -1.4298 , 0.766658 , 5.84721 , 0.870592,0.41531,0.263794 -1.28367 , 0.752448 , 5.48749 , -0.573867,-0.41622,-0.705292 -1.17398 , 0.751659 , 5.28162 , -0.276095,0.0109325,0.961068 -1.09599 , 0.768753 , 5.25057 , -0.209308,0.143317,0.96729 -1.02229 , 0.787537 , 5.23786 , -0.0622258,0.170994,0.983305 -0.950652 , 0.806569 , 5.23388 , -0.314602,-0.383103,-0.86848 -0.88283 , 0.83248 , 5.27776 , 0.466319,0.597674,0.652175 -0.901124 , 1.01661 , 6.52702 , 0.829376,0.53894,-0.147236 -0.753486 , 0.908437 , 5.54011 , -0.77959,-0.460638,-0.424326 -0.678115 , 0.935454 , 5.58031 , -0.672179,-0.580813,-0.459165 -0.633483 , 1.17116 , 7.05376 , -0.699422,-0.201628,0.685679 -0.525662 , 1.02262 , 5.87418 , 0.131219,0.459688,0.878333 -0.443689 , 1.0382 , 5.83104 , 0.497261,-0.802303,-0.330214 -0.367052 , 1.03187 , 5.64812 , 0.093059,-0.3602,0.928222 -0.284896 , 1.06418 , 5.71076 , 0.375145,-0.709687,0.596332 --0.0367448 , 1.73021 , 9.51101 , 0.288677,-0.94473,-0.155407 -0.0225168 , 1.32838 , 6.97016 , -0.945508,0.247155,-0.211967 -2.89906 , -0.851298 , -1.67838 , -0.387778,-0.0236896,0.921448 -2.64306 , -0.617877 , -0.640869 , -0.0762459,0.17749,0.981165 -2.7178 , -0.640427 , -0.634936 , -0.0607514,0.160744,0.985125 -2.79335 , -0.662709 , -0.626742 , -0.0961244,0.164296,0.981716 -2.86971 , -0.684722 , -0.616287 , -0.11865,0.187264,0.975118 -2.94592 , -0.706253 , -0.603692 , -0.064512,0.182172,0.981148 -3.03911 , -0.734677 , -0.598963 , -0.0661647,0.190487,0.979458 -3.11594 , -0.75539 , -0.581675 , -0.0909173,0.191859,0.977202 -3.21069 , -0.78308 , -0.571549 , -0.0486747,0.198705,0.97885 -3.30499 , -0.811084 , -0.558404 , -0.0369313,0.190887,0.980917 -3.41639 , -0.844636 , -0.551573 , -0.0867574,0.198135,0.976328 -3.52036 , -0.874704 , -0.536831 , -0.0620928,0.194111,0.979013 -3.6332 , -0.907192 , -0.523143 , -0.049982,0.184659,0.981531 -3.75563 , -0.943156 , -0.509703 , -0.0882767,0.187785,0.978235 -3.86965 , -0.975422 , -0.488474 , -0.256322,0.0846254,0.96288 -4.01042 , -1.01695 , -0.474877 , -0.934275,-0.229958,-0.272489 -3.90769 , -0.966901 , -0.356303 , -0.972527,-0.153501,-0.175009 -3.8891 , -0.949889 , -0.276215 , 0.987845,0.088193,0.128005 -3.89482 , -0.941226 , -0.207335 , 0.994148,0.102124,0.0352267 -3.88272 , -0.92585 , -0.13246 , 0.994281,0.100124,0.0371624 -3.87752 , -0.91403 , -0.061406 , 0.983423,0.00037307,-0.181329 -3.89819 , -0.911523 , 0.00072743 , 0.995893,-0.0536769,-0.0729051 -3.90812 , -0.904732 , 0.0656155 , -0.963678,0.0147916,-0.266658 -3.83491 , -0.869609 , 0.152551 , 0.985512,0.121246,0.118597 -3.843 , -0.862673 , 0.215933 , -0.980444,-0.056297,0.188572 -3.84914 , -0.855285 , 0.27917 , 0.957563,0.0412781,-0.285253 -3.87416 , -0.853391 , 0.338476 , -0.902038,0.0114162,0.431505 -3.91559 , -0.858288 , 0.394783 , -0.801666,0.0349381,0.596751 -3.98444 , -0.871764 , 0.447566 , -0.427632,0.109802,0.897259 -4.16554 , -0.922415 , 0.485654 , -0.158294,0.137895,0.977716 -9.22832 , -2.53252 , 0.2068 , -0.107683,0.193647,0.975144 -9.92104 , -2.73148 , 0.313517 , -0.0595744,0.188966,0.980175 -11.0047 , -3.05113 , 0.422033 , -0.0498329,0.188537,0.980801 -12.1652 , -3.38978 , 0.566374 , -0.0530348,0.193829,0.979601 -13.9453 , -3.91616 , 0.738407 , -0.0542189,0.186107,0.981032 -15.7247 , -4.43231 , 0.974288 , -0.122782,0.226428,0.966258 -20.7788 , -5.8927 , 1.68578 , 0.189157,0.8686,0.457989 -23.3903 , -6.62825 , 2.18244 , 0.755872,0.306273,0.578666 -23.5193 , -6.60525 , 2.60459 , 0.755872,0.306273,0.578666 -23.7072 , -6.599 , 3.03676 , -0.599446,-0.205866,0.773488 -24.8905 , -6.88573 , 3.58017 , 0.528038,0.0530209,-0.847564 -24.8627 , -6.81098 , 4.01893 , 0.528038,0.0530208,-0.847564 -24.3318 , -6.59246 , 4.38744 , -0.205746,-0.195863,0.958805 -21.648 , -5.75945 , 4.39593 , -0.512201,0.806083,-0.296445 -21.7561 , -5.73245 , 4.80225 , 0.636976,-0.763066,0.10951 -21.6958 , -5.65674 , 5.18133 , -0.308964,0.879045,-0.363072 -22.4411 , -5.80598 , 5.73259 , 0.0578168,-0.0460734,0.997264 -20.6443 , -5.25028 , 5.7225 , 0.776426,0.512369,0.366935 -20.4275 , -5.13493 , 6.04488 , 0.934545,0.22631,-0.274608 -25.7453 , -6.51441 , 7.85686 , -0.166718,-0.830243,0.531885 -23.9435 , -5.96194 , 7.81505 , -0.236942,-0.928244,0.286743 -23.0182 , -5.65036 , 7.97846 , -0.184691,-0.0952319,0.978172 -21.0332 , -5.06742 , 7.76327 , -0.859402,0.222859,0.460177 -24.227 , -5.83308 , 9.27191 , -0.220131,0.971083,-0.092407 -25.6091 , -6.11655 , 10.2461 , 0.269091,0.928195,-0.256992 -18.5328 , -4.2557 , 8.00988 , -0.949406,0.196753,0.244778 -18.7965 , -4.26766 , 8.48029 , -0.948816,0.179801,0.259655 -18.6819 , -4.1836 , 8.80441 , -0.922792,-0.352491,0.155581 -17.404 , -3.81729 , 8.60756 , -0.699832,-0.70836,-0.0919805 -19.1532 , -4.18501 , 9.78148 , 0.769265,-0.266775,0.580571 -18.8243 , -4.04745 , 10.0162 , -0.649562,-0.633299,0.420716 -17.7688 , -3.74231 , 9.87131 , 0.603231,0.784828,0.141975 -18.4257 , -3.83709 , 10.5998 , -0.0412049,-0.52412,0.850647 -17.8381 , -3.64486 , 10.6725 , -0.922857,0.344879,0.171446 -17.4225 , -3.4934 , 10.8249 , 0.806988,0.0292839,-0.589841 -19.0104 , -3.78459 , 12.1701 , 0.696598,0.270167,-0.664651 -21.144 , -4.18314 , 13.9386 , -0.332433,-0.503089,0.797741 -20.75 , -4.0255 , 14.177 , 0.104954,-0.34906,0.931204 -19.7148 , -3.73503 , 13.9756 , -0.861093,0.399724,0.314228 -19.7589 , -3.67264 , 14.4863 , 0.50337,-0.416108,0.75728 -19.7675 , -3.6009 , 14.9843 , -0.802552,0.457447,0.382952 -4.09374 , -0.372897 , 4.02771 , 0.470732,0.48297,0.738343 -4.00806 , -0.34229 , 4.05769 , 0.569894,0.49153,0.658498 -3.89215 , -0.305966 , 4.05884 , -0.87839,-0.323211,-0.352089 -3.86508 , -0.286066 , 4.13764 , -0.831634,-0.0294137,-0.554544 -3.98809 , -0.290423 , 4.35994 , 0.487992,0.500502,0.715095 -3.9479 , -0.267219 , 4.43394 , -0.444645,-0.39165,-0.805544 -3.80926 , -0.227742 , 4.40791 , -0.652586,-0.457823,-0.603762 -3.81601 , -0.212553 , 4.52977 , 0.68534,-0.197018,0.701066 -3.7592 , -0.18568 , 4.58638 , -0.941196,-0.201922,-0.270883 -3.70126 , -0.159763 , 4.6421 , 0.194923,0.875644,0.441874 -3.73988 , -0.147091 , 4.81018 , -0.853337,0.52118,-0.0136862 -3.96446 , -0.156585 , 5.21019 , -0.863839,-0.0669263,-0.499302 -3.6968 , -0.102295 , 5.02031 , 0.503902,-0.671674,0.543081 -3.8088 , -0.0945716 , 5.3029 , 0.722565,0.00633528,0.691274 -3.45155 , -0.0329175 , 4.97558 , 0.0937969,0.90911,-0.405858 -3.55657 , -0.0231167 , 5.25985 , -0.529598,-0.272353,-0.803337 -3.53908 , 0.000847775 , 5.38491 , 0.629881,0.0905706,0.771393 -3.60159 , 0.0182391 , 5.6347 , -0.94761,-0.230689,-0.220948 -3.1607 , 0.0796849 , 5.12532 , -0.639095,0.585547,-0.498691 -3.42284 , 0.083364 , 5.69456 , -0.655944,-0.701117,-0.279594 -3.16527 , 0.125678 , 5.44379 , -0.498961,0.845159,-0.191688 -3.05654 , 0.15658 , 5.42737 , 0.0479826,0.542911,0.838418 -2.89149 , 0.189745 , 5.30387 , -0.0405905,0.341238,0.9391 -2.83975 , 0.216966 , 5.37836 , -0.819296,-0.0857833,-0.566917 -2.8649 , 0.242634 , 5.60314 , -0.952407,-0.00180146,0.304823 -3.01144 , 0.269339 , 6.08949 , -0.186062,0.748314,-0.636715 -2.83372 , 0.300664 , 5.93185 , -0.307102,0.562336,-0.767768 -3.02618 , 0.3359 , 6.56997 , 0.0678535,0.320453,0.944831 -2.68208 , 0.362429 , 6.03324 , 0.636196,0.588225,-0.499245 -2.52214 , 0.389923 , 5.88344 , -0.602726,-0.196284,0.77343 -2.42004 , 0.418728 , 5.85977 , 0.692197,0.651117,-0.311304 -2.47779 , 0.458997 , 6.25473 , -0.103676,0.590427,0.800404 -2.36076 , 0.487381 , 6.20105 , 0.656937,0.604012,0.451225 -2.04521 , 0.490131 , 5.55844 , 0.984858,-0.154922,0.0778115 -1.96977 , 0.516917 , 5.58223 , -0.971371,0.142297,-0.190237 -1.90559 , 0.545399 , 5.64287 , 0.366655,-0.660683,0.655029 -1.87021 , 0.581065 , 5.80805 , 0.498987,-0.597851,0.627365 -1.78318 , 0.607166 , 5.79947 , -0.0480808,0.967907,0.246665 -2.02239 , 0.724269 , 7.08588 , -0.987154,-0.158271,-0.0218509 -1.80934 , 0.72285 , 6.63184 , 0.149143,0.506827,-0.849048 -1.69736 , 0.746815 , 6.56288 , 0.0514107,0.892137,0.448831 -1.48838 , 0.726713 , 5.9932 , 0.99498,-0.044046,-0.0898628 -1.48002 , 0.792692 , 6.41792 , 0.728397,0.432144,-0.531686 -1.24071 , 0.734506 , 5.52699 , -0.608923,-0.56065,-0.561146 -1.12555 , 0.730948 , 5.2607 , 0.273628,-0.137106,-0.952013 -1.05225 , 0.751832 , 5.24846 , -0.0265568,0.171475,0.984831 -0.980061 , 0.773159 , 5.24474 , -0.294682,-0.446689,-0.844767 -0.911416 , 0.798395 , 5.26919 , -0.519661,-0.519685,-0.678145 -0.990354 , 1.0548 , 7.16244 , 0.135244,-0.51513,0.846375 -0.834335 , 0.977487 , 6.31431 , -0.60621,-0.640551,0.471384 -0.711633 , 0.905639 , 5.57288 , -0.711785,-0.563214,-0.419706 -0.637296 , 0.940408 , 5.6517 , 0.803897,0.347984,0.482346 -0.562259 , 1.00148 , 5.90717 , 0.131367,0.53285,0.835951 -0.480212 , 1.02333 , 5.88409 , 0.345163,-0.323215,-0.881132 -0.401825 , 1.02776 , 5.75093 , 0.850182,-0.317614,-0.419896 -0.324342 , 1.04183 , 5.68565 , 0.44508,0.85966,0.250778 -0.143131 , 1.37254 , 7.52999 , -0.832365,-0.549008,-0.0758894 -0.071789 , 1.31331 , 6.9868 , 0.540904,0.669209,-0.509492 -2.92091 , -0.928011 , -1.66744 , -0.387778,-0.0236896,0.921448 -2.595 , -0.666859 , -0.640582 , -0.118564,0.161282,0.979761 -2.66837 , -0.691316 , -0.635348 , -0.0546595,0.173687,0.983283 -2.74353 , -0.715721 , -0.627732 , -0.0844728,0.18716,0.978691 -2.80303 , -0.733537 , -0.607044 , -0.0820666,0.188493,0.978639 -2.88708 , -0.760405 , -0.600676 , 0.084534,-0.153931,-0.984459 -2.97072 , -0.787697 , -0.591776 , -0.0520042,0.185083,0.981346 -3.05492 , -0.815629 , -0.580222 , -0.0783639,0.222369,0.971808 -3.13916 , -0.842038 , -0.566337 , -0.0901441,0.177308,0.980018 -3.23311 , -0.872298 , -0.554355 , -0.0531504,0.210613,0.976124 -3.33478 , -0.905867 , -0.54403 , -0.0528624,0.188869,0.980579 -3.43817 , -0.939185 , -0.530447 , -0.0618109,0.187472,0.980323 -3.54924 , -0.975681 , -0.517939 , -0.0522113,0.1937,0.97967 -3.66991 , -1.0157 , -0.505873 , -0.0716306,0.189223,0.979318 -3.78336 , -1.05126 , -0.485998 , -0.334903,0.195292,0.921792 -3.91329 , -1.09381 , -0.469998 , -0.320015,-0.0694191,0.944866 -4.01907 , -1.12514 , -0.438905 , 0.745179,0.0204653,0.66655 -3.91489 , -1.07279 , -0.321161 , -0.969105,-0.152682,-0.193709 -3.90459 , -1.05747 , -0.244391 , 0.996362,0.0803269,0.0284622 -3.90219 , -1.04597 , -0.171515 , 0.992041,0.118114,0.0436416 -3.89788 , -1.03412 , -0.0992705 , 0.995717,0.0924275,-0.00202483 -3.89263 , -1.02215 , -0.0275357 , 0.993752,0.0728494,-0.0845532 -3.92105 , -1.02302 , 0.0326481 , 0.996936,0.0750237,0.0221444 -3.85013 , -0.98605 , 0.121085 , 0.953423,0.0703894,0.293309 -3.84042 , -0.972488 , 0.190072 , 0.994051,0.0641174,-0.0880475 -3.85623 , -0.968862 , 0.251796 , 0.979759,0.057067,-0.191877 -3.86329 , -0.961535 , 0.315836 , 0.924035,-0.0121717,-0.382115 -3.90544 , -0.967576 , 0.372557 , -0.831916,0.00924119,0.554824 -3.93663 , -0.970307 , 0.432133 , 0.696098,-0.0303644,-0.717304 -4.04185 , -0.998914 , 0.480765 , 0.387894,-0.103989,-0.915819 -4.27776 , -1.07446 , 0.51499 , -0.208343,0.15205,0.966165 -8.89216 , -2.70403 , 0.18914 , -0.107861,0.201004,0.973634 -9.47556 , -2.88835 , 0.296637 , 0.10632,-0.196364,-0.97475 -10.3792 , -3.1824 , 0.404669 , 0.0501018,-0.190705,-0.980368 -11.4995 , -3.54755 , 0.53524 , -0.0647616,0.190646,0.97952 -12.7712 , -3.95847 , 0.702129 , -0.0447778,0.187707,0.981204 -14.6857 , -4.58444 , 0.909347 , -0.104732,0.209341,0.972218 -15.6533 , -4.87691 , 1.17751 , -0.130717,0.225,0.965551 -24.4406 , -7.68608 , 2.56826 , -0.615301,-0.45404,0.644401 -23.2854 , -7.24057 , 2.91022 , 0.873105,0.318951,0.368726 -23.2406 , -7.1651 , 3.32186 , -0.720521,-0.459834,0.51904 -25.0136 , -7.68165 , 3.94846 , 0.825742,0.354292,-0.438893 -25.2646 , -7.6971 , 4.43237 , -0.342287,0.410672,0.845097 -26.6465 , -8.07296 , 5.1027 , -0.301449,-0.215893,0.928719 -26.4366 , -7.93577 , 5.54885 , -0.292148,0.563102,0.773023 -21.0867 , -6.18234 , 5.00005 , 0.665016,0.177879,0.725337 -21.3426 , -6.20652 , 5.43758 , 0.289049,-0.0537616,0.955803 -20.6393 , -5.93222 , 5.66624 , 0.639904,-0.13655,0.756225 -20.2592 , -5.76002 , 5.95108 , 0.690587,-0.171448,0.702634 -20.7648 , -5.8594 , 6.46131 , 0.690587,-0.171448,0.702634 -23.1163 , -6.51014 , 7.52251 , -0.230134,-0.935015,0.269788 -23.3818 , -6.52553 , 8.03925 , -0.540872,0.343683,-0.767685 -19.5085 , -5.31747 , 7.22336 , -0.728601,0.672646,0.129178 -27.6084 , -7.63198 , 10.3907 , -0.793096,-0.600304,0.103119 -18.7591 , -4.99107 , 7.69893 , 0.837747,-0.232675,0.494007 -22.2573 , -5.94037 , 9.41048 , 0.0619177,-0.949013,0.309096 -18.5462 , -4.82373 , 8.34763 , 0.957012,-0.16822,-0.236285 -18.8108 , -4.84403 , 8.82954 , 0.960525,-0.15361,-0.23194 -18.9402 , -4.82426 , 9.26705 , -0.939831,0.0535711,0.337414 -19.4928 , -4.91982 , 9.9126 , -0.947504,-0.312423,0.0680365 -18.6764 , -4.63854 , 9.91818 , -0.92491,-0.365486,0.104695 -18.531 , -4.54262 , 10.2373 , 0.615314,0.668969,0.416976 -17.5896 , -4.23542 , 10.1325 , 0.666761,0.68457,0.294609 -19.6749 , -4.72563 , 11.6698 , -0.930441,-0.233722,0.282231 -19.8559 , -4.70896 , 12.2097 , 0.996788,0.0335578,-0.0727108 -19.0122 , -4.42908 , 12.1506 , -0.91024,-0.157026,0.383153 -21.6265 , -5.02367 , 14.2172 , 0.642204,0.23709,-0.728946 -21.8069 , -4.99479 , 14.8407 , 0.613385,0.487667,-0.62124 -22.6316 , -5.12006 , 15.9165 , -0.763065,-0.621745,0.176537 -19.6859 , -4.3292 , 14.4155 , -0.858216,0.497857,0.124914 -19.3403 , -4.17591 , 14.6554 , -0.93486,0.270446,0.229991 -20.3765 , -4.34634 , 15.9234 , -0.895597,0.217986,0.3878 -4.02568 , -0.470458 , 4.06883 , 0.569894,0.49153,0.658498 -3.94787 , -0.438614 , 4.10405 , -0.54915,-0.178228,-0.816498 -3.89961 , -0.41315 , 4.16408 , -0.864278,-0.317337,-0.390282 -4.03568 , -0.425193 , 4.4004 , -0.919066,-0.173421,-0.353896 -3.91888 , -0.38494 , 4.39916 , -0.330521,-0.311193,-0.891019 -3.84358 , -0.354188 , 4.43718 , -0.479677,-0.253023,-0.840172 -3.76156 , -0.321547 , 4.46615 , 0.699035,0.282768,0.656805 -3.85422 , -0.321599 , 4.68306 , -0.71673,-0.332971,-0.612723 -3.66337 , -0.269971 , 4.59242 , -0.694337,0.204243,-0.690059 -3.65233 , -0.250262 , 4.6996 , 0.132982,-0.430193,0.892889 -3.54162 , -0.213812 , 4.69237 , -0.532617,0.493892,-0.687306 -3.88828 , -0.250679 , 5.24818 , 0.543554,0.321928,0.775185 -3.8138 , -0.218672 , 5.29831 , 0.566015,0.160418,0.808636 -3.41613 , -0.137271 , 4.91654 , -0.0851868,-0.803055,0.589784 -3.36526 , -0.11101 , 4.98237 , -0.251793,0.59557,0.762821 -3.135 , -0.0593672 , 4.79402 , 0.188428,-0.42541,-0.885167 -3.17499 , -0.0449617 , 4.9873 , -0.0543607,-0.698974,0.713078 -3.40476 , -0.0515833 , 5.48337 , -0.45713,0.838717,-0.295948 -3.54023 , -0.0424672 , 5.86154 , 0.991409,0.130667,0.00588447 -3.12507 , 0.0263319 , 5.35756 , 0.441356,0.87849,-0.182923 -3.05423 , 0.0571511 , 5.40124 , -0.0218541,-0.868553,-0.495114 -2.94425 , 0.0903516 , 5.37414 , -0.0182237,-0.116615,0.99301 -2.89288 , 0.119783 , 5.4496 , -0.25247,-0.927112,-0.276988 -2.9817 , 0.139818 , 5.79932 , 0.378084,0.902273,0.207259 -2.77921 , 0.179097 , 5.58963 , -0.975778,0.182742,0.120265 -2.73014 , 0.209127 , 5.68085 , -0.877771,-0.449134,-0.166725 -2.7083 , 0.239184 , 5.83515 , -0.666576,-0.731569,0.143119 -2.66233 , 0.270058 , 5.94429 , 0.598404,0.765455,0.236624 -2.5346 , 0.30277 , 5.86829 , 0.683209,0.661687,0.308861 -2.60451 , 0.337626 , 6.27194 , -0.498781,0.196195,-0.844231 -2.55454 , 0.374139 , 6.39843 , -0.0629948,0.0472807,0.996893 -2.40505 , 0.404934 , 6.26183 , 0.652894,0.205315,-0.729092 -2.00152 , 0.41355 , 5.37513 , 0.572331,0.367048,-0.733289 -1.9739 , 0.446442 , 5.53113 , -0.715793,0.472017,-0.514626 -1.82654 , 0.465493 , 5.3151 , 0.231689,0.945212,0.22999 -1.71952 , 0.48713 , 5.21045 , 0.729938,0.596605,-0.333547 -1.79824 , 0.541227 , 5.7681 , -0.138463,-0.983027,-0.120359 -1.85439 , 0.6007 , 6.30949 , 0.496016,0.795325,-0.348463 -1.85459 , 0.657039 , 6.69797 , -0.149143,-0.506827,0.849048 -1.7222 , 0.679557 , 6.54189 , 0.317091,0.194921,-0.928148 -1.62953 , 0.712438 , 6.54915 , 0.0560581,0.881566,0.468721 -1.54541 , 0.749796 , 6.60342 , 0.391236,0.891084,-0.230009 -1.42828 , 0.770047 , 6.46985 , 0.728397,0.432144,-0.531686 -1.15547 , 0.691892 , 5.29056 , -0.203191,0.184515,0.961596 -1.07741 , 0.712086 , 5.24904 , -0.0871154,0.305494,0.948201 -1.00784 , 0.736977 , 5.2555 , -0.305868,-0.356889,-0.882652 -0.940597 , 0.765064 , 5.2903 , -0.450907,-0.428261,-0.783119 -1.04773 , 1.02957 , 7.3526 , -0.52077,0.76766,-0.373491 -0.868788 , 0.936949 , 6.29684 , 0.437653,0.882132,-0.174078 -0.766707 , 0.930349 , 6.01124 , 0.83877,0.396219,-0.373465 -0.66932 , 0.906955 , 5.62494 , -0.677929,-0.491984,-0.546227 -0.59531 , 0.952682 , 5.76205 , -0.918899,0.265402,-0.291868 -0.517498 , 1.0001 , 5.90785 , 0.186937,0.424422,0.885957 -0.436193 , 1.02365 , 5.87355 , -0.52093,-0.104772,0.847145 -0.361407 , 1.01793 , 5.6603 , -0.00927934,-0.897891,0.44012 -0.285211 , 1.04172 , 5.64339 , -0.0368637,-0.433795,0.900257 --0.0409651 , 1.71695 , 9.51297 , 0.288677,-0.94473,-0.155407 -0.0218165 , 1.3255 , 6.97066 , -0.928743,0.259462,-0.264793 -2.54567 , -0.712424 , -0.640545 , -0.141455,0.177328,0.973933 -2.6043 , -0.731987 , -0.624255 , -0.134867,0.168747,0.976389 -2.67714 , -0.75815 , -0.617751 , -0.0416286,0.203405,0.978209 -2.75153 , -0.785255 , -0.608862 , -0.0861287,0.210811,0.973725 -2.82576 , -0.811855 , -0.597736 , -0.0934393,0.20688,0.973894 -2.90081 , -0.838209 , -0.584446 , -0.0770664,0.205784,0.975558 -2.9839 , -0.867185 , -0.574178 , -0.0667829,0.201547,0.977199 -3.06754 , -0.896756 , -0.561063 , -0.0676957,0.183275,0.980728 -3.15993 , -0.930006 , -0.550166 , -0.0773985,0.190798,0.978573 -3.25307 , -0.962834 , -0.536326 , -0.0662808,0.176009,0.982155 -3.35394 , -0.998972 , -0.524144 , -0.0573994,0.195372,0.979048 -3.45629 , -1.03579 , -0.508411 , -0.0614921,0.196686,0.978536 -3.56655 , -1.07483 , -0.493948 , -0.0496611,0.190441,0.980442 -3.68616 , -1.11833 , -0.479634 , -0.072363,0.195906,0.977949 -3.80669 , -1.16023 , -0.461603 , -0.327233,0.178622,0.927908 -3.92768 , -1.20244 , -0.439459 , 0.554589,0.11179,-0.824581 -4.01449 , -1.23029 , -0.399052 , 0.981178,0.0635286,0.182357 -3.90245 , -1.17031 , -0.279199 , -0.976051,-0.115965,-0.184057 -3.91763 , -1.1664 , -0.211829 , 0.998111,0.0581772,0.0197325 -3.91517 , -1.15474 , -0.138273 , 0.997963,0.0628502,0.0109605 -3.90105 , -1.13872 , -0.0626664 , 0.996483,0.0835917,0.00585274 -3.89481 , -1.12644 , 0.00933669 , 0.992945,0.0610025,0.101678 -3.9239 , -1.1283 , 0.070617 , 0.984758,0.119679,0.126206 -3.85249 , -1.08923 , 0.158441 , 0.956817,0.149304,0.249421 -3.86024 , -1.08292 , 0.223479 , 0.989429,0.119454,-0.082221 -3.85828 , -1.07276 , 0.29042 , 0.973813,0.0617766,-0.218797 -3.87304 , -1.06867 , 0.353093 , -0.918038,-0.00800255,0.396413 -3.94175 , -1.08732 , 0.406109 , -0.761528,0.0239523,0.64769 -3.9726 , -1.09069 , 0.467244 , 0.566578,-0.0878897,-0.819308 -4.1221 , -1.14057 , 0.511849 , 0.266432,-0.167658,-0.94916 -9.01156 , -3.01046 , 0.283276 , -0.103634,0.200728,0.97415 -9.7097 , -3.25729 , 0.393704 , -0.0722728,0.191801,0.978769 -10.7252 , -3.62187 , 0.513256 , -0.046742,0.191863,0.980308 -11.8341 , -4.01623 , 0.666738 , -0.06406,0.190136,0.979666 -13.5412 , -4.63103 , 0.852281 , -0.0585857,0.1864,0.980726 -15.0047 , -5.14634 , 1.09969 , -0.136693,0.213955,0.967232 -16.4285 , -5.63881 , 1.39973 , -0.129751,0.219813,0.966875 -24.1297 , -8.38374 , 2.44569 , -0.713956,-0.452241,0.53455 -25.1447 , -8.69145 , 2.96053 , 0.6441,0.390257,-0.657901 -26.4976 , -9.11564 , 3.54556 , -0.679076,-0.351418,0.644485 -26.2784 , -8.96895 , 4.001 , -0.681586,-0.588572,0.434769 -26.4159 , -8.94965 , 4.49667 , 0.635972,0.589323,-0.498235 -25.9108 , -8.70172 , 4.90096 , -0.447688,-0.891556,0.0685795 -25.9213 , -8.63834 , 5.37629 , -0.447688,-0.891556,0.0685796 -21.2111 , -6.92771 , 4.95984 , 0.58042,0.284295,0.763078 -21.783 , -7.06922 , 5.46776 , 0.42935,0.403822,0.807828 -24.2864 , -7.8721 , 6.43804 , 0.706999,-0.200994,0.678052 -19.9822 , -6.34056 , 5.8308 , 0.131448,0.165237,0.977455 -20.4137 , -6.43377 , 6.31766 , -0.57671,-0.00856403,-0.816904 -18.7109 , -5.80777 , 6.21667 , 0.600564,-0.542418,0.587457 -18.8391 , -5.80026 , 6.60885 , -0.85115,0.473143,-0.227332 -19.1328 , -5.84521 , 7.06231 , 0.626586,0.622771,-0.468557 -20.9895 , -6.39972 , 8.06708 , 0.744035,-0.205562,-0.635732 -19.8802 , -5.98274 , 8.07292 , -0.147909,0.949367,0.277172 -18.3199 , -5.42576 , 7.86511 , -0.944572,0.0819949,-0.317901 -18.1491 , -5.31937 , 8.15872 , -0.927863,0.14717,0.342655 -18.6805 , -5.43512 , 8.74754 , -0.859666,-0.0149644,0.510637 -18.7244 , -5.39489 , 9.146 , -0.917641,0.066292,0.391842 -19.4768 , -5.57187 , 9.88106 , -0.933193,0.349764,0.0825621 -21.4581 , -6.12097 , 11.2534 , -0.7528,-0.215231,-0.622067 -19.163 , -5.36064 , 10.5398 , 0.791556,0.530068,0.304084 -19.0445 , -5.26632 , 10.8884 , -0.943282,-0.331166,-0.0234036 -19.0643 , -5.21228 , 11.3145 , -0.920613,-0.168743,0.352133 -19.3863 , -5.24682 , 11.9231 , -0.919071,-0.120266,0.375294 -20.8263 , -5.60197 , 13.2239 , 0.801803,-0.597458,0.0125152 -19.6255 , -5.18881 , 12.955 , 0.588877,0.806607,-0.05109 -20.218 , -5.29109 , 13.7983 , 0.87098,0.490982,0.0181902 -19.2295 , -4.94589 , 13.6176 , 0.98605,0.121836,0.113409 -19.2824 , -4.89301 , 14.1233 , 0.997951,0.043706,0.0467274 -19.4759 , -4.8776 , 14.7431 , 0.96718,0.198402,-0.158741 -19.7948 , -4.89253 , 15.4779 , -0.88945,-0.0247301,0.456362 -5.05036 , -0.835911 , 5.08198 , -0.457914,0.841149,-0.287721 -5.05261 , -0.816898 , 5.22196 , 0.612103,-0.790316,-0.0270158 -4.2515 , -0.603874 , 4.60249 , 0.325123,0.910773,0.254535 -3.95544 , -0.517276 , 4.43311 , 0.770373,0.557434,0.309503 -3.92983 , -0.494701 , 4.52149 , 0.546609,0.627919,0.554019 -4.05159 , -0.505425 , 4.76734 , -0.445642,-0.890412,-0.0925772 -3.83863 , -0.440863 , 4.66196 , 0.442046,0.812697,0.37963 -3.70818 , -0.395528 , 4.63851 , 0.425669,0.48939,0.76112 -3.58018 , -0.350507 , 4.6114 , -0.713492,-0.213137,-0.66746 -3.59999 , -0.337975 , 4.75632 , -0.24048,-0.224474,0.944342 -3.70903 , -0.341144 , 5.01833 , -0.951226,-0.016157,0.308073 -3.91391 , -0.360521 , 5.41808 , 0.755433,0.274412,0.594995 -3.76034 , -0.310245 , 5.36547 , -0.586183,-0.363383,-0.724114 -3.69078 , -0.27618 , 5.42126 , 0.498546,0.435782,0.749364 -3.18579 , -0.167161 , 4.85689 , 0.188428,-0.42541,-0.885167 -3.09068 , -0.132784 , 4.85325 , -0.188428,0.42541,0.885167 -3.0627 , -0.108461 , 4.94723 , 0.132638,-0.551238,0.823738 -3.26076 , -0.117607 , 5.40337 , 0.0244421,0.122191,0.992206 -3.42996 , -0.118055 , 5.84162 , 0.329709,0.584308,0.741536 -3.47854 , -0.0994338 , 6.10602 , 0.442393,-0.502275,0.742973 -3.03827 , -0.0169379 , 5.52153 , 0.124649,0.167751,0.977917 -2.84672 , 0.029584 , 5.34462 , 0.638873,-0.356422,0.681766 -2.87014 , 0.0517361 , 5.56051 , -0.0982381,-0.815056,0.570994 -2.74271 , 0.0902096 , 5.49237 , 0.107747,-0.896697,0.42933 -2.63216 , 0.125298 , 5.44836 , -0.110494,-0.676473,0.728131 -2.75329 , 0.143835 , 5.90043 , 0.426276,-0.702694,0.569658 -2.66709 , 0.179507 , 5.91874 , -0.919265,0.322553,-0.225635 -2.65827 , 0.210733 , 6.11959 , -0.940781,-0.292311,-0.171715 -2.64302 , 0.245763 , 6.32095 , 0.863269,0.181228,0.471087 -2.52828 , 0.282634 , 6.28054 , -0.304154,-0.0631138,0.95053 -2.11528 , 0.315032 , 5.42117 , -0.59001,-0.403831,0.699149 -2.02763 , 0.344829 , 5.39927 , 0.00903493,0.342614,0.939433 -1.93116 , 0.373668 , 5.34703 , 0.421115,0.859979,0.288269 -1.81393 , 0.399815 , 5.21644 , 0.231689,0.945212,0.22999 -1.73661 , 0.427632 , 5.20749 , 0.231689,0.945212,0.22999 -2.02024 , 0.503962 , 6.48719 , 0.76691,0.610456,-0.197969 -1.81528 , 0.519799 , 6.06521 , -0.832122,0.54164,-0.119155 -1.98669 , 0.607246 , 7.1225 , -0.691035,-0.624213,0.364457 -1.77211 , 0.618656 , 6.63728 , -0.149143,-0.506827,0.849048 -1.68009 , 0.655641 , 6.65496 , 0.317091,0.194921,-0.928148 -1.65998 , 0.718066 , 7.04343 , 0.390273,-0.915498,-0.097731 -1.47513 , 0.71984 , 6.56753 , -0.51822,-0.480445,0.707546 -1.22804 , 0.674108 , 5.5956 , -0.282076,0.287814,0.915203 -1.10557 , 0.673536 , 5.26909 , -0.0449821,0.390858,0.919351 -1.03444 , 0.699971 , 5.26594 , 0.166465,0.38045,0.909696 -0.965367 , 0.726656 , 5.27152 , 0.299723,0.392417,0.869583 -0.993124 , 0.866809 , 6.32513 , -0.73591,-0.66419,0.131482 -0.919213 , 0.918738 , 6.49733 , -0.838327,-0.523527,0.152077 -0.814596 , 0.923159 , 6.25171 , -0.179845,0.923328,0.339296 -0.702673 , 0.880201 , 5.65742 , -0.531204,-0.680511,-0.504705 -0.626753 , 0.911318 , 5.67619 , 0.791042,0.398315,0.464326 -0.553354 , 0.973033 , 5.91139 , 0.442901,0.154139,0.883222 -0.47248 , 1.00072 , 5.89757 , 0.345163,-0.323215,-0.881132 -0.395927 , 1.00369 , 5.71399 , -0.736011,0.277756,0.617364 -0.321547 , 1.02214 , 5.64816 , -0.408467,-0.444538,0.797208 -0.139856 , 1.35703 , 7.51208 , -0.832365,-0.549008,-0.0758894 -0.0703957 , 1.30753 , 6.98769 , -0.153299,0.795199,0.58665 -2.5019 , -0.759585 , -0.64662 , -0.185602,0.210277,0.959862 -2.55306 , -0.777209 , -0.624849 , -0.17375,0.194626,0.965366 -2.61822 , -0.802495 , -0.613153 , -0.118731,0.208734,0.970739 -2.68325 , -0.827363 , -0.599608 , -0.0895577,0.173258,0.980796 -2.7571 , -0.856174 , -0.58945 , 0.0805618,-0.189924,-0.978488 -2.83081 , -0.884523 , -0.577248 , -0.0789614,0.189772,0.978648 -2.9133 , -0.916661 , -0.56775 , -0.0734947,0.193608,0.978322 -2.98739 , -0.945145 , -0.550657 , -0.0604593,0.174355,0.982825 -3.08642 , -0.984469 , -0.545911 , -0.0734292,0.18486,0.980018 -3.16909 , -1.01608 , -0.528604 , -0.0741582,0.174164,0.98192 -3.26915 , -1.05642 , -0.517384 , -0.0650067,0.183405,0.980886 -3.36922 , -1.09513 , -0.503346 , -0.0705415,0.18775,0.979681 -3.47867 , -1.1384 , -0.489943 , -0.0500958,0.191292,0.980254 -3.59675 , -1.18497 , -0.477103 , -0.0654422,0.196347,0.978348 -3.70665 , -1.22685 , -0.456477 , -0.0722566,0.183992,0.980268 -3.83474 , -1.27716 , -0.43958 , 0.207021,-0.201346,-0.957394 -3.96252 , -1.32653 , -0.418499 , 0.741707,-0.206206,-0.63824 -3.98121 , -1.32404 , -0.348698 , -0.961635,0.148489,0.230673 -3.92071 , -1.28538 , -0.249793 , 0.988076,0.0902398,0.124753 -3.90939 , -1.26967 , -0.172365 , 0.997179,0.0748984,-0.00484638 -3.9233 , -1.26635 , -0.104238 , 0.995637,0.0908929,0.0211276 -3.90914 , -1.25019 , -0.0280479 , 0.991891,0.110546,-0.0627039 -3.91162 , -1.24155 , 0.041932 , 0.994032,0.0997923,0.0440724 -3.9482 , -1.24765 , 0.101849 , 0.988037,0.119903,0.096989 -3.87722 , -1.20655 , 0.189862 , 0.96308,0.191974,0.188742 -3.87518 , -1.19614 , 0.257873 , -0.984677,-0.132072,0.113879 -3.89062 , -1.19303 , 0.32174 , -0.943296,-0.0950196,0.318063 -3.89634 , -1.18604 , 0.387607 , -0.885754,0.00929526,0.464061 -3.95479 , -1.20248 , 0.444087 , -0.834674,0.030667,0.54989 -3.99401 , -1.21007 , 0.50505 , -0.622951,0.0921068,0.776819 -4.20636 , -1.29137 , 0.544166 , -0.181331,0.152964,0.971453 -8.67704 , -3.16347 , 0.260532 , -0.108436,0.209642,0.971747 -9.23767 , -3.37792 , 0.372832 , -0.0921524,0.205146,0.974383 -9.97444 , -3.66222 , 0.49573 , -0.0571291,0.189194,0.980277 -11.1072 , -4.10835 , 0.630714 , -0.0590582,0.194015,0.979219 -12.3142 , -4.57824 , 0.805895 , -0.0483483,0.18741,0.981091 -14.2798 , -5.35308 , 1.02525 , -0.111881,0.185893,0.97618 -15.392 , -5.76991 , 1.30237 , -0.142011,0.203489,0.968723 -24.8128 , -9.41803 , 2.83049 , 0.444115,-0.105531,-0.889733 -25.8487 , -9.76576 , 3.37997 , -0.507474,-0.00231146,0.861664 -26.8756 , -10.1044 , 3.96775 , 0.689123,0.107465,-0.716631 -27.8916 , -10.4335 , 4.59338 , -0.621396,-0.724432,0.298437 -27.6147 , -10.2532 , 5.06612 , -0.70146,0.050353,0.710927 -28.5841 , -10.5568 , 5.73874 , 0.419288,0.903987,0.0836993 -24.7756 , -9.02041 , 5.55977 , 0.540979,0.429206,0.723273 -23.6379 , -8.52316 , 5.78703 , 0.327678,0.761911,0.558676 -30.7816 , -11.1648 , 7.83034 , -0.35969,-0.929984,-0.0758515 -23.8397 , -8.47518 , 6.72074 , 0.816822,-0.148567,0.557432 -19.8985 , -6.94188 , 6.13521 , 0.0841777,0.231279,0.969239 -18.7782 , -6.47404 , 6.19576 , -0.577984,0.197172,-0.79187 -18.9787 , -6.49801 , 6.61381 , 0.731168,-0.0461208,0.680636 -22.7785 , -7.83297 , 8.19944 , 0.70971,-0.133986,0.691636 -18.8738 , -6.35712 , 7.30962 , -0.899329,0.276445,-0.3388 -21.2704 , -7.16684 , 8.54495 , -0.226496,0.169395,0.959169 -22.0507 , -7.38564 , 9.26368 , 0.0462366,0.439311,0.897145 -18.2481 , -5.97931 , 8.17586 , -0.966866,-0.142278,0.211962 -18.8108 , -6.12552 , 8.78192 , -0.902324,-0.0771598,0.424097 -19.099 , -6.1717 , 9.29384 , 0.986972,-0.04099,-0.155585 -18.9699 , -6.07232 , 9.62894 , -0.780029,0.465867,-0.41776 -18.466 , -5.84438 , 9.78116 , 0.779372,-0.245372,0.576517 -18.721 , -5.87606 , 10.3032 , 0.693414,-0.674222,0.254168 -19.4985 , -6.08028 , 11.1193 , -0.872048,0.0289852,0.488562 -18.8359 , -5.80039 , 11.1804 , -0.761792,0.500695,0.411068 -19.4666 , -5.94984 , 11.9636 , -0.898779,0.0270681,0.437566 -22.0296 , -6.72371 , 13.9405 , -0.281344,0.371724,0.884685 -22.3095 , -6.74254 , 14.6251 , -0.405476,0.0727594,0.911206 -22.988 , -6.88602 , 15.5905 , -0.0399396,-0.233225,0.971602 -20.3275 , -5.96768 , 14.3558 , -0.898248,-0.345532,-0.271586 -19.7597 , -5.72072 , 14.4576 , -0.92292,-0.34605,0.168728 -19.995 , -5.72439 , 15.1215 , -0.885877,-0.451375,-0.107158 -5.05967 , -1.06085 , 4.69765 , 0.998757,0.00994785,0.0488441 -4.92846 , -1.00442 , 4.71666 , -0.69774,0.524504,-0.487908 -4.92359 , -0.984968 , 4.84008 , 0.653493,-0.675247,0.342035 -5.01161 , -0.991868 , 5.04884 , 0.798754,-0.599151,0.0548631 -5.00678 , -0.971501 , 5.18182 , -0.581546,0.715144,-0.38778 -4.91432 , -0.926062 , 5.23467 , -0.289552,0.859872,0.420451 -4.33093 , -0.746929 , 4.80322 , -0.458472,-0.86139,-0.218659 -4.35565 , -0.736272 , 4.95509 , 0.47337,0.814572,0.335251 -4.30107 , -0.703015 , 5.02996 , 0.530363,0.773108,0.347878 -3.91237 , -0.584453 , 4.74182 , -0.376439,-0.922601,-0.0842723 -3.75607 , -0.526815 , 4.69105 , -0.507216,-0.581218,-0.636331 -4.00175 , -0.571292 , 5.09961 , 0.63812,0.468774,0.610781 -3.93205 , -0.534531 , 5.15303 , -0.796664,-0.292287,-0.529051 -3.91679 , -0.511875 , 5.27444 , -0.850086,-0.423083,-0.313615 -3.87408 , -0.481475 , 5.36492 , -0.699795,-0.169294,-0.693993 -3.81252 , -0.447172 , 5.43143 , -0.791516,-0.00322038,-0.61114 -3.77806 , -0.417882 , 5.53655 , -0.891908,-0.178918,-0.415317 -3.7643 , -0.393264 , 5.67428 , -0.885693,-0.241359,-0.396603 -3.15466 , -0.245953 , 4.94144 , -0.959487,0.260335,0.107753 -3.08212 , -0.212526 , 4.97033 , -0.959487,0.260336,0.107753 -3.55805 , -0.281926 , 5.8633 , 0.859452,0.242855,0.449848 -3.44522 , -0.236608 , 5.85576 , 0.615971,0.37403,0.693312 -2.97931 , -0.131204 , 5.24465 , -0.0144636,-0.525358,0.850758 -2.88264 , -0.0935839 , 5.2345 , 0.434618,-0.40569,0.804066 -2.84541 , -0.0651405 , 5.32717 , -0.467654,0.175897,-0.866233 -3.09705 , -0.0781123 , 5.97586 , 0.208714,-0.00338986,0.977971 -2.72598 , -0.000582028 , 5.43999 , -0.104926,-0.728106,0.677386 -2.62507 , 0.0368922 , 5.41393 , -0.0278878,-0.605163,0.795613 -2.54326 , 0.072445 , 5.4217 , -0.450903,0.610319,-0.651305 -2.51352 , 0.101483 , 5.54645 , -0.295304,0.581752,-0.757866 -2.72447 , 0.112331 , 6.2411 , -0.848644,-0.283973,-0.446276 -2.64086 , 0.151054 , 6.27722 , -0.516445,-0.265753,-0.814039 -2.56457 , 0.190382 , 6.33008 , 0.219794,-0.0933693,0.971068 -2.12446 , 0.241488 , 5.40691 , 0.42154,0.669051,0.612107 -2.05412 , 0.273694 , 5.43253 , 0.39405,0.60655,0.690523 -1.9682 , 0.305977 , 5.40948 , 0.00903494,0.342614,0.939433 -1.89411 , 0.337595 , 5.42272 , -0.676437,-0.735804,-0.0320274 -1.84395 , 0.370471 , 5.51116 , 0.9717,-0.105037,0.211579 -2.14445 , 0.434773 , 6.84932 , 0.917309,-0.00441243,0.398151 -1.84341 , 0.452038 , 6.09134 , -0.834682,0.0520161,0.54827 -1.74757 , 0.486703 , 6.05273 , 0.74189,-0.151696,-0.653136 -1.70717 , 0.529452 , 6.24606 , 0.0505475,-0.945633,0.321282 -1.54985 , 0.54939 , 5.92106 , -0.735118,-0.392132,0.553023 -1.529 , 0.600605 , 6.22925 , -0.84057,-0.526773,-0.126305 -1.47156 , 0.646149 , 6.39036 , -0.889462,-0.339621,0.305803 -1.24924 , 0.623794 , 5.57596 , 0.784053,-0.426854,0.450619 -1.13209 , 0.632214 , 5.28903 , -0.0248545,0.321673,0.946525 -1.06136 , 0.660751 , 5.28637 , 0.201573,0.569052,0.797213 -0.991708 , 0.688764 , 5.28246 , -0.287436,-0.375976,-0.880922 -0.932586 , 0.72703 , 5.38618 , 0.751096,0.55431,0.358601 -0.951376 , 0.872421 , 6.47966 , -0.838327,-0.523527,0.152077 -0.827728 , 0.849286 , 5.9568 , -0.843646,-0.144522,0.517083 -0.741384 , 0.866214 , 5.81867 , 0.433223,0.0690455,0.898638 -0.658596 , 0.879917 , 5.67938 , 0.673934,0.531181,0.513478 -0.585775 , 0.932485 , 5.83569 , -0.887995,0.165386,-0.429083 -0.507363 , 0.975994 , 5.92138 , 0.186937,0.424422,0.885957 -0.42865 , 0.998964 , 5.85698 , -0.536703,0.300364,0.7885 -0.357903 , 0.994331 , 5.61325 , 0.113791,-0.700552,0.704471 -0.28288 , 1.02395 , 5.6056 , 0.285098,-0.300984,0.910015 --0.0449653 , 1.70364 , 9.50479 , 0.288677,-0.94473,-0.155407 -0.0211234 , 1.3226 , 6.97106 , -0.928743,0.259462,-0.264793 -2.50128 , -0.820204 , -0.625471 , -0.162934,0.242299,0.956422 -2.56531 , -0.846446 , -0.614672 , -0.152351,0.222068,0.963055 -2.62289 , -0.869463 , -0.596036 , -0.0978443,0.186954,0.977484 -2.69516 , -0.901177 , -0.586573 , -0.0809358,0.180956,0.980155 -2.7675 , -0.931456 , -0.575168 , -0.0956707,0.165306,0.981591 -2.84066 , -0.961488 , -0.561598 , -0.066647,0.160291,0.984817 -2.92937 , -1.00008 , -0.555525 , -0.07664,0.186598,0.979442 -3.01162 , -1.03545 , -0.541614 , -0.06372,0.192254,0.979274 -3.09392 , -1.0693 , -0.525372 , -0.0672791,0.178065,0.981716 -3.19169 , -1.11146 , -0.515556 , -0.0798833,0.166111,0.982866 -3.28324 , -1.14945 , -0.4981 , -0.0862237,0.196201,0.976765 -3.38226 , -1.19165 , -0.481911 , -0.0699651,0.182924,0.980634 -3.48993 , -1.23723 , -0.466577 , -0.0522974,0.180343,0.982212 -3.60696 , -1.28728 , -0.451489 , -0.0669781,0.189389,0.979615 -3.72467 , -1.33669 , -0.432486 , -0.079872,0.182236,0.980006 -3.85073 , -1.3902 , -0.413169 , 0.26136,-0.230484,-0.937319 -3.99391 , -1.45164 , -0.396436 , 0.989645,-0.0899953,-0.111817 -3.93546 , -1.41207 , -0.295736 , 0.986294,-0.132661,-0.0981051 -3.92598 , -1.3965 , -0.216802 , 0.98969,0.0658635,0.127183 -3.93199 , -1.38932 , -0.144585 , 0.995638,0.0926285,-0.0111614 -3.92727 , -1.3779 , -0.0698081 , 0.994412,0.104936,0.0115836 -3.93063 , -1.36918 , 0.00155724 , 0.994342,0.101294,-0.0319961 -3.91572 , -1.35184 , 0.0775267 , 0.99796,0.0455927,0.0446869 -3.95177 , -1.35964 , 0.138714 , 0.991057,0.0642467,0.116955 -3.88903 , -1.32008 , 0.224091 , 0.975582,0.137508,0.171264 -3.8964 , -1.3143 , 0.291175 , 0.991684,0.060978,-0.113335 -3.90182 , -1.30807 , 0.358115 , 0.962154,0.0172578,-0.271959 -3.91618 , -1.30443 , 0.423223 , -0.896329,0.044877,0.441113 -3.96439 , -1.3187 , 0.482973 , 0.756777,-0.0377359,-0.652583 -4.05738 , -1.35245 , 0.537815 , 0.471072,-0.0732474,-0.879048 -4.34861 , -1.47646 , 0.57169 , -0.181162,0.145368,0.97265 -8.7601 , -3.4661 , 0.354905 , -0.104103,0.205221,0.973163 -9.46053 , -3.76112 , 0.468782 , 0.0811301,-0.197943,-0.97685 -10.3971 , -4.15977 , 0.598265 , -0.0482046,0.196652,0.979288 -11.5434 , -4.64733 , 0.757493 , -0.0619328,0.192583,0.979324 -13.0733 , -5.29937 , 0.957058 , -0.0408816,0.185553,0.981784 -14.8674 , -6.06101 , 1.21761 , 0.145042,-0.184079,-0.972151 -16.121 , -6.57519 , 1.52868 , -0.124029,0.144625,0.981682 -25.9019 , -10.6813 , 3.27566 , -0.357829,0.323664,0.8759 -26.6729 , -10.9459 , 3.83844 , -0.325256,0.840202,0.433901 -29.3069 , -12.003 , 4.66598 , 0.368792,-0.718888,-0.589231 -26.6082 , -10.7827 , 4.82168 , -0.208158,0.95676,0.203178 -26.9957 , -10.8791 , 5.38246 , -0.189121,0.95741,0.218173 -27.3294 , -10.9493 , 5.94956 , -0.285308,0.638719,0.714589 -28.8777 , -11.524 , 6.77719 , -0.440753,0.627209,0.642142 -28.7902 , -11.4129 , 7.30446 , -0.242256,0.890091,0.38607 -23.2778 , -9.07124 , 6.52456 , -0.770707,0.310732,-0.556288 -23.5052 , -9.1032 , 7.02741 , -0.770707,0.310732,-0.556288 -18.96 , -7.19692 , 6.20605 , 0.571027,-0.0413391,0.81989 -19.6246 , -7.41499 , 6.76973 , -0.0430272,0.187223,0.981375 -22.8675 , -8.66162 , 8.18672 , 0.666006,-0.197345,0.719368 -18.118 , -6.71074 , 7.02215 , -0.863737,0.41142,-0.291018 -18.318 , -6.74075 , 7.45086 , -0.944321,0.290612,-0.154282 -20.4761 , -7.5375 , 8.63599 , -0.13005,0.955414,-0.265088 -18.4315 , -6.68532 , 8.22881 , -0.929351,-0.142314,0.340666 -18.7994 , -6.77598 , 8.75837 , 0.971655,0.0164287,-0.235833 -19.1121 , -6.84332 , 9.28378 , 0.995145,-0.0806604,0.0563883 -18.7117 , -6.63601 , 9.49577 , -0.8745,0.136736,-0.465353 -18.7684 , -6.60344 , 9.91828 , -0.804572,0.15494,-0.573287 -18.3437 , -6.39023 , 10.1043 , -0.853076,0.174307,-0.491811 -18.0786 , -6.2366 , 10.361 , -0.853076,0.174307,-0.491811 -18.2172 , -6.23348 , 10.8356 , 0.876319,-0.47006,0.105398 -19.9821 , -6.82226 , 12.2596 , -0.93813,0.206775,0.27777 -19.9967 , -6.76528 , 12.7242 , -0.93813,0.206775,0.27777 -19.9294 , -6.67787 , 13.1464 , -0.790314,0.61262,0.0100681 -19.6616 , -6.51827 , 13.4438 , -0.919697,0.389328,-0.0508152 -20.728 , -6.82903 , 14.6337 , 0.253961,0.925674,-0.280413 -20.06 , -6.52722 , 14.6775 , -0.9697,-0.00946419,0.244118 -20.1131 , -6.47644 , 15.2189 , -0.933417,-0.339865,0.115001 -5.03558 , -1.21995 , 4.68204 , 0.67787,0.0826584,0.73052 -4.91309 , -1.16213 , 4.70806 , 0.67787,0.0826583,0.73052 -4.85742 , -1.12661 , 4.78748 , -0.78638,0.288592,-0.546188 -4.82965 , -1.10019 , 4.89179 , 0.890836,-0.37457,0.257114 -4.85769 , -1.09038 , 5.04862 , -0.536759,0.795906,-0.280042 -4.78959 , -1.05031 , 5.11991 , -0.35216,0.722454,-0.595015 -4.6711 , -0.995372 , 5.14185 , 0.249924,-0.130325,0.959455 -4.58075 , -0.948634 , 5.18829 , -0.0442122,-0.344275,0.937827 -4.38883 , -0.871917 , 5.12614 , -0.427609,-0.881391,-0.200748 -4.28014 , -0.821137 , 5.14481 , -0.0646512,0.97059,0.231897 -4.40651 , -0.838598 , 5.4245 , 0.40421,0.896685,0.180475 -4.26749 , -0.779493 , 5.41158 , -0.0515142,-0.836286,0.545868 -4.0621 , -0.700972 , 5.31163 , -0.0693651,0.00302176,0.997587 -3.99563 , -0.663094 , 5.37429 , -0.630826,-0.334458,-0.70014 -3.8742 , -0.610603 , 5.36573 , 0.765319,0.264034,0.587003 -3.79539 , -0.569493 , 5.40896 , -0.855026,-0.0708545,-0.513721 -3.74521 , -0.535949 , 5.49046 , -0.918553,-0.197354,-0.342509 -3.69916 , -0.502961 , 5.57928 , -0.944501,0.0408362,-0.325961 -3.7285 , -0.489114 , 5.78248 , 0.0528876,0.779924,0.623636 -3.06599 , -0.30985 , 4.9429 , 0.40935,0.547556,0.729805 -3.12746 , -0.304297 , 5.17996 , -0.865578,0.277269,-0.417009 -3.23983 , -0.308231 , 5.51321 , 0.332955,-0.671392,0.662097 -3.10934 , -0.258033 , 5.45741 , -0.148984,0.988749,-0.0133758 -2.92139 , -0.196963 , 5.29414 , 0.964101,-0.211913,0.160004 -2.82643 , -0.156814 , 5.28304 , 0.558739,-0.278362,0.781234 -3.11718 , -0.187211 , 6.00086 , -0.132246,0.936939,0.323507 -2.70183 , -0.0883405 , 5.37814 , 0.11084,-0.615761,0.780098 -2.58126 , -0.0437479 , 5.30718 , 0.0915347,-0.423779,0.901129 -2.54764 , -0.0142777 , 5.41417 , -0.508924,0.468261,-0.722308 -2.63825 , -0.00122229 , 5.80333 , -0.863664,-0.0113531,0.503939 -2.72877 , 0.015276 , 6.22418 , 0.675112,0.416443,0.608933 -2.65474 , 0.0565387 , 6.27894 , 0.40404,0.325494,0.854872 -2.5679 , 0.0981002 , 6.30461 , 0.208384,0.37849,0.901843 -2.45976 , 0.141324 , 6.27229 , 0.37892,0.143158,0.91429 -2.07227 , 0.200646 , 5.44657 , -0.394051,-0.60655,-0.690523 -1.986 , 0.23624 , 5.42388 , -0.356054,-0.786507,-0.504612 -1.95932 , 0.269027 , 5.5805 , -0.485773,-0.0923562,-0.869192 -2.1955 , 0.306755 , 6.61736 , 0.418037,-0.714278,0.561295 -2.16161 , 0.350938 , 6.83551 , -0.820314,0.499941,-0.277748 -1.9211 , 0.385685 , 6.31019 , -0.878633,0.133394,0.458487 -1.77868 , 0.420182 , 6.09855 , 0.686031,-0.375608,0.623121 -1.6893 , 0.457058 , 6.07832 , 0.0630064,-0.631925,0.772465 -1.57251 , 0.488701 , 5.92915 , 0.811955,0.295697,-0.503282 -1.53773 , 0.535586 , 6.15927 , -0.307399,-0.951029,-0.0323877 -1.45862 , 0.573816 , 6.18319 , 0.679616,0.71941,0.143428 -1.26237 , 0.571334 , 5.52619 , 0.753855,-0.464299,0.464897 -1.15522 , 0.588604 , 5.29896 , 0.0569987,0.342412,0.937819 -1.08688 , 0.619732 , 5.30658 , 0.182507,0.589848,0.78662 -1.01568 , 0.64929 , 5.29305 , 0.214086,0.564203,0.797397 -0.992963 , 0.720052 , 5.73382 , -0.574827,-0.660102,-0.483569 -0.96947 , 0.810244 , 6.32308 , -0.73591,-0.66419,0.131482 -0.890252 , 0.857419 , 6.40521 , -0.79176,-0.563522,0.235709 -0.764423 , 0.815376 , 5.69228 , 0.763676,0.643763,0.0486659 -0.758081 , 1.05304 , 7.40846 , 0.0057338,-0.724068,0.689705 -0.615525 , 0.886421 , 5.73021 , 0.808248,0.424109,0.408494 -0.550628 , 1.09537 , 7.04538 , 0.164903,-0.889557,0.426024 -0.460907 , 1.0186 , 6.18788 , -0.45829,-0.226385,-0.859488 -0.38791 , 0.990277 , 5.74612 , 0.687701,-0.561449,-0.460264 -0.317783 , 1.00266 , 5.61054 , -0.149461,-0.781325,0.605964 -0.240165 , 1.04393 , 5.66102 , 0.374062,-0.829788,0.414161 -0.0663552 , 1.3054 , 7.00802 , 0.0289341,0.961282,0.274043 -2.50457 , -0.885102 , -0.610158 , -0.146345,0.242003,0.959176 -2.56079 , -0.910049 , -0.592319 , -0.0875106,0.244703,0.965641 -2.63971 , -0.947881 , -0.589201 , 0.082875,-0.181063,-0.979973 -2.70366 , -0.97616 , -0.573116 , -0.0618824,0.15609,0.985802 -2.78322 , -1.0132 , -0.565403 , -0.124011,0.171556,0.977338 -2.85559 , -1.04582 , -0.550074 , 0.0985635,-0.207915,-0.973168 -2.93553 , -1.08297 , -0.537373 , -0.0704795,0.197533,0.977759 -3.01626 , -1.11976 , -0.522022 , -0.0492933,0.203116,0.977913 -3.11344 , -1.16515 , -0.513267 , -0.0594794,0.181761,0.981542 -3.2027 , -1.20497 , -0.497215 , -0.0680497,0.193595,0.978719 -3.30016 , -1.25016 , -0.482111 , -0.0798711,0.197899,0.976963 -3.39934 , -1.29511 , -0.463749 , 0.0584838,-0.183127,-0.981348 -3.51386 , -1.34802 , -0.450257 , -0.0563591,0.185319,0.981061 -3.62982 , -1.40148 , -0.432628 , -0.0621384,0.177179,0.982215 -3.75411 , -1.45904 , -0.414685 , -0.283656,0.216203,0.934236 -3.87022 , -1.51191 , -0.388956 , 0.297897,-0.121984,-0.946772 -4.00445 , -1.573 , -0.365982 , 0.99991,0.00787648,-0.0108691 -3.93688 , -1.52634 , -0.262318 , 0.999618,-0.0272505,0.00465897 -3.94354 , -1.52009 , -0.188713 , 0.993979,0.106924,0.0239246 -3.94067 , -1.50883 , -0.112527 , 0.996746,0.0787897,-0.0169967 -3.93613 , -1.49628 , -0.037169 , 0.997471,0.0710632,0.00121377 -3.93919 , -1.48834 , 0.0351719 , 0.995543,0.0914561,0.0230021 -3.91474 , -1.46593 , 0.114014 , 0.997246,0.0382979,0.063512 -3.95899 , -1.47912 , 0.174254 , 0.990486,0.0762585,0.114549 -3.8967 , -1.43759 , 0.259528 , 0.984863,0.0825566,0.152415 -3.91249 , -1.43618 , 0.325759 , 0.986012,0.00858028,-0.166451 -3.8999 , -1.42038 , 0.397008 , 0.969564,-0.0194415,-0.244067 -3.94883 , -1.43582 , 0.457076 , -0.837002,0.0330929,0.546198 -3.98724 , -1.44595 , 0.519994 , 0.621696,-0.0682444,-0.78028 -4.12259 , -1.50453 , 0.571575 , -0.239417,0.193346,0.951471 -8.41834 , -3.59813 , 0.328325 , -0.113738,0.213884,0.970215 -8.95572 , -3.84068 , 0.44462 , -0.103093,0.210388,0.972167 -9.68254 , -4.17207 , 0.57176 , -0.0663899,0.196837,0.978186 -10.7323 , -4.65665 , 0.716132 , -0.0476693,0.193246,0.979992 -11.926 , -5.20577 , 0.898656 , -0.0527317,0.187656,0.980818 -13.76 , -6.05459 , 1.13109 , -0.0600663,0.181272,0.981597 -15.1505 , -6.6836 , 1.42207 , -0.125097,0.176784,0.976268 -24.8164 , -11.1017 , 3.07265 , 0.912844,-0.321008,-0.25233 -24.8775 , -11.0682 , 3.54514 , -0.875432,0.468894,-0.117293 -25.0925 , -11.1052 , 4.03926 , -0.875432,0.468894,-0.117293 -25.0652 , -11.0295 , 4.50839 , -0.939382,0.323114,0.114711 -25.1298 , -10.9967 , 4.99248 , -0.904028,0.41815,-0.0887894 -25.2679 , -10.9953 , 5.49347 , 0.323839,-0.94601,0.0139349 -31.2134 , -13.5463 , 7.75793 , -0.390633,0.0827679,0.916818 -20.258 , -8.50501 , 6.13728 , 0.25335,0.08761,0.963399 -18.7762 , -7.79617 , 6.11698 , -0.457521,-0.18361,-0.870036 -29.1568 , -12.3173 , 9.57422 , -0.507161,-0.559521,0.655534 -19.924 , -8.20093 , 7.21448 , 0.800587,0.278436,0.530598 -27.8912 , -11.6128 , 10.3035 , -0.699364,0.714726,-0.0075538 -17.9411 , -7.2389 , 7.29425 , -0.877394,0.315404,0.361523 -19.0626 , -7.6724 , 8.07979 , -0.915846,-0.110552,-0.38601 -18.7249 , -7.47657 , 8.33162 , -0.962186,-0.0169107,0.271868 -18.8046 , -7.45909 , 8.7494 , 0.975474,-0.0795219,-0.205249 -22.3419 , -8.895 , 10.7051 , -0.868042,0.18654,-0.460115 -19.1191 , -7.4858 , 9.68062 , 0.984309,-0.0017781,0.176445 -18.3741 , -7.12161 , 9.72532 , -0.912855,-0.182345,-0.365302 -18.4852 , -7.1152 , 10.1779 , -0.869684,-0.432138,-0.238549 -19.0612 , -7.29678 , 10.8877 , 0.979268,0.192095,0.0642963 -23.4635 , -9.02762 , 13.7475 , 0.940394,0.205078,-0.271299 -24.6711 , -9.44317 , 14.9759 , -0.956303,-0.195916,0.217028 -19.011 , -7.10393 , 12.1478 , -0.89141,0.252338,0.37645 -19.2528 , -7.14056 , 12.7417 , -0.91556,0.350988,0.19636 -19.5761 , -7.20635 , 13.4088 , -0.933307,0.339076,0.118177 -21.7716 , -7.99937 , 15.3609 , -0.373879,-0.694446,0.614784 -26.0158 , -9.5689 , 18.8654 , -0.885767,0.307489,0.347661 -4.91472 , -1.33086 , 4.7173 , 0.540264,0.418613,0.729985 -4.99146 , -1.34122 , 4.9111 , 0.690479,0.568186,0.447664 -4.77463 , -1.24522 , 4.85137 , -0.924845,-0.0791081,-0.372027 -4.83155 , -1.24875 , 5.03413 , -0.918086,-0.117324,-0.378621 -4.70878 , -1.18719 , 5.0525 , 0.914422,0.0433639,0.402432 -4.66878 , -1.15514 , 5.14908 , 0.570831,0.115503,0.812903 -4.79086 , -1.1782 , 5.41183 , 0.88834,-0.396744,0.231183 -4.70489 , -1.12948 , 5.46802 , -0.930336,0.149871,-0.334683 -4.60539 , -1.07658 , 5.50786 , 0.165047,0.0772204,0.983258 -4.49239 , -1.01971 , 5.53049 , 0.160546,0.263117,0.951312 -4.16263 , -0.892707 , 5.29777 , -0.104156,0.939587,-0.32608 -4.06719 , -0.842296 , 5.32543 , 0.0698702,0.1799,-0.9812 -3.95224 , -0.787057 , 5.32772 , 0.331663,-0.175447,0.92694 -3.86277 , -0.740699 , 5.35818 , -0.00769581,-0.313637,0.949512 -3.88008 , -0.725595 , 5.52771 , 0.465996,-0.350669,0.81233 -3.7997 , -0.681844 , 5.57167 , -0.845066,0.0144805,-0.534466 -3.88901 , -0.687094 , 5.8558 , -0.863164,-0.504724,0.0142129 -3.83247 , -0.648311 , 5.93976 , -0.346536,0.510687,0.786837 -3.73525 , -0.597975 , 5.96494 , 0.0499154,0.702069,0.710357 -3.06651 , -0.395035 , 5.08511 , -0.279944,0.889107,0.362105 -3.05054 , -0.371302 , 5.20581 , -0.171144,0.521623,-0.835835 -2.92123 , -0.31742 , 5.13878 , 0.0100015,-0.654927,0.755626 -2.82881 , -0.274517 , 5.12879 , -0.290727,0.416096,-0.861593 -2.87535 , -0.264571 , 5.3692 , -0.991866,0.127053,-0.00767621 -2.84609 , -0.236359 , 5.48039 , -0.945175,-0.287074,-0.15567 -3.04299 , -0.255538 , 6.04387 , 0.0679997,0.865046,0.497062 -2.84739 , -0.188346 , 5.84524 , -0.489661,0.211719,0.845817 -2.5369 , -0.100805 , 5.37936 , 0.182002,0.790584,0.584682 -2.46855 , -0.0641976 , 5.41339 , -0.833536,-0.195164,-0.516845 -2.44499 , -0.0348422 , 5.54705 , -0.926109,0.244852,-0.287002 -2.77803 , -0.0592263 , 6.55726 , -0.0830184,-0.895741,0.436756 -2.62981 , -0.00440093 , 6.4367 , 0.0640776,0.617736,0.783771 -2.50399 , 0.0454008 , 6.35923 , 0.183481,0.655881,0.732226 -2.48785 , 0.0824872 , 6.5796 , 0.535204,0.814277,-0.224744 -2.37303 , 0.130392 , 6.5264 , 0.228738,0.629139,-0.742875 -2.29328 , 0.174961 , 6.57505 , 0.182652,-0.39267,0.901359 -2.17981 , 0.221508 , 6.51692 , -0.264146,0.345549,-0.900457 -2.30631 , 0.262836 , 7.27282 , -0.967588,-0.25097,0.0280764 -2.08734 , 0.3117 , 6.85652 , -0.820314,0.499941,-0.277748 -2.04039 , 0.360238 , 7.05473 , -0.969104,-0.100976,-0.225035 -2.00669 , 0.414119 , 7.33002 , -0.861466,-0.357314,0.360837 -1.57814 , 0.424318 , 5.86867 , -0.48656,0.747148,0.452802 -1.63518 , 0.48525 , 6.52965 , -0.533972,-0.355703,0.767039 -1.52245 , 0.522595 , 6.40776 , -0.692795,-0.677469,0.247125 -1.26239 , 0.514165 , 5.40763 , -0.757903,-0.500598,0.418312 -1.17773 , 0.54295 , 5.31855 , 0.258869,0.663723,0.701754 -1.1088 , 0.575429 , 5.31677 , -0.458566,-0.565788,-0.685275 -1.04418 , 0.610586 , 5.34318 , -0.493882,-0.73399,-0.466197 -0.983638 , 0.649528 , 5.41807 , -0.687465,-0.624392,-0.370846 -0.98068 , 0.745649 , 6.12635 , -0.870412,-0.298472,0.391531 -0.924232 , 0.814652 , 6.43723 , -0.85474,-0.503176,0.127408 -0.793082 , 0.780296 , 5.71447 , 0.782561,0.545696,0.299689 -0.78848 , 0.983063 , 7.21376 , 0.41956,-0.791934,0.443633 -0.6462 , 0.855226 , 5.74314 , -0.343917,-0.905377,-0.249028 -0.572222 , 0.896959 , 5.79008 , -0.840668,-0.411575,-0.351972 -0.495194 , 1.08434 , 6.91577 , 0.101055,0.88614,-0.452265 -0.392617 , 1.1994 , 7.41387 , 0.698878,0.680812,-0.219236 -0.35198 , 0.97534 , 5.58555 , -0.134908,-0.380946,0.914702 -0.278156 , 1.01283 , 5.60714 , 0.15447,-0.54353,0.825054 --0.0482407 , 1.68812 , 9.48687 , 0.288677,-0.94473,-0.155407 -0.019454 , 1.31994 , 6.97143 , -0.928743,0.259462,-0.264793 -2.45034 , -0.925482 , -0.611246 , -0.162807,0.251191,0.954147 -2.49932 , -0.947561 , -0.58822 , -0.162807,0.251191,0.954147 -2.56912 , -0.982226 , -0.580742 , -0.0426938,0.183567,0.98208 -2.63949 , -1.01758 , -0.570805 , -0.0373658,0.176468,0.983597 -2.71769 , -1.05656 , -0.563986 , -0.101658,0.196456,0.975229 -2.78073 , -1.08706 , -0.544488 , 0.105971,-0.212601,-0.971376 -2.85256 , -1.12139 , -0.527888 , -0.0960486,0.225212,0.969564 -2.93173 , -1.16119 , -0.51372 , -0.0522138,0.205755,0.97721 -3.02662 , -1.20843 , -0.506466 , 0.0304471,-0.18661,-0.981962 -3.1218 , -1.25713 , -0.495778 , -0.0785967,0.212643,0.973964 -3.20328 , -1.29576 , -0.473172 , -0.0685785,0.21814,0.973505 -3.30788 , -1.34747 , -0.46069 , -0.059201,0.193636,0.979286 -3.41199 , -1.39937 , -0.444606 , 0.0657572,-0.188461,-0.979877 -3.51755 , -1.45187 , -0.424678 , 0.0607125,-0.181761,-0.981467 -3.64033 , -1.5126 , -0.408598 , -0.0623283,0.183974,0.980953 -3.76259 , -1.57338 , -0.388333 , -0.288552,0.22058,0.931709 -3.89411 , -1.63835 , -0.36705 , -0.311012,0.0788441,0.94713 -4.0184 , -1.69881 , -0.337761 , 0.993354,-0.00532379,-0.114979 -3.95201 , -1.65134 , -0.233784 , 0.986439,0.132336,0.097084 -3.97477 , -1.65428 , -0.165022 , -0.982472,-0.177197,0.057876 -3.93756 , -1.6236 , -0.0767647 , 0.996708,0.0648016,0.0487309 -3.95863 , -1.62516 , -0.00844145 , 0.991904,0.10511,0.071264 -3.94355 , -1.60731 , 0.0697656 , 0.994053,0.107076,-0.0198377 -3.92758 , -1.58944 , 0.146976 , 0.99032,0.0891837,0.106365 -3.96201 , -1.59841 , 0.210773 , 0.987245,0.0887261,0.132195 -3.90016 , -1.55489 , 0.296041 , 0.987445,0.0318738,0.154717 -3.91469 , -1.55401 , 0.363224 , -0.966281,0.0285315,0.255904 -3.91148 , -1.5428 , 0.433741 , -0.93726,0.034949,0.346875 -3.96734 , -1.56409 , 0.494106 , -0.728243,0.0491974,0.683551 -4.02304 , -1.58492 , 0.556513 , 0.510537,-0.101193,-0.85388 -4.2002 , -1.67003 , 0.606201 , -0.30959,0.193719,0.930928 -8.49242 , -3.90928 , 0.421589 , -0.11726,0.2095,0.970752 -9.12806 , -4.22248 , 0.54266 , -0.0793232,0.200112,0.976557 -9.93283 , -4.61909 , 0.681599 , -0.0547174,0.191874,0.979893 -11.0472 , -5.17332 , 0.846 , -0.0558224,0.189596,0.980274 -12.4189 , -5.85487 , 1.0537 , -0.0465368,0.183305,0.981954 -14.4746 , -6.88017 , 1.32853 , -0.105722,0.177323,0.978458 -16.529 , -7.89487 , 1.6832 , 0.110284,-0.154538,-0.981812 -20.2631 , -9.75312 , 2.21773 , -0.42235,0.294099,0.857395 -25.0504 , -12.0624 , 3.45795 , -0.985303,-0.169083,-0.0242811 -24.9099 , -11.9297 , 3.91944 , 0.999641,0.0231785,0.0134713 -24.7358 , -11.7813 , 4.37157 , 0.999357,-0.0358407,-0.000630759 -24.6865 , -11.6955 , 4.83759 , 0.986192,-0.0514512,-0.157412 -24.9502 , -11.7633 , 5.35812 , 0.995324,0.0209756,0.0942879 -27.5561 , -12.9799 , 6.35084 , 0.725933,-0.0823734,-0.682815 -24.3826 , -11.3609 , 6.1993 , -0.60093,-0.102471,-0.792706 -31.9875 , -14.9919 , 8.46762 , 0.575831,-0.12845,-0.807415 -20.1058 , -9.17163 , 6.05508 , 0.80164,0.503461,0.322335 -20.2809 , -9.20434 , 6.49674 , -0.910352,-0.271759,-0.3121 -20.0469 , -9.04104 , 6.82716 , -0.910352,-0.271759,-0.3121 -18.8358 , -8.41319 , 6.84132 , 0.382154,0.861002,0.33561 -18.0081 , -7.9735 , 6.93846 , -0.920738,-0.382401,-0.0775354 -18.2761 , -8.05219 , 7.39629 , -0.896844,-0.419313,0.14088 -18.8352 , -8.26537 , 7.97906 , 0.999434,0.0165598,-0.0292678 -20.8824 , -9.16508 , 9.18371 , 0.0119919,0.0619191,0.998009 -18.602 , -8.05631 , 8.65774 , 0.98761,0.0589125,0.145449 -18.667 , -8.03502 , 9.07633 , 0.986338,-0.0631264,-0.152159 -18.7501 , -8.02123 , 9.51071 , 0.990214,0.0246453,-0.137368 -18.8829 , -8.02969 , 9.97828 , 0.993143,0.0336027,-0.111973 -19.2891 , -8.15892 , 10.5957 , 0.961947,-0.255242,0.0975203 -19.2055 , -8.06546 , 10.9769 , -0.88687,0.400005,-0.231209 -18.7885 , -7.82409 , 11.1762 , -0.88687,0.400005,-0.231209 -18.9695 , -7.84902 , 11.7081 , -0.975209,0.11736,0.187601 -19.5332 , -8.03882 , 12.4852 , -0.906434,0.239302,0.348011 -19.4098 , -7.92473 , 12.8676 , -0.885785,0.128556,0.445934 -24.7127 , -10.1534 , 16.7799 , -0.750061,0.439692,0.494044 -24.0185 , -9.77737 , 16.9172 , -0.548071,0.754605,0.360819 -25.3997 , -10.2855 , 18.4842 , -0.885767,0.307489,0.347661 -5.18058 , -1.60974 , 4.95212 , -0.681265,-0.553797,-0.478736 -5.02916 , -1.53118 , 4.95743 , -0.681265,-0.553797,-0.478736 -4.9652 , -1.48773 , 5.03474 , 0.66499,0.407056,0.626174 -4.86437 , -1.42963 , 5.07784 , -0.69535,-0.451951,-0.558775 -4.78419 , -1.38043 , 5.13815 , -0.656008,-0.492932,-0.571552 -4.69533 , -1.32881 , 5.18967 , -0.729033,-0.405724,-0.551271 -4.60783 , -1.27691 , 5.23906 , 0.909664,-0.387652,0.149124 -4.66465 , -1.27968 , 5.44056 , 0.693877,-0.491097,0.526649 -4.5998 , -1.23628 , 5.51658 , 0.329942,-0.440495,0.834927 -4.55852 , -1.20142 , 5.62014 , 0.964787,-0.262929,0.00733023 -4.60462 , -1.19832 , 5.82701 , 0.853622,0.196688,0.482332 -4.04188 , -0.975121 , 5.30842 , 0.0477152,0.0302951,0.998401 -3.95382 , -0.92531 , 5.342 , 0.238245,-0.014482,0.971097 -3.8234 , -0.860932 , 5.31918 , 0.157014,0.147055,0.976587 -3.69399 , -0.7986 , 5.29279 , 0.141357,0.0454034,0.988917 -3.68211 , -0.77529 , 5.4214 , -0.0428113,-0.396556,0.917012 -3.89915 , -0.827402 , 5.88054 , -0.938941,-0.307432,-0.154519 -3.81475 , -0.778396 , 5.92475 , -0.547171,0.497605,0.673047 -3.5473 , -0.671046 , 5.68693 , 0.247319,-0.00199789,0.968932 -3.48753 , -0.631102 , 5.75743 , -0.520537,0.722588,0.454871 -2.9732 , -0.452862 , 5.08495 , -0.0592834,-0.994254,-0.0891276 -2.92755 , -0.419878 , 5.15396 , 0.0100015,-0.654927,0.755626 -2.83095 , -0.372311 , 5.13613 , -0.126143,-0.816263,0.563739 -2.81144 , -0.34705 , 5.25489 , -0.527176,-0.776836,0.3444 -2.86805 , -0.341175 , 5.52318 , -0.256481,0.905826,0.33719 -2.82174 , -0.306794 , 5.60827 , 0.306127,0.896683,0.319758 -3.08421 , -0.347878 , 6.32692 , 0.646115,0.224434,-0.729496 -2.85161 , -0.265248 , 6.04701 , 0.526764,-0.827788,-0.1931 -2.55423 , -0.170417 , 5.5965 , 0.993122,0.115686,-0.0180725 -2.76889 , -0.190231 , 6.28962 , -0.863543,-0.148089,-0.482041 -2.73488 , -0.153086 , 6.43822 , -0.827419,-0.305469,0.471239 -2.71048 , -0.11695 , 6.62385 , -0.581663,-0.563016,0.587095 -2.61816 , -0.0672414 , 6.64172 , 0.154049,0.616423,-0.772199 -2.4571 , -0.00628936 , 6.46949 , 0.25032,0.0576504,0.966445 -2.35763 , 0.0434906 , 6.45381 , -0.172621,0.720888,0.67121 -2.24659 , 0.0930996 , 6.39815 , 0.264269,-0.231287,0.936306 -2.19055 , 0.136855 , 6.51176 , -0.523927,-0.201349,-0.827623 -2.2163 , 0.175776 , 6.91265 , -0.938625,-0.0433226,0.34221 -2.08299 , 0.22851 , 6.78463 , -0.85682,0.479782,-0.188858 -2.00733 , 0.277017 , 6.85716 , -0.820314,0.499941,-0.277748 -1.73353 , 0.32262 , 6.12143 , -0.0259031,0.135984,0.990372 -1.61071 , 0.362599 , 5.94444 , -0.722683,0.230085,0.65176 -1.51391 , 0.401114 , 5.86244 , -0.75359,0.191206,0.628922 -1.53452 , 0.456513 , 6.36705 , -0.4116,0.8085,0.42061 -1.27043 , 0.461873 , 5.35765 , -0.534503,-0.410811,-0.738607 -1.19905 , 0.496494 , 5.33793 , 0.48579,0.626753,0.609253 -1.13154 , 0.531802 , 5.34641 , 0.491475,0.656824,0.57187 -1.07006 , 0.569369 , 5.39327 , 0.594416,0.733233,0.33021 -1.00198 , 0.605315 , 5.3991 , 0.600218,0.684135,0.414364 -1.04427 , 0.729491 , 6.51465 , 0.843417,0.372356,0.387296 -0.889544 , 0.700863 , 5.68491 , 0.00293535,0.55559,0.831451 -0.832815 , 0.760606 , 5.91532 , 0.54908,0.60823,-0.573208 -0.749232 , 0.785217 , 5.77701 , -0.709071,-0.590316,-0.385677 -0.739133 , 1.01866 , 7.52408 , -0.163899,-0.911074,0.378262 -0.60164 , 0.864129 , 5.79362 , 0.823357,0.402392,0.400205 -0.533342 , 1.04244 , 6.89107 , 0.149605,0.602082,-0.784293 -0.44135 , 1.09116 , 6.90456 , 0.211013,-0.756404,0.619134 -0.278619 , 1.52708 , 9.60773 , -0.937981,0.333409,-0.0950286 -0.312325 , 0.985596 , 5.58254 , -0.0260621,-0.504017,0.863301 -0.236833 , 1.03147 , 5.63244 , 0.0519549,-0.645709,0.761814 -0.0596531 , 1.30694 , 7.04798 , -0.102361,0.986511,-0.127743 -2.49798 , -1.0143 , -0.572117 , -0.126419,0.195175,0.972587 -2.57381 , -1.05652 , -0.568547 , -0.0351524,0.192037,0.980758 -2.64363 , -1.09356 , -0.557243 , -0.0415062,0.164938,0.98543 -2.72009 , -1.13497 , -0.548979 , -0.13791,0.194366,0.971186 -2.7758 , -1.16233 , -0.523127 , -0.123109,0.206619,0.970645 -2.86161 , -1.20819 , -0.515012 , -0.0767462,0.180866,0.980509 -2.93901 , -1.25035 , -0.499107 , -0.0606657,0.16787,0.983941 -3.02516 , -1.29619 , -0.485421 , -0.0436429,0.192268,0.980372 -3.11206 , -1.3416 , -0.468792 , 0.0858945,-0.199044,-0.976219 -3.20719 , -1.39242 , -0.453208 , -0.073406,0.197842,0.977481 -3.30977 , -1.44742 , -0.438695 , -0.0476636,0.175962,0.983242 -3.42147 , -1.50782 , -0.424134 , -0.0553288,0.184789,0.98122 -3.53387 , -1.56762 , -0.405852 , -0.0627246,0.176912,0.982226 -3.65461 , -1.63152 , -0.387256 , -0.0654161,0.191103,0.979388 -3.77482 , -1.69547 , -0.364474 , -0.267994,0.208382,0.940615 -3.91265 , -1.76946 , -0.343664 , 0.416901,-0.0654032,-0.906596 -4.01104 , -1.81887 , -0.30215 , 0.999578,-0.0112136,-0.0267796 -3.9689 , -1.78352 , -0.2074 , 0.993242,0.066102,-0.0953964 -3.95827 , -1.76717 , -0.126057 , 0.99317,0.106502,0.0476421 -4.0289 , -1.7997 , -0.0718184 , 0.988307,0.151911,0.0131519 -3.94109 , -1.73764 , 0.0312778 , 0.987276,0.126318,0.0965889 -3.96842 , -1.74415 , 0.0984119 , 0.983591,0.15714,0.0886312 -3.93554 , -1.71572 , 0.181023 , 0.992751,0.0854443,0.0845305 -3.96845 , -1.72611 , 0.246261 , 0.973629,0.130315,0.187258 -3.89853 , -1.67597 , 0.333544 , 0.991984,0.0493356,0.116334 -3.91297 , -1.67485 , 0.401797 , -0.927148,0.0169844,0.374311 -3.94314 , -1.68345 , 0.467351 , -0.866292,-0.0125804,0.49938 -3.9974 , -1.70597 , 0.530032 , -0.800056,-0.0104521,0.599834 -4.03486 , -1.71823 , 0.596752 , 0.574295,-0.0337699,-0.817952 -8.17854 , -4.04006 , 0.388784 , -0.121143,0.215698,0.968916 -8.65674 , -4.2896 , 0.512117 , 0.11354,-0.207375,-0.97165 -9.34354 , -4.65408 , 0.644676 , -0.0798397,0.189085,0.97871 -10.2834 , -5.15486 , 0.797471 , 0.0525682,-0.192221,-0.979943 -11.5287 , -5.82168 , 0.98595 , -0.0576313,0.183136,0.981397 -13.0718 , -6.64586 , 1.22775 , -0.0456669,0.185651,0.981554 -15.1302 , -7.74538 , 1.54811 , -0.0965562,0.163665,0.981779 -20.3152 , -10.4964 , 2.51181 , -0.775326,-0.16241,0.610321 -24.9369 , -12.9523 , 3.33831 , -0.970013,-0.241672,0.0258679 -25.5801 , -13.2381 , 3.89481 , -0.96115,-0.271105,0.0518978 -25.5414 , -13.1549 , 4.38637 , -0.96115,-0.271105,0.0518978 -25.0587 , -12.8331 , 4.80903 , -0.931455,-0.35742,0.0681362 -25.1802 , -12.8363 , 5.31878 , -0.956012,-0.274893,0.10235 -27.8194 , -14.1715 , 6.32175 , -0.880268,0.47419,-0.0164839 -29.5888 , -15.0341 , 7.24661 , 0.34176,-0.468643,-0.8146 -22.9547 , -11.4805 , 6.28254 , -0.509266,0.303464,-0.805331 -22.5486 , -11.2114 , 6.6338 , -0.41863,0.230528,-0.878411 -20.0855 , -9.87447 , 6.40688 , -0.987814,0.153682,0.0246141 -20.5017 , -10.0393 , 6.93056 , -0.962448,0.198707,0.184959 -20.5915 , -10.0332 , 7.3712 , 0.984467,-0.127947,-0.120228 -19.8896 , -9.62091 , 7.55255 , -0.835852,-0.446108,-0.319906 -19.459 , -9.35045 , 7.80487 , -0.809634,-0.312902,-0.496574 -21.7984 , -10.4835 , 9.08984 , 0.995196,-0.0675079,-0.0709038 -19.4472 , -9.24251 , 8.60521 , -0.799053,-0.522523,-0.297464 -18.9718 , -8.95228 , 8.81323 , -0.910754,-0.375281,-0.172315 -18.6269 , -8.72982 , 9.06313 , -0.953456,-0.299536,-0.0346471 -18.7679 , -8.74926 , 9.52813 , 0.995394,0.0886051,0.036612 -18.827 , -8.72605 , 9.96415 , -0.906038,0.409982,0.104929 -18.902 , -8.71071 , 10.4166 , -0.851452,0.518702,-0.077324 -18.6441 , -8.53211 , 10.701 , 0.624707,-0.645379,0.439576 -18.6166 , -8.46524 , 11.1071 , -0.589696,0.642218,-0.489709 -18.4383 , -8.3245 , 11.4307 , -0.589696,0.642218,-0.489708 -19.2294 , -8.64871 , 12.3382 , -0.89013,0.018141,0.455346 -19.3083 , -8.62756 , 12.8437 , -0.963421,0.00731547,0.267891 -23.4197 , -10.5069 , 15.9929 , -0.905176,0.222334,0.362249 -23.8816 , -10.6498 , 16.8842 , -0.888464,-0.115593,0.44415 -23.4447 , -10.3703 , 17.1779 , 0.696501,-0.567351,-0.439317 -24.8221 , -10.9293 , 18.7841 , -0.869314,0.396056,0.295689 -24.4433 , -10.6737 , 19.1485 , -0.761468,0.213325,0.612094 -5.06724 , -1.73076 , 5.00842 , -0.664841,-0.573735,-0.478345 -5.01717 , -1.69089 , 5.10033 , 0.718984,0.463628,0.517795 -4.92447 , -1.6329 , 5.15258 , -0.767095,-0.453987,-0.453277 -4.87855 , -1.59532 , 5.2485 , 0.686582,0.491055,0.536162 -4.81054 , -1.54823 , 5.32335 , 0.636318,0.519224,0.570531 -4.68856 , -1.47844 , 5.34178 , -0.673102,-0.450478,-0.586518 -4.52732 , -1.39262 , 5.3146 , 0.729817,0.195638,0.655051 -4.53631 , -1.37786 , 5.46746 , 0.89666,-0.127689,0.423905 -4.41425 , -1.30889 , 5.47681 , -0.354552,0.388403,-0.85055 -4.55052 , -1.34506 , 5.78448 , -0.859403,0.093727,-0.502635 -4.27095 , -1.2132 , 5.60477 , -0.912559,0.198219,-0.357695 -4.34371 , -1.22272 , 5.84855 , -0.38453,-0.873917,-0.29733 -4.37428 , -1.21381 , 6.04966 , -0.782623,-0.190904,-0.5925 -3.78667 , -0.966866 , 5.4334 , 0.139524,0.174573,0.974709 -3.63079 , -0.888491 , 5.36656 , 0.342999,-0.16684,0.9244 -3.57286 , -0.848067 , 5.43144 , 0.478693,-0.285621,0.830225 -4.12677 , -1.03269 , 6.40425 , -0.429862,-0.459322,-0.77733 -3.46877 , -0.772068 , 5.58229 , -0.34536,0.646644,-0.680131 -3.39027 , -0.724014 , 5.61884 , -0.665483,0.52816,-0.527427 -3.32727 , -0.681231 , 5.6789 , -0.75894,0.382039,0.527311 -3.45344 , -0.702683 , 6.06072 , 0.0913456,-0.917215,0.38778 -3.45175 , -0.678358 , 6.24187 , 0.055251,0.992169,-0.112017 -3.37934 , -0.630949 , 6.30286 , -0.226273,-0.920695,0.317995 -2.86313 , -0.44329 , 5.52151 , -0.658775,0.74901,-0.0707086 -3.26111 , -0.542465 , 6.4818 , -0.375911,-0.547793,0.747405 -3.07982 , -0.461765 , 6.32487 , -0.606473,-0.357124,0.710389 -2.97964 , -0.4065 , 6.32466 , 0.125581,0.708015,-0.694942 -2.82744 , -0.337008 , 6.20419 , 0.681866,-0.069833,0.728136 -2.57623 , -0.244684 , 5.84239 , 0.68346,0.271287,0.677706 -2.72115 , -0.25388 , 6.40199 , -0.389859,-0.809729,0.438576 -2.60756 , -0.196385 , 6.35598 , 0.0609921,-0.628497,0.775417 -2.55594 , -0.153461 , 6.46578 , -0.379185,0.122373,-0.917193 -2.47392 , -0.103969 , 6.49999 , 0.206721,0.255472,0.944458 -2.37205 , -0.0511477 , 6.47585 , 0.0740675,0.338963,0.93788 -2.2838 , -0.000614303 , 6.48736 , 0.210103,0.188196,0.959395 -2.22516 , 0.0451426 , 6.59231 , 0.225274,-0.111584,0.967885 -2.12396 , 0.0975966 , 6.56213 , -0.345613,-0.114403,-0.931377 -2.02964 , 0.148709 , 6.5489 , 0.356534,0.0790007,0.930936 -2.03713 , 0.191409 , 6.92086 , -0.938624,-0.0433226,0.34221 -1.80009 , 0.248863 , 6.34194 , 0.75066,-0.16773,-0.639044 -1.65091 , 0.296498 , 6.05889 , 0.672844,-0.166699,-0.720758 -1.54724 , 0.339235 , 5.94849 , -0.854991,0.188363,0.483229 -1.37774 , 0.373968 , 5.48263 , -0.799384,0.145539,0.582927 -1.28478 , 0.409779 , 5.35671 , 0.499292,0.26683,0.824323 -1.21579 , 0.446992 , 5.34728 , -0.539699,-0.615845,-0.573986 -1.16035 , 0.487421 , 5.42529 , -0.649756,-0.663918,-0.370177 -1.10027 , 0.52786 , 5.48261 , 0.581055,0.768228,0.268703 -1.02885 , 0.564892 , 5.45926 , 0.580328,0.751813,0.313044 -1.0694 , 0.675281 , 6.50625 , -0.786972,-0.00943416,0.616916 -0.92474 , 0.668756 , 5.82553 , -0.101255,0.983356,0.150856 -0.855955 , 0.715471 , 5.89764 , 0.413437,0.666487,-0.620375 -0.77322 , 0.743122 , 5.74965 , -0.797167,-0.481945,-0.363668 -0.723362 , 0.837335 , 6.27612 , -0.48669,0.764959,0.421865 -0.630686 , 0.83332 , 5.83687 , -0.235171,-0.892926,-0.383899 -0.557567 , 0.874891 , 5.84352 , -0.918852,-0.200433,-0.339907 -0.478515 , 1.05057 , 6.89008 , -0.120278,-0.620335,0.77506 -0.378371 , 1.1752 , 7.42711 , -0.105568,-0.491596,0.864401 -0.343168 , 0.959055 , 5.57757 , -0.149397,-0.506412,0.849251 -0.271714 , 1.00314 , 5.60844 , 0.202369,0.11196,0.972888 --0.0601881 , 1.68679 , 9.54724 , -0.983301,0.0533809,-0.173982 -0.0168156 , 1.3175 , 6.97168 , -0.920491,0.306064,-0.242942 -2.39405 , -1.02754 , -0.598043 , -0.219682,0.213119,0.952009 -2.44137 , -1.05231 , -0.57474 , -0.201154,0.195126,0.959929 -2.50903 , -1.09156 , -0.566591 , -0.118987,0.196091,0.97334 -2.56973 , -1.12542 , -0.550926 , -0.0590482,0.165259,0.984481 -2.64462 , -1.1698 , -0.54365 , 0.0952012,-0.156885,-0.983018 -2.71375 , -1.20806 , -0.528935 , 0.125088,-0.18328,-0.97507 -2.78344 , -1.24697 , -0.511665 , -0.13129,0.17902,0.975046 -2.85951 , -1.29115 , -0.496946 , -0.0795589,0.159783,0.983941 -2.94433 , -1.339 , -0.484444 , -0.0686954,0.157542,0.98512 -3.03618 , -1.39307 , -0.473204 , -0.0835498,0.189747,0.978272 -3.11457 , -1.43613 , -0.450339 , 0.0913657,-0.167418,-0.981643 -3.21561 , -1.49416 , -0.437106 , -0.0651214,0.17915,0.981664 -3.31714 , -1.55261 , -0.420248 , -0.0526622,0.168678,0.984263 -3.42705 , -1.6153 , -0.403659 , -0.0628191,0.164056,0.984449 -3.53741 , -1.67832 , -0.383055 , -0.07278,0.179124,0.981131 -3.65685 , -1.7466 , -0.361818 , 0.0656659,-0.179962,-0.981479 -3.79198 , -1.82454 , -0.34299 , -0.0916606,0.182198,0.97898 -3.92774 , -1.90163 , -0.319371 , 0.520129,-0.0781535,-0.850504 -3.9838 , -1.92749 , -0.260528 , 0.676084,-0.143371,-0.722742 -3.98236 , -1.91678 , -0.180206 , 0.990456,0.0236192,-0.135787 -4.15825 , -2.01908 , -0.159212 , 0.999091,-0.0347389,0.0247015 -3.95905 , -1.88334 , -0.0163995 , 0.995894,0.0821042,0.0381297 -4.0112 , -1.90658 , 0.045362 , 0.986368,-0.00133831,0.164549 -3.96351 , -1.8668 , 0.134585 , 0.992228,0.121035,0.0288871 -3.95494 , -1.85293 , 0.211503 , 0.989907,0.11535,0.0823278 -3.97922 , -1.85834 , 0.280318 , 0.98489,0.0812004,0.152968 -3.9107 , -1.80637 , 0.367911 , 0.993205,0.0935604,0.0692137 -3.92384 , -1.80571 , 0.437505 , 0.973251,0.0768411,-0.216515 -3.97013 , -1.82582 , 0.502236 , -0.854298,-0.0174305,0.519492 -4.03224 , -1.85431 , 0.565821 , 0.737522,0.0164423,-0.675122 -4.12822 , -1.90304 , 0.627971 , 0.566244,-0.0969069,-0.818521 -8.20884 , -4.33932 , 0.48196 , -0.119733,0.20922,0.970511 -8.82458 , -4.68881 , 0.606969 , -0.082252,0.189896,0.978353 -9.61094 , -5.1376 , 0.750978 , 0.0734862,-0.182235,-0.980505 -10.6813 , -5.75078 , 0.923155 , -0.051816,0.187409,0.980914 -11.9495 , -6.47525 , 1.13972 , -0.0587091,0.180802,0.981766 -13.811 , -7.54289 , 1.42414 , -0.0648329,0.175817,0.982286 -15.8593 , -8.71195 , 1.79245 , -0.0862683,0.169122,0.981812 -18.8364 , -10.412 , 2.30691 , -0.0608551,0.192408,0.979426 -25.2196 , -14.0179 , 3.74238 , -0.98592,-0.149291,0.0753234 -25.5291 , -14.1345 , 4.27992 , 0.844878,0.310653,-0.435517 -26.9999 , -14.9162 , 5.00464 , -0.759618,0.622048,0.189833 -26.9733 , -14.8352 , 5.53573 , -0.649211,0.732315,0.205522 -26.9558 , -14.7591 , 6.06911 , -0.7512,0.659935,0.0135837 -27.0492 , -14.7455 , 6.62691 , 0.766325,-0.641813,-0.0286524 -29.5089 , -16.0664 , 7.73746 , -0.383425,0.409109,0.828019 -29.9024 , -16.2143 , 8.43202 , 0.409837,-0.412122,-0.81375 -30.7863 , -16.6329 , 9.27924 , -0.413478,0.0591286,0.908592 -24.5272 , -13.0728 , 8.07501 , -0.628502,-0.559967,-0.539836 -24.6122 , -13.0578 , 8.60391 , 0.655452,0.545198,0.52263 -19.7974 , -10.3405 , 7.49933 , 0.997129,0.0271174,-0.0706975 -20.3781 , -10.6088 , 8.11591 , 0.991593,-0.128746,0.0129759 -20.3145 , -10.5214 , 8.51737 , -0.936905,-0.341948,-0.0726696 -20.0293 , -10.314 , 8.83187 , -0.848338,-0.527087,-0.0500094 -19.3022 , -9.86818 , 8.95208 , -0.774444,-0.566721,-0.281182 -19.0607 , -9.68672 , 9.25965 , 0.845599,0.508379,0.16283 -20.1857 , -10.2378 , 10.197 , 0.652499,0.752157,0.0922247 -20.7459 , -10.4811 , 10.9148 , 0.900487,0.273341,0.338242 -18.5534 , -9.2636 , 10.2579 , -0.901956,0.212092,-0.376154 -18.4066 , -9.13466 , 10.5977 , 0.704178,-0.632376,0.322853 -18.1277 , -8.93596 , 10.8628 , 0.669522,-0.577179,0.467551 -19.2015 , -9.4437 , 11.9073 , -0.873033,0.00956554,0.487568 -19.2181 , -9.39697 , 12.3704 , -0.89013,0.0181411,0.455346 -19.2665 , -9.36399 , 12.8609 , 0.845079,0.275255,-0.458341 -26.7709 , -13.1473 , 18.2473 , 0.203329,-0.361895,0.909774 -25.0564 , -12.1929 , 17.7497 , 0.790689,0.604835,0.0947879 -24.434 , -11.7991 , 17.9468 , -0.950173,-0.0276976,0.310489 -24.7902 , -11.9005 , 18.8415 , -0.71954,-0.629667,0.292886 -24.2032 , -11.5267 , 19.0506 , -0.761468,0.213325,0.612094 -5.24841 , -2.00461 , 5.18655 , -0.419845,-0.670793,-0.611365 -5.23855 , -1.98262 , 5.32137 , 0.467752,0.505228,0.725226 -5.12979 , -1.91268 , 5.36644 , 0.467752,0.505228,0.725226 -5.06174 , -1.86213 , 5.44781 , 0.409203,0.251267,0.877165 -4.87869 , -1.75765 , 5.41356 , 0.309568,0.311125,0.898537 -4.73055 , -1.67068 , 5.40755 , 0.608948,0.291067,0.737876 -4.64886 , -1.61509 , 5.46651 , -0.585508,-0.280988,-0.760412 -4.598 , -1.57387 , 5.55887 , -0.836277,-0.424162,-0.347458 -4.40114 , -1.46589 , 5.48446 , -0.735918,-0.573787,-0.359433 -4.51798 , -1.49974 , 5.77001 , -0.949134,-0.0316125,-0.31328 -4.65758 , -1.54197 , 6.09811 , 0.581268,0.771701,0.258078 -4.33824 , -1.38172 , 5.86586 , -0.719885,-0.53498,-0.442223 -4.31595 , -1.35182 , 5.99857 , 0.785605,0.0407809,0.617383 -4.27367 , -1.31333 , 6.10833 , 0.886536,-0.126202,0.445114 -4.17725 , -1.25208 , 6.14652 , -0.595797,-0.0178719,-0.802936 -3.53096 , -0.961555 , 5.39156 , -0.478693,0.285622,-0.830225 -3.93021 , -1.10708 , 6.13494 , 0.737017,0.164352,-0.655587 -3.78728 , -1.02712 , 6.09123 , -0.0293436,-0.315404,0.948504 -3.51061 , -0.896453 , 5.82813 , 0.764292,0.335347,0.550818 -3.27834 , -0.784381 , 5.61457 , -0.75894,0.382039,0.527311 -3.29519 , -0.771375 , 5.80891 , -0.286166,0.838762,0.463235 -3.53094 , -0.837793 , 6.39879 , -0.108881,0.130814,0.98541 -3.37667 , -0.757053 , 6.3149 , -0.371572,-0.263099,0.890345 -3.21232 , -0.673854 , 6.2004 , 0.183745,0.448663,-0.874608 -3.23929 , -0.657959 , 6.45116 , 0.278766,0.707333,-0.649592 -3.05644 , -0.570104 , 6.28634 , 0.557153,0.422421,-0.714941 -2.73139 , -0.43757 , 5.80212 , -0.714435,-0.0129502,-0.699582 -2.68612 , -0.398616 , 5.89531 , -0.380622,0.339105,0.860311 -2.59453 , -0.345945 , 5.88779 , -0.682851,-0.219463,-0.696814 -2.77372 , -0.37276 , 6.5301 , -0.897641,-0.26896,-0.349144 -2.60804 , -0.29626 , 6.35637 , -0.378521,0.181704,0.907582 -2.48416 , -0.232788 , 6.27113 , 0.118945,-0.845549,0.520479 -2.64366 , -0.242837 , 6.9606 , -0.399212,-0.89967,-0.176701 -2.39664 , -0.149111 , 6.53455 , 0.15822,0.0193243,0.987215 -2.31476 , -0.0960805 , 6.56571 , 0.140202,0.0650632,0.987983 -2.20374 , -0.0380246 , 6.50013 , 0.550949,0.367986,0.749028 -2.15288 , 0.00740381 , 6.63307 , -0.398987,-0.0854944,-0.912963 -2.05639 , 0.0625309 , 6.61127 , 0.447185,0.0672042,0.891913 -1.99101 , 0.112543 , 6.70334 , -0.993499,-0.0809408,-0.080047 -1.75613 , 0.179053 , 6.11494 , -0.477599,0.239965,0.845172 -1.67584 , 0.226176 , 6.11445 , -0.129072,0.0939275,0.987177 -1.60142 , 0.273357 , 6.14153 , -0.525096,0.170975,0.833691 -1.38831 , 0.317419 , 5.4709 , -0.880067,-0.0794408,0.468157 -1.29971 , 0.356356 , 5.36526 , 0.682046,0.164948,-0.712464 -1.23311 , 0.39616 , 5.36611 , 0.499292,0.26683,0.824324 -1.17806 , 0.437703 , 5.43476 , -0.656901,-0.201385,-0.726585 -1.12787 , 0.482765 , 5.56166 , -0.586634,-0.719874,-0.371002 -1.05684 , 0.521963 , 5.53909 , -0.548388,-0.775094,-0.313848 -0.986918 , 0.56156 , 5.52483 , 0.459445,0.794347,0.397395 -0.977523 , 0.645133 , 6.15478 , -0.946463,-0.0280786,0.321589 -0.87215 , 0.663884 , 5.8 , 0.0681007,-0.997472,-0.0203075 -0.79782 , 0.702788 , 5.76193 , 0.678125,0.475469,0.560425 -0.731881 , 0.754492 , 5.86149 , -0.709,-0.647973,0.278298 -0.700231 , 0.931287 , 7.1424 , 0.11983,-0.726148,0.677016 -0.585346 , 0.840364 , 5.85719 , -0.761782,-0.466143,-0.449888 -0.515504 , 1.0099 , 6.88516 , 0.149605,0.602082,-0.784293 -0.425899 , 1.06622 , 6.91788 , 0.426198,-0.648331,0.63089 -0.261016 , 1.49549 , 9.60162 , -0.96719,0.253526,-0.016381 -0.305181 , 0.971973 , 5.57419 , -0.0396213,-0.542454,0.83915 -0.233518 , 1.02002 , 5.61381 , 0.26205,-0.547714,0.794569 -0.0539201 , 1.30826 , 7.08806 , -0.855369,0.45995,0.238304 -2.39691 , -1.09783 , -0.588945 , -0.222699,0.180834,0.957969 -2.44274 , -1.12413 , -0.564688 , -0.165514,0.224292,0.960364 -2.50305 , -1.16014 , -0.549698 , -0.0741062,0.161335,0.984114 -2.57658 , -1.20647 , -0.543316 , -0.0255106,0.167482,0.985545 -2.65091 , -1.25248 , -0.534478 , -0.10261,0.215728,0.971047 -2.7115 , -1.2883 , -0.513139 , -0.124305,0.156487,0.979827 -2.78623 , -1.33445 , -0.49941 , -0.0826431,0.17516,0.981065 -2.86947 , -1.38525 , -0.4878 , -0.0829685,0.158404,0.983882 -2.94575 , -1.43069 , -0.468771 , -0.06264,0.169053,0.983615 -3.0368 , -1.48732 , -0.455673 , -0.0977624,0.176792,0.979381 -3.12113 , -1.53764 , -0.435355 , -0.0839128,0.186834,0.978801 -3.22014 , -1.59891 , -0.419897 , -0.0672167,0.174964,0.982278 -3.32084 , -1.65986 , -0.40089 , -0.055736,0.164268,0.98484 -3.43615 , -1.73153 , -0.385673 , -0.0681028,0.17158,0.982813 -3.54447 , -1.79774 , -0.36265 , -0.0794727,0.187757,0.978995 -3.66186 , -1.8692 , -0.338896 , -0.0643147,0.174844,0.982493 -3.80233 , -1.95592 , -0.320565 , -0.11478,0.198145,0.973429 -3.93675 , -2.03728 , -0.293819 , 0.539958,-0.0856278,-0.837325 -3.99125 , -2.06448 , -0.233146 , -0.788945,0.164341,0.592079 -4.00543 , -2.06483 , -0.157078 , -0.951377,0.189372,0.242941 -3.98629 , -2.04222 , -0.0708955 , 0.996841,0.0792939,0.0045482 -3.99046 , -2.0355 , 0.00704319 , 0.996182,0.0726283,0.0484319 -4.00123 , -2.03308 , 0.0822334 , 0.996265,0.0470426,0.072403 -3.96105 , -1.99765 , 0.169607 , 0.996239,0.0621202,0.060403 -3.97747 , -1.99935 , 0.241831 , 0.996423,0.083237,-0.0146002 -3.99313 , -1.9998 , 0.314125 , 0.990996,0.0979197,0.0913163 -3.92406 , -1.94554 , 0.401981 , 0.991625,0.126385,0.0265759 -3.96158 , -1.96194 , 0.469125 , -0.940488,-0.0615954,0.334198 -3.99003 , -1.97141 , 0.538552 , -0.792719,0.0732413,0.605172 -4.05129 , -2.00228 , 0.604772 , -0.780537,0.0772461,0.620319 -7.90609 , -4.46039 , 0.443374 , -0.127839,0.228602,0.96509 -8.35107 , -4.72712 , 0.570787 , -0.114519,0.215376,0.969793 -9.07325 , -5.16832 , 0.705113 , -0.0751832,0.186032,0.979663 -9.89724 , -5.67005 , 0.866862 , 0.0678982,-0.187748,-0.979868 -11.0495 , -6.37537 , 1.06255 , -0.0531044,0.180001,0.982232 -12.5144 , -7.27304 , 1.31255 , -0.0539765,0.181475,0.981913 -14.6379 , -8.57628 , 1.65067 , -0.0716171,0.174409,0.982066 -16.5983 , -9.76658 , 2.06493 , -0.0837896,0.190095,0.978184 -20.324 , -12.0478 , 2.70835 , -0.0712643,0.199274,0.977349 -25.3986 , -15.0853 , 4.15549 , 0.587913,-0.19703,-0.784562 -25.6295 , -15.1663 , 4.69999 , -0.699702,0.283107,0.655948 -26.5956 , -15.6961 , 5.37731 , 0.774689,-0.601236,-0.195889 -26.3621 , -15.4895 , 5.87179 , -0.808544,0.586588,-0.046599 -26.332 , -15.407 , 6.40065 , -0.796207,0.604054,0.0342517 -26.7048 , -15.5681 , 7.02222 , 0.813225,-0.579085,-0.0576684 -36.1465 , -21.1963 , 9.92235 , -0.57669,-0.247191,0.778669 -37.2847 , -21.7893 , 10.9774 , -0.57669,-0.247191,0.778669 -30.3275 , -17.5372 , 9.72682 , 0.46223,-0.388883,-0.79694 -19.7382 , -11.1567 , 7.05049 , -0.884881,0.331958,0.326788 -19.8735 , -11.188 , 7.50716 , -0.929213,0.283979,0.236472 -20.0021 , -11.2132 , 7.97018 , 0.968354,0.0168449,-0.249011 -20.1884 , -11.2725 , 8.46432 , 0.988582,-0.0651785,-0.135857 -21.0755 , -11.7393 , 9.2501 , -0.913814,0.402071,0.0572968 -20.4857 , -11.342 , 9.45729 , 0.991564,0.122007,-0.0437719 -27.1084 , -15.1264 , 12.8421 , -0.961225,-0.254949,0.10511 -20.3725 , -11.168 , 10.3032 , 0.983245,0.150901,-0.102268 -24.6842 , -13.5893 , 12.867 , -0.59444,-0.751831,0.285291 -24.7854 , -13.5799 , 13.479 , -0.637903,-0.713414,0.290034 -23.1262 , -12.5685 , 13.1601 , -0.669217,-0.357074,0.65165 -20.2599 , -10.8831 , 12.0947 , 0.8848,0.461667,0.0631911 -22.2199 , -11.9282 , 13.7153 , -0.669217,-0.357074,0.65165 -26.3216 , -14.1614 , 16.7426 , -0.579177,-0.741012,0.339787 -23.2074 , -12.3503 , 15.414 , 0.714201,0.559155,-0.421026 -5.15979 , -2.12699 , 5.42293 , -0.381356,-0.528667,-0.758339 -4.95852 , -2.0049 , 5.37584 , 0.261381,0.204276,0.943372 -4.85205 , -1.93252 , 5.41519 , 0.187647,0.21529,0.958352 -4.75149 , -1.86399 , 5.45821 , 0.298468,0.12831,0.945756 -4.60561 , -1.77283 , 5.44978 , 0.591332,0.273367,0.758681 -4.6016 , -1.75284 , 5.59206 , 0.800438,0.584245,0.134005 -4.72466 , -1.79603 , 5.88563 , -0.880358,-0.474221,0.00921739 -4.74237 , -1.78566 , 6.06829 , 0.328004,-0.0128764,0.944589 -4.64762 , -1.719 , 6.11936 , 0.456205,-0.397049,0.796385 -4.52275 , -1.63847 , 6.13042 , 0.0431036,-0.050547,0.997791 -4.33376 , -1.52865 , 6.05402 , 0.747743,0.410509,0.521885 -4.42966 , -1.55285 , 6.35094 , 0.216073,-0.433884,0.874675 -4.2752 , -1.46002 , 6.31498 , 0.402495,0.389928,0.828223 -3.8148 , -1.22707 , 5.82884 , -0.706649,0.517433,0.482608 -3.68775 , -1.14962 , 5.80219 , 0.346403,0.209712,0.914345 -3.59849 , -1.0904 , 5.82903 , -0.319848,-0.128637,-0.938696 -3.32446 , -0.948751 , 5.55615 , 0.786324,0.562883,0.254672 -3.37587 , -0.951791 , 5.80057 , -0.859505,-0.509338,-0.0427226 -3.42524 , -0.953019 , 6.05636 , -0.758711,0.415585,-0.501644 -3.31052 , -0.883134 , 6.03326 , -0.9083,0.30972,-0.281185 -3.28613 , -0.85065 , 6.17089 , -0.226469,-0.751389,0.61978 -3.18488 , -0.786995 , 6.16933 , -0.201026,-0.414481,0.887577 -3.14181 , -0.747158 , 6.27954 , 0.528577,0.525512,-0.666666 -2.99325 , -0.665528 , 6.17634 , -0.254138,-0.150817,0.955337 -2.88998 , -0.601653 , 6.15823 , 0.306679,0.313238,-0.898794 -2.79241 , -0.540973 , 6.14671 , 0.142376,0.364768,-0.920148 -2.74156 , -0.4981 , 6.24199 , -0.301311,0.69567,-0.652116 -2.55285 , -0.406646 , 6.00643 , -0.688779,-0.247089,-0.681565 -2.71418 , -0.434374 , 6.63312 , -0.836384,-0.0741737,0.543102 -2.42896 , -0.313074 , 6.1322 , 0.421908,-0.875778,0.234534 -2.41244 , -0.279635 , 6.32437 , -0.475802,0.84032,-0.259759 -2.39794 , -0.244785 , 6.5359 , 0.159239,-0.183468,0.970043 -2.30238 , -0.186432 , 6.52064 , 0.141717,-0.0479931,0.988743 -2.21349 , -0.13046 , 6.52214 , 0.403126,0.151175,0.902572 -2.12498 , -0.0739536 , 6.52159 , 0.192134,-0.261043,0.946013 -2.15011 , -0.0421063 , 6.92311 , -0.905463,-0.34885,0.241744 -1.97689 , 0.0306934 , 6.62117 , -0.140479,-0.10411,-0.984595 -1.79187 , 0.10102 , 6.22732 , 0.733966,0.00220473,-0.679183 -1.68148 , 0.155813 , 6.10116 , -0.129072,0.0939276,0.987177 -1.59445 , 0.205711 , 6.06038 , -0.410132,0.281897,0.867367 -1.41047 , 0.258545 , 5.52769 , 0.98643,-0.0699221,-0.14855 -1.31425 , 0.301841 , 5.38328 , 0.700258,0.140336,-0.69996 -1.25277 , 0.343537 , 5.40444 , -0.631193,-0.37565,0.678589 -1.43732 , 0.418375 , 7.00448 , 0.414141,-0.8111,0.413043 -1.15383 , 0.43389 , 5.63065 , -0.37965,-0.683858,-0.62306 -1.07947 , 0.47516 , 5.58876 , -0.605589,-0.658266,-0.447155 -1.02242 , 0.522745 , 5.68416 , -0.485071,-0.730711,-0.480384 -1.064 , 0.633747 , 6.83161 , 0.217473,-0.928895,0.299766 -0.899708 , 0.623479 , 5.8712 , -0.956919,0.283702,-0.0618044 -0.822015 , 0.661407 , 5.78387 , 0.199146,0.890724,0.408599 -0.801393 , 0.78803 , 6.72961 , -0.91135,0.0547396,-0.407976 -0.730927 , 0.878362 , 7.11645 , 0.337446,-0.695899,0.633921 -0.619997 , 0.839531 , 6.19864 , 0.463548,-0.881789,-0.0870141 -0.541019 , 0.855226 , 5.91642 , -0.882075,-0.258273,-0.394004 -0.462338 , 1.01966 , 6.87376 , -0.120278,-0.620335,0.77506 -0.362202 , 1.15244 , 7.45006 , 0.0608036,-0.473651,0.878611 -0.334851 , 0.946713 , 5.58919 , -0.149397,-0.506412,0.849251 -0.265287 , 0.993398 , 5.60955 , 0.202369,0.11196,0.972888 --0.0711666 , 1.68524 , 9.60772 , -0.983301,0.0533811,-0.173982 -0.0141929 , 1.31606 , 6.98189 , -0.886855,0.325777,-0.327654 -2.3837 , -1.15959 , -0.568068 , -0.180471,0.232703,0.955657 -2.43509 , -1.19141 , -0.548623 , 0.159128,-0.221929,-0.961991 -2.50728 , -1.23971 , -0.543232 , 0.0597987,-0.162177,-0.984948 -2.57346 , -1.28282 , -0.530107 , -0.0545313,0.214537,0.975192 -2.63949 , -1.32545 , -0.514841 , -0.0845278,0.197973,0.976556 -2.71287 , -1.37357 , -0.502104 , -0.103326,0.207392,0.972786 -2.78026 , -1.41657 , -0.481925 , -0.0493034,0.181152,0.982219 -2.86923 , -1.47569 , -0.473149 , -0.0548203,0.194404,0.979388 -2.94375 , -1.5235 , -0.452482 , -0.0687212,0.190683,0.979243 -3.03326 , -1.58151 , -0.437748 , -0.0809895,0.194338,0.977586 -3.11558 , -1.63514 , -0.415496 , -0.0589239,0.195049,0.979022 -3.22123 , -1.70476 , -0.401974 , 0.0427436,-0.17335,-0.983932 -3.32758 , -1.77376 , -0.384634 , -0.0651862,0.163925,0.984317 -3.43341 , -1.84286 , -0.363303 , -0.0636223,0.185096,0.980659 -3.54808 , -1.9182 , -0.341239 , -0.0824287,0.185346,0.97921 -3.66245 , -1.99262 , -0.31509 , -0.0556879,0.191278,0.979955 -3.80159 , -2.08363 , -0.293729 , -0.122715,0.226502,0.966249 -3.92559 , -2.16231 , -0.261378 , -0.499008,0.247809,0.830411 -4.00165 , -2.20784 , -0.207602 , -0.939,0.0301844,0.34259 -3.9841 , -2.18626 , -0.119424 , 0.980196,-0.0725731,-0.184254 -4.00457 , -2.19165 , -0.0449342 , 0.998557,0.0537091,8.76609e-05 -3.99202 , -2.17325 , 0.0388887 , 0.998445,0.0548365,-0.0100595 -4.00173 , -2.17034 , 0.115223 , 0.997936,0.0495862,0.0407986 -3.98657 , -2.15057 , 0.197513 , 0.996858,0.0679126,0.040782 -3.98609 , -2.14171 , 0.275137 , 0.995273,0.0685849,0.0687619 -3.99313 , -2.13722 , 0.350814 , 0.993614,0.065688,0.091741 -3.94899 , -2.09836 , 0.434754 , 0.997834,0.0657777,0.000607961 -3.9699 , -2.10339 , 0.50642 , -0.94671,-0.00988995,0.321936 -3.9968 , -2.1142 , 0.577677 , -0.872415,0.0073184,0.488712 -4.06467 , -2.15171 , 0.645169 , -0.80995,-0.0586404,0.58356 -7.89325 , -4.74474 , 0.536649 , -0.10994,0.222995,0.9686 -8.4862 , -5.12989 , 0.665136 , 0.072633,-0.195337,-0.978043 -9.26062 , -5.63478 , 0.813216 , -0.0697061,0.186291,0.980019 -10.1105 , -6.18645 , 0.993105 , 0.0561358,-0.190392,-0.980102 -11.4896 , -7.09042 , 1.21665 , -0.0574377,0.18307,0.981421 -13.1081 , -8.14822 , 1.50633 , -0.0479097,0.181503,0.982223 -15.2408 , -9.54036 , 1.89307 , -0.0776973,0.188223,0.979048 -17.6768 , -11.1251 , 2.39278 , -0.0749957,0.185818,0.979718 -25.3551 , -16.1104 , 4.03572 , 0.828825,-0.100053,-0.550489 -25.3854 , -16.0702 , 4.5597 , -0.877211,0.138188,0.459788 -26.0301 , -16.4312 , 5.18553 , 0.861969,-0.419429,-0.284761 -25.837 , -16.2438 , 5.68624 , -0.860744,0.448719,0.240356 -25.8766 , -16.2074 , 6.22802 , 0.995247,-0.0686442,-0.0690822 -26.0065 , -16.2295 , 6.79384 , 0.995247,-0.0686442,-0.0690823 -26.1536 , -16.2607 , 7.37153 , -0.853405,0.010831,0.521136 -37.6135 , -23.5669 , 10.9931 , 0.550139,0.22653,-0.80376 -37.848 , -23.6244 , 11.8574 , 0.550139,0.22653,-0.80376 -24.6471 , -15.1081 , 8.55439 , 0.795262,0.187186,0.576645 -24.7559 , -15.1165 , 9.11553 , 0.795262,0.187186,0.576645 -20.2025 , -12.173 , 8.03064 , -0.918006,-0.0889107,0.386471 -21.0138 , -12.6345 , 8.77174 , -0.949622,-0.269729,0.159575 -20.1262 , -12.0243 , 8.87433 , -0.913335,-0.207727,0.35024 -19.9996 , -11.8936 , 9.26206 , -0.932801,-0.293974,0.208474 -26.4976 , -15.8182 , 13.1901 , -0.649497,-0.690938,0.317424 -26.1579 , -15.5373 , 13.6266 , 0.615678,0.740761,-0.268726 -5.40548 , -2.48768 , 5.53308 , -0.488046,-0.62883,-0.605296 -5.24369 , -2.37897 , 5.53451 , 0.45455,0.646795,0.612405 -5.18945 , -2.33007 , 5.63455 , 0.533955,0.684892,0.495797 -4.91136 , -2.15708 , 5.50795 , 0.341359,0.592462,0.729701 -4.76582 , -2.06027 , 5.5069 , -0.629618,-0.477215,-0.613064 -4.83873 , -2.08252 , 5.73506 , 0.98152,-0.182097,-0.0588103 -4.95589 , -2.1275 , 6.02305 , 0.995755,0.0616082,0.0683793 -4.83179 , -2.04158 , 6.04579 , -0.91187,-0.401289,-0.0863689 -4.60563 , -1.901 , 5.94159 , 0.616525,0.777157,-0.126192 -4.6748 , -1.919 , 6.19082 , -0.618095,-0.575639,-0.535349 -4.46894 , -1.79127 , 6.09956 , -0.0395736,-0.467438,0.88314 -4.36398 , -1.71679 , 6.13052 , 0.0636069,0.551118,-0.831999 -4.2368 , -1.6312 , 6.12773 , 0.0736336,-0.431825,0.898947 -4.16029 , -1.57271 , 6.19166 , 0.0901569,-0.266375,0.959644 -4.04015 , -1.49167 , 6.19052 , -0.0572992,-0.00654076,0.998336 -3.643 , -1.27276 , 5.76807 , 0.187125,0.0174314,0.982181 -3.60306 , -1.23364 , 5.86841 , -0.317042,-0.226739,-0.920909 -3.52566 , -1.17726 , 5.91096 , -0.392383,-0.225554,-0.891718 -3.42256 , -1.10783 , 5.9097 , -0.374444,-0.0571516,-0.925487 -3.61299 , -1.17721 , 6.41084 , 0.351501,-0.217524,0.910566 -3.48019 , -1.09346 , 6.36713 , 0.686468,-0.0247917,-0.726737 -3.25201 , -0.966527 , 6.13891 , 0.334968,-0.50653,0.794496 -3.23901 , -0.937749 , 6.30269 , 0.662245,-0.092644,-0.743538 -3.0551 , -0.833594 , 6.1341 , -0.0219294,-0.212143,0.976993 -2.95302 , -0.76724 , 6.11922 , 0.19622,0.0991006,0.975539 -2.83191 , -0.692347 , 6.0569 , -0.319951,0.292278,0.901224 -2.65257 , -0.594921 , 5.85625 , 0.24281,0.51712,0.82075 -2.642 , -0.567596 , 6.03112 , -0.741672,-0.354879,0.569195 -2.50032 , -0.487004 , 5.89567 , -0.678734,-0.213205,-0.702754 -2.61286 , -0.505492 , 6.39206 , 0.768657,-0.172693,-0.615909 -2.41394 , -0.405421 , 6.10476 , -0.355843,0.850923,-0.386401 -2.33557 , -0.350324 , 6.11968 , 0.379093,-0.778006,0.500995 -2.25359 , -0.294555 , 6.12338 , 0.384293,-0.822865,0.418583 -2.28613 , -0.275945 , 6.47499 , 0.47726,-0.453577,0.752656 -2.4876 , -0.304482 , 7.39914 , 0.724106,0.629513,0.281751 -2.15327 , -0.170726 , 6.61073 , 0.0961622,-0.087735,0.991491 -2.06549 , -0.111431 , 6.6093 , -0.128735,-0.267478,0.954925 -2.23588 , -0.114102 , 7.58048 , -0.894637,-0.431592,-0.115554 -2.16127 , -0.0516748 , 7.68592 , -0.894637,-0.431592,-0.115554 -1.69223 , 0.0828081 , 6.1167 , -0.405829,0.175778,0.896886 -1.61528 , 0.135276 , 6.11556 , -0.405829,0.175778,0.896886 -1.4163 , 0.198853 , 5.51539 , 0.61822,-0.574088,0.536868 -1.3219 , 0.246026 , 5.37158 , -0.546245,0.0167762,0.837457 -1.31079 , 0.289326 , 5.67859 , 0.631603,0.570559,0.524919 -1.37943 , 0.342505 , 6.53903 , -0.181072,0.0997075,0.978402 -1.19844 , 0.384812 , 5.84766 , -0.830922,-0.474023,-0.291325 -1.10071 , 0.426515 , 5.63802 , -0.605405,-0.54557,-0.579515 -1.03359 , 0.471856 , 5.64468 , -0.585926,-0.625677,-0.514994 -1.05588 , 0.560454 , 6.53436 , 0.69882,-0.377233,0.607738 -0.983071 , 0.619087 , 6.61859 , 0.783216,-0.562558,0.264765 -0.842057 , 0.616887 , 5.77558 , 0.199146,0.890723,0.408599 -0.77767 , 0.670551 , 5.86618 , 0.511837,0.684433,-0.519206 -0.757447 , 0.82026 , 7.04028 , 0.346616,-0.705042,0.618687 -0.671767 , 0.883903 , 7.08767 , 0.337445,-0.695899,0.633921 -0.568326 , 0.817743 , 5.92034 , -0.916941,-0.193374,-0.349036 -0.495427 , 0.971761 , 6.82927 , 0.0787041,-0.538468,0.838962 -0.408115 , 1.05092 , 7.00019 , 0.249264,-0.838316,0.484865 -0.240098 , 1.4738 , 9.66458 , -0.937981,0.333409,-0.0950288 -0.298038 , 0.95835 , 5.56583 , 0.0105861,-0.575707,0.817587 -0.227564 , 1.01324 , 5.62466 , 0.26205,-0.547714,0.794569 -0.0469894 , 1.30883 , 7.12812 , -0.877047,-0.440992,-0.190563 -2.33584 , -1.20235 , -0.583151 , -0.0938385,0.259726,0.961112 -2.36732 , -1.2216 , -0.547161 , -0.113695,0.224579,0.967801 -2.43158 , -1.26598 , -0.537388 , -0.122916,0.197058,0.972656 -2.48889 , -1.30501 , -0.520294 , 0.0799876,-0.172991,-0.98167 -2.56014 , -1.35547 , -0.511198 , 0.0861206,-0.192722,-0.977467 -2.6254 , -1.40077 , -0.494562 , 0.0668866,-0.220041,-0.973195 -2.69727 , -1.45039 , -0.480675 , -0.0866399,0.203676,0.975197 -2.77718 , -1.50653 , -0.468415 , -0.0519576,0.215664,0.975084 -2.85038 , -1.55641 , -0.449127 , -0.0513331,0.183747,0.981632 -2.93714 , -1.6182 , -0.435597 , -0.0755098,0.210816,0.974605 -3.01813 , -1.67386 , -0.414628 , -0.0805471,0.19954,0.976574 -3.11383 , -1.74054 , -0.398811 , -0.0485598,0.181254,0.982237 -3.21769 , -1.81245 , -0.383261 , -0.0518209,0.177518,0.982752 -3.3208 , -1.88541 , -0.363523 , -0.0585336,0.203965,0.977227 -3.42557 , -1.95796 , -0.339846 , -0.0707448,0.192181,0.978806 -3.54584 , -2.04122 , -0.318866 , -0.0780501,0.194863,0.97772 -3.65816 , -2.11881 , -0.290199 , -0.0572833,0.204247,0.977242 -3.79403 , -2.21369 , -0.26605 , -0.12394,0.228761,0.965561 -3.92287 , -2.30298 , -0.23351 , 0.633673,-0.0169673,-0.773415 -4.0138 , -2.3623 , -0.182811 , -0.934074,-0.0546463,0.352873 -4.00375 , -2.345 , -0.0961912 , 0.969278,-0.017048,-0.245376 -4.01554 , -2.34523 , -0.0173461 , 0.992811,0.119621,-0.0042626 -4.00288 , -2.32653 , 0.0678388 , 0.996442,0.0840015,0.00686561 -4.01224 , -2.32421 , 0.145927 , 0.99394,0.0905542,0.0623156 -3.99699 , -2.30416 , 0.229482 , 0.99736,0.070035,0.0192078 -3.98836 , -2.28843 , 0.310191 , 0.994986,0.0763193,0.0646363 -4.0106 , -2.29541 , 0.384244 , 0.996564,0.0455184,0.0692036 -3.96659 , -2.25529 , 0.469349 , 0.994815,0.0739814,-0.0697797 -3.99415 , -2.26704 , 0.541897 , -0.948869,-0.0502268,0.31165 -4.0371 , -2.28915 , 0.613305 , 0.784954,0.0281268,-0.618915 -4.15163 , -2.36378 , 0.67919 , 0.783242,-0.0256499,-0.621188 -7.60042 , -4.86076 , 0.493753 , -0.121571,0.237351,0.963787 -7.98687 , -5.12358 , 0.625792 , -0.105004,0.227963,0.967991 -8.64066 , -5.5773 , 0.764943 , -0.0664075,0.192178,0.979111 -9.45712 , -6.14383 , 0.929563 , -0.0718822,0.18964,0.979219 -10.5069 , -6.87518 , 1.1307 , -0.0466966,0.185284,0.981575 -11.8982 , -7.84574 , 1.38704 , -0.0594155,0.17948,0.981966 -13.8171 , -9.18457 , 1.72968 , 0.0502851,-0.184216,-0.981599 -15.9458 , -10.6625 , 2.16922 , -0.0913022,0.183725,0.978728 -18.8992 , -12.7145 , 2.77733 , -0.0613465,0.187914,0.980268 -26.5647 , -18.0117 , 4.61372 , 0.894612,0.37372,-0.244954 -27.2867 , -18.454 , 5.28505 , -0.911425,-0.388818,0.134627 -26.6763 , -17.9637 , 5.74887 , -0.855523,-0.498082,0.141403 -26.5299 , -17.799 , 6.28173 , -0.855523,-0.498082,0.141403 -26.9976 , -18.0607 , 6.94729 , -0.844849,-0.507557,0.169165 -27.5527 , -18.3791 , 7.65641 , 0.403431,0.378802,-0.832918 -24.3221 , -15.9142 , 8.95625 , 0.834496,0.167443,0.524956 -24.6845 , -16.1005 , 9.61606 , 0.834496,0.167443,0.524956 -5.11732 , -2.50439 , 5.60471 , 0.268293,0.754482,0.59898 -5.17848 , -2.52474 , 5.82293 , 0.607069,0.740149,0.289218 -5.14618 , -2.48717 , 5.95029 , 0.736602,0.558688,0.381164 -4.78015 , -2.25087 , 5.71475 , -0.786209,0.599871,-0.148427 -4.81023 , -2.25046 , 5.9047 , -0.643234,0.765416,0.01972 -4.83643 , -2.24754 , 6.09707 , -0.945698,-0.322865,0.0375908 -4.82807 , -2.22419 , 6.25543 , -0.790204,-0.139227,0.596819 -4.10396 , -1.78591 , 5.52699 , 0.718103,-0.121705,0.685212 -4.07793 , -1.75435 , 5.64302 , -0.750191,0.62188,0.224672 -4.23213 , -1.82547 , 6.00124 , 0.0966916,-0.499598,0.860844 -4.25361 , -1.81852 , 6.19729 , 0.0896592,0.338275,0.936766 -4.06356 , -1.69287 , 6.09966 , 0.0860674,-0.466088,0.880542 -4.01101 , -1.64471 , 6.1931 , 0.0956908,-0.338854,0.93596 -3.90871 , -1.5689 , 6.21338 , 0.0956908,-0.338854,0.93596 -3.617 , -1.39113 , 5.93143 , 0.275373,-0.127874,0.952795 -3.49392 , -1.30693 , 5.9015 , -0.333661,0.0597393,-0.940798 -3.40278 , -1.23896 , 5.91759 , -0.274413,0.131451,-0.952585 -3.32171 , -1.17779 , 5.94841 , -0.509329,0.00306626,-0.860567 -3.24006 , -1.11592 , 5.97687 , 0.598582,-0.248817,0.761439 -3.21282 , -1.08235 , 6.10623 , 0.536126,-0.167612,0.82733 -3.26865 , -1.08882 , 6.40018 , 0.452062,-0.569261,-0.686718 -3.02107 , -0.944147 , 6.10257 , 0.282117,0.144188,0.948483 -2.97593 , -0.900602 , 6.20285 , 0.15612,0.247038,0.956347 -2.88413 , -0.834397 , 6.2046 , -0.301206,0.132024,-0.944375 -2.80058 , -0.77328 , 6.22209 , -0.0715918,0.219746,0.972927 -2.62129 , -0.667539 , 6.01093 , -0.387381,0.256542,0.885507 -2.52552 , -0.601713 , 5.98585 , 0.367936,-0.0604401,0.927885 -2.56163 , -0.593912 , 6.28959 , -0.686897,-0.0218784,-0.726426 -2.49552 , -0.539701 , 6.3453 , -0.0414892,0.0101078,0.999088 -2.4084 , -0.47742 , 6.34386 , 0.597842,0.797402,-0.0820678 -2.28575 , -0.401905 , 6.23708 , -0.209581,0.935585,0.284176 -2.28135 , -0.371213 , 6.47611 , 0.44744,-0.558,0.69888 -2.20292 , -0.312587 , 6.49783 , -0.0648471,-0.464476,0.883209 -2.14826 , -0.26241 , 6.60351 , 0.0731482,-0.262341,0.962199 -2.03021 , -0.189931 , 6.48758 , -0.462052,-0.239196,0.853986 -2.19661 , -0.204113 , 7.4289 , -0.803487,-0.544121,-0.241539 -2.19451 , -0.160172 , 7.80551 , -0.894637,-0.431592,-0.115554 -1.79959 , -0.0169453 , 6.55962 , -0.0226624,-0.209466,0.977553 -1.62382 , 0.0618589 , 6.13155 , -0.405829,0.175778,0.896886 -1.40699 , 0.140133 , 5.44408 , -0.795031,0.0155734,0.606368 -1.3317 , 0.188323 , 5.38884 , 0.0068711,0.119061,0.992863 -1.30027 , 0.231269 , 5.5685 , -0.374141,0.80188,-0.46584 -1.38403 , 0.275008 , 6.49777 , -0.181072,0.0997075,0.978402 -1.27905 , 0.330691 , 6.32155 , 0.263247,-0.115617,-0.957775 -1.11811 , 0.373613 , 5.67738 , 0.559439,0.63374,0.53423 -1.04985 , 0.421525 , 5.66466 , -0.605405,-0.54557,-0.579516 -1.06263 , 0.497375 , 6.42577 , 0.841269,-0.44058,0.313299 -0.998699 , 0.559947 , 6.57 , -0.667672,0.584791,-0.460689 -0.879097 , 0.585035 , 6.02606 , -0.882884,0.334612,0.329471 -0.791676 , 0.618487 , 5.76869 , 0.199146,0.890724,0.408598 -0.778571 , 0.756288 , 6.91414 , 0.215649,-0.811534,0.543054 -0.698045 , 0.825924 , 7.02193 , 0.478428,-0.67794,0.558126 -0.597589 , 0.804959 , 6.19265 , 0.463548,-0.881789,-0.0870144 -0.523874 , 0.845826 , 6.07864 , -0.843543,0.536864,0.0145724 -0.44416 , 0.985157 , 6.81739 , 0.367981,-0.45007,0.813651 -0.346709 , 1.1234 , 7.42329 , 0.0608036,-0.473651,0.878611 -0.163672 , 1.51612 , 9.75705 , -0.623679,-0.756826,-0.19555 -0.257907 , 0.985936 , 5.63062 , -0.12772,0.46777,-0.874574 --0.0874136 , 1.69405 , 9.73722 , -0.956099,-0.288824,0.04956 -0.0117988 , 1.31559 , 6.99199 , 0.686064,-0.723478,0.0767837 -2.25105 , -1.211 , -0.564076 , -0.0959535,0.23413,0.967459 -2.30653 , -1.25162 , -0.551696 , -0.0829431,0.239284,0.9674 -2.36919 , -1.29887 , -0.542522 , -0.104004,0.234103,0.966633 -2.4317 , -1.34565 , -0.531208 , -0.0946426,0.189064,0.977393 -2.48846 , -1.38637 , -0.512746 , -0.0949354,0.199412,0.975306 -2.55915 , -1.43846 , -0.502088 , -0.0887112,0.202341,0.975289 -2.62288 , -1.48519 , -0.484011 , -0.0800926,0.192953,0.977934 -2.68623 , -1.53241 , -0.463694 , -0.0829789,0.191531,0.977973 -2.7581 , -1.5843 , -0.445592 , -0.067091,0.169853,0.983183 -2.85006 , -1.65385 , -0.437938 , -0.0658941,0.182703,0.980958 -2.92226 , -1.7057 , -0.414168 , -0.076899,0.195848,0.977614 -3.00799 , -1.76937 , -0.395765 , -0.0720141,0.17832,0.981334 -3.10167 , -1.83931 , -0.37782 , -0.0320289,0.162052,0.986262 -3.21718 , -1.92675 , -0.367457 , -0.0621297,0.189148,0.979981 -3.30483 , -1.98975 , -0.338474 , -0.0557976,0.202697,0.977651 -3.42241 , -2.07696 , -0.319475 , -0.0629895,0.191204,0.979527 -3.53202 , -2.15846 , -0.292596 , -0.0793314,0.198407,0.976904 -3.65065 , -2.24507 , -0.264403 , -0.0632558,0.204697,0.976779 -3.78325 , -2.34381 , -0.237466 , -0.121344,0.211482,0.96982 -3.9174 , -2.44182 , -0.205131 , -0.559241,0.00990237,0.828946 -4.02812 , -2.52184 , -0.159691 , -0.864564,-0.0860371,0.495103 -4.02604 , -2.51086 , -0.0737237 , -0.93584,-0.0215317,0.351768 -4.0531 , -2.52277 , 0.00252428 , 0.992679,0.120141,0.0124138 -4.02491 , -2.4916 , 0.0938086 , 0.993502,0.105802,0.041959 -4.02561 , -2.48421 , 0.175863 , 0.990757,0.0847071,0.10595 -4.01047 , -2.46283 , 0.260875 , 0.994016,0.0897335,-0.0622958 -4.00878 , -2.45303 , 0.341588 , 0.992879,0.118678,0.0103773 -4.10033 , -2.51606 , 0.405507 , 0.996943,0.0774227,0.0104701 -3.97173 , -2.40651 , 0.506454 , 0.986933,0.156097,-0.0399645 -4.02192 , -2.43772 , 0.578092 , -0.919875,-0.0916019,0.381365 -4.06325 , -2.46099 , 0.652109 , -0.936909,-0.066715,0.343148 -7.53908 , -5.11738 , 0.586714 , -0.0981401,0.234145,0.967236 -8.09961 , -5.53066 , 0.718212 , -0.0773393,0.19557,0.977635 -8.8189 , -6.06301 , 0.870649 , -0.0661068,0.18992,0.979572 -9.67244 , -6.69369 , 1.05406 , -0.0660147,0.190285,0.979507 -10.9394 , -7.63468 , 1.28418 , -0.0519333,0.179582,0.982371 -12.3317 , -8.66465 , 1.57468 , -0.0558996,0.179606,0.982149 -14.5437 , -10.3068 , 1.98083 , -0.0702368,0.187747,0.979703 -16.5846 , -11.8098 , 2.46791 , 0.0828224,-0.178904,-0.980374 -31.4036 , -22.7461 , 5.80593 , -0.200182,0.204929,0.958087 -31.4784 , -22.7289 , 6.49497 , 0.0340145,-0.104331,0.993961 -31.3934 , -22.5915 , 7.15728 , -0.241288,-0.108007,0.964424 -31.425 , -22.5421 , 7.84405 , -0.131421,-0.313291,0.94052 -39.2654 , -27.1786 , 20.2258 , -0.769626,0.593755,0.234799 -39.8538 , -27.3881 , 22.4423 , 0.653516,-0.744495,-0.136544 -4.68158 , -2.3908 , 5.65195 , -0.786209,0.599871,-0.148427 -4.58415 , -2.31235 , 5.69584 , 0.602622,-0.649153,0.464163 -4.95424 , -2.53055 , 6.28705 , -0.602132,-0.348331,-0.718403 -4.57323 , -2.2713 , 5.99731 , -0.229041,-0.832271,0.504843 -4.17195 , -2.00182 , 5.65668 , -0.903161,-0.0974426,-0.418096 -4.08216 , -1.9298 , 5.69396 , -0.783398,0.584026,0.212607 -4.09862 , -1.92332 , 5.87154 , -0.938748,0.32347,-0.118827 -4.31564 , -2.0389 , 6.33371 , -0.222957,0.666732,0.711167 -4.02873 , -1.84497 , 6.09996 , 0.15756,-0.173999,0.972059 -3.89277 , -1.74527 , 6.06855 , -0.133,-0.0729554,0.988427 -3.82063 , -1.6835 , 6.12816 , -0.272296,-0.133389,0.952923 -3.5342 , -1.49526 , 5.84722 , -0.23676,0.195703,0.951654 -3.42488 , -1.41419 , 5.83382 , 0.0575837,-0.276518,0.959282 -3.39466 , -1.37852 , 5.94943 , 0.449866,0.0913616,0.888411 -3.38661 , -1.35444 , 6.10662 , 0.584184,0.569912,0.577866 -3.22036 , -1.24166 , 5.98551 , 0.613334,0.340705,0.71256 -3.19526 , -1.20745 , 6.1154 , -0.649405,-0.422972,-0.631955 -3.09519 , -1.13283 , 6.10733 , 0.656434,0.280645,0.700238 -3.04827 , -1.08706 , 6.20101 , 0.371116,0.257909,0.892052 -2.987 , -1.03285 , 6.26757 , 0.272624,0.0905895,0.957846 -2.84763 , -0.937756 , 6.16427 , 0.0739709,-0.0500857,0.996002 -2.77857 , -0.879864 , 6.20885 , -0.570507,0.224372,-0.79005 -3.53356 , -1.23977 , 8.20347 , -0.871641,-0.464497,0.156476 -2.86287 , -0.875218 , 6.84891 , 0.099809,-0.444212,0.890345 -2.55835 , -0.701341 , 6.31495 , -0.134251,0.382117,-0.91431 -2.49081 , -0.644282 , 6.3624 , -0.0956176,-0.482973,0.870399 -2.22533 , -0.495775 , 5.85918 , 0.298485,0.867037,-0.39894 -2.24586 , -0.480786 , 6.14349 , -0.368516,-0.00319508,-0.929616 -2.19392 , -0.432811 , 6.23167 , 0.46951,-0.176144,0.865178 -2.1209 , -0.373643 , 6.25234 , 0.548715,-0.181145,0.816149 -2.06037 , -0.320621 , 6.31912 , 0.733354,-0.2504,0.632053 -1.99917 , -0.266631 , 6.3847 , -0.643306,0.450056,-0.61936 -1.95595 , -0.219241 , 6.52609 , 0.203865,-0.792475,0.574824 -1.91658 , -0.171121 , 6.69587 , -0.216639,-0.342108,0.914346 -1.62418 , -0.044477 , 5.80673 , -0.871045,-0.382131,0.308636 -1.72227 , -0.0364393 , 6.56576 , 0.101917,0.35976,-0.927462 -1.39774 , 0.0822887 , 5.38214 , 0.791799,-0.0515931,0.608599 -1.33657 , 0.129855 , 5.38637 , -0.0284103,0.240281,0.970288 -1.30435 , 0.173091 , 5.55635 , 0.0963853,-0.803786,0.587058 -1.2334 , 0.222796 , 5.51866 , 0.96002,-0.260328,0.10291 -1.29707 , 0.266806 , 6.36949 , 0.263247,-0.115617,-0.957776 -1.13261 , 0.320304 , 5.70622 , -0.937323,-0.249449,-0.24331 -1.07024 , 0.370893 , 5.73373 , -0.678924,-0.593538,-0.432175 -1.0622 , 0.43508 , 6.27688 , 0.561811,0.648516,0.51361 -0.995854 , 0.4944 , 6.35187 , 0.0518972,-0.713362,0.698872 -0.942233 , 0.562273 , 6.60494 , 0.500242,-0.833312,-0.235265 -0.823956 , 0.584892 , 5.97974 , -0.951218,-0.299149,-0.0754558 -0.799628 , 0.698248 , 6.85707 , -0.895905,0.313842,-0.314417 -0.720368 , 0.763762 , 6.90596 , 0.242052,-0.759776,0.60345 -0.64268 , 0.843693 , 7.09211 , 0.164614,-0.6264,0.761922 -0.548382 , 0.79476 , 5.97317 , -0.732522,-0.612984,-0.296078 -0.475154 , 0.941775 , 6.82261 , -0.254956,0.0333893,0.966376 -0.385457 , 1.05806 , 7.26095 , -0.861791,0.365309,-0.351947 -0.221225 , 1.43534 , 9.59847 , -0.96719,0.253526,-0.016381 -0.288492 , 0.950344 , 5.58677 , 0.095372,-0.650296,0.753671 -0.222554 , 1.0042 , 5.61564 , 0.26205,-0.547714,0.794569 -0.0402873 , 1.31037 , 7.16808 , -0.921427,-0.0321975,-0.387216 -2.23912 , -1.2756 , -0.550274 , -0.064072,0.241343,0.968323 -2.2931 , -1.31772 , -0.536842 , -0.105461,0.170339,0.979726 -2.35426 , -1.36649 , -0.526616 , -0.0535557,0.179988,0.98221 -2.41624 , -1.41499 , -0.514129 , -0.0904,0.189402,0.977729 -2.47782 , -1.46398 , -0.499401 , -0.100058,0.216807,0.971073 -2.5339 , -1.50597 , -0.477724 , -0.0912175,0.180371,0.97936 -2.60898 , -1.56669 , -0.467975 , -0.0998548,0.188997,0.976888 -2.67831 , -1.62132 , -0.450885 , 0.104657,-0.175806,-0.978846 -2.75493 , -1.68127 , -0.435544 , -0.0564575,0.17674,0.982637 -2.83208 , -1.74179 , -0.417258 , -0.076704,0.202338,0.976307 -2.91552 , -1.80731 , -0.400356 , -0.0754471,0.183248,0.980167 -3.00766 , -1.88028 , -0.383692 , -0.0600315,0.175192,0.982702 -3.09954 , -1.95249 , -0.363622 , -0.055773,0.193419,0.97953 -3.1847 , -2.01839 , -0.336332 , -0.0709905,0.198359,0.977555 -3.29861 , -2.1093 , -0.319339 , -0.0527326,0.19582,0.979221 -3.40574 , -2.19375 , -0.294444 , -0.0649496,0.191195,0.979401 -3.52072 , -2.28412 , -0.26845 , -0.0795124,0.196312,0.977312 -3.64347 , -2.38025 , -0.240678 , -0.0678814,0.19209,0.979027 -3.77376 , -2.48303 , -0.210638 , -0.110292,0.205322,0.97246 -3.91176 , -2.59135 , -0.177845 , 0.462628,-0.0358024,-0.88583 -4.05032 , -2.69866 , -0.139484 , 0.785355,0.0644744,-0.615679 -4.05521 , -2.69368 , -0.0539012 , -0.954873,-0.0838703,0.284926 -4.05816 , -2.6883 , 0.0313424 , 0.997117,0.0672192,0.0352142 -4.0301 , -2.65584 , 0.123889 , 0.992875,0.0568164,0.104746 -4.047 , -2.66022 , 0.204051 , 0.992292,0.088352,0.0868976 -4.01543 , -2.62638 , 0.294068 , 0.994851,0.0545549,-0.0854156 -4.01459 , -2.61642 , 0.376556 , 0.997433,0.0709925,0.0093076 -4.2409 , -2.79475 , 0.420537 , 0.989264,0.13524,0.0553756 -3.99256 , -2.58082 , 0.542132 , 0.989231,0.0995698,-0.107279 -4.04113 , -2.6132 , 0.616379 , 0.99605,0.0363889,-0.0809918 -4.10379 , -2.65637 , 0.690827 , 0.988397,-0.0655335,-0.137027 -7.21199 , -5.18829 , 0.543003 , -0.0986042,0.224551,0.969461 -7.6286 , -5.51153 , 0.673151 , -0.0907842,0.212542,0.972926 -8.24612 , -5.99654 , 0.81574 , -0.0756017,0.185545,0.979723 -9.01006 , -6.59754 , 0.984438 , 0.0723684,-0.1905,-0.979016 -9.90558 , -7.30148 , 1.18906 , -0.056549,0.180516,0.981945 -11.2128 , -8.33241 , 1.44918 , -0.0544464,0.182508,0.981696 -12.9319 , -9.68782 , 1.79229 , -0.048895,0.187743,0.981 -15.1765 , -11.4576 , 2.25559 , -0.0891975,0.181811,0.97928 -17.8376 , -13.5487 , 2.86269 , -0.0643395,0.198095,0.978069 -21.1227 , -16.1243 , 3.66826 , 0.185099,0.767672,0.61353 -35.939 , -27.6752 , 7.93636 , -0.554803,0.0145159,0.831855 -35.8263 , -27.5028 , 8.70887 , -0.51027,0.00417762,0.860004 -21.6619 , -16.3073 , 6.11112 , -0.0354769,0.993766,-0.105694 -21.6064 , -16.2129 , 6.57606 , 0.199575,0.895568,-0.397652 -21.5744 , -16.1386 , 7.04793 , 0.585781,0.577177,-0.56897 -16.5281 , -11.6369 , 11.0535 , 0.695514,-0.714374,-0.0770119 -16.0867 , -11.2658 , 11.1907 , 0.650579,-0.565169,-0.507278 -4.6257 , -2.56371 , 5.64326 , -0.0127869,-0.790151,0.612779 -4.48854 , -2.45368 , 5.63995 , 0.126683,0.559694,-0.818959 -4.22452 , -2.25581 , 5.47784 , 0.0530699,-0.303085,0.951485 -4.23119 , -2.24507 , 5.6339 , -0.967984,0.248787,-0.0333488 -4.29092 , -2.27003 , 5.86365 , -0.309212,-0.726807,0.613302 -4.06091 , -2.0986 , 5.72114 , 0.325918,-0.226329,0.917907 -4.02215 , -2.057 , 5.8247 , 0.447327,-0.663257,0.599991 -4.03114 , -2.04575 , 5.99613 , 0.502984,-0.782116,0.367835 -3.99916 , -2.00687 , 6.115 , 0.0950995,-0.841613,0.531642 -3.96889 , -1.96999 , 6.24143 , -0.183926,-0.143273,0.972442 -3.79876 , -1.84196 , 6.15379 , -0.3413,-0.160593,0.926134 -3.57196 , -1.678 , 5.96388 , 0.470099,-0.126173,-0.873548 -3.3512 , -1.51932 , 5.76584 , 0.406501,0.0834877,-0.909828 -3.36632 , -1.51213 , 5.9554 , 0.533172,0.303964,-0.789514 -3.4286 , -1.53306 , 6.23808 , -0.611424,-0.674901,-0.413122 -3.37417 , -1.48008 , 6.32207 , -0.445555,-0.5424,-0.712238 -3.15269 , -1.32513 , 6.08998 , -0.602157,-0.478291,-0.639253 -3.13399 , -1.29417 , 6.23721 , -0.678988,-0.514757,-0.523451 -3.12955 , -1.27196 , 6.42007 , 0.0191041,0.464524,0.885355 -2.9343 , -1.13607 , 6.20853 , 0.0698988,-0.0426072,0.996644 -2.8304 , -1.05494 , 6.1766 , 0.178355,0.126721,-0.975772 -2.75006 , -0.9881 , 6.1951 , -0.453172,0.119006,-0.883443 -2.73088 , -0.956287 , 6.35598 , 0.593495,-0.0512325,0.803205 -3.44784 , -1.32844 , 8.35248 , -0.871641,-0.464497,0.156476 -2.55387 , -0.814042 , 6.34891 , -0.273171,-0.458354,0.845748 -2.30954 , -0.660074 , 5.91756 , 0.420644,-0.635294,-0.647658 -2.18907 , -0.574966 , 5.79378 , -0.503797,-0.07704,0.86038 -2.12233 , -0.51912 , 5.81607 , 0.503797,0.0770395,-0.86038 -2.02446 , -0.448076 , 5.74268 , 0.307418,-0.235044,-0.922089 -2.09655 , -0.458101 , 6.20618 , -0.513692,0.307446,-0.800997 -2.03287 , -0.40188 , 6.25422 , 0.702561,-0.249789,0.666343 -2.00352 , -0.359179 , 6.42504 , -0.834687,0.0898877,-0.54334 -1.92573 , -0.296296 , 6.43259 , -0.754699,0.214994,-0.619844 -1.72359 , -0.184195 , 5.93594 , -0.904006,-0.279051,0.323889 -1.57777 , -0.0995736 , 5.61733 , 0.719569,0.374735,-0.584632 -1.48837 , -0.0379066 , 5.50886 , 0.31048,0.922594,0.228958 -1.38204 , 0.0261445 , 5.30042 , 0.762831,0.417644,-0.493622 -1.33384 , 0.0721962 , 5.36352 , 0.212785,-0.131532,0.968206 -1.28647 , 0.117826 , 5.43572 , -0.168439,0.722279,-0.670777 -1.2367 , 0.165895 , 5.50668 , 0.21704,-0.801935,0.556591 -1.30854 , 0.199341 , 6.3974 , -0.17982,0.437139,0.881234 -1.14625 , 0.263955 , 5.74474 , 0.997687,-0.0548944,0.0400889 -1.09056 , 0.316997 , 5.82245 , 0.829131,0.385059,0.405304 -1.0287 , 0.370432 , 5.85923 , -0.0466859,0.977686,0.204818 -1.01778 , 0.438356 , 6.43216 , -0.807385,0.471483,-0.35473 -0.964548 , 0.507321 , 6.67575 , -0.505118,0.678495,-0.533386 -0.871134 , 0.558217 , 6.43959 , 0.539736,0.841384,0.0275334 -0.791347 , 0.610259 , 6.3114 , -0.0025293,0.270384,0.962749 -0.744214 , 0.711163 , 6.919 , 0.320345,-0.635017,0.702946 -0.666752 , 0.783175 , 7.00643 , -0.137846,0.746377,-0.651091 -0.57266 , 0.767915 , 6.13626 , -0.940125,0.334403,0.0658848 -0.503348 , 0.834117 , 6.23075 , 0.913947,-0.400723,-0.0641945 -0.424602 , 0.959056 , 6.82018 , 0.818103,-0.567515,-0.0929188 -0.264702 , 1.39731 , 9.78627 , -0.97102,0.226404,-0.0765542 -0.138683 , 1.51266 , 9.91828 , -0.792986,-0.569798,-0.215648 -0.0220547 , 1.59476 , 9.79977 , -0.0113602,0.928953,0.370023 --0.104386 , 1.70506 , 9.87645 , -0.967782,-0.191534,-0.163439 -0.00845136 , 1.31635 , 7.01192 , 0.566266,-0.813166,0.13455 -2.18385 , -1.30707 , -0.560337 , -0.0996605,0.203399,0.974011 -2.23084 , -1.34538 , -0.541916 , -0.121572,0.201307,0.971955 -2.28406 , -1.39018 , -0.527114 , -0.045467,0.182331,0.982185 -2.34371 , -1.44042 , -0.515641 , -0.060998,0.209534,0.975897 -2.40417 , -1.49039 , -0.501907 , 0.0943296,-0.218779,-0.971204 -2.46424 , -1.54085 , -0.485932 , -0.0707499,0.209147,0.975322 -2.53166 , -1.59681 , -0.472486 , -0.061486,0.191742,0.979518 -2.59311 , -1.64766 , -0.451695 , -0.0970014,0.204964,0.973951 -2.66719 , -1.71038 , -0.43756 , -0.078548,0.184292,0.979728 -2.74205 , -1.77271 , -0.42058 , -0.0532328,0.197114,0.978934 -2.81743 , -1.83558 , -0.400558 , -0.0720491,0.190685,0.979004 -2.90007 , -1.90365 , -0.381702 , -0.0513327,0.191407,0.980168 -2.98945 , -1.97874 , -0.363326 , -0.0294218,0.18907,0.981523 -3.09299 , -2.06649 , -0.34854 , -0.0587457,0.205359,0.976922 -3.17635 , -2.13465 , -0.319124 , -0.0729229,0.190491,0.978977 -3.28724 , -2.22853 , -0.299735 , -0.0614001,0.195124,0.978855 -3.39232 , -2.31615 , -0.272323 , -0.0722333,0.198933,0.977347 -3.50426 , -2.40943 , -0.243739 , -0.0680214,0.193474,0.978745 -3.63188 , -2.51622 , -0.215972 , -0.0759747,0.188833,0.979066 -3.75911 , -2.62185 , -0.183049 , -0.0802179,0.186981,0.979083 -3.90094 , -2.74047 , -0.149701 , -0.326325,0.105833,0.939314 -4.05829 , -2.8721 , -0.114933 , -0.645178,0.088284,0.758915 -4.08412 , -2.88694 , -0.0340041 , -0.909819,-0.0118966,0.414834 -4.05779 , -2.8543 , 0.0615079 , 0.99679,0.0800524,0.00147356 -4.04476 , -2.83446 , 0.151752 , 0.988793,0.124561,0.0822932 -4.05322 , -2.83277 , 0.235877 , -0.977722,-0.164652,0.130192 -4.03783 , -2.81062 , 0.324294 , -0.908909,-0.221194,0.353494 -4.14739 , -2.89895 , 0.3891 , 0.99292,-0.0829712,0.0850013 -4.06276 , -2.81533 , 0.488489 , -0.96452,-0.14918,-0.217823 -4.04308 , -2.79046 , 0.57474 , -0.886324,-0.00264898,-0.463058 -4.0682 , -2.8042 , 0.655058 , -0.946034,-0.273227,0.174258 -4.25741 , -2.96016 , 0.722056 , -0.856014,-0.0924998,0.50861 -7.18969 , -5.48636 , 0.629731 , -0.0803725,0.224109,0.971244 -7.73195 , -5.93875 , 0.763663 , -0.0806744,0.189859,0.978491 -8.40918 , -6.50512 , 0.919724 , -0.0689938,0.191989,0.978969 -9.18523 , -7.1525 , 1.1073 , -0.0712771,0.191993,0.978805 -10.2486 , -8.04274 , 1.33886 , -0.0510457,0.182674,0.981847 -11.805 , -9.34759 , 1.64517 , -0.0561377,0.184142,0.981295 -13.64 , -10.8841 , 2.04389 , -0.0499905,0.177772,0.982801 -15.7834 , -12.6731 , 2.55693 , -0.0876082,0.18808,0.978239 -36.8579 , -30.1434 , 8.8184 , -0.957705,0.277591,-0.075793 -38.1524 , -29.9614 , 21.8146 , 0.459468,-0.879028,0.127273 -4.1362 , -2.38791 , 5.42956 , -0.302959,0.638833,-0.707183 -4.18365 , -2.40754 , 5.63488 , 0.0622309,0.952756,-0.297292 -4.10933 , -2.3384 , 5.69195 , 0.0247921,-0.71951,0.694039 -4.01277 , -2.25245 , 5.71735 , 0.0587043,-0.45577,0.88816 -3.93168 , -2.17892 , 5.76214 , -0.031572,-0.469986,0.882109 -3.81935 , -2.08235 , 5.75909 , 0.0682123,-0.741147,0.667869 -3.76949 , -2.03129 , 5.84437 , 0.0015965,-0.848171,0.52972 -3.7649 , -2.0118 , 5.99875 , 0.154598,0.866269,-0.475055 -3.70262 , -1.95163 , 6.06748 , -0.386875,0.882617,-0.26705 -3.53013 , -1.81383 , 5.95823 , -0.561117,-0.219033,0.798231 -3.34697 , -1.67118 , 5.81904 , 0.442968,-0.102231,-0.89069 -3.25775 , -1.59344 , 5.82886 , 0.124455,-0.384042,0.91489 -3.53788 , -1.76746 , 6.50021 , 0.953526,0.300941,0.0149193 -3.44515 , -1.68557 , 6.52076 , -0.900179,-0.435303,0.0137598 -3.43217 , -1.65744 , 6.69157 , 0.786751,0.604943,0.12275 -3.17105 , -1.46416 , 6.37396 , -0.462729,-0.464212,-0.755241 -3.06469 , -1.37542 , 6.35042 , 0.440584,0.668352,0.599326 -2.87482 , -1.23327 , 6.14001 , 0.08492,-0.259496,0.962003 -2.7931 , -1.16209 , 6.15249 , 0.190657,0.0385461,0.9809 -2.72321 , -1.09819 , 6.18959 , 0.627522,-0.0940848,0.772893 -2.56006 , -0.977189 , 6.00034 , -0.533347,-0.517325,0.669265 -2.47001 , -0.902824 , 5.97766 , 0.561912,-0.536102,0.62996 -2.44164 , -0.864592 , 6.10784 , -0.775991,0.630598,0.0135452 -2.35564 , -0.792217 , 6.09053 , -0.301589,0.0811026,0.949982 -2.17593 , -0.666668 , 5.8021 , -0.503797,-0.0770397,0.86038 -2.08832 , -0.596957 , 5.75988 , 0.307418,-0.235044,-0.922089 -1.99424 , -0.522577 , 5.68684 , 0.256058,-0.323512,-0.91092 -1.92484 , -0.463349 , 5.6868 , 0.359758,-0.337926,-0.869701 -2.02513 , -0.491341 , 6.26459 , 0.776444,-0.0224269,0.629787 -1.98313 , -0.443687 , 6.38844 , -0.877665,-0.101058,-0.468499 -1.91851 , -0.383384 , 6.43476 , -0.776852,0.103913,-0.621051 -1.85479 , -0.3237 , 6.48931 , 0.724559,-0.222445,0.652329 -1.56628 , -0.165804 , 5.58322 , -0.832225,-0.180545,0.524218 -1.45758 , -0.0921153 , 5.37788 , 0.694034,0.612817,-0.377853 -1.38829 , -0.0374482 , 5.33571 , -0.885163,-0.205348,0.417515 -1.3508 , 0.00575724 , 5.44856 , -0.641549,-0.252568,-0.724309 -1.28725 , 0.0592011 , 5.43268 , -0.0934219,0.61765,0.780885 -1.22104 , 0.112093 , 5.39576 , 0.0107508,-0.520301,0.853915 -1.17429 , 0.160261 , 5.47586 , 0.0587462,-0.763232,0.643448 -1.15555 , 0.205512 , 5.77302 , -0.954482,-0.236274,0.182039 -1.10826 , 0.259515 , 5.9009 , -0.76973,-0.458316,-0.444367 -1.04096 , 0.315725 , 5.87866 , -0.246554,-0.967459,-0.056865 -1.01717 , 0.377038 , 6.30298 , 0.836124,-0.446257,0.318984 -0.960542 , 0.441958 , 6.46727 , -0.845333,0.100624,-0.524677 -0.894458 , 0.50715 , 6.55062 , -0.934648,0.352277,0.0483109 -0.83289 , 0.579942 , 6.75203 , -0.754866,-0.607442,-0.247369 -0.759318 , 0.648495 , 6.80209 , -0.681532,-0.109853,-0.723496 -0.689561 , 0.728884 , 6.99994 , 0.232468,-0.773353,0.589817 -0.612686 , 0.807732 , 7.13624 , 0.164614,-0.626401,0.761922 -0.526328 , 0.77529 , 6.06577 , -0.947396,0.319171,0.0238751 -0.45224 , 0.915403 , 6.83529 , -0.624885,-0.0253932,-0.780304 -0.362688 , 1.04999 , 7.41269 , -0.209133,0.694375,-0.688554 -0.201147 , 1.40326 , 9.56167 , -0.93409,0.202282,-0.294205 -0.281332 , 0.93466 , 5.55833 , 0.0160433,-0.556597,0.830628 --0.044051 , 1.63535 , 9.78979 , -0.396237,0.108319,0.911736 -0.0472718 , 1.2833 , 7.0307 , -0.366025,-0.342169,-0.865417 -2.1156 , -1.32562 , -0.559074 , -0.109991,0.209748,0.971549 -2.16145 , -1.36488 , -0.541549 , -0.1038,0.217816,0.970455 -2.2133 , -1.41159 , -0.527445 , -0.1059,0.210556,0.971829 -2.27183 , -1.46283 , -0.517063 , -0.0772437,0.205603,0.975582 -2.32437 , -1.5089 , -0.499045 , -0.0727146,0.201661,0.976752 -2.3831 , -1.56133 , -0.484061 , -0.0687412,0.221032,0.972841 -2.44167 , -1.6133 , -0.467035 , 0.0531327,-0.209301,-0.976407 -2.51389 , -1.67747 , -0.457031 , -0.0590676,0.197249,0.978572 -2.57913 , -1.73623 , -0.439413 , -0.0903785,0.213832,0.972681 -2.63986 , -1.78824 , -0.414919 , -0.0638758,0.199532,0.977807 -2.71827 , -1.8594 , -0.400819 , -0.057424,0.19628,0.978865 -2.79839 , -1.93029 , -0.383364 , -0.057724,0.214747,0.974963 -2.87902 , -2.00166 , -0.362574 , -0.0387383,0.217873,0.975208 -2.96662 , -2.07906 , -0.342267 , -0.0119428,0.192848,0.981156 -3.06739 , -2.16889 , -0.325574 , -0.0624128,0.198768,0.978057 -3.15496 , -2.24678 , -0.297552 , -0.0694364,0.201883,0.976945 -3.2638 , -2.34385 , -0.275743 , -0.0537648,0.193243,0.979677 -3.37305 , -2.44108 , -0.249141 , -0.0667938,0.205858,0.9763 -3.49009 , -2.5441 , -0.220857 , -0.0620636,0.192197,0.979392 -3.61344 , -2.65447 , -0.190131 , -0.0635134,0.192661,0.979208 -3.75166 , -2.77696 , -0.159469 , -0.0674451,0.187467,0.979953 -3.89803 , -2.90693 , -0.124762 , 0.297686,-0.171507,-0.939132 -4.05106 , -3.04198 , -0.0863539 , 0.455751,-0.0159156,-0.889965 -4.22614 , -3.19807 , -0.0470013 , -0.975212,-0.21022,-0.0690659 -4.33636 , -3.29298 , 0.0172848 , -0.860604,-0.49775,0.107735 -4.09502 , -3.05725 , 0.171277 , 0.994275,0.102798,-0.0291507 -4.07306 , -3.02925 , 0.264871 , -0.987811,-0.0889945,0.127707 -4.12295 , -3.06745 , 0.343 , 0.998306,0.00210974,0.0581376 -4.06994 , -3.00999 , 0.440168 , 0.991239,0.098987,0.087445 -4.04426 , -2.97765 , 0.529938 , 0.974873,0.0373941,0.2196 -4.06877 , -2.9929 , 0.612402 , -0.952519,-0.0540462,0.299643 -6.79385 , -5.47589 , 0.587186 , -0.0661725,0.211991,0.975029 -7.27728 , -5.90481 , 0.713286 , -0.0732126,0.208682,0.975239 -7.84931 , -6.41141 , 0.859522 , -0.0725021,0.196652,0.977789 -8.56161 , -7.04295 , 1.03209 , -0.0667045,0.198493,0.97783 -9.44319 , -7.8254 , 1.2418 , 0.0618036,-0.190098,-0.979818 -10.7297 , -8.97222 , 1.51123 , -0.0470515,0.185074,0.981598 -12.2229 , -10.2988 , 1.85525 , -0.0586475,0.182296,0.981493 -14.7056 , -12.5107 , 2.36122 , -0.0923675,0.187996,0.977817 -16.8569 , -14.4151 , 2.94521 , -0.082863,0.189867,0.978307 -28.2072 , -24.439 , 6.22282 , -0.168602,0.498127,0.850554 -28.4033 , -24.5504 , 6.91828 , -0.0955987,0.15906,0.98263 -4.78139 , -3.08666 , 6.45969 , -0.113291,-0.0191752,0.993377 -3.9806 , -2.43957 , 5.59245 , -0.0020054,-0.680131,0.733088 -3.89286 , -2.35645 , 5.6249 , 0.174975,0.579633,-0.79587 -3.82057 , -2.28574 , 5.67674 , -0.1967,-0.520819,0.830697 -3.73787 , -2.20656 , 5.71139 , -0.0331017,-0.626937,0.778367 -3.64457 , -2.12005 , 5.72817 , 0.0807396,-0.782073,0.617934 -3.61122 , -2.08018 , 5.83499 , 0.0165246,-0.790569,0.61215 -3.56198 , -2.02765 , 5.91793 , -0.195037,-0.691148,0.695898 -3.48182 , -1.95137 , 5.95178 , 0.417481,0.162948,-0.893956 -3.5868 , -2.01382 , 6.2981 , -0.241584,0.88062,-0.407611 -3.47041 , -1.91005 , 6.27422 , -0.540778,0.770576,-0.337302 -3.50075 , -1.91469 , 6.51107 , 0.846432,0.479651,0.231273 -3.32612 , -1.76948 , 6.37419 , -0.802148,-0.52479,0.284875 -3.45837 , -1.84691 , 6.82276 , -0.00275073,-0.980093,0.198518 -3.0862 , -1.5607 , 6.27833 , -0.462729,-0.464212,-0.755241 -3.34558 , -1.72659 , 7.01476 , -0.234041,0.920425,-0.313118 -3.23839 , -1.6297 , 7.00421 , -0.154273,0.982818,-0.101334 -2.87941 , -1.3585 , 6.41831 , 0.101394,0.694241,0.712564 -2.71399 , -1.22489 , 6.23653 , 0.232249,0.582861,0.778674 -2.67026 , -1.17561 , 6.33573 , 0.645237,0.0418563,0.762835 -2.47894 , -1.02797 , 6.06395 , 0.228787,-0.568748,0.790052 -2.37526 , -0.938847 , 5.99477 , 0.228787,-0.568748,0.790052 -2.09267 , -0.736466 , 5.42682 , -0.0573252,0.531346,0.845213 -1.99563 , -0.656127 , 5.33843 , 0.0421707,0.448097,0.89299 -1.91882 , -0.589824 , 5.30283 , -0.37599,-0.23099,-0.897371 -1.85373 , -0.530474 , 5.29332 , 0.164211,0.410405,0.896996 -1.9194 , -0.550557 , 5.71585 , -0.514748,-0.0797533,0.853624 -2.04852 , -0.60404 , 6.39776 , 0.883299,0.178758,0.433391 -1.96515 , -0.530228 , 6.37026 , 0.883299,0.178758,0.433391 -1.9297 , -0.48355 , 6.52256 , 0.741705,0.00934685,0.670661 -1.632 , -0.29757 , 5.62435 , 0.59857,0.166377,-0.783602 -1.48761 , -0.199243 , 5.27727 , 0.870736,0.338585,-0.356621 -1.42058 , -0.142642 , 5.23698 , 0.575703,0.570844,-0.585408 -1.39978 , -0.10696 , 5.40951 , 0.783471,0.568557,-0.250833 -1.33575 , -0.0508399 , 5.3857 , 0.52272,0.549904,0.651436 -1.29775 , -0.00549423 , 5.49813 , 0.0518964,0.344368,0.937399 -1.21499 , 0.0565064 , 5.35359 , -0.153954,0.581564,0.7988 -1.16059 , 0.106994 , 5.37493 , 0.268429,0.0312159,-0.962794 -1.17556 , 0.142822 , 5.88991 , -0.989461,-0.0324729,-0.141114 -1.08534 , 0.204938 , 5.68127 , -0.864018,-0.195134,0.464107 -1.0522 , 0.258956 , 5.92748 , 0.815339,0.355408,0.457064 -1.02854 , 0.318349 , 6.32243 , -0.116654,-0.853031,0.508655 -0.966975 , 0.381799 , 6.40784 , 0.841169,-0.306218,0.445718 -0.908112 , 0.449277 , 6.56152 , -0.934648,0.352277,0.048311 -0.839239 , 0.516141 , 6.60399 , -0.908293,0.350588,-0.228236 -0.779982 , 0.594321 , 6.85441 , -0.572794,-0.345921,-0.743132 -0.703793 , 0.661463 , 6.8236 , 0.313035,-0.293121,0.903377 -0.630182 , 0.736636 , 6.91061 , -0.482716,0.631281,-0.607017 -0.547274 , 0.736036 , 6.10929 , -0.923883,0.367037,0.108277 -0.47749 , 0.897511 , 7.13899 , -0.0553091,-0.374316,0.92565 -0.402421 , 0.93863 , 6.86241 , 0.513768,0.124995,0.848775 -0.234458 , 1.38178 , 9.91848 , -0.980171,-0.0162446,-0.197487 -0.109849 , 1.51208 , 10.0989 , -0.217288,0.97348,0.0715788 -0.00771075 , 1.57664 , 9.79149 , 0.505373,0.261496,-0.822325 --0.122328 , 1.71523 , 10.0054 , -0.966321,-0.184063,-0.179849 -0.00414336 , 1.31836 , 7.04178 , 0.630031,0.301859,-0.715501 -2.09368 , -1.38158 , -0.540875 , -0.0882125,0.221829,0.971087 -2.15003 , -1.43497 , -0.533355 , -0.123002,0.219251,0.967884 -2.19404 , -1.47634 , -0.513025 , -0.0841918,0.217628,0.972394 -2.25082 , -1.53002 , -0.501296 , -0.0577605,0.202438,0.97759 -2.30843 , -1.58345 , -0.487403 , -0.0744494,0.218777,0.972931 -2.36564 , -1.63736 , -0.471173 , -0.079478,0.207982,0.974898 -2.4227 , -1.6908 , -0.4529 , -0.0459172,0.20202,0.978304 -2.48662 , -1.7516 , -0.436565 , -0.0500535,0.195243,0.979477 -2.5569 , -1.81759 , -0.42249 , -0.0743597,0.208485,0.975195 -2.62746 , -1.88506 , -0.405078 , -0.0592976,0.208489,0.976226 -2.69901 , -1.95117 , -0.384921 , -0.086248,0.213763,0.973071 -2.77086 , -2.01877 , -0.361524 , -0.0615265,0.221308,0.973261 -2.84876 , -2.0923 , -0.339217 , -0.0337935,0.206829,0.977793 -2.94706 , -2.18508 , -0.324509 , -0.0135891,0.195826,0.980545 -3.0386 , -2.27143 , -0.302093 , -0.0562317,0.183986,0.981319 -3.13778 , -2.36476 , -0.278868 , -0.0610818,0.206282,0.976584 -3.23739 , -2.45834 , -0.251238 , -0.0615232,0.197978,0.978274 -3.34362 , -2.55852 , -0.22224 , -0.0574337,0.194875,0.979145 -3.47051 , -2.67933 , -0.197017 , -0.0606664,0.197967,0.97833 -3.59081 , -2.79257 , -0.163505 , -0.0610589,0.198566,0.978184 -3.72573 , -2.91883 , -0.129667 , -0.0593486,0.196372,0.978732 -3.87471 , -3.05977 , -0.0940362 , -0.111705,0.156948,0.981269 -4.03105 , -3.20685 , -0.0538999 , -0.201489,0.00759438,0.979461 -4.19375 , -3.35975 , -0.00889202 , -0.0219096,0.128307,0.991492 -4.39329 , -3.54726 , 0.0348576 , -0.0833301,0.182807,0.979611 -4.0928 , -3.23498 , 0.294715 , -0.977651,-0.17524,-0.116149 -4.10576 , -3.23893 , 0.3824 , 0.987482,0.154839,0.0300596 -4.09611 , -3.22178 , 0.473814 , 0.988038,0.153715,0.0123196 -4.09182 , -3.20953 , 0.563236 , -0.975913,-0.0278145,0.21638 -4.12263 , -3.23208 , 0.648435 , -0.975913,-0.0278144,0.21638 -6.41435 , -5.45125 , 0.546358 , -0.0761774,0.197902,0.977257 -6.79904 , -5.81139 , 0.668175 , 0.0730944,-0.216264,-0.973595 -7.30572 , -6.28818 , 0.804043 , -0.0712874,0.199167,0.977369 -7.9116 , -6.85839 , 0.962747 , -0.0627091,0.197982,0.978198 -8.66852 , -7.57201 , 1.15266 , -0.0566499,0.198015,0.978561 -9.65473 , -8.50134 , 1.38729 , -0.0331867,0.201125,0.979003 -10.9427 , -9.71659 , 1.68832 , -0.0505,0.178456,0.982651 -12.5087 , -11.1931 , 2.07524 , -0.0613746,0.184831,0.980852 -15.1242 , -13.6636 , 2.6535 , -0.0849975,0.204326,0.975206 -28.6481 , -26.3289 , 6.86958 , -0.168602,0.498127,0.850554 -28.3136 , -25.9519 , 7.47697 , -0.168602,0.498127,0.850554 -4.50529 , -3.21154 , 4.97514 , -0.942124,0.111676,-0.316118 -4.442 , -3.14374 , 5.04906 , -0.942124,0.111676,-0.316118 -4.38265 , -3.0793 , 5.12671 , -0.817011,0.399908,-0.415411 -4.29072 , -2.9473 , 5.60266 , -0.777091,-0.590768,0.217078 -3.98254 , -2.67069 , 5.37219 , 0.604718,-0.363801,0.708495 -4.53499 , -3.12711 , 6.22855 , 0.635202,0.484685,-0.601331 -4.51548 , -3.09474 , 6.37654 , 0.546216,0.285783,-0.787385 -4.25711 , -2.86155 , 6.19896 , 0.719458,-0.0864813,-0.689131 -3.70248 , -2.38193 , 5.58358 , -0.0681618,-0.411821,0.908712 -3.59734 , -2.28081 , 5.58067 , -0.193075,0.5203,-0.831871 -3.52246 , -2.20585 , 5.61952 , -0.503541,0.465303,-0.72797 -3.51686 , -2.18711 , 5.76402 , -0.626941,0.466919,-0.623644 -3.43114 , -2.10179 , 5.78411 , -0.351703,0.626752,-0.695332 -3.34003 , -2.01418 , 5.79361 , -0.357047,-0.172712,0.91798 -3.23181 , -1.91174 , 5.76807 , 0.115299,0.111203,-0.987087 -3.15187 , -1.83321 , 5.78765 , 0.0762316,-0.0753142,0.994242 -3.06797 , -1.75071 , 5.79638 , -0.0544944,0.0430861,0.997584 -2.99276 , -1.67686 , 5.81932 , -0.0570279,0.0654175,0.996227 -2.8795 , -1.57197 , 5.76407 , 0.206636,0.447013,0.870334 -2.74802 , -1.4543 , 5.66253 , 0.575872,0.530327,-0.622193 -2.76446 , -1.45188 , 5.86612 , 0.575872,0.530327,-0.622193 -2.65003 , -1.34829 , 5.79308 , 0.656739,0.574059,0.48903 -2.58482 , -1.28208 , 5.82158 , 0.669772,0.636784,0.381984 -2.4335 , -1.15202 , 5.64453 , 0.543021,0.589869,-0.597648 -2.41614 , -1.12405 , 5.78401 , -0.491404,-0.642805,0.587643 -2.36872 , -1.07203 , 5.85148 , -0.573742,0.744613,-0.341132 -2.31276 , -1.01349 , 5.89966 , 0.547159,-0.752082,0.36741 -2.05692 , -0.812383 , 5.38795 , -0.236841,0.421237,0.875481 -1.98761 , -0.746582 , 5.37409 , 0.0249671,0.50522,0.862629 -1.90115 , -0.669573 , 5.30257 , -0.37599,-0.23099,-0.897371 -1.85958 , -0.624565 , 5.36856 , 0.479257,0.455264,0.750365 -1.81244 , -0.573877 , 5.41476 , 0.779037,0.312014,0.543827 -2.03115 , -0.696511 , 6.39731 , 0.883299,0.178758,0.433391 -1.7472 , -0.4925 , 5.62783 , -0.575807,-0.531073,0.621617 -1.67629 , -0.426075 , 5.5948 , 0.416525,-0.440282,-0.795398 -1.56328 , -0.336129 , 5.3867 , -0.938137,-0.345714,-0.0194944 -1.48638 , -0.269838 , 5.31039 , 0.85336,0.516548,0.0703894 -1.40401 , -0.200235 , 5.19284 , -0.570976,-0.297274,0.765254 -1.3627 , -0.154342 , 5.25834 , 0.223211,0.816602,-0.532295 -1.30432 , -0.0996318 , 5.24461 , 0.178512,-0.614557,0.76841 -1.29378 , -0.0672844 , 5.49442 , -0.136886,0.583044,0.800826 -1.22548 , -0.00711458 , 5.42928 , -0.491563,0.417641,0.764161 -1.15753 , 0.0526249 , 5.35234 , -0.69189,0.231774,0.68379 -1.14277 , 0.0927517 , 5.64983 , 0.336004,-0.89015,0.307789 -1.08084 , 0.150259 , 5.61999 , 0.767024,0.207884,-0.607008 -1.00968 , 0.20899 , 5.50902 , -0.633626,-0.649756,0.419923 -1.01123 , 0.259315 , 6.08295 , -0.913829,-0.405106,-0.0283896 -0.915744 , 0.319149 , 5.73031 , 0.167471,-0.905915,0.388938 -0.918064 , 0.390234 , 6.54208 , 0.446212,-0.698621,0.559306 -0.853093 , 0.459329 , 6.61518 , 0.516649,-0.629811,0.58001 -0.797523 , 0.538722 , 6.89613 , 0.298767,0.539229,0.787382 -0.721909 , 0.60701 , 6.84619 , 0.0191868,0.459675,0.88788 -0.649635 , 0.682074 , 6.914 , -0.66108,0.422074,-0.620344 -0.568977 , 0.712558 , 6.38181 , -0.960046,-0.116495,0.254442 -0.501437 , 0.760476 , 6.1977 , -0.919961,0.339575,-0.195857 -0.428618 , 0.892237 , 6.86764 , 0.57829,0.301616,0.758029 -0.267416 , 1.35303 , 10.2652 , 0.554398,0.832093,0.0162606 -0.173934 , 1.38704 , 9.64348 , -0.978022,0.183168,-0.0996153 -0.0419078 , 1.55234 , 10.07 , -0.0355326,0.806567,-0.590073 --0.0545673 , 1.6194 , 9.77123 , -0.505373,-0.261496,0.822325 --0.253682 , 1.91298 , 10.8983 , -0.954772,-0.250453,0.160263 -2.03665 , -1.40752 , -0.551702 , -0.0875365,0.225718,0.970252 -2.07964 , -1.4502 , -0.533825 , -0.0977822,0.227411,0.968877 -2.12885 , -1.49937 , -0.519565 , -0.108747,0.243167,0.963869 -2.17233 , -1.54247 , -0.498061 , -0.0664656,0.223803,0.972366 -2.23322 , -1.6033 , -0.490579 , -0.0672573,0.17627,0.982041 -2.28276 , -1.65239 , -0.470457 , -0.0736888,0.192616,0.978503 -2.34381 , -1.71433 , -0.457984 , -0.0898256,0.188737,0.977911 -2.40542 , -1.77689 , -0.442761 , -0.0631117,0.222842,0.972809 -2.46806 , -1.83818 , -0.425279 , -0.078043,0.206575,0.975313 -2.531 , -1.90102 , -0.404753 , -0.0716478,0.199291,0.977318 -2.59908 , -1.96973 , -0.386118 , -0.0632242,0.200807,0.977589 -2.66887 , -2.03823 , -0.364419 , -0.0906965,0.216167,0.972135 -2.74425 , -2.11456 , -0.343416 , -0.0875391,0.213406,0.973034 -2.8266 , -2.19694 , -0.322991 , -0.0443357,0.178193,0.982996 -2.91566 , -2.28623 , -0.302462 , -0.029157,0.166353,0.985635 -3.0186 , -2.38899 , -0.284743 , -0.0537212,0.193223,0.979683 -3.10758 , -2.47863 , -0.255916 , -0.058577,0.203844,0.97725 -3.21134 , -2.58179 , -0.228999 , -0.068313,0.196253,0.978171 -3.32074 , -2.6913 , -0.20064 , -0.0676666,0.186369,0.980147 -3.43147 , -2.80109 , -0.166977 , -0.0648349,0.191882,0.979274 -3.56158 , -2.932 , -0.135942 , -0.0669792,0.195997,0.978314 -3.69297 , -3.06299 , -0.0987291 , -0.0638083,0.198017,0.97812 -3.83767 , -3.20746 , -0.0599449 , -0.0588851,0.197407,0.978552 -4.00226 , -3.37353 , -0.0204554 , -0.0634391,0.198582,0.978029 -4.16823 , -3.53834 , 0.0267667 , -0.0804191,0.176547,0.981001 -4.36762 , -3.7389 , 0.0733467 , -0.071393,0.189919,0.979201 -4.56803 , -3.93876 , 0.129511 , -0.0761702,0.195744,0.977692 -4.78212 , -4.15216 , 0.192525 , -0.0739282,0.181296,0.980646 -5.05164 , -4.4222 , 0.256425 , -0.072035,0.179344,0.981146 -5.33455 , -4.7049 , 0.331068 , -0.0713819,0.18163,0.980773 -5.66616 , -5.03791 , 0.413817 , -0.0818759,0.182324,0.979824 -5.98476 , -5.35463 , 0.514016 , -0.0777623,0.194708,0.977774 -6.38579 , -5.75498 , 0.62362 , -0.0787952,0.201508,0.976312 -6.8423 , -6.21174 , 0.750508 , -0.0812986,0.196814,0.977064 -7.36868 , -6.7372 , 0.89822 , -0.0747333,0.200816,0.976774 -7.9852 , -7.35309 , 1.07235 , -0.0617883,0.202548,0.977321 -8.782 , -8.15028 , 1.28194 , -0.0300114,0.220919,0.97483 -9.85844 , -9.22825 , 1.54618 , -0.00949155,0.21348,0.976901 -11.2962 , -10.6689 , 1.892 , -0.0596594,0.18413,0.98109 -13.6497 , -13.0313 , 2.40456 , -0.0612744,0.190011,0.979868 -15.3875 , -14.7624 , 2.9549 , -0.0897144,0.210294,0.973513 -26.256 , -25.5927 , 6.2786 , -0.168602,0.498127,0.850554 -25.9706 , -25.2515 , 6.85807 , -0.295238,0.916725,0.269164 -26.166 , -25.3924 , 7.5473 , -0.248422,0.967201,0.0530065 -34.1666 , -33.257 , 11.279 , -0.282913,0.867469,0.409216 -34.4235 , -33.4395 , 12.2214 , -0.282913,0.867469,0.409216 -34.3378 , -33.28 , 13.0603 , 0.436398,-0.773333,0.459904 -34.2828 , -33.1516 , 13.9124 , -0.348372,0.923423,-0.161019 -32.1819 , -30.5695 , 19.0335 , 0.0456412,-0.763915,0.643701 -4.3882 , -3.33678 , 5.06234 , -0.81087,0.000702873,-0.585226 -4.33088 , -3.27138 , 5.14198 , -0.81087,0.000702868,-0.585226 -4.3413 , -3.26841 , 5.29544 , 0.852313,-0.0464118,0.520969 -4.35416 , -3.26859 , 5.4569 , 0.712282,-0.355256,0.605349 -4.58581 , -3.46894 , 5.88255 , -0.928735,0.216766,0.300772 -3.97835 , -2.89659 , 5.30151 , 0.695834,0.281548,0.660716 -3.95124 , -2.85993 , 5.41044 , -0.359302,-0.457569,-0.813347 -3.93757 , -2.83499 , 5.53968 , -0.558297,-0.389264,-0.732651 -4.09986 , -2.96968 , 5.91019 , 0.658945,0.605045,-0.446891 -4.17215 , -3.02115 , 6.17409 , 0.502226,0.809794,-0.303321 -3.87409 , -2.73827 , 5.91501 , -0.3901,-0.918941,0.0580413 -3.53926 , -2.42385 , 5.57658 , -0.621887,-0.230938,-0.748281 -3.50089 , -2.37721 , 5.66947 , -0.734043,-0.151311,-0.662032 -3.47065 , -2.33694 , 5.77684 , 0.837104,-0.172785,0.51904 -3.40978 , -2.27044 , 5.83726 , -0.849373,0.129695,-0.51161 -3.34484 , -2.19963 , 5.88827 , 0.554896,-0.0451511,0.830694 -3.19214 , -2.05281 , 5.78536 , 0.106199,0.186393,0.976719 -3.29211 , -2.12489 , 6.12989 , -0.825713,0.56409,0.000816687 -3.04526 , -1.89768 , 5.84093 , 0.40296,0.454354,0.794473 -2.96309 , -1.81267 , 5.84861 , 0.309815,0.488487,0.815717 -2.82833 , -1.68308 , 5.74485 , -0.204131,0.0441146,0.977949 -2.79233 , -1.63877 , 5.83947 , -0.289117,-0.018446,0.957116 -2.66065 , -1.51366 , 5.72792 , -0.452698,-0.290692,-0.842949 -2.59744 , -1.44643 , 5.7587 , -0.561717,-0.40191,-0.723147 -3.01652 , -1.77691 , 6.91598 , -0.239783,-0.2033,0.949302 -3.536 , -2.18187 , 8.40172 , 0.911977,-0.378274,-0.158764 -2.64318 , -1.43579 , 6.43729 , -0.31834,0.427304,0.84621 -2.35574 , -1.187 , 5.89981 , -0.679016,0.126138,-0.723206 -2.4543 , -1.24819 , 6.36615 , 0.275878,-0.42232,-0.863445 -2.27801 , -1.09179 , 6.08868 , -0.537714,0.711921,0.451699 -1.99724 , -0.856576 , 5.47346 , 0.0903476,-0.0938268,0.991481 -1.8876 , -0.757315 , 5.32949 , -0.156035,0.385596,0.909378 -1.86191 , -0.721174 , 5.44266 , -0.788587,-0.266739,-0.554059 -1.81491 , -0.669226 , 5.49003 , 0.128085,-0.693826,0.708661 -1.83359 , -0.663635 , 5.77241 , 0.461362,0.355921,-0.81269 -1.71793 , -0.562142 , 5.58135 , -0.258093,0.499442,-0.82701 -1.60268 , -0.462374 , 5.36726 , -0.759497,-0.178947,-0.625414 -1.54094 , -0.401054 , 5.35097 , -0.626813,-0.382693,0.678713 -1.48712 , -0.344435 , 5.36203 , 0.69672,0.707208,-0.120158 -1.37689 , -0.252758 , 5.10986 , 0.634645,0.206783,-0.744626 -1.39227 , -0.240074 , 5.44786 , 0.722937,0.0483936,0.689217 -1.29067 , -0.156862 , 5.21078 , 0.613426,-0.37414,0.695506 -1.24412 , -0.105652 , 5.24498 , 0.166985,-0.8545,0.491879 -1.21824 , -0.0659125 , 5.41581 , 0.0109811,0.72014,0.693742 -1.17011 , -0.0126639 , 5.45796 , -0.0341976,0.716197,0.69706 -1.10794 , 0.0473753 , 5.40966 , 0.279303,0.305732,0.91023 -1.06408 , 0.098875 , 5.48901 , 0.462313,-0.0252762,0.886357 -1.01704 , 0.15306 , 5.55725 , -0.617125,0.0258174,0.786442 -0.951867 , 0.212099 , 5.46505 , -0.160862,-0.234913,0.958613 -0.906605 , 0.267237 , 5.57042 , 0.0878056,-0.627566,0.773596 -0.856395 , 0.324535 , 5.64481 , -0.194052,-0.805031,0.560597 -0.807068 , 0.383383 , 5.748 , 0.592086,0.4252,-0.684573 -0.811265 , 0.479809 , 6.93759 , 0.205043,0.459349,0.864266 -0.737453 , 0.550965 , 6.8783 , 0.200607,0.630503,0.749815 -0.66514 , 0.623307 , 6.86706 , 0.458536,0.37547,0.805461 -0.591699 , 0.686556 , 6.72447 , -0.591969,0.80425,0.0524812 -0.519869 , 0.712669 , 6.17163 , -0.834783,0.514468,-0.196115 -0.450968 , 0.840556 , 6.85292 , -0.52561,-0.352389,-0.774311 -0.304604 , 1.29061 , 10.3938 , -0.282401,-0.948371,-0.144369 -0.21136 , 1.33406 , 9.76215 , -0.621725,0.783167,0.0104322 -0.0868793 , 1.48877 , 10.1009 , -0.464358,0.782252,-0.415276 --0.0075936 , 1.55975 , 9.79313 , -0.505373,-0.261496,0.822325 --0.139577 , 1.72119 , 10.1048 , -0.775653,-0.622214,-0.105888 -0.00246548 , 1.31467 , 7.0321 , 0.53675,-0.83103,0.145906 -1.96901 , -1.41899 , -0.551066 , -0.138017,0.235061,0.962132 -2.01062 , -1.46356 , -0.533789 , -0.108581,0.225654,0.968138 -2.05775 , -1.5135 , -0.520644 , -0.10175,0.241202,0.965126 -2.09913 , -1.55736 , -0.500255 , -0.105947,0.217247,0.97035 -2.15329 , -1.61353 , -0.488468 , -0.0628671,0.180129,0.981632 -2.20684 , -1.67117 , -0.47434 , -0.0660927,0.168349,0.983509 -2.26582 , -1.73391 , -0.463176 , -0.106165,0.205541,0.972873 -2.31442 , -1.78518 , -0.439445 , -0.0802257,0.210371,0.974324 -2.37453 , -1.84925 , -0.42317 , 0.0744946,-0.179432,-0.980946 -2.44074 , -1.91942 , -0.408762 , -0.0908308,0.20631,0.974262 -2.5012 , -1.98349 , -0.387013 , -0.0758921,0.199709,0.976912 -2.58005 , -2.06781 , -0.375046 , -0.0829001,0.198387,0.976612 -2.6418 , -2.13203 , -0.34741 , -0.0932623,0.216705,0.971772 -2.71467 , -2.20955 , -0.324988 , -0.074664,0.176035,0.981548 -2.80124 , -2.30172 , -0.306152 , -0.0440819,0.167057,0.984961 -2.89353 , -2.4005 , -0.28704 , -0.0603334,0.19313,0.979316 -2.98027 , -2.49212 , -0.260297 , -0.0446736,0.200414,0.978692 -3.08037 , -2.59901 , -0.235483 , -0.0547819,0.203682,0.977503 -3.18014 , -2.70491 , -0.206291 , -0.0805204,0.171519,0.981885 -3.29342 , -2.82485 , -0.17796 , -0.0755496,0.187863,0.979285 -3.40682 , -2.94576 , -0.144055 , -0.0779943,0.186434,0.979367 -3.53385 , -3.07945 , -0.109846 , -0.086977,0.184932,0.978895 -3.66687 , -3.22117 , -0.0717332 , -0.0775487,0.188419,0.979022 -3.81391 , -3.37745 , -0.0313419 , -0.072191,0.186915,0.97972 -3.97393 , -3.54784 , 0.012277 , -0.0769516,0.18889,0.978979 -4.14783 , -3.73235 , 0.0601199 , -0.0768301,0.184338,0.979855 -4.32869 , -3.92346 , 0.114904 , 0.0837819,-0.193978,-0.977422 -4.54256 , -4.15075 , 0.17148 , -0.0819348,0.187149,0.978909 -4.77663 , -4.39951 , 0.23482 , -0.0762564,0.18563,0.979656 -5.02493 , -4.66241 , 0.307761 , -0.0755907,0.181404,0.980499 -5.31261 , -4.96733 , 0.387366 , -0.0738571,0.183504,0.980241 -5.64745 , -5.32399 , 0.476519 , -0.0823059,0.18621,0.979057 -6.00286 , -5.70051 , 0.580631 , -0.0813618,0.190558,0.978299 -6.41948 , -6.14173 , 0.699291 , -0.0888468,0.190561,0.977647 -6.88156 , -6.63225 , 0.837301 , -0.0896727,0.19687,0.97632 -7.41169 , -7.19368 , 0.998454 , -0.0772338,0.198068,0.977141 -8.07646 , -7.89901 , 1.18918 , -0.0462234,0.238907,0.969942 -8.94387 , -8.8201 , 1.42287 , -0.0139193,0.241342,0.97034 -10.1357 , -10.0872 , 1.72393 , -0.00516918,0.194083,0.980972 -11.8348 , -11.8944 , 2.1349 , -0.0480129,0.181549,0.982209 -15.8025 , -16.1005 , 3.30291 , -0.846732,0.286515,0.44828 -25.0973 , -25.9615 , 5.94296 , -0.794261,0.541489,-0.275571 -25.3846 , -26.2177 , 6.64224 , -0.794261,0.541489,-0.275571 -25.4207 , -26.2046 , 7.29541 , -0.762156,0.446219,-0.469049 -33.2333 , -33.8184 , 18.0071 , 0.563405,-0.693793,0.448582 -31.4073 , -31.7775 , 18.7997 , 0.149589,-0.643164,0.750975 -4.57358 , -3.78643 , 5.18325 , 0.0493185,0.392196,0.918558 -4.38056 , -3.58095 , 5.1275 , -0.381893,-0.257847,0.88751 -4.35163 , -3.54088 , 5.24057 , 0.587317,0.201062,0.783985 -4.23311 , -3.41214 , 5.25344 , -0.733703,0.0519685,-0.67748 -4.19665 , -3.36479 , 5.35711 , -0.588409,0.341609,-0.732856 -4.09994 , -3.25764 , 5.3883 , -0.64439,0.0808551,-0.760411 -4.07793 , -3.22402 , 5.50889 , 0.518557,-0.0127351,0.854948 -4.01753 , -3.15289 , 5.58207 , 0.49298,0.117018,0.862136 -3.93039 , -3.05538 , 5.61873 , 0.276452,0.227155,0.933796 -3.83304 , -2.9484 , 5.63819 , 0.300682,0.260963,0.917327 -3.66132 , -2.76927 , 5.54671 , 0.00164552,-0.386073,0.922467 -3.63518 , -2.73114 , 5.65877 , 0.234978,-0.484367,0.842718 -3.58286 , -2.66895 , 5.73396 , -0.938112,-0.0507406,-0.342594 -3.54371 , -2.61934 , 5.83013 , -0.871682,0.0706027,-0.48496 -3.3493 , -2.42066 , 5.67405 , 0.454829,0.63339,0.626057 -3.41074 , -2.46691 , 5.93494 , -0.897698,-0.298813,-0.323803 -3.2833 , -2.33349 , 5.87867 , -0.589788,0.721812,-0.362129 -3.32503 , -2.35912 , 6.11915 , -0.936219,-0.331921,-0.115423 -3.34058 , -2.36067 , 6.32284 , -0.718652,0.222816,-0.658705 -3.22948 , -2.24189 , 6.29154 , -0.120842,-0.991758,0.0425889 -2.89245 , -1.91508 , 5.80244 , -0.433495,-0.449133,-0.781257 -2.92218 , -1.93017 , 6.03378 , 0.870758,-0.332421,0.362321 -2.89233 , -1.88836 , 6.14906 , -0.648947,0.690194,-0.320156 -2.8728 , -1.85534 , 6.29001 , 0.281481,0.908698,0.308279 -2.81563 , -1.78915 , 6.35335 , -0.969505,-0.0890089,0.228337 -2.8752 , -1.82674 , 6.69427 , 0.991039,-0.113923,-0.069732 -2.76733 , -1.71396 , 6.64298 , -0.820247,0.16592,0.547417 -2.44701 , -1.41437 , 6.03752 , 0.367372,0.727299,-0.579719 -2.46279 , -1.41241 , 6.27867 , -0.614509,-0.530212,0.584169 -2.36357 , -1.30968 , 6.21457 , -0.879734,-0.256415,0.400398 -2.31933 , -1.25536 , 6.302 , 0.670149,0.0767822,-0.738244 -2.17932 , -1.11884 , 6.10378 , -0.850915,0.499399,0.162922 -1.90058 , -0.869468 , 5.44779 , -0.108872,0.0822198,0.99065 -1.81017 , -0.779404 , 5.34835 , -0.159217,0.535944,0.829105 -1.79473 , -0.750741 , 5.4985 , -0.51528,-0.0566398,0.855148 -1.70129 , -0.659485 , 5.37585 , -0.214256,0.0149623,0.976663 -1.63071 , -0.587234 , 5.3257 , -0.174183,0.0518898,0.983345 -1.57627 , -0.527521 , 5.33067 , -0.0836714,-0.0484233,0.995316 -1.52628 , -0.470557 , 5.35304 , 0.521553,0.12855,-0.84348 -1.44262 , -0.391281 , 5.22992 , 0.671995,0.365218,-0.644235 -1.44521 , -0.372449 , 5.49105 , -0.59693,-0.691385,0.407015 -1.36046 , -0.29241 , 5.34496 , -0.0085151,-0.488586,0.872474 -1.26442 , -0.206389 , 5.11794 , 0.237883,-0.506301,0.828898 -1.24545 , -0.171454 , 5.29921 , -0.988624,-0.0921273,-0.118889 -1.23239 , -0.137347 , 5.53928 , -0.181563,0.638172,0.748178 -1.16309 , -0.0704663 , 5.44449 , 0.00842267,0.423063,0.906061 -1.08094 , 0.00183682 , 5.23887 , -0.669361,0.23229,-0.705689 -1.07357 , 0.0377059 , 5.58546 , 0.605594,0.514784,-0.606839 -1.0114 , 0.0995736 , 5.51556 , 0.496316,-0.0867297,-0.863799 -0.952646 , 0.159084 , 5.46372 , -0.212831,-0.0551154,0.975533 -1.07809 , 0.180856 , 7.45177 , -0.551436,0.625691,0.551751 -0.855826 , 0.273377 , 5.57481 , 0.184643,-0.520787,0.83348 -0.801233 , 0.330844 , 5.56876 , -0.289207,0.65236,-0.700561 -0.822066 , 0.418473 , 6.94865 , -0.0123385,0.442782,0.896544 -0.749639 , 0.492545 , 6.90001 , 0.238,0.473969,0.847768 -0.680671 , 0.568359 , 6.90951 , 0.230269,0.545625,0.805773 -0.604438 , 0.622609 , 6.55803 , -0.693468,0.49815,0.520527 -0.536605 , 0.67118 , 6.24495 , -0.410212,0.622518,0.666481 -0.474308 , 0.754232 , 6.42908 , -0.944135,0.00696167,0.329486 -0.402081 , 0.869738 , 6.89973 , 0.536029,0.35697,0.765014 -0.242009 , 1.28858 , 9.98995 , -0.0717537,0.958344,0.276457 -0.143145 , 1.37771 , 9.77455 , -0.942006,0.311545,-0.124756 -0.0184748 , 1.54238 , 10.1409 , -0.0355326,0.806567,-0.590073 --0.0670204 , 1.60493 , 9.76257 , 0.590163,0.0481581,-0.805847 --0.262299 , 1.90883 , 10.9186 , -0.954772,-0.250453,0.160263 -1.94695 , -1.47949 , -0.539766 , -0.0834709,0.237875,0.967702 -1.9873 , -1.52464 , -0.521732 , -0.150977,0.210254,0.965919 -2.03293 , -1.57609 , -0.507535 , -0.121921,0.195235,0.973149 -2.07916 , -1.62832 , -0.491268 , -0.0952184,0.179149,0.979203 -2.13598 , -1.6933 , -0.483357 , -0.071249,0.182363,0.980646 -2.18288 , -1.74486 , -0.463078 , -0.0776132,0.175134,0.981481 -2.2401 , -1.81001 , -0.450373 , -0.111972,0.214178,0.970356 -2.28744 , -1.86181 , -0.42569 , -0.0785115,0.188015,0.979023 -2.35645 , -1.94124 , -0.417103 , -0.0812172,0.181141,0.980098 -2.40927 , -2.00063 , -0.392045 , -0.108415,0.217883,0.969935 -2.47449 , -2.07278 , -0.373154 , -0.0738298,0.177274,0.981388 -2.54529 , -2.15283 , -0.355249 , -0.0957136,0.193445,0.976431 -2.60961 , -2.2256 , -0.330321 , -0.0867979,0.204794,0.974949 -2.69271 , -2.32042 , -0.3132 , -0.0511623,0.169958,0.984122 -2.77651 , -2.41461 , -0.292262 , -0.064782,0.192896,0.979078 -2.85477 , -2.50171 , -0.263986 , -0.0509517,0.209288,0.976526 -2.9445 , -2.60376 , -0.238365 , -0.0546407,0.192902,0.979695 -3.04682 , -2.71983 , -0.214602 , -0.0443515,0.169914,0.98446 -3.15644 , -2.84352 , -0.188471 , -0.0708237,0.184383,0.980299 -3.2595 , -2.95972 , -0.154344 , 0.0901209,-0.183272,-0.978923 -3.38268 , -3.09823 , -0.122624 , -0.0734752,0.176261,0.981597 -3.50519 , -3.23638 , -0.0849665 , -0.0847905,0.179926,0.980019 -3.64079 , -3.38898 , -0.0455409 , -0.0893255,0.179138,0.97976 -3.78918 , -3.55676 , -0.00327419 , -0.0753797,0.179279,0.980906 -3.95051 , -3.73857 , 0.0426093 , -0.0743982,0.179243,0.980988 -4.12544 , -3.93532 , 0.0934979 , -0.0847341,0.182852,0.979482 -4.31293 , -4.1466 , 0.150146 , -0.0782956,0.191453,0.978374 -4.52046 , -4.38054 , 0.212685 , -0.0820919,0.18245,0.979782 -4.7596 , -4.65079 , 0.279818 , 0.073031,-0.178551,-0.981217 -5.03211 , -4.95722 , 0.354217 , -0.0755874,0.18264,0.98027 -5.32398 , -5.28595 , 0.440541 , -0.0721547,0.18471,0.980141 -5.66754 , -5.67379 , 0.536766 , 0.0850194,-0.188152,-0.978453 -6.02432 , -6.07602 , 0.650283 , -0.0868359,0.180636,0.979709 -6.47211 , -6.58089 , 0.778032 , -0.0873957,0.193148,0.97727 -6.92618 , -7.09088 , 0.929095 , 0.0932837,-0.195487,-0.97626 -7.49145 , -7.72727 , 1.10527 , -0.0816399,0.216449,0.972875 -8.17305 , -8.49483 , 1.31501 , -0.0260127,0.265833,0.963668 -8.80087 , -9.19814 , 1.55742 , 0.0217992,0.267515,0.963307 -10.676 , -11.3231 , 1.9439 , -0.041218,0.180702,0.982674 -12.2972 , -13.153 , 2.40056 , -0.0438138,0.179519,0.982778 -15.295 , -16.5406 , 3.13836 , -0.846732,0.286515,0.44828 -16.1498 , -17.483 , 3.67484 , -0.846732,0.286515,0.44828 -16.1322 , -17.433 , 4.08737 , -0.846732,0.286515,0.44828 -16.0768 , -17.3396 , 4.49151 , -0.846731,0.286515,0.44828 -16.0763 , -17.3079 , 4.90759 , -0.846731,0.286515,0.44828 -16.0315 , -17.2264 , 5.31312 , -0.846731,0.286515,0.44828 -24.0856 , -26.2681 , 8.1658 , 0.771976,-0.505071,0.385949 -24.0296 , -26.1581 , 8.78611 , 0.771976,-0.505071,0.385949 -33.3723 , -36.5306 , 13.659 , -0.357338,0.933886,-0.0129125 -31.3292 , -34.0529 , 15.4471 , -0.37314,0.925824,0.0601373 -30.4267 , -32.9854 , 15.8719 , 0.686386,-0.703348,0.184866 -28.4707 , -30.571 , 18.1482 , -0.250974,-0.857997,0.448167 -28.5148 , -30.3696 , 21.589 , -0.198351,-0.979485,-0.0355787 -31.1152 , -33.1444 , 24.4624 , -0.327009,-0.862351,-0.386545 -31.5667 , -33.5645 , 25.804 , -0.341096,-0.86851,-0.359644 -4.14542 , -3.6008 , 4.95854 , -0.741064,0.666408,-0.082006 -4.08712 , -3.5289 , 5.03283 , -0.741064,0.666408,-0.082006 -4.10826 , -3.54092 , 5.19778 , -0.57984,-0.777799,0.242518 -4.1702 , -3.59518 , 5.4156 , -0.766616,-0.00960999,-0.642034 -4.11225 , -3.5233 , 5.49527 , -0.835061,0.0707478,-0.54559 -4.06322 , -3.46082 , 5.58595 , 0.6579,0.00246558,0.753101 -3.93779 , -3.31654 , 5.57434 , -0.0990387,-0.177624,0.979102 -3.87361 , -3.23864 , 5.64016 , -0.154977,-0.386993,0.908966 -3.71448 , -3.06016 , 5.57072 , -0.0221152,0.175683,0.984198 -3.61577 , -2.94659 , 5.57976 , 0.105319,-0.106912,0.988675 -3.49946 , -2.8144 , 5.55625 , 0.725135,-0.381974,0.572953 -3.4776 , -2.78124 , 5.6748 , 0.659409,-0.547068,0.515652 -3.4594 , -2.75059 , 5.80086 , 0.604854,-0.514402,0.607899 -3.44809 , -2.72689 , 5.94217 , 0.655432,-0.404517,0.637789 -3.41185 , -2.67854 , 6.04583 , -0.629214,0.341936,-0.697976 -3.32577 , -2.57803 , 6.06277 , 0.350774,-0.0987335,0.931241 -3.12008 , -2.35673 , 5.85531 , -0.241376,0.681303,-0.69106 -3.09658 , -2.32071 , 5.97555 , 0.068514,-0.990054,0.122877 -3.11964 , -2.33177 , 6.19306 , -0.170562,0.985327,-0.00632555 -3.13513 , -2.33376 , 6.40466 , -0.157552,0.230322,-0.960276 -3.07946 , -2.26503 , 6.47698 , 0.425815,-0.117286,0.897177 -2.96499 , -2.13779 , 6.42163 , 0.0848108,0.14499,0.985792 -2.81148 , -1.97181 , 6.26827 , 0.215046,0.511884,0.831703 -2.85911 , -2.0045 , 6.57297 , 0.997273,-0.0284809,0.0680774 -2.8327 , -1.96405 , 6.71616 , 0.986611,-0.115186,-0.115459 -2.44364 , -1.57301 , 5.94759 , 0.578731,-0.75234,0.314731 -2.4288 , -1.54514 , 6.09972 , 0.419061,-0.795401,0.437864 -2.39903 , -1.50191 , 6.21684 , -0.154359,-0.552263,0.819255 -2.27411 , -1.36956 , 6.07228 , -0.248656,0.0488119,0.967361 -2.17457 , -1.26178 , 5.98656 , -0.303363,0.533299,0.78966 -2.12781 , -1.20282 , 6.05281 , -0.303363,0.5333,0.78966 -1.85358 , -0.937109 , 5.38977 , 0.263517,-0.365069,-0.892908 -1.7967 , -0.870871 , 5.39288 , 0.0884803,0.261649,0.961099 -1.72897 , -0.796361 , 5.35702 , 0.119946,0.117499,0.985803 -1.67821 , -0.735841 , 5.37534 , 0.355881,0.268267,0.895199 -1.61407 , -0.66529 , 5.34497 , 0.73362,0.328296,0.594998 -1.57505 , -0.615294 , 5.40766 , -0.806128,-0.285703,-0.5182 -1.55657 , -0.58226 , 5.56513 , 0.605925,-0.639683,0.472929 -1.41825 , -0.451578 , 5.19382 , 0.431472,0.853635,-0.291785 -1.35353 , -0.381201 , 5.12644 , -0.973945,-0.212516,0.079174 -1.32211 , -0.338829 , 5.22225 , -0.878741,-0.474439,-0.0521747 -1.28946 , -0.293194 , 5.31713 , 0.432528,-0.598987,-0.673894 -1.29641 , -0.276121 , 5.65608 , 0.503511,0.524522,0.686551 -1.22605 , -0.203151 , 5.56405 , -0.518237,0.368329,0.771858 -1.1657 , -0.137603 , 5.51916 , -0.376814,0.454783,0.806959 -1.11055 , -0.0749386 , 5.50203 , -0.236699,0.233064,0.943215 -1.05141 , -0.0113609 , 5.444 , 0.00461103,-0.0832929,0.996514 -1.00998 , 0.0425981 , 5.53305 , 0.128535,0.721815,-0.680045 -0.961532 , 0.101393 , 5.57116 , -0.0273433,0.510238,0.859599 -0.903473 , 0.162749 , 5.50878 , -0.00264469,0.113395,0.993547 -0.857752 , 0.221274 , 5.57418 , 0.278048,-0.3496,0.894689 -0.806311 , 0.28113 , 5.58849 , -0.184643,0.520787,-0.83348 -0.832418 , 0.355893 , 7.01906 , -0.540724,-0.166206,-0.824617 -0.761213 , 0.433088 , 6.94133 , 0.0909567,0.491166,0.866304 -0.693393 , 0.510867 , 6.96168 , 0.206132,0.412584,0.88729 -0.624187 , 0.584728 , 6.87025 , 0.392246,0.419023,0.818879 -0.55114 , 0.625025 , 6.27794 , -0.722169,0.416292,0.552424 -0.490779 , 0.691692 , 6.24348 , -0.410212,0.622518,0.666481 -0.422067 , 0.818558 , 6.90487 , 0.553175,0.471089,0.687076 -0.353655 , 0.89874 , 6.92596 , 0.170222,0.449332,0.876998 -0.183041 , 1.29974 , 9.70468 , -0.686792,0.72017,0.0983445 -0.0657837 , 1.45994 , 10.0532 , -0.0825809,-0.789559,0.608092 --0.0236398 , 1.543 , 9.78441 , 0.505373,0.261496,-0.822325 --0.157779 , 1.72838 , 10.2139 , -0.929518,-0.332674,-0.159134 -0.00343348 , 1.30629 , 6.99285 , -0.576302,0.809895,-0.109299 -1.88934 , -1.49914 , -0.551338 , -0.0721841,0.284861,0.955847 -1.92292 , -1.53947 , -0.528318 , -0.0685022,0.266302,0.961452 -1.9674 , -1.59186 , -0.51492 , -0.0829458,0.210359,0.974099 -2.01153 , -1.64482 , -0.499671 , -0.107134,0.194451,0.975044 -2.05625 , -1.69851 , -0.482158 , -0.0581598,0.193047,0.979464 -2.10619 , -1.7584 , -0.467995 , -0.069831,0.1849,0.980273 -2.15574 , -1.81874 , -0.451397 , -0.0856444,0.193505,0.977354 -2.20707 , -1.87904 , -0.432515 , -0.0804662,0.203744,0.975712 -2.26867 , -1.95279 , -0.420622 , -0.0664893,0.169979,0.983202 -2.32451 , -2.02043 , -0.401291 , -0.098967,0.220455,0.970363 -2.38114 , -2.08772 , -0.379406 , -0.0865429,0.189933,0.977975 -2.44965 , -2.16959 , -0.362905 , -0.102811,0.197262,0.974945 -2.50661 , -2.23685 , -0.335351 , 0.104864,-0.200318,-0.974103 -2.58144 , -2.32608 , -0.316408 , -0.0600577,0.193038,0.979351 -2.65577 , -2.41548 , -0.293765 , -0.050609,0.182706,0.981864 -2.74257 , -2.52017 , -0.274241 , -0.052631,0.213476,0.97553 -2.81807 , -2.60932 , -0.24396 , -0.0681634,0.205124,0.976359 -2.90501 , -2.7134 , -0.216238 , -0.0436213,0.168564,0.984725 -3.02196 , -2.85539 , -0.198686 , -0.032913,0.176762,0.983703 -3.11565 , -2.96708 , -0.164118 , -0.0666621,0.191866,0.979155 -3.22163 , -3.0935 , -0.13014 , -0.0580192,0.18876,0.980308 -3.35215 , -3.251 , -0.10016 , -0.0627171,0.187014,0.980353 -3.47135 , -3.39287 , -0.0590341 , -0.0763175,0.188878,0.979031 -3.60832 , -3.55705 , -0.0181222 , -0.0777367,0.186973,0.979285 -3.7514 , -3.72801 , 0.0278585 , -0.0620454,0.182105,0.98132 -3.9263 , -3.93755 , 0.0727926 , -0.0630298,0.192326,0.979305 -4.09517 , -4.14014 , 0.128765 , -0.0763428,0.202625,0.976276 -4.28245 , -4.36426 , 0.18912 , -0.0702369,0.184436,0.980332 -4.49557 , -4.61792 , 0.254473 , -0.072218,0.183851,0.980298 -4.73952 , -4.91052 , 0.325984 , -0.0662599,0.183088,0.980861 -5.01435 , -5.24055 , 0.405986 , -0.0666491,0.19282,0.978968 -5.31526 , -5.59976 , 0.498017 , -0.0636884,0.198924,0.977943 -5.65952 , -6.01233 , 0.602452 , -0.0675359,0.199117,0.977646 -6.04881 , -6.47789 , 0.723133 , -0.0711589,0.196937,0.97783 -6.48093 , -6.99519 , 0.863418 , 0.0890175,-0.197183,-0.976317 -6.95659 , -7.56367 , 1.02683 , -0.0882215,0.190156,0.977782 -7.57225 , -8.29841 , 1.21972 , -0.0770965,0.268933,0.960068 -7.89899 , -8.68343 , 1.43103 , -0.0420498,0.40615,0.912839 -8.79659 , -9.75692 , 1.70581 , 0.0126358,0.239006,0.970936 -10.9686 , -12.3707 , 2.16746 , -0.0441328,0.183846,0.981964 -15.4572 , -17.7464 , 3.47192 , -0.846732,0.286515,0.44828 -24.0642 , -28.0429 , 6.16975 , 0.777567,-0.452646,0.436463 -24.3406 , -28.3321 , 6.88926 , -0.758153,0.49786,-0.421118 -24.2247 , -28.1476 , 7.51889 , 0.771976,-0.505071,0.385949 -30.0734 , -34.937 , 12.4394 , -0.27346,0.925735,-0.261217 -30.0933 , -34.9041 , 13.2911 , -0.168304,-0.981,0.0965007 -30.3077 , -35.0425 , 15.0995 , -0.541792,0.837401,-0.0722581 -30.2712 , -34.9417 , 15.9524 , -0.541792,0.837401,-0.0722581 -30.1099 , -34.6312 , 17.6264 , 0.406934,-0.871199,0.274622 -25.4803 , -29.0167 , 17.3152 , 0.113519,-0.980083,-0.162944 -26.3334 , -29.9091 , 19.4946 , 0.0080265,0.989444,0.144692 -26.9886 , -30.559 , 21.6743 , -0.0303635,-0.999094,0.0298134 -26.2141 , -29.6001 , 21.9214 , -0.0638094,0.996826,-0.047616 -29.6363 , -33.5122 , 25.6795 , 0.257817,0.870338,0.419575 -30.1603 , -34.0524 , 27.1367 , 0.19543,0.874892,0.443139 -3.94012 , -3.58716 , 5.52894 , -0.482886,0.118362,-0.867647 -3.7202 , -3.32917 , 5.38511 , 0.427933,0.311722,-0.848353 -3.5233 , -3.09763 , 5.25781 , 0.496113,0.61655,-0.611341 -3.46886 , -3.02763 , 5.32254 , 0.628136,-0.774818,0.0714313 -3.48431 , -3.03538 , 5.49114 , -0.50379,0.828126,-0.24577 -3.50754 , -3.0501 , 5.67597 , 0.351409,-0.568143,0.744127 -3.42637 , -2.94983 , 5.70268 , 0.755988,-0.292875,0.585412 -3.39448 , -2.90437 , 5.80773 , 0.722905,-0.294403,0.625088 -3.31737 , -2.80777 , 5.83681 , 0.369448,-0.649172,0.664894 -3.27475 , -2.75065 , 5.92445 , 0.435627,-0.582237,0.686461 -3.1879 , -2.64428 , 5.93322 , 0.125248,-0.372077,0.919713 -3.02737 , -2.45821 , 5.79741 , 0.207052,0.112887,0.971795 -2.97644 , -2.39127 , 5.86166 , 0.336371,-0.0169086,0.941578 -2.94467 , -2.34621 , 5.96496 , 0.770234,-0.632703,0.0801669 -2.86387 , -2.24749 , 5.96943 , 0.736657,-0.151934,0.658978 -2.95677 , -2.3348 , 6.3436 , 0.475142,-0.15177,0.866721 -2.86944 , -2.2291 , 6.33841 , 0.128141,-0.268738,-0.954652 -2.76154 , -2.10213 , 6.27949 , -0.123956,0.441076,0.888868 -2.65495 , -1.97642 , 6.21602 , -0.372664,0.329491,-0.8675 -2.58822 , -1.8942 , 6.24388 , -0.275182,0.299089,-0.913685 -2.39724 , -1.68057 , 5.94612 , 0.391625,-0.211057,0.895592 -2.32781 , -1.59653 , 5.9491 , -0.332037,0.681082,-0.652594 -2.30655 , -1.5614 , 6.08297 , 0.0563208,-0.75134,0.657508 -2.26396 , -1.50377 , 6.163 , -0.337063,-0.0725472,0.938683 -2.15143 , -1.37648 , 6.03418 , -0.607157,-0.131904,0.783557 -2.10011 , -1.31049 , 6.08329 , -0.567511,0.0380463,0.822486 -1.87811 , -1.07392 , 5.5702 , -0.0550048,0.341535,0.938258 -1.77267 , -0.956171 , 5.40891 , 0.224886,-0.391353,0.892339 -1.71141 , -0.883449 , 5.39245 , 0.359424,0.367186,0.857898 -1.6969 , -0.854914 , 5.54311 , -0.19824,0.293625,-0.935139 -1.60176 , -0.750279 , 5.39172 , 0.657976,0.249414,0.710535 -1.57927 , -0.713557 , 5.52165 , -0.768733,0.0207042,-0.639235 -1.52842 , -0.650473 , 5.53702 , 0.80604,-0.161802,0.569316 -1.49381 , -0.602085 , 5.62764 , -0.605309,0.315777,-0.730675 -1.36669 , -0.471593 , 5.27385 , -0.536233,-0.742423,0.401575 -1.28116 , -0.379334 , 5.08948 , -0.973945,-0.212516,0.0791732 -1.27172 , -0.354086 , 5.30129 , 0.759334,0.60366,-0.242912 -1.28458 , -0.344975 , 5.66972 , -0.463624,-0.00497228,0.886018 -1.22088 , -0.271635 , 5.60771 , 0.394764,-0.287085,-0.872779 -1.17466 , -0.213119 , 5.65221 , -0.296808,0.423961,0.855665 -1.09479 , -0.129383 , 5.4487 , 0.273174,-0.187459,-0.943523 -1.04286 , -0.0666542 , 5.43066 , -0.148349,-0.0479299,0.987773 -0.994874 , -0.00743701 , 5.44095 , 0.217117,0.36859,-0.903882 -0.946242 , 0.0526833 , 5.44976 , 0.499124,0.397182,-0.770144 -0.902129 , 0.110112 , 5.51686 , 0.175654,-0.0967144,-0.97969 -0.849841 , 0.171812 , 5.48331 , -0.527831,0.289979,-0.798315 -0.804399 , 0.231156 , 5.54793 , 0.278048,-0.3496,0.894689 -0.835395 , 0.291213 , 6.97931 , 0.107586,0.10968,0.988127 -0.768468 , 0.37145 , 6.97203 , -0.310323,-0.460197,-0.831816 -0.701854 , 0.450291 , 6.9432 , 0.143115,0.303458,0.942036 -0.636187 , 0.530486 , 6.9423 , 0.575223,0.461997,0.675038 -0.561446 , 0.566784 , 6.14117 , 0.986544,-0.148689,-0.0679958 -0.504987 , 0.635682 , 6.13734 , -0.817401,0.195854,-0.541753 -0.439938 , 0.767732 , 6.91932 , 0.512981,0.399661,0.759685 -0.375006 , 0.84631 , 6.90136 , -0.433544,-0.4359,-0.788689 -0.309031 , 0.925773 , 6.90163 , 0.170222,0.449332,0.876998 -0.110638 , 1.36876 , 9.89524 , 0.698833,-0.207247,0.684603 -0.00191596 , 1.51252 , 10.0632 , 0.0355327,-0.806567,0.590074 --0.0775694 , 1.5859 , 9.71397 , 0.590163,0.048158,-0.805847 --0.149012 , 1.64879 , 9.36428 , -0.493052,-0.652003,0.576014 -1.81572 , -1.4976 , -0.545761 , -0.0754493,0.352099,0.932917 -1.84816 , -1.53887 , -0.52354 , -0.0927821,0.337587,0.93671 -1.89033 , -1.59301 , -0.511253 , 0.0179193,-0.237315,-0.971268 -1.93872 , -1.65361 , -0.502391 , -0.0625301,0.213117,0.975024 -1.98134 , -1.70807 , -0.485992 , -0.077623,0.213193,0.973922 -2.02896 , -1.76967 , -0.472746 , -0.0447882,0.204423,0.977858 -2.07739 , -1.83102 , -0.457337 , -0.0498383,0.201597,0.9782 -2.13174 , -1.89959 , -0.444279 , -0.0911064,0.210316,0.973379 -2.17524 , -1.9546 , -0.419363 , 0.0856881,-0.181807,-0.979594 -2.23412 , -2.03053 , -0.40605 , -0.0606609,0.211345,0.975527 -2.28844 , -2.09961 , -0.385375 , -0.0742091,0.203704,0.976216 -2.35465 , -2.18331 , -0.370277 , -0.0627086,0.180733,0.981531 -2.41438 , -2.25971 , -0.348058 , -0.106949,0.239787,0.964917 -2.4756 , -2.33688 , -0.322676 , 0.104705,-0.221482,-0.969527 -2.54165 , -2.42067 , -0.298113 , -0.0553331,0.20179,0.977865 -2.61923 , -2.51963 , -0.277178 , -0.0487981,0.198118,0.978963 -2.69128 , -2.61149 , -0.248905 , -0.0474006,0.192259,0.980199 -2.78675 , -2.73312 , -0.229742 , -0.0667857,0.187597,0.979973 -2.87066 , -2.84012 , -0.199429 , -0.039682,0.187203,0.98152 -2.96691 , -2.96201 , -0.170485 , -0.0222649,0.186983,0.982111 -3.07994 , -3.10757 , -0.144403 , -0.0561325,0.207784,0.976563 -3.18284 , -3.23679 , -0.107347 , -0.0449669,0.200231,0.978716 -3.29651 , -3.38219 , -0.0695378 , -0.0506609,0.195661,0.979362 -3.4287 , -3.55113 , -0.0319166 , -0.0689631,0.195414,0.978293 -3.56039 , -3.71853 , 0.0125146 , -0.0683115,0.200702,0.977268 -3.70555 , -3.90215 , 0.0606889 , -0.0504784,0.191621,0.98017 -3.87345 , -4.11741 , 0.110197 , -0.0585401,0.200621,0.977919 -4.04167 , -4.33091 , 0.168582 , -0.0548069,0.197167,0.978837 -4.25218 , -4.6 , 0.227359 , -0.0604372,0.192509,0.979432 -4.46357 , -4.86797 , 0.297664 , -0.0620124,0.193643,0.97911 -4.70476 , -5.17448 , 0.374786 , -0.0540376,0.196608,0.978992 -4.97631 , -5.52015 , 0.46157 , 0.0580777,-0.197689,-0.978543 -5.28359 , -5.91225 , 0.559756 , -0.0557856,0.202125,0.97777 -5.62758 , -6.34933 , 0.672379 , -0.0529809,0.204533,0.977425 -6.0317 , -6.86405 , 0.801772 , -0.06429,0.201894,0.977295 -6.46696 , -7.41653 , 0.953526 , -0.0852454,0.200554,0.975967 -7.02876 , -8.13258 , 1.13161 , -0.0937123,0.222965,0.970312 -7.32596 , -8.50456 , 1.32996 , -0.110066,0.335162,0.93571 -7.99551 , -9.35499 , 1.5716 , 0.0520747,0.268069,0.961991 -9.39149 , -11.1381 , 1.92372 , -0.0343644,0.168086,0.985173 -11.1026 , -13.3213 , 2.39584 , 0.0423772,-0.192379,-0.980405 -7.58678 , -8.73118 , 3.16381 , -0.935325,-0.343911,0.0830241 -7.5687 , -8.69576 , 3.36364 , -0.935325,-0.343911,0.0830242 -7.54916 , -8.65802 , 3.56283 , -0.935325,-0.343911,0.0830242 -28.4325 , -34.9385 , 15.204 , -0.541792,0.837401,-0.0722582 -28.4824 , -34.9492 , 16.084 , -0.541792,0.837401,-0.0722581 -29.0563 , -35.6193 , 17.2736 , -0.37314,0.925824,0.0601376 -24.1617 , -29.3264 , 16.7289 , -0.479532,0.854039,0.201658 -24.228 , -29.363 , 17.5392 , 0.34279,-0.92723,-0.150795 -25.583 , -30.8008 , 22.7101 , -0.0638094,0.996826,-0.0476161 -25.1385 , -30.1966 , 23.1969 , 0.151005,-0.955853,-0.252078 -24.5387 , -29.4015 , 23.522 , -0.279562,0.952099,0.123908 -28.7131 , -34.4963 , 28.4608 , 0.225165,0.874217,0.430169 -28.4974 , -34.1665 , 29.2967 , 0.225165,0.874217,0.430169 -3.38003 , -3.17312 , 5.16345 , -0.658441,-0.183653,0.729881 -3.76526 , -3.6277 , 5.87444 , -0.685552,0.532072,-0.496908 -3.36833 , -3.14119 , 5.43013 , 0.812982,-0.570558,0.11629 -3.37747 , -3.14327 , 5.59317 , -0.721016,0.642,-0.260714 -3.59124 , -3.38897 , 6.09804 , 0.639768,0.527259,-0.559191 -3.53068 , -3.30721 , 6.16655 , -0.496397,-0.758042,0.423039 -3.53294 , -3.29916 , 6.34488 , -0.496397,-0.758042,0.423039 -3.19715 , -2.89063 , 5.91687 , -0.204012,-0.0450503,-0.977931 -3.19666 , -2.87949 , 6.08145 , 0.615296,0.19944,0.76265 -3.08334 , -2.73683 , 6.03596 , -0.521536,-0.73813,-0.427977 -2.98783 , -2.61507 , 6.01738 , 0.520113,0.525476,0.673319 -2.91342 , -2.51727 , 6.03518 , 0.711608,-0.479544,0.513471 -2.97191 , -2.57369 , 6.33475 , 0.660417,-0.693865,0.287056 -2.89418 , -2.47337 , 6.3506 , 0.0281758,-0.426438,0.904078 -2.89008 , -2.45615 , 6.53009 , 0.581193,-0.750941,0.313533 -2.7728 , -2.30931 , 6.44933 , -0.132529,0.0208551,-0.99096 -2.82669 , -2.3589 , 6.78135 , -0.304137,-0.456397,0.836183 -2.7228 , -2.2282 , 6.73 , 0.898037,-0.150477,-0.413383 -2.49613 , -1.95988 , 6.34415 , -0.425102,-0.240182,-0.872698 -2.45662 , -1.90295 , 6.43967 , -0.593352,0.158797,-0.789124 -2.23399 , -1.64025 , 6.01129 , 0.601017,-0.205651,0.772325 -2.191 , -1.58015 , 6.0825 , 0.143988,-0.177471,0.973536 -1.98724 , -1.34263 , 5.65659 , 0.0350381,0.613466,0.788943 -1.85988 , -1.19207 , 5.4398 , -0.286107,0.340564,0.895633 -1.81122 , -1.12748 , 5.46507 , -0.286107,0.340564,0.895633 -1.74338 , -1.04247 , 5.42396 , 0.097903,-0.0457453,0.994144 -1.70221 , -0.986252 , 5.47357 , -0.279023,0.54019,-0.793941 -1.64827 , -0.916813 , 5.47535 , 0.107272,-0.260431,0.959515 -1.58981 , -0.842128 , 5.45649 , 0.714567,0.123474,0.688585 -1.55072 , -0.787377 , 5.51162 , 0.760081,0.258523,0.59619 -1.49871 , -0.720626 , 5.51796 , 0.725286,-0.0619905,0.685651 -1.44934 , -0.656007 , 5.53238 , -0.661195,0.252593,-0.706412 -1.52491 , -0.714597 , 6.17126 , -0.929542,-0.294869,-0.221366 -1.37226 , -0.54787 , 5.67284 , 0.314356,-0.0743583,0.946388 -1.32477 , -0.484711 , 5.70273 , 0.28763,0.334157,0.897557 -1.39775 , -0.533227 , 6.46311 , -0.705512,0.34738,0.617722 -1.20211 , -0.333189 , 5.58238 , 0.467278,-0.143182,-0.872439 -1.15497 , -0.271084 , 5.60761 , -0.490951,0.280485,0.8248 -1.08888 , -0.192121 , 5.4837 , -0.164741,-0.162258,0.972899 -1.03504 , -0.125545 , 5.44646 , -0.0914413,0.114181,0.989243 -0.987644 , -0.0641739 , 5.44757 , 0.0129277,0.107809,0.994088 -0.939617 , -0.00194391 , 5.44701 , -0.0470526,-0.647609,0.760519 -0.898412 , 0.0558916 , 5.52462 , -0.268217,-0.448744,0.85246 -0.847499 , 0.119477 , 5.49166 , 0.165444,-0.460025,0.872356 -0.806493 , 0.178825 , 5.58694 , 0.261271,-0.512386,0.818045 -0.757882 , 0.241158 , 5.59123 , -0.184643,0.520787,-0.83348 -0.773685 , 0.307043 , 7.02243 , 0.352414,0.0315855,0.935311 -0.710784 , 0.390189 , 7.05427 , 0.682831,0.43679,0.585625 -0.644185 , 0.470089 , 6.9444 , -0.0616281,0.260066,0.963622 -0.581968 , 0.55628 , 7.04242 , 0.735807,0.449538,0.506462 -0.515577 , 0.587428 , 6.14029 , -0.836538,0.44633,-0.317795 -0.460058 , 0.664038 , 6.22544 , -0.861481,0.502858,0.0706021 -0.390715 , 0.798099 , 6.94611 , 0.673498,0.495082,0.548903 -0.328227 , 0.876987 , 6.91737 , 0.305597,0.667541,0.67897 -0.147666 , 1.28737 , 9.82572 , -0.411465,0.900316,-0.141871 -0.0458129 , 1.42575 , 9.94558 , 0.757839,-0.303088,0.577769 --0.048301 , 1.54554 , 9.90401 , -0.311874,-0.876333,-0.367118 --0.179588 , 1.74149 , 10.3626 , -0.95387,-0.167776,-0.248966 --0.199628 , 1.70887 , 9.38066 , -0.493053,-0.652002,0.576014 -1.75898 , -1.51322 , -0.557149 , -0.104203,0.349674,0.931058 -1.78606 , -1.54792 , -0.529924 , -0.0975346,0.337934,0.936102 -1.82169 , -1.5963 , -0.512849 , -0.104997,0.23869,0.965403 -1.86776 , -1.65863 , -0.505001 , -0.0404375,0.158401,0.986546 -1.90828 , -1.71385 , -0.489717 , -0.0664396,0.186468,0.980212 -1.94941 , -1.76982 , -0.472266 , -0.0691385,0.2052,0.976275 -1.99576 , -1.83198 , -0.458165 , 0.0536595,-0.206309,-0.977014 -2.04781 , -1.90233 , -0.446316 , -0.0502261,0.194069,0.979701 -2.08923 , -1.95814 , -0.42271 , -0.0880692,0.201908,0.975437 -2.14579 , -2.03586 , -0.410606 , -0.0765711,0.202234,0.976339 -2.19878 , -2.10696 , -0.391115 , 0.0906666,-0.224143,-0.97033 -2.25061 , -2.17726 , -0.369216 , -0.0516307,0.184666,0.981444 -2.31916 , -2.27049 , -0.356726 , -0.0600963,0.226507,0.972154 -2.37229 , -2.34095 , -0.328941 , -0.0995786,0.250873,0.962885 -2.42981 , -2.42006 , -0.302162 , -0.075563,0.210418,0.974687 -2.50513 , -2.52096 , -0.283118 , -0.06697,0.184285,0.980589 -2.57395 , -2.61454 , -0.256855 , -0.0611285,0.196848,0.978527 -2.65424 , -2.7231 , -0.233346 , -0.0557186,0.172571,0.98342 -2.7407 , -2.84025 , -0.208463 , -0.083849,0.201119,0.975972 -2.8216 , -2.95023 , -0.175851 , -0.035535,0.209167,0.977234 -2.92553 , -3.09043 , -0.150012 , -0.0390958,0.196685,0.979687 -3.01814 , -3.21508 , -0.113318 , -0.0543068,0.195572,0.979185 -3.13318 , -3.37143 , -0.0811534 , -0.0417831,0.204151,0.978047 -3.25417 , -3.53576 , -0.0447925 , -0.045124,0.192638,0.980232 -3.38109 , -3.70794 , -0.00374928 , -0.0776386,0.198295,0.977063 -3.50823 , -3.87972 , 0.0445195 , -0.0707301,0.200152,0.977209 -3.6582 , -4.0834 , 0.0929549 , -0.0567698,0.195294,0.9791 -3.81488 , -4.29462 , 0.148528 , -0.0670975,0.209714,0.975458 -3.98855 , -4.52907 , 0.20866 , -0.0549144,0.193862,0.979491 -4.19103 , -4.8035 , 0.272668 , 0.0645923,-0.195628,-0.978549 -4.40535 , -5.09354 , 0.34643 , -0.0617267,0.197647,0.978328 -4.64916 , -5.42287 , 0.428178 , -0.0582057,0.196165,0.978842 -4.92762 , -5.79971 , 0.519847 , -0.0643095,0.20152,0.977371 -5.22283 , -6.19973 , 0.626221 , -0.0591267,0.20701,0.97655 -5.58275 , -6.68658 , 0.745926 , -0.056803,0.200537,0.978038 -5.99468 , -7.24428 , 0.885195 , -0.0698005,0.200418,0.977221 -6.4655 , -7.88088 , 1.04883 , -0.0819443,0.19626,0.977122 -6.98212 , -8.57852 , 1.24139 , -0.17735,0.288588,0.940885 -7.27882 , -8.97431 , 1.45104 , -0.303032,0.322008,0.89693 -7.42553 , -9.16501 , 1.66457 , -0.19923,0.252022,0.946991 -7.42938 , -9.15815 , 1.8695 , -0.19923,0.252022,0.946991 -24.3953 , -32.123 , 7.4553 , -0.538988,0.247573,0.805108 -7.21991 , -8.7985 , 3.24697 , -0.935325,-0.343911,0.0830241 -7.23061 , -8.80125 , 3.45427 , -0.935325,-0.343911,0.0830241 -7.81889 , -9.58426 , 3.88843 , -0.935325,-0.343911,0.0830242 -7.79936 , -9.54611 , 4.1048 , -0.935325,-0.343911,0.0830242 -7.77835 , -9.50558 , 4.32073 , -0.935325,-0.343911,0.0830241 -7.75415 , -9.46127 , 4.53588 , -0.935325,-0.343911,0.0830241 -24.3501 , -31.7482 , 13.2878 , 0.194091,-0.684001,0.703186 -22.8807 , -29.62 , 15.4143 , 0.240088,-0.8686,0.433466 -23.2064 , -30.0164 , 16.3753 , 0.789995,-0.533771,-0.301657 -24.1778 , -31.2276 , 18.628 , -0.297841,0.933578,0.199306 -23.7167 , -30.4391 , 21.5546 , 0.34634,-0.937738,0.0263627 -23.8115 , -30.4716 , 23.3609 , -0.408377,0.82833,0.383533 -25.0089 , -31.9508 , 26.3858 , 0.0129044,0.815178,0.579067 -3.62536 , -3.73975 , 5.63822 , -0.240146,0.957525,0.159611 -3.63755 , -3.74808 , 5.81533 , 0.117766,0.967016,0.225859 -3.64333 , -3.74646 , 5.98716 , -0.937868,0.0441498,-0.344172 -3.55998 , -3.62983 , 6.01916 , -0.937868,0.0441496,-0.344171 -3.38212 , -3.39305 , 5.88922 , -0.580033,-0.703019,0.411493 -3.22059 , -3.17755 , 5.77249 , -0.915109,0.255472,-0.311946 -3.23501 , -3.18841 , 5.96032 , 0.977095,0.0404128,0.208932 -3.21851 , -3.15806 , 6.09707 , -0.980251,-0.149119,0.129893 -3.15945 , -3.07417 , 6.15739 , 0.831998,-0.129393,-0.539478 -2.92932 , -2.77325 , 5.8739 , 0.0542002,-0.560618,0.826299 -2.87338 , -2.69399 , 5.92574 , 0.00343166,-0.485352,0.874312 -2.9364 , -2.76401 , 6.23097 , 0.705204,0.642141,-0.300571 -2.7815 , -2.56105 , 6.07184 , -0.140277,0.598213,-0.788964 -2.76032 , -2.5239 , 6.20032 , -0.00091079,-0.952225,0.305396 -2.74712 , -2.49723 , 6.35367 , -0.265383,-0.722217,0.638729 -2.69981 , -2.42932 , 6.43204 , 0.00784399,-0.489689,0.871862 -2.60941 , -2.30657 , 6.39902 , 0.313551,0.359019,-0.879085 -2.5587 , -2.23303 , 6.46498 , 0.160836,0.384294,0.909093 -2.45025 , -2.08951 , 6.37371 , -0.14954,-0.140955,0.978657 -2.37727 , -1.99042 , 6.37406 , 0.595552,-0.164095,0.786378 -2.23461 , -1.80506 , 6.15988 , 0.114821,0.805277,0.581674 -2.11838 , -1.65487 , 6.0104 , -0.417776,-0.158142,-0.894681 -2.10445 , -1.62764 , 6.17066 , -0.417776,-0.158142,-0.894681 -1.85746 , -1.32083 , 5.561 , 0.15154,-0.689071,-0.708673 -1.74821 , -1.18148 , 5.3777 , -0.150852,0.699368,0.698662 -1.66165 , -1.06897 , 5.25425 , -0.279337,-0.313549,0.907556 -1.63379 , -1.02531 , 5.34027 , -0.126481,-0.676678,0.725334 -1.61378 , -0.990645 , 5.46324 , 0.15506,-0.561937,0.812517 -1.55743 , -0.915263 , 5.44521 , -0.110854,0.578458,-0.808145 -1.55777 , -0.903221 , 5.67091 , -0.563021,0.232,-0.793211 -1.49621 , -0.821536 , 5.63143 , -0.644251,-0.332616,-0.6887 -1.43713 , -0.743132 , 5.59935 , -0.711939,0.0136664,-0.702109 -1.40958 , -0.697861 , 5.71885 , -0.889919,-0.0899459,-0.447163 -1.64128 , -0.932295 , 7.26736 , -0.232171,0.943448,0.236647 -1.46544 , -0.725514 , 6.64551 , -0.81679,0.098292,0.5685 -1.35829 , -0.593737 , 6.35727 , 0.654669,0.595698,0.465352 -1.2982 , -0.51228 , 6.33872 , -0.654668,-0.595698,-0.465353 -1.21943 , -0.412048 , 6.1806 , -0.891578,-0.201274,0.405682 -1.07811 , -0.254792 , 5.50816 , 0.428744,-0.583342,-0.689848 -1.02507 , -0.185023 , 5.46193 , 0.126647,0.197697,0.972048 -0.989632 , -0.130175 , 5.56244 , 0.410181,0.254737,0.875706 -0.928764 , -0.0544819 , 5.42394 , 0.0145904,0.268951,0.963043 -0.879345 , 0.0112401 , 5.3828 , 0.00966101,-0.238016,0.971213 -0.842227 , 0.0668018 , 5.4898 , -0.402839,-0.0660075,0.912888 -0.921047 , 0.0600103 , 7.37053 , -0.501323,0.483558,0.717529 -0.843008 , 0.155018 , 7.14755 , -0.168769,-0.809148,-0.562847 -0.772221 , 0.243435 , 6.96227 , 0.227931,-0.0902175,0.969489 -0.712977 , 0.32683 , 7.01488 , -0.336249,-0.174856,-0.925398 -0.655059 , 0.414493 , 7.15554 , -0.780991,-0.568211,-0.259209 -0.588238 , 0.493447 , 6.9547 , -0.779808,0.500088,-0.376578 -0.525388 , 0.546158 , 6.30267 , 0.520976,-0.503731,-0.689086 -0.471398 , 0.610668 , 6.13873 , 0.720203,-0.0689516,0.690329 -0.40501 , 0.74706 , 6.9806 , 0.711183,0.224245,0.666283 -0.343009 , 0.834144 , 7.01223 , 0.567186,0.578114,0.586587 -0.285265 , 0.906703 , 6.89276 , 0.0121016,0.60613,0.795273 -0.0837275 , 1.34122 , 9.84682 , -0.432223,-0.887559,-0.159444 --0.0204007 , 1.49617 , 10.0641 , 0.0722977,-0.759496,0.646482 --0.0914804 , 1.57479 , 9.71472 , 0.590162,0.0481579,-0.805847 --0.151888 , 1.63618 , 9.31522 , -0.493052,-0.652003,0.576014 -1.72198 , -1.55641 , -0.535967 , -0.121762,0.296371,0.947279 -1.75648 , -1.60572 , -0.519691 , -0.106567,0.264549,0.958466 -1.79601 , -1.66231 , -0.507151 , 0.0819165,-0.167961,-0.982384 -1.8354 , -1.71849 , -0.492763 , -0.0575322,0.169536,0.983843 -1.87957 , -1.7828 , -0.481525 , 0.097218,-0.181245,-0.978621 -1.91846 , -1.83912 , -0.463341 , -0.0995696,0.207629,0.973127 -1.95891 , -1.89637 , -0.442771 , -0.0816544,0.17305,0.981522 -2.01262 , -1.97527 , -0.434723 , -0.071999,0.17737,0.981507 -2.06274 , -2.04749 , -0.418998 , -0.0875994,0.193953,0.977092 -2.10758 , -2.11172 , -0.396422 , -0.0728358,0.197113,0.977672 -2.15807 , -2.18405 , -0.375709 , -0.0920941,0.205474,0.97432 -2.21322 , -2.26412 , -0.356394 , -0.0865542,0.184411,0.979031 -2.26817 , -2.3436 , -0.334453 , -0.0742973,0.232465,0.969763 -2.3246 , -2.42381 , -0.309154 , 0.0968152,-0.211503,-0.97257 -2.39068 , -2.51891 , -0.288407 , -0.0840669,0.169068,0.982013 -2.46202 , -2.62259 , -0.267282 , -0.0871229,0.191144,0.977688 -2.52807 , -2.71822 , -0.239015 , -0.0923746,0.165147,0.981933 -2.6111 , -2.83814 , -0.216335 , 0.0665725,-0.171984,-0.982848 -2.68903 , -2.94895 , -0.186223 , -0.0887209,0.201162,0.975532 -2.77094 , -3.06881 , -0.154489 , -0.074685,0.17356,0.981987 -2.87062 , -3.21262 , -0.125788 , -0.0574003,0.177819,0.982388 -2.96966 , -3.35618 , -0.0915387 , -0.0679374,0.190338,0.979365 -3.07495 , -3.50692 , -0.0540691 , -0.0578338,0.182931,0.981423 -3.20205 , -3.69085 , -0.0187884 , -0.0602213,0.177496,0.982277 -3.31876 , -3.85929 , 0.0280516 , -0.0909559,0.199591,0.975649 -3.45194 , -4.05048 , 0.0761157 , -0.0756339,0.189798,0.978906 -3.60102 , -4.26605 , 0.126966 , -0.0765849,0.190991,0.9786 -3.75657 , -4.49003 , 0.185541 , -0.0752448,0.193349,0.97824 -3.94543 , -4.76294 , 0.245623 , -0.0699603,0.185102,0.980226 -4.13326 , -5.03437 , 0.316702 , -0.0776854,0.198258,0.977067 -4.35044 , -5.34633 , 0.394601 , -0.0756573,0.188398,0.979174 -4.60557 , -5.71552 , 0.480129 , -0.0738232,0.189328,0.979135 -4.8785 , -6.10831 , 0.579509 , -0.0841276,0.198177,0.976549 -5.17249 , -6.53268 , 0.693658 , -0.0801556,0.190675,0.978375 -5.55667 , -7.08687 , 0.821741 , -0.0754488,0.187618,0.97934 -5.98565 , -7.70519 , 0.972789 , -0.0798623,0.190661,0.978402 -6.48052 , -8.42033 , 1.15133 , -0.131669,0.186944,0.973507 -6.89553 , -9.01563 , 1.35616 , 0.403297,-0.233821,-0.884692 -7.3879 , -9.72334 , 1.59287 , -0.228436,0.0835329,0.969969 -8.61889 , -11.503 , 1.94208 , -0.0921197,0.165504,0.981897 -22.0296 , -30.8465 , 6.76977 , 0.636903,-0.215663,-0.740165 -22.3773 , -31.3171 , 7.54623 , -0.538988,0.247573,0.805108 -23.93 , -33.528 , 8.74424 , 0.999847,-0.0168646,0.00459984 -27.6054 , -38.7558 , 11.67 , 0.631137,-0.745164,0.215399 -22.8561 , -31.7476 , 13.4361 , 0.194091,-0.684001,0.703186 -22.2546 , -30.8189 , 14.5602 , 0.194091,-0.684001,0.703186 -22.3298 , -30.6804 , 20.0156 , 0.816073,-0.535619,0.217109 -22.3988 , -30.7398 , 20.896 , -0.609282,0.792278,0.0327224 -22.4618 , -30.7907 , 21.7901 , 0.731405,-0.636897,-0.24374 -23.7315 , -32.4641 , 25.7439 , 0.579754,-0.71738,-0.38633 -3.54691 , -3.95579 , 5.21214 , 0.35965,-0.234465,0.903149 -3.40782 , -3.75512 , 5.16221 , -0.315982,0.652962,-0.688328 -3.36933 , -3.69403 , 5.24864 , 0.257199,-0.739698,0.621848 -3.36332 , -3.68067 , 5.38693 , 0.41699,-0.697869,0.582322 -3.36098 , -3.66984 , 5.53263 , -0.132238,0.984808,-0.112546 -3.48324 , -3.8318 , 5.88596 , 0.0259791,0.996349,0.0813249 -3.46997 , -3.80597 , 6.03014 , -0.126739,0.477298,-0.869554 -3.15967 , -3.37058 , 5.66076 , -0.516062,0.822966,-0.237502 -3.135 , -3.3292 , 5.77508 , -0.30535,-0.65105,0.694907 -3.13795 , -3.32491 , 5.94116 , -0.0263897,-0.920888,0.388933 -3.13336 , -3.31164 , 6.10105 , -0.158638,-0.961414,0.22476 -3.11923 , -3.28424 , 6.24666 , -0.482558,-0.0268016,0.875454 -2.83992 , -2.89541 , 5.85197 , -0.499697,0.708413,-0.498452 -2.78238 , -2.80884 , 5.89659 , -0.443365,0.573672,-0.688714 -2.79268 , -2.81644 , 6.09016 , -0.09735,0.813838,-0.57288 -2.67389 , -2.6468 , 5.99592 , 0.0795556,-0.549701,0.831565 -2.64321 , -2.5967 , 6.0995 , -0.0260562,-0.642714,0.765663 -2.6013 , -2.53218 , 6.17811 , -0.117902,-0.886653,0.447153 -2.49224 , -2.37664 , 6.0883 , 0.0961568,-0.457605,0.883941 -2.45305 , -2.31613 , 6.17111 , 0.180584,0.764724,-0.618536 -2.44317 , -2.29484 , 6.33794 , 0.0587973,0.766327,-0.639755 -2.3798 , -2.20118 , 6.35915 , -0.221692,0.330925,-0.917247 -2.34331 , -2.14357 , 6.45648 , -0.579577,-0.00506377,-0.814901 -2.26772 , -2.03397 , 6.43854 , -0.358267,0.098612,-0.928397 -2.22918 , -1.97331 , 6.53298 , -0.128786,-0.1552,-0.979452 -2.12991 , -1.8325 , 6.42944 , 0.202775,0.747201,0.632909 -1.86241 , -1.47516 , 5.73489 , 0.173678,0.693371,0.699337 -1.8039 , -1.3897 , 5.72737 , 0.173678,0.693371,0.699337 -1.70982 , -1.25919 , 5.58039 , 0.0964899,0.774676,0.624953 -1.59538 , -1.10271 , 5.3367 , 0.388663,0.749328,0.536143 -1.55299 , -1.03972 , 5.3668 , 0.622276,-0.169795,0.764161 -1.49745 , -0.961163 , 5.33968 , 0.264325,-0.502795,0.823 -1.49912 , -0.952714 , 5.56486 , -0.453606,0.691808,-0.561821 -1.52884 , -0.978326 , 5.9431 , -0.574453,0.807356,-0.134835 -1.43569 , -0.850907 , 5.74179 , 0.709077,0.117784,0.695224 -1.35858 , -0.745864 , 5.60378 , 0.924425,-0.0844433,0.371898 -1.48603 , -0.886161 , 6.59986 , 0.67085,0.389671,-0.630965 -1.44122 , -0.817682 , 6.68395 , -0.763305,-0.22374,0.606058 -1.34939 , -0.693232 , 6.47498 , 0.816258,-0.225364,-0.531915 -1.27586 , -0.591654 , 6.36002 , -0.654668,-0.595698,-0.465352 -1.11382 , -0.391371 , 5.56623 , 0.37861,-0.399622,0.834839 -1.07126 , -0.327272 , 5.59134 , -0.322598,0.425519,0.845496 -1.00813 , -0.241669 , 5.44725 , -0.236915,0.522939,0.818783 -0.963498 , -0.176571 , 5.44937 , -0.329396,-0.155455,0.931307 -0.92183 , -0.114724 , 5.47989 , -0.013534,0.966581,0.256006 -0.873216 , -0.0458312 , 5.42967 , -0.0157308,0.139735,0.990064 -0.833834 , 0.0137542 , 5.48749 , 0.291767,-0.289679,0.911569 -0.784879 , 0.0821773 , 5.41432 , 0.795147,-0.24874,0.553055 -0.842208 , 0.0820247 , 7.25577 , 0.421583,-0.681747,-0.597904 -0.777761 , 0.172955 , 7.1814 , 0.373728,0.717321,0.58803 -0.712548 , 0.262759 , 7.04494 , 0.725589,-0.016472,0.687931 -0.651787 , 0.34869 , 7.00662 , -0.291711,-0.523127,-0.800776 -0.534709 , 0.526045 , 7.1442 , -0.966369,-0.183591,-0.18007 -0.478228 , 0.569211 , 6.29159 , -0.308128,0.22681,0.923913 -0.426965 , 0.642966 , 6.24644 , 0.749893,-0.66094,0.0286246 -0.357403 , 0.778137 , 6.9874 , 0.197046,0.491504,0.84829 -0.300145 , 0.858892 , 6.9283 , 0.237995,-0.786789,-0.569492 -0.105777 , 1.28052 , 9.97576 , -0.534569,-0.804351,-0.259336 -0.0170144 , 1.41088 , 9.9763 , 0.81431,0.0235692,0.579952 --0.0715855 , 1.53757 , 9.94417 , -0.693487,-0.702979,-0.157785 --0.22037 , 1.79047 , 10.7274 , -0.959189,-0.233013,0.160193 --0.20348 , 1.70466 , 9.37094 , -0.493052,-0.652003,0.576014 -1.66077 , -1.56146 , -0.542265 , -0.117671,0.312706,0.942533 -1.69314 , -1.61147 , -0.526812 , -0.121457,0.227855,0.96609 -1.72613 , -1.66229 , -0.509483 , -0.100924,0.17581,0.979237 -1.76859 , -1.72686 , -0.501503 , -0.0906273,0.198735,0.975854 -1.80552 , -1.78433 , -0.486184 , 0.0637404,-0.189144,-0.979879 -1.84817 , -1.85012 , -0.473699 , -0.0906909,0.199354,0.975722 -1.88555 , -1.9079 , -0.454268 , -0.132846,0.197473,0.971265 -1.92864 , -1.97395 , -0.437476 , -0.0930975,0.153398,0.983769 -1.97158 , -2.03951 , -0.418545 , -0.101557,0.172766,0.979713 -2.01921 , -2.11298 , -0.401693 , -0.0814546,0.213207,0.973606 -2.07176 , -2.19336 , -0.386924 , -0.0889037,0.206914,0.974311 -2.11952 , -2.26782 , -0.364595 , -0.0872365,0.186225,0.978627 -2.17216 , -2.3491 , -0.34396 , -0.0843166,0.195841,0.977004 -2.22533 , -2.43092 , -0.320186 , -0.121394,0.184543,0.975299 -2.28912 , -2.52786 , -0.30094 , -0.0907914,0.165498,0.982022 -2.35219 , -2.62594 , -0.277894 , -0.0862622,0.181078,0.979678 -2.41597 , -2.72346 , -0.251323 , -0.0910577,0.176217,0.980131 -2.49002 , -2.83674 , -0.227623 , -0.086839,0.160639,0.983186 -2.56928 , -2.95838 , -0.202573 , -0.0903169,0.198058,0.976021 -2.63724 , -3.06453 , -0.166959 , -0.0995093,0.17315,0.979856 -2.73254 , -3.21097 , -0.14097 , -0.0807517,0.17046,0.98205 -2.82246 , -3.34913 , -0.10677 , -0.0934764,0.181875,0.978869 -2.91746 , -3.49527 , -0.0695641 , -0.0812355,0.178317,0.980614 -3.02392 , -3.65865 , -0.0308 , -0.0596689,0.165559,0.984393 -3.15588 , -3.8628 , 0.00396344 , -0.065909,0.184541,0.980612 -3.27221 , -4.04132 , 0.0524346 , -0.0863515,0.195698,0.976855 -3.40428 , -4.24535 , 0.103111 , -0.0785696,0.182412,0.980078 -3.55317 , -4.47385 , 0.157278 , -0.0882023,0.190471,0.977722 -3.70656 , -4.71024 , 0.219318 , 0.0831055,-0.176859,-0.980721 -3.89298 , -4.99634 , 0.28384 , 0.0814129,-0.180916,-0.980123 -4.08906 , -5.2986 , 0.357974 , -0.0818871,0.182522,0.979786 -4.31223 , -5.64164 , 0.440151 , 0.0811984,-0.180244,-0.980265 -4.56741 , -6.03464 , 0.532501 , -0.0830001,0.184481,0.979325 -4.83838 , -6.45062 , 0.639338 , -0.0930463,0.184662,0.978388 -5.16878 , -6.95834 , 0.760013 , -0.0805577,0.183486,0.979716 -5.54085 , -7.53215 , 0.900572 , -0.0798473,0.187531,0.979008 -5.98242 , -8.21177 , 1.06506 , -0.0817803,0.184649,0.979396 -6.52639 , -9.04881 , 1.26174 , -0.173739,0.187483,0.966781 -6.92776 , -9.66349 , 1.4835 , -0.314347,0.134368,0.939751 -7.803 , -11.0119 , 1.77913 , -0.10466,0.156932,0.982048 -8.89285 , -12.689 , 2.16005 , -0.0665659,0.174887,0.982336 -23.2613 , -34.7604 , 8.51926 , -0.974189,-0.211927,0.0777333 -23.5258 , -35.1392 , 9.36531 , -0.974189,-0.211927,0.0777333 -25.5943 , -38.2601 , 11.7831 , -0.636767,0.20862,0.742297 -26.0472 , -38.9244 , 12.8357 , 0.633363,-0.718965,0.286254 -21.1498 , -31.3009 , 13.4087 , 0.194091,-0.684001,0.703186 -21.7696 , -32.2219 , 14.5277 , -0.958156,0.285393,-0.0220787 -21.2756 , -31.4387 , 14.9523 , 0.194091,-0.684001,0.703186 -21.3885 , -31.4382 , 19.6856 , 0.819085,-0.57028,0.062293 -21.9103 , -32.2 , 20.9889 , -0.801224,0.588035,-0.110707 -22.0318 , -32.2879 , 23.7158 , 0.75813,-0.584167,-0.289807 -3.3313 , -3.94252 , 5.18568 , 0.0501232,-0.157466,0.986252 -3.27589 , -3.85487 , 5.2482 , -0.213403,0.452712,-0.865743 -3.21029 , -3.74524 , 5.43996 , 0.426898,-0.792937,0.434752 -3.17798 , -3.6917 , 5.53791 , -0.387828,0.678961,-0.623379 -3.10422 , -3.57632 , 5.56526 , -0.438165,0.278383,-0.854701 -3.05079 , -3.49086 , 5.62462 , 0.167404,-0.304255,0.937766 -3.00779 , -3.42181 , 5.70347 , 0.235482,-0.565692,0.790279 -2.9189 , -3.28425 , 5.69302 , 0.260616,0.784697,-0.562433 -2.89464 , -3.24242 , 5.8049 , -0.512943,-0.684655,0.517819 -2.88703 , -3.22531 , 5.95435 , 0.691405,0.452384,-0.563301 -2.72631 , -2.98159 , 5.78207 , -0.676674,0.71416,-0.17913 -2.67883 , -2.90575 , 5.84272 , 0.56634,-0.758846,0.321577 -2.68255 , -2.9056 , 6.02017 , -0.563911,0.710367,-0.421168 -2.60659 , -2.78594 , 6.01482 , 0.328471,-0.189754,0.925257 -2.52331 , -2.65904 , 5.99003 , -0.314312,0.721514,-0.616948 -2.49072 , -2.60404 , 6.08455 , 0.662682,0.00535004,0.748882 -2.48768 , -2.59291 , 6.26128 , 0.282447,0.167602,0.944528 -2.3616 , -2.40352 , 6.11167 , 0.542398,-0.443462,0.713544 -2.35639 , -2.389 , 6.28696 , -0.420002,0.57588,-0.701399 -2.29007 , -2.28544 , 6.29152 , -0.420233,0.69143,-0.587646 -2.28637 , -2.27293 , 6.48423 , 0.227067,-0.611543,0.757929 -2.22192 , -2.17188 , 6.49413 , 0.258903,-0.39341,0.882155 -2.16293 , -2.07954 , 6.51925 , -0.063235,-0.0438231,0.997036 -2.08359 , -1.95746 , 6.47086 , -0.0407229,0.235065,0.971126 -1.9447 , -1.75259 , 6.20322 , -0.117793,0.833139,0.540374 -1.76236 , -1.48673 , 5.74701 , 0.173678,0.693371,0.699337 -1.70493 , -1.39728 , 5.72962 , -0.224738,-0.733397,-0.641577 -1.6043 , -1.24879 , 5.53482 , -0.110729,-0.760276,-0.640093 -1.53812 , -1.14911 , 5.46513 , -0.539749,-0.3854,-0.748424 -1.48457 , -1.06555 , 5.43918 , 0.579936,0.474466,0.662236 -1.45939 , -1.02304 , 5.54314 , -0.315547,-0.500806,0.805993 -1.4244 , -0.967119 , 5.6088 , -0.0129915,-0.722881,0.69085 -1.39032 , -0.9118 , 5.68278 , 0.10441,-0.813167,0.572589 -1.50096 , -1.05056 , 6.55978 , 0.443026,0.614097,-0.653156 -1.4389 , -0.956136 , 6.53044 , -0.538586,-0.473871,0.696686 -1.4084 , -0.901299 , 6.6824 , 0.54243,0.329721,-0.772693 -1.32816 , -0.784182 , 6.533 , 0.726998,-0.0471375,-0.68502 -1.15365 , -0.544006 , 5.6785 , -0.417742,-0.884852,0.206223 -1.18088 , -0.564714 , 6.23451 , 0.521377,0.852123,0.0452953 -1.0812 , -0.426291 , 5.84027 , 0.219436,0.818278,0.531289 -1.00515 , -0.316388 , 5.56988 , -0.12404,0.427092,0.89566 -0.951739 , -0.237908 , 5.48414 , 0.339469,0.0536269,0.939087 -0.900403 , -0.161328 , 5.38665 , -0.269912,0.271191,0.923907 -0.870684 , -0.109466 , 5.53533 , 0.0988686,0.435556,0.894716 -0.822219 , -0.0375293 , 5.46449 , -0.479114,0.786573,-0.389555 -0.90361 , -0.0905398 , 7.42441 , -0.50211,0.528926,0.684196 -0.845687 , 0.00112874 , 7.47289 , -0.50211,0.528925,0.684196 -0.777535 , 0.100781 , 7.31959 , -0.474372,0.736497,0.482228 -0.705658 , 0.199429 , 6.9543 , -0.754313,0.508248,-0.415568 -0.6555 , 0.2853 , 7.1868 , -0.783305,-0.466445,-0.410928 -0.599122 , 0.377849 , 7.30725 , 0.773151,0.268607,0.574533 -0.538967 , 0.463536 , 7.10631 , -0.808397,-0.42533,-0.406926 -0.484046 , 0.521764 , 6.38394 , -0.291517,0.773879,0.562253 -0.43491 , 0.593341 , 6.25988 , 0.162932,-0.364894,-0.916682 -0.368137 , 0.726839 , 7.04172 , 0.135289,-0.00115124,0.990806 -0.306956 , 0.825942 , 7.1627 , 0.618132,0.777678,0.114581 -0.25957 , 0.889095 , 6.89369 , 0.39345,-0.670417,-0.629077 -0.0484857 , 1.32983 , 9.92715 , -0.913695,-0.0884079,-0.396668 --0.0456318 , 1.48048 , 10.0648 , 0.734062,-0.18741,0.65271 --0.112606 , 1.5745 , 9.78434 , 0.590163,0.0481581,-0.805847 --0.161026 , 1.63315 , 9.32519 , -0.493052,-0.652003,0.576014 -1.59901 , -1.56428 , -0.548593 , -0.0962196,0.276888,0.956073 -1.63001 , -1.61615 , -0.533644 , 0.139531,-0.249606,-0.958242 -1.66113 , -1.66675 , -0.517432 , 0.100397,-0.182259,-0.978112 -1.69706 , -1.72559 , -0.504858 , 0.0984511,-0.160919,-0.982045 -1.73262 , -1.78497 , -0.490238 , -0.110153,0.191866,0.97522 -1.76387 , -1.83658 , -0.468646 , -0.0887063,0.197281,0.976326 -1.80847 , -1.91008 , -0.460647 , -0.0946616,0.173359,0.980299 -1.84947 , -1.97689 , -0.44497 , -0.060364,0.176775,0.982398 -1.89934 , -2.05898 , -0.436593 , -0.0952864,0.205686,0.973968 -1.93563 , -2.11847 , -0.411511 , -0.082174,0.210574,0.974118 -1.98077 , -2.19317 , -0.393436 , -0.0787873,0.201949,0.976222 -2.02646 , -2.26847 , -0.372513 , -0.0539661,0.189041,0.980485 -2.08188 , -2.35894 , -0.357408 , -0.0729103,0.200096,0.97706 -2.12791 , -2.43424 , -0.331011 , -0.0842233,0.198859,0.976402 -2.18339 , -2.52549 , -0.309455 , -0.0767655,0.188249,0.979117 -2.24322 , -2.62524 , -0.288226 , -0.0799175,0.191938,0.978148 -2.30375 , -2.72444 , -0.26347 , -0.071793,0.183091,0.980471 -2.37435 , -2.84039 , -0.241584 , -0.0703575,0.174071,0.982216 -2.43962 , -2.94823 , -0.212264 , -0.0673913,0.181112,0.981151 -2.51488 , -3.07259 , -0.184841 , -0.0817621,0.181427,0.98 -2.59553 , -3.20423 , -0.15568 , -0.0742499,0.183675,0.980179 -2.67633 , -3.33694 , -0.121334 , 0.0715528,-0.188524,-0.979459 -2.76672 , -3.48669 , -0.0867404 , -0.0780217,0.181273,0.980333 -2.86786 , -3.65255 , -0.0511014 , -0.0772718,0.183635,0.979953 -2.97375 , -3.82708 , -0.0110926 , -0.0522118,0.180938,0.982108 -3.09002 , -4.01831 , 0.0318133 , -0.0706051,0.198877,0.977478 -3.20553 , -4.20887 , 0.0820185 , -0.0727535,0.197938,0.977511 -3.34237 , -4.43289 , 0.133248 , -0.0687226,0.195101,0.978373 -3.48351 , -4.66586 , 0.19206 , -0.073812,0.181553,0.980607 -3.65556 , -4.94924 , 0.252533 , -0.0640451,0.187968,0.980085 -3.83291 , -5.24025 , 0.323042 , -0.0676513,0.195157,0.978436 -4.04062 , -5.58166 , 0.399689 , -0.0631023,0.193765,0.979016 -4.25854 , -5.93985 , 0.488699 , 0.0618513,-0.196343,-0.978583 -4.51619 , -6.36476 , 0.587207 , -0.0667545,0.196337,0.978262 -4.80068 , -6.83199 , 0.701279 , 0.0722753,-0.189276,-0.979261 -5.14007 , -7.39141 , 0.83163 , -0.0696515,0.191128,0.979091 -5.52625 , -8.02511 , 0.984092 , -0.0760091,0.190271,0.978785 -6.00839 , -8.81968 , 1.16472 , -0.0985044,0.195456,0.975753 -6.54647 , -9.7048 , 1.38096 , -0.17074,0.17916,0.968891 -7.15489 , -10.7047 , 1.63987 , 0.110492,-0.156996,-0.981399 -7.94696 , -12.0078 , 1.96308 , -0.0877075,0.186277,0.978575 -9.1996 , -14.0705 , 2.41276 , 0.0630549,-0.217418,-0.97404 -22.7594 , -36.3827 , 7.58623 , -0.738837,0.116111,0.663806 -25.4168 , -40.664 , 11.8222 , -0.636767,0.20862,0.742297 -21.6171 , -34.3346 , 13.1886 , -0.968494,0.026812,-0.247589 -21.9247 , -34.7277 , 17.3563 , -0.95336,0.301753,-0.00710765 -21.5311 , -33.9926 , 20.3751 , -0.881311,0.408151,-0.238127 -20.9693 , -33.0288 , 21.5486 , -0.831017,0.506794,0.229283 -3.29 , -4.20377 , 5.27521 , 0.410683,-0.36544,0.83534 -3.17169 , -4.00848 , 5.23936 , 0.231819,-0.280736,0.931369 -3.10221 , -3.89246 , 5.27489 , 0.560944,-0.641373,0.523434 -3.02894 , -3.77126 , 5.30045 , 0.726909,-0.483799,0.487384 -3.10068 , -3.88068 , 5.57309 , -0.883198,0.442436,-0.1556 -3.05211 , -3.79923 , 5.6443 , -0.894699,0.325268,-0.306129 -3.02542 , -3.74753 , 5.91742 , 0.658922,0.0645169,0.749439 -2.82888 , -3.42879 , 5.69418 , 0.195807,-0.112277,-0.974194 -2.69496 , -3.20954 , 5.57785 , 0.385372,0.137112,-0.912518 -2.62997 , -3.10123 , 5.59675 , -0.0656458,-0.409893,0.909768 -2.57914 , -3.01595 , 5.64319 , -0.388987,-0.471132,0.791659 -2.59198 , -3.03201 , 5.83444 , 0.469893,-0.855959,0.21572 -2.59249 , -3.02742 , 6.00417 , -0.456209,0.839018,-0.296517 -2.54497 , -2.94751 , 6.0641 , -0.253422,-0.957711,0.136261 -2.55392 , -2.95599 , 6.26701 , -0.326586,0.661257,-0.675338 -2.47285 , -2.82307 , 6.24349 , -0.408183,-0.675797,0.613746 -2.41116 , -2.72116 , 6.26594 , 0.00549202,0.215114,0.976574 -2.31501 , -2.56272 , 6.18527 , 0.123584,-0.0584776,0.99061 -2.24846 , -2.4539 , 6.18452 , -0.640467,0.171308,-0.748636 -2.23325 , -2.42429 , 6.33448 , -0.553902,0.284231,-0.782563 -2.16431 , -2.31019 , 6.32084 , 0.146726,-0.787676,0.598362 -2.14614 , -2.27582 , 6.46992 , -0.0465277,-0.505207,0.861743 -2.08206 , -2.16966 , 6.46943 , -0.0182007,-0.15186,0.988235 -2.01151 , -2.05322 , 6.43983 , -0.0806989,0.0767272,0.993781 -1.93335 , -1.92748 , 6.38012 , -0.127153,0.534451,0.83558 -1.89558 , -1.86128 , 6.46165 , -0.127153,0.534451,0.83558 -1.67624 , -1.51682 , 5.81317 , 0.521636,0.274412,0.807833 -1.60574 , -1.40188 , 5.73078 , -0.381152,-0.745732,-0.546448 -1.49728 , -1.22853 , 5.46913 , 0.482502,0.588039,0.649155 -1.46692 , -1.17757 , 5.54684 , -0.0977336,-0.0322406,0.99469 -1.39821 , -1.06578 , 5.43619 , -0.0199012,-0.247678,0.968638 -1.37097 , -1.01958 , 5.53012 , -0.0867872,-0.717931,0.690683 -1.32247 , -0.938319 , 5.50928 , -0.124218,-0.636966,0.760818 -1.32372 , -0.933305 , 5.77313 , 0.363599,-0.864672,0.34661 -1.38509 , -1.01687 , 6.43171 , -0.538586,-0.473871,0.696686 -1.34115 , -0.941914 , 6.48726 , -0.538586,-0.473871,0.696686 -1.28924 , -0.856361 , 6.49316 , -0.714318,-0.12442,0.688673 -1.14722 , -0.639046 , 5.82571 , 0.303094,-0.172766,0.937169 -1.05963 , -0.504487 , 5.49317 , 0.467158,0.376915,-0.799812 -1.02876 , -0.45091 , 5.58794 , -0.673165,-0.450696,0.586278 -0.997223 , -0.395334 , 5.69155 , 0.00708833,0.990321,0.138612 -0.935537 , -0.298174 , 5.49849 , -0.180161,-0.531721,-0.827535 -0.9 , -0.237685 , 5.5602 , -0.181244,0.0400695,0.982622 -0.849813 , -0.157312 , 5.45197 , 0.287915,-0.545831,-0.786876 -0.806568 , -0.0866927 , 5.41142 , 0.317961,-0.274417,0.907522 -0.772472 , -0.0275704 , 5.5088 , 0.155207,-0.0815874,0.984507 -0.829505 , -0.0699232 , 7.40992 , -0.50211,0.528926,0.684196 -0.769752 , 0.0275055 , 7.36743 , -0.50211,0.528926,0.684195 -0.694531 , 0.137157 , 6.83329 , 0.721173,0.00206836,-0.692752 -0.650055 , 0.220429 , 7.15633 , 0.392944,0.727826,0.562018 -0.596025 , 0.311795 , 7.19787 , 0.997887,0.00038097,-0.0649758 -0.538134 , 0.398392 , 6.8976 , -0.740058,0.672491,0.00837288 -0.486777 , 0.466046 , 6.29589 , -0.947463,0.270821,0.170204 -0.440165 , 0.542199 , 6.24253 , -0.161192,0.256903,0.9529 -0.37708 , 0.669798 , 7.02567 , 0.345165,0.159552,0.924881 -0.322403 , 0.759513 , 7.02806 , -0.086087,-0.36258,0.927968 -0.26925 , 0.847493 , 6.99858 , -0.6457,0.762615,-0.0385995 -0.0648483 , 1.27243 , 10.1159 , -0.825739,-0.195198,-0.5292 --0.021771 , 1.41657 , 10.1652 , -0.610321,-0.355028,-0.708141 --0.101548 , 1.54741 , 10.1027 , -0.433979,-0.722187,-0.538618 --0.236927 , 1.79116 , 10.7869 , -0.954772,-0.250453,0.160263 --0.206362 , 1.70023 , 9.36135 , -0.493052,-0.652003,0.576014 -1.54638 , -1.57917 , -0.56673 , -0.097807,0.281403,0.954592 -1.5643 , -1.61061 , -0.534754 , -0.0884543,0.278957,0.956221 -1.59752 , -1.6694 , -0.525169 , -0.109717,0.236132,0.965507 -1.63135 , -1.72896 , -0.513514 , -0.0850202,0.17572,0.980762 -1.66576 , -1.78928 , -0.499693 , -0.108161,0.199244,0.973963 -1.70326 , -1.85637 , -0.489558 , -0.114016,0.183455,0.976394 -1.73421 , -1.90871 , -0.466797 , 0.077866,-0.162593,-0.983616 -1.77608 , -1.98438 , -0.45728 , -0.0695698,0.189469,0.979419 -1.81043 , -2.04512 , -0.435452 , -0.0354022,0.188607,0.981414 -1.85391 , -2.12022 , -0.421316 , -0.0768808,0.225561,0.971191 -1.88871 , -2.18122 , -0.395181 , -0.0803451,0.234231,0.968855 -1.93622 , -2.26556 , -0.3802 , -0.0582425,0.217393,0.974345 -1.97942 , -2.34209 , -0.358055 , -0.0369364,0.201523,0.978787 -2.03234 , -2.43375 , -0.341531 , -0.0453363,0.220913,0.974239 -2.08456 , -2.52663 , -0.321597 , -0.0672047,0.226342,0.971727 -2.13247 , -2.61173 , -0.294595 , -0.039537,0.202488,0.978486 -2.18977 , -2.71262 , -0.271753 , -0.0613904,0.194622,0.978955 -2.24757 , -2.81394 , -0.245286 , -0.0683841,0.179563,0.981367 -2.3192 , -2.93989 , -0.224763 , -0.0547201,0.191043,0.980055 -2.3817 , -3.04975 , -0.193342 , -0.0629585,0.196388,0.978503 -2.45797 , -3.184 , -0.166796 , -0.0620845,0.18929,0.979957 -2.53439 , -3.31932 , -0.135065 , -0.0489121,0.194627,0.979657 -2.62065 , -3.47075 , -0.103382 , -0.0571479,0.19229,0.979673 -2.70701 , -3.62309 , -0.0658322 , -0.0625256,0.186607,0.980443 -2.80289 , -3.79225 , -0.0270629 , -0.0686481,0.191677,0.979054 -2.90375 , -3.96909 , 0.0160733 , -0.0529687,0.19429,0.979513 -3.01379 , -4.16336 , 0.0621833 , -0.0599384,0.202024,0.977545 -3.13856 , -4.38283 , 0.110767 , -0.0545026,0.192083,0.979864 -3.27306 , -4.62037 , 0.164977 , -0.0584745,0.192626,0.979528 -3.42211 , -4.88254 , 0.22419 , -0.0598472,0.19368,0.979238 -3.57534 , -5.15331 , 0.292543 , -0.0609405,0.193777,0.979151 -3.7483 , -5.45708 , 0.36725 , -0.0570011,0.197055,0.978734 -3.95087 , -5.81394 , 0.449369 , -0.0497083,0.196311,0.979281 -4.17697 , -6.21229 , 0.541993 , -0.0513007,0.194415,0.979577 -4.43684 , -6.67005 , 0.646953 , -0.0538866,0.196623,0.978997 -4.73095 , -7.18759 , 0.76807 , -0.0595431,0.19317,0.979357 -5.05784 , -7.76486 , 0.908921 , -0.0675828,0.189888,0.979477 -5.47356 , -8.49588 , 1.07333 , -0.0657204,0.183277,0.980862 -5.95149 , -9.33759 , 1.26994 , -0.104171,0.18949,0.976341 -6.4859 , -10.2799 , 1.5048 , -0.117402,0.182478,0.976175 -7.19647 , -11.5303 , 1.79778 , -0.0888596,0.184361,0.978834 -8.05538 , -13.043 , 2.16352 , -0.075165,0.17695,0.981346 -9.033 , -14.7643 , 2.61287 , -0.0765186,0.200698,0.97666 -23.8865 , -40.9114 , 9.5606 , -0.636767,0.20862,0.742297 -23.7292 , -40.6181 , 10.3511 , -0.636767,0.20862,0.742297 -3.02402 , -4.09229 , 5.16546 , -0.562151,-0.0420438,-0.825966 -3.01562 , -4.07427 , 5.29809 , 0.822505,-0.0985888,0.560148 -2.9868 , -4.02207 , 5.39877 , -0.912151,0.33295,-0.239008 -2.98296 , -4.01276 , 5.54552 , -0.835913,0.467691,-0.287254 -2.94051 , -3.93644 , 5.62463 , 0.833721,-0.404702,0.375667 -2.77681 , -3.64291 , 5.78019 , 0.134585,0.137872,0.981264 -2.62044 , -3.36949 , 5.60935 , -0.444323,-0.592423,0.672022 -2.56469 , -3.27047 , 5.64522 , 0.0979765,-0.126453,0.987122 -2.5191 , -3.18867 , 5.70137 , 0.171291,-0.239717,0.955612 -2.42434 , -3.02234 , 5.64019 , -0.00268504,-0.113884,0.993491 -2.3593 , -2.90872 , 5.64412 , -0.44495,-0.845327,0.295705 -2.32962 , -2.85376 , 5.73177 , -0.263628,-0.929176,0.259098 -2.37355 , -2.92702 , 6.01884 , 0.092109,-0.291365,0.952167 -2.31073 , -2.81531 , 6.02635 , -0.544268,0.371988,-0.751929 -2.27046 , -2.74348 , 6.09655 , 0.408092,-0.509618,0.757463 -2.24689 , -2.69936 , 6.21527 , -0.47024,0.450715,-0.758769 -2.1972 , -2.61088 , 6.25819 , -0.779213,0.268601,-0.566287 -2.16853 , -2.55807 , 6.36707 , 0.665712,-0.138488,0.733245 -2.08974 , -2.41856 , 6.31221 , -0.613401,0.194791,-0.765373 -2.05975 , -2.36388 , 6.41841 , 0.567273,-0.0565584,0.821585 -2.00619 , -2.26938 , 6.44519 , 0.454403,0.0357368,0.890079 -1.95302 , -2.17442 , 6.46963 , 0.0163235,-0.223941,0.974466 -1.91309 , -2.10255 , 6.5455 , 0.15885,0.038914,0.986535 -1.83337 , -1.96217 , 6.45821 , 0.113857,0.207987,0.971482 -1.67541 , -1.69108 , 6.03101 , -0.94555,-0.023833,-0.324603 -1.63491 , -1.61839 , 6.07973 , -0.153689,-0.749106,0.644375 -1.53839 , -1.45115 , 5.86876 , 0.436429,0.455157,0.77612 -1.50828 , -1.39655 , 5.95924 , 0.783158,0.19265,0.591227 -1.68231 , -1.68441 , 7.10519 , -0.889289,-0.0212831,-0.45685 -1.32436 , -1.0807 , 5.48885 , -0.0456859,0.309632,-0.949758 -1.2732 , -0.989816 , 5.44025 , 0.180965,-0.103133,0.978067 -1.30016 , -1.03008 , 5.85603 , 0.0479591,-0.998455,0.028053 -1.26083 , -0.959274 , 5.892 , 0.429372,-0.865748,0.25714 -1.29781 , -1.01552 , 6.45553 , -0.538586,-0.473871,0.696686 -1.25799 , -0.943997 , 6.52985 , -0.538586,-0.473871,0.696686 -1.07636 , -0.64057 , 5.50562 , 0.818087,-0.25802,-0.513965 -1.02595 , -0.55408 , 5.42662 , 0.741529,0.393875,-0.543137 -0.991714 , -0.491914 , 5.47263 , -0.407207,-0.753816,0.515698 -0.999241 , -0.497737 , 5.94004 , 0.290658,-0.202793,-0.93509 -0.913797 , -0.353876 , 5.48263 , 0.00337759,0.0564627,0.998399 -0.875669 , -0.286096 , 5.49531 , -0.157198,-0.349268,-0.923743 -0.835553 , -0.215903 , 5.48685 , 0.127923,-0.167681,-0.977506 -0.789344 , -0.136698 , 5.37774 , -0.0796019,-0.383601,-0.920062 -0.75174 , -0.0698977 , 5.3762 , 0.526792,-0.381409,0.759617 -0.837361 , -0.176387 , 7.89411 , 0.399884,0.259469,0.879073 -0.757425 , -0.0436145 , 7.36448 , -0.50211,0.528926,0.684195 -0.699122 , 0.0576346 , 7.25093 , 0.133997,0.661945,0.737478 -0.633691 , 0.163449 , 6.7556 , -0.390537,-0.655378,0.646499 -0.591667 , 0.246633 , 7.20784 , 0.474919,0.321093,0.81936 -0.537366 , 0.339362 , 7.08839 , -0.381417,0.361899,0.850617 -0.488356 , 0.411542 , 6.22752 , 0.82676,-0.48083,-0.292011 -0.442675 , 0.492549 , 6.27469 , -0.396692,-0.153832,0.90497 -0.398326 , 0.570013 , 6.23036 , 0.792122,0.130512,0.596247 -0.33249 , 0.701279 , 6.99242 , -0.0879398,0.203029,0.975216 -0.277998 , 0.798885 , 7.07363 , 0.858675,-0.417303,-0.297549 -0.227525 , 0.888128 , 7.03316 , 0.202198,-0.575068,0.792725 -0.0125106 , 1.31961 , 10.0072 , -0.905502,-0.353011,-0.235477 --0.0748879 , 1.47789 , 10.1541 , 0.496042,0.595601,0.631824 --0.138756 , 1.5855 , 9.92268 , -0.951751,-0.226911,-0.206595 --0.167525 , 1.62547 , 9.30568 , -0.493052,-0.652003,0.576014 -1.50251 , -1.60936 , -0.541797 , -0.116279,0.292651,0.949123 -1.53015 , -1.66256 , -0.527108 , -0.0749921,0.267004,0.960773 -1.56284 , -1.72308 , -0.516349 , -0.0425202,0.191494,0.980572 -1.59419 , -1.78394 , -0.503763 , -0.0479337,0.203563,0.977888 -1.62638 , -1.84462 , -0.489305 , -0.0539599,0.176072,0.982897 -1.65941 , -1.9051 , -0.472878 , -0.0907723,0.203421,0.974875 -1.69502 , -1.9742 , -0.45945 , -0.0766755,0.227925,0.970655 -1.7273 , -2.03574 , -0.438932 , -0.0584719,0.20916,0.976132 -1.76846 , -2.1126 , -0.425907 , -0.0638218,0.214996,0.974527 -1.80531 , -2.18165 , -0.405717 , -0.0783503,0.21571,0.973309 -1.84565 , -2.25936 , -0.387628 , -0.087038,0.224328,0.970619 -1.8829 , -2.32859 , -0.362742 , -0.07743,0.212576,0.974072 -1.92846 , -2.41473 , -0.343593 , 0.0750181,-0.199335,-0.977056 -1.97382 , -2.50024 , -0.321623 , -0.0631464,0.198751,0.978014 -2.01873 , -2.58608 , -0.296732 , -0.0540781,0.212329,0.975701 -2.07762 , -2.69695 , -0.279538 , -0.0545433,0.177901,0.982536 -2.13601 , -2.80795 , -0.258546 , -0.0795241,0.177748,0.980858 -2.19103 , -2.91132 , -0.230074 , -0.0847848,0.175115,0.980891 -2.25414 , -3.03092 , -0.204324 , -0.0730273,0.190504,0.978966 -2.32221 , -3.15983 , -0.177025 , -0.0749697,0.20037,0.976848 -2.38519 , -3.27966 , -0.142392 , 0.065625,-0.205174,-0.976523 -2.4626 , -3.42482 , -0.111344 , -0.0632733,0.180493,0.981539 -2.5484 , -3.58772 , -0.0797778 , -0.0534024,0.186471,0.981008 -2.63898 , -3.75941 , -0.0443282 , -0.0682834,0.191854,0.979045 -2.72536 , -3.922 , -0.000451497 , -0.0693852,0.187015,0.979904 -2.83437 , -4.12875 , 0.0399723 , -0.0626576,0.19425,0.978949 -2.93814 , -4.32595 , 0.0897727 , -0.0698356,0.201583,0.976979 -3.05638 , -4.54927 , 0.142439 , -0.0608899,0.195564,0.978799 -3.18363 , -4.78946 , 0.20051 , -0.0650656,0.19704,0.978234 -3.32492 , -5.05612 , 0.264272 , -0.0534534,0.193682,0.979607 -3.49338 , -5.375 , 0.331674 , -0.0591682,0.20304,0.977381 -3.65706 , -5.68468 , 0.41237 , -0.0569354,0.204899,0.977126 -3.85737 , -6.06319 , 0.498901 , -0.0525329,0.201334,0.978113 -4.08042 , -6.4858 , 0.597599 , -0.0556151,0.2009,0.978032 -4.33063 , -6.95955 , 0.71018 , -0.0574618,0.196933,0.978732 -4.63193 , -7.52879 , 0.838882 , -0.0617641,0.194863,0.978884 -4.97934 , -8.1848 , 0.989484 , -0.0634817,0.189322,0.979861 -5.38064 , -8.94512 , 1.16766 , -0.0625702,0.187875,0.980198 -5.87424 , -9.87856 , 1.38153 , -0.090027,0.193037,0.977053 -6.44453 , -10.9573 , 1.6402 , -0.0806213,0.183294,0.979747 -7.12883 , -12.2517 , 1.95782 , -0.0890877,0.18267,0.97913 -8.15422 , -14.1918 , 2.38756 , -0.0883123,0.21212,0.973245 -9.0026 , -15.7959 , 2.85715 , -0.0884329,0.20533,0.974689 -22.9449 , -42.1568 , 10.9887 , -0.636767,0.20862,0.742297 -2.59202 , -3.63678 , 5.29498 , 0.661257,0.33045,-0.673456 -2.53085 , -3.51959 , 5.31566 , 0.553692,0.408489,-0.725646 -2.48234 , -3.42861 , 5.36191 , 0.553692,0.408489,-0.725646 -2.42743 , -3.32487 , 5.39113 , -0.536872,-0.658638,0.527223 -2.4079 , -3.28712 , 5.49915 , -0.375504,-0.856811,0.353372 -2.41543 , -3.29888 , 5.67444 , 0.342773,-0.365619,0.865349 -2.34385 , -3.16414 , 5.66088 , -0.0591665,0.141365,-0.988188 -2.95514 , -4.31058 , 7.41569 , -0.671466,0.501742,0.545334 -2.24201 , -2.96921 , 5.72408 , 0.741286,-0.491433,0.457153 -2.30294 , -3.08359 , 6.06631 , 0.271778,-0.224756,0.935747 -2.22852 , -2.94324 , 6.03586 , 0.3791,-0.60615,0.699189 -2.2014 , -2.89078 , 6.13988 , 0.590441,-0.36028,0.722203 -2.17061 , -2.83183 , 6.23529 , -0.524729,0.31432,-0.791115 -2.10709 , -2.71221 , 6.22944 , -0.410141,0.609444,-0.6785 -2.09251 , -2.68345 , 6.38108 , -0.440747,0.761517,-0.475219 -2.0829 , -2.66419 , 6.55877 , -0.874811,0.203484,-0.439659 -2.05668 , -2.61357 , 6.68539 , 0.171946,-0.619068,0.766283 -1.95605 , -2.42265 , 6.53301 , 0.555715,-0.0491184,0.829921 -1.92427 , -2.36238 , 6.63873 , 0.561133,0.122393,0.818627 -1.83043 , -2.18709 , 6.49512 , 0.217155,0.0796657,0.972881 -1.7737 , -2.07856 , 6.48951 , 0.197625,0.219298,0.955433 -1.58767 , -1.73059 , 5.90286 , -0.555646,0.746507,0.366039 -1.55576 , -1.66914 , 5.9786 , -0.569044,-0.2622,0.779384 -1.51543 , -1.5924 , 6.01665 , 0.613952,0.658714,-0.434925 -1.50377 , -1.56904 , 6.20148 , -0.326095,-0.770518,0.54769 -1.44261 , -1.45413 , 6.1352 , 0.0489472,-0.287141,0.956637 -1.2799 , -1.14924 , 5.47511 , 0.266655,0.584045,0.766672 -1.24201 , -1.07718 , 5.49353 , -0.503258,-0.208938,-0.838497 -1.20557 , -1.00801 , 5.52001 , -0.738824,0.355396,-0.572568 -1.19004 , -0.978674 , 5.68851 , -0.377019,-0.788821,0.485405 -1.17572 , -0.951014 , 5.88585 , -0.0110494,-0.925685,0.378133 -1.13134 , -0.866349 , 5.87113 , 0.423123,0.899801,-0.106419 -1.27401 , -1.12566 , 7.38584 , -0.632208,-0.544448,-0.551262 -0.999701 , -0.618985 , 5.44714 , -0.558684,-0.140974,0.817312 -0.962021 , -0.548009 , 5.44536 , -0.266009,-0.013524,0.963876 -0.919401 , -0.467457 , 5.39265 , -0.196558,-0.670886,0.715036 -0.898572 , -0.426701 , 5.57441 , -0.214588,-0.303028,-0.928508 -0.859922 , -0.353232 , 5.5683 , 0.442925,-0.0144445,0.896443 -0.820046 , -0.278604 , 5.54098 , 0.230165,-0.266125,-0.936057 -0.779608 , -0.200884 , 5.48228 , -0.09673,0.0495488,-0.994077 -0.747043 , -0.139735 , 5.57099 , -0.121374,-0.0738078,0.989859 -0.705898 , -0.061213 , 5.4697 , 0.51856,-0.67622,0.523279 -0.711925 , -0.066318 , 6.61277 , -0.941638,0.205685,0.266481 -0.684691 , -0.0107213 , 7.22839 , 0.499914,-0.44713,-0.741728 -0.620968 , 0.105735 , 6.61412 , -0.274833,0.406155,-0.871496 -0.584126 , 0.179898 , 7.25709 , 0.0197709,-0.324218,0.945776 -0.530976 , 0.277822 , 6.74853 , -0.933302,-0.357594,0.0327769 -0.485133 , 0.363242 , 6.5482 , -0.451383,-0.780187,-0.433084 -0.441596 , 0.443454 , 6.38633 , 0.665353,-0.697541,0.265973 -0.399657 , 0.522717 , 6.29274 , 0.978591,0.0554749,0.198196 -0.336904 , 0.645247 , 7.00622 , 0.0861853,0.502373,0.860345 -0.290553 , 0.734109 , 6.94858 , 0.35682,-0.27996,-0.891236 -0.23759 , 0.835244 , 7.04863 , -0.496564,0.535175,-0.683383 --0.0032915 , 1.31419 , 10.7121 , -0.786172,-0.617902,0.0114411 --0.0679517 , 1.43513 , 10.4528 , -0.951921,-0.300682,-0.0586223 --0.126275 , 1.54381 , 10.1622 , -0.571969,-0.649792,-0.500623 --0.249193 , 1.78067 , 10.7673 , -0.954772,-0.250453,0.160263 --0.00906723 , 1.30301 , 7.0128 , 0.538077,-0.831001,0.141107 -1.46861 , -1.66043 , -0.53464 , -0.128772,0.189453,0.973409 -1.49498 , -1.71419 , -0.519095 , -0.101729,0.197248,0.975061 -1.52521 , -1.77603 , -0.507503 , -0.104233,0.17816,0.978465 -1.55209 , -1.83025 , -0.488527 , -0.0562864,0.176329,0.982721 -1.59018 , -1.90703 , -0.483869 , -0.0562813,0.174875,0.982981 -1.62073 , -1.96878 , -0.466413 , 0.0833252,-0.197091,-0.976838 -1.65091 , -2.03107 , -0.446911 , -0.0898309,0.205247,0.974579 -1.68487 , -2.10122 , -0.430388 , -0.109973,0.189137,0.975773 -1.71963 , -2.17108 , -0.411507 , -0.0997942,0.180643,0.978473 -1.7579 , -2.24962 , -0.394824 , 0.105685,-0.197185,-0.974653 -1.79673 , -2.32877 , -0.375391 , -0.110667,0.215699,0.970169 -1.83537 , -2.40738 , -0.353526 , -0.105425,0.2003,0.974046 -1.87843 , -2.49471 , -0.332959 , -0.0879352,0.169591,0.981584 -1.92512 , -2.58946 , -0.313426 , -0.102539,0.201254,0.974157 -1.96825 , -2.67761 , -0.286605 , 0.096457,-0.160348,-0.982336 -2.02341 , -2.79034 , -0.267624 , -0.0784653,0.141074,0.986885 -2.08285 , -2.91136 , -0.248094 , 0.111671,-0.151235,-0.98217 -2.13436 , -3.01559 , -0.217838 , -0.0983637,0.181524,0.978455 -2.19825 , -3.14606 , -0.192865 , -0.102555,0.189903,0.976432 -2.25803 , -3.26764 , -0.160438 , -0.0926183,0.185166,0.978333 -2.32629 , -3.4073 , -0.128952 , -0.0899766,0.172759,0.980846 -2.39966 , -3.55505 , -0.0949476 , 0.0814098,-0.182354,-0.979857 -2.47571 , -3.71231 , -0.0579794 , 0.0824651,-0.173837,-0.981316 -2.566 , -3.89434 , -0.0220661 , -0.0833455,0.179475,0.980226 -2.65957 , -4.08665 , 0.01888 , -0.0867564,0.185001,0.978901 -2.75458 , -4.27787 , 0.0667805 , -0.0873872,0.193348,0.977231 -2.85654 , -4.48686 , 0.118389 , -0.0798511,0.190692,0.978397 -2.97714 , -4.73159 , 0.171955 , -0.0735479,0.18934,0.979153 -3.10546 , -4.99371 , 0.231977 , -0.0707771,0.197555,0.977734 -3.24681 , -5.28191 , 0.298346 , -0.0639753,0.196188,0.978477 -3.40108 , -5.59589 , 0.372424 , -0.0785855,0.198892,0.976865 -3.56887 , -5.93642 , 0.45628 , -0.0747883,0.191937,0.978554 -3.77053 , -6.34784 , 0.547877 , -0.0748622,0.190298,0.978868 -3.98973 , -6.79334 , 0.653207 , 0.0781157,-0.187462,-0.979161 -4.25659 , -7.33709 , 0.772456 , 0.0759876,-0.186855,-0.979444 -4.55307 , -7.94083 , 0.911469 , -0.0840559,0.186735,0.978808 -4.90129 , -8.65117 , 1.07471 , -0.0738635,0.185537,0.979857 -5.32818 , -9.51958 , 1.26903 , -0.0703252,0.186843,0.979869 -5.78781 , -10.4567 , 1.50043 , -0.0847916,0.190828,0.977955 -6.52306 , -11.9528 , 1.80336 , -0.0829489,0.17587,0.980913 -7.14943 , -13.2285 , 2.14718 , -0.0983991,0.182031,0.978357 -7.97816 , -14.9167 , 2.5833 , -0.0841154,0.217811,0.97236 -8.58095 , -16.1968 , 11.3052 , 0.273883,-0.961614,-0.0169594 -2.47473 , -3.74249 , 5.41024 , 0.130922,-0.344932,0.929452 -2.37271 , -3.53479 , 5.33209 , -0.253951,-0.131305,0.958263 -2.30285 , -3.39196 , 5.31909 , -0.269733,-0.582583,0.766708 -2.25707 , -3.3005 , 5.36081 , -0.269733,-0.582583,0.766708 -2.2059 , -3.19657 , 5.38523 , 0.171808,-0.918389,0.356431 -2.24631 , -3.28009 , 5.64906 , -0.724604,0.606363,0.327526 -2.57816 , -3.96115 , 6.72443 , -0.803778,0.587555,0.093382 -2.51457 , -3.83254 , 6.7517 , -0.803778,0.587555,0.093382 -2.27714 , -3.34558 , 6.26202 , -0.309232,0.678622,-0.666219 -2.14473 , -3.07475 , 6.0516 , 0.526276,-0.814543,0.244034 -2.17975 , -3.1484 , 6.35146 , 0.372003,0.883877,0.283504 -2.08883 , -2.96231 , 6.25332 , -0.712244,-0.243527,-0.658334 -2.0158 , -2.81496 , 6.20761 , 0.203077,-0.316291,0.926671 -1.97874 , -2.73909 , 6.27581 , -0.1416,0.133102,-0.980935 -1.94929 , -2.68045 , 6.37642 , 0.317592,-0.81541,0.483986 -1.69239 , -2.15387 , 5.60856 , -0.284999,-0.945537,0.157274 -1.88723 , -2.55552 , 6.57527 , -0.592575,-0.128136,-0.795259 -1.81695 , -2.41275 , 6.51589 , -0.443449,-0.253111,-0.859818 -1.80126 , -2.38061 , 6.68251 , 0.320699,0.16616,0.932493 -1.71428 , -2.20313 , 6.53738 , 0.082862,0.357654,0.930171 -1.65788 , -2.08936 , 6.52197 , 0.219369,0.147227,0.964469 -1.50358 , -1.77296 , 6.01358 , -0.474016,-0.252116,0.84365 -1.45013 , -1.66147 , 5.97043 , 0.526787,0.556316,-0.642657 -1.38734 , -1.53567 , 5.87865 , -0.606745,0.558725,0.565408 -1.39521 , -1.55322 , 6.17338 , 0.0792442,-0.771115,0.631745 -1.33738 , -1.43401 , 6.0963 , -0.376245,0.919474,-0.114049 -1.21998 , -1.19261 , 5.63021 , -0.699354,-0.34147,-0.627935 -1.17511 , -1.10006 , 5.59209 , -0.776726,-0.0830498,-0.624339 -1.1506 , -1.05065 , 5.69463 , -0.355414,-0.298172,-0.885875 -1.13544 , -1.02257 , 5.88287 , 0.172514,0.647033,-0.742689 -1.06642 , -0.879755 , 5.64782 , 0.465275,0.213765,0.858967 -1.25265 , -1.27076 , 7.61335 , -0.629016,-0.00783933,-0.777353 -0.992439 , -0.730482 , 5.67109 , -0.875912,-0.130155,-0.464584 -0.916898 , -0.574132 , 5.28067 , -0.0331102,0.933408,-0.357287 -0.890943 , -0.521851 , 5.37506 , -0.0331102,0.933408,-0.357287 -0.866937 , -0.472475 , 5.49831 , -0.583342,0.371549,-0.722263 -0.838049 , -0.415527 , 5.59143 , -0.946384,0.134845,-0.293555 -0.810743 , -0.36159 , 5.73274 , 0.549148,-0.487013,-0.679157 -0.760686 , -0.258347 , 5.5069 , -0.136718,0.0691382,0.988194 -0.725111 , -0.184199 , 5.47733 , 0.294839,0.417561,-0.859484 -0.691245 , -0.116339 , 5.50563 , -0.3623,-0.0749995,0.929039 -0.656552 , -0.0462503 , 5.50315 , 0.504544,-0.0669921,-0.860783 -0.659187 , -0.058604 , 6.87579 , -0.292798,-0.492253,0.81973 -0.609985 , 0.0404943 , 6.70194 , -0.95577,0.0980265,-0.277299 -0.567298 , 0.128481 , 6.7458 , -0.717372,-0.0482319,-0.695019 -0.524773 , 0.210577 , 7.25808 , -0.478247,0.840769,0.253747 -0.479925 , 0.306711 , 6.58864 , -0.740937,-0.643408,-0.192455 -0.436837 , 0.393802 , 6.61757 , 0.398624,0.756197,0.518908 -0.397777 , 0.473934 , 6.39479 , 0.456364,0.817197,0.352025 -0.35926 , 0.55327 , 6.29043 , -0.983992,0.159373,-0.0797471 -0.294016 , 0.681406 , 6.9925 , -0.0168754,0.70801,0.706001 -0.248754 , 0.773911 , 6.97399 , -0.760243,-0.247316,0.600721 -0.195409 , 0.882097 , 7.12279 , 0.195383,0.792751,-0.577383 --0.0308368 , 1.32324 , 10.1958 , -0.850409,-0.33717,-0.403883 --0.105136 , 1.47453 , 10.2335 , -0.830228,-0.43937,-0.343039 --0.169215 , 1.60562 , 10.1201 , -0.890265,-0.327765,-0.316225 --0.17545 , 1.62316 , 9.31548 , -0.493052,-0.652003,0.576014 -1.41076 , -1.66358 , -0.548004 , -0.126302,0.2399,0.962546 -1.43178 , -1.71076 , -0.527456 , 0.113653,-0.212035,-0.970631 -1.45989 , -1.7733 , -0.516686 , -0.135777,0.179591,0.974326 -1.48465 , -1.82824 , -0.49863 , 0.107153,-0.145014,-0.98361 -1.51744 , -1.89859 , -0.489551 , -0.111329,0.167872,0.979502 -1.54171 , -1.95371 , -0.467892 , -0.124554,0.141523,0.982068 -1.5779 , -2.03245 , -0.459747 , -0.124975,0.188531,0.974083 -1.60681 , -2.09528 , -0.439293 , 0.140523,-0.184566,-0.972722 -1.64219 , -2.17489 , -0.42618 , -0.112288,0.184674,0.976364 -1.67447 , -2.246 , -0.406173 , -0.0995786,0.209535,0.972718 -1.71121 , -2.32595 , -0.387951 , -0.0960643,0.222558,0.970175 -1.74389 , -2.39721 , -0.363151 , 0.106657,-0.190614,-0.975854 -1.78754 , -2.49423 , -0.348061 , 0.0852637,-0.172004,-0.981399 -1.82711 , -2.58249 , -0.326003 , -0.112552,0.193079,0.974706 -1.86721 , -2.6713 , -0.300903 , -0.124886,0.162519,0.97877 -1.91912 , -2.78565 , -0.283544 , 0.122949,-0.139316,-0.982586 -1.96789 , -2.89142 , -0.258902 , -0.0990604,0.131031,0.986417 -2.02716 , -3.02314 , -0.240464 , -0.132014,0.183272,0.974158 -2.07231 , -3.12047 , -0.204839 , -0.106253,0.198318,0.974361 -2.13147 , -3.25249 , -0.177811 , -0.096917,0.182004,0.97851 -2.19201 , -3.3849 , -0.145967 , -0.102221,0.166556,0.980719 -2.26454 , -3.54403 , -0.117165 , 0.103797,-0.175134,-0.979058 -2.3284 , -3.6852 , -0.0779555 , 0.0884226,-0.177477,-0.980145 -2.41217 , -3.87044 , -0.0450909 , -0.0759185,0.177815,0.981131 -2.49245 , -4.0477 , -0.00318896 , -0.0886064,0.185178,0.978702 -2.5765 , -4.23337 , 0.0431565 , -0.0859308,0.18989,0.978038 -2.67742 , -4.45482 , 0.0891758 , -0.0877249,0.189967,0.977863 -2.77752 , -4.67547 , 0.143175 , -0.0825261,0.18577,0.979122 -2.89405 , -4.93222 , 0.19977 , -0.0836488,0.192187,0.977787 -3.01039 , -5.18903 , 0.266025 , -0.0848814,0.191012,0.977911 -3.15081 , -5.49854 , 0.334978 , -0.0701326,0.184454,0.980336 -3.30801 , -5.84416 , 0.412001 , 0.0843737,-0.190239,-0.978106 -3.48158 , -6.22636 , 0.49943 , -0.0832037,0.180708,0.980011 -3.68257 , -6.67002 , 0.596922 , -0.0857409,0.179261,0.980058 -3.91241 , -7.17575 , 0.708321 , 0.0880756,-0.178529,-0.979985 -4.17447 , -7.75407 , 0.837589 , -0.0821345,0.183182,0.979642 -4.47737 , -8.42011 , 0.987963 , 0.0867583,-0.182725,-0.979329 -4.8366 , -9.2121 , 1.16584 , -0.0803256,0.185716,0.979315 -5.27343 , -10.1735 , 1.37964 , -0.0740309,0.189206,0.979143 -5.73245 , -11.1848 , 1.63298 , -0.0735661,0.189838,0.979056 -6.49469 , -12.8638 , 1.97306 , -0.0881197,0.180982,0.979531 -7.22002 , -14.4628 , 2.37106 , -0.091843,0.206097,0.974212 -8.28273 , -16.804 , 2.91288 , -0.0959526,0.186885,0.977685 -2.68414 , -4.58319 , 5.63534 , 0.621769,-0.570201,0.536912 -2.63818 , -4.48345 , 5.70159 , -0.658158,0.650833,-0.378477 -2.28534 , -3.69711 , 5.0733 , 0.245493,0.842761,-0.479048 -2.22865 , -3.57309 , 5.0867 , -0.722423,-0.378455,0.578685 -2.176 , -3.45664 , 5.10387 , 0.476864,0.554802,-0.681759 -2.15678 , -3.41754 , 5.20359 , -0.535296,-0.601619,0.592885 -2.13703 , -3.37624 , 5.30308 , -0.896191,0.287127,-0.338231 -2.14643 , -3.40003 , 5.48338 , -0.884402,0.466658,0.00793145 -2.17231 , -3.46274 , 5.71872 , -0.64094,0.732186,-0.230433 -2.49467 , -4.19142 , 6.82675 , -0.803778,0.587555,0.093382 -2.39232 , -3.96575 , 6.73352 , -0.803778,0.587555,0.093382 -2.43384 , -4.06219 , 7.07313 , 0.485889,-0.830273,-0.273053 -2.05281 , -3.20669 , 6.06561 , -0.541734,0.837114,-0.0759217 -1.96028 , -3.0025 , 5.94641 , 0.55629,-0.608618,0.565796 -2.00583 , -3.10878 , 6.29409 , 0.0542607,-0.8219,0.567042 -1.9807 , -3.05585 , 6.40783 , 0.171017,-0.160564,0.972097 -1.91048 , -2.90037 , 6.35402 , -0.546738,-0.0343478,-0.836599 -1.82135 , -2.7033 , 6.21971 , -0.196939,-0.056888,-0.978764 -1.6324 , -2.27841 , 5.661 , -0.11606,-0.987026,-0.110952 -1.61879 , -2.25029 , 5.79549 , -0.565268,0.75044,-0.342508 -1.75283 , -2.5605 , 6.59331 , 0.375367,0.538113,-0.754675 -1.56749 , -2.14197 , 5.97782 , -0.789985,-0.610379,-0.0579692 -1.53907 , -2.08024 , 6.0591 , -0.271663,-0.0518246,0.960996 -1.73571 , -2.53645 , 7.2868 , 0.826029,0.461255,0.323913 -1.40895 , -1.79013 , 5.8481 , 0.424855,0.0141948,-0.90515 -1.36383 , -1.69078 , 5.83237 , -0.335399,-0.363286,0.869213 -1.32657 , -1.61063 , 5.86012 , 0.146685,-0.714899,0.683669 -1.31206 , -1.5833 , 6.02524 , -0.00213207,-0.900488,0.434876 -1.45366 , -1.91805 , 7.21545 , 0.809615,0.328481,0.48644 -1.18614 , -1.29953 , 5.7279 , -0.555789,-0.469395,-0.686125 -1.15043 , -1.22138 , 5.74788 , -0.555789,-0.469395,-0.686125 -1.10319 , -1.11842 , 5.68112 , -0.637157,-0.0430799,-0.769529 -1.0647 , -1.03361 , 5.66907 , 0.136813,0.245233,0.959762 -1.02223 , -0.938343 , 5.61654 , -0.00360804,-0.285275,0.958439 -1.00288 , -0.899791 , 5.77424 , -0.698985,0.674953,0.236345 -0.964379 , -0.813734 , 5.74793 , -0.861144,-0.0948483,-0.499434 -0.936105 , -0.755924 , 5.84594 , 0.317201,0.464488,0.826822 -0.888534 , -0.647544 , 5.70865 , -0.779607,0.0415433,0.624889 -0.856212 , -0.577251 , 5.74546 , 0.942545,0.202971,-0.265352 -0.815675 , -0.485573 , 5.66274 , 0.987916,0.154832,0.00694857 -0.772286 , -0.389144 , 5.52857 , -0.575947,-0.128391,0.807342 -0.736293 , -0.309013 , 5.47161 , 0.690211,0.157126,-0.706343 -0.705426 , -0.240407 , 5.50202 , -0.291026,-0.111149,0.950237 -0.672213 , -0.168138 , 5.49155 , -0.288477,-0.483064,0.826699 -0.640359 , -0.0998757 , 5.52926 , -0.430533,-0.150175,0.889994 -0.634816 , -0.110463 , 6.67261 , -0.506634,-0.0180962,-0.861971 -0.592937 , -0.0176016 , 6.61932 , 0.247027,0.0754332,0.966068 -0.556723 , 0.0529201 , 7.09347 , -0.496971,0.28273,0.820417 -0.51154 , 0.156102 , 6.78701 , -0.929381,-0.0701673,-0.362391 -0.4705 , 0.248694 , 6.71822 , 0.510275,0.547438,0.663273 -0.429413 , 0.338661 , 6.72794 , -0.0948978,-0.928608,-0.358722 -0.397886 , 0.41788 , 6.23611 , 0.839168,0.20234,-0.504832 -0.353253 , 0.510452 , 6.50246 , 0.308271,0.852876,0.421391 -0.293733 , 0.628392 , 7.06592 , 0.240945,0.115956,0.963587 -0.252204 , 0.722304 , 7.02825 , 0.17526,0.494466,0.851344 -0.213609 , 0.808094 , 6.91945 , 0.26136,-0.264178,-0.928386 -0.16081 , 0.919016 , 7.07703 , -0.370568,0.733706,-0.569521 --0.0954066 , 1.41379 , 10.4033 , -0.970189,-0.228286,-0.0813573 --0.193528 , 1.62015 , 10.8047 , -0.962072,-0.214496,0.168549 --0.259545 , 1.76772 , 10.7279 , -0.951315,-0.220013,0.215858 --0.0107536 , 1.29829 , 6.99308 , 0.348731,-0.928912,0.124532 -1.37417 , -1.713 , -0.541212 , -0.0679933,0.200972,0.977235 -1.39394 , -1.76079 , -0.520003 , -0.0981942,0.184423,0.97793 -1.42306 , -1.83092 , -0.514229 , -0.0900381,0.139923,0.98606 -1.44953 , -1.89455 , -0.500558 , 0.138428,-0.177015,-0.974425 -1.47661 , -1.95895 , -0.484818 , -0.101339,0.189987,0.976543 -1.50676 , -2.03009 , -0.47257 , -0.122941,0.194347,0.973198 -1.53333 , -2.09461 , -0.452936 , -0.110139,0.223251,0.968519 -1.56391 , -2.16601 , -0.436381 , -0.0879584,0.205972,0.974597 -1.59386 , -2.23884 , -0.417291 , -0.103751,0.228478,0.968005 -1.62366 , -2.31118 , -0.396061 , -0.0700615,0.229172,0.970861 -1.6579 , -2.39235 , -0.376616 , -0.0987593,0.21625,0.97133 -1.69197 , -2.473 , -0.354836 , -0.0654689,0.195941,0.978428 -1.73312 , -2.57121 , -0.338329 , -0.0759276,0.176032,0.981452 -1.77404 , -2.66871 , -0.318708 , -0.0784861,0.184083,0.979772 -1.81523 , -2.76765 , -0.295555 , -0.131728,0.142521,0.980987 -1.8598 , -2.87487 , -0.27285 , -0.103062,0.139726,0.984812 -1.91225 , -2.99939 , -0.253155 , -0.0867572,0.177453,0.980298 -1.95677 , -3.10709 , -0.222638 , -0.107415,0.219973,0.969574 -2.01011 , -3.23218 , -0.194524 , -0.0833898,0.195635,0.977125 -2.06527 , -3.3669 , -0.165026 , 0.0830829,-0.181137,-0.979942 -2.12557 , -3.50982 , -0.133496 , -0.0707178,0.176846,0.981695 -2.18882 , -3.66139 , -0.0995893 , -0.064647,0.211642,0.975207 -2.26021 , -3.83163 , -0.0648699 , -0.0412968,0.180229,0.982757 -2.33542 , -4.01043 , -0.0263878 , -0.0522551,0.185972,0.981165 -2.41767 , -4.20731 , 0.0144399 , -0.06222,0.200616,0.977692 -2.49992 , -4.4048 , 0.0624958 , -0.0618995,0.200953,0.977643 -2.59008 , -4.62027 , 0.11438 , -0.0701251,0.198749,0.977538 -2.69155 , -4.86207 , 0.169354 , -0.067148,0.19925,0.977645 -2.80054 , -5.12229 , 0.230592 , -0.072068,0.193749,0.9784 -2.9204 , -5.40921 , 0.297743 , -0.0706821,0.189326,0.979367 -3.0628 , -5.75019 , 0.369325 , -0.0679652,0.185642,0.980264 -3.21309 , -6.10971 , 0.452158 , -0.0773558,0.185097,0.979671 -3.39067 , -6.53201 , 0.543597 , -0.0676831,0.187344,0.97996 -3.59386 , -7.01799 , 0.647419 , -0.0709014,0.184956,0.980186 -3.81608 , -7.54834 , 0.767819 , -0.0690924,0.184492,0.980402 -4.09118 , -8.20679 , 0.906389 , -0.0657565,0.18714,0.98013 -4.397 , -8.93598 , 1.06991 , -0.0764962,0.193981,0.978018 -4.75842 , -9.80182 , 1.26422 , -0.0694823,0.199778,0.977375 -5.24686 , -10.9672 , 1.50368 , -0.0639778,0.198811,0.977947 -5.68921 , -12.0261 , 1.78102 , -0.0582943,0.186406,0.980742 -6.51597 , -13.9996 , 2.17176 , -0.0844128,0.215365,0.972879 -2.44064 , -4.46884 , 5.69807 , -0.541918,0.660437,-0.519757 -2.09992 , -3.63682 , 5.02079 , 0.995091,-0.0703965,0.0695565 -2.07667 , -3.58565 , 5.10803 , -0.939038,0.286675,-0.189802 -2.11191 , -3.67647 , 5.35072 , -0.736632,0.633628,-0.236409 -2.08651 , -3.62027 , 5.43933 , 0.726097,-0.678589,0.1109 -2.05045 , -3.53618 , 5.49763 , 0.795992,-0.60437,0.0336657 -2.36108 , -4.31247 , 6.59015 , -0.871579,-0.164739,0.461748 -2.29723 , -4.16213 , 6.60026 , 0.740084,-0.653107,-0.160396 -2.33521 , -4.26208 , 6.92889 , 0.403393,-0.914396,0.0339878 -2.312 , -4.21424 , 7.07609 , 0.403393,-0.914396,0.0339878 -1.96207 , -3.34861 , 6.09378 , -0.524886,0.666313,-0.529642 -1.90148 , -3.20543 , 6.07327 , -0.862355,0.497424,-0.0944066 -1.8883 , -3.17819 , 6.2193 , -0.619993,0.603111,-0.501863 -1.85602 , -3.10609 , 6.30031 , 0.746014,-0.378983,0.547572 -1.83805 , -3.06778 , 6.43824 , 0.676514,-0.27387,0.683611 -1.77275 , -2.90967 , 6.38276 , 0.189649,-0.219789,-0.956936 -1.71025 , -2.75976 , 6.3316 , 0.11881,-0.70381,0.700382 -1.51202 , -2.26457 , 5.64973 , -0.11606,-0.987026,-0.110952 -1.49023 , -2.21858 , 5.74915 , -0.816647,0.106396,-0.567246 -1.47848 , -2.19584 , 5.90051 , -0.789986,-0.610379,-0.0579691 -1.47757 , -2.20061 , 6.11459 , -0.585736,0.197056,-0.786182 -1.39662 , -2.00107 , 5.91076 , -0.139187,0.236574,0.961592 -1.34648 , -1.88191 , 5.86294 , -0.975726,0.214223,-0.0454634 -1.2983 , -1.7649 , 5.81216 , 0.389567,-0.104191,0.915086 -1.26969 , -1.69909 , 5.8774 , -0.793607,0.0991963,-0.60029 -1.23463 , -1.61849 , 5.90489 , 0.790937,-0.411046,0.453277 -1.22096 , -1.5916 , 6.07902 , -0.792379,0.543185,-0.277643 -1.23702 , -1.64332 , 6.48733 , -0.706117,-0.299967,-0.641419 -1.11517 , -1.33355 , 5.86412 , -0.688903,-0.467736,-0.553747 -1.05949 , -1.19523 , 5.70446 , 0.620293,0.303365,0.72333 -1.0286 , -1.12322 , 5.7411 , 0.666849,0.363569,0.650484 -1.00254 , -1.0638 , 5.82421 , 0.0797077,0.441038,0.893942 -0.94949 , -0.932975 , 5.6467 , 0.688977,-0.137126,0.711693 -0.927593 , -0.885158 , 5.77509 , -0.808833,0.355326,-0.468543 -1.04648 , -1.23265 , 7.62166 , -0.112105,0.985146,-0.130079 -0.989699 , -1.09509 , 7.50259 , 0.298318,0.925545,0.233181 -0.802514 , -0.576182 , 5.43306 , -0.00236483,-0.999846,0.0173983 -0.779279 , -0.52703 , 5.56629 , 0.938392,-0.109688,-0.327703 -0.742056 , -0.43312 , 5.45268 , -0.785935,0.0444285,0.61671 -0.707316 , -0.348901 , 5.37639 , -0.808739,-0.184217,0.558575 -0.767304 , -0.570697 , 7.5965 , -0.885517,-0.171723,-0.431708 -0.650394 , -0.216161 , 5.45688 , -0.199607,-0.119732,0.972534 -0.619778 , -0.144819 , 5.46531 , -0.394946,-0.134968,0.908736 -0.615425 , -0.181549 , 6.76781 , -0.19914,-0.948037,0.248131 -0.574318 , -0.0811467 , 6.65552 , -0.409769,-0.274267,-0.869981 -0.537118 , 0.0013286 , 6.81112 , -0.49847,-0.129209,0.857224 -0.4981 , 0.100563 , 6.65516 , 0.76982,0.0385748,0.637095 -0.457684 , 0.184855 , 6.94744 , 0.857871,0.488479,0.159518 -0.418681 , 0.279888 , 6.90806 , -0.604641,0.796203,-0.021651 -0.37572 , 0.376099 , 7.02673 , 0.0898166,-0.262039,0.960869 -0.349262 , 0.458119 , 6.52405 , 0.339091,0.799404,0.495954 -0.294054 , 0.570099 , 7.05886 , 0.3063,0.119445,0.944412 -0.252515 , 0.668265 , 7.06196 , 0.0116619,0.57247,0.819843 -0.215549 , 0.758953 , 6.97366 , 0.574197,0.703601,0.41862 -0.168672 , 0.865699 , 7.09284 , -0.0877515,-0.230971,0.968995 --0.0768557 , 1.32847 , 10.384 , -0.935558,-0.330203,-0.125286 --0.144466 , 1.48643 , 10.4213 , 0.816352,0.558878,0.145684 --0.225782 , 1.67139 , 10.6332 , -0.940629,-0.23558,0.244373 --0.182673 , 1.61766 , 9.30569 , -0.493052,-0.652003,0.576014 -1.3098 , -1.69753 , -0.543541 , -0.00613554,0.216624,0.976236 -1.33069 , -1.75328 , -0.528982 , 0.06195,-0.174578,-0.982693 -1.35544 , -1.81712 , -0.518374 , -0.0373236,0.154798,0.987241 -1.3828 , -1.88966 , -0.511155 , -0.0359217,0.205157,0.97807 -1.40503 , -1.9457 , -0.491292 , -0.0632208,0.214501,0.974676 -1.43286 , -2.01858 , -0.480059 , -0.040879,0.204082,0.9781 -1.45756 , -2.08289 , -0.461639 , -0.0624685,0.220681,0.973344 -1.4819 , -2.14775 , -0.441271 , -0.0797084,0.212745,0.973851 -1.51294 , -2.22845 , -0.428441 , -0.0646615,0.227587,0.971608 -1.53771 , -2.29356 , -0.403669 , -0.0566308,0.246124,0.967583 -1.56892 , -2.37537 , -0.385848 , -0.0638833,0.211824,0.975218 -1.60069 , -2.45779 , -0.365278 , -0.0879831,0.227905,0.9697 -1.63226 , -2.53965 , -0.342177 , -0.0802525,0.192914,0.977928 -1.66994 , -2.63885 , -0.32447 , -0.0444353,0.168739,0.984659 -1.71198 , -2.74657 , -0.307186 , -0.0627271,0.127706,0.989826 -1.75978 , -2.87226 , -0.293637 , -0.0718715,0.180243,0.980993 -1.80155 , -2.98145 , -0.268538 , -0.055969,0.188293,0.980517 -1.84665 , -3.09881 , -0.2434 , -0.0752138,0.213782,0.973982 -1.88482 , -3.19966 , -0.207707 , -0.0828007,0.211314,0.973905 -1.93701 , -3.33521 , -0.18071 , -0.0663786,0.193101,0.978931 -1.9896 , -3.47091 , -0.148919 , -0.0676377,0.191477,0.979164 -2.04848 , -3.62511 , -0.117724 , -0.0629914,0.223974,0.972557 -2.10344 , -3.7694 , -0.0788838 , -0.0524957,0.202923,0.977787 -2.17336 , -3.95078 , -0.043916 , -0.0234478,0.200386,0.979436 -2.23907 , -4.12304 , -0.000423685 , -0.0396858,0.194406,0.980118 -2.31861 , -4.33169 , 0.0412154 , 0.0513765,-0.202144,-0.978007 -2.40281 , -4.54874 , 0.0884891 , -0.0455503,0.210541,0.976523 -2.48921 , -4.77552 , 0.142134 , -0.0539525,0.197743,0.978768 -2.58665 , -5.0295 , 0.199455 , -0.0585687,0.19384,0.979283 -2.69799 , -5.32068 , 0.261179 , -0.0608331,0.198897,0.97813 -2.80931 , -5.61077 , 0.333241 , -0.0659452,0.187962,0.97996 -2.94927 , -5.97453 , 0.408654 , -0.0614636,0.186677,0.980497 -3.09831 , -6.36558 , 0.495021 , -0.0602889,0.188812,0.980161 -3.26993 , -6.81145 , 0.592366 , -0.0594345,0.187561,0.980453 -3.46488 , -7.32124 , 0.703315 , -0.0573877,0.185651,0.980939 -3.6962 , -7.92276 , 0.830908 , -0.0604204,0.18683,0.980533 -3.95798 , -8.60714 , 0.980511 , -0.0596486,0.192234,0.979535 -4.25541 , -9.38106 , 1.15649 , -0.066079,0.18496,0.980522 -4.64365 , -10.3948 , 1.36883 , -0.0600967,0.186404,0.980633 -5.10292 , -11.5919 , 1.62868 , -0.0692803,0.192652,0.978818 -5.69138 , -13.1263 , 1.95647 , 0.0627293,-0.175207,-0.982531 -6.26907 , -14.636 , 2.34035 , -0.0890333,0.215263,0.972489 -2.22939 , -4.42927 , 6.00633 , 0.612781,-0.673345,0.413651 -2.32537 , -4.70283 , 6.47932 , -0.95396,-0.18846,0.233331 -2.18402 , -4.32352 , 6.24415 , -0.95396,-0.18846,0.233331 -2.19709 , -4.37157 , 6.48417 , -0.892267,-0.336141,0.301446 -2.13829 , -4.22126 , 6.49508 , 0.194645,-0.951085,0.239898 -2.13306 , -4.21745 , 6.6846 , 0.204512,-0.970014,0.131331 -1.87244 , -3.50475 , 5.96346 , 0.524345,-0.420874,0.740221 -1.81843 , -3.36702 , 5.95495 , 0.523676,-0.639114,0.563291 -1.78373 , -3.28101 , 6.01404 , -0.524886,0.666313,-0.529642 -1.79853 , -3.33401 , 6.27278 , 0.619152,-0.66274,0.42122 -1.76876 , -3.25903 , 6.35549 , -0.712962,0.622727,-0.322329 -1.75242 , -3.22646 , 6.50316 , 0.680399,-0.597109,0.424874 -1.41396 , -2.32601 , 5.97104 , -0.789989,-0.610374,-0.0579724 -1.3692 , -2.2103 , 5.94846 , -0.84915,-0.404328,0.339799 -1.33609 , -2.12517 , 5.98495 , 0.726825,0.567402,0.387014 -1.27474 , -1.96145 , 5.84976 , -0.822831,-0.162654,-0.544511 -1.26079 , -1.93125 , 5.99896 , -0.594449,-0.492799,-0.635436 -1.22404 , -1.83854 , 6.01188 , -0.605108,0.180862,-0.775328 -1.37182 , -2.29254 , 7.35406 , 0.5108,-0.160108,0.844659 -1.34382 , -2.2286 , 7.5022 , -0.564166,-0.108767,-0.818466 -1.13655 , -1.62179 , 6.19745 , 0.230846,0.108593,0.966912 -1.1325 , -1.62736 , 6.48498 , 0.593772,-0.239182,0.768262 -1.08858 , -1.51358 , 6.44398 , 0.763824,0.564378,-0.31313 -0.989642 , -1.22432 , 5.84049 , -0.596876,-0.470702,-0.649752 -0.963947 , -1.16266 , 5.92466 , -0.478663,0.220421,-0.84988 -0.919277 , -1.04036 , 5.79719 , -0.589993,-0.484893,-0.64559 -0.886511 , -0.957779 , 5.80149 , 0.840644,-0.114214,0.529409 -0.865957 , -0.911472 , 5.94954 , -0.86873,0.134302,-0.476731 -0.837803 , -0.844921 , 6.02903 , -0.745931,0.194207,-0.637079 -0.779207 , -0.670441 , 5.60947 , 0.84522,0.466335,-0.261025 -0.741631 , -0.565135 , 5.4693 , 0.981298,-0.0585305,-0.18338 -0.712574 , -0.489576 , 5.46447 , -0.77789,-0.130357,0.614731 -0.680242 , -0.400379 , 5.36945 , -0.842679,0.0148743,0.538211 -0.722936 , -0.623824 , 7.41904 , -0.391278,0.621321,0.678868 -0.680004 , -0.511999 , 7.37486 , -0.741616,-0.393862,0.543027 -0.598432 , -0.196271 , 5.47041 , 0.508867,0.221925,-0.831747 -0.568881 , -0.117666 , 5.40872 , -0.394946,-0.134968,0.908736 -0.552873 , -0.14291 , 6.65132 , -0.409769,-0.274267,-0.869981 -0.516938 , -0.0528361 , 6.67785 , -0.434762,0.574197,-0.693744 -0.481306 , 0.0333842 , 6.80271 , 0.723711,-0.297796,0.622543 -0.444838 , 0.128291 , 6.77588 , -0.324821,-0.197892,-0.924841 -0.403429 , 0.217872 , 7.07728 , 0.883024,-0.461399,0.085902 -0.358064 , 0.317496 , 7.3869 , 0.102596,0.442349,0.890955 -0.350776 , 0.397852 , 6.25552 , -0.9471,-0.31273,-0.0721281 -0.298631 , 0.502941 , 6.81143 , -0.992958,-0.0952187,-0.0704848 -0.250452 , 0.61159 , 7.0852 , 0.138629,-0.0595597,-0.988552 -0.218368 , 0.701419 , 6.94791 , 0.00895741,0.523234,0.852142 -0.1842 , 0.793293 , 6.88895 , -0.31362,0.548942,0.774794 -0.127741 , 0.921322 , 7.20572 , -0.485307,0.683593,-0.54514 --0.13288 , 1.411 , 10.492 , 0.787597,0.535345,0.305118 --0.208026 , 1.59587 , 10.6957 , -0.954069,-0.187913,0.233328 -0.020329 , 1.20593 , 7.0511 , -0.114418,0.304247,0.945697 --0.0148415 , 1.30024 , 7.0128 , -0.487387,0.858418,-0.159916 -1.21401 , -1.58265 , -0.580426 , -0.0204443,0.254571,0.966838 -1.22768 , -1.62436 , -0.557447 , -0.0204443,0.254571,0.966838 -1.24777 , -1.68043 , -0.545343 , -0.0274394,0.248984,0.968119 -1.26656 , -1.73692 , -0.5318 , -0.0235521,0.176808,0.983964 -1.28945 , -1.80055 , -0.522407 , -0.0718223,0.174748,0.98199 -1.3127 , -1.8659 , -0.510747 , -0.0263955,0.174689,0.98427 -1.33484 , -1.93061 , -0.497359 , -0.0529917,0.184278,0.981445 -1.35783 , -1.99517 , -0.482197 , -0.0697082,0.220737,0.972839 -1.38045 , -2.06027 , -0.464989 , -0.0633988,0.214953,0.974565 -1.40662 , -2.13419 , -0.45066 , -0.0651753,0.22182,0.972907 -1.43144 , -2.20839 , -0.434212 , -0.0793501,0.223891,0.971379 -1.45802 , -2.28252 , -0.415284 , 0.0765125,-0.234093,-0.969199 -1.48349 , -2.35597 , -0.394435 , -0.0649868,0.223447,0.972547 -1.51513 , -2.44697 , -0.379853 , -0.0645707,0.225144,0.972184 -1.54171 , -2.5217 , -0.353697 , -0.0937564,0.192911,0.976727 -1.57637 , -2.62155 , -0.337711 , -0.0784174,0.183407,0.979904 -1.60864 , -2.71401 , -0.314221 , -0.0527812,0.144583,0.988084 -1.65609 , -2.84924 , -0.306561 , -0.0414152,0.171022,0.984396 -1.68862 , -2.94143 , -0.27643 , -0.0521287,0.202292,0.977937 -1.72332 , -3.04265 , -0.246668 , -0.038763,0.195879,0.979862 -1.7683 , -3.17084 , -0.223206 , -0.0806115,0.214131,0.973473 -1.81297 , -3.2981 , -0.195658 , -0.0677998,0.217418,0.973721 -1.85783 , -3.42656 , -0.163509 , -0.070389,0.197443,0.977784 -1.90571 , -3.56387 , -0.129858 , -0.0780007,0.189443,0.978789 -1.95985 , -3.7196 , -0.0965119 , -0.0824687,0.212876,0.973593 -2.00752 , -3.85691 , -0.0530061 , -0.076375,0.212398,0.974194 -2.07501 , -4.04926 , -0.0181052 , -0.0471027,0.173754,0.983662 -2.15182 , -4.26902 , 0.0174089 , -0.0502761,0.193261,0.979858 -2.21628 , -4.45205 , 0.0682778 , -0.0631162,0.210033,0.975655 -2.29555 , -4.68126 , 0.116902 , -0.0485145,0.198538,0.978892 -2.38586 , -4.93768 , 0.169106 , -0.0624664,0.195994,0.978613 -2.47578 , -5.19517 , 0.230875 , -0.0611227,0.200379,0.97781 -2.5811 , -5.49793 , 0.295482 , -0.055529,0.195544,0.979122 -2.69692 , -5.82792 , 0.368049 , -0.0656332,0.189363,0.979711 -2.82904 , -6.20548 , 0.448568 , -0.0605831,0.195315,0.978868 -2.97337 , -6.61952 , 0.540084 , -0.0620148,0.193112,0.979215 -3.13389 , -7.07914 , 0.644025 , -0.0562286,0.190669,0.980043 -3.3373 , -7.65924 , 0.760486 , -0.0581861,0.190272,0.980006 -3.54935 , -8.26756 , 0.898149 , -0.0570569,0.194461,0.979249 -3.81056 , -9.01374 , 1.05817 , -0.0583671,0.193054,0.979451 -4.13692 , -9.9461 , 1.24968 , 0.0589386,-0.198842,-0.978258 -4.43047 , -10.7903 , 1.47238 , -0.0501262,0.195366,0.979449 -4.85933 , -12.0173 , 1.74887 , -0.0649601,0.197492,0.97815 -5.53362 , -13.9426 , 2.12423 , -0.0647799,0.186681,0.980282 -17.3261 , -47.7296 , 10.1119 , 0.529666,-0.343416,-0.775577 -2.32839 , -5.17442 , 5.39977 , 0.128316,-0.448903,0.88432 -2.26911 , -5.02212 , 5.59202 , 0.731148,-0.225332,0.643932 -2.17937 , -4.76518 , 5.52782 , 0.386933,-0.657886,0.646118 -2.144 , -4.66988 , 5.60049 , -0.528009,0.552406,-0.645022 -2.15674 , -4.72173 , 5.81164 , -0.800971,0.578407,-0.154569 -2.16718 , -4.76812 , 6.0261 , -0.934049,0.27885,0.22315 -2.11478 , -4.62499 , 6.05566 , 0.980935,-0.0912257,-0.171594 -1.84854 , -3.82427 , 5.3874 , 0.227866,-0.959371,-0.166388 -1.83635 , -3.79943 , 5.51286 , 0.234705,-0.951824,-0.197345 -1.82285 , -3.77107 , 5.63856 , -0.699831,-0.685893,0.199469 -1.82426 , -3.79076 , 5.82402 , 0.288381,0.916262,-0.278031 -1.7725 , -3.64318 , 5.815 , -0.535522,-0.721564,0.438819 -1.78037 , -3.681 , 6.03228 , 0.145636,-0.577261,0.803468 -1.9424 , -4.20321 , 6.89024 , -0.212397,-0.963674,-0.161924 -1.70029 , -3.46243 , 6.10369 , -0.791994,0.358142,-0.494449 -1.6634 , -3.36217 , 6.14778 , -0.135221,0.976693,0.16669 -1.66236 , -3.37323 , 6.35166 , 0.619247,-0.709136,0.337134 -1.63753 , -3.3133 , 6.45891 , 0.579839,-0.712689,0.394793 -1.61244 , -3.25031 , 6.56544 , -0.608589,0.616448,-0.499611 -1.50966 , -2.93647 , 6.26848 , -0.378919,-0.231931,0.895895 -1.45985 , -2.7948 , 6.23328 , -0.543079,-0.518573,0.660414 -1.45359 , -2.79347 , 6.43491 , -0.338432,-0.431744,0.836099 -1.39758 , -2.62766 , 6.35166 , 0.542386,0.460961,-0.702377 -1.23789 , -2.12369 , 5.6163 , 0.598308,0.734481,-0.320259 -1.17655 , -1.93717 , 5.43896 , 0.0806833,0.899455,-0.429501 -1.18738 , -1.99041 , 5.73744 , -0.0188265,-0.929231,0.369021 -1.21339 , -2.09759 , 6.17402 , 0.0587284,0.224103,0.972794 -1.15369 , -1.91624 , 5.9991 , -0.18357,-0.771094,0.609685 -1.12682 , -1.84631 , 6.06601 , -0.228508,-0.930504,0.286263 -1.10181 , -1.78171 , 6.14998 , 0.237586,-0.786715,0.569766 -1.08762 , -1.75552 , 6.33533 , 0.699414,-0.703035,0.12869 -1.06817 , -1.71275 , 6.493 , 0.877087,-0.460822,-0.135505 -1.03376 , -1.61667 , 6.50975 , 0.541023,0.302826,-0.784595 -0.989404 , -1.48549 , 6.42038 , 0.763824,0.564378,-0.31313 -0.960656 , -1.41258 , 6.49942 , 0.538279,0.398588,0.742552 -0.88342 , -1.15091 , 5.94592 , 0.447153,0.254255,0.85756 -0.838934 , -1.01367 , 5.76904 , 0.842062,-0.12579,0.524508 -0.828835 , -1.00603 , 6.06239 , 0.298601,-0.304525,0.90449 -0.797263 , -0.918739 , 6.0655 , -0.535971,0.257184,-0.804109 -0.764087 , -0.820483 , 6.01823 , -0.535971,0.257184,-0.804109 -0.82614 , -1.14609 , 8.00374 , -0.105114,-0.6272,0.771733 -0.677299 , -0.526099 , 5.36781 , -0.0141413,0.442303,0.896754 -0.649453 , -0.444491 , 5.32264 , -0.786149,-0.0931839,0.610972 -0.623855 , -0.372474 , 5.32513 , 0.789485,0.297031,-0.537109 -0.64433 , -0.59029 , 7.40571 , 0.0877908,-0.893972,-0.43944 -0.606833 , -0.483323 , 7.40035 , -0.892598,-0.338258,-0.298077 -0.570169 , -0.392306 , 7.54204 , 0.325733,-0.403573,0.855001 -0.530444 , -0.245136 , 7.10455 , -0.428569,-0.213811,0.877846 -0.494012 , -0.181393 , 7.60149 , 0.767839,0.590525,-0.248401 -0.460658 , -0.0262381 , 6.77938 , 0.71179,-0.201832,0.67277 -0.41937 , 0.0440103 , 7.3931 , -0.452374,0.789159,0.415435 -0.383479 , 0.150381 , 7.31583 , 0.901555,-0.0236315,-0.432019 -0.354281 , 0.255333 , 7.01674 , 0.665084,0.302959,0.682554 -0.330152 , 0.350362 , 6.67586 , 0.074906,0.741096,0.667208 -0.299424 , 0.441642 , 6.61308 , -0.936075,-0.290265,-0.198773 -0.249639 , 0.550562 , 7.00785 , -0.112929,0.262525,0.958294 -0.21322 , 0.650599 , 7.03116 , -0.292512,0.353256,0.888621 -0.177153 , 0.751235 , 7.05272 , -0.484225,0.17366,-0.857536 -0.156038 , 0.827808 , 6.80381 , 0.670865,-0.605714,-0.427845 --0.108945 , 1.30712 , 10.3136 , -0.964791,-0.0366369,-0.260452 --0.170723 , 1.47297 , 10.401 , 0.899398,0.405975,0.162074 --0.237616 , 1.65265 , 10.554 , 0.989961,0.0322643,0.137612 --0.00100057 , 1.25346 , 7.04197 , 0.484592,0.851505,0.200274 -1.17146 , -1.61184 , -0.564258 , -0.129881,0.246833,0.960315 -1.18944 , -1.66862 , -0.553074 , -0.0964136,0.230991,0.968167 -1.20407 , -1.71777 , -0.534409 , -0.0410511,0.164258,0.985563 -1.22785 , -1.79035 , -0.531662 , -0.0914116,0.129927,0.987301 -1.24503 , -1.84801 , -0.515511 , -0.096776,0.147889,0.984258 -1.26628 , -1.91276 , -0.503314 , -0.0932131,0.145588,0.984944 -1.29016 , -1.98621 , -0.494507 , -0.0829709,0.196252,0.977037 -1.31066 , -2.05202 , -0.478218 , -0.0941265,0.216522,0.97173 -1.3308 , -2.11838 , -0.459982 , -0.0865735,0.201689,0.975616 -1.35473 , -2.19261 , -0.444724 , -0.0822253,0.202637,0.975796 -1.37826 , -2.26731 , -0.427129 , -0.0672339,0.240471,0.968325 -1.39871 , -2.33355 , -0.402834 , -0.0802474,0.2478,0.965482 -1.42535 , -2.41739 , -0.3851 , 0.0586362,-0.206109,-0.976771 -1.45182 , -2.50071 , -0.36503 , -0.0677281,0.177088,0.981862 -1.48417 , -2.60237 , -0.35035 , -0.107807,0.190285,0.975792 -1.51001 , -2.68546 , -0.32483 , -0.0946046,0.193374,0.976553 -1.54532 , -2.79578 , -0.30787 , 0.0691426,-0.148696,-0.986463 -1.57726 , -2.89847 , -0.28343 , -0.0313607,0.202146,0.978853 -1.61257 , -3.00942 , -0.259339 , -0.0413317,0.190899,0.980739 -1.6598 , -3.15581 , -0.244961 , -0.0592472,0.1786,0.982136 -1.69147 , -3.25829 , -0.209693 , -0.0961716,0.196379,0.9758 -1.7324 , -3.38737 , -0.180164 , -0.0724764,0.189312,0.979239 -1.77869 , -3.53486 , -0.151937 , -0.0867065,0.176468,0.98048 -1.82866 , -3.69219 , -0.121111 , 0.110056,-0.209376,-0.971622 -1.87546 , -3.84077 , -0.0823211 , -0.113632,0.214029,0.970196 -1.92421 , -3.99773 , -0.0410803 , -0.096941,0.183159,0.978292 -1.98568 , -4.19211 , -0.0028808 , -0.0860909,0.176931,0.980451 -2.05066 , -4.39581 , 0.0401542 , 0.101153,-0.186942,-0.977149 -2.11815 , -4.6085 , 0.0884877 , -0.0880779,0.201634,0.975493 -2.19039 , -4.83941 , 0.140776 , -0.081212,0.184674,0.979439 -2.27545 , -5.10868 , 0.195695 , -0.0912117,0.19572,0.976409 -2.36056 , -5.37703 , 0.260175 , -0.0696019,0.195411,0.978248 -2.46597 , -5.71102 , 0.326294 , -0.0799504,0.184109,0.979649 -2.57519 , -6.05417 , 0.403501 , -0.08519,0.196937,0.976708 -2.69457 , -6.4347 , 0.490008 , -0.0823536,0.186724,0.978955 -2.8415 , -6.90018 , 0.584906 , -0.0684475,0.190814,0.979237 -3.0001 , -7.4022 , 0.69489 , -0.0759755,0.183949,0.979995 -3.19176 , -8.00695 , 0.820359 , 0.0748477,-0.190214,-0.978885 -3.39729 , -8.65793 , 0.967479 , -0.0661299,0.190474,0.979463 -3.65008 , -9.45832 , 1.13984 , -0.0638794,0.185685,0.980531 -3.95005 , -10.4084 , 1.34593 , -0.0615831,0.196678,0.978532 -4.28443 , -11.4691 , 1.59229 , -0.0561926,0.196361,0.97892 -4.72942 , -12.8754 , 1.90019 , -0.0617631,0.181484,0.981452 -5.30419 , -14.6942 , 2.29508 , -0.0589413,0.185758,0.980826 -2.16614 , -5.29449 , 5.36166 , 0.0952824,-0.457771,0.88395 -2.11923 , -5.15453 , 5.40786 , 0.000537509,-0.608331,0.793683 -2.0887 , -5.06712 , 5.49387 , 0.000537541,-0.608331,0.793683 -2.0506 , -4.95593 , 5.55884 , 0.20675,-0.744399,0.63492 -2.02957 , -4.90284 , 5.67315 , 0.632475,-0.68105,0.36898 -2.02319 , -4.8975 , 5.83316 , 0.287744,-0.837684,0.464208 -1.71158 , -3.84949 , 5.00073 , -0.693669,0.702941,-0.157151 -1.679 , -3.75599 , 5.0478 , -0.693671,0.70294,-0.15715 -1.66382 , -3.71657 , 5.14878 , -0.09296,-0.981598,0.166804 -1.67439 , -3.77004 , 5.34954 , 0.348497,0.826649,-0.441817 -1.6634 , -3.75066 , 5.48054 , 0.398945,0.797589,-0.452432 -1.61179 , -3.58654 , 5.45011 , 0.365907,-0.778088,0.510579 -1.59781 , -3.55776 , 5.57218 , 0.166853,-0.950371,0.262594 -1.58447 , -3.52592 , 5.69454 , -0.142815,-0.96199,0.232764 -1.6116 , -3.6448 , 6.01019 , -0.393613,-0.726827,0.562842 -1.83469 , -4.46026 , 7.25511 , -0.40719,0.903711,-0.132298 -1.78032 , -4.29276 , 7.2529 , -0.40719,0.903711,-0.132298 -1.54494 , -3.468 , 6.32187 , -0.179385,0.979692,-0.0895793 -1.46144 , -3.19023 , 6.1122 , 0.487737,0.482949,-0.727236 -1.4294 , -3.09502 , 6.158 , -0.0748659,-0.45061,0.889576 -1.38094 , -2.94059 , 6.10995 , -0.240844,-0.0426582,0.969626 -1.35785 , -2.87702 , 6.20139 , -0.18325,-0.151473,0.971327 -1.31624 , -2.74585 , 6.18111 , 0.141377,0.460237,-0.876467 -1.28508 , -2.65619 , 6.22658 , -0.294606,-0.377314,0.877976 -1.26123 , -2.58908 , 6.31388 , -0.491635,-0.441068,0.750836 -1.11563 , -2.05845 , 5.52123 , -0.323352,0.718999,-0.61521 -1.10983 , -2.06016 , 5.71381 , -0.175589,-0.966159,0.188958 -1.06431 , -1.90891 , 5.60328 , -0.492872,-0.86538,-0.0905284 -1.07574 , -1.979 , 5.95803 , 0.612742,-0.12134,-0.780912 -1.03261 , -1.83698 , 5.86158 , -0.701377,-0.124427,0.701846 -1.01427 , -1.79176 , 5.98168 , 0.509558,0.780442,-0.362301 -1.00046 , -1.76901 , 6.16608 , 0.434146,-0.821799,0.369002 -0.973769 , -1.69112 , 6.22092 , 0.343247,-0.608653,-0.715348 -0.93398 , -1.55728 , 6.12451 , -0.0711312,0.387339,0.919189 -1.03274 , -2.03004 , 7.76865 , 0.198393,-0.403177,0.893358 -0.991746 , -1.90259 , 7.76159 , -0.115378,-0.710644,0.694027 -0.828839 , -1.21084 , 5.92105 , 0.509307,0.219038,0.832243 -0.801169 , -1.13026 , 5.94715 , 0.0206219,-0.391682,0.919869 -0.77335 , -1.04346 , 5.95241 , 0.232794,-0.30686,0.922846 -0.746718 , -0.963917 , 5.98488 , 0.174675,-0.214236,0.961037 -0.720516 , -0.886896 , 6.02597 , -0.535972,0.257184,-0.804109 -0.704438 , -0.867467 , 6.33862 , -0.702135,0.677898,-0.217854 -0.723647 , -1.08494 , 7.86696 , -0.0929353,0.266985,0.959209 -0.690107 , -0.997061 , 8.02768 , -0.0929354,0.266985,0.959209 -0.64269 , -0.809249 , 7.62495 , -0.239757,0.413304,0.878462 -0.604038 , -0.667584 , 7.42572 , -0.551702,-0.233804,-0.8006 -0.568262 , -0.552173 , 7.37191 , -0.428631,-0.65451,-0.62281 -0.535813 , -0.494732 , 7.79255 , -0.845298,0.490824,-0.211099 -0.499242 , -0.351608 , 7.49642 , -0.0452707,-0.463999,0.884678 -0.463972 , -0.252988 , 7.61563 , -0.862589,-0.416844,-0.286672 -0.438038 , -0.0821135 , 6.69575 , 0.825373,0.163202,0.540486 -0.399857 , -0.0110737 , 7.17004 , -0.0916863,-0.772567,0.628278 -0.368684 , 0.0921644 , 7.12384 , 0.0591822,0.464487,0.8836 -0.335621 , 0.193248 , 7.10554 , -0.580914,-0.0967644,-0.808193 -0.31556 , 0.294886 , 6.73551 , 0.119321,0.623495,0.772668 -0.291177 , 0.386202 , 6.56393 , -0.359217,-0.670885,-0.64875 -0.238603 , 0.495643 , 7.08963 , 0.133634,0.323139,0.936869 -0.208029 , 0.594626 , 7.06418 , -0.138629,0.0595598,0.988552 -0.17801 , 0.692092 , 7.00673 , 0.662405,-0.228166,0.713554 -0.144198 , 0.794061 , 7.03741 , 0.310693,-0.231333,0.92193 -0.123251 , 0.877517 , 6.85737 , 0.3534,-0.841636,0.408359 --0.173709 , 1.41505 , 10.6198 , -0.774358,-0.63207,-0.0292753 --0.224226 , 1.57402 , 10.5963 , -0.962668,-0.221858,0.155078 -0.0121436 , 1.20063 , 7.0411 , -0.114417,0.304247,0.945697 --0.0155674 , 1.29427 , 6.98315 , 0.0978891,-0.967344,0.2338 -1.12926 , -1.64769 , -0.554473 , -0.140983,0.258764,0.955597 -1.14827 , -1.71215 , -0.548674 , -0.123412,0.141738,0.982181 -1.16466 , -1.77015 , -0.535075 , 0.168975,-0.131143,-0.976857 -1.18297 , -1.83579 , -0.52567 , -0.12469,0.190333,0.973769 -1.20211 , -1.90125 , -0.514394 , -0.129493,0.176375,0.975768 -1.22089 , -1.96727 , -0.501168 , -0.099549,0.171303,0.980176 -1.23931 , -2.03384 , -0.485995 , -0.0930639,0.22571,0.969739 -1.25855 , -2.10021 , -0.468852 , -0.0964404,0.232529,0.967796 -1.27743 , -2.16714 , -0.44976 , -0.0659504,0.190324,0.979504 -1.30086 , -2.25047 , -0.438446 , -0.11848,0.212355,0.969984 -1.3192 , -2.31745 , -0.415168 , -0.131456,0.25033,0.959194 -1.34108 , -2.39318 , -0.394381 , 0.110201,-0.24122,-0.964193 -1.3645 , -2.47711 , -0.375838 , -0.0808179,0.176771,0.980929 -1.39406 , -2.57845 , -0.36298 , 0.0905273,-0.157137,-0.983419 -1.42026 , -2.67218 , -0.342739 , -0.0918176,0.181855,0.979029 -1.44723 , -2.7655 , -0.319652 , -0.0944071,0.168204,0.981221 -1.47879 , -2.87767 , -0.300809 , 0.0632989,-0.178944,-0.981821 -1.51012 , -2.98908 , -0.278658 , 0.0784592,-0.200426,-0.976562 -1.54192 , -3.10089 , -0.252784 , -0.0803113,0.148154,0.985698 -1.57918 , -3.23143 , -0.229573 , 0.0848398,-0.202697,-0.975559 -1.6133 , -3.35332 , -0.198884 , -0.100184,0.213432,0.971808 -1.65307 , -3.49281 , -0.170277 , 0.0859345,-0.176757,-0.980496 -1.69792 , -3.65156 , -0.142288 , -0.0928669,0.180048,0.979264 -1.73982 , -3.80059 , -0.106434 , 0.0960228,-0.196593,-0.975772 -1.78539 , -3.95941 , -0.0677875 , -0.113908,0.196306,0.973904 -1.83824 , -4.14657 , -0.0304206 , 0.109438,-0.170425,-0.979275 -1.89392 , -4.342 , 0.0109773 , -0.101511,0.167608,0.980614 -1.95743 , -4.56641 , 0.0537488 , -0.112132,0.195561,0.97426 -2.01213 , -4.76283 , 0.109482 , -0.115133,0.185297,0.975915 -2.08907 , -5.03424 , 0.159552 , 0.108624,-0.172057,-0.97908 -2.1638 , -5.2955 , 0.220525 , 0.112359,-0.206991,-0.971869 -2.23942 , -5.56685 , 0.2896 , -0.0974101,0.174344,0.979855 -2.34689 , -5.94212 , 0.356766 , -0.0950849,0.181763,0.978735 -2.44974 , -6.30703 , 0.438002 , -0.093637,0.181144,0.978989 -2.57197 , -6.73808 , 0.527499 , -0.0894101,0.189223,0.977855 -2.70479 , -7.20679 , 0.630505 , -0.0803592,0.181013,0.980192 -2.86457 , -7.76984 , 0.746647 , -0.0824546,0.180586,0.980097 -3.04535 , -8.40872 , 0.881996 , -0.0851063,0.187871,0.9785 -3.25312 , -9.14097 , 1.04024 , -0.0776945,0.188844,0.978929 -3.5009 , -10.0158 , 1.2279 , -0.0759238,0.194096,0.97804 -3.80433 , -11.0876 , 1.45433 , -0.0750168,0.194314,0.978067 -4.17192 , -12.3853 , 1.73225 , -0.0700992,0.196276,0.97804 -4.66894 , -14.1377 , 2.09092 , -0.0658631,0.188592,0.979844 -5.32114 , -16.4375 , 2.56406 , -0.0297153,0.187362,0.981841 -5.51583 , -17.7517 , 7.48687 , -0.899547,0.375938,-0.222454 -5.16851 , -16.5489 , 7.39883 , 0.779228,0.0753188,0.622199 -5.42174 , -17.671 , 9.32941 , 0.907426,-0.148227,-0.393201 -5.41108 , -17.7444 , 10.1535 , 0.884346,0.402141,-0.237099 -5.39858 , -17.7559 , 10.5645 , 0.884345,0.402141,-0.237099 -1.9347 , -5.20406 , 5.4755 , 0.209877,-0.392557,0.895461 -1.88593 , -5.03906 , 5.49833 , -0.161107,0.648335,-0.744114 -1.85897 , -4.95717 , 5.5873 , -0.161107,0.648335,-0.744114 -1.84603 , -4.93233 , 5.7271 , 0.164767,-0.832265,0.529328 -1.62458 , -4.09078 , 5.11164 , -0.954258,0.209736,-0.213079 -1.55812 , -3.85239 , 5.02633 , 0.806185,-0.295143,0.512793 -1.56424 , -3.89747 , 5.21151 , 0.859438,-0.316842,0.401221 -1.53542 , -3.80674 , 5.26493 , -0.504275,0.827795,-0.24589 -1.5207 , -3.76995 , 5.37404 , -0.434691,0.654776,-0.618314 -1.49339 , -3.68396 , 5.43173 , -0.34214,0.748811,-0.567646 -1.48373 , -3.6688 , 5.56934 , 0.457193,-0.702515,0.545387 -1.4719 , -3.64399 , 5.70018 , 0.419172,-0.766909,0.485948 -1.46472 , -3.6412 , 5.86214 , 0.338061,0.797904,-0.499063 -1.42394 , -3.49923 , 5.85438 , 0.499298,-0.491869,0.713278 -1.39037 , -3.38844 , 5.88226 , -0.376205,0.566741,-0.73299 -1.36234 , -3.30133 , 5.93944 , 0.471341,-0.624171,0.623096 -1.52871 , -4.03285 , 7.15141 , 0.128202,0.709139,0.693316 -1.38085 , -3.43824 , 6.50747 , 0.113222,-0.989807,-0.0863861 -1.29478 , -3.10117 , 6.20055 , 0.00694792,-0.148225,0.988929 -1.25345 , -2.95676 , 6.16845 , 0.236464,-0.0410544,0.970773 -1.21512 , -2.82405 , 6.1494 , 0.182676,-0.224767,0.957136 -1.19361 , -2.76375 , 6.24724 , 0.402992,-0.0559425,0.913492 -1.13296 , -2.5252 , 6.03282 , 0.56417,0.661479,0.494124 -1.11872 , -2.49808 , 6.18711 , 0.697259,0.277924,-0.660749 -1.08275 , -2.37042 , 6.15663 , 0.6522,-0.208309,-0.728864 -1.03389 , -2.18197 , 5.99849 , 0.509887,-0.39348,-0.764976 -0.991191 , -2.01806 , 5.87133 , 0.800359,0.0469026,-0.597683 -0.954435 , -1.88313 , 5.79392 , 0.901349,0.212006,-0.377655 -0.929178 , -1.79942 , 5.82278 , 0.901349,0.212006,-0.377655 -0.931248 , -1.85381 , 6.18121 , 0.410098,-0.886707,0.213474 -0.9185 , -1.83793 , 6.39458 , 0.543885,-0.831167,0.115544 -0.864285 , -1.60629 , 6.05823 , 0.253691,0.542785,0.800641 -0.836107 , -1.51218 , 6.06284 , -0.312992,-0.685229,-0.657645 -0.914669 , -2.00793 , 7.79495 , -0.0548207,-0.351804,0.934467 -0.874011 , -1.86433 , 7.73945 , -0.275071,-0.353319,0.894149 -0.748508 , -1.19407 , 5.9414 , 0.0206219,-0.391682,0.919869 -0.723647 , -1.11445 , 5.97635 , -0.10045,-0.423874,0.900134 -0.69911 , -1.03415 , 6.00994 , 0.407414,-0.377069,0.831765 -0.68204 , -1.00955 , 6.26523 , -0.539427,0.78715,-0.29902 -0.656168 , -0.926256 , 6.30657 , -0.84293,0.505789,-0.183428 -0.669351 , -1.19222 , 7.97904 , -0.105114,-0.6272,0.771733 -0.633882 , -1.06441 , 7.94486 , -0.0929353,0.266985,0.959209 -0.594631 , -0.890389 , 7.64247 , 0.155253,0.780939,0.605005 -0.561342 , -0.772846 , 7.62218 , -0.0666394,0.190142,0.979492 -0.527474 , -0.646834 , 7.53056 , 0.622391,0.187838,0.759833 -0.495402 , -0.507562 , 7.30738 , 0.274368,-0.0581099,0.959867 -0.462659 , -0.429583 , 7.56825 , -0.0520372,-0.155772,0.986421 -0.431905 , -0.311066 , 7.47967 , -0.60535,0.0300491,0.795392 -0.408765 , -0.158566 , 6.91034 , -0.0392367,0.701645,0.711446 -0.362827 , -0.1107 , 7.74504 , -0.466113,-0.636868,-0.614115 -0.343093 , 0.0239846 , 7.24084 , 0.236527,0.971438,0.0190419 -0.316955 , 0.132288 , 7.1136 , 0.343421,-0.460843,-0.818343 -0.29858 , 0.23682 , 6.78488 , 0.458243,-0.694752,-0.554377 -0.274563 , 0.333199 , 6.6939 , -0.119404,0.776423,0.618798 -0.227021 , 0.437711 , 7.12077 , 0.033524,-0.291461,-0.955995 -0.199202 , 0.53834 , 7.07613 , 0.141868,0.274354,0.951106 -0.173215 , 0.636138 , 7.02004 , -0.15325,0.168531,0.97371 -0.141757 , 0.740808 , 7.06148 , -0.383513,-0.00564998,-0.923518 -0.120062 , 0.830759 , 6.93214 , 0.720021,0.594397,0.358138 --0.145553 , 1.29598 , 10.3226 , -0.973569,-0.172553,-0.149628 --0.202951 , 1.47305 , 10.4693 , 0.802477,0.516057,0.299525 --0.257366 , 1.6479 , 10.5633 , -0.921983,-0.285432,0.261678 --0.00414481 , 1.24499 , 7.00243 , 0.665508,-0.261832,-0.698959 -1.09293 , -1.70457 , -0.563041 , -0.129999,0.1338,0.982445 -1.11044 , -1.77052 , -0.556092 , -0.0832349,0.167734,0.982312 -1.12458 , -1.82882 , -0.541565 , 0.0994447,-0.188588,-0.977008 -1.13838 , -1.88773 , -0.525381 , -0.0899345,0.175272,0.980404 -1.15626 , -1.95373 , -0.513153 , -0.0911335,0.175471,0.980258 -1.17256 , -2.02102 , -0.498899 , 0.0882927,-0.222506,-0.970925 -1.18673 , -2.08001 , -0.477533 , -0.0874505,0.213532,0.973014 -1.20574 , -2.15462 , -0.464919 , -0.0815325,0.206015,0.975146 -1.22509 , -2.23086 , -0.44965 , 0.0831299,-0.174992,-0.981054 -1.24602 , -2.3154 , -0.437015 , -0.111142,0.239603,0.964489 -1.26038 , -2.37392 , -0.408132 , -0.137364,0.238339,0.961418 -1.28172 , -2.45864 , -0.390801 , -0.102894,0.215611,0.971043 -1.30362 , -2.54398 , -0.37072 , 0.0751229,-0.173546,-0.981956 -1.32946 , -2.64724 , -0.356367 , -0.0552537,0.168802,0.9841 -1.35242 , -2.74097 , -0.334929 , -0.0758877,0.179823,0.980768 -1.38097 , -2.85383 , -0.318002 , -0.0769495,0.178088,0.981001 -1.40496 , -2.94857 , -0.29009 , 0.0671889,-0.201005,-0.977283 -1.4328 , -3.06091 , -0.266448 , 0.0819012,-0.170394,-0.981966 -1.46611 , -3.19202 , -0.245663 , -0.0517294,0.171029,0.983907 -1.49961 , -3.32432 , -0.220276 , 0.0798289,-0.199854,-0.976568 -1.53022 , -3.44706 , -0.187707 , -0.0857864,0.198589,0.976321 -1.56783 , -3.59671 , -0.159948 , -0.0701535,0.183856,0.980447 -1.60792 , -3.75692 , -0.129514 , -0.0677337,0.197169,0.978027 -1.64837 , -3.91716 , -0.0937041 , -0.0822529,0.204596,0.975384 -1.69052 , -4.08664 , -0.0548563 , -0.0808598,0.179143,0.980495 -1.74246 , -4.29285 , -0.0192177 , -0.0739858,0.172523,0.982223 -1.79512 , -4.50083 , 0.0239672 , -0.0806912,0.198039,0.976867 -1.84607 , -4.70798 , 0.0741361 , -0.0914946,0.189816,0.977547 -1.91031 , -4.96281 , 0.123113 , -0.0920316,0.178178,0.979685 -1.97691 , -5.22617 , 0.179431 , -0.0948876,0.209085,0.973283 -2.03989 , -5.48113 , 0.246537 , -0.10112,0.193383,0.975899 -2.13074 , -5.84049 , 0.309796 , -0.0829317,0.183401,0.979534 -2.21082 , -6.16013 , 0.389494 , -0.0822105,0.184238,0.979438 -2.32278 , -6.60516 , 0.47028 , -0.0746074,0.196955,0.97757 -2.41626 , -6.98253 , 0.571416 , -0.0717779,0.183513,0.980393 -2.56474 , -7.5704 , 0.675979 , -0.0651559,0.182139,0.981112 -2.71198 , -8.15677 , 0.801492 , -0.0629513,0.193144,0.979149 -2.88593 , -8.84859 , 0.947054 , -0.0156768,0.193333,0.981008 -3.09335 , -9.67263 , 1.11839 , -0.054034,0.201127,0.978074 -3.30057 , -10.5041 , 1.31956 , -0.0600715,0.208615,0.976151 -3.5978 , -11.6899 , 1.56655 , -0.0653545,0.189532,0.979697 -3.97447 , -13.1894 , 1.87589 , -0.0574285,0.186723,0.980733 -4.52322 , -15.3678 , 2.29425 , -0.0300687,0.193429,0.980653 -5.23365 , -18.1924 , 2.8557 , 0.167839,0.519421,0.837873 -4.90573 , -17.6633 , 7.19922 , -0.899547,0.375938,-0.222454 -4.85521 , -17.5228 , 7.50715 , -0.899547,0.375938,-0.222454 -4.85921 , -17.6054 , 7.89922 , -0.899547,0.375938,-0.222454 -4.82897 , -17.5448 , 8.2415 , -0.688503,0.724099,-0.0405491 -4.78321 , -17.4232 , 8.56031 , -0.907115,0.420811,-0.00779676 -4.8993 , -17.9752 , 9.1791 , 0.908957,-0.336077,-0.246677 -4.73247 , -17.3511 , 9.27807 , -0.845793,-0.297365,0.442953 -4.63709 , -17.02 , 9.49889 , 0.753363,0.457408,-0.472465 -4.53207 , -16.6502 , 9.69207 , 0.754329,0.559674,-0.343151 -4.80045 , -17.8523 , 10.7127 , 0.8749,0.245548,-0.417441 -4.20259 , -15.395 , 9.76109 , 0.558667,0.741027,-0.372518 -4.16189 , -15.2913 , 10.0654 , 0.67479,0.72093,-0.157854 -4.72322 , -17.9301 , 12.916 , -0.766986,-0.58985,-0.252605 -4.63449 , -17.6318 , 13.174 , -0.762143,-0.609187,-0.219155 -4.46642 , -16.9852 , 13.1821 , 0.691709,0.609193,0.387844 -1.77616 , -5.34542 , 5.46077 , -0.308096,0.320657,-0.895688 -1.72651 , -5.15618 , 5.46768 , 0.37304,-0.395395,0.839348 -1.70807 , -5.10447 , 5.58352 , 0.36531,-0.510298,0.778553 -1.67158 , -4.97571 , 5.63375 , 0.534251,-0.815702,0.221823 -1.51817 , -4.31234 , 5.19816 , -0.90209,0.159683,-0.400917 -1.50011 , -4.25661 , 5.29329 , -0.868687,0.109674,-0.483069 -1.66312 , -5.03629 , 6.19806 , 0.0298899,-0.906426,0.421305 -1.63826 , -4.95655 , 6.29949 , 0.49631,0.780809,-0.37949 -1.41157 , -3.94123 , 5.43122 , 0.351031,-0.762764,0.54311 -1.37066 , -3.77854 , 5.41178 , 0.36272,-0.790313,0.493801 -1.36233 , -3.7715 , 5.55738 , -0.457977,0.709108,-0.536118 -1.34359 , -3.71476 , 5.65151 , -0.0455854,-0.861506,0.505698 -1.31575 , -3.61804 , 5.69944 , -0.0756887,-0.849379,0.522328 -1.29529 , -3.55136 , 5.78369 , -0.0192505,-0.742757,0.669284 -1.28248 , -3.52692 , 5.92174 , 0.458669,-0.257481,0.850486 -1.2644 , -3.47402 , 6.0285 , -0.576472,0.440928,-0.687941 -1.47078 , -4.54812 , 7.68366 , -0.686706,0.716301,-0.123887 -1.11331 , -2.79547 , 5.43578 , -0.831412,-0.151411,-0.534629 -1.0999 , -2.76054 , 5.54767 , -0.594947,0.101607,-0.797317 -1.14668 , -3.04329 , 6.15064 , -0.468699,-0.0097486,-0.883304 -1.1277 , -2.98868 , 6.25952 , 0.551307,-0.108179,0.827259 -1.1082 , -2.9319 , 6.36808 , 0.411759,0.0335257,0.910676 -1.00265 , -2.41066 , 5.68445 , 0.768215,0.624123,-0.142535 -1.03207 , -2.61922 , 6.2443 , 0.697259,0.277924,-0.660748 -0.989074 , -2.42786 , 6.10218 , -0.00040817,0.651342,0.758784 -0.948449 , -2.25582 , 5.98116 , -0.596934,0.420156,0.683476 -0.902561 , -2.03969 , 5.75737 , 0.769566,0.61953,-0.154763 -0.874033 , -1.92569 , 5.72569 , 0.769566,0.61953,-0.154763 -0.845356 , -1.80546 , 5.67318 , 0.76442,0.543794,-0.346338 -0.850759 , -1.90172 , 6.11243 , -0.146208,0.756081,0.637938 -0.830319 , -1.83511 , 6.19639 , -0.423614,0.85214,0.30726 -0.795964 , -1.67802 , 6.05639 , 0.0298786,0.177544,0.983659 -0.773889 , -1.60734 , 6.12759 , -0.484343,-0.204224,-0.850708 -0.747827 , -1.50509 , 6.11315 , 0.56589,0.05279,0.822789 -0.790294 , -1.92851 , 7.65931 , -0.275071,-0.353319,0.894149 -0.721393 , -1.50818 , 6.72542 , -0.55628,0.420119,-0.716975 -0.694876 , -1.40349 , 6.72725 , 0.575732,0.606881,0.547931 -0.668021 , -1.30461 , 6.74629 , -0.646932,-0.526339,-0.551767 -0.627058 , -1.05611 , 6.19291 , -0.444163,0.774887,-0.449744 -0.602142 , -0.952173 , 6.14743 , -0.67557,0.70264,-0.223389 -0.605778 , -1.27017 , 7.95285 , -0.105114,-0.6272,0.771733 -0.573321 , -1.13527 , 7.89056 , -0.600967,-0.362047,0.712573 -0.542618 , -1.01879 , 7.91388 , -0.0785098,0.280597,0.956609 -0.510534 , -0.830557 , 7.52135 , -0.018451,0.265276,0.963996 -0.480815 , -0.730434 , 7.59869 , 0.0873248,-0.00104948,0.996179 -0.451755 , -0.611324 , 7.55554 , -0.36989,-0.169285,-0.913523 -0.423097 , -0.498153 , 7.53998 , 0.152201,-0.318289,-0.935696 -0.389752 , -0.413793 , 7.80049 , 0.512259,-0.82978,-0.221486 -0.378102 , -0.222661 , 6.93456 , 0.463713,0.847743,0.257494 -0.340094 , -0.15548 , 7.40059 , -0.704477,0.259052,0.66076 -0.304647 , -0.0610911 , 7.64614 , 0.464274,0.877293,-0.12168 -0.293778 , 0.0701658 , 7.13094 , 0.760313,-0.305893,-0.573022 -0.277986 , 0.179425 , 6.82303 , 0.0949483,0.579148,0.809674 -0.255205 , 0.276729 , 6.77346 , -0.0158946,0.705584,0.708448 -0.214358 , 0.378996 , 7.10122 , 0.018652,-0.250061,-0.96805 -0.186623 , 0.481764 , 7.11768 , 0.1419,-0.148058,-0.978746 -0.163202 , 0.582228 , 7.0623 , 0.142702,-0.539071,-0.830083 -0.137138 , 0.683876 , 7.05508 , 0.141816,-0.330643,0.93304 -0.10929 , 0.787597 , 7.06587 , 0.588931,0.109097,-0.800786 -0.112154 , 0.848417 , 6.6379 , -0.755242,0.61037,0.238869 --0.207679 , 1.40635 , 10.6285 , -0.774358,-0.63207,-0.0292753 --0.243781 , 1.55902 , 10.536 , 0.880246,0.465706,-0.0910244 -0.00442259 , 1.19726 , 7.03081 , -0.0941028,0.551063,0.829141 --0.0196638 , 1.29519 , 6.99281 , 0.152285,-0.967918,0.19986 -1.03767 , -1.68831 , -0.570934 , -0.111843,0.16204,0.980426 -1.048 , -1.73865 , -0.553038 , 0.0710467,-0.195571,-0.978113 -1.06329 , -1.80497 , -0.545452 , -0.0726785,0.18399,0.980238 -1.07521 , -1.86365 , -0.530386 , -0.048584,0.229052,0.972201 -1.09099 , -1.93042 , -0.519271 , -0.0535376,0.195918,0.979158 -1.10543 , -1.9975 , -0.506232 , -0.0700803,0.208582,0.975491 -1.1195 , -2.06514 , -0.491244 , -0.0624216,0.229794,0.971236 -1.13441 , -2.13257 , -0.474287 , -0.0587607,0.231882,0.970967 -1.14918 , -2.19961 , -0.455578 , -0.0582561,0.182342,0.981508 -1.16804 , -2.28498 , -0.44435 , -0.0395097,0.221809,0.974289 -1.18498 , -2.36105 , -0.426012 , -0.079068,0.248867,0.965305 -1.2013 , -2.43855 , -0.405236 , -0.0600912,0.247234,0.967091 -1.21843 , -2.51576 , -0.382102 , -0.0671284,0.202143,0.977053 -1.2388 , -2.60983 , -0.365404 , -0.0398505,0.162313,0.985934 -1.26237 , -2.71331 , -0.349733 , -0.0433223,0.181324,0.982469 -1.28282 , -2.80823 , -0.326877 , -0.0621806,0.171205,0.983271 -1.30789 , -2.92199 , -0.308361 , -0.0313782,0.19806,0.979687 -1.33103 , -3.02646 , -0.282736 , -0.050981,0.184382,0.981532 -1.36037 , -3.1581 , -0.264183 , -0.0451477,0.182617,0.982147 -1.38493 , -3.27261 , -0.234642 , -0.0445487,0.176224,0.983342 -1.41656 , -3.41422 , -0.210787 , -0.0604311,0.196728,0.978594 -1.44268 , -3.53758 , -0.176458 , -0.0588316,0.20513,0.976965 -1.47652 , -3.68895 , -0.146329 , -0.0486628,0.17942,0.982568 -1.51186 , -3.85065 , -0.113549 , -0.060871,0.197434,0.978425 -1.54683 , -4.01123 , -0.0758075 , -0.0679333,0.202078,0.977011 -1.58884 , -4.20109 , -0.0390509 , -0.0534517,0.177457,0.982676 -1.63708 , -4.41881 , -0.00252715 , -0.049149,0.187082,0.981114 -1.6807 , -4.61825 , 0.0456625 , -0.0530235,0.199502,0.978462 -1.73476 , -4.86488 , 0.0916166 , -0.0585644,0.17777,0.982328 -1.79397 , -5.13159 , 0.143209 , -0.0553047,0.196818,0.978879 -1.85133 , -5.39703 , 0.203731 , -0.0655648,0.217669,0.973818 -1.91374 , -5.68225 , 0.271253 , -0.0669839,0.175359,0.982223 -1.99405 , -6.04414 , 0.340056 , -0.0742268,0.19504,0.977982 -2.07099 , -6.39505 , 0.422366 , -0.0703083,0.18522,0.980179 -2.16696 , -6.83351 , 0.510653 , -0.0656502,0.197577,0.978087 -2.26647 , -7.28987 , 0.613117 , -0.0387281,0.20034,0.978961 -2.39034 , -7.85271 , 0.727875 , 0.0151745,0.212322,0.977082 -2.53309 , -8.50159 , 0.860798 , 0.0352997,0.206036,0.977908 -2.69631 , -9.2454 , 1.01648 , 0.0117881,0.191662,0.98139 -2.89803 , -10.1619 , 1.20129 , -0.0323056,0.208212,0.97755 -3.09718 , -11.0762 , 1.41902 , -0.0508861,0.195687,0.979345 -3.38003 , -12.3651 , 1.68874 , -0.0496939,0.192966,0.979946 -3.74328 , -14.0185 , 2.03021 , -0.0259721,0.190751,0.981295 -4.27694 , -16.4414 , 2.49854 , -0.000881806,0.191065,0.981577 -5.44089 , -22.3265 , 6.32241 , -0.69136,-0.666823,-0.27815 -5.40916 , -22.2751 , 6.73471 , -0.69136,-0.666823,-0.27815 -5.37583 , -22.2171 , 7.14684 , -0.69136,-0.666823,-0.278151 -5.33847 , -22.142 , 7.55552 , -0.69136,-0.666823,-0.278151 -4.47221 , -18.3755 , 7.55432 , 0.787181,-0.574636,0.223917 -4.42135 , -18.2188 , 7.86894 , 0.787181,-0.574636,0.223917 -4.41057 , -18.3457 , 8.67326 , 0.822985,-0.564529,-0.0632681 -4.32703 , -18.036 , 8.92644 , -0.898104,0.439333,0.0198987 -3.93298 , -16.2274 , 8.49581 , 0.827745,0.505656,-0.24321 -3.89842 , -16.1464 , 8.80992 , -0.829659,-0.416267,0.372005 -3.83915 , -15.944 , 9.06641 , 0.558667,0.741027,-0.372518 -3.83319 , -15.9999 , 9.45337 , 0.558667,0.741028,-0.372518 -3.80379 , -15.9441 , 9.78868 , 0.558667,0.741027,-0.372518 -3.22049 , -13.1506 , 8.59061 , 0.0859495,-0.901588,0.42397 -3.65817 , -15.4042 , 10.2215 , -0.592583,-0.805103,-0.0255834 -3.20115 , -13.2111 , 9.25903 , 0.426554,-0.804096,0.414104 -3.1473 , -13.0213 , 9.46605 , -0.708417,0.640446,-0.296605 -3.07088 , -12.7134 , 9.59289 , -0.708417,0.640446,-0.296605 -3.56823 , -15.3318 , 11.7097 , -0.737036,-0.671941,-0.0726123 -4.04186 , -17.8661 , 13.9099 , -0.747147,-0.525619,-0.406811 -3.91014 , -17.3053 , 13.9787 , 0.776069,0.34314,0.529123 -4.21847 , -19.0354 , 15.7753 , -0.708233,-0.558928,-0.431284 -1.57722 , -5.33735 , 5.48997 , -0.55496,0.462919,-0.691177 -1.53636 , -5.16271 , 5.50792 , -0.633117,0.498691,-0.592005 -1.54003 , -5.22279 , 5.71922 , 0.831888,-0.337012,0.440892 -1.52234 , -5.17289 , 5.84242 , 0.777129,-0.38195,0.500185 -1.49853 , -5.09134 , 5.93859 , -0.414564,-0.857269,0.305331 -1.47987 , -5.03727 , 6.06046 , 0.497629,0.723539,-0.478389 -1.43782 , -4.85204 , 6.05712 , -0.45019,-0.854818,0.258098 -1.42406 , -4.82242 , 6.20379 , -0.49631,-0.78081,0.37949 -1.40564 , -4.76969 , 6.32959 , 0.909561,0.396091,0.125745 -1.22888 , -3.82333 , 5.49254 , -0.436039,0.596805,-0.673567 -1.38081 , -4.73324 , 6.66827 , -0.612485,-0.61971,-0.490736 -1.16837 , -3.60559 , 5.72018 , 0.254315,-0.777583,0.575055 -1.16935 , -3.66252 , 5.95863 , -0.060716,-0.955739,0.287884 -1.13327 , -3.49965 , 5.92553 , 0.503623,-0.698499,0.508393 -1.1186 , -3.46485 , 6.05555 , -0.497315,0.253492,-0.829711 -1.09792 , -3.39128 , 6.13731 , -0.497314,0.253492,-0.829711 -0.992881 , -2.78621 , 5.45812 , 0.428468,0.312392,0.847837 -0.994921 , -2.84941 , 5.71832 , 0.595652,0.275014,0.754696 -0.95426 , -2.64511 , 5.58054 , -0.594947,0.101607,-0.797316 -0.929722 , -2.54159 , 5.58925 , -0.104408,0.452408,0.885678 -0.897515 , -2.38256 , 5.5017 , -0.126827,0.262548,0.956548 -0.875843 , -2.292 , 5.52229 , 0.0310718,-0.500265,-0.865314 -0.850007 , -2.17177 , 5.48838 , 0.587586,-0.498106,0.637678 -0.857351 , -2.28847 , 5.89221 , 0.692209,-0.445035,-0.568146 -0.906461 , -2.7323 , 6.96787 , -0.225754,-0.973987,-0.0196311 -0.910387 , -2.869 , 7.50425 , 0.991426,0.113651,-0.0644876 -0.88277 , -2.75842 , 7.55852 , 0.991426,0.113651,-0.0644875 -0.855412 , -2.65607 , 7.62917 , 0.962263,0.149763,-0.227204 -0.755095 , -1.91118 , 6.20078 , 0.393377,-0.16107,0.905158 -0.740215 , -1.8914 , 6.40509 , 0.198118,-0.201252,-0.959295 -0.767115 , -2.28073 , 7.68152 , 0.743982,0.0422649,-0.666862 -0.685526 , -1.60804 , 6.20607 , -0.659935,0.0346753,-0.750522 -0.659883 , -1.4808 , 6.12516 , -0.656941,-0.103844,-0.746757 -0.654097 , -1.59517 , 6.76267 , -0.84664,0.452313,-0.280381 -0.62846 , -1.4675 , 6.69903 , -0.939314,0.261166,0.222444 -0.607919 , -1.41928 , 6.89178 , -0.887829,-0.05716,-0.45661 -0.577024 , -1.18945 , 6.4479 , -0.933896,0.242336,0.262892 -0.551834 , -1.02072 , 6.17232 , 0.830124,-0.47264,0.295814 -0.539161 , -1.29965 , 7.73108 , -0.870206,-0.239019,0.430827 -0.511083 , -1.08718 , 7.30819 , 0.900994,0.402848,-0.161008 -0.48335 , -1.12704 , 8.05582 , -0.401642,-0.822783,-0.402134 -0.456051 , -0.968016 , 7.86266 , -0.0341317,0.873909,0.484889 -0.432303 , -0.789827 , 7.51783 , 0.238494,0.0298444,0.970685 -0.405274 , -0.693797 , 7.62426 , -0.241448,0.0105152,-0.970357 -0.373661 , -0.611357 , 7.86745 , -0.523404,0.646879,-0.554613 -0.355381 , -0.448856 , 7.48392 , -0.501926,0.0223669,0.864621 -0.342867 , -0.290172 , 6.99765 , -0.204203,-0.877625,-0.433677 -0.322277 , -0.18207 , 6.91661 , 0.714427,0.365828,0.59646 -0.276645 , -0.123206 , 7.56146 , 0.392925,0.912923,-0.110372 -0.270054 , 0.0114178 , 7.06761 , -0.807891,0.302227,0.505935 -0.254813 , 0.12046 , 6.87081 , -0.572493,-0.45036,-0.685148 -0.234804 , 0.220418 , 6.812 , 0.608685,0.420628,0.672737 -0.196569 , 0.320211 , 7.13095 , 0.162732,0.509786,0.84477 -0.175326 , 0.422851 , 7.07854 , -0.018652,0.250062,0.96805 -0.151035 , 0.526679 , 7.09409 , -0.0501166,0.329427,0.94285 -0.131989 , 0.625993 , 7.01813 , -0.0376338,0.258802,0.965197 -0.11571 , 0.719193 , 6.90078 , -0.608782,0.408241,0.680238 -0.0833117 , 0.831829 , 7.0302 , -0.88462,0.0172409,0.465994 -0.0114976 , 1.07809 , 7.34133 , -0.113235,0.181502,0.976849 --0.276888 , 1.64308 , 10.5623 , -0.921983,-0.285432,0.261678 --0.010408 , 1.24537 , 7.01195 , 0.0604163,-0.973415,0.220939 -0.982114 , -1.66884 , -0.578955 , -0.0580745,0.264905,0.962524 -0.993351 , -1.72817 , -0.567803 , -0.0714485,0.286203,0.955501 -1.00243 , -1.77911 , -0.549248 , 0.0145081,-0.216111,-0.976261 -1.01548 , -1.84578 , -0.540928 , -0.0119322,0.180414,0.983518 -1.02615 , -1.90505 , -0.525104 , -0.0468561,0.191614,0.980351 -1.03873 , -1.97194 , -0.513376 , -0.0574771,0.18532,0.980996 -1.05191 , -2.03958 , -0.499482 , -0.0627157,0.210688,0.97554 -1.06472 , -2.10778 , -0.483639 , -0.0594362,0.221429,0.973363 -1.07739 , -2.17556 , -0.465947 , -0.0671949,0.210867,0.975203 -1.09144 , -2.2527 , -0.45118 , -0.0838028,0.212896,0.973474 -1.10631 , -2.32957 , -0.43415 , 0.0419769,-0.225733,-0.973284 -1.11807 , -2.39794 , -0.410227 , -0.0327363,0.231686,0.97224 -1.13509 , -2.48376 , -0.393277 , -0.0495481,0.231951,0.971465 -1.15071 , -2.56978 , -0.373818 , 0.0609781,-0.206749,-0.976492 -1.16859 , -2.66505 , -0.355799 , -0.0465131,0.176142,0.983265 -1.187 , -2.76088 , -0.334738 , -0.0625292,0.167112,0.983953 -1.20833 , -2.87423 , -0.318651 , -0.0375403,0.206775,0.977668 -1.22583 , -2.97064 , -0.291359 , -0.0454548,0.198371,0.979073 -1.2498 , -3.09339 , -0.271821 , -0.0425613,0.184712,0.981871 -1.27303 , -3.2172 , -0.248193 , -0.0465405,0.187726,0.981118 -1.2967 , -3.34133 , -0.220452 , -0.0421352,0.195017,0.979894 -1.32362 , -3.48456 , -0.194835 , -0.0564654,0.197743,0.978626 -1.35021 , -3.62678 , -0.164742 , -0.0657091,0.193778,0.978842 -1.38068 , -3.789 , -0.13519 , -0.0569788,0.182845,0.981489 -1.4115 , -3.95122 , -0.100164 , -0.058779,0.197323,0.978575 -1.44306 , -4.12249 , -0.0623185 , -0.0763725,0.192317,0.978357 -1.47932 , -4.31353 , -0.0229471 , -0.0523371,0.181438,0.982009 -1.51925 , -4.52388 , 0.0188995 , -0.0472268,0.19695,0.979275 -1.55974 , -4.7428 , 0.0657057 , -0.0532987,0.19283,0.979784 -1.60883 , -5.00146 , 0.113594 , -0.0457184,0.18513,0.98165 -1.65704 , -5.25916 , 0.170144 , -0.0457451,0.202776,0.978156 -1.70939 , -5.53654 , 0.23299 , -0.0517664,0.199765,0.978475 -1.77456 , -5.88094 , 0.297125 , -0.0604651,0.180223,0.981766 -1.83492 , -6.20647 , 0.375552 , -0.0878348,0.200071,0.975836 -1.91076 , -6.60848 , 0.458426 , 0.0132417,-0.224744,-0.974328 -1.98708 , -7.01941 , 0.554656 , 0.00761239,0.212829,0.97706 -2.09092 , -7.56685 , 0.658894 , 0.0474869,0.258835,0.964754 -2.2009 , -8.15101 , 0.780926 , 0.0759264,0.251384,0.964905 -2.32507 , -8.81335 , 0.92301 , -0.0434341,-0.209106,-0.976928 -2.48398 , -9.65904 , 1.08904 , 0.00551952,0.193433,0.981098 -2.67265 , -10.6586 , 1.28875 , -0.0283161,0.204016,0.978558 -2.89305 , -11.8305 , 1.531 , -0.0352097,0.195069,0.980157 -3.12622 , -13.0769 , 1.81969 , 0.0328768,-0.204947,-0.978221 -3.4561 , -14.8355 , 2.19208 , -0.0089157,0.221874,0.975035 -3.7645 , -16.4975 , 2.6188 , -0.00393704,0.317895,0.948118 -4.2654 , -19.1748 , 3.21955 , 0.049638,0.965224,0.256669 -4.11537 , -18.5898 , 3.83441 , 0.29609,0.952514,-0.0710529 -4.10415 , -18.6302 , 4.18365 , -0.20375,-0.962571,-0.178725 -4.15309 , -18.992 , 4.59537 , -0.329558,-0.852375,-0.406015 -4.2633 , -19.7877 , 5.48123 , -0.129264,0.69264,0.709606 -4.35741 , -20.4009 , 6.0018 , 0.191425,0.553756,0.810377 -4.40171 , -20.7549 , 6.48119 , 0.214515,0.573767,0.790427 -4.65896 , -22.2655 , 7.29832 , -0.597439,-0.742343,-0.303304 -3.53567 , -16.267 , 5.94995 , 0.53265,0.208772,-0.820182 -3.44704 , -15.8736 , 6.14477 , -0.239286,-0.605734,0.758834 -4.55443 , -22.0847 , 8.54186 , -0.499633,-0.687874,-0.526494 -3.11472 , -14.2171 , 6.18993 , -0.215846,-0.4261,0.878549 -2.98551 , -13.5847 , 6.24184 , 0.0635459,-0.997851,-0.0160079 -2.94421 , -13.441 , 6.46501 , 0.0821549,-0.978283,0.190299 -3.17172 , -14.8151 , 7.31674 , 0.777475,0.62012,0.104806 -2.98987 , -13.8758 , 7.22005 , -0.760562,0.641601,-0.0994656 -2.91916 , -13.5634 , 7.37529 , -0.904359,0.353242,-0.23949 -2.88312 , -13.4469 , 7.61529 , -0.121284,0.975708,-0.182437 -3.06267 , -14.5899 , 8.48516 , 0.81739,0.576064,-0.0048952 -2.89658 , -13.7176 , 8.3581 , -0.440383,0.853565,-0.278369 -2.83328 , -13.4447 , 8.52415 , 0.551546,-0.801078,0.232531 -3.17126 , -15.5543 , 10.0358 , -0.359489,-0.817395,0.450148 -2.75083 , -13.1595 , 8.98995 , 0.426553,-0.804096,0.414104 -2.71177 , -13.0324 , 9.23166 , 0.426554,-0.804096,0.414104 -2.65579 , -12.8004 , 9.40697 , -0.648583,0.739919,-0.178494 -3.1053 , -15.6621 , 11.6316 , -0.580066,-0.813713,-0.0373386 -3.00053 , -15.1549 , 11.6865 , -0.580361,-0.731109,-0.358693 -2.95637 , -15.0135 , 11.9865 , -0.715753,-0.696603,0.0494178 -3.31846 , -17.4318 , 14.1872 , -0.682027,-0.516848,-0.517404 -3.21517 , -16.9471 , 14.298 , -0.682027,-0.516848,-0.517404 -3.08739 , -16.2938 , 14.2598 , -0.629351,-0.580233,-0.51696 -3.17268 , -17.017 , 15.334 , -0.639271,-0.623077,-0.450674 -1.27776 , -4.961 , 6.02961 , 0.497629,0.723539,-0.478389 -1.26915 , -5.11141 , 6.73323 , -0.612485,-0.619709,-0.490736 -1.2533 , -5.07427 , 6.89336 , -0.612486,-0.619709,-0.490736 -0.97989 , -3.50472 , 6.15362 , 0.597573,-0.0917109,0.796552 -0.952979 , -3.36501 , 6.14648 , 0.397533,0.408046,-0.821867 -0.93099 , -3.26577 , 6.19335 , 0.536984,0.0877632,-0.839015 -0.858569 , -2.74059 , 5.59868 , 0.289425,0.157198,0.944204 -0.846632 , -2.72228 , 5.74362 , -0.206722,-0.386741,-0.89872 -0.80378 , -2.42632 , 5.44725 , -0.0359772,0.537419,0.842548 -0.786693 , -2.35593 , 5.50275 , -0.342471,0.615629,0.709728 -0.765583 , -2.25008 , 5.49639 , -0.342471,0.615629,0.709729 -0.763748 , -2.32747 , 5.82035 , 0.325293,-0.898202,0.295665 -0.747939 , -2.27827 , 5.92719 , -0.2362,0.872991,-0.426727 -0.777227 , -2.72101 , 7.0148 , -0.962065,-0.209809,0.174386 -0.774775 , -2.8661 , 7.57911 , 0.991426,0.113651,-0.0644876 -0.700598 , -2.1466 , 6.31803 , 0.836313,-0.158466,-0.524852 -0.722306 , -2.60978 , 7.61219 , 0.962263,0.149763,-0.227204 -0.654232 , -1.87963 , 6.19693 , -0.398851,0.00420827,-0.917006 -0.662316 , -2.23461 , 7.33776 , -0.818445,-0.254286,0.515254 -0.614329 , -1.69471 , 6.25036 , -0.601197,0.112614,-0.791126 -0.594484 , -1.59514 , 6.25579 , 0.634271,0.0274858,0.772622 -0.574536 , -1.51241 , 6.30654 , 0.60815,0.191209,0.770449 -0.560845 , -1.60061 , 6.88852 , 0.634844,-0.720466,0.279107 -0.539789 , -1.55311 , 7.09239 , -0.853311,-0.0753937,-0.515922 -0.517482 , -1.44652 , 7.11352 , -0.806366,-0.170332,-0.566358 -0.494554 , -1.45381 , 7.55771 , 0.989036,-0.00230653,-0.147656 -0.472801 , -1.22902 , 7.13087 , -0.122761,-0.657762,0.743155 -0.448719 , -1.19194 , 7.44808 , 0.838889,-0.163021,0.519316 -0.425841 , -1.06508 , 7.39398 , 0.427753,0.29654,-0.853869 -0.389784 , -1.12247 , 8.25997 , -0.541688,-0.822166,-0.174979 -0.376405 , -0.880251 , 7.6231 , 0.417623,-0.0169842,0.908462 -0.354136 , -0.763444 , 7.61244 , -0.326018,0.0929451,-0.940784 -0.330141 , -0.652178 , 7.63887 , 0.529092,-0.206954,0.822941 -0.304202 , -0.55173 , 7.7527 , 0.221053,-0.806549,0.548283 -0.291394 , -0.400583 , 7.43752 , 0.51883,-0.321376,-0.79217 -0.282225 , -0.257134 , 7.07942 , 0.795737,0.357315,0.489008 -0.268899 , -0.140117 , 6.89802 , -0.686599,-0.327336,-0.649179 -0.242835 , -0.0467336 , 7.03338 , -0.964302,0.00188995,0.264799 -0.227587 , 0.0612289 , 6.91751 , -0.906459,-0.236218,-0.350047 -0.207013 , 0.161348 , 6.92976 , 0.877103,-0.479741,-0.0232089 -0.15259 , 0.366176 , 7.16828 , 0.162732,0.509786,0.84477 -0.137361 , 0.469363 , 7.08515 , -0.083754,0.135535,0.987226 -0.117651 , 0.572027 , 7.07016 , -0.114686,0.552097,0.825854 -0.097345 , 0.67544 , 7.053 , 0.137552,-0.128856,0.982077 -0.0864257 , 0.768283 , 6.92514 , 0.538402,-0.57815,0.613079 -0.0638284 , 0.87348 , 6.95438 , 0.972319,-0.232689,0.021266 -0.0068032 , 1.0309 , 7.42739 , -0.171756,0.863652,0.473925 --0.0099566 , 1.13206 , 7.35293 , 0.420828,-0.322324,-0.847945 --0.00521229 , 1.19635 , 7.04026 , -0.00179051,0.259918,0.965629 --0.0220664 , 1.29369 , 6.99287 , 0.0978892,-0.967344,0.2338 -0.931005 , -1.65593 , -0.592977 , 0.0229146,0.212468,0.976899 -0.936959 , -1.69996 , -0.570151 , -0.0194873,0.261653,0.964965 -0.946214 , -1.75872 , -0.558657 , -0.0288466,0.259416,0.965335 -0.954044 , -1.81028 , -0.539441 , -0.0509043,0.215379,0.975203 -0.964881 , -1.87733 , -0.530582 , -0.0726066,0.156916,0.984939 -0.97536 , -1.94497 , -0.519871 , -0.0915565,0.169215,0.981317 -0.98667 , -2.0124 , -0.507191 , -0.0845149,0.183023,0.979469 -0.997613 , -2.08039 , -0.492563 , -0.0629758,0.223144,0.972749 -1.00819 , -2.14893 , -0.475986 , -0.0755671,0.212735,0.974183 -1.02039 , -2.22588 , -0.46253 , -0.094799,0.208625,0.97339 -1.03045 , -2.29452 , -0.441962 , -0.120516,0.211119,0.970002 -1.04307 , -2.37171 , -0.424101 , -0.0915604,0.24361,0.965542 -1.05606 , -2.4579 , -0.408604 , -0.0764906,0.214241,0.973781 -1.06789 , -2.536 , -0.385971 , -0.0997532,0.190354,0.976634 -1.08272 , -2.63189 , -0.369479 , -0.0869911,0.173597,0.980967 -1.09833 , -2.72741 , -0.35024 , -0.0784976,0.151193,0.985383 -1.11663 , -2.84141 , -0.335875 , -0.0938578,0.203156,0.974638 -1.12798 , -2.92035 , -0.302606 , -0.11803,0.185205,0.975586 -1.14942 , -3.05313 , -0.288905 , -0.0787606,0.173819,0.981623 -1.16583 , -3.15852 , -0.260591 , -0.0665136,0.162594,0.984449 -1.18795 , -3.2929 , -0.238565 , -0.0795967,0.175392,0.981276 -1.20878 , -3.42615 , -0.212574 , -0.0778279,0.181644,0.98028 -1.22981 , -3.56058 , -0.181982 , -0.0960375,0.174548,0.979954 -1.25403 , -3.71393 , -0.152637 , -0.0886518,0.181184,0.979445 -1.27998 , -3.87668 , -0.120936 , -0.0780386,0.198694,0.97695 -1.30644 , -4.04946 , -0.0863157 , -0.085105,0.186623,0.978738 -1.33554 , -4.23162 , -0.048148 , -0.0942396,0.193683,0.976527 -1.36604 , -4.4238 , -0.00596726 , -0.0844622,0.189501,0.978241 -1.40055 , -4.64424 , 0.0365202 , -0.0739529,0.197012,0.977608 -1.43633 , -4.8743 , 0.0847718 , -0.0609726,0.191547,0.979588 -1.47635 , -5.12438 , 0.13786 , -0.0514989,0.198553,0.978736 -1.51989 , -5.4029 , 0.194857 , -0.0558403,0.212701,0.97552 -1.56324 , -5.68144 , 0.261611 , -0.0752342,0.18005,0.980776 -1.62445 , -6.06689 , 0.325779 , -0.0267241,0.190274,0.981367 -1.68719 , -6.46169 , 0.40245 , -0.0140891,0.250147,0.968105 -1.74824 , -6.85637 , 0.492847 , -0.0346405,-0.276417,-0.960413 -1.824 , -7.33806 , 0.591757 , -0.0514242,-0.249393,-0.967036 -1.87518 , -7.68078 , 0.713162 , 0.0645138,0.248755,0.966415 -1.93226 , -8.06052 , 0.845526 , 0.0768813,0.25062,0.965028 -2.03903 , -8.74442 , 0.989536 , 0.0497812,0.198545,0.978827 -2.22537 , -9.89899 , 1.16344 , 0.001164,0.178255,0.983984 -2.38583 , -10.9218 , 1.37402 , -0.0244251,0.192595,0.980974 -2.5834 , -12.1783 , 1.63242 , -0.0315687,0.200481,0.979189 -2.81832 , -13.6744 , 1.9509 , -0.0217473,0.20324,0.978887 -3.08082 , -15.3604 , 2.33881 , 0.00820956,0.219549,0.975567 -3.45311 , -17.7341 , 2.85647 , -0.131764,0.558162,0.819203 -3.53176 , -18.459 , 3.60013 , -0.321765,-0.865918,-0.382954 -3.51226 , -18.4639 , 3.93817 , -0.0784442,0.891818,0.445541 -3.52875 , -18.6973 , 4.31753 , -0.0784443,0.891818,0.445541 -3.71259 , -20.2755 , 5.71914 , 0.110677,0.72025,0.684829 -3.74599 , -20.637 , 6.18987 , 0.134485,0.646843,0.750671 -3.27338 , -17.7184 , 5.80859 , -0.578442,0.386229,-0.718493 -3.01571 , -16.1612 , 5.70692 , -0.379351,-0.570764,0.728232 -3.02207 , -16.328 , 6.0709 , -0.379351,-0.570764,0.728232 -2.92798 , -15.8262 , 6.22933 , -0.35307,-0.857932,0.373222 -2.92041 , -15.906 , 6.57016 , 0.265647,0.734292,-0.624697 -2.63252 , -14.0877 , 6.23241 , -0.00951539,-0.391565,0.920101 -2.53073 , -13.5174 , 6.30141 , -0.162132,0.766141,-0.621885 -2.56949 , -13.896 , 6.73197 , 0.349738,-0.925933,-0.14259 -2.6243 , -14.3914 , 7.23114 , 0.158525,-0.205693,-0.965692 -2.51497 , -13.7591 , 7.25595 , -0.401001,0.864548,-0.302911 -2.52547 , -13.9586 , 7.64419 , -0.35236,0.699515,-0.621708 -2.47286 , -13.7107 , 7.82893 , 0.370765,-0.887853,0.272488 -2.429 , -13.5325 , 8.0429 , -0.0885019,0.983043,-0.160606 -2.43579 , -13.7098 , 8.4426 , 0.212238,-0.976288,-0.0426309 -2.37943 , -13.4349 , 8.60625 , 0.458452,-0.888401,-0.0237822 -2.40427 , -13.7615 , 9.10843 , -0.635926,0.766293,0.0916122 -2.48566 , -14.5183 , 9.88929 , 0.738502,-0.596331,-0.314651 -2.37617 , -13.8512 , 9.82823 , -0.216794,0.974784,-0.0528755 -2.31832 , -13.566 , 9.98903 , 0.849531,-0.173484,0.498197 -2.42606 , -14.5516 , 10.9953 , 0.518284,0.845785,0.126608 -2.50045 , -15.311 , 11.9021 , -0.580361,-0.731109,-0.358694 -2.38363 , -14.5835 , 11.784 , -0.695151,-0.682914,0.224487 -2.30543 , -14.1442 , 11.8527 , -0.120207,0.961634,-0.246599 -2.28774 , -14.1937 , 12.2874 , 0.145556,0.962928,-0.227118 -2.29735 , -14.4736 , 12.9205 , -0.357878,-0.933478,0.0232642 -2.6305 , -17.4737 , 15.8487 , 0.489662,0.671005,0.556762 -2.05819 , -14.0853 , 15.8042 , 0.837639,-0.51404,0.184727 -1.98628 , -13.7008 , 15.9154 , 0.837639,-0.51404,0.184727 -1.05271 , -5.00504 , 6.87091 , -0.612485,-0.619709,-0.490736 -1.02749 , -4.8846 , 6.94009 , -0.612485,-0.619709,-0.490736 -1.00491 , -4.78268 , 7.02959 , 0.338367,-0.919053,0.202113 -0.917171 , -4.00298 , 6.29087 , 0.645509,0.0283425,0.763227 -0.886062 , -3.78952 , 6.20869 , -0.228371,0.462297,0.856813 -0.83239 , -3.32459 , 5.7868 , 0.0456052,-0.946057,0.320774 -0.813244 , -3.2314 , 5.83319 , -0.77835,0.414726,-0.471354 -0.788476 , -3.06148 , 5.77159 , 0.0261085,-0.541692,0.840172 -0.769905 , -2.96382 , 5.80479 , 0.900795,-0.355127,0.249908 -0.758775 , -2.96345 , 5.98581 , 0.700009,-0.0571465,0.711844 -0.723521 , -2.64842 , 5.67902 , -0.0437556,-0.376843,0.925243 -0.704298 , -2.5219 , 5.65292 , -0.0827324,-0.994036,0.0710489 -0.68581 , -2.41644 , 5.65794 , 0.615807,-0.787576,0.0224731 -0.675774 , -2.43094 , 5.86995 , -0.568515,0.817414,-0.0928733 -0.668794 , -2.51895 , 6.23283 , -0.135893,0.828367,-0.543454 -0.666944 , -2.7384 , 6.87514 , 0.386898,-0.903228,-0.185715 -0.649367 , -2.67823 , 7.00743 , 0.656718,-0.753336,-0.0347337 -0.613573 , -2.23945 , 6.35411 , -0.475588,-0.137458,0.868862 -0.592188 , -2.06096 , 6.20612 , -0.680487,0.184101,0.709257 -0.576238 , -2.00406 , 6.31954 , 0.535438,-0.111273,-0.837212 -0.557082 , -1.8782 , 6.2752 , -0.456485,-0.0246095,0.889391 -0.539149 , -1.76531 , 6.25587 , -0.158592,0.453773,-0.876891 -0.522837 , -1.77428 , 6.55292 , -0.890608,-0.351568,0.288474 -0.505172 , -1.60268 , 6.3711 , -0.728908,-0.345157,-0.591236 -0.48699 , -1.49754 , 6.36481 , 0.634271,0.0274856,0.772622 -0.465662 , -1.65395 , 7.17635 , 0.899523,-0.384671,-0.207092 -0.444802 , -1.55951 , 7.247 , -0.842684,0.0694687,-0.533908 -0.427567 , -1.39088 , 7.05643 , -0.793346,-0.54761,0.265941 -0.406163 , -1.33216 , 7.25825 , -0.884283,-0.184605,-0.428912 -0.387087 , -1.20882 , 7.21705 , 0.171608,-0.66907,0.723115 -0.36459 , -1.13523 , 7.38789 , 0.311517,0.317574,-0.895602 -0.34604 , -1.01182 , 7.3426 , -0.125315,0.06007,0.990297 -0.312463 , -0.999381 , 7.87426 , 0.128479,0.863305,0.488054 -0.300364 , -0.831604 , 7.59957 , 0.44262,-0.0297065,0.896217 -0.279996 , -0.721054 , 7.63702 , -0.334677,0.163719,-0.928002 -0.248025 , -0.650461 , 7.96961 , 0.967926,0.125148,0.217845 -0.23136 , -0.5156 , 7.85506 , 0.649234,0.741123,-0.170975 -0.231499 , -0.349271 , 7.38025 , 0.608676,-0.413509,-0.677144 -0.22945 , -0.207737 , 7.01129 , 0.795737,0.357315,0.489008 -0.209635 , -0.107972 , 7.05821 , -0.957844,0.0538108,-0.282205 -0.195217 , -0.000133095 , 6.99341 , 0.984379,0.176021,-0.00377192 -0.159413 , 0.0913494 , 7.33601 , -0.177813,-0.82319,-0.539204 -0.129119 , 0.308562 , 7.23741 , -0.884673,0.226139,-0.407695 -0.119421 , 0.412867 , 7.09534 , -0.0257473,0.23652,0.971285 -0.09253 , 0.522254 , 7.24101 , -0.17299,-0.969624,-0.172929 -0.0890601 , 0.617229 , 7.01578 , -0.00431904,0.185934,0.982553 -0.0849602 , 0.70773 , 6.82903 , 0.733975,-0.656856,0.172686 -0.0574229 , 0.820299 , 6.969 , -0.937154,0.34879,0.00940425 --0.00778793 , 1.07527 , 7.35029 , -0.113235,0.181502,0.976849 --0.00335933 , 1.14597 , 7.06812 , -0.106351,0.395654,0.912221 --0.0169155 , 1.24376 , 7.01162 , -0.0289485,0.967825,-0.249954 -0.870085 , -1.56801 , -0.601644 , -0.0522061,0.243019,0.968616 -0.87656 , -1.61924 , -0.587537 , 0.0108257,0.247679,0.968782 -0.884036 , -1.67805 , -0.578425 , -0.00996211,0.205429,0.978621 -0.891168 , -1.73749 , -0.567657 , -0.0266974,0.281784,0.959107 -0.897118 , -1.78879 , -0.549461 , -0.0887495,0.184493,0.978819 -0.906082 , -1.85561 , -0.541719 , -0.0560635,0.144586,0.987903 -0.915414 , -1.92416 , -0.53171 , 0.0877559,-0.149483,-0.984862 -0.923646 , -1.99209 , -0.52007 , 0.08702,-0.216408,-0.972417 -0.932717 , -2.05985 , -0.506559 , -0.0819235,0.232956,0.969031 -0.939415 , -2.12025 , -0.485738 , -0.0723941,0.208601,0.975318 -0.949752 , -2.19701 , -0.473594 , -0.0641255,0.152857,0.986166 -0.961451 , -2.28306 , -0.464081 , -0.114304,0.230997,0.966217 -0.967278 , -2.34415 , -0.437515 , -0.129314,0.245938,0.960621 -0.977657 , -2.42165 , -0.418726 , -0.121758,0.213218,0.969388 -0.988391 , -2.50811 , -0.402203 , -0.0991423,0.194561,0.975867 -0.999677 , -2.59518 , -0.382929 , -0.113262,0.186325,0.975938 -1.01202 , -2.69228 , -0.365117 , 0.101986,-0.169454,-0.980247 -1.02584 , -2.79737 , -0.348577 , 0.104847,-0.19194,-0.97579 -1.03751 , -2.89413 , -0.324828 , 0.101989,-0.201244,-0.974217 -1.05042 , -2.99977 , -0.301959 , -0.113167,0.192326,0.974784 -1.06525 , -3.11538 , -0.279165 , 0.101762,-0.193391,-0.97583 -1.08243 , -3.25007 , -0.259492 , 0.0979464,-0.179974,-0.978783 -1.09886 , -3.37464 , -0.232396 , 0.110463,-0.180636,-0.977327 -1.11594 , -3.50965 , -0.20423 , -0.107624,0.167922,0.979908 -1.13663 , -3.67276 , -0.18055 , 0.116783,-0.181928,-0.976352 -1.15492 , -3.81724 , -0.145939 , 0.103762,-0.20894,-0.972408 -1.17378 , -3.97191 , -0.109089 , 0.0926892,-0.184626,-0.978428 -1.20049 , -4.17411 , -0.0792144 , -0.103595,0.174321,0.979224 -1.22382 , -4.35739 , -0.0381402 , -0.109655,0.184615,0.976675 -1.2489 , -4.55963 , 0.00477868 , -0.105538,0.190761,0.975947 -1.27759 , -4.78106 , 0.0507565 , -0.0950932,0.205214,0.974087 -1.30742 , -5.02289 , 0.101016 , -0.0775324,0.20275,0.976156 -1.34071 , -5.28348 , 0.156184 , -0.0762571,0.200551,0.976711 -1.37523 , -5.56309 , 0.217382 , -0.0541184,0.191116,0.980074 -1.42344 , -5.93042 , 0.277412 , 0.00562502,0.209376,0.977819 -1.47509 , -6.33778 , 0.346124 , 0.0335126,0.250501,0.967536 -1.50703 , -6.60563 , 0.440657 , 0.0627538,0.26408,0.962457 -1.5319 , -6.83349 , 0.547317 , 0.0413802,0.27609,0.960241 -1.58779 , -7.27679 , 0.650469 , 0.0505426,0.240806,0.969256 -1.64963 , -7.77866 , 0.767187 , 0.0243297,0.264598,0.964052 -1.72226 , -8.35762 , 0.900064 , 0.0343449,0.207959,0.977534 -1.83426 , -9.23107 , 1.05356 , 0.00958514,0.166764,0.98595 -1.98007 , -10.3598 , 1.24267 , -0.00770445,0.196496,0.980474 -2.12727 , -11.5151 , 1.47272 , -0.0185057,0.201734,0.979266 -2.29567 , -12.8533 , 1.75345 , -0.0194126,0.21307,0.976844 -2.4952 , -14.442 , 2.09968 , -0.00699851,0.225492,0.97422 -2.71579 , -16.211 , 2.51883 , 0.0420868,0.246057,0.968341 -2.98824 , -18.5655 , 3.3998 , -0.660149,0.719947,0.214196 -2.96446 , -18.5542 , 3.73489 , 0.589509,-0.806843,-0.0385094 -2.94929 , -18.6048 , 4.08119 , 0.246903,-0.880373,-0.404948 -2.98545 , -19.06 , 4.50349 , 0.225563,-0.780639,-0.582858 -3.03817 , -19.8471 , 5.37757 , 0.0938737,0.742112,0.66367 -3.11514 , -20.651 , 5.93603 , 0.110677,0.72025,0.684829 -2.77722 , -18.1211 , 5.68588 , 0.817028,-0.237388,0.525465 -2.63509 , -17.1495 , 5.76671 , -0.0299675,0.0572242,0.997912 -2.3163 , -14.6919 , 5.38332 , -0.192975,-0.342346,0.919543 -2.28446 , -14.5785 , 5.63378 , 0.73723,-0.602072,0.306596 -2.27643 , -14.6697 , 5.9499 , -0.895213,0.377193,-0.237317 -2.15582 , -13.8052 , 5.94057 , -0.511308,0.634595,-0.579529 -2.15192 , -13.9256 , 6.26247 , -0.511308,0.634595,-0.579529 -2.12899 , -13.8912 , 6.53248 , -0.470136,0.880126,0.0659549 -2.09969 , -13.7958 , 6.78022 , 0.324924,-0.940126,-0.102895 -2.11387 , -14.0896 , 7.19454 , 0.542826,-0.834478,0.0947987 -2.0968 , -14.1098 , 7.50259 , 0.52496,-0.746535,0.408782 -2.03393 , -13.7097 , 7.61857 , -0.106649,0.88687,-0.449542 -2.01931 , -13.7567 , 7.94182 , 0.0185561,-0.97967,0.199754 -1.98566 , -13.6291 , 8.18247 , 0.470013,-0.876906,-0.100618 -1.98898 , -13.856 , 8.61283 , 0.513275,-0.857438,-0.0367169 -1.97749 , -13.9428 , 8.98077 , -0.172093,0.981748,0.080957 -1.97637 , -14.1408 , 9.4237 , 0.58481,0.766339,-0.265935 -1.9439 , -14.0385 , 9.70088 , 0.435794,0.900042,0.00277734 -1.88945 , -13.7199 , 9.84423 , -0.278092,0.960538,-0.00557484 -1.87099 , -13.7586 , 10.2131 , 0.555079,-0.64948,0.519676 -1.92814 , -14.5907 , 11.1287 , 0.0976495,0.979139,0.178189 -1.90117 , -14.5709 , 11.4964 , 0.00347495,-0.98644,0.164088 -1.87611 , -14.5745 , 11.8896 , 0.156624,-0.949292,0.272607 -1.82264 , -14.2761 , 12.0637 , 0.0980402,-0.886359,0.452501 -1.80626 , -14.3834 , 12.5505 , -0.146406,0.985321,-0.0877973 -1.74061 , -13.9439 , 12.6099 , 0.0744689,0.986434,0.146295 -1.92292 , -16.3999 , 15.0931 , 0.42989,0.695589,0.57563 -0.76943 , -3.39226 , 4.86325 , -0.5349,0.612701,-0.58179 -1.44653 , -13.6894 , 16.582 , 0.643606,-0.0924029,-0.759758 -0.822803 , -4.63936 , 6.71754 , -0.691549,-0.49962,-0.52167 -0.725626 , -3.28774 , 5.30982 , -0.460731,0.886785,-0.0366036 -0.714317 , -3.26451 , 5.43366 , 0.471934,-0.879984,0.0539019 -0.704717 , -3.28639 , 5.62075 , 0.313615,-0.94603,0.0816912 -0.689685 , -3.20784 , 5.68258 , -0.0591105,0.978678,-0.196712 -0.680497 , -3.2504 , 5.91229 , 0.0239616,-0.936532,0.349764 -0.66583 , -3.1895 , 6.00599 , 0.525386,-0.62856,0.573482 -0.635354 , -2.77276 , 5.57708 , -0.167646,0.452841,0.875688 -0.616852 , -2.59062 , 5.47043 , -0.554484,0.39956,0.729999 -0.601371 , -2.46623 , 5.44365 , -0.417277,0.879823,0.227575 -0.588659 , -2.42614 , 5.55082 , -0.290226,0.956178,-0.0386323 -0.577784 , -2.45842 , 5.78755 , 0.411975,-0.903231,0.120207 -0.567409 , -2.53109 , 6.11392 , -0.274946,-0.890628,-0.362196 -0.558267 , -2.79681 , 6.82339 , -0.439835,0.841698,-0.313194 -0.535652 , -2.29977 , 6.10187 , -0.64896,-0.176199,0.740139 -0.525293 , -2.8293 , 7.40266 , 0.487974,-0.863441,-0.12787 -0.505067 , -2.12393 , 6.18857 , -0.712727,-0.130695,0.689158 -0.491214 , -1.86253 , 5.84635 , -0.97538,-0.0848616,0.203549 -0.477115 , -1.77998 , 5.88298 , -0.893614,-0.420108,0.157998 -0.461069 , -1.77471 , 6.11218 , -0.447516,-0.861163,0.241098 -0.43648 , -2.04502 , 7.06987 , 0.761257,0.192475,-0.619226 -0.42925 , -1.66754 , 6.36796 , 0.978615,-0.167075,-0.119995 -0.416024 , -1.53921 , 6.29698 , 0.271381,-0.463811,0.843345 -0.388213 , -1.67647 , 7.02076 , 0.337318,-0.901533,-0.271025 -0.357102 , -1.7808 , 7.72206 , 0.787396,0.483687,-0.38217 -0.351136 , -1.51616 , 7.24781 , -0.575979,-0.0556991,-0.815565 -0.337499 , -1.3717 , 7.14263 , -0.37546,-0.235677,-0.896374 -0.323233 , -1.24932 , 7.10252 , 0.126193,-0.866798,0.482428 -0.300294 , -1.19506 , 7.34182 , -0.0419665,0.45764,0.888146 -0.285685 , -1.06814 , 7.28771 , -0.150838,0.131066,0.979831 -0.2692 , -0.961804 , 7.31962 , -0.150838,0.131065,0.979832 -0.237933 , -0.919614 , 7.7036 , -0.667965,0.528543,0.523893 -0.224485 , -0.787722 , 7.62419 , 0.356234,-0.402574,-0.843227 -0.167679 , -0.804221 , 8.5308 , -0.150897,0.983792,-0.0968709 -0.157198 , -0.650059 , 8.35962 , -0.846153,0.504936,0.170484 -0.157282 , -0.481498 , 7.99685 , -0.690427,-0.677801,-0.252777 -0.182515 , -0.284492 , 7.19319 , -0.93034,-0.031656,-0.36533 -0.166938 , -0.178021 , 7.20149 , -0.97264,-0.00505678,-0.232261 -0.141002 , -0.08263 , 7.39737 , 0.473099,0.880077,0.0405342 -0.12057 , 0.0250629 , 7.47164 , -0.895154,0.438328,-0.0810394 -0.131894 , 0.147224 , 7.03538 , -0.86622,-0.49919,0.0217363 -0.100366 , 0.248959 , 7.29571 , -0.928776,0.131266,-0.346619 -0.0766355 , 0.359211 , 7.43412 , -0.911793,-0.221473,-0.345809 -0.0666178 , 0.467488 , 7.35136 , 0.786297,0.601601,0.140762 -0.0720275 , 0.563874 , 7.05739 , -0.119281,0.55749,0.82157 -0.0589698 , 0.667707 , 7.04078 , 0.125803,-0.192945,-0.973111 -0.0599848 , 0.755868 , 6.83367 , 0.850426,-0.525164,-0.031281 --0.0108771 , 1.01854 , 7.35681 , -0.473373,0.520446,0.710671 --0.0249256 , 1.12826 , 7.34208 , -0.531166,0.0397524,0.846335 --0.0158235 , 1.19569 , 7.0497 , -0.11901,0.938305,-0.324684 --0.024249 , 1.29214 , 6.98278 , 0.0978891,-0.967344,0.2338 -0.823687 , -1.55182 , -0.614513 , -0.107056,0.322253,0.940581 -0.826922 , -1.59578 , -0.594579 , -0.0622712,0.206831,0.976393 -0.831415 , -1.64645 , -0.58013 , -0.0518516,0.19113,0.980194 -0.837651 , -1.70589 , -0.570455 , -0.0569399,0.192379,0.979667 -0.842801 , -1.76476 , -0.559344 , -0.0764384,0.18745,0.979296 -0.84965 , -1.83228 , -0.552425 , -0.101718,0.165456,0.980958 -0.857108 , -1.9006 , -0.543533 , -0.0388612,0.143707,0.988857 -0.863467 , -1.9683 , -0.533011 , -0.0508664,0.161967,0.985484 -0.869385 , -2.02905 , -0.51484 , 0.0875741,-0.221159,-0.971298 -0.874209 , -2.08922 , -0.495137 , -0.0637687,0.221331,0.973112 -0.882453 , -2.16674 , -0.484107 , -0.0800438,0.209087,0.974616 -0.889575 , -2.24359 , -0.471154 , -0.0582051,0.176684,0.982545 -0.898784 , -2.33087 , -0.460418 , -0.0985504,0.242222,0.965203 -0.903577 , -2.39155 , -0.433097 , 0.0939868,-0.243073,-0.965444 -0.912224 , -2.4788 , -0.417786 , -0.0828705,0.204731,0.975304 -0.920697 , -2.56551 , -0.400139 , -0.107056,0.171247,0.979394 -0.930216 , -2.66223 , -0.383857 , -0.0931187,0.18784,0.977776 -0.939303 , -2.75931 , -0.364751 , -0.074909,0.181427,0.980547 -0.949635 , -2.86532 , -0.346719 , -0.0683305,0.187403,0.979904 -0.961176 , -2.98017 , -0.329276 , -0.115098,0.189136,0.975182 -0.971535 , -3.08687 , -0.304405 , -0.0793321,0.190801,0.978418 -0.982845 , -3.20329 , -0.279634 , -0.0848286,0.174575,0.980983 -0.995077 , -3.32934 , -0.254573 , -0.084237,0.174791,0.980996 -1.00983 , -3.47335 , -0.23205 , -0.0945002,0.170803,0.980763 -1.02377 , -3.61826 , -0.204658 , -0.0948215,0.176712,0.979685 -1.03716 , -3.76312 , -0.172691 , -0.090069,0.206943,0.974198 -1.05208 , -3.91843 , -0.138559 , -0.0900749,0.201918,0.975252 -1.06912 , -4.09213 , -0.104433 , -0.0841441,0.176372,0.98072 -1.08773 , -4.28595 , -0.0691419 , -0.0751807,0.184069,0.980034 -1.10905 , -4.49893 , -0.0317879 , -0.0933188,0.18794,0.977737 -1.12832 , -4.70216 , 0.0146214 , 0.0895659,-0.216675,-0.972127 -1.14794 , -4.91496 , 0.065993 , -0.0810425,0.206769,0.975028 -1.17226 , -5.16663 , 0.117964 , -0.0666723,0.208079,0.975837 -1.19987 , -5.4477 , 0.174041 , -0.0169069,0.25522,0.966735 -1.23585 , -5.80773 , 0.229253 , 0.022887,0.235744,0.971546 -1.26026 , -6.07726 , 0.306744 , -0.0860631,-0.252777,-0.963689 -1.27115 , -6.23838 , 0.404282 , 0.0821594,0.249689,0.964834 -1.30961 , -6.63614 , 0.488344 , 0.0614503,0.269629,0.961002 -1.34783 , -7.04166 , 0.585346 , 0.0256444,0.250198,0.967855 -1.3941 , -7.52581 , 0.692894 , 0.0161788,0.234972,0.971868 -1.44328 , -8.04837 , 0.816324 , -0.0349889,0.220089,0.974852 -1.51104 , -8.74763 , 0.95617 , -0.0136885,0.172242,0.98496 -1.61256 , -9.77228 , 1.12309 , -0.00480027,0.174464,0.984652 -1.71996 , -10.8746 , 1.32813 , -0.011425,0.19933,0.979866 -1.83872 , -12.1008 , 1.57723 , -0.00709255,0.211308,0.977394 -1.9747 , -13.5207 , 1.8814 , -0.00371925,0.218816,0.975759 -2.12129 , -15.0724 , 2.24637 , 0.00677281,0.236271,0.971664 -2.32688 , -17.229 , 2.72469 , 0.0756341,0.335905,0.938854 -2.54184 , -19.5324 , 3.29689 , -0.543754,0.838014,0.0454405 -2.4397 , -19.0041 , 3.92321 , 0.53389,-0.832542,-0.147769 -2.41385 , -18.9926 , 4.26694 , 0.53389,-0.832542,-0.147769 -2.00774 , -15.9522 , 5.24141 , 0.404651,0.0290551,-0.91401 -1.96928 , -15.7535 , 5.4901 , 0.504628,0.302191,-0.808722 -1.89358 , -15.1509 , 5.61439 , 0.883807,-0.200505,0.422709 -1.83923 , -14.7761 , 5.79069 , -0.842198,0.330881,-0.425701 -1.90043 , -15.7138 , 6.39473 , 0.576053,0.81575,0.0521052 -1.82864 , -15.1318 , 6.50062 , -0.894319,0.282107,-0.347287 -1.78493 , -14.8691 , 6.70663 , -0.875682,0.304409,-0.374856 -1.74649 , -14.6584 , 6.92672 , 0.218985,-0.66412,0.714836 -1.71374 , -14.5195 , 7.17189 , -0.00492859,-0.553583,0.832779 -1.67996 , -14.3662 , 7.40961 , -0.0991892,-0.624001,0.775103 -1.6561 , -14.3375 , 7.7019 , -0.302465,0.863926,-0.402676 -1.5892 , -13.7523 , 7.733 , -0.319081,0.900701,-0.294831 -1.60263 , -14.2081 , 8.26209 , 0.461871,-0.874828,-0.14612 -1.57478 , -14.1348 , 8.54155 , -0.36152,0.923698,0.126826 -1.55623 , -14.1889 , 8.8922 , 0.522138,0.822326,-0.226167 -1.50237 , -13.7566 , 8.9767 , 0.705058,0.665301,-0.245495 -1.47086 , -13.6352 , 9.23053 , 0.576203,0.815585,-0.0530174 -1.52146 , -14.7189 , 10.2224 , -0.390719,-0.87242,-0.293637 -1.4592 , -14.1626 , 10.2309 , 0.737553,0.458101,0.496145 -1.42544 , -14.019 , 10.4925 , 0.731886,0.524563,0.434945 -1.41988 , -14.3406 , 11.0737 , 0.728922,0.682436,0.0543495 -1.41151 , -14.6377 , 11.6631 , -0.217866,-0.972366,-0.0839015 -1.36822 , -14.3724 , 11.8623 , 0.403793,0.91485,-0.00106802 -1.3586 , -14.6918 , 12.5047 , 0.451994,-0.795332,-0.403917 -1.35787 , -15.2202 , 13.3411 , 0.0338774,0.781169,0.6234 -1.31961 , -15.0912 , 13.6792 , 0.128725,0.911668,0.390245 -1.28368 , -15.0001 , 14.0552 , -0.37966,-0.890877,-0.249391 -1.3075 , -16.1535 , 15.5352 , 0.468888,-0.404862,0.785003 -1.24586 , -15.6207 , 15.5631 , 0.564496,0.72543,-0.393823 -1.20654 , -15.5419 , 16.0024 , -0.556722,-0.611992,0.561718 -0.666278 , -3.60593 , 4.85489 , -0.463452,0.568859,-0.67942 -0.652775 , -3.48969 , 4.87224 , 0.391298,-0.569029,0.723251 -0.638623 , -3.36799 , 4.87968 , 0.380224,-0.758281,0.529566 -0.991611 , -13.8624 , 16.4051 , 0.643607,-0.0924032,-0.759758 -0.617508 , -3.31987 , 5.1017 , -0.479711,0.839611,-0.254817 -0.606816 , -3.31383 , 5.23964 , -0.528598,0.834078,-0.157791 -0.596707 , -3.30457 , 5.37864 , 0.460731,-0.886785,0.0366037 -0.591369 , -3.55412 , 5.84628 , -0.220681,0.539394,0.812621 -0.574037 , -3.33004 , 5.73044 , 0.123439,0.271495,0.954491 -0.560618 , -3.22483 , 5.76057 , -0.143688,0.964019,-0.223652 -0.547175 , -3.15414 , 5.83704 , 0.632016,-0.668402,0.392165 -0.534707 , -3.14501 , 6.00303 , -0.600355,0.696738,-0.392594 -0.521466 , -3.06933 , 6.07849 , -0.600355,0.696738,-0.392594 -0.506622 , -2.45121 , 5.3116 , 0.428653,-0.206841,-0.879473 -0.494569 , -2.44044 , 5.4606 , 0.083985,0.995851,-0.0350456 -0.481659 , -2.49127 , 5.72203 , 0.232303,-0.972438,-0.0199937 -0.469134 , -2.49395 , 5.9171 , -0.425097,0.90194,-0.0761386 -0.455285 , -2.45725 , 6.0522 , -0.864386,0.430609,-0.25964 -0.443867 , -2.30985 , 5.98414 , -0.118658,-0.825901,0.551187 -0.428795 , -2.30464 , 6.18885 , 0.154108,0.107432,0.982196 -0.422615 , -2.01073 , 5.80985 , 0.637219,-0.502965,-0.583933 -0.418494 , -1.73506 , 5.43151 , 0.239719,0.970575,0.0227739 -0.402101 , -1.76728 , 5.71263 , 0.690204,-0.170153,-0.703325 -0.382713 , -1.82958 , 6.08841 , 0.378683,0.92529,-0.0209045 -0.369311 , -1.76418 , 6.17995 , 0.67121,0.484863,-0.5607 -0.337291 , -1.9378 , 6.90587 , -0.485928,0.156146,0.859937 -0.316511 , -1.92029 , 7.17831 , -0.864512,-0.000214473,0.502612 -0.300378 , -1.82945 , 7.26257 , -0.45382,-0.16531,0.875626 -0.29812 , -1.60436 , 6.9365 , 0.0717641,0.377806,0.9231 -0.253584 , -1.76019 , 7.81936 , -0.698856,-0.351312,0.623041 -0.275814 , -1.36397 , 6.87305 , 0.581737,0.567673,-0.58252 -0.255978 , -1.30789 , 7.07414 , 0.135248,-0.965002,0.224674 -0.223391 , -1.31102 , 7.53703 , -0.032708,-0.868095,0.495319 -0.220546 , -1.13984 , 7.31005 , 0.0453795,-0.0416458,0.998101 -0.207416 , -1.02868 , 7.32364 , 0.413865,0.0143514,0.910225 -0.195705 , -0.913931 , 7.31567 , 0.749391,-0.0289515,0.661494 -0.164239 , -0.865363 , 7.67949 , 0.367032,-0.0820709,-0.926581 -0.11253 , -0.861169 , 8.40819 , 0.331934,-0.927957,0.169457 -0.087367 , -0.757511 , 8.60431 , -0.114488,0.963158,0.243351 -0.122191 , -0.516817 , 7.71872 , -0.277324,-0.745626,0.605916 -0.137839 , -0.349996 , 7.24454 , -0.460593,0.771616,0.438706 -0.0986521 , -0.280134 , 7.69168 , -0.957431,-0.280684,0.0673923 -0.0727462 , -0.178168 , 7.89902 , -0.945688,-0.131233,0.297409 -0.0786322 , -0.0427356 , 7.59628 , 0.814508,0.213233,0.539545 -0.0687968 , 0.0731574 , 7.55046 , -0.926473,-0.308094,-0.216162 -0.0582525 , 0.186646 , 7.5226 , -0.905013,0.158374,-0.394803 -0.0344754 , 0.300209 , 7.69213 , 0.169676,-0.313789,0.934209 -0.0397557 , 0.410765 , 7.441 , -0.854775,-0.364836,-0.369127 -0.0530843 , 0.509809 , 7.08824 , -0.0706943,0.337642,0.938616 -0.0468402 , 0.612373 , 7.02298 , 0.0283794,0.0841214,0.996051 -0.0490192 , 0.703508 , 6.83666 , 0.733975,-0.656856,0.172686 --0.303129 , 1.17949 , 11.0979 , 0.523021,-0.753031,0.39924 --0.343887 , 1.38313 , 11.3571 , 0.744904,-0.667108,0.00921741 --0.0268618 , 1.07137 , 7.33906 , 0.0013496,0.267649,0.963516 --0.0149493 , 1.14344 , 7.05725 , 0.149408,0.395943,0.906039 --0.0215164 , 1.23971 , 6.99164 , 0.0714564,0.959401,-0.272845 -0.777727 , -1.57034 , -0.601627 , -0.111054,0.32588,0.938866 -0.782169 , -1.62979 , -0.594139 , -0.114256,0.268449,0.956494 -0.786509 , -1.68893 , -0.58529 , -0.0953521,0.181978,0.978669 -0.789417 , -1.74084 , -0.568621 , -0.0714639,0.167532,0.983273 -0.794393 , -1.80813 , -0.562818 , -0.0984483,0.205591,0.973674 -0.797098 , -1.85943 , -0.543425 , -0.0412439,0.181558,0.982515 -0.802332 , -1.92811 , -0.533897 , 0.025719,-0.177055,-0.983865 -0.806473 , -1.9962 , -0.522835 , -0.0427911,0.161565,0.985934 -0.812255 , -2.07277 , -0.515186 , -0.0808413,0.218979,0.972375 -0.815817 , -2.13349 , -0.494628 , 0.0943419,-0.222447,-0.970369 -0.820051 , -2.20247 , -0.477602 , -0.0492342,0.184312,0.981634 -0.825666 , -2.28081 , -0.463501 , 0.0385723,-0.178085,-0.983259 -0.831896 , -2.36723 , -0.452154 , -0.0677876,0.215065,0.974244 -0.835223 , -2.43679 , -0.428897 , -0.0878235,0.259895,0.961635 -0.841616 , -2.52432 , -0.41256 , -0.0936805,0.182152,0.978798 -0.8481 , -2.62167 , -0.397902 , -0.0663505,0.197284,0.978098 -0.853888 , -2.70903 , -0.376405 , -0.0595006,0.215612,0.974665 -0.859738 , -2.80612 , -0.356199 , -0.040811,0.184869,0.981915 -0.867802 , -2.91237 , -0.336947 , -0.0439835,0.187583,0.981263 -0.874193 , -3.01961 , -0.314308 , -0.0447138,0.190324,0.980703 -0.881779 , -3.13563 , -0.292063 , -0.0547805,0.203393,0.977563 -0.890294 , -3.2613 , -0.269625 , -0.0490419,0.177696,0.982863 -0.901107 , -3.40593 , -0.249723 , -0.0682144,0.167205,0.98356 -0.909725 , -3.54208 , -0.221931 , -0.0613087,0.177486,0.982212 -0.920569 , -3.69696 , -0.195702 , -0.0447268,0.18991,0.980782 -0.930828 , -3.85174 , -0.164607 , -0.057636,0.205017,0.97706 -0.940254 , -4.00733 , -0.128252 , -0.058696,0.19162,0.979713 -0.954253 , -4.20078 , -0.0966772 , -0.0358398,0.17956,0.983094 -0.967332 , -4.39476 , -0.0586764 , -0.0415129,0.18574,0.981722 -0.980579 , -4.59942 , -0.0161969 , -0.0574945,0.195445,0.979028 -0.994421 , -4.81271 , 0.0309505 , -0.0757409,0.217856,0.973037 -1.00966 , -5.04555 , 0.0817935 , -0.0425538,0.211507,0.97645 -1.02736 , -5.31759 , 0.134067 , 0.0314829,0.238443,0.970646 -1.04933 , -5.62883 , 0.189959 , 0.0688861,0.259943,0.963164 -1.05108 , -5.74173 , 0.281066 , 0.085789,0.232475,0.968812 -1.07106 , -6.05193 , 0.354769 , 0.0736774,0.275016,0.958613 -1.09287 , -6.40107 , 0.435451 , 0.0612302,0.252212,0.965733 -1.11931 , -6.79901 , 0.524519 , -0.000798586,0.236434,0.971647 -1.14802 , -7.24568 , 0.624555 , -0.0350873,0.210754,0.976909 -1.18172 , -7.76987 , 0.736819 , -0.0465504,0.214335,0.97565 -1.21894 , -8.34284 , 0.866423 , -0.0525654,0.202963,0.977775 -1.2751 , -9.17292 , 1.01532 , -0.0400064,0.169398,0.984735 -1.34555 , -10.1996 , 1.19611 , -0.0159495,0.180179,0.983505 -1.42072 , -11.3318 , 1.41599 , -0.0134993,0.199257,0.979854 -1.50531 , -12.6089 , 1.68307 , -0.00591393,0.209842,0.977717 -1.59879 , -14.0604 , 2.00704 , 0.00318147,0.222497,0.974928 -1.70338 , -15.7117 , 2.39918 , -0.0790006,-0.327279,-0.94162 -1.82029 , -17.5824 , 2.87284 , 0.14316,0.325901,0.934502 -1.91019 , -19.1532 , 3.37727 , 0.526813,-0.149058,-0.836809 -2.1293 , -22.6 , 4.19763 , -0.703106,0.698659,0.132357 -1.75457 , -19.62 , 5.94698 , -0.796687,-0.543765,-0.263835 -1.52519 , -16.3496 , 5.44959 , 0.351573,0.499478,0.791782 -1.60444 , -18.0679 , 6.24865 , -0.161353,-0.0541092,-0.985412 -1.62198 , -18.8072 , 6.81945 , -0.263625,0.184926,-0.946734 -1.49878 , -17.1274 , 6.64388 , -0.00110752,0.249335,0.968417 -1.45525 , -16.8019 , 6.86931 , -0.723747,0.0950479,-0.683488 -1.33137 , -14.9801 , 6.5464 , -0.87133,-0.489992,-0.0262962 -1.32101 , -15.2197 , 6.93965 , 0.281794,-0.466734,0.838303 -1.64706 , -22.0525 , 9.98603 , 0.128056,0.989511,0.0668572 -1.21748 , -14.0869 , 7.08911 , -0.526037,-0.828715,0.191092 -1.19311 , -14.0453 , 7.36704 , 0.238881,0.971004,0.00930029 -1.2636 , -16.0471 , 8.59243 , 0.991412,0.0571335,-0.117637 -1.15116 , -14.1424 , 8.01904 , -0.0364065,0.981918,0.185772 -1.11502 , -13.8502 , 8.18369 , -0.212445,0.971314,0.106846 -1.07142 , -13.3541 , 8.23327 , 0.237008,-0.625625,0.74325 -1.03397 , -13.0002 , 8.34461 , -0.248785,-0.935174,0.252102 -1.01637 , -13.1316 , 8.72359 , -0.396622,-0.888006,-0.232673 -0.996089 , -13.2462 , 9.10444 , 0.453006,0.845088,0.283922 -0.996829 , -13.9546 , 9.86508 , -0.229907,-0.877449,-0.420982 -0.952514 , -13.3884 , 9.84665 , 0.28305,0.878823,0.384127 -0.924559 , -13.3177 , 10.1389 , -0.588371,-0.789867,-0.173005 -0.913319 , -13.823 , 10.8358 , 0.316579,0.806913,0.498668 -0.879654 , -13.6351 , 11.068 , 0.478019,0.866071,0.146349 -0.865801 , -14.197 , 11.859 , 0.548018,0.835819,-0.0329049 -0.829475 , -13.9128 , 12.0358 , 0.285605,0.581057,0.762104 -0.829905 , -15.3654 , 13.6011 , 0.161472,0.948501,0.272529 -0.816064 , -16.4612 , 14.9643 , -0.234571,0.230071,0.944481 -0.77514 , -16.24 , 15.2728 , 0.468888,-0.404862,0.785003 -0.737256 , -16.2816 , 15.8171 , 0.468888,-0.404862,0.785003 -0.690502 , -15.6999 , 15.8044 , 0.811424,0.375484,-0.447888 -0.648522 , -15.4052 , 16.0452 , 0.811424,0.375484,-0.447888 -0.528477 , -3.64233 , 4.93528 , 0.61052,-0.559689,0.56037 -0.518158 , -3.46932 , 4.89575 , 0.463452,-0.56886,0.67942 -0.50781 , -3.49149 , 5.0552 , 0.544754,-0.74407,0.386786 -0.496507 , -3.42746 , 5.12747 , 0.487039,-0.838933,0.242868 -0.486544 , -3.38237 , 5.22149 , 0.690778,-0.696268,0.195028 -0.474613 , -3.44556 , 5.44477 , 0.425783,-0.800724,-0.421366 -0.464016 , -3.32996 , 5.46248 , 0.408494,-0.912755,-0.00323137 -0.448885 , -3.51302 , 5.85393 , 0.456848,-0.36363,-0.811827 -0.436292 , -3.48362 , 5.99077 , 0.498453,0.818276,-0.286304 -0.425595 , -3.33145 , 5.96681 , -0.874226,0.435633,-0.214367 -0.409726 , -3.40242 , 6.24921 , -0.728566,0.265867,-0.631274 -0.400356 , -3.23229 , 6.19693 , 0.722348,-0.309195,0.618556 -0.408012 , -2.55922 , 5.37223 , 0.573716,0.764665,0.293494 -0.400305 , -2.41901 , 5.31953 , -0.0939994,0.993222,0.068373 -0.380257 , -2.58366 , 5.75836 , -0.187598,0.982243,0.0025355 -0.369181 , -2.52154 , 5.84198 , -0.372995,0.914396,-0.157336 -0.352321 , -2.55551 , 6.09889 , 0.70521,-0.545276,0.453158 -0.339582 , -2.49562 , 6.20016 , -0.284947,-0.241612,-0.927593 -0.331631 , -2.36378 , 6.16763 , -0.318541,-0.251067,-0.914055 -0.325938 , -2.19857 , 6.06051 , -0.243146,0.633409,0.734625 -0.326184 , -1.97339 , 5.81386 , -0.379471,-0.112906,0.918289 -0.324217 , -1.8072 , 5.67031 , 0.759173,-0.157714,-0.631493 -0.306659 , -1.81357 , 5.90747 , -0.0872711,-0.733868,0.673663 -0.298846 , -1.70641 , 5.88783 , -0.281251,-0.951663,0.123427 -0.285569 , -1.65794 , 6.01445 , 0.340297,0.938776,-0.0538383 -0.239252 , -1.87431 , 6.86172 , 0.0615679,-0.125226,0.990216 -0.220615 , -1.83325 , 7.06784 , -0.879594,-0.428645,0.206341 -0.216234 , -1.67658 , 6.95154 , -0.0604092,0.0889268,0.994205 -0.210925 , -1.54091 , 6.8798 , 0.124687,0.243928,0.961744 -0.203596 , -1.42172 , 6.85285 , -0.749316,0.226472,0.622283 -0.193414 , -1.31755 , 6.87174 , 0.782349,-0.56461,-0.262957 -0.163707 , -1.30603 , 7.24652 , -0.0916442,-0.861196,0.499943 -0.145256 , -1.23215 , 7.41852 , -0.859055,-0.0607108,-0.508271 -0.137781 , -1.10797 , 7.38509 , 0.801924,0.0567811,0.594722 -0.118125 , -1.02695 , 7.55466 , 0.996993,0.0630113,-0.0450961 -0.113084 , -0.89665 , 7.48775 , 0.683366,0.6371,-0.356531 -0.103196 , -0.779702 , 7.47736 , 0.826707,0.549966,-0.11871 -0.102576 , -0.645976 , 7.35624 , -0.844442,-0.212916,-0.491513 -0.0916464 , -0.537259 , 7.38093 , -0.501817,0.467685,0.727633 -0.0885587 , -0.414548 , 7.28484 , -0.580567,0.550035,0.600336 -0.042457 , -0.356934 , 7.83188 , -0.945037,-0.207839,0.252403 -0.0237778 , -0.247772 , 7.96094 , -0.22086,-0.860971,-0.458203 -0.0420707 , -0.102069 , 7.56039 , 0.729007,-0.683849,0.0300018 -0.0220942 , 0.00541665 , 7.70515 , -0.869156,0.102936,-0.483707 -0.0529452 , 0.135933 , 7.16023 , -0.894647,0.0750167,-0.440431 --0.0252041 , 0.23538 , 8.0886 , -0.784299,-0.267413,0.55979 -0.000895217 , 0.354365 , 7.61921 , -0.330471,-0.911182,-0.246043 -0.00552762 , 0.46367 , 7.4373 , 0.597644,0.614751,0.514688 -0.0271045 , 0.558598 , 7.04414 , 0.111243,0.350477,0.929942 -0.028102 , 0.656319 , 6.92871 , 0.807612,-0.572563,-0.14119 --0.000319316 , 0.779408 , 7.16902 , -0.708628,0.214506,-0.672186 --0.354896 , 1.28785 , 11.3254 , 0.744904,-0.667108,0.00921741 --0.0328425 , 1.01629 , 7.35517 , -0.0667469,0.0876219,0.993915 --0.0389498 , 1.12222 , 7.31136 , 0.497565,-0.327464,-0.803241 --0.0242777 , 1.19348 , 7.03908 , -0.11901,0.938305,-0.324684 --0.0266601 , 1.28962 , 6.97279 , 0.00367301,-0.990247,0.139275 -0.734242 , -1.56709 , -0.627802 , -0.0729703,0.310106,0.947897 -0.7342 , -1.60367 , -0.601555 , -0.0816759,0.272854,0.958582 -0.735551 , -1.65464 , -0.587271 , -0.0658193,0.178241,0.981783 -0.738769 , -1.72205 , -0.584142 , -0.0986286,0.191654,0.976494 -0.740657 , -1.77359 , -0.566913 , -0.047145,0.181997,0.982168 -0.743401 , -1.84123 , -0.560376 , -0.0596785,0.200806,0.977812 -0.744857 , -1.89313 , -0.540323 , -0.0611485,0.208427,0.976125 -0.74689 , -1.96194 , -0.530181 , -0.0779881,0.135494,0.987704 -0.750814 , -2.03831 , -0.523844 , -0.0363154,0.203765,0.978346 -0.752267 , -2.09976 , -0.504205 , -0.0226959,0.218214,0.975637 -0.755436 , -2.17718 , -0.493679 , -0.0472162,0.226431,0.972882 -0.75743 , -2.24648 , -0.475823 , -0.0783983,0.216083,0.973222 -0.760256 , -2.31559 , -0.455997 , -0.0421051,0.161625,0.985954 -0.763806 , -2.41161 , -0.44854 , -0.0625351,0.206551,0.976435 -0.765848 , -2.48167 , -0.424137 , -0.064719,0.222312,0.972825 -0.76977 , -2.57775 , -0.411498 , -0.0645421,0.184587,0.980695 -0.772509 , -2.6657 , -0.391431 , -0.0344941,0.202803,0.978612 -0.7758 , -2.75426 , -0.368614 , -0.050976,0.205069,0.977419 -0.779875 , -2.86098 , -0.351302 , -0.0436422,0.18779,0.981239 -0.783247 , -2.95767 , -0.327054 , -0.0373566,0.177149,0.983475 -0.788299 , -3.08374 , -0.310645 , -0.0479477,0.173521,0.983662 -0.792618 , -3.19969 , -0.28691 , -0.0618496,0.178735,0.981951 -0.797624 , -3.32622 , -0.262689 , 0.0703246,-0.15463,-0.985466 -0.802975 , -3.47124 , -0.241051 , -0.0552247,0.175043,0.983011 -0.80832 , -3.60729 , -0.211673 , -0.047469,0.19405,0.979842 -0.813287 , -3.75343 , -0.180663 , -0.046836,0.189812,0.980703 -0.819453 , -3.91791 , -0.15056 , -0.0475053,0.207459,0.97709 -0.824778 , -4.08318 , -0.1151 , -0.037937,0.192729,0.980518 -0.832067 , -4.27761 , -0.081129 , -0.0315385,0.186562,0.981937 -0.839647 , -4.47187 , -0.0409052 , -0.0413464,0.184516,0.981959 -0.848938 , -4.70576 , -0.00219288 , -0.0572946,0.19499,0.97913 -0.856263 , -4.91896 , 0.0477376 , -0.0541297,0.239162,0.96947 -0.866311 , -5.19124 , 0.0947671 , 0.0304189,0.287686,0.957242 -0.870378 , -5.3753 , 0.164803 , 0.0976601,0.27453,0.956606 -0.872957 , -5.54802 , 0.242136 , 0.0722308,0.277357,0.958048 -0.884197 , -5.85956 , 0.309018 , 0.0614562,0.259405,0.963811 -0.895496 , -6.18934 , 0.38434 , 0.00310942,0.239684,0.970846 -0.90833 , -6.55882 , 0.467712 , -0.036628,0.21683,0.975522 -0.921812 , -6.96636 , 0.560862 , -0.0444738,0.216399,0.975292 -0.939978 , -7.46336 , 0.664078 , -0.0466106,0.208818,0.976843 -0.959102 , -8.00786 , 0.782617 , -0.054469,0.209451,0.976301 -0.982802 , -8.67076 , 0.918471 , -0.0551169,0.185122,0.981169 -1.01388 , -9.5103 , 1.07791 , -0.029285,0.172578,0.984561 -1.05486 , -10.5879 , 1.27201 , -0.0222334,0.183887,0.982696 -1.09533 , -11.7108 , 1.5054 , -0.0121342,0.201063,0.979503 -1.1397 , -12.998 , 1.78738 , -0.00433996,0.213207,0.976997 -1.19044 , -14.4876 , 2.12964 , 0.0205619,0.245771,0.96911 -1.24563 , -16.1686 , 2.54238 , 0.182627,0.372253,0.909986 -1.24807 , -16.7672 , 2.8971 , 0.329804,0.330963,0.884134 -1.27369 , -17.9424 , 3.34688 , 0.133498,0.360073,0.923323 -1.26742 , -22.4746 , 6.37684 , 0.747431,-0.564479,0.350301 -1.22714 , -22.2726 , 6.74524 , 0.747431,-0.564479,0.350301 -1.19668 , -22.393 , 7.19736 , 0.747431,-0.564479,0.350301 -1.14269 , -21.7173 , 7.42679 , 0.689762,-0.652178,0.314472 -1.10584 , -21.6037 , 7.80883 , 0.755636,-0.605015,0.250942 -1.08701 , -22.1673 , 8.4132 , 0.714075,-0.670952,0.199801 -1.04156 , -21.7531 , 8.70429 , -0.155174,-0.969867,-0.187825 -1.00571 , -21.6742 , 9.1076 , 0.128056,0.989511,0.0668573 -0.806592 , -14.0162 , 6.57906 , -0.525442,-0.791866,0.311222 -0.783987 , -14.0015 , 6.86114 , 0.266427,0.959585,0.0906247 -0.757863 , -13.9081 , 7.11287 , 0.266427,0.959585,0.0906247 -0.734715 , -13.9374 , 7.42027 , 0.241183,0.960867,0.136255 -0.713701 , -14.0964 , 7.79421 , 0.0419243,-0.968955,-0.243658 -0.691459 , -14.3091 , 8.20642 , -0.39497,0.914071,-0.0920471 -0.679449 , -15.4903 , 9.12954 , 0.789112,0.220192,-0.573427 -0.638167 , -14.1312 , 8.75218 , -0.108708,0.974221,-0.197678 -0.603379 , -13.0776 , 8.49056 , -0.248785,-0.935174,0.252102 -0.578507 , -12.9898 , 8.74704 , -0.0869014,-0.988998,-0.119716 -0.55413 , -13.1876 , 9.17822 , 0.0193289,0.963311,0.26769 -0.528574 , -13.4342 , 9.65593 , 0.194724,-0.800036,-0.567473 -0.501168 , -16.5745 , 12.0398 , 0.298812,-0.849493,-0.434825 -0.472974 , -13.9048 , 10.6547 , 0.387214,-0.893817,-0.226179 -0.443147 , -13.9646 , 11.0609 , -0.521842,0.839146,-0.153346 -0.412742 , -13.9982 , 11.4601 , -0.469513,0.876346,-0.107591 -0.38303 , -13.8065 , 11.7006 , -0.394494,0.918837,-0.0106306 -0.355883 , -13.4617 , 11.8206 , -0.394494,0.918837,-0.0106306 -0.311506 , -14.4442 , 13.0097 , -0.486244,-0.780802,-0.392319 -0.234268 , -17.2026 , 15.7616 , 0.468888,-0.404863,0.785003 -0.224968 , -15.3155 , 14.6441 , -0.560111,-0.813656,-0.155691 -0.196348 , -14.8318 , 14.6921 , 0.306276,0.94895,0.0754245 -0.157793 , -14.8039 , 15.1505 , -0.833682,-0.420913,0.3575 -0.387913 , -4.19537 , 5.38429 , 0.874783,-0.482063,-0.0486809 -0.394025 , -3.53932 , 4.88113 , -0.282459,0.880319,-0.381124 -0.384235 , -3.49248 , 4.96861 , -0.307243,0.899965,-0.309296 -0.371139 , -3.55303 , 5.1728 , 0.568396,-0.776668,0.271502 -0.354489 , -3.67439 , 5.4545 , -0.0979809,-0.994884,-0.0245979 -0.349594 , -3.4986 , 5.4095 , 0.659721,-0.741811,-0.120353 -0.339038 , -3.44094 , 5.49756 , -0.648227,0.754996,-0.0989134 -0.323301 , -3.50076 , 5.73254 , -0.254638,0.828082,0.499439 -0.313797 , -3.41869 , 5.79768 , -0.675317,-0.0829725,0.732846 -0.307789 , -3.26879 , 5.77345 , -0.515155,0.0325627,0.856479 -0.28491 , -3.42087 , 6.15804 , 0.717193,-0.357886,0.597957 -0.278352 , -3.27947 , 6.14793 , -0.728566,0.265867,-0.631274 -0.264896 , -3.24062 , 6.2837 , -0.629918,0.11412,-0.768232 -0.255473 , -3.14241 , 6.33554 , -0.524,0.111305,-0.844414 -0.231624 , -3.24073 , 6.69949 , -0.903444,0.367665,-0.220481 -0.272299 , -2.51339 , 5.71482 , -0.515204,0.844057,-0.148768 -0.210423 , -3.05066 , 6.83559 , -0.696646,0.716436,-0.0374686 -0.191767 , -3.05081 , 7.07609 , -0.978964,0.123662,-0.16229 -0.230697 , -2.44803 , 6.19815 , 0.513013,0.25764,0.818804 -0.230438 , -2.27158 , 6.07574 , 0.318541,0.251067,0.914055 -0.242643 , -2.00794 , 5.76024 , 0.506883,-0.401458,-0.762824 -0.236494 , -1.91693 , 5.78127 , -0.552416,-0.282679,-0.784174 -0.238499 , -1.75645 , 5.64537 , -0.339031,0.862882,0.374824 -0.231559 , -1.67942 , 5.68923 , -0.085101,0.947276,0.308911 -0.205713 , -1.72587 , 6.03741 , -0.320445,-0.943123,-0.0885071 -0.19995 , -1.62753 , 6.04355 , 0.549225,-0.52103,0.65336 -0.13439 , -1.88422 , 7.02307 , 0.772055,0.621218,-0.134237 -0.134056 , -1.73469 , 6.92781 , 0.151236,0.134129,0.979356 -0.12127 , -1.65617 , 7.03782 , -0.0485266,-0.384391,-0.921894 -0.14753 , -1.38737 , 6.53594 , -0.979548,-0.171147,-0.105802 -0.139079 , -1.29666 , 6.58318 , -0.364093,-0.293485,0.883914 -0.0972774 , -1.33673 , 7.12043 , -0.623085,0.715874,-0.315103 -0.127128 , -1.09248 , 6.59569 , 0.00145509,-0.0673285,0.99773 -0.122097 , -0.988475 , 6.58951 , 0.309477,-0.499943,0.808877 -0.0477138 , -1.09856 , 7.58635 , 0.973487,0.183737,-0.136246 -0.0847638 , -0.858697 , 6.96292 , -0.592195,0.724375,0.352967 -0.037951 , -0.855357 , 7.55146 , 0.702044,-0.118322,-0.702235 -0.0348037 , -0.730516 , 7.50103 , 0.877145,-0.0596459,-0.476508 -0.0315246 , -0.61044 , 7.46802 , 0.999648,-0.00616908,-0.0257925 -0.0277565 , -0.492826 , 7.44282 , -0.826802,0.532265,0.181912 --0.0352593 , -0.45914 , 8.19886 , -0.499504,0.783456,0.369718 --0.0151597 , -0.302578 , 7.85283 , -0.757421,0.598971,0.2599 --0.00979083 , -0.172173 , 7.70259 , 0.0906071,0.10332,0.990513 --0.000285182 , -0.044146 , 7.49009 , 0.344554,0.899489,-0.268706 -0.0109953 , 0.0766692 , 7.27533 , -0.188702,0.685377,0.703313 --0.0525673 , 0.172384 , 8.0055 , 0.829997,0.349103,-0.435008 --0.0708355 , 0.294244 , 8.14561 , -0.784299,-0.267413,0.55979 --0.0719661 , 0.417359 , 8.08421 , -0.784299,-0.267413,0.55979 -0.00311891 , 0.506652 , 7.09438 , -0.413042,-0.611731,-0.674671 -0.0029178 , 0.608899 , 7.02974 , -0.370396,0.413371,0.831824 -0.0024202 , 0.709768 , 6.97331 , -0.366279,0.488303,0.792086 --0.0231136 , 0.835158 , 7.20284 , 0.540064,-0.325049,0.776321 --0.383525 , 1.37666 , 11.3242 , 0.744904,-0.667108,0.00921741 --0.0456915 , 1.06944 , 7.33768 , -0.0292658,0.304255,0.952141 --0.0284606 , 1.14339 , 7.06622 , 0.169206,0.354952,0.919445 --0.0285043 , 1.24228 , 7.01089 , 0.0290621,-0.976036,0.21566 -0.688013 , -1.58251 , -0.615531 , -0.0630634,0.272871,0.959981 -0.688209 , -1.63437 , -0.601851 , -0.0578045,0.303075,0.951212 -0.688311 , -1.68594 , -0.586907 , -0.0454964,0.185069,0.981672 -0.68821 , -1.74584 , -0.576881 , -0.0944954,0.190995,0.977032 -0.688961 , -1.80561 , -0.565178 , -0.0329839,0.215532,0.97594 -0.689611 , -1.86506 , -0.552113 , -0.0780324,0.194978,0.977699 -0.689771 , -1.93364 , -0.543088 , -0.0798197,0.17873,0.980655 -0.69077 , -2.00204 , -0.532192 , -0.0841817,0.180792,0.979912 -0.690357 , -2.06328 , -0.513767 , -0.0988382,0.203463,0.974081 -0.690859 , -2.13184 , -0.499171 , -0.065507,0.239074,0.968789 -0.691002 , -2.20097 , -0.482724 , -0.0577833,0.184357,0.981159 -0.692331 , -2.28782 , -0.474216 , -0.0851283,0.222756,0.97115 -0.691941 , -2.35701 , -0.453582 , -0.0830238,0.186949,0.978855 -0.693441 , -2.44498 , -0.440181 , -0.0775898,0.200302,0.976657 -0.693033 , -2.52366 , -0.419768 , -0.0756719,0.211306,0.974486 -0.69395 , -2.61153 , -0.401499 , -0.0773519,0.197702,0.977206 -0.69421 , -2.70802 , -0.385034 , -0.0705909,0.214403,0.974191 -0.694758 , -2.80599 , -0.365231 , -0.0801046,0.192501,0.978022 -0.695588 , -2.9127 , -0.346722 , -0.0718388,0.192462,0.978671 -0.696913 , -3.01986 , -0.324684 , -0.0813423,0.180637,0.98018 -0.697265 , -3.13634 , -0.303182 , -0.0825043,0.16864,0.982219 -0.698547 , -3.26247 , -0.281487 , -0.0894642,0.164452,0.982319 -0.700181 , -3.40711 , -0.262472 , -0.0718216,0.175719,0.981817 -0.700404 , -3.53337 , -0.232502 , -0.068587,0.202203,0.976939 -0.701676 , -3.67919 , -0.204408 , -0.0733537,0.192468,0.978558 -0.70255 , -3.83502 , -0.174391 , 0.0649048,-0.201213,-0.977395 -0.703795 , -3.99093 , -0.139191 , -0.0709371,0.198305,0.97757 -0.704013 , -4.16554 , -0.104261 , -0.0621617,0.189465,0.979918 -0.705662 , -4.35028 , -0.0657064 , -0.0695693,0.181445,0.980937 -0.707135 , -4.57435 , -0.029586 , -0.0806683,0.172625,0.981679 -0.710013 , -4.81802 , 0.0100354 , -0.0264571,0.230212,0.972781 -0.712174 , -5.07073 , 0.0558605 , -0.0323891,-0.295323,-0.954848 -0.706748 , -5.1662 , 0.136326 , 0.0611586,0.313533,0.947606 -0.706866 , -5.3795 , 0.202497 , 0.0323903,0.296505,0.954482 -0.707721 , -5.67041 , 0.26528 , -0.0346262,0.235361,0.971291 -0.709267 , -5.99163 , 0.334754 , -0.0494638,0.219396,0.974381 -0.710641 , -6.34159 , 0.412354 , -0.0570226,0.214863,0.974978 -0.713535 , -6.75032 , 0.497272 , -0.0694242,0.213759,0.974416 -0.714755 , -7.18764 , 0.594381 , -0.0737004,0.21295,0.97428 -0.717632 , -7.70384 , 0.703263 , -0.0705049,0.209941,0.975169 -0.720658 , -8.2892 , 0.828495 , -0.0751883,0.205557,0.975753 -0.725842 , -9.03096 , 0.972453 , -0.0548871,0.187414,0.980746 -0.731938 , -9.91122 , 1.14386 , 0.0302295,-0.178117,-0.983545 -0.739297 , -11.007 , 1.3517 , -0.0242314,0.202912,0.978897 -0.74524 , -12.1695 , 1.60112 , -0.0161218,0.211224,0.977305 -0.750107 , -13.4853 , 1.9008 , 0.00486697,-0.225487,-0.974234 -0.755592 , -15.0626 , 2.26781 , 0.172978,0.37043,0.912612 -0.746193 , -15.9553 , 2.62415 , 0.297002,0.440247,0.847333 -0.724515 , -16.1539 , 2.93279 , 0.297002,0.440247,0.847333 -0.717752 , -17.7045 , 3.42906 , 0.336166,0.264225,0.903979 -0.528703 , -22.7807 , 7.02279 , 0.747431,-0.564479,0.350301 -0.492023 , -22.7027 , 7.43127 , -0.759093,0.562925,-0.326945 -0.454451 , -22.7311 , 7.87247 , 0.772652,-0.558528,0.301755 -0.420219 , -21.8085 , 8.01893 , 0.367091,0.794517,0.483722 -0.381126 , -22.28 , 8.60203 , 0.481019,0.749882,-0.4542 -0.344362 , -22.1544 , 8.99657 , -0.360247,-0.931188,0.0557739 -0.309848 , -21.8166 , 9.31221 , 0.360247,0.931188,-0.0557738 -0.340231 , -15.2221 , 7.15443 , 0.113465,-0.869112,0.481425 -0.331867 , -13.7183 , 6.84522 , 0.138161,0.979563,0.146175 -0.304502 , -13.908 , 7.21535 , -0.117007,-0.980211,-0.159676 -0.279915 , -13.8713 , 7.49449 , 0.0513402,0.952647,0.299713 -0.24149 , -14.6045 , 8.14424 , 0.0293277,-0.83112,0.555319 -0.221379 , -14.2369 , 8.28163 , -0.0207026,-0.984145,0.176152 -0.195942 , -14.1441 , 8.55163 , -0.115085,-0.942801,0.31286 -0.168511 , -14.1252 , 8.86334 , -0.058533,-0.934301,0.351647 -0.164499 , -13.1595 , 8.64525 , 0.566921,-0.622595,0.539421 -0.139924 , -13.0936 , 8.91841 , -0.309702,0.873517,0.375571 -0.107853 , -13.252 , 9.33232 , -0.3918,0.806024,0.443642 -0.0532603 , -14.1095 , 10.2052 , 0.32616,0.92523,-0.193828 -0.0256779 , -14.0135 , 10.4981 , 0.127246,0.984664,-0.119353 --0.00836462 , -14.0848 , 10.9092 , 0.100711,0.982472,0.156861 --0.0509424 , -14.3746 , 11.488 , 0.397989,-0.873362,0.28079 --0.0796054 , -14.2619 , 11.7946 , 0.503643,-0.75785,0.414738 --0.0958068 , -13.8419 , 11.8696 , 0.527044,-0.670487,0.522181 --0.211468 , -15.6625 , 13.7108 , 0.14158,0.954752,0.261541 --0.210945 , -14.8137 , 13.4716 , -0.88722,-0.284942,0.362833 --0.241796 , -14.6622 , 13.7904 , -0.898317,-0.437429,-0.0410318 --0.293616 , -14.9018 , 14.4583 , -0.739847,-0.671499,0.04142 --0.263751 , -13.6249 , 13.7692 , 0.847274,-0.395983,-0.354011 -0.233297 , -4.34717 , 5.43542 , 0.445019,-0.892841,0.0692347 -0.251162 , -3.83397 , 5.08855 , -0.391717,0.282508,-0.875641 -0.245953 , -3.72065 , 5.11694 , -0.538445,0.456744,-0.70814 -0.243902 , -3.57308 , 5.10649 , -0.403701,0.539063,-0.739213 -0.237327 , -3.49505 , 5.16577 , -0.336028,-0.533123,0.776444 -0.224919 , -3.48137 , 5.29796 , 0.497415,0.782956,-0.373574 -0.217255 , -3.41976 , 5.37814 , 0.386344,0.912017,-0.137709 -0.194041 , -3.54045 , 5.68058 , -0.616017,-0.580947,0.532 -0.197621 , -3.32836 , 5.58258 , -0.440437,-0.701505,0.560273 -0.192632 , -3.21737 , 5.60504 , 0.503355,0.761196,-0.408918 -0.177174 , -3.23221 , 5.7937 , -0.81883,-0.522979,0.236667 -0.178393 , -3.06134 , 5.73228 , 0.773263,0.501967,-0.387419 -0.134302 , -3.34136 , 6.31584 , 0.425981,-0.126332,0.895868 -0.0819005 , -3.68004 , 7.02716 , -0.732188,0.638599,-0.23684 -0.0980718 , -3.35371 , 6.75011 , -0.825861,0.154796,0.54221 -0.118956 , -3.00741 , 6.41289 , -0.378249,-0.924587,0.0454658 -0.0530214 , -3.39543 , 7.28564 , -0.53949,0.303435,-0.785416 -0.0509011 , -3.24143 , 7.27064 , -0.818966,0.154102,-0.552763 -0.0453318 , -3.11291 , 7.29589 , -0.818966,0.154102,-0.552763 -0.0571597 , -2.86456 , 7.08865 , -0.643097,0.642087,0.417314 -0.0955536 , -2.44942 , 6.52657 , 0.407688,-0.91288,0.020988 -0.175785 , -1.80203 , 5.42157 , 0.341173,-0.910186,-0.234864 -0.17904 , -1.6751 , 5.34833 , 0.242272,-0.969654,0.03279 -0.167143 , -1.63992 , 5.47333 , 0.242272,-0.969654,0.0327902 -0.12894 , -1.74533 , 5.9481 , -0.276618,0.880072,-0.385947 -0.112209 , -1.71794 , 6.13113 , 0.418301,-0.495258,0.761409 -0.106471 , -1.63517 , 6.18386 , 0.254193,-0.832836,0.491701 -0.0905982 , -1.59522 , 6.35754 , 0.280802,-0.755779,0.591564 -0.0425613 , -1.68581 , 6.93761 , 0.139636,-0.353967,-0.924775 -0.0383029 , -1.57993 , 6.96169 , -0.0606174,0.712426,0.699124 -0.0640638 , -1.35943 , 6.60133 , 0.43179,0.515865,0.739892 -0.0611936 , -1.25608 , 6.60974 , -0.364093,-0.293485,0.883914 -0.0560102 , -1.158 , 6.63562 , -0.0617254,0.238578,-0.96916 -0.0548825 , -1.05039 , 6.6211 , 0.00459057,-0.372635,0.927967 -0.0403232 , -0.981204 , 6.77008 , 0.798821,-0.130211,0.587308 -0.045946 , -0.856451 , 6.67397 , -0.891063,0.162647,-0.423737 -0.0446049 , -0.752133 , 6.66357 , 0.68036,-0.0423558,0.731653 --0.0795773 , -0.901765 , 8.15512 , 0.160068,0.716585,-0.678885 --0.125059 , -0.851478 , 8.66757 , 0.0218573,-0.987248,-0.15768 --0.136513 , -0.727555 , 8.76496 , 0.0357339,-0.516585,0.85549 --0.108461 , -0.548437 , 8.39531 , 0.676266,-0.716163,-0.172554 --0.0912194 , -0.394314 , 8.15065 , 0.585029,-0.786255,-0.198859 --0.0562752 , -0.232759 , 7.69441 , -0.463532,0.273802,0.842717 --0.0552946 , -0.112429 , 7.65251 , 0.606881,-0.78753,-0.107197 --0.0368838 , 0.0144903 , 7.3997 , -0.462406,0.880858,-0.101343 --0.0754831 , 0.11473 , 7.82172 , 0.734637,0.66445,0.137164 --0.0952096 , 0.231739 , 8.02284 , 0.761943,0.25116,-0.596961 --0.0979038 , 0.354267 , 8.02262 , -0.784299,-0.267413,0.55979 --0.0603462 , 0.46391 , 7.55229 , -0.560197,-0.655933,-0.505896 --0.0300937 , 0.562041 , 7.16974 , -0.875947,-0.454048,-0.162967 --0.0223746 , 0.662387 , 7.05473 , 0.838388,0.478744,0.260595 --0.04101 , 0.783365 , 7.24589 , -0.603837,0.251269,-0.756468 --0.0434691 , 0.892293 , 7.23611 , 0.518869,-0.385996,0.762746 --0.0555642 , 1.01422 , 7.34336 , -0.0791233,0.073668,0.994139 --0.0553683 , 1.12282 , 7.31997 , -0.471603,0.473743,0.743746 --0.0334567 , 1.19347 , 7.03819 , 0.0835469,-0.947,0.310179 --0.0305279 , 1.29151 , 6.98235 , 0.0264896,-0.976592,0.213465 -0.640793 , -1.59765 , -0.603089 , -0.0528514,0.272756,0.960631 -0.640117 , -1.65687 , -0.595522 , -0.0767576,0.180307,0.980611 -0.639224 , -1.72437 , -0.592679 , -0.0781325,0.184414,0.979738 -0.636888 , -1.76839 , -0.569549 , -0.123424,0.180666,0.97577 -0.635534 , -1.83615 , -0.563493 , -0.142657,0.213842,0.966396 -0.633959 , -1.89598 , -0.549791 , -0.0891412,0.197408,0.97626 -0.633085 , -1.96414 , -0.540012 , -0.0973678,0.135076,0.98604 -0.631699 , -2.04137 , -0.533981 , -0.0837074,0.239284,0.967335 -0.630252 , -2.10219 , -0.514802 , -0.084774,0.247754,0.965107 -0.628514 , -2.17107 , -0.499374 , -0.0621204,0.202202,0.977372 -0.626229 , -2.2489 , -0.487209 , -0.109572,0.184002,0.9768 -0.624706 , -2.31905 , -0.467472 , 0.107493,-0.171694,-0.979268 -0.622417 , -2.40642 , -0.455721 , -0.119278,0.201124,0.972277 -0.621127 , -2.48516 , -0.436596 , -0.0971216,0.194687,0.976045 -0.618762 , -2.58186 , -0.424287 , -0.0858088,0.213088,0.973258 -0.616152 , -2.65204 , -0.395886 , -0.0918404,0.204351,0.97458 -0.614645 , -2.75817 , -0.382411 , 0.119897,-0.175472,-0.977156 -0.61219 , -2.8552 , -0.361706 , -0.0942179,0.191343,0.976991 -0.609769 , -2.96189 , -0.341903 , 0.11604,-0.182177,-0.976395 -0.607344 , -3.07813 , -0.322514 , -0.0966672,0.171428,0.980443 -0.604644 , -3.20475 , -0.302856 , -0.107872,0.16366,0.980601 -0.602119 , -3.33978 , -0.283031 , -0.0967867,0.173575,0.980053 -0.598382 , -3.46659 , -0.25539 , -0.0827074,0.19301,0.977705 -0.595938 , -3.61203 , -0.22992 , -0.0818686,0.190996,0.978171 -0.591719 , -3.75815 , -0.1997 , 0.0894112,-0.19533,-0.976653 -0.588307 , -3.91355 , -0.167634 , -0.0849355,0.20792,0.974451 -0.58446 , -4.07885 , -0.133158 , -0.10188,0.195517,0.975394 -0.580269 , -4.26388 , -0.0979525 , -0.122796,0.164467,0.978709 -0.576173 , -4.48741 , -0.0658646 , -0.115561,0.198939,0.973175 -0.570721 , -4.70228 , -0.0240144 , 0.0416609,-0.24298,-0.969136 -0.565731 , -4.91582 , 0.0247668 , 0.0157451,0.296385,0.954939 -0.557742 , -5.02124 , 0.0997857 , 0.0255492,0.318079,0.94772 -0.551404 , -5.26436 , 0.156379 , 0.00746481,0.28728,0.957818 -0.544312 , -5.51641 , 0.219662 , -0.0513287,0.236105,0.970371 -0.536268 , -5.82789 , 0.284066 , -0.0739011,0.210771,0.974738 -0.528095 , -6.16826 , 0.35601 , -0.0794199,0.21461,0.973466 -0.518528 , -6.54761 , 0.435935 , -0.0816708,0.205623,0.975217 -0.508191 , -6.98589 , 0.524693 , -0.0910275,0.210763,0.97329 -0.496827 , -7.45366 , 0.627126 , -0.0887849,0.209334,0.973805 -0.483119 , -7.99909 , 0.742503 , -0.086784,0.206529,0.974584 -0.466985 , -8.65286 , 0.874767 , -0.0809872,0.20222,0.975986 -0.449269 , -9.39403 , 1.02963 , -0.0597645,0.192301,0.979514 -0.426751 , -10.4324 , 1.21519 , -0.0359596,0.18713,0.981677 -0.400667 , -11.4667 , 1.43675 , 0.0251469,-0.211274,-0.977103 -0.36919 , -12.7261 , 1.7061 , -0.021197,0.220091,0.975249 -0.332322 , -14.1192 , 2.02907 , -0.11309,-0.331109,-0.936791 -0.294627 , -15.2057 , 2.37485 , 0.308456,0.438373,0.844207 -0.264819 , -15.5177 , 2.67911 , -0.305532,-0.481973,-0.821189 -0.233366 , -15.9131 , 3.00554 , -0.305533,-0.481973,-0.821189 -0.147069 , -19.2329 , 3.75362 , 0.435555,0.593217,0.677042 --0.117768 , -31.0051 , 5.94639 , 0.0648875,0.183689,0.98084 --0.4295 , -43.215 , 8.63825 , 0.542973,0.309668,0.780567 --0.490325 , -42.7808 , 9.33679 , 0.542973,0.309668,0.780567 --0.548737 , -42.2465 , 10.0038 , 0.542973,0.309668,0.780568 --0.259651 , -21.5434 , 8.08418 , 0.203725,0.952878,0.224766 --0.293408 , -21.4254 , 8.46587 , 0.322206,0.94158,0.0980342 --0.331952 , -21.4333 , 8.89351 , 0.33364,0.941486,-0.0478374 --0.122464 , -15.2504 , 6.96642 , -0.404103,0.330401,-0.852957 --0.153555 , -15.3204 , 7.30656 , -0.0805941,-0.927661,0.364622 --0.160388 , -14.8214 , 7.41404 , 0.027791,-0.718276,0.695203 --0.186846 , -14.7801 , 7.70813 , 0.580888,-0.589068,0.561755 --0.18232 , -14.0808 , 7.70041 , -0.820026,0.571763,-0.0253741 --0.217185 , -14.2224 , 8.07567 , 0.26718,-0.838392,0.475094 --0.240338 , -14.0973 , 8.32702 , -0.278995,0.960083,-0.0200815 --0.27026 , -14.1174 , 8.65548 , -0.179901,0.962358,-0.20372 --0.298032 , -14.0951 , 8.96755 , -0.172494,0.963127,-0.206474 --0.319438 , -13.9541 , 9.21667 , -0.45465,0.750256,-0.48001 --0.35587 , -14.0482 , 9.60637 , 0.326999,0.915597,-0.233997 --0.373958 , -13.8453 , 9.82307 , 0.318892,0.945571,-0.064834 --0.411804 , -13.9407 , 10.23 , -0.272334,-0.962158,0.00928271 --0.443919 , -13.9344 , 10.5817 , -0.0301735,0.95312,0.301084 --0.449731 , -13.5357 , 10.6679 , 0.136888,0.987693,0.0756637 --0.530707 , -14.2224 , 11.5267 , 0.478207,-0.870463,-0.116676 --0.570377 , -14.2758 , 11.957 , 0.637425,-0.658647,0.399842 --0.584493 , -13.972 , 12.1229 , 0.162085,-0.285379,0.944609 --0.628105 , -14.0628 , 12.6009 , -0.335589,0.535861,0.774747 -0.107748 , -4.55554 , 5.08634 , -0.365118,-0.228765,0.902416 -0.103228 , -4.44508 , 5.13722 , -0.253374,-0.904398,0.343317 -0.102514 , -4.30584 , 5.15917 , 0.253374,0.904398,-0.343317 -0.0604814 , -4.62054 , 5.59818 , -0.320549,0.947003,0.0208315 -0.0715296 , -4.33893 , 5.48956 , -0.0135598,-0.743959,-0.668087 -0.118369 , -3.70793 , 5.02069 , 0.17506,-0.0151805,0.984441 -0.107187 , -3.68675 , 5.13986 , 0.17506,-0.0151804,0.984441 -0.107657 , -3.55277 , 5.14294 , -0.208749,-0.501238,0.839753 -0.108012 , -3.42631 , 5.15007 , 0.0379705,-0.899637,0.434984 -0.101337 , -3.36042 , 5.22165 , -0.183244,0.885748,-0.426465 -0.0728053 , -3.49832 , 5.53612 , -0.071742,-0.959454,0.272583 -0.0771919 , -3.33072 , 5.49314 , 0.654067,-0.682661,0.325837 -0.0657356 , -3.30765 , 5.62615 , -0.922722,-0.106077,0.370584 -0.0715249 , -3.13702 , 5.56903 , 0.301028,-0.865073,0.401287 -0.0451208 , -3.22177 , 5.85346 , -0.308674,0.90794,-0.283488 --0.0125064 , -3.52663 , 6.46824 , -0.953504,0.190085,0.233876 --0.0279501 , -3.50375 , 6.64119 , 0.820363,0.200711,-0.535462 --0.0339111 , -3.41031 , 6.71472 , -0.891251,0.0629236,0.449124 --0.00266649 , -3.06607 , 6.39004 , 0.221472,0.954489,-0.199753 --0.0275425 , -3.10041 , 6.66093 , 0.686033,-0.393723,-0.611834 --0.0798597 , -3.29673 , 7.22775 , 0.678612,-0.100636,0.72757 --0.100381 , -3.28029 , 7.45481 , 0.22336,0.0620021,0.972762 -0.00105456 , -2.56102 , 6.38223 , 0.308781,-0.949593,-0.0540973 --0.0226402 , -2.5765 , 6.64412 , 0.43353,0.281294,0.85611 -0.101416 , -1.80589 , 5.32418 , -0.601056,0.784949,-0.150291 -0.0961336 , -1.74317 , 5.38723 , 0.55255,-0.827334,-0.101028 -0.092213 , -1.67107 , 5.4312 , 0.55255,-0.827334,-0.101028 -0.0517977 , -1.76595 , 5.86796 , 0.0324987,-0.997075,0.0691715 -0.0281575 , -1.77432 , 6.1338 , -0.728874,-0.00454112,-0.684632 -0.0278605 , -1.67394 , 6.14112 , 0.677279,-0.144585,0.721379 -0.0268823 , -1.57711 , 6.15588 , 0.591929,-0.592895,0.545982 --0.0234306 , -1.66714 , 6.70552 , 0.775771,0.424131,-0.467218 --0.0469712 , -1.64093 , 6.96592 , 0.439888,0.897197,-0.0391842 --0.0276272 , -1.46441 , 6.76088 , 0.198031,-0.636416,-0.745492 --0.00310728 , -1.28007 , 6.50337 , -0.364093,-0.293485,0.883914 --0.00963755 , -1.19779 , 6.57814 , 0.408546,0.264172,-0.873672 --0.0130798 , -1.10471 , 6.62255 , 0.386733,0.0942173,0.917366 --0.0164279 , -1.01191 , 6.66568 , -0.572153,-0.430107,0.698319 --0.0255704 , -0.931259 , 6.77507 , 0.429404,0.283065,0.857605 --0.0281582 , -0.832879 , 6.80549 , -0.297787,0.859958,0.414481 --0.154151 , -0.973312 , 8.1872 , 0.334486,-0.616553,0.712728 --0.153688 , -0.844912 , 8.18866 , 0.334487,-0.616553,0.712728 --0.197935 , -0.786537 , 8.68078 , -0.8287,0.0429366,0.558043 --0.113602 , -0.537194 , 7.76938 , 0.0143913,0.330917,0.94355 --0.119021 , -0.424011 , 7.83233 , 0.452142,-0.421234,-0.786212 --0.10377 , -0.290117 , 7.67525 , 0.608733,-0.378016,-0.69753 --0.0746893 , -0.151159 , 7.36655 , -0.138198,0.692445,0.708111 --0.0791191 , -0.0426407 , 7.41326 , 0.395852,0.824347,-0.404665 --0.0921947 , 0.0640398 , 7.56745 , 0.279513,0.933482,-0.224687 --0.127814 , 0.170853 , 7.969 , 0.70732,0.508218,-0.491338 --0.134657 , 0.292298 , 8.04981 , -0.784299,-0.267413,0.55979 --0.107405 , 0.410419 , 7.76007 , -0.231569,-0.367535,0.900719 --0.0534651 , 0.507951 , 7.16984 , -0.358087,-0.810913,-0.46281 --0.0733919 , 0.627679 , 7.39397 , -0.0291366,0.6908,0.722459 --0.0518526 , 0.722791 , 7.15875 , -0.873016,0.241477,-0.423713 --0.0571324 , 0.83661 , 7.22999 , -0.521319,0.0413856,-0.852358 --0.180559 , 1.08964 , 8.59652 , -0.592601,-0.248448,0.766223 --0.0671754 , 1.07118 , 7.35584 , 0.180042,0.093482,0.979207 --0.0398293 , 1.14185 , 7.05534 , 0.196024,0.422796,0.88477 --0.0347917 , 1.24061 , 7.00041 , 0.0714564,0.959401,-0.272845 -0.593462 , -1.63368 , -0.610403 , -0.0661461,0.150631,0.986375 -0.589459 , -1.68537 , -0.595841 , -0.047777,0.198159,0.979005 -0.587546 , -1.75249 , -0.592438 , -0.0682264,0.178093,0.981646 -0.584185 , -1.81235 , -0.581021 , -0.122645,0.231962,0.964962 -0.580375 , -1.86523 , -0.561858 , -0.0930236,0.214151,0.972361 -0.577628 , -1.93317 , -0.553195 , -0.0964365,0.178618,0.979181 -0.573552 , -2.00146 , -0.542803 , -0.0560453,0.161939,0.985208 -0.57008 , -2.07053 , -0.530341 , -0.0893004,0.246116,0.965118 -0.565599 , -2.12305 , -0.505143 , 0.0754277,-0.234,-0.969306 -0.562431 , -2.20093 , -0.494266 , -0.130089,0.162176,0.978149 -0.558923 , -2.28671 , -0.486459 , -0.082481,0.208705,0.974494 -0.553995 , -2.36532 , -0.471028 , -0.0902706,0.20019,0.97559 -0.549878 , -2.44365 , -0.453335 , -0.0758572,0.19615,0.977635 -0.544911 , -2.53168 , -0.437832 , -0.0984978,0.219975,0.97052 -0.540739 , -2.61941 , -0.419872 , -0.121469,0.215904,0.96883 -0.535181 , -2.70731 , -0.399405 , -0.117109,0.18254,0.976199 -0.530179 , -2.81435 , -0.384341 , -0.115845,0.196372,0.973662 -0.524473 , -2.91136 , -0.362342 , -0.108726,0.196157,0.974526 -0.519021 , -3.02825 , -0.344675 , 0.122355,-0.171957,-0.977476 -0.512354 , -3.14418 , -0.323821 , -0.109406,0.179109,0.977727 -0.506373 , -3.27069 , -0.302479 , -0.108787,0.173793,0.978755 -0.50011 , -3.39634 , -0.277344 , 0.075075,-0.196517,-0.977622 -0.492323 , -3.53298 , -0.251278 , -0.0744779,0.191299,0.978702 -0.484822 , -3.68793 , -0.227018 , 0.0786282,-0.197246,-0.977196 -0.476332 , -3.83366 , -0.194944 , -0.0869716,0.202152,0.975485 -0.467585 , -3.99938 , -0.163307 , -0.100778,0.183598,0.977822 -0.45779 , -4.18376 , -0.131648 , -0.128737,0.157148,0.979148 -0.447734 , -4.39767 , -0.10084 , -0.117492,0.195575,0.973625 -0.435858 , -4.62167 , -0.065114 , -0.0596076,0.261937,0.963242 -0.426079 , -4.75683 , -0.00386484 , -0.00126394,0.300821,0.95368 -0.414076 , -4.94179 , 0.0527402 , -0.028758,0.332977,0.942497 -0.401632 , -5.12541 , 0.11528 , -0.0541215,0.283466,0.957454 -0.386954 , -5.38747 , 0.171931 , -0.0850239,0.22987,0.9695 -0.370398 , -5.67854 , 0.233353 , -0.0882205,0.213261,0.973004 -0.352595 , -5.9995 , 0.301224 , -0.0828137,0.207853,0.974648 -0.333659 , -6.34902 , 0.377003 , -0.08067,0.204277,0.975584 -0.310951 , -6.76775 , 0.459087 , -0.0719602,0.204665,0.976183 -0.286338 , -7.22559 , 0.553048 , -0.072224,0.211963,0.974605 -0.257732 , -7.7312 , 0.660173 , -0.0796653,0.203949,0.975735 -0.226166 , -8.31593 , 0.782582 , -0.0710577,0.203765,0.976438 -0.188149 , -8.99814 , 0.923853 , -0.0710531,0.209768,0.975166 -0.142884 , -9.84789 , 1.08978 , -0.052311,0.192636,0.979875 -0.0869522 , -10.8939 , 1.28968 , -0.0303158,0.212203,0.976755 -0.0254173 , -11.9947 , 1.52815 , 0.0241775,-0.215078,-0.976298 --0.0473699 , -13.281 , 1.81612 , 0.0674642,0.304513,0.950116 --0.118165 , -14.4406 , 2.14005 , 0.299827,0.437288,0.847869 --0.162431 , -14.8857 , 2.43926 , -0.250447,-0.416967,-0.873736 --0.211301 , -15.3941 , 2.76188 , 0.295537,0.466625,0.833618 --0.328288 , -17.3024 , 3.28189 , -0.0267082,0.462297,0.886323 --0.410493 , -18.3767 , 3.74987 , 0.463692,0.742282,0.483743 --0.440635 , -18.3342 , 4.0756 , 0.872121,0.33406,0.357503 --0.470032 , -18.2969 , 4.40275 , -0.929923,-0.35766,-0.0855763 --0.500261 , -18.2542 , 4.72965 , 0.762755,0.642566,-0.0728994 --0.529689 , -18.1955 , 5.0539 , -0.599852,-0.796187,0.079148 --0.55912 , -18.1406 , 5.37945 , -0.994684,0.0373052,-0.0959758 --0.588598 , -18.0896 , 5.70688 , 0.994669,-0.0376487,0.0960055 --0.616561 , -18.0039 , 6.02598 , 0.994326,-0.0434492,0.0970952 --0.645463 , -17.9417 , 6.35207 , -0.994567,0.0395118,-0.0963062 --0.674212 , -17.8823 , 6.68033 , 0.994542,-0.0400799,0.096331 --0.703784 , -17.8174 , 7.00824 , -0.994542,0.0400831,-0.0963317 --0.736232 , -17.7938 , 7.35212 , -0.271242,0.942507,-0.195211 --0.765608 , -17.7262 , 7.68333 , 0.00117958,-0.994224,0.107314 --0.794596 , -17.6526 , 8.01402 , 0.0158593,0.960394,0.278193 --0.638429 , -15.07 , 7.32101 , -0.0152339,-0.919397,0.393037 --0.648358 , -14.8099 , 7.52456 , 0.0442595,-0.881388,0.470316 --0.714524 , -15.2668 , 8.04466 , 0.00490629,-0.910647,0.413156 --0.699311 , -14.6805 , 8.09759 , 0.145856,-0.822795,0.549303 --0.718002 , -14.5356 , 8.3484 , 0.402217,-0.754758,0.51823 --0.733669 , -14.3516 , 8.57827 , 0.233247,-0.891763,0.387756 --0.760512 , -14.3036 , 8.87924 , 0.159719,-0.92239,0.351691 --0.853042 , -14.9813 , 9.59003 , 0.418041,-0.902548,0.103193 --0.798742 , -14.01 , 9.37788 , 0.182309,0.824956,-0.534987 --0.80749 , -13.759 , 9.56386 , 0.319804,0.941989,-0.101896 --0.838251 , -13.7411 , 9.8923 , 0.063322,0.98415,0.165647 --0.940093 , -14.4337 , 10.6928 , -0.131083,0.979784,0.151135 --0.934461 , -14.0218 , 10.7851 , 0.350029,-0.927273,-0.132833 --1.05644 , -14.8651 , 11.7519 , -0.222979,0.778364,0.586881 --1.07477 , -14.6748 , 12.0146 , -0.356188,0.8424,0.404342 --1.1251 , -14.7806 , 12.503 , -0.493141,0.460016,0.738375 --0.0597216 , -4.78181 , 5.0417 , 0.290017,0.155551,-0.944296 --1.0217 , -13.1411 , 12.0191 , 0.535603,0.11865,-0.836093 --0.041226 , -4.37942 , 4.99743 , -0.167462,-0.564843,0.808028 --0.0492722 , -4.33136 , 5.09791 , 0.18803,0.885637,-0.424607 --0.0583699 , -4.28906 , 5.20486 , -0.0744927,0.968671,-0.236914 --0.0775946 , -4.33037 , 5.39315 , -0.153382,-0.973896,0.167331 --0.0829153 , -4.25359 , 5.47327 , -0.274293,-0.895659,0.350084 --0.0428384 , -3.83841 , 5.21237 , -0.528471,-0.453195,-0.717867 --0.0176352 , -3.54444 , 5.0536 , -0.250515,-0.832524,0.494112 --0.0310607 , -3.54057 , 5.19306 , -0.058685,-0.892576,0.447063 --0.0404879 , -3.50682 , 5.30397 , 0.638061,-0.729028,0.247783 --0.0460293 , -3.44453 , 5.38488 , -0.612306,0.783205,-0.108037 --0.0581788 , -3.42436 , 5.51829 , 0.303963,-0.641967,0.703907 --0.116905 , -3.70657 , 6.03321 , -0.92926,0.317373,0.18908 --0.155784 , -3.83717 , 6.38575 , -0.880184,0.270597,0.38994 --0.118981 , -3.49893 , 6.12996 , 0.967577,0.250597,-0.0315578 --0.138532 , -3.50104 , 6.32448 , -0.784436,0.0520352,0.618023 --0.147078 , -3.44253 , 6.43932 , -0.48562,-0.869675,0.0885373 --0.280158 , -4.07539 , 7.59684 , -0.528233,-0.259851,-0.808361 --0.131966 , -3.13691 , 6.39055 , -0.564662,0.7125,0.416534 --0.148436 , -3.11592 , 6.56837 , 0.241756,-0.706066,-0.665601 --0.222008 , -3.38434 , 7.24353 , -0.296845,0.366982,-0.881594 --0.219321 , -3.24951 , 7.26344 , 0.22336,0.0620021,0.972762 --0.116456 , -2.63903 , 6.40785 , 0.672225,0.286937,-0.682481 --0.126898 , -2.58538 , 6.53752 , 0.672225,0.286937,-0.682481 --0.014753 , -1.98864 , 5.59126 , -0.0976189,-0.90463,0.414867 --0.000634387 , -1.84376 , 5.49597 , -0.331776,0.94109,-0.065379 --0.0135593 , -1.81563 , 5.6415 , 0.0791933,-0.939503,0.333261 --0.0748986 , -1.97378 , 6.22452 , 0.615989,0.0684736,0.784773 --0.0778199 , -1.88971 , 6.28179 , 0.80597,-0.174842,0.565547 --0.0738933 , -1.78336 , 6.28242 , 0.802222,-0.147954,0.578402 --0.0557659 , -1.62713 , 6.15033 , 0.460359,-0.571396,0.679394 --0.109273 , -1.71093 , 6.67047 , -0.123407,-0.605311,0.786365 --0.117906 , -1.64094 , 6.78991 , 0.775771,0.424131,-0.467218 --0.130033 , -1.57595 , 6.93674 , -0.865619,-0.0903894,0.492476 --0.106168 , -1.40635 , 6.74931 , -0.0488923,0.242274,0.968975 --0.0757963 , -1.22798 , 6.50047 , -0.000129811,-0.174328,0.984688 --0.0982175 , -1.19 , 6.74802 , -0.61242,0.378029,-0.694288 --0.0751646 , -1.03809 , 6.56042 , 0.142201,0.302315,-0.942541 --0.0986979 , -0.995079 , 6.82587 , -0.229373,0.101021,-0.968082 --0.0785122 , -0.856312 , 6.66272 , -0.536649,0.462859,-0.705527 --0.224438 , -1.02553 , 8.11996 , 0.371686,-0.42966,0.822947 --0.227101 , -0.909204 , 8.19124 , 0.233942,-0.518815,0.822255 --0.251058 , -0.823968 , 8.47734 , -0.0869601,-0.988481,0.123867 --0.186399 , -0.610842 , 7.87454 , -0.321765,0.840873,0.435201 --0.172124 , -0.478263 , 7.7809 , 0.471087,-0.429278,-0.770583 --0.256655 , -0.445236 , 8.67529 , -0.8287,0.0429366,0.558043 --0.145434 , -0.224738 , 7.59612 , -0.616453,0.264413,0.741668 --0.152175 , -0.115596 , 7.70388 , 0.562279,-0.072018,-0.823805 --0.117158 , 0.0150343 , 7.38239 , 0.514493,0.337054,0.788475 --0.168002 , 0.111459 , 7.95382 , 0.70732,0.508218,-0.491338 --0.159865 , 0.233096 , 7.9065 , -0.826796,-0.358157,0.433742 --0.166298 , 0.354189 , 8.01651 , -0.784299,-0.267413,0.55979 --0.126063 , 0.467172 , 7.64657 , -0.848765,-0.513367,0.126693 --0.0982112 , 0.571923 , 7.39443 , 0.388192,0.794979,0.466171 --0.0845024 , 0.677114 , 7.28967 , -0.0101244,0.652221,0.757961 --0.0777317 , 0.784396 , 7.25258 , 0.363863,0.321624,0.874163 --0.447233 , 1.2829 , 11.2874 , 0.744905,-0.667107,0.00921775 --0.0859099 , 1.02404 , 7.43046 , 0.255592,0.842784,-0.473696 --0.0698971 , 1.11891 , 7.28884 , -0.18799,0.53151,0.825928 --0.0436034 , 1.19473 , 7.04733 , 0.361768,0.0945496,0.927461 --0.0336637 , 1.29118 , 6.98209 , -0.050162,-0.976406,0.210037 -0.548825 , -1.60222 , -0.618469 , -0.0537305,0.203617,0.977575 -0.543904 , -1.65384 , -0.604709 , -0.0258159,0.177821,0.983724 -0.539007 , -1.71282 , -0.595969 , 0.00723769,0.167714,0.985809 -0.533774 , -1.77244 , -0.585669 , -0.121855,0.130609,0.983917 -0.529277 , -1.84052 , -0.579777 , -0.0592964,0.20896,0.976125 -0.523714 , -1.89186 , -0.560372 , -0.0857336,0.208322,0.974295 -0.518742 , -1.96017 , -0.551073 , -0.077688,0.166678,0.982946 -0.513396 , -2.029 , -0.539728 , -0.0908333,0.208061,0.973889 -0.507684 , -2.09839 , -0.526435 , 0.101088,-0.228852,-0.968198 -0.501667 , -2.1758 , -0.516699 , -0.10903,0.202673,0.973158 -0.49527 , -2.25373 , -0.504819 , -0.0707472,0.208734,0.97541 -0.489083 , -2.3144 , -0.480475 , -0.0646043,0.171336,0.983092 -0.482486 , -2.41022 , -0.474026 , -0.0520938,0.191793,0.980052 -0.475585 , -2.47934 , -0.450707 , 0.0699443,-0.215576,-0.973979 -0.468364 , -2.56765 , -0.434178 , -0.0869026,0.168048,0.981941 -0.460502 , -2.66463 , -0.419646 , -0.108653,0.179154,0.977803 -0.45196 , -2.77016 , -0.406625 , 0.106126,-0.191458,-0.975746 -0.444657 , -2.85883 , -0.381797 , -0.11853,0.192253,0.974161 -0.435688 , -2.97428 , -0.366464 , -0.100312,0.172173,0.979946 -0.426498 , -3.08179 , -0.343485 , -0.104098,0.178869,0.97835 -0.41581 , -3.20764 , -0.324596 , -0.104256,0.174575,0.979109 -0.405579 , -3.33382 , -0.301692 , -0.0789374,0.217882,0.972778 -0.394289 , -3.46907 , -0.278156 , -0.065953,0.216976,0.973946 -0.383983 , -3.59563 , -0.247051 , -0.0579192,0.181626,0.98166 -0.371007 , -3.75092 , -0.220859 , -0.080352,0.186263,0.979209 -0.357439 , -3.90609 , -0.189704 , -0.0907315,0.191932,0.977205 -0.343009 , -4.09003 , -0.161469 , -0.107871,0.159118,0.981349 -0.327371 , -4.30336 , -0.1345 , -0.102296,0.196505,0.975152 -0.310263 , -4.49812 , -0.0957962 , -0.0294092,0.248858,0.968094 -0.295741 , -4.64373 , -0.0399408 , -0.00940849,0.269706,0.962897 -0.278275 , -4.83802 , 0.0107579 , -0.00807385,0.300008,0.953902 -0.261119 , -5.01142 , 0.071357 , -0.0804042,0.289901,0.953673 -0.239788 , -5.25325 , 0.126338 , -0.0814926,0.240326,0.967265 -0.2173 , -5.51569 , 0.187017 , -0.0785414,0.222312,0.971807 -0.191279 , -5.81546 , 0.250931 , -0.0719543,0.203336,0.976462 -0.161653 , -6.16585 , 0.319841 , -0.0603462,0.21122,0.975574 -0.131002 , -6.53391 , 0.398626 , -0.0626133,0.200541,0.977682 -0.0942855 , -6.96179 , 0.485741 , -0.0522516,0.21004,0.976296 -0.0546508 , -7.42843 , 0.585195 , -0.0560108,0.204281,0.977309 -0.00758802 , -7.98214 , 0.696772 , -0.0628729,0.196175,0.978551 --0.0482111 , -8.65428 , 0.824783 , -0.057431,0.203201,0.977451 --0.10916 , -9.36447 , 0.976011 , -0.0616781,0.206639,0.976471 --0.183889 , -10.2612 , 1.15395 , -0.040444,0.197154,0.979538 --0.268595 , -11.2535 , 1.36588 , -0.0263758,0.209826,0.977383 --0.37286 , -12.4711 , 1.62304 , -0.0120706,0.226341,0.973973 --0.482913 , -13.7222 , 1.92514 , 0.152401,0.354593,0.922517 --0.54566 , -14.2388 , 2.21208 , -0.267426,-0.474141,-0.838853 --0.596094 , -14.5825 , 2.50129 , 0.317329,0.451743,0.833805 --0.692803 , -15.5035 , 2.87025 , -0.132235,-0.396089,-0.908641 --0.917687 , -18.0464 , 3.48969 , 0.0408692,0.840552,0.540187 --2.08602 , -32.3705 , 5.98486 , 0.0909886,0.441409,0.892681 --2.19785 , -33.0317 , 6.68114 , 0.0909886,0.441409,0.892681 --2.59118 , -37.0387 , 8.03136 , -0.615676,-0.288788,-0.733174 --2.86235 , -39.4352 , 9.20018 , -0.575397,-0.333381,-0.746843 --4.79113 , -59.5966 , 15.5372 , 0.107581,0.259906,0.959622 --1.67078 , -23.2852 , 7.62671 , 0.989404,-0.103588,-0.101728 --1.70321 , -23.144 , 8.03079 , -0.96089,0.249081,-0.121035 --1.59462 , -21.5448 , 7.97149 , 0.0932862,0.995441,0.0198849 --1.60952 , -21.2571 , 8.29723 , 0.326472,0.893143,-0.309374 --1.64098 , -21.1429 , 8.6785 , -0.7684,-0.593124,0.240344 --1.73582 , -21.6554 , 9.2965 , -0.959411,0.110618,-0.259413 --1.68514 , -20.7376 , 9.37392 , 0.0299859,-0.905085,0.424171 --1.72835 , -20.7417 , 9.80455 , 0.0299859,-0.905085,0.424171 --1.12694 , -14.7659 , 7.62605 , -0.11633,0.947797,-0.296896 --1.16322 , -14.81 , 7.96265 , -0.120714,0.822708,-0.555499 --1.20396 , -14.8814 , 8.31977 , 0.0750926,-0.726599,0.682946 --1.17404 , -14.3236 , 8.36954 , 0.251984,-0.813829,0.523629 --1.19818 , -14.253 , 8.65594 , 0.269977,-0.839019,0.472398 --1.23937 , -14.3253 , 9.0232 , -0.364928,0.82431,-0.432828 --1.30747 , -14.6051 , 9.51828 , 0.531336,0.835434,-0.140473 --1.22336 , -13.6401 , 9.29561 , -0.207301,0.864457,-0.457975 --1.26923 , -13.7374 , 9.68913 , -0.542877,0.726477,-0.421326 --1.3555 , -14.1343 , 10.2869 , 0.0730528,-0.927809,-0.365833 --1.41421 , -14.3078 , 10.7635 , 0.195545,0.978595,0.0641398 --1.44307 , -14.2401 , 11.0907 , 0.032225,0.992633,0.116795 --1.48648 , -14.2698 , 11.4938 , 0.0177416,0.926197,0.376621 --1.49895 , -14.0757 , 11.7411 , 0.260752,-0.852128,-0.453747 --0.212926 , -4.73734 , 4.92609 , -0.171294,-0.3072,0.936102 --0.206768 , -4.59881 , 4.95786 , -0.0985348,-0.302235,0.948127 --0.199588 , -4.45216 , 4.97934 , 0.135644,-0.572841,0.808365 --0.206463 , -4.39705 , 5.07472 , 0.389554,-0.811379,0.435789 --0.214954 , -4.36175 , 5.18916 , 0.392294,-0.894923,0.212644 --0.230138 , -4.36088 , 5.33739 , -0.0893283,-0.932314,0.350444 --0.289205 , -4.62896 , 5.74774 , -0.334837,-0.931657,0.141067 --0.227469 , -4.15067 , 5.44203 , 0.097943,-0.634898,0.766363 --0.139875 , -3.53159 , 4.9644 , 0.232601,0.762465,-0.603775 --0.155371 , -3.54327 , 5.1176 , -0.0622627,-0.92367,0.378097 --0.191348 , -3.66444 , 5.39741 , -0.825874,0.463878,-0.320545 --0.246767 , -3.88204 , 5.80218 , 0.372717,-0.835437,0.403889 --0.306575 , -4.11149 , 6.2459 , 0.676274,-0.226381,-0.701003 --0.269514 , -3.81169 , 6.06861 , 0.0101621,-0.999424,0.032389 --0.264676 , -3.69265 , 6.10108 , 0.51534,-0.429927,-0.741342 --0.216757 , -3.35028 , 5.83799 , 0.128195,0.894697,0.427882 --0.231324 , -3.33567 , 5.99745 , -0.865202,0.29232,-0.4074 --0.227136 , -3.22528 , 6.02803 , -0.865202,0.29232,-0.4074 --0.244706 , -3.2149 , 6.20405 , -0.920004,-0.28033,-0.273875 --0.22375 , -3.02619 , 6.1154 , -0.93724,-0.044028,0.345894 --0.386371 , -3.66106 , 7.32421 , 0.193996,0.423162,0.885042 --0.436959 , -3.77082 , 7.75813 , 0.193996,0.423162,0.885042 --0.180175 , -2.57439 , 5.97447 , 0.627128,-0.496009,-0.600572 --0.240746 , -2.73376 , 6.46634 , -0.852078,0.00233748,0.523409 --0.214272 , -2.53951 , 6.33502 , 0.580912,-0.796265,-0.168827 --0.151937 , -2.21024 , 5.92465 , -0.820586,-0.0306612,0.5707 --0.083534 , -1.87481 , 5.46 , 0.504716,0.685623,-0.524578 --0.0956544 , -1.84351 , 5.59645 , -0.0976189,-0.90463,0.414867 --0.097743 , -1.77502 , 5.66069 , -0.113602,-0.913148,0.39148 --0.170141 , -1.93931 , 6.27182 , -0.649853,0.0719289,-0.756649 --0.179465 , -1.88466 , 6.40259 , -0.650001,0.456545,-0.607507 --0.283721 , -2.11545 , 7.28334 , 0.339101,0.620592,0.70702 --0.175409 , -1.69488 , 6.47628 , 0.972024,-0.0742925,0.222823 --0.194357 , -1.66076 , 6.68909 , 0.0388099,-0.780256,0.624256 --0.160171 , -1.47761 , 6.46782 , -0.54936,0.366157,-0.751088 --0.18827 , -1.46153 , 6.75504 , -0.418532,-0.00915073,0.908156 --0.176713 , -1.34165 , 6.71855 , 0.289763,0.00358996,-0.957092 --0.199762 , -1.30116 , 6.96733 , 0.645594,-0.249406,0.721807 --0.172319 , -1.14561 , 6.7924 , 0.343542,-0.583967,0.735501 --0.169987 , -1.04975 , 6.83681 , 0.196611,0.15612,0.967972 --0.15802 , -0.93278 , 6.79186 , -0.275928,0.523613,0.806035 --0.233516 , -0.968977 , 7.51527 , -0.0647239,0.17726,0.982033 --0.297671 , -0.964676 , 8.15359 , -0.371686,0.42966,-0.822947 --0.322343 , -0.882273 , 8.44038 , 0.119545,-0.897979,0.423489 --0.29979 , -0.731457 , 8.31281 , 0.320116,0.932758,0.165795 --0.231088 , -0.533522 , 7.75816 , 0.414887,-0.28076,-0.865473 --0.229068 , -0.419889 , 7.81189 , 0.398031,-0.388472,-0.83106 --0.201412 , -0.283489 , 7.62598 , 0.473505,-0.554524,-0.684322 --0.191004 , -0.165122 , 7.59602 , 0.568543,0.239506,-0.787017 --0.159999 , -0.0378202 , 7.37531 , -0.4184,-0.234845,-0.877376 --0.169632 , 0.067039 , 7.54004 , -0.667376,0.284997,0.688031 --0.191899 , 0.176258 , 7.82218 , -0.947528,0.207475,0.243198 --0.160996 , 0.294927 , 7.59519 , -0.0853654,0.212355,0.973457 --0.162728 , 0.411602 , 7.68445 , -0.789579,0.320019,0.523596 --0.146908 , 0.525226 , 7.60261 , -0.583953,0.743052,-0.326914 --0.116709 , 0.628143 , 7.36977 , -0.049363,0.685728,0.726182 --0.100241 , 0.731473 , 7.2644 , 0.226057,0.260847,0.93854 --0.0904667 , 0.839929 , 7.2467 , -0.521319,0.0413855,-0.852358 --0.212924 , 1.09274 , 8.61335 , -0.592601,-0.248448,0.766223 --0.0862895 , 1.07134 , 7.34389 , -0.0438395,0.33679,0.940559 --0.052876 , 1.14373 , 7.06401 , 0.230656,0.306093,0.923637 --0.0408348 , 1.24093 , 6.99979 , 0.0878208,0.976813,-0.195254 -0.498784 , -1.62031 , -0.613486 , -0.066426,0.200199,0.977501 -0.49285 , -1.67159 , -0.599263 , -0.0973278,0.157505,0.98271 -0.485743 , -1.73098 , -0.59008 , -0.0638107,0.119906,0.990732 -0.479602 , -1.79785 , -0.585406 , -0.0787258,0.155177,0.984745 -0.472035 , -1.85751 , -0.57301 , 0.125636,-0.221643,-0.967001 -0.465183 , -1.92555 , -0.564731 , -0.0950963,0.231865,0.968088 -0.45811 , -1.98565 , -0.548806 , 0.0771946,-0.184735,-0.979752 -0.44941 , -2.0631 , -0.542448 , -0.075305,0.181971,0.980416 -0.441855 , -2.12341 , -0.523018 , -0.0319899,0.173594,0.984298 -0.433606 , -2.20116 , -0.512547 , -0.0442776,0.188126,0.981146 -0.42538 , -2.27004 , -0.494726 , -0.0500082,0.23057,0.97177 -0.416591 , -2.34783 , -0.479972 , -0.0704311,0.194341,0.978402 -0.407406 , -2.42608 , -0.46288 , -0.0889093,0.194206,0.976923 -0.397608 , -2.51308 , -0.448176 , -0.0941573,0.193549,0.976562 -0.386486 , -2.61895 , -0.439895 , -0.0876227,0.172753,0.98106 -0.376809 , -2.70693 , -0.419616 , -0.0888981,0.187597,0.978215 -0.365498 , -2.80329 , -0.401163 , -0.115864,0.196063,0.973722 -0.354475 , -2.90113 , -0.379373 , 0.100414,-0.18808,-0.977007 -0.340781 , -3.02543 , -0.366713 , -0.0861481,0.197205,0.97657 -0.32856 , -3.13191 , -0.342442 , -0.0766614,0.173023,0.98193 -0.313843 , -3.26766 , -0.325421 , -0.0739409,0.200947,0.976807 -0.300659 , -3.37456 , -0.294141 , 0.0623413,-0.227848,-0.971699 -0.285674 , -3.50055 , -0.265877 , -0.0546182,0.210236,0.976124 -0.269246 , -3.65461 , -0.242896 , -0.0649734,0.174911,0.982438 -0.251199 , -3.81936 , -0.21772 , -0.109664,0.183494,0.976885 -0.232532 , -3.98391 , -0.187191 , -0.113569,0.163175,0.980039 -0.210941 , -4.18764 , -0.161599 , -0.0733331,0.187944,0.979438 -0.188495 , -4.38088 , -0.127028 , 0.0173021,-0.257947,-0.966004 -0.169471 , -4.53601 , -0.0768611 , 0.00256982,0.261532,0.965191 -0.146311 , -4.71982 , -0.0280291 , 0.0289098,-0.275785,-0.960784 -0.122578 , -4.91311 , 0.0250608 , -0.0655824,0.278452,0.958209 -0.0982289 , -5.11576 , 0.0829924 , -0.0802876,0.255896,0.963365 -0.0675813 , -5.37629 , 0.138009 , -0.0702787,0.238464,0.968605 -0.0365574 , -5.63797 , 0.202299 , -0.0697148,0.222722,0.972386 -0.000821189 , -5.94735 , 0.269098 , -0.0603343,0.212711,0.975251 --0.039163 , -6.28568 , 0.343249 , -0.0586415,0.209677,0.976011 --0.0857965 , -6.69267 , 0.422955 , -0.0535788,0.202255,0.977866 --0.136271 , -7.12879 , 0.514709 , -0.0525563,0.211573,0.975948 --0.193812 , -7.62275 , 0.618076 , -0.0533858,0.203107,0.9777 --0.26157 , -8.22489 , 0.734935 , -0.0521893,0.197192,0.978975 --0.341866 , -8.92405 , 0.870616 , -0.0553522,0.20244,0.977729 --0.431142 , -9.70103 , 1.03081 , -0.0519875,0.205843,0.977203 --0.533941 , -10.5833 , 1.21962 , -0.0288411,0.205014,0.978334 --0.656602 , -11.641 , 1.44566 , -0.0190007,0.211347,0.977226 --0.799414 , -12.8525 , 1.71666 , 0.0804017,0.29373,0.952501 --0.911854 , -13.7301 , 2.00773 , 0.286477,0.445605,0.848155 --0.956774 , -13.9064 , 2.26931 , 0.21258,0.493336,0.843463 --1.03082 , -14.3653 , 2.56747 , 0.26103,0.476852,0.83933 --1.37398 , -17.3244 , 3.18778 , -0.260974,0.321817,0.910125 --3.18828 , -33.1806 , 6.31513 , 0.0829995,0.513557,0.854032 --3.24285 , -33.0968 , 6.9022 , 0.0829994,0.513557,0.854032 --3.30063 , -33.0424 , 7.49576 , 0.248722,0.561625,0.789123 --2.40233 , -23.9177 , 7.06254 , 0.52414,-0.0461424,-0.850381 --2.45006 , -23.9201 , 7.51561 , 0.524139,-0.0461424,-0.850382 --2.19542 , -21.4698 , 7.27084 , 0.287423,0.947816,-0.137963 --2.20529 , -21.2017 , 7.60397 , 0.244087,0.924742,-0.292017 --2.53078 , -23.393 , 8.72978 , -0.89539,0.302573,-0.32669 --2.29755 , -21.224 , 8.44521 , -0.352375,-0.919117,0.17623 --2.48917 , -22.337 , 9.27517 , 0.707482,-0.102352,0.699281 --2.27562 , -20.3882 , 8.97985 , -0.394806,-0.905779,-0.153926 --2.31829 , -20.3719 , 9.39268 , 0.974182,0.0570212,0.218446 --2.17045 , -18.9772 , 9.22551 , -0.958045,-0.19965,0.205645 --1.6494 , -14.9786 , 7.84588 , 0.185658,-0.842825,0.50515 --1.67127 , -14.8903 , 8.12897 , -0.362892,0.803728,-0.47152 --1.69584 , -14.8144 , 8.41982 , 0.491854,-0.776278,0.394299 --2.46414 , -19.7764 , 11.2843 , 0.699303,-0.395521,0.595432 --1.7192 , -14.4986 , 8.92135 , -0.0327196,-0.886734,0.461121 --2.29926 , -18.0641 , 11.2397 , -0.988263,-0.148605,-0.0353919 --2.28416 , -17.6741 , 11.4408 , 0.784608,0.614911,0.0792197 --1.74788 , -13.9816 , 9.64192 , -0.215407,-0.976445,-0.0124314 --1.78354 , -13.9772 , 9.98559 , -0.324343,-0.942758,-0.0775188 --1.82939 , -14.0238 , 10.3697 , -0.13248,0.954236,0.268111 --1.8906 , -14.1601 , 10.8251 , 0.195546,0.978595,0.0641398 --2.07808 , -15.0375 , 11.8178 , -0.324858,0.716291,0.617571 --2.0226 , -14.4601 , 11.8051 , 0.00124705,0.418911,0.908027 --1.83232 , -13.1225 , 11.1958 , -0.647903,-0.530765,0.546362 --1.82258 , -12.8385 , 11.3502 , -0.00783586,0.995601,0.0933681 --0.372079 , -4.55857 , 4.98981 , -0.0985348,-0.302236,0.948127 --0.365472 , -4.44234 , 5.03621 , 0.405812,-0.673215,0.618141 --0.445589 , -4.78887 , 5.48399 , 0.64059,0.401315,-0.654669 --0.428397 , -4.60697 , 5.47965 , 0.727608,0.336717,-0.59767 --2.18018 , -13.582 , 14.0625 , 0.124708,0.925879,0.356646 --0.452699 , -4.55374 , 5.7529 , -0.59705,-0.794625,0.110007 --0.28564 , -3.63217 , 4.99435 , -0.420815,-0.890536,-0.172801 --0.385776 , -4.04805 , 5.57029 , 0.149,-0.651939,0.743488 --0.38119 , -3.9407 , 5.61711 , -0.573192,-0.819144,-0.021308 --0.429928 , -4.08984 , 5.94946 , -0.53225,0.557571,0.637044 --0.454298 , -4.11295 , 6.15351 , -0.648161,0.205648,0.733209 --0.433205 , -3.92727 , 6.11633 , 0.56649,-0.0261337,-0.823654 --0.413721 , -3.75686 , 6.08968 , 0.18675,-0.857316,0.479722 --0.35842 , -3.43042 , 5.85489 , 0.432582,-0.681092,-0.590751 --0.308278 , -3.13805 , 5.64222 , 0.211378,0.592159,0.777604 --0.336422 , -3.17821 , 5.87101 , -0.534389,-0.837423,-0.114678 --0.388238 , -3.3062 , 6.24091 , -0.430583,-0.80321,-0.411644 --0.402732 , -3.28059 , 6.40282 , -0.353791,0.894698,-0.272668 --0.384186 , -3.12067 , 6.36501 , -0.00803678,0.771518,0.636157 --0.425904 , -3.19334 , 6.69449 , -0.310432,0.884886,0.347287 --0.32335 , -2.73008 , 6.14215 , 0.580505,-0.558199,-0.592814 --0.312455 , -2.61063 , 6.14332 , -0.644105,0.587454,0.489926 --0.274112 , -2.39691 , 5.96799 , 0.028364,0.525142,0.850542 --0.267834 , -2.30091 , 5.99755 , 0.142684,0.410192,0.900768 --0.168584 , -1.89795 , 5.41398 , 0.376898,0.912016,0.161785 --0.174692 , -1.85033 , 5.5147 , -0.0171557,-0.974932,0.221842 --0.18741 , -1.82116 , 5.66043 , 0.361673,0.900753,-0.240492 --0.29858 , -2.08111 , 6.47848 , -0.557449,0.632822,-0.537389 --0.271344 , -1.92027 , 6.36431 , 0.663539,-0.419435,0.619508 --0.291616 , -1.89608 , 6.57834 , 0.564443,-0.582358,0.585033 --0.276807 , -1.77061 , 6.54226 , 0.394229,-0.678714,0.619621 --0.239097 , -1.59075 , 6.34482 , 0.816836,0.106124,0.567025 --0.270598 , -1.58891 , 6.65053 , 0.13903,-0.243641,-0.959849 --0.244937 , -1.44223 , 6.53205 , -0.367624,-0.750263,0.549507 --0.251525 , -1.3736 , 6.65749 , -0.290955,-0.682903,0.670066 --0.276713 , -1.34118 , 6.92562 , 0.148096,-0.779635,0.608472 --0.234531 , -1.16594 , 6.67579 , -0.161191,-0.15849,0.974114 --0.261059 , -1.12945 , 6.96192 , 0.475346,0.228906,0.849499 --0.224537 , -0.974488 , 6.75449 , 0.423435,-0.0465748,-0.904728 --0.219599 , -0.87775 , 6.79612 , 0.245818,-0.440447,-0.86347 --0.301861 , -0.91038 , 7.53878 , 0.209344,0.175095,-0.962038 --0.374065 , -0.906512 , 8.21607 , -0.387333,0.386962,-0.8368 --0.375574 , -0.795227 , 8.33534 , 0.119545,-0.897979,0.42349 --0.301363 , -0.596158 , 7.81301 , 0.414887,-0.28076,-0.865473 --0.284156 , -0.469623 , 7.75961 , -0.301029,0.55474,0.775658 --0.259576 , -0.339837 , 7.64455 , 0.372233,-0.683419,-0.627998 --0.234068 , -0.212862 , 7.51704 , -0.534101,0.214356,0.817795 --0.225951 , -0.100601 , 7.53598 , 0.702488,0.0522047,-0.709778 --0.219084 , 0.0115059 , 7.57295 , -0.576432,0.519887,0.630432 --0.20463 , 0.12683 , 7.53821 , -0.866939,-0.121998,0.483254 --0.205945 , 0.239801 , 7.65065 , 0.988492,0.0956371,-0.117203 --0.190759 , 0.355185 , 7.60187 , -0.99491,-0.100754,-0.00171252 --0.175855 , 0.469147 , 7.56111 , -0.212468,0.42945,0.877741 --0.163612 , 0.582231 , 7.5484 , -0.344848,-0.67157,-0.6558 --0.127765 , 0.680581 , 7.29522 , 0.082233,0.635799,0.767462 --0.113982 , 0.787331 , 7.25888 , 0.0566017,0.470043,0.880827 --0.492497 , 1.28277 , 11.253 , 0.744905,-0.667107,0.0092176 --0.101016 , 1.01615 , 7.33892 , -0.0223381,-0.063126,0.997756 --0.0877735 , 1.12287 , 7.30686 , 0.00399674,0.646414,0.762976 --0.0525537 , 1.19569 , 7.04634 , -0.337743,-0.237541,-0.910771 --0.036571 , 1.29183 , 6.98173 , 0.0838441,0.984247,-0.155654 -0.431203 , -1.77815 , -0.609084 , -0.15642,0.202708,0.966666 -0.423463 , -1.82273 , -0.584996 , -0.111019,0.161679,0.980579 -0.413761 , -1.89031 , -0.577858 , -0.0830733,0.202184,0.975818 -0.404816 , -1.95018 , -0.56305 , -0.0907609,0.232657,0.968315 -0.395747 , -2.00967 , -0.546589 , -0.063366,0.200056,0.977733 -0.386013 , -2.0867 , -0.539476 , 0.0728086,-0.196612,-0.977774 -0.375089 , -2.15558 , -0.524838 , 0.0707365,-0.197707,-0.977706 -0.364822 , -2.23266 , -0.513539 , -0.081581,0.225891,0.97073 -0.354357 , -2.30186 , -0.494886 , 0.108144,-0.181307,-0.977462 -0.341709 , -2.39734 , -0.488964 , -0.135183,0.202823,0.96984 -0.330696 , -2.46655 , -0.465931 , -0.113781,0.197153,0.973748 -0.31745 , -2.56188 , -0.454948 , 0.114042,-0.176607,-0.977653 -0.305428 , -2.6403 , -0.431963 , -0.0868785,0.17923,0.979964 -0.290615 , -2.74649 , -0.419467 , -0.118199,0.153298,0.981086 -0.276063 , -2.86135 , -0.407972 , -0.110978,0.215923,0.970083 -0.261538 , -2.94886 , -0.381068 , -0.0862662,0.213895,0.97304 -0.245808 , -3.06515 , -0.362658 , -0.0877412,0.182232,0.979333 -0.228343 , -3.18952 , -0.344711 , -0.0630151,0.170315,0.983373 -0.210124 , -3.31493 , -0.322576 , -0.0631671,0.231959,0.970673 -0.192896 , -3.43168 , -0.292969 , 0.0534138,-0.225222,-0.972842 -0.173114 , -3.56629 , -0.266405 , -0.0859387,0.173324,0.981108 -0.150403 , -3.73052 , -0.244266 , -0.113208,0.151546,0.981946 -0.127315 , -3.89361 , -0.217067 , 0.133801,-0.173934,-0.975625 -0.101753 , -4.07709 , -0.189767 , -0.0995305,0.184267,0.977824 -0.0744568 , -4.27091 , -0.158716 , 0.0215433,-0.228956,-0.973198 -0.0524744 , -4.40613 , -0.107304 , -0.017949,0.257428,0.966131 -0.0258001 , -4.57896 , -0.0603912 , -0.0352981,0.2676,0.962883 --0.00433548 , -4.78145 , -0.0137177 , -0.0586513,0.251485,0.966082 --0.0363064 , -4.99399 , 0.0380686 , -0.0724936,0.263532,0.961923 --0.0707987 , -5.2251 , 0.0935539 , -0.0733505,0.250001,0.965463 --0.106978 , -5.46505 , 0.155122 , -0.0828362,0.236769,0.968028 --0.149237 , -5.7546 , 0.218499 , -0.0846851,0.227146,0.970172 --0.197327 , -6.08164 , 0.286722 , -0.0755028,0.221331,0.972272 --0.249966 , -6.43839 , 0.363369 , -0.0641967,0.212152,0.975126 --0.311522 , -6.86403 , 0.446792 , -0.064224,0.21126,0.975318 --0.376525 , -7.30711 , 0.543354 , -0.0709832,0.212759,0.974523 --0.456623 , -7.85885 , 0.650277 , -0.0638749,0.205675,0.976534 --0.545413 , -8.4679 , 0.774532 , -0.0595012,0.202973,0.977375 --0.650256 , -9.19393 , 0.918562 , -0.054123,0.21096,0.975995 --0.767843 , -9.99559 , 1.08808 , -0.0440063,0.208523,0.977027 --0.906286 , -10.9432 , 1.2892 , -0.0277774,0.212154,0.976842 --1.0661 , -12.0255 , 1.52925 , -0.00318347,-0.243022,-0.970016 --1.22661 , -13.0812 , 1.80588 , 0.226638,0.448204,0.864724 --1.30918 , -13.5077 , 2.07304 , 0.257464,0.42677,0.866937 --1.39743 , -13.9677 , 2.35908 , 0.236176,0.451523,0.860435 --1.64141 , -15.565 , 2.78787 , 0.0269791,0.283356,0.958635 --2.07084 , -18.4663 , 3.44136 , -0.367293,0.385302,0.846545 --4.23315 , -33.2579 , 6.53814 , -0.0803294,-0.708054,-0.701575 --3.69204 , -29.0085 , 6.37157 , -0.0305441,-0.474843,0.87954 --4.33869 , -33.0499 , 7.71408 , -0.0334264,-0.997239,-0.0663129 --4.91836 , -36.527 , 9.08547 , 0.502532,0.345549,0.792501 --4.98125 , -36.4397 , 9.74563 , 0.502532,0.345548,0.792501 --5.03559 , -36.2929 , 10.3933 , -0.615208,-0.448348,-0.648462 --2.85731 , -21.5968 , 7.04813 , 0.287423,0.947815,-0.137963 --2.80057 , -20.9333 , 7.26977 , -0.745477,-0.32545,0.581676 --2.89325 , -21.2319 , 7.77118 , 0.562663,0.408825,-0.718521 --2.7309 , -19.924 , 7.75523 , -0.831673,-0.217691,0.510814 --2.77732 , -19.9392 , 8.15846 , 0.991563,-0.0882368,-0.0949627 --2.53299 , -18.1762 , 7.90635 , 0.775164,0.614816,0.145333 --3.03464 , -20.9384 , 9.3622 , 0.417286,-0.176052,0.891559 --3.10032 , -21.0407 , 9.83947 , 0.263232,-0.165321,0.950462 --2.73715 , -18.631 , 9.23916 , -0.939459,-0.269676,0.211403 --2.74207 , -18.3995 , 9.53373 , 0.999117,0.031087,-0.0282777 --2.71543 , -17.995 , 9.74254 , -0.908263,-0.287625,0.303858 --3.02352 , -19.4711 , 10.8767 , -0.966451,0.250536,-0.0566106 --2.57115 , -16.6992 , 9.87486 , -0.988715,0.063581,-0.135649 --2.3335 , -15.168 , 9.42877 , -0.207302,0.963581,-0.168929 --2.34613 , -15.0237 , 9.70452 , 0.454702,-0.756188,0.470559 --2.18228 , -13.9396 , 9.42677 , 0.277598,-0.827521,0.488004 --2.22973 , -13.9902 , 9.80017 , 0.657474,-0.721857,-0.215989 --2.8163 , -16.8101 , 11.9505 , -0.0755217,-0.316227,0.945673 --2.88765 , -16.9258 , 12.4576 , 0.0215804,-0.626061,0.779476 --2.62484 , -15.363 , 11.8248 , 0.833108,-0.552604,-0.0236483 --2.65255 , -15.2732 , 12.1739 , -0.147804,0.294525,0.944145 --2.80566 , -15.7866 , 12.9763 , -0.501131,0.0634286,-0.863044 --2.40581 , -13.6335 , 11.7655 , 0.1358,0.400762,0.906062 --2.22777 , -12.5854 , 11.3265 , 0.0749984,0.951401,-0.298684 --0.596604 , -4.81014 , 5.26682 , -0.0485949,-0.308621,0.949943 --0.601162 , -4.74993 , 5.36924 , -0.244503,-0.457287,0.855048 --0.578185 , -4.56924 , 5.36602 , 0.0277645,-0.509357,0.860107 --0.566923 , -4.44106 , 5.40462 , 0.332282,-0.449274,0.829302 --0.571477 , -4.38482 , 5.50824 , -0.288349,-0.94349,0.163347 --0.609667 , -4.47301 , 5.7569 , -0.324083,-0.945922,0.0142139 --0.625588 , -4.45808 , 5.91125 , -0.390398,-0.867967,0.306957 --0.63419 , -4.41184 , 6.0378 , 0.0513423,-0.636504,0.769563 --0.615445 , -4.2568 , 6.04766 , -0.422505,-0.0623959,0.904211 --0.561711 , -3.95915 , 5.89008 , 0.88302,-0.0226747,-0.468787 --0.536468 , -3.78365 , 5.85942 , 0.637437,0.743363,-0.202695 --0.567008 , -3.82305 , 6.08395 , 0.620206,0.0021813,-0.784436 --0.553607 , -3.69697 , 6.10993 , -0.572722,0.0516262,0.818122 --0.436456 , -3.18301 , 5.62185 , -0.546934,-0.701535,-0.456849 --0.429743 , -3.09016 , 5.66717 , -0.549878,-0.802935,-0.230062 --0.533662 , -3.3887 , 6.26721 , -0.20491,-0.372839,0.904988 --0.548236 , -3.36285 , 6.4302 , 0.789084,-0.611645,-0.0568974 --0.598499 , -3.45111 , 6.77562 , -0.218763,-0.975775,0.00236579 --0.574211 , -3.28666 , 6.74121 , 0.691545,-0.722314,0.0052733 --0.568908 , -3.18559 , 6.8042 , -0.00992296,0.84371,0.536708 --0.661616 , -3.39658 , 7.40401 , 0.230885,-0.890847,-0.391259 --0.365972 , -2.39054 , 5.8636 , 0.142684,0.410192,0.900768 --0.337589 , -2.23517 , 5.78016 , -0.835859,-0.169677,0.522062 --0.363478 , -2.24184 , 6.00083 , 0.148742,0.654364,0.741407 --0.268759 , -1.90252 , 5.53069 , 0.399087,-0.862381,-0.311493 --0.239688 , -1.7559 , 5.42614 , 0.35856,0.909382,0.210854 --0.576268 , -2.59795 , 7.52089 , -0.324422,0.324596,-0.888475 --0.383225 , -2.00327 , 6.44349 , 0.295628,-0.485584,0.822686 --0.376484 , -1.90823 , 6.4842 , 0.568327,0.493391,-0.65846 --0.524411 , -2.18912 , 7.50191 , -0.554295,-0.0807379,-0.828395 --0.373089 , -1.74332 , 6.6348 , 0.642724,-0.411848,0.645978 --0.376086 , -1.67118 , 6.74595 , 0.0760233,0.424516,0.902223 --0.333091 , -1.49662 , 6.55462 , -0.603403,0.301134,-0.738393 --0.336361 , -1.42305 , 6.66224 , -0.288535,-0.394124,0.87259 --0.325108 , -1.3194 , 6.67379 , -0.308046,-0.395849,0.865108 --0.321027 , -1.23084 , 6.74085 , 0.0752605,0.183014,-0.980225 --0.314921 , -1.13554 , 6.78711 , 0.384446,0.818539,-0.426842 --0.294491 , -1.01683 , 6.7353 , 0.0103374,-0.206645,0.978361 --0.280635 , -0.911073 , 6.72972 , 0.335042,-0.454543,-0.825311 --0.317251 , -0.877337 , 7.09188 , 0.70462,-0.149309,0.693698 --0.469239 , -0.985717 , 8.33356 , 0.569839,-0.244748,0.784463 --0.449271 , -0.849997 , 8.30748 , -0.312103,0.59072,-0.744071 --0.405104 , -0.688989 , 8.0826 , -0.725294,-0.565456,-0.392692 --0.338881 , -0.515296 , 7.6868 , 0.786046,-0.134954,-0.603258 --0.313716 , -0.388668 , 7.60283 , 0.415146,-0.620189,-0.665597 --0.289034 , -0.265575 , 7.51642 , -0.488236,0.529756,0.69353 --0.272049 , -0.149753 , 7.48711 , -0.566392,0.0699316,0.821164 --0.261158 , -0.038344 , 7.51539 , 0.549525,-0.373465,-0.74736 --0.239873 , 0.0777733 , 7.4521 , 0.668199,-0.452209,-0.590777 --0.227076 , 0.189014 , 7.45651 , -0.855897,-0.133785,0.499543 --0.222606 , 0.301557 , 7.53832 , -0.914554,-0.257989,0.311502 --0.207879 , 0.414669 , 7.53885 , 0.567748,0.135479,-0.811978 --0.214791 , 0.535057 , 7.72598 , -0.0711214,-0.90435,0.420825 --0.162665 , 0.632221 , 7.36491 , -0.000204977,0.791221,0.61153 --0.143668 , 0.739053 , 7.32 , 0.00291647,0.260745,0.965403 --0.525711 , 1.1943 , 11.2377 , -0.744904,0.667107,-0.00921764 --0.23984 , 1.09055 , 8.56045 , -0.592601,-0.248448,0.766223 --0.109223 , 1.07746 , 7.38151 , -0.349294,0.260888,-0.899962 --0.0676166 , 1.14803 , 7.0823 , -0.652632,-0.364872,-0.664033 --0.0466493 , 1.24222 , 6.99906 , 0.148677,0.983042,-0.107345 -0.375562 , -1.78499 , -0.597088 , -0.075386,0.244157,0.966801 -0.363981 , -1.85231 , -0.59097 , -0.0800891,0.248441,0.965331 -0.354124 , -1.91214 , -0.577061 , -0.0582485,0.244722,0.967842 -0.342946 , -1.97236 , -0.56152 , -0.0956149,0.187036,0.977689 -0.330606 , -2.04799 , -0.555842 , -0.0776942,0.194112,0.977898 -0.320075 , -2.10017 , -0.531172 , 0.103199,-0.194297,-0.975499 -0.305844 , -2.18507 , -0.526831 , -0.100716,0.173781,0.979621 -0.293513 , -2.25406 , -0.509393 , -0.119723,0.194391,0.973591 -0.279446 , -2.34007 , -0.500061 , 0.124543,-0.188026,-0.974236 -0.265416 , -2.41724 , -0.483574 , -0.116847,0.207213,0.971293 -0.25053 , -2.5041 , -0.469178 , 0.123277,-0.206109,-0.970733 -0.235234 , -2.59138 , -0.45225 , -0.123455,0.185097,0.974935 -0.219288 , -2.6873 , -0.437223 , 0.155004,-0.166736,-0.973742 -0.200007 , -2.80144 , -0.427888 , -0.110256,0.200323,0.973506 -0.183645 , -2.88883 , -0.402588 , -0.0896894,0.25493,0.962791 -0.165857 , -2.99477 , -0.382351 , -0.0783447,0.209917,0.974575 -0.146639 , -3.10077 , -0.35902 , -0.0847294,0.198277,0.976477 -0.125908 , -3.22507 , -0.339585 , -0.0606268,0.195611,0.978806 -0.103461 , -3.35022 , -0.316179 , -0.0702554,0.223599,0.972146 -0.0814569 , -3.47566 , -0.288564 , -0.0857872,0.202071,0.975607 -0.0551161 , -3.62855 , -0.266788 , -0.117377,0.146494,0.982223 -0.0240142 , -3.82051 , -0.251552 , 0.144501,-0.15533,-0.977237 --0.00460074 , -3.98379 , -0.221741 , -0.0985121,0.236721,0.96657 --0.0322822 , -4.13824 , -0.183681 , -0.0353508,0.246892,0.968398 --0.0621227 , -4.30113 , -0.143358 , -0.0236065,0.247438,0.968616 --0.09451 , -4.4842 , -0.10196 , -0.0434054,0.266541,0.962846 --0.128301 , -4.66572 , -0.0548461 , -0.0646822,0.241141,0.968332 --0.16584 , -4.87772 , -0.00709223 , -0.0641405,0.261678,0.963022 --0.203009 , -5.07856 , 0.0492717 , -0.0786506,0.255546,0.963592 --0.244781 , -5.30833 , 0.107611 , -0.0856605,0.236753,0.967786 --0.295415 , -5.597 , 0.165232 , -0.0908084,0.231011,0.968704 --0.34887 , -5.89379 , 0.231052 , -0.094144,0.22344,0.97016 --0.409851 , -6.24019 , 0.301968 , -0.090186,0.222488,0.970755 --0.476179 , -6.61494 , 0.381867 , -0.08628,0.210513,0.973776 --0.555362 , -7.06709 , 0.468422 , -0.0845739,0.210493,0.97393 --0.643619 , -7.56689 , 0.567736 , -0.085823,0.213659,0.973131 --0.742582 , -8.12501 , 0.682196 , -0.0816037,0.208574,0.974596 --0.860295 , -8.80009 , 0.813248 , -0.0604726,0.20936,0.975967 --0.990285 , -9.53145 , 0.967402 , -0.0614223,0.21846,0.973911 --1.141 , -10.3782 , 1.14854 , -0.0472306,0.217536,0.974909 --1.31636 , -11.359 , 1.36315 , -0.0238333,0.230261,0.972837 --1.52305 , -12.5217 , 1.62093 , 0.128822,0.340178,0.931495 --1.62329 , -12.979 , 1.87565 , -0.271862,-0.429142,-0.861352 --1.69335 , -13.2437 , 2.13169 , 0.322106,0.463353,0.825562 --1.86873 , -14.1421 , 2.46027 , -0.0966131,-0.406347,-0.908597 --2.42847 , -17.3245 , 3.08726 , -0.0772048,0.221614,0.972074 --2.95497 , -20.2341 , 3.79282 , -0.251923,0.73679,0.627436 --4.85054 , -31.0953 , 5.81439 , -0.00323002,0.123759,0.992307 --4.89312 , -30.9582 , 6.35885 , -0.111111,-0.0579368,0.992118 --4.41921 , -27.8689 , 6.34576 , 0.19932,0.927493,0.316272 --4.59829 , -28.5358 , 7.00018 , 0.0135471,-0.574049,0.818709 --4.64088 , -28.4282 , 7.50884 , 0.20186,0.374192,0.905115 --4.68777 , -28.3414 , 8.02304 , -0.43854,-0.313956,-0.84209 --3.3653 , -20.7887 , 6.57749 , -0.567774,-0.400726,0.719063 --3.49943 , -21.2606 , 7.11094 , 0.595538,-0.322975,-0.735542 --2.76548 , -17.0926 , 6.27055 , -0.968953,-0.205529,0.137432 --2.7843 , -16.9842 , 6.57327 , -0.877888,-0.470447,0.0894002 --2.92664 , -17.5226 , 7.09563 , 0.587227,0.677732,0.442542 --3.10526 , -18.2238 , 7.7021 , 0.591517,0.682157,0.429849 --3.18201 , -18.3936 , 8.13961 , -0.885601,-0.464425,0.00447891 --3.14616 , -17.9881 , 8.35897 , -0.947761,-0.31381,0.0571967 --2.74352 , -15.7779 , 7.80706 , -0.416797,-0.862898,0.285808 --2.76658 , -15.6978 , 8.10991 , 0.472088,0.762138,-0.443034 --3.14488 , -17.3328 , 9.20976 , -0.973954,-0.165119,0.155399 --2.76934 , -15.3267 , 8.61938 , 0.576085,0.68754,-0.442057 --2.78241 , -15.1961 , 8.89883 , 0.314958,0.923152,-0.220437 --2.83203 , -15.2354 , 9.26838 , -0.246457,-0.931292,0.268244 --3.13367 , -16.4351 , 10.2884 , -0.951538,-0.139879,-0.273879 --2.82827 , -14.8361 , 9.75904 , -0.257384,-0.966304,0.00308743 --2.9648 , -15.2589 , 10.3745 , 0.0339139,0.515894,0.855981 --3.33312 , -16.6975 , 11.6531 , -0.103271,0.771501,0.627791 --3.44089 , -16.9502 , 12.2416 , 0.236302,0.855233,-0.461234 --3.21548 , -15.7546 , 11.8754 , -0.18884,-0.0392138,0.981225 --2.67159 , -13.2273 , 10.5232 , -0.280976,-0.741221,0.609626 --2.70553 , -13.1911 , 10.8601 , -0.0277045,-0.95855,0.283574 --2.65753 , -12.8114 , 10.9443 , -0.0277045,-0.95855,0.283574 --2.71522 , -12.873 , 11.3636 , -0.0822214,0.971979,-0.220217 --2.74675 , -12.8162 , 11.7012 , 0.446374,0.76727,0.460487 --0.767312 , -4.75698 , 5.29884 , -0.0737598,-0.675896,0.733296 --0.751278 , -4.62178 , 5.33652 , 0.344033,-0.456674,0.820421 --0.763046 , -4.59549 , 5.4695 , 0.239534,-0.57738,0.780548 --0.756569 , -4.50208 , 5.54252 , -0.319084,0.752596,-0.576008 --0.749179 , -4.40022 , 5.60672 , 0.148739,-0.924681,0.350489 --0.770788 , -4.40926 , 5.78056 , 0.418389,0.884544,-0.206234 --0.790096 , -4.40633 , 5.94898 , 0.38566,0.871406,-0.30318 --0.710106 , -4.04467 , 5.73614 , -0.472009,-0.815797,-0.33419 --0.661112 , -3.80513 , 5.63728 , 0.549694,-0.0142409,-0.835244 --0.655674 , -3.71629 , 5.70222 , 0.431645,0.372605,-0.821492 --0.656314 , -3.65252 , 5.79611 , -0.582485,-0.57059,0.578912 --0.650009 , -3.56132 , 5.85831 , -0.758455,-0.550462,0.348908 --0.657802 , -3.51814 , 5.98119 , 0.612265,0.779078,-0.134797 --0.583608 , -3.2074 , 5.749 , -0.338066,-0.929221,-0.149197 --0.543199 , -3.01533 , 5.65929 , 0.479444,0.781258,0.399713 --0.586964 , -3.08463 , 5.93667 , -0.336136,-0.94179,-0.00663781 --0.593984 , -3.04107 , 6.0623 , -0.762145,-0.640832,0.0920282 --0.61257 , -3.02639 , 6.23758 , 0.567421,0.79985,-0.195635 --0.624837 , -2.99192 , 6.38913 , -0.767326,-0.630449,0.117242 --0.543773 , -2.68701 , 6.09143 , -0.0285435,0.212649,0.976712 --0.801131 , -3.33631 , 7.44682 , 0.242613,-0.900503,-0.360879 --0.416168 , -2.20195 , 5.63358 , -0.898105,-0.0188871,-0.439376 --0.433246 , -2.18518 , 5.80049 , -0.72884,-0.632895,-0.261221 --0.377536 , -1.97827 , 5.59787 , 0.753135,-0.588239,0.294554 --0.311484 , -1.74923 , 5.32688 , -0.117196,0.802534,0.584983 --0.305529 , -1.67818 , 5.37254 , -0.760506,-0.583579,0.284721 --0.695515 , -2.54484 , 7.57875 , 0.574367,0.335811,-0.746548 --0.669883 , -2.39585 , 7.54742 , -0.43725,-0.217137,0.872734 --0.659543 , -2.2846 , 7.60468 , -0.554295,-0.080738,-0.828395 --0.518344 , -1.8938 , 6.91124 , 0.417621,0.0129032,0.90853 --0.488006 , -1.75136 , 6.83877 , 0.220765,0.478754,0.84974 --0.438721 , -1.57453 , 6.65069 , 0.286404,0.233297,0.929272 --0.404965 , -1.43183 , 6.54296 , 0.887474,0.321539,0.330156 --0.420138 , -1.38294 , 6.73523 , 0.803093,-0.542359,0.246757 --0.429745 , -1.32032 , 6.89902 , 0.0662251,-0.991033,0.116047 --0.435543 , -1.24697 , 7.04309 , -0.27511,0.110056,-0.955093 --0.36966 , -1.05925 , 6.72468 , 0.41766,-0.236058,0.877404 --0.377213 , -0.989521 , 6.88466 , -0.475585,-0.430238,-0.767277 --0.335898 , -0.848079 , 6.71405 , 0.27049,-0.657184,-0.703523 --0.565631 , -1.05635 , 8.40986 , 0.454878,-0.863411,0.218192 --0.529579 , -0.905618 , 8.29802 , -0.620951,0.389227,-0.680385 --0.510905 , -0.777359 , 8.31043 , -0.582132,0.637137,0.505153 --0.384309 , -0.546107 , 7.52448 , -0.332704,-0.251674,0.908828 --0.389959 , -0.450929 , 7.69796 , 0.531449,-0.394128,-0.749817 --0.359435 , -0.324657 , 7.60346 , 0.211717,-0.438694,-0.873341 --0.326167 , -0.199426 , 7.47682 , 0.351917,-0.514044,0.782249 --0.326422 , -0.0949975 , 7.61522 , -0.461162,0.402828,-0.790607 --0.288756 , 0.0262884 , 7.45454 , -0.439888,0.663412,0.605296 --0.262562 , 0.14008 , 7.38083 , 0.721281,-0.212435,-0.659261 --0.249568 , 0.249951 , 7.41434 , 0.69226,0.421383,-0.585843 --0.260496 , 0.363403 , 7.65444 , 0.935601,0.35099,0.0381675 --0.236231 , 0.476377 , 7.59476 , -0.191526,0.117835,0.974388 --0.233811 , 0.596641 , 7.73162 , 0.0688606,-0.884121,0.462156 --0.166276 , 0.684035 , 7.27091 , -0.00342922,-0.500831,-0.865538 --0.148585 , 0.791941 , 7.25495 , 0.0566018,0.470042,0.880827 --0.534901 , 1.28502 , 11.2081 , 0.744905,-0.667107,0.00921775 --0.123982 , 1.01921 , 7.34649 , 0.307896,0.925512,0.220516 --0.109249 , 1.13275 , 7.36429 , -0.646487,-0.201179,-0.735922 --0.064387 , 1.19934 , 7.06499 , 0.58134,0.0572414,0.811645 --0.0394782 , 1.29247 , 6.98136 , 0.113601,0.990189,-0.0813628 -0.328826 , -1.76261 , -0.621043 , -0.0535335,0.259975,0.96413 -0.317314 , -1.81392 , -0.603527 , -0.0756395,0.21863,0.972872 -0.305708 , -1.86495 , -0.584747 , -0.0664722,0.19032,0.979469 -0.291778 , -1.93227 , -0.576338 , 0.0903321,-0.206273,-0.974316 -0.278451 , -2.00036 , -0.565859 , -0.0987578,0.21638,0.971302 -0.264994 , -2.06805 , -0.553629 , -0.0894068,0.220254,0.971336 -0.250201 , -2.13608 , -0.539572 , -0.106915,0.170233,0.979587 -0.234672 , -2.22144 , -0.53389 , -0.111402,0.183532,0.976681 -0.219353 , -2.28954 , -0.515744 , -0.105403,0.170202,0.979756 -0.203026 , -2.37581 , -0.50529 , -0.083937,0.203106,0.975552 -0.186728 , -2.45322 , -0.487581 , -0.131854,0.193994,0.972101 -0.167424 , -2.54819 , -0.477029 , -0.113534,0.173584,0.978253 -0.148651 , -2.6437 , -0.463433 , 0.129545,-0.177613,-0.975537 -0.127994 , -2.74851 , -0.451273 , -0.0807159,0.21875,0.972437 -0.110271 , -2.8266 , -0.423341 , -0.0419257,0.243861,0.968904 -0.0887227 , -2.93204 , -0.405143 , -0.0764988,0.202765,0.976235 -0.0652326 , -3.04658 , -0.387602 , -0.0871346,0.202571,0.975383 -0.0427339 , -3.15247 , -0.362588 , -0.086903,0.193587,0.977227 -0.017753 , -3.27644 , -0.34159 , -0.0629988,0.207,0.976311 --0.00624386 , -3.39173 , -0.313023 , -0.103776,0.192333,0.975827 --0.0363015 , -3.54425 , -0.293871 , 0.121658,-0.154535,-0.980468 --0.0704707 , -3.71597 , -0.27593 , -0.14679,0.125322,0.981197 --0.106073 , -3.89729 , -0.255312 , -0.0814234,0.223681,0.971255 --0.136408 , -4.04064 , -0.217591 , -0.0292267,0.270832,0.962183 --0.168517 , -4.18467 , -0.175121 , -0.0290927,0.233408,0.971944 --0.206258 , -4.36617 , -0.137662 , 0.0522798,-0.242496,-0.968743 --0.242852 , -4.53781 , -0.0918571 , -0.0594046,0.242433,0.968348 --0.286685 , -4.74812 , -0.0485511 , -0.066021,0.247626,0.966604 --0.328543 , -4.9388 , 0.00558061 , -0.0725012,0.248638,0.965879 --0.379786 , -5.18786 , 0.0558539 , -0.0836651,0.236433,0.968039 --0.43561 , -5.4547 , 0.111238 , -0.0967523,0.224084,0.969755 --0.493702 , -5.73193 , 0.17456 , -0.0951552,0.226829,0.969275 --0.559783 , -6.04722 , 0.242487 , -0.0901058,0.225169,0.970144 --0.633023 , -6.40035 , 0.31699 , -0.0894637,0.215388,0.972422 --0.718107 , -6.81213 , 0.398613 , -0.0876877,0.206574,0.974494 --0.817177 , -7.29105 , 0.489424 , -0.0885359,0.211152,0.973435 --0.92108 , -7.78759 , 0.595881 , -0.08084,0.211649,0.973997 --1.0508 , -8.42118 , 0.715024 , -0.0747638,0.208712,0.975115 --1.19458 , -9.11108 , 0.854983 , -0.0631031,0.2168,0.974174 --1.3527 , -9.86599 , 1.01904 , -0.0579901,0.222666,0.973169 --1.53831 , -10.7562 , 1.21223 , -0.0469311,0.226161,0.972959 --1.75713 , -11.7988 , 1.44197 , 0.0596759,0.296884,0.953047 --1.91179 , -12.4813 , 1.69058 , 0.32579,0.442246,0.835631 --1.9981 , -12.787 , 1.93799 , 0.301202,0.449982,0.84071 --2.11488 , -13.2438 , 2.21019 , -0.162566,-0.323352,-0.93221 --2.57033 , -15.4224 , 2.67918 , -0.0755948,0.220668,0.972415 --3.2584 , -18.7269 , 3.36497 , -0.170868,0.26946,0.947732 --6.19589 , -32.8492 , 6.28964 , 0.399682,0.551775,0.731983 --6.29873 , -32.9917 , 6.91896 , -0.35161,-0.932058,-0.0873946 --6.34716 , -32.8624 , 7.50474 , -0.35161,-0.932058,-0.0873947 --6.50858 , -33.279 , 8.20682 , -0.35161,-0.932058,-0.0873947 --6.56743 , -33.1943 , 8.81321 , -0.35161,-0.932058,-0.0873944 --6.59905 , -32.9848 , 9.39054 , -0.35161,-0.932058,-0.0873945 --4.46803 , -22.747 , 7.25883 , -0.339023,0.158816,0.927276 --3.21907 , -16.7698 , 5.97266 , 0.829655,0.30948,-0.464645 --3.28405 , -16.8808 , 6.33774 , 0.829655,0.30948,-0.464645 --3.35206 , -17.0033 , 6.71486 , -0.877888,-0.470447,0.0894002 --3.41379 , -17.0902 , 7.08842 , -0.877888,-0.470447,0.0894002 --3.44496 , -17.0401 , 7.41953 , 0.786043,0.485255,0.382968 --3.17991 , -15.6987 , 7.25186 , 0.502793,0.798937,-0.329998 --3.19764 , -15.6015 , 7.5425 , -0.462499,-0.878356,0.12077 --3.2562 , -15.678 , 7.90902 , -0.416798,-0.862898,0.285808 --4.27832 , -19.7993 , 10.1099 , -0.938823,0.0653516,-0.338144 --3.26023 , -15.3474 , 8.43918 , 0.509149,0.651023,-0.562971 --3.17105 , -14.809 , 8.51725 , -0.680632,-0.718434,-0.143501 --3.22002 , -14.8361 , 8.87013 , -0.657999,-0.752925,0.0118928 --3.33262 , -15.1226 , 9.37081 , -0.275656,-0.960322,0.0423761 --3.30428 , -14.8335 , 9.56737 , -0.275656,-0.960322,0.0423761 --3.34043 , -14.8039 , 9.91005 , 0.115745,0.9879,0.103233 --3.93626 , -16.9425 , 11.585 , -0.250428,-0.96623,-0.0607133 --3.96609 , -16.8575 , 11.9591 , 0.211645,0.977285,-0.0109813 --4.6177 , -19.1273 , 13.8975 , -0.871544,-0.191321,-0.451451 --4.04636 , -16.7546 , 12.77 , -0.353389,-0.82961,0.432277 --3.84913 , -15.819 , 12.5561 , -0.401054,0.204267,0.89299 --3.07212 , -12.7801 , 10.7415 , -0.182905,0.928217,-0.323974 --3.16704 , -12.9605 , 11.248 , 0.10428,-0.951708,0.288751 --3.20476 , -12.9295 , 11.6058 , 0.359436,-0.740225,0.568219 --3.1715 , -12.642 , 11.7602 , -0.359436,0.740225,-0.568219 --3.67816 , -14.2354 , 13.525 , -0.814583,-0.0826334,0.574131 --0.950538 , -4.6871 , 5.47766 , -0.15735,-0.606306,0.779509 --0.932274 , -4.55776 , 5.52011 , -0.156296,-0.622931,0.766504 --0.917337 , -4.44228 , 5.57285 , -0.341945,-0.68761,0.64052 --0.909267 , -4.34764 , 5.64356 , 0.487915,0.801905,-0.3448 --1.19965 , -5.22643 , 6.71436 , -0.532309,0.711526,0.45867 --0.929563 , -4.28217 , 5.91476 , -0.876923,0.096655,0.470812 --0.836743 , -3.91945 , 5.69195 , 0.722473,0.0882393,-0.685745 --0.801185 , -3.74694 , 5.66428 , -0.599583,-0.424309,0.678574 --0.780798 , -3.62071 , 5.68416 , 0.431499,0.633659,-0.642095 --0.795294 , -3.59949 , 5.83 , -0.365145,-0.643218,0.673008 --0.77319 , -3.4724 , 5.84591 , -0.196535,-0.789077,0.582006 --0.773873 , -3.41078 , 5.9446 , -0.194763,-0.914547,0.354503 --0.809468 , -3.44514 , 6.17728 , 0.121945,0.826091,-0.550185 --0.662235 , -2.96663 , 5.69102 , -0.478241,-0.875534,-0.0687466 --0.693763 , -2.99393 , 5.91193 , -0.62123,-0.783009,0.0311428 --0.729445 , -3.02468 , 6.15171 , -0.814137,-0.546532,0.196172 --0.742133 , -2.99227 , 6.30297 , -0.823338,-0.456491,0.33724 --0.684917 , -2.77754 , 6.16016 , -0.213325,0.353863,0.910645 --0.526178 , -2.31059 , 5.56101 , -0.93605,-0.191526,-0.295175 --0.517341 , -2.23056 , 5.60784 , -0.93605,-0.191526,-0.295176 --0.574841 , -2.31199 , 5.95724 , 0.066063,-0.330072,-0.941641 --0.561249 , -2.21577 , 5.98648 , -0.661044,-0.0377368,-0.749398 --0.49631 , -2.00445 , 5.77564 , -0.888614,0.166451,-0.427386 --0.608842 , -2.1948 , 6.4057 , -0.452729,0.432359,0.779809 --0.512765 , -1.91774 , 6.03729 , -0.983388,-0.0744306,-0.165554 --0.526834 , -1.8828 , 6.20412 , 0.387378,0.739681,-0.550282 --0.538295 , -1.84078 , 6.36266 , 0.582159,0.761188,-0.285802 --0.518682 , -1.73281 , 6.36451 , 0.648546,0.620349,-0.441084 --0.727963 , -2.06409 , 7.57774 , 0.448214,0.121744,0.885597 --0.691774 , -1.91183 , 7.50894 , -0.626333,-0.519696,-0.581054 --0.434273 , -1.37021 , 6.21726 , -0.10943,-0.0338849,0.993417 --0.414864 , -1.26828 , 6.20997 , -0.0159245,-0.498791,0.866576 --0.448305 , -1.25356 , 6.50451 , 0.878117,-0.0214257,-0.477966 --0.41472 , -1.12735 , 6.41847 , 0.741375,-0.651701,0.160153 --0.446266 , -1.09942 , 6.71304 , 0.724938,0.175642,0.666044 --0.443298 , -1.01887 , 6.81616 , 0.799359,0.0811663,0.595347 --0.396988 , -0.877292 , 6.64712 , 0.560563,-0.581472,-0.589627 --0.502047 , -0.926202 , 7.43606 , -0.512871,0.653327,0.556891 --0.426438 , -0.748904 , 7.07899 , -0.617825,0.319541,-0.718461 --0.468851 , -0.704704 , 7.48975 , -0.162833,-0.415661,0.894825 --0.448903 , -0.591082 , 7.49898 , 0.383299,0.382322,-0.84078 --0.504498 , -0.540249 , 8.02732 , -0.259099,-0.795307,-0.548046 --0.41997 , -0.372268 , 7.59038 , 0.338694,-0.633237,-0.695914 --0.387542 , -0.250874 , 7.50505 , -0.739119,0.639325,-0.212052 --0.380554 , -0.144626 , 7.60512 , 0.567362,-0.416624,0.710299 --0.338642 , -0.0219904 , 7.4459 , -0.459998,0.326069,0.825882 --0.30724 , 0.0919053 , 7.36372 , -0.353449,0.353305,0.866169 --0.29023 , 0.201101 , 7.38863 , -0.694921,-0.148225,0.703643 --0.276187 , 0.311568 , 7.43134 , 0.694846,0.447309,-0.56312 --0.27544 , 0.424461 , 7.60161 , 0.391437,0.80518,-0.445491 --0.284156 , 0.547266 , 7.8489 , 0.616719,0.762511,-0.195535 --0.20577 , 0.63871 , 7.34975 , -0.204572,0.605481,0.769119 --0.179777 , 0.744002 , 7.29563 , 0.0995877,-0.218189,-0.970812 --0.178885 , 0.867675 , 7.46738 , -0.893879,0.08814,0.439559 --0.264368 , 1.08884 , 8.49754 , 0.592601,0.248448,-0.766223 --0.132654 , 1.08571 , 7.4186 , 0.78109,0.459509,0.422788 --0.0785136 , 1.14839 , 7.07102 , -0.717696,-0.274429,-0.640001 --0.0562916 , 1.24845 , 7.03785 , 0.0820167,0.986337,-0.142871 -0.27194 , -1.76612 , -0.609686 , 0.0467018,-0.238982,-0.9699 -0.257458 , -1.83282 , -0.604027 , -0.0340488,0.216574,0.975672 -0.242756 , -1.89158 , -0.590723 , 0.0746818,-0.186195,-0.97967 -0.227549 , -1.95941 , -0.581264 , -0.0853393,0.190437,0.977983 -0.212379 , -2.01841 , -0.564649 , 0.0974988,-0.182803,-0.978303 -0.195782 , -2.0937 , -0.557311 , 0.0834074,-0.182174,-0.979722 -0.179711 , -2.16225 , -0.542204 , -0.1092,0.1712,0.979166 -0.161384 , -2.23834 , -0.530701 , -0.103161,0.188644,0.976612 -0.142464 , -2.32325 , -0.521877 , -0.0804443,0.199132,0.976665 -0.123339 , -2.40026 , -0.505601 , -0.076521,0.187526,0.979274 -0.103607 , -2.48604 , -0.491809 , -0.0780414,0.169234,0.982481 -0.0820282 , -2.58122 , -0.479939 , -0.0861454,0.165079,0.982511 -0.0602537 , -2.67581 , -0.465441 , -0.0569783,0.199431,0.978254 -0.0382729 , -2.76249 , -0.443493 , -0.0344927,0.229138,0.972783 -0.0156208 , -2.85775 , -0.423152 , -0.0300899,0.21908,0.975243 --0.00917972 , -2.96316 , -0.40366 , -0.0640687,0.181342,0.981331 --0.035693 , -3.07671 , -0.384924 , -0.0810598,0.197623,0.976921 --0.0629317 , -3.1914 , -0.362389 , -0.0593507,0.207601,0.976411 --0.0919194 , -3.31411 , -0.340123 , -0.0940736,0.199409,0.97539 --0.123415 , -3.44756 , -0.316854 , -0.124909,0.17282,0.977001 --0.162005 , -3.61782 , -0.302244 , -0.152419,0.132743,0.979361 --0.203226 , -3.79844 , -0.284977 , 0.0689651,-0.224053,-0.972134 --0.23645 , -3.93165 , -0.247399 , 0.000106819,0.280099,0.959971 --0.27105 , -4.07462 , -0.207921 , -0.0232793,0.248005,0.968479 --0.312592 , -4.24594 , -0.171502 , -0.0359108,0.237592,0.970701 --0.354775 , -4.41698 , -0.129438 , -0.0484231,0.238512,0.969932 --0.40029 , -4.60686 , -0.0859367 , -0.0512846,0.231103,0.971577 --0.451146 , -4.81493 , -0.0402659 , -0.0682795,0.240893,0.968147 --0.504094 , -5.03394 , 0.011007 , -0.0721474,0.238063,0.968567 --0.563394 , -5.28035 , 0.0644001 , -0.082267,0.226257,0.970587 --0.629623 , -5.55576 , 0.121767 , -0.0761121,0.218643,0.972832 --0.702899 , -5.85979 , 0.184665 , -0.0798424,0.221603,0.971863 --0.780221 , -6.18218 , 0.255619 , -0.0800193,0.218573,0.972534 --0.873127 , -6.5723 , 0.330947 , -0.0823547,0.210645,0.974087 --0.975634 , -6.99998 , 0.416405 , 0.0748597,-0.206599,-0.975558 --1.09343 , -7.49523 , 0.51249 , -0.0709894,0.210068,0.975106 --1.22558 , -8.047 , 0.622944 , -0.0694589,0.20951,0.975336 --1.37155 , -8.65578 , 0.751101 , -0.0675312,0.212116,0.974908 --1.54874 , -9.39884 , 0.89883 , -0.0501925,0.21533,0.975251 --1.74804 , -10.2265 , 1.07317 , 0.0444827,-0.22449,-0.973461 --1.96658 , -11.1281 , 1.27861 , 0.0178166,0.275899,0.961021 --2.17348 , -11.9561 , 1.5134 , 0.285824,0.488045,0.824692 --2.2644 , -12.2433 , 1.74778 , 0.278989,0.421782,0.862708 --2.3317 , -12.4182 , 1.98455 , 0.347437,0.439678,0.828233 --2.71415 , -13.9876 , 2.35695 , -0.0202699,0.245464,0.969194 --3.42113 , -16.9513 , 2.94052 , -0.0735566,0.213599,0.974148 --6.40666 , -29.4735 , 5.39993 , 0.823688,0.483039,0.297004 --6.56494 , -29.8509 , 6.00591 , 0.823688,0.483039,0.297004 --6.59769 , -29.6898 , 6.53088 , -0.867736,-0.468799,-0.165112 --6.5616 , -29.2428 , 6.99611 , -0.944047,-0.327512,0.0388766 --7.30753 , -32.0399 , 8.16402 , 0.971866,0.101991,0.212309 --7.33159 , -31.8218 , 8.72075 , 0.971866,0.101991,0.212309 --6.78491 , -29.2867 , 8.67656 , 0.377994,-0.0166207,0.925659 --3.94334 , -17.5745 , 5.99548 , -0.684619,-0.728832,0.0100591 --4.46941 , -19.4906 , 6.9107 , -0.330279,-0.273784,0.903304 --4.46698 , -19.2845 , 7.23354 , -0.365884,-0.395134,0.842614 --3.63344 , -15.841 , 6.4643 , -0.16596,-0.648196,0.743169 --3.71941 , -16.012 , 6.84949 , -0.0654143,-0.885304,0.460389 --3.59074 , -15.3569 , 6.93457 , 0.0911123,0.89097,-0.444826 --3.64758 , -15.4179 , 7.28188 , -0.286059,-0.762139,0.580788 --3.6722 , -15.3543 , 7.58453 , -0.414478,-0.887795,0.200072 --3.70649 , -15.3208 , 7.90271 , 0.592328,0.662664,-0.458285 --3.53185 , -14.5233 , 7.87243 , 0.763409,0.225501,-0.605273 --3.55979 , -14.4747 , 8.17493 , 0.776864,-0.507146,-0.37321 --3.62132 , -14.5425 , 8.53946 , 0.35822,0.931762,0.0591416 --3.69043 , -14.6363 , 8.92697 , 0.18678,0.980242,0.0651 --3.90339 , -15.2307 , 9.60155 , -0.379256,0.841488,0.384789 --3.77481 , -14.6192 , 9.61785 , 0.0720071,0.963503,0.25783 --7.38954 , -26.9317 , 17.3585 , -0.347576,-0.936968,0.0358005 --4.45016 , -16.6066 , 11.5874 , 0.445925,0.891441,-0.0805246 --4.46197 , -16.4629 , 11.9215 , 0.661998,0.595808,-0.454721 --4.50436 , -16.4181 , 12.3248 , -0.587017,-0.640597,0.495021 --4.14282 , -15.0383 , 11.7992 , -0.316118,0.35023,0.881708 --3.87456 , -13.9884 , 11.4508 , 0.426396,-0.54368,0.72291 --3.67023 , -13.166 , 11.2266 , 0.457408,-0.858189,0.233003 --3.7791 , -13.3559 , 11.7618 , 0.272998,-0.40291,0.873577 --3.62111 , -12.6969 , 11.6267 , 0.215574,-0.661182,0.718587 --3.61953 , -12.5355 , 11.885 , 0.215574,-0.661182,0.718586 --7.61988 , -24.6788 , 22.93 , 0.15182,-0.98789,0.0320091 --1.05756 , -4.37975 , 5.44324 , -0.564786,-0.307206,0.765925 --1.46274 , -5.51823 , 6.71584 , -0.691942,0.674306,0.257929 --0.95811 , -3.96782 , 5.35422 , -0.0317192,-0.238741,0.970565 --0.942145 , -3.86395 , 5.40287 , 0.596089,0.0963397,-0.797118 --0.928321 , -3.76692 , 5.45651 , 0.611866,0.30947,-0.727907 --0.916431 , -3.6757 , 5.51533 , -0.548812,-0.48815,0.678613 --0.932012 , -3.65952 , 5.66089 , 0.173313,0.967924,-0.181896 --1.61143 , -5.44829 , 8.00035 , -0.149263,-0.556914,0.817048 --0.971204 , -3.64508 , 5.99278 , -0.353837,0.528655,-0.771572 --0.93432 , -3.48631 , 5.97139 , 0.0866657,-0.773746,0.62754 --0.915508 , -3.37608 , 6.00854 , 0.230271,0.896524,-0.378445 --0.827852 , -3.09064 , 5.79714 , 0.471896,0.875387,0.104939 --0.782235 , -2.91834 , 5.72977 , -0.458863,-0.876117,-0.147864 --0.837535 , -2.99734 , 6.03274 , -0.420862,-0.742685,0.520858 --0.819891 , -2.89356 , 6.06776 , -0.874754,-0.426965,0.229145 --0.806206 , -2.79945 , 6.11732 , 0.781982,0.220038,-0.58317 --0.811774 , -2.7503 , 6.24128 , -0.929475,-0.33918,0.14503 --0.710175 , -2.45774 , 5.93896 , -0.239765,0.464366,0.852571 --0.774025 , -2.53854 , 6.29906 , -0.736533,0.361222,-0.571873 --0.791141 , -2.51331 , 6.48132 , -0.787793,0.416472,-0.453799 --0.6159 , -2.0751 , 5.83932 , -0.910595,-0.123482,-0.394423 --0.734781 , -2.26298 , 6.45848 , -0.311702,0.293202,0.903811 --0.64528 , -2.0148 , 6.1659 , -0.19698,-0.875938,0.440377 --0.629735 , -1.92133 , 6.1994 , -0.148836,-0.920852,0.360386 --0.630688 , -1.86178 , 6.31313 , -0.303987,-0.799769,0.51765 --0.610242 , -1.75816 , 6.32538 , -0.405122,-0.795286,0.450995 --0.87527 , -2.16566 , 7.71768 , -0.448214,-0.121744,-0.885597 --0.826137 , -1.99736 , 7.61497 , -0.626333,-0.519696,-0.581054 --0.626125 , -1.58152 , 6.74264 , 0.632596,-0.0316123,-0.773837 --0.522259 , -1.3425 , 6.32677 , -0.704203,0.708996,-0.0377066 --0.635235 , -1.44769 , 7.03757 , 0.709526,-0.541535,0.450903 --0.592702 , -1.30771 , 6.93738 , -0.38972,-0.792358,0.469348 --0.593805 , -1.23209 , 7.07266 , -0.813508,0.114509,-0.570169 --0.58347 , -1.13782 , 7.14937 , -0.882054,0.122517,-0.45494 --0.526188 , -0.984226 , 6.95511 , -0.71417,0.476007,-0.513204 --0.629946 , -1.0257 , 7.70546 , 0.78576,-0.469314,0.402896 --0.536331 , -0.830595 , 7.2936 , 0.987949,-0.127789,-0.0873287 --0.490086 , -0.697481 , 7.15967 , -0.962474,-0.270988,-0.0144579 --0.523121 , -0.639436 , 7.51157 , 0.35555,-0.266314,0.895914 --0.505992 , -0.530766 , 7.55943 , 0.0152407,-0.381605,0.9242 --0.481324 , -0.41662 , 7.55656 , 0.509472,-0.135612,-0.849734 --0.441844 , -0.292385 , 7.45281 , -0.443305,0.713,0.543241 --0.443653 , -0.194627 , 7.6332 , 0.437833,-0.498832,0.747976 --0.416676 , -0.0791505 , 7.61416 , -0.0852433,0.79634,0.598812 --0.37147 , 0.040449 , 7.4645 , 0.434744,-0.5553,-0.708971 --0.268009 , 0.165092 , 6.85642 , -0.715113,-0.211804,-0.666148 --0.322055 , 0.261837 , 7.44583 , 0.69226,0.421383,-0.585844 --0.304795 , 0.373443 , 7.49787 , -0.551229,-0.49664,0.670444 --0.301161 , 0.488637 , 7.65735 , 0.59315,0.462693,-0.658854 --0.297212 , 0.610602 , 7.83465 , -0.769041,-0.638941,0.018162 --0.20957 , 0.692598 , 7.2858 , -0.108758,0.50191,0.858055 --0.627516 , 1.1239 , 11.2833 , -0.744904,0.667107,-0.00921764 --0.182688 , 0.926245 , 7.46148 , -0.934237,-0.182777,0.306257 --0.147453 , 1.02441 , 7.35364 , -0.578515,-0.772722,0.261192 --0.119241 , 1.12781 , 7.30319 , 0.509065,0.442708,0.738148 --0.0731088 , 1.20127 , 7.0639 , 0.651612,0.151217,0.743327 --0.0435832 , 1.29236 , 6.98098 , 0.113601,0.990189,-0.0813628 -0.287086 , -1.51732 , -0.668861 , -0.0821931,0.170828,0.981867 -0.214287 , -1.78459 , -0.610531 , -0.0158932,0.172009,0.984967 -0.19794 , -1.84213 , -0.598443 , 0.0758809,-0.175541,-0.981543 -0.181103 , -1.9088 , -0.590397 , -0.0489888,0.179922,0.98246 -0.162938 , -1.97584 , -0.580619 , -0.0621022,0.184553,0.980859 -0.145605 , -2.04267 , -0.568873 , -0.0638185,0.178588,0.981852 -0.125792 , -2.11804 , -0.560727 , -0.0962629,0.165428,0.981513 -0.105591 , -2.1939 , -0.550341 , -0.0603241,0.225421,0.972392 -0.0873658 , -2.26136 , -0.532557 , -0.0692938,0.206179,0.976058 -0.0663891 , -2.33821 , -0.517691 , 0.0703852,-0.179244,-0.981284 -0.0440802 , -2.42268 , -0.505724 , 0.0654046,-0.188668,-0.97986 -0.0211258 , -2.50852 , -0.491027 , -0.0511203,0.156836,0.986301 --0.00345458 , -2.60277 , -0.478254 , -0.0465397,0.164278,0.985316 --0.0284665 , -2.69738 , -0.462656 , -0.0375276,0.210882,0.976791 --0.0522366 , -2.78242 , -0.439979 , -0.0459667,0.228342,0.972495 --0.0795852 , -2.8866 , -0.422701 , 0.0592458,-0.188536,-0.980278 --0.109844 , -2.99969 , -0.406199 , -0.0398676,0.177422,0.983327 --0.142074 , -3.1218 , -0.389964 , -0.0454376,0.201038,0.978529 --0.170862 , -3.22662 , -0.362268 , -0.0686695,0.171643,0.982763 --0.209094 , -3.3772 , -0.348583 , -0.117506,0.166964,0.978936 --0.247354 , -3.51875 , -0.326866 , -0.135744,0.124581,0.98288 --0.294521 , -3.70663 , -0.316215 , 0.084267,-0.216802,-0.972572 --0.326944 , -3.82043 , -0.275352 , 0.0182079,0.277287,0.960615 --0.365387 , -3.95309 , -0.236332 , -0.0179426,0.255272,0.966703 --0.410352 , -4.12326 , -0.203512 , -0.0334624,0.231388,0.972286 --0.456928 , -4.29292 , -0.165168 , 0.0381414,-0.228123,-0.972885 --0.506947 , -4.47154 , -0.123415 , 0.0457265,-0.233243,-0.971343 --0.562387 , -4.67933 , -0.0818506 , -0.0542674,0.2226,0.973398 --0.619776 , -4.88727 , -0.033202 , 0.0641983,-0.236772,-0.969442 --0.684447 , -5.12252 , 0.0169596 , -0.0638645,0.228975,0.971335 --0.752932 , -5.37681 , 0.0720642 , -0.0610659,0.21721,0.974213 --0.832441 , -5.66979 , 0.130151 , -0.0636216,0.218294,0.973807 --0.914816 , -5.97075 , 0.19702 , -0.073977,0.225295,0.971478 --1.0096 , -6.32012 , 0.268966 , -0.0703679,0.211578,0.974825 --1.11891 , -6.72654 , 0.347472 , -0.0686458,0.205801,0.976183 --1.24391 , -7.18914 , 0.435336 , -0.0626798,0.208159,0.976085 --1.3771 , -7.68024 , 0.538075 , -0.0607376,0.208483,0.976138 --1.54045 , -8.2864 , 0.653038 , -0.0636535,0.208483,0.975952 --1.71732 , -8.93761 , 0.787962 , -0.0503917,0.215634,0.975173 --1.92017 , -9.68386 , 0.945397 , -0.045105,0.217837,0.974942 --2.15454 , -10.5427 , 1.13043 , -0.0177618,0.231262,0.972729 --2.41369 , -11.4851 , 1.34874 , 0.19446,0.386074,0.901739 --2.52007 , -11.801 , 1.57334 , -0.38999,-0.539359,-0.746324 --2.61581 , -12.0642 , 1.80644 , -0.310098,-0.466912,-0.82815 --2.79396 , -12.6505 , 2.07565 , 0.305284,0.428543,0.850384 --3.49527 , -15.2557 , 2.56492 , -0.0566771,0.20899,0.976274 --4.45404 , -18.8075 , 3.26008 , -0.225303,0.19377,0.954826 --6.81028 , -27.6294 , 4.79477 , -0.852393,-0.363422,-0.375967 --6.87633 , -27.6217 , 5.30534 , -0.87448,-0.480376,-0.0672561 --6.94073 , -27.6057 , 5.81744 , 0.567421,0.822474,0.0396194 --6.98017 , -27.4949 , 6.31464 , -0.387998,-0.919514,0.0628641 --7.0269 , -27.4136 , 6.81775 , -0.405345,-0.911599,0.0684384 --7.09488 , -27.4084 , 7.33943 , -0.402773,-0.911097,0.0876093 --7.13285 , -27.2904 , 7.83767 , -0.360405,-0.92334,0.132482 --7.17253 , -27.1828 , 8.33937 , -0.374805,-0.914763,0.150764 --7.21109 , -27.0664 , 8.83966 , 0.0271596,-0.974378,0.223273 --4.93912 , -18.8285 , 6.86637 , 0.143568,0.141283,0.979504 --4.97813 , -18.789 , 7.23322 , -0.335859,-0.502381,0.796751 --4.19898 , -15.9251 , 6.62966 , 0.0241137,-0.861276,0.507564 --4.19244 , -15.7545 , 6.89772 , 0.0241137,-0.861276,0.507565 --4.18818 , -15.5897 , 7.16529 , -0.108386,-0.772256,0.625998 --4.19199 , -15.4554 , 7.44335 , 0.215721,-0.85412,0.473226 --4.06224 , -14.8739 , 7.52931 , 0.620561,-0.548615,0.560291 --4.01039 , -14.5592 , 7.71527 , 0.617368,-0.616064,0.489206 --4.186 , -14.9921 , 8.24545 , -0.874308,0.434666,-0.215991 --4.45973 , -15.731 , 8.95162 , -0.773641,0.628353,-0.0815616 --4.40153 , -15.3872 , 9.13846 , 0.678974,-0.732513,-0.0491855 --4.18532 , -14.551 , 9.05053 , 0.396464,-0.872024,-0.287038 --4.55938 , -15.5792 , 9.98024 , 0.0652997,-0.923547,0.377886 --4.55761 , -15.4151 , 10.2666 , 0.13643,-0.916117,0.376984 --4.90198 , -16.3145 , 11.204 , 0.556857,0.753736,0.348987 --4.92362 , -16.21 , 11.5556 , -0.723817,-0.677147,0.132517 --4.92698 , -16.0504 , 11.875 , -0.628864,-0.170095,0.758682 --4.36457 , -14.2037 , 11.0329 , -0.572136,0.601688,-0.557344 --4.18182 , -13.5126 , 10.9301 , 0.426396,-0.54368,0.72291 --4.19523 , -13.4037 , 11.2319 , 0.455245,-0.525413,0.718814 --4.18663 , -13.227 , 11.4858 , -0.173851,-0.392216,0.903295 --4.17573 , -13.0463 , 11.7369 , -0.173851,-0.392216,0.903295 --4.72599 , -14.4489 , 13.3055 , -0.920781,0.204507,0.332175 --8.35144 , -24.384 , 22.3369 , 0.15182,-0.98789,0.0320091 --1.46645 , -5.12788 , 5.89267 , 0.378935,0.0377987,0.924651 --1.17278 , -4.26234 , 5.26865 , 0.0224062,-0.00620019,0.99973 --1.16763 , -4.19357 , 5.35814 , 0.0224062,-0.00620012,0.99973 --1.68292 , -5.50511 , 6.82506 , -0.691943,0.674305,0.257929 --1.11767 , -3.95144 , 5.43001 , 0.203496,-0.293244,0.934129 --1.07628 , -3.78712 , 5.41541 , 0.217706,-0.309616,0.925604 --1.05112 , -3.67021 , 5.4467 , 0.17835,-0.515319,0.838235 --1.03257 , -3.56708 , 5.48985 , 0.48934,0.664377,-0.564934 --1.11757 , -3.72403 , 5.84255 , -0.50391,0.664653,-0.551644 --1.05694 , -3.51758 , 5.76528 , -0.437223,-0.876869,0.199843 --1.05739 , -3.46352 , 5.87341 , -0.413065,-0.485688,0.770379 --1.06612 , -3.42475 , 6.00431 , -0.552878,-0.633259,0.541579 --1.06542 , -3.36582 , 6.11193 , -0.316388,-0.740891,0.592435 --1.0695 , -3.31513 , 6.23493 , -0.417101,-0.626815,0.658126 --1.03447 , -3.17485 , 6.22858 , 0.916898,-0.375141,0.136264 --1.01906 , -3.07883 , 6.28431 , 0.619443,-0.639371,-0.455516 --0.91789 , -2.79715 , 6.04054 , 0.604635,0.25197,-0.755598 --0.901439 , -2.70492 , 6.08939 , 0.621124,-0.315864,-0.717241 --0.824965 , -2.48546 , 5.91642 , 0.435882,-0.470736,-0.767082 --0.94058 , -2.6667 , 6.45497 , -0.356928,0.895954,-0.264326 --0.974262 , -2.67169 , 6.69977 , -0.194131,0.973205,-0.123229 --1.00236 , -2.66027 , 6.92905 , 0.0756828,0.945912,-0.315471 --0.821556 , -2.24536 , 6.33333 , -0.00331596,0.290685,0.956813 --1.01413 , -2.54294 , 7.23244 , 0.0183696,-0.558438,0.829343 --0.703223 , -1.90298 , 6.06828 , -0.0211793,-0.621765,0.782917 --0.691844 , -1.8231 , 6.12757 , -0.318633,-0.667408,0.673082 --0.691505 , -1.76307 , 6.24005 , -0.425068,-0.588098,0.688082 --0.723995 , -1.75501 , 6.49854 , -0.531324,-0.844699,0.0646464 --0.724657 , -1.68968 , 6.62024 , 0.711012,0.369576,-0.598227 --0.658186 , -1.51761 , 6.43482 , -0.902613,0.428269,-0.0432971 --0.612161 , -1.38293 , 6.33855 , 0.652208,-0.674277,0.346375 --0.624421 , -1.33576 , 6.52095 , 0.137338,-0.963549,0.22959 --0.744393 , -1.4338 , 7.24267 , 0.677623,-0.396118,0.619611 --0.728768 , -1.33345 , 7.30433 , -0.592971,0.590164,-0.547806 --0.794397 , -1.33536 , 7.79439 , -0.436768,0.7241,0.533772 --0.705132 , -1.14196 , 7.48065 , -0.980791,0.110715,0.160596 --0.618659 , -0.959476 , 7.16157 , 0.486385,0.115699,-0.86605 --0.677024 , -0.939021 , 7.64146 , 0.802937,0.335367,0.492769 --0.550986 , -0.726663 , 7.08299 , -0.0302507,-0.118565,0.992485 --0.543259 , -0.635705 , 7.1913 , -0.920221,-0.362897,0.146628 --0.552399 , -0.556332 , 7.40603 , 0.239335,0.032197,-0.970403 --0.551311 , -0.46358 , 7.5708 , -0.11857,0.213339,0.969757 --0.505034 , -0.337391 , 7.44912 , 0.436672,-0.712507,-0.549228 --0.510769 , -0.243951 , 7.66987 , 0.0716649,-0.409217,0.909618 --0.497133 , -0.135911 , 7.76119 , -0.17673,-0.981817,0.0693022 --0.422388 , -0.00453607 , 7.44517 , 0.199567,0.675016,0.710301 --0.312542 , 0.123141 , 6.84921 , 0.542373,-0.581815,-0.606072 --0.274254 , 0.223553 , 6.74572 , -0.883896,-0.368982,-0.287369 --0.345309 , 0.324755 , 7.46299 , 0.709104,0.540057,-0.453332 --0.326266 , 0.43579 , 7.52454 , -0.0517538,-0.824636,0.563291 --0.337221 , 0.558998 , 7.83192 , -0.769041,-0.638941,0.0181617 --0.24938 , 0.647339 , 7.33417 , 0.496624,-0.392567,-0.774116 --0.214461 , 0.749629 , 7.26104 , -0.0731643,0.262881,0.96205 --0.213 , 0.876249 , 7.48315 , -0.444811,-0.343975,0.826937 --0.20457 , 1.00507 , 7.65327 , -0.943698,-0.146266,0.296717 --0.14245 , 1.07867 , 7.32736 , 0.841177,0.0676279,0.536515 --0.0966175 , 1.15955 , 7.12852 , -0.90358,-0.214351,-0.370941 --0.0611455 , 1.24849 , 7.0272 , 0.149662,0.984047,-0.0961943 -0.153429 , -1.79922 , -0.611964 , 0.0483287,-0.174062,-0.983548 -0.134712 , -1.86564 , -0.604937 , -0.0493829,0.186481,0.981217 -0.116017 , -1.92318 , -0.590559 , 0.0617672,-0.155103,-0.985965 -0.0956962 , -1.99807 , -0.585748 , 0.0833643,-0.187218,-0.978775 -0.0762834 , -2.05677 , -0.567667 , 0.0481078,-0.143819,-0.988434 -0.0533237 , -2.13971 , -0.564316 , 0.0575327,-0.17915,-0.982138 -0.0322633 , -2.20674 , -0.547868 , -0.0530312,0.241647,0.968914 -0.0110652 , -2.27336 , -0.529571 , -0.0718981,0.199939,0.977167 --0.0130876 , -2.35769 , -0.51911 , 0.0779281,-0.176306,-0.981246 --0.0386265 , -2.4422 , -0.50614 , 0.077936,-0.190981,-0.978495 --0.0660054 , -2.53613 , -0.495189 , -0.0490513,0.178801,0.982662 --0.0911806 , -2.62069 , -0.476939 , -0.0510042,0.178575,0.982604 --0.119194 , -2.71436 , -0.46044 , -0.0578042,0.2127,0.975406 --0.147653 , -2.80835 , -0.440921 , -0.0644276,0.209256,0.975736 --0.179223 , -2.9123 , -0.422469 , -0.0611935,0.194057,0.97908 --0.212505 , -3.02439 , -0.404773 , -0.03671,0.19789,0.979537 --0.244789 , -3.12784 , -0.379703 , -0.0760676,0.190456,0.978744 --0.284749 , -3.26741 , -0.365653 , -0.0931649,0.152265,0.983939 --0.327978 , -3.41645 , -0.350529 , -0.130534,0.135302,0.982168 --0.376517 , -3.58545 , -0.336638 , -0.0896655,0.183262,0.978966 --0.419411 , -3.72551 , -0.308202 , -0.00652503,0.26777,0.963461 --0.456077 , -3.839 , -0.265873 , 0.0179265,-0.286122,-0.958026 --0.504628 , -3.99797 , -0.234001 , 0.039399,-0.235391,-0.971102 --0.553799 , -4.15671 , -0.196775 , -0.0424714,0.227903,0.972757 --0.610236 , -4.34449 , -0.161243 , 0.035826,-0.229264,-0.972705 --0.665303 , -4.52142 , -0.11737 , -0.0470144,0.218349,0.974738 --0.732637 , -4.7466 , -0.077595 , -0.0620419,0.22869,0.97152 --0.796094 , -4.95248 , -0.0262662 , 0.053989,-0.2317,-0.971288 --0.869914 , -5.19571 , 0.0251205 , -0.065775,0.229349,0.971119 --0.950499 , -5.45722 , 0.0816715 , -0.065845,0.220658,0.973126 --1.0438 , -5.76561 , 0.140156 , -0.0667904,0.215194,0.974285 --1.14263 , -6.09391 , 0.207555 , -0.0715867,0.224076,0.971939 --1.25353 , -6.45878 , 0.2818 , -0.0672128,0.217996,0.973633 --1.37905 , -6.87082 , 0.36448 , -0.0624029,0.211763,0.975327 --1.51841 , -7.32966 , 0.458341 , -0.0605543,0.212428,0.975299 --1.68318 , -7.87343 , 0.563323 , -0.0598097,0.204981,0.976937 --1.87832 , -8.52205 , 0.683863 , -0.0545351,0.2169,0.974669 --2.07562 , -9.16745 , 0.827464 , -0.0472458,0.217724,0.974866 --2.32055 , -9.97294 , 0.993499 , -0.0411211,0.222413,0.974085 --2.58978 , -10.8523 , 1.18982 , 0.0665842,0.309074,0.948704 --2.76265 , -11.3699 , 1.40649 , 0.32781,0.467771,0.820811 --2.86121 , -11.6146 , 1.62895 , -0.302076,-0.49681,-0.813591 --2.95106 , -11.8253 , 1.85856 , 0.300361,0.479784,0.824373 --3.60741 , -14.0048 , 2.26541 , -0.0470955,0.204363,0.977762 --4.18316 , -15.8645 , 2.71931 , -0.0566771,0.20899,0.976274 --7.1059 , -25.7184 , 4.22038 , 0.469974,0.36051,0.805703 --7.4589 , -26.6888 , 4.83569 , 0.720549,0.544728,0.429047 --7.71594 , -27.3233 , 5.43649 , 0.0265223,0.991849,0.124624 --7.75308 , -27.2084 , 5.93087 , 0.0152869,-0.973577,0.227846 --7.77316 , -27.0371 , 6.41367 , 0.236091,0.967918,-0.0859979 --7.87338 , -27.1309 , 6.95131 , -0.232573,-0.967141,0.10271 --7.91354 , -27.0269 , 7.45058 , 0.0570688,0.98656,-0.153109 --7.95184 , -26.9152 , 7.94867 , -0.0820776,-0.969875,0.229357 --7.99045 , -26.8042 , 8.44793 , -0.0910317,0.97334,-0.210531 --8.03254 , -26.702 , 8.95098 , -0.103774,0.991418,-0.0795108 --5.48373 , -18.4757 , 6.91345 , -0.246092,-0.422051,0.872532 --5.42305 , -18.1255 , 7.17459 , -0.274623,-0.519275,0.809281 --8.14797 , -26.3642 , 10.4624 , -0.263353,0.932446,-0.247367 --8.18578 , -26.2456 , 10.9687 , -0.286909,0.934765,-0.209518 --5.18746 , -16.9338 , 7.84586 , 0.00124251,-0.873476,0.486866 --5.31639 , -17.1663 , 8.30886 , 0.00124212,-0.873476,0.486866 --5.15443 , -16.5303 , 8.40732 , -0.840732,0.540548,0.0312731 --5.45282 , -17.2602 , 9.11209 , 0.83512,-0.497992,-0.233621 --8.47537 , -25.9321 , 13.6853 , -0.160463,0.961097,-0.224818 --4.98487 , -15.5872 , 9.05804 , -0.664387,0.729806,-0.161159 --8.55736 , -25.6889 , 14.7595 , -0.163805,0.965223,-0.203747 --4.9955 , -15.327 , 9.65653 , -0.0571259,-0.944015,0.324918 --5.09425 , -15.4579 , 10.1079 , 0.116926,-0.932445,0.341869 --4.98864 , -15.0126 , 10.2277 , 0.388435,-0.710709,0.586525 --4.95736 , -14.7797 , 10.4662 , 0.312463,-0.735818,0.600782 --5.06838 , -14.9356 , 10.9551 , -0.51786,0.624473,-0.584683 --4.95205 , -14.4707 , 11.0403 , -0.595464,0.68592,-0.418255 --4.92152 , -14.2421 , 11.277 , -0.609601,0.644831,-0.461064 --4.8871 , -14.0019 , 11.5032 , 0.376177,-0.467988,0.799674 --9.00494 , -24.6693 , 20.018 , 0.31041,-0.932739,0.183424 --8.97109 , -24.3193 , 20.4692 , 0.258773,-0.956151,0.137158 --8.84506 , -23.7329 , 20.7262 , 0.15182,-0.98789,0.032009 --9.19961 , -24.3718 , 22.0106 , 0.15182,-0.98789,0.0320091 --1.62169 , -5.04369 , 5.7482 , 0.218167,0.0346362,0.975297 --1.58663 , -4.89594 , 5.78806 , 0.218167,0.0346362,0.975296 --1.34921 , -4.25522 , 5.35566 , -0.149547,-0.00166445,0.988753 --1.34845 , -4.19814 , 5.45949 , -0.0853942,-0.0352225,0.995724 --1.2705 , -3.95802 , 5.37776 , 0.182552,-0.243751,0.952502 --1.244 , -3.84142 , 5.41425 , -0.248579,0.633089,-0.73308 --1.26388 , -3.83494 , 5.56868 , -0.542682,0.800195,-0.255312 --1.25709 , -3.76735 , 5.65949 , -0.43114,0.868771,-0.243629 --1.29161 , -3.79193 , 5.85951 , -0.495151,0.721958,-0.483325 --1.26216 , -3.66987 , 5.89036 , 0.383303,-0.454401,0.804114 --1.27037 , -3.63165 , 6.02431 , -0.101577,-0.219306,0.970354 --1.2114 , -3.44488 , 5.96668 , 0.232214,0.233209,-0.944294 --1.17569 , -3.31245 , 5.97397 , -0.248179,-0.310979,0.917442 --1.16396 , -3.2315 , 6.04896 , 0.708349,0.0993801,-0.698831 --1.11258 , -3.0678 , 6.00277 , -0.31143,0.414216,0.85524 --1.05819 , -2.90213 , 5.94432 , 0.483454,-0.15824,-0.860948 --1.01978 , -2.76956 , 5.9302 , -0.786237,-0.179848,0.591174 --1.0016 , -2.67878 , 5.9792 , 0.611475,-0.267512,-0.744671 --1.18065 , -2.97064 , 6.6889 , 0.676082,-0.61273,-0.409238 --1.07552 , -2.70812 , 6.45376 , -0.263307,0.904002,-0.336824 --1.04698 , -2.59499 , 6.47598 , 0.378885,-0.899535,0.217445 --1.08218 , -2.59749 , 6.72082 , -0.115062,0.963846,-0.240338 --1.06682 , -2.5065 , 6.79279 , 0.000832819,-0.979843,0.199768 --1.07953 , -2.46463 , 6.96936 , 0.494514,0.848857,-0.18681 --1.08895 , -2.41275 , 7.13734 , 0.0183696,-0.558439,0.829343 --0.81796 , -1.89319 , 6.2115 , -0.459709,0.338081,-0.8212 --0.792266 , -1.79248 , 6.22613 , 0.423445,0.594459,-0.683603 --0.794334 , -1.73743 , 6.35735 , 0.605157,0.750353,-0.265999 --0.759387 , -1.62206 , 6.33215 , -0.134131,-0.554543,0.821274 --0.722677 , -1.50536 , 6.29516 , 0.622027,-0.543731,0.563417 --0.998691 , -1.83546 , 7.63196 , 0.483325,-0.616814,0.621239 --0.720956 , -1.37803 , 6.54129 , -0.738402,0.674212,-0.0141308 --0.71417 , -1.30149 , 6.63974 , -0.845586,0.527988,0.0788235 --0.828483 , -1.37697 , 7.31485 , 0.32542,-0.838888,0.436313 --0.855705 , -1.33216 , 7.6048 , -0.591202,0.794261,0.140105 --0.844955 , -1.23659 , 7.71363 , -0.436768,0.7241,0.533772 --0.791055 , -1.09384 , 7.60996 , -0.586888,0.497788,0.638569 --0.734367 , -0.951217 , 7.48371 , 0.314136,-0.0562617,0.947709 --0.755746 , -0.886401 , 7.7707 , -0.66813,-0.441981,0.598544 --0.612743 , -0.671583 , 7.16329 , 0.536889,-0.687154,0.489459 --0.648785 , -0.61609 , 7.53476 , 0.266895,-0.142628,0.953113 --0.655206 , -0.528903 , 7.74988 , 0.732578,-0.495042,0.467186 --0.567847 , -0.378379 , 7.42471 , 0.346413,-0.0876673,0.933977 --0.559352 , -0.279306 , 7.55787 , -0.521915,-0.702654,0.483614 --0.581915 , -0.190899 , 7.8964 , -0.956435,0.276059,-0.0949939 --0.55764 , -0.0758922 , 7.94789 , -0.909944,-0.413663,-0.0297467 --0.386526 , 0.0758127 , 7.01906 , 0.156548,0.844486,0.512188 --0.31578 , 0.184153 , 6.71894 , -0.688761,0.499367,0.525587 --0.300885 , 0.27988 , 6.80306 , -0.883896,-0.368982,-0.287369 --0.354958 , 0.386706 , 7.41066 , 0.806365,0.509361,-0.300543 --0.316594 , 0.493387 , 7.34255 , -0.300667,-0.591254,-0.748344 --0.348087 , 0.623864 , 7.82766 , -0.769042,-0.638941,0.0181619 --0.248839 , 0.702291 , 7.2704 , -0.33241,0.508854,0.794085 --0.209611 , 0.931181 , 7.4379 , 0.765968,0.147681,-0.625686 --0.296979 , 1.16895 , 8.54589 , -0.592602,-0.248448,0.766223 --0.142175 , 1.14105 , 7.37003 , -0.971219,-0.190563,-0.142897 --0.085431 , 1.20807 , 7.09208 , 0.796808,0.121228,0.591947 --0.0455298 , 1.29176 , 6.97069 , 0.149468,0.987429,-0.0514215 -0.112882 , -1.7485 , -0.618526 , 0.0885389,-0.185945,-0.978563 -0.092535 , -1.81375 , -0.612911 , -0.0978359,0.180142,0.978763 -0.0729365 , -1.87128 , -0.59953 , -0.0773587,0.199216,0.976897 -0.0511383 , -1.93652 , -0.59053 , -0.0658352,0.160821,0.984785 -0.0299356 , -2.00251 , -0.579364 , 0.0708945,-0.183348,-0.980488 -0.00552791 , -2.0759 , -0.572214 , -0.0494102,0.171773,0.983897 --0.0185418 , -2.15093 , -0.562409 , -0.0489898,0.221745,0.973873 --0.0416057 , -2.21733 , -0.545326 , 0.0830112,-0.196311,-0.977022 --0.0697441 , -2.30941 , -0.541532 , -0.0990849,0.170862,0.9803 --0.095733 , -2.38467 , -0.525031 , -0.0888165,0.207512,0.974192 --0.121881 , -2.45945 , -0.506391 , -0.0978263,0.183369,0.978165 --0.151293 , -2.55266 , -0.494416 , 0.069653,-0.171059,-0.982796 --0.181876 , -2.64505 , -0.479838 , 0.066473,-0.196712,-0.978205 --0.213134 , -2.73872 , -0.462142 , 0.0782797,-0.203743,-0.97589 --0.24703 , -2.84045 , -0.445906 , 0.0654478,-0.208315,-0.97587 --0.278951 , -2.93378 , -0.422272 , -0.0492752,0.207057,0.977087 --0.316462 , -3.04561 , -0.403306 , 0.0790433,-0.165845,-0.982979 --0.358422 , -3.17501 , -0.388207 , -0.112969,0.160698,0.980518 --0.405132 , -3.32272 , -0.375904 , -0.127197,0.145582,0.981135 --0.453632 , -3.47106 , -0.358657 , -0.105415,0.177133,0.978525 --0.507212 , -3.63839 , -0.342743 , -0.0163056,0.258718,0.965815 --0.541892 , -3.73169 , -0.296914 , -0.0355589,0.279647,0.959444 --0.595108 , -3.89013 , -0.268078 , -0.0400904,0.244686,0.968773 --0.645934 , -4.03808 , -0.23146 , 0.0495175,-0.227532,-0.972511 --0.702179 , -4.20566 , -0.194615 , 0.0483607,-0.230537,-0.971861 --0.762593 , -4.38105 , -0.154777 , -0.0601408,0.22478,0.972552 --0.83061 , -4.58611 , -0.115075 , -0.0677896,0.219603,0.973231 --0.900103 , -4.78942 , -0.0686829 , -0.0658671,0.241287,0.968216 --0.981136 , -5.0309 , -0.0225458 , -0.0669203,0.229178,0.971081 --1.06301 , -5.27149 , 0.0319606 , -0.0757208,0.232934,0.96954 --1.15662 , -5.54969 , 0.0887416 , -0.0816638,0.2188,0.972347 --1.26521 , -5.87501 , 0.148677 , -0.0814919,0.225286,0.970879 --1.37487 , -6.19876 , 0.219997 , -0.0804724,0.227119,0.970537 --1.50502 , -6.589 , 0.295866 , 0.0779844,-0.219532,-0.972484 --1.65496 , -7.03557 , 0.380515 , -0.0712291,0.216785,0.973617 --1.8196 , -7.52739 , 0.47768 , -0.0692315,0.21526,0.9741 --2.01295 , -8.10395 , 0.58804 , -0.0623747,0.215162,0.974584 --2.21683 , -8.70738 , 0.718385 , -0.0524883,0.224097,0.973152 --2.46121 , -9.43127 , 0.868087 , -0.0524223,0.224135,0.973147 --2.73136 , -10.2284 , 1.04443 , -0.0218237,0.248694,0.968336 --2.98089 , -10.945 , 1.24833 , 0.215835,0.527026,0.821985 --3.07468 , -11.1511 , 1.45986 , 0.228734,0.498963,0.835893 --3.19753 , -11.4482 , 1.68443 , -0.260577,-0.514807,-0.816746 --3.36397 , -11.8742 , 1.93001 , 0.112678,0.366655,0.923508 --4.13564 , -14.1813 , 2.36408 , -0.0360483,0.210081,0.977019 --7.17003 , -23.4592 , 3.65089 , 0.159021,0.24361,0.956748 --7.48581 , -24.2349 , 4.19017 , -0.254744,-0.272338,-0.927867 --8.08008 , -25.8439 , 4.88324 , -0.0510675,-0.518086,-0.853803 --8.76088 , -27.6878 , 5.67849 , -0.273046,0.949785,-0.152819 --8.81472 , -27.6221 , 6.19426 , -0.273467,0.949571,-0.153396 --8.75702 , -27.2217 , 6.64325 , -0.281612,0.951472,-0.124082 --8.9435 , -27.5481 , 7.24343 , -0.247998,0.964766,-0.0878798 --8.98034 , -27.4281 , 7.75281 , -0.270419,0.958227,-0.093144 --9.01962 , -27.3173 , 8.26533 , -0.249021,0.946537,-0.205079 --9.05705 , -27.1989 , 8.77666 , 0.249252,-0.948262,0.196653 --9.10475 , -27.1074 , 9.29744 , 0.198825,-0.958982,0.202046 --9.1451 , -26.9984 , 9.81542 , 0.246352,-0.935809,0.252137 --9.18318 , -26.8796 , 10.3325 , 0.258119,-0.941403,0.217108 --5.88966 , -17.4895 , 7.48928 , -0.145958,-0.641397,0.753198 --5.77683 , -17.0291 , 7.68572 , 0.00124249,-0.873476,0.486866 --9.31875 , -26.5756 , 11.9205 , -0.0828257,-0.993945,0.0721976 --5.92588 , -17.1442 , 8.4779 , 0.00124288,-0.873476,0.486866 --9.39769 , -26.3346 , 12.9832 , 0.115831,-0.968776,0.219217 --9.43747 , -26.2123 , 13.5201 , 0.144692,-0.966057,0.214003 --9.48434 , -26.1057 , 14.0696 , 0.154647,-0.964597,0.21363 --9.52457 , -25.9804 , 14.6156 , -0.137026,0.96676,-0.215866 --9.5743 , -25.8784 , 15.1798 , -0.139282,0.96849,-0.206463 --9.61484 , -25.7488 , 15.7358 , -0.138667,0.970013,-0.199614 --9.6579 , -25.6249 , 16.302 , -0.500495,-0.864894,0.0382676 --5.62244 , -15.1854 , 10.5426 , -0.510913,0.713787,-0.479036 --5.7212 , -15.2906 , 11.0069 , -0.904885,-0.272166,-0.327275 --5.69699 , -15.0847 , 11.2788 , -0.633583,0.625392,-0.455474 --9.85632 , -25.1574 , 18.6689 , -0.357118,-0.879748,0.313862 --9.89234 , -24.9994 , 19.2559 , 0.0950569,-0.946818,0.30741 --9.90856 , -24.7912 , 19.8149 , 0.097236,-0.885951,0.453472 --1.48364 , -4.44068 , 4.72125 , 0.177988,-0.856654,0.484215 --1.4598 , -4.33786 , 4.77937 , -0.175551,0.899436,-0.400246 --10.1029 , -24.4875 , 21.8074 , 0.15182,-0.98789,0.0320092 --1.95779 , -5.39247 , 5.98562 , 0.845961,-0.319802,-0.426706 --1.73283 , -4.81754 , 5.65184 , 0.845114,0.315173,-0.431796 --1.71883 , -4.72803 , 5.74039 , 0.845114,0.315173,-0.431796 --1.50119 , -4.18633 , 5.38963 , 0.46515,0.188573,-0.864914 --1.44382 , -4.00775 , 5.37166 , 0.56808,0.0157891,-0.822822 --1.6191 , -4.34039 , 5.87911 , -0.478441,0.54177,-0.691071 --1.51228 , -4.05349 , 5.74837 , 0.69078,-0.391058,0.608191 --1.49886 , -3.97056 , 5.82983 , 0.653279,-0.451476,0.607779 --1.46032 , -3.8358 , 5.85171 , -0.58452,0.50943,-0.631519 --1.44264 , -3.74473 , 5.92178 , 0.453503,-0.548478,0.702501 --1.40367 , -3.61127 , 5.93792 , 0.465608,-0.234062,0.853478 --1.34133 , -3.43174 , 5.88999 , -0.354525,-0.0518425,0.933608 --1.31411 , -3.32415 , 5.9295 , -0.381923,-0.499157,0.777803 --1.31476 , -3.27175 , 6.04456 , 0.444984,0.086212,-0.891379 --1.19361 , -2.98283 , 5.81904 , -0.670972,0.665086,0.327807 --1.10253 , -2.75682 , 5.6647 , 0.776228,-0.405619,-0.482643 --1.11861 , -2.73744 , 5.81999 , 0.776228,-0.405619,-0.482643 --1.09268 , -2.63929 , 5.853 , -0.870188,0.138636,0.472814 --1.02431 , -2.46301 , 5.75095 , -0.684149,0.425457,0.592391 --1.02535 , -2.41441 , 5.86242 , -0.684149,0.425457,0.592391 --1.18834 , -2.64632 , 6.50037 , 0.118693,-0.991555,-0.0522491 --1.33667 , -2.8395 , 7.11453 , 0.754287,-0.653243,0.065768 --1.21789 , -2.57613 , 6.85421 , 0.0897303,-0.932983,0.348556 --1.2152 , -2.50777 , 6.97927 , 0.160237,-0.907103,0.389215 --1.239 , -2.48105 , 7.2013 , -0.0875677,-0.000442937,0.996158 --0.950579 , -1.96551 , 6.30224 , 0.219062,-0.131734,-0.966777 --0.883555 , -1.80455 , 6.17539 , 0.598407,-0.376339,0.707303 --0.857098 , -1.70965 , 6.19838 , 0.267153,-0.465092,0.84399 --0.854113 , -1.6472 , 6.31052 , -0.96583,-0.0338069,0.256963 --0.857233 , -1.5923 , 6.44991 , -0.938444,0.207042,0.276508 --1.0425 , -1.77938 , 7.33819 , -0.808011,-0.202012,0.553452 --1.09574 , -1.77536 , 7.71456 , -0.483009,0.276156,-0.830928 --1.06431 , -1.6578 , 7.74637 , 0.293956,-0.0228389,0.955546 --0.910626 , -1.39437 , 7.23917 , -0.325495,-0.913353,-0.24462 --0.895385 , -1.30258 , 7.33007 , 0.0190445,-0.803179,0.595433 --0.923126 , -1.25559 , 7.6198 , -0.808662,0.353108,0.470511 --0.878261 , -1.12895 , 7.58477 , 0.0952976,0.615395,0.782437 --0.744086 , -0.914968 , 7.10465 , 0.12795,0.0939322,-0.987322 --0.796332 , -0.88518 , 7.53551 , -0.917707,0.0373746,0.395497 --0.75696 , -0.767328 , 7.51234 , 0.812202,0.0178838,-0.583102 --0.742726 , -0.669152 , 7.6227 , -0.844232,0.351135,-0.40494 --0.78898 , -0.611479 , 8.06343 , -0.150265,-0.15982,0.975642 --0.661325 , -0.433173 , 7.55553 , 0.0226749,0.145422,0.98911 --0.675512 , -0.348051 , 7.83755 , -0.788229,0.487579,-0.375449 --0.61219 , -0.21859 , 7.67601 , -0.405721,-0.737876,0.539378 --0.653534 , -0.133689 , 8.14241 , 0.462691,-0.484682,0.742294 --0.401777 , 0.0463033 , 6.78252 , 0.345955,-0.93493,-0.0788758 --0.382775 , 0.141692 , 6.84966 , -0.140831,0.126858,-0.981873 --0.33415 , 0.240878 , 6.72727 , -0.568925,0.575908,-0.587073 --0.319387 , 0.33745 , 6.83052 , -0.824211,-0.22201,-0.520948 --0.383696 , 0.451532 , 7.51661 , -0.776181,-0.384915,0.499382 --0.318611 , 0.551261 , 7.27968 , 0.63031,-0.258777,-0.731946 --0.311056 , 0.668018 , 7.47672 , -0.239096,0.0119559,0.970922 --0.252972 , 0.760195 , 7.26596 , 0.326014,0.0231669,0.945081 --0.249762 , 0.888458 , 7.51836 , -0.281862,-0.293073,0.913599 --0.213297 , 0.995736 , 7.4914 , -0.811696,-0.0189282,0.583774 --0.189604 , 1.11673 , 7.59135 , -0.939009,0.240921,-0.245397 --0.133206 , 1.1963 , 7.36337 , 0.96959,0.172234,0.173868 --0.0652905 , 1.24533 , 6.99687 , 0.211386,0.974312,-0.077673 -0.150324 , -1.49344 , -0.671593 , -0.0550269,0.228218,0.972054 -0.0506551 , -1.76838 , -0.626588 , 0.108741,-0.21785,-0.969906 -0.0294123 , -1.82469 , -0.614423 , 0.0935749,-0.1752,-0.980076 -0.00573384 , -1.88968 , -0.606444 , -0.111024,0.190225,0.975442 --0.0192041 , -1.96252 , -0.602336 , -0.0736696,0.190618,0.978896 --0.0415242 , -2.02057 , -0.584618 , -0.074189,0.180179,0.980832 --0.0679497 , -2.09329 , -0.57664 , -0.0544162,0.167897,0.984302 --0.0940302 , -2.16766 , -0.566103 , 0.0920223,-0.190624,-0.97734 --0.121468 , -2.24231 , -0.553447 , -0.098581,0.193288,0.976177 --0.149072 , -2.31645 , -0.538553 , -0.0846499,0.184479,0.979184 --0.17922 , -2.39894 , -0.526384 , -0.102033,0.204365,0.973563 --0.209779 , -2.48185 , -0.511684 , 0.0919041,-0.216803,-0.97188 --0.242199 , -2.57411 , -0.498709 , -0.0695327,0.205513,0.976181 --0.276026 , -2.66649 , -0.482935 , -0.07595,0.202369,0.97636 --0.310293 , -2.75922 , -0.464238 , -0.0696597,0.208749,0.975485 --0.347213 , -2.85995 , -0.446808 , -0.0558743,0.215928,0.974809 --0.384828 , -2.9619 , -0.425968 , 0.0781294,-0.17259,-0.98189 --0.432748 , -3.09851 , -0.417291 , -0.121806,0.154653,0.980431 --0.476287 , -3.21795 , -0.396643 , -0.135399,0.13877,0.981025 --0.530968 , -3.3745 , -0.385815 , -0.114924,0.171833,0.9784 --0.586987 , -3.52972 , -0.370146 , -0.0474193,0.237122,0.970322 --0.627173 , -3.63222 , -0.32964 , 0.000456822,0.279638,0.960105 --0.679323 , -3.77039 , -0.298105 , -0.0329341,0.265664,0.963503 --0.733601 , -3.9171 , -0.264697 , -0.0490953,0.238523,0.969895 --0.795222 , -4.08306 , -0.231498 , -0.052487,0.240134,0.96932 --0.854475 , -4.23847 , -0.190227 , -0.0663574,0.232934,0.970226 --0.925756 , -4.43164 , -0.152836 , -0.0952831,0.2128,0.972439 --1.00897 , -4.66117 , -0.117577 , -0.0807507,0.23363,0.968966 --1.08198 , -4.8541 , -0.0658767 , -0.0820944,0.236011,0.968276 --1.17671 , -5.11128 , -0.0206061 , -0.0831992,0.2263,0.970498 --1.2716 , -5.36859 , 0.034033 , -0.0897149,0.223784,0.970501 --1.38025 , -5.66281 , 0.0918727 , -0.0875439,0.219907,0.971585 --1.50278 , -5.99354 , 0.154664 , -0.084748,0.224913,0.970686 --1.63167 , -6.34272 , 0.227315 , -0.0859555,0.22498,0.970565 --1.78095 , -6.74746 , 0.306678 , 0.0802704,-0.220871,-0.971994 --1.95083 , -7.20713 , 0.395573 , 0.0790655,-0.216698,-0.973032 --2.14398 , -7.732 , 0.496949 , -0.0772431,0.218738,0.972721 --2.35844 , -8.31127 , 0.614572 , 0.0608212,-0.226987,-0.971997 --2.60081 , -8.96378 , 0.751079 , -0.0599234,0.224637,0.972598 --2.89025 , -9.7461 , 0.909797 , -0.0613255,0.22983,0.971297 --3.20514 , -10.5897 , 1.09741 , -0.0606864,-0.457923,-0.886918 --3.33163 , -10.8719 , 1.30324 , 0.188902,0.586142,0.787879 --3.42551 , -11.0547 , 1.51557 , -0.224321,-0.542699,-0.809418 --3.60135 , -11.4692 , 1.74923 , 0.172615,0.491025,0.853873 --4.15872 , -12.96 , 2.08366 , -0.0544556,0.213778,0.975363 --7.22488 , -21.5083 , 3.1615 , 0.179746,0.211848,0.960631 --7.50935 , -22.1351 , 3.64019 , 0.164162,0.217646,0.962123 --8.5127 , -24.7478 , 4.41205 , -0.323892,-0.208965,-0.922728 --9.70839 , -27.849 , 5.36 , 0.192734,0.945693,-0.261761 --9.76582 , -27.7862 , 5.88303 , -0.192734,-0.945693,0.261761 --9.78179 , -27.6126 , 6.3864 , 0.193905,0.973832,-0.118538 --9.87054 , -27.6338 , 6.92842 , 0.234699,0.971796,-0.0230155 --9.92882 , -27.5718 , 7.4568 , -0.309935,-0.940001,0.142611 --9.9664 , -27.4551 , 7.97439 , -0.328458,-0.923524,0.198037 --10.0052 , -27.339 , 8.49284 , 0.351167,0.913424,-0.205765 --10.0466 , -27.232 , 9.0153 , 0.370504,0.908614,-0.192735 --10.0893 , -27.1253 , 9.53968 , 0.36984,0.894227,-0.252143 --10.1312 , -27.0182 , 10.0665 , -0.4683,-0.812579,0.347002 --6.57038 , -17.7271 , 7.36979 , -0.31763,-0.583705,0.747262 --6.38431 , -17.1115 , 7.5198 , -0.145958,-0.641397,0.753198 --10.2549 , -26.6777 , 11.6573 , 0.74522,0.63985,-0.187721 --10.2944 , -26.56 , 12.1928 , 0.612005,0.76616,-0.196083 --10.3216 , -26.4067 , 12.7167 , -0.554206,-0.826402,0.0995756 --10.3798 , -26.3304 , 13.2785 , 0.550796,0.823959,-0.133096 --10.4268 , -26.2257 , 13.8339 , 0.569063,0.814719,-0.111357 --10.4684 , -26.103 , 14.3859 , 0.586647,0.801578,-0.115402 --10.5159 , -25.995 , 14.9513 , -0.372577,-0.917924,0.13639 --10.5601 , -25.876 , 15.5179 , 0.40577,0.906119,-0.119578 --10.6121 , -25.7699 , 16.0991 , -0.657453,-0.752969,-0.0281708 --10.6555 , -25.6456 , 16.6772 , 0.794255,0.596991,0.112961 --10.6415 , -25.3816 , 17.176 , -0.898457,-0.410238,-0.156458 --10.7508 , -25.4006 , 17.8613 , 0.750733,0.609195,-0.255503 --10.794 , -25.265 , 18.4581 , 0.431819,0.900578,0.0499161 --10.8359 , -25.1243 , 19.0614 , 0.197412,0.971261,0.132969 --10.8515 , -24.9191 , 19.6269 , -0.00416338,-0.998803,0.0487367 --1.71745 , -4.58707 , 4.77986 , 0.0401556,-0.86522,0.499782 --1.67836 , -4.45413 , 4.81895 , -0.177988,0.856654,-0.484215 --1.66807 , -4.38566 , 4.90807 , -0.175551,0.899436,-0.400246 --1.69472 , -4.39513 , 5.06364 , -0.109016,0.904552,-0.412191 --1.68349 , -4.32285 , 5.15196 , 0.39009,-0.87665,0.281629 --1.62235 , -4.14545 , 5.14297 , -0.393003,-0.461612,0.795275 --1.61629 , -4.08688 , 5.24008 , -0.447964,-0.208722,0.869347 --1.60699 , -4.01812 , 5.32937 , 0.46515,0.188573,-0.864914 --1.82079 , -4.40343 , 5.88645 , -0.277611,-0.439105,0.85447 --1.79552 , -4.29782 , 5.95462 , -0.257299,-0.379779,0.888575 --1.74675 , -4.14774 , 5.97144 , -0.0182305,-0.296292,0.954923 --1.72743 , -4.05454 , 6.04866 , 0.46575,-0.38194,0.798247 --1.6594 , -3.86921 , 6.01516 , 0.510031,-0.534017,0.674309 --1.64059 , -3.78174 , 6.09456 , 0.458651,-0.172243,0.871763 --1.5974 , -3.64687 , 6.11244 , 0.377757,-0.347576,0.85819 --1.44646 , -3.31303 , 5.86039 , 0.328664,-0.204249,-0.922097 --1.35256 , -3.08985 , 5.73629 , 0.113461,-0.445572,-0.888027 --1.28905 , -2.92628 , 5.68373 , -0.183474,0.468787,0.864047 --1.30907 , -2.91436 , 5.84904 , -0.218289,0.973962,-0.0612178 --1.33765 , -2.91298 , 6.03943 , 0.134432,-0.866124,0.481412 --1.51632 , -3.16774 , 6.65486 , -0.20321,0.944415,0.258429 --1.38679 , -2.88974 , 6.41711 , 0.664137,-0.427002,-0.61367 --1.34992 , -2.7728 , 6.43724 , 0.366342,-0.926846,0.0821538 --1.35829 , -2.72969 , 6.58949 , -0.257435,-0.952175,0.164593 --1.36483 , -2.68275 , 6.74214 , 0.225751,-0.845459,0.483979 --1.3644 , -2.62318 , 6.87787 , 0.992414,0.0339951,-0.118146 --1.37433 , -2.57703 , 7.04802 , 0.0983843,-0.919045,0.381676 --1.37505 , -2.51334 , 7.19209 , 0.433412,0.19349,-0.880179 --1.3074 , -2.34961 , 7.11482 , 0.433412,0.19349,-0.880179 --1.26984 , -2.23141 , 7.13173 , 0.0114659,-0.241603,0.970308 --1.21917 , -2.09481 , 7.10095 , 0.1612,-0.380926,0.910445 --1.20599 , -2.01071 , 7.203 , 0.262419,0.752308,-0.604292 --1.22848 , -1.97361 , 7.44118 , -0.51975,0.851037,-0.0748151 --1.27115 , -1.95724 , 7.76302 , 0.313754,-0.718325,0.620941 --1.21743 , -1.8155 , 7.72525 , -0.368826,0.150138,-0.917293 --1.20813 , -1.72961 , 7.86165 , 0.242712,-0.02004,0.969891 --1.13613 , -1.56907 , 7.7438 , -0.19057,-0.121691,-0.974102 --1.01114 , -1.35485 , 7.39575 , 0.781506,0.607882,0.14046 --1.03478 , -1.30424 , 7.66728 , 0.639726,-0.712502,-0.288254 --0.999842 , -1.18917 , 7.69128 , 0.773532,0.546824,0.320362 --0.913353 , -1.02772 , 7.48364 , 0.327785,-0.335855,-0.883039 --0.784371 , -0.833326 , 7.05999 , 0.365227,-0.378713,-0.850403 --0.863625 , -0.82238 , 7.61602 , 0.999164,0.0261259,-0.0314478 --0.811704 , -0.697904 , 7.55364 , -0.730455,0.151967,-0.665839 --0.816006 , -0.613975 , 7.77078 , -0.486702,0.234227,-0.841581 --0.728509 , -0.468301 , 7.51868 , 0.233578,0.259914,0.936956 --0.759304 , -0.394329 , 7.88924 , 0.814463,-0.552575,-0.176951 --0.684256 , -0.260747 , 7.69065 , -0.528693,-0.720417,-0.448868 --0.624638 , -0.14022 , 7.56775 , 0.544396,0.508273,0.667302 --0.615122 , -0.0389605 , 7.73801 , -0.724867,-0.574025,0.380872 --0.407421 , 0.109 , 6.68283 , -0.584658,0.811276,0.00231529 --0.397697 , 0.201908 , 6.82826 , 0.090182,0.538923,0.837514 --0.346549 , 0.298282 , 6.70546 , -0.568925,0.575907,-0.587073 --0.408906 , 0.404776 , 7.36237 , 0.489557,-0.536285,-0.687556 --0.3597 , 0.507038 , 7.26564 , 0.388375,-0.669173,-0.633539 --0.396354 , 0.638608 , 7.81066 , -0.769041,-0.638941,0.018162 --0.26965 , 0.82991 , 7.39977 , -0.645262,-0.0782879,0.75994 --0.243221 , 0.944728 , 7.48332 , -0.859407,-0.0225495,0.510794 --0.208069 , 1.05415 , 7.49556 , -0.90623,0.321715,-0.274311 --0.153617 , 1.14051 , 7.3284 , -0.859087,-0.288543,-0.422745 --0.103045 , 1.22424 , 7.17942 , -0.961795,-0.00370729,-0.273745 --0.0484371 , 1.2924 , 6.97033 , 0.149468,0.987428,-0.0514213 --0.0130816 , -1.78579 , -0.634702 , -0.128848,0.221711,0.966562 --0.0355946 , -1.84265 , -0.621585 , 0.118721,-0.224938,-0.967113 --0.0591927 , -1.89894 , -0.607033 , -0.098685,0.180865,0.978544 --0.0849977 , -1.96292 , -0.596765 , -0.0779572,0.223435,0.971596 --0.111176 , -2.02744 , -0.584452 , -0.0637687,0.183316,0.980984 --0.142197 , -2.1094 , -0.580897 , -0.0763183,0.132594,0.988228 --0.171028 , -2.18193 , -0.56985 , 0.118928,-0.199285,-0.972698 --0.200491 , -2.25589 , -0.556268 , 0.103169,-0.188741,-0.976593 --0.23464 , -2.34608 , -0.550571 , -0.090359,0.184779,0.978617 --0.267064 , -2.42878 , -0.537085 , 0.0832708,-0.229962,-0.969631 --0.298474 , -2.50288 , -0.516419 , -0.064083,0.219125,0.97359 --0.334636 , -2.59302 , -0.502763 , 0.0787651,-0.181963,-0.980146 --0.370504 , -2.68467 , -0.485868 , 0.0830152,-0.220558,-0.971835 --0.407786 , -2.77642 , -0.466075 , -0.0528861,0.215098,0.975159 --0.448919 , -2.87693 , -0.447569 , 0.0730515,-0.191263,-0.978817 --0.49423 , -2.99417 , -0.433614 , -0.0950754,0.154447,0.983416 --0.54395 , -3.12182 , -0.419385 , -0.121964,0.135648,0.983221 --0.602838 , -3.2759 , -0.411793 , -0.124358,0.162208,0.978889 --0.659844 , -3.42129 , -0.395539 , 0.0644131,-0.23252,-0.970456 --0.706013 , -3.53093 , -0.361162 , 0.016046,0.252325,0.96751 --0.760681 , -3.66797 , -0.33223 , -0.0405995,0.274088,0.960847 --0.814129 , -3.79537 , -0.295926 , -0.0386176,0.23484,0.971267 --0.877155 , -3.94963 , -0.263728 , 0.0506887,-0.222272,-0.973666 --0.946353 , -4.12228 , -0.23133 , -0.0654724,0.218332,0.973676 --1.023 , -4.31384 , -0.197682 , -0.0849689,0.220683,0.971638 --1.10293 , -4.51319 , -0.15985 , -0.0834714,0.232652,0.968971 --1.18505 , -4.71361 , -0.114639 , -0.0790385,0.241047,0.96729 --1.27638 , -4.94095 , -0.0683515 , -0.0820645,0.231776,0.969302 --1.37921 , -5.19536 , -0.0193773 , -0.085163,0.221081,0.97153 --1.49171 , -5.47696 , 0.0338868 , -0.0847488,0.220839,0.971621 --1.6133 , -5.77686 , 0.0944113 , -0.0771454,0.217446,0.973019 --1.75194 , -6.1231 , 0.159502 , -0.0843133,0.220455,0.971746 --1.89991 , -6.48693 , 0.234967 , 0.0804806,-0.226847,-0.9706 --2.06812 , -6.90514 , 0.318015 , -0.0759806,0.218647,0.972842 --2.26623 , -7.39703 , 0.410339 , -0.0791452,0.215126,0.973374 --2.4865 , -7.94347 , 0.517136 , 0.0634417,-0.224809,-0.972335 --2.72919 , -8.54376 , 0.641616 , -0.0605579,0.223556,0.972808 --3.01603 , -9.25314 , 0.785188 , -0.0652742,0.219719,0.973377 --3.36143 , -10.1099 , 0.954073 , -0.0354133,0.332018,0.942608 --3.54838 , -10.5305 , 1.15015 , 0.108016,0.567528,0.816238 --3.67996 , -10.7974 , 1.3579 , 0.124498,0.631786,0.765079 --3.79821 , -11.0227 , 1.57401 , 0.102767,0.560068,0.822048 --4.19753 , -11.98 , 1.84741 , -0.0683479,0.273912,0.959323 --7.01405 , -19.1895 , 2.68619 , 0.509241,0.211429,0.834249 --7.61107 , -20.5796 , 3.19526 , 0.167541,0.218917,0.961252 --7.94599 , -21.28 , 3.67447 , -0.201869,-0.178865,-0.962941 --9.7555 , -25.7036 , 4.70781 , 0.363158,0.172162,0.915684 --10.4876 , -27.3517 , 5.46831 , 0.309272,0.933323,-0.182369 --10.5211 , -27.2303 , 5.97814 , -0.647842,-0.755744,0.0956699 --10.5002 , -26.9726 , 6.46031 , 0.664458,0.737964,-0.11792 --10.5751 , -26.9527 , 6.98885 , 0.707624,0.699988,-0.0963544 --10.6066 , -26.824 , 7.49554 , 0.75138,0.653252,-0.0932201 --10.634 , -26.6873 , 8.00042 , -0.763017,-0.63934,0.0951325 --10.6583 , -26.5424 , 8.50315 , -0.775675,-0.620254,0.116672 --10.6872 , -26.4072 , 9.00887 , -0.797634,-0.592421,0.113211 --10.7076 , -26.2551 , 9.51027 , -0.84375,-0.509267,0.169508 --10.7293 , -26.1036 , 10.0122 , -0.842641,-0.520897,0.136467 --10.7477 , -25.9428 , 10.5119 , -0.882503,-0.460483,0.0956228 --10.624 , -25.4543 , 10.887 , -0.90142,-0.428252,0.0635791 --10.8223 , -25.7101 , 11.5501 , -0.90943,-0.412941,0.0491661 --10.797 , -25.4482 , 12.0122 , -0.908992,-0.416301,0.0206436 --10.8688 , -25.407 , 12.5711 , -0.901377,-0.43042,0.0475182 --10.8886 , -25.2468 , 13.0815 , -0.906709,-0.419599,0.0426117 --10.9197 , -25.1102 , 13.6069 , -0.917558,-0.39568,0.0390359 --10.958 , -24.9902 , 14.1449 , -0.92447,-0.377596,0.0526871 --10.9894 , -24.8507 , 14.6786 , -0.936664,-0.345494,0.0574028 --11.0022 , -24.6702 , 15.194 , -0.954017,-0.289659,0.0771327 --11.0265 , -24.5127 , 15.7268 , -0.964561,-0.252558,0.0763909 --11.017 , -24.2815 , 16.2199 , -0.954842,-0.296975,0.00908876 --10.9637 , -23.9555 , 16.6545 , -0.956072,-0.292472,-0.0196516 --11.2642 , -24.3732 , 17.585 , -0.952911,-0.301327,-0.0341025 --11.1912 , -24.0037 , 18.0048 , -0.863965,-0.502366,-0.0345278 --11.8105 , -25.0584 , 19.4558 , 0.197413,0.971261,0.132968 --1.86221 , -4.52745 , 4.6815 , 0.0985241,0.675963,-0.73032 --1.85181 , -4.4616 , 4.77328 , 0.098524,0.675963,-0.730319 --1.8299 , -4.37309 , 4.8462 , 0.255198,0.78293,-0.567357 --1.82866 , -4.32596 , 4.95334 , -0.177176,-0.95238,0.248154 --1.87378 , -4.36848 , 5.14028 , -0.00220012,0.999979,0.00615821 --1.857 , -4.28821 , 5.22311 , -0.266141,0.95976,-0.0896151 --1.91324 , -4.3502 , 5.43973 , -0.130278,-0.99146,0.00593148 --1.76151 , -4.01154 , 5.27269 , -0.625894,0.762267,-0.164941 --1.95542 , -4.3297 , 5.75677 , -0.414376,-0.875332,0.24917 --1.94213 , -4.25321 , 5.85263 , -0.38499,-0.741246,0.549852 --1.94812 , -4.21295 , 5.98895 , -0.122335,-0.500253,0.857194 --1.85395 , -3.98983 , 5.92059 , -0.0255317,-0.322685,0.946162 --1.86536 , -3.95856 , 6.06789 , 0.25217,-0.262549,0.931385 --1.8458 , -3.87065 , 6.15033 , 0.182188,-0.226025,0.956933 --1.63865 , -3.45541 , 5.81573 , 0.27797,0.23345,0.931791 --1.60579 , -3.34859 , 5.8583 , -0.526726,0.00569935,0.850016 --1.76488 , -3.57088 , 6.34964 , -0.0610864,-0.470977,0.880028 --1.52574 , -3.11476 , 5.90581 , 0.600416,-0.0761862,-0.79605 --1.48279 , -2.99371 , 5.91755 , 0.0814171,-0.961122,0.263848 --1.48394 , -2.94539 , 6.03771 , -0.576321,0.727443,-0.372399 --1.48009 , -2.88846 , 6.14961 , 0.42231,-0.74845,0.511348 --1.84579 , -3.41646 , 7.24082 , -0.979664,0.0178485,0.199848 --1.44512 , -2.73107 , 6.30673 , 0.388662,-0.892661,0.228249 --1.39106 , -2.59387 , 6.28296 , -0.58183,-0.468827,0.664586 --1.66082 , -2.94501 , 7.17609 , -0.347349,0.922349,0.169179 --1.50496 , -2.65432 , 6.87391 , 0.992414,0.0339951,-0.118146 --1.45151 , -2.51694 , 6.8553 , -0.87054,0.17024,0.461712 --1.42604 , -2.42149 , 6.92034 , -0.857152,-0.132021,0.497856 --1.34355 , -2.24764 , 6.80828 , 0.989864,-0.141967,-0.00381485 --1.38155 , -2.23813 , 7.0722 , -0.227897,-0.0188747,0.973502 --1.30997 , -2.08273 , 6.98991 , -0.59043,-0.595128,0.545174 --1.32542 , -2.03921 , 7.19139 , 0.132752,-0.635683,0.76045 --1.30137 , -1.94446 , 7.26656 , 0.0578848,-0.579129,0.813179 --1.25414 , -1.8203 , 7.25786 , 0.22827,-0.0906344,-0.96937 --1.34629 , -1.85978 , 7.75299 , -0.0672944,0.456867,0.886986 --1.33334 , -1.77119 , 7.88145 , -0.107519,-0.0111628,0.99414 --1.27174 , -1.62866 , 7.83154 , 0.153637,0.270096,0.950497 --1.20261 , -1.4796 , 7.74105 , -0.250093,-0.219677,-0.942972 --0.962554 , -1.16349 , 6.95764 , -0.123086,-0.666518,0.735258 --0.92122 , -1.05525 , 6.95128 , -0.103158,-0.672849,0.732552 --1.00113 , -1.05653 , 7.45771 , -0.939707,0.316544,0.129426 --1.03116 , -1.00428 , 7.77516 , 0.429243,-0.149682,0.890699 --0.889238 , -0.808549 , 7.33284 , 0.761734,-0.568614,-0.310547 --0.930066 , -0.758992 , 7.71558 , -0.757165,-0.343439,-0.555653 --0.906662 , -0.657279 , 7.80834 , -0.688299,0.0722415,-0.721821 --0.807447 , -0.50641 , 7.52942 , 0.360645,0.125289,0.92425 --0.771762 , -0.398762 , 7.55906 , -0.0142429,0.106976,0.99416 --0.806052 , -0.324194 , 7.95873 , -0.724249,0.43672,-0.533609 --0.685441 , -0.177301 , 7.53418 , 0.44997,0.829565,-0.33068 --0.674252 , -0.0773349 , 7.70527 , -0.461402,-0.506554,0.728362 --0.495706 , 0.0655254 , 6.89977 , -0.631641,-0.624909,-0.458822 --0.438611 , 0.166425 , 6.77043 , 0.675993,-0.297797,0.674055 --0.410125 , 0.260451 , 6.81699 , 0.708036,-0.530823,0.465738 --0.447403 , 0.361803 , 7.29664 , 0.495855,-0.592758,-0.634638 --0.420727 , 0.467985 , 7.37938 , -0.0569963,0.0636,0.996347 --0.365445 , 0.567715 , 7.26251 , -0.485557,0.181223,0.855215 --0.402307 , 0.704305 , 7.82642 , 0.454513,0.217666,0.863736 --0.270542 , 0.890991 , 7.42466 , -0.873249,-0.028393,0.486447 --0.239936 , 1.0057 , 7.50762 , -0.840075,-0.469855,-0.27113 --0.195825 , 1.10886 , 7.46993 , 0.418072,-0.11997,0.900457 --0.13885 , 1.1924 , 7.30236 , -0.909892,-0.199059,-0.363966 --0.0715938 , 1.24977 , 7.00568 , 0.211386,0.974312,-0.0776729 -0.0661513 , -1.46164 , -0.684737 , -0.0221564,0.397539,0.917318 --0.052323 , -1.73796 , -0.648631 , -0.0944205,0.227044,0.969297 --0.0744039 , -1.78552 , -0.630696 , -0.0755957,0.248953,0.965561 --0.103814 , -1.85675 , -0.629238 , -0.0619869,0.229349,0.971369 --0.128682 , -1.91358 , -0.613734 , -0.0658971,0.211156,0.975229 --0.156498 , -1.97692 , -0.602735 , -0.100763,0.195704,0.975473 --0.184687 , -2.04079 , -0.58969 , -0.0908531,0.171764,0.98094 --0.218466 , -2.12088 , -0.585528 , -0.0823575,0.126698,0.988517 --0.251914 , -2.20258 , -0.578612 , 0.079775,-0.193926,-0.977767 --0.281993 , -2.26678 , -0.559262 , 0.0741219,-0.186391,-0.979676 --0.319136 , -2.35607 , -0.552761 , -0.0672205,0.193235,0.978847 --0.352155 , -2.42907 , -0.533798 , -0.0526057,0.228175,0.972198 --0.387747 , -2.51033 , -0.517172 , -0.0675637,0.202732,0.976901 --0.429567 , -2.60921 , -0.506796 , -0.0769484,0.181554,0.980366 --0.469413 , -2.69969 , -0.489022 , -0.0649173,0.223067,0.972639 --0.508506 , -2.78973 , -0.468208 , -0.0745369,0.229737,0.970394 --0.555105 , -2.8979 , -0.452595 , -0.0839804,0.175829,0.980832 --0.608085 , -3.02322 , -0.441189 , -0.101287,0.126924,0.986727 --0.667746 , -3.16646 , -0.432917 , -0.126699,0.113741,0.985399 --0.728219 , -3.31057 , -0.419678 , -0.0785782,0.22527,0.971123 --0.780362 , -3.42737 , -0.391529 , 0.0107967,0.267216,0.963576 --0.833274 , -3.54518 , -0.358997 , 0.0386561,-0.262754,-0.964088 --0.893666 , -3.67954 , -0.329041 , -0.0321687,0.238548,0.970598 --0.960151 , -3.83253 , -0.299955 , -0.042757,0.239538,0.969945 --1.02822 , -3.98509 , -0.265637 , -0.062691,0.216565,0.974253 --1.10623 , -4.16511 , -0.23367 , -0.0722951,0.205136,0.97606 --1.19246 , -4.36274 , -0.200188 , -0.0677041,0.205562,0.976299 --1.28246 , -4.56999 , -0.161836 , -0.0621476,0.236856,0.969555 --1.37421 , -4.77632 , -0.11611 , -0.0671812,0.234824,0.969714 --1.47263 , -5.00123 , -0.0665816 , -0.0687836,0.222124,0.972589 --1.59018 , -5.27097 , -0.0179137 , -0.0621271,0.206638,0.976443 --1.71655 , -5.55818 , 0.0373309 , -0.067647,0.214278,0.974427 --1.85395 , -5.87283 , 0.0990823 , -0.0723905,0.211184,0.974762 --2.0114 , -6.2329 , 0.166205 , 0.072354,-0.222175,-0.972318 --2.17798 , -6.60947 , 0.244186 , -0.0690057,0.219892,0.97308 --2.37432 , -7.06018 , 0.329398 , -0.07354,0.210882,0.974741 --2.60628 , -7.59145 , 0.424495 , -0.0510529,0.221168,0.973898 --2.84039 , -8.1212 , 0.539544 , -0.0510331,0.220968,0.973945 --3.1201 , -8.75942 , 0.669938 , -0.0551984,0.214785,0.9751 --3.46759 , -9.55214 , 0.820614 , -0.0605902,0.219438,0.973743 --3.83937 , -10.3957 , 1.00092 , 0.0512508,0.502067,0.863309 --3.96489 , -10.6242 , 1.20371 , 0.0403951,0.652354,0.756837 --4.03356 , -10.7103 , 1.41088 , -0.017485,0.6704,0.741794 --4.22705 , -11.0966 , 1.63759 , -0.0684039,0.524939,0.848387 --4.85242 , -12.5094 , 1.95292 , -0.218602,0.290077,0.931702 --7.6614 , -19.0824 , 2.78862 , 0.231877,0.213421,0.949044 --7.90419 , -19.5151 , 3.20417 , 0.140531,0.232241,0.962453 --9.81758 , -23.8482 , 4.13943 , -0.881952,-0.256015,-0.395749 --9.98402 , -24.0594 , 4.63502 , -0.881952,-0.256015,-0.395749 --10.014 , -23.9536 , 5.08921 , 0.982618,0.13362,0.128867 --10.0292 , -23.813 , 5.53624 , 0.980605,0.158005,0.115966 --10.0995 , -23.7996 , 6.00802 , -0.975416,-0.212861,-0.0570377 --10.1921 , -23.8325 , 6.49381 , 0.974657,0.217629,0.0517802 --10.1935 , -23.6608 , 6.93515 , 0.975889,0.214476,0.0404993 --10.2189 , -23.5435 , 7.38907 , 0.978251,0.206759,0.0165777 --10.2535 , -23.4459 , 7.84908 , 0.979409,0.201884,0.000724856 --10.2769 , -23.3239 , 8.3031 , 0.977571,0.210573,0.00385321 --10.3056 , -23.2102 , 8.76097 , 0.975819,0.218462,-0.00723572 --10.3308 , -23.0903 , 9.21809 , -0.97127,-0.228026,0.0681107 --10.3475 , -22.9534 , 9.67068 , 0.977315,0.210765,-0.0208172 --10.3547 , -22.7922 , 10.1149 , 0.977884,0.208536,-0.0159886 --10.2337 , -22.3622 , 10.4479 , 0.982966,0.18373,0.00463455 --10.4854 , -22.7177 , 11.1138 , 0.978419,0.0918725,0.185085 --10.4378 , -22.4417 , 11.5133 , 0.970001,0.0794888,0.229736 --10.9783 , -23.3805 , 12.4973 , -0.901851,-0.261275,-0.344095 --11.0191 , -23.2784 , 13.0068 , -0.97693,-0.210351,-0.0368746 --11.0526 , -23.1589 , 13.5128 , -0.876816,-0.150296,0.456733 --11.0785 , -23.0221 , 14.0145 , -0.965935,-0.0592842,0.251903 --10.6796 , -22.036 , 14.027 , -0.940057,0.0472898,0.337722 --10.6982 , -21.8898 , 14.5119 , 0.994946,-0.0252435,-0.0971848 --10.7416 , -21.7893 , 15.0308 , 0.99292,0.00437841,-0.118703 --10.7455 , -21.61 , 15.5055 , 0.991879,0.0994124,-0.0793304 --10.7687 , -21.4681 , 16.0102 , 0.992164,0.124741,0.00715907 --10.5226 , -20.8064 , 16.1504 , 0.999286,0.0299879,0.0229766 --2.15693 , -4.74883 , 4.79722 , -0.276163,0.617437,-0.73655 --2.05628 , -4.51357 , 4.76475 , 0.173726,-0.589229,0.789068 --2.02823 , -4.41778 , 4.83452 , -0.199418,0.891308,-0.407189 --2.00418 , -4.32864 , 4.90797 , -0.199418,0.891308,-0.407189 --2.02064 , -4.31586 , 5.04622 , -0.158453,0.982053,-0.102296 --2.09026 , -4.39572 , 5.27216 , 0.0252958,-0.985045,0.170432 --2.08207 , -4.33317 , 5.37582 , -0.0761719,-0.982882,0.16775 --2.10995 , -4.33665 , 5.54361 , 0.388803,0.905006,-0.172617 --2.09666 , -4.26412 , 5.64067 , -0.373373,-0.897612,0.234277 --2.12192 , -4.25948 , 5.81022 , -0.389647,-0.848137,0.358943 --2.09452 , -4.16336 , 5.88584 , 0.511837,0.742862,-0.431485 --2.09255 , -4.10908 , 6.00807 , 0.658993,0.417922,-0.625355 --2.08258 , -4.04084 , 6.11593 , 0.37208,0.372003,-0.850394 --1.95998 , -3.78641 , 5.99945 , 0.392172,0.229997,-0.890676 --1.98363 , -3.77562 , 6.17524 , -0.524455,0.0749109,-0.848136 --1.89733 , -3.58425 , 6.12179 , -0.194071,-0.449861,0.871758 --1.86734 , -3.48435 , 6.18329 , -0.219673,-0.415967,0.882449 --1.59863 , -3.01133 , 5.71441 , -0.557063,0.293967,0.7767 --1.51207 , -2.83014 , 5.63245 , 0.41241,0.131646,-0.901436 --1.52036 , -2.79729 , 5.76575 , -0.0478488,0.949462,0.310215 --1.62717 , -2.91101 , 6.13871 , -0.963964,-0.218833,0.15128 --1.61184 , -2.83861 , 6.22742 , 0.215211,-0.867797,0.447898 --1.75416 , -2.99629 , 6.7159 , 0.438456,0.785597,0.43657 --2.14927 , -3.50716 , 7.87486 , 0.371197,-0.811286,0.451694 --1.91181 , -3.10417 , 7.41608 , 0.991133,-0.0426051,-0.12586 --1.90739 , -3.03518 , 7.56148 , 0.9811,-0.0461424,0.187917 --1.48416 , -2.39725 , 6.55221 , 0.645317,-0.484329,-0.590756 --1.43077 , -2.2715 , 6.53827 , 0.611177,0.317005,-0.725238 --1.39631 , -2.17076 , 6.5737 , 0.611177,0.317005,-0.725238 --1.51323 , -2.26384 , 7.06449 , 0.138061,0.276708,-0.950985 --1.49735 , -2.1837 , 7.17092 , -0.0400456,-0.476869,0.878062 --1.43801 , -2.04887 , 7.14201 , -0.322837,-0.692557,0.64509 --1.43723 , -1.9849 , 7.29938 , 0.230135,-0.669273,0.706478 --1.40529 , -1.8832 , 7.35671 , -0.503892,0.799264,-0.327522 --1.32083 , -1.72276 , 7.23806 , -0.049457,0.0530998,0.997364 --1.44195 , -1.78537 , 7.82517 , -0.107519,-0.0111628,0.99414 --1.35305 , -1.62129 , 7.6939 , -0.277221,0.400458,0.873374 --1.32479 , -1.51945 , 7.77281 , -0.0889663,0.645881,0.758237 --1.3697 , -1.48737 , 8.13226 , 0.899914,0.421966,-0.110001 --1.01019 , -1.07984 , 6.93417 , -0.123086,-0.666518,0.735258 --0.989748 , -0.994153 , 7.02211 , -0.134089,-0.525679,0.840049 --0.959004 , -0.898193 , 7.07057 , -0.00278,-0.283832,0.95887 --0.917392 , -0.794292 , 7.07909 , -0.45416,0.695362,0.556966 --0.834641 , -0.660172 , 6.90242 , 0.671468,0.61517,0.413155 --1.0173 , -0.707228 , 7.9116 , 0.762783,-0.642851,-0.0700341 --0.91874 , -0.559092 , 7.67446 , -0.79851,-0.265064,-0.540484 --0.861785 , -0.44082 , 7.61859 , -0.317097,-0.382303,-0.867925 --0.801101 , -0.322796 , 7.54064 , -0.0673252,0.0249371,0.997419 --0.763695 , -0.217198 , 7.57765 , 0.620878,-0.484243,-0.616458 --0.724292 , -0.109325 , 7.60269 , 0.752191,0.595293,-0.282552 --0.659043 , 0.00424835 , 7.48846 , -0.915738,-0.190989,-0.353478 --0.501518 , 0.130231 , 6.82983 , -0.817351,0.191479,-0.54339 --0.477077 , 0.224245 , 6.91711 , 0.178174,0.764198,0.619884 --0.542084 , 0.323329 , 7.56552 , -0.46108,0.820553,-0.337785 --0.466148 , 0.425556 , 7.35362 , 0.330419,-0.211661,-0.919795 --0.407061 , 0.524646 , 7.2382 , -0.188037,0.482601,0.855417 --0.366111 , 0.626162 , 7.23949 , 0.263225,0.270103,0.926152 --0.297157 , 0.838005 , 7.34511 , -0.62761,0.431338,-0.648115 --0.258211 , 0.94393 , 7.37034 , 0.519384,0.0554635,-0.852739 --0.221758 , 1.05408 , 7.42312 , -0.759768,0.624574,0.180721 --0.204369 , 1.19159 , 7.66102 , -0.960899,-0.157,0.22809 --0.119698 , 1.23917 , 7.25683 , -0.856178,-0.389039,-0.340011 --0.0511157 , 1.29402 , 6.96987 , 0.149468,0.987428,-0.0514213 -0.0165634 , -1.457 , -0.676014 , -0.0221564,0.397539,0.917318 --0.117312 , -1.75203 , -0.657287 , -0.0422547,0.2466,0.968196 --0.138579 , -1.79205 , -0.632461 , -0.0409859,0.247424,0.96804 --0.167894 , -1.85462 , -0.624625 , -0.0859786,0.17254,0.981243 --0.199681 , -1.92575 , -0.620487 , -0.0788263,0.211779,0.974134 --0.229515 , -1.98842 , -0.60866 , -0.0709521,0.228816,0.970881 --0.259715 , -2.05164 , -0.594884 , -0.0698542,0.163538,0.984061 --0.298844 , -2.13974 , -0.595171 , -0.0529251,0.14032,0.988691 --0.332923 , -2.21164 , -0.582293 , -0.0708024,0.210032,0.975127 --0.367162 , -2.28307 , -0.567275 , -0.0368365,0.191213,0.980857 --0.404188 , -2.36376 , -0.554687 , -0.0232446,0.216471,0.976012 --0.442365 , -2.44369 , -0.539788 , -0.0592398,0.19413,0.979185 --0.483372 , -2.53276 , -0.526736 , -0.0700079,0.196521,0.977997 --0.529177 , -2.63044 , -0.515384 , -0.0549982,0.215001,0.975064 --0.571084 , -2.72012 , -0.496197 , -0.0706291,0.245914,0.966715 --0.61417 , -2.80894 , -0.47431 , -0.0774156,0.203688,0.97597 --0.667226 , -2.92448 , -0.461419 , -0.118902,0.140755,0.982879 --0.727667 , -3.05686 , -0.45237 , -0.125851,0.119965,0.984769 --0.798496 , -3.21635 , -0.449687 , -0.0897846,0.157498,0.983429 --0.856864 , -3.34123 , -0.427374 , 0.0091616,-0.278226,-0.960472 --0.903396 , -3.43066 , -0.387206 , -0.0122579,0.254479,0.967001 --0.973475 , -3.58137 , -0.366613 , -0.0321443,0.232414,0.972086 --1.03072 , -3.69694 , -0.328435 , -0.0375551,0.234549,0.971379 --1.10199 , -3.84737 , -0.297816 , 0.0565543,-0.215458,-0.974874 --1.18257 , -4.01651 , -0.267161 , -0.0651318,0.217343,0.97392 --1.27014 , -4.20266 , -0.235653 , -0.0558633,0.211802,0.975715 --1.36242 , -4.39828 , -0.199685 , -0.0513899,0.203495,0.977727 --1.45923 , -4.60227 , -0.158873 , -0.0514447,0.219432,0.974271 --1.56819 , -4.83246 , -0.116957 , -0.0609032,0.226257,0.972162 --1.68202 , -5.07162 , -0.0684422 , -0.0563782,0.226276,0.97243 --1.80769 , -5.33855 , -0.0158763 , -0.0558894,0.215384,0.974929 --1.94698 , -5.63153 , 0.041664 , -0.0605417,0.208876,0.976067 --2.10983 , -5.97804 , 0.101827 , -0.0619219,0.209472,0.975852 --2.283 , -6.34187 , 0.172535 , -0.0645676,0.222808,0.972722 --2.47235 , -6.74072 , 0.252719 , 0.0700192,-0.217269,-0.973597 --2.7032 , -7.22986 , 0.339414 , 0.0601699,-0.218556,-0.973968 --2.9361 , -7.7178 , 0.444699 , -0.0442519,0.228288,0.972588 --3.21002 , -8.29473 , 0.563328 , -0.0499819,0.217198,0.974847 --3.54659 , -9.0051 , 0.698482 , -0.0511061,0.211023,0.976144 --3.94291 , -9.84054 , 0.858458 , -0.0401863,0.302877,0.952182 --4.22876 , -10.4162 , 1.05022 , -0.0172676,0.519675,0.854189 --4.40609 , -10.7398 , 1.25904 , -0.122365,0.660594,0.740704 --4.51891 , -10.913 , 1.47478 , -0.17267,0.610967,0.772595 --5.00939 , -11.9196 , 1.74605 , -0.26907,0.300743,0.914962 --7.61089 , -17.5596 , 2.41351 , 0.415147,0.226435,0.881124 --7.93338 , -18.138 , 2.81153 , 0.424409,0.231172,0.875464 --9.22603 , -20.8126 , 3.47592 , -0.353089,-0.596484,-0.720788 --10.0196 , -22.3747 , 4.09616 , 0.992006,0.0755472,0.101079 --10.191 , -22.5826 , 4.57121 , -0.97881,-0.128491,-0.159439 --10.1368 , -22.3077 , 4.97365 , 0.969779,0.104108,0.220656 --10.0579 , -21.9825 , 5.35897 , -0.973218,-0.103629,-0.205202 --10.394 , -22.5297 , 5.92171 , 0.974169,0.169822,0.148844 --10.4273 , -22.4377 , 6.36119 , 0.961326,0.221313,0.163927 --10.4621 , -22.3471 , 6.80183 , -0.957199,-0.289394,-0.00467434 --10.4968 , -22.2593 , 7.24444 , -0.952826,-0.303342,-0.010355 --10.5209 , -22.146 , 7.68114 , -0.948445,-0.315028,0.0347847 --10.5445 , -22.0345 , 8.11932 , -0.958348,-0.279647,0.0580215 --10.5827 , -21.9499 , 8.56784 , -0.967401,-0.250165,0.0393972 --10.6137 , -21.8488 , 9.01316 , -0.969596,-0.244382,0.012706 --10.6282 , -21.7161 , 9.44865 , -0.973309,-0.22492,0.0456043 --10.6474 , -21.5926 , 9.88928 , -0.970638,-0.236017,0.0464538 --10.5394 , -21.2196 , 10.2256 , 0.989416,0.145049,0.00399896 --10.7265 , -21.4217 , 10.8114 , -0.971225,-0.232476,-0.0517333 --10.6936 , -21.1934 , 11.2114 , 0.972288,0.213897,0.0943647 --10.8012 , -21.235 , 11.7439 , -0.954918,0.0599368,-0.290755 --10.8241 , -21.1132 , 12.2027 , -0.498203,0.820797,-0.279441 --10.8694 , -21.0309 , 12.6872 , 0.489862,-0.819268,0.298053 --10.8941 , -20.9078 , 13.155 , -0.666639,0.743208,-0.0568748 --10.9185 , -20.7848 , 13.6278 , -0.931754,-0.0872779,0.352444 --10.9146 , -20.6065 , 14.0716 , -0.959176,-0.230794,0.163448 --10.9026 , -20.4137 , 14.5089 , 0.98101,0.0506265,-0.187236 --10.8752 , -20.1896 , 14.9281 , 0.986301,0.0265108,-0.162814 --10.8724 , -20.0112 , 15.381 , 0.985164,0.030274,-0.168926 --2.30291 , -4.66793 , 4.68852 , -0.404967,0.673062,-0.618861 --10.5673 , -19.1248 , 15.8949 , 0.994701,0.0290813,0.0986104 --11.1207 , -19.9135 , 17.1163 , -0.98879,-0.103156,-0.107948 --14.0289 , -24.7404 , 21.7431 , -0.037741,0.996321,-0.0769413 --2.25894 , -4.41717 , 5.08877 , 0.0636916,-0.981673,0.179615 --2.24317 , -4.34504 , 5.18178 , 0.0153183,-0.996481,0.0824024 --2.27379 , -4.35231 , 5.34828 , 0.472082,0.818556,-0.327267 --2.20828 , -4.19715 , 5.36396 , 0.777622,0.584286,-0.232193 --2.25617 , -4.23113 , 5.56347 , -0.720052,-0.686561,0.100787 --2.24066 , -4.15821 , 5.65999 , -0.742198,-0.64463,0.183288 --2.28186 , -4.17762 , 5.85671 , -0.274213,-0.904156,0.327582 --2.19438 , -3.98957 , 5.82918 , -0.798071,-0.148707,0.583926 --2.15699 , -3.8818 , 5.88678 , -0.811303,-0.071842,0.580195 --2.15993 , -3.83867 , 6.02031 , -0.568877,-0.107405,0.815379 --2.09418 , -3.68922 , 6.02394 , 0.628281,0.0485105,-0.776473 --2.20454 , -3.80685 , 6.36874 , 0.572019,0.0216757,0.819954 --2.04129 , -3.51016 , 6.17523 , 0.675164,0.360671,-0.643482 --1.68967 , -2.9404 , 5.57772 , -0.560445,0.0163569,0.82803 --1.65458 , -2.84672 , 5.62034 , 0.349457,-0.582764,-0.733666 --1.62439 , -2.75801 , 5.66864 , 0.349457,-0.582764,-0.733666 --2.06262 , -3.3351 , 6.76585 , 0.761821,-0.354015,-0.542496 --2.05343 , -3.26681 , 6.88823 , 0.997066,-0.0385463,-0.0661284 --2.00733 , -3.14791 , 6.92885 , 0.98053,-0.110982,0.162001 --1.91387 , -2.96522 , 6.8522 , -0.479177,0.517712,0.708776 --1.89494 , -2.88391 , 6.95273 , 0.412976,0.873349,0.258288 --1.99126 , -2.95294 , 7.34599 , 0.550423,0.653784,-0.519231 --1.60983 , -2.40326 , 6.51491 , -0.189074,0.576149,0.795175 --1.54264 , -2.2659 , 6.47718 , 0.400802,0.043922,-0.915111 --1.56813 , -2.2445 , 6.68671 , -0.0540981,-0.930404,0.362522 --1.6505 , -2.28785 , 7.06339 , -0.352783,0.228244,-0.907441 --1.56632 , -2.129 , 6.97725 , 0.334865,0.346917,0.876079 --1.48272 , -1.97506 , 6.88704 , -0.877984,-0.41792,-0.233425 --1.53687 , -1.97569 , 7.20446 , -0.369685,-0.243317,0.896733 --1.56634 , -1.94556 , 7.46148 , -0.0586751,0.989351,0.133196 --1.69597 , -2.01478 , 8.04708 , -0.222774,0.74128,-0.633147 --1.38432 , -1.62504 , 7.21784 , 0.726652,0.539089,-0.425864 --1.43575 , -1.61073 , 7.56488 , -0.431425,0.815354,0.386095 --1.44394 , -1.54836 , 7.77478 , -0.180221,-0.964002,0.195502 --1.42524 , -1.45858 , 7.90062 , -0.50639,-0.803683,0.312512 --1.10231 , -1.10079 , 6.91559 , -0.162822,0.957627,0.237572 --1.10481 , -1.03686 , 7.09925 , -0.208106,0.723519,-0.658189 --1.05358 , -0.926832 , 7.08294 , -0.676575,0.394176,-0.62199 --1.19832 , -0.963591 , 7.84757 , 0.357168,-0.0967542,0.929015 --0.926111 , -0.694179 , 6.93824 , 0.671468,0.61517,0.413154 --0.86709 , -0.583998 , 6.87622 , -0.787742,-0.592514,-0.168494 --1.03511 , -0.60879 , 7.80756 , 0.691826,0.352898,0.629953 --0.983294 , -0.494478 , 7.80246 , -0.320575,0.77678,0.542075 --0.872422 , -0.352942 , 7.51274 , -0.323339,-0.144893,-0.935124 --0.815939 , -0.241733 , 7.47292 , 0.605309,-0.15062,-0.781611 --0.790636 , -0.143221 , 7.57785 , -0.0794962,-0.435404,0.896718 --0.774189 , -0.0433046 , 7.73978 , 0.650893,0.31569,-0.690419 --0.601821 , 0.0892973 , 7.06493 , -0.914207,0.008227,-0.405165 --0.527314 , 0.190693 , 6.88785 , 0.792452,-0.081504,0.604464 --0.566494 , 0.284476 , 7.36927 , -0.689279,0.720235,-0.0784611 --0.50782 , 0.38632 , 7.28691 , -0.223876,0.32198,0.919896 --0.465362 , 0.4881 , 7.30141 , -0.637158,-0.3955,-0.66152 --0.431574 , 0.59239 , 7.3734 , 0.521678,0.208444,0.827287 --0.366701 , 0.686494 , 7.23579 , 0.111655,-0.202091,-0.972981 --0.33957 , 0.796576 , 7.36323 , 0.397034,-0.673295,0.623729 --0.294906 , 0.899392 , 7.37017 , -0.932947,-0.176703,0.313666 --0.25587 , 1.00716 , 7.41452 , 0.760627,0.169036,-0.626796 --0.219319 , 1.12018 , 7.49646 , -0.984861,-0.170871,-0.0292058 --0.166831 , 1.217 , 7.43821 , 0.69609,0.0335881,0.717169 --0.0764635 , 1.24881 , 6.98508 , 0.261742,0.9635,-0.0562064 --0.0186614 , -1.4323 , -0.705393 , -0.0962259,0.169653,0.980795 --0.0381071 , -1.46451 , -0.68127 , -0.0962259,0.169652,0.980795 --0.178918 , -1.74862 , -0.653702 , 0.0687443,-0.280972,-0.957251 --0.204007 , -1.79523 , -0.634767 , -0.0493965,0.226943,0.972655 --0.238393 , -1.86498 , -0.632162 , -0.101675,0.159584,0.981934 --0.272198 , -1.93544 , -0.627196 , -0.0665706,0.206422,0.976196 --0.301922 , -1.9895 , -0.609185 , -0.0745261,0.219923,0.972666 --0.334125 , -2.05209 , -0.594775 , -0.0630762,0.17058,0.983323 --0.371933 , -2.13086 , -0.589053 , -0.0928675,0.147771,0.984652 --0.411126 , -2.20982 , -0.580822 , -0.0468774,0.194899,0.979702 --0.450494 , -2.28825 , -0.570256 , -0.0275708,0.211223,0.977049 --0.488115 , -2.35925 , -0.552192 , -0.0531837,0.184691,0.981357 --0.535061 , -2.4556 , -0.545854 , -0.0931039,0.193849,0.976603 --0.575694 , -2.53519 , -0.527205 , -0.0788545,0.208065,0.974931 --0.620882 , -2.62248 , -0.51055 , 0.0771098,-0.201939,-0.976358 --0.670149 , -2.7195 , -0.495082 , -0.0775439,0.232664,0.969461 --0.718686 , -2.81602 , -0.476283 , -0.115463,0.197611,0.973457 --0.782366 , -2.94614 , -0.470349 , -0.127231,0.153205,0.97997 --0.843395 , -3.06884 , -0.45592 , -0.136697,0.118348,0.983518 --0.922684 , -3.23508 , -0.455326 , -0.025407,0.224043,0.974248 --0.97175 , -3.32333 , -0.417567 , 0.00574358,0.283228,0.959035 --1.03442 , -3.44606 , -0.389996 , -0.0350926,0.250363,0.967516 --1.0986 , -3.56859 , -0.358263 , -0.0483111,0.240325,0.96949 --1.17429 , -3.71757 , -0.330975 , -0.0503151,0.21927,0.974366 --1.26255 , -3.89252 , -0.307084 , -0.0789069,0.211249,0.974242 --1.34325 , -4.05007 , -0.271348 , -0.065568,0.218184,0.973703 --1.43408 , -4.22495 , -0.23502 , -0.0652469,0.214851,0.974465 --1.53972 , -4.43562 , -0.201478 , -0.0542028,0.21554,0.97499 --1.64334 , -4.63637 , -0.158207 , 0.0610478,-0.220265,-0.973528 --1.76316 , -4.87312 , -0.11531 , -0.0656019,0.237175,0.969249 --1.8772 , -5.09088 , -0.0601315 , -0.0701933,0.227634,0.971214 --2.02766 , -5.38831 , -0.011981 , -0.0753806,0.216332,0.973406 --2.19235 , -5.7133 , 0.0432899 , -0.0659807,0.211822,0.975079 --2.36682 , -6.05394 , 0.107738 , -0.0697457,0.217747,0.97351 --2.56269 , -6.44025 , 0.179774 , -0.0749367,0.224957,0.971483 --2.78259 , -6.8691 , 0.261172 , -0.0729241,0.224481,0.971746 --3.02014 , -7.33286 , 0.355819 , 0.0571979,-0.23324,-0.970735 --3.28525 , -7.84788 , 0.464307 , -0.0549763,0.227572,0.972208 --3.60688 , -8.47943 , 0.586886 , -0.0610351,0.22187,0.973164 --3.98795 , -9.2235 , 0.729316 , 0.0605089,-0.22355,-0.972813 --4.4096 , -10.0463 , 0.899858 , -0.0619793,0.358977,0.931286 --4.68824 , -10.5568 , 1.10016 , -0.120246,0.569533,0.813126 --4.95507 , -11.0357 , 1.31991 , -0.276793,0.497211,0.822294 --5.13159 , -11.3204 , 1.55012 , 0.3617,-0.451321,-0.815771 --7.54085 , -16.1755 , 2.08158 , -0.422451,-0.225025,-0.878008 --7.9202 , -16.8332 , 2.45513 , -0.420351,-0.221268,-0.879969 --8.23732 , -17.3564 , 2.8422 , -0.177749,-0.193036,-0.964957 --10.0184 , -20.8073 , 3.60833 , -0.892837,-0.180649,-0.412564 --10.1754 , -20.9746 , 4.04814 , -0.890529,-0.158821,-0.426302 --10.1869 , -20.8515 , 4.45078 , -0.873531,-0.265163,-0.408205 --10.2211 , -20.7759 , 4.8606 , -0.940254,-0.223351,-0.256977 --10.5269 , -21.2267 , 5.3768 , -0.934832,-0.196375,-0.295848 --10.6413 , -21.3006 , 5.83158 , -0.903532,-0.21222,-0.37228 --10.5453 , -20.9664 , 6.19486 , -0.938149,-0.182903,-0.293979 --10.8793 , -21.4577 , 6.76609 , -0.936449,-0.315659,-0.153046 --10.9123 , -21.3684 , 7.1978 , -0.934164,-0.327303,-0.142162 --10.9279 , -21.2472 , 7.62145 , -0.94221,-0.318961,0.102491 --10.9223 , -21.0846 , 8.03206 , -0.93521,-0.309482,0.172058 --10.8542 , -20.8073 , 8.4016 , -0.958526,-0.17041,0.228447 --10.7732 , -20.5078 , 8.7572 , -0.955606,-0.13144,0.263707 --10.7032 , -20.2293 , 9.11437 , 0.984398,0.0528857,-0.167822 --10.7287 , -20.1284 , 9.53991 , 0.985025,0.0810781,-0.152161 --10.5926 , -19.7333 , 9.83918 , 0.995859,0.0832387,-0.0365581 --10.8058 , -19.968 , 10.4192 , 0.966244,0.142317,0.21475 --10.7626 , -19.7402 , 10.7936 , -0.94109,-0.148191,-0.303957 --12.0129 , -21.7971 , 12.3338 , -0.600334,0.566144,-0.564872 --12.0582 , -21.71 , 12.8363 , 0.449904,-0.891497,-0.0531093 --12.091 , -21.5981 , 13.3315 , 0.630793,-0.767759,-0.112457 --11.6461 , -20.6595 , 13.3469 , -0.808161,0.568272,-0.154736 --10.9632 , -19.3262 , 13.0824 , -0.965599,-0.101936,0.239221 --10.9524 , -19.1498 , 13.4999 , 0.972613,0.132654,-0.190858 --10.9863 , -19.0481 , 13.9702 , -0.959153,-0.226593,0.169358 --11.0111 , -18.9305 , 14.4366 , 0.973941,0.0657563,-0.217059 --10.9095 , -18.6005 , 14.7558 , -0.972207,-0.0632018,0.22543 --10.9883 , -18.5689 , 15.2953 , 0.997332,0.0714254,-0.0150755 --10.7838 , -18.0721 , 15.4826 , 0.987725,0.141016,0.0671831 --11.2351 , -18.6376 , 16.5236 , 0.983666,0.0720814,0.164938 --11.1654 , -18.3557 , 16.8973 , 0.980405,0.0969622,0.171476 --2.3159 , -3.99558 , 5.45227 , -0.890667,-0.357687,0.280663 --2.40958 , -4.09228 , 5.72534 , -0.957677,-0.28163,0.0594878 --2.4566 , -4.11497 , 5.92966 , -0.402773,0.538087,-0.74043 --2.25248 , -3.76639 , 5.71596 , -0.952665,0.158078,0.259694 --2.30903 , -3.80275 , 5.93931 , 0.600056,-0.387341,-0.699928 --2.17191 , -3.55709 , 5.82323 , -0.755833,-0.0128349,0.654639 --2.49024 , -3.96452 , 6.53385 , 0.45887,-0.665643,-0.588522 --2.57751 , -4.03541 , 6.84279 , -0.5285,-0.23313,-0.816295 --1.83688 , -2.95239 , 5.56185 , 0.615898,-0.386659,-0.686414 --1.78542 , -2.83825 , 5.57578 , 0.615899,-0.386659,-0.686413 --2.0628 , -3.17038 , 6.25755 , 0.156655,0.435323,-0.88654 --2.00357 , -3.04223 , 6.26725 , 0.0941782,-0.818078,0.567343 --1.98423 , -2.96774 , 6.36072 , 0.148956,-0.873397,0.463671 --2.02942 , -2.97778 , 6.59778 , 0.302156,0.930474,-0.207173 --2.01478 , -2.90618 , 6.70718 , 0.711082,0.457864,-0.533595 --1.91315 , -2.72589 , 6.61863 , -0.187581,0.256314,0.948218 --2.0831 , -2.88259 , 7.16496 , -0.754843,-0.635923,-0.160668 --1.80469 , -2.48785 , 6.64439 , -0.203561,0.435931,0.876657 --1.6775 , -2.28452 , 6.47452 , 0.189074,-0.576149,-0.795175 --1.66453 , -2.21721 , 6.58148 , -0.400802,-0.0439225,0.915111 --1.95963 , -2.49958 , 7.50231 , 0.55949,-0.777777,0.286415 --1.78234 , -2.24032 , 7.19578 , 0.506132,-0.532411,0.678505 --1.72444 , -2.11752 , 7.19837 , 0.54336,-0.255677,0.799619 --1.619 , -1.94548 , 7.06447 , -0.925748,-0.378117,-0.00413748 --1.59557 , -1.86126 , 7.15903 , -0.754869,-0.256114,0.603803 --1.6824 , -1.88653 , 7.58711 , 0.382953,-0.887551,0.256126 --1.7422 , -1.87941 , 7.9554 , -0.265082,0.952152,-0.152114 --1.48794 , -1.57002 , 7.34407 , 0.70381,0.510782,-0.493714 --1.47125 , -1.48917 , 7.47013 , -0.81457,-0.579549,-0.0244642 --1.57574 , -1.51116 , 8.00438 , 0.578777,0.59331,-0.559464 --1.2 , -1.12301 , 6.91467 , -0.162822,0.957627,0.237571 --1.13347 , -1.00592 , 6.85443 , -0.340162,-0.744199,0.574854 --1.43455 , -1.16913 , 8.13491 , 0.898683,0.39564,-0.18931 --1.14436 , -0.879623 , 7.25783 , -0.961816,0.24605,-0.119874 --1.03419 , -0.734605 , 7.02966 , -0.16928,0.219052,0.960917 --0.930759 , -0.598402 , 6.80669 , -0.438643,-0.759479,-0.480399 --0.957181 , -0.542686 , 7.10965 , -0.468482,-0.241958,-0.849695 --1.09623 , -0.53959 , 7.91617 , -0.469581,-0.750256,-0.465413 --0.975478 , -0.394542 , 7.61971 , -0.63708,-0.349647,-0.686932 --0.902562 , -0.278042 , 7.52369 , -0.234652,0.415804,0.878661 --0.833441 , -0.165481 , 7.43455 , 0.637301,-0.145391,-0.756775 --0.922595 , -0.099803 , 8.12612 , -0.332622,-0.677947,-0.655553 --0.755286 , 0.0384175 , 7.54327 , -0.779893,-0.251783,-0.573038 --0.66388 , 0.148082 , 7.31983 , -0.873607,0.424021,-0.238783 --0.617923 , 0.249092 , 7.32974 , -0.689279,0.720235,-0.0784611 --0.565894 , 0.350472 , 7.30815 , -0.134947,0.031226,0.990361 --0.564051 , 0.456943 , 7.59065 , -0.335715,0.914214,0.226956 --0.452099 , 0.545818 , 7.19018 , 0.0991577,0.215088,0.971548 --0.408162 , 0.644619 , 7.21235 , -0.107118,0.0735286,0.991524 --0.448534 , 0.788962 , 7.8348 , -0.364874,-0.690294,-0.624789 --0.333291 , 0.855139 , 7.35921 , -0.764249,0.1547,-0.626092 --0.290908 , 0.960318 , 7.40522 , 0.519384,0.0554635,-0.852739 --0.264456 , 1.08396 , 7.58711 , 0.240439,-0.597103,0.765283 --0.215378 , 1.19095 , 7.59918 , -0.94289,0.0602169,0.327615 --0.135422 , 1.25083 , 7.30442 , -0.386814,-0.496468,-0.777107 --0.0540387 , 1.29366 , 6.95956 , 0.149468,0.987428,-0.0514214 --0.0730815 , -1.43889 , -0.71104 , -0.096226,0.169652,0.980795 --0.0963205 , -1.47778 , -0.693198 , -0.0962259,0.169652,0.980795 --0.243126 , -1.75111 , -0.65628 , 0.0767897,-0.254293,-0.964074 --0.276096 , -1.81182 , -0.64893 , -0.0785168,0.235036,0.96881 --0.306365 , -1.86528 , -0.633766 , -0.0602279,0.184017,0.981076 --0.343142 , -1.9349 , -0.628287 , 0.0788337,-0.194419,-0.977746 --0.380072 , -2.00406 , -0.620764 , -0.102487,0.230906,0.967564 --0.414293 , -2.06598 , -0.605526 , -0.13393,0.188023,0.972991 --0.458212 , -2.1515 , -0.604183 , -0.0674371,0.1816,0.981058 --0.493943 , -2.21324 , -0.584781 , -0.0689673,0.186322,0.980065 --0.536305 , -2.29076 , -0.57341 , -0.100636,0.207523,0.97304 --0.578114 , -2.36889 , -0.559289 , 0.109564,-0.183809,-0.976837 --0.629045 , -2.46405 , -0.551975 , -0.107821,0.202251,0.97338 --0.675841 , -2.55024 , -0.537024 , -0.100187,0.204243,0.97378 --0.730854 , -2.65346 , -0.527883 , -0.109425,0.225219,0.968144 --0.778793 , -2.74118 , -0.506503 , -0.133846,0.210068,0.968482 --0.842571 , -2.86145 , -0.498792 , -0.15189,0.181174,0.971651 --0.903448 , -2.97339 , -0.482979 , -0.148103,0.143161,0.978555 --0.982298 , -3.12807 , -0.481878 , -0.0728672,0.193922,0.978307 --1.03736 , -3.22343 , -0.450054 , 0.0147672,0.271753,0.962254 --1.09637 , -3.32727 , -0.418253 , -0.0511654,0.277974,0.959225 --1.17218 , -3.46571 , -0.396027 , -0.0686426,0.239438,0.968482 --1.2439 , -3.59505 , -0.36558 , -0.0676417,0.252337,0.965272 --1.32439 , -3.74143 , -0.336563 , -0.0847116,0.215639,0.972792 --1.41771 , -3.91462 , -0.310261 , -0.0792225,0.21696,0.972961 --1.51269 , -4.08719 , -0.27785 , -0.0652214,0.22423,0.972351 --1.61213 , -4.26833 , -0.241469 , -0.0765436,0.223107,0.971784 --1.72059 , -4.46575 , -0.203114 , -0.0770401,0.224184,0.971497 --1.8474 , -4.69977 , -0.165567 , -0.0787055,0.219434,0.972448 --1.97484 , -4.93186 , -0.119459 , -0.0836423,0.232537,0.968984 --2.11701 , -5.1911 , -0.0698562 , -0.0879676,0.231498,0.96885 --2.27355 , -5.4752 , -0.015403 , 0.0534844,0.115311,0.991889 --2.44791 , -5.79478 , 0.0442971 , -0.0837328,0.219207,0.972079 --2.65084 , -6.16627 , 0.108351 , -0.077942,0.226322,0.970929 --2.86809 , -6.56345 , 0.183511 , 0.0786845,-0.226143,-0.970911 --3.1184 , -7.02105 , 0.267285 , -0.0729783,0.230027,0.970444 --3.38431 , -7.50315 , 0.366326 , -0.0737916,0.236903,0.968727 --3.6971 , -8.07285 , 0.478472 , -0.0730692,0.233452,0.969619 --4.05297 , -8.71953 , 0.608802 , -0.0675296,0.224213,0.972198 --4.4978 , -9.53221 , 0.759717 , -0.0687618,0.244503,0.967207 --4.99181 , -10.4283 , 0.94142 , -0.217832,0.40563,0.887701 --5.67682 , -11.684 , 1.16216 , -0.364898,0.397331,0.842008 --6.47319 , -13.136 , 1.43818 , -0.250713,0.320264,0.91355 --7.45948 , -14.9323 , 1.78877 , 0.384017,0.197265,0.902008 --7.95919 , -15.7791 , 2.14538 , -0.400334,-0.215521,-0.890664 --8.18126 , -16.0888 , 2.48948 , 0.406132,0.239763,0.8818 --10.083 , -19.5447 , 3.18854 , -0.944567,-0.253537,-0.208595 --10.2846 , -19.7858 , 3.61485 , 0.994025,0.0754655,0.0788679 --10.3798 , -19.8265 , 4.02402 , 0.979133,0.0825664,0.185692 --10.3008 , -19.5476 , 4.38393 , 0.981904,0.0434268,0.184335 --10.1904 , -19.2121 , 4.72516 , 0.981758,0.00213511,0.190125 --10.6701 , -19.95 , 5.28101 , -0.951608,-0.0975681,-0.291416 --10.7104 , -19.8853 , 5.68658 , -0.913211,-0.107382,-0.393083 --10.9421 , -20.1638 , 6.17996 , -0.945108,-0.155406,-0.287438 --11.1478 , -20.3895 , 6.67527 , 0.970094,0.135304,0.201519 --11.1781 , -20.3006 , 7.09289 , 0.975521,0.185,0.118885 --11.2145 , -20.2229 , 7.51553 , 0.969214,0.212501,-0.12437 --11.0413 , -19.7797 , 7.8173 , 0.981308,0.0596765,-0.18296 --11.2818 , -20.0545 , 8.36356 , 0.96452,0.0725089,-0.253857 --10.9816 , -19.3983 , 8.5727 , -0.963455,-0.0208446,0.267056 --10.8034 , -18.9541 , 8.84481 , 0.979126,-0.0703052,-0.19071 --10.8169 , -18.8414 , 9.24524 , 0.998972,0.00567361,-0.0449663 --10.4887 , -18.1524 , 9.3871 , 0.996097,0.0346743,0.0811705 --10.8925 , -18.6899 , 10.088 , 0.992486,0.0805799,0.092075 --10.8617 , -18.5007 , 10.4595 , -0.984611,-0.103215,-0.141024 --11.5121 , -19.4282 , 11.4177 , 0.980824,0.13479,0.140769 --11.365 , -18.5964 , 12.9694 , -0.964187,-0.153758,0.216106 --11.5556 , -18.7465 , 13.5937 , -0.960284,-0.15484,0.232119 --11.3442 , -18.2626 , 13.8032 , -0.960284,-0.15484,0.232119 --11.0851 , -17.7075 , 13.9466 , -0.962939,0.0428774,0.26629 --11.0498 , -17.5036 , 14.3332 , 0.973589,-0.0192945,-0.22749 --11.0341 , -17.3278 , 14.7439 , 0.98019,0.0525371,-0.190964 --11.0051 , -17.1316 , 15.1419 , 0.990173,0.122002,0.0683648 --10.773 , -16.6287 , 15.2852 , 0.986758,0.0339636,0.158601 --11.2885 , -17.243 , 16.3894 , 0.972079,0.103379,0.210653 --11.1556 , -16.8866 , 16.6705 , 0.972079,0.103379,0.210653 --2.93031 , -4.51822 , 6.3379 , -0.41665,0.835032,0.359338 --2.70944 , -4.15959 , 6.13192 , 0.776216,-0.298591,0.555276 --3.08397 , -4.62574 , 6.88246 , 0.992369,0.103627,-0.0668213 --3.05174 , -4.52519 , 6.98519 , -0.965678,0.258533,-0.0250251 --2.59191 , -3.85339 , 6.35532 , -0.351431,0.0442436,0.935168 --2.48677 , -3.66469 , 6.31149 , 0.458728,-0.0982311,-0.883131 --2.45233 , -3.56922 , 6.38737 , -0.458728,0.0982312,0.883131 --2.23769 , -3.24363 , 6.13114 , 0.0952794,-0.180541,0.978942 --2.22387 , -3.17788 , 6.23666 , 0.0775143,-0.647341,0.758249 --2.18365 , -3.08008 , 6.29517 , 0.193363,-0.714549,0.672332 --2.12048 , -2.95299 , 6.30448 , -0.195623,0.755432,-0.625343 --2.14518 , -2.93504 , 6.49327 , 0.0493547,-0.915036,0.400342 --2.12204 , -2.85725 , 6.58689 , -0.195036,0.754888,-0.626183 --2.12474 , -2.80876 , 6.7364 , 0.169951,-0.734253,0.657259 --2.047 , -2.66677 , 6.71331 , 0.596075,-0.272401,0.755309 --1.9118 , -2.45927 , 6.55286 , -0.0261521,0.422368,0.906047 --1.80036 , -2.283 , 6.43635 , 0.254956,-0.552605,-0.79349 --1.72925 , -2.15512 , 6.40824 , -0.400802,-0.0439224,0.915111 --1.99522 , -2.39158 , 7.21028 , 0.577412,-0.339213,-0.74265 --1.95053 , -2.2869 , 7.26171 , -0.232202,0.438345,-0.868295 --1.95577 , -2.2324 , 7.44226 , -0.890565,0.0195063,0.454438 --1.83928 , -2.05434 , 7.30495 , -0.381322,0.431609,-0.8175 --1.8383 , -1.99217 , 7.47415 , 0.194542,-0.636507,0.746332 --1.67581 , -1.77519 , 7.19437 , 0.627078,0.0525873,-0.77718 --1.62973 , -1.67138 , 7.23315 , -0.341686,0.0686991,0.9373 --1.54973 , -1.5373 , 7.16956 , -0.318594,0.164415,0.933523 --1.93887 , -1.81134 , 8.54519 , -0.667925,0.0406104,-0.74312 --1.60219 , -1.45353 , 7.6983 , -0.397773,-0.914346,0.0758232 --1.3226 , -1.1607 , 6.98672 , -0.0253067,0.994972,0.0968997 --1.22346 , -1.02224 , 6.83537 , 0.064841,-0.882175,0.466436 --1.5139 , -1.16968 , 8.01718 , -0.676202,-0.30804,0.669225 --1.51761 , -1.09559 , 8.25344 , -0.412538,-0.910917,-0.00663014 --1.20358 , -0.809343 , 7.32831 , -0.908702,-0.403329,0.107643 --1.03726 , -0.635902 , 6.89891 , -0.398928,-0.682972,-0.611887 --1.01032 , -0.550846 , 6.99159 , -0.18691,0.0176334,-0.982219 --1.2491 , -0.600939 , 8.17242 , -0.20549,-0.928971,0.307873 --1.25268 , -0.512871 , 8.4408 , -0.751357,0.312053,-0.581452 --1.16543 , -0.381979 , 8.32995 , -0.853271,0.100175,0.511756 --1.16721 , -0.285584 , 8.61528 , 0.998836,0.034966,-0.0332306 --1.02367 , -0.140289 , 8.23577 , -0.404948,-0.56887,-0.715824 --0.844559 , 0.00103498 , 7.64651 , -0.875355,-0.178941,-0.449148 --0.791743 , 0.106531 , 7.65078 , -0.78707,-0.326368,-0.523455 --0.70844 , 0.213486 , 7.49581 , -0.854706,0.386704,-0.34632 --0.687036 , 0.31638 , 7.67296 , 0.556465,-0.720184,0.414344 --0.672243 , 0.425538 , 7.89775 , 0.718029,-0.650572,0.247367 --0.527561 , 0.514968 , 7.35156 , -0.824257,-0.0768131,0.560981 --0.469395 , 0.611964 , 7.30603 , 0.559125,0.260257,0.787176 --0.406058 , 0.704341 , 7.21907 , 0.266465,-0.314457,0.911105 --0.385764 , 0.819988 , 7.43612 , 0.135207,-0.601296,0.787504 --0.33434 , 0.920311 , 7.43404 , -0.604681,0.0478871,-0.795027 --0.281808 , 1.02 , 7.43024 , -0.353563,-0.73445,0.57929 --0.246161 , 1.13938 , 7.57215 , 0.969675,-0.145007,-0.196732 --0.180414 , 1.22612 , 7.4558 , 0.646085,-0.165778,0.745045 --0.0810888 , 1.24983 , 6.97433 , 0.629325,-0.519533,-0.577958 --0.126231 , -1.43601 , -0.709997 , -0.0962259,0.169653,0.980795 --0.309563 , -1.75001 , -0.659423 , -0.104277,0.214267,0.971193 --0.344537 , -1.81009 , -0.651439 , -0.0754919,0.245568,0.966435 --0.376802 , -1.86295 , -0.635738 , 0.0822081,-0.199186,-0.976507 --0.418436 , -1.93873 , -0.635395 , -0.117876,0.15332,0.981121 --0.457383 , -2.00722 , -0.627044 , -0.109045,0.198376,0.974041 --0.497687 , -2.07598 , -0.616574 , -0.0939851,0.224047,0.970036 --0.534071 , -2.13679 , -0.598561 , -0.0955642,0.187338,0.977636 --0.582371 , -2.22158 , -0.593904 , 0.11893,-0.191433,-0.974274 --0.629898 , -2.306 , -0.586499 , -0.129749,0.211341,0.968762 --0.679068 , -2.3915 , -0.576096 , -0.111433,0.199838,0.973472 --0.728449 , -2.47635 , -0.562872 , -0.102584,0.216323,0.970918 --0.77923 , -2.56135 , -0.546945 , -0.118302,0.199261,0.972779 --0.837281 , -2.66353 , -0.536415 , -0.123966,0.208806,0.970068 --0.892395 , -2.7575 , -0.51827 , -0.146432,0.182518,0.972237 --0.958996 , -2.87571 , -0.509076 , -0.135096,0.16202,0.977496 --1.03542 , -3.01215 , -0.503278 , -0.124473,0.175914,0.976504 --1.10873 , -3.13922 , -0.489089 , -0.012526,0.289631,0.957056 --1.16315 , -3.22425 , -0.452352 , 0.0284026,-0.274571,-0.961147 --1.24125 , -3.36058 , -0.432829 , -0.0863451,0.239499,0.96705 --1.31274 , -3.47941 , -0.402068 , -0.0724508,0.258218,0.963366 --1.39298 , -3.61534 , -0.373028 , -0.0744247,0.237646,0.968497 --1.4877 , -3.77685 , -0.347823 , -0.0758521,0.212877,0.97413 --1.58212 , -3.93821 , -0.316462 , -0.067381,0.221189,0.972901 --1.69117 , -4.12473 , -0.287086 , -0.07783,0.219234,0.972563 --1.8012 , -4.31162 , -0.250506 , -0.0810589,0.219624,0.972211 --1.92528 , -4.52437 , -0.213551 , -0.083172,0.224463,0.970927 --2.05493 , -4.74503 , -0.170704 , -0.0800889,0.232951,0.969185 --2.20359 , -4.99971 , -0.127137 , -0.0514632,-0.177872,-0.982707 --2.35439 , -5.25393 , -0.0737632 , 0.06554,0.243474,0.967691 --2.53325 , -5.55996 , -0.0200268 , 0.00482108,0.121989,0.99252 --2.73753 , -5.90813 , 0.0383509 , -0.0910432,0.224328,0.970252 --2.95604 , -6.2822 , 0.106862 , -0.0873114,0.229347,0.969421 --3.20536 , -6.70688 , 0.183376 , -0.0837041,0.231713,0.969176 --3.47527 , -7.16573 , 0.273168 , -0.0805637,0.241877,0.966956 --3.77153 , -7.66556 , 0.377138 , -0.0669291,0.223857,0.972321 --4.14014 , -8.2943 , 0.4926 , -0.0662821,0.219481,0.973363 --4.56527 , -9.01718 , 0.628813 , 0.0103043,-0.170241,-0.985349 --5.04098 , -9.82292 , 0.791484 , -0.0451248,0.298992,0.953188 --5.67864 , -10.9131 , 0.985063 , 0.348983,-0.404826,-0.845178 --6.41396 , -12.162 , 1.22426 , -0.186038,0.217506,0.958166 --7.31902 , -13.7 , 1.5239 , 0.196297,0.185397,0.962858 --7.92201 , -14.6778 , 1.85483 , 0.384016,0.197265,0.902008 --8.18722 , -15.0478 , 2.18105 , 0.384017,0.197265,0.902008 --8.83143 , -16.0769 , 2.58585 , 0.235796,0.267337,0.934308 --10.2506 , -18.441 , 3.18715 , -0.984755,-0.116923,-0.128791 --10.3392 , -18.4707 , 3.57178 , -0.986082,-0.165867,-0.0113973 --10.3686 , -18.3987 , 3.94455 , 0.957921,0.278913,0.0677911 --10.3761 , -18.2873 , 4.31046 , -0.956016,-0.260836,-0.134156 --10.4599 , -18.3065 , 4.70068 , -0.926289,-0.357467,-0.119186 --10.5905 , -18.4031 , 5.11233 , -0.93909,-0.328902,-0.0996711 --10.618 , -18.3243 , 5.48996 , -0.950413,-0.307789,-0.0445179 --10.6472 , -18.2479 , 5.86904 , -0.959243,-0.282315,-0.0122901 --10.6722 , -18.1663 , 6.24787 , -0.956988,-0.289198,-0.0231905 --10.6946 , -18.0781 , 6.62604 , -0.945834,-0.324539,0.00855326 --10.7134 , -17.9837 , 7.00325 , -0.943393,-0.33122,0.0174108 --10.7445 , -17.9077 , 7.38825 , -0.942677,-0.333356,0.0152783 --10.7609 , -17.8103 , 7.76755 , -0.945089,-0.326466,0.01503 --10.7947 , -17.7386 , 8.15866 , -0.968048,-0.238074,0.0787604 --10.8155 , -17.6442 , 8.54335 , -0.966866,-0.220227,0.12911 --10.8466 , -17.5672 , 8.93839 , 0.972632,0.23021,-0.0314643 --10.7398 , -17.2726 , 9.23515 , 0.98422,0.16175,0.0717544 --10.9549 , -17.48 , 9.7718 , -0.961697,-0.190549,-0.197051 --10.9606 , -17.3587 , 10.1576 , 0.956845,0.199074,0.211701 --11.0182 , -17.3161 , 10.588 , -0.980563,-0.172422,-0.0936366 --11.0308 , -17.205 , 10.9867 , -0.948952,-0.315343,0.00694329 --11.0557 , -17.1093 , 11.3983 , -0.94911,-0.314444,0.017781 --11.0812 , -17.0134 , 11.815 , -0.949616,-0.311973,0.0300241 --11.0977 , -16.9027 , 12.2276 , -0.949755,-0.310595,0.0386745 --11.1151 , -16.7929 , 12.6455 , -0.966459,-0.248238,0.0658434 --11.1381 , -16.6889 , 13.0737 , -0.972458,-0.217484,0.0838234 --11.1619 , -16.5845 , 13.5079 , 0.992173,0.0849922,-0.0914879 --11.1861 , -16.4788 , 13.9484 , 0.993786,0.0744414,-0.0827497 --11.0716 , -16.1732 , 14.2362 , -0.983892,-0.062653,0.167425 --11.1542 , -16.1484 , 14.7533 , 0.996382,0.0724976,0.0443526 --10.957 , -15.7266 , 14.9405 , 0.988058,0.0774705,0.133188 --11.423 , -16.2281 , 15.9485 , 0.973393,0.106914,0.202673 --11.3623 , -15.9929 , 16.3188 , 0.973393,0.106914,0.202673 --3.13912 , -4.51091 , 6.29592 , -0.487255,-0.370032,0.790986 --3.1227 , -4.43818 , 6.41794 , -0.487256,-0.370032,0.790986 --3.16657 , -4.44436 , 6.6347 , 0.530344,0.821053,0.211206 --2.97316 , -4.14487 , 6.48567 , 0.441288,0.0762082,0.894124 --2.64134 , -3.67547 , 6.10012 , 0.651197,-0.701798,-0.288829 --2.72678 , -3.73612 , 6.37954 , -0.00265516,0.75514,0.655558 --2.56503 , -3.4863 , 6.24708 , -0.71613,0.305449,0.627582 --2.52273 , -3.38832 , 6.31403 , -0.638828,0.0872677,-0.764384 --2.53144 , -3.34979 , 6.46914 , -0.61214,0.161074,-0.77417 --2.3465 , -3.08202 , 6.27361 , 0.161411,-0.771261,0.615714 --2.35661 , -3.04757 , 6.43272 , 0.24146,-0.817898,0.522245 --2.6902 , -3.3826 , 7.22084 , -0.464272,0.814195,-0.348623 --2.28388 , -2.86633 , 6.57771 , 0.0236337,-0.835311,0.54927 --2.27771 , -2.80949 , 6.71221 , -0.0607547,-0.755992,0.651755 --2.43004 , -2.92568 , 7.18102 , -0.182884,0.311868,0.932358 --2.2383 , -2.66247 , 6.93111 , -0.300959,-0.900737,0.313203 --2.23514 , -2.60586 , 7.08117 , 0.706559,0.400737,-0.583253 --2.24087 , -2.55654 , 7.25637 , 0.0542677,-0.651144,0.757011 --2.55122 , -2.81696 , 8.14829 , 0.220258,0.185578,0.957626 --2.10455 , -2.30536 , 7.2724 , 0.406713,0.151102,-0.900973 --2.17629 , -2.3176 , 7.6192 , -0.471629,-0.419436,0.775654 --2.03441 , -2.12129 , 7.44317 , -0.156322,0.69196,-0.704809 --2.02177 , -2.04814 , 7.58804 , -0.759976,-0.371712,0.533167 --2.00748 , -1.9723 , 7.73264 , 0.135055,-0.979664,0.148389 --1.88828 , -1.80384 , 7.59791 , 0.0255162,0.997334,0.0683612 --1.65642 , -1.54185 , 7.1316 , -0.518745,0.205808,0.829787 --1.60462 , -1.43783 , 7.15791 , -0.217153,0.391665,0.894116 --1.72103 , -1.46924 , 7.68827 , 0.661571,0.747092,-0.0646358 --1.74262 , -1.41711 , 7.95437 , 0.430072,-0.66586,0.609646 --1.53367 , -1.19336 , 7.50434 , 0.998834,-0.0459854,0.0147144 --1.57532 , -1.15387 , 7.84262 , -0.982291,0.152949,0.10822 --1.53955 , -1.05591 , 7.93715 , -0.982081,-0.166654,0.0879951 --1.50997 , -0.961291 , 8.05881 , -0.975241,-0.195785,0.10283 --1.15651 , -0.674251 , 7.01741 , 0.199478,0.0432227,0.978949 --1.02949 , -0.536588 , 6.74857 , -0.570547,-0.784312,0.243578 --1.0437 , -0.475967 , 7.00364 , 0.103046,-0.292081,0.950826 --1.42012 , -0.573336 , 8.72444 , -0.621065,0.649248,-0.439038 --1.28683 , -0.423194 , 8.45233 , 0.71268,-0.63279,-0.30276 --1.2109 , -0.300731 , 8.40895 , -0.910842,0.077456,0.405423 --1.20744 , -0.200386 , 8.68412 , -0.909074,-0.394392,0.134314 --1.01471 , -0.0509862 , 8.0994 , 0.502603,0.543618,0.672213 --0.860045 , 0.0752367 , 7.64628 , -0.826761,-0.403405,-0.392084 --0.836196 , 0.176163 , 7.81686 , -0.912565,-0.191658,-0.361238 --0.744449 , 0.28219 , 7.64217 , 0.467322,-0.1721,0.867174 --0.781893 , 0.392212 , 8.16343 , -0.579465,0.606679,-0.544206 --0.713128 , 0.502192 , 8.12223 , -0.885456,0.183676,-0.426886 --0.623498 , 0.604191 , 7.94079 , 0.684343,-0.382842,0.62057 --0.458298 , 0.669865 , 7.2539 , 0.621069,0.125322,0.773672 --0.539209 , 0.835336 , 8.17302 , 0.0613513,-0.0842266,0.994556 --0.38065 , 0.880862 , 7.46212 , -0.421175,-0.5728,0.703215 --0.310207 , 0.967586 , 7.34119 , -0.775781,0.442807,0.449539 --0.253964 , 1.06419 , 7.32695 , -0.0223758,0.706219,0.70764 --0.222276 , 1.18936 , 7.52749 , -0.942768,-0.190443,-0.273713 --0.143444 , 1.25564 , 7.30284 , -0.386814,-0.496468,-0.777107 --0.0343502 , 1.25352 , 6.71353 , 0.998887,-0.0277551,-0.0381489 --0.179173 , -1.43209 , -0.708762 , -0.11313,0.190807,0.975087 --0.345075 , -1.70366 , -0.681068 , -0.0880337,0.193537,0.977135 --0.378868 , -1.75566 , -0.668141 , -0.0761226,0.23526,0.968947 --0.415616 , -1.81414 , -0.659623 , -0.0729021,0.233923,0.969518 --0.452967 , -1.87413 , -0.648959 , -0.0992801,0.179768,0.978686 --0.497595 , -1.94901 , -0.647811 , -0.0615149,0.159377,0.985299 --0.535235 , -2.00812 , -0.633256 , -0.0986527,0.220669,0.970347 --0.577564 , -2.07619 , -0.621859 , -0.0805964,0.185317,0.979368 --0.627251 , -2.1589 , -0.618909 , -0.114053,0.173923,0.978132 --0.674244 , -2.23432 , -0.608047 , -0.0987497,0.194508,0.975918 --0.721654 , -2.31015 , -0.594556 , -0.103825,0.195659,0.975161 --0.772636 , -2.39393 , -0.583133 , -0.0781557,0.191007,0.978472 --0.825025 , -2.47784 , -0.568909 , -0.086153,0.206755,0.974592 --0.882227 , -2.57032 , -0.55619 , -0.0855945,0.174072,0.981006 --0.944041 , -2.67031 , -0.544688 , -0.108665,0.181684,0.977335 --1.01415 , -2.7871 , -0.537925 , -0.100213,0.171455,0.980082 --1.08137 , -2.89555 , -0.522963 , -0.141363,0.138284,0.980252 --1.16602 , -3.03776 , -0.519354 , -0.0347807,0.233353,0.97177 --1.21857 , -3.11347 , -0.480988 , 0.0171473,-0.25673,-0.966331 --1.29645 , -3.23926 , -0.461052 , -0.0655922,0.24237,0.967964 --1.37934 , -3.37304 , -0.439995 , -0.0494375,0.243157,0.968726 --1.45464 , -3.48952 , -0.40758 , -0.0470482,0.243246,0.968823 --1.54884 , -3.63972 , -0.382938 , -0.0669222,0.215512,0.974205 --1.64743 , -3.79874 , -0.355397 , 0.0613544,-0.221292,-0.973276 --1.74293 , -3.94835 , -0.319367 , -0.061448,0.210343,0.975695 --1.86727 , -4.14952 , -0.292757 , -0.0700429,0.204587,0.976339 --1.98765 , -4.34118 , -0.256077 , -0.0673997,0.221868,0.972745 --2.12308 , -4.55839 , -0.218753 , -0.0534739,0.216852,0.974739 --2.27465 , -4.80056 , -0.179155 , 0.0779911,0.271652,0.95923 --2.43217 , -5.05122 , -0.131815 , 0.0131307,0.134707,0.990798 --2.60502 , -5.32655 , -0.0799384 , -0.0913096,0.060854,0.993961 --2.81279 , -5.66153 , -0.0279874 , -0.148598,0.121797,0.981369 --2.59179 , -5.22552 , 0.159519 , 0.877946,0.0516067,0.475971 --3.26841 , -6.38757 , 0.107183 , -0.068676,0.217647,0.973609 --3.54089 , -6.82147 , 0.187549 , -0.0584478,0.222778,0.973116 --3.84473 , -7.30598 , 0.2803 , -0.0582357,0.2324,0.970875 --2.48482 , -4.89192 , 0.624077 , 0.777794,0.626825,-0.0461254 --2.49203 , -4.87066 , 0.728105 , -0.756766,-0.651329,0.0554601 --2.48431 , -4.82353 , 0.832851 , 0.71832,0.693912,-0.0500163 --2.47577 , -4.77385 , 0.935644 , 0.603487,0.79737,-0.00207399 --2.22613 , -4.31766 , 1.03685 , 0.692792,-0.713422,0.105204 --2.36663 , -4.52448 , 1.13343 , -0.661536,0.695841,-0.279601 --2.5278 , -4.76301 , 1.23995 , -0.389384,0.908741,-0.150234 --8.17691 , -14.0983 , 1.90201 , -0.203262,-0.228046,-0.952197 --8.5869 , -14.6809 , 2.2412 , 0.384016,0.197266,0.902008 --10.2434 , -17.2956 , 2.81047 , 0.998507,0.0311119,0.0448909 --10.6421 , -17.8292 , 3.23701 , 0.999553,0.0290421,0.00708816 --10.7044 , -17.8121 , 3.60995 , 0.988302,0.0276719,0.149978 --10.4185 , -17.2345 , 3.89386 , 0.964844,-0.096649,0.244409 --10.3212 , -16.9653 , 4.21344 , 0.960824,-0.0271875,0.275824 --10.8154 , -17.6348 , 4.71739 , -0.922365,-0.200149,-0.330428 --10.8491 , -17.5697 , 5.08728 , -0.951335,-0.282732,-0.122575 --10.81 , -17.3916 , 5.43029 , -0.957449,-0.271268,-0.0985112 --10.9105 , -17.4302 , 5.82839 , -0.940463,-0.33745,-0.0407 --10.9448 , -17.3652 , 6.20236 , -0.938342,-0.342336,-0.0481757 --10.9752 , -17.2927 , 6.57608 , -0.942759,-0.333416,0.00631316 --10.9912 , -17.1997 , 6.94468 , -0.944551,-0.328049,0.0144187 --11.0203 , -17.124 , 7.32084 , -0.945161,-0.325817,0.0226725 --11.0451 , -17.0429 , 7.69724 , -0.949635,-0.29708,0.0996847 --11.0506 , -16.9319 , 8.06389 , -0.957179,-0.250472,0.145163 --10.9426 , -16.6516 , 8.35864 , -0.965905,-0.0379855,0.256097 --10.9621 , -16.5617 , 8.73363 , 0.992188,0.066253,-0.105703 --10.7836 , -16.1814 , 8.97177 , 0.99489,0.0887941,0.0480525 --11.033 , -16.4243 , 9.51388 , -0.97056,-0.118692,-0.209583 --11.0307 , -16.3003 , 9.88139 , 0.975641,0.0982226,0.196157 --11.2651 , -16.5132 , 10.4394 , 0.974043,0.199185,0.107547 --11.2866 , -16.419 , 10.8378 , -0.965468,-0.247875,-0.0801876 --11.3149 , -16.3317 , 11.2452 , -0.94911,-0.314444,0.017781 --11.3494 , -16.2523 , 11.663 , -0.949616,-0.311974,0.0300241 --11.3686 , -16.151 , 12.0726 , 0.974444,0.22148,-0.0374987 --11.3587 , -16.0063 , 12.4578 , 0.980231,0.185982,-0.0675193 --11.3908 , -15.9187 , 12.8878 , 0.953624,0.247516,0.171281 --11.2759 , -15.6315 , 13.1732 , 0.984274,-0.0159737,-0.175922 --11.2185 , -15.4223 , 13.5159 , 0.988715,0.00990819,-0.149479 --11.1731 , -15.2274 , 13.8715 , 0.989901,0.0517458,-0.131982 --11.1885 , -15.1131 , 14.2979 , 0.981282,0.0521617,-0.185379 --11.1298 , -14.9003 , 14.6441 , 0.992505,0.117517,0.0335273 --10.9053 , -14.4715 , 14.7909 , 0.992505,0.117517,0.0335273 --11.4356 , -15.0156 , 15.8662 , 0.969034,0.0811817,0.233201 --11.314 , -14.7164 , 16.1521 , 0.969034,0.0811817,0.233201 --3.30866 , -4.44987 , 6.20012 , -0.625583,-0.767784,0.138398 --3.24794 , -4.32672 , 6.26348 , 0.487255,0.370032,-0.790986 --3.19619 , -4.21499 , 6.33708 , -0.487256,-0.370032,0.790986 --2.69261 , -3.55801 , 5.74373 , 0.417801,0.881663,-0.219347 --2.81337 , -3.66042 , 6.05831 , 0.0875919,0.942054,0.323824 --2.89458 , -3.71056 , 6.32251 , -0.0058846,0.880656,0.473719 --3.13883 , -3.9478 , 6.85786 , -0.986695,0.158123,0.0378078 --3.06815 , -3.81459 , 6.90058 , -0.715615,-0.495834,0.491979 --2.86561 , -3.53097 , 6.71634 , -0.538495,0.79447,-0.280786 --2.51217 , -3.08416 , 6.25784 , -0.56648,0.410191,-0.714733 --2.56121 , -3.09283 , 6.48681 , 0.506973,-0.613782,0.605186 --2.85936 , -3.36976 , 7.17687 , -0.57387,0.738475,-0.354018 --2.80712 , -3.2595 , 7.24395 , -0.573869,0.738475,-0.354018 --2.96122 , -3.3679 , 7.70768 , -0.275098,0.960244,-0.0474702 --3.05583 , -3.40723 , 8.07389 , -0.842036,0.517503,-0.152203 --3.00058 , -3.28732 , 8.15053 , -0.842036,0.517503,-0.152203 --2.3851 , -2.60586 , 7.059 , -0.529258,-0.763358,0.370366 --2.37941 , -2.54652 , 7.21007 , -0.425935,-0.609715,0.668451 --2.52531 , -2.63176 , 7.69899 , -0.876627,-0.406134,-0.258031 --2.24382 , -2.30555 , 7.24695 , -0.0873682,0.00272145,0.996172 --2.15653 , -2.168 , 7.21386 , -0.358343,-0.0353107,0.932922 --2.1086 , -2.06788 , 7.27253 , -0.677589,-0.112515,0.726783 --2.08155 , -1.98666 , 7.38232 , -0.917941,-0.236552,0.318476 --2.09954 , -1.94209 , 7.6061 , -0.497588,-0.724068,0.477631 --2.17494 , -1.94429 , 7.99188 , 0.289355,0.956274,-0.0425826 --2.28533 , -1.96729 , 8.48892 , 0.76667,-0.360705,0.531139 --1.69871 , -1.43318 , 7.09322 , -0.525887,0.359845,0.770685 --1.65993 , -1.34393 , 7.16455 , -0.0568485,0.426372,0.90276 --1.74602 , -1.34625 , 7.60281 , -0.864664,-0.256112,-0.432161 --1.87428 , -1.36974 , 8.19268 , -0.0587818,-0.387898,0.919826 --1.57273 , -1.09377 , 7.48181 , 0.989178,0.0624705,-0.13276 --1.69875 , -1.10528 , 8.09155 , -0.171354,0.985153,0.0105336 --1.61799 , -0.980477 , 8.0551 , -0.975241,-0.195785,0.10283 --1.23808 , -0.688731 , 6.99199 , 0.154896,0.217083,0.963785 --1.15652 , -0.578484 , 6.90656 , 0.671789,-0.435089,0.599498 --1.20931 , -0.536083 , 7.30636 , -0.365813,0.625418,0.689227 --1.05789 , -0.39368 , 6.95779 , -0.242842,-0.936877,0.251574 --1.33314 , -0.430837 , 8.26384 , 0.698015,-0.0156859,-0.715911 --1.26729 , -0.316582 , 8.27018 , 0.756761,-0.165883,-0.632294 --1.30133 , -0.232339 , 8.70161 , -0.835114,-0.316552,-0.449866 --1.13647 , -0.0903982 , 8.28579 , -0.250419,-0.572217,-0.780934 --1.01473 , 0.0316028 , 8.0314 , 0.434263,0.694981,0.573076 --0.941724 , 0.141279 , 7.98874 , 0.830849,-0.535257,-0.152283 --0.863066 , 0.249269 , 7.91429 , -0.738312,0.639363,0.214732 --0.946408 , 0.360939 , 8.68256 , -0.465284,-0.826114,0.317878 --0.787211 , 0.466593 , 8.18128 , -0.815354,0.349715,-0.461408 --0.696161 , 0.56957 , 8.0316 , -0.885456,0.183676,-0.426886 --0.518862 , 0.63807 , 7.32719 , -0.837206,-0.000486909,-0.546887 --0.465932 , 0.735776 , 7.34977 , -0.723284,0.616024,-0.312049 --0.438899 , 0.848997 , 7.5581 , -0.804577,-0.107412,-0.584053 --0.367322 , 0.938782 , 7.45836 , -0.0515097,0.688343,0.723554 --0.319026 , 1.04554 , 7.53426 , -0.391684,-0.691579,0.606879 --0.267009 , 1.15313 , 7.59833 , -0.940544,0.0740531,0.3315 --0.192312 , 1.23179 , 7.45373 , 0.646085,-0.165778,0.745045 --0.083793 , 1.24836 , 6.94372 , 0.673637,-0.619092,-0.403656 --0.408735 , -1.69158 , -0.678669 , -0.0664029,0.22727,0.971565 --0.45018 , -1.75672 , -0.677428 , -0.0447405,0.191298,0.980512 --0.485131 , -1.80793 , -0.662093 , -0.0710209,0.225617,0.971624 --0.524249 , -1.86635 , -0.650992 , -0.0497995,0.160357,0.985802 --0.567799 , -1.93282 , -0.64354 , 0.0815095,-0.143139,-0.98634 --0.618677 , -2.01403 , -0.644922 , -0.0589755,0.19847,0.978331 --0.659685 , -2.07277 , -0.627516 , 0.0583494,-0.165685,-0.984451 --0.712373 , -2.15455 , -0.623662 , -0.0919001,0.158182,0.983124 --0.761155 , -2.22833 , -0.612072 , -0.0691053,0.18706,0.979915 --0.814707 , -2.31082 , -0.602571 , -0.0577941,0.184112,0.981205 --0.86943 , -2.39248 , -0.590466 , -0.0653305,0.180905,0.981328 --0.928958 , -2.48274 , -0.579964 , -0.0766632,0.17754,0.981123 --0.993336 , -2.58147 , -0.57048 , -0.075852,0.174527,0.981727 --1.05381 , -2.67221 , -0.55326 , -0.0862774,0.168205,0.981969 --1.12331 , -2.77857 , -0.541097 , 0.112633,-0.137522,-0.984074 --1.21216 , -2.91833 , -0.540821 , -0.0758884,0.174429,0.981741 --1.28371 , -3.02453 , -0.520213 , -0.00563409,0.293203,0.956034 --1.34715 , -3.11565 , -0.48812 , -0.0193227,0.253863,0.967047 --1.43425 , -3.24696 , -0.4703 , -0.0402969,0.210607,0.97674 --1.51748 , -3.37013 , -0.444158 , -0.0345031,0.238675,0.970486 --1.60105 , -3.4923 , -0.413542 , -0.0444819,0.226911,0.972899 --1.70476 , -3.64879 , -0.390039 , 0.058373,-0.202414,-0.977559 --1.80891 , -3.80395 , -0.360699 , 0.056208,-0.221995,-0.973426 --1.92319 , -3.97639 , -0.330474 , -0.0562003,0.195905,0.979011 --2.05886 , -4.18209 , -0.303787 , -0.0503181,0.212598,0.975843 --2.18585 , -4.36945 , -0.264456 , 0.0454268,-0.218057,-0.974878 --2.32338 , -4.57454 , -0.221806 , -0.054253,0.21106,0.975966 --2.48255 , -4.81212 , -0.179289 , 0.0335629,0.414081,0.909621 --2.63786 , -5.03992 , -0.125534 , -0.144166,0.256413,0.955756 --2.53769 , -4.83528 , 0.0231968 , -0.981709,0.0914935,-0.16696 --2.54175 , -4.80647 , 0.131923 , 0.368123,-0.8824,0.29301 --2.55976 , -4.80153 , 0.235544 , 0.616972,0.785218,-0.0527126 --2.55602 , -4.7611 , 0.343768 , -0.837845,-0.545811,0.0102691 --2.56628 , -4.74439 , 0.447569 , 0.810373,0.585546,-0.0207687 --2.58091 , -4.73426 , 0.549859 , -0.800554,-0.599048,0.0159397 --2.59434 , -4.72338 , 0.65217 , -0.756766,-0.651329,0.0554601 --2.61219 , -4.71893 , 0.753651 , 0.71832,0.693912,-0.0500164 --2.61785 , -4.69633 , 0.855849 , -0.639347,-0.768055,-0.0364188 --2.62913 , -4.68091 , 0.957294 , 0.603486,0.797371,-0.00207402 --2.65472 , -4.68828 , 1.0584 , -0.438218,-0.89601,-0.071634 --2.69542 , -4.72099 , 1.16113 , -0.389384,0.908741,-0.150234 --2.73556 , -4.75041 , 1.26521 , -0.389384,0.908741,-0.150234 --2.71521 , -4.68643 , 1.36493 , -0.389384,0.908741,-0.150234 --2.70966 , -4.64709 , 1.465 , -0.389384,0.908741,-0.150234 --5.06964 , -8.22284 , 1.9509 , -0.953756,0.0885232,-0.287251 --10.4819 , -16.3893 , 3.17578 , 0.987628,0.13363,0.0820555 --10.498 , -16.3073 , 3.51664 , 0.987628,0.13363,0.0820555 --10.5115 , -16.2199 , 3.85596 , -0.970411,-0.11721,-0.211101 --10.5986 , -16.2424 , 4.21587 , 0.96011,0.0763756,0.268989 --10.9195 , -16.6101 , 4.65388 , -0.906644,-0.1356,-0.399512 --10.9228 , -16.5049 , 5.00032 , -0.927128,-0.101856,-0.360636 --11.1658 , -16.7504 , 5.43658 , -0.954741,-0.251539,-0.158737 --11.2011 , -16.6899 , 5.80237 , -0.949224,-0.291718,-0.11779 --11.2163 , -16.5992 , 6.16095 , -0.942652,-0.333424,0.0153621 --11.245 , -16.5278 , 6.52661 , -0.945497,-0.325224,0.0162569 --11.2587 , -16.434 , 6.88647 , -0.946104,-0.32336,0.0180245 --11.2745 , -16.3434 , 7.24866 , 0.97574,0.205146,-0.0764658 --11.3087 , -16.2784 , 7.62263 , 0.980138,0.0946493,-0.174272 --11.1125 , -15.8913 , 7.86424 , -0.97556,0.00831889,0.219576 --11.0076 , -15.634 , 8.151 , -0.976799,-0.0420298,0.209993 --11.0313 , -15.5545 , 8.51582 , 0.989589,0.0726744,-0.124227 --10.8482 , -15.1923 , 8.74318 , 0.993321,-0.0124115,0.114714 --11.095 , -15.4158 , 9.26577 , 0.998661,0.0152769,0.0494344 --11.0961 , -15.3035 , 9.62372 , 0.993218,0.0371476,0.110175 --10.963 , -15.011 , 9.88027 , 0.99028,0.0110319,0.13865 --11.4583 , -15.0683 , 12.154 , 0.998663,-0.0516906,-0.000929559 --12.3281 , -16.0531 , 13.3792 , -0.959104,-0.0974268,0.265758 --11.3418 , -14.6724 , 12.8191 , 0.993505,-0.0353727,-0.108149 --11.2752 , -14.4639 , 13.1439 , 0.998453,-0.00421124,-0.0554396 --11.2793 , -14.3424 , 13.5426 , 0.997796,0.0219466,-0.0626237 --11.2159 , -14.1361 , 13.8731 , 0.987042,0.0143471,-0.159819 --11.2723 , -14.0768 , 14.3402 , 0.97995,0.0105482,-0.198962 --11.0672 , -13.6978 , 14.5124 , 0.996524,0.0648152,-0.0523394 --11.5671 , -14.1655 , 15.521 , 0.973014,0.0664399,0.220973 --11.4943 , -13.9419 , 15.8651 , 0.973014,0.0664399,0.220973 --3.45444 , -4.25901 , 6.36849 , -0.401063,-0.39561,0.826221 --3.33554 , -4.07468 , 6.35555 , -0.189362,-0.102247,0.976569 --2.83582 , -3.46377 , 5.79391 , 0.149658,0.984802,0.0881378 --3.1797 , -3.80445 , 6.43102 , 0.818159,-0.486277,0.30684 --3.07558 , -3.64148 , 6.42407 , 0.487549,-0.858212,0.160527 --3.11735 , -3.59055 , 6.79204 , 0.747862,-0.663067,0.0323167 --3.17124 , -3.5977 , 7.03777 , -0.814851,0.57846,0.0374425 --3.45653 , -3.84358 , 7.68004 , 0.632658,-0.13855,-0.761937 --3.40217 , -3.73056 , 7.76804 , 0.632658,-0.13855,-0.761937 --3.32094 , -3.5892 , 7.80692 , 0.632658,-0.13855,-0.761937 --3.23437 , -3.44417 , 7.83437 , -0.739958,0.194601,0.643888 --3.41789 , -3.5657 , 8.36178 , 0.794568,-0.400214,0.456608 --3.14234 , -3.23474 , 8.03199 , -0.639638,-0.705874,0.30431 --2.50177 , -2.5637 , 6.96071 , -0.0775455,-0.355449,0.931473 --2.4354 , -2.4495 , 6.98766 , -0.529258,-0.763358,0.370366 --2.39617 , -2.36116 , 7.07034 , 0.638534,0.185411,-0.746925 --2.43858 , -2.34629 , 7.32953 , -0.112035,-0.397642,0.910675 --2.30648 , -2.17383 , 7.21429 , -0.337452,0.200645,0.919711 --2.23015 , -2.05288 , 7.21476 , -0.582518,-0.070981,0.809713 --2.14595 , -1.92659 , 7.19466 , 0.770456,-0.360381,-0.525855 --2.15043 , -1.87394 , 7.38236 , -0.813242,-0.531665,0.236578 --2.12733 , -1.7968 , 7.50831 , 0.772531,0.558164,-0.302736 --2.49365 , -2.01949 , 8.62673 , 0.836499,-0.547828,0.012372 --1.83566 , -1.45457 , 7.13554 , 0.556908,-0.177369,-0.811415 --1.7266 , -1.31703 , 7.02708 , 0.514492,-0.266481,-0.815037 --1.6366 , -1.19557 , 6.9602 , -0.970969,-0.0489446,0.234145 --1.97327 , -1.36205 , 8.10638 , -0.0587814,-0.387898,0.919826 --1.90595 , -1.248 , 8.13374 , -0.556265,0.336141,-0.759986 --1.60581 , -0.991414 , 7.44935 , -0.905645,-0.397529,0.147575 --1.81369 , -1.04363 , 8.31227 , -0.287288,0.00350477,0.957838 --1.58745 , -0.842676 , 7.82365 , -0.415224,0.00356339,0.909712 --1.28556 , -0.613924 , 7.04258 , 0.11704,0.202176,0.972331 --1.21295 , -0.512604 , 7.00476 , -0.0647813,-0.101791,-0.992694 --1.4126 , -0.528622 , 7.94059 , -0.379413,0.453306,0.806573 --1.47185 , -0.469976 , 8.42115 , -0.593567,0.545208,0.591968 --1.36123 , -0.341567 , 8.27561 , -0.552512,0.0669571,0.830811 --1.3155 , -0.23597 , 8.37831 , -0.888381,-0.458996,0.0100674 --1.24058 , -0.121178 , 8.36259 , 0.59091,-0.370751,-0.716497 --1.12713 , -0.00133755 , 8.1791 , -0.405167,-0.654751,-0.638076 --1.01318 , 0.112603 , 7.97283 , -0.104731,0.751964,0.650831 --0.919367 , 0.219758 , 7.84152 , 0.292244,-0.833572,-0.468776 --0.89774 , 0.323924 , 8.06054 , 0.816426,-0.571742,0.0809984 --0.942372 , 0.44074 , 8.65158 , -0.616712,-0.672775,0.408707 --0.788623 , 0.540027 , 8.19923 , -0.822994,0.339631,-0.455337 --0.713387 , 0.646115 , 8.15714 , 0.760015,-0.223871,0.61013 --0.508916 , 0.698238 , 7.30488 , 0.674697,0.381026,0.632141 --0.578135 , 0.85915 , 8.15518 , -0.103576,-0.128387,0.986301 --0.412955 , 0.900171 , 7.46594 , -0.764609,-0.422743,-0.48648 --0.341226 , 0.987666 , 7.38574 , -0.254657,0.945417,0.203315 --0.297135 , 1.09823 , 7.51042 , -0.633038,0.770406,0.075745 --0.230142 , 1.18903 , 7.46582 , 0.549359,-0.788471,0.276619 --0.156033 , 1.26658 , 7.34055 , 0.344777,0.9276,-0.14383 --0.0317359 , 1.24682 , 6.66405 , 0.971297,-0.153243,-0.181933 --0.477844 , -1.69222 , -0.688301 , -0.0181729,0.237525,0.971211 --0.514432 , -1.74224 , -0.67428 , -0.0292867,0.191782,0.981 --0.559231 , -1.80705 , -0.670382 , -0.0657939,0.192709,0.979048 --0.600123 , -1.86386 , -0.658748 , -0.0939726,0.16501,0.981805 --0.649528 , -1.9362 , -0.656163 , -0.0875754,0.166326,0.982174 --0.695262 , -2.00151 , -0.645645 , -0.0493132,0.201657,0.978214 --0.742124 , -2.06611 , -0.633107 , 0.0926771,-0.167833,-0.981449 --0.796838 , -2.14719 , -0.628327 , -0.0898712,0.150991,0.984442 --0.852723 , -2.22744 , -0.620945 , -0.0677773,0.191427,0.979164 --0.904931 , -2.30067 , -0.605726 , -0.0554664,0.181396,0.981845 --0.966787 , -2.38871 , -0.59744 , -0.0745683,0.189947,0.978959 --1.02496 , -2.46974 , -0.581317 , -0.0808418,0.182583,0.979861 --1.09211 , -2.56656 , -0.571031 , -0.0778845,0.176622,0.981193 --1.16391 , -2.67079 , -0.561474 , 0.108798,-0.155736,-0.981789 --1.25137 , -2.79917 , -0.560376 , -0.131229,0.153872,0.979338 --1.33082 , -2.91215 , -0.546432 , -0.0347639,0.245699,0.968723 --1.39657 , -3.00112 , -0.516847 , -0.0256475,0.29022,0.956616 --1.47239 , -3.10525 , -0.491371 , -0.0393739,0.249793,0.967498 --1.56329 , -3.23426 , -0.47209 , -0.0531084,0.219644,0.974133 --1.65031 , -3.35516 , -0.444587 , -0.0506609,0.246446,0.967832 --1.74782 , -3.49168 , -0.418757 , -0.0586402,0.214787,0.974899 --1.86156 , -3.65227 , -0.396616 , -0.0674567,0.213959,0.974511 --1.97526 , -3.81359 , -0.367831 , -0.064675,0.228114,0.971484 --2.0961 , -3.98189 , -0.335637 , -0.063467,0.203667,0.976981 --2.23263 , -4.17481 , -0.304089 , -0.0576993,0.224643,0.972731 --2.37093 , -4.36677 , -0.264974 , -0.0603004,0.22555,0.972364 --2.53584 , -4.60103 , -0.228466 , -0.0286253,0.385082,0.922438 --2.68156 , -4.79972 , -0.174919 , -0.296485,0.225006,0.928154 --2.90734 , -5.12332 , -0.140343 , 0.225006,-0.278432,-0.933728 --3.12397 , -5.42895 , -0.0892051 , -0.0726348,0.210621,0.974866 --3.36417 , -5.76728 , -0.0314078 , 0.0506097,-0.215733,-0.97514 --3.6385 , -6.1537 , 0.0324451 , -0.0716057,0.224328,0.97188 --3.93095 , -6.56348 , 0.108961 , -0.0581923,0.241476,0.968661 --4.23677 , -6.98785 , 0.200521 , 0.0485689,-0.234534,-0.970894 --4.62052 , -7.52706 , 0.29885 , -0.0152353,0.497488,0.867337 --5.08371 , -8.1793 , 0.410929 , -0.80419,0.45027,0.387989 --5.5733 , -8.86172 , 0.548621 , -0.0930367,0.181371,0.979004 --5.25394 , -8.32535 , 0.754913 , -0.868056,0.479173,0.129891 --4.79688 , -7.58852 , 0.942023 , -0.245991,-0.954547,0.168312 --4.7981 , -7.5397 , 1.10503 , 0.527183,0.808188,-0.262508 --4.84246 , -7.55468 , 1.26864 , 0.527183,0.808188,-0.262508 --4.80643 , -7.4518 , 1.42777 , 0.527183,0.808188,-0.262508 --5.32297 , -8.15289 , 1.64085 , -0.962458,0.270045,-0.0273906 --10.3905 , -15.4003 , 2.4897 , -0.935987,-0.320856,0.144845 --10.5128 , -15.4754 , 2.83283 , 0.99359,0.112885,-0.0059788 --10.5515 , -15.4305 , 3.16548 , 0.991155,0.12888,0.0316644 --10.5427 , -15.3164 , 3.48791 , 0.994019,0.0994615,-0.0450974 --10.4542 , -15.093 , 3.789 , -0.962851,-0.184534,-0.197145 --10.6387 , -15.251 , 4.1599 , 0.968313,0.142304,0.20523 --10.729 , -15.2745 , 4.51125 , 0.972252,0.215759,0.0904076 --10.751 , -15.2051 , 4.84467 , -0.931594,-0.3635,-0.00016626 --10.7596 , -15.1149 , 5.17324 , -0.936215,-0.350414,0.0266783 --10.7752 , -15.0359 , 5.50525 , -0.933119,-0.359105,0.0182481 --10.7998 , -14.9674 , 5.84135 , -0.912868,-0.404966,0.0517195 --10.8028 , -14.8713 , 6.16961 , -0.907406,-0.416254,0.0578565 --10.826 , -14.7997 , 6.50747 , -0.901657,-0.427082,0.0679412 --10.8338 , -14.7089 , 6.83976 , -0.897769,-0.434503,0.072242 --10.8383 , -14.6128 , 7.17111 , -0.89347,-0.442959,0.0741558 --10.8623 , -14.5419 , 7.51472 , -0.89937,-0.411414,0.147891 --10.8717 , -14.4508 , 7.85166 , -0.892681,-0.424118,0.15246 --10.8881 , -14.3691 , 8.19545 , 0.987106,0.148678,-0.0592935 --10.7706 , -14.1137 , 8.45272 , -0.966331,-0.251169,-0.0558401 --10.9849 , -14.2834 , 8.93384 , 0.980743,0.181071,0.0731887 --11.0195 , -14.22 , 9.29962 , 0.94953,0.245619,0.1951 --10.9585 , -14.0374 , 9.59925 , -0.965723,-0.227557,-0.124889 --11.1652 , -14.187 , 10.1053 , -0.962287,-0.22746,-0.149216 --11.1868 , -14.1036 , 10.477 , -0.959295,-0.277524,-0.0522857 --11.1936 , -14.0003 , 10.84 , -0.937183,-0.346315,0.0418836 --11.1897 , -13.8839 , 11.1982 , -0.933939,-0.3533,0.0541876 --11.2158 , -13.8022 , 11.5861 , -0.929425,-0.363841,0.0615629 --11.2259 , -13.7002 , 11.965 , -0.946435,-0.312405,0.0816339 --11.243 , -13.6046 , 12.3548 , 0.96708,0.237451,-0.0915046 --11.2617 , -13.5084 , 12.7508 , 0.993288,0.100211,-0.0577672 --11.2801 , -13.4118 , 13.1538 , 0.997501,0.0695749,-0.0122622 --11.2513 , -13.2575 , 13.5119 , 0.99782,0.0470201,-0.0463076 --11.2873 , -13.1766 , 13.9449 , 0.984038,0.0563184,-0.168814 --11.2235 , -12.9795 , 14.2723 , 0.999906,0.00508089,0.0127504 --11.0125 , -12.6183 , 14.4316 , 0.989691,0.0892788,0.111983 --11.4322 , -12.9591 , 15.3373 , 0.970863,0.0475286,0.234873 --11.3944 , -12.786 , 15.7154 , -0.944338,-0.0942623,-0.315182 --3.60171 , -4.12331 , 6.40088 , -0.379093,0.0134162,0.925261 --3.30268 , -3.71197 , 6.29921 , -0.650138,0.568181,-0.504471 --4.21011 , -4.30556 , 8.72231 , -0.977037,0.0938567,0.191284 --3.46012 , -3.51757 , 7.67686 , -0.0491742,-0.0771149,0.995809 --3.35644 , -3.36343 , 7.68257 , -0.442313,-0.0444105,0.89576 --3.26354 , -3.21899 , 7.69953 , 0.465103,0.457257,-0.75802 --3.3057 , -3.20156 , 7.96124 , 0.81819,0.180645,-0.545832 --3.26614 , -3.10604 , 8.07891 , -0.718557,-0.610704,0.33274 --2.64457 , -2.49425 , 7.07932 , 0.139383,0.856182,-0.497519 --2.53975 , -2.35067 , 7.04052 , -0.139383,-0.856182,0.497519 --2.59215 , -2.34354 , 7.31634 , 0.346624,-0.509582,0.787514 --2.69757 , -2.3769 , 7.7136 , -0.267591,-0.681985,-0.680655 --2.34954 , -2.03339 , 7.15592 , 0.242895,0.609512,0.75465 --2.19952 , -1.85924 , 6.99928 , -0.371095,0.490695,0.788358 --2.1323 , -1.75385 , 7.02027 , -0.187102,0.486085,0.853648 --2.28794 , -1.81802 , 7.55859 , 0.272815,0.954944,-0.116852 --1.93254 , -1.49625 , 6.89474 , 0.495083,-0.70059,-0.513874 --2.3253 , -1.72264 , 8.04482 , -0.821615,0.554903,-0.13051 --1.71889 , -1.23775 , 6.70909 , -0.745649,0.633127,0.207744 --1.60704 , -1.10885 , 6.58768 , -0.957891,-0.0614486,0.280479 --1.6919 , -1.10975 , 6.99375 , 0.967344,0.068803,-0.243949 --1.64818 , -1.02351 , 7.06151 , 0.804258,0.0935154,-0.586876 --1.91229 , -1.11783 , 8.01907 , -0.556265,0.336141,-0.759986 --1.62414 , -0.884884 , 7.38877 , -0.912606,-0.40447,0.0596201 --1.83952 , -0.932369 , 8.27062 , -0.248209,0.0828757,0.965155 --1.61399 , -0.743359 , 7.79955 , 0.303228,-0.0487404,-0.951671 --1.62297 , -0.673286 , 8.07097 , -0.731999,0.556216,-0.393449 --1.57481 , -0.572967 , 8.16127 , -0.730963,0.520178,0.441711 --1.51685 , -0.468721 , 8.2214 , -0.731302,0.531226,0.427781 --1.43422 , -0.354315 , 8.19277 , 0.421614,-0.543478,-0.725861 --1.35657 , -0.243596 , 8.18095 , -0.764279,0.276417,0.582641 --1.30121 , -0.139199 , 8.25391 , 0.780537,-0.316756,-0.538913 --1.2126 , -0.0274893 , 8.18902 , -0.34751,-0.485281,-0.802334 --1.14602 , 0.0798595 , 8.21866 , -0.405167,-0.654751,-0.638075 --0.994163 , 0.192872 , 7.85559 , -0.0274449,0.840954,0.54041 --0.904167 , 0.294325 , 7.75304 , -0.292807,-0.89882,-0.326172 --0.989639 , 0.405342 , 8.52068 , 0.668487,0.689091,-0.279784 --0.967734 , 0.524554 , 8.79738 , -0.72369,-0.689987,0.0138172 --1.083 , 0.686051 , 9.86912 , -0.96772,-0.146369,-0.205171 --0.709318 , 0.716989 , 8.1845 , -0.23151,0.140803,0.962589 --0.635908 , 0.820725 , 8.16942 , 0.117942,0.10198,0.98777 --0.481786 , 0.875715 , 7.61034 , -0.884827,-0.207904,-0.416962 --0.394798 , 0.956007 , 7.45283 , -0.0515098,0.688343,0.723554 --0.335174 , 1.05415 , 7.48044 , 0.214142,-0.787018,0.578573 --0.380447 , 1.26919 , 8.39235 , 0.644637,0.00246213,-0.764485 --0.204706 , 1.24063 , 7.4613 , -0.646085,0.165778,-0.745045 --0.0908283 , 1.25502 , 6.96236 , 0.708919,-0.530052,-0.465273 --0.469283 , -1.58553 , -0.715972 , -0.0470161,0.238291,0.970055 --0.507399 , -1.6347 , -0.704726 , -0.0678358,0.232673,0.970186 --0.541603 , -1.6759 , -0.685839 , -0.0403953,0.248597,0.967764 --0.583011 , -1.73221 , -0.677441 , -0.0921698,0.191548,0.977146 --0.633635 , -1.80296 , -0.678801 , -0.119612,0.181104,0.976163 --0.680368 , -1.86568 , -0.672229 , -0.0947243,0.205116,0.974143 --0.724629 , -1.92212 , -0.657744 , 0.105667,-0.203516,-0.973353 --0.776217 , -1.99329 , -0.652093 , -0.112671,0.18409,0.97643 --0.834256 , -2.07185 , -0.649262 , -0.117808,0.175695,0.97737 --0.887655 , -2.14358 , -0.638376 , -0.0699054,0.201559,0.976979 --0.941235 , -2.21476 , -0.625058 , 0.0884218,-0.189596,-0.977873 --1.0013 , -2.29323 , -0.614072 , -0.094524,0.197901,0.975654 --1.0652 , -2.38051 , -0.604568 , -0.0928548,0.201336,0.975111 --1.13467 , -2.47514 , -0.596596 , -0.106236,0.194136,0.975205 --1.20561 , -2.56971 , -0.585045 , -0.123903,0.175495,0.976652 --1.28657 , -2.67963 , -0.578381 , -0.146643,0.147299,0.978161 --1.37784 , -2.80566 , -0.575629 , -0.115951,0.206901,0.971467 --1.46551 , -2.92444 , -0.563969 , -0.0518316,0.313488,0.948177 --1.52007 , -2.98827 , -0.521444 , -0.0632514,0.290105,0.954902 --1.61938 , -3.12188 , -0.509051 , -0.0789918,0.232593,0.969361 --1.70424 , -3.23267 , -0.480893 , -0.0580101,0.24332,0.96821 --1.80572 , -3.36577 , -0.458497 , -0.0746084,0.241966,0.967412 --1.91252 , -3.50756 , -0.433712 , -0.0784023,0.228134,0.970468 --2.02663 , -3.65748 , -0.406195 , -0.0730593,0.226465,0.971275 --2.14591 , -3.81488 , -0.375319 , -0.0808977,0.229131,0.970028 --2.28826 , -4.00423 , -0.348711 , 0.0776616,-0.218861,-0.97266 --2.43141 , -4.19284 , -0.314415 , -0.0836625,0.228249,0.970002 --2.59687 , -4.41297 , -0.281445 , -0.0848729,0.234728,0.968349 --2.75891 , -4.62532 , -0.237233 , -0.151101,0.360039,0.92062 --2.94919 , -4.8771 , -0.19393 , 0.110236,-0.225049,-0.968091 --3.16933 , -5.16948 , -0.149024 , -0.100528,0.224756,0.969216 --3.41831 , -5.50115 , -0.0999657 , 0.0461372,0.154192,0.986963 --3.69172 , -5.86396 , -0.0428147 , -0.0202798,-0.129715,-0.991344 --3.97834 , -6.24187 , 0.0271426 , -0.0687263,0.236676,0.969155 --4.27921 , -6.63441 , 0.110855 , -0.0568958,0.243831,0.968148 --4.63187 , -7.0975 , 0.202943 , -0.057647,0.233219,0.970714 --5.05563 , -7.65633 , 0.305806 , 0.794424,-0.55792,-0.240033 --5.58631 , -8.35929 , 0.422049 , 0.564885,-0.398551,-0.722538 --6.17179 , -9.13143 , 0.564844 , -0.0937256,0.209902,0.97322 --6.84276 , -10.0118 , 0.737129 , 0.0313837,0.209458,0.977314 --5.06949 , -7.47307 , 0.9753 , -0.531299,-0.805389,0.262812 --5.0457 , -7.39045 , 1.1386 , 0.527183,0.808188,-0.262508 --5.03806 , -7.33049 , 1.30006 , 0.527183,0.808188,-0.262508 --5.02792 , -7.26936 , 1.46 , 0.527183,0.808188,-0.262508 --5.04571 , -7.24525 , 1.62088 , -0.527183,-0.808188,0.262508 --5.04397 , -7.19495 , 1.77935 , -0.527183,-0.808188,0.262508 --10.7734 , -14.8366 , 2.86508 , -0.882833,-0.4287,0.191894 --10.7157 , -14.6641 , 3.1734 , -0.887143,-0.317761,0.334672 --10.6251 , -14.4475 , 3.46952 , 0.977329,0.20985,-0.0281309 --10.6317 , -14.3618 , 3.78353 , -0.901031,-0.274044,-0.33622 --10.9459 , -14.6795 , 4.18167 , -0.895041,-0.317438,-0.313266 --10.9761 , -14.6217 , 4.5104 , -0.936734,-0.31801,-0.146287 --10.9372 , -14.4742 , 4.81723 , -0.939968,-0.330778,-0.0839409 --11.0261 , -14.492 , 5.1676 , -0.785194,-0.616995,-0.0527933 --11.0512 , -14.4287 , 5.49855 , -0.482429,-0.865018,-0.137863 --11.0677 , -14.3513 , 5.82646 , -0.493193,-0.842136,0.218099 --11.0865 , -14.2781 , 6.15698 , -0.551539,-0.787504,0.275031 --11.1017 , -14.1986 , 6.48695 , -0.744564,-0.63469,0.206864 --11.1243 , -14.1307 , 6.8229 , -0.875925,-0.47589,0.0792694 --11.1383 , -14.0487 , 7.15561 , -0.877704,-0.463614,0.121235 --11.1483 , -13.9626 , 7.48819 , -0.928336,-0.349497,0.126663 --11.1076 , -13.8129 , 7.7925 , -0.93789,-0.22285,0.265896 --11.1285 , -13.739 , 8.13391 , -0.972626,-0.212555,0.0939102 --10.9673 , -13.4468 , 8.36219 , 0.987329,0.151578,0.0469597 --11.17 , -13.5884 , 8.82559 , -0.971709,-0.204479,-0.118198 --11.2029 , -13.5258 , 9.18448 , -0.960943,-0.21692,-0.171854 --11.1738 , -13.3884 , 9.50211 , 0.937535,0.246278,0.245713 --11.3858 , -13.5325 , 10.0031 , -0.892551,-0.415933,-0.174219 --11.3998 , -13.4436 , 10.3643 , -0.914359,-0.399644,0.0650549 --11.4278 , -13.3682 , 10.74 , 0.906133,0.420828,-0.0427393 --11.4504 , -13.2865 , 11.117 , 0.909551,0.411577,-0.0576393 --11.4747 , -13.2042 , 11.5 , 0.916104,0.394429,-0.0719624 --11.4659 , -13.0837 , 11.8586 , 0.924785,0.355637,-0.135259 --11.4813 , -12.9885 , 12.2433 , 0.907578,0.38476,-0.168113 --11.3905 , -12.7759 , 12.531 , 0.897437,0.349184,-0.269588 --11.3631 , -12.6322 , 12.8813 , 0.942667,0.0751396,-0.325167 --11.3486 , -12.501 , 13.2477 , 0.987826,0.0724412,-0.137664 --11.3348 , -12.3695 , 13.6197 , 0.991687,0.0515997,-0.117874 --11.3494 , -12.2666 , 14.0275 , -0.972699,-0.0150313,0.231581 --11.1244 , -11.9108 , 14.1723 , -0.962471,0.0227695,0.270426 --11.6056 , -12.2909 , 15.1291 , -0.969975,-0.0993851,-0.221969 --11.5862 , -12.1429 , 15.5265 , 0.960074,0.156186,0.232085 --4.4343 , -4.33026 , 8.45688 , 0.982403,-0.107579,-0.152684 --4.37857 , -4.21609 , 8.57741 , -0.977037,0.0938567,0.191284 --4.27702 , -4.06065 , 8.62737 , -0.977037,0.0938567,0.191284 --4.37218 , -4.01489 , 9.21568 , -0.981393,0.124245,0.146395 --3.37403 , -3.07661 , 7.72194 , 0.465103,0.457258,-0.758021 --4.19491 , -3.72321 , 9.36448 , 0.817296,-0.313549,-0.48344 --2.80282 , -2.483 , 7.06098 , -0.0657165,-0.931406,0.358001 --3.39981 , -2.92443 , 8.34895 , -0.968019,-0.250469,-0.0142885 --2.79594 , -2.37291 , 7.39228 , -0.0820326,-0.860503,0.502797 --3.31291 , -2.72854 , 8.59673 , 0.799327,0.45973,0.386943 --2.59932 , -2.11006 , 7.35928 , 0.431596,0.029495,0.901585 --2.35107 , -1.86581 , 7.01959 , 0.223702,0.619216,0.752681 --2.20399 , -1.70561 , 6.87832 , 0.0992167,0.210946,0.972449 --2.15904 , -1.62099 , 6.94993 , -0.426628,-0.0168553,-0.90427 --2.05514 , -1.49465 , 6.88771 , 0.479253,-0.634254,-0.606662 --1.93002 , -1.35599 , 6.76838 , -0.694085,0.689201,0.207961 --1.74421 , -1.18087 , 6.49197 , -0.691915,0.292568,0.660044 --1.77614 , -1.15148 , 6.74249 , 0.760098,-0.640073,0.112064 --1.65981 , -1.02586 , 6.62072 , -0.978738,-0.193076,-0.0692314 --1.72468 , -1.00952 , 6.97165 , 0.948384,0.182377,-0.259434 --1.72601 , -0.951602 , 7.16826 , -0.949846,-0.123664,0.287227 --1.96522 , -1.01691 , 8.05226 , 0.703298,-0.304735,-0.642268 --1.62183 , -0.772182 , 7.28126 , 0.985769,0.063937,0.15547 --1.46277 , -0.632273 , 7.01595 , -0.039061,-0.164064,0.985676 --1.76573 , -0.701168 , 8.18145 , 0.726119,-0.270793,-0.631999 --1.31828 , -0.441669 , 6.98274 , 0.153106,0.384738,0.910239 --1.54181 , -0.455967 , 7.96421 , 0.767566,-0.3902,-0.508515 --1.52067 , -0.368661 , 8.15709 , 0.753319,-0.4889,-0.439871 --1.42508 , -0.255095 , 8.08922 , -0.633454,0.583047,0.508716 --1.57165 , -0.202921 , 8.93591 , -0.40354,-0.749556,-0.524711 --1.29076 , -0.0480642 , 8.15855 , -0.376981,0.248357,0.892303 --1.22753 , 0.0560888 , 8.20933 , -0.188696,0.604382,0.774026 --1.06094 , 0.16941 , 7.81973 , -0.315719,-0.945277,-0.082299 --0.952664 , 0.269325 , 7.65054 , -0.211907,0.972951,0.091991 --1.06262 , 0.37522 , 8.50611 , -0.597671,-0.770602,0.221274 --1.00312 , 0.485703 , 8.59815 , -0.733375,-0.570746,0.369337 --1.17813 , 0.64861 , 9.9448 , -0.96772,-0.146369,-0.205171 --0.817176 , 0.696118 , 8.44144 , 0.87214,-0.257766,0.415848 --0.698972 , 0.786392 , 8.19201 , -0.309472,0.290294,0.905515 --0.61873 , 0.886363 , 8.1568 , -0.103576,-0.128387,0.986301 --0.432586 , 0.913609 , 7.39072 , -0.104925,0.185408,0.977044 --0.355729 , 0.996893 , 7.31154 , 0.704934,-0.264942,-0.657932 --0.291179 , 1.0866 , 7.30946 , 0.719199,-0.509995,-0.471867 --0.245924 , 1.20164 , 7.48245 , 0.583338,-0.764919,-0.273157 --0.171987 , 1.28439 , 7.41747 , -0.932118,0.361216,-0.0260728 --0.0231051 , 1.22854 , 6.54568 , -0.758945,-0.648609,0.0575261 --0.49127 , -1.5219 , -0.724272 , -0.0609713,0.226784,0.972035 --0.529826 , -1.56913 , -0.714319 , -0.0436324,0.231766,0.971792 --0.572755 , -1.6246 , -0.708792 , -0.0497226,0.247277,0.967668 --0.616556 , -1.67849 , -0.701735 , -0.0929516,0.231566,0.968368 --0.660959 , -1.73388 , -0.692532 , -0.136675,0.179094,0.974292 --0.709321 , -1.79544 , -0.687372 , -0.0948558,0.199097,0.975378 --0.758308 , -1.85844 , -0.679774 , -0.0958429,0.194092,0.97629 --0.808423 , -1.92074 , -0.670157 , 0.116993,-0.192453,-0.974307 --0.866872 , -1.99744 , -0.669009 , -0.127535,0.19488,0.9725 --0.918525 , -2.05947 , -0.65484 , -0.0994474,0.206203,0.973443 --0.978791 , -2.13672 , -0.648359 , -0.101952,0.185599,0.977322 --1.04458 , -2.22145 , -0.643993 , -0.127904,0.211171,0.969045 --1.10671 , -2.29911 , -0.631595 , -0.0971593,0.216351,0.971469 --1.17341 , -2.3844 , -0.6209 , -0.108688,0.214082,0.97075 --1.24253 , -2.46949 , -0.607038 , -0.124213,0.179773,0.975834 --1.32994 , -2.58452 , -0.607409 , -0.146206,0.174222,0.973792 --1.41494 , -2.69305 , -0.598893 , -0.132811,0.156627,0.978688 --1.50563 , -2.80859 , -0.59045 , -0.0940813,0.269651,0.958351 --1.57675 , -2.89427 , -0.561595 , -0.0492826,0.299713,0.952756 --1.66408 , -3.00179 , -0.540839 , 0.0750986,-0.297942,-0.951625 --1.75739 , -3.11712 , -0.519277 , -0.0565467,0.249754,0.966657 --1.85692 , -3.24112 , -0.496322 , -0.0613875,0.242212,0.968279 --1.95778 , -3.36381 , -0.468623 , -0.0862088,0.226479,0.970194 --2.0803 , -3.51833 , -0.447993 , -0.0829194,0.222939,0.971299 --2.20449 , -3.6722 , -0.421158 , -0.0823352,0.229969,0.969709 --2.33958 , -3.84206 , -0.39327 , 0.0908711,-0.224819,-0.970154 --2.48855 , -4.02706 , -0.363719 , 0.0817969,-0.226726,-0.970518 --2.64858 , -4.22761 , -0.33117 , -0.0908727,0.234719,0.967806 --2.81618 , -4.4355 , -0.292387 , -0.0763576,0.253582,0.964296 --3.0024 , -4.66564 , -0.251406 , -0.107554,0.229737,0.967292 --3.22394 , -4.94405 , -0.211715 , 0.0974826,-0.220322,-0.970544 --3.47043 , -5.25312 , -0.167266 , 0.027694,0.271544,0.962027 --3.73066 , -5.57668 , -0.112858 , 0.11535,0.136431,0.983911 --4.03253 , -5.95525 , -0.054167 , -0.0959233,0.134905,0.986205 --4.34963 , -6.34818 , 0.018353 , 0.0586128,-0.244974,-0.967757 --4.66262 , -6.73104 , 0.108946 , -0.0633392,0.235696,0.969761 --5.10192 , -7.2795 , 0.197621 , -0.195516,0.543112,0.81658 --5.60365 , -7.90469 , 0.302876 , 0.366032,-0.215926,-0.905205 --6.1985 , -8.64577 , 0.427164 , -0.109121,0.218413,0.969736 --3.79452 , -5.40068 , 0.771022 , -0.835169,-0.549993,-9.2518e-05 --7.53707 , -10.2957 , 0.768417 , 0.262479,0.211037,0.941578 --8.03875 , -10.8853 , 0.994542 , 0.230646,0.193882,0.953526 --8.30374 , -11.1593 , 1.24165 , 0.230646,0.193882,0.953526 --8.8378 , -11.7752 , 1.51518 , 0.178862,0.248511,0.951972 --9.64731 , -12.7391 , 1.83878 , 0.287066,0.302093,0.909029 --10.5572 , -13.8183 , 2.2163 , 0.341497,-0.141934,-0.929104 --11.112 , -14.4316 , 2.59439 , -0.936168,-0.301824,0.180254 --11.1269 , -14.3563 , 2.91425 , 0.980193,-0.195469,-0.0318314 --10.6547 , -13.6726 , 3.14193 , -0.977738,0.121465,0.171101 --10.5559 , -13.4602 , 3.42304 , -0.955108,-0.148572,-0.25631 --11.0192 , -13.9452 , 3.83448 , -0.895036,-0.126884,-0.427565 --11.0755 , -13.9225 , 4.16037 , -0.922867,-0.19095,-0.334446 --11.0785 , -13.8349 , 4.47298 , 0.986929,0.0454827,0.154603 --11.3519 , -14.0751 , 4.8728 , 0.755005,0.480113,0.446609 --11.7912 , -14.5104 , 5.34501 , 0.00886601,-0.999415,0.0330286 --11.8209 , -14.448 , 5.68631 , -0.081722,0.995358,-0.0508284 --11.8286 , -14.36 , 6.02058 , 0.0227162,-0.933307,0.35836 --11.857 , -14.2953 , 6.36443 , 0.189655,-0.952268,0.239202 --11.428 , -13.6944 , 6.50101 , 0.214953,-0.896799,0.386713 --12.0079 , -14.2757 , 7.10477 , -0.542939,-0.688952,0.480169 --11.4481 , -13.5282 , 7.15702 , -0.978113,0.207801,0.0106324 --11.239 , -13.1923 , 7.36934 , 0.994142,0.0109724,-0.107527 --11.1695 , -13.0188 , 7.65049 , -0.963422,0.00207341,0.267981 --11.1957 , -12.9533 , 7.98579 , 0.992766,0.0715834,-0.0963925 --11.0141 , -12.6542 , 8.19593 , 0.993984,0.10077,0.0429209 --11.2286 , -12.8001 , 8.6549 , 0.98333,0.115328,0.140579 --11.2546 , -12.7325 , 9.00034 , 0.990103,0.0800573,0.115269 --11.2586 , -12.6382 , 9.33367 , -0.968034,-0.0765678,-0.238846 --11.6943 , -13.0159 , 9.98699 , -0.927816,-0.269829,-0.257583 --11.7056 , -12.9262 , 10.3452 , -0.872335,-0.488873,-0.00589507 --11.7197 , -12.8368 , 10.7085 , -0.884057,-0.461306,0.0751003 --11.7223 , -12.7354 , 11.0677 , -0.891855,-0.444447,0.0840344 --11.7217 , -12.6284 , 11.4271 , -0.861691,-0.507418,0.00399298 --11.7338 , -12.533 , 11.8019 , -0.877895,-0.468518,0.0989534 --11.9926 , -12.6943 , 12.4072 , -0.952295,-0.178841,0.247286 --11.6798 , -12.2589 , 12.494 , -0.937092,-0.164514,0.307885 --11.4292 , -11.8918 , 12.6277 , 0.991957,0.0182522,-0.125253 --11.4412 , -11.7939 , 13.0147 , 0.991086,0.0277715,-0.130296 --11.3568 , -11.5973 , 13.3084 , 0.994678,0.0416695,-0.0942335 --11.4396 , -11.5663 , 13.7796 , -0.964317,-0.00520529,0.264698 --11.2626 , -11.2759 , 13.9776 , -0.956913,0.0631452,0.283424 --11.0552 , -10.959 , 14.1368 , 0.991746,0.092819,0.0884598 --11.663 , -11.4279 , 15.2389 , -0.93185,-0.12744,-0.339727 --11.4827 , -11.1325 , 15.445 , -0.93706,-0.118178,-0.32856 --4.54562 , -4.12544 , 8.43985 , 0.981599,-0.0526262,-0.18356 --4.17361 , -3.43237 , 9.14034 , 0.732078,-0.408123,-0.545434 --4.17837 , -3.36737 , 9.37714 , -0.476494,0.452408,0.753844 --3.91231 , -3.09388 , 9.12879 , -0.322434,0.356416,0.876929 --3.82087 , -2.95638 , 9.18657 , -0.163667,0.363975,0.916916 --2.78957 , -2.12766 , 7.42206 , -0.532518,-0.347855,-0.771635 --2.53788 , -1.89204 , 7.10565 , 0.569428,0.342546,0.747271 --2.53501 , -1.83808 , 7.27808 , 0.612368,0.405129,0.678878 --2.28707 , -1.61364 , 6.93873 , -0.530396,0.00807492,-0.847712 --2.22709 , -1.52234 , 6.98446 , -0.426628,-0.0168553,-0.90427 --2.10384 , -1.38928 , 6.8866 , 0.526881,-0.308245,0.792074 --1.8431 , -1.17274 , 6.46365 , 0.46285,-0.0159451,-0.886293 --1.82815 , -1.11408 , 6.59716 , -0.794944,-0.160255,0.585135 --1.89942 , -1.10363 , 6.94751 , -0.841349,0.168518,0.513551 --1.74825 , -0.963716 , 6.75387 , 0.981595,0.185194,-0.0466319 --1.75161 , -0.910693 , 6.94979 , 0.966988,-0.0493053,-0.250006 --1.73106 , -0.841443 , 7.09038 , -0.950667,-0.0400357,0.307619 --2.69904 , -1.24763 , 10.0103 , 0.379963,-0.274226,0.883418 --1.50384 , -0.614302 , 6.85588 , 0.630632,-0.522804,-0.573567 --1.44549 , -0.528523 , 6.88824 , 0.805993,-0.144105,-0.574116 --1.4108 , -0.452003 , 6.99463 , -0.400792,0.217057,0.890085 --1.64246 , -0.467821 , 7.96411 , -0.458208,-0.384123,-0.801558 --1.61497 , -0.380551 , 8.13908 , -0.718827,0.490051,0.49309 --1.51511 , -0.269656 , 8.07357 , 0.729563,-0.472107,-0.494827 --1.68938 , -0.225397 , 8.99594 , -0.283614,-0.846508,-0.450541 --1.45679 , -0.0810044 , 8.455 , -0.763288,-0.577303,-0.290021 --1.32397 , 0.0341269 , 8.25675 , -0.280468,-0.630814,-0.723472 --1.10379 , 0.151215 , 7.67572 , 0.583136,0.606471,0.540505 --1.02302 , 0.246701 , 7.64485 , 0.767808,-0.340646,0.542615 --0.964437 , 0.342221 , 7.70926 , 0.726047,0.618022,-0.301503 --1.07279 , 0.455984 , 8.57428 , -0.650173,-0.662699,0.371625 --1.28639 , 0.615825 , 10.0678 , -0.974281,-0.123704,-0.188347 --1.08315 , 0.715965 , 9.50136 , -0.862493,-0.362753,0.352868 --0.75844 , 0.751155 , 8.18412 , -0.336486,0.0318229,0.94115 --0.680869 , 0.851947 , 8.18009 , 0.155937,0.254965,0.954294 --0.606243 , 0.953945 , 8.19355 , -0.174612,-0.112871,0.978147 --0.424685 , 0.977819 , 7.46654 , -0.275346,0.372317,-0.886321 --0.35203 , 1.06596 , 7.44629 , -0.824024,0.528773,-0.20343 --0.283318 , 1.1556 , 7.44381 , 0.657435,-0.363529,-0.66002 --0.214209 , 1.24677 , 7.44913 , 0.646085,-0.165778,0.745045 --0.0651695 , 1.20844 , 6.65696 , 0.508926,-0.860587,-0.0196013 --0.639386 , -1.61108 , -0.713109 , -0.124963,0.246141,0.961145 --0.685182 , -1.66436 , -0.705515 , -0.124648,0.219564,0.967602 --0.735175 , -1.72476 , -0.701767 , -0.105413,0.203204,0.973446 --0.785555 , -1.78564 , -0.695778 , -0.0948992,0.192192,0.976758 --0.842099 , -1.85313 , -0.693487 , -0.112336,0.199234,0.973492 --0.894246 , -1.91471 , -0.682846 , -0.111806,0.175375,0.978132 --0.95546 , -1.98953 , -0.680993 , -0.0829032,0.19831,0.976627 --1.00915 , -2.05082 , -0.665704 , -0.07968,0.194535,0.977654 --1.07631 , -2.13352 , -0.663336 , -0.122347,0.178898,0.976231 --1.14489 , -2.2163 , -0.657973 , -0.0854441,0.21328,0.973248 --1.2047 , -2.28492 , -0.639737 , -0.0942523,0.200485,0.975152 --1.28538 , -2.38217 , -0.637557 , -0.0983348,0.184911,0.977823 --1.35633 , -2.46548 , -0.622383 , -0.12241,0.161778,0.979206 --1.44338 , -2.57099 , -0.616962 , -0.13637,0.146379,0.979784 --1.54687 , -2.69933 , -0.619637 , -0.109304,0.172364,0.97895 --1.64138 , -2.81249 , -0.609345 , -0.0204039,0.290697,0.956598 --1.71091 , -2.88801 , -0.575164 , 0.00277757,0.265929,0.963989 --1.80205 , -2.9932 , -0.552851 , -0.0395135,0.238102,0.970436 --1.89398 , -3.09936 , -0.52596 , -0.0482442,0.236403,0.970457 --2.00326 , -3.22664 , -0.505149 , -0.0662975,0.216929,0.973933 --2.12428 , -3.37011 , -0.485156 , 0.0710975,-0.220986,-0.972682 --2.24694 , -3.51301 , -0.459348 , 0.0662958,-0.217208,-0.973871 --2.38667 , -3.67848 , -0.436087 , -0.0769788,0.218548,0.972785 --2.53382 , -3.85173 , -0.408538 , 0.0716452,-0.216689,-0.973608 --2.69393 , -4.0402 , -0.378622 , -0.0789729,0.213084,0.973837 --2.86707 , -4.24366 , -0.345365 , -0.0613088,0.231502,0.970901 --3.04756 , -4.45346 , -0.305878 , -0.0809032,0.225374,0.970908 --3.27052 , -4.71786 , -0.271305 , -0.0875579,0.218563,0.971887 --3.50129 , -4.98886 , -0.22719 , -0.0609428,0.218909,0.97384 --3.75244 , -5.28283 , -0.176323 , 0.402387,0.12544,0.906835 --3.93251 , -5.48074 , -0.0941617 , -0.587803,-0.570139,0.573958 --3.87203 , -5.3636 , 0.0514347 , 0.611723,0.690008,-0.386889 --3.85638 , -5.30765 , 0.182841 , 0.61659,0.723368,-0.310736 --3.81485 , -5.21781 , 0.316024 , -0.613807,-0.71787,0.328487 --3.80842 , -5.17461 , 0.440784 , 0.566207,0.783003,-0.25752 --3.80706 , -5.13696 , 0.563131 , -0.819531,-0.565127,0.0948673 --3.80298 , -5.09711 , 0.684154 , -0.809822,-0.58396,0.0563883 --3.79762 , -5.05673 , 0.804226 , -0.835674,-0.548543,0.0273856 --3.86094 , -5.09988 , 0.920781 , -0.833415,-0.548885,-0.0643772 --3.87827 , -5.08764 , 1.04018 , -0.523104,-0.84709,-0.0938097 --3.89393 , -5.07272 , 1.15929 , 0.460941,0.887353,0.0117842 --3.90937 , -5.0568 , 1.27841 , 0.460941,0.887353,0.0117842 --3.88382 , -4.99285 , 1.39435 , 0.460941,0.887353,0.0117842 --10.736 , -13.1693 , 2.24881 , 0.970029,0.0316809,-0.240916 --10.7697 , -13.1236 , 2.55062 , 0.969995,0.156342,-0.186193 --10.7418 , -13.0057 , 2.84308 , 0.958597,0.255599,-0.125543 --10.7164 , -12.8909 , 3.13327 , 0.972206,0.233682,0.0144478 --10.7078 , -12.7958 , 3.4247 , -0.884819,-0.209842,-0.416007 --11.0501 , -13.1094 , 3.79886 , -0.915187,-0.157493,-0.370984 --11.0539 , -13.027 , 4.10046 , -0.971392,-0.137452,-0.193659 --11.0146 , -12.8969 , 4.38966 , 0.959823,0.164453,0.227364 --11.1015 , -12.9096 , 4.71621 , 0.87181,0.42851,0.237333 --11.1343 , -12.8588 , 5.02835 , -0.502317,-0.864224,-0.028192 --11.1489 , -12.7892 , 5.33625 , -0.265327,-0.942829,0.201681 --11.1544 , -12.7078 , 5.64114 , -0.301326,-0.929728,0.21168 --11.1822 , -12.6513 , 5.95636 , -0.384685,-0.899227,0.208346 --11.1805 , -12.5614 , 6.26037 , -0.337293,-0.89421,0.294317 --11.2002 , -12.4963 , 6.5759 , -0.414692,-0.878657,0.236628 --11.2167 , -12.4258 , 6.89147 , 0.963565,0.177074,-0.200467 --11.2037 , -12.3232 , 7.19377 , 0.964248,0.0752229,-0.254099 --11.2261 , -12.2571 , 7.51588 , 0.978503,0.0864815,-0.187225 --11.2507 , -12.1938 , 7.84245 , 0.996174,0.0757663,-0.0435488 --11.0616 , -11.9038 , 8.04286 , 0.994031,0.0974064,0.049136 --11.2944 , -12.0578 , 8.50178 , 0.986729,0.104438,0.124331 --11.3064 , -11.9783 , 8.83036 , 0.987743,0.0872705,0.129413 --11.2462 , -11.8234 , 9.11213 , 0.99705,0.0608219,0.0468253 --11.376 , -11.8624 , 9.52911 , 0.971386,0.126157,0.201229 --11.3815 , -11.7736 , 9.86468 , -0.958363,-0.198281,-0.205485 --11.4085 , -11.7048 , 10.2199 , 0.810838,0.585264,-0.00297475 --11.4373 , -11.6364 , 10.5812 , 0.560288,0.807349,-0.185108 --11.4605 , -11.5606 , 10.9441 , -0.569839,-0.798814,0.192822 --11.4736 , -11.4734 , 11.3032 , -0.558137,-0.805531,0.199003 --11.4518 , -11.3509 , 11.6365 , -0.703295,-0.65844,0.268017 --11.4673 , -11.2638 , 12.0076 , -0.937806,-0.326966,0.116671 --11.4905 , -11.1806 , 12.391 , 0.960136,0.0998441,-0.261093 --11.4963 , -11.0806 , 12.7648 , 0.986945,0.0413838,-0.155648 --11.3908 , -10.8736 , 13.0326 , 0.99483,0.038012,-0.0941767 --11.4628 , -10.8326 , 13.4842 , 0.968576,-0.0281965,-0.247115 --11.3832 , -10.6491 , 13.7851 , -0.943184,0.0403098,0.329815 --11.1466 , -10.3209 , 13.9122 , 0.985907,0.159511,0.0504373 --11.718 , -10.7254 , 14.9528 , -0.935407,-0.182698,-0.302714 --11.6284 , -10.5246 , 15.2626 , 0.924929,0.197965,0.324524 --4.2066 , -3.26021 , 8.80101 , -0.964035,-0.00435332,0.265741 --4.16562 , -3.16599 , 8.95465 , 0.458706,-0.0111117,-0.888519 --4.08981 , -3.04518 , 9.05009 , -0.344134,-0.306804,0.88738 --3.98555 , -2.90435 , 9.09369 , 0.271398,-0.00284287,-0.962463 --3.07184 , -2.19857 , 7.63969 , -0.532518,-0.347856,-0.771636 --2.87003 , -2.0054 , 7.44921 , -0.437167,-0.0858737,-0.895271 --2.77604 , -1.88963 , 7.45596 , 0.27572,0.295933,0.91455 --2.10692 , -1.3993 , 6.2974 , -0.742341,-0.21275,0.635348 --2.07151 , -1.33164 , 6.3822 , -0.579439,0.051317,0.813398 --2.32983 , -1.44301 , 7.09724 , 0.827311,-0.0525964,0.559277 --2.40121 , -1.43161 , 7.44192 , -0.65427,-0.299841,0.694281 --2.32904 , -1.33278 , 7.4777 , -0.213973,-0.690602,0.690858 --2.30978 , -1.26353 , 7.63701 , -0.387295,-0.522789,0.759404 --1.78234 , -0.921297 , 6.57307 , -0.806066,-0.375634,0.457336 --1.75495 , -0.855232 , 6.68621 , -0.481077,-0.512691,0.711135 --1.76904 , -0.807663 , 6.90888 , 0.984861,0.00493616,-0.173277 --1.73238 , -0.73336 , 7.01201 , -0.816639,0.357406,0.453169 --1.82166 , -0.712344 , 7.46779 , 0.973478,0.228231,-0.0158466 --1.88828 , -0.673622 , 7.88908 , 0.692052,-0.272068,0.668613 --1.51586 , -0.462146 , 7.03298 , 0.0469986,0.266836,0.962595 --1.76626 , -0.482605 , 8.02864 , 0.715962,-0.511542,-0.475104 --1.64556 , -0.367831 , 7.91046 , -0.734865,0.513487,0.443062 --1.57208 , -0.270251 , 7.9418 , -0.772051,0.385317,0.505439 --1.49659 , -0.170439 , 7.96096 , 0.692401,-0.0638076,-0.718686 --1.71311 , -0.127993 , 9.03693 , -0.287622,-0.811302,-0.508982 --1.55058 , -0.00284553 , 8.77552 , -0.313838,-0.863213,-0.395436 --1.24583 , 0.127468 , 7.9286 , -0.34697,-0.700176,-0.623992 --1.12241 , 0.226867 , 7.74462 , -0.669709,-0.0400517,-0.741543 --1.00418 , 0.320509 , 7.5672 , -0.394421,0.453154,-0.799427 --1.08801 , 0.425036 , 8.28524 , -0.317895,-0.948042,0.0126095 --1.09955 , 0.540105 , 8.74016 , 0.517823,0.843238,-0.144253 --1.10946 , 0.670043 , 9.23327 , 0.864895,0.35221,-0.357639 --1.05472 , 0.795215 , 9.431 , -0.862493,-0.362753,0.352868 --0.746141 , 0.821137 , 8.20182 , -0.299115,0.149066,0.942502 --0.661974 , 0.917213 , 8.17786 , -0.201581,-0.0210265,0.979246 --0.463947 , 0.937777 , 7.4039 , -0.104925,0.185408,0.977044 --0.350355 , 0.990531 , 7.09979 , -0.867248,0.497853,-0.00483159 --0.313997 , 1.10588 , 7.34472 , 0.944686,-0.326962,-0.0257775 --0.270119 , 1.22432 , 7.56794 , 0.735427,-0.650455,-0.189884 --0.187955 , 1.30118 , 7.48444 , 0.565404,-0.128161,0.814796 --0.0212082 , 1.22401 , 6.50583 , 0.7603,0.647104,-0.0565773 --0.766992 , -1.66855 , -0.727213 , 0.115686,-0.218325,-0.968995 --0.810167 , -1.71434 , -0.710735 , 0.0970112,-0.182943,-0.978326 --0.867136 , -1.77992 , -0.709933 , -0.0834308,0.184532,0.979279 --0.915621 , -1.83216 , -0.695476 , -0.0973563,0.184595,0.977981 --0.979413 , -1.90567 , -0.695447 , -0.0889352,0.135379,0.986794 --1.04364 , -1.97952 , -0.692497 , -0.0913817,0.192227,0.977087 --1.09913 , -2.03914 , -0.676381 , -0.0875527,0.187151,0.978422 --1.17004 , -2.1197 , -0.673235 , -0.0781178,0.186448,0.979354 --1.23631 , -2.19341 , -0.661936 , -0.0603287,0.19811,0.978321 --1.30813 , -2.27453 , -0.65246 , -0.0734697,0.174145,0.981975 --1.3865 , -2.36272 , -0.644344 , -0.101396,0.14986,0.983494 --1.48195 , -2.47289 , -0.646102 , 0.10629,-0.152066,-0.982639 --1.56768 , -2.56906 , -0.634574 , -0.112432,0.125304,0.985727 --1.67475 , -2.6941 , -0.635792 , -0.026417,0.201975,0.979034 --1.74658 , -2.76747 , -0.60412 , -0.0210744,0.316731,0.948281 --1.82944 , -2.85583 , -0.576872 , 0.00959278,0.246147,0.969185 --1.93497 , -2.97343 , -0.56064 , -0.0364884,0.233403,0.971695 --2.03565 , -3.08315 , -0.536063 , -0.0526679,0.223854,0.973199 --2.16061 , -3.2233 , -0.519991 , -0.079116,0.211966,0.974069 --2.28623 , -3.3631 , -0.497981 , -0.048798,0.219368,0.974421 --2.41896 , -3.50998 , -0.472951 , 0.0577865,-0.206077,-0.976828 --2.56526 , -3.67125 , -0.447428 , -0.057888,0.204828,0.977085 --2.7178 , -3.83952 , -0.417499 , -0.0631094,0.206149,0.976483 --2.90196 , -4.0462 , -0.392662 , -0.0578335,0.207674,0.976487 --3.08248 , -4.24407 , -0.356489 , -0.0619273,0.210587,0.975612 --3.29364 , -4.47895 , -0.322565 , -0.0728174,0.206217,0.975793 --3.52504 , -4.73724 , -0.283834 , -0.0600162,0.205315,0.976854 --3.7773 , -5.0165 , -0.239352 , 0.00936534,0.211654,0.9773 --4.06283 , -5.33189 , -0.190937 , 0.103542,0.354299,0.929382 --4.38712 , -5.69326 , -0.136977 , -0.231873,-0.0160727,0.972613 --4.00949 , -5.19384 , 0.0824123 , 0.703695,0.519719,-0.484465 --3.9736 , -5.11508 , 0.21624 , 0.794792,0.580343,-0.177507 --3.96746 , -5.07268 , 0.341877 , -0.562668,-0.782841,0.265639 --3.98467 , -5.05914 , 0.462631 , 0.505322,0.843253,-0.183234 --3.99481 , -5.03672 , 0.583961 , 0.479271,0.86712,-0.135654 --3.99665 , -5.00481 , 0.705208 , -0.517856,-0.850262,0.0942267 --4.00362 , -4.97824 , 0.825014 , 0.495653,0.86797,-0.030912 --3.99561 , -4.93545 , 0.944638 , -0.506035,-0.85864,-0.0816489 --4.06532 , -4.98284 , 1.06352 , 0.536052,0.843633,-0.0305034 --4.08673 , -4.97471 , 1.18354 , 0.460941,0.887352,0.0117843 --10.3051 , -12.0372 , 1.66015 , 0.761615,0.396586,0.512505 --10.7049 , -12.4125 , 1.9724 , -0.914667,0.0309863,-0.403018 --11.5407 , -13.2734 , 2.35114 , -0.953422,0.105198,0.282701 --11.2954 , -12.9115 , 2.62566 , -0.842803,0.533666,-0.0698797 --10.7326 , -12.2014 , 2.83582 , 0.989487,0.0738717,0.12433 --10.6892 , -12.0738 , 3.11274 , -0.913114,-0.0915665,-0.397289 --11.0975 , -12.4415 , 3.48145 , -0.88427,-0.170365,-0.43479 --11.1682 , -12.4376 , 3.79106 , -0.963633,-0.186001,-0.191872 --11.1761 , -12.3627 , 4.08686 , -0.97563,-0.189212,-0.111107 --11.1731 , -12.2774 , 4.38 , -0.865164,-0.245899,-0.437065 --11.6874 , -12.7452 , 4.83392 , -0.819646,-0.533893,-0.207698 --11.724 , -12.6983 , 5.15302 , 0.768449,0.638691,0.0394818 --11.6173 , -12.4987 , 5.4222 , -0.747682,-0.658506,0.0856819 --11.7599 , -12.562 , 5.78295 , 0.731886,0.64194,-0.228594 --11.672 , -12.3841 , 6.05676 , -0.706792,-0.707353,-0.00981819 --11.647 , -12.2718 , 6.35438 , 0.778755,0.613921,-0.129003 --11.824 , -12.3665 , 6.74526 , -0.000834533,-0.866936,0.498418 --11.5269 , -11.9742 , 6.91439 , -0.894936,-0.127021,0.427733 --11.306 , -11.6648 , 7.10951 , 0.986277,0.0880639,-0.139651 --11.261 , -11.5328 , 7.38916 , 0.955435,0.000474529,-0.2952 --11.3041 , -11.4906 , 7.71851 , 0.995727,0.049415,-0.0780172 --11.1065 , -11.2088 , 7.9101 , 0.993818,0.010948,0.110477 --11.3323 , -11.3445 , 8.3541 , 0.986224,0.0991419,0.132414 --11.3498 , -11.2738 , 8.67881 , 0.994443,0.0586802,0.0874109 --11.3046 , -11.1416 , 8.9653 , 0.999418,0.034029,-0.00245745 --14.5218 , -14.1443 , 11.5295 , -0.272404,0.722945,-0.634938 --11.8645 , -11.4964 , 10.0107 , -0.860139,-0.48583,-0.15534 --14.5596 , -13.9492 , 12.3793 , -0.122155,0.283802,0.95107 --11.8956 , -11.3326 , 10.7177 , -0.904084,-0.408104,0.126819 --11.8125 , -11.0593 , 11.3496 , -0.872807,-0.479054,0.0933601 --11.9794 , -11.1119 , 11.8491 , -0.0162147,-0.797569,0.60301 --11.8429 , -10.8863 , 12.0916 , -0.859508,-0.363179,0.359648 --11.6111 , -10.575 , 12.2432 , -0.876943,0.00222378,0.480589 --11.4451 , -10.3254 , 12.449 , 0.937111,-0.110362,-0.331126 --11.4573 , -10.2336 , 12.8264 , 0.994675,0.0442911,-0.0930543 --11.4759 , -10.1449 , 13.217 , 0.992589,0.0397067,-0.114846 --11.4713 , -10.0348 , 13.591 , -0.966472,0.00969173,0.256589 --11.249 , -9.737 , 13.7371 , -0.955515,0.0363164,0.292699 --11.7884 , -10.084 , 14.723 , -0.961159,-0.0166249,-0.275493 --11.7294 , -9.91822 , 15.0661 , -0.938953,-0.128336,-0.319215 --4.30319 , -3.26087 , 8.17559 , 0.33202,0.943208,0.0110363 --4.34615 , -3.23316 , 8.44541 , -0.571482,-0.784225,0.241659 --4.15289 , -3.03587 , 8.35574 , 0.732855,0.659867,-0.165831 --4.34673 , -3.11226 , 8.88071 , -0.967481,-0.114796,0.225393 --4.36099 , -3.05875 , 9.13184 , -0.512165,-0.0451213,0.857701 --4.13249 , -2.83783 , 8.97531 , -0.678632,0.0678921,0.731334 --4.06613 , -2.72925 , 9.09172 , 0.271398,-0.00284301,-0.962463 --3.05417 , -2.00652 , 7.49228 , -0.469264,-0.229267,-0.852777 --2.90228 , -1.85719 , 7.40069 , 0.27572,0.295933,0.91455 --2.78873 , -1.73364 , 7.37199 , 0.134045,0.263322,0.95535 --2.64111 , -1.59058 , 7.2704 , 0.010286,-0.203888,0.97894 --2.0188 , -1.17447 , 6.18956 , -0.875653,-0.013698,0.482747 --2.4904 , -1.3965 , 7.34244 , -0.181703,-0.696069,0.694602 --1.96761 , -1.05521 , 6.40521 , -0.765076,-0.156797,0.624559 --1.87557 , -0.958329 , 6.36922 , -0.611897,-0.0375566,0.790045 --1.84308 , -0.89286 , 6.4653 , -0.879663,0.245731,0.407196 --1.83089 , -0.837476 , 6.61518 , -0.954233,-0.267222,0.134283 --1.78603 , -0.764406 , 6.69175 , -0.495455,-0.307974,0.812205 --1.75849 , -0.697749 , 6.81299 , -0.895437,0.0929406,0.435378 --1.69981 , -0.616463 , 6.85955 , -0.688883,0.547982,0.474506 --1.69163 , -0.554967 , 7.04424 , -0.580406,0.176142,0.795049 --1.50453 , -0.426362 , 6.73259 , 0.401813,-0.149232,-0.90348 --1.48054 , -0.358309 , 6.87658 , 0.835202,0.532956,0.135628 --1.65178 , -0.346525 , 7.62571 , -0.892941,0.433475,0.121478 --1.55271 , -0.246734 , 7.57159 , 0.836909,0.547336,0.00266173 --1.56797 , -0.175364 , 7.88737 , -0.881789,0.0466875,0.469327 --1.83426 , -0.143684 , 9.09518 , 0.592669,0.804068,0.0471032 --1.62434 , -0.0143391 , 8.69276 , -0.029487,-0.985762,-0.165541 --1.36915 , 0.108883 , 8.0818 , -0.574569,-0.694476,-0.433098 --1.2073 , 0.210026 , 7.77478 , -0.712495,0.00161147,-0.701676 --1.14355 , 0.30288 , 7.84264 , 0.574249,-0.0743058,0.815302 --1.04396 , 0.39505 , 7.76253 , -0.379818,0.331211,-0.863734 --1.18977 , 0.516696 , 8.7931 , 0.146896,0.974247,0.171068 --1.09361 , 0.620312 , 8.76915 , -0.429669,0.548379,0.717402 --1.11898 , 0.758519 , 9.35967 , 0.864895,0.35221,-0.357639 --1.16874 , 0.926433 , 10.1656 , 0.975082,0.15482,0.158892 --0.718906 , 0.883677 , 8.16094 , 0.262863,-0.248938,-0.932166 --0.641301 , 0.982981 , 8.19538 , -0.167563,-0.618244,0.767918 --0.461276 , 1.00723 , 7.5393 , -0.782217,0.614301,-0.103784 --0.346129 , 1.05844 , 7.24481 , -0.864362,0.448821,0.2268 --0.277787 , 1.1451 , 7.27309 , -0.929634,0.352145,0.108514 --0.222524 , 1.25264 , 7.42694 , 0.465794,-0.728543,-0.502256 --0.0693146 , 1.2124 , 6.65586 , -0.496324,0.853192,-0.160391 --0.836236 , -1.648 , -0.731153 , -0.0538447,0.198253,0.978671 --0.886206 , -1.69952 , -0.720054 , 0.0438267,-0.188841,-0.981029 --0.944956 , -1.76348 , -0.71862 , -0.0728959,0.186329,0.979779 --1.00052 , -1.82228 , -0.70876 , -0.0809219,0.198768,0.9767 --1.06202 , -1.88666 , -0.702503 , -0.0921552,0.161688,0.98253 --1.12395 , -1.95144 , -0.693617 , -0.0919663,0.196058,0.97627 --1.19622 , -2.02997 , -0.692469 , 0.0945014,-0.190349,-0.977158 --1.26386 , -2.10166 , -0.683168 , -0.0565036,0.194936,0.979187 --1.33291 , -2.17344 , -0.67097 , -0.0650708,0.19737,0.978167 --1.4136 , -2.25945 , -0.665265 , -0.0724359,0.169835,0.982807 --1.49478 , -2.34565 , -0.655958 , -0.135436,0.150751,0.97925 --1.59401 , -2.45355 , -0.656353 , -0.102717,0.180592,0.97818 --1.68232 , -2.54675 , -0.643733 , -0.0791932,0.119388,0.989684 --1.79392 , -2.66831 , -0.643712 , 0.0577101,-0.274197,-0.95994 --1.86242 , -2.73302 , -0.606859 , -0.0177984,0.283792,0.958721 --1.97095 , -2.84739 , -0.593842 , -0.0424461,0.258857,0.964983 --2.07489 , -2.95481 , -0.572186 , -0.0645938,0.234339,0.970007 --2.18557 , -3.06874 , -0.549459 , -0.0754305,0.217527,0.973135 --2.31512 , -3.20525 , -0.531467 , -0.0465222,0.217755,0.974894 --2.43988 , -3.33372 , -0.504449 , 0.0526316,-0.217406,-0.974661 --2.58982 , -3.4909 , -0.483822 , 0.063229,-0.207569,-0.976175 --2.75245 , -3.66247 , -0.461608 , -0.0655859,0.212366,0.974987 --2.92352 , -3.84143 , -0.434449 , -0.0642695,0.215354,0.974419 --3.09639 , -4.01933 , -0.399235 , -0.0542154,0.220331,0.973917 --3.30728 , -4.24155 , -0.369796 , -0.0713812,0.211915,0.974678 --3.52685 , -4.47046 , -0.332297 , 0.00684652,0.151785,0.98839 --3.78041 , -4.73602 , -0.294295 , 0.100241,0.0959334,0.990328 --4.02835 , -4.99171 , -0.24248 , 0.0247662,0.404966,0.913996 --4.07231 , -5.00815 , -0.125994 , 0.011793,0.699313,0.714719 --4.28985 , -5.22397 , -0.0483332 , 0.579392,-0.127953,-0.804943 --5.07586 , -6.08745 , -0.0737705 , -0.06865,0.24814,0.966289 --5.50285 , -6.53089 , 0.00392304 , 0.0745081,-0.238919,-0.968177 --6.00324 , -7.0528 , 0.0919155 , -0.068575,0.230306,0.970699 --6.5808 , -7.65319 , 0.195687 , -0.058857,0.225445,0.972476 --7.22815 , -8.32315 , 0.321483 , 0.0357566,0.275408,0.960662 --7.99905 , -9.12251 , 0.471207 , 0.349736,0.228542,0.908544 --8.14871 , -9.22623 , 0.684124 , 0.374775,0.260097,0.889884 --8.3441 , -9.37946 , 0.902558 , 0.374775,0.260097,0.889884 --8.76086 , -9.77098 , 1.13138 , 0.340805,0.166285,0.925311 --9.64617 , -10.6631 , 1.39633 , -0.249453,-0.159279,-0.955198 --10.6291 , -11.6471 , 1.70979 , -0.940802,-0.141467,-0.308023 --10.7666 , -11.718 , 1.99925 , -0.965349,-0.161482,-0.204999 --10.786 , -11.6611 , 2.28099 , 0.991163,0.105305,0.0806586 --10.8003 , -11.6003 , 2.56202 , 0.996361,0.0479358,-0.0704846 --10.799 , -11.522 , 2.84004 , 0.994197,0.0778234,0.0742684 --10.676 , -11.3178 , 3.09481 , 0.976765,0.118385,0.178649 --10.9835 , -11.5603 , 3.43278 , -0.898773,0.0192337,-0.437992 --11.2266 , -11.7317 , 3.77007 , -0.915848,-0.00154445,-0.401521 --11.2109 , -11.6371 , 4.05248 , -0.962593,0.0960504,-0.253355 --11.4808 , -11.8315 , 4.41444 , -0.935562,0.0312854,-0.351775 --11.6519 , -11.842 , 5.05627 , 0.965478,-0.129092,0.226245 --11.6215 , -11.7302 , 5.34278 , 0.996346,0.0666001,0.0534733 --11.7037 , -11.7299 , 5.67139 , 0.992801,0.047392,-0.110004 --11.5561 , -11.5024 , 5.91139 , 0.993622,-0.0969799,-0.0575406 --12.6325 , -12.4665 , 6.67 , -0.0282523,-0.974182,0.22399 --11.5037 , -11.2057 , 6.7813 , 0.974627,-0.180493,-0.132379 --11.3284 , -10.9572 , 6.99325 , -0.984482,0.15017,0.0907961 --11.1852 , -10.7408 , 7.2146 , -0.957994,0.147495,0.245954 --11.2953 , -10.7625 , 7.57106 , 0.996607,-0.0822807,-0.00195719 --11.0042 , -10.4091 , 7.70239 , 0.989534,-0.0100801,0.14395 --11.3757 , -10.6707 , 8.22182 , 0.980685,0.00536147,0.195522 --11.3917 , -10.6019 , 8.53946 , 0.993104,0.01179,0.116638 --11.3112 , -10.4435 , 8.79666 , 0.997716,-0.00173983,0.0675305 --14.5847 , -13.3097 , 11.3435 , -0.341108,0.796028,-0.499985 --11.8848 , -10.7841 , 9.82822 , -0.955363,-0.0990352,-0.278342 --14.6203 , -13.1188 , 12.1758 , 0.23065,-0.421966,0.876781 --14.6486 , -13.0314 , 12.6088 , 0.0881125,-0.342817,0.935261 --14.0622 , -12.4057 , 12.5621 , 0.0881125,-0.342817,0.935261 --11.8902 , -10.4166 , 11.1887 , 0.984982,0.130604,-0.11293 --12.8069 , -11.1053 , 12.3158 , -0.280794,-0.93817,0.202467 --12.0642 , -10.3701 , 12.0461 , -0.956914,0.185479,0.223414 --11.5536 , -9.83994 , 11.9492 , 0.982512,-0.152085,-0.10743 --11.5699 , -9.75574 , 12.3206 , 0.99855,0.00300787,-0.0537526 --11.5427 , -9.63476 , 12.6577 , 0.998272,0.0509377,-0.0292919 --11.5051 , -9.50299 , 12.9884 , 0.995004,0.0282782,-0.0957442 --11.5542 , -9.43976 , 13.412 , -0.954414,0.0117613,0.298254 --11.3321 , -9.15657 , 13.5583 , -0.932178,0.0931605,0.349808 --11.1609 , -8.91656 , 13.7547 , 0.999099,0.0421454,-0.00490473 --11.8021 , -9.31143 , 14.8595 , -0.949171,-0.028554,-0.313463 --11.5829 , -9.02869 , 15.0204 , -0.949171,-0.028554,-0.313463 --4.51567 , -3.16094 , 8.35284 , 0.732855,0.659866,-0.165831 --4.42085 , -3.03861 , 8.42263 , -0.0842119,-0.786777,0.611466 --4.36025 , -2.93906 , 8.54435 , -0.851708,-0.306927,0.424722 --4.31248 , -2.84744 , 8.68849 , -0.945833,-0.26598,0.186158 --4.34695 , -2.80804 , 8.96905 , 0.693104,-0.262435,-0.671368 --4.24951 , -2.68319 , 9.03888 , 0.693104,-0.262435,-0.671368 --2.30227 , -1.42377 , 5.90034 , 0.817277,0.0158077,-0.576028 --2.27465 , -1.3667 , 5.99569 , -0.858613,-0.049801,0.5102 --2.85744 , -1.66596 , 7.21591 , 0.596039,0.0577104,0.800879 --2.73719 , -1.54637 , 7.17617 , 0.446119,-0.198867,0.872599 --2.12288 , -1.15467 , 6.16572 , 0.914235,0.368831,-0.167745 --2.635 , -1.38537 , 7.35506 , -0.359951,-0.181242,0.915198 --2.09652 , -1.05156 , 6.436 , -0.416004,0.379496,0.826392 --2.06629 , -0.989269 , 6.54445 , 0.507477,-0.83689,0.20514 --1.9221 , -0.870645 , 6.40197 , -0.674559,0.638423,-0.370658 --1.95379 , -0.836348 , 6.6511 , 0.161287,-0.832482,0.530057 --1.89933 , -0.76166 , 6.71147 , 0.868911,0.168006,-0.465584 --1.83252 , -0.680336 , 6.74259 , -0.292476,-0.430998,0.853638 --1.75149 , -0.593703 , 6.73523 , -0.293084,-0.178689,0.93924 --1.69476 , -0.5165 , 6.79017 , 0.27744,-0.249911,0.92767 --1.84302 , -0.510325 , 7.40289 , 0.988384,-0.144929,0.0457553 --1.52856 , -0.345315 , 6.75515 , -0.56835,-0.485981,0.663928 --1.4863 , -0.272696 , 6.85178 , 0.972064,-0.00970269,0.234516 --1.71326 , -0.267458 , 7.77133 , -0.877127,-0.434362,-0.204885 --1.57027 , -0.160036 , 7.59367 , -0.530033,-0.846889,0.0429337 --1.8491 , -0.136353 , 8.78847 , 0.0299579,-0.911531,0.410138 --1.76831 , -0.0314383 , 8.84871 , -0.125782,-0.966188,-0.225076 --1.52029 , 0.0906452 , 8.30984 , -0.624239,-0.621619,-0.473197 --1.32334 , 0.195278 , 7.90957 , -0.49058,-0.523283,-0.696783 --1.22446 , 0.288375 , 7.85335 , 0.557051,-0.027202,0.830033 --1.11254 , 0.378242 , 7.73635 , -0.453976,0.265677,-0.850483 --1.04278 , 0.468181 , 7.79226 , 0.418597,0.201742,0.885481 --1.14551 , 0.592015 , 8.64668 , 0.612929,-0.478155,-0.629035 --1.17801 , 0.723668 , 9.25788 , 0.864895,0.35221,-0.357639 --1.11171 , 0.843277 , 9.42741 , -0.875469,-0.304431,0.375334 --0.769885 , 0.848759 , 8.0938 , 0.518346,-0.247991,-0.818424 --0.69303 , 0.946393 , 8.13956 , -0.34414,-0.12733,0.930244 --0.391139 , 0.894144 , 6.75855 , -0.744303,0.64616,0.168793 --0.342792 , 0.985699 , 6.89802 , -0.739336,0.669484,0.0719246 --0.308742 , 1.09849 , 7.17348 , -0.94322,0.293564,0.155423 --0.274393 , 1.22521 , 7.49618 , 0.747376,-0.638895,0.182325 --0.136873 , 1.22237 , 6.94245 , 0.617625,-0.629381,-0.471614 --0.0238869 , 1.22563 , 6.50537 , 0.7603,0.647104,-0.0565774 --0.858692 , -1.58339 , -0.750501 , -0.02284,0.193823,0.980771 --0.90528 , -1.62639 , -0.734805 , -0.0791693,0.211511,0.974164 --0.961823 , -1.68265 , -0.729086 , -0.095434,0.166595,0.981396 --1.02357 , -1.7457 , -0.726847 , -0.109614,0.204688,0.97267 --1.08067 , -1.80193 , -0.716553 , 0.103673,-0.182118,-0.977796 --1.15387 , -1.8781 , -0.720324 , -0.090668,0.175722,0.980256 --1.21857 , -1.94095 , -0.710539 , -0.117023,0.18885,0.975008 --1.29364 , -2.01752 , -0.708296 , -0.0742236,0.207063,0.975508 --1.35921 , -2.08109 , -0.692862 , -0.0657387,0.214562,0.974496 --1.43615 , -2.15802 , -0.684508 , -0.0815992,0.192801,0.977839 --1.51332 , -2.23425 , -0.673042 , -0.119236,0.158081,0.980201 --1.6146 , -2.33911 , -0.676434 , -0.103473,0.170509,0.979908 --1.7052 , -2.43018 , -0.66642 , -0.0817918,0.183684,0.979577 --1.81467 , -2.54156 , -0.665454 , -0.103316,0.168509,0.980271 --1.93109 , -2.66049 , -0.66351 , -0.0492333,0.297507,0.95345 --1.99604 , -2.7155 , -0.621284 , -0.0329473,0.30929,0.950397 --2.10201 , -2.81992 , -0.60282 , -0.0542402,0.23938,0.96941 --2.22208 , -2.93821 , -0.587003 , -0.0744249,0.233927,0.969402 --2.34821 , -3.06403 , -0.569115 , -0.0613483,0.234703,0.970129 --2.4705 , -3.18166 , -0.542614 , -0.0589463,0.225516,0.972455 --2.6177 , -3.32716 , -0.523187 , -0.0803408,0.222823,0.971543 --2.76682 , -3.47289 , -0.497066 , -0.0771593,0.225116,0.971272 --2.94152 , -3.64781 , -0.474997 , -0.0850629,0.222841,0.971137 --3.12544 , -3.82884 , -0.447814 , -0.0658466,0.230551,0.97083 --3.32316 , -4.02358 , -0.417122 , -0.0811316,0.223251,0.971379 --3.54773 , -4.24637 , -0.386517 , 0.00628028,0.229177,0.973365 --3.78101 , -4.47576 , -0.347465 , 0.091655,0.141724,0.985654 --4.06309 , -4.75462 , -0.31136 , -0.136085,-0.0240225,-0.990406 --4.3727 , -5.06113 , -0.26921 , -0.418853,0.678983,0.602946 --4.73759 , -5.425 , -0.225112 , -0.11369,0.171065,0.978678 --5.09938 , -5.77845 , -0.162576 , 0.0711287,-0.251069,-0.965352 --5.48304 , -6.15311 , -0.0865007 , -0.0841796,0.259987,0.961936 --5.96512 , -6.62583 , -0.00804755 , -0.0812002,0.251454,0.964457 --6.5169 , -7.1678 , 0.0839373 , -0.0658609,0.234076,0.969985 --7.16096 , -7.80012 , 0.192434 , -0.009144,0.23759,0.971322 --7.85788 , -8.47898 , 0.327545 , 0.205301,0.279982,0.937796 --8.14838 , -8.72642 , 0.520287 , -0.255221,-0.28859,-0.92281 --8.32862 , -8.8538 , 0.729486 , 0.250085,0.331461,0.90972 --8.56212 , -9.03592 , 0.945539 , 0.31755,0.329128,0.88929 --9.25649 , -9.68572 , 1.1782 , 0.0930667,0.384649,0.918359 --10.6097 , -10.9977 , 1.46898 , -0.964203,-0.22357,-0.142582 --10.7948 , -11.1111 , 1.7503 , -0.969543,-0.103238,-0.222102 --10.8141 , -11.0577 , 2.02513 , 0.981266,0.0877524,0.171512 --10.8157 , -10.9861 , 2.29748 , 0.998209,0.057944,0.0148686 --10.828 , -10.9254 , 2.57046 , 0.995039,0.0956587,-0.0273161 --10.8089 , -10.8336 , 2.83803 , 0.982051,0.160495,0.0990875 --10.885 , -10.8359 , 3.1216 , -0.970165,-0.168306,-0.17451 --11.0007 , -10.8753 , 3.41638 , -0.965472,-0.113059,-0.234693 --11.0142 , -10.8137 , 3.69235 , 0.99387,0.0545469,0.0961582 --11.0229 , -10.7491 , 3.96821 , 0.996005,0.0842595,0.029572 --11.0367 , -10.6882 , 4.24535 , 0.995957,0.0836975,0.0326381 --11.0525 , -10.6306 , 4.52452 , 0.99544,0.0893658,0.0333618 --11.073 , -10.5746 , 4.80545 , 0.995372,0.0907352,0.0316512 --11.0819 , -10.5092 , 5.08452 , 0.995776,0.0876147,0.0274646 --11.088 , -10.4405 , 5.36323 , 0.996473,0.0810112,0.0218596 --11.112 , -10.3877 , 5.65007 , 0.996634,0.0777523,0.0259967 --11.1171 , -10.3175 , 5.93153 , 0.996275,0.0802467,0.0315639 --11.1333 , -10.257 , 6.21906 , 0.99631,0.0785329,0.0346214 --11.1455 , -10.1922 , 6.50695 , 0.996005,0.088054,0.0148241 --11.1687 , -10.1358 , 6.80197 , 0.998957,0.0384904,0.0245495 --11.1449 , -10.0375 , 7.07604 , 0.993477,0.048352,-0.103273 --11.1873 , -9.9983 , 7.38688 , 0.999967,-0.00612383,0.00527425 --11.039 , -9.79048 , 7.59337 , 0.985557,0.106242,0.13187 --11.2811 , -9.92236 , 8.02614 , 0.969672,0.0321924,0.24228 --11.3044 , -9.86133 , 8.33821 , 0.983789,0.0322701,0.176402 --11.2678 , -9.74965 , 8.61637 , 0.992069,0.0742995,0.10139 --11.4052 , -9.78396 , 9.01147 , 0.988571,0.069665,0.133698 --11.4215 , -9.71425 , 9.3331 , 0.991859,0.105139,0.0718483 --11.4337 , -9.63912 , 9.65556 , 0.994396,0.102346,0.0264749 --11.4409 , -9.55968 , 9.97926 , 0.994604,0.101957,0.0191556 --11.4699 , -9.49671 , 10.3243 , 0.994874,0.0986369,0.0222627 --11.4739 , -9.41236 , 10.6553 , 0.995761,0.0885642,0.0248142 --11.5066 , -9.34873 , 11.0143 , 0.996535,0.079959,0.0229192 --11.52 , -9.26862 , 11.3643 , 0.99807,0.0448336,0.0429744 --11.5281 , -9.18221 , 11.7155 , 0.999116,0.0259181,0.0330949 --11.544 , -9.10062 , 12.0798 , 0.999822,0.0181397,-0.00516145 --11.5487 , -9.00803 , 12.4396 , 0.999313,0.0175581,-0.0326361 --11.5032 , -8.87556 , 12.7577 , 0.998004,0.0426852,-0.046542 --11.5827 , -8.83743 , 13.2065 , -0.921041,-2.31418e-05,0.389465 --11.4344 , -8.62509 , 13.4296 , -0.897856,0.0661239,0.435295 --11.2152 , -8.36012 , 13.5756 , -0.605889,-0.0167459,0.795373 --11.6822 , -8.59862 , 14.4721 , -0.980935,-0.0436077,-0.189381 --11.6502 , -8.4661 , 14.8403 , -0.960605,-0.00307191,-0.277902 --4.62281 , -3.35227 , 7.03362 , -0.857426,-0.509017,-0.0756496 --4.46551 , -3.14564 , 7.19942 , -0.768424,0.634825,0.0807533 --4.62942 , -3.20888 , 7.59045 , 0.875911,0.384856,-0.290975 --4.52172 , -3.08502 , 7.64245 , 0.903547,-0.372244,-0.21222 --4.4586 , -2.99101 , 7.7506 , -0.506037,0.845184,0.172018 --4.46494 , -2.94168 , 7.95557 , 0.140073,0.990141,-0.00098955 --4.6761 , -3.02289 , 8.46194 , 0.229692,-0.664508,0.711105 --4.95164 , -3.13721 , 9.08643 , 0.115805,0.781451,0.613126 --3.45943 , -2.15181 , 7.05733 , 0.210963,0.576951,-0.789064 --4.39838 , -2.67272 , 8.70369 , -0.894055,0.31501,0.318489 --3.90281 , -2.31803 , 8.13299 , -0.934555,0.132954,-0.330047 --2.36703 , -1.36931 , 5.79667 , -0.792129,-0.229332,0.565631 --2.37314 , -1.33386 , 5.9502 , 0.817278,0.0158076,-0.576028 --2.29064 , -1.24851 , 5.95362 , -0.79952,-0.0780097,0.595552 --2.25043 , -1.18677 , 6.03076 , -0.739311,-0.0322011,0.672593 --2.3136 , -1.1786 , 6.3038 , -0.924978,-0.190852,0.32862 --2.18328 , -1.06821 , 6.21652 , -0.521341,-0.826434,-0.212625 --2.11731 , -0.991023 , 6.24697 , 0.478786,0.77654,-0.409574 --3.92754 , -1.80507 , 10.131 , -0.522361,0.631363,-0.573166 --3.89708 , -1.71167 , 10.3594 , -0.522361,0.631363,-0.573166 --2.52711 , -1.02944 , 7.66991 , -0.453828,-0.421369,0.785167 --3.37675 , -1.32428 , 9.81378 , 0.58079,-0.423522,0.695206 --1.83602 , -0.632454 , 6.50816 , 0.835383,-0.438255,-0.331765 --1.73885 , -0.544767 , 6.46434 , -0.624186,0.517607,0.585214 --1.80503 , -0.515979 , 6.82305 , 0.185912,0.191642,-0.963696 --1.7027 , -0.425799 , 6.76704 , 0.193041,0.192218,0.962179 --1.6705 , -0.357948 , 6.89452 , 0.367457,-0.717119,0.592212 --1.59548 , -0.27687 , 6.90894 , -0.94111,0.12874,0.312631 --1.56167 , -0.206806 , 7.04395 , -0.96686,-0.254759,-0.016756 --1.60475 , -0.150693 , 7.41507 , 0.490168,0.857294,0.157423 --1.90066 , -0.131072 , 8.61548 , 0.328665,-0.345634,-0.878929 --1.82813 , -0.0326156 , 8.70565 , -0.104282,-0.968486,0.226185 --1.73719 , 0.0689373 , 8.73647 , -0.121333,0.827166,-0.548702 --1.46602 , 0.181657 , 8.11931 , 0.621377,0.590457,0.515026 --1.33011 , 0.27573 , 7.94989 , -0.269436,-0.39128,-0.879946 --1.2225 , 0.364743 , 7.87429 , 0.111874,0.610096,0.78439 --1.11684 , 0.452553 , 7.79562 , 0.469897,0.00563918,0.882703 --1.22602 , 0.57067 , 8.65024 , -0.422621,0.660529,0.620559 --1.12303 , 0.667618 , 8.61751 , -0.740627,0.319044,0.591339 --1.17483 , 0.810396 , 9.34544 , 0.864895,0.35221,-0.357639 --1.11295 , 0.932811 , 9.56375 , 0.822186,0.478346,-0.308538 --0.760535 , 0.920245 , 8.17096 , -0.302589,0.0310061,0.952617 --0.693367 , 1.02391 , 8.30519 , 0.33699,0.552921,-0.762048 --0.379993 , 0.950463 , 6.83568 , -0.843647,0.52162,-0.127172 --0.341157 , 1.05419 , 7.07314 , -0.898757,0.426393,-0.102103 --0.284252 , 1.15052 , 7.21043 , -0.904185,0.377723,0.199438 --0.221701 , 1.2473 , 7.33631 , -0.114184,0.966898,-0.228189 --0.0700964 , 1.20949 , 6.61555 , -0.868337,0.47619,0.138686 --0.870419 , -1.50514 , -0.757124 , 0.125526,-0.196961,-0.972342 --0.922451 , -1.55358 , -0.748828 , -0.0798487,0.194748,0.977598 --0.980389 , -1.60773 , -0.744718 , -0.0966601,0.210106,0.972889 --1.04352 , -1.66869 , -0.744186 , -0.105989,0.187968,0.97644 --1.10707 , -1.73005 , -0.741023 , -0.104512,0.188226,0.976549 --1.17177 , -1.79065 , -0.73555 , -0.0951899,0.196847,0.975802 --1.23785 , -1.85145 , -0.727665 , -0.0900217,0.193275,0.977006 --1.30942 , -1.9198 , -0.722187 , -0.0841214,0.182918,0.979523 --1.38121 , -1.98751 , -0.713888 , -0.0569418,0.210995,0.975827 --1.45441 , -2.05534 , -0.702788 , 0.0790607,-0.217187,-0.972923 --1.54022 , -2.13719 , -0.698303 , -0.110957,0.17246,0.978747 --1.64335 , -2.23795 , -0.704404 , -0.149791,0.168507,0.974253 --1.73626 , -2.32684 , -0.6968 , -0.0887057,0.188446,0.978069 --1.81917 , -2.40095 , -0.676887 , -0.115238,0.168309,0.978975 --1.94984 , -2.53039 , -0.68699 , -0.0772748,0.187996,0.979125 --2.03993 , -2.61137 , -0.663181 , -0.0229696,0.309883,0.950497 --2.13763 , -2.69891 , -0.639588 , -0.0124282,0.282826,0.959091 --2.25335 , -2.80662 , -0.623267 , -0.0612759,0.228086,0.971711 --2.37088 , -2.91491 , -0.601809 , -0.0699719,0.225614,0.971701 --2.49519 , -3.02959 , -0.578695 , -0.0674046,0.233852,0.969933 --2.63988 , -3.16436 , -0.560271 , -0.0941284,0.234654,0.967511 --2.80532 , -3.31979 , -0.544687 , -0.0883837,0.232703,0.968524 --2.96628 , -3.46792 , -0.518907 , -0.0898088,0.228087,0.96949 --3.16006 , -3.65128 , -0.49954 , -0.0801188,0.230979,0.969655 --3.34393 , -3.81956 , -0.466597 , -0.0801127,0.23311,0.969145 --3.5673 , -4.02977 , -0.439772 , -0.00579356,0.304543,0.952481 --3.76663 , -4.2095 , -0.394296 , 0.137993,0.322299,0.936526 --3.80553 , -4.21918 , -0.289854 , -0.00156067,-0.990992,0.133916 --3.88967 , -4.277 , -0.197955 , 0.2807,0.917195,-0.282773 --3.75508 , -4.10677 , -0.0473155 , 0.20879,-0.939542,0.271419 --3.72055 , -4.04221 , 0.0721437 , 0.122115,-0.916124,0.381844 --3.71136 , -4.00363 , 0.183041 , -0.164561,-0.889013,0.427289 --3.72057 , -3.9857 , 0.288905 , -0.490065,-0.829648,0.267432 --3.7293 , -3.96591 , 0.39418 , 0.519508,0.825198,-0.221719 --3.70141 , -3.9092 , 0.503303 , 0.509618,0.82673,-0.238343 --3.73502 , -3.91571 , 0.604031 , 0.507829,0.827848,-0.238279 --3.71778 , -3.87186 , 0.709404 , 0.614495,0.788626,0.0215784 --3.71323 , -3.8401 , 0.812246 , 0.592135,0.803617,0.0598016 --3.81479 , -3.91218 , 0.910897 , 0.592135,0.803617,0.0598015 --3.80101 , -3.87099 , 1.01446 , 0.592135,0.803617,0.0598015 --3.79927 , -3.84283 , 1.11687 , 0.592135,0.803617,0.0598015 --10.7624 , -10.4721 , 1.51025 , -0.882501,-0.422268,-0.20708 --10.8258 , -10.4625 , 1.77976 , -0.917877,-0.392913,-0.0558653 --10.8575 , -10.4221 , 2.04816 , -0.817391,-0.576073,0.00349695 --10.8854 , -10.3785 , 2.31663 , -0.913589,-0.391877,0.10857 --10.8878 , -10.3102 , 2.58186 , -0.913312,-0.38552,0.131287 --10.756 , -10.119 , 2.8254 , -0.89481,-0.442591,-0.0585477 --10.9703 , -10.2465 , 3.12502 , -0.737715,-0.636446,-0.225196 --11.0573 , -10.2565 , 3.4084 , -0.870854,-0.490537,-0.0314067 --11.0612 , -10.1885 , 3.67614 , -0.858172,-0.509562,0.0623523 --11.0829 , -10.1381 , 3.94879 , -0.865347,-0.487488,0.116318 --11.0861 , -10.0711 , 4.21763 , -0.861298,-0.497911,0.101245 --11.1078 , -10.0193 , 4.49213 , -0.870143,-0.483284,0.0963709 --11.1269 , -9.96492 , 4.76705 , -0.864334,-0.492494,0.101868 --11.1341 , -9.90028 , 5.03972 , -0.857802,-0.501318,0.113385 --11.1375 , -9.83242 , 5.31216 , -0.853421,-0.508267,0.115487 --11.1459 , -9.76705 , 5.58694 , -0.853739,-0.510937,0.100364 --11.1711 , -9.71669 , 5.87064 , -0.850207,-0.518707,0.0899549 --11.1857 , -9.65679 , 6.15217 , -0.846941,-0.525093,0.0834769 --11.1893 , -9.58658 , 6.43063 , -0.854771,-0.506412,0.113638 --11.2109 , -9.53078 , 6.71955 , -0.850617,-0.508369,0.134207 --11.1918 , -9.44134 , 6.99114 , -0.686487,-0.651376,0.323178 --11.2195 , -9.38965 , 7.28845 , -0.817241,-0.534405,0.215704 --11.0448 , -9.17123 , 7.47621 , -0.860441,-0.50362,0.0775096 --11.3338 , -9.33169 , 7.92798 , -0.838243,-0.521001,-0.160955 --11.3557 , -9.27215 , 8.23453 , -0.894474,-0.445556,0.0373584 --11.303 , -9.15174 , 8.49804 , -0.723595,-0.688158,0.0533864 --11.456 , -9.19401 , 8.89686 , -0.848832,-0.527121,-0.0403332 --11.4719 , -9.12558 , 9.21284 , -0.731059,-0.627208,0.268631 --11.4955 , -9.06244 , 9.53973 , -0.600101,-0.796936,0.0690794 --11.5084 , -8.99003 , 9.86336 , -0.796202,-0.5787,0.17655 --11.523 , -8.91699 , 10.1931 , -0.78695,-0.590894,0.177631 --11.5265 , -8.83387 , 10.5187 , -0.790748,-0.585355,0.1791 --11.5449 , -8.7613 , 10.8618 , -0.801139,-0.575636,0.163764 --11.5511 , -8.67792 , 11.2008 , -0.691986,-0.71799,-0.0751351 --11.5708 , -8.60314 , 11.5581 , -0.803855,-0.572147,0.162681 --11.5864 , -8.52273 , 11.9172 , 0.691393,0.639693,-0.335811 --11.5889 , -8.43271 , 12.2721 , -0.735631,-0.672276,0.0830188 --11.5544 , -8.31291 , 12.5972 , -0.64001,-0.704887,0.305814 --11.6281 , -8.26897 , 13.0352 , -0.808587,-0.456164,0.37162 --11.5001 , -8.08102 , 13.2786 , -0.657925,-0.288733,0.695534 --11.2753 , -7.82582 , 13.4197 , -0.657925,-0.288733,0.695534 --4.62094 , -3.19379 , 6.58887 , 0.718803,-0.297156,-0.628507 --4.59325 , -3.13106 , 6.72684 , -0.958156,-0.28558,0.0195088 --4.72668 , -3.17372 , 7.05083 , 0.907196,0.414407,0.0725442 --4.43708 , -2.93663 , 6.88822 , 0.604275,-0.709623,-0.362336 --4.18098 , -2.72496 , 6.75043 , -0.779192,0.616107,-0.115201 --4.33964 , -2.78138 , 7.11985 , 0.225764,0.158705,0.961168 --4.06778 , -2.5636 , 6.94928 , 0.0424522,-0.443233,0.895401 --3.98677 , -2.46784 , 7.01633 , -0.0096108,-0.405045,0.914246 --3.86086 , -2.34484 , 7.02003 , -0.0699955,-0.23032,0.970594 --4.09552 , -2.43762 , 7.52871 , -0.938839,0.343967,0.0163619 --4.87435 , -2.84118 , 8.85286 , -0.21196,0.973688,0.0836983 --4.33749 , -2.47264 , 8.2818 , -0.945019,0.109839,-0.308016 --4.01118 , -2.23235 , 7.996 , -0.957997,0.1041,-0.267216 --2.46507 , -1.33057 , 5.74978 , 0.661746,0.163008,-0.731792 --2.40711 , -1.26163 , 5.79671 , -0.666231,-0.154677,0.729528 --2.37233 , -1.20496 , 5.88353 , -0.756456,-0.15137,0.636287 --2.30244 , -1.13042 , 5.91096 , 0.709505,0.332364,-0.621399 --2.28478 , -1.0818 , 6.02968 , 0.710564,0.259389,-0.654077 --2.22728 , -1.01316 , 6.07972 , 0.760392,0.286806,-0.582706 --2.27315 , -0.992471 , 6.32737 , 0.870336,-0.286616,-0.400459 --2.78461 , -1.17681 , 7.5029 , -0.879844,-0.177231,0.44098 --2.66167 , -1.0684 , 7.46311 , -0.895266,0.0089991,0.445441 --2.64629 , -1.00575 , 7.6417 , -0.786743,-0.422559,0.449977 --3.94402 , -1.46046 , 10.6784 , 0.496304,0.213429,0.841505 --3.44818 , -1.18675 , 9.89499 , 0.58079,-0.423522,0.695206 --1.82204 , -0.528852 , 6.43153 , -0.301027,0.35816,0.883801 --1.74661 , -0.452959 , 6.4417 , 0.301027,-0.35816,-0.883801 --1.82246 , -0.424495 , 6.82782 , -0.0121069,-0.0260851,0.999586 --1.68122 , -0.327533 , 6.67871 , 0.196691,0.466258,0.862506 --1.43623 , -0.206781 , 6.23623 , -0.623401,0.738637,-0.25649 --1.57891 , -0.186446 , 6.83774 , 0.555062,0.0143913,-0.831685 --1.53508 , -0.115437 , 6.94369 , 0.79055,0.039625,-0.611114 --1.76409 , -0.0898588 , 7.88285 , 0.253853,0.9518,0.172152 --1.93185 , -0.0354518 , 8.70484 , -0.500195,-0.753563,0.426554 --1.89006 , 0.0587074 , 8.90984 , 0.390942,0.896346,0.209114 --1.58474 , 0.173259 , 8.2207 , -0.274855,-0.928045,-0.251369 --1.42675 , 0.266228 , 7.99634 , 0.708202,0.652933,0.268566 --1.38463 , 0.356647 , 8.18371 , 0.760616,0.227596,-0.608 --1.21736 , 0.441306 , 7.89489 , 0.306234,0.0966153,0.947041 --1.30395 , 0.553754 , 8.63263 , -0.422621,0.660529,0.620559 --1.19357 , 0.646342 , 8.58263 , 0.599558,-0.413559,-0.685201 --1.11167 , 0.745442 , 8.6567 , -0.841893,-0.116112,0.527004 --1.14791 , 0.888883 , 9.33547 , 0.662074,0.584793,-0.468695 --0.486495 , 0.741454 , 6.34918 , 0.156673,-0.77934,0.606699 --0.728127 , 0.979495 , 8.14067 , 0.165098,0.0185478,-0.986103 --0.447379 , 0.939067 , 6.95863 , 0.942424,-0.319948,-0.0973136 --0.342168 , 0.987516 , 6.7555 , 0.642965,-0.702163,-0.305881 --0.289804 , 1.0799 , 6.9139 , -0.928054,0.323295,0.184922 --0.271933 , 1.21946 , 7.37514 , -0.748058,0.636188,0.188879 --0.125432 , 1.2024 , 6.77369 , -0.271876,0.95407,0.125834 --0.0246359 , 1.22578 , 6.4951 , 0.7603,0.647104,-0.0565773 --0.783559 , -1.34719 , -0.783551 , -0.0762592,0.166432,0.9831 --0.830757 , -1.38712 , -0.774041 , -0.0801597,0.20036,0.976438 --0.888836 , -1.44022 , -0.775214 , -0.0880802,0.201852,0.975447 --0.941308 , -1.48672 , -0.768211 , -0.0816019,0.186177,0.979122 --1.00567 , -1.54605 , -0.771428 , -0.102722,0.189295,0.976533 --1.05964 , -1.5924 , -0.760457 , -0.0912656,0.174565,0.980407 --1.12554 , -1.65145 , -0.759122 , -0.082816,0.151688,0.984953 --1.19089 , -1.71115 , -0.755134 , -0.0783797,0.173809,0.981655 --1.25256 , -1.76382 , -0.743309 , -0.075516,0.168037,0.982884 --1.33132 , -1.83612 , -0.745184 , -0.094687,0.173429,0.980284 --1.40545 , -1.90157 , -0.738907 , -0.0598157,0.203482,0.97725 --1.48003 , -1.96733 , -0.72961 , -0.0902572,0.20093,0.975439 --1.5621 , -2.04005 , -0.722281 , -0.0890286,0.197236,0.976305 --1.6444 , -2.11207 , -0.711839 , -0.132952,0.165736,0.977167 --1.75131 , -2.21058 , -0.716675 , -0.105761,0.191313,0.975815 --1.84681 , -2.29648 , -0.707883 , 0.0837232,-0.198578,-0.976503 --1.95676 , -2.39458 , -0.704199 , -0.105989,0.150543,0.982905 --2.07977 , -2.50697 , -0.704014 , -0.0126908,0.20888,0.977859 --2.16017 , -2.57158 , -0.670745 , -0.021015,0.327869,0.94449 --2.2666 , -2.66279 , -0.649952 , -0.0427842,0.257391,0.96536 --2.39327 , -2.77452 , -0.635699 , -0.0663459,0.217408,0.973823 --2.53292 , -2.89915 , -0.623196 , -0.0667479,0.226391,0.971747 --2.668 , -3.01672 , -0.601568 , 0.0826665,-0.224164,-0.971039 --2.82474 , -3.15492 , -0.583678 , -0.0867392,0.220694,0.971478 --2.99557 , -3.30533 , -0.565519 , 0.0819898,-0.228773,-0.970021 --3.17461 , -3.46222 , -0.542806 , 0.0837969,-0.22629,-0.970449 --3.36834 , -3.63284 , -0.517679 , -0.0704306,0.227528,0.971221 --3.58383 , -3.82212 , -0.492011 , -0.0776381,0.220176,0.972366 --3.81538 , -4.02536 , -0.461615 , -0.0546448,0.318234,0.946436 --4.03515 , -4.21378 , -0.416624 , -0.178748,-0.739511,-0.648979 --4.07407 , -4.22174 , -0.308974 , 0.279911,0.816398,0.505119 --4.11282 , -4.22853 , -0.200549 , 0.133796,0.658912,0.740226 --4.34689 , -4.42582 , -0.139407 , -0.101621,0.519169,0.848608 --5.50561 , -5.5159 , -0.268891 , -0.0824313,0.259613,0.962188 --5.96193 , -5.91436 , -0.206935 , -0.0821869,0.258575,0.962489 --6.4487 , -6.33872 , -0.128958 , -0.0678831,0.252821,0.965129 --3.88623 , -3.86511 , 0.408858 , -0.51251,-0.830886,0.216707 --3.87084 , -3.82337 , 0.517037 , 0.513032,0.826949,-0.230114 --3.86149 , -3.78695 , 0.622781 , 0.42234,0.893336,-0.153557 --3.87929 , -3.77704 , 0.725295 , -0.563532,-0.825952,-0.0153428 --3.87382 , -3.74534 , 0.828939 , 0.592135,0.803617,0.0598015 --3.94037 , -3.77943 , 0.929636 , 0.592135,0.803617,0.0598016 --10.9542 , -10.1449 , 1.02427 , 0.302044,0.797902,0.521653 --11.0022 , -10.1189 , 1.29009 , 0.0340406,0.915206,0.401547 --11.2169 , -10.2442 , 1.56449 , 0.205108,0.97727,0.0536139 --11.2203 , -10.1782 , 1.83314 , -0.372109,-0.923769,0.0904745 --11.2207 , -10.109 , 2.10036 , 0.622022,0.770681,-0.138346 --11.2393 , -10.0561 , 2.36877 , -0.380639,-0.901759,0.204802 --11.2097 , -9.96178 , 2.6308 , -0.37206,-0.927426,0.0381061 --11.2888 , -9.96243 , 2.90813 , 0.346815,0.933854,0.0873882 --11.4768 , -10.0554 , 3.20817 , 0.203274,0.975259,0.0868869 --11.4816 , -9.98961 , 3.47912 , 0.262664,0.957786,-0.116851 --11.5127 , -9.94649 , 3.75621 , -0.220298,-0.951898,0.212975 --11.5029 , -9.86808 , 4.02437 , -0.218749,-0.952599,0.211434 --11.534 , -9.82353 , 4.3034 , -0.222269,-0.953573,0.203209 --11.5311 , -9.75122 , 4.57447 , 0.214233,0.958403,-0.188596 --11.5695 , -9.71317 , 4.85905 , 0.221632,0.953703,-0.203295 --11.5824 , -9.65232 , 5.13709 , -0.216858,-0.953721,0.208302 --11.5905 , -9.58843 , 5.41521 , -0.20458,-0.955305,0.213401 --11.6036 , -9.52692 , 5.69617 , 0.202958,0.958309,-0.201129 --11.6186 , -9.46741 , 5.98042 , 0.199653,0.958695,-0.202589 --11.6388 , -9.41109 , 6.26829 , 0.203805,0.954337,-0.218416 --11.6463 , -9.34482 , 6.55363 , -0.195057,-0.957628,0.211901 --11.6358 , -9.2624 , 6.83182 , -0.201342,-0.940394,0.27408 --11.7015 , -9.24001 , 7.15018 , -0.226235,-0.907297,0.354442 --11.5511 , -9.04874 , 7.36036 , -0.23079,-0.964858,0.125635 --11.5587 , -8.98007 , 7.65193 , 0.22361,0.974159,-0.0318228 --11.843 , -9.12241 , 8.10561 , -0.134093,-0.989347,-0.0566738 --11.8257 , -9.03087 , 8.39531 , -0.178452,-0.98347,-0.0306961 --12.0122 , -9.09226 , 8.81383 , -0.0343166,-0.998999,0.0287081 --12.0704 , -9.05597 , 9.16261 , 0.00241361,-0.994167,0.107826 --12.0956 , -8.99232 , 9.49512 , 0.016079,0.98203,-0.18804 --12.1012 , -8.91418 , 9.81965 , 0.0221845,0.978035,-0.207255 --12.137 , -8.85574 , 10.1701 , 0.0183663,0.975682,-0.218422 --12.1471 , -8.77704 , 10.5071 , 0.017607,0.976117,-0.216529 --12.1511 , -8.69327 , 10.8455 , 0.0192904,0.973651,-0.227225 --12.1777 , -8.62432 , 11.207 , 0.0204461,0.976035,-0.21665 --12.1773 , -8.53472 , 11.5534 , -0.0118439,-0.97519,0.221051 --12.2131 , -8.46764 , 11.9354 , -0.0373942,-0.95875,0.281779 --12.1955 , -8.36296 , 12.2788 , 0.041491,0.954274,-0.29604 --12.0662 , -8.1809 , 12.5258 , -0.0819766,-0.94437,0.318505 --12.1689 , -8.15459 , 12.9911 , -0.205569,-0.854153,0.477665 --12.0038 , -7.94839 , 13.2097 , -0.138708,-0.82538,0.547273 --11.7786 , -7.702 , 13.3647 , -0.265067,-0.279533,0.922822 --4.73849 , -3.07444 , 6.46137 , 0.699216,0.55484,-0.450833 --4.64192 , -2.97048 , 6.52577 , -0.140387,-0.187299,0.97222 --4.74428 , -2.99122 , 6.80509 , -0.877666,-0.458908,0.138222 --4.37449 , -2.71719 , 6.56168 , 0.152421,-0.75388,0.639087 --4.82769 , -2.9503 , 7.25743 , 0.756925,0.638641,0.138574 --4.37623 , -2.63142 , 6.90225 , 0.626144,-0.528083,0.573648 --4.34061 , -2.56472 , 7.03333 , 0.316743,-0.234098,0.919169 --4.12838 , -2.39463 , 6.94165 , -0.0184773,-0.211913,0.977114 --4.03299 , -2.29417 , 6.99278 , -0.344632,-0.128034,0.929966 --3.94223 , -2.19785 , 7.04882 , -0.485712,-0.0704853,0.871273 --3.94608 , -2.15333 , 7.23357 , -0.100595,-0.828787,0.550448 --3.97873 , -2.12324 , 7.46631 , -0.175003,0.213621,0.961114 --3.8671 , -2.01374 , 7.4943 , 0.0638981,-0.283909,0.95672 --2.59358 , -1.30492 , 5.75024 , 0.661746,0.163008,-0.731792 --2.49715 , -1.2191 , 5.74215 , 0.6265,0.108614,-0.771816 --2.45725 , -1.16208 , 5.82157 , -0.407988,-0.360764,0.838687 --2.40555 , -1.09901 , 5.88344 , 0.667989,0.35776,-0.652533 --2.35844 , -1.03853 , 5.95264 , -0.675585,-0.286756,0.679232 --2.33296 , -0.987279 , 6.06302 , 0.856714,0.335259,-0.391973 --2.25967 , -0.913222 , 6.08712 , 0.824239,0.369577,-0.429001 --2.7729 , -1.08834 , 7.2188 , -0.516344,0.785397,0.341381 --2.77938 , -1.0392 , 7.43284 , 0.954854,-0.0968448,-0.280845 --2.71984 , -0.961454 , 7.52415 , -0.827754,0.181804,0.53082 --2.64608 , -0.877307 , 7.58732 , -0.913636,-0.254946,0.316658 --4.0169 , -1.30546 , 10.761 , -0.664498,-0.43838,-0.605198 --1.91699 , -0.514045 , 6.42491 , -0.301027,0.35816,0.883801 --1.79582 , -0.426797 , 6.33673 , -0.312739,0.227748,0.922131 --1.7497 , -0.363333 , 6.41917 , -0.501022,0.084257,0.861323 --1.45671 , -0.232172 , 5.89167 , -0.0244655,0.971752,0.234731 --1.68935 , -0.24142 , 6.67376 , -0.449126,-0.123492,0.884893 --1.54195 , -0.152864 , 6.50162 , -0.00493033,-0.999395,0.0344219 --1.55556 , -0.0986021 , 6.75714 , -0.702975,-0.421236,0.573051 --1.80306 , -0.0777877 , 7.71204 , -0.303654,-0.95016,0.0706393 --1.99954 , -0.0291203 , 8.58858 , 0.551382,0.753382,0.35832 --1.98551 , 0.0583519 , 8.88019 , 0.383746,0.898154,-0.214614 --1.74432 , 0.165666 , 8.44437 , 0.0816014,-0.707431,0.702056 --1.60354 , 0.259454 , 8.30982 , -0.580678,0.0174241,-0.813947 --1.35471 , 0.345867 , 7.76714 , 0.757165,0.642806,-0.116194 --1.27408 , 0.430073 , 7.8084 , 0.0639961,-0.475282,0.877503 --1.28389 , 0.526544 , 8.21626 , -0.879853,0.281846,-0.382652 --1.2608 , 0.628327 , 8.5269 , -0.44636,0.24295,0.861242 --1.17483 , 0.722686 , 8.59309 , 0.645897,-0.0891926,-0.758196 --1.20798 , 0.858422 , 9.23334 , 0.672472,0.522849,-0.523842 --1.32726 , 1.05148 , 10.4018 , 0.975082,0.15482,0.158892 --0.467786 , 0.789234 , 6.3587 , 0.0397594,-0.764959,0.642851 --0.436695 , 0.877829 , 6.58996 , 0.672775,-0.564438,-0.478314 --0.391391 , 0.965114 , 6.77108 , -0.562797,0.0719537,-0.823457 --0.314578 , 1.03288 , 6.76396 , 0.328319,0.541144,-0.77419 --0.268858 , 1.13374 , 6.99077 , -0.90383,0.275436,-0.327455 --0.230495 , 1.25735 , 7.3337 , -0.114184,0.966898,-0.228189 --0.0670347 , 1.20264 , 6.54568 , -0.0907187,0.849858,0.519146 --0.904139 , -1.37491 , -0.792749 , 0.0815557,-0.183756,-0.979583 --0.958255 , -1.4202 , -0.786964 , 0.0724719,-0.181703,-0.980679 --1.01347 , -1.46488 , -0.779548 , -0.0400366,0.155391,0.987041 --1.06907 , -1.51007 , -0.769988 , -0.0625774,0.170408,0.983384 --1.13538 , -1.56727 , -0.770336 , -0.0330098,0.142284,0.989275 --1.19729 , -1.61862 , -0.762529 , -0.06776,0.135801,0.988416 --1.27119 , -1.68249 , -0.76358 , -0.0559717,0.145102,0.987832 --1.34044 , -1.73956 , -0.756673 , -0.06842,0.161069,0.984569 --1.41497 , -1.80319 , -0.752273 , -0.0919118,0.165522,0.981914 --1.49187 , -1.86674 , -0.745193 , -0.0708335,0.170244,0.982853 --1.58089 , -1.94246 , -0.745414 , -0.0887547,0.203146,0.975118 --1.6587 , -2.00656 , -0.732005 , -0.102702,0.18533,0.977295 --1.76768 , -2.10199 , -0.739644 , -0.11275,0.150941,0.982092 --1.86622 , -2.18455 , -0.733581 , -0.0808095,0.168653,0.982357 --1.96527 , -2.26725 , -0.723721 , -0.0872118,0.201199,0.97566 --2.0717 , -2.35557 , -0.714275 , -0.0852149,0.150006,0.985006 --2.19828 , -2.46469 , -0.71273 , -0.0441627,0.231224,0.971898 --2.29451 , -2.53944 , -0.686469 , -0.0340339,0.327971,0.944075 --2.40994 , -2.63512 , -0.6676 , -0.0357267,0.255753,0.966082 --2.54096 , -2.7423 , -0.651818 , -0.0679706,0.222895,0.97247 --2.68496 , -2.86235 , -0.637593 , -0.0740974,0.215556,0.973676 --2.84418 , -2.99559 , -0.624091 , 0.0739897,-0.211078,-0.974665 --3.00532 , -3.12904 , -0.603798 , -0.0688358,0.219154,0.973259 --3.18776 , -3.28089 , -0.586178 , -0.0763566,0.212047,0.974272 --3.37941 , -3.4389 , -0.563639 , -0.0543243,0.21403,0.975315 --3.57931 , -3.6032 , -0.535671 , -0.0627802,0.220552,0.973353 --3.80844 , -3.79318 , -0.509423 , -0.071165,0.226719,0.971357 --4.07538 , -4.01523 , -0.485328 , -0.0165832,0.533424,0.845685 --4.17979 , -4.08393 , -0.399164 , -0.0594199,0.647953,0.759359 --4.19823 , -4.07043 , -0.285173 , 0.0744466,0.859891,0.50502 --4.30792 , -4.14234 , -0.195489 , -0.0129442,0.714646,0.699367 --4.76661 , -4.53251 , -0.182556 , -0.392802,-0.450588,-0.801671 --5.92331 , -5.55201 , -0.293601 , 0.0792277,-0.261845,-0.961853 --6.40064 , -5.94393 , -0.225231 , -0.0762733,0.25906,0.962845 --6.94626 , -6.39147 , -0.146918 , -0.0648118,0.25326,0.965225 --7.5695 , -6.90204 , -0.0548096 , 0.0101792,0.263523,0.964599 --8.19547 , -7.40935 , 0.0649367 , 0.135409,0.250108,0.958703 --8.26933 , -7.42295 , 0.260783 , 0.133214,0.260585,0.956216 --8.86038 , -7.88776 , 0.424514 , 0.098175,0.262754,0.959855 --9.80684 , -8.65533 , 0.598795 , -0.00534934,0.374917,0.927043 --11.1434 , -9.74799 , 0.806847 , -0.232006,0.632163,0.739286 --11.7471 , -10.1991 , 1.0721 , -0.111568,0.968754,0.221516 --11.8175 , -10.1883 , 1.34925 , 0.0367905,-0.999304,-0.00614412 --11.9832 , -10.2596 , 1.63321 , 0.0459881,-0.998707,0.0216768 --12.0245 , -10.2227 , 1.91422 , 0.0669792,-0.990528,0.119865 --12.0379 , -10.1635 , 2.19373 , 0.0799162,-0.972572,0.21844 --12.0321 , -10.0886 , 2.47071 , -0.0809186,0.973916,-0.211992 --11.8697 , -9.88371 , 2.72517 , -0.0861514,0.994611,-0.0576878 --12.1489 , -10.043 , 3.04214 , 0.0748404,-0.995687,0.0548297 --12.2699 , -10.0706 , 3.34247 , 0.019615,-0.997529,0.0674693 --12.2875 , -10.0135 , 3.62707 , 0.0411784,-0.983284,0.177362 --12.3013 , -9.95318 , 3.91154 , -0.0521506,0.981875,-0.182213 --12.3113 , -9.88966 , 4.19577 , 0.0654184,-0.974877,0.212922 --12.3328 , -9.8341 , 4.48362 , -0.0580466,0.975763,-0.210989 --12.3351 , -9.76413 , 4.76758 , -0.0562985,0.97649,-0.208083 --12.348 , -9.7022 , 5.05586 , -0.0501938,0.976745,-0.208448 --12.3727 , -9.64888 , 5.34931 , -0.054109,0.976514,-0.208548 --12.3858 , -9.58625 , 5.64071 , -0.0553355,0.976669,-0.207496 --12.4018 , -9.5254 , 5.93527 , -0.051512,0.975484,-0.213958 --12.415 , -9.46098 , 6.23016 , -0.0552583,0.975841,-0.211379 --12.4224 , -9.39364 , 6.52574 , 0.0477419,-0.965066,0.25762 --12.4189 , -9.31604 , 6.81798 , 0.0314973,-0.96614,0.256088 --12.4714 , -9.27967 , 7.13837 , -0.0892788,0.959602,-0.26682 --12.2875 , -9.06876 , 7.34651 , 0.0840065,-0.974632,0.207448 --12.4058 , -9.07961 , 7.70515 , -0.114066,0.985177,-0.128123 --12.7049 , -9.21821 , 8.16921 , 0.0849497,-0.996326,0.0108739 --12.5825 , -9.05093 , 8.41263 , -0.0634048,0.997775,-0.0206278 --12.8611 , -9.16893 , 8.8891 , 0.0802763,-0.990694,0.109913 --12.891 , -9.10763 , 9.23001 , 0.047646,-0.992608,0.111618 --12.8933 , -9.02627 , 9.55879 , -0.0626751,0.97514,-0.212543 --12.9122 , -8.95552 , 9.90271 , 0.0595197,-0.975165,0.213334 --12.9259 , -8.87946 , 10.248 , -0.0565688,0.973609,-0.221101 --12.9348 , -8.79904 , 10.5948 , 0.0488814,-0.973875,0.221762 --12.9373 , -8.71264 , 10.9425 , 0.0571841,-0.974125,0.218657 --12.9553 , -8.63563 , 11.3075 , -0.0481134,0.97447,-0.219303 --12.9891 , -8.56771 , 11.6909 , 0.0547292,-0.96635,0.251343 --12.9605 , -8.45689 , 12.0315 , -0.0270147,0.948883,-0.31447 --12.8854 , -8.31435 , 12.3372 , 0.0408839,-0.946512,0.320069 --12.8809 , -8.21682 , 12.7065 , -0.0331121,-0.917106,0.397265 --12.9099 , -8.13791 , 13.1131 , 0.0602674,-0.845886,0.529948 --12.6386 , -7.87101 , 13.2498 , -0.0774188,0.816254,-0.572482 --12.3926 , -7.6208 , 13.4023 , -0.0777461,-0.674963,0.733745 --4.99518 , -3.03724 , 6.47589 , -0.686992,-0.530347,0.496764 --4.85746 , -2.91194 , 6.50482 , -0.686992,-0.530347,0.496764 --4.78352 , -2.82518 , 6.59599 , -0.669141,-0.564821,0.482937 --4.80913 , -2.7966 , 6.79444 , 0.688978,0.704333,-0.170949 --4.75639 , -2.72139 , 6.911 , 0.200242,0.825549,-0.52761 --4.81824 , -2.711 , 7.16081 , -0.42755,-0.903142,0.039192 --4.60782 , -2.54726 , 7.09716 , -0.101335,-0.0699951,0.992387 --4.35224 , -2.36103 , 6.96786 , 0.25199,-0.410485,0.876358 --4.27659 , -2.27506 , 7.05224 , -0.871764,0.300771,-0.386735 --4.30508 , -2.24381 , 7.27022 , 0.0825139,-0.98331,0.162154 --4.23224 , -2.1581 , 7.36011 , 0.736362,-0.210837,-0.642899 --4.15128 , -2.06902 , 7.44049 , 0.341347,0.0463234,-0.938795 --4.00891 , -1.94841 , 7.43208 , -0.368735,-0.20194,0.907334 --3.82869 , -1.81178 , 7.36376 , -0.221023,1.95114e-05,0.975269 --4.10103 , -1.89155 , 7.96609 , -0.897917,-0.401673,-0.180013 --3.91772 , -1.75218 , 7.89441 , 0.837814,0.439943,0.323293 --4.24663 , -1.84738 , 8.63344 , -0.918657,-0.0714115,-0.388547 --3.30476 , -1.37433 , 7.31726 , -0.317156,0.92565,0.206359 --3.18409 , -1.27256 , 7.30861 , -0.552968,0.672948,0.491292 --3.05871 , -1.17025 , 7.28796 , 0.402698,-0.795936,-0.452019 --2.8052 , -1.01829 , 7.03149 , 0.638588,-0.70648,-0.30511 --2.72641 , -0.938522 , 7.07957 , -0.864008,-0.410654,0.291297 --2.7511 , -0.896825 , 7.32714 , -0.890687,-0.42551,0.160056 --2.73985 , -0.838758 , 7.51417 , -0.946789,-0.239075,0.215485 --3.85711 , -1.15525 , 10.0446 , 0.367389,0.5775,0.729054 --3.90777 , -1.09101 , 10.4661 , 0.496304,0.213429,0.841505 --1.88043 , -0.407628 , 6.31284 , -0.312739,0.227748,0.922131 --2.00899 , -0.394052 , 6.79728 , -0.511914,-0.436209,0.740044 --1.63834 , -0.246913 , 6.13053 , -0.376695,0.915217,-0.143101 --1.66687 , -0.204037 , 6.3944 , -0.362584,-0.204319,0.909278 --1.70727 , -0.159835 , 6.70622 , -0.690908,-0.373561,0.618949 --1.98172 , -0.151646 , 7.66432 , -0.23027,-0.888414,0.39711 --1.94138 , -0.0762596 , 7.82268 , 0.473588,0.826762,-0.303611 --2.59077 , -0.0823172 , 9.992 , 0.729881,-0.286296,0.620732 --1.99741 , 0.0710323 , 8.59264 , 0.0527948,0.917464,0.394299 --1.83672 , 0.166954 , 8.4263 , -0.257424,0.799638,0.542505 --1.7347 , 0.256549 , 8.43803 , 0.445404,0.843919,0.299025 --1.48592 , 0.34337 , 7.93781 , -0.463547,-0.444318,-0.766619 --1.35605 , 0.423914 , 7.81757 , -0.369109,-0.33957,0.865131 --1.32775 , 0.512629 , 8.07141 , 0.716266,0.644518,-0.267506 --1.27363 , 0.603926 , 8.24694 , 0.7433,-0.555634,0.372525 --1.23898 , 0.704123 , 8.52827 , 0.645897,-0.0891927,-0.758196 --1.15123 , 0.796859 , 8.59383 , 0.641163,0.389121,-0.661434 --1.20872 , 0.946868 , 9.38024 , 0.651244,0.645307,-0.399326 --1.28879 , 1.13551 , 10.3918 , 0.975082,0.15482,0.158892 --0.446133 , 0.836259 , 6.36809 , -0.602743,-0.673782,0.427456 --0.449008 , 0.949546 , 6.82478 , -0.967857,0.121254,0.220342 --0.359765 , 1.00763 , 6.75037 , 0.522427,-0.678268,0.516742 --0.288132 , 1.07943 , 6.79201 , -0.156719,0.586909,-0.79434 --0.241368 , 1.18196 , 7.03826 , 0.521787,-0.834711,0.176056 --0.125529 , 1.20136 , 6.72294 , 0.0409719,0.988418,0.146124 --0.0261023 , 1.22812 , 6.49446 , 0.7603,0.647104,-0.0565773 --0.962037 , -1.34259 , -0.792233 , -0.0603247,0.158823,0.985462 --1.02343 , -1.39154 , -0.792536 , -0.0558127,0.180882,0.98192 --1.07945 , -1.43483 , -0.784465 , -0.0260501,0.163598,0.986183 --1.14161 , -1.48479 , -0.780384 , 0.042546,-0.163598,-0.985609 --1.2049 , -1.53404 , -0.774283 , 0.0647378,-0.171573,-0.983042 --1.27414 , -1.58887 , -0.771786 , -0.0634493,0.118414,0.990935 --1.34961 , -1.65013 , -0.772208 , -0.0798362,0.146613,0.985967 --1.42647 , -1.71152 , -0.769927 , -0.0673042,0.139987,0.987863 --1.51056 , -1.77899 , -0.770103 , -0.0732366,0.154879,0.985215 --1.58929 , -1.84078 , -0.761808 , -0.0872748,0.165212,0.982389 --1.67527 , -1.9086 , -0.755775 , -0.0893017,0.167708,0.981784 --1.76733 , -1.98158 , -0.751497 , -0.128776,0.177136,0.975725 --1.87988 , -2.07376 , -0.757873 , -0.119845,0.169873,0.978152 --1.97416 , -2.14773 , -0.745827 , -0.0908348,0.205393,0.974455 --2.08288 , -2.23393 , -0.739084 , 0.0791728,-0.190165,-0.978555 --2.199 , -2.3257 , -0.732559 , -0.0679401,0.186185,0.980163 --2.33605 , -2.43699 , -0.73367 , -0.0602704,0.252918,0.965609 --2.43512 , -2.50961 , -0.705634 , -0.033239,0.320968,0.946507 --2.55489 , -2.6008 , -0.685431 , -0.0486091,0.264329,0.963207 --2.69545 , -2.71019 , -0.671504 , -0.0696236,0.220881,0.972813 --2.8369 , -2.82025 , -0.651637 , -0.0564358,0.209284,0.976225 --3.00766 , -2.95512 , -0.639551 , -0.0748174,0.210882,0.974644 --3.18013 , -3.0892 , -0.620578 , -0.0747199,0.21521,0.973705 --3.38258 , -3.24938 , -0.606266 , -0.0571778,0.215548,0.974818 --3.5794 , -3.40137 , -0.581155 , -0.0578559,0.212698,0.975404 --3.80637 , -3.57897 , -0.558469 , -0.0654593,0.212568,0.974951 --4.05617 , -3.77467 , -0.533807 , -0.057085,0.257084,0.964702 --4.33736 , -3.99497 , -0.508188 , -0.159184,0.656166,0.737635 --4.53268 , -4.13726 , -0.444657 , -0.00427122,0.901083,0.433625 --4.55149 , -4.12262 , -0.325607 , -0.0844643,0.839927,0.536087 --4.643 , -4.17157 , -0.225056 , 0.0672494,0.85945,0.506777 --4.82334 , -4.29556 , -0.141518 , 0.733127,0.228588,0.640525 --6.36341 , -5.58282 , -0.319533 , -0.076425,0.259431,0.962733 --6.86863 , -5.97206 , -0.246239 , -0.0673314,0.261051,0.962974 --7.45907 , -6.42867 , -0.163872 , -0.0251297,0.252103,0.967374 --8.14465 , -6.95774 , -0.0682214 , 0.0867234,0.279536,0.95621 --8.36557 , -7.09282 , 0.105871 , 0.0407056,0.377378,0.925164 --8.72438 , -7.33936 , 0.277078 , 0.122061,0.301581,0.945595 --9.44485 , -7.88026 , 0.441158 , -0.0413978,0.363485,0.93068 --10.6326 , -8.79447 , 0.61824 , -0.0444462,0.354508,0.933996 --12.4449 , -10.2021 , 0.836706 , -0.183113,0.978727,0.0925415 --12.5747 , -10.2356 , 1.12303 , -0.0657914,0.997829,-0.0030671 --12.7388 , -10.2953 , 1.41436 , -0.0384761,0.999245,-0.00548175 --12.8139 , -10.2832 , 1.7072 , -0.0155636,0.99826,-0.0568671 --12.8546 , -10.242 , 1.99942 , -0.0411237,0.996873,-0.0674735 --12.8821 , -10.1924 , 2.29167 , 0.0961822,-0.988638,0.11552 --12.8824 , -10.1198 , 2.58073 , 0.199479,-0.979248,0.0357851 --13.1385 , -10.2456 , 2.9044 , 0.248814,-0.968351,0.0197014 --13.4935 , -10.4445 , 3.25425 , -0.157344,0.986551,-0.044272 --13.5053 , -10.3787 , 3.55746 , -0.182597,0.983077,0.0147507 --13.4262 , -10.2435 , 3.84283 , -0.174083,0.957483,-0.230046 --14.3822 , -10.887 , 4.35545 , 0.138429,-0.983992,0.112235 --14.3949 , -10.657 , 5.32273 , -0.980712,-0.194992,0.0135159 --14.1141 , -10.3709 , 5.5585 , -0.981359,0.0536093,0.184554 --14.4149 , -10.5102 , 5.97626 , -0.914618,-0.35368,0.195921 --14.4766 , -10.4723 , 6.32349 , 0.818591,0.504094,-0.275315 --13.856 , -9.94733 , 6.41941 , -0.137561,-0.713854,0.68665 --13.5911 , -9.68116 , 6.63097 , 0.0293031,-0.90025,0.434387 --13.5168 , -9.55086 , 6.91236 , 0.0362539,-0.929881,0.36607 --13.5614 , -9.5044 , 7.24525 , 0.0427524,-0.953243,0.299164 --13.3092 , -9.25127 , 7.44462 , 0.141602,-0.970121,0.197012 --13.6434 , -9.4019 , 7.9202 , -0.0854395,0.983116,-0.161814 --13.6587 , -9.33161 , 8.25102 , -0.086836,0.988624,-0.122811 --13.5164 , -9.15407 , 8.50183 , 0.109947,-0.989511,0.0937038 --14.7521 , -9.89879 , 9.51488 , -0.995743,0.0468523,-0.0793727 --14.7524 , -9.80944 , 9.87449 , 0.997307,-0.0512168,0.0524897 --14.7781 , -9.73616 , 10.2529 , 0.997335,-0.0513725,0.0518139 --14.7975 , -9.65675 , 10.6328 , -0.981845,0.1851,0.0414477 --14.804 , -9.56755 , 11.0096 , 0.989824,-0.135468,-0.0435633 --14.0715 , -9.00622 , 10.8926 , -0.960208,0.218136,0.174405 --14.5583 , -9.2226 , 11.5984 , 0.120833,-0.864295,0.488256 --14.1721 , -8.88516 , 11.7006 , -0.017418,-0.93367,0.35771 --13.8076 , -8.56507 , 11.8048 , -0.084617,0.917863,-0.387773 --13.8199 , -8.47922 , 12.1889 , -0.0783189,0.912115,-0.402384 --13.62 , -8.26323 , 12.4102 , -0.0479765,0.950648,-0.306541 --13.7747 , -8.25973 , 12.9212 , 0.0475125,-0.878786,0.474846 --13.6142 , -8.06656 , 13.178 , 0.053884,-0.852215,0.520409 --13.3203 , -7.79581 , 13.3145 , 0.0422656,-0.833407,0.551041 --14.1045 , -8.15003 , 14.4294 , -0.0513789,0.998557,-0.0156197 --13.8977 , -7.92497 , 14.6621 , -0.0513789,0.998557,-0.0156197 --4.96466 , -2.74224 , 6.54126 , -0.441213,-0.715514,0.541637 --4.91317 , -2.67162 , 6.65958 , -0.680434,-0.579694,0.44829 --4.99427 , -2.67203 , 6.92047 , -0.473596,-0.87434,0.106002 --5.05815 , -2.66092 , 7.17131 , 0.859877,0.5041,0.080588 --5.09776 , -2.63439 , 7.40392 , 0.792352,0.605969,-0.0705653 --4.99732 , -2.53415 , 7.48034 , -0.487141,0.094291,-0.868218 --4.47013 , -2.21894 , 7.04087 , -0.830528,0.495833,-0.253719 --4.17688 , -2.02793 , 6.858 , 0.522086,-0.234122,-0.82013 --4.14725 , -1.96958 , 6.99741 , -0.468286,0.232813,0.852353 --4.0342 , -1.87015 , 7.02922 , -0.911496,-0.338482,0.233677 --4.12108 , -1.86517 , 7.32947 , -0.729688,-0.653428,0.201464 --4.02685 , -1.77407 , 7.38982 , 0.0864911,0.134896,0.987078 --4.01972 , -1.72168 , 7.57495 , -0.947801,-0.254668,0.19188 --4.33969 , -1.81069 , 8.25322 , -0.967538,-0.200271,-0.154147 --3.39944 , -1.35627 , 7.03271 , -0.721248,0.537408,0.43703 --3.2409 , -1.24474 , 6.96948 , 0.596342,-0.68731,-0.414705 --3.2477 , -1.20069 , 7.16871 , -0.610328,0.705739,0.359767 --3.15554 , -1.11648 , 7.20857 , 0.484264,-0.788013,-0.380165 --2.92593 , -0.980808 , 7.00714 , 0.230735,-0.849835,-0.473858 --2.81638 , -0.892726 , 7.00538 , 0.83952,-0.0499473,-0.541028 --3.01647 , -0.912212 , 7.57429 , 0.00523068,-0.439157,0.898395 --2.75405 , -0.77215 , 7.29136 , 0.939741,-0.0202492,-0.341286 --2.85691 , -0.750655 , 7.70788 , -0.503423,-0.0677548,0.861379 --2.63583 , -0.627549 , 7.48635 , 0.963113,-0.226469,0.145345 --2.68826 , -0.58534 , 7.82486 , -0.969317,0.0459643,-0.241479 --1.91374 , -0.32476 , 6.36349 , -0.186603,-0.0734645,0.979685 --1.82856 , -0.256202 , 6.36515 , 0.23113,0.414653,-0.880138 --1.78652 , -0.196423 , 6.46548 , -0.489299,-0.666002,0.563052 --1.77112 , -0.141104 , 6.63916 , -0.812167,-0.414706,0.410371 --1.74173 , -0.0803539 , 6.78479 , -0.642576,-0.562271,0.520527 --2.1847 , -0.0854319 , 8.20215 , -0.611244,0.790979,-0.0270564 --2.81725 , -0.0815148 , 10.2623 , -0.658733,0.446921,-0.605254 --2.11829 , 0.0764959 , 8.63668 , 0.631055,0.75689,0.169962 --1.88944 , 0.174525 , 8.28324 , 0.359784,-0.828995,-0.428162 --1.80715 , 0.260036 , 8.36318 , 0.250338,-0.9233,-0.291288 --1.57978 , 0.343335 , 7.96228 , 0.708074,0.407157,0.576935 --1.44115 , 0.421361 , 7.82516 , 0.562961,-0.0442898,0.825296 --1.36281 , 0.502967 , 7.89675 , -0.464506,-0.830914,0.306296 --1.36761 , 0.598458 , 8.29575 , -0.570254,0.692321,0.442156 --1.26257 , 0.680996 , 8.2872 , -0.83496,0.547737,0.0531627 --1.24242 , 0.787164 , 8.64586 , -0.0956472,-0.627307,0.772876 --1.1469 , 0.877038 , 8.70186 , -0.0956472,-0.627307,0.772876 --1.25463 , 1.05721 , 9.77128 , -0.888289,-0.432296,0.155125 --0.83015 , 0.99546 , 8.15146 , -0.232974,-0.0330162,0.971922 --0.4611 , 0.904521 , 6.59321 , -0.620218,0.530877,0.577494 --0.412384 , 0.98902 , 6.77511 , -0.796578,-0.0992378,-0.596336 --0.326636 , 1.0477 , 6.72981 , -0.225634,-0.520298,0.823638 --0.277969 , 1.14385 , 6.95769 , 0.572803,-0.815606,0.0817532 --0.234004 , 1.25909 , 7.28216 , -0.340654,0.639109,-0.689562 --0.0745589 , 1.21245 , 6.57385 , -0.87006,0.450884,0.199244 --1.08793 , -1.35991 , -0.798214 , -0.0638336,0.184848,0.980692 --1.15703 , -1.41291 , -0.801877 , -0.0690914,0.210843,0.975075 --1.20943 , -1.44901 , -0.785191 , -0.0747124,0.180589,0.980717 --1.28607 , -1.5088 , -0.790141 , -0.0851504,0.174532,0.980963 --1.35132 , -1.55591 , -0.781074 , -0.0785602,0.14219,0.986717 --1.42954 , -1.61528 , -0.780792 , -0.0828072,0.131835,0.987807 --1.51476 , -1.67979 , -0.78326 , -0.0754001,0.155105,0.985016 --1.58878 , -1.7327 , -0.772098 , -0.0862202,0.15933,0.983453 --1.68777 , -1.81039 , -0.778578 , -0.0845253,0.176183,0.980722 --2.21505 , -2.20626 , -0.763609 , -0.0876138,0.19435,0.977012 --2.32176 , -2.28251 , -0.747038 , -0.107275,0.174523,0.978792 --2.47616 , -2.40141 , -0.754918 , -0.0620046,0.260818,0.963395 --2.56382 , -2.45913 , -0.717373 , -0.0351504,0.287725,0.957068 --2.70738 , -2.56536 , -0.706953 , -0.0719355,0.254932,0.964279 --2.85157 , -2.67131 , -0.690888 , -0.0590608,0.245719,0.96754 --3.00454 , -2.78305 , -0.672631 , 0.0814147,-0.221699,-0.971711 --3.18761 , -2.91828 , -0.661791 , -0.0814143,0.227253,0.970427 --3.37168 , -3.0538 , -0.643357 , -0.067444,0.227615,0.971413 --3.56469 , -3.19463 , -0.620688 , -0.0612488,0.227686,0.971807 --3.7883 , -3.35908 , -0.601542 , -0.0707996,0.223222,0.972193 --4.02844 , -3.53545 , -0.578572 , 0.0818834,-0.220538,-0.971935 --4.3081 , -3.74248 , -0.558097 , -0.0959474,0.260861,0.960596 --4.61177 , -3.96681 , -0.533141 , -0.0592761,0.611574,0.788964 --4.75893 , -4.05832 , -0.450971 , 0.181578,0.881379,0.436119 --4.74035 , -4.01264 , -0.320006 , -0.306742,-0.868484,-0.389417 --4.91717 , -4.12625 , -0.237934 , 0.549895,0.66955,0.499318 --4.97157 , -4.13935 , -0.122877 , -0.802275,-0.530861,-0.273022 --4.98668 , -4.11943 , 0.000705264 , -0.89575,-0.44246,-0.0431456 --4.98375 , -4.08669 , 0.126639 , -0.958275,-0.285458,0.0148927 --4.99422 , -4.06495 , 0.249334 , -0.965327,-0.260267,0.0201109 --5.00322 , -4.0416 , 0.371463 , -0.96393,-0.265705,0.015471 --5.00979 , -4.01686 , 0.49305 , -0.969989,-0.242558,0.0169635 --5.00776 , -3.98577 , 0.614974 , -0.968351,-0.249411,0.00955605 --5.019 , -3.96441 , 0.734922 , -0.96972,-0.244038,0.00938922 --5.02042 , -3.93604 , 0.854838 , -0.966103,-0.258078,0.00633562 --5.02826 , -3.91352 , 0.974364 , -0.968586,-0.24814,0.0163819 --5.03439 , -3.88842 , 1.09313 , -0.967954,-0.250821,0.012413 --5.03931 , -3.8626 , 1.21172 , -0.971368,-0.237051,0.0158319 --5.04204 , -3.83634 , 1.33006 , 0.972861,0.230338,-0.0220653 --5.04307 , -3.8075 , 1.44764 , -0.974793,-0.221815,0.0240205 --5.05828 , -3.7906 , 1.56665 , -0.975304,-0.220464,0.0133127 --5.04795 , -3.75334 , 1.68266 , -0.971556,-0.235329,-0.026457 --5.05956 , -3.73422 , 1.80154 , -0.922766,-0.383515,-0.0376774 --5.08595 , -3.72458 , 1.9229 , -0.886707,-0.460104,-0.0453369 --14.3785 , -10.3332 , 3.70631 , -0.0907022,0.979127,-0.181891 --14.4405 , -10.2997 , 4.03179 , -0.0907021,0.979127,-0.181891 --14.4563 , -10.2339 , 4.35034 , 0.138429,-0.983992,0.112235 --14.4759 , -10.17 , 4.67067 , -0.970149,-0.237514,0.0489794 --14.4916 , -10.1028 , 4.99125 , -0.95781,-0.278604,0.0705653 --14.5026 , -10.0325 , 5.31202 , -0.948164,-0.31674,0.0256877 --14.5163 , -9.96412 , 5.63537 , -0.965215,-0.260768,-0.0189572 --14.5261 , -9.89148 , 5.95878 , -0.894518,-0.425153,0.13814 --14.5465 , -9.82652 , 6.28816 , -0.943172,-0.302571,0.137391 --14.5145 , -9.72556 , 6.60037 , 0.0170505,-0.909972,0.41432 --14.4774 , -9.62091 , 6.9112 , -0.0145627,-0.928902,0.37004 --14.4995 , -9.5553 , 7.24678 , -0.0497633,0.957057,-0.285596 --14.2169 , -9.29141 , 7.45329 , -0.0987867,0.981958,-0.161246 --14.5823 , -9.44753 , 7.94618 , 0.0467781,-0.990125,0.132152 --14.5964 , -9.37394 , 8.2893 , -0.0289584,0.99496,-0.0960033 --14.6132 , -9.30077 , 8.63724 , -0.128427,0.991333,-0.0276499 --14.6865 , -9.26332 , 9.01906 , 0.491021,-0.870959,-0.0181263 --14.6991 , -9.18543 , 9.37458 , 0.995238,-0.0563549,0.0795365 --14.7224 , -9.11331 , 9.74006 , 0.996035,-0.0538251,0.0708401 --14.731 , -9.03175 , 10.1029 , -0.981663,0.144271,0.124596 --14.7499 , -8.95388 , 10.476 , -0.981845,0.1851,0.0414477 --14.7627 , -8.8709 , 10.8507 , -0.960208,0.218137,0.174405 --14.7608 , -8.77959 , 11.2223 , -0.990881,0.00291878,0.134712 --14.7314 , -8.66976 , 11.5792 , -0.0343649,-0.941983,0.333896 --14.7404 , -8.58065 , 11.9678 , 0.0108467,-0.889278,0.457239 --14.6695 , -8.44445 , 12.3039 , 0.0472794,-0.881593,0.469637 --14.644 , -8.3334 , 12.6774 , -0.00298941,-0.910109,0.414359 --14.6618 , -8.24628 , 13.0914 , 0.0583922,-0.838335,0.542019 --14.3106 , -7.9504 , 13.2098 , 0.0474595,-0.864637,0.500151 --14.1 , -7.73506 , 13.4357 , -0.0416056,0.983084,-0.178369 --14.9572 , -8.10079 , 14.5952 , 0.183161,-0.982824,-0.0225567 --5.13414 , -2.60231 , 6.6435 , -0.482489,-0.821412,0.304115 --5.16286 , -2.48501 , 7.21536 , -0.426282,-0.855785,0.293114 --5.11196 , -2.41319 , 7.34889 , 0.0369168,-0.820675,0.570202 --4.99682 , -2.31149 , 7.40933 , 0.0369168,-0.820675,0.570202 --4.29716 , -1.93686 , 6.76824 , -0.428259,0.472094,0.770533 --4.18258 , -1.84226 , 6.80392 , -0.762985,-0.64468,0.0473452 --4.09223 , -1.75819 , 6.86629 , -0.658275,-0.015818,0.752611 --4.47172 , -1.88058 , 7.54047 , -0.159821,0.131246,0.978382 --4.17583 , -1.70501 , 7.34206 , -0.28831,0.177321,0.940975 --4.16361 , -1.65217 , 7.52027 , -0.204896,0.590419,0.780656 --3.88066 , -1.48732 , 7.3155 , 0.69353,-0.509719,-0.509119 --3.81615 , -1.41393 , 7.41711 , 0.972133,-0.220004,-0.0809689 --3.40684 , -1.20699 , 6.99372 , -0.385732,0.650107,0.654654 --3.2935 , -1.11843 , 7.00385 , 0.485793,-0.672196,-0.558711 --3.09687 , -1.00116 , 6.87699 , 0.419132,-0.749478,-0.512456 --2.98092 , -0.91447 , 6.87109 , 0.3416,-0.837341,-0.426812 --2.169 , -0.596928 , 5.65816 , -0.906412,-0.412142,0.0924977 --3.14672 , -0.872028 , 7.55664 , 0.503451,0.394046,-0.768937 --2.95254 , -0.758826 , 7.41737 , -0.370993,-0.861717,-0.346134 --2.26147 , -0.504954 , 6.31548 , -0.657425,0.694926,0.291324 --2.67608 , -0.573865 , 7.31704 , -0.66645,0.276503,0.692381 --2.59681 , -0.499027 , 7.37738 , -0.918858,0.000422767,0.394588 --2.63098 , -0.451156 , 7.67887 , -0.931533,0.353683,-0.0845828 --1.91132 , -0.233245 , 6.34146 , -0.340839,-0.569065,0.748327 --1.90452 , -0.183178 , 6.52514 , -0.297372,-0.746235,0.59557 --1.81178 , -0.114522 , 6.51603 , -0.349023,-0.845997,0.403079 --1.80534 , -0.0606485 , 6.71763 , 0.842748,0.484409,-0.234784 --1.85223 , -0.00995488 , 7.0682 , 0.340106,0.176942,-0.923591 --2.10727 , 0.0249701 , 8.00105 , 0.338481,-0.770592,0.540018 --2.80035 , 0.0464143 , 10.2305 , 0.710053,-0.405535,0.575645 --2.01895 , 0.181915 , 8.36679 , -0.371748,0.841656,0.391686 --1.83063 , 0.26796 , 8.13515 , -0.398994,0.647883,0.648884 --1.82388 , 0.350993 , 8.4524 , -0.250337,0.9233,0.291288 --1.56484 , 0.42548 , 7.95563 , -0.679981,-0.0857915,-0.728194 --1.43698 , 0.500266 , 7.86604 , 0.577801,-0.0606634,0.81392 --1.45945 , 0.595451 , 8.32351 , -0.570254,0.692321,0.442156 --1.34681 , 0.674623 , 8.29768 , -0.83496,0.547736,0.0531623 --1.24139 , 0.754792 , 8.29842 , -0.932615,0.30033,0.20008 --1.2348 , 0.86676 , 8.73474 , -0.0956472,-0.627307,0.772876 --1.2777 , 1.01268 , 9.46313 , -0.570641,-0.666478,0.479768 --1.24452 , 1.14727 , 9.90854 , -0.905595,-0.423766,0.0179084 --0.52234 , 0.894654 , 6.64474 , -0.299055,0.790099,0.535079 --0.438646 , 0.952286 , 6.62234 , -0.479306,0.463516,0.745264 --0.368491 , 1.02068 , 6.68633 , 0.110815,0.350406,0.930019 --0.301599 , 1.09458 , 6.77803 , 0.090879,0.303302,-0.948551 --0.229313 , 1.16696 , 6.84858 , -0.5493,0.829548,-0.100592 --0.134779 , 1.21156 , 6.74081 , 0.691532,0.596304,0.407683 --0.030482 , 1.23217 , 6.50371 , 0.7603,0.647104,-0.0565773 --1.22866 , -1.38375 , -0.81277 , -0.0780745,0.206372,0.975354 --1.28839 , -1.42336 , -0.801491 , -0.0779187,0.205085,0.975638 --2.21286 , -2.0775 , -0.783685 , -0.0580055,0.209625,0.97606 --2.33364 , -2.16313 , -0.778483 , 0.102538,-0.189938,-0.976427 --2.46972 , -2.25948 , -0.777345 , -0.0722116,0.210727,0.974874 --2.60169 , -2.35071 , -0.766881 , -0.0488519,0.262705,0.963639 --2.71902 , -2.42927 , -0.743695 , -0.053838,0.305707,0.950602 --2.86597 , -2.53109 , -0.731237 , -0.0510413,0.268715,0.961867 --3.00047 , -2.62071 , -0.705907 , -0.0873812,0.249132,0.964519 --3.19317 , -2.7573 , -0.702982 , 0.09494,-0.230837,-0.96835 --3.38069 , -2.88766 , -0.689155 , 0.078852,-0.240298,-0.967491 --3.56274 , -3.01095 , -0.665109 , -0.0612237,0.236234,0.969765 --3.78351 , -3.16403 , -0.648526 , -0.0711047,0.233102,0.969849 --4.01957 , -3.3284 , -0.628681 , -0.0885205,0.224826,0.97037 --4.28933 , -3.51516 , -0.610095 , 0.0889048,-0.230736,-0.968946 --4.58304 , -3.7194 , -0.587903 , -0.0725876,0.268467,0.96055 --4.91724 , -3.95239 , -0.565218 , 0.106105,0.765267,0.634907 --5.03069 , -4.00927 , -0.468315 , -0.399828,-0.909394,-0.114632 --5.03412 , -3.98085 , -0.340439 , -0.718982,-0.685175,-0.116618 --5.03533 , -3.95208 , -0.213297 , -0.818431,-0.573438,0.0365876 --5.04307 , -3.92649 , -0.0890099 , -0.853502,-0.517234,0.0632663 --5.04762 , -3.90074 , 0.0347616 , -0.86968,-0.48877,0.0690003 --5.05167 , -3.87318 , 0.157749 , -0.848403,-0.525122,0.06677 --5.0535 , -3.84526 , 0.2801 , -0.862735,-0.501366,0.0657365 --5.05286 , -3.81601 , 0.401617 , -0.861672,-0.500377,0.0845293 --5.06667 , -3.79732 , 0.520845 , -0.868445,-0.494829,0.0307899 --5.06211 , -3.76513 , 0.640962 , -0.860874,-0.506883,0.0443324 --5.08062 , -3.74974 , 0.758939 , -0.859795,-0.507948,0.0523631 --5.07334 , -3.71535 , 0.877733 , -0.863891,-0.501102,0.0508778 --5.08823 , -3.69777 , 0.995384 , -0.865453,-0.498116,0.0535988 --5.08467 , -3.66696 , 1.11276 , -0.865998,-0.497654,0.0488686 --5.09691 , -3.64695 , 1.23006 , -0.862647,-0.500327,0.0742573 --5.08967 , -3.61411 , 1.34642 , -0.859491,-0.506003,0.0723581 --5.09828 , -3.59196 , 1.4632 , -0.869956,-0.489598,0.0589053 --5.0958 , -3.56223 , 1.57909 , -0.866645,-0.498887,0.0061602 --5.10827 , -3.54322 , 1.69639 , -0.845461,-0.533695,-0.0191174 --5.13673 , -3.53446 , 1.81615 , -0.862222,-0.495779,-0.103809 --15.5114 , -10.5027 , 3.57704 , -0.0441533,0.942415,0.331519 --15.8718 , -10.6635 , 3.97198 , 0.0115496,0.998036,0.0615632 --16.1194 , -10.7477 , 4.35994 , -0.317094,-0.944627,-0.0844493 --16.1325 , -10.6726 , 4.70619 , -0.472069,-0.871232,0.134558 --16.1571 , -10.6054 , 5.05655 , 0.560757,0.80372,-0.198962 --16.1921 , -10.5452 , 5.41161 , 0.59222,0.790409,-0.156614 --16.0339 , -10.3597 , 5.71455 , 0.489077,0.833773,-0.256174 --16.2475 , -10.413 , 6.1248 , 0.297517,0.869447,-0.394393 --15.9415 , -10.1339 , 6.3768 , 0.082867,0.870044,-0.48596 --15.5739 , -9.81899 , 6.59651 , 0.118256,-0.876669,0.466333 --15.5123 , -9.69792 , 6.91439 , -0.0973793,0.934083,-0.34352 --15.4941 , -9.60471 , 7.24881 , 0.100569,-0.951354,0.291224 --15.2689 , -9.38353 , 7.50005 , 0.0656676,-0.978043,0.197786 --15.6257 , -9.51826 , 7.99492 , 0.0473524,-0.984251,0.170317 --15.6069 , -9.42234 , 8.33801 , 0.0538001,-0.988578,0.14078 --16.4655 , -9.8502 , 9.09996 , 0.802851,0.59302,-0.0612981 --16.3683 , -9.70216 , 9.42829 , 0.786568,0.617288,-0.0162827 --16.4954 , -9.68581 , 9.87223 , 0.650753,0.722901,-0.232237 --16.4421 , -9.56209 , 10.2284 , 0.627751,0.748215,-0.214717 --16.5239 , -9.5149 , 10.6622 , 0.545002,0.766348,-0.340122 --16.0716 , -9.16209 , 10.791 , -0.378411,-0.821053,0.427407 --16.3879 , -9.24671 , 11.3732 , 0.168887,0.91158,-0.374832 --16.1361 , -9.00892 , 11.6146 , 0.0883415,0.929996,-0.356796 --15.7293 , -8.68703 , 11.7476 , -0.149001,0.889054,-0.432875 --15.7652 , -8.6116 , 12.1698 , 0.060503,-0.921782,0.382958 --15.5629 , -8.4048 , 12.4307 , 0.0412437,-0.904112,0.4253 --15.7272 , -8.39377 , 12.9565 , 0.0490901,-0.875631,0.48048 --15.448 , -8.14613 , 13.1616 , 0.0468254,-0.872935,0.485584 --15.1088 , -7.86803 , 13.3117 , 0.0624517,-0.856409,0.512507 --16.0719 , -8.26561 , 14.5104 , 0.141429,-0.988667,0.0503589 --5.34641 , -2.3005 , 7.55123 , 0.792352,0.605969,-0.0705655 --4.34453 , -1.77443 , 6.7753 , 0.999546,0.0226523,0.0198722 --4.25308 , -1.69327 , 6.84016 , 0.999546,0.0226523,0.0198722 --4.40724 , -1.71316 , 7.21369 , 0.0757892,0.432976,0.898214 --4.31511 , -1.62964 , 7.28567 , -0.378443,-0.562594,0.73503 --3.97162 , -1.44931 , 7.02014 , -0.798383,0.0427546,0.60063 --3.9329 , -1.39009 , 7.15438 , 0.764493,-0.407012,-0.499891 --3.4871 , -1.17829 , 6.71185 , 0.236367,-0.611636,-0.755005 --3.42326 , -1.11225 , 6.79749 , 0.236367,-0.611636,-0.755005 --3.29342 , -1.02333 , 6.78348 , -0.320724,0.778935,0.538884 --3.07861 , -0.90701 , 6.63321 , 0.312781,-0.878583,-0.360915 --3.03065 , -0.847152 , 6.73592 , 0.3416,-0.837341,-0.426812 --2.27866 , -0.568395 , 5.66975 , -0.929212,-0.333984,0.158177 --2.20095 , -0.508669 , 5.69083 , -0.926189,-0.186235,0.327859 --2.98361 , -0.692685 , 7.23802 , -0.942803,-0.209766,0.259076 --2.40236 , -0.484937 , 6.38043 , -0.730247,0.511069,0.453375 --2.39929 , -0.44008 , 6.55987 , -0.779611,0.177147,0.600688 --2.78796 , -0.485141 , 7.51995 , -0.806877,0.583338,-0.0930907 --2.18241 , -0.29549 , 6.51798 , -0.674852,0.699938,-0.233797 --2.03139 , -0.216917 , 6.39832 , 0.250859,-0.166877,0.953531 --1.92104 , -0.147908 , 6.35621 , -0.222026,-0.657091,0.720372 --2.05977 , -0.121963 , 6.87801 , -0.664121,-0.0931444,0.7418 --1.82463 , -0.0330397 , 6.54899 , -0.629159,-0.545524,0.553681 --1.79728 , 0.0238905 , 6.70417 , 0.862896,0.425547,0.272619 --2.16855 , 0.0460915 , 7.89283 , -0.302981,-0.441686,0.844462 --2.10863 , 0.120689 , 8.02518 , -0.833374,0.552021,0.0275837 --1.5559 , 0.216489 , 6.79131 , 0.883255,0.202952,-0.422696 --1.90925 , 0.277595 , 8.08765 , -0.681839,0.675281,0.281233 --1.82659 , 0.355752 , 8.16805 , -0.643589,0.664879,0.379117 --1.35241 , 0.411306 , 6.99591 , -0.0418555,-0.00854631,0.999087 --1.58385 , 0.509258 , 8.08352 , -0.393498,0.633903,-0.665827 --1.40051 , 0.573412 , 7.81133 , 0.234541,-0.396715,0.887473 --1.38687 , 0.662971 , 8.14293 , -0.89333,0.112377,0.435124 --1.28575 , 0.740114 , 8.1645 , -0.729023,0.337888,0.595279 --1.31359 , 0.856435 , 8.7276 , -0.0956473,-0.627307,0.772876 --1.33379 , 0.987419 , 9.33 , 0.539704,0.691054,-0.480795 --1.23957 , 1.08756 , 9.46437 , 0.549892,0.687638,-0.474101 --0.861972 , 1.03696 , 8.14126 , 0.415325,0.551696,-0.723282 --0.48096 , 0.931211 , 6.57656 , -0.620218,0.530877,0.577494 --0.425231 , 1.00806 , 6.72997 , -0.720933,-0.325252,-0.611937 --0.352125 , 1.07568 , 6.79375 , 0.0599049,-0.678031,0.732588 --0.306764 , 1.17669 , 7.08165 , -0.949018,0.290192,0.123102 --0.194988 , 1.20746 , 6.87714 , 0.038138,0.999172,0.0141472 --0.0787112 , 1.21643 , 6.57285 , -0.884012,-0.466872,0.0235445 --2.12491 , -1.90145 , -0.827993 , -0.051435,0.165748,0.984826 --2.21276 , -1.95509 , -0.806492 , -0.0381516,0.169818,0.984737 --2.32947 , -2.03098 , -0.800103 , -0.0908024,0.183205,0.978872 --2.46757 , -2.12436 , -0.802254 , -0.100738,0.188077,0.976974 --2.60013 , -2.2109 , -0.795256 , -0.0525458,0.20728,0.976869 --2.74852 , -2.30989 , -0.79115 , -0.0768532,0.244267,0.966658 --2.87019 , -2.38391 , -0.766436 , -0.0858903,0.269125,0.959268 --3.02769 , -2.48764 , -0.755564 , -0.0626742,0.259556,0.963692 --3.19473 , -2.5959 , -0.742429 , 0.0780609,-0.222762,-0.971743 --3.37061 , -2.70975 , -0.726323 , -0.0782157,0.225406,0.97112 --3.57838 , -2.84543 , -0.716711 , -0.0631939,0.235741,0.969759 --3.77904 , -2.97528 , -0.695858 , -0.0646684,0.233764,0.970141 --4.0048 , -3.12121 , -0.676122 , 0.0878696,-0.217734,-0.972045 --4.27841 , -3.301 , -0.66402 , 0.0891966,-0.218895,-0.971663 --4.56243 , -3.48599 , -0.643812 , -0.0874647,0.21317,0.973092 --4.90162 , -3.70895 , -0.629417 , 0.00659758,0.328698,0.944412 --5.19726 , -3.89716 , -0.587966 , 0.0111682,0.958405,0.285195 --5.18675 , -3.85836 , -0.454199 , 0.548455,0.759203,0.350439 --5.18901 , -3.82912 , -0.326011 , 0.794938,0.605651,-0.0354941 --5.1973 , -3.80519 , -0.200259 , 0.682435,0.717588,-0.139109 --5.20412 , -3.77968 , -0.0752666 , 0.695863,0.702304,-0.150145 --5.19289 , -3.7414 , 0.051785 , 0.688084,0.712516,-0.137336 --5.18672 , -3.70866 , 0.176522 , 0.702507,0.695347,-0.151578 --5.21962 , -3.7023 , 0.294542 , 0.628267,0.768868,-0.11884 --5.19384 , -3.65545 , 0.419508 , -0.618943,-0.774285,0.131877 --5.20744 , -3.63572 , 0.538927 , 0.624549,0.765873,-0.152896 --5.21886 , -3.61547 , 0.658391 , 0.631977,0.760027,-0.151541 --5.2195 , -3.58842 , 0.777944 , 0.718409,0.687044,-0.108902 --5.22704 , -3.56512 , 0.896494 , 0.716318,0.686841,-0.123039 --5.22475 , -3.53484 , 1.01482 , 0.718397,0.686203,-0.114155 --5.23727 , -3.51566 , 1.1329 , 0.713913,0.688708,-0.126526 --5.23994 , -3.48955 , 1.25056 , 0.711514,0.69095,-0.127812 --5.24019 , -3.46202 , 1.36778 , 0.698901,0.701398,-0.139925 --5.24764 , -3.43899 , 1.48516 , 0.694581,0.709722,-0.117693 --5.24424 , -3.40934 , 1.60176 , -0.429312,-0.896275,0.11128 --5.25652 , -3.38921 , 1.71964 , -0.429312,-0.896275,0.11128 --5.26641 , -3.36756 , 1.83756 , -0.564616,-0.79344,-0.227293 --16.426 , -10.3744 , 3.7259 , -0.384283,-0.920904,-0.0652912 --16.6646 , -10.4423 , 4.11159 , -0.384283,-0.920904,-0.0652911 --16.6378 , -10.3432 , 4.45435 , -0.529794,-0.847736,0.0257355 --16.6383 , -10.2614 , 4.80269 , 0.606045,0.77865,-0.162526 --16.6435 , -10.1812 , 5.1525 , 0.565859,0.799256,-0.202468 --16.6925 , -10.1285 , 5.51531 , 0.602784,0.776867,-0.182014 --16.6448 , -10.0165 , 5.85394 , 0.510908,0.827007,-0.234591 --16.6829 , -9.95575 , 6.21801 , 0.454195,0.855138,-0.249893 --16.6088 , -9.82677 , 6.54851 , -0.148574,-0.933479,0.326408 --16.6774 , -9.78372 , 6.92746 , -0.18346,-0.942374,0.279775 --16.5425 , -9.62052 , 7.23708 , -0.0291858,0.972384,-0.231553 --16.5751 , -9.55445 , 7.60796 , 0.015738,-0.98141,0.191277 --16.7498 , -9.56866 , 8.04015 , 0.0416638,-0.994862,0.092268 --16.5996 , -9.39583 , 8.34359 , -0.0134475,-0.999754,-0.0176455 --16.7527 , -9.39451 , 8.78004 , -0.81093,-0.58465,0.0240408 --16.7858 , -9.32437 , 9.17002 , 0.802851,0.59302,-0.0612982 --16.7963 , -9.24006 , 9.55384 , -0.773493,-0.630794,0.0617099 --16.8328 , -9.16977 , 9.95555 , 0.627752,0.748214,-0.214717 --16.918 , -9.1239 , 10.3892 , 0.628211,0.740261,-0.239508 --16.8143 , -8.97479 , 10.7253 , 0.475483,0.83033,-0.290633 --16.8228 , -8.88514 , 11.1272 , -0.404501,-0.857492,0.31794 --16.8561 , -8.8072 , 11.5494 , 0.116945,0.899567,-0.420836 --16.8502 , -8.70677 , 11.9546 , -0.0303899,-0.924368,0.380291 --16.6924 , -8.52793 , 12.2657 , -0.0588596,0.905265,-0.420751 --16.7888 , -8.47766 , 12.7476 , 0.0155516,-0.92097,0.389324 --16.6185 , -8.2913 , 13.0542 , -0.00951863,0.910134,-0.414204 --16.2414 , -8.00278 , 13.2087 , 0.0491404,-0.881445,0.469724 --17.1946 , -8.36791 , 14.3526 , -0.117038,0.991041,-0.0643368 --16.9135 , -8.1239 , 14.5933 , -0.0795237,0.996667,-0.0182105 --4.62867 , -1.65797 , 7.25062 , -0.247086,-0.150652,0.957211 --4.54572 , -1.58192 , 7.34149 , -0.247086,-0.150652,0.957211 --4.12649 , -1.38285 , 6.99843 , 0.872644,-0.463242,-0.154594 --3.99307 , -1.29178 , 7.00918 , 0.648112,-0.602845,-0.465327 --3.9189 , -1.22088 , 7.09511 , -0.819325,0.223767,0.527859 --3.61561 , -1.07493 , 6.85902 , -0.413967,-0.428853,-0.802943 --3.487 , -0.989564 , 6.85682 , 0.236367,-0.611636,-0.755005 --2.38877 , -0.603371 , 5.38976 , 0.4961,0.40761,-0.766641 --2.2866 , -0.538805 , 5.3722 , 0.4961,0.40761,-0.766641 --2.33707 , -0.519912 , 5.59555 , 0.894527,0.435865,-0.0992126 --2.35064 , -0.4877 , 5.77013 , -0.926189,-0.186235,0.327859 --2.5305 , -0.496579 , 6.23701 , -0.490538,0.653769,0.576159 --2.41981 , -0.427122 , 6.21775 , -0.401193,0.510733,0.760392 --2.38085 , -0.376337 , 6.32677 , -0.730246,0.511069,0.453375 --2.01561 , -0.252729 , 5.81881 , -0.309312,-0.605613,0.733184 --2.24224 , -0.257702 , 6.43612 , 0.577096,-0.698942,-0.422422 --2.12311 , -0.188547 , 6.39001 , 0.378394,-0.413273,-0.828266 --2.05678 , -0.130665 , 6.44941 , -0.111012,-0.776875,0.619792 --1.97684 , -0.0695628 , 6.4798 , 0.206912,0.768921,-0.604936 --2.45267 , -0.0792322 , 7.78002 , -0.258229,-0.59256,0.763014 --1.89291 , 0.0434694 , 6.71976 , -0.92796,-0.352991,-0.119532 --1.87549 , 0.100243 , 6.91299 , -0.385234,-0.919923,0.0730524 --1.62958 , 0.1739 , 6.52829 , 0.65927,0.594391,-0.460503 --1.6906 , 0.228993 , 6.93387 , 0.324391,-0.0550594,0.944319 --1.57046 , 0.292386 , 6.86118 , -0.259994,-0.568775,0.78032 --1.90811 , 0.367063 , 8.13023 , -0.729841,0.653715,0.19997 --1.43084 , 0.419442 , 7.00221 , -0.11391,-0.0356666,0.992851 --1.6952 , 0.517888 , 8.16435 , -0.574227,0.749338,-0.329782 --1.52337 , 0.582741 , 7.95271 , 0.66267,-0.57932,0.474613 --1.45536 , 0.661248 , 8.0933 , 0.467606,-0.883152,-0.037249 --1.08501 , 0.671014 , 7.09316 , 0.392037,0.0384605,-0.919145 --1.26019 , 0.81091 , 8.17662 , -0.729023,0.337887,0.595279 --0.917862 , 0.800279 , 7.16626 , 0.433977,0.714975,0.548157 --1.32848 , 1.07658 , 9.48757 , -0.566055,-0.75816,0.323689 --1.24276 , 1.18145 , 9.69034 , 0.584665,0.75759,-0.290215 --0.52352 , 0.913162 , 6.52987 , 0.242437,-0.435538,-0.866909 --0.451983 , 0.97448 , 6.58673 , 0.664776,-0.440906,-0.603054 --0.404096 , 1.05905 , 6.80853 , 0.649649,0.162968,-0.742562 --0.320573 , 1.11809 , 6.82311 , -0.00892774,-0.236281,0.971644 --0.222748 , 1.16133 , 6.72792 , -0.372319,0.91509,-0.154883 --0.132946 , 1.20905 , 6.68025 , -0.012999,-0.998535,-0.0525291 --0.0355634 , 1.23941 , 6.53253 , 0.760299,0.647104,-0.0565774 --1.99655 , -1.70509 , -0.837492 , -0.0229129,0.090354,0.995646 --2.10453 , -1.77275 , -0.836732 , -0.0443588,0.116196,0.992235 --2.21497 , -1.84009 , -0.83232 , -0.0505422,0.152899,0.986949 --2.33278 , -1.9131 , -0.828515 , -0.0553394,0.189231,0.980372 --2.45896 , -1.99143 , -0.824954 , -0.0921473,0.179482,0.979436 --2.59356 , -2.07498 , -0.821148 , 0.0760054,-0.173156,-0.981957 --2.72972 , -2.15819 , -0.812498 , -0.0759492,0.176742,0.981323 --2.89599 , -2.26254 , -0.815093 , -0.0783927,0.229856,0.970062 --3.02054 , -2.33434 , -0.788214 , -0.0447356,0.279124,0.959213 --3.1891 , -2.43783 , -0.779249 , -0.0446636,0.245105,0.968467 --3.36747 , -2.54671 , -0.767434 , -0.0722079,0.205579,0.975973 --3.56261 , -2.66616 , -0.755715 , -0.0534697,0.223779,0.973172 --3.75157 , -2.7797 , -0.733459 , -0.0582891,0.222315,0.973231 --3.98144 , -2.91951 , -0.719523 , 0.0783301,-0.212375,-0.974044 --4.25069 , -3.08646 , -0.711231 , -0.0793162,0.20927,0.974636 --4.53107 , -3.25748 , -0.695345 , -0.0694558,0.213689,0.97443 --4.82889 , -3.43875 , -0.673714 , -0.0856814,0.201518,0.97573 --5.20831 , -3.67384 , -0.664512 , 0.08771,0.486698,0.869156 --5.58226 , -3.90252 , -0.638154 , -0.226527,0.351427,0.908397 --6.11321 , -4.23398 , -0.636258 , 0.576336,-0.34893,0.738976 --6.65541 , -4.56815 , -0.615262 , -0.253698,0.302586,0.918738 --7.1843 , -4.88891 , -0.569475 , -0.0482662,0.24377,0.968631 --7.75002 , -5.22805 , -0.509331 , -0.0517282,0.25765,0.964853 --8.3842 , -5.60879 , -0.437696 , -0.0178178,0.275416,0.96116 --9.07834 , -6.0228 , -0.349858 , 0.0463489,0.328425,0.943392 --9.37638 , -6.17118 , -0.185087 , 0.0589696,0.37156,0.926534 --5.42191 , -3.55292 , 0.428492 , 0.611776,0.778615,-0.139602 --10.5401 , -6.82524 , 0.129921 , 0.0816749,0.293758,0.952384 --11.6776 , -7.50068 , 0.287051 , -0.0104033,0.238992,0.970966 --13.509 , -8.60607 , 0.460495 , -0.060482,0.282372,0.957396 --15.9471 , -10.0771 , 0.694548 , -0.0300477,0.398769,0.916559 --16.8584 , -10.5695 , 1.0269 , 0.203682,0.577992,0.790215 --17.2409 , -10.7253 , 1.38421 , -0.176911,0.976601,-0.122287 --17.8063 , -10.991 , 1.7631 , -0.192975,-0.9812,0.00266746 --5.64011 , -3.4624 , 1.40488 , -0.0778671,-0.97408,0.212379 --5.69022 , -3.46366 , 1.53146 , 0.079059,0.972536,-0.218913 --5.59209 , -3.37612 , 1.64522 , 0.126599,0.985346,-0.114302 --17.9408 , -10.73 , 3.24109 , 0.52193,0.85212,-0.0384824 --17.8838 , -10.6108 , 3.60028 , 0.516454,0.854279,-0.0590126 --17.9916 , -10.5887 , 3.9834 , -0.521901,-0.842745,0.131912 --17.9917 , -10.5028 , 4.35183 , -0.521705,-0.8428,0.132332 --18.0112 , -10.4281 , 4.7245 , -0.5224,-0.843513,0.124837 --18.025 , -10.3504 , 5.09766 , 0.530285,0.834626,-0.148987 --18.0508 , -10.2784 , 5.47479 , 0.501483,0.843563,-0.192138 --18.0612 , -10.1979 , 5.85055 , -0.470684,-0.852464,0.227511 --18.0752 , -10.1181 , 6.22867 , 0.436131,0.869072,-0.233459 --17.9563 , -9.96351 , 6.56904 , -0.334355,-0.878153,0.342132 --17.9422 , -9.86802 , 6.94005 , -0.289124,-0.912181,0.290402 --17.6863 , -9.64001 , 7.23048 , -0.0616251,-0.984714,0.162911 --17.9701 , -9.7071 , 7.7079 , 0.262362,0.952441,-0.154995 --18.0048 , -9.63631 , 8.10408 , -0.270091,-0.960426,0.0680608 --18.0164 , -9.55232 , 8.49531 , -0.315694,-0.945586,0.0787681 --18.2456 , -9.58161 , 8.98214 , -0.342187,-0.936169,0.0806026 --18.2843 , -9.50894 , 9.39774 , 0.379229,0.920522,-0.0939362 --18.2837 , -9.41508 , 9.80038 , -0.420118,-0.892585,0.163683 --18.3084 , -9.33256 , 10.2195 , -0.418647,-0.892481,0.167968 --18.3272 , -9.2458 , 10.6407 , -0.372215,-0.904902,0.20642 --18.3302 , -9.14985 , 11.0593 , 0.318851,0.897956,-0.30333 --18.1902 , -8.9818 , 11.4035 , -0.293081,-0.89409,0.338685 --18.0843 , -8.8308 , 11.7666 , -0.0420672,-0.946337,0.320434 --18.0355 , -8.7077 , 12.1652 , 0.00353938,-0.924124,0.382077 --17.9643 , -8.57332 , 12.5537 , 0.0483601,-0.930463,0.36318 --10.1974 , -4.78326 , 7.96384 , -0.563673,0.817221,0.120092 --17.5007 , -8.14958 , 13.1241 , -0.181922,0.967751,-0.17425 --18.4331 , -8.47977 , 14.2131 , -0.0645144,0.986993,-0.147251 --18.2007 , -8.26228 , 14.5159 , -0.0269768,0.995259,-0.093446 --9.57885 , -3.58811 , 11.4307 , 0.854255,-0.333536,-0.398749 --9.42629 , -3.45386 , 11.5966 , 0.854255,-0.333536,-0.398749 --9.08208 , -3.24913 , 11.5509 , 0.586254,-0.695847,-0.414854 --4.78095 , -1.57131 , 7.20274 , -0.247086,-0.150652,0.957211 --4.70318 , -1.49938 , 7.303 , -0.247086,-0.150652,0.957211 --4.5988 , -1.41865 , 7.37107 , -0.247086,-0.150652,0.957211 --4.51276 , -1.34382 , 7.45977 , -0.347101,-0.587262,0.731193 --4.02643 , -1.14219 , 7.02173 , 0.47123,-0.129488,0.872454 --6.24835 , -1.78083 , 10.241 , 0.459546,0.386784,-0.79951 --3.86615 , -1.00334 , 7.18353 , -0.988346,0.150126,-0.0251775 --2.50979 , -0.568642 , 5.41258 , 0.496101,0.407609,-0.766641 --2.39968 , -0.504089 , 5.38924 , -0.313721,-0.0540196,0.947978 --2.34367 , -0.456717 , 5.44645 , 0.709554,0.345855,-0.613936 --2.31888 , -0.415626 , 5.55259 , -0.921614,-0.0844633,0.378806 --2.28107 , -0.371792 , 5.64193 , -0.927082,-0.0592194,0.370152 --2.52652 , -0.390853 , 6.21949 , -0.401193,0.510733,0.760392 --2.9179 , -0.432481 , 7.09153 , 0.762563,0.358731,-0.538339 --2.30791 , -0.261856 , 6.18558 , 0.670425,-0.561284,-0.485274 --2.22078 , -0.202866 , 6.20424 , -0.474703,0.85519,0.208102 --2.2555 , -0.164197 , 6.46068 , -0.962352,-0.0841211,0.258463 --2.12107 , -0.0970943 , 6.3875 , -0.0431187,-0.290464,0.955914 --2.12045 , -0.0497973 , 6.59097 , -0.229763,-0.782655,0.578498 --2.48741 , -0.0410701 , 7.61339 , 0.595238,-0.168021,-0.785787 --2.06013 , 0.0600342 , 6.89876 , 0.411087,-0.879664,-0.239161 --1.87098 , 0.129255 , 6.68835 , -0.264636,0.142762,0.953723 --1.74472 , 0.190413 , 6.6122 , -0.148743,0.603989,0.78299 --1.69266 , 0.248126 , 6.7196 , 0.475185,0.774772,-0.417047 --1.6241 , 0.307406 , 6.78841 , -0.230207,-0.524524,0.819682 --1.92322 , 0.38034 , 7.90254 , -0.46649,0.805858,-0.364665 --1.51617 , 0.429864 , 7.02649 , 0.229218,0.490962,-0.840486 --1.4168 , 0.490189 , 7.01554 , -0.11391,-0.0356666,0.992851 --1.31438 , 0.548398 , 6.99296 , 0.396064,-0.109605,0.911658 --1.22327 , 0.608499 , 7.00653 , -0.20661,0.499615,0.841247 --1.05678 , 0.650455 , 6.73892 , 0.375661,-0.914809,0.148336 --0.962717 , 0.704944 , 6.71882 , -0.704288,0.659313,0.263221 --0.879034 , 0.76122 , 6.73547 , -0.852168,0.444425,0.276215 --1.40208 , 1.06217 , 9.43148 , 0.501769,0.732581,-0.459949 --0.660256 , 0.850367 , 6.52986 , -0.215636,0.253214,0.943071 --0.578555 , 0.903873 , 6.54093 , 0.132649,-0.134823,0.981951 --0.490727 , 0.953641 , 6.52102 , 0.562688,-0.214085,-0.798467 --0.4155 , 1.01194 , 6.56773 , -0.962935,0.205558,0.174646 --0.36776 , 1.0974 , 6.80885 , 0.187571,-0.673714,0.714791 --0.295679 , 1.16902 , 6.92108 , -0.721942,0.576588,0.382552 --0.189107 , 1.19996 , 6.76693 , 0.0480347,-0.896198,0.441045 --0.0790128 , 1.21645 , 6.54219 , -0.298654,0.709033,0.638809 --1.70248 , -1.42779 , -0.856627 , -0.0331861,0.161397,0.986332 --1.78944 , -1.47791 , -0.852607 , -0.0211504,0.116682,0.992944 --1.88999 , -1.53783 , -0.856329 , -0.0485705,0.11301,0.992406 --1.98519 , -1.59205 , -0.851484 , -0.0503115,0.127104,0.990613 --2.07402 , -1.6409 , -0.838437 , -0.0404983,0.118786,0.992094 --2.19235 , -1.71107 , -0.84189 , -0.068114,0.101056,0.992546 --2.31881 , -1.78568 , -0.846075 , -0.0785245,0.151332,0.985359 --2.4468 , -1.86004 , -0.845805 , -0.0762485,0.16512,0.983322 --2.57536 , -1.93435 , -0.840863 , -0.0798494,0.166045,0.98288 --2.72803 , -2.02439 , -0.844339 , 0.0677781,-0.181744,-0.981007 --2.85969 , -2.09806 , -0.829904 , -0.0855022,0.159625,0.983468 --3.05202 , -2.2138 , -0.842555 , -0.0544527,0.218718,0.974268 --3.17109 , -2.27629 , -0.809867 , -0.00275021,0.286602,0.958046 --3.31414 , -2.35327 , -0.784434 , -0.0521538,0.223477,0.973313 --3.53446 , -2.48344 , -0.788614 , -0.0834759,0.209022,0.974342 --3.73355 , -2.59622 , -0.774789 , -0.0487725,0.217763,0.974782 --3.95071 , -2.72004 , -0.759815 , -0.0669373,0.214799,0.974362 --4.1995 , -2.86317 , -0.749007 , 0.0664094,-0.207839,-0.975906 --4.45958 , -3.01158 , -0.731575 , -0.0676487,0.197781,0.977909 --4.76985 , -3.18989 , -0.720689 , 0.0760675,-0.202096,-0.976407 --5.12182 , -3.39375 , -0.710532 , -0.0904592,0.213294,0.972791 --5.52681 , -3.62771 , -0.701125 , -0.153307,0.281961,0.947098 --5.99038 , -3.8975 , -0.691277 , 0.219131,0.0481923,0.974505 --6.4749 , -4.17506 , -0.667876 , 0.465089,-0.544147,-0.69828 --7.09474 , -4.53382 , -0.65554 , 0.0638981,-0.242204,-0.968119 --7.61893 , -4.82719 , -0.598732 , -0.0440934,0.243466,0.968907 --8.24528 , -5.17999 , -0.540121 , 0.0396109,-0.248606,-0.967794 --6.51858 , -4.06568 , -0.0811564 , 0.999696,0.0158792,0.0188766 --9.6683 , -5.97373 , -0.37241 , 0.0825999,0.352694,0.932086 --6.16945 , -3.78498 , 0.250471 , 0.998338,0.042821,-0.0385792 --10.2573 , -6.2355 , -0.0126215 , 0.108641,0.351279,0.929946 --11.2417 , -6.77858 , 0.129509 , 0.0130238,0.290812,0.956692 --12.5976 , -7.53501 , 0.288758 , -0.0311359,0.227882,0.973191 --14.7829 , -8.77069 , 0.47009 , -0.0502964,0.222225,0.973697 --17.9986 , -10.5934 , 0.719464 , 0.201042,0.942049,0.268563 --18.0204 , -10.5222 , 1.08713 , -0.20663,-0.966794,-0.150375 --18.2783 , -10.5871 , 1.45929 , 0.300403,0.948979,0.0958984 --18.3239 , -10.528 , 1.8315 , -0.362794,-0.927549,0.0896249 --18.3282 , -10.4459 , 2.20211 , 0.360735,0.919003,-0.159073 --18.2582 , -10.3216 , 2.56603 , 0.343022,0.938969,-0.0259445 --18.5119 , -10.379 , 2.95912 , -0.303888,-0.952686,-0.00646553 --18.5427 , -10.3112 , 3.3353 , -0.335527,-0.940564,0.0525496 --18.5685 , -10.2394 , 3.71166 , 0.39079,0.906753,-0.158374 --18.5876 , -10.1649 , 4.08844 , 0.390257,0.908322,-0.150505 --18.6099 , -10.0904 , 4.46661 , 0.408709,0.896021,-0.173501 --18.635 , -10.0179 , 4.84688 , -0.412213,-0.895509,0.16776 --18.6456 , -9.93672 , 5.22575 , -0.414035,-0.894118,0.170671 --18.6674 , -9.86135 , 5.60881 , -0.420579,-0.890793,0.172051 --18.6834 , -9.78304 , 5.99266 , -0.397655,-0.893774,0.207458 --18.7008 , -9.70484 , 6.37931 , 0.350651,0.904823,-0.241534 --18.7134 , -9.62346 , 6.76672 , -0.379741,-0.892074,0.24495 --18.6164 , -9.48457 , 7.12166 , -0.332539,-0.929494,0.159558 --18.7965 , -9.48701 , 7.56867 , -0.309782,-0.948365,0.0681159 --18.8578 , -9.42788 , 7.98329 , -0.324737,-0.945763,0.00889213 --18.8019 , -9.30923 , 8.35876 , 0.290936,0.949762,-0.115358 --18.9511 , -9.29171 , 8.81723 , -0.272107,-0.959325,0.0751859 --18.9583 , -9.20216 , 9.2252 , 0.253804,0.955824,-0.148272 --18.9842 , -9.12018 , 9.64531 , -0.31067,-0.932765,0.182846 --19.0023 , -9.03449 , 10.0673 , -0.314409,-0.931598,0.182405 --19.0218 , -8.9473 , 10.4949 , 0.278791,0.941569,-0.189004 --19.042 , -8.85973 , 10.9285 , -0.263736,-0.938131,0.224396 --19.0551 , -8.76721 , 11.3641 , -0.22174,-0.924225,0.310868 --10.4907 , -4.74221 , 7.08657 , -0.625755,0.774714,0.0908245 --10.2548 , -4.5787 , 7.19919 , 0.625755,-0.774714,-0.0908245 --8.00614 , -3.51437 , 6.10513 , 0.826941,0.0028603,-0.562282 --10.2026 , -4.44213 , 7.66161 , 0.525527,-0.832073,-0.177416 --10.1674 , -4.36879 , 7.89015 , -0.563673,0.817221,0.120092 --19.2359 , -8.22549 , 14.1858 , -0.0555446,0.982619,-0.177129 --10.0674 , -4.20771 , 8.33538 , 0.546128,-0.837585,-0.0139515 --8.5031 , -3.49005 , 7.47812 , -0.704149,0.708921,-0.0400627 --8.31255 , -3.3597 , 7.56413 , -0.869095,0.361853,0.337249 --8.28747 , -3.29775 , 7.77125 , -0.5657,-0.0506473,0.823054 --8.07169 , -3.15716 , 7.8304 , 0.549038,-0.0337203,-0.835117 --8.64043 , -3.33035 , 8.52498 , 0.681267,-0.729527,0.0605379 --7.74345 , -2.92269 , 8.0155 , -0.437776,-0.00943896,0.899035 --7.63534 , -2.8288 , 8.15149 , -0.406461,-0.374038,0.833598 --9.72923 , -3.49635 , 10.5735 , 0.64355,-0.648714,-0.406219 --9.70349 , -3.41669 , 10.8567 , 0.64355,-0.648713,-0.406219 --9.39072 , -3.23278 , 10.8605 , -0.705312,0.636205,0.312696 --9.43928 , -3.17807 , 11.2234 , 0.854256,-0.333537,-0.398749 --9.36641 , -3.07889 , 11.4695 , 0.586254,-0.695847,-0.414854 --6.23535 , -1.54281 , 10.1881 , -0.396208,-0.391136,0.830681 --3.80933 , -0.836541 , 7.08277 , 0.464476,-0.154244,0.87205 --2.5245 , -0.467689 , 5.42065 , -0.77614,0.0696165,0.626706 --2.40128 , -0.40459 , 5.38063 , -0.168653,-0.299801,0.938976 --2.37179 , -0.36521 , 5.47909 , -0.875183,0.11388,0.470199 --2.32433 , -0.31989 , 5.55164 , -0.916371,-0.122783,0.381037 --2.3258 , -0.284874 , 5.7086 , 0.999494,0.0270667,-0.016684 --2.24775 , -0.233038 , 5.73765 , -0.303335,-0.787912,0.535894 --2.45931 , -0.232821 , 6.27639 , 0.679897,-0.559357,-0.474193 --2.16902 , -0.142225 , 5.93013 , -0.160244,-0.951221,0.263629 --2.25521 , -0.114937 , 6.27288 , -0.586124,0.809927,0.0218486 --2.10677 , -0.0503582 , 6.17387 , -0.558871,0.785127,0.266906 --2.14969 , -0.0104786 , 6.45677 , 0.16686,0.856155,-0.489036 --2.15546 , 0.0369641 , 6.67865 , 0.704602,-0.670338,-0.232773 --1.90007 , 0.10775 , 6.33704 , -0.914262,0.000730809,0.405122 --1.94599 , 0.155071 , 6.6573 , 0.061307,0.58327,0.809962 --1.78197 , 0.215261 , 6.49999 , 0.0163916,0.672084,0.740294 --1.72657 , 0.269313 , 6.59881 , -0.667675,-0.556056,0.494987 --1.72294 , 0.326101 , 6.83645 , -0.437208,-0.278897,0.855024 --1.64098 , 0.383672 , 6.87755 , 0.447271,0.0928093,-0.88957 --1.57675 , 0.443369 , 6.9736 , -0.484556,-0.457884,0.745351 --1.4974 , 0.502768 , 7.03054 , 0.271745,0.698205,-0.662317 --1.41149 , 0.561538 , 7.06694 , 0.563878,-0.312782,0.764336 --1.29489 , 0.615621 , 7.00596 , 0.199673,0.263913,0.943653 --1.12937 , 0.656008 , 6.76001 , 0.694182,0.00397356,0.719788 --0.988243 , 0.696749 , 6.57784 , 0.467071,-0.816954,-0.338276 --0.932318 , 0.758008 , 6.7019 , 0.888056,-0.0781572,-0.453043 --0.867678 , 0.81918 , 6.80556 , 0.542686,-0.493167,0.679911 --0.713102 , 0.843383 , 6.51917 , 0.134124,-0.238154,-0.961922 --0.629985 , 0.89471 , 6.53156 , 0.352097,-0.12781,-0.927196 --0.53956 , 0.942049 , 6.50304 , -0.168566,0.284538,0.943729 --0.46123 , 0.995778 , 6.54155 , -0.486047,0.400806,0.776603 --0.41328 , 1.07727 , 6.77393 , 0.649648,0.162968,-0.742562 --0.335458 , 1.13965 , 6.84848 , 0.200263,-0.846348,0.493548 --0.230117 , 1.17311 , 6.72522 , -0.30156,-0.694733,0.653 --0.139061 , 1.21853 , 6.68824 , -0.012999,-0.998535,-0.0525291 --0.0360766 , 1.24052 , 6.52206 , 0.7603,0.647104,-0.0565774 --1.7041 , -1.34052 , -0.878616 , -0.0116101,0.185939,0.982493 --1.77909 , -1.37803 , -0.865349 , -0.0204622,0.164184,0.986218 --1.86666 , -1.42571 , -0.860385 , 0.0616553,-0.139608,-0.988286 --1.96294 , -1.47706 , -0.858222 , -0.0700765,0.135417,0.988307 --2.06725 , -1.53314 , -0.858055 , -0.0523843,0.155293,0.986479 --2.17888 , -1.59503 , -0.859178 , -0.0858172,0.154531,0.984254 --2.29958 , -1.66122 , -0.861445 , -0.0901354,0.141764,0.985788 --2.42865 , -1.73276 , -0.864051 , -0.0946258,0.141942,0.985342 --2.56684 , -1.80842 , -0.867024 , -0.0855152,0.166893,0.98226 --2.69777 , -1.8787 , -0.860701 , -0.0842228,0.179524,0.980142 --2.84597 , -1.95915 , -0.858197 , -0.0760744,0.188997,0.979026 --3.00337 , -2.04346 , -0.854892 , -0.0841696,0.162148,0.98317 --3.18506 , -2.14297 , -0.85767 , -0.0386352,0.25401,0.96643 --3.32132 , -2.21193 , -0.831074 , -0.032944,0.300085,0.953344 --3.51422 , -2.31532 , -0.825383 , 0.078645,-0.236853,-0.968357 --3.70786 , -2.41812 , -0.812685 , -0.0637441,0.232015,0.970621 --3.92723 , -2.53615 , -0.802784 , -0.0633951,0.235393,0.96983 --4.15609 , -2.6572 , -0.788384 , -0.0602215,0.220847,0.973448 --4.41085 , -2.79294 , -0.774446 , -0.0680588,0.207301,0.975907 --4.70876 , -2.95361 , -0.765081 , -0.0774442,0.208137,0.975029 --5.0326 , -3.12723 , -0.752873 , -0.0920847,0.209221,0.973523 --5.43427 , -3.34568 , -0.750833 , -0.0949807,0.204193,0.974312 --5.87071 , -3.58266 , -0.742881 , -0.0111439,0.0950302,0.995412 --6.37823 , -3.85689 , -0.736025 , 0.144849,0.274822,-0.950522 --6.96489 , -4.17528 , -0.727559 , -0.0862716,0.226639,0.970151 --7.52106 , -4.46987 , -0.68951 , -0.0482662,0.24377,0.968631 --8.10556 , -4.7762 , -0.635503 , -0.0406163,0.245652,0.968507 --6.42197 , -3.75172 , -0.1646 , 0.999586,0.00881337,-0.0273813 --6.39336 , -3.70317 , -0.0179141 , 0.998338,0.042821,-0.0385793 --10.0807 , -5.7928 , -0.367828 , 0.119274,0.351981,0.928377 --6.45642 , -3.67622 , 0.254586 , 0.998338,0.042821,-0.0385792 --10.9645 , -6.19707 , -0.0239313 , 0.0721856,0.342931,0.936583 --12.0445 , -6.75269 , 0.125935 , -0.018061,0.263003,0.964626 --13.7557 , -7.65047 , 0.283757 , -0.0429855,0.226333,0.973101 --16.5563 , -9.13489 , 0.471114 , -0.0263227,0.317288,0.947964 --18.7774 , -10.2774 , 0.775003 , 0.350534,0.930782,0.103777 --18.9551 , -10.2896 , 1.15244 , 0.386899,0.915132,0.113327 --19.1708 , -10.3205 , 1.53621 , -0.398758,-0.915057,-0.0605254 --19.1785 , -10.2384 , 1.91797 , -0.27549,-0.959576,0.0576132 --19.1897 , -10.1586 , 2.29947 , 0.226462,0.97264,-0.0518348 --19.3095 , -10.1352 , 2.68964 , 0.202402,0.977727,-0.0555279 --19.52 , -10.159 , 3.09358 , 0.191909,0.974913,-0.112763 --19.5305 , -10.0772 , 3.48084 , -0.230023,-0.961523,0.150209 --19.5434 , -9.99658 , 3.86913 , -0.213684,-0.957154,0.195436 --19.5503 , -9.91231 , 4.25704 , -0.222291,-0.955346,0.194683 --19.5515 , -9.82532 , 4.64476 , 0.232081,0.952286,-0.198215 --19.5634 , -9.74343 , 5.0355 , -0.242136,-0.949478,0.199654 --19.5611 , -9.65389 , 5.42445 , 0.249761,0.948151,-0.196542 --19.5698 , -9.57024 , 5.8174 , -0.267692,-0.940655,0.208589 --19.5895 , -9.49134 , 6.21492 , -0.290617,-0.930307,0.223763 --19.5156 , -9.36687 , 6.58918 , 0.325573,0.892032,-0.313499 --19.4967 , -9.2677 , 6.97853 , -0.28133,-0.947866,0.149679 --19.1851 , -9.03083 , 7.27686 , -0.296534,-0.949265,0.104705 --19.7872 , -9.22363 , 7.87255 , -0.202102,-0.978579,0.0392318 --19.627 , -9.05804 , 8.2239 , 0.214653,0.976661,-0.0075448 --20.0205 , -9.14676 , 8.78027 , -0.168441,-0.97916,0.113464 --20.0184 , -9.051 , 9.19894 , -0.173572,-0.975284,0.136723 --20.0188 , -8.95481 , 9.62175 , 0.155731,0.966818,-0.20251 --20.0284 , -8.86298 , 10.0531 , 0.162323,0.965718,-0.202584 --20.0384 , -8.76995 , 10.4897 , 0.168016,0.965281,-0.200008 --20.0585 , -8.6798 , 10.9358 , 0.167377,0.966324,-0.195454 --20.0621 , -8.5816 , 11.3797 , 0.223926,0.956289,-0.188067 --10.9629 , -4.59634 , 7.05329 , -0.625755,0.774714,0.0908245 --8.13068 , -3.34532 , 5.75794 , -0.703349,0.434703,0.562436 --7.89875 , -3.20516 , 5.81912 , 0.936735,-0.337488,-0.0928914 --8.08877 , -3.24026 , 6.12208 , -0.628305,-0.271332,0.729117 --7.92682 , -3.12976 , 6.2201 , 0.837551,0.0379933,-0.545037 --7.76329 , -3.01969 , 6.31288 , 0.917731,-0.380547,-0.113815 --8.66026 , -3.3303 , 7.10285 , -0.644635,0.759929,-0.0833853 --7.91342 , -2.98836 , 6.81154 , -0.90067,-0.418413,-0.117154 --7.95237 , -2.95717 , 7.04716 , 0.990236,0.0545147,0.128297 --7.94142 , -2.90501 , 7.25092 , -0.957881,0.0537574,-0.28209 --8.3612 , -3.01258 , 7.78626 , 0.641023,-0.0248762,-0.767118 --8.08899 , -2.86012 , 7.80284 , 0.526892,-0.147274,-0.837075 --8.01135 , -2.77979 , 7.96882 , -0.599516,-0.147778,0.786602 --7.25908 , -2.46082 , 7.56819 , -0.664116,0.371768,0.648644 --7.38778 , -2.45644 , 7.89661 , -0.938701,-0.00388372,-0.344711 --10.3221 , -3.41041 , 10.7557 , 0.64355,-0.648713,-0.406219 --7.50892 , -2.39466 , 8.46528 , -0.879519,-0.117786,0.461055 --9.75281 , -3.07831 , 10.8534 , -0.578022,0.754503,0.31083 --9.5255 , -2.93293 , 10.9444 , -0.705312,0.636205,0.312696 --8.98965 , -2.69279 , 10.7157 , 0.79237,-0.571327,-0.213858 --7.2954 , -2.1023 , 9.24343 , -0.883419,-0.387075,0.26409 --6.3551 , -1.41024 , 10.0355 , -0.319056,-0.337753,0.885509 --3.87261 , -0.750673 , 6.96512 , 0.464476,-0.154244,0.87205 --3.82175 , -0.694943 , 7.08687 , 0.449153,-0.244256,0.859418 --6.05926 , -1.13907 , 10.521 , -0.308748,-0.389336,0.867808 --2.37756 , -0.302415 , 5.33918 , -0.659689,-0.396421,0.638484 --2.40122 , -0.274755 , 5.5203 , 0.918237,-0.184554,-0.350401 --2.61567 , -0.279822 , 6.01489 , -0.506691,0.793062,0.338109 --2.41295 , -0.206072 , 5.85267 , 0.566889,-0.542883,0.619609 --2.29212 , -0.148445 , 5.81382 , -0.228385,-0.803646,0.54954 --2.28971 , -0.109282 , 5.9802 , 0.565371,-0.820337,-0.0860487 --2.92356 , -0.152151 , 7.32167 , 0.146837,0.439428,-0.886195 --2.84468 , -0.0908512 , 7.40241 , -0.370856,0.0477917,0.92746 --2.28858 , 0.018302 , 6.5461 , -0.184378,-0.782937,0.59415 --1.92628 , 0.096733 , 6.0144 , -0.174473,0.489316,0.854476 --1.90669 , 0.141907 , 6.16951 , -0.871549,-0.489785,0.0226548 --2.49196 , 0.162742 , 7.67351 , -0.584064,-0.284829,0.760093 --1.87905 , 0.239235 , 6.53504 , -0.000944102,0.749096,0.662461 --1.78138 , 0.29245 , 6.53338 , 0.530792,-0.385259,-0.754875 --1.79418 , 0.34743 , 6.80854 , -0.986156,0.106363,0.127217 --1.72558 , 0.40372 , 6.88831 , 0.70535,0.0636817,-0.705993 --1.62302 , 0.458006 , 6.88246 , -0.290881,-0.48645,0.823866 --1.54344 , 0.514423 , 6.9405 , -0.42172,-0.610578,0.670333 --1.52028 , 0.578915 , 7.16767 , -0.32103,-0.383203,0.86608 --1.36696 , 0.624752 , 7.00438 , 0.199673,0.263913,0.943653 --1.24496 , 0.673383 , 6.92355 , 0.161046,0.395566,0.904208 --1.04652 , 0.699435 , 6.56169 , -0.0222857,0.955789,0.293208 --0.96956 , 0.752332 , 6.60975 , -0.0164523,-0.923082,0.384251 --0.894404 , 0.806293 , 6.66586 , -0.783543,0.302966,0.542469 --0.816737 , 0.86142 , 6.72046 , -0.953229,0.227449,-0.199052 --0.680473 , 0.888301 , 6.51125 , -0.183504,0.210865,0.960137 --0.599897 , 0.939001 , 6.54291 , 0.104384,-0.29107,0.95099 --0.510091 , 0.984274 , 6.52396 , -0.517801,-0.02761,0.855056 --0.423266 , 1.03086 , 6.52299 , -0.370887,-0.183289,0.910411 --0.375242 , 1.11424 , 6.77468 , 0.618668,-0.424292,-0.661231 --0.289397 , 1.16652 , 6.8 , 0.417317,-0.410013,-0.811009 --0.191159 , 1.20546 , 6.73521 , -0.282855,0.946582,0.154842 --0.0862841 , 1.22927 , 6.59025 , -0.160814,-0.0309462,0.9865 --1.69073 , -1.24389 , -0.888239 , -0.0322242,0.208484,0.977495 --1.76516 , -1.27978 , -0.876632 , -0.0375198,0.200876,0.978898 --1.85385 , -1.3245 , -0.873961 , -0.032644,0.196294,0.980002 --1.95125 , -1.3729 , -0.874091 , 0.0909796,-0.205302,-0.974461 --2.05595 , -1.42722 , -0.875996 , -0.0846381,0.178171,0.980353 --2.16185 , -1.48057 , -0.874715 , -0.103988,0.192153,0.97584 --2.27681 , -1.53828 , -0.87487 , 0.111168,-0.185863,-0.976267 --2.4067 , -1.60609 , -0.880745 , 0.0770205,-0.17426,-0.981683 --2.53128 , -1.66809 , -0.877566 , -0.0925843,0.162736,0.982316 --2.67944 , -1.74409 , -0.883978 , -0.0990728,0.173923,0.979763 --2.82845 , -1.82083 , -0.88484 , -0.0826619,0.19407,0.977499 --2.97978 , -1.896 , -0.880885 , 0.0778794,-0.203954,-0.975878 --3.14058 , -1.97592 , -0.875639 , 0.0904324,-0.176472,-0.980143 --3.33332 , -2.07521 , -0.880421 , -0.0815637,0.258065,0.962678 --3.48852 , -2.14909 , -0.859674 , -0.0929615,0.290334,0.952399 --3.69254 , -2.25204 , -0.855014 , -0.0582912,0.261575,0.963421 --3.89014 , -2.34811 , -0.839918 , 0.0659744,-0.244388,-0.967431 --4.12239 , -2.46416 , -0.830806 , -0.0537274,0.234633,0.970598 --4.3632 , -2.58331 , -0.816491 , 0.0715177,-0.219297,-0.973033 --4.6565 , -2.73024 , -0.811327 , -0.0831933,0.217393,0.972532 --4.96796 , -2.88629 , -0.800932 , -0.0886496,0.213191,0.97298 --5.34024 , -3.07394 , -0.797695 , -0.0974439,0.208494,0.973157 --5.75807 , -3.28465 , -0.792852 , 0.0295393,0.190966,0.981152 --6.22045 , -3.51712 , -0.784046 , -0.0638315,-0.0188719,0.997782 --6.89828 , -3.86659 , -0.811434 , -0.320983,0.253858,0.912429 --7.41891 , -4.12316 , -0.775622 , -0.0473642,0.238459,0.969997 --7.97746 , -4.39519 , -0.72794 , -0.0440934,0.243466,0.968907 --6.32324 , -3.44889 , -0.243421 , -0.95886,0.0591876,-0.277641 --9.36143 , -5.07101 , -0.613863 , 0.0126334,0.253469,0.967261 --6.34881 , -3.4018 , 0.0290729 , -0.947776,-0.011432,-0.318732 --10.4679 , -5.57525 , -0.359259 , 0.100825,0.377073,0.920679 --10.8676 , -5.73949 , -0.184812 , 0.0721855,0.342931,0.936583 --11.7695 , -6.16488 , -0.0402915 , -0.00835777,0.303048,0.952939 --13.1249 , -6.81881 , 0.107051 , -0.0381388,0.262086,0.964291 --15.477 , -7.9776 , 0.257047 , 0.0831535,0.130002,0.988021 --19.311 , -9.87776 , 0.452879 , 0.253015,0.845034,0.471064 --20.4748 , -10.3849 , 0.822495 , 0.0644614,0.860142,0.505964 --21.1628 , -10.6425 , 1.2312 , 0.093167,-0.991611,0.0895997 --21.4079 , -10.673 , 1.65268 , 0.093167,-0.991611,0.0895997 --20.8598 , -10.3081 , 2.04508 , 0.161513,-0.980633,0.110779 --20.5284 , -10.054 , 2.43002 , -0.146311,0.98351,-0.106308 --21.6412 , -10.5079 , 2.92481 , -0.125612,0.985688,-0.112432 --21.6279 , -10.4074 , 3.34428 , -0.132599,0.985994,-0.101159 --21.7239 , -10.3601 , 3.77687 , -0.130736,0.987704,-0.0857212 --21.7415 , -10.2749 , 4.20221 , -0.0574038,0.979351,-0.193848 --21.7613 , -10.1899 , 4.62897 , -0.0606985,0.97797,-0.199728 --21.7755 , -10.1021 , 5.05593 , -0.0596898,0.976754,-0.205885 --21.7721 , -10.0063 , 5.48136 , -0.0869057,0.966246,-0.24252 --21.7899 , -9.91882 , 5.91215 , -0.0896092,0.967877,-0.234915 --21.7464 , -9.8039 , 6.33081 , 0.0286139,-0.970562,0.239146 --21.7502 , -9.70942 , 6.76156 , 0.0263916,-0.976375,0.214467 --21.277 , -9.40274 , 7.06275 , -0.160659,0.966913,-0.198163 --21.8242 , -9.54892 , 7.64973 , 0.0270759,-0.985157,0.169508 --21.7095 , -9.40145 , 8.05196 , 0.0685873,-0.985431,0.155633 --21.9742 , -9.41867 , 8.57998 , -0.0956321,0.983006,-0.156695 --21.993 , -9.32713 , 9.03444 , -0.0766365,0.982095,-0.172093 --22.0133 , -9.23524 , 9.49374 , -0.0950968,0.978939,-0.180655 --22.035 , -9.14205 , 9.95778 , 0.0953758,-0.974533,0.202951 --22.0563 , -9.04881 , 10.4275 , 0.115215,-0.9683,0.221633 --9.7762 , -3.91407 , 5.52842 , 0.574484,-0.79714,-0.185839 --9.71189 , -3.84116 , 5.71358 , 0.574484,-0.79714,-0.185839 --21.8856 , -8.66703 , 11.758 , 0.114889,-0.967956,0.223297 --8.39379 , -3.22265 , 5.48769 , -0.599207,-0.476138,0.643617 --9.63468 , -3.66469 , 6.32746 , -0.692227,0.690777,0.208921 --7.83576 , -2.92117 , 5.57126 , -0.915148,0.317043,0.248973 --8.17245 , -3.0088 , 5.94731 , 0.367662,0.541225,-0.756241 --8.11511 , -2.94319 , 6.10925 , -0.375947,-0.638946,0.671127 --7.83618 , -2.79659 , 6.13598 , -0.514657,-0.469806,0.717224 --7.89657 , -2.77547 , 6.36837 , -0.275821,-0.729712,0.625654 --7.76031 , -2.68157 , 6.47727 , -0.843549,-0.521887,0.126721 --7.83747 , -2.66498 , 6.72855 , 0.982217,0.16477,-0.0900033 --7.77425 , -2.59697 , 6.88883 , 0.990236,0.0545147,0.128297 --8.46364 , -2.78827 , 7.6002 , -0.957631,0.263487,-0.116268 --8.2344 , -2.6593 , 7.65486 , -0.963735,0.19541,-0.181739 --8.07329 , -2.55521 , 7.75642 , 0.705164,0.0804469,-0.704466 --7.51985 , -2.32396 , 7.53636 , 0.706564,0.0868875,-0.702295 --7.35351 , -2.22259 , 7.6159 , 0.818205,0.347147,-0.458291 --7.86384 , -2.33332 , 8.27605 , -0.630108,-0.159119,0.76003 --7.70994 , -2.23372 , 8.37778 , 0.642746,0.0326768,-0.765382 --7.49077 , -2.11313 , 8.41549 , 0.925507,-0.173025,-0.336896 --7.42706 , -2.04113 , 8.59557 , -0.928246,-0.327613,0.176151 --7.5069 , -2.00994 , 8.91911 , -0.883419,-0.387075,0.26409 --7.44137 , -1.93469 , 9.10692 , -0.883419,-0.387075,0.26409 --8.63441 , -2.20341 , 10.6167 , -0.917126,0.0202808,-0.398081 --6.13567 , -1.00427 , 10.3145 , -0.308748,-0.389336,0.867808 --6.0435 , -0.918225 , 10.4899 , -0.361628,-0.460308,0.810766 --4.6888 , -0.610908 , 8.78688 , -0.240351,0.959102,-0.149517 --4.42691 , -0.509511 , 8.64627 , 0.574682,0.123825,0.808955 --3.1225 , -0.252975 , 6.82575 , 0.141858,0.254235,0.956682 --2.34333 , -0.0993886 , 5.74085 , -0.495278,-0.719715,0.486528 --3.81267 , -0.247651 , 8.42351 , -0.0590102,0.871045,0.487646 --3.0494 , -0.10231 , 7.33558 , 0.505552,0.221559,-0.833864 --2.93505 , -0.0400427 , 7.35697 , 0.505552,0.221559,-0.833864 --2.82027 , 0.0225832 , 7.37553 , -0.427293,-0.186714,0.884624 --1.98984 , 0.131242 , 5.97309 , -0.174473,0.489316,0.854476 --1.94915 , 0.176645 , 6.08356 , -0.782103,-0.578307,0.232113 --1.85949 , 0.22386 , 6.09407 , -0.782103,-0.578307,0.232113 --2.00323 , 0.268216 , 6.62265 , 0.276449,0.628803,0.726761 --1.84262 , 0.319798 , 6.48564 , -0.556704,0.353421,0.751781 --1.771 , 0.370685 , 6.54804 , 0.696032,-0.174845,-0.696397 --1.91683 , 0.433337 , 7.16741 , -0.537687,-0.0545032,-0.841381 --1.68836 , 0.478361 , 6.84678 , 0.545233,0.0987521,-0.832448 --1.64004 , 0.53514 , 6.99081 , 0.380891,0.615723,-0.689788 --1.56729 , 0.590786 , 7.07751 , 0.681188,0.27118,-0.680033 --1.47629 , 0.645432 , 7.11533 , -0.299786,-0.135138,-0.944386 --1.34359 , 0.691137 , 7.01796 , 0.201542,0.428855,0.880605 --1.16146 , 0.720916 , 6.73566 , 0.197515,-0.36982,0.907866 --1.02237 , 0.754956 , 6.57449 , -0.0164522,-0.923082,0.38425 --0.976437 , 0.817287 , 6.74752 , -0.225804,-0.493209,0.840094 --0.887313 , 0.866127 , 6.76523 , 0.307333,0.290936,0.906037 --0.740545 , 0.887946 , 6.52896 , -0.0471249,0.251634,0.966675 --0.650414 , 0.93268 , 6.523 , -0.344755,0.0416201,0.93777 --0.564226 , 0.978923 , 6.53481 , 0.417239,0.00485381,0.908784 --0.482721 , 1.02892 , 6.5743 , -0.263155,-0.514839,0.815898 --0.418391 , 1.09359 , 6.7198 , -0.979362,-0.126567,0.157581 --0.34242 , 1.15536 , 6.82468 , -0.194106,-0.813613,-0.548048 --0.235328 , 1.18334 , 6.70248 , -0.566158,-0.213176,0.796255 --0.139867 , 1.22069 , 6.65716 , 0.148008,0.908273,0.391324 --0.0392355 , 1.24631 , 6.54118 , 0.109893,-0.915473,0.387083 --1.77554 , -1.20106 , -0.90978 , -0.0438899,0.206792,0.9774 --1.85154 , -1.23429 , -0.897349 , 0.0469067,-0.221697,-0.973987 --1.94935 , -1.28086 , -0.89926 , 0.11497,-0.231698,-0.96597 --2.0486 , -1.32745 , -0.89798 , -0.0900673,0.202285,0.975176 --2.15564 , -1.37783 , -0.898894 , -0.108206,0.197616,0.974289 --2.2783 , -1.43729 , -0.906528 , -0.113217,0.186364,0.975936 --2.39489 , -1.49214 , -0.904984 , 0.077476,-0.18784,-0.979139 --2.51371 , -1.54571 , -0.899887 , -0.0866654,0.172267,0.98123 --2.66271 , -1.61794 , -0.909374 , -0.109136,0.150802,0.982521 --2.81353 , -1.69071 , -0.913528 , -0.0885088,0.176873,0.980246 --2.95879 , -1.7567 , -0.908727 , -0.0854591,0.182353,0.979512 --3.12804 , -1.83716 , -0.911181 , -0.0853141,0.191723,0.977734 --3.30777 , -1.92202 , -0.911881 , -0.0838207,0.202327,0.975724 --3.52003 , -2.02391 , -0.922055 , -0.0815548,0.233952,0.968822 --3.671 , -2.08909 , -0.894839 , 0.063562,-0.282099,-0.957277 --3.88668 , -2.18937 , -0.89124 , -0.0491049,0.253819,0.966004 --4.08874 , -2.28054 , -0.873059 , -0.0549245,0.245471,0.967847 --4.32477 , -2.38873 , -0.860967 , -0.0646323,0.234177,0.970043 --4.59516 , -2.51444 , -0.852823 , -0.0799626,0.21872,0.972506 --4.90995 , -2.66173 , -0.849792 , -0.0872549,0.21049,0.973694 --5.2616 , -2.82608 , -0.846375 , -0.0930527,0.207403,0.97382 --5.66597 , -3.01583 , -0.845982 , 0.00563504,0.132469,0.991171 --6.08281 , -3.20833 , -0.833253 , 0.386524,0.0292775,0.921815 --6.66462 , -3.48549 , -0.84823 , 0.792801,-0.599989,-0.107146 --6.23793 , -3.22993 , -0.595807 , 0.982878,-0.0982209,0.155893 --6.2482 , -3.20443 , -0.459763 , -0.962841,0.226379,-0.147276 --6.37862 , -3.24158 , -0.348843 , 0.981095,-0.052818,0.186181 --6.27894 , -3.16029 , -0.192437 , 0.975857,-0.0190592,0.217576 --6.32659 , -3.15461 , -0.0648793 , -0.938057,-0.0265824,-0.34546 --6.5315 , -3.22793 , 0.0410536 , -0.938057,-0.0265824,-0.34546 --6.54086 , -3.20244 , 0.178094 , -0.9037,-0.0857958,-0.419482 --11.6293 , -5.67841 , -0.207657 , 0.0163177,0.371718,0.928202 --12.7162 , -6.15678 , -0.063517 , -0.0241288,0.293854,0.955546 --14.577 , -7.00226 , 0.0714481 , -0.00942968,0.232424,0.972569 --17.5511 , -8.36635 , 0.226205 , 0.0607466,0.0607417,0.996303 --22.3577 , -10.5766 , 0.445202 , 0.0692464,-0.995114,0.0703726 --22.4637 , -10.5319 , 0.878364 , -0.0953087,0.993011,-0.069604 --23.3055 , -10.8302 , 1.32253 , -0.0671302,0.996184,-0.0557699 --23.0721 , -10.6231 , 1.76412 , -0.0453718,0.997652,-0.0513055 --22.713 , -10.3611 , 2.18983 , -0.0541684,0.995526,-0.0774193 --23.5822 , -10.6608 , 2.68533 , 0.0320798,-0.993789,0.106553 --23.6082 , -10.5738 , 3.13966 , -0.0446023,0.991503,-0.122202 --23.6538 , -10.495 , 3.59674 , 0.0788686,-0.988056,0.132379 --23.6751 , -10.4047 , 4.05252 , -0.0481337,0.979712,-0.194545 --23.706 , -10.3188 , 4.51104 , -0.0474622,0.978794,-0.199275 --23.7114 , -10.2218 , 4.96732 , -0.0465875,0.977224,-0.207035 --23.7283 , -10.1286 , 5.42658 , 0.051093,-0.9713,0.232305 --23.7373 , -10.0321 , 5.88629 , -0.0757068,-0.970754,0.227828 --23.6937 , -9.91282 , 6.33626 , -0.0819735,-0.973146,0.215098 --23.6608 , -9.7987 , 6.78905 , -0.00328624,-0.976154,0.217055 --23.3321 , -9.5612 , 7.16663 , -0.0579444,0.980375,-0.188434 --23.8228 , -9.66219 , 7.76047 , -0.000486186,-0.985929,0.167164 --23.821 , -9.55795 , 8.22983 , 0.0518339,-0.985352,0.162467 --23.8906 , -9.48212 , 8.72506 , 0.0613132,-0.98664,0.150941 --23.9074 , -9.38398 , 9.2086 , 0.0639639,-0.986828,0.148589 --9.90378 , -3.7859 , 4.72707 , -0.243122,0.676286,0.695363 --9.9113 , -3.74361 , 4.93723 , -0.643751,0.702577,0.303266 --9.70555 , -3.61883 , 5.0652 , -0.643751,0.702577,0.303266 --9.69843 , -3.56991 , 5.2691 , -0.643751,0.702577,0.303266 --8.89877 , -3.22523 , 5.13016 , 0.321837,-0.945946,-0.0401023 --8.62221 , -3.07992 , 5.19853 , -0.538759,0.841585,0.0383937 --8.69569 , -3.06515 , 5.42521 , 0.615796,0.63123,-0.471533 --8.53594 , -2.96419 , 5.54043 , -0.530685,-0.725678,0.437909 --8.57734 , -2.93649 , 5.7563 , -0.65546,-0.651164,0.382568 --8.63112 , -2.91179 , 5.98344 , -0.52298,-0.776577,0.351313 --8.35633 , -2.77264 , 6.03015 , 0.18486,0.764473,-0.617582 --8.42017 , -2.75088 , 6.26655 , -0.28043,-0.736219,0.615907 --8.32298 , -2.67352 , 6.41112 , 0.329159,0.667928,-0.667477 --8.19161 , -2.58525 , 6.53265 , -0.408901,-0.614186,0.674963 --8.0671 , -2.49917 , 6.65569 , 0.456582,0.703867,-0.544154 --7.96373 , -2.42194 , 6.79181 , -0.525254,-0.767738,0.366996 --7.91481 , -2.3605 , 6.96413 , -0.593636,-0.584202,0.553447 --7.93243 , -2.31936 , 7.18706 , -0.440347,-0.73874,0.510253 --7.77487 , -2.22494 , 7.28335 , 0.803644,-0.201412,-0.559991 --8.0386 , -2.25617 , 7.70442 , 0.787948,-0.584032,0.195049 --7.63882 , -2.08913 , 7.60931 , -0.682337,0.0731266,0.727371 --8.05341 , -2.15969 , 8.17728 , -0.781954,0.0545046,0.620948 --7.80181 , -2.03681 , 8.1989 , -0.521664,0.511583,0.682752 --7.6103 , -1.93183 , 8.26511 , -0.738392,0.395186,0.546448 --7.46105 , -1.83963 , 8.36611 , 0.991772,0.128007,-0.00158748 --7.63864 , -1.83385 , 8.77465 , -0.870934,-0.460227,0.172237 --8.22 , -1.92689 , 9.59738 , 0.748084,0.0673514,0.660177 --8.75106 , -1.99702 , 10.4133 , -0.883984,-0.111979,-0.453909 --8.76175 , -1.93313 , 10.7289 , -0.88605,0.161592,-0.434515 --7.4823 , -1.2377 , 11.1571 , 0.956773,-0.108563,-0.269813 --7.2692 , -1.12581 , 11.2115 , 0.555079,0.495526,0.668087 --4.87421 , -0.58317 , 8.55208 , -0.179206,-0.898165,-0.401477 --4.8214 , -0.519278 , 8.73071 , -0.240351,0.959102,-0.149517 --4.55528 , -0.424354 , 8.59435 , -0.240351,0.959102,-0.149517 --3.39402 , -0.214794 , 7.06035 , -0.633854,-0.581187,-0.510345 --3.26433 , -0.153613 , 7.06442 , 0.42571,0.0959564,0.899758 --4.87495 , -0.278188 , 9.94583 , -0.83772,-0.308959,0.450299 --4.95953 , -0.216281 , 10.4118 , -0.416369,0.652494,-0.633158 --4.84461 , -0.131834 , 10.551 , 0.799163,0.166196,-0.577683 --2.93123 , 0.0710223 , 7.37513 , -0.282638,-0.137517,0.949318 --2.8194 , 0.129868 , 7.40235 , -0.191705,-0.341516,0.920118 --2.0115 , 0.211913 , 6.04228 , -0.782103,-0.578307,0.232113 --2.04746 , 0.254317 , 6.31526 , 0.622832,0.580364,-0.524651 --1.96537 , 0.301927 , 6.3541 , -0.365905,-0.678806,0.63666 --1.89076 , 0.348596 , 6.40987 , -0.52907,0.293012,0.796385 --1.7832 , 0.394661 , 6.39062 , 0.746158,-0.118318,-0.655171 --1.98715 , 0.46142 , 7.12756 , 0.101672,0.546407,0.831325 --1.84112 , 0.50877 , 7.0338 , 0.057148,0.678272,0.732585 --1.72613 , 0.558639 , 7.01137 , -0.378515,0.825709,0.418248 --1.62909 , 0.608584 , 7.03374 , -0.0967837,-0.492818,0.864733 --1.54408 , 0.661565 , 7.09183 , -0.354964,-0.189258,0.915523 --1.39683 , 0.701443 , 6.95842 , -0.419498,-0.461335,-0.781787 --1.29529 , 0.748188 , 6.95553 , 0.207699,0.476901,0.854065 --1.1113 , 0.771138 , 6.66278 , -0.73808,-0.157269,-0.656128 --0.998629 , 0.809428 , 6.59695 , -0.0164522,-0.923082,0.384251 --0.964118 , 0.876107 , 6.82797 , 0.0388402,-0.0393271,-0.998471 --0.852146 , 0.913799 , 6.75842 , 0.413055,0.351366,0.840195 --0.703329 , 0.92985 , 6.51199 , 0.047125,-0.251634,-0.966675 --0.621728 , 0.977278 , 6.55443 , -0.493203,-0.00922268,0.869865 --0.525366 , 1.01401 , 6.51734 , 0.363772,0.199051,-0.909972 --0.439446 , 1.05879 , 6.53696 , -0.323284,-0.435473,0.840149 --0.399778 , 1.14811 , 6.85802 , -0.442398,-0.267152,0.856104 --0.280934 , 1.16453 , 6.67887 , 0.556812,0.58195,-0.592701 --0.193935 , 1.21314 , 6.71322 , -0.318851,0.947608,0.0193061 --0.0827494 , 1.22538 , 6.53013 , 0.0508532,0.807999,0.586985 --1.93803 , -1.18452 , -0.91781 , -0.0755099,0.253343,0.964425 --2.03744 , -1.22837 , -0.918702 , -0.0965298,0.227596,0.968959 --2.13805 , -1.27129 , -0.916505 , -0.0630492,0.210315,0.975598 --2.24766 , -1.3187 , -0.916328 , 0.106134,-0.17571,-0.978704 --2.37267 , -1.3742 , -0.922873 , 0.082026,-0.178318,-0.980548 --2.4916 , -1.42513 , -0.920435 , -0.0654413,0.168598,0.98351 --2.62722 , -1.48465 , -0.923572 , -0.0884941,0.161929,0.982826 --2.77198 , -1.54824 , -0.926881 , -0.0998136,0.145101,0.984369 --2.94115 , -1.62439 , -0.938835 , -0.076052,0.149642,0.985811 --3.08786 , -1.68646 , -0.932047 , -0.0699304,0.163397,0.984079 --3.26887 , -1.7656 , -0.937115 , -0.0859272,0.173486,0.981081 --3.44291 , -1.84014 , -0.931912 , 0.0919484,-0.162445,-0.982424 --3.67562 , -1.94446 , -0.94789 , -0.0877961,0.220873,0.971343 --3.84536 , -2.01344 , -0.925941 , -0.0305381,0.25739,0.965825 --4.06525 , -2.10791 , -0.919649 , -0.0493106,0.254481,0.96582 --4.27896 , -2.19641 , -0.902529 , -0.0522973,0.241861,0.968901 --4.54431 , -2.31032 , -0.897292 , 0.066685,-0.221537,-0.972869 --4.82819 , -2.43158 , -0.888895 , -0.076674,0.201737,0.976434 --5.16524 , -2.57795 , -0.887733 , -0.0815631,0.193197,0.977764 --5.54866 , -2.74371 , -0.888524 , -0.0802234,0.179014,0.98057 --5.97718 , -2.93059 , -0.888006 , 0.329496,0.313057,0.890745 --6.401 , -3.10977 , -0.870067 , -0.753455,0.460672,0.469135 --6.19613 , -2.97934 , -0.675293 , -0.967345,0.226104,-0.114546 --6.15367 , -2.92903 , -0.528899 , -0.949094,0.189408,-0.251685 --6.28598 , -2.96362 , -0.423117 , -0.921232,0.168295,-0.350725 --6.19392 , -2.89055 , -0.269843 , -0.874195,0.135016,-0.466427 --6.42993 , -2.97293 , -0.17888 , -0.950983,0.111711,-0.28836 --6.38719 , -2.92349 , -0.0363773 , -0.850476,0.118707,-0.512444 --6.42341 , -2.91191 , 0.0927549 , -0.833164,0.147002,-0.533131 --11.4816 , -5.20475 , -0.367045 , 0.0315339,0.39774,0.916956 --12.5087 , -5.62229 , -0.238154 , 0.0070379,0.365745,0.930688 --13.9201 , -6.20476 , -0.101976 , -0.0340542,0.267403,0.962983 --16.5471 , -7.31944 , 0.013271 , 0.203691,-0.0222314,0.978783 --20.2962 , -8.90936 , 0.179897 , 0.0833758,0.903351,0.42072 --24.6589 , -10.7384 , 0.471995 , -0.0671302,0.996184,-0.0557699 --24.9863 , -10.7785 , 0.941211 , 0.06235,-0.996625,0.0533962 --25.0577 , -10.7072 , 1.41759 , -0.165329,0.986065,0.018509 --25.058 , -10.6044 , 1.89297 , -0.157866,0.987419,-0.00901449 --27.1937 , -11.4038 , 2.47852 , -0.175855,0.984415,-0.0012269 --27.2801 , -11.3293 , 2.99818 , 0.157046,-0.984918,0.0726091 --27.2021 , -11.1855 , 3.50602 , -0.11665,-0.970942,0.20896 --27.2346 , -11.0881 , 4.02289 , -0.11609,-0.971587,0.206256 --27.2499 , -10.9836 , 4.53921 , -0.11609,-0.971587,0.206256 --27.2293 , -10.8636 , 5.05123 , 0.389544,-0.900269,0.194346 --27.2368 , -10.7556 , 5.56829 , 0.390384,-0.899916,0.1943 --27.2165 , -10.6362 , 6.08187 , 0.390357,-0.899923,0.19432 --27.2716 , -10.5454 , 6.61108 , -0.390359,0.899917,-0.194345 --25.2235 , -9.64143 , 6.68306 , -0.172417,0.960883,-0.216738 --27.3807 , -10.3614 , 7.6819 , -0.156893,0.963897,-0.215143 --27.3086 , -10.22 , 8.19139 , -0.139909,0.97345,-0.181166 --27.3909 , -10.1366 , 8.74377 , -0.139909,0.97345,-0.181166 --8.19343 , -2.9203 , 3.60737 , -0.582247,0.293746,0.758091 --8.39692 , -2.95844 , 3.83908 , 0.666075,0.412006,-0.621768 --8.12895 , -2.82464 , 3.92278 , 0.841178,-0.140025,-0.522315 --9.71879 , -3.35607 , 4.65426 , 0.471816,-0.407023,-0.782126 --9.61965 , -3.27709 , 4.81917 , -0.643751,0.702577,0.303266 --7.88918 , -2.63039 , 4.3403 , 0.986564,0.156988,0.045247 --8.47091 , -2.79426 , 4.75006 , -0.64448,0.695295,0.318135 --8.15039 , -2.64607 , 4.79372 , 0.0632189,-0.934271,0.350916 --8.98783 , -2.88798 , 5.35264 , -0.565427,0.824687,-0.0135437 --8.00449 , -2.51935 , 5.08248 , -0.986251,0.0566086,0.155255 --8.59395 , -2.67358 , 5.55486 , 0.667244,-0.74476,-0.0108378 --8.1561 , -2.49033 , 5.52266 , -0.916581,0.255199,-0.30782 --7.91566 , -2.37389 , 5.58099 , 0.994383,-0.0758253,0.0738463 --8.76053 , -2.59724 , 6.24083 , 0.750379,0.420587,-0.509939 --8.47871 , -2.46595 , 6.28336 , 0.444886,-0.854136,0.269311 --8.00707 , -2.27931 , 6.20141 , -0.204667,-0.698616,-0.6856 --8.22861 , -2.30281 , 6.53785 , 0.0919868,-0.974832,0.20308 --8.53219 , -2.3467 , 6.94144 , -0.217088,-0.890579,0.399678 --8.26961 , -2.22503 , 6.98049 , -0.115366,-0.857092,0.502079 --7.32237 , -1.91113 , 6.52996 , 0.849906,-0.504867,0.150892 --7.0602 , -1.79639 , 6.53509 , -0.842303,0.461382,-0.278662 --7.79985 , -1.95584 , 7.28424 , -0.871544,0.363155,0.329437 --7.70071 , -1.88231 , 7.42283 , -0.967493,0.164989,0.191667 --7.56133 , -1.79926 , 7.52876 , -0.783682,0.151018,0.602525 --7.63812 , -1.77169 , 7.81315 , -0.924771,0.36736,-0.0992227 --7.20935 , -1.61613 , 7.67202 , 0.994931,0.0648005,-0.0768952 --7.5084 , -1.63984 , 8.15804 , -0.949793,-0.159288,-0.269295 --7.80781 , -1.66033 , 8.66931 , 0.732717,0.669737,0.120744 --8.48048 , -1.75998 , 9.55878 , -0.812632,0.50506,-0.290764 --8.86104 , -1.78388 , 10.21 , 0.841394,0.362476,0.400833 --9.0278 , -1.75554 , 10.6794 , -0.971449,0.0530785,-0.231234 --7.39945 , -0.968343 , 11.055 , 0.956774,-0.108562,-0.269812 --7.28841 , -0.879428 , 11.2415 , 0.55508,0.495526,0.668087 --7.05933 , -0.772866 , 11.274 , -0.636852,-0.116089,-0.762196 --5.00539 , -0.428501 , 8.74584 , -0.240351,0.959102,-0.149517 --5.38479 , -0.417165 , 9.5582 , -0.0362762,-0.974246,0.222551 --3.46821 , -0.142322 , 6.98161 , 0.450092,-0.324484,-0.831942 --3.34278 , -0.0853496 , 6.99577 , -0.468322,0.338553,0.816123 --3.27084 , -0.0328528 , 7.09165 , 0.601649,-0.315567,-0.733782 --5.10303 , -0.123214 , 10.3546 , -0.508433,0.539392,-0.671232 --5.03244 , -0.0448416 , 10.5737 , 0.279804,-0.394615,0.875208 --3.04244 , 0.126421 , 7.37253 , -0.282638,-0.137517,0.949318 --2.94844 , 0.181661 , 7.43706 , -0.0693929,-0.43469,0.897903 --2.10991 , 0.249646 , 6.07114 , -0.86051,-0.508534,0.0302655 --1.97308 , 0.293525 , 5.99525 , -0.782103,-0.578307,0.232113 --2.01186 , 0.337363 , 6.27685 , 0.515256,0.439037,-0.736042 --1.94105 , 0.381791 , 6.3426 , 0.315022,0.533161,-0.785176 --1.89395 , 0.428464 , 6.4618 , 0.511847,0.509178,-0.691918 --1.78818 , 0.471617 , 6.45171 , -0.780276,0.169145,0.602129 --1.93149 , 0.538896 , 7.05079 , 0.101672,0.546407,0.831325 --1.81747 , 0.58612 , 7.03978 , -0.150049,0.0425219,0.987764 --1.72834 , 0.635817 , 7.09204 , -0.0194998,-0.141256,0.989781 --1.59873 , 0.678007 , 7.02977 , -0.186405,-0.241002,0.952455 --1.50598 , 0.727184 , 7.06865 , 0.50897,-0.393038,0.765814 --1.3495 , 0.759784 , 6.90612 , -0.250966,-0.416128,-0.873987 --1.20453 , 0.791132 , 6.75925 , 0.545103,-0.0124394,0.838277 --1.1046 , 0.833363 , 6.75294 , -0.127819,0.556452,-0.820989 --1.0129 , 0.876959 , 6.77378 , -0.0260277,-0.183883,0.982604 --0.901668 , 0.912959 , 6.71545 , -0.14617,-0.0889631,0.985251 --0.792446 , 0.947932 , 6.65483 , -0.782101,-0.114103,-0.612617 --0.661711 , 0.967635 , 6.48548 , -0.501169,-0.0245909,0.865 --0.589617 , 1.01799 , 6.57631 , 0.26204,0.164163,0.950992 --0.505172 , 1.0633 , 6.61698 , -0.199251,-0.220794,0.954751 --0.439353 , 1.12662 , 6.77297 , 0.852557,0.417143,-0.314862 --0.342653 , 1.1655 , 6.76183 , 0.191438,0.790709,0.58149 --0.244146 , 1.19951 , 6.71924 , -0.30156,-0.694733,0.653 --0.133954 , 1.21626 , 6.57699 , 0.108025,0.807948,-0.579268 --0.0440726 , 1.25553 , 6.57985 , -0.838721,-0.54007,0.0697939 --2.03776 , -1.14003 , -0.949163 , -0.0805909,0.210653,0.974233 --2.11734 , -1.16829 , -0.932262 , 0.0653839,-0.202954,-0.977003 --2.23441 , -1.21654 , -0.939956 , -0.0930945,0.199824,0.975399 --2.3454 , -1.2602 , -0.938569 , -0.0821097,0.154181,0.984625 --2.46544 , -1.30825 , -0.938716 , -0.0757992,0.154567,0.98507 --2.5943 , -1.35962 , -0.940107 , -0.0798141,0.174692,0.981383 --2.73229 , -1.41513 , -0.941961 , -0.0817556,0.146567,0.985817 --2.87822 , -1.47394 , -0.943869 , -0.0882805,0.13583,0.986791 --3.0429 , -1.54054 , -0.950038 , -0.073569,0.140558,0.987335 --3.20822 , -1.60687 , -0.950561 , -0.0756432,0.143522,0.986752 --3.40864 , -1.68888 , -0.962285 , -0.0776769,0.163188,0.983532 --3.58586 , -1.75803 , -0.955143 , -0.0922724,0.145402,0.98506 --3.83883 , -1.86371 , -0.976539 , -0.0642034,0.207909,0.976039 --4.00191 , -1.92262 , -0.948761 , -0.0373287,0.230497,0.972357 --4.25076 , -2.02217 , -0.950882 , -0.0640577,0.252675,0.965429 --4.48509 , -2.11265 , -0.937523 , -0.0457305,0.245544,0.968306 --4.75424 , -2.21862 , -0.929015 , -0.0618735,0.212067,0.975294 --5.07794 , -2.34761 , -0.929447 , -0.0680072,0.19372,0.978697 --5.42038 , -2.48339 , -0.924191 , -0.0596153,0.172532,0.983198 --5.82667 , -2.64577 , -0.925906 , -0.00228215,0.16803,0.985779 --6.28834 , -2.83033 , -0.928485 , -0.316465,0.255481,0.913553 --6.10833 , -2.71836 , -0.740954 , 0.887632,-0.404852,0.219555 --7.53289 , -3.3327 , -0.96171 , -0.120863,0.134766,0.983479 --6.11931 , -2.66619 , -0.477156 , -0.926685,0.21182,-0.310462 --6.16134 , -2.65666 , -0.354774 , -0.92698,0.184504,-0.326597 --6.29159 , -2.68643 , -0.248594 , -0.86654,0.290866,-0.405593 --6.31166 , -2.66737 , -0.119844 , -0.880923,0.268426,-0.389771 --6.31242 , -2.63891 , 0.01141 , -0.880923,0.268426,-0.389771 --11.8801 , -4.98737 , -0.590762 , -0.00864478,0.432553,0.901567 --12.2609 , -5.09794 , -0.398346 , -0.0203872,0.408221,0.912655 --13.4583 , -5.54791 , -0.26947 , -0.00972044,0.373974,0.927388 --15.4593 , -6.32232 , -0.157202 , 0.186092,0.337651,0.922692 --16.3204 , -6.61201 , 0.0924091 , 0.696185,-0.119979,0.707765 --16.4304 , -6.5901 , 0.401099 , 0.661482,-0.19428,0.72436 --16.8595 , -6.69677 , 0.706624 , 0.456888,-0.162111,0.874628 --29.0632 , -11.4964 , 1.01897 , 0.0690916,-0.997501,0.0147845 --29.0992 , -11.3945 , 1.56384 , 0.0870346,-0.995249,0.0436352 --29.0796 , -11.2709 , 2.10696 , 0.0870346,-0.995249,0.0436352 --30.3167 , -11.6344 , 2.717 , -0.0575847,0.997332,-0.0448668 --30.3728 , -11.5351 , 3.28575 , -0.0593803,0.996066,-0.0657697 --30.5491 , -11.4821 , 3.86772 , -0.0809532,0.991407,-0.102754 --30.5864 , -11.375 , 4.44083 , 0.36332,-0.911277,0.193837 --30.6035 , -11.2604 , 5.01356 , -0.0544788,-0.966984,0.248946 --30.6492 , -11.1555 , 5.59177 , -0.0605005,-0.962331,0.265063 --30.137 , -10.8468 , 6.08104 , -0.0456141,-0.970745,0.235742 --30.0064 , -10.6795 , 6.62296 , -0.0332337,-0.979525,0.198563 --30.0611 , -10.579 , 7.19935 , 0.0371914,-0.982096,0.184672 --30.0605 , -10.4571 , 7.76753 , 0.0555461,-0.986484,0.154157 --30.8322 , -10.6041 , 8.52319 , 0.284075,0.873587,-0.395154 --30.8464 , -10.484 , 9.11566 , 0.307619,0.839143,-0.448564 --8.42888 , -2.73953 , 3.5085 , 0.63835,-0.150753,-0.754839 --8.31599 , -2.6656 , 3.64515 , 0.723185,0.13933,-0.676455 --8.383 , -2.65162 , 3.83517 , 0.666075,0.412006,-0.621768 --8.07615 , -2.51378 , 3.90379 , 0.692404,0.490994,-0.528679 --8.00239 , -2.45545 , 4.04515 , -0.743949,-0.428285,0.512944 --7.98057 , -2.41219 , 4.20383 , 0.745155,0.636606,-0.198688 --8.08094 , -2.40832 , 4.41165 , -0.823604,-0.527703,-0.207862 --8.08901 , -2.3742 , 4.58682 , -0.959558,-0.143127,-0.24241 --8.21605 , -2.37603 , 4.81634 , -0.954517,-0.297253,0.0231858 --8.23414 , -2.3433 , 5.00321 , -0.909861,-0.187608,0.370075 --8.05687 , -2.25253 , 5.10045 , -0.921658,0.263325,0.284969 --8.04309 , -2.20957 , 5.2734 , 0.920237,-0.0307984,-0.390148 --7.89715 , -2.12901 , 5.38018 , 0.989827,-0.118948,0.0780698 --8.08178 , -2.14255 , 5.66181 , 0.990896,-0.0172919,0.133517 --8.05826 , -2.09631 , 5.8369 , 0.996046,0.0476849,0.0749603 --8.00497 , -2.04055 , 5.99716 , -0.873858,-0.461578,-0.1527 --7.46606 , -1.85391 , 5.8639 , 0.369706,-0.513191,-0.774567 --7.40366 , -1.79837 , 6.00865 , -0.469572,-0.359904,0.806208 --7.10152 , -1.68011 , 5.99746 , 0.628239,-0.575675,-0.523368 --6.93071 , -1.5982 , 6.06446 , -0.680536,0.568931,0.461723 --7.00859 , -1.57929 , 6.30077 , -0.846692,-0.455569,-0.274899 --7.21594 , -1.5892 , 6.63858 , -0.81578,0.169671,-0.552915 --7.47797 , -1.60979 , 7.03189 , -0.890956,0.444524,-0.0927083 --7.52002 , -1.5757 , 7.27268 , 0.733015,-0.677039,-0.0656327 --7.48731 , -1.52279 , 7.46052 , -0.951565,-0.222097,0.212594 --7.54887 , -1.49041 , 7.73057 , 0.937751,0.298684,0.177232 --7.70241 , -1.47503 , 8.08745 , 0.653039,0.632894,0.415915 --7.85281 , -1.45659 , 8.45774 , -0.628487,-0.742841,-0.230633 --8.14058 , -1.46227 , 8.96818 , 0.831305,-0.260871,0.490794 --8.52929 , -1.4831 , 9.5991 , -0.75993,0.511712,-0.40082 --8.65925 , -1.4478 , 10.0093 , 0.856745,-0.295251,0.422864 --8.77954 , -1.4073 , 10.4256 , -0.922513,0.215507,-0.320198 --8.09886 , -1.22125 , 10.0232 , 0.660191,-0.747053,0.0778391 --8.87907 , -1.29042 , 11.1591 , 0.520657,-0.847503,-0.103227 --7.30348 , -0.775999 , 10.6276 , -0.0489715,0.920202,0.388369 --7.23347 , -0.698148 , 10.8586 , 0.469968,0.702204,0.534827 --6.77077 , -0.572807 , 10.5819 , -0.31863,0.902731,-0.289054 --6.44981 , -0.468799 , 10.4688 , -0.507995,-0.617959,0.600057 --6.42301 , -0.397504 , 10.7534 , -0.49845,-0.700458,0.510791 --4.56922 , -0.159733 , 8.3993 , 0.0129824,0.665951,0.745882 --3.44574 , -0.0161627 , 6.96816 , -0.473836,0.3528,0.806853 --3.29794 , 0.0386521 , 6.94798 , -0.421725,0.404597,0.811449 --5.51836 , -0.0407096 , 10.7375 , -0.279804,0.394615,-0.875208 --3.43757 , 0.124875 , 7.61748 , 0.444219,-0.658083,0.607944 --5.05835 , 0.128151 , 10.6674 , 0.799163,0.166196,-0.577683 --4.86113 , 0.208382 , 10.6769 , 0.799163,0.166196,-0.577683 --4.80172 , 0.287648 , 10.9375 , 0.717884,-0.400621,0.569338 --2.03185 , 0.331112 , 5.95422 , -0.782103,-0.578307,0.232113 --2.10916 , 0.376118 , 6.3069 , 0.328763,0.464045,-0.822543 --2.08073 , 0.420682 , 6.46454 , 0.503965,0.116132,-0.855881 --1.98087 , 0.463583 , 6.47658 , 0.494497,0.39719,-0.773119 --1.88943 , 0.505691 , 6.50513 , -0.0615646,-0.539315,0.839851 --1.78951 , 0.546761 , 6.51348 , 0.365831,-0.0619862,0.928615 --1.83514 , 0.608031 , 6.88108 , -0.104155,0.827408,0.551858 --1.72237 , 0.649041 , 6.86902 , 0.894238,0.0482837,-0.444981 --1.67917 , 0.703601 , 7.04185 , -0.00987047,-0.312999,0.949702 --1.6316 , 0.759138 , 7.21448 , -0.142155,-0.681351,0.71802 --1.43479 , 0.781767 , 6.95071 , 0.237816,0.443901,0.863942 --1.3212 , 0.820896 , 6.92043 , -0.450809,0.704848,0.547687 --1.27063 , 0.878833 , 7.09808 , 0.73001,-0.393749,0.558613 --1.1376 , 0.910028 , 6.99703 , -0.130136,0.877518,0.461548 --0.965566 , 0.921199 , 6.72948 , -0.341357,0.69732,0.630254 --0.861167 , 0.956406 , 6.69971 , 0.32718,0.335309,0.883471 --0.720891 , 0.971239 , 6.50308 , -0.318684,0.0696001,0.945302 --0.639463 , 1.01464 , 6.55629 , -0.418279,-0.193754,0.887413 --0.54016 , 1.04668 , 6.52037 , 0.332884,0.351855,-0.874863 --0.461148 , 1.09301 , 6.58991 , 0.337321,0.748882,-0.57043 --0.430569 , 1.19051 , 6.99016 , 0.124201,0.956412,-0.264294 --0.283531 , 1.17622 , 6.64602 , 0.491444,0.622612,-0.608965 --0.187566 , 1.20961 , 6.62271 , 0.440075,0.894476,-0.0790378 --0.0856968 , 1.23009 , 6.52905 , -0.332685,0.69505,0.637359 --2.20442 , -1.10659 , -0.951656 , -0.0606954,0.21523,0.974675 --2.31554 , -1.14758 , -0.952733 , -0.0701508,0.19647,0.977997 --2.43643 , -1.19181 , -0.955759 , -0.0535669,0.193183,0.979699 --2.55783 , -1.23614 , -0.954794 , -0.0847738,0.172876,0.981289 --2.69666 , -1.28787 , -0.959722 , -0.0863458,0.181653,0.979565 --2.84439 , -1.34273 , -0.965019 , -0.0795418,0.175564,0.981249 --2.99345 , -1.3963 , -0.96567 , -0.0817528,0.150726,0.985189 --3.15956 , -1.45901 , -0.969948 , -0.0729585,0.146901,0.986457 --3.345 , -1.5271 , -0.977737 , -0.0952828,0.144236,0.984945 --3.54742 , -1.60293 , -0.987308 , -0.0793928,0.169795,0.982276 --3.75273 , -1.67873 , -0.99011 , 0.0929401,-0.160473,-0.982655 --3.98451 , -1.76467 , -0.997424 , -0.0528407,0.203038,0.977744 --4.2094 , -1.84574 , -0.993299 , -0.0688774,0.236901,0.969089 --4.42836 , -1.92179 , -0.978148 , -0.0528525,0.259462,0.964306 --4.67415 , -2.00855 , -0.96556 , -0.0339097,0.238139,0.970639 --4.96544 , -2.11395 , -0.960476 , -0.0616999,0.212736,0.97516 --5.29351 , -2.23273 , -0.957472 , -0.0430363,0.190051,0.980831 --5.64977 , -2.36077 , -0.951703 , 0.0614352,0.00049834,0.998111 --6.10584 , -2.52959 , -0.962869 , -0.131291,0.483034,0.865702 --6.75292 , -2.77536 , -1.01087 , 0.0546456,-0.357485,-0.932319 --7.74468 , -3.16067 , -1.12519 , 0.145429,-0.166877,-0.975194 --7.27661 , -2.93215 , -0.847238 , -0.44144,0.0246617,0.896952 --6.19145 , -2.39905 , -0.192455 , 0.806429,-0.392508,0.442278 --6.20124 , -2.37663 , -0.0656508 , -0.807173,0.390663,-0.442554 --7.35188 , -2.80391 , -0.10596 , 0.680472,0.275324,-0.679084 --12.4667 , -4.77074 , -0.607013 , 0.00659977,0.455762,0.890077 --13.1947 , -5.00178 , -0.442659 , 0.017753,0.470921,0.881997 --14.658 , -5.50871 , -0.318465 , -0.0295563,0.360594,0.932255 --16.2742 , -6.06255 , -0.152206 , -0.762108,-0.188371,-0.619442 --16.3594 , -6.02871 , 0.152453 , 0.975761,-0.115453,0.185907 --16.2514 , -5.92427 , 0.465833 , 0.975761,-0.115453,0.185907 --16.598 , -5.98718 , 0.7668 , -0.914328,0.199772,-0.352271 --32.3538 , -11.6507 , 1.1156 , -0.144519,0.98936,0.0167543 --32.3686 , -11.5304 , 1.71371 , -0.158352,0.987346,0.00851747 --35.2366 , -12.4266 , 2.42197 , -0.876719,-0.470277,0.101015 --35.1949 , -12.2757 , 3.06796 , -0.876719,-0.470277,0.101015 --35.1894 , -12.1386 , 3.7151 , -0.874591,-0.475112,0.0967423 --35.2118 , -12.01 , 4.36433 , 0.502137,0.859241,-0.0977867 --35.2312 , -11.8808 , 5.01469 , 0.0241161,-0.971914,0.234096 --35.2506 , -11.7513 , 5.66651 , -0.497899,0.85583,-0.140182 --35.1076 , -11.5669 , 6.29624 , -0.593491,0.791507,-0.145897 --32.515 , -10.577 , 6.51611 , 0.261738,0.959483,-0.104338 --35.3433 , -11.3713 , 7.64169 , -0.80234,0.570221,-0.176348 --35.5419 , -11.2969 , 8.34072 , -0.808938,0.542467,-0.226604 --35.533 , -11.1542 , 9.0038 , -0.808938,0.542467,-0.226604 --35.559 , -11.0226 , 9.6785 , -0.817396,0.526098,-0.234701 --8.59623 , -2.52436 , 3.38823 , -0.951713,-0.133388,0.276495 --8.63073 , -2.4994 , 3.56874 , -0.935212,-0.284171,-0.211246 --8.11006 , -2.30516 , 3.5871 , -0.554229,-0.525282,0.645685 --8.31479 , -2.33208 , 3.81568 , -0.0598862,-0.888395,0.455156 --8.48781 , -2.34722 , 4.04262 , -0.273206,-0.632948,0.724386 --8.27408 , -2.2494 , 4.1414 , -0.57993,-0.714442,0.391477 --8.21362 , -2.19571 , 4.29012 , 0.553757,0.755908,-0.349221 --8.15088 , -2.14183 , 4.43742 , -0.9295,0.130297,0.34504 --8.53269 , -2.21198 , 4.76783 , -0.674408,-0.723594,-0.14692 --7.98118 , -2.023 , 4.71155 , -0.933374,0.352882,-0.0654833 --8.22047 , -2.0503 , 4.99325 , 0.7822,0.175689,-0.597742 --7.93479 , -1.93728 , 5.03845 , 0.999929,-0.00833261,0.00852234 --7.9811 , -1.91267 , 5.23862 , -0.893775,-0.3396,0.292983 --8.03227 , -1.88756 , 5.4455 , -0.917611,-0.374177,-0.134098 --8.01924 , -1.84564 , 5.62264 , -0.791579,-0.57715,-0.200752 --8.16442 , -1.84227 , 5.89106 , -0.808014,-0.569067,-0.152567 --7.41635 , -1.62087 , 5.64835 , 0.265179,-0.487473,-0.831896 --7.36379 , -1.57063 , 5.79634 , -0.364613,-0.109234,0.92473 --7.45847 , -1.55494 , 6.03757 , -0.237724,-0.592246,0.769891 --7.13645 , -1.44191 , 6.01476 , -0.516163,0.586704,0.623983 --6.98742 , -1.37025 , 6.09756 , 0.601921,0.389507,0.697119 --7.37878 , -1.41705 , 6.55448 , 0.900213,0.42711,-0.0848196 --7.16679 , -1.33031 , 6.59775 , 0.677472,0.605605,-0.417463 --7.27833 , -1.31285 , 6.87804 , -0.936756,0.186601,0.296087 --7.03344 , -1.22066 , 6.89057 , 0.701299,0.135151,-0.699938 --8.14477 , -1.39595 , 7.98565 , -0.804417,-0.4886,-0.337909 --7.8401 , -1.28783 , 7.96913 , -0.333985,-0.78527,-0.52135 --7.5215 , -1.1803 , 7.93096 , 0.0859914,-0.0574096,-0.994641 --7.34844 , -1.10099 , 8.00838 , -0.304801,-0.16457,0.93809 --7.05692 , -1.00171 , 7.97406 , -0.309262,-0.0929973,0.946419 --7.81343 , -1.07895 , 8.92212 , -0.852153,0.421112,-0.310644 --8.00187 , -1.05417 , 9.36874 , -0.884479,0.466371,0.0139889 --7.90574 , -0.981046 , 9.54738 , -0.712707,0.624479,0.319492 --7.68931 , -0.890815 , 9.60264 , -0.831138,0.360898,0.423039 --7.6021 , -0.81972 , 9.79126 , 0.770754,-0.547571,-0.325737 --7.55723 , -0.75283 , 10.0306 , -0.035326,-0.909215,0.414825 --7.3554 , -0.666033 , 10.0975 , -0.873712,-0.205572,0.44087 --7.20523 , -0.58527 , 10.2205 , 0.717788,-0.137888,-0.682471 --7.15417 , -0.515806 , 10.4644 , 0.466409,-0.661835,-0.586888 --6.80655 , -0.414522 , 10.3396 , 0.284902,0.0110338,-0.958493 --6.68781 , -0.33822 , 10.4998 , 0.475417,0.34989,-0.80719 --6.56653 , -0.260863 , 10.6579 , 0.593614,0.695545,-0.404771 --3.62373 , 0.0112657 , 6.84715 , -0.477309,0.431609,0.765434 --3.47425 , 0.0624858 , 6.83191 , 0.464161,-0.553935,-0.691167 --3.43614 , 0.107822 , 6.97952 , 0.41787,-0.468377,-0.778465 --3.28106 , 0.15796 , 6.95056 , -0.536548,0.369361,0.758742 --3.50656 , 0.197451 , 7.53026 , 0.669629,-0.521518,0.528787 --3.33539 , 0.249226 , 7.48281 , -0.776229,0.437185,-0.454244 --4.96842 , 0.302282 , 10.5707 , 0.799163,0.166196,-0.577683 --4.85779 , 0.377448 , 10.736 , -0.829591,0.51381,-0.218581 --2.99634 , 0.400824 , 7.61568 , 0.236647,-0.183366,0.954136 --2.84828 , 0.449238 , 7.59028 , 0.291487,-0.223187,0.930174 --2.09388 , 0.458756 , 6.32329 , -0.261469,-0.506725,0.821501 --2.03852 , 0.501117 , 6.4265 , 0.479484,-0.0686013,-0.874865 --1.94687 , 0.540287 , 6.45634 , -0.0733522,-0.474305,0.877299 --1.81862 , 0.575989 , 6.40171 , 0.00513323,-0.16539,0.986215 --1.74931 , 0.617657 , 6.48278 , 0.307698,-0.405175,0.860904 --1.8629 , 0.69035 , 7.02694 , -0.0696174,0.733625,0.675979 --1.6837 , 0.71791 , 6.84699 , 0.65162,-0.425068,-0.628258 --1.71972 , 0.788338 , 7.2449 , -0.00454517,-0.504599,0.863342 --1.58534 , 0.824062 , 7.1825 , 0.654522,-0.0764987,0.752163 --1.5974 , 0.89962 , 7.56284 , 0.776414,0.565371,-0.278455 --1.24376 , 0.864531 , 6.78251 , 0.00589735,-0.772561,0.634913 --1.19069 , 0.918669 , 6.9499 , 0.469678,-0.65902,-0.587448 --1.08555 , 0.956469 , 6.94365 , -0.340212,0.755501,0.559888 --0.910737 , 0.959653 , 6.65612 , -0.474722,-0.0801343,-0.87648 --0.823964 , 1.00046 , 6.70322 , 0.619684,-0.132289,0.773623 --0.679722 , 1.00811 , 6.48682 , -0.39343,0.0859039,0.915333 --0.591964 , 1.04487 , 6.51055 , 0.247936,0.221254,0.943172 --0.513459 , 1.09046 , 6.59111 , -0.0523397,-0.861056,0.505809 --0.435553 , 1.13893 , 6.68989 , -0.884386,-0.20839,-0.417654 --0.350331 , 1.18444 , 6.75781 , -0.0637638,0.854538,0.515461 --0.255603 , 1.22035 , 6.76549 , 0.597376,-0.312483,0.738577 --0.131877 , 1.21574 , 6.52628 , 0.0560039,0.774931,0.62956 --0.0409781 , 1.25176 , 6.54003 , -0.243175,-0.927758,0.283074 --2.31211 , -1.05351 , -0.986572 , -0.0754713,0.210722,0.974628 --2.40239 , -1.0793 , -0.970513 , -0.0677674,0.239602,0.968503 --2.52489 , -1.12073 , -0.972132 , -0.10064,0.207153,0.973118 --2.67192 , -1.17212 , -0.985152 , 0.0874005,-0.198504,-0.976195 --2.79599 , -1.21153 , -0.978915 , -0.0882013,0.190499,0.977717 --2.95445 , -1.26548 , -0.987581 , -0.0890746,0.20929,0.973788 --3.10613 , -1.31593 , -0.986459 , -0.0789247,0.187361,0.979115 --3.28352 , -1.37546 , -0.993941 , -0.0939716,0.176791,0.979752 --3.47881 , -1.4426 , -1.00381 , -0.0957305,0.166812,0.981331 --3.68514 , -1.51182 , -1.01157 , -0.0926355,0.176977,0.979846 --3.9095 , -1.5883 , -1.02016 , -0.0749181,0.192454,0.978442 --4.13658 , -1.66362 , -1.0213 , -0.0762695,0.199115,0.977004 --4.41598 , -1.75939 , -1.03662 , -0.0604047,0.237837,0.969425 --4.62931 , -1.82494 , -1.01479 , -0.0682856,0.270971,0.960162 --4.88782 , -1.90852 , -1.00212 , -0.0487863,0.277906,0.959369 --5.19988 , -2.01146 , -0.999855 , -0.0357544,0.226468,0.973362 --5.50621 , -2.1088 , -0.984038 , 0.230267,0.149879,0.961516 --5.88526 , -2.23371 , -0.980264 , -0.158452,-0.0908182,0.983181 --6.47275 , -2.43672 , -1.02454 , -0.213641,0.377942,0.900842 --7.44516 , -2.78451 , -1.15268 , -0.178988,0.198406,0.963638 --7.44421 , -2.75202 , -0.994867 , -0.243439,0.0517007,0.968537 --7.39496 , -2.70114 , -0.827437 , -0.243439,0.0517007,0.968537 --5.92067 , -2.11612 , -0.354183 , 0.890017,-0.289383,0.352317 --5.92223 , -2.09126 , -0.231119 , 0.792213,-0.555239,0.253196 --6.04313 , -2.10974 , -0.130284 , -0.770039,0.554457,-0.315623 --6.13372 , -2.1172 , -0.0211493 , -0.770039,0.554457,-0.315623 --13.1355 , -4.61085 , -0.88373 , -0.00361604,-0.473264,-0.880913 --13.1901 , -4.57856 , -0.636268 , -0.00361602,-0.473264,-0.880913 --14.1806 , -4.87459 , -0.485731 , -0.0292068,0.504943,0.862658 --16.2057 , -5.5243 , -0.388722 , -0.928194,0.0387657,-0.370072 --16.2747 , -5.48466 , -0.0874591 , 0.993097,0.110717,-0.038729 --16.2252 , -5.40465 , 0.220712 , 0.981154,0.185123,0.0553662 --16.2265 , -5.3424 , 0.524377 , -0.95588,-0.0670621,-0.286002 --17.892 , -5.8349 , 0.805918 , 0.363287,0.127879,0.922859 --17.8377 , -5.74806 , 1.13757 , 0.256556,0.19082,0.947505 --39.1559 , -12.6268 , 1.96674 , -0.362923,0.931709,-0.0143638 --39.8816 , -12.7131 , 2.70998 , 0.684353,0.0947961,-0.722963 --35.7822 , -11.2583 , 3.19244 , -0.866402,-0.492628,0.0816432 --35.7044 , -11.0985 , 3.83818 , 0.858751,0.506917,-0.0747064 --39.8471 , -12.253 , 4.88385 , -0.352992,-0.247265,0.902362 --37.0836 , -11.2539 , 5.29683 , -0.316672,-0.861776,-0.39631 --34.2665 , -10.2584 , 5.60404 , -0.189068,-0.396649,0.898289 --34.175 , -10.1012 , 6.21828 , -0.301757,-0.495293,0.814633 --34.3856 , -9.90286 , 7.51585 , -0.920836,0.389867,-0.00808989 --34.2806 , -9.74034 , 8.13103 , -0.866592,0.487192,-0.107995 --34.3349 , -9.62467 , 8.78101 , -0.853022,0.516422,-0.075254 --34.7998 , -9.62213 , 9.53492 , 0.81778,-0.5221,0.242174 --34.9045 , -9.51576 , 10.2167 , -0.795722,0.562486,-0.224582 --10.6229 , -2.74459 , 4.13036 , -0.366721,-0.014849,0.930212 --10.5725 , -2.68746 , 4.32423 , -0.228281,-0.0661468,0.971346 --8.80781 , -2.17535 , 3.97709 , 0.420487,0.7181,-0.554548 --8.66529 , -2.10167 , 4.10746 , 0.0837155,0.923013,-0.375551 --8.40275 , -1.99704 , 4.19097 , -0.453703,-0.74578,0.487818 --9.17819 , -2.15756 , 4.654 , -0.200192,-0.955124,0.218314 --8.85402 , -2.03774 , 4.71718 , -0.401443,-0.837834,0.36997 --7.90784 , -1.76715 , 4.51266 , -0.939884,0.19091,0.283145 --8.45708 , -1.86495 , 4.92009 , -0.361894,-0.468214,0.806107 --7.91029 , -1.69771 , 4.8547 , -0.9271,-0.0519067,-0.371203 --8.19016 , -1.72669 , 5.16089 , -0.481946,-0.834884,0.265887 --8.19002 , -1.68898 , 5.34285 , 0.633689,0.72531,-0.269005 --8.57807 , -1.73776 , 5.7283 , -0.658995,-0.749508,-0.0629601 --8.41233 , -1.66109 , 5.83496 , -0.853673,-0.447264,0.266829 --8.3057 , -1.59741 , 5.97048 , -0.59293,-0.0825616,0.80101 --7.74574 , -1.43939 , 5.84093 , -0.240818,-0.407047,0.88109 --8.63258 , -1.58334 , 6.56492 , -0.975149,-0.165533,-0.14725 --6.9619 , -1.20345 , 5.72629 , 0.688078,-0.237016,-0.685837 --7.04625 , -1.184 , 5.95747 , -0.822263,-0.446299,-0.353129 --7.34706 , -1.2032 , 6.34151 , -0.905392,-0.279257,-0.319814 --7.45824 , -1.18458 , 6.61261 , -0.930184,-0.136687,0.340695 --7.33167 , -1.12111 , 6.72026 , -0.842023,-0.137392,0.521652 --7.1475 , -1.04659 , 6.78284 , -0.842023,-0.137392,0.521652 --7.89541 , -1.13214 , 7.56423 , -0.872961,-0.431231,-0.22799 --7.99386 , -1.10229 , 7.86921 , 0.0601348,-0.278711,-0.958491 --7.69517 , -1.00588 , 7.85499 , 0.408018,-0.246225,-0.879144 --7.43661 , -0.918692 , 7.86484 , 0.372863,0.00918141,-0.927841 --7.27701 , -0.847455 , 7.95315 , -0.309262,-0.0929976,0.946419 --7.17419 , -0.785393 , 8.09152 , 0.981158,0.162131,-0.105086 --7.4153 , -0.768904 , 8.55684 , 0.925602,-0.303145,0.226638 --7.21013 , -0.690711 , 8.60648 , -0.844167,-0.524826,0.109275 --7.76853 , -0.706421 , 9.42414 , -0.709752,0.465175,0.529023 --7.73719 , -0.645143 , 9.67095 , -0.773874,0.509231,0.376567 --7.49782 , -0.559987 , 9.69874 , -0.837299,0.358154,0.413106 --7.49176 , -0.49984 , 9.98082 , -0.826985,-0.108893,0.551578 --7.64095 , -0.451032 , 10.4534 , -0.949043,-0.271304,0.160347 --7.32899 , -0.360334 , 10.3971 , -0.10044,-0.394001,0.913606 --7.54279 , -0.310124 , 10.9766 , -0.879142,0.213668,0.425977 --6.85806 , -0.194833 , 10.4404 , -0.487398,-0.536271,0.689098 --6.94687 , -0.134146 , 10.8803 , -0.489255,-0.415677,0.766708 --6.69335 , -0.0513521 , 10.873 , 0.593614,0.695545,-0.404771 --3.48589 , 0.143126 , 6.67983 , 0.555627,-0.697462,-0.452576 --3.46197 , 0.184852 , 6.84374 , 0.464161,-0.553935,-0.691166 --3.32369 , 0.229919 , 6.84119 , -0.424958,0.445851,0.787799 --3.10537 , 0.274468 , 6.70883 , -0.908049,0.412208,0.0743707 --3.27968 , 0.318932 , 7.20139 , 0.987869,-0.0983362,0.120187 --3.20898 , 0.365621 , 7.3134 , -0.905874,-0.422015,0.0360048 --4.9622 , 0.47079 , 10.6305 , -0.829591,0.51381,-0.218581 --3.12185 , 0.462978 , 7.64882 , 0.106023,0.138434,0.98468 --2.92942 , 0.505491 , 7.54666 , -0.178256,-0.133589,-0.974874 --2.20406 , 0.504924 , 6.37877 , 0.510394,0.163334,-0.844287 --2.07615 , 0.538756 , 6.34006 , 0.510394,0.163334,-0.844287 --2.00998 , 0.577861 , 6.42527 , 0.584278,0.311992,-0.749186 --1.97421 , 0.622558 , 6.5822 , -0.763016,-0.50299,0.405964 --1.95364 , 0.671103 , 6.78513 , -0.731921,0.607396,0.308807 --1.93349 , 0.723651 , 7.00686 , -0.645701,-0.759494,-0.0789883 --1.7412 , 0.744815 , 6.80158 , 0.0108898,0.783965,0.620709 --1.77652 , 0.813112 , 7.19005 , -0.282762,-0.637011,-0.717121 --1.67158 , 0.853008 , 7.21394 , 0.232381,0.117427,-0.96551 --1.57845 , 0.896935 , 7.27356 , 0.404374,-0.318229,0.857445 --1.34302 , 0.893717 , 6.8857 , -0.712485,0.643159,0.280558 --1.22271 , 0.923823 , 6.83514 , -0.547046,0.577254,-0.606232 --1.14992 , 0.96962 , 6.94534 , -0.223236,0.854627,0.468806 --1.03651 , 1.00036 , 6.90984 , 0.191109,0.648431,0.736896 --0.896571 , 1.01482 , 6.75665 , 0.589899,-0.138589,0.795495 --0.760768 , 1.02761 , 6.60055 , -0.698178,-0.166402,-0.696318 --0.650011 , 1.04943 , 6.52904 , -0.382013,-0.269263,0.884061 --0.553757 , 1.08011 , 6.52343 , -0.272147,-0.272983,0.922722 --0.535729 , 1.17554 , 6.95446 , -0.355394,-0.93168,0.0752775 --0.411117 , 1.18608 , 6.80964 , 0.170926,0.950666,0.25888 --0.290695 , 1.19405 , 6.65246 , -0.528852,-0.533364,0.66018 --0.186725 , 1.21345 , 6.5814 , -0.0575584,-0.997919,0.0290669 --0.0874393 , 1.23554 , 6.52789 , 0.341247,-0.554878,-0.758723 --2.51234 , -1.01691 , -1.00379 , -0.0503331,0.254498,0.965763 --2.62769 , -1.05038 , -0.99897 , -0.0740851,0.227399,0.97098 --2.77688 , -1.09671 , -1.01052 , 0.0760637,-0.2057,-0.975654 --2.92048 , -1.14033 , -1.01239 , -0.0941509,0.197885,0.975693 --3.07253 , -1.1851 , -1.01474 , 0.0834828,-0.20926,-0.97429 --3.23377 , -1.23377 , -1.01648 , -0.0693355,0.206963,0.975889 --3.4136 , -1.28907 , -1.0217 , -0.093464,0.188537,0.977609 --3.62119 , -1.35266 , -1.03422 , -0.104916,0.176021,0.97878 --3.85519 , -1.4265 , -1.05173 , -0.104453,0.181644,0.977801 --4.0833 , -1.49521 , -1.05773 , -0.0792093,0.188514,0.978871 --4.32184 , -1.56684 , -1.05983 , -0.0864769,0.202704,0.975414 --4.62287 , -1.66022 , -1.07936 , -0.0884304,0.242411,0.966135 --4.83081 , -1.71624 , -1.05075 , -0.0571833,0.262294,0.963292 --5.11849 , -1.80035 , -1.04507 , -0.0136152,0.268056,0.963307 --5.41679 , -1.88673 , -1.03267 , -0.0864026,-0.242309,-0.966344 --5.71801 , -1.97139 , -1.0104 , 0.137469,0.452081,0.88132 --5.75873 , -1.96086 , -0.896779 , -0.208334,0.965602,-0.155596 --5.76914 , -1.93928 , -0.774765 , -0.169508,-0.971963,0.162955 --5.77832 , -1.91705 , -0.653216 , -0.973959,-0.0779489,-0.212903 --5.78529 , -1.89444 , -0.532207 , -0.983813,-0.106875,-0.14384 --5.78907 , -1.87162 , -0.41152 , -0.964292,-0.0449812,-0.260994 --5.80114 , -1.85049 , -0.293639 , 0.997929,0.0628277,0.0137956 --5.80146 , -1.82666 , -0.174054 , 0.979701,0.0700742,-0.187818 --5.79934 , -1.80149 , -0.055206 , -0.976208,0.183586,-0.115387 --5.83224 , -1.78892 , 0.0572999 , 0.939868,-0.323643,0.109102 --13.9931 , -4.4192 , -0.938995 , 0.010968,0.252367,0.967569 --14.0954 , -4.39779 , -0.684406 , -0.210872,-0.211976,0.954253 --15.722 , -4.86089 , -0.579501 , 0.504683,0.138951,0.852049 --16.5051 , -5.04655 , -0.34819 , 0.764445,0.558564,0.321916 --16.2662 , -4.90951 , -0.0252252 , -0.943463,-0.331281,0.0114352 --16.5186 , -4.92536 , 0.26566 , 0.840505,0.519664,0.153304 --16.5456 , -4.87116 , 0.570769 , 0.840504,0.519664,0.153304 --42.5285 , -12.5897 , 0.628234 , 0.456342,-0.0236678,-0.88949 --42.5807 , -12.4487 , 1.39775 , 0.456342,-0.0236679,-0.88949 --36.278 , -10.4512 , 2.00166 , -0.802456,-0.59602,0.028721 --36.3603 , -10.3404 , 2.66053 , -0.786668,-0.616847,-0.0255763 --36.2957 , -10.1895 , 3.31356 , 0.719314,0.690669,0.0745926 --36.4608 , -10.1023 , 3.9823 , 0.702881,0.680636,-0.206622 --39.0418 , -10.6842 , 4.89277 , -0.0419777,0.309313,0.950033 --36.3542 , -9.80422 , 5.28887 , -0.466637,-0.5881,0.660598 --34.4262 , -9.14876 , 5.69141 , 0.581225,-0.103096,-0.807186 --35.5042 , -9.30847 , 6.48078 , -0.436587,-0.879896,0.187549 --34.6588 , -8.95408 , 6.98559 , -0.954929,0.276691,0.107483 --32.8033 , -8.22019 , 7.87732 , -0.875757,0.38932,0.285448 --33.614 , -8.30125 , 8.66607 , -0.796856,0.592001,0.120644 --33.8249 , -8.22541 , 9.34226 , 0.819901,-0.572125,0.0208576 --33.2032 , -7.94439 , 9.81377 , 0.819901,-0.572125,0.0208575 --11.265 , -2.53648 , 4.32087 , 0.535847,0.319731,-0.781435 --10.6302 , -2.34156 , 4.3522 , 0.184262,-0.0357189,-0.982228 --10.0898 , -2.17215 , 4.3911 , 0.530369,-0.107057,-0.84098 --10.2077 , -2.15902 , 4.63262 , 0.789831,-0.609882,-0.0648915 --34.3471 , -7.41624 , 14.0795 , -0.798435,0.559846,-0.221529 --10.2418 , -2.03842 , 5.26974 , -0.876206,0.462023,-0.137104 --10.169 , -1.97954 , 5.45315 , -0.879585,0.442097,-0.175729 --12.0123 , -2.32223 , 6.46758 , 0.225304,-0.939571,0.257769 --8.4938 , -1.54873 , 5.12398 , 0.846615,0.531986,0.0152951 --8.47567 , -1.50703 , 5.30114 , 0.993648,0.108459,0.0300219 --8.46342 , -1.46607 , 5.48286 , -0.921721,-0.384478,-0.0510607 --10.1111 , -1.74425 , 6.52524 , -0.860663,0.506699,0.0501542 --8.32402 , -1.36195 , 5.79177 , -0.889141,0.0975073,0.447124 --8.08616 , -1.27908 , 5.85234 , 0.241926,-0.290054,0.925927 --8.07894 , -1.23878 , 6.0401 , 0.241926,-0.290054,0.925927 --7.11312 , -1.03053 , 5.64966 , 0.903541,0.236064,0.357615 --7.25843 , -1.01887 , 5.91732 , -0.843321,-0.378825,-0.381185 --7.35581 , -0.998185 , 6.16422 , -0.894674,-0.324704,-0.306801 --7.2253 , -0.939108 , 6.26555 , -0.910978,-0.360003,-0.201289 --7.3539 , -0.919583 , 6.54553 , 0.992588,0.0957062,-0.0748927 --7.33886 , -0.877267 , 6.73209 , -0.961725,-0.168393,0.21617 --7.62873 , -0.878026 , 7.15224 , -0.750843,-0.264536,-0.605191 --7.95474 , -0.87986 , 7.62032 , -0.934736,-0.125666,0.332381 --7.80237 , -0.812612 , 7.72636 , -0.218267,-0.195888,0.956027 --7.81031 , -0.766895 , 7.96265 , -0.159212,-0.300219,0.940489 --7.45771 , -0.675942 , 7.8953 , -0.383779,-0.30762,0.87068 --7.34655 , -0.615705 , 8.02977 , -0.326459,-0.219772,0.919307 --7.16797 , -0.547433 , 8.10115 , -0.778522,-0.501817,0.376939 --6.12148 , -0.391205 , 7.34341 , -0.928306,-0.224589,0.296323 --7.83987 , -0.514579 , 9.24537 , 0.75995,-0.382904,-0.525224 --6.57996 , -0.344979 , 8.23964 , -0.476639,0.791054,0.383468 --6.43505 , -0.283551 , 8.32897 , 0.150542,0.150289,0.977113 --7.34512 , -0.302688 , 9.56114 , -0.819691,0.3935,0.416251 --7.15954 , -0.231573 , 9.63939 , -0.93089,-0.365297,-0.00129304 --7.37705 , -0.185819 , 10.1828 , -0.731925,-0.184592,0.655905 --7.29201 , -0.11875 , 10.39 , -0.137094,0.269974,0.953058 --7.00631 , -0.0412402 , 10.3552 , -0.51405,-0.192577,0.835863 --3.49211 , 0.151381 , 6.16489 , -0.266535,-0.0476635,0.962646 --3.42572 , 0.189202 , 6.25432 , -0.394807,-0.0671812,0.916305 --3.5169 , 0.224971 , 6.56107 , -0.626499,0.777163,0.0593081 --3.53458 , 0.264655 , 6.78197 , 0.51706,-0.747937,-0.41622 --3.21598 , 0.3051 , 6.51657 , -0.585452,0.781834,0.214431 --3.22895 , 0.346381 , 6.7356 , 0.993407,0.0988371,-0.0580782 --3.21515 , 0.38805 , 6.92262 , -0.976453,0.0771934,0.201448 --3.09672 , 0.429108 , 6.94797 , -0.993112,0.0715101,0.0928146 --3.13473 , 0.4767 , 7.23844 , -0.989171,-0.0175756,-0.145713 --3.22385 , 0.530746 , 7.63579 , 0.0738873,0.170552,0.982575 --3.08113 , 0.572636 , 7.63336 , 0.0169535,-0.00226413,0.999854 --4.4423 , 0.753277 , 10.506 , -0.717884,0.400621,-0.569338 --2.17543 , 0.587015 , 6.37809 , 0.443585,0.476898,-0.758815 --2.2205 , 0.638428 , 6.69883 , 0.505062,0.8148,0.28463 --2.02544 , 0.660889 , 6.52337 , -0.89886,-0.291324,0.327387 --1.98678 , 0.704984 , 6.68086 , -0.809894,-0.1204,0.574086 --1.91129 , 0.74366 , 6.76501 , 0.358291,0.498431,0.789427 --1.80777 , 0.778471 , 6.78295 , 0.00745767,0.632761,0.774312 --1.89402 , 0.857101 , 7.29214 , 0.385833,0.443112,-0.809188 --1.73822 , 0.881897 , 7.18744 , -0.0146792,0.696588,0.717321 --1.66425 , 0.927894 , 7.30509 , -0.351901,-0.485047,0.800559 --1.35732 , 0.9001 , 6.72202 , 0.797495,-0.369814,0.476697 --1.39074 , 0.980647 , 7.16677 , 0.529977,-0.492307,0.690476 --1.17908 , 0.97323 , 6.82147 , 0.829643,-0.448923,-0.331904 --1.09542 , 1.01347 , 6.89252 , 0.324154,-0.639656,-0.696968 --0.96414 , 1.03102 , 6.78948 , 0.347867,-0.362179,0.864763 --0.855734 , 1.05709 , 6.76094 , 0.339194,-0.0625436,0.938635 --0.699403 , 1.05198 , 6.50762 , -0.520447,0.14133,-0.842117 --0.611597 , 1.08571 , 6.54211 , 0.0069751,0.662498,0.749031 --0.451801 , 1.06254 , 6.19568 , -0.0974927,0.724279,0.68258 --0.460847 , 1.17904 , 6.78214 , 0.818711,0.57071,0.0632591 --0.34286 , 1.18878 , 6.65593 , 0.0379986,-0.254889,0.966223 --0.296899 , 1.27943 , 7.03647 , -0.00780617,0.974005,0.22639 --0.127878 , 1.21378 , 6.46586 , -0.0426125,-0.978035,0.204037 --0.0467829 , 1.26225 , 6.58872 , 0.674029,-0.623067,0.396828 --2.49522 , -0.915007 , -1.03417 , -0.0469311,0.22842,0.972431 --2.61194 , -0.946423 , -1.03124 , -0.0670677,0.205443,0.976368 --2.72966 , -0.975882 , -1.02514 , -0.0635184,0.190136,0.979701 --2.87289 , -1.01499 , -1.03016 , -0.101885,0.1882,0.976832 --3.05009 , -1.06659 , -1.0499 , -0.0856444,0.188187,0.978392 --3.19621 , -1.10406 , -1.04544 , -0.0711313,0.192483,0.978719 --3.36897 , -1.15048 , -1.05009 , -0.0897495,0.194249,0.976838 --3.56013 , -1.20244 , -1.05784 , -0.098432,0.183597,0.978061 --3.76876 , -1.25997 , -1.06769 , -0.103355,0.172959,0.979491 --3.9981 , -1.32314 , -1.07883 , -0.0921211,0.165867,0.981836 --4.24602 , -1.39124 , -1.09035 , -0.070681,0.182652,0.980634 --4.48733 , -1.45533 , -1.08984 , -0.108565,0.18593,0.976547 --4.87249 , -1.56755 , -1.13863 , -0.0530481,0.232952,0.97104 --5.07291 , -1.61339 , -1.1026 , -0.0133746,0.270605,0.962597 --5.33884 , -1.68001 , -1.0829 , 0.00629858,0.258386,0.966021 --5.6226 , -1.75114 , -1.06064 , -0.242004,-0.335273,-0.910509 --6.0266 , -1.85938 , -1.06711 , -0.38863,0.343977,0.854779 --6.98126 , -2.14434 , -1.2258 , -0.0835908,-0.469015,-0.879226 --7.35661 , -2.23607 , -1.18432 , -0.560042,0.134171,0.817528 --7.11412 , -2.1282 , -0.967259 , -0.377738,0.567968,0.73125 --7.08008 , -2.08765 , -0.812093 , -0.377738,0.567968,0.73125 --5.96896 , -1.71369 , -0.417316 , 0.98128,0.0771957,0.176437 --5.9047 , -1.66896 , -0.281913 , 0.997081,0.0691085,-0.0324449 --5.96014 , -1.66189 , -0.172208 , 0.989718,0.115291,-0.0846512 --12.7003 , -3.65459 , -1.19 , 0.00651811,0.371668,0.928343 --14.2864 , -4.07484 , -1.18478 , 0.550888,-0.151733,-0.82067 --15.0498 , -4.24336 , -1.01457 , -0.0983083,0.471613,0.876309 --15.3733 , -4.27925 , -0.768449 , -0.0040363,0.64192,0.766761 --16.9682 , -4.67571 , -0.633678 , 0.744771,0.640573,-0.187037 --16.6255 , -4.51647 , -0.292473 , -0.490402,-0.860975,-0.135008 --16.4877 , -4.4159 , 0.0227712 , -0.710134,-0.704066,-0.000509294 --17.0958 , -4.52175 , 0.300692 , -0.509358,-0.836857,-0.200563 --17.4497 , -4.55473 , 0.605563 , 0.418329,0.546193,0.725723 --42.6399 , -11.2077 , 0.763684 , 0.616629,0.00730093,-0.78722 --36.8841 , -9.40742 , 2.12474 , 0.719314,0.690669,0.0745926 --37.4445 , -9.41712 , 2.81189 , 0.740025,0.670306,-0.0552575 --37.5482 , -9.30868 , 3.48953 , 0.659881,0.719364,-0.216963 --37.6787 , -9.20598 , 4.17336 , -0.366189,0.928508,-0.0614631 --37.0335 , -8.9122 , 4.78518 , 0.970047,-0.233518,-0.0669233 --36.5624 , -8.66485 , 5.39563 , 0.837405,-0.521699,-0.163043 --37.0038 , -8.50312 , 6.78305 , 0.749042,-0.283755,-0.598681 --33.7027 , -7.60622 , 6.88963 , -0.79119,-0.12563,0.598528 --33.3011 , -7.39125 , 7.42822 , 0.803963,-0.297441,-0.514948 --11.5597 , -2.4033 , 3.53647 , -0.635444,0.771115,0.0399037 --11.4401 , -2.33325 , 3.72835 , 0.708112,-0.706051,0.00836346 --11.2787 , -2.25421 , 3.90713 , 0.683549,-0.729673,-0.0183775 --11.5511 , -2.2689 , 4.19493 , -0.494172,0.218459,0.841469 --11.2694 , -2.16486 , 4.33899 , -0.495092,0.377275,0.782655 --10.3278 , -1.92764 , 4.27724 , 0.43593,-0.131717,-0.89029 --10.1485 , -1.85118 , 4.42432 , -0.568793,0.0330277,0.821817 --9.90298 , -1.7612 , 4.54358 , -0.896719,0.277863,0.344512 --9.87758 , -1.71639 , 4.73425 , -0.862058,0.500566,-0.0793081 --10.1354 , -1.72521 , 5.03219 , -0.887808,0.399667,-0.228173 --9.99162 , -1.65686 , 5.18401 , -0.887808,0.399667,-0.228173 --7.24701 , -1.05168 , 4.56672 , 0.537605,-0.0681916,-0.840435 --8.44994 , -1.22474 , 5.29954 , -0.951073,0.306107,0.0419354 --10.0396 , -1.44986 , 6.2769 , -0.823148,0.564822,0.0583301 --9.85185 , -1.37449 , 6.40359 , 0.773964,-0.6022,-0.195794 --9.76726 , -1.3165 , 6.5816 , -0.0897923,0.566419,0.819211 --8.44351 , -1.06893 , 6.0636 , -0.513324,0.383894,-0.767544 --7.96074 , -0.957519 , 5.98189 , -0.149173,0.498552,-0.853928 --8.12719 , -0.942476 , 6.27611 , 0.288811,-0.718373,0.632873 --7.4812 , -0.812435 , 6.06883 , 0.335464,0.931814,-0.138517 --7.3498 , -0.757287 , 6.17255 , -0.910978,-0.360003,-0.201289 --8.28738 , -0.840204 , 6.99842 , -0.617387,-0.661745,0.425355 --8.80255 , -0.860523 , 7.57694 , 0.497835,0.677518,0.541415 --7.71458 , -0.68337 , 7.02037 , -0.509855,-0.807706,0.296072 --7.60161 , -0.628175 , 7.14789 , 0.630437,0.775409,0.03592 --8.18593 , -0.648013 , 7.81839 , 0.62149,0.185525,-0.761138 --7.78033 , -0.559306 , 7.72754 , -0.187331,-0.249623,0.95005 --7.89345 , -0.523729 , 8.05274 , -0.175125,-0.143337,0.974056 --7.59015 , -0.447824 , 8.03127 , 0.299581,-0.0711729,-0.951412 --6.31389 , -0.290026 , 7.13004 , -0.490179,-0.0293985,0.871126 --6.15562 , -0.23583 , 7.19034 , 0.723417,0.0921603,-0.684233 --7.84578 , -0.318608 , 9.01267 , -0.828366,-0.0780356,0.554726 --6.61978 , -0.181872 , 8.07145 , 0.150542,0.150289,0.977113 --6.39824 , -0.120804 , 8.08341 , -0.166547,0.651193,0.740412 --7.58161 , -0.136227 , 9.56935 , 0.760225,-0.63087,0.15512 --7.62328 , -0.0809151 , 9.90282 , -0.984926,-0.00515345,-0.172901 --7.52293 , -0.016521 , 10.09 , -0.951908,-0.0751796,0.297018 --7.5546 , 0.0440553 , 10.4355 , 0.552302,-0.413478,-0.723877 --3.76761 , 0.197215 , 6.18839 , -0.097552,-0.0240854,0.994939 --3.63846 , 0.234679 , 6.20415 , -0.217509,0.018559,0.975882 --3.50294 , 0.271461 , 6.20902 , -0.209656,-0.0205515,0.977559 --3.41144 , 0.306985 , 6.26671 , -0.554052,0.0689884,0.829619 --3.33586 , 0.343721 , 6.34669 , -0.809532,0.23104,0.539702 --3.30442 , 0.380647 , 6.49138 , -0.692846,0.709955,0.126206 --3.20705 , 0.417005 , 6.5449 , -0.817109,-0.541252,0.198444 --3.25698 , 0.459696 , 6.82284 , -0.886427,-0.249277,0.390011 --3.17033 , 0.498445 , 6.90041 , 0.843083,0.175325,-0.508402 --3.17066 , 0.542408 , 7.12214 , -0.958095,0.136965,-0.251585 --3.29944 , 0.59957 , 7.57833 , -0.213983,0.299767,0.929705 --3.15983 , 0.638164 , 7.58669 , 0.311277,-0.282695,-0.907298 --3.03121 , 0.677231 , 7.60955 , -0.0471231,0.0426276,0.997979 --2.86575 , 0.710858 , 7.55898 , -0.445965,-0.0691718,-0.892374 --2.49005 , 0.713933 , 7.07521 , 0.34641,0.93781,0.0226167 --2.11383 , 0.707304 , 6.54526 , -0.736215,-0.315311,-0.598804 --2.01274 , 0.738407 , 6.56776 , -0.91638,-0.256712,0.307159 --2.09806 , 0.806684 , 7.01799 , 0.807828,0.025145,-0.588881 --1.80273 , 0.798891 , 6.58846 , 0.477271,-0.735832,0.480378 --2.3423 , 0.984239 , 8.22585 , 0.320131,0.437496,0.840305 --1.82037 , 0.917837 , 7.20682 , 0.225297,0.668359,0.708899 --1.67564 , 0.940468 , 7.12913 , -0.0855608,0.732557,0.675307 --1.70662 , 1.01799 , 7.55716 , -0.204414,-0.31778,0.925868 --1.46225 , 1.00597 , 7.17299 , 0.357055,-0.318511,0.878102 --1.27556 , 1.00612 , 6.92558 , -0.469563,0.628539,0.62004 --1.15886 , 1.03049 , 6.89372 , -0.407344,0.489159,0.771229 --1.04417 , 1.05384 , 6.85957 , 0.199858,0.225887,0.953432 --0.908691 , 1.06516 , 6.73657 , -0.507043,0.168221,-0.845345 --0.769687 , 1.06913 , 6.57221 , 0.465962,0.0129699,0.88471 --0.667014 , 1.09169 , 6.5503 , -0.111488,-0.159508,0.980881 --0.475064 , 1.04443 , 6.0603 , -0.10304,0.481321,0.870467 --0.399742 , 1.07923 , 6.13062 , 0.976338,-0.200658,0.0806303 --0.401031 , 1.19189 , 6.69766 , 0.0622802,0.416671,0.906921 --0.30242 , 1.21798 , 6.69809 , -0.424625,-0.552802,0.71701 --0.186603 , 1.21946 , 6.54973 , 0.244083,0.96843,0.0506736 --0.0891818 , 1.24099 , 6.52674 , -0.0457804,-0.458004,0.887771 --2.56862 , -0.834209 , -1.04647 , -0.0272889,0.202609,0.978879 --2.69479 , -0.864199 , -1.04797 , -0.0390794,0.172465,0.98424 --2.83055 , -0.896301 , -1.05083 , -0.0583287,0.162808,0.984932 --2.97593 , -0.930404 , -1.05458 , 0.0929814,-0.163611,-0.982133 --3.13859 , -0.970683 , -1.06315 , -0.0735233,0.166264,0.983336 --3.3026 , -1.00958 , -1.06669 , -0.0694499,0.166517,0.98359 --3.4943 , -1.05699 , -1.07848 , -0.088497,0.182952,0.979131 --3.69582 , -1.10584 , -1.08863 , -0.0949184,0.17252,0.980422 --3.92519 , -1.16266 , -1.10471 , -0.089316,0.157441,0.983481 --4.15632 , -1.21856 , -1.11331 , -0.0767125,0.160612,0.984032 --4.39862 , -1.27618 , -1.11825 , -0.0675134,0.173321,0.982549 --4.66898 , -1.34114 , -1.12629 , -0.0893701,0.174742,0.98055 --4.98635 , -1.41841 , -1.14338 , -0.0554088,0.209133,0.976316 --5.24358 , -1.47507 , -1.1261 , 0.0244716,0.277632,0.960376 --5.52056 , -1.53591 , -1.10689 , 0.031217,0.253833,0.966744 --5.84376 , -1.60866 , -1.09398 , -0.0593555,0.296916,0.953057 --6.7286 , -1.8457 , -1.24729 , -0.0396956,0.510572,0.858918 --7.34546 , -1.99753 , -1.28763 , -0.381247,0.396559,0.8351 --7.30715 , -1.95634 , -1.12427 , -0.381247,0.396559,0.8351 --7.19096 , -1.89412 , -0.943826 , -0.118528,0.511342,0.851164 --5.82279 , -1.4804 , -0.470729 , 0.98128,0.0771957,0.176437 --5.8338 , -1.45975 , -0.353895 , 0.997081,0.0691085,-0.0324449 --5.82353 , -1.43415 , -0.233405 , 0.986227,-0.0631782,-0.152858 --8.46422 , -2.12275 , -0.598506 , -0.841389,0.450721,0.298188 --13.729 , -3.4914 , -1.29805 , 0.109254,0.347898,0.931145 --15.8181 , -3.98866 , -1.34313 , 0.00614363,0.525738,0.850625 --14.2549 , -3.52507 , -0.847441 , 0.714201,0.220659,-0.664249 --14.2299 , -3.46606 , -0.578602 , 0.714201,0.220659,-0.664248 --14.0158 , -3.3604 , -0.294699 , -0.943394,0.292032,-0.157245 --14.1739 , -3.34772 , -0.0474293 , 0.714201,0.220659,-0.664249 --17.3827 , -4.08162 , 0.0329326 , 0.573977,0.808319,0.131035 --17.6254 , -4.07749 , 0.340374 , 0.573977,0.808319,0.131035 --42.7046 , -9.97745 , 0.137199 , -0.762012,0.00828691,0.647509 --42.7368 , -9.83471 , 0.898454 , -0.756714,0.0810453,0.648704 --41.2075 , -9.33125 , 1.63722 , -0.763841,-0.199943,0.613653 --40.407 , -8.86191 , 3.06321 , 0.242646,0.929705,0.277079 --40.7674 , -8.79929 , 3.80608 , 0.242646,0.929705,0.277079 --41.0859 , -8.72404 , 4.55848 , 0.242646,0.929705,0.277079 --35.7176 , -7.43444 , 4.74209 , 0.639778,-0.356335,-0.680963 --34.9962 , -7.15613 , 5.29441 , -0.819212,-0.0639586,0.569912 --35.2351 , -7.08073 , 5.95515 , -0.618358,-0.739524,0.265965 --35.375 , -6.98458 , 6.61139 , -0.849006,-0.22673,0.477265 --34.1508 , -6.6131 , 7.03818 , -0.702465,-0.19961,0.683153 --10.9181 , -1.94056 , 3.22042 , -0.928503,0.29078,-0.230931 --10.8684 , -1.89042 , 3.4153 , 0.997474,0.0255406,0.0662855 --10.7575 , -1.82896 , 3.59583 , 0.779611,-0.61302,-0.128113 --10.9877 , -1.83118 , 3.85732 , -0.785154,0.615719,0.0665124 --10.946 , -1.78224 , 4.05701 , 0.732488,-0.673755,-0.0975536 --10.5216 , -1.66458 , 4.1485 , -0.553331,0.502485,0.664329 --10.3139 , -1.58766 , 4.29133 , 0.58982,-0.242273,-0.770335 --10.4243 , -1.56554 , 4.52953 , 0.552329,-0.226026,-0.8024 --9.8745 , -1.43359 , 4.55097 , -0.661907,0.0918263,0.74394 --9.89423 , -1.39755 , 4.75691 , -0.931455,0.231043,0.281087 --9.7532 , -1.33456 , 4.9049 , 0.977972,-0.202487,0.0506999 --9.77538 , -1.29818 , 5.11459 , 0.977972,-0.202487,0.0506999 --9.98525 , -1.28978 , 5.40594 , -0.877434,0.45387,-0.155279 --7.44504 , -0.874944 , 4.50825 , 0.388271,0.226042,-0.893393 --7.19198 , -0.806244 , 4.55414 , -0.87986,-0.108068,0.462783 --7.04614 , -0.754488 , 4.64356 , -0.736548,-0.276607,0.61724 --9.49369 , -1.05367 , 6.02221 , 0.826489,-0.522144,-0.210433 --11.2026 , -1.23506 , 7.12369 , -0.439239,0.737125,-0.513533 --9.50467 , -0.970043 , 6.45796 , -0.401935,0.66812,0.62615 --8.03124 , -0.74611 , 5.8478 , -0.293756,-0.0874038,0.951876 --8.66584 , -0.783091 , 6.41101 , -0.392344,-0.461104,0.795896 --8.20383 , -0.689595 , 6.33972 , 0.191327,-0.819352,0.540422 --8.27732 , -0.657496 , 6.5891 , 0.325843,-0.865485,0.380476 --8.03672 , -0.590953 , 6.6401 , 0.337553,-0.892976,0.297745 --7.82104 , -0.528766 , 6.70113 , -0.220535,-0.884917,0.410226 --7.98889 , -0.502798 , 7.02607 , -0.354651,-0.016548,0.934852 --7.9632 , -0.45784 , 7.2229 , 0.064865,-0.997809,0.013009 --7.46339 , -0.372708 , 7.06524 , 0.385442,0.0091211,0.922687 --6.74248 , -0.274332 , 6.71374 , 0.705111,0.442162,-0.554357 --7.83488 , -0.314714 , 7.79785 , -0.44382,0.108093,0.889573 --7.60878 , -0.25234 , 7.84182 , -0.287506,0.115851,0.950747 --7.5554 , -0.203254 , 8.03084 , -0.369753,0.00364151,0.929123 --6.20558 , -0.0795511 , 7.0582 , -0.0543785,0.223441,0.973199 --6.78133 , -0.0224503 , 8.02886 , 0.0955904,0.290441,0.952106 --6.32439 , 0.0411942 , 7.81263 , 0.263844,0.218743,0.939435 --5.91777 , 0.0992309 , 7.62578 , 0.308909,0.335425,-0.88998 --6.04764 , 0.140201 , 7.98737 , -0.17982,-0.416739,0.891063 --5.80316 , 0.191788 , 7.9557 , 0.486713,0.471283,-0.735529 --7.45293 , 0.22329 , 10.0632 , -0.493633,0.545721,0.677138 --7.37223 , 0.284738 , 10.2786 , -0.493633,0.54572,0.677138 --3.72005 , 0.323247 , 6.16378 , 0.0204634,-0.0301602,0.999336 --3.61505 , 0.357206 , 6.20977 , -0.127612,0.0197197,0.991628 --3.44276 , 0.38857 , 6.1666 , -0.396705,0.13048,0.908625 --3.37404 , 0.422496 , 6.25523 , -0.560425,0.10221,0.821874 --3.29813 , 0.455943 , 6.33495 , 0.83589,-0.170322,-0.521804 --7.07172 , 0.690651 , 11.9768 , -0.95521,0.00915663,-0.295786 --3.29024 , 0.53277 , 6.71484 , -0.840027,-0.50381,0.201322 --3.35089 , 0.579528 , 7.01985 , -0.872957,-0.416239,0.254344 --3.28628 , 0.618197 , 7.14164 , -0.587652,-0.698617,-0.408167 --3.09 , 0.645836 , 7.04836 , 0.748707,-0.00838075,0.662848 --3.25255 , 0.71017 , 7.56465 , -0.225355,0.308117,0.924272 --3.11682 , 0.745088 , 7.58106 , -0.460783,0.181332,0.868791 --3.01541 , 0.783884 , 7.65623 , 0.292347,0.0161168,-0.956177 --2.56716 , 0.768712 , 7.05463 , -0.426094,-0.90264,-0.0607036 --2.42093 , 0.795389 , 7.01345 , 0.380437,0.28581,0.879534 --2.06134 , 0.779206 , 6.50878 , -0.44813,0.129044,0.884606 --2.13141 , 0.843481 , 6.91232 , 0.80357,0.463753,0.373107 --1.94877 , 0.856171 , 6.76107 , 0.437607,-0.00571311,0.899148 --1.76826 , 0.865502 , 6.59613 , 0.730206,0.332096,0.597086 --1.86021 , 0.946146 , 7.11327 , 0.263066,0.646206,0.716389 --1.73656 , 0.971233 , 7.09318 , -0.151965,0.588467,0.794112 --1.70175 , 1.02517 , 7.32391 , -0.507076,-0.774146,0.378909 --1.65659 , 1.07888 , 7.5457 , -0.204414,-0.31778,0.925868 --1.539 , 1.10917 , 7.55862 , 0.340686,-0.055995,0.938508 --1.20241 , 1.0432 , 6.82696 , -0.500165,0.544387,0.673408 --1.09542 , 1.06734 , 6.8229 , -0.148354,0.505745,0.849831 --1.00413 , 1.09851 , 6.87457 , 0.534646,-0.10253,0.838834 --0.859651 , 1.10056 , 6.71249 , -0.327071,0.13588,-0.93518 --0.721489 , 1.10042 , 6.54756 , -0.411392,-0.151174,-0.898834 --0.543507 , 1.06462 , 6.15693 , -0.69956,-0.714478,-0.0117273 --0.441297 , 1.07541 , 6.09293 , -0.676039,0.419077,0.60609 --0.465942 , 1.20348 , 6.7672 , 0.994628,0.0727292,0.0736597 --0.347402 , 1.20804 , 6.65216 , 0.141725,-0.157118,0.977358 --0.276611 , 1.26564 , 6.85741 , 0.720748,-0.413969,-0.556014 --0.125557 , 1.21524 , 6.425 , -0.545396,-0.804311,0.235853 --0.049706 , 1.269 , 6.60764 , 0.677542,0.703862,-0.213341 --2.64115 , -0.749386 , -1.0586 , -0.021748,0.165476,0.985974 --2.77678 , -0.777927 , -1.06441 , -0.0495515,0.173347,0.983613 --2.92106 , -0.808686 , -1.07099 , -0.0755905,0.160439,0.984147 --3.07596 , -0.841165 , -1.07828 , -0.0768807,0.150914,0.985553 --3.23242 , -0.873282 , -1.08063 , -0.0780079,0.162218,0.983667 --3.42347 , -0.915406 , -1.09655 , -0.0944526,0.162559,0.982168 --3.61715 , -0.956667 , -1.10639 , -0.0827707,0.1746,0.981154 --3.82161 , -0.999122 , -1.1146 , -0.0869956,0.16823,0.981902 --4.04434 , -1.04582 , -1.12455 , -0.080697,0.166162,0.982791 --4.29504 , -1.10017 , -1.13897 , -0.0821523,0.162448,0.983291 --4.56709 , -1.15761 , -1.15326 , -0.075189,0.173605,0.981941 --4.84944 , -1.21662 , -1.1621 , -0.0978202,0.137042,0.985723 --5.21512 , -1.29646 , -1.19361 , -0.0457317,0.222189,0.973931 --5.4929 , -1.34967 , -1.17916 , -0.00933802,0.294484,0.955611 --5.69914 , -1.38191 , -1.1301 , 0.00711664,0.29443,0.955647 --6.15403 , -1.47955 , -1.15643 , -0.116527,0.276308,0.953979 --6.99238 , -1.67469 , -1.28521 , 0.0562487,0.326576,0.943496 --7.68958 , -1.82579 , -1.34208 , 0.293117,0.245902,0.923912 --8.4187 , -1.98135 , -1.38255 , -0.247712,0.921966,0.297688 --8.43712 , -1.95305 , -1.21742 , 0.581485,-0.710447,-0.396409 --8.26365 , -1.87703 , -1.00838 , -0.828738,0.538249,0.153237 --8.27524 , -1.84811 , -0.847303 , -0.815916,0.578127,-0.00706766 --11.8945 , -2.68734 , -1.3955 , -0.0801983,0.270436,0.959392 --13.3238 , -2.98184 , -1.42252 , -0.0343438,0.516559,0.855563 --14.913 , -3.30408 , -1.42476 , -0.183845,0.358066,0.915418 --17.3769 , -3.81669 , -1.49522 , 0.469557,0.78206,0.409755 --19.5991 , -4.25776 , -1.44871 , -0.178694,0.844679,0.504566 --19.7985 , -4.23178 , -1.1107 , -0.178694,0.844679,0.504566 --36.8231 , -7.64113 , -0.930628 , -0.96891,-0.245198,-0.0330312 --46.0913 , -9.45278 , -0.600254 , -0.349055,0.3116,0.883779 --42.8239 , -8.62049 , 0.274424 , -0.857035,0.0252775,0.514638 --42.8593 , -8.47967 , 1.03279 , -0.870224,0.0339463,0.491486 --41.7045 , -8.10211 , 1.77076 , -0.787231,-0.102281,0.608117 --41.4685 , -7.91273 , 2.49983 , -0.825208,-0.341654,0.449783 --40.9245 , -7.66499 , 3.20444 , 0.825208,0.341654,-0.449783 --34.5048 , -6.07255 , 4.70639 , -0.89679,0.215951,0.386178 --35.7687 , -6.17876 , 5.4759 , -0.945587,0.294922,0.13743 --34.4121 , -5.81655 , 5.92503 , -0.869365,0.279747,0.407366 --35.6851 , -5.78981 , 7.38551 , 0.994414,0.0843064,0.0635078 --10.8286 , -1.57021 , 3.22814 , -0.811343,-0.0827453,0.578684 --10.922 , -1.54499 , 3.45098 , 0.999128,-0.0274184,-0.0314906 --10.8374 , -1.49149 , 3.63772 , -0.903178,0.141228,0.405369 --10.4714 , -1.39537 , 3.75327 , 0.736548,-0.056664,-0.674008 --10.5541 , -1.36861 , 3.97604 , -0.56215,0.483443,0.671022 --10.1755 , -1.27329 , 4.07224 , 0.631074,-0.618334,-0.46841 --10.2328 , -1.24271 , 4.28813 , -0.676988,0.467062,0.568807 --10.0116 , -1.17272 , 4.41862 , -0.69446,0.486286,0.530331 --8.03276 , -0.864095 , 3.94426 , 0.162405,-0.57849,-0.799359 --7.95808 , -0.822682 , 4.08119 , 0.181438,0.950854,0.250913 --7.43653 , -0.723597 , 4.0472 , 0.392669,-0.821838,-0.412787 --7.87753 , -0.748398 , 4.37858 , 0.510829,-0.823136,-0.247994 --7.77678 , -0.703393 , 4.50317 , 0.638369,-0.706303,-0.305975 --7.45718 , -0.634253 , 4.52935 , -0.178771,0.222186,0.958475 --7.27362 , -0.581553 , 4.6076 , 0.894081,0.314636,-0.318785 --9.68288 , -0.812656 , 5.92449 , 0.826489,-0.522144,-0.210432 --9.34507 , -0.734739 , 5.96917 , -0.0416169,0.586486,0.80889 --8.3282 , -0.59187 , 5.64878 , -0.935496,-0.0896444,0.341777 --6.98244 , -0.424658 , 5.10914 , 0.0382603,-0.487599,0.872229 --6.21282 , -0.321478 , 4.83902 , -0.265589,0.558792,0.78563 --6.53693 , -0.320528 , 5.1809 , -0.0146964,0.471579,0.881701 --6.10247 , -0.253242 , 5.07698 , 0.537503,0.272362,-0.798066 --5.89147 , -0.206538 , 5.09829 , -0.386636,0.1694,0.906541 --5.74935 , -0.165451 , 5.15716 , -0.52064,-0.17984,0.834621 --5.6475 , -0.129222 , 5.24075 , 0.573822,0.591449,-0.566495 --8.04703 , -0.252636 , 7.09363 , -0.340372,0.181268,0.922653 --8.75856 , -0.252467 , 7.83524 , 0.298768,-0.948653,-0.103903 --6.90328 , -0.104299 , 6.66747 , 0.975051,0.212583,-0.063909 --6.95041 , -0.0678102 , 6.90364 , 0.975051,0.212583,-0.063909 --7.8052 , -0.0650778 , 7.80566 , -0.256141,0.127587,0.958182 --6.75133 , 0.0207269 , 7.15298 , -0.299983,-0.260821,0.917596 --6.51288 , 0.0695764 , 7.15663 , -0.00272794,0.0265332,0.999644 --6.20925 , 0.118873 , 7.09339 , -0.503035,-0.0399898,0.86334 --8.12414 , 0.120316 , 9.08872 , -0.839782,-0.153084,0.520895 --7.83058 , 0.178213 , 9.08025 , -0.839782,-0.153084,0.520895 --6.15817 , 0.244949 , 7.68638 , -0.276025,-0.298497,0.913625 --6.15686 , 0.289383 , 7.91234 , 0.437196,-0.0806538,-0.895743 --5.95177 , 0.334332 , 7.92826 , -0.477194,0.0775084,0.875373 --5.80126 , 0.377825 , 7.99862 , -0.440363,-0.204417,0.874239 --6.90823 , 0.44702 , 9.50249 , -0.909583,0.181938,-0.373574 --7.03571 , 0.507492 , 9.94579 , 0.0698517,0.66085,0.747261 --3.6749 , 0.447205 , 6.14655 , 0.00788349,-0.0957449,0.995375 --3.57567 , 0.477765 , 6.19967 , -0.108167,-0.370577,0.922482 --3.42781 , 0.504782 , 6.18741 , -0.245523,-0.282135,0.927426 --3.35143 , 0.536198 , 6.26803 , 0.633226,0.318044,-0.7056 --7.17697 , 0.848128 , 11.8351 , -0.935119,-0.104451,-0.33859 --3.37535 , 0.613684 , 6.6891 , -0.892059,-0.4108,0.188346 --3.3177 , 0.648776 , 6.81066 , -0.919626,-0.31084,0.240139 --3.46002 , 0.706134 , 7.25161 , -0.862434,-0.493105,0.11426 --3.12967 , 0.714115 , 6.95012 , 0.225915,0.0677019,-0.971792 --2.9923 , 0.741767 , 6.94866 , -0.0385331,0.0567608,0.997644 --3.1722 , 0.812264 , 7.49927 , -0.394077,0.241149,0.886877 --3.07058 , 0.848122 , 7.57573 , -0.583743,0.162845,0.795441 --2.9962 , 0.887729 , 7.70359 , 0.378019,0.0558769,-0.92411 --2.69345 , 0.887514 , 7.38535 , -0.639127,-0.623028,-0.450947 --2.13424 , 0.828631 , 6.50287 , -0.470845,0.189453,0.861633 --2.02758 , 0.852528 , 6.51755 , -0.470845,0.189454,0.861633 --2.04609 , 0.906663 , 6.81221 , -0.565337,-0.206958,-0.798475 --1.8967 , 0.921481 , 6.73283 , 0.369008,0.232962,0.899757 --1.74231 , 0.932658 , 6.63172 , -0.897018,-0.31551,-0.309535 --1.80966 , 1.00939 , 7.09351 , -0.793856,-0.60791,0.0154687 --1.84428 , 1.08374 , 7.51201 , 0.364951,0.170174,-0.915342 --1.7446 , 1.11837 , 7.58532 , -0.43218,-0.451642,0.780539 --1.65677 , 1.15717 , 7.69493 , -0.195026,-0.469125,0.861328 --1.37372 , 1.11409 , 7.17686 , -0.505992,0.617094,-0.602634 --1.16082 , 1.08984 , 6.83299 , -0.0397502,0.0325772,0.998679 --1.04749 , 1.10838 , 6.80949 , 0.0963387,0.250096,0.963416 --0.95969 , 1.13908 , 6.88002 , -0.787635,-0.159258,-0.595204 --0.785083 , 1.11713 , 6.58253 , 0.290994,0.374383,0.880432 --0.659521 , 1.11946 , 6.46513 , -0.00991739,-0.170662,0.98528 --0.479963 , 1.07389 , 6.04445 , -0.10304,0.481321,0.870467 --0.393531 , 1.09406 , 6.05753 , -0.593301,0.699685,0.398038 --0.407528 , 1.21663 , 6.70279 , 0.107849,0.115397,0.987447 --0.307419 , 1.23529 , 6.69452 , -0.134667,-0.586982,0.798321 --0.192498 , 1.23599 , 6.57681 , 0.728582,-0.451229,0.515325 --0.0906871 , 1.24844 , 6.53553 , 0.199606,-0.432992,0.87902 --2.61477 , -0.647711 , -1.08915 , -0.0291039,0.179947,0.983246 --2.71869 , -0.662357 , -1.07622 , -0.0262216,0.180029,0.983312 --2.85571 , -0.687152 , -1.08082 , -0.083569,0.173635,0.981258 --3.01857 , -0.718325 , -1.0964 , -0.0934362,0.165524,0.98177 --3.18277 , -0.748141 , -1.10704 , -0.0720296,0.176101,0.981733 --3.3414 , -0.775191 , -1.10781 , -0.088679,0.165109,0.98228 --3.54279 , -0.814239 , -1.12633 , -0.0973523,0.16121,0.982107 --3.7382 , -0.848421 , -1.13451 , -0.0859252,0.173568,0.981066 --3.96122 , -0.889679 , -1.149 , -0.0854163,0.179051,0.980125 --4.19512 , -0.931867 , -1.1607 , -0.0775165,0.179854,0.980634 --4.44934 , -0.977492 , -1.17273 , -0.0807665,0.173963,0.981435 --4.74083 , -1.03211 , -1.19157 , -0.0701446,0.182114,0.980772 --5.02651 , -1.08133 , -1.19772 , -0.0909178,0.167197,0.981723 --5.40478 , -1.15276 , -1.2291 , -0.0590676,0.249229,0.966641 --5.77671 , -1.21938 , -1.24484 , -0.0307953,0.322887,0.945937 --5.94754 , -1.23577 , -1.17842 , -0.0436779,0.316405,0.947618 --6.76925 , -1.40352 , -1.31739 , -0.137222,0.195143,0.971128 --7.29957 , -1.49793 , -1.33722 , -0.149526,0.323529,0.934329 --8.05878 , -1.64091 , -1.40363 , -0.412161,0.372524,0.831474 --8.81305 , -1.77812 , -1.44148 , 0.486642,-0.306205,-0.81818 --8.08169 , -1.58388 , -1.08508 , -0.841094,0.505061,0.193584 --8.09398 , -1.55556 , -0.927726 , -0.861203,0.446176,-0.243426 --8.09355 , -1.52479 , -0.768741 , -0.861203,0.446176,-0.243426 --9.75158 , -1.76793 , -0.557971 , -0.412666,-0.767636,-0.490349 --19.5727 , -3.67681 , -1.72719 , 0.369292,-0.57434,-0.730587 --24.6748 , -4.51402 , -1.53461 , 0.180099,0.155232,0.971323 --42.8232 , -7.54138 , -1.10403 , 0.995905,0.0776882,0.0462384 --42.878 , -7.40584 , -0.348681 , -0.965335,0.0225839,0.260034 --42.9197 , -7.2672 , 0.406831 , -0.952819,0.0864102,0.290981 --36.9165 , -6.09658 , 1.14557 , -0.370574,-0.748763,0.549571 --37.3244 , -6.03961 , 1.80436 , 0.41921,-0.895005,-0.152413 --37.4839 , -5.93923 , 2.46775 , 0.240485,-0.970451,0.0197953 --37.2862 , -5.78099 , 3.11743 , -0.542854,0.83951,-0.0230809 --35.5711 , -5.38406 , 3.65049 , 0.843163,-0.0865654,-0.530643 --37.4098 , -5.54664 , 4.44428 , -0.767254,0.50823,0.391181 --35.3307 , -5.10608 , 4.88297 , -0.847434,-0.34684,0.401942 --34.6484 , -4.88429 , 5.4251 , -0.847434,-0.34684,0.401942 --34.6257 , -4.76258 , 6.03916 , 0.941094,0.303978,0.148122 --35.3168 , -4.6184 , 7.40331 , -0.966688,-0.248708,-0.0604907 --10.9811 , -1.24035 , 3.28352 , 0.86015,0.294898,-0.416145 --10.8492 , -1.18366 , 3.46104 , -0.798842,-0.238738,0.552137 --10.8014 , -1.13857 , 3.65454 , -0.800538,-0.323242,0.504632 --10.702 , -1.0869 , 3.83499 , 0.834683,0.497382,-0.236463 --9.72738 , -0.930334 , 3.7785 , 0.108683,-0.484084,-0.868246 --9.75044 , -0.89676 , 3.97364 , -0.827275,0.264754,-0.495502 --9.90256 , -0.877146 , 4.21074 , -0.827275,0.264754,-0.495502 --9.97386 , -0.847748 , 4.42945 , -0.967262,0.199432,-0.156942 --7.95149 , -0.596062 , 3.93522 , -0.162632,0.571566,0.804278 --7.23076 , -0.491501 , 3.8363 , 0.711926,-0.645197,0.277277 --7.23066 , -0.462457 , 3.9866 , 0.711926,-0.645197,0.277277 --7.45957 , -0.455021 , 4.23029 , -0.889392,0.440999,0.120423 --7.33334 , -0.412984 , 4.33556 , -0.879275,0.472025,-0.0637724 --7.40643 , -0.389032 , 4.52586 , -0.814492,-0.0546865,-0.577592 --7.51224 , -0.366509 , 4.73604 , 0.536479,-0.148389,0.830765 --9.45433 , -0.486675 , 5.83881 , 0.775923,-0.529712,-0.342563 --6.65563 , -0.238131 , 4.64074 , 0.138676,0.990325,-0.00513191 --7.05442 , -0.236367 , 5.00369 , -0.262573,-0.0485411,0.96369 --6.45372 , -0.164825 , 4.84028 , -0.036161,0.732152,0.680181 --6.30301 , -0.125858 , 4.90931 , 0.102453,-0.417891,-0.902702 --6.2558 , -0.0936164 , 5.03506 , 0.621338,-0.230293,-0.748935 --6.06941 , -0.0534403 , 5.07657 , -0.726319,0.0548117,0.685169 --5.97563 , -0.0190808 , 5.1719 , 0.463585,0.105202,-0.879785 --5.88961 , 0.0147431 , 5.27058 , 0.620998,0.714847,-0.321488 --6.10568 , 0.036192 , 5.57692 , 0.608971,0.717248,-0.338688 --5.88213 , 0.0758467 , 5.58431 , 0.351015,-0.619028,0.702562 --7.54295 , 0.0589569 , 6.97395 , 0.246657,-0.430131,0.868417 --6.97377 , 0.113477 , 6.75159 , 0.975051,0.212583,-0.063909 --6.92326 , 0.153729 , 6.91484 , 0.992077,0.038261,-0.119662 --6.86959 , 0.194199 , 7.07786 , -0.686447,-0.0915085,0.721399 --6.53061 , 0.237247 , 7.00139 , 0.0222914,0.24723,0.9687 --6.35372 , 0.277777 , 7.05352 , 0.543094,-0.0137625,-0.839559 --6.28104 , 0.317562 , 7.1954 , 0.746536,-0.0636581,-0.662293 --8.02745 , 0.374726 , 9.04761 , -0.776686,-0.119878,0.618375 --6.88603 , 0.409927 , 8.21502 , 0.755419,-0.138176,0.640508 --6.2344 , 0.443309 , 7.80684 , -0.293029,-0.0432752,0.955124 --6.06326 , 0.482675 , 7.86168 , 0.355159,0.0738277,-0.931886 --5.93994 , 0.523703 , 7.96367 , -0.135313,0.109895,0.98469 --7.35129 , 0.629764 , 9.77307 , -0.217787,0.752249,0.621845 --7.11578 , 0.676872 , 9.80536 , -0.839479,0.262861,-0.475583 --3.84265 , 0.546546 , 6.21224 , -0.039194,0.0288573,0.998815 --3.7031 , 0.571839 , 6.22227 , 0.289085,0.305768,-0.907158 --3.60143 , 0.599806 , 6.27595 , 0.241993,0.498712,-0.832302 --3.49345 , 0.627289 , 6.31963 , 0.411333,0.714951,-0.565376 --3.50229 , 0.664212 , 6.52258 , 0.774705,0.384913,-0.501671 --3.32745 , 0.685412 , 6.47397 , -0.946384,-0.309867,0.091328 --3.43033 , 0.735501 , 6.82565 , 0.981989,-0.0765567,-0.172735 --3.34677 , 0.766931 , 6.91493 , -0.861244,0.0242006,0.507615 --3.28329 , 0.800667 , 7.03692 , -0.277497,0.574288,0.770187 --3.02434 , 0.807623 , 6.8428 , -0.170156,0.540922,0.823681 --2.98429 , 0.845693 , 7.00329 , 0.416996,-0.249791,0.87391 --3.13977 , 0.918883 , 7.52006 , -0.583743,0.162845,0.795441 --3.04184 , 0.952171 , 7.60505 , 0.0962535,0.3402,0.935414 --2.81345 , 0.959294 , 7.44109 , 0.186719,0.861965,0.471331 --2.28246 , 0.897409 , 6.64723 , -0.799913,-0.230468,-0.554097 --2.07426 , 0.896918 , 6.45789 , 0.486917,-0.28638,-0.825165 --2.11619 , 0.954676 , 6.79779 , -0.0177695,-0.415069,0.909616 --2.02367 , 0.981964 , 6.85752 , 0.628847,0.101954,0.770816 --1.84715 , 0.985068 , 6.71352 , 0.486594,0.0884046,0.869144 --1.89063 , 1.05406 , 7.11079 , -0.772213,-0.348158,-0.531481 --1.84802 , 1.10066 , 7.31549 , 0.920171,0.389627,-0.0384203 --1.82758 , 1.15972 , 7.60444 , -0.498201,-0.301458,0.812969 --1.68902 , 1.17605 , 7.56502 , -0.195026,-0.469125,0.861328 --0.865998 , 0.892769 , 5.35835 , 0.801954,0.182671,-0.568771 --1.40486 , 1.20056 , 7.44004 , -0.669271,0.562994,-0.484885 --1.12564 , 1.13775 , 6.86786 , -0.183065,0.109345,-0.977001 --1.00596 , 1.15066 , 6.82483 , 0.522428,0.120739,0.844092 --0.877972 , 1.15425 , 6.73159 , -0.436184,-0.452698,-0.777694 --0.778662 , 1.17577 , 6.75139 , 0.816197,0.0383108,0.576503 --0.537384 , 1.0876 , 6.0825 , 0.603536,0.475202,0.640256 --0.436308 , 1.09455 , 6.02905 , 0.303317,-0.497007,-0.813008 --0.458771 , 1.21706 , 6.68418 , 0.273096,0.51017,0.815565 --0.359176 , 1.23501 , 6.68703 , -0.035422,-0.623239,0.781229 --0.277741 , 1.275 , 6.8252 , 0.791524,0.537262,-0.291271 --0.129505 , 1.22526 , 6.43313 , 0.47529,0.854471,-0.20971 --0.0502264 , 1.27013 , 6.59727 , 0.387225,0.764059,-0.516015 --2.67417 , -0.556671 , -1.09615 , -0.0449435,0.195925,0.979589 --2.81084 , -0.576889 , -1.10362 , -0.0464522,0.178211,0.982895 --2.94903 , -0.596899 , -1.10682 , -0.07956,0.183446,0.979805 --3.10497 , -0.621054 , -1.11576 , -0.0780699,0.171727,0.982046 --3.27133 , -0.645847 , -1.12502 , -0.0728713,0.182679,0.980468 --3.45555 , -0.674434 , -1.13846 , -0.0902338,0.15429,0.983897 --3.65989 , -0.707116 , -1.15514 , -0.0957613,0.162174,0.982105 --3.8748 , -0.739952 , -1.17 , -0.0944485,0.176396,0.979778 --4.09961 , -0.773977 , -1.18215 , -0.0821007,0.183986,0.979494 --4.34445 , -0.810641 , -1.1955 , -0.0773067,0.187762,0.979168 --4.60966 , -0.850632 , -1.2087 , -0.0777866,0.184137,0.979818 --4.88588 , -0.891135 , -1.21725 , -0.0794664,0.188177,0.978915 --5.24545 , -0.948449 , -1.24939 , -0.109108,0.181194,0.977376 --5.63688 , -1.00916 , -1.28026 , -0.0326559,0.267085,0.96312 --6.06684 , -1.07611 , -1.31125 , -0.105913,0.296579,0.949117 --6.52891 , -1.14572 , -1.33766 , -0.145776,0.247022,0.957982 --7.06914 , -1.22816 , -1.37245 , -0.0765816,0.175302,0.981532 --7.61216 , -1.30825 , -1.38906 , -0.0776982,-0.196351,-0.97745 --8.35847 , -1.42354 , -1.44339 , 0.496469,-0.295576,-0.816182 --7.91906 , -1.30796 , -1.16159 , 0.569659,-0.80506,-0.165431 --7.93135 , -1.28132 , -1.00725 , -0.879013,0.427619,-0.210898 --7.93165 , -1.25104 , -0.8515 , -0.879013,0.427619,-0.210898 --12.4242 , -2.03017 , -1.62151 , -0.0668175,0.260861,0.963061 --8.11682 , -1.22521 , -0.578285 , -0.928012,0.372386,-0.0111115 --15.6506 , -2.50055 , -1.70034 , -0.196401,0.243179,0.94989 --18.0243 , -2.84848 , -1.77086 , 0.233781,-0.588977,-0.773597 --42.8969 , -6.34389 , -1.71669 , -0.965335,0.0225839,0.260034 --42.9484 , -6.2084 , -0.962741 , -0.965335,0.0225839,0.260034 --42.987 , -6.0708 , -0.208618 , 0.908889,-0.145173,-0.390954 --38.6764 , -5.31114 , 0.594797 , -0.317291,-0.800205,0.508919 --38.0532 , -5.09546 , 1.26979 , -0.571209,0.816425,0.0846775 --36.2336 , -4.59973 , 2.53096 , -0.00781871,-0.727536,0.686025 --35.6147 , -4.39849 , 3.13129 , -0.820549,0.498477,0.279678 --36.5091 , -4.39342 , 3.82498 , -0.82055,0.498477,0.279678 --35.7299 , -4.175 , 4.39564 , -0.763044,-0.58059,0.28404 --35.7111 , -4.05343 , 5.02455 , 0.747423,0.583288,-0.318017 --35.7203 , -3.93445 , 5.65823 , -0.894955,-0.246195,0.372081 --11.4867 , -1.06433 , 2.77788 , 0.767726,0.429644,-0.475398 --11.2738 , -1.0007 , 2.95411 , 0.767726,0.429644,-0.475398 --11.1264 , -0.945961 , 3.1358 , 0.672994,0.513938,-0.531927 --11.1898 , -0.913115 , 3.35524 , 0.692459,0.547598,-0.469719 --11.0071 , -0.854924 , 3.5248 , 0.695577,0.533995,-0.480648 --10.7924 , -0.794675 , 3.68167 , -0.745565,0.627569,-0.224252 --10.9038 , -0.76604 , 3.91462 , -0.98401,-0.0622146,0.166895 --11.0585 , -0.740905 , 4.16519 , 0.780946,0.382741,-0.493592 --9.81033 , -0.593194 , 4.01791 , 0.867574,0.455467,0.199661 --9.74168 , -0.550607 , 4.18876 , -0.865736,-0.421826,-0.269378 --8.38139 , -0.407062 , 3.93749 , 0.986343,0.0807633,0.143544 --8.26654 , -0.365643 , 4.06672 , -0.932454,-0.00645662,0.361232 --7.52274 , -0.280226 , 3.96388 , -0.0924337,-0.477874,0.873552 --7.02663 , -0.216973 , 3.9294 , -0.396984,0.747989,-0.531899 --7.191 , -0.200021 , 4.14409 , -0.396984,0.747989,-0.531899 --7.17464 , -0.169419 , 4.29093 , 0.673473,-0.693514,0.255878 --7.14758 , -0.139057 , 4.43421 , 0.929943,0.0419906,-0.365299 --7.58846 , -0.132357 , 4.796 , -0.974279,-0.216704,0.0618015 --9.37586 , -0.187975 , 5.83239 , -0.0538429,0.573604,0.817361 --7.0844 , -0.0452683 , 4.8809 , 0.0688039,-0.901758,-0.426731 --6.84242 , -0.00430939 , 4.91661 , 0.0281821,0.682126,0.730692 --6.57509 , 0.0363781 , 4.93062 , -0.66483,0.630091,0.401232 --6.2051 , 0.07858 , 4.87701 , 0.364404,-0.68487,-0.631001 --6.027 , 0.112582 , 4.92444 , -0.797114,0.448532,0.404263 --5.9866 , 0.142462 , 5.05093 , 0.735007,-0.209096,-0.645015 --6.04451 , 0.170151 , 5.24193 , -0.620591,-0.743854,0.248089 --6.08841 , 0.199141 , 5.4306 , -0.598902,-0.741127,0.303392 --5.95598 , 0.23161 , 5.50221 , 0.0399217,-0.235572,0.971037 --5.86303 , 0.263467 , 5.59969 , -0.893773,0.419374,-0.159046 --6.93234 , 0.294635 , 6.55979 , -0.857028,0.399507,-0.325418 --6.81366 , 0.331566 , 6.66688 , 0.713093,-0.679268,0.173477 --6.99074 , 0.371626 , 7.0082 , -0.953453,-0.29296,-0.071429 --6.87254 , 0.409985 , 7.12162 , -0.843402,-0.537173,-0.0109124 --6.36497 , 0.439299 , 6.9017 , -0.935036,-0.0751887,0.34649 --6.36886 , 0.478148 , 7.10973 , 0.96764,-0.0627946,-0.244397 --6.26364 , 0.514881 , 7.22511 , -0.943771,-0.199986,0.263254 --6.62866 , 0.570112 , 7.78491 , 0.433548,0.696308,0.572007 --7.97642 , 0.67444 , 9.33763 , 0.693326,-0.407092,-0.594622 --6.32325 , 0.64438 , 7.95062 , -0.183195,-0.0512043,0.981742 --5.99715 , 0.67047 , 7.84794 , 0.44185,0.178212,-0.879209 --6.84784 , 0.770562 , 9.00642 , -0.82497,0.496569,-0.269895 --7.06235 , 0.838578 , 9.52397 , -0.899976,0.303498,-0.31294 --6.85029 , 0.878395 , 9.57415 , -0.95803,0.199857,-0.205514 --3.8028 , 0.670061 , 6.21188 , -0.222087,0.00886463,0.974987 --3.63189 , 0.688792 , 6.18215 , -0.590575,0.061419,0.804642 --3.61599 , 0.721832 , 6.34527 , 0.75604,-0.106789,-0.645754 --3.48186 , 0.742627 , 6.35755 , -0.762679,0.117015,0.636104 --3.48358 , 0.779312 , 6.55266 , 0.807191,-0.174321,-0.563964 --3.39277 , 0.806778 , 6.62641 , 0.997524,0.0349522,0.0610308 --3.38514 , 0.844602 , 6.82298 , -0.959134,-0.11402,0.258963 --3.27297 , 0.869633 , 6.86999 , 0.815223,0.166089,-0.554821 --2.86075 , 0.844989 , 6.43303 , 0.498514,0.815703,0.29345 --2.78753 , 0.87163 , 6.5223 , 0.661605,-0.747162,0.0634716 --2.86174 , 0.927242 , 6.86901 , 0.757629,-0.535786,0.372736 --2.81268 , 0.963099 , 7.01947 , 0.325283,-0.353954,0.876874 --2.75949 , 0.998981 , 7.16992 , 0.768284,0.639995,-0.0120683 --2.34528 , 0.952589 , 6.62033 , -0.104898,0.983401,-0.148047 --2.13451 , 0.946854 , 6.43411 , 0.557034,0.33447,0.76016 --2.06595 , 0.975051 , 6.5304 , -0.651198,0.0463484,0.757491 --2.08757 , 1.02982 , 6.83455 , 0.671319,0.0796587,0.736876 --1.90822 , 1.02857 , 6.69319 , 0.158704,0.131424,0.97854 --1.79846 , 1.04564 , 6.70398 , 0.386215,-0.0697399,0.919769 --1.98499 , 1.16679 , 7.48082 , 0.759479,0.38678,-0.523061 --1.8732 , 1.19028 , 7.51992 , -0.547497,-0.156347,0.822072 --1.76628 , 1.21534 , 7.57599 , -0.518502,-0.196576,0.832174 --0.917699 , 0.917477 , 5.37009 , -0.463782,-0.0810771,0.882232 --0.833105 , 0.927781 , 5.36379 , -0.463782,-0.0810771,0.882232 --0.456895 , 0.787812 , 4.34795 , -0.263889,0.247787,-0.932183 --1.08966 , 1.18536 , 6.91241 , 0.0971589,0.379805,-0.91995 --0.943955 , 1.1773 , 6.76391 , 0.596065,0.557683,0.577664 --0.791577 , 1.16113 , 6.56399 , 0.294109,0.478197,0.827543 --0.686624 , 1.17205 , 6.54446 , -0.434189,-0.646628,-0.627177 --0.48487 , 1.10336 , 6.02869 , 0.0832499,0.563103,0.822183 --0.402463 , 1.12241 , 6.07205 , 0.861231,0.065423,0.503985 --0.413079 , 1.24017 , 6.69819 , -0.0452868,0.653551,0.755526 --0.314111 , 1.25607 , 6.71071 , -0.201601,-0.679518,0.705417 --0.202977 , 1.25765 , 6.63322 , 0.770806,-0.334156,0.542401 --0.0977384 , 1.2612 , 6.57344 , 0.990509,0.12961,0.0457491 --2.63393 , -0.453902 , -1.12006 , -0.0442028,0.168528,0.984705 --2.75457 , -0.466894 , -1.11913 , -0.0442028,0.168528,0.984705 --2.90074 , -0.485532 , -1.13033 , -0.0713759,0.172291,0.982457 --3.04918 , -0.50275 , -1.1374 , -0.0801721,0.156932,0.98435 --3.21517 , -0.523054 , -1.14991 , -0.0779905,0.178086,0.980919 --3.37365 , -0.541022 , -1.15231 , -0.0726496,0.168128,0.983084 --3.56006 , -0.564454 , -1.16378 , -0.0897573,0.160198,0.982996 --3.77405 , -0.591161 , -1.18346 , -0.107979,0.149446,0.982856 --4.0174 , -0.62341 , -1.20921 , -0.0880272,0.172407,0.981085 --4.244 , -0.650157 , -1.21882 , -0.0863115,0.174753,0.980822 --4.50899 , -0.68294 , -1.23753 , -0.0891443,0.177514,0.980073 --4.79415 , -0.717945 , -1.25559 , -0.069073,0.188307,0.979678 --5.07275 , -0.748788 , -1.26096 , -0.103114,0.196183,0.975131 --5.47229 , -0.801564 , -1.30378 , -0.104902,0.184978,0.977128 --5.87594 , -0.85168 , -1.33363 , -0.0838859,0.232829,0.968893 --6.31868 , -0.905723 , -1.36325 , 0.120211,-0.223152,-0.967343 --6.83074 , -0.969302 , -1.4001 , -0.0988219,0.165341,0.981273 --7.44938 , -1.04748 , -1.45227 , -0.0149432,0.286413,0.95799 --8.07294 , -1.12225 , -1.48379 , -0.239797,0.391063,0.888576 --9.0053 , -1.24285 , -1.57833 , -0.150668,-0.341028,-0.9279 --9.81003 , -1.33728 , -1.60699 , 0.204827,0.644391,0.736754 --10.9747 , -1.48166 , -1.69342 , -0.154904,0.228864,0.961055 --9.79812 , -1.26404 , -1.22434 , -0.361491,-0.73619,-0.572143 --9.68499 , -1.21273 , -1.01401 , -0.0273514,0.807274,0.589543 --15.0404 , -1.95311 , -1.81265 , 0.0791334,0.164902,0.98313 --41.0835 , -4.09103 , 2.13668 , 0.413599,-0.635427,-0.65205 --36.685 , -3.26701 , 3.94827 , -0.97729,0.0966405,0.188584 --11.4096 , -0.572523 , 3.43247 , 0.793149,0.0563984,-0.606411 --10.637 , -0.441099 , 3.67713 , 0.665107,-0.707056,-0.240219 --10.3886 , -0.387634 , 3.81626 , 0.704479,-0.701536,-0.107499 --10.8717 , -0.378889 , 4.14761 , -0.937027,0.347345,0.036506 --8.10651 , -0.185456 , 3.55084 , -0.105127,0.258061,0.960392 --9.98071 , -0.253188 , 4.29332 , -0.750568,-0.659976,0.0328642 --10.3245 , -0.232868 , 4.60377 , -0.717568,-0.14897,0.680371 --10.1879 , -0.18858 , 4.76264 , -0.986384,-0.150286,0.0667954 --10.2366 , -0.152091 , 4.98678 , -0.977516,0.0208974,0.209823 --7.71837 , -0.0175689 , 4.22127 , 0.639341,0.53982,-0.547574 --7.45086 , 0.0228456 , 4.27473 , 0.402193,0.589659,-0.700388 --7.57037 , 0.0487765 , 4.48497 , 0.676297,0.735672,0.0375313 --7.6478 , 0.0766719 , 4.68403 , 0.981546,0.0978066,0.164323 --7.5757 , 0.109831 , 4.81862 , -0.597208,0.341696,0.725663 --7.62808 , 0.141063 , 5.01304 , -0.70072,-0.677433,0.223774 --8.47631 , 0.160747 , 5.61949 , -0.176692,0.673481,0.717777 --6.32313 , 0.220191 , 4.66879 , -0.323337,0.662795,0.675393 --6.06789 , 0.250294 , 4.67813 , 0.878817,-0.223812,0.421412 --5.77071 , 0.278996 , 4.65483 , -0.229046,0.777236,0.586039 --6.37782 , 0.306669 , 5.16232 , -0.610785,-0.359834,0.705309 --6.31425 , 0.336185 , 5.28435 , 0.461341,0.548252,0.697556 --6.26619 , 0.366307 , 5.41609 , -0.270813,0.74305,0.611994 --6.22288 , 0.396595 , 5.55309 , 0.692154,0.308674,-0.652414 --5.74321 , 0.418716 , 5.38679 , -0.825936,0.15446,0.542192 --6.37227 , 0.463601 , 6.00171 , -0.666959,0.645271,-0.372546 --5.95813 , 0.48543 , 5.87222 , 0.0595985,-0.50404,0.861621 --6.45092 , 0.534809 , 6.42845 , 0.630741,-0.757697,-0.167514 --7.19064 , 0.600717 , 7.2152 , 0.209628,-0.299345,0.930832 --6.39207 , 0.605724 , 6.76979 , 0.976403,-0.194198,0.0944745 --6.39809 , 0.64392 , 6.97719 , 0.992018,0.0094177,-0.125743 --6.38409 , 0.682114 , 7.17302 , 0.973772,0.121963,-0.192077 --6.32135 , 0.717938 , 7.32955 , -0.934526,0.15328,-0.321194 --6.46491 , 0.768484 , 7.68549 , -0.465229,-0.883921,-0.0473859 --6.51982 , 0.816022 , 7.97071 , -0.595999,-0.763069,0.25002 --6.93635 , 0.894716 , 8.63783 , 0.173936,-0.833518,-0.524399 --6.57761 , 0.912331 , 8.52314 , 0.383384,-0.688945,-0.615119 --6.4598 , 0.950673 , 8.65627 , 0.501754,-0.577332,-0.644151 --6.37958 , 0.99253 , 8.83237 , -0.513083,0.760429,0.398114 --6.7677 , 1.08557 , 9.56209 , -0.95803,0.199857,-0.205514 --3.67672 , 0.781981 , 6.11171 , 0.69128,-0.468853,-0.549827 --3.59435 , 0.805969 , 6.18901 , 0.683269,-0.110442,-0.721766 --3.60136 , 0.841739 , 6.38352 , -0.856236,0.305489,0.416578 --3.73968 , 0.897135 , 6.76405 , -0.181208,-0.179533,0.966918 --3.34926 , 0.878024 , 6.42905 , 0.636091,0.502091,-0.585912 --3.37363 , 0.919334 , 6.66501 , -0.948045,-0.236937,0.212302 --3.34696 , 0.954663 , 6.83685 , 0.889273,-0.0685062,-0.452218 --2.86492 , 0.907784 , 6.30516 , -0.142348,0.74421,0.652602 --2.83475 , 0.941268 , 6.46215 , 0.738953,0.673016,0.0315892 --2.77477 , 0.969134 , 6.57699 , 0.661605,-0.747162,0.0634716 --2.81589 , 1.01964 , 6.87273 , 0.625693,-0.746858,0.225192 --2.71363 , 1.04129 , 6.92706 , -0.468635,-0.482587,0.739926 --1.2963 , 0.73876 , 4.47133 , -0.128195,-0.1663,-0.977707 --2.2699 , 1.02122 , 6.55997 , 0.351578,0.813062,0.464029 --2.0871 , 1.01645 , 6.42604 , 0.557034,0.33447,0.76016 --2.22073 , 1.10228 , 6.96399 , 0.774517,0.196069,0.601399 --1.99319 , 1.08277 , 6.72632 , 0.537716,0.235336,0.809616 --1.85431 , 1.0892 , 6.67498 , 0.413825,0.334189,0.846798 --2.19518 , 1.26469 , 7.81823 , 0.224943,0.974131,0.0216822 --1.92192 , 1.22643 , 7.45355 , 0.759479,0.38678,-0.523061 --1.84593 , 1.26206 , 7.59455 , 0.487278,0.203894,-0.84911 --0.968677 , 0.944996 , 5.38105 , -0.463782,-0.081077,0.882232 --0.590859 , 0.815102 , 4.46132 , 0.588389,-0.807749,0.0366136 --1.44983 , 1.29529 , 7.53905 , 0.660961,-0.535576,0.525631 --1.13471 , 1.20157 , 6.85564 , -0.385099,-0.0661923,-0.920499 --1.00033 , 1.19818 , 6.75664 , 0.510509,0.609762,0.606277 --0.852553 , 1.18323 , 6.58755 , -0.457536,-0.508989,-0.729103 --0.737783 , 1.18512 , 6.53112 , -0.195187,-0.624448,-0.756285 --0.548075 , 1.12645 , 6.105 , -0.852496,0.0615179,-0.519101 --0.446233 , 1.12819 , 6.05268 , 0.561257,-0.108853,-0.820452 --0.460722 , 1.24181 , 6.6694 , -0.0472227,0.799384,0.598961 --0.356013 , 1.24847 , 6.64424 , 0.0451389,0.716135,0.696501 --0.277414 , 1.28706 , 6.80266 , -0.447761,-0.841581,-0.302079 --0.14211 , 1.25047 , 6.52949 , -0.351597,0.725024,-0.592217 --0.0565129 , 1.28374 , 6.6554 , -0.783626,-0.609457,0.120384 --2.70326 , -0.362714 , -1.13822 , -0.0489858,0.146835,0.987947 --2.8243 , -0.372197 , -1.13605 , -0.0547662,0.141513,0.98842 --2.98071 , -0.38811 , -1.1514 , -0.0754517,0.144276,0.986657 --3.12935 , -0.400758 , -1.15695 , -0.0891443,0.160049,0.983076 --3.30563 , -0.41816 , -1.17283 , -0.063914,0.172964,0.982852 --3.47417 , -0.432232 , -1.17861 , -0.0764871,0.163277,0.983611 --3.67958 , -0.452548 , -1.19776 , -0.096333,0.150731,0.98387 --3.8946 , -0.473232 , -1.21496 , -0.102826,0.150513,0.983246 --4.12145 , -0.494675 , -1.22969 , -0.0883515,0.163235,0.982623 --4.38619 , -0.520316 , -1.25421 , -0.0840933,0.165189,0.98267 --4.66169 , -0.54554 , -1.27438 , -0.081862,0.175808,0.981015 --4.9666 , -0.57454 , -1.29723 , -0.0897205,0.190776,0.977525 --5.31095 , -0.607421 , -1.32512 , -0.100541,0.181599,0.978219 --5.68689 , -0.642879 , -1.35252 , -0.08769,0.169869,0.981557 --6.09235 , -0.680086 , -1.37803 , -0.0827506,0.165043,0.982809 --6.55635 , -0.72396 , -1.40937 , -0.0924872,0.160936,0.982622 --7.12773 , -0.778787 , -1.4597 , -0.104662,0.163329,0.981004 --7.80836 , -0.844979 , -1.5231 , 0.0139234,0.425582,0.904813 --8.54963 , -0.915829 , -1.58011 , 0.15132,-0.273557,-0.949878 --9.2671 , -0.977458 , -1.60474 , 0.0495214,0.495166,0.867386 --9.72873 , -1.00297 , -1.53962 , 0.204827,0.644391,0.736754 --11.5152 , -1.1889 , -1.76908 , -0.0757415,0.18775,0.979292 --13.2464 , -1.35708 , -1.92277 , 0.0800897,-0.218674,-0.972506 --9.54718 , -0.878293 , -0.944411 , 0.0309018,0.668026,0.743496 --10.9422 , -0.195918 , 3.37473 , -0.432025,0.312756,0.845895 --10.4341 , -0.137752 , 3.46688 , 0.570704,-0.102,-0.814796 --10.1681 , -0.091865 , 3.6006 , 0.754613,-0.54096,-0.371378 --10.2495 , -0.0586153 , 3.81574 , -0.934508,-0.189939,0.301029 --10.6067 , -0.0327105 , 4.11168 , 0.975136,-0.198648,0.0982273 --8.0704 , 0.0710153 , 3.56889 , 0.472019,-0.361214,-0.80419 --8.08322 , 0.100942 , 3.73335 , 0.472019,-0.361215,-0.80419 --8.1223 , 0.130126 , 3.90845 , -0.918635,0.392514,0.0451966 --7.98745 , 0.162066 , 4.026 , 0.921811,-0.325192,-0.210987 --10.044 , 0.16749 , 4.95403 , -0.945889,0.0432796,0.321591 --8.19716 , 0.220849 , 4.43889 , -0.539949,-0.824881,0.167408 --7.71264 , 0.255018 , 4.41248 , 0.147652,0.968601,-0.200025 --7.44243 , 0.286483 , 4.46148 , -0.373905,0.673314,-0.637843 --7.51049 , 0.316075 , 4.65458 , -0.916081,0.38558,-0.110103 --6.78735 , 0.342218 , 4.4794 , -0.566076,0.114166,0.816409 --7.86599 , 0.381852 , 5.16512 , 0.608533,0.748661,-0.263049 --7.7316 , 0.412447 , 5.27563 , 0.189443,-0.766273,0.613952 --5.93954 , 0.413569 , 4.49386 , 0.691283,-0.571472,-0.442206 --5.92267 , 0.439281 , 4.62787 , 0.878817,-0.223812,0.421412 --6.05837 , 0.470117 , 4.85256 , -0.940705,0.111375,-0.320423 --6.19727 , 0.501898 , 5.0881 , -0.710923,-0.124608,-0.692143 --6.08376 , 0.527547 , 5.17515 , 0.744975,-0.666796,0.019888 --5.9859 , 0.552519 , 5.27065 , 0.131547,0.208995,-0.969029 --5.88666 , 0.577723 , 5.36383 , -0.504506,-0.753319,-0.421882 --6.14615 , 0.619801 , 5.7076 , 0.536457,-0.827746,0.164468 --6.04845 , 0.646934 , 5.80825 , 0.738344,0.624399,0.2549 --5.93296 , 0.672043 , 5.89506 , 0.74226,0.668753,-0.0426627 --7.04325 , 0.774917 , 6.93911 , -0.964348,-0.238938,-0.11376 --6.25681 , 0.759709 , 6.51351 , 0.804972,-0.540854,-0.243919 --6.16833 , 0.789068 , 6.63414 , 0.767535,-0.631273,-0.111284 --6.39414 , 0.843726 , 7.02816 , -0.979464,0.175287,0.0996229 --6.04398 , 0.852068 , 6.92439 , -0.780339,0.588545,-0.211391 --6.64158 , 0.945033 , 7.68714 , -0.719522,-0.694389,-0.0106025 --7.02048 , 1.02423 , 8.2851 , -0.23877,0.605634,0.759076 --6.90042 , 1.05894 , 8.4186 , 0.303001,-0.582127,-0.754532 --6.65962 , 1.08014 , 8.42857 , -0.570951,0.340981,0.746825 --6.54305 , 1.11392 , 8.56355 , -0.644376,0.377054,0.665289 --6.43691 , 1.14979 , 8.71138 , 0.776528,-0.185284,-0.602225 --6.81396 , 1.24896 , 9.41289 , -0.862526,0.256274,-0.436318 --6.85867 , 1.30974 , 9.76402 , 0.902935,-0.38619,0.188587 --5.71837 , 1.20063 , 8.6751 , 0.253055,-0.967234,0.0205499 --5.55249 , 1.22653 , 8.73979 , -0.253056,0.967234,-0.0205499 --7.28755 , 1.55943 , 11.3068 , -0.968586,-0.147158,-0.200464 --5.68506 , 1.35479 , 9.49375 , -0.0939933,0.995436,-0.0165082 --3.47812 , 1.01437 , 6.67914 , 0.34393,-0.782867,0.518489 --3.43415 , 1.04479 , 6.82768 , -0.955223,-0.0744083,0.286378 --3.72993 , 1.14508 , 7.50004 , 0.48199,0.536789,0.692491 --2.78394 , 0.990963 , 6.25067 , -0.172163,0.824487,0.539056 --3.49028 , 1.18658 , 7.6217 , 0.128706,0.638071,0.759144 --2.99477 , 1.11877 , 7.03561 , -0.898063,-0.37599,-0.228288 --2.85474 , 1.12972 , 7.03277 , -0.88059,-0.432859,0.192857 --1.35414 , 0.782578 , 4.49187 , 0.0620225,0.615397,0.785774 --1.2749 , 0.788209 , 4.48705 , -0.128195,-0.1663,-0.977707 --1.19173 , 0.791773 , 4.47188 , 0.212293,0.378894,0.900762 --2.72256 , 1.29387 , 7.87082 , 0.0207075,0.220082,0.975261 --2.14193 , 1.1625 , 6.9026 , -0.675279,0.0204851,-0.737278 --1.9283 , 1.14129 , 6.6908 , 0.413825,0.334189,0.846798 --2.25627 , 1.31402 , 7.7753 , 0.251611,0.962686,0.0996391 --2.11256 , 1.32259 , 7.75529 , 0.470381,-0.347024,0.811367 --1.9016 , 1.30068 , 7.54704 , -0.547497,-0.156347,0.822072 --0.993759 , 0.963011 , 5.31631 , -0.864721,-0.436529,0.248396 --0.595118 , 0.820057 , 4.36357 , 0.345059,-0.846007,0.406457 --0.577464 , 0.848832 , 4.51329 , -0.581388,0.710814,-0.395894 --1.41281 , 1.35019 , 7.60476 , 0.693907,-0.614208,0.375823 --1.16187 , 1.285 , 7.13934 , 0.534773,-0.654735,0.534172 --0.898615 , 1.19796 , 6.55283 , -0.605432,-0.300469,-0.737001 --0.783406 , 1.1979 , 6.4977 , -0.303118,-0.742534,-0.597296 --0.688232 , 1.21092 , 6.52724 , 0.303752,0.161816,0.938909 --0.489509 , 1.13581 , 6.03263 , -0.548004,-0.556814,-0.624219 --0.410914 , 1.15368 , 6.09622 , -0.806921,0.0252141,-0.590122 --0.41284 , 1.26039 , 6.67432 , -0.0452868,0.653552,0.755526 --0.318621 , 1.27735 , 6.72685 , 0.497621,0.720109,-0.483545 --0.210557 , 1.27762 , 6.67995 , 0.636594,0.0664657,0.768329 --0.0992438 , 1.26865 , 6.58224 , 0.0252953,0.160681,0.986682 --2.76267 , -0.265417 , -1.15054 , -0.0428524,0.146848,0.98823 --2.89295 , -0.272478 , -1.15279 , -0.0559495,0.129819,0.989958 --3.04047 , -0.281869 , -1.16155 , -0.104708,0.136928,0.985032 --3.23308 , -0.297084 , -1.19148 , -0.0870455,0.1553,0.984025 --3.38448 , -0.304585 , -1.19069 , -0.0684447,0.164258,0.98404 --3.58011 , -0.31775 , -1.20928 , -0.07549,0.161449,0.98399 --3.76924 , -0.328233 , -1.2173 , -0.0978227,0.157669,0.982635 --4.02112 , -0.347317 , -1.25056 , -0.103718,0.156401,0.982233 --4.25867 , -0.362328 , -1.26734 , -0.0816079,0.15937,0.98384 --4.51584 , -0.377921 , -1.28503 , -0.0847324,0.156245,0.984077 --4.81105 , -0.397251 , -1.31047 , -0.0983576,0.151722,0.983517 --5.14565 , -0.420636 , -1.34173 , -0.0950346,0.165852,0.981561 --5.50116 , -0.443422 , -1.36975 , -0.0984993,0.174156,0.979779 --5.89705 , -0.468305 , -1.40041 , -0.0794408,0.168889,0.982428 --6.31354 , -0.494114 , -1.42468 , -0.0842524,0.163313,0.98297 --6.83751 , -0.528332 , -1.471 , -0.0989751,0.16031,0.982092 --7.46886 , -0.571848 , -1.53339 , 0.0994768,-0.15129,-0.983471 --8.14269 , -0.615473 , -1.58628 , -0.0817308,0.286759,0.95451 --9.01212 , -0.675081 , -1.6713 , -0.0616104,0.183444,0.981098 --9.92668 , -0.732237 , -1.73763 , -0.355422,0.476847,0.803923 --11.0487 , -0.804993 , -1.82308 , -0.0852445,0.165316,0.98255 --12.3417 , -0.885854 , -1.90876 , -0.0851038,0.181784,0.979649 --13.866 , -0.978494 , -1.9982 , 0.0652634,-0.192294,-0.979165 --15.7294 , -1.09059 , -2.1003 , 0.216636,0.196948,0.95618 --17.7884 , -1.20676 , -2.17205 , -0.00677308,0.117908,0.993002 --59.5661 , -3.30775 , -2.15473 , -0.0122276,0.497098,0.867608 --10.6596 , 0.154375 , 3.35429 , -0.460202,0.363754,0.809875 --10.4238 , 0.19269 , 3.50156 , 0.5456,-0.818443,-0.180198 --10.3216 , 0.22947 , 3.67437 , -0.853963,0.292042,-0.43065 --10.6336 , 0.263792 , 3.95349 , -0.661419,-0.741356,0.113648 --10.5917 , 0.300831 , 4.14674 , 0.763542,-0.632291,0.131193 --10.4405 , 0.337762 , 4.30785 , -0.958514,0.0876396,0.271238 --8.13306 , 0.358527 , 3.78073 , 0.921811,-0.325192,-0.210987 --10.0181 , 0.408059 , 4.57908 , -0.900324,-0.0297635,0.434202 --10.182 , 0.447954 , 4.83909 , -0.925214,0.0112166,0.37928 --10.1984 , 0.484933 , 5.05349 , -0.956218,0.0703622,0.284071 --9.90467 , 0.517852 , 5.14781 , -0.956218,0.0703622,0.284071 --8.33599 , 0.516406 , 4.7049 , -0.434161,-0.740097,0.513575 --8.61859 , 0.556698 , 5.00737 , 0.767845,-0.522567,-0.370592 --6.97514 , 0.537373 , 4.446 , 0.00185441,-0.334713,0.942318 --6.76172 , 0.557753 , 4.50037 , 0.0716311,-0.301123,0.950891 --6.75359 , 0.585895 , 4.65086 , 0.0716311,-0.301123,0.950891 --7.98506 , 0.668437 , 5.44697 , -0.128623,0.338673,0.932071 --7.8453 , 0.695749 , 5.55821 , -0.400829,-0.412231,0.81817 --7.14733 , 0.69331 , 5.35194 , -0.312104,0.643902,-0.698556 --7.21689 , 0.729104 , 5.5681 , 0.329333,-0.940921,0.0787838 --6.42942 , 0.714378 , 5.26766 , 0.388874,-0.236045,0.890539 --6.17745 , 0.727718 , 5.27334 , 0.179721,0.292565,0.939205 --6.22754 , 0.760774 , 5.46916 , 0.712016,0.691685,-0.12085 --6.95636 , 0.845223 , 6.13536 , 0.3335,0.942202,0.0321371 --6.22289 , 0.822152 , 5.80616 , -0.55734,-0.788052,-0.261431 --6.38804 , 0.867974 , 6.10338 , -0.690555,-0.676947,-0.254709 --6.5133 , 0.911952 , 6.38364 , 0.611049,0.676146,-0.411637 --7.61533 , 1.04963 , 7.4483 , -0.944635,-0.307577,0.114288 --7.23924 , 1.05495 , 7.3711 , -0.767796,-0.153625,-0.622004 --6.34436 , 1.0033 , 6.83856 , -0.754065,0.439306,-0.488258 --6.0838 , 1.01192 , 6.81655 , -0.754065,0.439306,-0.488258 --6.17376 , 1.0598 , 7.10206 , -0.841296,-0.0504425,-0.538216 --7.53231 , 1.26231 , 8.59336 , 0.319987,0.787768,0.526336 --6.87761 , 1.22795 , 8.22198 , 0.465791,-0.397894,-0.790392 --6.70144 , 1.25034 , 8.29728 , -0.417782,0.364644,0.832162 --6.53769 , 1.27378 , 8.38302 , 0.69692,-0.160166,-0.699035 --1.47316 , 0.583362 , 3.17108 , -0.268288,0.32524,0.906775 --6.3359 , 1.33891 , 8.68493 , -0.925304,-0.152742,0.347106 --6.8041 , 1.46326 , 9.50029 , -0.862526,0.256274,-0.436318 --5.732 , 1.33811 , 8.51599 , -0.164702,0.707817,0.686927 --5.61162 , 1.36682 , 8.63616 , 0.223902,-0.972769,-0.0599007 --7.17742 , 1.70386 , 10.9288 , -0.968586,-0.147158,-0.200464 --7.18084 , 1.76943 , 11.2967 , -0.968586,-0.147158,-0.200464 --6.62705 , 1.72751 , 10.9101 , -0.97885,-0.0590804,-0.195861 --3.41732 , 1.12035 , 6.66991 , -0.914928,0.393414,0.0901813 --3.61065 , 1.20105 , 7.17261 , -0.617704,0.641086,-0.455466 --3.68535 , 1.26209 , 7.52463 , 0.249134,-0.150208,0.95675 --3.34043 , 1.22458 , 7.22391 , -0.259233,0.938923,-0.226322 --3.26644 , 1.25082 , 7.34767 , -0.253684,-0.889841,-0.379246 --2.9565 , 1.21554 , 7.06656 , -0.725722,-0.683203,-0.0809942 --1.40123 , 0.827226 , 4.4938 , -0.111404,0.588302,0.800931 --1.33157 , 0.832873 , 4.50799 , -0.139709,-0.471243,-0.870868 --1.25179 , 0.836253 , 4.5031 , 0.085404,0.467094,0.880074 --2.08766 , 1.1354 , 6.38577 , -0.502643,-0.0458096,0.86328 --2.67914 , 1.3818 , 7.91094 , -0.389282,-0.744307,-0.542648 --1.99823 , 1.19652 , 6.69614 , -0.580501,-0.363458,-0.728641 --1.89753 , 1.20851 , 6.73753 , 0.443744,0.408468,0.79765 --2.18231 , 1.37682 , 7.74083 , 0.233205,0.969027,0.0812545 --0.949976 , 0.915434 , 4.85544 , -0.253976,-0.147333,0.955923 --1.84745 , 1.35981 , 7.55736 , 0.406745,0.114929,-0.906284 --0.629102 , 0.841284 , 4.35943 , 0.492522,-0.507047,0.707337 --0.571177 , 0.847541 , 4.37775 , 0.345059,-0.846007,0.406457 --0.506215 , 0.851072 , 4.37614 , 0.015331,-0.461,0.887268 --1.41704 , 1.42996 , 7.82222 , -0.45945,-0.0365197,-0.887453 --0.994414 , 1.24862 , 6.70797 , -0.802015,-0.24984,-0.542542 --0.844642 , 1.22413 , 6.5307 , -0.437292,0.0699281,-0.896597 --0.723553 , 1.21547 , 6.44618 , 0.295376,0.118235,0.948037 --0.549145 , 1.15913 , 6.08901 , -0.965579,0.133007,0.223531 --0.463603 , 1.16956 , 6.125 , 0.061914,-0.389388,0.918991 --0.354357 , 1.15914 , 6.03301 , 0.856942,-0.515117,-0.0174884 --0.361753 , 1.27409 , 6.66969 , -0.320761,-0.820768,0.472708 --0.263592 , 1.28288 , 6.69259 , -0.436776,0.88993,0.131344 --0.151107 , 1.2708 , 6.59649 , 0.266395,-0.484525,0.833228 --0.0534184 , 1.27997 , 6.61558 , 0.677542,0.703862,-0.213341 --2.69744 , -0.164274 , -1.16256 , -0.00849708,0.170171,0.985378 --2.82664 , -0.167946 , -1.16745 , -0.0430961,0.158446,0.986427 --2.97477 , -0.172589 , -1.17939 , -0.082989,0.149425,0.985284 --3.14022 , -0.179386 , -1.19706 , -0.10952,0.148664,0.982804 --3.30821 , -0.185563 , -1.20973 , -0.0731911,0.159906,0.984415 --3.48643 , -0.191293 , -1.22233 , -0.0674785,0.168113,0.983455 --3.67418 , -0.197633 , -1.23406 , -0.0903205,0.168949,0.981478 --3.90014 , -0.206626 , -1.25863 , -0.108267,0.159279,0.981279 --4.13554 , -0.214815 , -1.28048 , -0.0901966,0.168471,0.981571 --4.39174 , -0.224389 , -1.30347 , -0.0766828,0.162559,0.983715 --4.65073 , -0.232617 , -1.31823 , -0.0874074,0.154734,0.984082 --4.9744 , -0.245705 , -1.35265 , -0.0966835,0.150067,0.983937 --5.31094 , -0.25744 , -1.38073 , -0.0967103,0.158684,0.982582 --5.69556 , -0.271383 , -1.4161 , -0.0863489,0.165525,0.982418 --6.10268 , -0.28593 , -1.44582 , -0.0794587,0.169656,0.982295 --6.5781 , -0.302517 , -1.48592 , -0.0899572,0.172372,0.980916 --7.12255 , -0.322278 , -1.5326 , -0.091666,0.162698,0.982409 --7.76649 , -0.346189 , -1.59152 , 0.0935774,-0.150325,-0.984198 --8.50028 , -0.372893 , -1.65475 , 0.0939398,-0.151306,-0.984013 --9.37384 , -0.404498 , -1.7313 , -0.0650333,0.212425,0.975011 --10.175 , -0.425916 , -1.75829 , -0.101165,0.193411,0.975888 --11.4354 , -0.471831 , -1.86957 , -0.0890723,0.166068,0.982083 --13.1899 , -0.540543 , -2.04787 , -0.0873762,0.162045,0.982907 --14.9933 , -0.601176 , -2.17481 , -0.0864195,-0.299003,-0.950331 --15.9122 , -0.601097 , -2.07162 , 0.722539,0.582202,0.372798 --15.9756 , -0.552326 , -1.79061 , 0.722538,0.582202,0.372799 --15.9256 , -0.498487 , -1.4915 , 0.722538,0.582202,0.372799 --56.1046 , -1.90961 , -4.70987 , -0.0122277,0.497097,0.867609 --23.8772 , -0.352755 , 0.248061 , 0.0495156,0.182864,0.981891 --9.94443 , 0.438975 , 3.05775 , 0.493822,-0.642925,-0.58548 --9.9564 , 0.472819 , 3.24719 , -0.294717,0.750569,0.591429 --10.033 , 0.508247 , 3.45314 , -0.637673,0.764181,0.0969568 --9.69802 , 0.534932 , 3.5616 , 0.425424,0.61626,-0.66275 --9.38229 , 0.559959 , 3.66437 , 0.812952,0.132508,-0.567054 --9.51739 , 0.596258 , 3.88571 , 0.812952,0.132508,-0.567054 --9.23684 , 0.620388 , 3.9877 , -0.916295,0.0759776,0.393232 --10.2773 , 0.691578 , 4.50632 , -0.869929,0.00870076,0.493101 --12.0028 , 0.797289 , 5.30007 , 0.319555,0.447975,0.834987 --10.2903 , 0.765863 , 4.92502 , 0.782259,0.409927,-0.469074 --8.55825 , 0.722108 , 4.47845 , -0.505912,-0.497016,0.705002 --8.58912 , 0.755903 , 4.6704 , 0.432388,0.56271,-0.704555 --8.49662 , 0.78381 , 4.81417 , 0.697399,0.480642,-0.531619 --8.10915 , 0.793479 , 4.82729 , -0.733842,-0.266727,0.624767 --7.23365 , 0.771605 , 4.60265 , 0.0095465,-0.318718,0.947802 --6.8643 , 0.776746 , 4.58748 , 0.0716311,-0.301123,0.950891 --6.73851 , 0.796653 , 4.68178 , 0.714133,-0.602863,0.355767 --6.69951 , 0.821811 , 4.81931 , -0.66031,0.501399,-0.559097 --7.06933 , 0.879312 , 5.1816 , 0.535649,-0.808645,0.243254 --7.37673 , 0.934883 , 5.52811 , -0.40552,0.553287,-0.727618 --6.91927 , 0.928023 , 5.43875 , 0.213654,-0.871889,0.440638 --6.55211 , 0.926221 , 5.38747 , 0.37373,0.810973,-0.450164 --6.48186 , 0.950627 , 5.51311 , 0.3687,0.822655,-0.43278 --6.44376 , 0.976877 , 5.65988 , -0.625725,-0.763147,0.161478 --4.88543 , 0.848347 , 4.75903 , -0.346686,-0.37217,0.860987 --7.10315 , 1.11108 , 6.48684 , -0.883738,-0.453195,0.116714 --6.7574 , 1.10865 , 6.43225 , -0.376109,-0.785776,0.491017 --7.49 , 1.22956 , 7.19375 , -0.714297,-0.320841,-0.621965 --7.47362 , 1.26807 , 7.40408 , 0.971559,0.161202,0.173458 --7.03744 , 1.25373 , 7.2735 , 0.075504,-0.212256,0.974293 --6.4127 , 1.21075 , 6.96156 , 0.446467,-0.176619,0.877196 --7.30468 , 1.37164 , 7.96355 , -0.817388,0.105481,0.566348 --7.05663 , 1.37914 , 7.98198 , -0.301942,0.484892,0.820799 --7.00497 , 1.41557 , 8.17886 , -0.585573,-0.28929,0.757242 --6.81356 , 1.43095 , 8.24361 , -0.695942,-0.498655,0.516728 --6.66459 , 1.45315 , 8.34632 , 0.835184,0.546636,-0.0604705 --1.50016 , 0.632369 , 3.15214 , -0.409148,0.251345,0.877168 --1.46279 , 0.638577 , 3.18621 , 0.352435,-0.041232,-0.934928 --6.55052 , 1.57599 , 9.02429 , 0.755123,0.647034,0.105525 --1.3405 , 0.643526 , 3.19914 , -0.241432,-0.362072,0.900341 --4.35987 , 1.25055 , 6.9466 , 0.378544,0.917848,-0.119414 --7.23421 , 1.87651 , 10.7813 , -0.97885,-0.0590804,-0.195861 --7.27206 , 1.94811 , 11.1877 , -0.968586,-0.147158,-0.200464 --6.89705 , 1.93188 , 11.056 , -0.968586,-0.147158,-0.200464 --1.58548 , 0.776861 , 3.9699 , -0.43127,-0.315043,-0.845431 --3.10836 , 1.16178 , 6.30151 , -0.227104,-0.973769,0.0140519 --2.85082 , 1.13376 , 6.11435 , 0.112999,0.613285,0.781737 --3.12202 , 1.23917 , 6.73939 , 0.445292,-0.300816,-0.843342 --3.00481 , 1.248 , 6.77512 , 0.713072,0.688725,-0.131095 --3.108 , 1.31947 , 7.18393 , -0.255726,-0.966115,0.0350108 --3.12026 , 1.36824 , 7.46022 , 0.590021,0.649207,0.480007 --1.33955 , 0.866103 , 4.44079 , -0.114761,0.723542,0.680674 --1.28389 , 0.874208 , 4.48052 , -0.185711,0.589648,0.786019 --1.18729 , 0.868086 , 4.43976 , 0.20713,0.279829,0.93744 --1.09728 , 0.863908 , 4.40558 , 0.20713,0.279829,0.93744 --2.41259 , 1.38414 , 7.46546 , -0.171744,0.542946,0.822018 --1.88661 , 1.23351 , 6.56196 , -0.836969,-0.291786,0.462974 --1.05198 , 0.937893 , 4.81141 , -0.468921,0.0769885,0.879878 --0.988683 , 0.945252 , 4.84654 , -0.324318,-0.0894064,0.941714 --0.972501 , 0.975155 , 5.01008 , -0.825066,0.4773,-0.30241 --1.00639 , 1.03156 , 5.33278 , -0.935959,-0.056939,0.347474 --0.604214 , 0.868618 , 4.37402 , 0.492521,-0.507046,0.707338 --0.551281 , 0.87684 , 4.41106 , -0.0115505,-0.367071,0.930121 --0.482901 , 0.876512 , 4.39998 , 0.0306386,-0.374577,0.92669 --1.24875 , 1.40193 , 7.4321 , -0.743275,0.474795,-0.471288 --0.913566 , 1.25899 , 6.59108 , 0.700039,-0.128938,0.702368 --0.785779 , 1.24303 , 6.48949 , 0.378679,0.141127,0.914705 --0.636433 , 1.20666 , 6.26964 , -0.912314,-0.0997962,-0.397145 --0.487412 , 1.16372 , 6.00757 , 0.303063,-0.00885764,0.95293 --0.397928 , 1.16598 , 6.01393 , -0.134054,0.746329,0.651938 --0.408015 , 1.27653 , 6.63126 , 0.120996,0.639361,0.759327 --0.304106 , 1.27607 , 6.61639 , 0.503605,-0.789615,-0.350557 --0.21356 , 1.2925 , 6.69744 , -0.617669,0.000905399,0.786438 --0.100017 , 1.27388 , 6.5812 , 0.671251,0.354842,0.650776 --2.75774 , -0.0647688 , -1.18048 , 0.0466322,-0.184168,-0.981788 --2.8883 , -0.0647166 , -1.18425 , -0.0398842,0.189908,0.980991 --3.03663 , -0.0648327 , -1.19487 , -0.0929525,0.181444,0.978999 --3.22073 , -0.0678699 , -1.22177 , -0.0943226,0.156097,0.983228 --3.38871 , -0.0684582 , -1.23282 , -0.0768589,0.169749,0.982486 --3.57679 , -0.0692747 , -1.2487 , -0.0815703,0.175292,0.981132 --3.78308 , -0.0705299 , -1.26821 , -0.0972662,0.184441,0.978019 --4.01778 , -0.0735643 , -1.29477 , -0.0966735,0.169201,0.980829 --4.25497 , -0.0744986 , -1.31418 , -0.0807932,0.170089,0.982111 --4.51275 , -0.0757776 , -1.33454 , -0.0731496,0.171333,0.982494 --4.78999 , -0.0764894 , -1.35513 , -0.0876453,0.166067,0.982212 --5.10685 , -0.078275 , -1.38265 , -0.103364,0.149322,0.983371 --5.49933 , -0.0833303 , -1.43018 , -0.0969104,0.165643,0.981413 --5.89494 , -0.0860067 , -1.4649 , -0.08122,0.169873,0.982113 --6.32259 , -0.0876414 , -1.49742 , -0.0854769,0.171952,0.98139 --6.83736 , -0.0909399 , -1.54582 , -0.0883204,0.171869,0.981153 --7.40282 , -0.0940158 , -1.59291 , -0.0899868,0.164122,0.982327 --8.10546 , -0.100445 , -1.66302 , -0.0946247,0.156469,0.98314 --8.91844 , -0.106386 , -1.74106 , -0.0906763,0.154742,0.983785 --9.82361 , -0.111872 , -1.81558 , -0.0608324,0.210851,0.975624 --10.9951 , -0.120089 , -1.92762 , -0.0876888,0.172203,0.981151 --12.1924 , -0.123011 , -2.00454 , 0.0840753,-0.166788,-0.982402 --14.0591 , -0.137744 , -2.18839 , -0.0858879,0.160107,0.983356 --16.1217 , -0.146921 , -2.34656 , 0.928387,0.354655,0.110981 --16.0799 , -0.0941521 , -2.04206 , 0.928387,0.354655,0.110981 --19.0064 , -0.0405119 , -1.8961 , -0.0383804,0.273203,0.96119 --10.406 , 0.740901 , 2.99403 , -0.690172,-0.690493,0.216523 --9.95705 , 0.754647 , 3.10033 , -0.579715,-0.538122,0.611846 --10.0163 , 0.790936 , 3.3008 , 0.509512,0.620979,-0.595637 --10.179 , 0.832343 , 3.52901 , 0.613172,0.535153,-0.581061 --9.56139 , 0.833553 , 3.56857 , 0.619521,0.358744,-0.698209 --9.44772 , 0.860498 , 3.72288 , -0.768932,-0.328663,0.548383 --9.29189 , 0.883555 , 3.86322 , -0.838609,-0.0832432,0.538336 --9.45075 , 0.925932 , 4.0956 , -0.774205,-0.225498,0.591403 --9.19533 , 0.941334 , 4.2015 , 0.682683,0.227633,-0.694354 --9.19462 , 0.974419 , 4.38722 , 0.521948,0.114897,-0.845204 --10.0051 , 1.06762 , 4.87133 , -0.729328,-0.34876,-0.588597 --11.0892 , 1.18726 , 5.4954 , 0.335028,0.168185,0.927076 --11.0085 , 1.22106 , 5.69412 , -0.335028,-0.168185,-0.927076 --11.0334 , 1.2642 , 5.93815 , 0.335028,0.168185,0.927076 --8.18545 , 1.057 , 4.90712 , -0.488211,0.853533,0.182018 --8.35059 , 1.1042 , 5.16539 , 0.807886,-0.134519,-0.573781 --6.59231 , 0.969979 , 4.49636 , -0.18733,0.682466,0.706504 --6.44987 , 0.98295 , 4.57713 , -0.138663,0.678528,0.721368 --6.43878 , 1.00862 , 4.72429 , 0.690523,-0.0683767,0.720072 --6.98998 , 1.09481 , 5.18551 , 0.535649,-0.808645,0.243254 --5.70784 , 0.982969 , 4.61781 , -0.390076,-0.0884369,0.916526 --7.37606 , 1.19994 , 5.7631 , 0.998678,0.0502883,0.0106619 --6.8774 , 1.17376 , 5.63995 , -0.273063,-0.844804,0.460155 --6.66044 , 1.17869 , 5.67978 , 0.410006,0.460339,0.78739 --5.21579 , 1.02597 , 4.88621 , -0.0634701,-0.340142,0.93823 --4.89406 , 1.00873 , 4.80758 , -0.346686,-0.37217,0.860987 --4.87494 , 1.03141 , 4.93473 , 0.681661,0.448599,-0.578012 --7.16393 , 1.38021 , 6.79979 , -0.867177,-0.115758,-0.48436 --7.41263 , 1.45454 , 7.20554 , -0.714297,-0.320841,-0.621965 --7.36468 , 1.48632 , 7.39076 , 0.971559,0.161202,0.173458 --3.20704 , 0.876046 , 4.14184 , 0.249125,-0.132545,-0.959358 --7.3966 , 1.57364 , 7.88518 , 0.250115,-0.954219,-0.164039 --6.43891 , 1.45689 , 7.27087 , 0.263361,-0.249229,0.931947 --7.01767 , 1.59617 , 8.03115 , 0.45329,0.614805,-0.645401 --6.71432 , 1.58551 , 7.9876 , -0.695942,-0.498655,0.516728 --6.94781 , 1.67255 , 8.46778 , -0.695941,-0.498655,0.516729 --1.53916 , 0.686129 , 3.14686 , -0.197547,0.302293,0.932521 --1.45456 , 0.68186 , 3.1311 , 0.42302,-0.463976,-0.778319 --1.41026 , 0.686747 , 3.15694 , -0.604519,0.197881,0.771622 --1.3983 , 0.696778 , 3.2196 , 0.413025,0.0512223,-0.909278 --1.30252 , 0.689764 , 3.18371 , -0.37821,0.354323,0.855226 --4.27102 , 1.37534 , 6.91969 , -0.293472,-0.94128,0.166929 --4.15894 , 1.387 , 6.99335 , 0.293472,0.94128,-0.166929 --1.31086 , 0.735463 , 3.43971 , -0.837549,0.460527,0.293983 --1.63469 , 0.832076 , 3.97463 , -0.43127,-0.315044,-0.845431 --1.46836 , 0.808925 , 3.84896 , -0.335885,-0.379802,-0.861935 --1.38572 , 0.805152 , 3.83325 , 0.322254,0.349469,0.879786 --1.31364 , 0.80391 , 3.83233 , -0.243727,-0.468075,-0.849413 --1.23744 , 0.80164 , 3.82125 , -0.207814,0.951494,0.226874 --3.05629 , 1.37037 , 6.95909 , 0.503901,0.845908,0.17471 --1.39476 , 0.891377 , 4.32438 , -0.356835,0.740173,0.569923 --1.34157 , 0.898206 , 4.36514 , 0.356835,-0.740173,-0.569923 --1.27756 , 0.901735 , 4.38771 , -0.246695,0.729135,0.63836 --1.07879 , 0.856824 , 4.14521 , -0.835952,0.455601,-0.305961 --1.14926 , 0.907958 , 4.42917 , 0.0508626,0.424853,0.903832 --2.52833 , 1.46995 , 7.5534 , 0.426607,0.677203,0.599502 --1.14331 , 0.963704 , 4.74564 , -0.3114,-0.0230619,0.949999 --1.08156 , 0.969704 , 4.7825 , 0.446795,-0.113627,-0.887391 --1.02546 , 0.978617 , 4.83678 , -0.503822,-0.14617,0.851351 --0.954915 , 0.980334 , 4.85336 , 0.154776,0.0453706,-0.986907 --0.99743 , 1.03944 , 5.18386 , 0.998281,0.0450929,0.0374447 --0.975211 , 1.0701 , 5.35827 , -0.690701,-0.082817,0.718382 --0.634729 , 0.927731 , 4.56685 , -0.922455,0.190894,-0.335613 --0.512378 , 0.894967 , 4.38787 , -0.0115505,-0.367071,0.930121 --1.38872 , 1.4868 , 7.70449 , 0.632452,0.770983,-0.0747722 --1.13629 , 1.40073 , 7.23136 , -0.830629,0.337351,-0.443001 --0.847766 , 1.27547 , 6.5313 , 0.543234,-0.244458,0.803204 --0.763165 , 1.28798 , 6.61167 , 0.386679,-0.639937,0.664048 --0.531432 , 1.17753 , 5.99623 , -0.775121,-0.0675115,-0.628195 --0.463648 , 1.19897 , 6.11979 , 0.000958383,-0.411496,0.911411 --0.350493 , 1.17653 , 5.99987 , 0.578301,-0.695472,-0.426483 --0.374723 , 1.30846 , 6.74391 , -0.159131,-0.794129,0.586546 --0.234599 , 1.25904 , 6.47544 , -0.639639,-0.15021,-0.753856 --0.165153 , 1.30038 , 6.71221 , -0.276031,0.0265249,0.960783 --0.0536944 , 1.28308 , 6.61506 , 0.677542,0.703862,-0.213341 --2.71145 , 0.0304183 , -1.20839 , -0.0367928,0.192865,0.980535 --2.83312 , 0.0352495 , -1.20889 , -0.036851,0.19286,0.980534 --2.97249 , 0.0397805 , -1.2168 , -0.0666547,0.181853,0.981064 --3.1299 , 0.0432795 , -1.23096 , -0.0893099,0.17576,0.980373 --3.2975 , 0.0471367 , -1.24545 , -0.0831983,0.167141,0.982416 --3.4842 , 0.0504847 , -1.26494 , -0.0883194,0.17488,0.980621 --3.68096 , 0.0554501 , -1.2836 , -0.082173,0.186227,0.979064 --3.88828 , 0.0601958 , -1.30073 , -0.0955884,0.179082,0.979179 --4.13343 , 0.0645228 , -1.32964 , -0.0931785,0.175173,0.980118 --4.38013 , 0.0708008 , -1.35098 , -0.080034,0.175569,0.981208 --4.64747 , 0.0768658 , -1.37267 , -0.0783186,0.178433,0.98083 --4.9539 , 0.0835842 , -1.40247 , -0.0881847,0.172596,0.981037 --5.30757 , 0.0905544 , -1.4419 , -0.105061,0.163389,0.980952 --5.68319 , 0.0985376 , -1.47734 , -0.089768,0.165166,0.982172 --6.09928 , 0.108664 , -1.51536 , -0.0853826,0.167956,0.98209 --6.58324 , 0.118785 , -1.56356 , -0.0901701,0.17024,0.981268 --7.10927 , 0.131477 , -1.60912 , -0.0863985,0.169143,0.981797 --7.72455 , 0.145139 , -1.66544 , -0.093013,0.163502,0.982149 --8.48607 , 0.160675 , -1.74562 , -0.0928229,0.163602,0.98215 --9.37748 , 0.17983 , -1.83691 , -0.0876443,0.15444,0.984107 --10.3616 , 0.203301 , -1.9219 , -0.0833188,0.161472,0.983354 --11.584 , 0.231072 , -2.03281 , -0.0705669,0.169723,0.982962 --12.8131 , 0.265905 , -2.10244 , 0.0884898,-0.160447,-0.98307 --14.9364 , 0.309984 , -2.32465 , -0.00494156,0.266158,0.963917 --16.5612 , 0.364365 , -2.37255 , 0.872865,0.47584,0.108088 --16.3903 , 0.415659 , -2.03755 , 0.872865,0.47584,0.108088 --16.3711 , 0.467277 , -1.7353 , 0.872865,0.47584,0.108088 --10.5728 , 1.0419 , 2.87282 , 0.619046,0.601994,-0.504366 --10.5472 , 1.07437 , 3.06505 , 0.619046,0.601994,-0.504366 --10.5279 , 1.1077 , 3.25899 , 0.619046,0.601994,-0.504366 --11.1876 , 1.19218 , 3.60253 , -0.194941,-0.38597,0.901679 --10.2369 , 1.15347 , 3.58928 , -0.624601,-0.504007,0.596532 --9.92775 , 1.16225 , 3.70726 , -0.498318,-0.529858,0.686243 --9.53187 , 1.16151 , 3.79171 , 0.505358,0.308656,-0.80582 --9.64295 , 1.20322 , 4.01207 , -0.526603,-0.327832,0.784357 --9.17836 , 1.19342 , 4.05897 , 0.669002,-0.0624662,-0.740631 --9.12291 , 1.22049 , 4.22536 , 0.669002,-0.0624662,-0.740631 --10.717 , 1.41173 , 4.97031 , 0.768254,0.544589,0.336465 --13.0903 , 1.6938 , 6.06821 , -0.165927,-0.970016,-0.177587 --10.7361 , 1.48978 , 5.42008 , -0.730941,-0.523435,-0.437882 --10.5631 , 1.51063 , 5.57546 , -0.730941,-0.523435,-0.437882 --12.7363 , 1.79522 , 6.73713 , -0.291171,0.561097,-0.774849 --6.77699 , 1.14684 , 4.32271 , 0.780828,-0.384993,-0.492025 --7.43564 , 1.25306 , 4.78754 , -0.168621,0.982922,0.0737006 --6.20864 , 1.12975 , 4.35205 , 0.197449,-0.755934,-0.624161 --6.22814 , 1.15755 , 4.50837 , -0.210348,0.517736,0.829279 --6.68985 , 1.24418 , 4.90637 , -0.823682,-0.0579714,-0.564081 --5.82232 , 1.15449 , 4.58339 , -0.326121,-0.00595665,0.945309 --5.62095 , 1.1525 , 4.61179 , 0.508725,0.205768,-0.835977 --7.19336 , 1.40349 , 5.71131 , 0.36693,-0.833023,0.414048 --7.12475 , 1.42558 , 5.85421 , 0.253598,0.967033,-0.0231459 --5.25473 , 1.17329 , 4.81529 , -0.0461793,-0.319297,0.946529 --5.30059 , 1.20564 , 4.99247 , -0.242402,-0.385448,0.890321 --4.92995 , 1.17145 , 4.8804 , -0.483205,-0.433925,0.760409 --5.01192 , 1.21007 , 5.08523 , -0.0899978,-0.499722,0.861498 --7.38362 , 1.6411 , 7.04017 , 0.751691,0.0591312,0.65686 --7.55532 , 1.70924 , 7.39662 , -0.932395,0.238443,-0.271634 --3.26251 , 0.975165 , 4.11769 , -0.249126,0.132546,0.959358 --3.15372 , 0.974394 , 4.13758 , -0.249125,0.132546,0.959358 --6.32622 , 1.5997 , 7.03507 , 0.790052,0.0331912,-0.612141 --6.08677 , 1.58922 , 7.03256 , -0.67343,-0.175678,0.718074 --6.07211 , 1.62417 , 7.2338 , -0.673431,-0.175678,0.718073 --4.53127 , 1.34198 , 5.95118 , -0.228614,0.276293,0.933487 --4.36619 , 1.33761 , 5.96015 , -0.279886,-0.0153799,0.95991 --1.50633 , 0.737719 , 3.14094 , -0.259124,0.302665,0.917196 --1.41431 , 0.729988 , 3.11737 , -0.332576,0.783802,0.52445 --1.4168 , 0.743454 , 3.19453 , 0.601863,-0.404682,-0.688471 --1.37761 , 0.747929 , 3.22748 , -0.39245,-0.314879,0.864196 --1.30757 , 0.744072 , 3.22164 , -0.967418,0.212807,0.137169 --1.26823 , 0.748107 , 3.25265 , 0.551476,0.635145,-0.5408 --1.25873 , 0.76015 , 3.32208 , 0.614775,0.410339,-0.673553 --1.21168 , 0.761544 , 3.34449 , 0.689815,0.380218,-0.616108 --1.52661 , 0.865817 , 3.87124 , -0.43127,-0.315044,-0.845431 --1.45898 , 0.864893 , 3.88173 , -0.335885,-0.379802,-0.861935 --1.3972 , 0.864745 , 3.89911 , -0.316127,-0.311047,-0.896278 --1.28774 , 0.850608 , 3.84015 , 0.360276,0.425504,0.830149 --1.05166 , 0.794569 , 3.5683 , -0.0399599,-0.565447,0.823816 --0.947076 , 0.777212 , 3.49305 , 0.115456,-0.577564,0.80814 --1.38862 , 0.947753 , 4.37552 , -0.396249,0.775108,0.492132 --1.32036 , 0.947624 , 4.39061 , 0.282005,-0.768666,-0.57413 --1.06482 , 0.877974 , 4.04598 , -0.835952,0.455601,-0.305961 --1.19977 , 0.953607 , 4.4521 , 0.0508626,0.424853,0.903832 --2.62227 , 1.55326 , 7.5945 , 0.561992,0.444192,0.697752 --1.18767 , 1.00432 , 4.75166 , -0.26105,-0.0258695,0.964979 --1.1214 , 1.00751 , 4.78034 , -0.295606,0.10041,0.950019 --1.05528 , 1.0095 , 4.80815 , 0.726614,-0.0849757,-0.681771 --1.01303 , 1.02316 , 4.89918 , -0.251992,-0.134276,0.958369 --0.916782 , 1.01141 , 4.85114 , -0.03798,-0.0713613,0.996727 --0.983032 , 1.08452 , 5.25627 , -0.939651,-0.112346,0.323162 --1.69363 , 1.52607 , 7.64598 , -0.396202,0.276729,0.875468 --0.562498 , 0.926831 , 4.44107 , -0.815643,-0.0510992,-0.576295 --1.38045 , 1.48122 , 7.45433 , -0.588549,-0.571321,-0.572016 --0.91752 , 1.24799 , 6.21408 , 0.542845,-0.827718,0.142134 --0.93186 , 1.32576 , 6.6581 , 0.614592,-0.373083,0.695044 --0.81388 , 1.31198 , 6.60596 , -0.195239,-0.159414,0.967713 --0.621407 , 1.23277 , 6.19559 , -0.571981,0.553721,-0.605171 --0.513954 , 1.21928 , 6.13736 , 0.212462,-0.336407,0.917437 --0.325955 , 1.12051 , 5.61213 , -0.377962,0.923841,-0.0605185 --0.380061 , 1.27023 , 6.46197 , 0.00804386,-0.98937,0.145197 --0.279705 , 1.26342 , 6.44776 , -0.50621,-0.177964,-0.843849 --0.213917 , 1.30375 , 6.69549 , -0.776129,0.539613,-0.326254 --0.0995929 , 1.27987 , 6.58019 , -0.377953,-0.859373,0.344426 --2.75909 , 0.134237 , -1.22079 , -0.0437902,0.186704,0.98144 --2.89739 , 0.142157 , -1.23134 , -0.0363321,0.183589,0.982332 --3.04581 , 0.150215 , -1.24319 , -0.0828932,0.192334,0.977822 --3.21206 , 0.158303 , -1.261 , -0.0827172,0.180079,0.980168 --3.37966 , 0.16777 , -1.27378 , -0.0895314,0.168505,0.981626 --3.57577 , 0.178022 , -1.29656 , -0.099329,0.186808,0.977362 --3.78145 , 0.187818 , -1.3178 , -0.0867137,0.180713,0.979706 --4.00788 , 0.199987 , -1.34224 , -0.0941415,0.177411,0.979624 --4.25268 , 0.212157 , -1.36837 , -0.087679,0.175104,0.980638 --4.50989 , 0.225972 , -1.39127 , -0.0830675,0.178008,0.980517 --4.79625 , 0.240852 , -1.41853 , -0.0741154,0.175716,0.981647 --5.07554 , 0.257752 , -1.43267 , -0.100169,0.175813,0.979314 --5.48519 , 0.275445 , -1.49237 , -0.101273,0.165783,0.980949 --5.8803 , 0.295972 , -1.53117 , -0.0860501,0.160985,0.983199 --6.30602 , 0.319272 , -1.56784 , -0.0910974,0.159519,0.982983 --6.82961 , 0.345795 , -1.62486 , -0.0926679,0.162009,0.982428 --7.41319 , 0.375204 , -1.68392 , -0.0925824,0.165378,0.981875 --8.08531 , 0.410093 , -1.75143 , -0.0903682,0.166277,0.981929 --8.84967 , 0.450193 , -1.82299 , -0.091432,0.161547,0.98262 --9.7996 , 0.499155 , -1.92157 , -0.0795665,0.17292,0.981717 --10.9105 , 0.556649 , -2.02955 , -0.0875266,0.173225,0.980985 --12.2893 , 0.628407 , -2.16584 , -0.0781388,0.163155,0.983501 --13.9382 , 0.715861 , -2.31635 , 0.0872172,-0.147394,-0.985225 --16.093 , 0.829808 , -2.51793 , 0.0220472,0.309028,0.950797 --18.5231 , 0.965998 , -2.69807 , -0.0383804,0.273203,0.961191 --19.0842 , 1.04519 , -2.45977 , -0.0383804,0.273203,0.96119 --19.2378 , 1.11009 , -2.13793 , -0.0383804,0.273203,0.96119 --11.9418 , 1.51159 , 3.15187 , 0.339081,0.70583,-0.621955 --11.3918 , 1.49457 , 3.271 , -0.250258,-0.360856,0.898417 --10.7144 , 1.45995 , 3.34614 , 0.38417,0.712596,-0.587044 --10.3403 , 1.45507 , 3.46567 , 0.595029,0.590392,-0.545324 --8.23513 , 1.25754 , 3.1543 , -0.012669,0.662361,0.749077 --8.14639 , 1.27474 , 3.29261 , -0.213217,0.811117,0.544635 --8.09383 , 1.29631 , 3.43915 , -0.213217,0.811117,0.544636 --8.40102 , 1.36086 , 3.69238 , -0.370488,0.534047,0.759956 --9.28824 , 1.49877 , 4.1433 , 0.669002,-0.0624665,-0.740631 --9.01302 , 1.49572 , 4.23963 , -0.732437,-0.187025,0.654643 --9.01258 , 1.6253 , 4.99674 , -0.69612,-0.436233,0.570191 --6.69477 , 1.32622 , 4.18122 , -0.674997,0.118226,0.728287 --6.16866 , 1.27484 , 4.09099 , 0.53039,-0.592656,-0.606173 --6.58611 , 1.362 , 4.43296 , -0.82224,-0.550022,0.146275 --6.23121 , 1.33419 , 4.40884 , 0.249012,-0.899652,-0.358636 --6.56395 , 1.41112 , 4.73178 , -0.70164,-0.315949,-0.638653 --5.87031 , 1.32615 , 4.51258 , -0.577235,-0.000257132,0.816578 --5.88431 , 1.35418 , 4.66648 , -0.597964,-0.23653,0.765828 --8.02397 , 1.74188 , 6.08171 , 0.618867,0.583293,-0.526092 --6.40623 , 1.49629 , 5.29046 , -0.3669,0.863895,0.345067 --5.55492 , 1.37328 , 4.91407 , -0.558104,-0.465892,0.686633 --5.08909 , 1.31434 , 4.75589 , -0.0131173,-0.650236,0.759619 --5.06968 , 1.3355 , 4.88619 , 0.258341,0.425857,-0.867125 --4.98359 , 1.34333 , 4.97111 , -0.372169,-0.6734,0.638766 --4.99146 , 1.37082 , 5.12467 , 0.431556,0.601363,-0.6724 --7.04459 , 1.80777 , 6.86055 , -0.00580599,0.438568,0.898679 --3.26876 , 1.06986 , 4.05503 , -0.249126,0.132546,0.959358 --3.19907 , 1.074 , 4.1076 , -0.249126,0.132546,0.959358 --3.08332 , 1.06788 , 4.12017 , -0.249126,0.132546,0.959358 --6.32143 , 1.80119 , 7.11542 , -0.515577,0.088514,0.852259 --4.67534 , 1.46714 , 5.81494 , -0.228614,0.276293,0.933487 --4.49664 , 1.45459 , 5.81598 , -0.228614,0.276293,0.933487 --4.48055 , 1.47977 , 5.97184 , -0.228614,0.276293,0.933487 --1.44583 , 0.770465 , 3.03671 , -0.322976,0.781618,0.533628 --1.44363 , 0.782243 , 3.10627 , -0.558558,0.668339,0.49126 --1.42037 , 0.788576 , 3.15447 , -0.451522,0.705281,0.546541 --1.32294 , 0.776423 , 3.12109 , 0.365275,-0.513957,-0.776159 --1.31755 , 0.788353 , 3.19014 , 0.0501754,0.954512,0.293919 --1.3228 , 0.803056 , 3.27503 , 0.889219,0.051493,-0.454575 --1.29435 , 0.808935 , 3.32218 , 0.614775,0.410339,-0.673553 --1.25328 , 0.811501 , 3.35323 , -0.712818,0.00808156,0.701302 --1.20645 , 0.811899 , 3.37565 , 0.868138,0.143214,-0.475212 --1.19307 , 0.823059 , 3.44546 , 0.941314,0.125836,-0.313198 --1.35446 , 0.890661 , 3.77618 , 0.360276,0.425504,0.830149 --1.28328 , 0.885481 , 3.77546 , 0.360276,0.425504,0.830149 --1.2294 , 0.885215 , 3.79804 , 0.150826,0.137789,-0.978911 --0.997461 , 0.82354 , 3.52448 , 0.0537183,-0.571637,0.818746 --0.957856 , 0.826161 , 3.55911 , 0.115456,-0.577564,0.80814 --1.09855 , 0.896979 , 3.91994 , -0.488277,-0.31922,0.812209 --1.02385 , 0.889888 , 3.90408 , -0.887911,0.42789,0.168892 --1.00399 , 0.903194 , 3.99199 , -0.813819,0.567491,-0.125109 --1.14973 , 0.987026 , 4.42474 , -0.0149537,0.177758,0.983961 --2.54781 , 1.62165 , 7.58255 , 0.47267,0.44161,0.762603 --1.16052 , 1.04814 , 4.7775 , 0.13732,0.0213417,-0.990297 --1.07479 , 1.03924 , 4.76103 , 0.364941,-0.0407332,-0.930139 --1.02323 , 1.04706 , 4.82488 , 0.731243,0.134403,-0.668745 --0.955513 , 1.0463 , 4.85147 , -0.150185,-0.0436657,0.987693 --0.888442 , 1.04644 , 4.87659 , -0.0833264,0.00559382,0.996507 --0.975312 , 1.13395 , 5.35689 , -0.939651,-0.112346,0.323162 --0.902138 , 1.13465 , 5.39199 , -0.690701,-0.0828168,0.718383 --0.516367 , 0.939382 , 4.39964 , 0.0356702,-0.318914,0.947112 --0.951336 , 1.26904 , 6.1586 , 0.542845,-0.827718,0.142134 --0.917374 , 1.30811 , 6.4028 , -0.489072,0.587012,0.645156 --0.860265 , 1.33496 , 6.58026 , 0.137443,0.662757,0.736113 --0.763584 , 1.33369 , 6.61365 , -0.0114714,-0.130624,0.991366 --0.554383 , 1.23327 , 6.1058 , 0.150384,-0.881393,0.447808 --0.466333 , 1.23199 , 6.13392 , 0.000958349,-0.411496,0.911411 --0.366373 , 1.2176 , 6.09281 , -0.583447,0.443396,-0.680433 --0.342161 , 1.29196 , 6.53606 , 0.0663773,0.990841,0.117594 --0.22871 , 1.26679 , 6.43373 , -0.639639,-0.150211,-0.753856 --0.155364 , 1.29509 , 6.63252 , 0.416564,-0.791935,0.446445 --0.0532299 , 1.28501 , 6.61476 , 0.677542,0.703862,-0.213341 --2.81941 , 0.240042 , -1.24384 , -0.0565756,0.174348,0.983058 --2.94952 , 0.251607 , -1.2473 , -0.0701978,0.176503,0.981794 --3.11538 , 0.264118 , -1.26865 , -0.0874368,0.183029,0.979212 --3.28162 , 0.277793 , -1.28484 , -0.0754946,0.178724,0.980999 --3.46747 , 0.293122 , -1.30637 , -0.0931757,0.178894,0.979446 --3.67227 , 0.309178 , -1.33183 , -0.0911053,0.177312,0.979929 --3.87875 , 0.325927 , -1.35089 , -0.0892031,0.180187,0.979579 --4.11393 , 0.344053 , -1.37734 , -0.0957962,0.174916,0.979912 --4.36898 , 0.364646 , -1.40551 , -0.0820554,0.176122,0.980942 --4.63552 , 0.386779 , -1.42985 , -0.080711,0.173587,0.981506 --4.93971 , 0.411275 , -1.46247 , -0.0831585,0.175047,0.981042 --5.27494 , 0.438788 , -1.49736 , -0.102421,0.154975,0.982595 --5.63062 , 0.468849 , -1.5292 , 0.0871237,-0.159597,-0.98333 --6.05398 , 0.502244 , -1.57517 , 0.0857228,-0.160431,-0.983318 --6.52628 , 0.540648 , -1.6251 , 0.0915739,-0.149532,-0.984507 --7.04041 , 0.582531 , -1.67276 , 0.0912036,-0.155992,-0.983539 --7.69018 , 0.634286 , -1.74878 , -0.0984469,0.154554,0.983067 --8.43042 , 0.693584 , -1.83069 , -0.0873505,0.15135,0.984613 --9.24191 , 0.759979 , -1.90778 , 0.0911609,-0.150395,-0.984414 --10.241 , 0.841475 , -2.00956 , -0.0837299,0.147843,0.98546 --11.4386 , 0.939125 , -2.12885 , -0.0892551,0.140312,0.986076 --12.9233 , 1.06093 , -2.27725 , -0.0859392,0.150485,0.98487 --14.7674 , 1.21206 , -2.45514 , 0.0875621,-0.138233,-0.986521 --17.0581 , 1.40256 , -2.66296 , -0.0893401,0.304732,0.948239 --27.6462 , 2.40621 , -2.89714 , -0.0262862,0.273772,0.961435 --11.8237 , 1.83303 , 2.9679 , -0.261237,0.272679,0.92596 --11.8038 , 1.8678 , 3.18469 , -0.261237,0.272679,0.92596 --11.625 , 1.88115 , 3.37159 , -0.190457,-0.0023464,0.981693 --11.0352 , 1.83988 , 3.46709 , -0.303926,-0.458537,0.835088 --8.37886 , 1.51115 , 3.07028 , 0.988867,0.118126,0.0904941 --8.36728 , 1.53745 , 3.23121 , 0.988867,0.118126,0.0904941 --8.25783 , 1.54903 , 3.36719 , -0.012669,0.662361,0.749077 --7.68024 , 1.49206 , 3.36727 , 0.238214,-0.219012,-0.946197 --7.69167 , 1.5205 , 3.5262 , 0.238214,-0.219012,-0.946197 --11.1483 , 2.07376 , 4.79925 , -0.980825,0.0240341,0.193401 --3.98985 , 1.01068 , 2.66455 , 0.954586,-0.225333,-0.19491 --9.17851 , 1.86959 , 4.73483 , -0.558671,0.710182,-0.428403 --6.88982 , 1.52305 , 4.0104 , 0.946093,0.323088,-0.0228718 --6.59748 , 1.4985 , 4.03875 , 0.213329,0.74249,0.63498 --6.19811 , 1.45446 , 4.00978 , 0.617909,-0.385939,-0.685011 --6.08978 , 1.45916 , 4.10108 , -0.805673,0.395411,0.441069 --6.10363 , 1.48509 , 4.25012 , -0.882969,0.429544,0.189359 --6.76576 , 1.63128 , 4.73127 , -0.921982,-0.0261195,0.38635 --5.92134 , 1.50049 , 4.44597 , -0.864167,-0.196436,0.46328 --5.85909 , 1.51343 , 4.55746 , -0.806312,-0.14951,0.572282 --5.69201 , 1.50477 , 4.60897 , -0.735284,-0.269923,0.62169 --5.68497 , 1.5285 , 4.75205 , -0.653891,-0.300442,0.694379 --5.80939 , 1.57919 , 4.97956 , -0.38409,-0.771054,0.507889 --5.86955 , 1.61782 , 5.17502 , 0.0918033,0.918404,0.384845 --5.34511 , 1.53413 , 4.9827 , -0.199543,-0.317327,0.927085 --4.38575 , 1.35247 , 4.46284 , -0.716687,0.096918,-0.690627 --4.3148 , 1.35869 , 4.54217 , 0.764612,0.634975,-0.110341 --4.09484 , 1.33058 , 4.50734 , 0.260048,-0.91506,0.308287 --7.0916 , 2.04139 , 6.98324 , -0.624057,0.513217,-0.589203 --3.28663 , 1.18538 , 4.11436 , -0.0645329,0.03188,0.997406 --3.08061 , 1.15431 , 4.05367 , 0.0359381,0.211484,0.97672 --3.07001 , 1.17056 , 4.15482 , 0.202279,-0.794464,0.572634 --2.97759 , 1.16632 , 4.18404 , 0.660845,-0.636501,0.397683 --4.64233 , 1.61174 , 5.85741 , -0.228614,0.276293,0.933487 --4.48474 , 1.59916 , 5.87868 , -0.228614,0.276293,0.933487 --4.46674 , 1.624 , 6.03517 , -0.228614,0.276293,0.933487 --4.25413 , 1.5964 , 5.99403 , -0.143129,0.253227,0.95676 --4.07101 , 1.57466 , 5.9763 , 0.432675,-0.49084,0.75622 --2.70551 , 1.21401 , 4.62772 , 0.717571,0.516369,-0.467391 --1.33245 , 0.833349 , 3.16632 , -0.227119,0.909893,0.347147 --2.58802 , 1.22361 , 4.75364 , -0.645488,-0.671082,0.364684 --3.52909 , 1.53625 , 6.06379 , -0.11651,0.624515,0.772273 --1.27063 , 0.855156 , 3.33016 , -0.583573,-0.225102,0.780239 --1.21171 , 0.850492 , 3.33755 , 0.868138,0.143214,-0.475212 --1.23968 , 0.874017 , 3.46317 , -0.954715,-0.262142,0.140717 --1.43081 , 0.954928 , 3.83266 , -0.316126,-0.311047,-0.896278 --1.17387 , 0.883245 , 3.55593 , -0.359422,-0.545987,0.756778 --1.10683 , 0.876363 , 3.5522 , 0.405099,-0.326958,-0.853811 --1.06282 , 0.876541 , 3.58031 , -0.366124,-0.503687,0.782465 --1.02708 , 0.881053 , 3.62451 , -0.127267,-0.591717,0.796036 --0.927592 , 0.859307 , 3.55748 , 0.136264,-0.597842,0.789947 --0.87738 , 0.857609 , 3.57383 , 0.830706,-0.53555,0.152031 --1.01818 , 0.934795 , 3.95511 , 0.00322988,-0.517893,0.855439 --0.970577 , 0.936624 , 3.99042 , 0.00323007,-0.517894,0.855439 --2.70585 , 1.74161 , 7.76437 , -0.561992,-0.444192,-0.697752 --1.19435 , 1.08862 , 4.76502 , -0.0979807,-0.0685059,0.992828 --1.11681 , 1.08153 , 4.76777 , -0.177671,0.114206,0.977441 --1.04299 , 1.07587 , 4.77804 , -0.63496,-0.018769,0.772317 --0.993751 , 1.08303 , 4.85112 , 0.464497,0.136814,-0.874943 --0.966989 , 1.10369 , 4.98783 , -0.971786,-0.212834,-0.101655 --1.01097 , 1.16724 , 5.33798 , -0.939651,-0.112346,0.323162 --1.6527 , 1.59755 , 7.52773 , -0.0569385,0.157378,0.985896 --0.550654 , 0.964863 , 4.40551 , -0.377239,0.0630175,-0.92397 --0.976966 , 1.28828 , 6.08389 , 0.481968,-0.848439,0.218765 --0.910581 , 1.30123 , 6.19528 , 0.542845,-0.827718,0.142134 --0.914322 , 1.36759 , 6.59189 , -0.398092,0.38558,-0.832377 --0.797721 , 1.34799 , 6.54045 , -0.56231,0.722148,0.402878 --0.689643 , 1.33289 , 6.51573 , 0.999614,-0.023079,0.0154927 --0.500527 , 1.23963 , 6.07414 , 0.469743,0.75482,-0.457808 --0.261152 , 1.07967 , 5.25954 , -0.264936,0.0768629,0.961198 --0.180106 , 1.06801 , 5.23429 , 0.163866,-0.000542651,-0.986483 --0.283238 , 1.28552 , 6.47406 , 0.584549,0.238209,0.775603 --0.210414 , 1.31207 , 6.67393 , -0.776129,0.539613,-0.326254 --0.0965142 , 1.28221 , 6.55964 , 0.338653,-0.670347,0.660264 --3.03286 , 0.366408 , -1.28489 , -0.0759988,0.179466,0.980824 --3.19776 , 0.384358 , -1.30421 , 0.083864,-0.179315,-0.980211 --3.34771 , 0.403866 , -1.30827 , -0.0827127,0.185006,0.97925 --3.55952 , 0.424991 , -1.34301 , -0.0952405,0.160583,0.982417 --3.74802 , 0.446858 , -1.35644 , -0.0886259,0.160116,0.983112 --3.98106 , 0.471828 , -1.38787 , -0.0992516,0.149216,0.983811 --4.21585 , 0.497732 , -1.41183 , -0.086067,0.148359,0.985181 --4.47997 , 0.527528 , -1.44193 , -0.0820227,0.144921,0.986038 --4.74713 , 0.557784 , -1.46332 , -0.0888877,0.140103,0.986139 --5.06993 , 0.593151 , -1.50122 , -0.100148,0.155459,0.982753 --5.43135 , 0.632774 , -1.54449 , -0.10415,0.163998,0.980947 --5.81525 , 0.675659 , -1.5837 , -0.0804278,0.16232,0.983455 --6.22951 , 0.722204 , -1.62127 , -0.0827425,0.152754,0.984794 --6.74 , 0.778655 , -1.68048 , -0.0921299,0.155374,0.98355 --7.31048 , 0.841968 , -1.74283 , -0.0934552,0.151484,0.984032 --7.99783 , 0.91663 , -1.82427 , -0.0947816,0.151111,0.983962 --8.76631 , 1.00169 , -1.9069 , -0.0876491,0.153998,0.984176 --9.70139 , 1.10443 , -2.0122 , -0.081079,0.148143,0.985637 --10.6714 , 1.21642 , -2.09434 , -0.0814115,0.142701,0.986412 --12.0312 , 1.3658 , -2.24418 , -0.081054,0.14633,0.98591 --13.7093 , 1.55221 , -2.42363 , -0.0879968,0.14533,0.985462 --15.7644 , 1.78259 , -2.62887 , 0.0261748,0.253651,0.966942 --18.5501 , 2.09448 , -2.91373 , 0.0536129,0.214299,0.975296 --9.10727 , 1.81667 , 2.76076 , -0.144443,0.35723,0.92278 --9.01431 , 1.83015 , 2.91657 , -0.0294076,0.564134,0.825159 --9.45868 , 1.93209 , 3.18618 , -0.517949,-0.442665,-0.731968 --8.39769 , 1.78489 , 3.12115 , 0.5091,-0.187958,-0.839934 --8.15585 , 1.77075 , 3.22542 , -0.563783,0.19674,0.802148 --7.57955 , 1.6975 , 3.23165 , -0.249067,0.230664,0.940617 --7.62267 , 1.73093 , 3.39707 , 0.178287,-0.299478,-0.937297 --4.046 , 1.11379 , 2.44599 , -0.871426,-0.266791,-0.41163 --3.96291 , 1.11316 , 2.5068 , -0.871426,-0.266791,-0.41163 --4.01832 , 1.13755 , 2.61393 , -0.759474,-0.390917,-0.519984 --6.83432 , 1.68666 , 3.74065 , -0.92293,0.370819,-0.103411 --6.88389 , 1.71998 , 3.90798 , -0.92293,0.370818,-0.103411 --6.90237 , 1.74904 , 4.06656 , -0.92293,0.370819,-0.103411 --6.98074 , 1.78951 , 4.25418 , -0.915738,0.400046,0.0372472 --6.9299 , 1.80584 , 4.38862 , -0.939331,-0.203529,0.276103 --6.70682 , 1.78596 , 4.44283 , -0.732917,0.390473,0.557103 --6.0181 , 1.66662 , 4.2598 , -0.839426,0.435201,0.325522 --5.94907 , 1.67639 , 4.36912 , -0.921594,0.106859,0.373157 --5.96529 , 1.70407 , 4.52376 , -0.831212,0.160273,0.532353 --5.96933 , 1.72915 , 4.67537 , 0.86415,0.342642,-0.368567 --7.75735 , 2.15726 , 5.87465 , -0.850823,0.505289,-0.144163 --5.72394 , 1.72435 , 4.83401 , -0.0860921,-0.984864,0.150434 --5.60523 , 1.72147 , 4.91135 , -0.345219,-0.91877,0.191535 --5.50125 , 1.72181 , 4.99673 , -0.611341,-0.764088,0.20599 --4.33664 , 1.46579 , 4.35344 , 0.160689,0.860911,0.482713 --3.85252 , 1.36813 , 4.1368 , 0.133975,0.748373,0.649607 --3.53575 , 1.30764 , 4.02101 , 0.491369,0.577298,0.652138 --3.54371 , 1.32888 , 4.13928 , -0.491369,-0.577298,-0.652138 --6.71594 , 2.17262 , 6.77786 , -0.064094,0.286822,0.955838 --6.46779 , 2.14221 , 6.78595 , 0.136044,-0.320258,-0.937511 --6.4008 , 2.15862 , 6.94008 , 0.136044,-0.320258,-0.937511 --2.82661 , 1.21126 , 3.9883 , -0.0413755,0.681006,0.731108 --2.80942 , 1.22389 , 4.07985 , -0.0413755,0.681006,0.731108 --3.00955 , 1.30018 , 4.38085 , -0.63555,0.682742,-0.360471 --3.59726 , 1.49143 , 5.08206 , 0.053677,0.922016,0.383412 --4.17395 , 1.68738 , 5.8191 , -0.0060225,0.942623,0.333804 --3.79878 , 1.60157 , 5.59528 , 0.120083,0.980388,0.15627 --2.71496 , 1.29282 , 4.57077 , 0.717571,0.516369,-0.467392 --2.66484 , 1.29833 , 4.64203 , -0.712132,-0.668977,0.212925 --2.61838 , 1.30513 , 4.72022 , -0.777122,-0.604471,0.175206 --2.59534 , 1.32074 , 4.82809 , -0.645488,-0.671082,0.364684 --3.43604 , 1.62825 , 6.03586 , -0.0490261,0.553196,0.831607 --3.29357 , 1.60961 , 6.03516 , 0.277934,0.779327,0.561606 --1.20357 , 0.900201 , 3.36908 , -0.853883,-0.21575,0.473641 --1.28078 , 0.942569 , 3.56725 , 0.015927,-0.26214,0.964898 --1.17438 , 0.919995 , 3.50956 , -0.544941,-0.0523882,0.836836 --1.1307 , 0.919485 , 3.53903 , -0.422043,0.290209,0.85887 --1.09075 , 0.920449 , 3.57623 , 0.479458,-0.408993,-0.776431 --1.03573 , 0.914477 , 3.58784 , 0.528091,0.54647,-0.649993 --1.00497 , 0.919835 , 3.64032 , 0.165029,0.459806,-0.87255 --0.910659 , 0.897919 , 3.58147 , -0.418775,0.575657,-0.702315 --0.906498 , 0.914034 , 3.68443 , -0.251652,0.631783,-0.733158 --1.07749 , 1.01137 , 4.13692 , -0.984792,0.130009,-0.115252 --0.94501 , 0.972511 , 4.00652 , -0.672981,0.379104,-0.635119 --2.44688 , 1.72115 , 7.37219 , -0.256291,-0.531859,-0.807119 --1.14946 , 1.12283 , 4.7556 , -0.306038,-0.155106,0.939299 --1.07902 , 1.11697 , 4.77605 , -0.510977,-0.165209,0.843569 --1.03509 , 1.12433 , 4.85897 , -0.739296,-0.146001,0.657363 --0.956807 , 1.11437 , 4.85893 , -0.17189,-0.195977,0.965426 --1.04901 , 1.20398 , 5.32778 , -0.939651,-0.112346,0.323162 --1.69865 , 1.64348 , 7.48145 , -0.0569385,0.157378,0.985896 --0.586127 , 0.994549 , 4.42011 , 0.401342,-0.0320642,0.915367 --0.592196 , 1.0344 , 4.65571 , 0.0902364,0.81528,-0.571994 --1.00187 , 1.36592 , 6.34747 , -0.552015,0.799977,-0.235195 --0.864965 , 1.32623 , 6.21328 , 0.370606,-0.870606,0.323568 --0.847968 , 1.3789 , 6.54329 , -0.394446,0.918098,0.0388442 --0.731263 , 1.35398 , 6.48155 , 0.58101,-0.745064,-0.327577 --0.585285 , 1.29888 , 6.26362 , -0.140982,-0.80759,0.572645 --0.346425 , 1.14349 , 5.51096 , -0.377961,0.923841,-0.0605184 --0.395503 , 1.27585 , 6.27299 , 0.245171,0.922667,-0.297619 --0.333193 , 1.3031 , 6.48394 , 0.00804386,-0.98937,0.145197 --0.22475 , 1.27706 , 6.41197 , -0.639639,-0.15021,-0.753856 --0.152561 , 1.30054 , 6.61146 , 0.369321,-0.323029,0.871352 --0.0559087 , 1.29374 , 6.64353 , -0.783626,-0.609457,0.120384 diff --git a/thirdparty/libpointmatcher/examples/data/car_cloud400_scaled.csv b/thirdparty/libpointmatcher/examples/data/car_cloud400_scaled.csv deleted file mode 100644 index 731a537..0000000 --- a/thirdparty/libpointmatcher/examples/data/car_cloud400_scaled.csv +++ /dev/null @@ -1,24990 +0,0 @@ -x,y,z,nx,ny,nz --1.7379088159807159e+00 , 1.9209515712549907e+00 , 5.6814880000000012e-01 , -6.0180999999999998e-02 , 1.7372899999999999e-01 , 9.8295299999999997e-01 --1.9166145509958672e+00 , 1.9160163261460781e+00 , 5.6349999999999989e-01 , -6.2612299999999996e-02 , 1.6017400000000001e-01 , 9.8510100000000000e-01 --2.1687730151446747e+00 , 1.9040652265049156e+00 , 5.2415680000000009e-01 , -9.7616300000000003e-02 , 1.6673499999999999e-01 , 9.8115799999999997e-01 --2.4150638783129006e+00 , 1.8954672382079054e+00 , 4.9743919999999986e-01 , -7.8440800000000005e-02 , 1.5742900000000001e-01 , 9.8441000000000001e-01 --2.6633414281702654e+00 , 1.8874565837696193e+00 , 4.7847999999999979e-01 , -7.2544600000000001e-02 , 1.6010700000000000e-01 , 9.8443000000000003e-01 --2.9690960335348144e+00 , 1.8748641506489359e+00 , 4.4034319999999982e-01 , -6.7088599999999998e-02 , 1.5790299999999999e-01 , 9.8517299999999997e-01 --3.2781235384111884e+00 , 1.8633411298191345e+00 , 4.1206559999999981e-01 , 9.5791399999999999e-02 , -1.6266100000000000e-01 , -9.8202100000000003e-01 --3.6938957012925613e+00 , 1.8447675576002416e+00 , 3.4710719999999995e-01 , -1.0112300000000000e-01 , 1.7057700000000001e-01 , 9.8014199999999996e-01 --4.1144313839139741e+00 , 1.8280733217067178e+00 , 2.9574159999999972e-01 , 7.3228900000000000e-02 , -1.6651099999999999e-01 , -9.8331700000000000e-01 --4.5276604264246183e+00 , 1.8136008994638164e+00 , 2.6221200000000011e-01 , -7.9160700000000001e-02 , 1.6370199999999999e-01 , 9.8332900000000001e-01 --5.0809204009303102e+00 , 1.7909683667438490e+00 , 1.8990079999999998e-01 , -8.7911199999999995e-02 , 1.5961600000000001e-01 , 9.8325700000000005e-01 --5.6474905456671838e+00 , 1.7697656117747864e+00 , 1.3240959999999991e-01 , -8.6838200000000004e-02 , 1.6039200000000001e-01 , 9.8322600000000004e-01 --6.3654169577429158e+00 , 1.7401550113285320e+00 , 4.3094399999999977e-02 , -9.3464000000000005e-02 , 1.5124899999999999e-01 , 9.8406700000000003e-01 --7.1488994141321278e+00 , 1.7100636522644614e+00 , -4.1551200000000232e-02 , -8.5496900000000001e-02 , 1.5216499999999999e-01 , 9.8465000000000003e-01 --8.0963165059297726e+00 , 1.6739384334153233e+00 , -1.4897280000000013e-01 , -7.9928500000000000e-02 , 1.5492900000000001e-01 , 9.8468699999999998e-01 --9.1591486251022367e+00 , 1.6344307645090148e+00 , -2.5563520000000040e-01 , -7.4619000000000005e-02 , 1.5217000000000000e-01 , 9.8553400000000002e-01 --1.0500621448657226e+01 , 1.5834751363256401e+00 , -3.9949840000000014e-01 , -8.6753899999999995e-02 , 1.4682700000000001e-01 , 9.8535099999999998e-01 --1.2081651072661561e+01 , 1.5254606109315103e+00 , -5.5583120000000052e-01 , -8.2777199999999995e-02 , 1.4302899999999999e-01 , 9.8625099999999999e-01 --1.4258752089699431e+01 , 1.4424278823719789e+00 , -7.9479200000000017e-01 , 8.0906300000000000e-02 , -1.3821900000000001e-01 , -9.8709199999999997e-01 --3.8613054179789863e+01 , 5.0385072953692567e-01 , -3.4930512000000009e+00 , 9.0098799999999996e-03 , 8.0395300000000003e-02 , 9.9672200000000000e-01 --3.7254708468098194e+01 , 6.7729857213610578e-01 , -2.5741592000000004e+00 , -4.3768500000000002e-02 , 8.1380599999999997e-02 , 9.9572200000000000e-01 --1.1832034870502557e+01 , 2.3696749761035054e+00 , 4.7627912000000006e+00 , -1.3304399999999999e-02 , 3.8657999999999998e-01 , 9.2215999999999998e-01 --1.2317197671819136e+01 , 2.4094790382129450e+00 , 5.0782752000000002e+00 , 8.8347200000000001e-02 , 2.3817700000000000e-01 , 9.6719500000000003e-01 --7.8591415808302045e+00 , 2.4365643616427959e+00 , 4.6566279999999995e+00 , 1.0192000000000000e-01 , 1.1632500000000000e-01 , 9.8796799999999996e-01 --7.4618458878026228e+00 , 2.4627373482964687e+00 , 4.7711736000000000e+00 , -3.4012900000000001e-01 , 8.8491899999999998e-02 , 9.3620599999999998e-01 --7.3181521884580825e+00 , 2.4898387021113817e+00 , 4.9205176000000002e+00 , 4.1861599999999999e-01 , -2.4839100000000000e-01 , -8.7353499999999995e-01 --7.0611378804348188e+00 , 2.5139554928622716e+00 , 5.0423640000000001e+00 , -3.9664100000000002e-01 , 1.7074600000000001e-01 , 9.0195400000000003e-01 --6.8731611200431111e+00 , 2.5383289565963993e+00 , 5.1718440000000001e+00 , -5.0448800000000005e-01 , 1.4427699999999999e-01 , 8.5127900000000001e-01 --6.6132333427517054e+00 , 2.5613172699201305e+00 , 5.2781320000000003e+00 , -1.5098500000000001e-01 , 2.9148099999999999e-01 , 9.4458600000000004e-01 --2.3378292607352247e+00 , 2.5016409851965560e+00 , 4.3289552000000002e+00 , -8.7036100000000005e-01 , 4.5548600000000000e-01 , 1.8709600000000001e-01 --2.2847873291743568e+00 , 2.5142819682964639e+00 , 4.4030448000000000e+00 , -7.1341500000000002e-01 , 5.1002099999999995e-01 , 4.8053899999999999e-01 --3.3867970705007986e+00 , 2.5564893683816217e+00 , 4.8200848000000001e+00 , -2.8502300000000003e-01 , -9.3214500000000000e-01 , 2.2331200000000001e-01 --3.3056687357782781e+00 , 2.5711309369161275e+00 , 4.9047720000000004e+00 , -2.8502300000000003e-01 , -9.3214500000000000e-01 , 2.2331200000000001e-01 --6.7421599314058636e+00 , 2.6985575798658656e+00 , 6.1689960000000008e+00 , -9.2906500000000003e-01 , 3.6287700000000001e-01 , 7.1830000000000005e-02 --6.6668165822740626e+00 , 2.7236248694840750e+00 , 6.3200143999999998e+00 , -9.2906500000000003e-01 , 3.6287700000000001e-01 , 7.1829900000000002e-02 --3.1639098637450580e+00 , 2.6182991000657445e+00 , 5.1849791999999999e+00 , 5.1643899999999998e-01 , 4.7778399999999999e-01 , -7.1064300000000002e-01 --3.0194083561148517e+00 , 2.6304746176168630e+00 , 5.2393712000000008e+00 , -6.6388899999999995e-01 , 4.1462500000000002e-01 , 6.2236499999999995e-01 --2.8942389663507848e+00 , 2.6421163970208550e+00 , 5.2974760000000005e+00 , 2.4065400000000001e-01 , -9.2400899999999997e-01 , -2.9714099999999999e-01 --4.9882985177060419e+00 , 2.7593371990405466e+00 , 6.3178719999999995e+00 , -5.0045300000000001e-02 , -7.2916899999999996e-01 , 6.8250100000000002e-01 --5.1106711324493608e+00 , 2.7898064704109453e+00 , 6.5273072000000001e+00 , 6.8448200000000003e-01 , -7.2216000000000002e-01 , -9.9850099999999997e-02 --2.8171460818077589e+00 , 2.6908518532246894e+00 , 5.5927216000000008e+00 , -5.6381400000000004e-01 , 8.2587999999999995e-01 , 6.0397899999999997e-03 --5.0597887868570934e+00 , 2.8375476775962380e+00 , 6.8225527999999995e+00 , -1.5692000000000000e-01 , -9.1166700000000001e-01 , 3.7978800000000001e-01 --4.3197154768215160e+00 , 2.8175289041786584e+00 , 6.6017815999999998e+00 , -8.5946299999999998e-01 , -1.5687199999999998e-02 , 5.1095699999999999e-01 --4.9325960898921952e+00 , 2.8805109710500179e+00 , 7.0840607999999996e+00 , -1.0593600000000000e-01 , -9.4935099999999994e-01 , 2.9582199999999997e-01 --5.2863975650916046e+00 , 2.9313019058837240e+00 , 7.4503696000000001e+00 , -8.2147800000000004e-01 , -5.0928700000000000e-02 , 5.6796100000000005e-01 --2.6484273175921897e+00 , 2.7708097313434261e+00 , 6.0783184000000006e+00 , 7.4797800000000003e-01 , -6.3531400000000005e-01 , -1.9210500000000000e-01 --2.4886395998154107e+00 , 2.7769898410389566e+00 , 6.1008968000000001e+00 , -1.5598300000000001e-01 , 5.7021299999999997e-01 , 8.0655200000000005e-01 --1.6466822740415270e+00 , 2.7291080923991164e+00 , 5.6845224000000005e+00 , 2.6936599999999999e-01 , 9.6191199999999999e-01 , 4.6556699999999999e-02 --1.7824873381399229e+00 , 2.7562708376644727e+00 , 5.8746760000000000e+00 , 4.6899600000000002e-01 , 7.4842299999999995e-01 , 4.6894200000000003e-01 --2.1945631484811532e+00 , 2.8088211191322059e+00 , 6.2636880000000001e+00 , -1.0786400000000000e-01 , 3.4007599999999999e-01 , 9.3419200000000002e-01 --1.3100557236944321e+00 , 2.7477580207800720e+00 , 5.7540256000000003e+00 , -6.9725499999999996e-01 , -5.0041199999999997e-01 , 5.1324899999999996e-01 --1.7458921420094424e+00 , 2.8046601452868360e+00 , 6.1753711999999998e+00 , -4.7982200000000003e-01 , -6.7506699999999997e-01 , -5.6040599999999996e-01 --1.2879383106036508e+00 , 2.7775817616549476e+00 , 5.9384072000000003e+00 , -9.1339899999999996e-01 , -1.2834599999999999e-01 , 3.8630199999999998e-01 --1.3016574040502809e+00 , 2.7950581630271589e+00 , 6.0538679999999996e+00 , -9.6034399999999998e-01 , 2.5930999999999998e-01 , 1.0245700000000001e-01 --1.3367637107874657e+00 , 2.8155953938530200e+00 , 6.1904408000000002e+00 , 1.8353900000000001e-01 , 6.7684699999999998e-01 , 7.1287599999999995e-01 --2.3158394060292204e+00 , 2.9438133023806250e+00 , 7.1344384000000005e+00 , -7.4177400000000004e-01 , -6.1727299999999996e-01 , 2.6219300000000001e-01 --4.4976160598540682e+00 , 3.2236913213255405e+00 , 9.2017087999999987e+00 , -2.6106000000000001e-01 , 3.9760899999999999e-01 , 8.7963400000000003e-01 --1.3816157676176477e+00 , 2.8762529789894407e+00 , 6.5768215999999997e+00 , -8.4625600000000001e-01 , -1.3163300000000000e-01 , -5.1626000000000005e-01 --1.3191663731777941e+00 , 2.8878191109831377e+00 , 6.6423000000000005e+00 , -8.0974599999999997e-01 , 4.6227200000000002e-01 , -3.6140899999999998e-01 --1.3301849721795711e+00 , 2.9084109184851039e+00 , 6.7790288000000007e+00 , -9.6236200000000005e-01 , -9.0919399999999997e-02 , 2.5611299999999998e-01 --1.2286352162609675e+00 , 2.9149145807819967e+00 , 6.8066512000000001e+00 , -7.1179099999999995e-01 , -6.4618600000000004e-01 , 2.7531299999999997e-01 --1.3124148170677570e+00 , 2.9479543390040988e+00 , 7.0265279999999999e+00 , -5.6218299999999999e-01 , -7.9660699999999995e-01 , 2.2218700000000000e-01 --1.2075474695863817e+00 , 2.9540056888618214e+00 , 7.0526008000000004e+00 , 8.2730599999999999e-01 , 3.9943600000000001e-01 , -3.9498800000000001e-01 --1.1435399743357855e+00 , 2.9664182397255594e+00 , 7.1225823999999998e+00 , 6.1480500000000005e-01 , 7.0263200000000003e-01 , -3.5822199999999998e-01 --1.1525148308162576e+00 , 2.9916901669895202e+00 , 7.2777191999999999e+00 , -6.3848099999999997e-01 , -6.5120199999999995e-01 , 4.1021600000000003e-01 --1.0315845845274909e+00 , 2.9950339511539488e+00 , 7.2832728000000007e+00 , -5.4073599999999999e-01 , -7.7149900000000005e-01 , 3.3525300000000002e-01 --1.0416785710119738e+00 , 3.0200684080110705e+00 , 7.4475200000000008e+00 , -6.3641800000000004e-01 , -6.3829800000000003e-01 , 4.3306699999999998e-01 --1.0011085560594708e+00 , 3.0380655707750641e+00 , 7.5560231999999994e+00 , -6.3641800000000004e-01 , -6.3829800000000003e-01 , 4.3306699999999998e-01 -5.4612738944673622e-01 , 2.7684646313100933e+00 , 5.6415496000000003e+00 , 9.6783800000000003e-02 , -4.4786500000000000e-02 , 9.9429699999999999e-01 -6.0298503642206347e-01 , 2.7723329712381020e+00 , 5.6570768000000005e+00 , -4.0700700000000001e-01 , 1.2158300000000000e-01 , 9.0529700000000002e-01 -6.9022890607728526e-01 , 2.7703115179568467e+00 , 5.6287576000000001e+00 , 5.5394699999999997e-01 , 6.7527699999999996e-02 , -8.2980900000000002e-01 -6.8997949491881405e-01 , 2.7849430644010074e+00 , 5.7276927999999998e+00 , -7.2388200000000003e-01 , -2.7967599999999998e-01 , 6.3069500000000001e-01 -7.0333756018504334e-01 , 2.7987197589566968e+00 , 5.8094783999999997e+00 , -7.0836399999999999e-01 , -3.5141800000000001e-01 , 6.1214900000000005e-01 -5.8358326846442021e-01 , 2.8434935488156299e+00 , 6.1115256000000002e+00 , -7.0495500000000000e-01 , -4.3466199999999999e-01 , 5.6045299999999998e-01 -8.6839595632665412e-01 , 2.7928757897550778e+00 , 5.7524344000000003e+00 , 7.6424599999999998e-01 , -2.6804200000000000e-01 , 5.8658399999999999e-01 -9.1658071422705323e-01 , 2.7983254946295766e+00 , 5.7792247999999997e+00 , 9.8974499999999999e-01 , -5.9264699999999997e-02 , 1.2996800000000000e-01 -7.3614094752992831e-01 , 2.8644012427120247e+00 , 6.2215056000000004e+00 , 4.5074300000000000e-01 , -3.0939200000000000e-01 , 8.3732099999999998e-01 -8.2097296429982980e-01 , 2.8619131668471183e+00 , 6.1956720000000001e+00 , 5.7544399999999996e-01 , -3.0201200000000000e-01 , 7.6003500000000002e-01 -7.9274724970444987e-01 , 2.8914748484972979e+00 , 6.3890288000000002e+00 , 7.8598199999999996e-01 , 5.1023200000000002e-01 , -3.4913600000000000e-01 --7.4013377919825762e-01 , 3.3873582535512146e+00 , 9.7353848000000003e+00 , -2.5629099999999999e-01 , -5.3185899999999997e-01 , -8.0711900000000003e-01 --5.9192783824400852e-01 , 3.3891638197742058e+00 , 9.7233000000000001e+00 , 3.1357799999999998e-02 , 4.3512899999999999e-01 , 8.9982200000000001e-01 -7.1892758275855329e-01 , 2.9940228778257958e+00 , 7.0456640000000004e+00 , 6.0466900000000001e-01 , 4.4309799999999999e-01 , -6.6184600000000005e-01 -7.7706373638424608e-01 , 3.0042053194695022e+00 , 7.1033320000000000e+00 , 5.0749999999999995e-01 , 7.5415299999999996e-01 , 4.1676900000000000e-01 -8.7822804565471135e-01 , 2.9985549335650159e+00 , 7.0547432000000008e+00 , 1.4964100000000000e-04 , 1.0288799999999999e-01 , 9.9469300000000005e-01 -1.0141690951335347e+00 , 2.9779140065812362e+00 , 6.9075103999999996e+00 , -1.5696900000000000e-01 , -8.6264600000000002e-01 , 4.8083500000000001e-01 -1.1301994767661787e+00 , 2.9631269277676022e+00 , 6.7956480000000008e+00 , 2.1493999999999999e-01 , -4.8243599999999998e-01 , 8.4914999999999996e-01 -1.2576146705151143e+00 , 2.9406303859782268e+00 , 6.6320872000000000e+00 , -9.7489700000000001e-01 , 1.5947100000000000e-01 , 1.5538800000000000e-01 -1.2559010024108619e+00 , 2.9756299946579543e+00 , 6.8581208000000000e+00 , -5.5816900000000003e-02 , -9.5974499999999996e-01 , 2.7527000000000001e-01 -1.3960646165205071e+00 , 2.9430263029236610e+00 , 6.6313384000000006e+00 , -5.0810200000000005e-01 , -2.7912300000000001e-01 , 8.1481499999999996e-01 -9.0456453830267591e-01 , 3.2491683703693544e+00 , 8.6415439999999997e+00 , 3.8133600000000001e-01 , -9.0234300000000001e-01 , -2.0089799999999999e-01 -9.5126031981716852e-01 , 3.2860436403576863e+00 , 8.8661735999999998e+00 , -2.4191199999999999e-01 , 8.3053399999999999e-01 , 5.0168999999999997e-01 -1.4026299413737138e+00 , 3.0707510223715637e+00 , 7.4406248000000001e+00 , -2.6702199999999998e-01 , 4.5840399999999998e-01 , 8.4768200000000005e-01 -1.4792203072025178e+00 , 3.0751451694855723e+00 , 7.4577224000000006e+00 , -2.7208199999999999e-01 , 5.4304799999999998e-01 , 7.9439899999999997e-01 -1.5490652071419679e+00 , 3.0855893982368121e+00 , 7.5139344000000001e+00 , -2.5500099999999998e-01 , -1.5462000000000001e-01 , 9.5449899999999999e-01 -1.7000358884970677e+00 , 3.0280957982717744e+00 , 7.1342927999999999e+00 , -1.9453100000000001e-01 , 6.5878199999999998e-01 , -7.2674899999999998e-01 -1.5178382185129347e+00 , 3.2662874845407126e+00 , 8.6676584000000005e+00 , -6.3963899999999996e-01 , -1.5021000000000001e-01 , -7.5385599999999997e-01 -1.5909335071277120e+00 , 3.2977753372755179e+00 , 8.8553472000000006e+00 , -3.7229099999999998e-01 , 2.8145500000000001e-01 , -8.8441099999999995e-01 -1.6823732059218295e+00 , 3.3151225911783886e+00 , 8.9504136000000010e+00 , -8.5345899999999997e-01 , -4.9682199999999999e-01 , 1.5740100000000001e-01 --1.6547415724481200e+00 , 2.0496526855145194e+00 , 5.5009440000000009e-01 , -4.6602999999999999e-02 , 1.6280600000000001e-01 , 9.8555700000000002e-01 --1.8319121664819233e+00 , 2.0492891557693831e+00 , 5.4210719999999979e-01 , -5.2919700000000000e-02 , 1.6383200000000001e-01 , 9.8506800000000005e-01 --2.0480982977479885e+00 , 2.0474972427856031e+00 , 5.1870719999999992e-01 , -8.5684800000000005e-02 , 1.8019800000000000e-01 , 9.7989099999999996e-01 --2.3014769206177341e+00 , 2.0446539242740744e+00 , 4.8215119999999989e-01 , -7.7247700000000002e-02 , 1.7764099999999999e-01 , 9.8105900000000001e-01 --2.5579520580312751e+00 , 2.0414864007754594e+00 , 4.5385279999999995e-01 , -7.3104400000000000e-02 , 1.8494400000000000e-01 , 9.8002599999999995e-01 --2.8262989596681294e+00 , 2.0405050191113272e+00 , 4.2862240000000007e-01 , -6.5040799999999996e-02 , 1.8982599999999999e-01 , 9.7966100000000000e-01 --3.1244813481669800e+00 , 2.0377234778981332e+00 , 3.9864959999999994e-01 , -8.0439399999999994e-02 , 1.9319100000000000e-01 , 9.7785800000000000e-01 --3.5013230478192110e+00 , 2.0331951240230755e+00 , 3.4318640000000000e-01 , 1.0299100000000000e-01 , -1.8075500000000000e-01 , -9.7812100000000002e-01 --3.9096197111887498e+00 , 2.0278934180012986e+00 , 2.8770240000000014e-01 , -7.8779000000000002e-02 , 1.6837800000000000e-01 , 9.8257000000000005e-01 --4.3026647975374379e+00 , 2.0251952295955626e+00 , 2.5368400000000002e-01 , 7.1667400000000006e-02 , -1.6317300000000001e-01 , -9.8399099999999995e-01 --4.7952725067774251e+00 , 2.0204816274346036e+00 , 1.9370719999999997e-01 , 8.7483699999999998e-02 , -1.6788100000000000e-01 , -9.8191799999999996e-01 --5.3410603871049451e+00 , 2.0154826681276599e+00 , 1.3146320000000000e-01 , 8.3124199999999995e-02 , -1.6299400000000000e-01 , -9.8311899999999997e-01 --5.9784756002919304e+00 , 2.0095781163622113e+00 , 5.5730399999999847e-02 , 8.9950000000000002e-02 , -1.6387699999999999e-01 , -9.8237099999999999e-01 --6.7484109963065997e+00 , 2.0006544880298089e+00 , -4.2175199999999968e-02 , 9.0329699999999999e-02 , -1.5520100000000001e-01 , -9.8374499999999998e-01 --7.6234582705543747e+00 , 1.9918589055829155e+00 , -1.4607120000000018e-01 , 8.6415099999999995e-02 , -1.5709200000000001e-01 , -9.8379600000000000e-01 --8.5941222367263812e+00 , 1.9844582240881448e+00 , -2.4763760000000001e-01 , -7.1853399999999998e-02 , 1.5496699999999999e-01 , 9.8530300000000004e-01 --9.7613871137832167e+00 , 1.9748648635981150e+00 , -3.7031600000000031e-01 , -7.8831100000000001e-02 , 1.5686700000000001e-01 , 9.8446900000000004e-01 --1.1237063721257684e+01 , 1.9619656541334636e+00 , -5.3316959999999991e-01 , -7.7010599999999998e-02 , 1.5221199999999999e-01 , 9.8534299999999997e-01 --1.3065942401369126e+01 , 1.9466984224765558e+00 , -7.3042640000000025e-01 , -7.8870700000000002e-02 , 1.4148700000000000e-01 , 9.8679300000000003e-01 --1.5370406574527397e+01 , 1.9292237370727623e+00 , -9.7164399999999995e-01 , -7.7682699999999993e-02 , 1.4174400000000001e-01 , 9.8685100000000003e-01 --3.6674468241156553e+01 , 1.7923068402416291e+00 , -3.0138919999999993e+00 , -2.1424900000000000e-02 , 2.3636600000000001e-02 , 9.9949100000000002e-01 --4.2287213421661605e+01 , 1.8262927671357223e+00 , -3.0995255999999998e+00 , 1.5923100000000001e-01 , 1.0344299999999999e-01 , 9.8180699999999999e-01 --1.1538552995685722e+01 , 2.7472683519387209e+00 , 4.5439752000000002e+00 , -1.1563100000000000e-01 , 2.5260300000000002e-01 , 9.6063600000000005e-01 --1.0922751113451145e+01 , 2.7686564375237372e+00 , 4.7130688000000003e+00 , -1.4068000000000000e-01 , -2.5455499999999999e-02 , 9.8972800000000005e-01 --1.0644262448812787e+01 , 2.7961924817557073e+00 , 4.9091088000000003e+00 , -1.4561600000000000e-03 , -2.5726500000000002e-01 , 9.6633999999999998e-01 --8.3095970126292080e+00 , 2.7554515963242316e+00 , 4.7729520000000001e+00 , -2.8977100000000000e-01 , -6.0840000000000005e-01 , 7.3883799999999999e-01 --8.3595074787349901e+00 , 2.7871967060979213e+00 , 4.9726008000000004e+00 , -3.1810300000000002e-01 , -3.0255900000000002e-01 , 8.9848099999999997e-01 --8.2221460489273142e+00 , 2.8116667817837686e+00 , 5.1391672000000002e+00 , -3.1810300000000002e-01 , -3.0256000000000000e-01 , 8.9848099999999997e-01 --7.2687329797560345e+00 , 2.8017755521513599e+00 , 5.1301296000000001e+00 , -3.6635499999999999e-01 , -1.9039400000000001e-01 , 9.1078800000000004e-01 --2.4501995854586385e+00 , 2.6190300130311650e+00 , 4.2025223999999994e+00 , -5.2181299999999997e-01 , 4.7046100000000002e-01 , 7.1160199999999996e-01 --2.2981689375364125e+00 , 2.6261526180060479e+00 , 4.2544599999999999e+00 , 9.8609100000000005e-01 , -1.5107000000000001e-01 , 6.9296999999999997e-02 --2.2169660441877932e+00 , 2.6348774584133472e+00 , 4.3203855999999998e+00 , 9.8609100000000005e-01 , -1.5107000000000001e-01 , 6.9296800000000006e-02 --2.3740276837844645e+00 , 2.6564472881021817e+00 , 4.4518936000000000e+00 , -8.7586200000000003e-01 , 1.1453400000000000e-01 , -4.6877300000000000e-01 --2.7068861867513636e+00 , 2.6891463155873447e+00 , 4.6433263999999994e+00 , -3.7507200000000002e-01 , 1.8243400000000001e-01 , -9.0886699999999998e-01 --2.5599455484379989e+00 , 2.6951522323417763e+00 , 4.6939328000000007e+00 , 1.0910900000000000e-01 , 7.7339899999999995e-01 , -6.2445899999999999e-01 --6.0967638749865909e+00 , 2.9261523246207686e+00 , 5.9975312000000010e+00 , -4.6984399999999998e-01 , -8.0901100000000004e-01 , 3.5319699999999998e-01 --3.1728943890697012e+00 , 2.7647526712939356e+00 , 5.1088719999999999e+00 , 5.6484400000000001e-01 , -1.1941800000000000e-01 , -8.1651099999999999e-01 --3.1361931720926526e+00 , 2.7794824932699003e+00 , 5.2056231999999998e+00 , -3.8757399999999997e-01 , 1.9624000000000000e-01 , 9.0070899999999998e-01 --2.9818176469342257e+00 , 2.7860829451377822e+00 , 5.2554911999999998e+00 , 5.8498399999999995e-01 , -5.2282600000000001e-01 , -6.2003699999999995e-01 --2.0813788285249997e+00 , 2.7367809654384292e+00 , 4.9868696000000003e+00 , 4.5013199999999998e-01 , -8.3677100000000004e-01 , -3.1176199999999998e-01 --2.7121641681861064e+00 , 2.7993594678390363e+00 , 5.3578688000000003e+00 , 3.4792400000000001e-01 , -9.3740100000000004e-01 , 1.5131400000000000e-02 --2.2568066338153248e+00 , 2.7792783592500481e+00 , 5.2552415999999997e+00 , 3.4709000000000001e-01 , -8.8116700000000003e-01 , 3.2105099999999998e-01 --2.7584879446510806e+00 , 2.8369676132070687e+00 , 5.5978903999999998e+00 , 7.0922600000000002e-01 , -7.0498099999999997e-01 , -9.9780500000000005e-04 --1.0211150336129075e+01 , 3.4963372567132947e+00 , 9.4727744000000005e+00 , 2.7115400000000001e-01 , -6.1354100000000000e-01 , 7.4164900000000000e-01 --2.3178525033126363e+00 , 2.8318250526314324e+00 , 5.5926279999999995e+00 , 5.8674400000000004e-01 , 7.2749200000000003e-01 , -3.5564800000000002e-01 --1.0040490479907147e+01 , 3.5663529892978487e+00 , 9.9409823999999993e+00 , -2.7115400000000001e-01 , 6.1354100000000000e-01 , -7.4164900000000000e-01 --2.5948638470053123e+00 , 2.8925367869882934e+00 , 5.9665911999999999e+00 , 1.7146100000000000e-01 , 4.1449999999999998e-01 , 8.9375099999999996e-01 --2.5073454675103886e+00 , 2.9009394996944695e+00 , 6.0322567999999999e+00 , 1.7146100000000000e-01 , 4.1449999999999998e-01 , 8.9375099999999996e-01 --1.9173888109939323e+00 , 2.8585977784379506e+00 , 5.7846120000000001e+00 , 3.8513799999999998e-01 , 9.0466999999999997e-01 , -1.8232100000000001e-01 --1.5464950471127676e+00 , 2.8350944934015345e+00 , 5.6522096000000008e+00 , 2.6936599999999999e-01 , 9.6191199999999999e-01 , 4.6556699999999999e-02 --1.5775956036096530e+00 , 2.8533027189005784e+00 , 5.7728496000000007e+00 , 2.6936599999999999e-01 , 9.6191199999999999e-01 , 4.6556599999999997e-02 --2.0989964928940275e+00 , 2.9300110119387091e+00 , 6.2373136000000002e+00 , 2.9427900000000001e-01 , 2.3906700000000000e-01 , 9.2533600000000005e-01 --3.0172123564108944e+00 , 3.0575348676598049e+00 , 7.0169391999999995e+00 , -8.3129699999999995e-01 , -2.0794399999999999e-01 , 5.1546499999999995e-01 --4.2491938157514104e+00 , 3.2318257493029163e+00 , 8.0829184000000005e+00 , -8.7229699999999999e-01 , 4.1190100000000002e-01 , -2.6350499999999999e-01 --1.3449050374504754e+00 , 2.8896795119340646e+00 , 6.0188616000000001e+00 , -9.1339899999999996e-01 , -1.2834599999999999e-01 , 3.8630199999999998e-01 --1.2837887974318858e+00 , 2.8978237775234339e+00 , 6.0776112000000007e+00 , -9.7260100000000005e-01 , 6.5613599999999994e-02 , 2.2303000000000001e-01 --2.3199661767345248e+00 , 3.0560425526300401e+00 , 7.0475984000000000e+00 , -7.4177400000000004e-01 , -6.1727299999999996e-01 , 2.6219300000000001e-01 --2.4450576936398631e+00 , 3.0959461193187643e+00 , 7.2980512000000006e+00 , -7.0028100000000004e-01 , -6.5202800000000005e-01 , 2.9063099999999997e-01 --2.4077898403333080e+00 , 3.1139530383134453e+00 , 7.4164240000000001e+00 , 6.7620700000000000e-01 , 5.3536499999999998e-01 , -5.0609199999999999e-01 --1.1997043281246076e+00 , 2.9552560035784405e+00 , 6.4544135999999996e+00 , 4.3654300000000001e-01 , -1.9784399999999999e-01 , 8.7766100000000002e-01 --1.1094197071232244e+00 , 2.9603250318952448e+00 , 6.4882759999999999e+00 , 2.5464399999999998e-01 , 7.5009800000000004e-01 , 6.1033599999999999e-01 --1.1804214890290798e+00 , 2.9903733206231125e+00 , 6.6802288000000001e+00 , -4.9046000000000001e-01 , 8.6637399999999998e-01 , -9.4049300000000002e-02 --1.5055944315406800e+00 , 3.0644659493897288e+00 , 7.1419576000000005e+00 , -4.3641700000000000e-01 , -7.7450900000000000e-01 , 4.5790300000000000e-01 --1.2566166164081185e+00 , 3.0433190757452380e+00 , 7.0216400000000005e+00 , 6.3294300000000003e-01 , 7.3145499999999997e-01 , -2.5368400000000002e-01 --1.2143656026997709e+00 , 3.0572638228959406e+00 , 7.1156664000000003e+00 , 7.7442100000000003e-01 , 5.6855599999999995e-01 , -2.7751700000000001e-01 --1.2851783088261577e+00 , 3.0930276045150307e+00 , 7.3413152000000004e+00 , -6.1539900000000003e-01 , -7.2063200000000005e-01 , 3.1933299999999998e-01 -4.7788148521524310e-01 , 2.7803634473094228e+00 , 5.4120112000000002e+00 , 3.8558100000000001e-01 , -2.5891500000000001e-01 , -8.8560200000000000e-01 --1.0799365029316319e+00 , 3.1010679279036646e+00 , 7.4039336000000002e+00 , -6.3641800000000004e-01 , -6.3829800000000003e-01 , 4.3306699999999998e-01 --1.0032761141703870e+00 , 3.1099012748715356e+00 , 7.4641704000000004e+00 , -6.3641800000000004e-01 , -6.3829800000000003e-01 , 4.3306699999999998e-01 --9.6272908662240075e-01 , 3.1257608615364783e+00 , 7.5725800000000003e+00 , -6.3641800000000004e-01 , -6.3829800000000003e-01 , 4.3306699999999998e-01 -5.7412780348934267e-01 , 2.8152284171140955e+00 , 5.6424647999999999e+00 , -6.4031800000000000e-02 , 2.9510100000000000e-01 , -9.5331800000000000e-01 -6.0812745430422299e-01 , 2.8225555600215451e+00 , 5.6913552000000003e+00 , 1.4467200000000000e-01 , 5.9922100000000000e-01 , -7.8740399999999999e-01 -4.6307413755826432e-01 , 2.8726745577948098e+00 , 6.0040624000000005e+00 , 7.5430799999999998e-01 , -5.6210300000000002e-01 , 3.3920400000000001e-01 -4.8115398500535234e-01 , 2.8849348587425849e+00 , 6.0898208000000000e+00 , 6.4339199999999996e-01 , 7.3440599999999995e-02 , -7.6200599999999996e-01 -7.4913368052219442e-01 , 2.8360599615590552e+00 , 5.7832287999999998e+00 , -9.0644899999999995e-01 , 3.9568300000000001e-01 , -1.4759900000000001e-01 -7.4357095633870873e-01 , 2.8535555661401624e+00 , 5.9004992000000005e+00 , -1.0420599999999999e-01 , 2.4521200000000000e-02 , 9.9425300000000005e-01 -9.1846403741349891e-01 , 2.8237207474826471e+00 , 5.7159408000000003e+00 , 9.8974499999999999e-01 , -5.9264699999999997e-02 , 1.2996800000000000e-01 -6.9846498277591551e-01 , 2.9036350480112096e+00 , 6.2184792000000000e+00 , 5.0905500000000004e-01 , 6.9752700000000001e-01 , -5.0430100000000000e-01 -5.5008763831621299e-01 , 2.9684244956943533e+00 , 6.6296328000000004e+00 , -5.1612499999999994e-01 , 5.0261900000000004e-01 , 6.9353399999999998e-01 -6.5028833487727411e-01 , 2.9611674431330046e+00 , 6.5886359999999993e+00 , 1.7994800000000000e-01 , -9.7983600000000004e-01 , -8.6833099999999996e-02 -7.8998385570742102e-01 , 2.9403113249633286e+00 , 6.4622136000000001e+00 , 7.4122800000000000e-01 , 6.6542800000000002e-01 , -8.8246199999999997e-02 -7.3685581064693206e-01 , 2.9822703997559437e+00 , 6.7329255999999997e+00 , 6.2908200000000003e-01 , -3.8605000000000000e-01 , -6.7470100000000000e-01 -6.6627164168448649e-01 , 3.0336582253651376e+00 , 7.0624808000000003e+00 , -4.9906099999999998e-01 , -5.3282300000000005e-01 , 6.8340199999999995e-01 -7.0926382710094038e-01 , 3.0480821727027174e+00 , 7.1590760000000007e+00 , -2.6793600000000001e-01 , -5.0806200000000001e-01 , 8.1858600000000004e-01 -8.6262188979937671e-01 , 3.0208909012991216e+00 , 6.9883183999999998e+00 , -5.9223199999999998e-01 , 8.0455100000000002e-01 , -4.4261900000000000e-02 -1.0101099284594559e+00 , 2.9921383137747153e+00 , 6.8138688000000007e+00 , -5.5468899999999999e-01 , -7.0632200000000001e-01 , -4.3980700000000000e-01 -1.0656075337872712e+00 , 3.0004806777488184e+00 , 6.8671168000000007e+00 , -3.0783800000000000e-01 , -5.8986000000000005e-01 , 7.4652600000000002e-01 -1.2369362304371292e+00 , 2.9562185393682463e+00 , 6.5891143999999997e+00 , -9.7489700000000001e-01 , 1.5947100000000000e-01 , 1.5538800000000000e-01 -1.2668552574757974e+00 , 2.9734785842083342e+00 , 6.7075287999999995e+00 , -2.7894400000000003e-01 , -9.4525300000000001e-01 , 1.6937300000000000e-01 -1.2824833479335143e+00 , 3.0010636716749319e+00 , 6.8846512000000004e+00 , 1.5589300000000000e-01 , 9.1771700000000000e-01 , -3.6536600000000002e-01 -8.8650816980881886e-01 , 3.2553025999111664e+00 , 8.5153192000000004e+00 , 5.8940199999999998e-01 , -8.0453699999999995e-01 , 7.2979500000000003e-02 -9.2670486689709763e-01 , 3.2913379588441192e+00 , 8.7501511999999995e+00 , 7.8732899999999995e-01 , 5.6746399999999997e-01 , -2.4103500000000000e-01 -1.0096864016004425e+00 , 3.3058988940810847e+00 , 8.8454359999999994e+00 , -6.7907799999999996e-01 , -3.7405200000000000e-01 , -6.3161599999999996e-01 -1.4453641826316224e+00 , 3.0831913844739010e+00 , 7.4271671999999995e+00 , -2.6702199999999998e-01 , 4.5840300000000000e-01 , 8.4768200000000005e-01 -1.5241746329199213e+00 , 3.0832922137651630e+00 , 7.4339792000000005e+00 , -1.1098900000000000e-01 , -1.4975800000000001e-03 , 9.9382099999999995e-01 -1.6508041828947924e+00 , 3.0460667916637654e+00 , 7.1971503999999999e+00 , -5.1093299999999997e-01 , 4.8198800000000003e-01 , -7.1178300000000005e-01 -1.4574247464868280e+00 , 3.2823738365274249e+00 , 8.7187848000000017e+00 , -5.0621000000000005e-01 , -1.7796400000000001e-01 , -8.4384899999999996e-01 -1.5327212340906873e+00 , 3.3078136417071873e+00 , 8.8874624000000004e+00 , 6.5978599999999998e-01 , -3.3788400000000002e-01 , 6.7120599999999997e-01 -1.6486662871281412e+00 , 3.2948556711047980e+00 , 8.8110120000000016e+00 , -9.2783499999999997e-01 , 2.4206800000000001e-01 , -2.8377100000000000e-01 --1.2107445788306874e+00 , 2.1680634427230903e+00 , 5.7903760000000015e-01 , -9.6943199999999993e-02 , 9.3088400000000002e-02 , 9.9092700000000000e-01 --1.3752708733196193e+00 , 2.1718059549754436e+00 , 5.6251199999999990e-01 , -8.2915699999999995e-02 , 1.0462299999999999e-01 , 9.9104999999999999e-01 --1.5502011003352330e+00 , 2.1758854419749762e+00 , 5.4542479999999993e-01 , 8.0308699999999997e-02 , -1.3586500000000001e-01 , -9.8746699999999998e-01 --1.7268358515821998e+00 , 2.1800502326809341e+00 , 5.3368319999999980e-01 , -7.4751200000000004e-02 , 1.5982399999999999e-01 , 9.8431100000000005e-01 --1.9227204311504322e+00 , 2.1850551800743161e+00 , 5.1672079999999987e-01 , -6.1546200000000002e-02 , 1.8334600000000001e-01 , 9.8111999999999999e-01 --2.1665293224382776e+00 , 2.1892357233339208e+00 , 4.8017519999999991e-01 , -8.6911600000000006e-02 , 1.8402600000000000e-01 , 9.7907100000000002e-01 --2.4123346798754612e+00 , 2.1939994957527267e+00 , 4.5138799999999990e-01 , -8.2110100000000005e-02 , 1.8007100000000001e-01 , 9.8022100000000001e-01 --2.6876813327090252e+00 , 2.1997520281544687e+00 , 4.1592399999999996e-01 , -7.3949600000000004e-02 , 1.9386300000000001e-01 , 9.7823800000000005e-01 --2.9661957196697992e+00 , 2.2063692654650104e+00 , 3.8931039999999983e-01 , -6.8491499999999997e-02 , 1.9171099999999999e-01 , 9.7905900000000001e-01 --3.3033196791270658e+00 , 2.2118976741488141e+00 , 3.4479839999999995e-01 , -9.7803000000000001e-02 , 1.9780100000000000e-01 , 9.7535099999999997e-01 --3.7004384670514909e+00 , 2.2180408039045196e+00 , 2.8527919999999996e-01 , -9.5537300000000006e-02 , 1.7643900000000001e-01 , 9.7966399999999998e-01 --4.1111205962255077e+00 , 2.2264962052158879e+00 , 2.3437120000000000e-01 , -7.1330099999999994e-02 , 1.6192599999999999e-01 , 9.8422200000000004e-01 --4.5344826005239778e+00 , 2.2363605900858037e+00 , 1.9301039999999992e-01 , -7.8367599999999996e-02 , 1.6672999999999999e-01 , 9.8288299999999995e-01 --5.0575945633352912e+00 , 2.2456571997482353e+00 , 1.2750079999999975e-01 , -8.7951299999999996e-02 , 1.6731499999999999e-01 , 9.8197299999999998e-01 --5.6429546467927416e+00 , 2.2577328119698414e+00 , 5.7279999999999776e-02 , -8.5228100000000001e-02 , 1.6546800000000000e-01 , 9.8252600000000001e-01 --6.3322468803068350e+00 , 2.2711837075962991e+00 , -2.8353599999999979e-02 , -8.9277499999999996e-02 , 1.6645900000000000e-01 , 9.8199800000000004e-01 --7.1341111037624607e+00 , 2.2868052701347263e+00 , -1.2717440000000035e-01 , -8.8875700000000002e-02 , 1.5952200000000000e-01 , 9.8318600000000000e-01 --8.1300187231082184e+00 , 2.3042119444531717e+00 , -2.5854719999999975e-01 , -7.7370200000000000e-02 , 1.5834400000000001e-01 , 9.8434800000000000e-01 --9.1340209092453968e+00 , 2.3276286776448076e+00 , -3.5661919999999991e-01 , 7.1947100000000000e-02 , -1.5389700000000001e-01 , -9.8546400000000001e-01 --1.0464513027113590e+01 , 2.3559916704694905e+00 , -5.1022720000000010e-01 , 7.9192899999999997e-02 , -1.5335900000000000e-01 , -9.8499199999999998e-01 --1.2084806571485304e+01 , 2.3901164601565146e+00 , -6.9181120000000007e-01 , -7.7204200000000001e-02 , 1.5249499999999999e-01 , 9.8528400000000005e-01 --1.4108739641496367e+01 , 2.4335512352721738e+00 , -9.1339360000000047e-01 , -7.9657400000000003e-02 , 1.4254300000000000e-01 , 9.8657799999999995e-01 --1.6560090192023956e+01 , 2.4894770548254832e+00 , -1.1589792000000001e+00 , 8.9118100000000006e-02 , -1.4869399999999999e-01 , -9.8485900000000004e-01 --3.8388004500457228e+01 , 2.9172092938076459e+00 , -3.8307184000000003e+00 , -4.3768500000000002e-02 , 8.1380599999999997e-02 , 9.9572200000000000e-01 --4.8412196257664775e+01 , 3.5810626957543885e+00 , -1.9524576000000002e+00 , 5.2535100000000001e-01 , -7.1407299999999996e-01 , 4.6271699999999999e-01 --1.2276530669295910e+01 , 3.1678831129789073e+00 , 4.4293256000000003e+00 , 9.9720399999999998e-01 , 7.2444200000000000e-02 , -1.8310799999999999e-02 --1.0752281280046748e+01 , 3.1238608038332147e+00 , 4.5202944000000009e+00 , -2.0468800000000001e-01 , -1.1521900000000000e-01 , 9.7202200000000005e-01 --1.1012020727905382e+01 , 3.1734404332292883e+00 , 4.7847455999999999e+00 , 2.6211400000000001e-01 , 2.0480300000000001e-01 , -9.4305499999999998e-01 --9.9305495215753776e+00 , 3.1443982846571110e+00 , 4.8660528000000003e+00 , 1.8916600000000000e-01 , 7.2634299999999999e-02 , -9.7925499999999999e-01 --8.9631698450326844e+00 , 3.1175371227404307e+00 , 4.9286712000000001e+00 , 3.8183499999999998e-01 , 4.9679400000000001e-01 , -7.7935699999999997e-01 --9.0605538451459626e+00 , 3.1545574504280323e+00 , 5.1495256000000005e+00 , 3.1683699999999998e-01 , 4.7540800000000000e-01 , -8.2073200000000002e-01 --8.0541755572199669e+00 , 3.1170633660036828e+00 , 5.1571487999999999e+00 , -3.1581900000000002e-01 , -6.0002400000000000e-01 , 7.3500299999999996e-01 --8.2880135118296021e+00 , 3.1617807056560068e+00 , 5.3977528000000001e+00 , 3.8183499999999998e-01 , 4.9679499999999999e-01 , -7.7935699999999997e-01 --2.2857312738491578e+00 , 2.7514173552158581e+00 , 4.1884720000000000e+00 , 7.6332900000000004e-01 , -2.9981200000000002e-01 , -5.7222499999999998e-01 --2.2045870506247436e+00 , 2.7591752654413315e+00 , 4.2548031999999996e+00 , 7.7272200000000002e-01 , 3.6901000000000000e-01 , 5.1646099999999995e-01 --2.3526124623582296e+00 , 2.7835955355039657e+00 , 4.3813296000000008e+00 , -8.4176300000000004e-01 , -3.9369199999999999e-01 , -3.6937999999999999e-01 --2.4482547770498222e+00 , 2.8050091882282100e+00 , 4.4988288000000001e+00 , -9.4311599999999995e-01 , -1.0332700000000000e-02 , -3.3230399999999999e-01 --2.7292340887589246e+00 , 2.8425793176541112e+00 , 4.6780520000000001e+00 , 1.3788600000000001e-01 , -7.8428399999999995e-02 , 9.8733800000000005e-01 --2.4822249439443835e+00 , 2.8356985009301203e+00 , 4.6966160000000006e+00 , 1.6488300000000000e-01 , -8.7734199999999996e-01 , 4.5065000000000000e-01 --3.4999090828813699e+00 , 2.9422102170898263e+00 , 5.1451680000000000e+00 , -5.9857499999999997e-01 , -2.0023600000000000e-01 , 7.7563700000000002e-01 --2.3243438674077250e+00 , 2.8495568735425794e+00 , 4.8307135999999993e+00 , 6.5673199999999998e-01 , -3.3687000000000000e-01 , -6.7470200000000002e-01 --2.3021253669731472e+00 , 2.8617116953495292e+00 , 4.9168775999999994e+00 , -6.1342900000000000e-01 , 1.0367899999999999e-01 , 7.8291500000000003e-01 --2.1820126022381858e+00 , 2.8649003793231458e+00 , 4.9636151999999996e+00 , -6.1342900000000000e-01 , 1.0367899999999999e-01 , 7.8291500000000003e-01 --2.1861228428645463e+00 , 2.8791567794098936e+00 , 5.0598255999999999e+00 , 7.2963500000000003e-01 , -6.7412200000000000e-01 , -1.1485900000000000e-01 --2.5178470457018074e+00 , 2.9289792871025351e+00 , 5.3048288000000001e+00 , -3.8255299999999998e-01 , -4.9034600000000000e-01 , 7.8308000000000000e-01 --2.3558182503528071e+00 , 2.9267212286108775e+00 , 5.3334808000000002e+00 , -9.0632999999999997e-01 , -2.4884899999999999e-01 , -3.4152600000000000e-01 --2.5378087352419438e+00 , 2.9626462085582190e+00 , 5.5256832000000005e+00 , -3.9171899999999998e-01 , -8.9851099999999995e-01 , 1.9807800000000000e-01 --2.3274777648496920e+00 , 2.9548988911428857e+00 , 5.5268480000000002e+00 , -9.0956700000000001e-01 , -3.3498499999999998e-01 , 2.4591199999999999e-01 --2.3655154402095828e+00 , 2.9756059338582412e+00 , 5.6531039999999999e+00 , 5.6778099999999998e-01 , 7.4584300000000003e-01 , -3.4834199999999998e-01 --2.6260939814294559e+00 , 3.0231478423874822e+00 , 5.9072800000000001e+00 , 7.0368399999999998e-01 , -5.5682900000000002e-01 , -4.4132900000000003e-01 --2.2710374572788989e+00 , 2.9963705207789908e+00 , 5.8184848000000002e+00 , -3.4671500000000000e-01 , -8.8923399999999997e-01 , 2.9841400000000001e-01 --2.1149903967772223e+00 , 2.9931545811797262e+00 , 5.8358319999999999e+00 , -5.3641399999999995e-01 , -6.9006400000000001e-01 , 4.8587100000000000e-01 --1.6538587986298245e+00 , 2.9488293333141304e+00 , 5.6562552000000004e+00 , 2.6936599999999999e-01 , 9.6191199999999999e-01 , 4.6556800000000002e-02 --1.6339052857148357e+00 , 2.9613739413395486e+00 , 5.7438856000000005e+00 , 2.6936599999999999e-01 , 9.6191199999999999e-01 , 4.6556800000000002e-02 --2.0128243340178438e+00 , 3.0300684645182034e+00 , 6.1040792000000001e+00 , -8.4837499999999999e-01 , -5.2279699999999996e-01 , 8.3322400000000005e-02 --2.8800523835470413e+00 , 3.1718861602705450e+00 , 6.8285016000000001e+00 , 9.3869000000000002e-01 , -3.4075200000000000e-01 , -5.2440500000000001e-02 --2.9958750029450485e+00 , 3.2106655642136754e+00 , 7.0542128000000002e+00 , -8.9221200000000001e-01 , -3.8796700000000003e-02 , 4.4994800000000001e-01 --2.9485646902870224e+00 , 3.2249885790708852e+00 , 7.1670423999999997e+00 , 6.9952300000000001e-01 , -1.9699399999999999e-02 , -7.1433899999999995e-01 --2.7939048193350979e+00 , 3.2242186038934921e+00 , 7.1962352000000003e+00 , 2.3364799999999999e-01 , 1.3166500000000000e-01 , -9.6336599999999994e-01 --2.5365870449557368e+00 , 3.2054308496952659e+00 , 7.1367992000000005e+00 , -7.0028100000000004e-01 , -6.5202800000000005e-01 , 2.9063200000000000e-01 --2.5188076582520953e+00 , 3.2249840303583279e+00 , 7.2692328000000002e+00 , -6.1890699999999998e-01 , -2.9562800000000000e-01 , 7.2770800000000002e-01 --2.9022386221616996e+00 , 3.3118010169975327e+00 , 7.7553496000000006e+00 , -8.6291300000000004e-01 , -3.3314400000000000e-01 , 3.7999600000000000e-01 --1.4334759176420531e+00 , 3.0817804229957488e+00 , 6.5950632000000002e+00 , -8.3212500000000000e-01 , -5.2716600000000002e-01 , -1.7223200000000000e-01 --1.1227008468045669e+00 , 3.0445836391515049e+00 , 6.4293287999999995e+00 , -2.5697900000000001e-01 , 8.8453700000000002e-01 , -3.8930199999999998e-01 --1.0405112897374060e+00 , 3.0480223282947452e+00 , 6.4692024000000004e+00 , 2.5464399999999998e-01 , 7.5009800000000004e-01 , 6.1033599999999999e-01 --1.3505827944201347e+00 , 3.1251973931078592e+00 , 6.9020296000000005e+00 , -7.5689799999999996e-01 , -6.5163099999999996e-01 , -4.9827700000000003e-02 --1.5388493815028168e+00 , 3.1823465750099547e+00 , 7.2351312000000005e+00 , 4.7452400000000000e-01 , 6.4342600000000005e-01 , -6.0069099999999997e-01 --1.4581770384873156e+00 , 3.1880350869198693e+00 , 7.2963768000000000e+00 , 4.7452400000000000e-01 , 6.4342600000000005e-01 , -6.0069099999999997e-01 --1.2858627667449882e+00 , 3.1757118027475668e+00 , 7.2561704000000002e+00 , -5.0962200000000002e-01 , -7.5336599999999998e-01 , 4.1560100000000000e-01 --2.6239598397141117e-01 , 2.9805775705440296e+00 , 6.2214431999999995e+00 , -6.8092299999999994e-01 , 7.4819600000000000e-02 , 7.2852300000000003e-01 -4.9965233554430211e-01 , 2.8312657037414288e+00 , 5.4215999999999998e+00 , 4.8422300000000001e-01 , 3.4078799999999998e-01 , 8.0584800000000001e-01 -3.4767461184301940e-01 , 2.8782195417529968e+00 , 5.6959727999999998e+00 , -6.2672099999999997e-01 , -6.7849099999999996e-01 , -3.8323800000000002e-01 -4.1330655719466192e-01 , 2.8777500375901015e+00 , 5.7076624000000002e+00 , -5.4149000000000003e-01 , -8.3708199999999999e-01 , 7.7989600000000006e-02 -4.6046432759300449e-01 , 2.8817277292846928e+00 , 5.7427520000000003e+00 , -3.3065400000000000e-01 , -7.0790500000000001e-01 , 6.2412999999999996e-01 -5.3155241845768542e-01 , 2.8788412146086730e+00 , 5.7436048000000000e+00 , 1.1753500000000000e-01 , 8.2734600000000003e-01 , -5.4925700000000000e-01 -5.7373435396303796e-01 , 2.8832852564696685e+00 , 5.7851840000000001e+00 , 2.6270500000000002e-01 , 9.5518000000000003e-01 , -1.3644700000000001e-01 -6.1599011881467280e-01 , 2.8875744798962719e+00 , 5.8260560000000003e+00 , 2.1423600000000001e-01 , -2.3322699999999999e-01 , -9.4852899999999996e-01 -5.4774253494820768e-01 , 2.9228289197129782e+00 , 6.0391728000000002e+00 , 1.9244800000000001e-01 , 9.7648800000000002e-01 , -9.7137000000000001e-02 -7.6248262128926503e-01 , 2.8800447541268923e+00 , 5.8093848000000001e+00 , -1.4723900000000001e-01 , 6.1273599999999995e-01 , 7.7644999999999997e-01 -8.9521683428641396e-01 , 2.8580534086228742e+00 , 5.6969088000000001e+00 , 1.9992599999999999e-01 , -8.7394399999999997e-02 , 9.7590600000000005e-01 -6.2622669727449520e-01 , 2.9558017776167289e+00 , 6.2775407999999997e+00 , -4.9629200000000001e-01 , -7.2209199999999996e-01 , 4.8195100000000002e-01 -7.0745365543390637e-01 , 2.9505879536832502e+00 , 6.2637192000000006e+00 , 6.8582200000000004e-01 , 6.8554000000000004e-01 , -2.4430199999999999e-01 -6.2115469163172343e-01 , 2.9994587586836752e+00 , 6.5669312000000000e+00 , -4.8042600000000002e-01 , 8.7677700000000003e-01 , -2.1292300000000000e-02 -6.5485321326254531e-01 , 3.0112029228062092e+00 , 6.6534592000000004e+00 , 5.5102600000000002e-01 , -5.9164000000000005e-01 , -5.8850000000000002e-01 -7.1822800480787530e-01 , 3.0135972779231404e+00 , 6.6841704000000002e+00 , -5.7481099999999996e-01 , 5.5709100000000000e-01 , 5.9936699999999998e-01 -7.6145162791502230e-01 , 3.0229533854412978e+00 , 6.7608808000000007e+00 , 6.4751400000000003e-01 , -2.6441900000000002e-01 , -7.1470900000000004e-01 -8.2185148742419534e-01 , 3.0269731120168943e+00 , 6.7990279999999998e+00 , -6.2517000000000000e-01 , 4.7471799999999997e-01 , 6.1951999999999996e-01 -8.6086236300203556e-01 , 3.0390407253935594e+00 , 6.8935952000000000e+00 , -3.8810800000000001e-01 , 8.1533500000000003e-01 , 4.2965300000000001e-01 -9.3958506500330730e-01 , 3.0364178286096584e+00 , 6.8920871999999997e+00 , -5.2153799999999995e-01 , -8.0854300000000001e-01 , -2.7250099999999999e-01 -1.0217099441188826e+00 , 3.0314072453130629e+00 , 6.8795032000000003e+00 , 4.4356400000000001e-01 , 3.4070299999999998e-01 , 8.2895799999999997e-01 -1.1958154644488455e+00 , 2.9832723799325578e+00 , 6.6039136000000003e+00 , -9.6657199999999999e-01 , 3.3481499999999997e-02 , 2.5420100000000001e-01 -1.2776913104305523e+00 , 2.9744230010570547e+00 , 6.5669623999999995e+00 , -3.4054400000000001e-01 , -3.4196100000000001e-01 , 8.7583800000000001e-01 -1.2151285720844989e+00 , 3.0388760740097327e+00 , 6.9789064000000005e+00 , -3.8225900000000002e-01 , -7.1070599999999995e-01 , 5.9057300000000001e-01 -1.2903429465929852e+00 , 3.0359346304227266e+00 , 6.9803623999999997e+00 , -2.1799300000000001e-03 , -8.5459600000000002e-01 , 5.1928799999999997e-01 -8.9885671297825542e-01 , 3.3027986352420502e+00 , 8.6535352000000003e+00 , -4.1509800000000002e-01 , -9.0684799999999999e-01 , -7.2945300000000005e-02 -1.0082729597483266e+00 , 3.2964970761278867e+00 , 8.6403584000000002e+00 , 7.1692900000000004e-01 , 6.9639300000000004e-01 , -3.2390599999999999e-02 -1.4148975398598589e+00 , 3.0921581349658096e+00 , 7.3861287999999998e+00 , -2.6702199999999998e-01 , 4.5840300000000000e-01 , 8.4768200000000005e-01 -1.4813523171821226e+00 , 3.0987953637886489e+00 , 7.4437968000000003e+00 , -1.6382200000000000e-01 , 8.9171399999999998e-02 , 9.8245099999999996e-01 -1.5894877155631633e+00 , 3.0744704726971754e+00 , 7.3092312000000002e+00 , 7.7914799999999995e-01 , -3.4678799999999999e-01 , 5.2217599999999997e-01 -1.7005970369716301e+00 , 3.0435432008607544e+00 , 7.1320256000000004e+00 , 7.7267500000000003e-02 , -6.3012199999999996e-01 , 7.7264200000000005e-01 -1.5196034463343471e+00 , 3.2796232077716478e+00 , 8.6551679999999998e+00 , -6.3963899999999996e-01 , -1.5021000000000001e-01 , -7.5385599999999997e-01 -1.5902464809118269e+00 , 3.3070484919437142e+00 , 8.8537767999999986e+00 , -3.7229099999999998e-01 , 2.8145500000000001e-01 , -8.8441099999999995e-01 -1.6766017506550344e+00 , 3.3245429602157328e+00 , 8.9906512000000003e+00 , -7.0659700000000003e-01 , -6.7291400000000001e-01 , 2.1887999999999999e-01 --9.5300197290273880e-01 , 2.2701984132447515e+00 , 6.0340479999999985e-01 , -9.4916000000000000e-02 , 1.5809899999999999e-01 , 9.8285100000000003e-01 --1.0805769144800670e+00 , 2.2786946235215622e+00 , 6.0254159999999990e-01 , 8.2032400000000005e-02 , -1.3533999999999999e-01 , -9.8739699999999997e-01 --1.2609571658782488e+00 , 2.2863649352494004e+00 , 5.7049919999999998e-01 , -9.8182099999999994e-02 , 1.4980299999999999e-01 , 9.8382899999999995e-01 --1.4255266807426112e+00 , 2.2956601860197061e+00 , 5.5515919999999985e-01 , -8.4743299999999994e-02 , 1.2381300000000001e-01 , 9.8868000000000000e-01 --1.6180353002912993e+00 , 2.3048979680099082e+00 , 5.2831680000000003e-01 , 8.8587500000000000e-02 , -1.4538400000000001e-01 , -9.8540099999999997e-01 --1.8309493055720467e+00 , 2.3140805656593466e+00 , 4.9683600000000006e-01 , -6.9196300000000002e-02 , 1.7350599999999999e-01 , 9.8239900000000002e-01 --2.0456626089034202e+00 , 2.3246535736045657e+00 , 4.7189679999999989e-01 , -8.2461900000000005e-02 , 1.8324799999999999e-01 , 9.7960199999999997e-01 --2.2808813056920378e+00 , 2.3364499751755532e+00 , 4.4333839999999980e-01 , -8.7216799999999997e-02 , 1.7108300000000001e-01 , 9.8138899999999996e-01 --2.5554415191649316e+00 , 2.3495777630394459e+00 , 4.0248719999999993e-01 , 9.3044900000000000e-02 , -1.7146500000000001e-01 , -9.8078699999999996e-01 --2.8321209950439332e+00 , 2.3635281149762557e+00 , 3.7051759999999989e-01 , -6.7321599999999995e-02 , 1.8237600000000001e-01 , 9.8092100000000004e-01 --3.1395838329052195e+00 , 2.3788362216875312e+00 , 3.3346239999999994e-01 , -8.9157600000000004e-02 , 1.8576799999999999e-01 , 9.7853999999999997e-01 --3.5057951014527466e+00 , 2.3954680023405923e+00 , 2.7991279999999996e-01 , -9.1154499999999999e-02 , 1.6975100000000001e-01 , 9.8126199999999997e-01 --3.8765082585233106e+00 , 2.4146253387832073e+00 , 2.3791760000000006e-01 , -8.1769400000000006e-02 , 1.6349900000000001e-01 , 9.8314900000000005e-01 --4.2875857813900176e+00 , 2.4347157123071672e+00 , 1.9193919999999998e-01 , -7.4357599999999996e-02 , 1.6209000000000001e-01 , 9.8397100000000004e-01 --4.7691270333338878e+00 , 2.4591668284536636e+00 , 1.3151519999999972e-01 , -8.8565000000000005e-02 , 1.6324500000000000e-01 , 9.8260199999999998e-01 --5.3227190303585568e+00 , 2.4857044627385667e+00 , 6.0774399999999895e-02 , -8.7566099999999994e-02 , 1.6175999999999999e-01 , 9.8293699999999995e-01 --5.9587580756811986e+00 , 2.5168265815780910e+00 , -2.0636800000000122e-02 , -8.9374499999999996e-02 , 1.6349800000000000e-01 , 9.8248700000000000e-01 --6.6878757109978153e+00 , 2.5521608008074095e+00 , -1.1153279999999999e-01 , -9.0062299999999998e-02 , 1.5924500000000000e-01 , 9.8312299999999997e-01 --7.5810965341628425e+00 , 2.5952750317841087e+00 , -2.3043600000000009e-01 , -8.9621999999999993e-02 , 1.5155800000000000e-01 , 9.8437699999999995e-01 --8.5496089974415472e+00 , 2.6443711627426096e+00 , -3.4095679999999984e-01 , -7.1480000000000002e-02 , 1.5196299999999999e-01 , 9.8579799999999995e-01 --9.7143012450026713e+00 , 2.7026506428169603e+00 , -4.7414960000000006e-01 , -7.7989799999999998e-02 , 1.5383800000000000e-01 , 9.8501399999999995e-01 --1.1176623260495150e+01 , 2.7762046904756503e+00 , -6.4771519999999994e-01 , -7.8609200000000004e-02 , 1.5090000000000001e-01 , 9.8541900000000004e-01 --1.2959844181790762e+01 , 2.8670653472104153e+00 , -8.5125360000000017e-01 , -7.7037800000000003e-02 , 1.4739400000000000e-01 , 9.8607299999999998e-01 --1.5289762144207266e+01 , 2.9840573559083126e+00 , -1.1209984000000004e+00 , -8.2804900000000001e-02 , 1.5548300000000001e-01 , 9.8436199999999996e-01 --3.8877746245705644e+01 , 4.2977319703275469e+00 , -3.0068824000000003e+00 , -3.0806899999999998e-01 , 1.5760300000000000e-04 , 9.5136399999999999e-01 --3.8992742810127581e+01 , 4.4101211814209265e+00 , -2.2944824000000006e+00 , -4.5197300000000001e-01 , -8.0594600000000002e-02 , 8.8838300000000003e-01 --4.4946161208795765e+01 , 4.8201814363872852e+00 , -2.2358368000000004e+00 , 3.4907899999999997e-01 , -7.3521999999999998e-01 , 5.8103000000000005e-01 --4.5480134765441896e+01 , 4.9699057858922693e+00 , -1.4588008000000001e+00 , 4.7898600000000002e-01 , -8.0130599999999996e-01 , 3.5844199999999998e-01 --4.8091777688090794e+01 , 5.3684773290032499e+00 , 5.1601600000000136e-02 , 2.5795099999999999e-01 , -8.6001600000000000e-01 , 4.4026500000000002e-01 --4.7194722198193020e+01 , 5.4419758193024430e+00 , 9.6615264000000001e-01 , 2.0919800000000000e-01 , -9.6740199999999998e-01 , 1.4272199999999999e-01 --4.7247518578169249e+01 , 5.5715578103560066e+00 , 1.8245041600000000e+00 , 3.5175200000000001e-01 , -9.2543399999999998e-01 , 1.4086099999999999e-01 --5.0802063776798690e+01 , 5.9343463107971344e+00 , 2.6563148800000000e+00 , 4.3275300000000000e-01 , -7.2121000000000002e-01 , 5.4090700000000003e-01 --5.1217654652657032e+01 , 6.0984115308996998e+00 , 3.5819440000000000e+00 , -7.3361499999999996e-02 , -9.3205700000000002e-01 , 3.5480699999999998e-01 --5.0922106902031565e+01 , 6.2129713744585446e+00 , 4.5036855999999998e+00 , 1.9001000000000001e-01 , -6.3620800000000000e-01 , 7.4775400000000003e-01 --4.7750312111791700e+01 , 6.1150294042148348e+00 , 5.2897176000000004e+00 , 1.9001000000000001e-01 , -6.3620800000000000e-01 , 7.4775400000000003e-01 --1.1914815209623985e+01 , 3.5030670440898231e+00 , 3.9618872000000001e+00 , -9.4175799999999998e-01 , -1.8444199999999999e-01 , 2.8120000000000001e-01 --1.1904712975562223e+01 , 3.5390823565988296e+00 , 4.2113415999999999e+00 , -9.4175799999999998e-01 , -1.8444199999999999e-01 , 2.8120000000000001e-01 --1.1735874390124453e+01 , 3.5620700283455102e+00 , 4.4458615999999997e+00 , -9.4175799999999998e-01 , -1.8444199999999999e-01 , 2.8120000000000001e-01 --1.1810347571149363e+01 , 3.6054218412980426e+00 , 4.7030744000000002e+00 , 7.1812600000000004e-01 , 3.8367699999999999e-01 , -5.8059200000000000e-01 --1.2002306233147578e+01 , 3.6587983182265038e+00 , 4.9797455999999993e+00 , -6.4808900000000003e-01 , -3.7759899999999999e-02 , 7.6062799999999997e-01 --1.1166010205058415e+01 , 3.6216220400258807e+00 , 5.1107127999999999e+00 , -2.1081700000000000e-01 , -2.2161400000000001e-01 , 9.5207299999999995e-01 --9.0108754933904365e+00 , 3.4586200229470028e+00 , 4.9934943999999994e+00 , -2.7538200000000002e-01 , -1.3398399999999999e-01 , 9.5195200000000002e-01 --9.1053490793095015e+00 , 3.4980342798771145e+00 , 5.2163456000000004e+00 , -2.2586300000000001e-01 , 4.5139600000000002e-02 , 9.7311300000000001e-01 --8.3950459166966258e+00 , 3.4591939124135784e+00 , 5.2805135999999999e+00 , 3.8183499999999998e-01 , 4.9679400000000001e-01 , -7.7935699999999997e-01 --2.4196758658863722e+00 , 2.8920018018764484e+00 , 4.1566896000000000e+00 , -9.2292300000000005e-01 , 5.9109399999999999e-02 , -3.8041999999999998e-01 --2.3691673404208426e+00 , 2.9000225783536924e+00 , 4.2336808000000001e+00 , -7.5825500000000001e-01 , 1.9504800000000000e-01 , -6.2209800000000004e-01 --2.4675654166392267e+00 , 2.9230954190743512e+00 , 4.3482680000000000e+00 , -9.6548100000000003e-01 , -1.4978600000000000e-01 , -2.1309700000000001e-01 --2.6032983087448418e+00 , 2.9507397013823722e+00 , 4.4776024000000003e+00 , -7.9712499999999997e-01 , -7.3233000000000006e-02 , -5.9935700000000003e-01 --2.7549381873827947e+00 , 2.9823116450530867e+00 , 4.6177320000000002e+00 , 4.9139200000000000e-01 , -6.9106800000000002e-01 , -5.3005500000000005e-01 --2.4399828366153722e+00 , 2.9603514724287741e+00 , 4.6181272000000000e+00 , -9.0773599999999999e-01 , -1.4660400000000001e-01 , 3.9309300000000003e-01 --2.5290147897680875e+00 , 2.9849090708531456e+00 , 4.7420640000000001e+00 , -2.5719799999999998e-01 , 5.0144000000000000e-01 , 8.2607900000000001e-01 --2.2941338163643925e+00 , 2.9712190272369772e+00 , 4.7559064000000006e+00 , 5.4797099999999999e-01 , -4.9526900000000001e-01 , -6.7411900000000002e-01 --2.3988403792233939e+00 , 2.9981914981125559e+00 , 4.8885064000000007e+00 , -7.0432899999999998e-01 , -7.6700400000000002e-02 , 7.0571799999999996e-01 --2.2013285067061883e+00 , 2.9873574908083631e+00 , 4.9084743999999993e+00 , 6.7375399999999996e-01 , -3.0451200000000000e-01 , -6.7329600000000001e-01 --2.0633978769489163e+00 , 2.9835783454179148e+00 , 4.9454984000000000e+00 , -9.4322899999999994e-03 , -1.4379800000000001e-01 , 9.8956200000000005e-01 --2.1236322421420786e+00 , 3.0049006509109137e+00 , 5.0648383999999993e+00 , -7.7391299999999996e-01 , 5.6168300000000004e-01 , -2.9252499999999998e-01 --2.6700078189459955e+00 , 3.0924211640402728e+00 , 5.4089951999999997e+00 , -2.3734400000000000e-01 , 6.7077200000000003e-01 , -7.0266099999999998e-01 --2.1325021719328916e+00 , 3.0345233496547155e+00 , 5.2627088000000004e+00 , 6.9850900000000005e-01 , -4.7585300000000003e-01 , 5.3446099999999996e-01 --2.6566386473729082e+00 , 3.1231562641352673e+00 , 5.6224032000000008e+00 , 6.4459100000000003e-01 , -7.5507599999999997e-01 , 1.1984700000000000e-01 --2.4087835587077810e+00 , 3.1039359419381363e+00 , 5.6062104000000001e+00 , 8.3643500000000004e-01 , 5.1261400000000001e-01 , -1.9391300000000000e-01 --2.5534799046132264e+00 , 3.1415101992621519e+00 , 5.7934832000000007e+00 , 3.4324500000000002e-01 , 8.0791400000000002e-01 , -4.7901899999999997e-01 --2.5490140967138686e+00 , 3.1575368850220347e+00 , 5.9056160000000002e+00 , 4.2409000000000002e-01 , -3.0858099999999999e-01 , -8.5142600000000002e-01 --2.3906863204268491e+00 , 3.1502415371339998e+00 , 5.9295255999999998e+00 , -5.5715999999999999e-01 , -5.1151500000000005e-01 , 6.5415999999999996e-01 --2.4529527881090720e+00 , 3.1765107346729149e+00 , 6.0835184000000000e+00 , 3.7586900000000001e-01 , -3.9130599999999999e-01 , -8.4000100000000000e-01 --2.1817987789866669e+00 , 3.1508712372822343e+00 , 6.0299167999999996e+00 , 6.1022600000000005e-01 , 5.1712199999999997e-01 , -6.0017399999999999e-01 --2.1285197692339883e+00 , 3.1594111726317529e+00 , 6.1100175999999999e+00 , -9.1383199999999998e-01 , -2.6850400000000002e-01 , 3.0465799999999998e-01 --3.1170100543859078e+00 , 3.3423437413010735e+00 , 6.9072192000000001e+00 , -2.3883499999999999e-01 , 4.8415799999999998e-01 , -8.4175400000000000e-01 --3.2833340396657427e+00 , 3.3930640967067038e+00 , 7.1709008000000001e+00 , -5.6460200000000005e-01 , -3.1073499999999998e-01 , 7.6463599999999998e-01 --3.0682366844831170e+00 , 3.3775603006038422e+00 , 7.1662103999999998e+00 , -5.0517999999999996e-01 , -2.7658199999999999e-01 , 8.1749400000000005e-01 --2.9130712780477754e+00 , 3.3722025089398171e+00 , 7.1990847999999996e+00 , 5.3305300000000000e-01 , -7.4865000000000001e-02 , -8.4276300000000004e-01 --2.8069875307573584e+00 , 3.3748182364223993e+00 , 7.2663104000000001e+00 , 4.5371899999999998e-01 , -1.1101800000000000e-02 , -8.9107599999999998e-01 --2.5254903640303104e+00 , 3.3435926575101589e+00 , 7.1871872000000003e+00 , -4.6649900000000000e-01 , -3.8389400000000001e-01 , 7.9687100000000000e-01 --2.5838039012397793e+00 , 3.3768496722102168e+00 , 7.3872416000000003e+00 , 6.1774099999999998e-01 , 3.2862799999999998e-01 , -7.1442300000000003e-01 --1.6288824559705204e+00 , 3.2114764218913407e+00 , 6.6964008000000002e+00 , -8.9686299999999997e-01 , -4.1515600000000003e-01 , -1.5258500000000000e-01 --1.4429911808738871e+00 , 3.1931614367854833e+00 , 6.6557160000000000e+00 , -7.8020699999999998e-01 , -5.2611900000000000e-01 , 3.3834300000000000e-01 --1.2148120821654125e+00 , 3.1644770475880777e+00 , 6.5673056000000001e+00 , -4.4753399999999999e-01 , 8.9782299999999995e-02 , -8.8974900000000001e-01 --1.7164221054678777e+00 , 3.2895533180394319e+00 , 7.1865008000000001e+00 , -5.9337499999999999e-01 , -8.0413999999999997e-01 , -3.5566000000000000e-02 --1.5707825794080819e+00 , 3.2798344958331169e+00 , 7.1851487999999994e+00 , -7.0055800000000001e-01 , -6.7236700000000005e-01 , 2.3904300000000001e-01 --1.5670483361606058e+00 , 3.3003076759829786e+00 , 7.3297400000000001e+00 , -7.0055800000000001e-01 , -6.7236700000000005e-01 , 2.3904300000000001e-01 --1.3870299854709573e+00 , 3.2815449968411583e+00 , 7.2855608000000007e+00 , -4.7452400000000000e-01 , -6.4342600000000005e-01 , 6.0069099999999997e-01 --4.2914096374607125e-01 , 3.0793889050434080e+00 , 6.3495296000000003e+00 , -4.0521800000000002e-01 , -1.3724000000000000e-02 , 9.1411699999999996e-01 -2.9529728203711203e-01 , 2.9228669482945104e+00 , 5.6165479999999999e+00 , 1.8318999999999999e-01 , 8.9195199999999997e-01 , 4.1335699999999997e-01 -3.3388381020326463e-01 , 2.9271445757774401e+00 , 5.6617984000000003e+00 , 1.4967300000000000e-01 , 9.0056000000000003e-01 , 4.0815400000000002e-01 -6.0370801295455312e-01 , 2.8725207293801773e+00 , 5.4166808000000000e+00 , -4.8557500000000003e-02 , 5.5056400000000005e-01 , 8.3338000000000001e-01 -6.6975320157592266e-01 , 2.8684421834275513e+00 , 5.4157967999999999e+00 , -9.7180500000000003e-02 , 3.0164999999999997e-01 , 9.4845299999999999e-01 -6.9969575753510083e-01 , 2.8735355798024171e+00 , 5.4632832000000002e+00 , -2.5244899999999998e-01 , -1.3997999999999999e-01 , 9.5743100000000003e-01 -6.1138064611578913e-01 , 2.9110465986927978e+00 , 5.6780536000000001e+00 , 3.6977500000000002e-01 , -6.9873799999999997e-01 , 6.1239800000000000e-01 -6.5781530439673053e-01 , 2.9123097194994463e+00 , 5.7099919999999997e+00 , -6.3383900000000004e-01 , 6.2109199999999998e-01 , -4.6096999999999999e-01 -6.9913610380252300e-01 , 2.9153482636485850e+00 , 5.7497304000000007e+00 , 4.3969100000000000e-01 , -4.0348699999999998e-01 , -8.0241499999999999e-01 -6.0382447964702157e-01 , 2.9593678276123554e+00 , 6.0058408000000005e+00 , 3.1579099999999999e-01 , -9.4659000000000004e-01 , 6.5147099999999999e-02 -8.2700815379079207e-01 , 2.9081294220296598e+00 , 5.7569896000000007e+00 , -3.3398899999999998e-01 , 3.4274700000000002e-01 , -8.7805299999999997e-01 -8.8960545565273552e-01 , 2.9036278544532719e+00 , 5.7585704000000000e+00 , -8.0722700000000003e-01 , -3.4325899999999998e-01 , 4.8016500000000001e-01 -6.0158678267746879e-01 , 3.0158450501725387e+00 , 6.3858152000000006e+00 , 6.2968299999999999e-01 , 7.6527500000000004e-01 , -1.3361700000000001e-01 -7.4791704473547482e-01 , 2.9864226972285315e+00 , 6.2552016000000004e+00 , 6.8582100000000001e-01 , 6.8554000000000004e-01 , -2.4430199999999999e-01 -6.2572163617803533e-01 , 3.0494840456644701e+00 , 6.6317544000000002e+00 , 5.2395400000000003e-01 , -4.3378100000000003e-01 , -7.3301200000000000e-01 -7.6087697551275402e-01 , 3.0235372582155962e+00 , 6.5159919999999998e+00 , 7.9902899999999999e-01 , -4.1438799999999998e-01 , 4.3569999999999998e-01 -7.3955057838832738e-01 , 3.0553251996263144e+00 , 6.7218912000000000e+00 , -6.9010899999999997e-01 , 1.3679700000000000e-01 , 7.1065900000000004e-01 -7.9129847450653013e-01 , 3.0604880324442654e+00 , 6.7796319999999994e+00 , 4.7503499999999999e-01 , -1.3945900000000000e-01 , -8.6884600000000001e-01 -8.5271566417836109e-01 , 3.0623263891560963e+00 , 6.8177064000000005e+00 , -6.4310699999999998e-01 , 5.0042299999999995e-01 , 5.7964700000000002e-01 -9.0026927010382773e-01 , 3.0701620232239577e+00 , 6.8930960000000008e+00 , 4.1584800000000000e-01 , 9.0836200000000000e-01 , -4.4146299999999999e-02 -8.6738910520967427e-01 , 3.1142305800144365e+00 , 7.1785863999999995e+00 , -2.3579300000000000e-01 , 7.9605800000000004e-01 , -5.5739799999999995e-01 -9.9328018209602909e-01 , 3.0884114116293091e+00 , 7.0615032000000006e+00 , -2.1090200000000001e-01 , 8.7836899999999996e-01 , -4.2893799999999999e-01 -1.2386009315356690e+00 , 3.0014957950736325e+00 , 6.5823127999999995e+00 , -9.6657199999999999e-01 , 3.3481600000000000e-02 , 2.5420100000000001e-01 -1.2402016922586929e+00 , 3.0313839911655016e+00 , 6.7889608000000008e+00 , -9.2768799999999996e-01 , -3.6086600000000002e-01 , 9.5763000000000001e-02 -1.2545065557920201e+00 , 3.0580004866721024e+00 , 6.9768160000000004e+00 , 6.5084100000000000e-01 , 7.3159799999999997e-01 , -2.0290500000000000e-01 -8.8293972431437262e-01 , 3.3109582671432713e+00 , 8.5272480000000002e+00 , 5.2719099999999997e-01 , -8.4860800000000003e-01 , 4.3984599999999999e-02 -9.9011084138727190e-01 , 3.3017291126194106e+00 , 8.5148512000000007e+00 , -3.7920399999999999e-01 , -7.1119800000000000e-01 , 5.9194700000000000e-01 -1.5174005894084610e+00 , 3.0165202248301433e+00 , 6.8164688000000000e+00 , -6.2739599999999995e-01 , -7.7868700000000002e-01 , 4.5245099999999998e-03 -1.5713053338119445e+00 , 3.0232663170312284e+00 , 6.8825816000000009e+00 , 4.2440899999999998e-01 , -8.7561900000000004e-01 , -2.3058300000000001e-01 -1.5227813634837883e+00 , 3.1080423691545409e+00 , 7.4405624000000001e+00 , -5.2679299999999996e-01 , 3.6910199999999999e-01 , 7.6567099999999999e-01 -1.6549032306644311e+00 , 3.0603849567706716e+00 , 7.1742496000000004e+00 , -5.1093299999999997e-01 , 4.8198800000000003e-01 , -7.1178300000000005e-01 -1.4615217280954265e+00 , 3.2967021943267403e+00 , 8.6958944000000002e+00 , -6.3963899999999996e-01 , -1.5021100000000001e-01 , -7.5385599999999997e-01 -1.5238368964809581e+00 , 3.3296551727587493e+00 , 8.9465760000000003e+00 , 7.1697999999999995e-01 , -6.8806999999999996e-01 , -1.1180100000000000e-01 -1.6417782577293347e+00 , 3.3084216472429988e+00 , 8.8610672000000008e+00 , -5.3617899999999996e-01 , -4.3030600000000002e-01 , 7.2618799999999994e-01 --8.6401485094156882e-01 , 2.3723354458021655e+00 , 6.0231279999999998e-01 , -6.9228999999999999e-02 , 1.8781400000000001e-01 , 9.7976200000000002e-01 --9.9883146241307053e-01 , 2.3846758258256728e+00 , 5.9264080000000008e-01 , -7.6875499999999999e-02 , 1.9812299999999999e-01 , 9.7715799999999997e-01 --1.1602913929021117e+00 , 2.3964817826056817e+00 , 5.6934480000000010e-01 , -8.9498499999999995e-02 , 1.7284099999999999e-01 , 9.8087500000000005e-01 --1.3243640458138195e+00 , 2.4103929557366861e+00 , 5.5065600000000003e-01 , -7.7472799999999994e-02 , 1.6300799999999999e-01 , 9.8357899999999998e-01 --1.5065795763312462e+00 , 2.4238713895393493e+00 , 5.2596639999999995e-01 , -8.7503600000000001e-02 , 1.6242699999999999e-01 , 9.8283299999999996e-01 --1.7177939245133724e+00 , 2.4395362302139070e+00 , 4.9013839999999997e-01 , 9.8422399999999993e-02 , -1.4995000000000000e-01 , -9.8378299999999996e-01 --1.9230798436968479e+00 , 2.4562648731294554e+00 , 4.6611439999999993e-01 , -9.0990100000000004e-02 , 1.6466600000000001e-01 , 9.8214400000000002e-01 --2.1654074435329074e+00 , 2.4738678995946550e+00 , 4.2803999999999998e-01 , -8.2751699999999997e-02 , 1.7369299999999999e-01 , 9.8131699999999999e-01 --2.4008306019292505e+00 , 2.4936876129762955e+00 , 4.0239359999999991e-01 , -9.1154600000000002e-02 , 1.7325800000000000e-01 , 9.8064899999999999e-01 --2.6943801605492670e+00 , 2.5148509768770033e+00 , 3.5518799999999984e-01 , -8.0545599999999995e-02 , 1.7154300000000000e-01 , 9.8187899999999995e-01 --2.9723318613012522e+00 , 2.5380089154613867e+00 , 3.2650479999999993e-01 , -7.6150399999999993e-02 , 1.6478999999999999e-01 , 9.8338499999999995e-01 --3.2889556702146505e+00 , 2.5631220662675340e+00 , 2.8870079999999998e-01 , -9.0346700000000002e-02 , 1.5679399999999999e-01 , 9.8348999999999998e-01 --3.6752981748697735e+00 , 2.5923755820905408e+00 , 2.3027360000000008e-01 , -9.3020800000000001e-02 , 1.4783099999999999e-01 , 9.8462799999999995e-01 --4.0651945095410520e+00 , 2.6242937770567574e+00 , 1.8424320000000005e-01 , -7.7936699999999998e-02 , 1.5502199999999999e-01 , 9.8483200000000004e-01 --4.4954977873060802e+00 , 2.6593966328681242e+00 , 1.3492640000000011e-01 , -8.1061499999999995e-02 , 1.5304999999999999e-01 , 9.8488799999999999e-01 --5.0074806284877820e+00 , 2.6988575352581066e+00 , 6.8667999999999951e-02 , -8.8051199999999996e-02 , 1.5603100000000000e-01 , 9.8382000000000003e-01 --5.5815058360733660e+00 , 2.7451078586283000e+00 , -3.4247999999998946e-03 , -9.3157799999999999e-02 , 1.5222900000000000e-01 , 9.8394499999999996e-01 --6.2862474680566045e+00 , 2.7990191466826810e+00 , -1.0233919999999985e-01 , 9.4533900000000004e-02 , -1.3656900000000000e-01 , -9.8611000000000004e-01 --7.0652320032685090e+00 , 2.8603346379446255e+00 , -2.0138880000000015e-01 , -1.1215700000000001e-01 , 1.1496000000000001e-01 , 9.8701799999999995e-01 --8.0185975954569280e+00 , 2.9350082340569350e+00 , -3.2929840000000032e-01 , -8.3364400000000005e-02 , 1.4684600000000000e-01 , 9.8563999999999996e-01 --9.0272819569298406e+00 , 3.0176431843284988e+00 , -4.4015199999999988e-01 , -9.8305699999999996e-02 , 1.1164300000000001e-01 , 9.8887400000000003e-01 --1.0312249699121555e+01 , 3.1203361246256982e+00 , -5.9456080000000000e-01 , -9.3508900000000006e-02 , 1.1851800000000000e-01 , 9.8853899999999995e-01 --1.1875032228516270e+01 , 3.2460874189698088e+00 , -7.7824560000000043e-01 , -8.8094300000000000e-02 , 1.2136700000000000e-01 , 9.8869099999999999e-01 --1.3810985127378757e+01 , 3.4025420278699285e+00 , -9.9975520000000007e-01 , -9.1979800000000000e-02 , 1.1278000000000001e-01 , 9.8935399999999996e-01 --1.6544575630555183e+01 , 3.6206164004671200e+00 , -1.3387120000000001e+00 , -8.2804799999999998e-02 , 1.5548300000000001e-01 , 9.8436199999999996e-01 --4.5098375959495250e+01 , 6.0568725191615931e+00 , -3.7244616000000006e+00 , -3.2696199999999997e-01 , 7.4923700000000004e-01 , -5.7596899999999995e-01 --4.6140302924690332e+01 , 6.3818637741321922e+00 , -2.1653039999999999e+00 , -3.0679099999999998e-01 , 7.9566999999999999e-01 , -5.2229199999999998e-01 --4.6439998467926500e+01 , 6.5285677738744399e+00 , -1.3426952000000001e+00 , 3.7074299999999999e-01 , -7.0248800000000000e-01 , 6.0750400000000004e-01 --4.8394079699412451e+01 , 6.9466781336054044e+00 , 2.5208239999999993e-01 , 3.5022500000000001e-01 , -8.2699400000000001e-01 , 4.3980000000000002e-01 --4.6064103409625496e+01 , 6.8597603959071138e+00 , 1.2246727200000000e+00 , -3.4654000000000001e-01 , 9.0897799999999995e-01 , 2.3166600000000001e-01 --4.4421512629624331e+01 , 6.8255713012837305e+00 , 2.1011921039999999e+00 , 5.6979100000000005e-01 , -8.2065600000000005e-01 , 4.3157000000000001e-02 --4.9785613255161707e+01 , 7.5913047069265920e+00 , 3.8029856000000004e+00 , 1.9001000000000001e-01 , -6.3620800000000000e-01 , 7.4775400000000003e-01 --4.9824632982158391e+01 , 7.7251649771530637e+00 , 4.7121016000000004e+00 , -5.4739599999999999e-01 , 4.2069400000000001e-01 , 7.2344600000000003e-01 --4.9393680422571009e+01 , 7.8104010810121025e+00 , 5.6011456000000006e+00 , -2.7930899999999997e-01 , 3.1035099999999999e-01 , 9.0866300000000000e-01 --4.1806051016292720e+01 , 7.1300445025819998e+00 , 6.0043432000000001e+00 , 7.3279899999999998e-01 , -6.6494799999999998e-01 , -1.4439500000000000e-01 --1.2322257845596781e+01 , 4.0195479195920436e+00 , 4.3145199999999999e+00 , -8.9664699999999997e-01 , -2.2163400000000000e-01 , 3.8327800000000001e-01 --1.2130075154853595e+01 , 4.0352129845044296e+00 , 4.5544792000000003e+00 , -9.4791499999999995e-01 , -1.5395300000000001e-01 , 2.7884700000000001e-01 --1.1893753178005129e+01 , 4.0446192117966167e+00 , 4.7834040000000000e+00 , -7.8164800000000001e-01 , 7.8834600000000001e-03 , 6.2367099999999998e-01 --1.0138271715481716e+01 , 3.8764970899502886e+00 , 4.7979120000000002e+00 , -8.2884899999999997e-02 , 8.8494699999999999e-03 , 9.9651999999999996e-01 --1.0399763986120641e+01 , 3.9389115288946517e+00 , 5.0623839999999998e+00 , 1.3401300000000000e-02 , 4.3811799999999998e-02 , 9.9895000000000000e-01 --2.2898829941409931e+00 , 2.9836472727070769e+00 , 3.8961800000000002e+00 , -9.2153300000000005e-01 , -2.4969800000000000e-01 , -2.9736699999999999e-01 --2.2232492977496063e+00 , 2.9869781401647435e+00 , 3.9690943999999999e+00 , -9.0642599999999995e-01 , -2.6019399999999998e-01 , -3.3270100000000002e-01 --4.4590551271173400e+00 , 3.2832179657603939e+00 , 4.5196392000000003e+00 , -5.5631100000000003e-02 , 5.8287000000000000e-01 , 8.1065900000000002e-01 --3.0426721004791855e+00 , 3.1183245436172990e+00 , 4.3249200000000005e+00 , -4.7001300000000001e-01 , -5.3720299999999999e-01 , -7.0035800000000004e-01 --2.3666771977631011e+00 , 3.0434221372744368e+00 , 4.2607936000000004e+00 , 7.3230700000000004e-01 , -1.2987499999999999e-01 , -6.6847500000000004e-01 --2.5439853752089219e+00 , 3.0795959073467083e+00 , 4.3972624000000007e+00 , 6.3471900000000003e-01 , -6.4404700000000004e-01 , 4.2700800000000000e-01 --2.1615854480980055e+00 , 3.0401626042848680e+00 , 4.3832432000000008e+00 , -7.7232900000000004e-01 , 3.4591699999999997e-01 , -5.3277500000000000e-01 --2.4825973135723167e+00 , 3.0984916900852051e+00 , 4.5673648000000000e+00 , 7.8761999999999999e-01 , -6.0506499999999996e-01 , 1.1640800000000000e-01 --2.5617941306340590e+00 , 3.1230055566902317e+00 , 4.6879735999999994e+00 , -8.8085800000000003e-01 , -4.0010099999999998e-01 , 2.5300000000000000e-01 --2.8833915428286794e+00 , 3.1837521005270881e+00 , 4.8945072000000005e+00 , 3.2547700000000002e-01 , 8.1378600000000001e-01 , 4.8147299999999998e-01 --2.9947600384481392e+00 , 3.2156349299287976e+00 , 5.0395248000000006e+00 , -1.8517200000000000e-01 , -9.8127399999999998e-01 , -5.3025999999999997e-02 --3.2755535505270430e+00 , 3.2742747633473375e+00 , 5.2548360000000001e+00 , 3.3362900000000001e-01 , -7.2726700000000000e-01 , 5.9981099999999998e-01 --3.1110374066961626e+00 , 3.2645622723642234e+00 , 5.3049847999999997e+00 , 4.7257399999999999e-01 , -5.6230500000000005e-01 , 6.7859199999999997e-01 --1.9504935233158998e+00 , 3.0989127879300749e+00 , 4.9307096000000001e+00 , -7.7391299999999996e-01 , 5.6168300000000004e-01 , -2.9252499999999998e-01 --2.0945398627012493e+00 , 3.1343797765375214e+00 , 5.0865328000000005e+00 , -7.7391299999999996e-01 , 5.6168300000000004e-01 , -2.9252499999999998e-01 --2.1508667197795219e+00 , 3.1582026285012095e+00 , 5.2085976000000000e+00 , -9.0109700000000004e-01 , -2.7079999999999999e-01 , 3.3866099999999999e-01 --2.4274473462479529e+00 , 3.2179935787830898e+00 , 5.4410480000000003e+00 , 2.8417200000000000e-02 , 5.8682900000000005e-01 , 8.0921200000000004e-01 --2.8605659786812012e+00 , 3.3066126717134101e+00 , 5.7674311999999999e+00 , -5.7620899999999997e-01 , -2.8813499999999997e-01 , 7.6482799999999995e-01 --2.7751128209330620e+00 , 3.3091848660123939e+00 , 5.8405848000000002e+00 , 5.0807700000000000e-01 , 3.7719100000000000e-01 , -7.7432900000000005e-01 --2.5450408094592234e+00 , 3.2859246631228807e+00 , 5.8322023999999999e+00 , 4.0524500000000002e-01 , -6.7042999999999997e-01 , -6.2153099999999994e-01 --2.4408911600421863e+00 , 3.2832670285226735e+00 , 5.8886535999999996e+00 , 4.8685899999999999e-01 , -8.0640199999999995e-01 , -3.3568300000000001e-01 --2.4252860817512509e+00 , 3.2965855629530756e+00 , 5.9949624000000004e+00 , 3.5972100000000001e-01 , -8.5363100000000003e-01 , -3.7671700000000002e-01 --2.2935742207864198e+00 , 3.2896675709741237e+00 , 6.0309360000000005e+00 , -6.6144199999999997e-01 , -1.7844299999999999e-01 , 7.2845899999999997e-01 --2.5330436298142009e+00 , 3.3516437408955113e+00 , 6.3032392000000002e+00 , -1.6106799999999999e-01 , -8.3835400000000004e-01 , 5.2078800000000003e-01 --2.2185532811121593e+00 , 3.3093106853461149e+00 , 6.2182088000000002e+00 , -1.9259499999999999e-01 , -7.8723299999999996e-01 , 5.8580900000000002e-01 --2.8101805344690032e+00 , 3.4433368958764303e+00 , 6.7519159999999996e+00 , -8.0094299999999996e-01 , 5.8362099999999995e-01 , -1.3370399999999999e-01 --3.0012312513510402e+00 , 3.5012905933224112e+00 , 7.0304279999999997e+00 , -8.2689999999999997e-01 , -6.0370600000000003e-02 , 5.5909900000000001e-01 --2.8885672564830704e+00 , 3.4998177142675391e+00 , 7.0945856000000003e+00 , -4.5794600000000002e-01 , 2.9229700000000000e-03 , 8.8897499999999996e-01 --2.9299776800290633e+00 , 3.5296248921946995e+00 , 7.2758576000000001e+00 , 5.7246799999999998e-01 , 3.6728300000000003e-01 , -7.3306400000000005e-01 --2.7016969472145886e+00 , 3.5034229788156050e+00 , 7.2472471999999994e+00 , -4.7921300000000000e-01 , -3.8964199999999999e-01 , 7.8647000000000000e-01 --2.6509170917430076e+00 , 3.5137696227413118e+00 , 7.3568216000000000e+00 , -4.1705199999999998e-01 , -5.4980899999999999e-01 , 7.2372499999999995e-01 --2.5654767563611580e+00 , 3.5181325653718378e+00 , 7.4388984000000002e+00 , 6.5460900000000000e-01 , 4.4254900000000003e-01 , -6.1289199999999999e-01 --1.6108314140483357e+00 , 3.3240734544948847e+00 , 6.7373768000000007e+00 , -6.9755500000000004e-01 , -7.0802399999999999e-01 , -1.1008400000000000e-01 --1.6720763198805111e+00 , 3.3575002810844370e+00 , 6.9271144000000007e+00 , 7.7771900000000005e-01 , 6.2715399999999999e-01 , 4.2784799999999998e-02 -1.2205327085355933e-01 , 2.9546436958523241e+00 , 5.3315048000000003e+00 , -7.0644200000000001e-01 , -1.6053300000000001e-01 , 6.8932499999999997e-01 -1.5502817216250619e-01 , 2.9576033943479825e+00 , 5.3795736000000005e+00 , -7.0644200000000001e-01 , -1.6053300000000001e-01 , 6.8932499999999997e-01 -2.1060557060704133e-01 , 2.9560613813073759e+00 , 5.4048248000000001e+00 , 6.0850599999999999e-01 , 2.3017099999999999e-01 , -7.5943600000000000e-01 --2.2542545061717663e+00 , 3.5872477843836545e+00 , 8.1382048000000005e+00 , -4.6747499999999997e-01 , 2.1873600000000001e-01 , 8.5651699999999997e-01 -3.0169254712517124e-01 , 2.9576957485077457e+00 , 5.4745568000000002e+00 , 3.4505100000000000e-01 , -6.8743399999999999e-01 , -6.3904099999999997e-01 -3.1758113147118161e-01 , 2.9655325369392220e+00 , 5.5432280000000009e+00 , 5.9602500000000003e-02 , 8.6861500000000003e-01 , 4.9188999999999999e-01 -4.9294771976784602e-01 , 2.9316605143543786e+00 , 5.4230559999999999e+00 , -1.6180900000000001e-01 , -9.5555800000000002e-01 , -2.4642700000000001e-01 -4.5143817026944921e-01 , 2.9548896766320021e+00 , 5.5610952000000005e+00 , -2.1607399999999999e-01 , -8.9044699999999999e-01 , -4.0051999999999999e-01 -5.9036770063349220e-01 , 2.9293789983370897e+00 , 5.4746711999999995e+00 , -3.5662600000000000e-01 , -4.0736299999999998e-01 , 8.4075800000000001e-01 -7.1216023785980709e-01 , 2.9070585166187968e+00 , 5.4004151999999994e+00 , -6.3249999999999995e-01 , 6.6373099999999996e-01 , 3.9925600000000000e-01 -7.2448949533217144e-01 , 2.9157549108474501e+00 , 5.4725599999999996e+00 , 8.1911900000000004e-01 , 1.3746500000000000e-01 , -5.5690899999999999e-01 -7.4308066240742177e-01 , 2.9235559061006295e+00 , 5.5363120000000006e+00 , -8.7470599999999998e-01 , -1.9312900000000000e-01 , 4.4451299999999999e-01 -7.1273654176849166e-01 , 2.9457800634707092e+00 , 5.6770551999999999e+00 , -4.3806600000000001e-01 , 6.0045199999999999e-01 , 6.6899600000000004e-01 -7.1456272409019816e-01 , 2.9603803026210755e+00 , 5.7762399999999996e+00 , -4.9225700000000000e-01 , 4.9675999999999998e-01 , 7.1478100000000000e-01 -8.0080198715263773e-01 , 2.9473537352349624e+00 , 5.7457992000000004e+00 , 2.7455499999999999e-01 , 3.4337899999999999e-01 , 8.9817000000000002e-01 -8.5281142119064013e-01 , 2.9448974525710412e+00 , 5.7658088000000003e+00 , -8.4726199999999996e-01 , -3.2340799999999997e-01 , 4.2137300000000000e-01 -8.5989032054561743e-01 , 2.9592254181553281e+00 , 5.8648064000000000e+00 , -4.7054200000000002e-01 , -6.5334599999999998e-01 , 5.9306800000000004e-01 -9.2459441604142567e-01 , 2.9524237571265117e+00 , 5.8659295999999994e+00 , 5.4598700000000000e-01 , 4.8218800000000001e-01 , -6.8512300000000004e-01 -9.7371597026712764e-01 , 2.9514513194208347e+00 , 5.8926575999999997e+00 , -2.9505000000000000e-02 , -3.6791600000000002e-01 , 9.2939099999999997e-01 -6.8305001737362514e-01 , 3.0812351448563584e+00 , 6.5960304000000010e+00 , -7.8761899999999996e-01 , 5.0803699999999996e-01 , 3.4864699999999998e-01 -7.2301180214431771e-01 , 3.0876485673522209e+00 , 6.6732816000000001e+00 , -8.4517299999999995e-01 , 3.0032599999999998e-01 , 4.4213900000000000e-01 -7.7040595184263161e-01 , 3.0928838892376658e+00 , 6.7409752000000003e+00 , -5.5103700000000000e-01 , 2.9606300000000002e-01 , 7.8019600000000000e-01 -8.3065540149670203e-01 , 3.0927876894910495e+00 , 6.7797360000000007e+00 , 5.6917499999999999e-01 , -4.2144399999999999e-01 , -7.0599199999999995e-01 -8.7705253461117527e-01 , 3.0986698280283722e+00 , 6.8557184000000007e+00 , -5.7619100000000001e-01 , 5.1596100000000000e-01 , 6.3386699999999996e-01 -8.9036209695632307e-01 , 3.1209672946886684e+00 , 7.0166687999999997e+00 , -6.1081300000000005e-01 , 1.6592899999999999e-01 , 7.7419300000000002e-01 -9.6032100047195779e-01 , 3.1181808396486366e+00 , 7.0440936000000001e+00 , -5.8204300000000000e-02 , -7.1320099999999997e-01 , -6.9853900000000002e-01 -1.0336462133205542e+00 , 3.1130737080045914e+00 , 7.0607440000000006e+00 , 2.0845200000000000e-01 , 9.6717699999999995e-01 , -1.4531600000000000e-01 -1.1439305572013916e+00 , 3.0898423442189058e+00 , 6.9689639999999997e+00 , -5.4907600000000001e-01 , -8.3343500000000004e-01 , -6.2456800000000000e-02 -1.1873278096419229e+00 , 3.0998809511086289e+00 , 7.0702496000000004e+00 , -3.9971800000000002e-01 , -8.0553100000000000e-01 , 4.3743100000000001e-01 -6.1155342568918125e-01 , 3.4704256637454858e+00 , 9.2661055999999995e+00 , -7.6873700000000000e-01 , -2.3880799999999999e-01 , -5.9330799999999995e-01 -8.6984956382498146e-01 , 3.3731836179045454e+00 , 8.7648152000000010e+00 , 1.2790500000000000e-02 , 9.9860599999999999e-01 , 5.1206300000000003e-02 -1.4667579565485984e+00 , 3.0443286029916172e+00 , 6.8752080000000007e+00 , 8.2166500000000003e-02 , -4.4214900000000001e-01 , 8.9317000000000002e-01 -1.5603607742649928e+00 , 3.0216950479400695e+00 , 6.7828352000000001e+00 , -1.3401800000000000e-01 , -3.8776400000000000e-01 , 9.1196400000000000e-01 -1.4832909339352747e+00 , 3.1234781192666503e+00 , 7.4402088000000006e+00 , -2.8128399999999998e-01 , 1.2453000000000000e-01 , 9.5150999999999997e-01 -1.5890204066820979e+00 , 3.0960975340994850e+00 , 7.3163656000000001e+00 , -8.1129700000000005e-01 , 4.2223200000000000e-01 , -4.0437200000000001e-01 -1.6976775759801912e+00 , 3.0611077143619356e+00 , 7.1500696000000001e+00 , 2.7694400000000002e-01 , -6.8608400000000003e-01 , 6.7274800000000001e-01 -1.5132225279097515e+00 , 3.3003698668930257e+00 , 8.6935336000000003e+00 , -6.3963899999999996e-01 , -1.5021100000000001e-01 , -7.5385599999999997e-01 -1.5881643540644519e+00 , 3.3194557564373017e+00 , 8.8727775999999992e+00 , 4.5658999999999998e-02 , -5.4213900000000004e-01 , 8.3904699999999999e-01 -1.6695949813863844e+00 , 3.3350287476823337e+00 , 9.0412160000000004e+00 , -6.1258599999999996e-01 , -7.6304600000000000e-01 , 2.0615500000000000e-01 --9.2304077566837117e-01 , 2.4838077901357600e+00 , 5.7906879999999994e-01 , -6.9228999999999999e-02 , 1.8781400000000001e-01 , 9.7976200000000002e-01 --1.0753710336920697e+00 , 2.5000971422466725e+00 , 5.5891360000000012e-01 , -7.7946799999999997e-02 , 1.8922400000000000e-01 , 9.7883500000000001e-01 --1.2466857697301594e+00 , 2.5178545236628556e+00 , 5.3142639999999997e-01 , -6.8457400000000002e-02 , 1.7879800000000001e-01 , 9.8150099999999996e-01 --1.4109456433801308e+00 , 2.5364583626649364e+00 , 5.1495280000000010e-01 , -5.3061999999999998e-02 , 1.6572000000000001e-01 , 9.8474399999999995e-01 --1.5943313171411448e+00 , 2.5567562601407547e+00 , 4.9223919999999999e-01 , -7.7029899999999998e-02 , 1.5437400000000001e-01 , 9.8500500000000002e-01 --1.7969330115350153e+00 , 2.5789315464408911e+00 , 4.6420079999999975e-01 , -9.8131599999999999e-02 , 1.4584600000000000e-01 , 9.8442799999999997e-01 --2.0101486244959013e+00 , 2.6017991733600416e+00 , 4.3733759999999999e-01 , -9.5866900000000005e-02 , 1.5350500000000000e-01 , 9.8348700000000000e-01 --2.2438274900781501e+00 , 2.6269386656260623e+00 , 4.0684480000000001e-01 , -8.1596100000000005e-02 , 1.6564799999999999e-01 , 9.8280400000000001e-01 --2.4980924730418428e+00 , 2.6545373477988234e+00 , 3.7362720000000005e-01 , -9.2788999999999996e-02 , 1.5385199999999999e-01 , 9.8372700000000002e-01 --2.7917763984995156e+00 , 2.6857862565530799e+00 , 3.2903199999999999e-01 , -8.8043999999999997e-02 , 1.5105900000000000e-01 , 9.8459600000000003e-01 --3.0975210689877040e+00 , 2.7195777475280121e+00 , 2.8921039999999998e-01 , -9.3743300000000002e-02 , 1.5477299999999999e-01 , 9.8349299999999995e-01 --3.4519612861393636e+00 , 2.7571870284534095e+00 , 2.3688799999999999e-01 , 9.0072700000000006e-02 , -1.3158100000000000e-01 , -9.8720500000000000e-01 --3.8198275166532492e+00 , 2.7968499075277338e+00 , 1.9184559999999995e-01 , -9.6560999999999994e-02 , 1.3442799999999999e-01 , 9.8620699999999994e-01 --4.2377897090233478e+00 , 2.8431558748673806e+00 , 1.3750560000000012e-01 , -7.9809699999999997e-02 , 1.5034800000000001e-01 , 9.8540700000000003e-01 --4.6983972481388436e+00 , 2.8930098435154976e+00 , 8.1137599999999921e-02 , -9.0673500000000004e-02 , 1.4591199999999999e-01 , 9.8513399999999995e-01 --5.2386561706484871e+00 , 2.9516123126818847e+00 , 8.9824000000000570e-03 , -9.1341400000000003e-02 , 1.4414900000000000e-01 , 9.8533099999999996e-01 --5.8611769107114622e+00 , 3.0188585821249374e+00 , -7.4654400000000010e-02 , -9.4925499999999996e-02 , 1.2723300000000001e-01 , 9.8731999999999998e-01 --6.5765045240781657e+00 , 3.0964099888065357e+00 , -1.6911760000000031e-01 , -9.5411099999999999e-02 , 9.4212299999999999e-02 , 9.9097000000000002e-01 --7.4243490001928407e+00 , 3.1884626180378359e+00 , -2.8316400000000019e-01 , -1.2237600000000000e-01 , 7.8037599999999999e-02 , 9.8941100000000004e-01 --8.3965385398755146e+00 , 3.2945931168192502e+00 , -4.0653920000000010e-01 , -8.5986499999999993e-02 , 9.3234899999999996e-02 , 9.9192400000000003e-01 --9.5341839455090334e+00 , 3.4196262026843236e+00 , -5.4520239999999998e-01 , -1.1304599999999999e-01 , 5.5279799999999997e-02 , 9.9205100000000002e-01 --1.0918187268703344e+01 , 3.5716748382893471e+00 , -7.1302720000000042e-01 , -1.1218599999999999e-01 , 8.8978100000000004e-02 , 9.8969600000000002e-01 --1.2670783950861573e+01 , 3.7637801444581269e+00 , -9.2926400000000031e-01 , -9.6344899999999997e-02 , 8.4943400000000002e-02 , 9.9171699999999996e-01 --1.4896673836935335e+01 , 4.0078051436954452e+00 , -1.1997263999999999e+00 , 1.0213200000000000e-01 , -1.4327400000000001e-01 , -9.8439900000000002e-01 --2.9859734087277488e+01 , 5.6366990061254167e+00 , -3.1327536000000000e+00 , 2.5217300000000002e-02 , 8.5168800000000003e-02 , 9.9604700000000002e-01 --4.1677704908748510e+01 , 7.0386980912991683e+00 , -3.8292104000000000e+00 , -2.5338800000000000e-01 , 9.6627399999999997e-01 , -4.5918000000000000e-02 --4.2116749970863786e+01 , 7.1944009943170508e+00 , -3.1081576000000002e+00 , 1.9016000000000000e-01 , -8.0035500000000004e-01 , 5.6856899999999999e-01 --4.2850958169505425e+01 , 7.3854567376156961e+00 , -2.4108375999999998e+00 , -2.4901000000000001e-01 , 7.6597199999999999e-01 , -5.9269000000000005e-01 --5.4111830575180946e+01 , 8.7623611699332198e+00 , -2.7813480000000004e+00 , -5.2651300000000001e-01 , -8.4201999999999999e-01 , 1.1741900000000000e-01 --4.4347021678829478e+01 , 7.7793667764888061e+00 , -9.4926320000000031e-01 , -3.3741100000000002e-01 , 9.1021600000000003e-01 , -2.4012800000000001e-01 --4.4478730270282746e+01 , 7.9087636410930005e+00 , -1.4006000000000007e-01 , -6.1038999999999999e-01 , 7.8743399999999997e-01 , -8.5862300000000003e-02 --4.5038933740544451e+01 , 8.0899929121138197e+00 , 6.5047520000000003e-01 , -6.1038999999999999e-01 , 7.8743399999999997e-01 , -8.5862200000000000e-02 --4.3677156056351954e+01 , 8.0397345522192047e+00 , 1.5242634399999999e+00 , -6.1038999999999999e-01 , 7.8743399999999997e-01 , -8.5862300000000003e-02 --4.4643701790003796e+01 , 8.2718749098811308e+00 , 2.3121830399999999e+00 , -5.1107199999999997e-01 , 2.0178099999999999e-01 , -8.3551799999999998e-01 --4.7513892936104391e+01 , 8.7513168747171157e+00 , 3.1359088000000002e+00 , -3.5241499999999998e-01 , 5.1288800000000001e-01 , -7.8278300000000001e-01 --4.9510932029133549e+01 , 9.1316436690838376e+00 , 4.0441408000000001e+00 , 5.7899900000000004e-01 , -7.3813499999999999e-01 , 3.4629100000000002e-01 --1.2370104490680568e+01 , 4.4319965717344232e+00 , 4.1327280000000002e+00 , -6.9088300000000002e-01 , 5.9784400000000004e-01 , 4.0652700000000003e-01 --1.2191163339330839e+01 , 4.4438844567554714e+00 , 4.3774607999999997e+00 , -3.9082600000000001e-01 , 7.7439000000000002e-01 , 4.9757000000000001e-01 --1.2008343440353810e+01 , 4.4544362980483001e+00 , 4.6164008000000001e+00 , 3.9082699999999998e-01 , -7.7438899999999999e-01 , -4.9757000000000001e-01 --1.1555503296525353e+01 , 4.4243687982123507e+00 , 4.8167880000000007e+00 , -2.2421500000000000e-01 , 3.7582199999999999e-01 , 8.9915800000000001e-01 --9.4196519647099013e+00 , 4.1465780323746175e+00 , 4.7633320000000001e+00 , -7.0285100000000003e-02 , 2.3948600000000000e-01 , 9.6835199999999999e-01 --5.9405791500106506e+00 , 3.6571225780594370e+00 , 4.4203088000000008e+00 , 6.6701399999999994e-02 , 7.0085299999999995e-01 , 7.1018000000000003e-01 --2.3482228288798916e+00 , 3.1327237409563553e+00 , 3.9332352000000004e+00 , -9.3975600000000004e-01 , -2.5461000000000000e-01 , -2.2810500000000000e-01 --2.6135542419598901e+00 , 3.1859662317261419e+00 , 4.0723663999999999e+00 , -9.6111899999999995e-01 , -1.7876100000000000e-01 , -2.1046500000000001e-01 --2.9262247836519943e+00 , 3.2484798957035954e+00 , 4.2315904000000000e+00 , 4.1893399999999997e-01 , -5.7521100000000003e-01 , 7.0258600000000004e-01 --3.4640968320494334e+00 , 3.3476034882104395e+00 , 4.4560119999999994e+00 , -5.2984799999999999e-01 , -8.4489700000000001e-01 , 7.3549000000000003e-02 --2.9592576482449271e+00 , 3.2810888873982957e+00 , 4.4391432000000002e+00 , -8.8940900000000001e-01 , 3.4764000000000000e-01 , 2.9681400000000002e-01 --2.3182802291483924e+00 , 3.1902699092739706e+00 , 4.3675496000000003e+00 , 9.0297000000000005e-01 , 2.9398099999999999e-01 , 3.1340200000000001e-01 --2.3326950221677327e+00 , 3.2046871162645623e+00 , 4.4623976000000001e+00 , 7.2856600000000005e-01 , 4.9103999999999998e-01 , 4.7756900000000002e-01 --3.1404816042968813e+00 , 3.3547446568727830e+00 , 4.8029039999999998e+00 , 2.4942600000000001e-01 , -5.6567299999999998e-01 , -7.8600300000000001e-01 --2.6981311881395627e+00 , 3.2933478699548480e+00 , 4.7665039999999994e+00 , -9.2512000000000005e-01 , -3.7964399999999998e-01 , -4.8786400000000001e-03 --2.7433933002673374e+00 , 3.3156677887927986e+00 , 4.8834415999999994e+00 , -7.5623899999999999e-01 , -1.3152900000000001e-01 , -6.4093900000000004e-01 --2.9114393975101542e+00 , 3.3603831125359847e+00 , 5.0484271999999999e+00 , -9.0220400000000001e-01 , 3.9272000000000001e-01 , -1.7832300000000001e-01 --2.8174926497875861e+00 , 3.3580130056962010e+00 , 5.1199583999999998e+00 , -8.2499299999999998e-01 , 2.4608800000000000e-01 , -5.0875099999999995e-01 --2.9880698549858096e+00 , 3.4042738841094238e+00 , 5.2973616000000003e+00 , -5.3174200000000005e-01 , 5.8457199999999998e-01 , -6.1280100000000004e-01 --2.0901214668378296e+00 , 3.2524054314926798e+00 , 5.0250480000000000e+00 , 8.6625500000000000e-01 , -7.6627000000000001e-02 , 4.9369099999999999e-01 --2.3429433195146308e+00 , 3.3140306854130479e+00 , 5.2348056000000005e+00 , -4.0277900000000000e-01 , -8.2051300000000005e-01 , 4.0561999999999998e-01 --2.2849630919278328e+00 , 3.3171248558322590e+00 , 5.3099456000000007e+00 , -2.4320000000000000e-01 , -4.3699300000000002e-01 , 8.6596300000000004e-01 --2.1980125364691769e+00 , 3.3148752215884043e+00 , 5.3700472000000001e+00 , 1.6000100000000000e-01 , -4.0223199999999998e-01 , 9.0144800000000003e-01 --2.0373754882339323e+00 , 3.2972348433558443e+00 , 5.3905976000000004e+00 , -6.4855300000000005e-01 , -2.2505000000000000e-01 , 7.2713899999999998e-01 --2.8062708333000810e+00 , 3.4669229850641212e+00 , 5.9053456000000004e+00 , -5.9988900000000001e-01 , -4.2751000000000000e-01 , 6.7628999999999995e-01 --2.3266123452014860e+00 , 3.3845969768280244e+00 , 5.7571872000000006e+00 , 4.7413000000000000e-01 , -8.6210100000000001e-01 , -1.7883800000000000e-01 --2.2510993994084441e+00 , 3.3844856643974204e+00 , 5.8254424000000000e+00 , 4.6314800000000000e-01 , -8.8395699999999999e-01 , -6.4137200000000005e-02 --2.2621586144745569e+00 , 3.4026604226704062e+00 , 5.9449176000000001e+00 , -7.9944700000000002e-01 , 5.4145100000000002e-01 , 2.6022099999999998e-01 --2.8230526738194328e+00 , 3.5397118798059912e+00 , 6.4158920000000004e+00 , -1.2290800000000000e-01 , -9.9199199999999998e-01 , 2.9088599999999999e-02 --2.2753541517210465e+00 , 3.4383886601569733e+00 , 6.1879552000000002e+00 , -6.8728900000000004e-01 , 6.9831900000000002e-01 , -1.9996300000000000e-01 --2.2614183436603268e+00 , 3.4528225955460066e+00 , 6.2994952000000000e+00 , 7.9069299999999998e-01 , -4.3892599999999998e-01 , 4.2678899999999997e-01 --3.2868153686851596e+00 , 3.7015039247021466e+00 , 7.1515775999999995e+00 , 1.7316399999999999e-02 , -3.4735199999999999e-01 , 9.3757500000000005e-01 --3.1225312701463812e+00 , 3.6853456468452350e+00 , 7.1855024000000007e+00 , 5.5142400000000003e-01 , 2.0156600000000000e-01 , -8.0950800000000001e-01 --2.9748808667207669e+00 , 3.6725644813172726e+00 , 7.2273623999999996e+00 , -8.9383999999999997e-01 , -1.0946300000000000e-01 , 4.3481999999999998e-01 --2.9639969828412305e+00 , 3.6919508111405483e+00 , 7.3733367999999997e+00 , -6.5781599999999996e-01 , -5.3225900000000004e-01 , 5.3289600000000004e-01 --4.3948998467590732e+00 , 4.0596053090486217e+00 , 8.7083848000000010e+00 , -2.3843099999999999e-02 , 1.7964600000000000e-01 , 9.8344200000000004e-01 --2.7611191025283759e+00 , 3.6866826105898287e+00 , 7.5222336000000007e+00 , 6.5451199999999998e-01 , 5.4901699999999998e-01 , -5.1980199999999999e-01 --3.9833851041471089e+00 , 4.0149529941320452e+00 , 8.7642951999999994e+00 , -9.8376099999999994e-02 , 5.4847400000000001e-03 , 9.9513399999999996e-01 --4.1223453510174215e+00 , 4.0796670270162805e+00 , 9.0980103999999997e+00 , -7.3022900000000002e-01 , 3.7322200000000000e-01 , -5.7225099999999995e-01 -9.3569865948872177e-02 , 3.0165819583962126e+00 , 5.3166328000000007e+00 , 6.8062299999999998e-01 , 2.7571600000000002e-02 , -7.3211499999999996e-01 -1.2645744710463380e-01 , 3.0186113651576028e+00 , 5.3653151999999995e+00 , -7.0644200000000001e-01 , -1.6053300000000001e-01 , 6.8932499999999997e-01 -1.6762412970166718e-01 , 3.0197404285371974e+00 , 5.4060623999999997e+00 , -6.7295600000000000e-01 , -1.6061100000000000e-01 , 7.2203499999999998e-01 -2.1598206343882187e-01 , 3.0179022251880170e+00 , 5.4388743999999996e+00 , 5.9823499999999996e-01 , 1.9636300000000001e-01 , -7.7688900000000005e-01 -2.7268949173624524e-01 , 3.0139788456381176e+00 , 5.4631480000000003e+00 , -2.5158700000000001e-01 , 3.5721300000000000e-01 , 8.9950200000000002e-01 -4.3716228505926114e-01 , 2.9794053778935514e+00 , 5.3635368000000003e+00 , 2.8619400000000000e-01 , -1.6774799999999999e-02 , 9.5802500000000002e-01 -5.3744101518956144e-01 , 2.9617648500121532e+00 , 5.3289672000000001e+00 , 1.0441499999999999e-01 , 8.7842600000000004e-01 , 4.6633200000000002e-01 -6.8739607769102951e-01 , 2.9286628865159989e+00 , 5.2283056000000006e+00 , 3.6231900000000000e-01 , -4.2490200000000000e-01 , -8.2956799999999997e-01 -7.0078869541182653e-01 , 2.9355161988848173e+00 , 5.2915375999999998e+00 , -8.6019299999999999e-01 , 3.1659899999999998e-02 , 5.0898500000000002e-01 -5.8519135377912468e-01 , 2.9833398412330570e+00 , 5.5253399999999999e+00 , -8.2384200000000005e-02 , -9.1936899999999999e-01 , 3.8467400000000002e-01 -7.2552889553945965e-01 , 2.9520872353534471e+00 , 5.4264776000000001e+00 , 4.9581599999999998e-01 , -4.8602499999999998e-01 , -7.1968500000000002e-01 -7.6791673452478304e-01 , 2.9510868580146989e+00 , 5.4569080000000003e+00 , 6.1805900000000003e-01 , -7.1908200000000000e-01 , -3.1768600000000002e-01 -7.8648397779395141e-01 , 2.9567182527788707e+00 , 5.5204728000000003e+00 , -5.3079900000000002e-01 , 7.5570400000000004e-01 , -3.8362000000000002e-01 -7.0110738641129244e-01 , 2.9995364558206248e+00 , 5.7463607999999997e+00 , -4.9677699999999998e-02 , -1.3834199999999999e-01 , 9.8913799999999996e-01 -7.7053796599098856e-01 , 2.9905094433520683e+00 , 5.7427311999999997e+00 , 1.3083800000000001e-01 , -6.2663599999999997e-01 , -7.6825100000000002e-01 -8.0151961032930674e-01 , 2.9940731834352343e+00 , 5.7986728000000003e+00 , -6.5579200000000004e-01 , 2.8607500000000002e-01 , 6.9864000000000004e-01 -8.4507707319719594e-01 , 2.9935009080270261e+00 , 5.8367368000000006e+00 , 8.3533100000000005e-01 , 2.1405800000000000e-01 , -5.0636000000000003e-01 -5.4478138215876037e-01 , 3.1231684825510699e+00 , 6.4900440000000001e+00 , -9.0912899999999996e-01 , -1.2323300000000000e-01 , 3.9786700000000003e-01 -9.6715511070712568e-01 , 2.9798124114631719e+00 , 5.8475424000000000e+00 , -2.9505000000000000e-02 , -3.6791600000000002e-01 , 9.2939099999999997e-01 -6.8968005145189060e-01 , 3.1073676393343268e+00 , 6.5110312000000006e+00 , -6.4494200000000002e-01 , 8.0752599999999994e-02 , 7.5995299999999999e-01 -7.1382753964979995e-01 , 3.1189266145884504e+00 , 6.6157176000000000e+00 , -7.7892899999999998e-01 , 4.9623400000000001e-01 , 3.8343500000000003e-01 -7.2414752456689868e-01 , 3.1375088873738459e+00 , 6.7576255999999999e+00 , -8.5256900000000002e-01 , 1.4495500000000000e-01 , 5.0210999999999995e-01 -7.9800012777853557e-01 , 3.1303863582515419e+00 , 6.7696168000000005e+00 , -4.6340799999999999e-01 , 1.0632000000000001e-02 , 8.8608100000000001e-01 -8.6350549041801639e-01 , 3.1260498228191347e+00 , 6.7989759999999997e+00 , 5.6647000000000003e-01 , -3.8479400000000002e-01 , -7.2872899999999996e-01 -9.9854760809418863e-01 , 3.0883649617217599e+00 , 6.6565479999999999e+00 , 6.0289400000000004e-01 , 7.1694199999999997e-01 , 3.5001900000000002e-01 -1.0356258332017334e+00 , 3.0969528539726348e+00 , 6.7492640000000002e+00 , 5.1330699999999996e-01 , -7.9941300000000004e-01 , -3.1217699999999998e-01 -1.0091713874717914e+00 , 3.1387054388433606e+00 , 7.0246560000000002e+00 , -7.4796899999999999e-02 , -8.7860099999999997e-01 , 4.7166300000000000e-01 -1.0922459493576029e+00 , 3.1261621763120222e+00 , 7.0117080000000005e+00 , 3.9800799999999997e-01 , 9.0549900000000005e-01 , 1.4717600000000000e-01 -1.1073171514518696e+00 , 3.1510345535417805e+00 , 7.2016223999999998e+00 , -2.4774700000000000e-01 , -7.5006499999999998e-01 , 6.1320799999999998e-01 -5.1243854597887584e-01 , 3.5337831075967943e+00 , 9.4013576000000008e+00 , -9.3476499999999996e-01 , -4.0476800000000000e-02 , -3.5295399999999999e-01 -5.5871542445947076e-01 , 3.5643020510597037e+00 , 9.6628448000000002e+00 , -9.2487900000000001e-01 , -3.7952699999999999e-02 , -3.7836300000000000e-01 -8.1567946059664287e-01 , 3.4628424878520119e+00 , 9.1718919999999997e+00 , -6.0437200000000002e-01 , 4.2255500000000001e-01 , -6.7541200000000001e-01 -1.5095218754326081e+00 , 3.0516390034366991e+00 , 6.8521200000000002e+00 , -2.2260300000000000e-01 , -3.0782300000000001e-01 , 9.2503700000000000e-01 -1.5665175055251535e+00 , 3.0521778277376890e+00 , 6.9090808000000008e+00 , -7.5811799999999996e-01 , 2.7449100000000001e-02 , 6.5153899999999998e-01 -1.5212399823324836e+00 , 3.1348423595144048e+00 , 7.4572960000000004e+00 , -6.3027400000000000e-01 , 3.2595700000000000e-01 , 7.0463299999999995e-01 -1.6508653332337890e+00 , 3.0821053113883385e+00 , 7.2021112000000009e+00 , 7.4815799999999999e-01 , -3.7964500000000001e-01 , 5.4417700000000002e-01 -1.7325126966676883e+00 , 3.0670867674667335e+00 , 7.1660855999999997e+00 , -3.2030599999999999e-02 , 6.1635799999999996e-01 , -7.8681400000000001e-01 -1.5206364351213038e+00 , 3.3462182990304337e+00 , 8.9753840000000000e+00 , -2.7603100000000003e-01 , 2.6524499999999999e-02 , 9.6078300000000005e-01 -1.6349343886456440e+00 , 3.3230046698990465e+00 , 8.9109040000000004e+00 , -6.0003399999999996e-01 , -7.5176299999999996e-01 , 2.7351799999999998e-01 --1.1574107951116197e+00 , 2.6231781841141482e+00 , 5.1987199999999989e-01 , -8.9527999999999996e-02 , 1.3911699999999999e-01 , 9.8622100000000001e-01 --1.3114472767545329e+00 , 2.6461571079782624e+00 , 5.0616479999999986e-01 , -6.3562700000000000e-02 , 1.3451199999999999e-01 , 9.8887100000000006e-01 --1.4758620020239159e+00 , 2.6693986275575243e+00 , 4.9159439999999988e-01 , -6.2159800000000001e-02 , 1.4004200000000000e-01 , 9.8819299999999999e-01 --1.6506055377601050e+00 , 2.6950669028189256e+00 , 4.7628559999999998e-01 , 8.2915799999999998e-02 , -1.3868800000000001e-01 , -9.8685900000000004e-01 --1.8620714936313636e+00 , 2.7243271599376664e+00 , 4.4466960000000011e-01 , -1.0933100000000000e-01 , 1.4913599999999999e-01 , 9.8275400000000002e-01 --2.1203718602463884e+00 , 2.7570184482081497e+00 , 3.9367839999999998e-01 , 1.0677100000000000e-01 , -1.6082399999999999e-01 , -9.8119100000000004e-01 --2.3630251954667933e+00 , 2.7916187754137427e+00 , 3.6081439999999976e-01 , 8.2557000000000005e-02 , -1.5448700000000001e-01 , -9.8453999999999997e-01 --2.6274045722650099e+00 , 2.8278105270125087e+00 , 3.2591199999999998e-01 , 8.7951600000000005e-02 , -1.4810699999999999e-01 , -9.8505299999999996e-01 --2.9026752856608056e+00 , 2.8662725585055204e+00 , 2.9471200000000009e-01 , 8.4930199999999997e-02 , -1.4063100000000001e-01 , -9.8641299999999998e-01 --3.2352185942203535e+00 , 2.9118648115609425e+00 , 2.4449039999999989e-01 , -8.6492399999999997e-02 , 1.4296400000000001e-01 , 9.8594099999999996e-01 --3.5534075423241633e+00 , 2.9576290643453049e+00 , 2.1399760000000012e-01 , -9.4384200000000001e-02 , 1.3438200000000000e-01 , 9.8642500000000000e-01 --3.9868102550707514e+00 , 3.0159265049331898e+00 , 1.4209199999999989e-01 , -1.0050700000000000e-01 , 1.3230000000000000e-01 , 9.8610100000000001e-01 --4.4041243359421065e+00 , 3.0749491184268027e+00 , 9.3003999999999865e-02 , -8.5706900000000003e-02 , 8.8821100000000000e-02 , 9.9235300000000004e-01 --4.9117916079714901e+00 , 3.1450501547775156e+00 , 2.1670400000000090e-02 , -1.2565100000000001e-01 , 4.2442199999999999e-02 , 9.9116599999999999e-01 --5.4624992833741723e+00 , 3.2215903372100985e+00 , -4.7936800000000002e-02 , -1.2494200000000000e-01 , 5.8691800000000002e-02 , 9.9042699999999995e-01 --6.1134366313700106e+00 , 3.3125975347829586e+00 , -1.3567119999999999e-01 , -9.8069299999999998e-02 , 3.8057500000000001e-02 , 9.9445200000000000e-01 --6.9054187170875068e+00 , 3.4213328507689003e+00 , -2.4988399999999977e-01 , -9.2826099999999995e-02 , 1.3790800000000001e-02 , 9.9558700000000000e-01 --7.8212307459567114e+00 , 3.5476249210108235e+00 , -3.7708640000000004e-01 , -1.2864500000000001e-01 , 2.6914600000000000e-02 , 9.9132500000000001e-01 --8.8324938646144506e+00 , 3.6892571693671457e+00 , -5.0128320000000004e-01 , -1.0605000000000001e-01 , 4.3174299999999999e-02 , 9.9342299999999994e-01 --1.0097126849016826e+01 , 3.8656413203992006e+00 , -6.6508320000000021e-01 , -1.0782500000000000e-01 , 5.6901700000000000e-02 , 9.9253999999999998e-01 --1.1648008656645434e+01 , 4.0824006242458033e+00 , -8.6360880000000018e-01 , 4.1111200000000001e-02 , 1.6097100000000000e-02 , -9.9902500000000005e-01 --1.3438468921093765e+01 , 4.3356569468862727e+00 , -1.0690400000000002e+00 , -2.4327299999999999e-01 , 1.1022400000000000e-02 , 9.6989499999999995e-01 --1.6502682646294403e+01 , 4.7556385268193280e+00 , -1.5197759999999998e+00 , 1.0213200000000000e-01 , -1.4327400000000001e-01 , -9.8439900000000002e-01 --2.6995189347653206e+01 , 6.2022389388048209e+00 , -2.9927071999999999e+00 , -7.8819700000000006e-02 , 2.1792500000000001e-01 , 9.7277800000000003e-01 --2.7035522710604571e+01 , 6.2797616290909133e+00 , -2.4689215999999998e+00 , -7.8819700000000006e-02 , 2.1792500000000001e-01 , 9.7277800000000003e-01 --3.9404791794526631e+01 , 8.0069895817080017e+00 , -4.0456136000000003e+00 , -4.1415600000000002e-01 , 5.0483299999999998e-01 , 7.5737600000000005e-01 --3.9466327593236258e+01 , 8.1168665293411060e+00 , -3.3080040000000004e+00 , -4.1415700000000000e-01 , 5.0483400000000000e-01 , 7.5737500000000002e-01 --3.9658243396812949e+01 , 8.2454131185043913e+00 , -2.5894367999999996e+00 , -4.1415600000000002e-01 , 5.0483299999999998e-01 , 7.5737600000000005e-01 --3.9704333095484166e+01 , 8.3529031531513063e+00 , -1.8496432000000000e+00 , -2.3071800000000000e-02 , 3.2343100000000002e-01 , 9.4596999999999998e-01 --4.3009291466994050e+01 , 9.0370915003384908e+00 , -6.3496480000000011e-01 , -7.1072700000000000e-01 , 5.4693700000000001e-01 , -4.4241000000000003e-01 --4.3461135401993822e+01 , 9.2124841437529987e+00 , 1.3394879999999976e-01 , -7.6643499999999998e-01 , 5.7445700000000000e-01 , -2.8736099999999998e-01 --4.4088870626057322e+01 , 9.5268875425481490e+00 , 1.7239091200000001e+00 , -7.3826700000000001e-01 , 6.3537699999999997e-01 , -2.2640500000000000e-01 --4.6913985709180487e+01 , 1.0076589255878243e+01 , 2.5057239199999999e+00 , 5.4925299999999999e-01 , 9.0275800000000003e-02 , 8.3076600000000000e-01 --4.6980199263300264e+01 , 1.0204830949203098e+01 , 3.3703664000000000e+00 , 5.4925299999999999e-01 , 9.0275800000000003e-02 , 8.3076600000000000e-01 --4.7083387596489281e+01 , 1.0339584695413260e+01 , 4.2389016000000002e+00 , 6.1828499999999997e-01 , 8.9539300000000002e-02 , 7.8083700000000000e-01 --4.7858178290486578e+01 , 1.0583217992085064e+01 , 5.1401864000000002e+00 , 7.9242999999999997e-01 , -3.5437999999999997e-01 , 4.9645699999999998e-01 --1.1705332806125522e+01 , 4.7405267803332087e+00 , 3.9086600000000002e+00 , -6.2475199999999997e-01 , 7.7675799999999995e-01 , 7.9572500000000004e-02 --1.1591859158044315e+01 , 4.7555279384785578e+00 , 4.1496279999999999e+00 , -7.5045200000000001e-01 , 6.3094600000000001e-01 , 1.9679500000000000e-01 --1.1668208369047093e+01 , 4.8018527029076772e+00 , 4.4053640000000005e+00 , -8.3767700000000000e-01 , 5.4092399999999996e-01 , 7.5492600000000007e-02 --1.0965645127862986e+01 , 4.7150816273955796e+00 , 4.5778376000000005e+00 , -1.9309599999999999e-01 , 2.8394399999999997e-01 , 9.3919600000000003e-01 --1.0840739090748070e+01 , 4.7260333311354685e+00 , 4.8012192000000002e+00 , 3.0209300000000000e-01 , -1.7707999999999999e-01 , -9.3668700000000005e-01 --2.4832179975151041e+00 , 3.2788572827226128e+00 , 3.8076032000000000e+00 , -9.1890700000000003e-01 , 2.0319600000000000e-02 , -3.9395000000000002e-01 --2.4076827272273214e+00 , 3.2772224362369466e+00 , 3.8840848000000001e+00 , -9.1890700000000003e-01 , 2.0319600000000000e-02 , -3.9395000000000002e-01 --2.4312322664608415e+00 , 3.2937248138974207e+00 , 3.9767904000000001e+00 , -9.4208400000000003e-01 , 1.5117400000000000e-01 , -2.9937200000000003e-01 --2.4432017690297601e+00 , 3.3074386035914718e+00 , 4.0686432000000003e+00 , -9.1440399999999999e-01 , 1.8650300000000000e-01 , -3.5927999999999999e-01 --2.4434657681542955e+00 , 3.3203099245362018e+00 , 4.1588528000000000e+00 , 9.7201599999999999e-01 , 1.5447700000000000e-01 , 1.7697900000000000e-01 --2.5814843812907782e+00 , 3.3586541914876253e+00 , 4.2828207999999997e+00 , -8.2860400000000001e-01 , 4.1739900000000003e-02 , -5.5827700000000002e-01 --2.9045389011346936e+00 , 3.4338129372276742e+00 , 4.4604423999999998e+00 , -6.2656400000000001e-01 , 7.7146999999999999e-01 , -1.1068500000000001e-01 --2.7798102553621833e+00 , 3.4228158849282870e+00 , 4.5273456000000003e+00 , 5.3450600000000004e-01 , -7.4543800000000005e-01 , 3.9827899999999999e-01 --2.9665170400339269e+00 , 3.4738931169920830e+00 , 4.6830335999999999e+00 , 4.9983800000000000e-01 , -8.0743200000000004e-01 , 3.1339499999999998e-01 --2.9653510348013814e+00 , 3.4874575520823354e+00 , 4.7874808000000009e+00 , -2.9726000000000002e-01 , 7.1682999999999997e-01 , 6.3070599999999999e-01 --3.0012792427017079e+00 , 3.5095366306562013e+00 , 4.9052608000000006e+00 , -5.9801700000000002e-01 , 6.4271100000000003e-01 , 4.7885100000000003e-01 --2.7736528696466252e+00 , 3.4777159140855645e+00 , 4.9328935999999999e+00 , -8.8492800000000005e-01 , -4.1632900000000000e-01 , -2.0874200000000001e-01 --2.7386310492221630e+00 , 3.4841360510121926e+00 , 5.0249544000000004e+00 , 3.4818600000000000e-01 , 3.0153200000000002e-01 , 8.8760700000000003e-01 --3.4139509201392748e+00 , 3.6412978772133933e+00 , 5.3973576000000003e+00 , -7.2608600000000001e-01 , -8.6832400000000004e-02 , 6.8209900000000001e-01 --3.0410956068079358e+00 , 3.5780700457393584e+00 , 5.3634015999999995e+00 , -8.3674800000000005e-01 , 5.2565099999999998e-01 , 1.5343999999999999e-01 --3.0544648505981469e+00 , 3.5966997405945582e+00 , 5.4846552000000006e+00 , -8.8236099999999995e-01 , 3.9682699999999999e-01 , -2.5291700000000000e-01 --2.5465524952077416e+00 , 3.5006289282835841e+00 , 5.3691632000000000e+00 , -2.8468500000000002e-01 , -3.4512799999999999e-01 , 8.9433900000000000e-01 --3.0466118536668745e+00 , 3.6262742106360895e+00 , 5.7174280000000000e+00 , -7.2677599999999998e-01 , 3.7371500000000002e-01 , 5.7630999999999999e-01 --2.2409141214754564e+00 , 3.4614464587518698e+00 , 5.4348808000000002e+00 , -3.4386000000000000e-01 , 6.8422099999999997e-01 , -6.4311799999999997e-01 --2.1071807373981644e+00 , 3.4458123391656716e+00 , 5.4701263999999998e+00 , -8.5489400000000004e-01 , -4.6655300000000000e-01 , 2.2690099999999999e-01 --2.2243616200913578e+00 , 3.4868950098369407e+00 , 5.6385336000000006e+00 , -5.1623399999999997e-01 , 8.5222200000000004e-01 , 8.4969500000000003e-02 --2.0185740711403692e+00 , 3.4529818797339207e+00 , 5.6300368000000001e+00 , -6.9205600000000000e-01 , -4.6306399999999998e-01 , 5.5374299999999999e-01 --2.0243267274342580e+00 , 3.4690064274318866e+00 , 5.7400064000000004e+00 , 7.2674000000000002e-02 , -9.9310100000000001e-01 , 9.2025800000000005e-02 --2.2266365741715513e+00 , 3.5334004589827450e+00 , 5.9742768000000002e+00 , -8.5052499999999998e-01 , 5.2442200000000005e-01 , 3.9864900000000002e-02 --4.0156207118605440e+00 , 3.9857841322827112e+00 , 7.2423384000000004e+00 , 1.1779899999999999e-02 , -1.5481500000000001e-01 , 9.8787300000000000e-01 --3.8212497408730863e+00 , 3.9600303214308687e+00 , 7.2771992000000001e+00 , 1.1779899999999999e-02 , -1.5481500000000001e-01 , 9.8787300000000000e-01 --2.6579675525374160e+00 , 3.6897863277004328e+00 , 6.6320560000000004e+00 , 6.4095500000000005e-01 , -5.1355099999999998e-01 , 5.7047499999999995e-01 --3.6415170564237771e+00 , 3.9601088590968647e+00 , 7.4793544000000001e+00 , 2.8718800000000000e-01 , 7.5980599999999998e-01 , -5.8328199999999997e-01 --3.3501863942086212e+00 , 3.9075418871559258e+00 , 7.4281344000000002e+00 , 2.2711000000000001e-01 , 7.3535499999999998e-01 , -6.3849299999999998e-01 --2.9583357415717462e+00 , 3.8261456893131838e+00 , 7.2869543999999999e+00 , -8.3902900000000002e-01 , -2.5518999999999997e-01 , 4.8053000000000001e-01 --2.9696904508516369e+00 , 3.8504895125241996e+00 , 7.4528032000000000e+00 , 7.7443499999999998e-01 , 3.9272200000000002e-01 , -4.9600499999999997e-01 --2.9144516763696533e+00 , 3.8575803066777783e+00 , 7.5682847999999998e+00 , 5.7357899999999995e-01 , 4.3151200000000001e-01 , -6.9627899999999998e-01 --2.8327180171434119e+00 , 3.8582949228046246e+00 , 7.6630704000000005e+00 , 5.7357899999999995e-01 , 4.3151200000000001e-01 , -6.9627899999999998e-01 --4.0224921960180442e+00 , 4.2128997710295684e+00 , 8.9004311999999999e+00 , -5.4649199999999998e-01 , -3.8344600000000001e-01 , 7.4452399999999996e-01 --3.8358159067772277e+00 , 4.1891940891233492e+00 , 8.9385575999999993e+00 , 4.4262099999999999e-01 , -4.2978899999999998e-01 , 7.8699900000000000e-01 -9.3021592457339208e-02 , 3.0853502200594134e+00 , 5.3574216000000003e+00 , 6.9369599999999998e-01 , -4.2865000000000000e-02 , -7.1899100000000005e-01 -1.3401983323112265e-01 , 3.0845881218932432e+00 , 5.3992920000000000e+00 , 6.5083899999999995e-01 , -9.3858899999999995e-02 , -7.5339199999999995e-01 -1.7511848721912870e-01 , 3.0836447595375329e+00 , 5.4402471999999999e+00 , 5.8820200000000000e-01 , -1.5303600000000001e-01 , -7.9410199999999997e-01 -2.2445479790731793e-01 , 3.0797021823095747e+00 , 5.4733920000000005e+00 , 4.8760900000000003e-02 , 5.2121300000000004e-01 , 8.5203200000000001e-01 -3.4250428569437830e-01 , 3.0551691681202677e+00 , 5.4295144000000004e+00 , 4.7062199999999998e-01 , 1.9485400000000000e-01 , 8.6055000000000004e-01 -5.9723538716183300e-01 , 2.9872138434060309e+00 , 5.2203391999999997e+00 , 2.2021499999999999e-01 , 7.3280500000000004e-01 , 6.4381900000000003e-01 -5.3141452041977422e-01 , 3.0187155935422405e+00 , 5.3785024000000003e+00 , -1.1805599999999999e-01 , -9.8908799999999997e-01 , -8.8130600000000003e-02 -6.0419397403052111e-01 , 3.0070141898674168e+00 , 5.3728239999999996e+00 , 2.5355000000000000e-01 , -9.3669199999999997e-01 , -2.4149699999999999e-01 -6.6993672977162722e-01 , 2.9968894382060061e+00 , 5.3734688000000004e+00 , -8.1529399999999996e-01 , -2.5474900000000000e-01 , 5.1999799999999996e-01 -6.8632807628354509e-01 , 3.0027695059204325e+00 , 5.4377928000000004e+00 , -9.3133800000000000e-01 , -2.1150700000000000e-01 , 2.9643500000000000e-01 -6.8100545218077890e-01 , 3.0173531660049471e+00 , 5.5353864000000002e+00 , -8.4112500000000001e-01 , -5.1961199999999996e-01 , 1.5004000000000001e-01 -6.7765360864564284e-01 , 3.0309568249699450e+00 , 5.6338431999999994e+00 , 5.4342100000000004e-01 , -8.3165199999999995e-01 , -1.1423200000000000e-01 -6.6695293328015715e-01 , 3.0485145137791951e+00 , 5.7502920000000000e+00 , 4.6971200000000002e-01 , -5.2969599999999994e-01 , -7.0625300000000002e-01 -7.5282129839158385e-01 , 3.0306694104338998e+00 , 5.7221912000000001e+00 , 8.5304199999999997e-02 , 4.0813600000000000e-01 , 9.0892700000000004e-01 -8.0979549627076053e-01 , 3.0233831970314515e+00 , 5.7351184000000002e+00 , -8.4593399999999996e-01 , 4.2010799999999998e-01 , 3.2849099999999998e-01 -8.2621439340853597e-01 , 3.0327812639740497e+00 , 5.8168831999999995e+00 , 5.5251099999999997e-01 , -7.5806799999999996e-01 , -3.4650300000000001e-01 -8.3417742736088840e-01 , 3.0451661477164871e+00 , 5.9169312000000005e+00 , 5.3279399999999999e-01 , 3.3585900000000002e-01 , -7.7674299999999996e-01 -8.9868193947500274e-01 , 3.0343340961140228e+00 , 5.9190735999999999e+00 , -2.6694200000000001e-01 , -4.4989800000000002e-01 , 8.5225200000000001e-01 -9.6866756780003738e-01 , 3.0232442351789279e+00 , 5.9105872000000002e+00 , 1.8306200000000000e-01 , -3.3310699999999999e-01 , 9.2494799999999999e-01 -6.7937083593463621e-01 , 3.1633547286737347e+00 , 6.6128472000000000e+00 , -6.9259700000000002e-01 , 7.0772500000000005e-01 , 1.3940800000000000e-01 -7.2450142622176594e-01 , 3.1656905538334623e+00 , 6.6814976000000001e+00 , 8.3443800000000001e-01 , -2.2358100000000000e-01 , -5.0371100000000002e-01 -7.7920376959437099e-01 , 3.1637801509163803e+00 , 6.7311056000000002e+00 , -7.0468799999999998e-01 , -1.6037400000000000e-02 , 7.0933599999999997e-01 -8.4354241148533227e-01 , 3.1575092656416297e+00 , 6.7611512000000005e+00 , -3.1010399999999999e-01 , 1.6018700000000000e-01 , 9.3711000000000000e-01 -8.2594735739787795e-01 , 3.1913057475623794e+00 , 6.9883496000000003e+00 , -8.8853599999999999e-01 , -1.3297800000000001e-01 , 4.3911299999999998e-01 -1.0602784315146354e+00 , 3.1017379525722770e+00 , 6.5990672000000004e+00 , 2.7553299999999997e-01 , 6.1638199999999999e-01 , 7.3766799999999999e-01 -8.9572788031034145e-01 , 3.2131549262546226e+00 , 7.2276640000000008e+00 , -1.5828100000000001e-01 , -8.1361499999999998e-01 , 5.5944499999999997e-01 -1.1096788122683781e+00 , 3.1299718921953561e+00 , 6.8604296000000007e+00 , 3.3330700000000002e-01 , -9.3159800000000004e-01 , 1.4502599999999999e-01 -1.1335899874098561e+00 , 3.1465128267914406e+00 , 7.0108760000000006e+00 , -4.6197800000000000e-01 , -8.7437399999999998e-01 , -1.4848000000000000e-01 -1.1594201122959333e+00 , 3.1639627164337751e+00 , 7.1715248000000003e+00 , -3.0901299999999998e-01 , 7.5083999999999995e-01 , -5.8373799999999998e-01 -4.7716042692869931e-01 , 3.6202891895441436e+00 , 9.7388376000000001e+00 , -8.5063699999999998e-01 , 1.7608100000000002e-02 , -5.2545799999999998e-01 -7.3332383124104106e-01 , 3.5161205644738378e+00 , 9.2712327999999999e+00 , -7.6873700000000000e-01 , -2.3880699999999999e-01 , -5.9330899999999998e-01 -1.4863870462298265e+00 , 3.0635775994757539e+00 , 6.8115392000000003e+00 , 8.2166500000000003e-02 , -4.4214900000000001e-01 , 8.9317000000000002e-01 -1.5544566776269626e+00 , 3.0547522277322177e+00 , 6.8191416000000009e+00 , -1.6125100000000001e-01 , -4.8273100000000002e-01 , 8.6079600000000001e-01 -1.5175793004070872e+00 , 3.1248894997302687e+00 , 7.2964392000000009e+00 , -9.0181599999999995e-01 , -2.0236199999999999e-01 , -3.8180799999999998e-01 -1.5613300044350464e+00 , 3.1409634312847423e+00 , 7.4646072000000006e+00 , 5.1179399999999997e-01 , -8.4971600000000003e-01 , -1.2668499999999999e-01 -1.6958217635926598e+00 , 3.0796943159324246e+00 , 7.1681447999999994e+00 , 1.4172100000000001e-01 , -6.9754000000000005e-01 , 7.0239099999999999e-01 -1.7741756173832774e+00 , 3.0635836835945862e+00 , 7.1417912000000001e+00 , 4.7957199999999998e-02 , -6.2440700000000005e-01 , 7.7962500000000001e-01 -1.5789558750406323e+00 , 3.3392790603576241e+00 , 8.9428528000000007e+00 , 3.7150899999999998e-01 , -8.1007600000000002e-01 , 4.5360499999999998e-01 -1.6744012916455122e+00 , 3.3338701186841622e+00 , 9.0101720000000007e+00 , 6.1892400000000003e-01 , 7.6353000000000004e-01 , -1.8427199999999999e-01 --8.9910924711129425e-01 , 2.6965387060522810e+00 , 5.4382320000000006e-01 , -6.5435199999999999e-02 , 1.2842500000000001e-01 , 9.8955800000000005e-01 --1.0414275687105103e+00 , 2.7208637007281724e+00 , 5.2876400000000001e-01 , 8.5086599999999998e-02 , -1.1330000000000000e-01 , -9.8991099999999999e-01 --1.1929420689039461e+00 , 2.7473675283538803e+00 , 5.1205119999999993e-01 , -8.4628900000000007e-02 , 1.0999500000000000e-01 , 9.9032299999999995e-01 --1.3557817773900722e+00 , 2.7751410946641970e+00 , 4.9396559999999989e-01 , -7.5799300000000000e-02 , 1.2168600000000000e-01 , 9.8967000000000005e-01 --1.5453877006265051e+00 , 2.8069649715527834e+00 , 4.6386799999999995e-01 , -7.8464000000000006e-02 , 1.3444700000000001e-01 , 9.8780900000000005e-01 --1.7378028182895213e+00 , 2.8390364838864355e+00 , 4.3968800000000008e-01 , 9.2255799999999999e-02 , -1.4218800000000001e-01 , -9.8553100000000005e-01 --1.9582375811744721e+00 , 2.8755833613981396e+00 , 4.0540959999999981e-01 , 1.1829199999999999e-01 , -1.4931900000000001e-01 , -9.8168800000000001e-01 --2.1991281662442113e+00 , 2.9154647628795152e+00 , 3.6749119999999991e-01 , 9.3393199999999996e-02 , -1.5692400000000001e-01 , -9.8318499999999998e-01 --2.4507613353783047e+00 , 2.9584530737094696e+00 , 3.3215200000000000e-01 , -8.1604399999999994e-02 , 1.3761599999999999e-01 , 9.8711800000000005e-01 --2.7231158836201654e+00 , 3.0041490551604904e+00 , 2.9531520000000011e-01 , -8.4921300000000005e-02 , 1.2483800000000000e-01 , 9.8853599999999997e-01 --3.0162078043994596e+00 , 3.0547778852412319e+00 , 2.5746959999999985e-01 , -9.0754100000000004e-02 , 1.1843800000000000e-01 , 9.8880599999999996e-01 --3.3500507559075174e+00 , 3.1107076000918132e+00 , 2.1083599999999980e-01 , -8.2657099999999997e-02 , 1.0265500000000000e-01 , 9.9127699999999996e-01 --3.6851927426045563e+00 , 3.1689101417060956e+00 , 1.7523679999999997e-01 , -1.0580199999999999e-01 , 9.6340599999999998e-02 , 9.8970899999999995e-01 --4.1367038757117500e+00 , 3.2431469200883698e+00 , 9.9514399999999892e-02 , -1.0633900000000000e-01 , 6.8021999999999999e-02 , 9.9199999999999999e-01 --4.5643023612591156e+00 , 3.3165220322013873e+00 , 5.0956800000000024e-02 , -5.1480499999999998e-02 , -2.8271100000000000e-02 , 9.9827399999999999e-01 --5.0901985926150717e+00 , 3.4049892339295065e+00 , -2.2685599999999972e-02 , 1.4386499999999999e-01 , 4.4777299999999999e-02 , -9.8858400000000002e-01 --5.6681805872442803e+00 , 3.5029008514512343e+00 , -9.7471999999999781e-02 , -1.5443999999999999e-01 , -2.4266300000000001e-02 , 9.8770400000000003e-01 --6.3275316135327149e+00 , 3.6151552383833652e+00 , -1.8170159999999980e-01 , -1.2465400000000000e-01 , -1.9038800000000002e-02 , 9.9201799999999996e-01 --6.7089177685764128e+00 , 3.6921466076525560e+00 , -1.4442800000000000e-01 , -1.1723900000000000e-01 , -1.9343800000000001e-02 , 9.9291499999999999e-01 --7.4634967724460495e+00 , 3.8233518718423163e+00 , -2.1815359999999995e-01 , -1.5175200000000000e-01 , 2.6172000000000001e-02 , 9.8807199999999995e-01 --8.5574358526625947e+00 , 4.0073416732290799e+00 , -3.7110640000000039e-01 , 1.3723099999999999e-01 , -4.6986500000000000e-02 , -9.8942399999999997e-01 --9.9444723505159214e+00 , 4.2401552313505517e+00 , -5.7083840000000041e-01 , -1.0707999999999999e-01 , 4.8146300000000003e-02 , 9.9308399999999997e-01 --1.1607235415517394e+01 , 4.5220029964420352e+00 , -7.9683040000000016e-01 , 3.2349099999999999e-02 , -1.6663800000000001e-01 , 9.8548700000000000e-01 --1.3300099418348966e+01 , 4.8157143094677846e+00 , -9.7047920000000021e-01 , -2.0626800000000001e-01 , -2.1135300000000001e-01 , 9.5539700000000005e-01 --2.5121521661100285e+01 , 6.7582227033160356e+00 , -2.9954840000000003e+00 , -1.2901099999999999e-01 , 2.9368300000000003e-01 , 9.4715700000000003e-01 --2.6066942909758684e+01 , 6.9761917658670187e+00 , -2.6846904000000000e+00 , -8.8236800000000004e-02 , 1.5421599999999999e-01 , 9.8408899999999999e-01 --3.9744043612417016e+01 , 9.3706694567146194e+00 , -3.9268352000000002e+00 , -6.9726800000000000e-01 , 3.3078800000000003e-01 , 6.3592199999999999e-01 --3.9952292584151515e+01 , 9.5054555203693134e+00 , -3.2022672000000005e+00 , -6.9726800000000000e-01 , 3.3078800000000003e-01 , 6.3592199999999999e-01 --1.2440924172769689e+01 , 4.9692913974717978e+00 , 1.4034372799999999e+00 , 9.8819400000000002e-01 , 1.5290400000000001e-01 , 9.6178700000000006e-03 --1.2451274158898460e+01 , 5.0056919604423662e+00 , 1.6662255200000000e+00 , 9.8816199999999998e-01 , 1.5271599999999999e-01 , 1.4586900000000000e-02 --4.2754847015472272e+01 , 1.0398768695624431e+01 , -4.0965920000000011e-01 , 7.2253400000000001e-01 , -6.5476500000000004e-01 , 2.2187299999999999e-01 --1.2498761013047543e+01 , 5.0834305755397793e+00 , 2.1894349599999998e+00 , 9.8800800000000000e-01 , 1.5346799999999999e-01 , 1.6948700000000001e-02 --4.4016495117603341e+01 , 1.0838711476655174e+01 , 1.1305152800000000e+00 , -8.8587300000000002e-01 , 4.4335799999999997e-01 , -1.3661000000000001e-01 --4.7715004283033764e+01 , 1.1627445300093195e+01 , 1.8581450399999999e+00 , -5.9843000000000002e-01 , -2.0745900000000001e-02 , -8.0090600000000001e-01 --4.2932539402795257e+01 , 1.0853425534657406e+01 , 2.7734563200000002e+00 , -8.9234899999999995e-01 , 4.3339600000000000e-01 , -1.2601999999999999e-01 --4.2748485785234337e+01 , 1.0924373581048698e+01 , 3.5706080000000000e+00 , -9.1935699999999998e-01 , 3.7625199999999998e-01 , 1.1496500000000000e-01 --1.1773556361212455e+01 , 5.1189627767768080e+00 , 3.4850783999999999e+00 , 9.8740099999999997e-01 , -3.6339999999999997e-02 , -1.5400600000000000e-01 --1.1665970365829422e+01 , 5.1321231456714180e+00 , 3.7313920000000000e+00 , 9.9642699999999995e-01 , 2.8079300000000001e-02 , -7.9656099999999994e-02 --1.1667542206334716e+01 , 5.1655279410586949e+00 , 3.9813040000000002e+00 , 9.9642699999999995e-01 , 2.8079300000000001e-02 , -7.9656099999999994e-02 --1.1653265056460430e+01 , 5.1961287517477466e+00 , 4.2309767999999996e+00 , 9.9314999999999998e-01 , -8.6156600000000000e-02 , -7.8930899999999998e-02 --1.1696205571732738e+01 , 5.2378290173122313e+00 , 4.4867960000000000e+00 , -9.7222600000000003e-01 , 1.1093400000000000e-01 , 2.0608199999999999e-01 --1.1633577040103591e+01 , 5.2581435234055771e+00 , 4.7327560000000002e+00 , 9.7341900000000003e-01 , -1.4150699999999999e-01 , -1.8008500000000000e-01 --3.8911894695438090e+00 , 3.7044618888834484e+00 , 3.9383520000000001e+00 , 1.6838100000000002e-02 , 3.0093700000000001e-01 , 9.5349499999999998e-01 --3.7922831289293164e+00 , 3.7000304108625404e+00 , 4.0376200000000004e+00 , -4.2083500000000001e-01 , -8.9893600000000004e-02 , 9.0267200000000003e-01 --3.6611293468317365e+00 , 3.6873327368873250e+00 , 4.1290359999999993e+00 , -4.2083399999999999e-01 , -8.9893200000000006e-02 , 9.0267200000000003e-01 --2.3991398655943597e+00 , 3.4342644251013263e+00 , 4.0013551999999999e+00 , -9.4145000000000001e-01 , 3.0811899999999998e-01 , -1.3687500000000000e-01 --2.9283005045009460e+00 , 3.5599318162459439e+00 , 4.2012224000000007e+00 , 5.7720300000000002e-01 , -6.9179999999999997e-01 , 4.3387700000000001e-01 --2.6582457922907743e+00 , 3.5146928375381785e+00 , 4.2398375999999995e+00 , 5.6842199999999998e-01 , 9.0260599999999996e-02 , 8.1777100000000003e-01 --2.6947146161655082e+00 , 3.5352509951383526e+00 , 4.3446072000000004e+00 , 2.4175400000000000e-01 , 6.9002799999999997e-01 , 6.8221399999999999e-01 --2.8166958426452249e+00 , 3.5752014150903904e+00 , 4.4747319999999995e+00 , -1.6051000000000001e-01 , 9.8669300000000004e-01 , 2.5965599999999998e-02 --2.6821435848245381e+00 , 3.5576215961563027e+00 , 4.5374128000000002e+00 , 6.0561600000000004e-01 , -7.1072199999999996e-01 , 3.5791699999999999e-01 --2.8189493118109779e+00 , 3.6024937495028033e+00 , 4.6782496000000000e+00 , 4.9041299999999999e-01 , -8.4055500000000005e-01 , 2.3013600000000001e-01 --2.8751392774636084e+00 , 3.6293580235446630e+00 , 4.7995967999999998e+00 , -5.1352900000000001e-01 , 8.1650100000000003e-01 , -2.6384600000000002e-01 --2.8327047233910125e+00 , 3.6331316900932515e+00 , 4.8906176000000006e+00 , -7.0502500000000001e-01 , 7.0327600000000001e-01 , 9.1333200000000003e-02 --2.9320858061834372e+00 , 3.6702671537554310e+00 , 5.0326608000000004e+00 , -5.3017599999999998e-01 , 5.3266300000000000e-01 , -6.5968499999999997e-01 --2.9522687405637340e+00 , 3.6894257194669002e+00 , 5.1497856000000004e+00 , -5.0101200000000001e-01 , 8.1573300000000004e-01 , -2.8907899999999997e-01 --3.1109720392101838e+00 , 3.7422320522539412e+00 , 5.3253168000000004e+00 , -9.5056099999999999e-01 , 1.8929299999999999e-01 , -2.4617600000000001e-01 --2.8538955248059956e+00 , 3.6954764726267619e+00 , 5.3325656000000006e+00 , -4.7590600000000000e-01 , 8.2764499999999996e-01 , 2.9751800000000000e-01 --2.8305592478411432e+00 , 3.7044728028018779e+00 , 5.4349120000000006e+00 , -4.7590600000000000e-01 , 8.2764499999999996e-01 , 2.9751800000000000e-01 --2.4557413190312767e+00 , 3.6261712112075735e+00 , 5.3739368000000001e+00 , 5.2549100000000004e-01 , 2.9071000000000002e-01 , -7.9959199999999997e-01 --2.0402181795963736e+00 , 3.5358847980605077e+00 , 5.2780072000000002e+00 , -9.8533099999999998e-02 , -4.7508400000000001e-01 , 8.7440600000000002e-01 --2.2430981320754793e+00 , 3.6006832281315813e+00 , 5.4825128000000003e+00 , -6.4099899999999999e-01 , -1.6761499999999999e-01 , 7.4901600000000002e-01 --2.2343488852105109e+00 , 3.6134821616971493e+00 , 5.5848072000000002e+00 , -9.4626800000000000e-01 , 2.5686100000000001e-01 , 1.9646700000000000e-01 --2.1084372793589585e+00 , 3.5946601490469754e+00 , 5.6236408000000004e+00 , 8.0970900000000001e-01 , -4.6789100000000000e-02 , -5.8496300000000001e-01 --2.1412648426057412e+00 , 3.6173571478846736e+00 , 5.7504168000000000e+00 , -8.0331500000000000e-01 , -5.7475299999999996e-01 , 1.5602500000000000e-01 --1.9192007018059325e+00 , 3.5723011621464531e+00 , 5.7269959999999998e+00 , -8.4911999999999999e-01 , -7.3981400000000003e-02 , 5.2299399999999996e-01 --2.1452699688102452e+00 , 3.6484222866676568e+00 , 5.9775320000000001e+00 , -5.4214399999999996e-01 , 8.3966399999999997e-01 , -3.2325300000000001e-02 --1.9824747380157901e+00 , 3.6189312489209131e+00 , 5.9870999999999999e+00 , 1.5578300000000000e-01 , -7.5306600000000001e-01 , 6.3923700000000006e-01 --2.1883332162606823e+00 , 3.6910420988228321e+00 , 6.2430960000000004e+00 , 7.8323900000000002e-01 , -5.6916900000000004e-01 , 2.5016800000000000e-01 --2.2304944462251877e+00 , 3.7193706402558124e+00 , 6.3958303999999995e+00 , -7.9476999999999998e-01 , 3.4762100000000001e-01 , -4.9749399999999999e-01 --3.1178334689461886e+00 , 3.9889810485096051e+00 , 7.1757264000000003e+00 , 5.8651200000000003e-01 , -5.3515100000000004e-01 , 6.0796200000000000e-01 --4.9940122958903261e+00 , 4.5498817265125169e+00 , 8.7635567999999999e+00 , -5.8266799999999996e-01 , 3.3700799999999997e-01 , -7.3954200000000003e-01 --3.1108600103008053e+00 , 4.0289144706334499e+00 , 7.4861143999999999e+00 , 6.3795100000000005e-01 , 6.2904199999999999e-01 , -4.4421200000000000e-01 --3.0156635224361308e+00 , 4.0220543474398855e+00 , 7.5725175999999994e+00 , 6.3795100000000005e-01 , 6.2904199999999999e-01 , -4.4421200000000000e-01 --2.8737366831247426e+00 , 4.0015974822988376e+00 , 7.6172063999999997e+00 , -4.4687100000000002e-01 , -3.9739000000000002e-01 , 8.0149099999999995e-01 --3.8864746610349954e+00 , 4.3312640896118806e+00 , 8.6789632000000001e+00 , -4.9290299999999998e-01 , -2.8616999999999998e-01 , 8.2167699999999999e-01 --2.5734571353229327e+00 , 3.9540916656130713e+00 , 7.6826224000000005e+00 , 1.4877699999999999e-01 , 3.6589300000000002e-01 , -9.1868799999999995e-01 -6.8823924658192315e-02 , 3.1502264917016873e+00 , 5.3422376000000007e+00 , 6.9369599999999998e-01 , -4.2864899999999997e-02 , -7.1899100000000005e-01 -1.3813014512586186e-01 , 3.1384364972043701e+00 , 5.3564752000000002e+00 , 2.8138400000000002e-01 , -1.4277200000000001e-01 , -9.4891499999999995e-01 -1.8528135801107437e-01 , 3.1347513393063480e+00 , 5.3903791999999999e+00 , -4.1080400000000003e-02 , 6.0947399999999996e-01 , 7.9174100000000003e-01 -2.8960346574212070e-01 , 3.1112982421498545e+00 , 5.3647640000000001e+00 , 1.6397000000000000e-01 , 5.4940800000000001e-01 , 8.1930800000000004e-01 -3.1665117553670519e-01 , 3.1135021234506399e+00 , 5.4183760000000003e+00 , 1.6397000000000000e-01 , 5.4940800000000001e-01 , 8.1930800000000004e-01 -6.3326019042136816e-01 , 3.0181058503779288e+00 , 5.1442215999999998e+00 , 3.6231900000000000e-01 , -4.2490299999999998e-01 , -8.2956799999999997e-01 -6.1785959001441926e-01 , 3.0335647726244983e+00 , 5.2387367999999999e+00 , -9.6616400000000002e-01 , -2.5069599999999997e-01 , -6.0660100000000002e-02 -4.9560430429971181e-01 , 3.0871166693910483e+00 , 5.4679111999999996e+00 , -5.7368399999999997e-01 , -6.9689599999999996e-01 , -4.3037500000000001e-01 -6.7619520283097989e-01 , 3.0341205482953573e+00 , 5.3277087999999999e+00 , -2.1557799999999999e-01 , -9.3740900000000005e-01 , -2.7347700000000003e-01 -7.1629098981523454e-01 , 3.0313715546116105e+00 , 5.3595120000000005e+00 , -2.8901700000000002e-01 , -7.5795699999999999e-01 , 5.8478200000000002e-01 -7.8120101917899065e-01 , 3.0187222426314775e+00 , 5.3580248000000008e+00 , -1.1849200000000000e-01 , 9.6799299999999999e-01 , 2.2124400000000000e-01 -7.9151502115747330e-01 , 3.0262885407162647e+00 , 5.4293999999999993e+00 , 8.3459200000000000e-01 , -1.7734500000000000e-01 , -5.2154100000000003e-01 -7.4791394217506069e-01 , 3.0553545281304748e+00 , 5.5854520000000001e+00 , 2.7816400000000002e-01 , -8.4842700000000004e-01 , 4.5032899999999998e-01 -8.3069379443527591e-01 , 3.0353659043052450e+00 , 5.5565815999999995e+00 , -8.8042699999999996e-01 , 4.7347000000000000e-01 , -2.5974600000000000e-02 -8.0975013160718112e-01 , 3.0576386121141637e+00 , 5.6890152000000000e+00 , -7.0811999999999997e-01 , 6.7332400000000003e-01 , 2.1260699999999999e-01 -8.1883396397871788e-01 , 3.0680541074785630e+00 , 5.7795471999999997e+00 , 4.6501100000000001e-01 , -7.9202499999999998e-01 , -3.9555099999999999e-01 -7.4947198453252062e-01 , 3.1114339175058059e+00 , 6.0117063999999996e+00 , 1.5258700000000000e-01 , -6.7952900000000005e-01 , 7.1760500000000005e-01 -9.1529318835176898e-01 , 3.0575873589160416e+00 , 5.8377663999999996e+00 , -6.3865600000000000e-01 , 1.4211699999999999e-01 , 7.5625500000000001e-01 -9.3481718567123795e-01 , 3.0647179147781713e+00 , 5.9195207999999999e+00 , -8.4114000000000000e-01 , -3.9432600000000001e-01 , 3.7012200000000001e-01 -1.0405721622724320e+00 , 3.0342014883979642e+00 , 5.8380159999999997e+00 , 1.3441000000000000e-01 , -1.3390700000000000e-01 , 9.8183600000000004e-01 -6.4049838695153460e-01 , 3.2336181558031889e+00 , 6.7793304000000001e+00 , -5.3393900000000005e-01 , -6.7542300000000000e-01 , 5.0863800000000003e-01 -7.5307850917665098e-01 , 3.2032649296762097e+00 , 6.7106800000000000e+00 , 5.6124099999999999e-01 , -6.6488800000000003e-01 , -4.9288199999999999e-01 -7.8337285663596190e-01 , 3.2115069796749021e+00 , 6.8160216000000000e+00 , 2.4407599999999999e-01 , -1.9019800000000001e-01 , -9.5092100000000002e-01 -9.7307885640132885e-01 , 3.1412578378967408e+00 , 6.5552832000000008e+00 , -4.3315799999999999e-01 , -5.5541600000000002e-01 , -7.0985100000000001e-01 -1.0378317608312577e+00 , 3.1313781174483633e+00 , 6.5727656000000003e+00 , -3.5926999999999998e-01 , -4.2916300000000002e-01 , -8.2870100000000002e-01 -1.1177096209488941e+00 , 3.1139846878890816e+00 , 6.5509256000000002e+00 , 3.7985799999999997e-01 , 1.0108900000000000e-01 , 9.1950500000000002e-01 -1.1957128239519479e+00 , 3.0962961387114358e+00 , 6.5272135999999996e+00 , 4.0986299999999998e-01 , 3.2533000000000001e-01 , 8.5215799999999997e-01 -1.0302545043019971e+00 , 3.2171643624004771e+00 , 7.2077375999999997e+00 , -1.2159100000000000e-01 , -6.3499200000000000e-01 , 7.6288999999999996e-01 -1.1088286637837106e+00 , 3.2034435350383168e+00 , 7.2143831999999994e+00 , -2.1950200000000000e-01 , -6.7152199999999995e-01 , 7.0772599999999997e-01 -1.1984936438793876e+00 , 3.1821234340563360e+00 , 7.1803960000000009e+00 , -3.3365699999999998e-01 , 6.0531500000000005e-01 , -7.2267999999999999e-01 -6.8410032218406158e-01 , 3.5523238175981504e+00 , 9.2506823999999988e+00 , -7.6873700000000000e-01 , -2.3880799999999999e-01 , -5.9330799999999995e-01 -1.4457224488088349e+00 , 3.0901190531192579e+00 , 6.8397543999999995e+00 , 1.1874000000000000e-01 , -5.8333800000000002e-01 , 8.0350299999999997e-01 -1.5136328670510069e+00 , 3.0793831675256578e+00 , 6.8483656000000002e+00 , -6.6757199999999996e-04 , -5.9491000000000005e-01 , 8.0379199999999995e-01 -1.5727356968511628e+00 , 3.0747250346408856e+00 , 6.8958520000000005e+00 , -3.9073099999999999e-01 , -8.1698400000000004e-01 , -4.2410700000000001e-01 -1.5229120532813925e+00 , 3.1584948232761239e+00 , 7.4643680000000003e+00 , -6.3027299999999997e-01 , 3.2595700000000000e-01 , 7.0463299999999995e-01 -1.6399613011312881e+00 , 3.1111777273684744e+00 , 7.2702936000000005e+00 , -7.1501000000000003e-01 , 3.2857100000000000e-01 , -6.1709099999999995e-01 -1.7236703512851106e+00 , 3.0899555170669419e+00 , 7.2250016000000006e+00 , -5.3092499999999998e-01 , -6.9731100000000001e-01 , 4.8153499999999999e-01 -1.5059159772242474e+00 , 3.3754084552171792e+00 , 9.0749431999999999e+00 , -5.9221699999999999e-01 , -7.8952800000000001e-01 , 1.6101099999999999e-01 -1.6090338307124261e+00 , 3.3597335557748185e+00 , 9.1034912000000006e+00 , 4.1648700000000000e-01 , 8.8992599999999999e-01 , -1.8593199999999999e-01 --7.9055314005388588e-01 , 2.7859485187364625e+00 , 5.5226799999999998e-01 , -6.5088199999999999e-02 , 9.9997100000000005e-02 , 9.9285699999999999e-01 --9.2272299283298587e-01 , 2.8136571503856618e+00 , 5.4037040000000003e-01 , -6.5088199999999999e-02 , 9.9997100000000005e-02 , 9.9285699999999999e-01 --1.0737592872832704e+00 , 2.8437172719344335e+00 , 5.2030880000000002e-01 , -8.8685399999999998e-02 , 1.0414100000000000e-01 , 9.9060099999999995e-01 --1.2340164161474667e+00 , 2.8760255091188478e+00 , 4.9891600000000014e-01 , -8.7842400000000001e-02 , 1.2368899999999999e-01 , 9.8842500000000000e-01 --1.4133325484671317e+00 , 2.9110069938122756e+00 , 4.7087759999999990e-01 , 9.5595399999999997e-02 , -1.2818900000000000e-01 , -9.8713200000000001e-01 --1.6030777663550331e+00 , 2.9485434687542940e+00 , 4.4278719999999994e-01 , 8.7459499999999996e-02 , -1.4219399999999999e-01 , -9.8596700000000004e-01 --1.8032910506453526e+00 , 2.9887225358545084e+00 , 4.1505039999999993e-01 , 1.0930300000000000e-01 , -1.3284899999999999e-01 , -9.8509100000000005e-01 --2.0501412560813437e+00 , 3.0363838232971410e+00 , 3.6702319999999977e-01 , 1.1891200000000000e-01 , -1.2827700000000000e-01 , -9.8458400000000001e-01 --2.2814402745531330e+00 , 3.0828149329946966e+00 , 3.3733119999999994e-01 , -8.7826600000000005e-02 , 1.0100600000000000e-01 , 9.9100200000000005e-01 --2.5420901922740562e+00 , 3.1342686366662091e+00 , 2.9993280000000011e-01 , -1.0017100000000000e-01 , 7.3603500000000002e-02 , 9.9224400000000001e-01 --2.8224064211526594e+00 , 3.1905539581381435e+00 , 2.6124479999999983e-01 , -1.1461100000000000e-01 , 8.4226899999999993e-02 , 9.8983299999999996e-01 --3.1344335857386731e+00 , 3.2535057753072527e+00 , 2.1723200000000009e-01 , -1.0711400000000000e-01 , 8.2768300000000003e-02 , 9.9079600000000001e-01 --3.4753360347886924e+00 , 3.3213325332885892e+00 , 1.7020320000000000e-01 , -9.9827899999999997e-02 , 8.4666000000000005e-02 , 9.9139600000000005e-01 --3.8483386754367706e+00 , 3.3964896875708037e+00 , 1.2107360000000011e-01 , -1.1302900000000000e-01 , 5.4590399999999997e-02 , 9.9209099999999995e-01 --4.2515752726515812e+00 , 3.4781988866087366e+00 , 7.1631999999999918e-02 , 7.2019399999999997e-02 , 2.1641199999999999e-02 , -9.9716800000000005e-01 --4.5075605668973751e+00 , 3.5374744238143552e+00 , 1.0040879999999985e-01 , -2.7165999999999999e-02 , -2.2773399999999999e-02 , 9.9937100000000001e-01 --4.8490740748183292e+00 , 3.6120323585261200e+00 , 1.0247839999999986e-01 , -8.6676600000000006e-02 , -7.1631700000000006e-02 , 9.9365800000000004e-01 --5.3845350626143658e+00 , 3.7204628736466070e+00 , 4.1544800000000048e-02 , -1.4970400000000000e-01 , -3.0924400000000001e-02 , 9.8824699999999999e-01 --6.0581929499360818e+00 , 3.8550300972646983e+00 , -5.0911199999999823e-02 , 1.3933000000000001e-01 , -1.6195200000000000e-02 , -9.9011400000000005e-01 --6.9019820885779879e+00 , 4.0228221434500648e+00 , -1.7818639999999997e-01 , 1.0837300000000000e-01 , -4.1839500000000002e-02 , -9.9322999999999995e-01 --7.7904974577659107e+00 , 4.2021765364847621e+00 , -2.8918560000000015e-01 , -1.2191700000000000e-01 , 5.9073199999999999e-02 , 9.9078100000000002e-01 --8.9675739827330574e+00 , 4.4365587710021099e+00 , -4.5743679999999998e-01 , 1.2882500000000000e-01 , -7.8987299999999996e-02 , -9.8851699999999998e-01 --1.0398761252492982e+01 , 4.7223301555250838e+00 , -6.5673199999999987e-01 , -1.2161000000000000e-01 , 8.2076700000000002e-02 , 9.8917900000000003e-01 --1.2115907674284085e+01 , 5.0672541404345948e+00 , -8.8175679999999979e-01 , 1.0902800000000000e-01 , -9.3983499999999998e-02 , 9.8958599999999997e-01 --1.2398858772698713e+01 , 5.1899852868177163e+00 , -4.0670560000000000e-01 , 1.0902800000000000e-01 , -9.3983499999999998e-02 , 9.8958599999999997e-01 --1.2448812302341350e+01 , 5.2343493807253125e+00 , -1.4445920000000001e-01 , -1.4995500000000000e-01 , -9.8235099999999997e-01 , 1.1180500000000000e-01 --1.2495685981522804e+01 , 5.2787010997900135e+00 , 1.1835920000000000e-01 , 6.9094999999999995e-01 , 7.2278100000000001e-01 , 1.3249600000000000e-02 --4.0121951644119846e+01 , 1.0689479110530703e+01 , -4.5820040000000004e+00 , -6.9726800000000000e-01 , 3.3078800000000003e-01 , 6.3592199999999999e-01 --4.0207549157863973e+01 , 1.0804983915802280e+01 , -3.8267040000000003e+00 , -6.9726800000000000e-01 , 3.3078800000000003e-01 , 6.3592199999999999e-01 --1.3677032748257373e+01 , 5.6177493195016357e+00 , 7.5861439999999991e-01 , 6.4929999999999999e-01 , 7.0148400000000000e-01 , -2.9382000000000003e-01 --1.2604444673814710e+01 , 5.4393638414284986e+00 , 1.1825204800000000e+00 , 9.8756500000000003e-01 , 1.5634600000000001e-01 , 1.6467800000000001e-02 --1.2626724275569753e+01 , 5.4780788912902363e+00 , 1.4489830399999999e+00 , 9.8736100000000004e-01 , 1.5842100000000001e-01 , 4.7028800000000004e-03 --1.2635552241353327e+01 , 5.5142998529556015e+00 , 1.7164772799999999e+00 , 9.8794400000000004e-01 , 1.5441800000000000e-01 , 1.1086100000000000e-02 --1.2659860061846755e+01 , 5.5541212104550581e+00 , 1.9826858720000000e+00 , 9.8710200000000003e-01 , 1.5932800000000000e-01 , 1.5628199999999998e-02 --1.2668688027630331e+01 , 5.5903421721204261e+00 , 2.2501803200000001e+00 , 9.8714599999999997e-01 , 1.5878800000000001e-01 , 1.8124800000000000e-02 --1.2704467483155556e+01 , 5.6328361418733035e+00 , 2.5166200000000001e+00 , 9.8714599999999997e-01 , 1.5878800000000001e-01 , 1.8124800000000000e-02 --4.7424982254539159e+01 , 1.3252814962045782e+01 , 2.9935858400000002e+00 , -2.7239000000000002e-01 , 1.0718600000000000e-01 , 9.5619799999999999e-01 --4.3545391097837360e+01 , 1.2618788422228125e+01 , 4.6326040000000006e+00 , 9.5031900000000002e-01 , -2.4094399999999999e-01 , -1.9707700000000000e-01 --1.1899160245604069e+01 , 5.6249903993440924e+00 , 3.8195424000000000e+00 , -9.3517200000000000e-01 , 3.5412300000000002e-01 , -7.0150899999999999e-03 --1.1857282842483166e+01 , 5.6476881998368551e+00 , 4.0729280000000001e+00 , -9.7863199999999995e-01 , -1.2472400000000000e-02 , 2.0524000000000001e-01 --1.1639200116734367e+01 , 5.6308582709417649e+00 , 4.3100376000000002e+00 , 9.7507699999999997e-01 , -9.2418600000000004e-02 , -2.0170299999999999e-01 --1.0228038432485276e+01 , 5.3375044733049943e+00 , 4.4146824000000002e+00 , -6.1787300000000001e-01 , 7.5114599999999998e-01 , -2.3240600000000000e-01 --1.1515015324685928e+01 , 5.6673542706420843e+00 , 4.8022488000000001e+00 , -5.5111100000000002e-01 , 3.2753599999999999e-01 , 7.6746099999999995e-01 --1.0534059543943437e+01 , 5.4688235015091102e+00 , 4.9168880000000001e+00 , 3.7618200000000002e-01 , -4.1194300000000000e-01 , 8.2993399999999995e-01 --1.0463857372207247e+01 , 5.4826615598470063e+00 , 5.1428384000000005e+00 , -4.7854799999999997e-01 , 5.2230399999999999e-01 , -7.0582599999999995e-01 --2.4800550888039217e+00 , 3.5915302989089226e+00 , 3.9582679999999999e+00 , -5.7063799999999998e-01 , 3.1719900000000001e-01 , -7.5746800000000003e-01 --2.5018313757837634e+00 , 3.6084982478365797e+00 , 4.0536463999999999e+00 , 5.3630999999999995e-01 , -4.8271999999999998e-01 , 6.9235300000000000e-01 --2.4520756731202553e+00 , 3.6079833156268570e+00 , 4.1355152000000004e+00 , 5.3630999999999995e-01 , -4.8271999999999998e-01 , 6.9235300000000000e-01 --2.6576339502547759e+00 , 3.6705515900979337e+00 , 4.2757072000000003e+00 , 7.7363400000000004e-01 , -3.5676099999999999e-01 , 5.2365200000000001e-01 --3.6723414320581398e+00 , 3.9372746368252018e+00 , 4.6294111999999998e+00 , 9.8887599999999998e-01 , 5.8700099999999998e-02 , -1.3667099999999999e-01 --7.8531472432828746e+00 , 5.0091745781678121e+00 , 5.8848056000000000e+00 , 3.2429799999999998e-01 , -4.0058700000000003e-01 , 8.5694800000000004e-01 --7.6625594406562048e+00 , 4.9864315836627293e+00 , 6.0286999999999997e+00 , 3.5244700000000001e-01 , -5.2834400000000004e-01 , 7.7242100000000002e-01 --8.0109964222442098e+00 , 5.1013211846240019e+00 , 6.3348447999999999e+00 , -9.0938099999999994e-02 , 4.7364099999999998e-01 , -8.7600999999999996e-01 --3.5390360309196893e+00 , 3.9645834905711346e+00 , 5.0621656000000002e+00 , -7.6332599999999995e-01 , -4.5456000000000002e-01 , 4.5903100000000002e-01 --2.6914258587305699e+00 , 3.7565312429725726e+00 , 4.8849912000000000e+00 , -8.4595299999999995e-01 , 4.1656199999999999e-01 , -3.3292600000000000e-01 --2.7797799454532273e+00 , 3.7933446121186494e+00 , 5.0225208000000006e+00 , 7.4095800000000001e-01 , -4.3397599999999997e-01 , 5.1249100000000003e-01 --2.9409238774310342e+00 , 3.8505481165946129e+00 , 5.1929976000000000e+00 , 9.8332799999999998e-01 , 1.6186900000000001e-01 , 8.2854899999999995e-02 --2.8913695647088122e+00 , 3.8521783345641438e+00 , 5.2854120000000009e+00 , -8.2154499999999997e-01 , -4.9484099999999998e-01 , -2.8318900000000002e-01 --2.7855985036721487e+00 , 3.8378052966452403e+00 , 5.3525960000000001e+00 , -8.8576100000000002e-01 , -4.5282099999999997e-01 , 1.0188899999999999e-01 --3.0182865736881466e+00 , 3.9163730374364176e+00 , 5.5716928000000001e+00 , 9.6949900000000000e-01 , 2.1601799999999999e-01 , 1.1579600000000000e-01 --2.7534558068354862e+00 , 3.8580098098060756e+00 , 5.5651512000000007e+00 , 1.6318500000000000e-01 , 8.5591899999999999e-01 , -4.9068699999999998e-01 --2.5095684651114425e+00 , 3.8038160782462365e+00 , 5.5590256000000000e+00 , 5.5050200000000005e-01 , 6.9166700000000003e-01 , -4.6748800000000001e-01 --2.2044921089892080e+00 , 3.7313905042162059e+00 , 5.5123400000000000e+00 , -9.4626800000000000e-01 , 2.5686100000000001e-01 , 1.9646700000000000e-01 --2.0798088413278695e+00 , 3.7096241679950803e+00 , 5.5521720000000006e+00 , 7.6176600000000005e-01 , 3.3167600000000003e-01 , -5.5650999999999995e-01 --2.1572587912100021e+00 , 3.7455175155310103e+00 , 5.7032424000000006e+00 , -9.3040000000000000e-01 , 3.6244100000000001e-01 , -5.4700400000000003e-02 --2.2477927716962407e+00 , 3.7868551915609632e+00 , 5.8680096000000006e+00 , -7.3236299999999999e-01 , -3.8926500000000003e-01 , 5.5867500000000003e-01 --2.1634141667053832e+00 , 3.7767728571191430e+00 , 5.9308151999999996e+00 , -7.0882100000000003e-01 , -5.0888699999999998e-01 , 4.8847400000000002e-01 --1.9411402000223155e+00 , 3.7247664108854792e+00 , 5.9045864000000003e+00 , 5.7318899999999995e-01 , 6.8575100000000000e-01 , -4.4855299999999998e-01 --1.9658885214667308e+00 , 3.7465543873588452e+00 , 6.0337855999999999e+00 , -8.6168100000000003e-01 , -4.6224999999999999e-01 , 2.0935699999999999e-01 --2.1106931476428192e+00 , 3.8061256074591849e+00 , 6.2511352000000002e+00 , -9.0500999999999998e-01 , -1.6689200000000001e-01 , -3.9128499999999999e-01 --2.0456157123491892e+00 , 3.8016386577153813e+00 , 6.3270863999999998e+00 , -8.5810399999999998e-01 , -6.4019499999999998e-04 , -5.1347500000000001e-01 --2.8020331585008549e+00 , 4.0552996413588929e+00 , 7.0189151999999995e+00 , 7.2880800000000001e-01 , -1.1477000000000000e-01 , 6.7503100000000005e-01 --4.7606241692708506e+00 , 4.6966748793286195e+00 , 8.6933983999999995e+00 , -1.1289100000000001e-01 , -6.2705999999999995e-01 , 7.7074699999999996e-01 --5.1542983145069705e+00 , 4.8509315639587856e+00 , 9.2222176000000005e+00 , -1.2153600000000001e-01 , 9.0253700000000003e-01 , -4.1310500000000000e-01 --5.1208750398178990e+00 , 4.8689019549645183e+00 , 9.4239567999999991e+00 , -9.7291000000000002e-02 , 8.1027400000000005e-01 , -5.7791899999999996e-01 --7.7950800055895062e+00 , 5.7807835650994717e+00 , 1.1982741599999999e+01 , 7.4875300000000006e-02 , -2.7088000000000001e-01 , 9.5969700000000002e-01 --7.4554382572115507e+00 , 5.7091251668563849e+00 , 1.2005184800000000e+01 , 7.4875300000000006e-02 , -2.7088000000000001e-01 , 9.5969700000000002e-01 --2.4993913208219034e+00 , 4.0773324826479289e+00 , 7.7040568000000009e+00 , -2.3930199999999999e-02 , 7.4291499999999996e-02 , 9.9694899999999997e-01 --2.2142378222638399e+00 , 4.0009532376455290e+00 , 7.5966248000000007e+00 , 3.7593500000000002e-01 , 2.8263500000000003e-01 , 8.8249100000000003e-01 --7.8307330839606468e+00 , 5.9697527953196889e+00 , 1.3397984000000001e+01 , -1.2680400000000000e-01 , -4.8236000000000001e-01 , 8.6674700000000005e-01 --1.7776204665021118e+00 , 3.8916717617347603e+00 , 7.4794168000000001e+00 , -4.5410800000000001e-01 , 4.0528300000000000e-01 , 7.9342999999999997e-01 -3.4803905499493348e-01 , 3.1541293725654360e+00 , 5.3474064000000006e+00 , 1.9525600000000001e-01 , 4.3139499999999997e-01 , 8.8078000000000001e-01 -3.7513057404057548e-01 , 3.1551748668024464e+00 , 5.4005191999999997e+00 , 1.9525600000000001e-01 , 4.3139400000000000e-01 , 8.8078000000000001e-01 -6.2835462665272113e-01 , 3.0738194275608000e+00 , 5.1930703999999999e+00 , 3.6231999999999998e-01 , -4.2490200000000000e-01 , -8.2956799999999997e-01 -6.4566884552400694e-01 , 3.0769790131914192e+00 , 5.2493031999999999e+00 , -5.3216599999999998e-03 , 9.9500900000000003e-01 , 9.9643399999999993e-02 -7.2869770885799356e-01 , 3.0561388868708677e+00 , 5.2268392000000006e+00 , -8.8171500000000003e-01 , -5.0662300000000000e-02 , 4.6905400000000003e-01 -7.8523544131861778e-01 , 3.0445408110009455e+00 , 5.2340776000000000e+00 , -6.9394900000000004e-01 , 1.8795200000000001e-01 , 6.9506000000000001e-01 -6.9667870778083318e-01 , 3.0898553784137790e+00 , 5.4348183999999993e+00 , -1.5770500000000001e-01 , -9.8713700000000004e-01 , -2.6245899999999999e-02 --1.4888783898329594e-01 , 3.4365476008545279e+00 , 6.7011224000000000e+00 , -7.7432999999999996e-01 , -5.7851799999999998e-01 , 2.5637799999999999e-01 --3.9190249844440750e-03 , 3.3961634640708067e+00 , 6.6317336000000005e+00 , 8.8477799999999995e-01 , 3.3524399999999999e-01 , -3.2369700000000001e-01 -8.1711596488501392e-01 , 3.0765240282547941e+00 , 5.5366447999999995e+00 , 1.4018200000000000e-01 , 5.1139100000000004e-01 , -8.4783799999999998e-01 -8.5534431527246557e-01 , 3.0730569176646032e+00 , 5.5750104000000000e+00 , -9.7951600000000005e-01 , 1.1186099999999999e-02 , 2.0105500000000001e-01 -8.4580690510191125e-01 , 3.0903516703754166e+00 , 5.6904608000000003e+00 , 6.2337299999999995e-01 , -7.1449799999999997e-01 , -3.1764500000000001e-01 -6.3803202639941992e-01 , 3.1946408137898223e+00 , 6.1479360000000005e+00 , 9.7397599999999995e-01 , -1.0261000000000001e-01 , 2.0209500000000000e-01 -9.0777916561080230e-01 , 3.0909018243500030e+00 , 5.8012416000000000e+00 , -1.9526199999999999e-01 , 8.6744100000000002e-01 , 4.5762199999999997e-01 -5.1880359439158075e-01 , 3.2826252111265779e+00 , 6.6329919999999998e+00 , -8.1019799999999997e-01 , -3.5760100000000000e-01 , 4.6443600000000002e-01 -9.2365180061571661e-01 , 3.1142600392835282e+00 , 6.0101671999999997e+00 , -3.5158099999999998e-01 , 7.0020000000000004e-01 , -6.2137900000000001e-01 -6.3463664383359952e-01 , 3.2688168374003643e+00 , 6.7209136000000003e+00 , -6.9346600000000003e-01 , -6.2157899999999999e-01 , 3.6434200000000000e-01 -6.5945829716524673e-01 , 3.2783901678952088e+00 , 6.8369879999999998e+00 , -8.6988700000000002e-02 , -3.6928600000000000e-01 , 9.2523599999999995e-01 -7.7519918716528058e-01 , 3.2427988768271048e+00 , 6.7587800000000007e+00 , -5.0556000000000001e-01 , 7.7477600000000002e-01 , 3.7964599999999998e-01 -8.9242786499094140e-01 , 3.2056839931561321e+00 , 6.6681336000000009e+00 , 5.5631900000000001e-01 , -8.1562100000000004e-01 , -1.5897100000000000e-01 -1.0100845364692428e+00 , 3.1671278086394992e+00 , 6.5651008000000006e+00 , 2.4936300000000000e-01 , 2.6372899999999999e-01 , 9.3180799999999997e-01 -1.0780414516468881e+00 , 3.1530268838133502e+00 , 6.5728175999999996e+00 , 1.3294600000000001e-01 , 1.9681899999999999e-01 , 9.7138400000000003e-01 -1.1708360248056435e+00 , 3.1251253464408899e+00 , 6.5121232000000004e+00 , 4.7581200000000001e-01 , 9.9868999999999999e-02 , 8.7385900000000005e-01 -1.1661208740139388e+00 , 3.1531496100660323e+00 , 6.7187295999999996e+00 , -9.6570100000000003e-01 , 2.1399699999999999e-01 , 1.4706200000000000e-01 -1.0681031725435040e+00 , 3.2396609662940512e+00 , 7.2273312000000001e+00 , -2.1950200000000000e-01 , -6.7152299999999998e-01 , 7.0772599999999997e-01 -1.1499182298235171e+00 , 3.2216521312615400e+00 , 7.2239199999999997e+00 , -2.6382000000000000e-01 , 7.3631300000000000e-01 , -6.2309099999999995e-01 -5.7060499796342334e-01 , 3.6345304367302727e+00 , 9.4552920000000000e+00 , 7.1809199999999995e-01 , 6.8311299999999997e-01 , 1.3304400000000000e-01 -7.8419413911845082e-01 , 3.5442067890688804e+00 , 9.1157840000000014e+00 , -8.2528299999999999e-01 , 1.4531200000000000e-01 , -5.4570300000000005e-01 -1.4816787733602785e+00 , 3.1007079449059205e+00 , 6.8472528000000006e+00 , -6.7146600000000001e-02 , -2.6100299999999999e-01 , 9.6299999999999997e-01 -1.5540246619211007e+00 , 3.0835810566787751e+00 , 6.8356984000000001e+00 , 1.3193000000000000e-02 , -8.2834399999999997e-01 , 5.6006500000000004e-01 -1.5975073700395652e+00 , 3.0893923766970515e+00 , 6.9528335999999999e+00 , -8.9767900000000000e-01 , 1.1700900000000000e-01 , 4.2483199999999999e-01 -1.5562633438680042e+00 , 3.1688633827309074e+00 , 7.5018600000000006e+00 , 5.1179399999999997e-01 , -8.4971600000000003e-01 , -1.2668399999999999e-01 -1.6961903342561622e+00 , 3.0961744449892130e+00 , 7.1762151999999997e+00 , 8.1427600000000003e-02 , -5.3019700000000003e-01 , 8.4395600000000004e-01 -1.7755861316606014e+00 , 3.0738550530659605e+00 , 7.1403767999999994e+00 , -8.3829799999999996e-02 , -7.6180800000000004e-01 , 6.4235600000000004e-01 -1.5732611955415712e+00 , 3.3569283121798112e+00 , 8.9923047999999994e+00 , -3.1356499999999998e-01 , 1.5547100000000000e-01 , 9.3675299999999995e-01 -1.7686334657303422e+00 , 3.2242965861678856e+00 , 8.2966800000000003e+00 , -1.7376099999999998e-02 , -8.1728800000000001e-01 , 5.7596700000000001e-01 --7.0617659648385223e-01 , 2.8729824339565324e+00 , 5.4370879999999988e-01 , -5.1961599999999997e-02 , 1.0939699999999999e-01 , 9.9263900000000005e-01 --8.2074529917097960e-01 , 2.9009694229297791e+00 , 5.4227360000000013e-01 , -5.1961599999999997e-02 , 1.0939699999999999e-01 , 9.9263900000000005e-01 --9.6923386251143606e-01 , 2.9356314318774346e+00 , 5.1920639999999985e-01 , -9.3067499999999997e-02 , 1.2409400000000000e-01 , 9.8789600000000000e-01 --1.1269854011016869e+00 , 2.9714930847396310e+00 , 4.9491199999999980e-01 , -9.8016300000000001e-02 , 1.3321500000000000e-01 , 9.8622799999999999e-01 --1.2960895660601546e+00 , 3.0097543514340233e+00 , 4.6953599999999995e-01 , -8.3354399999999995e-02 , 1.4410899999999999e-01 , 9.8604499999999995e-01 --1.4668065353984643e+00 , 3.0501611715843699e+00 , 4.4919359999999986e-01 , -9.2602599999999993e-02 , 1.4160700000000001e-01 , 9.8558199999999996e-01 --1.6556487746998534e+00 , 3.0933986818211663e+00 , 4.2323520000000014e-01 , -7.8597700000000006e-02 , 1.0553899999999999e-01 , 9.9130399999999996e-01 --1.8647250885141093e+00 , 3.1417559564400142e+00 , 3.9202479999999995e-01 , -1.3879700000000000e-01 , 8.7152199999999999e-02 , 9.8647899999999999e-01 --2.1194521183405621e+00 , 3.1987504022377702e+00 , 3.4124160000000003e-01 , -1.3700399999999999e-01 , 7.4476200000000006e-02 , 9.8776699999999995e-01 --2.3674144985215682e+00 , 3.2560337349586446e+00 , 3.0382239999999983e-01 , 8.3767900000000006e-02 , -3.7997499999999997e-02 , -9.9576100000000001e-01 --2.6008569380763564e+00 , 3.3109970894616993e+00 , 2.8440559999999993e-01 , -1.1809600000000001e-01 , 2.6617800000000000e-02 , 9.9264600000000003e-01 --2.8901382781082932e+00 , 3.3778487414266847e+00 , 2.4355439999999984e-01 , -1.2974100000000000e-01 , 3.0178400000000001e-02 , 9.9108900000000000e-01 --3.1815847559584363e+00 , 3.4466915372207714e+00 , 2.1208399999999994e-01 , -1.2074300000000000e-01 , 2.1408799999999999e-02 , 9.9245300000000003e-01 --3.5127137057803539e+00 , 3.5240442751327148e+00 , 1.7225200000000007e-01 , -1.1376500000000001e-01 , 2.4680100000000000e-02 , 9.9320100000000000e-01 --3.8550987303836006e+00 , 3.6043149404798660e+00 , 1.3925279999999995e-01 , -1.0631200000000000e-01 , -6.3946200000000002e-03 , 9.9431199999999997e-01 --4.2097571875533912e+00 , 3.6896955090506101e+00 , 1.1315919999999990e-01 , 5.9456799999999997e-02 , 2.3425900000000000e-02 , -9.9795599999999995e-01 --4.5668853202985487e+00 , 3.7765279700114567e+00 , 9.8983999999999961e-02 , 4.5695699999999999e-02 , 4.2599199999999997e-02 , -9.9804700000000002e-01 --5.0020704287135063e+00 , 3.8809425761748768e+00 , 6.5891199999999817e-02 , 1.0394800000000000e-01 , 1.1200800000000001e-03 , -9.9458199999999997e-01 --5.5737466882125091e+00 , 4.0136011761449799e+00 , -3.7783999999998485e-03 , -1.1905200000000001e-01 , -6.3988099999999996e-03 , 9.9286700000000006e-01 --6.3117099242939840e+00 , 4.1835534441870372e+00 , -1.1347759999999996e-01 , 1.1891000000000000e-01 , -4.7963499999999999e-02 , -9.9174600000000002e-01 --7.1319327185047108e+00 , 4.3738120353758330e+00 , -2.2434160000000025e-01 , -1.0171500000000000e-01 , 5.8878899999999998e-02 , 9.9307000000000001e-01 --8.1624969523419342e+00 , 4.6110784605144541e+00 , -3.7334239999999985e-01 , -9.6638000000000002e-02 , 1.3392000000000001e-01 , 9.8626899999999995e-01 --9.4912928316415197e+00 , 4.9161624401711421e+00 , -5.7611120000000016e-01 , 1.1831999999999999e-01 , -1.0834500000000000e-01 , -9.8704700000000001e-01 --1.1092935386822028e+01 , 5.2843941027427999e+00 , -8.0836400000000008e-01 , 1.0325300000000000e-01 , -2.3969600000000001e-02 , 9.9436599999999997e-01 --1.2802360532411246e+01 , 5.6844077948177540e+00 , -1.0112576000000000e+00 , -2.5353500000000001e-01 , 3.7584499999999998e-01 , 8.9132500000000003e-01 --2.1894423971278599e+01 , 7.7516594355345267e+00 , -2.5409312000000002e+00 , -6.2511700000000003e-02 , -3.9705000000000001e-01 , 9.1566599999999998e-01 --2.2004547787626095e+01 , 7.8326818649255534e+00 , -2.1149160000000000e+00 , -6.2511700000000003e-02 , -3.9705000000000001e-01 , 9.1566599999999998e-01 --4.0536307805850740e+01 , 1.2141503055447469e+01 , -4.4782431999999996e+00 , 9.1563000000000005e-01 , 1.3247600000000001e-01 , 3.7956800000000002e-01 --1.3741381114413318e+01 , 6.1089861028419108e+00 , 5.2683999999999975e-01 , 5.9079000000000004e-01 , 7.5640300000000005e-01 , -2.8075099999999997e-01 --1.3754057542565061e+01 , 6.1490111209265255e+00 , 8.1768639999999992e-01 , 7.3161900000000002e-01 , 4.5099400000000001e-01 , -5.1121200000000000e-01 --1.2806321818235292e+01 , 5.9641204390343150e+00 , 1.2247995999999999e+00 , 7.3658699999999999e-01 , 4.5620500000000003e-01 , -4.9931599999999998e-01 --1.2827110392060748e+01 , 6.0028087779769921e+00 , 1.4966764000000001e+00 , 9.8503900000000000e-01 , 1.7205599999999999e-01 , 9.7351199999999999e-03 --1.2843835655954869e+01 , 6.0413445304132960e+00 , 1.7687518400000000e+00 , 9.8529800000000001e-01 , 1.7025699999999999e-01 , 1.4167400000000000e-02 --1.2866760573925923e+01 , 6.0811490934605192e+00 , 2.0404760720000001e+00 , 9.8529800000000001e-01 , 1.7025699999999999e-01 , 1.4167400000000000e-02 --1.2883514067979815e+01 , 6.1187771438212044e+00 , 2.3132625600000001e+00 , 9.8529800000000001e-01 , 1.7025699999999999e-01 , 1.4167400000000000e-02 --4.2937267341833554e+01 , 1.3498875101181861e+01 , 1.6204832000000000e+00 , 8.6586900000000000e-01 , -4.7286099999999998e-01 , 1.6332099999999999e-01 --4.8614458095253653e+01 , 1.5113945289279357e+01 , 3.2602408000000000e+00 , -4.1936099999999998e-01 , -1.3999100000000000e-01 , 8.9696100000000001e-01 --4.3211238906739034e+01 , 1.3870982732223260e+01 , 4.0572656000000000e+00 , -9.4247099999999995e-01 , 3.3353500000000003e-01 , -2.2435299999999998e-02 --4.2338362194317334e+01 , 1.3752286543304313e+01 , 4.8401879999999995e+00 , -9.4359400000000004e-01 , 3.0212099999999997e-01 , 1.3547500000000001e-01 --4.2096453751002485e+01 , 1.3991163976572894e+01 , 7.2365144000000008e+00 , 8.7117500000000003e-01 , -3.6622600000000000e-01 , 3.2700499999999999e-01 --1.0270456720223237e+01 , 5.7425430657198149e+00 , 4.4976015999999994e+00 , 6.0733300000000001e-01 , -1.7317199999999999e-01 , 7.7534400000000003e-01 --9.7783245696693868e+00 , 5.6416604958800054e+00 , 4.6658216000000001e+00 , -5.9128700000000001e-01 , 8.0145699999999997e-01 , -8.9700799999999997e-02 --4.1825102739211157e+00 , 4.1761329989889528e+00 , 4.0617584000000004e+00 , 4.0120400000000001e-01 , -4.0026499999999998e-01 , 8.2390699999999994e-01 --4.1217836322306738e+00 , 4.1748919825504505e+00 , 4.1739328000000002e+00 , 6.6223100000000001e-01 , -5.1299099999999997e-01 , 5.4615899999999995e-01 --2.2905096046106745e+00 , 3.6925504507418490e+00 , 3.9572903999999998e+00 , 6.4978100000000005e-01 , -3.2649099999999998e-01 , 6.8643200000000004e-01 --2.3023426134998157e+00 , 3.7071089964216029e+00 , 4.0481344000000004e+00 , 5.2816300000000005e-01 , -4.2724299999999998e-01 , 7.3383100000000001e-01 --2.5768457705878109e+00 , 3.7938711036118056e+00 , 4.1988304000000003e+00 , 5.5118000000000000e-01 , -5.4603899999999997e-02 , 8.3259799999999995e-01 --2.4951482580390385e+00 , 3.7834044576856591e+00 , 4.2749687999999999e+00 , 5.5118000000000000e-01 , -5.4603800000000001e-02 , 8.3259799999999995e-01 --9.7058729024346331e+00 , 5.8208151861983577e+00 , 6.2503760000000002e+00 , 7.9262900000000003e-01 , -2.1940999999999999e-01 , -5.6885699999999995e-01 --7.8078166245257705e+00 , 5.3121754256685048e+00 , 5.9543504000000000e+00 , -2.3139199999999999e-01 , 5.4753799999999997e-01 , -8.0415099999999995e-01 --9.1358630793253823e+00 , 5.7171596466736432e+00 , 6.5532136000000003e+00 , -4.3679600000000002e-01 , -2.7923900000000001e-01 , 8.5512299999999997e-01 --4.0249283991527642e+00 , 4.2727642766458880e+00 , 5.1494736000000003e+00 , 5.8433199999999996e-01 , -8.1106299999999998e-01 , -2.7078600000000001e-02 --2.6660125496376246e+00 , 3.8936901341643084e+00 , 4.8175471999999999e+00 , 8.0103500000000005e-01 , -3.1099900000000003e-01 , 5.1149000000000000e-01 --3.0004241985797684e+00 , 4.0043024782087073e+00 , 5.0421975999999997e+00 , 8.2631100000000002e-01 , -2.0028299999999999e-01 , 5.2640100000000001e-01 --3.4688407662462106e+00 , 4.1572773855855347e+00 , 5.3326279999999997e+00 , -6.6450500000000001e-01 , -5.4263300000000003e-01 , 5.1379200000000003e-01 --3.0078239056950284e+00 , 4.0348386742345443e+00 , 5.2712680000000001e+00 , -9.5740000000000003e-01 , -2.7648600000000001e-01 , -8.3311099999999999e-02 --4.1391705994086214e+00 , 4.3899648639566209e+00 , 5.8649104000000003e+00 , 1.9796900000000001e-01 , -9.6534799999999998e-01 , 1.7003299999999999e-01 --3.1350363922956301e+00 , 4.1028466870831153e+00 , 5.5605752000000006e+00 , 6.3590400000000002e-01 , 6.5410299999999999e-01 , -4.0960400000000002e-01 --2.4525961050337051e+00 , 3.9088312506615246e+00 , 5.3650967999999999e+00 , -4.6671699999999999e-01 , -5.7906199999999997e-01 , 6.6847699999999999e-01 --2.7974133384042590e+00 , 4.0294208041385868e+00 , 5.6423711999999995e+00 , -2.6209500000000002e-01 , -6.7939499999999997e-01 , 6.8536799999999998e-01 --3.0267739556990261e+00 , 4.1154968744369160e+00 , 5.8783784000000008e+00 , 7.8123799999999999e-01 , 5.0995500000000005e-01 , -3.6001699999999998e-01 --2.5861772180204330e+00 , 3.9928662861766409e+00 , 5.7695319999999999e+00 , -7.3119999999999996e-01 , -5.0260800000000005e-01 , 4.6122800000000003e-01 --2.4582929918882650e+00 , 3.9660928740755210e+00 , 5.8167584000000003e+00 , -5.8458900000000003e-01 , -7.4175300000000000e-01 , 3.2872099999999999e-01 --2.4867162126426257e+00 , 3.9900434691518214e+00 , 5.9506376000000003e+00 , -5.0992199999999999e-01 , -6.3480099999999995e-01 , 5.8052300000000001e-01 --2.5539638188122940e+00 , 4.0266466590735916e+00 , 6.1127112000000006e+00 , 5.1235200000000003e-01 , 6.1570300000000000e-01 , -5.9867000000000004e-01 --2.1854965890635540e+00 , 3.9222479739645868e+00 , 6.0051752000000000e+00 , -8.6692800000000003e-01 , -1.6579600000000000e-01 , 4.7005200000000003e-01 --2.1408171345072580e+00 , 3.9223806561108079e+00 , 6.0944384000000005e+00 , 9.8263100000000003e-01 , 1.1345500000000000e-01 , -1.4684700000000001e-01 --2.0361122732484507e+00 , 3.9023265539435696e+00 , 6.1437448000000003e+00 , 9.9872899999999998e-01 , 5.0398300000000000e-02 , -1.8228799999999999e-04 --2.2670504652576051e+00 , 3.9950333822272688e+00 , 6.4281224000000003e+00 , -9.3389400000000000e-01 , 1.4089900000000000e-01 , -3.2861800000000002e-01 --2.6108770297967787e+00 , 4.1283771870953974e+00 , 6.8110607999999999e+00 , -2.7726000000000001e-01 , 7.2353900000000004e-01 , -6.3215399999999999e-01 --2.8304115159862233e+00 , 4.2217827093446569e+00 , 7.1223951999999997e+00 , 6.6639700000000002e-01 , -2.8165400000000002e-01 , 6.9035199999999997e-01 --5.2957841960216676e+00 , 5.0983415869968365e+00 , 9.2341879999999996e+00 , -1.2153600000000001e-01 , 9.0253700000000003e-01 , -4.1310500000000000e-01 --4.9528344961640567e+00 , 5.0064384299365088e+00 , 9.1832799999999999e+00 , -9.7291000000000002e-02 , 8.1027400000000005e-01 , -5.7791899999999996e-01 --4.8900211535013502e+00 , 5.0121783305503955e+00 , 9.3568975999999999e+00 , -1.3482900000000001e-02 , -8.9164399999999999e-01 , 4.5253700000000002e-01 --8.2789275885031408e+00 , 6.2584840959419585e+00 , 1.2595624000000001e+01 , -2.5471199999999999e-02 , -2.5225999999999998e-01 , 9.6732399999999996e-01 --4.1896927959884378e+00 , 4.8171305264541004e+00 , 9.1865144000000001e+00 , 1.8669500000000000e-01 , -1.4601100000000000e-01 , 9.7150700000000001e-01 --4.1174131545555648e+00 , 4.8187832182509611e+00 , 9.3418904000000005e+00 , 1.8669500000000000e-01 , -1.4601100000000000e-01 , 9.7150700000000001e-01 --1.9181204679377015e+00 , 4.0299404893926045e+00 , 7.3978496000000007e+00 , -4.5410800000000001e-01 , 4.0528300000000000e-01 , 7.9342999999999997e-01 --1.8054524676406469e+00 , 4.0073514895435007e+00 , 7.4415607999999995e+00 , -4.5410800000000001e-01 , 4.0528300000000000e-01 , 7.9342999999999997e-01 --1.7494754880310994e+00 , 4.0058798640910558e+00 , 7.5410367999999997e+00 , -4.5410800000000001e-01 , 4.0528300000000000e-01 , 7.9342999999999997e-01 --4.3143341706661564e-01 , 3.5179123375836694e+00 , 6.2540887999999999e+00 , 5.7914500000000002e-01 , 4.3365300000000001e-01 , -6.9031600000000004e-01 --4.0167431297830003e-01 , 3.5206127880980782e+00 , 6.3371120000000003e+00 , 6.5769200000000005e-01 , 1.9748299999999999e-01 , -7.2694000000000003e-01 --2.3377513408656014e-01 , 3.4688746882230395e+00 , 6.2584464000000004e+00 , 3.5085899999999998e-01 , 9.3542300000000000e-01 , 4.3386599999999997e-02 --2.2827474301886630e-01 , 3.4815774568859115e+00 , 6.3701008000000003e+00 , -6.8257800000000002e-01 , 5.3249700000000000e-01 , 5.0053300000000001e-01 --2.2079544485217406e-01 , 3.4933124832827165e+00 , 6.4826288000000005e+00 , 8.4563400000000000e-01 , -2.1205700000000000e-01 , -4.8983100000000002e-01 --1.6089188096995999e-01 , 3.4846675613530822e+00 , 6.5315608000000003e+00 , -9.3233699999999997e-01 , -2.6418799999999998e-01 , 2.4688499999999999e-01 --1.3590312269628768e-01 , 3.4903803363932866e+00 , 6.6284679999999998e+00 , -8.6153000000000002e-01 , -3.9301599999999998e-01 , 3.2140999999999997e-01 --1.4290290052007482e-01 , 3.5106725892602704e+00 , 6.7751391999999999e+00 , -8.4578100000000001e-01 , -5.0697999999999999e-01 , 1.6621100000000000e-01 -7.9325637972217300e-01 , 3.1235778031975414e+00 , 5.5332024000000004e+00 , -8.5023199999999999e-01 , -2.6362099999999999e-01 , 4.5564100000000002e-01 -7.9819112610704135e-01 , 3.1330142873824185e+00 , 5.6232351999999999e+00 , 9.3081499999999995e-01 , 1.1341700000000000e-01 , -3.4744900000000001e-01 -3.2226493840021098e-01 , 3.3591189906654799e+00 , 6.4858424000000010e+00 , -5.3491599999999995e-01 , -8.3474700000000002e-01 , -1.3062299999999999e-01 -4.2288602706927669e-01 , 3.3306286041126092e+00 , 6.4554847999999998e+00 , -5.3491599999999995e-01 , -8.3474700000000002e-01 , -1.3062299999999999e-01 -9.1801944857511164e-01 , 3.1181587788953902e+00 , 5.7384567999999998e+00 , 6.8667500000000004e-01 , -3.1164100000000000e-01 , -6.5677799999999997e-01 -5.1205545712569678e-01 , 3.3237670610752712e+00 , 6.5827600000000004e+00 , -7.6970899999999998e-01 , -3.9558700000000002e-01 , 5.0105699999999997e-01 -5.4940676358539187e-01 , 3.3246108395260072e+00 , 6.6634224000000009e+00 , -7.7180800000000005e-01 , 1.8141900000000000e-01 , 6.0942600000000002e-01 -9.6595271423855289e-01 , 3.1384125761995492e+00 , 6.0020448000000002e+00 , -5.1716799999999996e-01 , 5.1085700000000001e-01 , -6.8670500000000001e-01 -1.0842787749450395e+00 , 3.0953972937105920e+00 , 5.8928551999999996e+00 , 4.6598899999999999e-01 , 2.6085199999999999e-02 , 8.8440600000000003e-01 -6.8783377749463459e-01 , 3.3170166638332841e+00 , 6.8766119999999997e+00 , -9.1143300000000005e-01 , 2.6875599999999999e-02 , 4.1056900000000002e-01 -8.5654668692957792e-01 , 3.2504282088633980e+00 , 6.6770047999999997e+00 , -2.7408600000000000e-01 , 9.5056099999999999e-01 , 1.4598300000000000e-01 -8.9533601931832907e-01 , 3.2512345323576657e+00 , 6.7630752000000003e+00 , 6.4506300000000005e-01 , -1.4273299999999999e-02 , 7.6399600000000001e-01 -1.0544813853583408e+00 , 3.1857097016148934e+00 , 6.5561255999999997e+00 , 8.1906999999999994e-02 , 2.2781699999999999e-01 , 9.7025300000000003e-01 -1.1289340675530282e+00 , 3.1662827199353201e+00 , 6.5441136000000002e+00 , -3.7306400000000001e-01 , -1.2200400000000000e-01 , -9.1974900000000004e-01 -1.2035084377994612e+00 , 3.1455539651466129e+00 , 6.5308951999999998e+00 , 5.1127199999999995e-01 , -4.3345800000000001e-01 , 7.4210200000000004e-01 -1.0156129386277843e+00 , 3.2861531142612361e+00 , 7.2782496000000005e+00 , -2.8212999999999999e-01 , -4.1525499999999999e-01 , 8.6485000000000001e-01 -4.0075197644179017e-01 , 3.7073714206948765e+00 , 9.4327344000000011e+00 , 7.8217599999999998e-01 , 6.1530700000000005e-01 , 9.7967200000000004e-02 -5.5216347262110421e-01 , 3.6577666484492379e+00 , 9.3347872000000010e+00 , -7.2647799999999996e-01 , -6.6358300000000003e-01 , -1.7856900000000001e-01 -1.2086444379243697e+00 , 3.2582283162616319e+00 , 7.4443480000000006e+00 , -9.2673600000000000e-01 , -3.3411600000000002e-01 , -1.7183399999999999e-01 -1.4289617700611030e+00 , 3.1387285743973465e+00 , 6.9245871999999995e+00 , 8.5389499999999996e-01 , 4.7427300000000000e-01 , -2.1430800000000000e-01 -1.5131269114770041e+00 , 3.1123248909500134e+00 , 6.8747504000000008e+00 , -4.9937599999999999e-01 , -1.2105299999999999e-01 , 8.5788699999999996e-01 -1.5777396539893564e+00 , 3.0983100984912273e+00 , 6.8927424000000004e+00 , -9.7806599999999999e-01 , -5.0698199999999999e-02 , -2.0203099999999999e-01 -1.6209804168781528e+00 , 3.1030430559566300e+00 , 7.0203400000000000e+00 , 8.9874799999999999e-01 , -3.5247499999999998e-01 , -2.6079500000000000e-01 -1.6437085960217761e+00 , 3.1285974343089862e+00 , 7.2679952000000005e+00 , -7.7541099999999996e-01 , 2.4165100000000000e-01 , -5.8338900000000005e-01 -1.7353250619362721e+00 , 3.0938142687591039e+00 , 7.1728768000000001e+00 , -8.2792299999999999e-02 , -8.8891600000000004e-01 , 4.5052599999999998e-01 -1.4909908588939711e+00 , 3.4056501116509406e+00 , 9.1849544000000005e+00 , -5.6585799999999997e-01 , -8.2132499999999997e-01 , 7.2317099999999995e-02 -1.5677535612951286e+00 , 3.4143556372845678e+00 , 9.4079303999999997e+00 , -3.5907099999999997e-01 , -8.9090899999999995e-01 , 2.7811799999999998e-01 --7.3212362902890682e-01 , 2.9877390463653430e+00 , 5.3329839999999984e-01 , -7.6916600000000002e-02 , 1.0271900000000000e-01 , 9.9173199999999995e-01 --8.6195430591212707e-01 , 3.0225965010315248e+00 , 5.2051680000000000e-01 , -5.9262000000000002e-02 , 1.1833600000000000e-01 , 9.9120399999999997e-01 --1.0105628723598938e+00 , 3.0618289740315756e+00 , 4.9907199999999996e-01 , -7.9034999999999994e-02 , 1.3443099999999999e-01 , 9.8776600000000003e-01 --1.1683964055436529e+00 , 3.1033299480520884e+00 , 4.7637920000000000e-01 , -8.3710800000000002e-02 , 1.4844499999999999e-01 , 9.8537100000000000e-01 --1.3278684927676068e+00 , 3.1458994918912659e+00 , 4.5862639999999999e-01 , -8.6389499999999994e-02 , 1.4091000000000001e-01 , 9.8624599999999996e-01 --1.5237814884898424e+00 , 3.1959594545051067e+00 , 4.2283999999999988e-01 , -1.1038300000000000e-01 , 8.3722099999999994e-02 , 9.9035700000000004e-01 --1.7029719607666935e+00 , 3.2445597739781200e+00 , 4.0450480000000000e-01 , -1.0294900000000000e-01 , 5.6353399999999998e-02 , 9.9308900000000000e-01 --1.9286554300728658e+00 , 3.3025497284020542e+00 , 3.6484959999999989e-01 , -1.5390400000000001e-01 , 4.2865000000000000e-02 , 9.8715600000000003e-01 --2.1649737779053879e+00 , 3.3645810162309173e+00 , 3.2718080000000005e-01 , -1.2406200000000001e-01 , 2.0177500000000000e-03 , 9.9227200000000004e-01 --2.3594099547230840e+00 , 3.4177205641420336e+00 , 3.2279199999999997e-01 , 1.1590600000000000e-01 , 3.2892400000000002e-02 , -9.9271500000000001e-01 --2.5995423252192085e+00 , 3.4828625290807098e+00 , 2.9973519999999998e-01 , -1.4685400000000001e-01 , -1.2999600000000000e-02 , 9.8907299999999998e-01 --2.9231187938454166e+00 , 3.5657786098392208e+00 , 2.4168239999999996e-01 , -1.5822900000000001e-01 , -1.0427300000000000e-02 , 9.8734699999999997e-01 --3.2500121855937856e+00 , 3.6520228615371053e+00 , 1.9420639999999989e-01 , -1.4675199999999999e-01 , -1.7852300000000002e-02 , 9.8901200000000000e-01 --3.5881535255921131e+00 , 3.7411972995236473e+00 , 1.5356320000000001e-01 , -1.2777600000000000e-01 , -2.6745499999999998e-02 , 9.9144200000000005e-01 --3.9296568299171097e+00 , 3.8337650588133099e+00 , 1.2379839999999986e-01 , -8.6084099999999997e-02 , -3.1113600000000002e-02 , 9.9580199999999996e-01 --4.2636997518389279e+00 , 3.9249693894842466e+00 , 1.0994559999999987e-01 , -5.1663000000000001e-02 , -2.0838200000000001e-02 , 9.9844699999999997e-01 --4.6367410144493038e+00 , 4.0274858350705856e+00 , 9.1194399999999787e-02 , -7.3018700000000006e-02 , 3.8628099999999999e-02 , 9.9658199999999997e-01 --5.1357778442688460e+00 , 4.1599175391121124e+00 , 3.5908000000000051e-02 , -9.4196799999999997e-02 , 9.2609999999999998e-02 , 9.9123700000000003e-01 --5.7704589146904270e+00 , 4.3274607858502439e+00 , -5.3199199999999891e-02 , 1.0162300000000000e-01 , -1.1428300000000000e-01 , -9.8823700000000003e-01 --6.5427654641380002e+00 , 4.5296290661818110e+00 , -1.6847279999999998e-01 , -1.0649500000000001e-01 , 1.1317199999999999e-01 , 9.8785199999999995e-01 --7.4947263721219226e+00 , 4.7776083044934605e+00 , -3.1609040000000022e-01 , -9.0186900000000000e-02 , 1.2902400000000000e-01 , 9.8753199999999997e-01 --8.6635032285359905e+00 , 5.0830723319954325e+00 , -4.9867280000000003e-01 , -9.4276700000000005e-02 , 1.3731099999999999e-01 , 9.8603099999999999e-01 --9.9187874269794190e+00 , 5.4148260471907879e+00 , -6.6407440000000006e-01 , -9.3376200000000006e-02 , 1.3538100000000000e-01 , 9.8638400000000004e-01 --1.1765256156962360e+01 , 5.8962203766653181e+00 , -9.5081280000000001e-01 , 3.0040699999999998e-01 , 2.0674600000000001e-01 , 9.3113500000000005e-01 --2.3771192924475788e+01 , 8.9651659410119766e+00 , -3.3640704000000001e+00 , -1.4497699999999999e-01 , 1.5162999999999999e-01 , 9.7774700000000003e-01 --3.1349098458588188e+01 , 1.1088432488161576e+01 , -3.3437487999999993e+00 , -6.0688899999999997e-02 , 8.3702299999999996e-01 , -5.4379200000000005e-01 --3.1850479155240201e+01 , 1.1293046171615917e+01 , -2.8093759999999994e+00 , -6.0688899999999997e-02 , 8.3702200000000004e-01 , -5.4379299999999997e-01 --4.2770832449142695e+01 , 1.4422071064812004e+01 , -2.2158480000000003e+00 , -8.6119100000000004e-01 , -5.0575000000000003e-01 , -5.0673900000000001e-02 --4.2508366310287961e+01 , 1.4450126273288962e+01 , -1.3721687999999999e+00 , -8.0937599999999998e-01 , -5.8180900000000002e-01 , 8.0056500000000003e-02 --4.1260521104148111e+01 , 1.4211763458718814e+01 , -4.6024479999999990e-01 , -9.2530100000000004e-01 , -3.6448199999999997e-01 , -1.0474000000000000e-01 --4.1839654586997334e+01 , 1.4464391131286421e+01 , 2.9054159999999984e-01 , 9.4455999999999996e-01 , 2.9613099999999998e-01 , -1.4182200000000000e-01 --4.2436695608470352e+01 , 1.4724743096730231e+01 , 1.0604775200000001e+00 , -9.9167099999999997e-01 , -1.7353899999999998e-02 , -1.2762599999999999e-01 --5.3406323251301927e+01 , 1.7978015363345705e+01 , 2.5763128799999997e+00 , 8.9236800000000005e-01 , 2.9902600000000001e-01 , 3.3802900000000002e-01 --4.2992511914849594e+01 , 1.5273277613181968e+01 , 4.3074896000000003e+00 , -7.3674499999999998e-01 , 3.0024899999999999e-01 , -6.0585299999999997e-01 --1.1346695096785131e+01 , 6.3420178924674087e+00 , 3.7018352000000001e+00 , 8.4148299999999998e-01 , -4.2387599999999998e-01 , -3.3501500000000001e-01 --4.4474250136304214e+01 , 1.6001171080074279e+01 , 6.8979736000000003e+00 , -9.2401400000000000e-01 , 2.2517999999999999e-01 , -3.0901800000000001e-01 --1.1063706355524415e+01 , 6.3504952592470243e+00 , 4.4261536000000001e+00 , 4.2038300000000001e-01 , -6.5742599999999995e-01 , -6.2535600000000002e-01 --9.8216165891088920e+00 , 6.0148890211041763e+00 , 4.5273976000000005e+00 , 4.1353099999999998e-01 , -1.2655700000000000e-01 , 9.0165099999999998e-01 --9.7493778897434709e+00 , 6.0212979878034272e+00 , 4.7433744000000004e+00 , 7.1266600000000002e-01 , -3.3961900000000000e-01 , 6.1381300000000005e-01 --1.0776074398113176e+01 , 6.3554357894147095e+00 , 5.1286632000000001e+00 , 3.5420200000000002e-01 , -3.8525399999999999e-01 , -8.5212699999999997e-01 --3.8554142509557039e+00 , 4.3026272094754843e+00 , 4.1743592000000005e+00 , 4.6550300000000000e-01 , -8.6971799999999999e-01 , 1.6400699999999999e-01 --1.0243173477712130e+01 , 6.2534050365814569e+00 , 5.5212839999999996e+00 , 5.8215700000000004e-01 , -5.9273200000000004e-01 , -5.5656300000000003e-01 --2.7156392671221399e+00 , 3.9832937337903962e+00 , 4.1712392000000005e+00 , 2.2040999999999999e-01 , -4.9745400000000002e-02 , 9.7413799999999995e-01 --2.5379754005667898e+00 , 3.9405492514540423e+00 , 4.2289176000000008e+00 , -5.5540500000000004e-01 , 1.0897500000000000e-01 , -8.2440899999999995e-01 --7.5679036117511522e+00 , 5.5121603676391615e+00 , 5.5804288000000000e+00 , 1.8317200000000000e-01 , -1.6014800000000001e-01 , 9.6994899999999995e-01 --3.9034982754229537e+00 , 4.3903787775644529e+00 , 4.7894047999999998e+00 , -6.6781800000000002e-01 , 7.4309700000000001e-01 , 4.2721400000000000e-02 --3.8314331666118093e+00 , 4.3827771786248926e+00 , 4.8935399999999998e+00 , -7.4481699999999995e-01 , 6.5117000000000003e-01 , -1.4568700000000001e-01 --3.7678149381554098e+00 , 4.3778458716754756e+00 , 4.9985903999999994e+00 , 4.1891200000000001e-01 , -9.0721300000000005e-01 , -3.8442299999999999e-02 --3.7973542614940339e+00 , 4.4019628479448212e+00 , 5.1330520000000002e+00 , 4.7323500000000002e-01 , -8.8077099999999997e-01 , 1.7055899999999999e-02 --3.8609841413605990e+00 , 4.4379941698435061e+00 , 5.2825208000000003e+00 , 4.3674400000000002e-01 , -8.9860700000000004e-01 , 4.1946600000000001e-02 --3.8007785534056602e+00 , 4.4347692908380090e+00 , 5.3900152000000006e+00 , -4.6715600000000002e-01 , 8.6046599999999995e-01 , 2.0337900000000000e-01 --3.7755206638689325e+00 , 4.4420859039882625e+00 , 5.5107904000000003e+00 , 1.4100799999999999e-01 , -9.7919199999999995e-01 , 1.4594599999999999e-01 --3.6012551128005530e+00 , 4.4010295303720506e+00 , 5.5708088000000000e+00 , -5.6466899999999998e-01 , -7.7704700000000004e-01 , 2.7811200000000003e-01 --3.2351364616792075e+00 , 4.2946585399238693e+00 , 5.5426143999999997e+00 , 5.5320800000000003e-01 , 3.8833899999999999e-01 , -7.3699000000000003e-01 --3.2892730556309653e+00 , 4.3279876216889370e+00 , 5.6911991999999998e+00 , 3.4278700000000001e-01 , 3.3342100000000002e-01 , -8.7825299999999995e-01 --3.1506699234029174e+00 , 4.2962348722556269e+00 , 5.7529024000000000e+00 , 6.0681200000000002e-01 , 3.6098599999999997e-01 , -7.0814500000000002e-01 --2.9593936469991577e+00 , 4.2464341023146694e+00 , 5.7837072000000003e+00 , 2.2726499999999999e-01 , -5.4506899999999997e-02 , 9.7230600000000000e-01 --2.9451367387079355e+00 , 4.2566142376799618e+00 , 5.9005512000000007e+00 , 6.7114300000000002e-02 , 9.9450700000000003e-01 , 8.0324999999999994e-02 --2.9367296348372278e+00 , 4.2692164771391665e+00 , 6.0228344000000007e+00 , -5.3185300000000002e-01 , 8.3602600000000005e-01 , 1.3488000000000000e-01 --2.9787921200026855e+00 , 4.2995706131674840e+00 , 6.1750591999999997e+00 , -1.2881899999999999e-01 , -6.2741300000000000e-01 , 7.6795700000000000e-01 --2.6223078945333151e+00 , 4.1897928491670147e+00 , 6.0962896000000004e+00 , 4.0130399999999999e-01 , 4.9292500000000000e-01 , -7.7199799999999996e-01 --2.5338572619127309e+00 , 4.1738613070025412e+00 , 6.1678416000000000e+00 , -3.1532900000000003e-01 , -3.8124300000000000e-01 , 8.6903500000000000e-01 --2.1098774357986176e+00 , 4.0379829751767264e+00 , 6.0212952000000000e+00 , 8.3335300000000001e-01 , 2.7153200000000000e-01 , -4.8144900000000002e-01 --2.1977025301447233e+00 , 4.0839127602515299e+00 , 6.1988960000000004e+00 , -8.7413099999999999e-01 , -3.2530199999999998e-01 , 3.6065799999999998e-01 --2.1899955509868994e+00 , 4.0959380049218419e+00 , 6.3182255999999999e+00 , -9.7896600000000000e-01 , -1.3389599999999999e-01 , -1.5393799999999999e-01 --3.2696912431126757e+00 , 4.5083099687462518e+00 , 7.2281216000000006e+00 , 5.8155299999999999e-01 , -9.5919300000000002e-03 , 8.1345199999999995e-01 --2.8132019542167193e+00 , 4.3583185479759177e+00 , 7.0448112000000007e+00 , -9.8939699999999997e-01 , 1.4420100000000000e-01 , 1.7335199999999999e-02 --4.5570506086659091e+00 , 5.0296520774407814e+00 , 8.5607463999999993e+00 , 4.5134099999999999e-01 , -8.1815400000000005e-01 , -3.5625200000000001e-01 --9.0619918780781745e+00 , 6.7577697084545836e+00 , 1.2424336000000000e+01 , 1.8482199999999999e-01 , -2.4191199999999999e-01 , 9.5253299999999996e-01 --8.1399071543235326e+00 , 6.4486710698063971e+00 , 1.1998705600000001e+01 , 1.8587400000000001e-01 , -2.6233800000000002e-01 , 9.4690500000000000e-01 --4.5362437883081723e+00 , 5.0990776436368233e+00 , 9.1838519999999999e+00 , 2.3301900000000000e-01 , 9.5330099999999995e-01 , 1.9214500000000001e-01 --4.2942239687191517e+00 , 5.0328432817365414e+00 , 9.1913191999999988e+00 , 1.3437199999999999e-01 , 4.0277700000000000e-01 , 9.0538099999999999e-01 --4.1566331172880426e+00 , 5.0060319219608225e+00 , 9.2879040000000010e+00 , 1.3437199999999999e-01 , 4.0277700000000000e-01 , 9.0538099999999999e-01 --1.8826263039790430e+00 , 4.1290949795037228e+00 , 7.3020136000000004e+00 , 4.2049199999999998e-01 , -5.0937600000000005e-01 , -7.5081500000000001e-01 --1.7945029313562255e+00 , 4.1119510538628434e+00 , 7.3674712000000007e+00 , 4.2049100000000000e-01 , -5.0937500000000002e-01 , -7.5081500000000001e-01 --1.7254566439029273e+00 , 4.1028567530476865e+00 , 7.4530735999999997e+00 , -4.5410800000000001e-01 , 4.0528300000000000e-01 , 7.9343100000000000e-01 --4.2002425911048347e-01 , 3.5854329033005827e+00 , 6.1963792000000000e+00 , 5.7914500000000002e-01 , 4.3365300000000001e-01 , -6.9031600000000004e-01 --4.1172126984519286e-01 , 3.5957219485031500e+00 , 6.3019183999999999e+00 , 6.7478300000000002e-01 , 1.5316199999999999e-01 , -7.2194899999999995e-01 --3.2173837440947972e-01 , 3.5725456063093199e+00 , 6.3167800000000005e+00 , -3.5334100000000002e-01 , -3.9089299999999999e-01 , 8.4991300000000003e-01 --2.4584486814271234e-01 , 3.5547477461509702e+00 , 6.3447976000000006e+00 , -5.9929299999999996e-01 , -1.8145500000000001e-01 , 7.7969299999999997e-01 --1.0396227646431355e+00 , 3.9128824733604990e+00 , 7.4628391999999995e+00 , 8.2317899999999999e-02 , 8.8988699999999998e-01 , 4.4869300000000001e-01 --1.9197260500756652e-01 , 3.5618268228405938e+00 , 6.5231784000000008e+00 , -9.8545799999999995e-01 , 5.3778600000000003e-02 , 1.6118399999999999e-01 --2.8744148400830660e-01 , 3.6192380875131480e+00 , 6.7825024000000003e+00 , -8.8619999999999999e-01 , -4.0437800000000002e-01 , 2.2611300000000001e-01 --1.1747244821593927e-01 , 3.5605870053286477e+00 , 6.6857304000000006e+00 , -8.4578100000000001e-01 , -5.0697999999999999e-01 , 1.6621100000000000e-01 -7.3747727871758273e-01 , 3.1872942942430953e+00 , 5.5793160000000004e+00 , 9.6404699999999999e-01 , -3.7463200000000002e-02 , -2.6307900000000001e-01 -7.6921598603131836e-01 , 3.1840609503771509e+00 , 5.6279776000000004e+00 , 7.3767899999999997e-01 , 2.8992200000000001e-01 , -6.0973299999999997e-01 -3.8122051536017310e-01 , 3.3792831973307065e+00 , 6.3402528000000009e+00 , -5.6796700000000000e-01 , -7.9446399999999995e-01 , -2.1503600000000000e-01 -8.1102103498970601e-01 , 3.1891183426120087e+00 , 5.7674104000000002e+00 , -6.3367799999999996e-01 , 3.5096100000000002e-01 , 6.8940400000000002e-01 -7.6163016412304629e-01 , 3.2265398296484502e+00 , 5.9637104000000001e+00 , -6.7249499999999995e-01 , -6.4865700000000004e-01 , -3.5636299999999999e-01 -6.1804481301448688e-01 , 3.3125050041459487e+00 , 6.3386720000000008e+00 , -8.4729399999999999e-01 , -4.9494500000000002e-01 , -1.9267100000000001e-01 -5.6357825749020596e-01 , 3.3566227884280315e+00 , 6.5776640000000004e+00 , -9.1139400000000004e-01 , -2.3469899999999999e-01 , 3.3805000000000002e-01 --6.3729194122499333e-02 , 3.6970793001890101e+00 , 7.9438912000000004e+00 , 2.6743200000000000e-01 , 6.0365300000000000e-01 , 7.5105500000000003e-01 -1.0807558100719936e+00 , 3.1238011751974746e+00 , 5.8486240000000000e+00 , -6.4197700000000002e-01 , -1.0465400000000000e-01 , -7.5954800000000000e-01 -1.1814380135407412e+00 , 3.0855499636354331e+00 , 5.7645920000000004e+00 , 7.0252999999999999e-01 , 9.7822000000000006e-02 , 7.0489800000000002e-01 -8.7252962679002533e-01 , 3.2694156127673262e+00 , 6.5743672000000002e+00 , 6.5795800000000004e-01 , 2.2487799999999999e-01 , 7.1869400000000006e-01 -8.7215623708817458e-01 , 3.2898307757472529e+00 , 6.7441472000000005e+00 , -6.2322299999999997e-01 , -3.5077799999999998e-01 , -6.9896300000000000e-01 -1.0203799840052650e+00 , 3.2276312387256771e+00 , 6.5671808000000000e+00 , -1.6167400000000001e-01 , 3.3766499999999999e-01 , 9.2727800000000005e-01 -1.1095654214765656e+00 , 3.1970031268202281e+00 , 6.5184984000000004e+00 , 8.4444300000000005e-01 , -4.9304599999999998e-01 , -2.0933800000000000e-01 -1.1625893875658266e+00 , 3.1867832454699139e+00 , 6.5634160000000001e+00 , 3.6432300000000001e-02 , -1.1644100000000000e-01 , 9.9252899999999999e-01 -1.2824098655435716e+00 , 3.1357832961249281e+00 , 6.4148936000000001e+00 , 5.7884300000000000e-01 , 1.3528000000000001e-01 , 8.0413900000000005e-01 -2.6049293157597808e-01 , 3.8189055061233681e+00 , 9.6981424000000001e+00 , -5.4902099999999998e-01 , 5.9808000000000000e-02 , -8.3366600000000002e-01 -1.1370238546614826e+00 , 3.2834927087139794e+00 , 7.2962103999999997e+00 , -6.5437300000000004e-02 , -8.8126400000000005e-01 , 4.6807300000000002e-01 -1.1742231159410454e+00 , 3.2894628667387220e+00 , 7.4391895999999997e+00 , 8.4410300000000005e-01 , 4.3745000000000001e-01 , 3.1004500000000002e-01 -8.1716732201331910e-01 , 3.5838501776491611e+00 , 9.0402799999999992e+00 , -9.0494200000000002e-01 , -2.6946999999999999e-01 , -3.2934200000000002e-01 -1.4537115468886066e+00 , 3.1567128848494699e+00 , 6.9822655999999998e+00 , 4.9598199999999998e-01 , 8.6323300000000003e-01 , 9.3969700000000003e-02 -1.5511848863988713e+00 , 3.1155403382271603e+00 , 6.8724832000000005e+00 , -2.0525600000000001e-02 , -2.6594099999999998e-01 , 9.6377100000000004e-01 -1.6247461969491437e+00 , 3.0930038859493769e+00 , 6.8501024000000008e+00 , 8.1699100000000002e-01 , -5.7059800000000005e-01 , -8.3328700000000006e-02 -1.5858674942061799e+00 , 3.1672347553502309e+00 , 7.3789008000000003e+00 , 7.2663100000000003e-01 , -6.1543300000000001e-01 , 3.0536799999999997e-01 -1.6941419440575705e+00 , 3.1157937730275105e+00 , 7.2046384000000003e+00 , 6.2854900000000002e-01 , 5.9990200000000005e-01 , -4.9501899999999999e-01 -1.7652832867521480e+00 , 3.0977860198258043e+00 , 7.2200512000000003e+00 , 4.4023000000000001e-01 , 4.8607299999999998e-01 , -7.5493800000000000e-01 -1.5780472695270951e+00 , 3.3619733226185211e+00 , 8.9709848000000001e+00 , -4.0250000000000002e-01 , 7.7577099999999999e-01 , -4.8597699999999999e-01 -1.7770593615989183e+00 , 3.2178973954922325e+00 , 8.2350704000000015e+00 , 7.7041000000000004e-01 , 5.4366700000000001e-01 , -3.3300800000000003e-01 --6.3417104336327412e-01 , 3.0683672163595626e+00 , 5.3278880000000006e-01 , -5.7579499999999999e-02 , 9.9908200000000003e-02 , 9.9332900000000002e-01 --7.6261759683234542e-01 , 3.1058716165813625e+00 , 5.1759440000000012e-01 , -8.0608100000000002e-02 , 1.0093900000000000e-01 , 9.9162200000000000e-01 --8.9251097676491620e-01 , 3.1452262584048238e+00 , 5.0601919999999989e-01 , -7.5501899999999997e-02 , 1.1667900000000000e-01 , 9.9029599999999995e-01 --1.0401808819064811e+00 , 3.1889891207824275e+00 , 4.8620719999999995e-01 , -1.1122500000000000e-01 , 1.3389200000000001e-01 , 9.8473400000000000e-01 --1.2220480657319386e+00 , 3.2410049424096723e+00 , 4.4729039999999998e-01 , -8.5418800000000003e-02 , 5.5784899999999998e-02 , 9.9478200000000006e-01 --1.3979797878680356e+00 , 3.2929505588082408e+00 , 4.1988639999999999e-01 , -1.0110000000000000e-01 , 3.8943100000000001e-02 , 9.9411400000000005e-01 --1.5756176949074892e+00 , 3.3460889853826368e+00 , 3.9801519999999990e-01 , -1.0492799999999999e-01 , 2.0554200000000002e-02 , 9.9426700000000001e-01 --1.7211387429477694e+00 , 3.3917624444937919e+00 , 4.0392239999999990e-01 , -1.0544000000000001e-01 , 1.3285900000000000e-02 , 9.9433700000000003e-01 --1.9185892497712227e+00 , 3.4510823328143343e+00 , 3.8218639999999993e-01 , -1.5383100000000000e-01 , 2.1913999999999999e-02 , 9.8785400000000001e-01 --2.1539131665419662e+00 , 3.5197245622874238e+00 , 3.4593200000000013e-01 , -1.3756399999999999e-01 , -4.3658000000000002e-02 , 9.8953000000000002e-01 --2.3814046704020013e+00 , 3.5874714038467115e+00 , 3.2265679999999985e-01 , -1.2129300000000000e-01 , -4.6523799999999997e-02 , 9.9152600000000002e-01 --2.6381888398486879e+00 , 3.6645078650466898e+00 , 2.9186240000000008e-01 , -1.5144199999999999e-01 , -5.0160999999999997e-02 , 9.8719299999999999e-01 --2.9147192101696637e+00 , 3.7465083109356208e+00 , 2.6040240000000003e-01 , 1.7366699999999999e-01 , 7.6275099999999998e-02 , -9.8184600000000000e-01 --3.2297323643011824e+00 , 3.8399996609609168e+00 , 2.1976960000000001e-01 , 1.8290799999999999e-01 , 6.6843600000000003e-02 , -9.8085500000000003e-01 --3.5835449607410599e+00 , 3.9443977605918596e+00 , 1.7232479999999994e-01 , -1.5642100000000000e-01 , -4.7225999999999997e-02 , 9.8656100000000002e-01 --3.9407790258393991e+00 , 4.0523256807365335e+00 , 1.3636159999999986e-01 , -1.2042200000000000e-01 , -6.0942200000000002e-02 , 9.9085000000000001e-01 --4.2728512446253024e+00 , 4.1535435334427024e+00 , 1.2516079999999996e-01 , -8.0816499999999999e-02 , -3.8086100000000000e-03 , 9.9672200000000000e-01 --4.7273002381307885e+00 , 4.2891773011736412e+00 , 7.4252800000000008e-02 , 8.8365299999999994e-02 , -4.2256799999999997e-02 , -9.9519100000000005e-01 --5.3259045582906115e+00 , 4.4653176616408459e+00 , -1.7194400000000165e-02 , 1.0334000000000000e-01 , -1.1071100000000000e-01 , -9.8846500000000004e-01 --6.0327584046617346e+00 , 4.6731878451341702e+00 , -1.2710160000000004e-01 , 1.0345000000000000e-01 , -1.2213300000000001e-01 , -9.8710799999999999e-01 --6.8775626919166832e+00 , 4.9206364400372262e+00 , -2.5973280000000010e-01 , -9.8624699999999996e-02 , 1.3509099999999999e-01 , 9.8591300000000004e-01 --7.9473471969482414e+00 , 5.2324995677072783e+00 , -4.3688640000000012e-01 , -9.4439200000000001e-02 , 1.4335700000000001e-01 , 9.8515500000000000e-01 --9.1491862255212837e+00 , 5.5857411252681644e+00 , -6.1603680000000027e-01 , -8.1898299999999993e-02 , 1.3979400000000000e-01 , 9.8678800000000000e-01 --1.0762604849353608e+01 , 6.0586559375780098e+00 , -8.7396720000000006e-01 , 7.9239900000000002e-02 , -1.7342800000000000e-01 , -9.8165400000000003e-01 --1.9134411343046011e+01 , 8.4706222874144004e+00 , -2.5523192000000003e+00 , -8.5272799999999996e-02 , 5.2354000000000001e-01 , -8.4772300000000000e-01 --2.0060712957682092e+01 , 8.7801076682687995e+00 , -2.3677504000000003e+00 , -8.5272799999999996e-02 , 5.2354000000000001e-01 , -8.4772300000000000e-01 --2.9268328806491013e+01 , 1.1458228910685360e+01 , -3.9998016000000005e+00 , -8.3921999999999997e-02 , 9.1960200000000003e-01 , -3.8378400000000001e-01 --2.9421492932503831e+01 , 1.1571497731491130e+01 , -3.4387527999999996e+00 , 8.3921999999999997e-02 , -9.1960200000000003e-01 , 3.8378299999999999e-01 --2.9861400534286176e+01 , 1.1768622963093033e+01 , -2.9286120000000002e+00 , -8.2130599999999998e-02 , 8.5256299999999996e-01 , -5.1613100000000001e-01 --2.9868684691404734e+01 , 1.1840153676378115e+01 , -2.3326712000000001e+00 , -6.0688899999999997e-02 , 8.3702200000000004e-01 , -5.4379200000000005e-01 --4.1856135045973275e+01 , 1.5435612739863959e+01 , -3.5251248000000004e+00 , 9.2678400000000005e-01 , 3.7251699999999999e-01 , 4.7988799999999998e-02 --5.0304231120392423e+01 , 1.8032332660676335e+01 , -3.8174168000000002e+00 , -5.0458599999999998e-01 , -7.3087500000000005e-01 , -4.5958199999999999e-01 --4.3711897513698339e+01 , 1.6179052960045102e+01 , -2.1123159999999999e+00 , -8.6119100000000004e-01 , -5.0575000000000003e-01 , -5.0673799999999998e-02 --4.3962242636934477e+01 , 1.6352420877838121e+01 , -1.2946472000000004e+00 , -8.7678000000000000e-01 , -4.7371600000000003e-01 , -8.2759899999999997e-02 --4.1608437872062318e+01 , 1.5738589944162438e+01 , -2.7142240000000006e-01 , -9.4455999999999996e-01 , -2.9613099999999998e-01 , 1.4182300000000000e-01 --4.1830095952406317e+01 , 1.5900263998859577e+01 , 5.1579519999999990e-01 , -9.4327099999999997e-01 , -2.8165300000000001e-02 , 3.3082600000000001e-01 --4.2670044250801922e+01 , 1.6540187905903451e+01 , 3.7442256000000000e+00 , -8.6549799999999999e-01 , 4.3573200000000001e-01 , -2.4708500000000000e-01 --4.1553768859623162e+01 , 1.6283962134380211e+01 , 4.5290928000000008e+00 , 9.2140800000000000e-01 , -3.7047000000000002e-01 , 1.1729900000000000e-01 --1.1240719317986404e+01 , 6.7525929963963289e+00 , 3.7805735999999999e+00 , 6.1048700000000000e-01 , -4.6561599999999997e-01 , -6.4070800000000006e-01 --1.1188817178039946e+01 , 6.7650984360134920e+00 , 4.0276256000000004e+00 , 5.6725099999999995e-01 , -4.7478799999999999e-01 , -6.7290600000000000e-01 --9.6037755512653060e+00 , 6.2850730465520694e+00 , 4.1388327999999994e+00 , -5.2550100000000000e-01 , 9.4325800000000001e-02 , -8.4554799999999997e-01 --9.7044957496105120e+00 , 6.3437861859430260e+00 , 4.3719383999999994e+00 , -5.2549999999999997e-01 , 9.4325599999999996e-02 , -8.4554799999999997e-01 --1.0263597492238103e+01 , 6.5515129216044512e+00 , 4.6669967999999997e+00 , 1.6076299999999999e-01 , -2.3576100000000000e-01 , 9.5842200000000000e-01 --1.0295458235919792e+01 , 6.5898562833961556e+00 , 4.9085680000000007e+00 , -5.8710200000000001e-01 , -6.4361100000000004e-01 , -4.9099500000000001e-01 --3.7942277793192503e+00 , 4.4694067722820865e+00 , 4.0929272000000001e+00 , 5.6319399999999997e-01 , -8.0478200000000000e-01 , 1.8745300000000001e-01 --9.5401972492580285e+00 , 6.3949291126062997e+00 , 5.2511232000000003e+00 , -9.1388899999999995e-01 , -1.2484700000000000e-01 , -3.8629100000000000e-01 --3.9041345381407826e+00 , 4.5336539358918966e+00 , 4.3514815999999996e+00 , -5.0778599999999996e-01 , 8.5788100000000000e-01 , -7.8704499999999997e-02 --3.8195183080377824e+00 , 4.5200436868612464e+00 , 4.4548160000000001e+00 , 3.7020999999999998e-01 , -9.2847000000000002e-01 , -2.9818200000000000e-02 --3.7442737310429619e+00 , 4.5078551167043148e+00 , 4.5579216000000002e+00 , -4.5174100000000000e-01 , 8.8423099999999999e-01 , 1.1859900000000000e-01 --3.7053148740203481e+00 , 4.5093537190303508e+00 , 4.6685672000000000e+00 , -6.2824999999999998e-01 , 7.7703900000000004e-01 , 3.8904099999999997e-02 --3.6922613884665765e+00 , 4.5187699438544211e+00 , 4.7866072000000006e+00 , 8.1830000000000003e-01 , -5.6876899999999997e-01 , 8.2983500000000002e-02 --3.7440615024082504e+00 , 4.5508854212513032e+00 , 4.9243864000000004e+00 , -8.5006300000000001e-01 , 5.2255700000000005e-01 , -6.5780699999999998e-02 --3.7842938385387708e+00 , 4.5802204372131321e+00 , 5.0614272000000007e+00 , 6.9089500000000004e-01 , -7.0650800000000002e-01 , -1.5332999999999999e-01 --4.5685715153562425e+00 , 4.8703403996910550e+00 , 5.4539232000000002e+00 , -7.6435699999999995e-01 , -5.7686899999999997e-01 , 2.8806399999999999e-01 --3.5668809961741657e+00 , 4.5324070160021064e+00 , 5.2394232000000001e+00 , -4.4575700000000001e-01 , 8.8719000000000003e-01 , 1.1914100000000000e-01 --3.6829121377592253e+00 , 4.5886001073645488e+00 , 5.4092343999999999e+00 , 5.5711500000000003e-01 , -8.2950199999999996e-01 , 3.9352999999999999e-02 --3.6389817052168212e+00 , 4.5881352712242673e+00 , 5.5217312000000005e+00 , -5.4924399999999995e-01 , 8.0216600000000005e-01 , 2.3422299999999999e-01 --3.7299201395316430e+00 , 4.6367553580515137e+00 , 5.6909288000000000e+00 , 4.6692899999999998e-01 , -7.7924400000000005e-01 , -4.1803800000000002e-01 --3.5103771790006180e+00 , 4.5722042873580460e+00 , 5.7283272000000007e+00 , -8.1529500000000005e-02 , 5.9041699999999997e-01 , 8.0296999999999996e-01 --3.3538633260237303e+00 , 4.5307223120635980e+00 , 5.7877320000000001e+00 , 7.5115500000000002e-01 , 7.6755299999999999e-02 , -6.5564800000000001e-01 --3.1181723120901053e+00 , 4.4589604281492274e+00 , 5.8033008000000006e+00 , 5.1946400000000004e-01 , 2.4619900000000000e-01 , -8.1825599999999998e-01 --2.8659333873632820e+00 , 4.3799520593559400e+00 , 5.8023128000000002e+00 , -3.2505899999999999e-01 , 5.5475699999999994e-01 , 7.6588599999999996e-01 --2.6503297615703376e+00 , 4.3141567619703647e+00 , 5.8116000000000003e+00 , -8.3472199999999996e-01 , -3.5106700000000002e-01 , 4.2425499999999999e-01 --3.2561530552999498e+00 , 4.5571613670036948e+00 , 6.2718520000000000e+00 , -9.2169400000000001e-01 , -2.8865499999999999e-01 , 2.5914799999999999e-01 --2.7287207706117869e+00 , 4.3730667503311125e+00 , 6.1030911999999997e+00 , -5.4871999999999997e-02 , 8.0797400000000005e-02 , 9.9521899999999996e-01 --2.7834357515420276e+00 , 4.4091967563477663e+00 , 6.2654560000000004e+00 , 2.2081400000000001e-01 , -8.4083100000000000e-01 , 4.9421100000000001e-01 --2.3340246880612234e+00 , 4.2508836291843730e+00 , 6.1131688000000004e+00 , -3.2213700000000001e-01 , 5.3830200000000002e-02 , 9.4516100000000003e-01 --2.1555764536789566e+00 , 4.1967315849318130e+00 , 6.1196272000000000e+00 , -8.7412999999999996e-01 , -3.2530199999999998e-01 , 3.6065799999999998e-01 --2.2156371067975584e+00 , 4.2343671814022681e+00 , 6.2830840000000006e+00 , -6.6006200000000004e-01 , -7.5010900000000003e-01 , 4.0678199999999998e-02 --2.1013266465862808e+00 , 4.2037280207106615e+00 , 6.3292912000000001e+00 , 9.6805799999999997e-01 , 1.9432300000000000e-01 , 1.5843599999999999e-01 --2.9507557266308284e+00 , 4.5572775661639042e+00 , 7.0859536000000007e+00 , -8.1613000000000002e-01 , 5.6865399999999999e-01 , 1.0277900000000000e-01 --2.9493465000317185e+00 , 4.5745628919656447e+00 , 7.2405496000000005e+00 , -2.9986800000000002e-01 , 8.4687499999999999e-02 , -9.5021400000000000e-01 --2.8066093498118994e+00 , 4.5358699023834852e+00 , 7.2845000000000004e+00 , -9.1471899999999995e-01 , 3.3673799999999998e-01 , -2.2337799999999999e-01 --2.2358396591994989e+00 , 4.3205759904201795e+00 , 6.9701496000000001e+00 , -8.5383699999999996e-01 , 5.0144000000000000e-01 , -1.3971400000000000e-01 --2.1519030081884258e+00 , 4.3031988426839876e+00 , 7.0441352000000004e+00 , -8.5383699999999996e-01 , 5.0144000000000000e-01 , -1.3971400000000000e-01 --4.2884193671624047e+00 , 5.2098847197672100e+00 , 9.1015568000000009e+00 , 7.6813199999999998e-02 , 9.5984499999999995e-01 , 2.6980900000000002e-01 --4.0512907581989843e+00 , 5.1366845723824319e+00 , 9.1050824000000006e+00 , 7.6813199999999998e-02 , 9.5984499999999995e-01 , 2.6980900000000002e-01 --2.1240111007063911e+00 , 4.3454201239006158e+00 , 7.4757144000000002e+00 , 6.0894099999999995e-01 , 3.3161499999999999e-01 , 7.2057099999999996e-01 --1.8705064147536143e+00 , 4.2557703024753391e+00 , 7.3852552000000005e+00 , 2.0698200000000000e-01 , -1.2013500000000001e-01 , -9.7094100000000005e-01 --1.7115218696342880e+00 , 4.2053979625439766e+00 , 7.3799720000000004e+00 , 4.2049100000000000e-01 , -5.0937500000000002e-01 , -7.5081500000000001e-01 --1.6566659204228151e+00 , 4.1997197714844603e+00 , 7.4794376000000007e+00 , -4.2049100000000000e-01 , 5.0937600000000005e-01 , 7.5081500000000001e-01 --4.3177806947947017e-01 , 3.6784372771059579e+00 , 6.2812951999999997e+00 , 7.3236500000000004e-01 , -1.2049200000000000e-01 , -6.7016600000000004e-01 --3.6242649286585005e-01 , 3.6609793114213440e+00 , 6.3201184000000001e+00 , -6.0802999999999996e-01 , -1.5272100000000000e-01 , 7.7908599999999995e-01 --3.3779281041133702e-01 , 3.6644129120402611e+00 , 6.4109416000000001e+00 , 4.5532400000000001e-01 , 3.5612100000000002e-01 , -8.1600099999999998e-01 --1.9865319437283802e-01 , 3.6146232072407836e+00 , 6.3621552000000001e+00 , 6.8263499999999999e-01 , -2.9399500000000001e-01 , -6.6901200000000005e-01 --9.7090322408479102e-01 , 3.9861734790526713e+00 , 7.4776072000000005e+00 , 1.0464600000000000e-01 , 8.0964300000000000e-01 , 5.7751900000000000e-01 --2.5156612400408029e-01 , 3.6691368748708308e+00 , 6.6847008000000008e+00 , 9.7810900000000001e-01 , 2.0802300000000001e-01 , -5.4294900000000004e-03 -7.1415343699208034e-01 , 3.2275591791652469e+00 , 5.4843328000000007e+00 , -8.9266699999999999e-01 , -9.7705500000000001e-02 , 4.3999899999999997e-01 --1.1975437999472227e-01 , 3.6395304688543697e+00 , 6.7766992000000004e+00 , -8.4578100000000001e-01 , -5.0697999999999999e-01 , 1.6621100000000000e-01 -7.3725093975901412e-01 , 3.2389583694553106e+00 , 5.6406656000000002e+00 , 8.7715100000000001e-01 , -1.3778399999999999e-01 , -4.6002399999999999e-01 -7.6996724506131398e-01 , 3.2347028692537920e+00 , 5.6897640000000003e+00 , 8.7715100000000001e-01 , -1.3778399999999999e-01 , -4.6002399999999999e-01 -8.3691929341258242e-01 , 3.2132991382900240e+00 , 5.6874343999999999e+00 , 8.4554700000000005e-01 , 1.5448999999999999e-01 , -5.1106099999999999e-01 -6.4015848615634141e-01 , 3.3257527864273442e+00 , 6.1245256000000001e+00 , -7.1606599999999998e-01 , 1.6075700000000001e-01 , -6.7926900000000001e-01 -6.0173973105657708e-01 , 3.3596469854393334e+00 , 6.3162079999999996e+00 , 6.9602200000000003e-01 , 6.9925199999999998e-01 , 1.6309599999999999e-01 --2.2397270576117201e-01 , 3.8103031681255302e+00 , 7.9604168000000000e+00 , -2.6743200000000000e-01 , -6.0365300000000000e-01 , -7.5105500000000003e-01 -9.8222128954023868e-01 , 3.1898654755313980e+00 , 5.8761735999999996e+00 , 4.5067800000000002e-01 , 5.8512500000000001e-01 , 6.7418000000000000e-01 -1.0436106607833828e+00 , 3.1714514054006253e+00 , 5.8769431999999995e+00 , -4.4485999999999998e-01 , -2.1917900000000001e-01 , -8.6836700000000000e-01 -1.1619053203299770e+00 , 3.1201315458232939e+00 , 5.7581335999999999e+00 , 7.0252999999999999e-01 , 9.7822000000000006e-02 , 7.0489900000000005e-01 -8.0618463162760690e-01 , 3.3365295065543830e+00 , 6.6561631999999999e+00 , 8.4790900000000002e-01 , 1.8357499999999999e-01 , 4.9734299999999998e-01 -8.9559142455579988e-01 , 3.3047047173149364e+00 , 6.6227168000000001e+00 , 6.5795800000000004e-01 , 2.2487699999999999e-01 , 7.1869400000000006e-01 -1.0340755980875409e+00 , 3.2426637873480422e+00 , 6.4655312000000000e+00 , 6.5183199999999997e-01 , 5.6903400000000004e-01 , 5.0131400000000004e-01 -1.1146554005709515e+00 , 3.2141856561719946e+00 , 6.4362240000000002e+00 , -8.2681200000000003e-03 , 7.7767299999999995e-01 , 6.2861500000000003e-01 -1.1293270796056152e+00 , 3.2268268511025942e+00 , 6.5759167999999999e+00 , -3.2071900000000000e-02 , 6.0486499999999999e-01 , 7.9568200000000000e-01 -1.2541170200248737e+00 , 3.1688013380071336e+00 , 6.4199168000000002e+00 , 5.7884300000000000e-01 , 1.3528000000000001e-01 , 8.0413900000000005e-01 -9.4171831251288118e-01 , 3.3967294837963635e+00 , 7.5320200000000002e+00 , 7.2925200000000001e-01 , 6.5144199999999997e-01 , -2.0932000000000001e-01 -1.0487135989969816e+00 , 3.3551632076299938e+00 , 7.4644824000000005e+00 , -7.0491899999999996e-01 , -5.7637899999999997e-01 , -4.1337200000000002e-01 -1.1735423296263066e+00 , 3.3006473606152311e+00 , 7.3259440000000007e+00 , -9.1344599999999998e-01 , 2.7434700000000001e-01 , 3.0058299999999999e-01 -1.3317428387372894e+00 , 3.2184831357103727e+00 , 7.0467352000000005e+00 , -8.4453299999999998e-01 , -5.3541300000000003e-01 , 9.8303499999999999e-03 -1.4383856956686207e+00 , 3.1704891156684010e+00 , 6.9208536000000000e+00 , -7.0276300000000003e-01 , -3.0284800000000001e-01 , -6.4374500000000001e-01 -1.4739377377525442e+00 , 3.1757645740159344e+00 , 7.0600368000000007e+00 , 7.6683800000000002e-01 , -1.9425700000000001e-01 , -6.1173900000000003e-01 -1.5959299554031934e+00 , 3.1124073601683682e+00 , 6.8401288000000005e+00 , 1.1308500000000000e-01 , -7.3170999999999997e-01 , 6.7217000000000005e-01 -1.5843546141940141e+00 , 3.1603807690890262e+00 , 7.2180856000000002e+00 , -7.5559799999999999e-01 , -6.4998299999999998e-01 , 8.1201999999999996e-02 -1.6620465368651240e+00 , 3.1333864828712237e+00 , 7.1955072000000007e+00 , -4.9732199999999999e-01 , -8.5279800000000003e-02 , 8.6336500000000005e-01 -1.7366502162483020e+00 , 3.1082174407879508e+00 , 7.1813840000000004e+00 , 4.5986399999999999e-01 , 5.6904600000000005e-01 , -6.8169800000000003e-01 -1.4933489367895239e+00 , 3.4200292141283590e+00 , 9.1935968000000017e+00 , -5.6585799999999997e-01 , -8.2132499999999997e-01 , 7.2317099999999995e-02 -1.5961729010958519e+00 , 3.3899373484445730e+00 , 9.2137519999999995e+00 , -6.1552300000000004e-01 , -7.6548000000000005e-01 , -1.8754199999999999e-01 --6.3015203524370866e-01 , 3.1784169375643661e+00 , 5.4228399999999999e-01 , -1.6368500000000001e-02 , 3.4263599999999998e-02 , 9.9927900000000003e-01 --7.8130388569590714e-01 , 3.2270025786818408e+00 , 5.0876479999999979e-01 , 8.1898799999999994e-02 , -1.1745400000000000e-01 , -9.8969499999999999e-01 --9.3513586733148779e-01 , 3.2756179526072837e+00 , 4.8005040000000010e-01 , -1.0515400000000000e-01 , 3.1700699999999998e-02 , 9.9395100000000003e-01 --1.0981615636543816e+00 , 3.3285986328826018e+00 , 4.5000479999999987e-01 , -1.1779600000000000e-01 , 1.9450800000000001e-02 , 9.9284700000000004e-01 --1.2465560173496324e+00 , 3.3780297371422487e+00 , 4.3704640000000006e-01 , -1.1679100000000001e-01 , -1.2635200000000001e-04 , 9.9315600000000004e-01 --1.3465083052553677e+00 , 3.4152085846554376e+00 , 4.6323359999999991e-01 , 1.1771700000000000e-01 , 4.3972299999999999e-02 , -9.9207299999999998e-01 --1.5470633626063903e+00 , 3.4808921437359874e+00 , 4.2495119999999997e-01 , -1.1214399999999999e-01 , 3.6631400000000001e-03 , 9.9368500000000004e-01 --1.7330928167067330e+00 , 3.5420815100521068e+00 , 4.0439039999999982e-01 , -1.0145200000000000e-01 , 3.3226400000000000e-03 , 9.9483500000000002e-01 --1.9470591646596285e+00 , 3.6119970141502735e+00 , 3.7371040000000000e-01 , -1.3330300000000000e-01 , -3.8928999999999998e-02 , 9.9031100000000005e-01 --2.1541173365965918e+00 , 3.6819121536875947e+00 , 3.5506320000000002e-01 , 1.2229700000000000e-01 , 6.4423599999999998e-02 , -9.9039999999999995e-01 --2.3718402690423366e+00 , 3.7548120283773718e+00 , 3.3839200000000003e-01 , -1.4779000000000000e-01 , -7.3966799999999999e-02 , 9.8624900000000004e-01 --2.6168359129805134e+00 , 3.8359359858397566e+00 , 3.1456559999999989e-01 , -1.4628300000000000e-01 , -8.6290400000000003e-02 , 9.8547200000000001e-01 --2.8648227226912804e+00 , 3.9198280686101561e+00 , 2.9858079999999987e-01 , -1.6720399999999999e-01 , -9.2651100000000000e-02 , 9.8155899999999996e-01 --3.1767379060898291e+00 , 4.0220121666231528e+00 , 2.5962239999999981e-01 , 1.8769200000000000e-01 , 9.0146900000000002e-02 , -9.7808300000000004e-01 --3.5184916303971967e+00 , 4.1355505922883111e+00 , 2.1790799999999999e-01 , -1.6929900000000001e-01 , -8.4234600000000007e-02 , 9.8195800000000000e-01 --3.9081115146180787e+00 , 4.2641533639643043e+00 , 1.6701040000000011e-01 , 1.6322000000000000e-01 , 8.7190000000000004e-02 , -9.8272899999999996e-01 --4.3479753564525243e+00 , 4.4084526882135950e+00 , 1.0950879999999996e-01 , -1.2961700000000001e-01 , 2.0228800000000002e-02 , 9.9135799999999996e-01 --4.8640766872609840e+00 , 4.5773245768463005e+00 , 3.6459199999999914e-02 , -1.2114000000000000e-01 , 8.4312999999999999e-02 , 9.8904800000000004e-01 --5.5324879848906710e+00 , 4.7954174897531576e+00 , -7.7764000000000166e-02 , -1.0264500000000000e-01 , 1.2049300000000000e-01 , 9.8739299999999997e-01 --6.3284557846969793e+00 , 5.0538481062077585e+00 , -2.1396240000000022e-01 , -1.0639200000000000e-01 , 1.3151599999999999e-01 , 9.8558800000000002e-01 --7.2997344087333342e+00 , 5.3685948108924677e+00 , -3.8213039999999987e-01 , -9.6305699999999994e-02 , 1.4182100000000000e-01 , 9.8519599999999996e-01 --8.3252539456515748e+00 , 5.7042551908309420e+00 , -5.3183840000000027e-01 , 8.9365799999999995e-02 , -1.4493500000000001e-01 , -9.8539699999999997e-01 --9.6894195018787475e+00 , 6.1490116509591886e+00 , -7.4987439999999994e-01 , -8.0073000000000005e-02 , 1.8523999999999999e-01 , 9.7942600000000002e-01 --1.1673981957024179e+01 , 6.7923486643527706e+00 , -1.1002399999999999e+00 , -1.5115099999999999e-02 , 2.8935200000000000e-01 , 9.5710399999999995e-01 --1.7970672316946960e+01 , 8.7932200176947291e+00 , -2.5684600000000009e+00 , 4.5092100000000003e-02 , 3.6128500000000002e-01 , -9.3136500000000000e-01 --2.7545600651839074e+01 , 1.1917060238876367e+01 , -4.0689408000000000e+00 , 6.6364400000000004e-02 , -9.4333100000000003e-01 , 3.2514999999999999e-01 --2.0579955622061568e+01 , 9.7580763379674273e+00 , -1.9730704000000006e+00 , 1.3506399999999999e-01 , -5.9273299999999995e-01 , 7.9399299999999995e-01 --2.8076640040155791e+01 , 1.2216683516250148e+01 , -3.0432823999999998e+00 , 6.6364400000000004e-02 , -9.4333100000000003e-01 , 3.2514999999999999e-01 --2.8349059109827262e+01 , 1.2368598385197625e+01 , -2.5212752000000007e+00 , 7.2226299999999993e-02 , -9.3508500000000006e-01 , 3.4698699999999999e-01 --4.2362353056242213e+01 , 1.6996353654050345e+01 , -4.2347999999999999e+00 , -9.2656200000000000e-01 , -3.7347700000000000e-01 , 4.4687499999999998e-02 --3.0125453706060341e+01 , 1.3148713625962689e+01 , -1.0309968000000000e+00 , -2.2546000000000000e-02 , -8.5217900000000002e-01 , 5.2276400000000001e-01 --3.0433470243160393e+01 , 1.3318667958113686e+01 , -4.6379120000000018e-01 , -2.2545900000000001e-02 , -8.5217900000000002e-01 , 5.2276400000000001e-01 --4.1778892575490602e+01 , 1.7635334430882562e+01 , 3.1827712000000004e+00 , -8.8528200000000001e-01 , 4.2086099999999999e-01 , -1.9786999999999999e-01 --4.2684662075479331e+01 , 1.8041408251356344e+01 , 4.0141992000000002e+00 , 7.8635200000000005e-01 , -3.7577899999999997e-01 , 4.9034800000000001e-01 --4.1269067193435383e+01 , 1.7641904053417214e+01 , 4.7896231999999994e+00 , 9.1876100000000005e-01 , -2.9422799999999999e-01 , 2.6326300000000002e-01 --4.2784143086827974e+01 , 1.8264140236084749e+01 , 5.6836488000000003e+00 , 7.8635200000000005e-01 , -3.7577899999999997e-01 , 4.9034800000000001e-01 --1.1430005189324822e+01 , 7.3005626086191739e+00 , 4.1358584000000000e+00 , 5.2114000000000005e-01 , -4.9498599999999998e-01 , -6.9527099999999997e-01 --9.4295917105075393e+00 , 6.6199664043090616e+00 , 4.2044775999999997e+00 , -8.3340599999999998e-01 , -3.4691000000000000e-01 , -4.3021799999999999e-01 --9.6346542418905976e+00 , 6.7185127340203801e+00 , 4.4495431999999999e+00 , -8.3340599999999998e-01 , -3.4691000000000000e-01 , -4.3021799999999999e-01 --1.0049254156099456e+01 , 6.8928703913061051e+00 , 4.7311128000000000e+00 , -8.3340599999999998e-01 , -3.4691000000000000e-01 , -4.3021799999999999e-01 --3.6589995235425450e+00 , 4.6120282127434349e+00 , 4.0022288000000001e+00 , 6.0585900000000004e-01 , -7.9389500000000002e-01 , 5.1638299999999998e-02 --3.6199242598760435e+00 , 4.6111203728712749e+00 , 4.1114600000000001e+00 , 6.0585900000000004e-01 , -7.9389500000000002e-01 , 5.1638200000000002e-02 --3.5978473024553361e+00 , 4.6157547665537599e+00 , 4.2235303999999996e+00 , 6.6493500000000005e-01 , -7.4264799999999997e-01 , 7.9599000000000003e-02 --3.6024295835267477e+00 , 4.6311358045636801e+00 , 4.3410399999999996e+00 , -7.1228199999999997e-01 , 6.8284800000000001e-01 , -1.6239600000000001e-01 --3.6242846885058855e+00 , 4.6525233933186296e+00 , 4.4636144000000009e+00 , 7.5066800000000000e-01 , -6.4722700000000000e-01 , 1.3264699999999999e-01 --3.6442345776195175e+00 , 4.6730450286188159e+00 , 4.5875512000000001e+00 , -8.0247999999999997e-01 , 5.8293700000000004e-01 , -1.2732399999999999e-01 --3.6805625379826665e+00 , 4.6998182591510718e+00 , 4.7179880000000001e+00 , -8.0954700000000002e-01 , 5.8373200000000003e-01 , -6.2372999999999998e-02 --3.7333287700219255e+00 , 4.7340299838953621e+00 , 4.8554344000000000e+00 , -8.9954699999999999e-01 , 4.0492000000000000e-01 , -1.6387699999999999e-01 --4.8575407565099811e+00 , 5.1744653244448031e+00 , 5.3259304000000007e+00 , -8.7535300000000005e-01 , 3.4653600000000001e-01 , -3.3715000000000001e-01 --4.7774175812421804e+00 , 5.1607719869799835e+00 , 5.4489520000000002e+00 , -8.7535300000000005e-01 , 3.4653600000000001e-01 , -3.3715000000000001e-01 --4.6395835525330780e+00 , 5.1243852694223602e+00 , 5.5507576000000007e+00 , -8.7535300000000005e-01 , 3.4653600000000001e-01 , -3.3715000000000001e-01 --3.5842352250896221e+00 , 4.7341266250825083e+00 , 5.3093528000000001e+00 , -3.0526700000000001e-01 , 9.5043800000000001e-01 , 5.8991599999999998e-02 --3.4789796379684219e+00 , 4.7077960231339837e+00 , 5.3961512000000003e+00 , 3.5982100000000000e-01 , -9.3300099999999997e-01 , 6.1635500000000003e-03 --3.3811143329494966e+00 , 4.6841058311931700e+00 , 5.4838855999999998e+00 , 3.0518800000000001e-01 , -9.0399700000000005e-01 , -2.9941699999999999e-01 --3.4443018168437165e+00 , 4.7233466192474092e+00 , 5.6388352000000008e+00 , -7.8469499999999998e-02 , 8.9861599999999997e-01 , 4.3166199999999999e-01 --3.2813171896393909e+00 , 4.6736047401897487e+00 , 5.6954735999999997e+00 , -9.6849900000000003e-02 , 4.8613400000000001e-01 , 8.6850099999999997e-01 --3.1540955602565957e+00 , 4.6373270373971716e+00 , 5.7639263999999999e+00 , 4.0735100000000002e-01 , -6.8066499999999996e-01 , -6.0890100000000003e-01 --2.8072017467053092e+00 , 4.5135080633106206e+00 , 5.7187903999999996e+00 , -1.9736200000000001e-01 , 2.9560900000000001e-01 , 9.3469999999999998e-01 --3.1404494843882542e+00 , 4.6611995551319119e+00 , 6.0170624000000004e+00 , 4.9163200000000001e-01 , -8.6882599999999999e-01 , 5.8642199999999998e-02 --3.1394909239364859e+00 , 4.6761014372016483e+00 , 6.1492152000000004e+00 , 8.9481200000000005e-01 , -4.4290800000000002e-01 , -5.6072999999999998e-02 --2.7355801610503150e+00 , 4.5258405035405298e+00 , 6.0535144000000001e+00 , -7.8006100000000000e-01 , 2.2724900000000001e-01 , 5.8297800000000000e-01 --2.6982891765374895e+00 , 4.5255684556325857e+00 , 6.1602703999999999e+00 , -6.8785099999999999e-01 , 2.8194200000000003e-01 , 6.6885700000000003e-01 --2.4934521883998935e+00 , 4.4556699669038693e+00 , 6.1627248000000003e+00 , 5.4463799999999996e-01 , 1.8205299999999999e-01 , -8.1867299999999998e-01 --3.0312377519586056e+00 , 4.6938751126101677e+00 , 6.6400016000000006e+00 , 7.6559900000000003e-01 , -3.3639100000000000e-01 , -5.4835999999999996e-01 --2.6096055154008733e+00 , 4.5329339997432392e+00 , 6.5003815999999999e+00 , -2.0986299999999999e-01 , -6.2910600000000005e-01 , 7.4845399999999995e-01 --2.8784841131230117e+00 , 4.6622530396849919e+00 , 6.8265984000000000e+00 , -7.7039599999999997e-01 , 4.2708600000000002e-01 , 4.7337899999999999e-01 --2.8271401127248881e+00 , 4.6580383037742319e+00 , 6.9378576000000001e+00 , -8.1661899999999998e-01 , 5.2238200000000001e-01 , 2.4545900000000001e-01 --2.8296203733658185e+00 , 4.6760844739815930e+00 , 7.0901240000000003e+00 , -8.1613000000000002e-01 , 5.6865399999999999e-01 , 1.0277900000000000e-01 --2.7050863111338135e+00 , 4.6395590970280942e+00 , 7.1462424000000002e+00 , -8.1613000000000002e-01 , 5.6865399999999999e-01 , 1.0277900000000000e-01 --2.0992901205382886e+00 , 4.3920815463188010e+00 , 6.8060999999999998e+00 , 9.2365600000000003e-01 , -3.4177700000000000e-01 , 1.7334500000000000e-01 --2.0866052347955986e+00 , 4.4028449964763885e+00 , 6.9360064000000001e+00 , 9.2365600000000003e-01 , -3.4177700000000000e-01 , 1.7334500000000000e-01 --2.1151397852055691e+00 , 4.4319514476200927e+00 , 7.1060151999999999e+00 , -8.1950400000000001e-01 , 5.3568000000000005e-01 , -2.0361699999999999e-01 --8.2822845166165209e+00 , 7.2090949038223018e+00 , 1.2896599999999999e+01 , 6.9902699999999995e-01 , -1.2402900000000000e-01 , -7.0425700000000002e-01 --3.9162888078163292e+00 , 5.2792707499933051e+00 , 9.1195488000000005e+00 , 3.8407700000000000e-01 , -7.6080800000000004e-01 , -5.2312199999999998e-01 --1.9490314211735353e+00 , 4.4092018069503691e+00 , 7.4080208000000001e+00 , 8.2145400000000002e-01 , 5.6349499999999997e-01 , 8.7679099999999996e-02 --1.7207227118271553e+00 , 4.3221378631033911e+00 , 7.3355328000000002e+00 , -6.4073599999999997e-01 , -3.6388599999999999e-01 , -6.7605099999999996e-01 --1.2930357285327703e+00 , 4.1411692256157071e+00 , 7.0397775999999999e+00 , -5.7592500000000002e-01 , 1.0950500000000001e-01 , 8.1013500000000005e-01 --1.1634507147996742e+00 , 4.0972634002223352e+00 , 7.0445511999999999e+00 , -5.7592500000000002e-01 , 1.0950500000000001e-01 , 8.1013500000000005e-01 --5.7678834576066507e-01 , 3.8365478677090272e+00 , 6.5239168000000003e+00 , 2.0006599999999999e-01 , -4.7804900000000000e-01 , 8.5524400000000000e-01 --3.5085628496530941e-01 , 3.7434098802085254e+00 , 6.3838911999999999e+00 , -6.9129399999999996e-01 , 3.4414499999999998e-01 , 6.3535600000000003e-01 --2.4873461646067829e-01 , 3.7080927321278807e+00 , 6.3832256000000003e+00 , -2.4262600000000001e-01 , -2.5015399999999999e-01 , 9.3731299999999995e-01 --1.6780833427296971e-01 , 3.6820618172381696e+00 , 6.4030584000000008e+00 , -3.6369299999999999e-01 , 1.2403000000000000e-01 , 9.2322499999999996e-01 -6.5514050129950063e-01 , 3.2901107863149743e+00 , 5.4448960000000000e+00 , -6.2875300000000001e-01 , -2.8635499999999999e-03 , 7.7759999999999996e-01 --6.7042480571509389e-01 , 3.9617668170513793e+00 , 7.3468168000000000e+00 , 1.7228099999999999e-01 , 9.3033100000000002e-01 , 3.2373200000000002e-01 --1.0745111486754930e+00 , 4.1849251632347375e+00 , 8.0835944000000008e+00 , 2.9136800000000002e-01 , 8.5249299999999995e-01 , -4.3400600000000000e-01 -7.4561971725093734e-01 , 3.2760654601837773e+00 , 5.5947600000000008e+00 , -8.4553500000000004e-01 , 3.6480899999999997e-02 , 5.3267200000000003e-01 -7.8865361832459935e-01 , 3.2658579050049950e+00 , 5.6270623999999998e+00 , 8.7715100000000001e-01 , -1.3778399999999999e-01 , -4.6002399999999999e-01 -8.4826955501783008e-01 , 3.2454820017715420e+00 , 5.6334895999999999e+00 , 8.7715100000000001e-01 , -1.3778399999999999e-01 , -4.6002399999999999e-01 -1.1034409184373484e-02 , 3.7027585419493647e+00 , 7.1237056000000001e+00 , -2.6769100000000001e-01 , -1.8529699999999999e-01 , 9.4551900000000000e-01 --3.2805439910255618e-01 , 3.9035545468605930e+00 , 7.8740448000000001e+00 , 2.6743200000000000e-01 , 6.0365300000000000e-01 , 7.5105500000000003e-01 -9.3651007449952495e-01 , 3.2342618303115733e+00 , 5.8021776000000003e+00 , 2.7487400000000001e-01 , -7.5872200000000001e-01 , -5.9058100000000002e-01 -9.8301891028483368e-01 , 3.2211401495918803e+00 , 5.8313184000000007e+00 , -3.5990600000000000e-01 , -6.6575499999999999e-01 , -6.5363499999999997e-01 -1.0348732028088736e+00 , 3.2058124741614149e+00 , 5.8506415999999994e+00 , -4.0745199999999998e-01 , -6.0030600000000001e-01 , -6.8819699999999995e-01 -1.1130869637404190e+00 , 3.1750189289685551e+00 , 5.8145951999999994e+00 , 7.7171699999999999e-01 , 3.6008600000000002e-01 , 5.2420500000000003e-01 -7.1903728196990380e-01 , 3.4198219034267963e+00 , 6.7822008000000009e+00 , -7.8956800000000005e-01 , 2.2606299999999999e-01 , -5.7050699999999999e-01 -8.8513540680341385e-01 , 3.3410943981353030e+00 , 6.5849960000000003e+00 , 8.0715700000000001e-01 , -2.8960900000000000e-03 , 5.9033000000000002e-01 -9.2066472670998034e-01 , 3.3378654197555595e+00 , 6.6714199999999995e+00 , -6.8472000000000000e-01 , 7.0716599999999996e-01 , 1.7627899999999999e-01 -1.1027490842722183e+00 , 3.2447527429251042e+00 , 6.4009263999999995e+00 , 1.2388399999999999e-01 , 6.6358600000000001e-01 , 7.3777199999999998e-01 -1.1334159070286611e+00 , 3.2450692083180130e+00 , 6.4934136000000002e+00 , -6.0558000000000001e-01 , 7.2793900000000000e-01 , 3.2152399999999998e-01 -8.8384682327579633e-01 , 3.4278476860192484e+00 , 7.3578824000000003e+00 , -9.5385200000000003e-01 , -2.9026200000000002e-01 , 7.6908900000000002e-02 -1.2867416876005049e+00 , 3.1860262095172365e+00 , 6.4385952000000000e+00 , 5.5019399999999996e-01 , -5.5895199999999999e-02 , 8.3316400000000002e-01 -1.0265049815279617e+00 , 3.3869845446030808e+00 , 7.4279263999999996e+00 , -3.6136499999999999e-01 , -9.1918500000000003e-01 , -1.5657199999999999e-01 -1.1240368972330832e+00 , 3.3483812492442713e+00 , 7.3783392000000001e+00 , -7.5365300000000002e-01 , -5.4834000000000005e-01 , -3.6239500000000002e-01 -1.3698881588592313e+00 , 3.1995169805545118e+00 , 6.8078992000000005e+00 , 9.6213700000000002e-01 , 2.4364100000000000e-01 , -1.2218999999999999e-01 -1.3891991426711829e+00 , 3.2124725292059946e+00 , 6.9869767999999999e+00 , 6.4450700000000005e-01 , 4.2631100000000000e-01 , 6.3471999999999995e-01 -1.4674981879828499e+00 , 3.1822162366882409e+00 , 6.9589488000000008e+00 , 5.4259700000000000e-01 , -1.4806100000000000e-01 , 8.2684100000000005e-01 -1.5516224868863606e+00 , 3.1464342983729066e+00 , 6.8993983999999999e+00 , -5.5130599999999996e-01 , -2.5462899999999999e-01 , 7.9449700000000001e-01 -1.6027131063789053e+00 , 3.1377007480110888e+00 , 6.9776688000000000e+00 , 8.3939500000000000e-01 , 5.8782800000000003e-02 , -5.4033399999999998e-01 -1.6085591814694167e+00 , 3.1719513148449749e+00 , 7.2964808000000003e+00 , -7.3365400000000003e-01 , 6.3357799999999997e-01 , -2.4562300000000001e-01 -1.6919335633754951e+00 , 3.1374817511387221e+00 , 7.2432951999999995e+00 , 2.8511599999999998e-01 , 3.0063800000000002e-01 , 9.1012400000000004e-01 -1.4438215640733327e+00 , 3.4421212132802204e+00 , 9.1820215999999988e+00 , -5.6585799999999997e-01 , -8.2132499999999997e-01 , 7.2317099999999995e-02 -1.5932142969784775e+00 , 3.3574924262127310e+00 , 8.8887104000000008e+00 , -6.7917300000000003e-01 , 7.1529600000000004e-01 , -1.6454700000000000e-01 -1.7889050284542720e+00 , 3.2072889026325671e+00 , 8.1533472000000007e+00 , 5.8758800000000000e-01 , -7.8464100000000003e-01 , 1.9768200000000000e-01 --5.5962141627736894e-01 , 3.2595774144840157e+00 , 5.1747999999999994e-01 , -4.6578599999999998e-02 , -9.5738000000000004e-03 , 9.9886900000000001e-01 --6.7054921199384099e-01 , 3.3008028270957106e+00 , 5.1395440000000003e-01 , -3.1888600000000003e-02 , -7.6128299999999997e-04 , 9.9949100000000002e-01 --8.0461340307104257e-01 , 3.3494778436238621e+00 , 4.9504719999999991e-01 , -1.3047700000000001e-01 , -1.6554700000000000e-03 , 9.9145000000000005e-01 --9.4120360852286433e-01 , 3.4000920737295255e+00 , 4.7992559999999984e-01 , -1.5121499999999999e-01 , -1.9992800000000002e-02 , 9.8829900000000004e-01 --1.0382491891564216e+00 , 3.4379556436929573e+00 , 4.9958159999999996e-01 , -1.4018300000000000e-01 , -6.0484600000000003e-04 , 9.9012500000000003e-01 --1.2094377902903677e+00 , 3.4996915262758010e+00 , 4.6909919999999983e-01 , -1.0478899999999999e-01 , -1.3001800000000001e-02 , 9.9441000000000002e-01 --1.3823665906321843e+00 , 3.5615840061668194e+00 , 4.4427440000000007e-01 , -1.1227400000000000e-01 , 3.1997400000000000e-03 , 9.9367200000000000e-01 --1.5656688448994527e+00 , 3.6281650581961906e+00 , 4.1938720000000007e-01 , 9.4131300000000001e-02 , 1.3669199999999999e-02 , -9.9546599999999996e-01 --1.7419985904021198e+00 , 3.6935384612999345e+00 , 4.0583599999999986e-01 , -1.2176600000000000e-01 , -3.7007800000000000e-02 , 9.9186900000000000e-01 --1.9452454080652171e+00 , 3.7676324997973980e+00 , 3.8239439999999991e-01 , -1.3413400000000000e-01 , -6.3277299999999995e-02 , 9.8894099999999996e-01 --2.1240796776553523e+00 , 3.8345250118160292e+00 , 3.8107360000000012e-01 , 1.3503499999999999e-01 , 8.0672499999999994e-02 , -9.8755099999999996e-01 --2.3573034579552941e+00 , 3.9190857850492753e+00 , 3.5578079999999979e-01 , -1.3455400000000001e-01 , -7.2598399999999993e-02 , 9.8824299999999998e-01 --2.5914050694100945e+00 , 4.0063018900025815e+00 , 3.3817359999999996e-01 , -1.3411799999999999e-01 , -8.5966600000000004e-02 , 9.8722900000000002e-01 --2.8363619369969193e+00 , 4.0968142950253759e+00 , 3.2406079999999982e-01 , 1.4630299999999999e-01 , 7.6619599999999996e-02 , -9.8626800000000003e-01 --3.1540246554543874e+00 , 4.2114903413742608e+00 , 2.8260639999999992e-01 , 1.6127400000000000e-01 , 5.3241799999999999e-02 , -9.8547300000000004e-01 --3.5026501439363082e+00 , 4.3376748377149044e+00 , 2.3895759999999977e-01 , 1.5033600000000000e-01 , 4.1997199999999998e-02 , -9.8774300000000004e-01 --3.8161837281272479e+00 , 4.4543339456082158e+00 , 2.2408559999999977e-01 , 1.5856600000000001e-01 , 4.1262500000000001e-02 , -9.8648599999999997e-01 --4.3961927656403752e+00 , 4.6601889326301897e+00 , 1.0485999999999995e-01 , 1.7115000000000000e-01 , -2.1899800000000001e-02 , -9.8500200000000004e-01 --5.0462648573831155e+00 , 4.8911995779106565e+00 , -2.0345600000000186e-02 , -1.3166600000000001e-01 , 1.0620000000000000e-01 , 9.8558900000000005e-01 --5.7011406408044003e+00 , 5.1270621933494684e+00 , -1.2252560000000035e-01 , 1.0293700000000000e-01 , -1.2995799999999999e-01 , -9.8616199999999998e-01 --6.5840770118877501e+00 , 5.4424305866917404e+00 , -2.8458879999999986e-01 , -9.9554400000000001e-02 , 1.5458800000000000e-01 , 9.8294999999999999e-01 --7.4729136149950044e+00 , 5.7623543897921028e+00 , -4.1471359999999979e-01 , -8.9507199999999995e-02 , 1.5454399999999999e-01 , 9.8392299999999999e-01 --8.7810366602536511e+00 , 6.2298149484512919e+00 , -6.5039839999999982e-01 , -6.9176299999999996e-02 , 1.8658300000000000e-01 , 9.8000100000000001e-01 --1.0709904261032941e+01 , 6.9157883096098303e+00 , -1.0302584000000001e+00 , -8.1969899999999998e-02 , 2.5647999999999999e-01 , 9.6306800000000004e-01 --1.6784519808178214e+01 , 9.0382279901805198e+00 , -2.5488143999999995e+00 , -8.6281800000000006e-02 , -3.1576300000000002e-01 , 9.4490700000000005e-01 --2.6338597322886610e+01 , 1.2574838555376438e+01 , -3.1238304000000001e+00 , 4.7700800000000002e-02 , -9.4504999999999995e-01 , 3.2342599999999999e-01 --2.6841370800128200e+01 , 1.2813020669747777e+01 , -2.6761832000000005e+00 , 4.2354799999999998e-02 , -9.3600700000000003e-01 , 3.4942400000000001e-01 --2.6506231426512532e+01 , 1.2754255187664342e+01 , -2.0637375999999996e+00 , 3.6878000000000001e-02 , -9.3127599999999999e-01 , 3.6244399999999999e-01 --2.7366149058373747e+01 , 1.3183312507898126e+01 , -1.0977128000000000e+00 , 1.0212599999999999e-01 , -9.0308699999999997e-01 , 4.1713699999999998e-01 --2.7691851380894839e+01 , 1.3361991121683797e+01 , -5.8079119999999973e-01 , -2.3200999999999999e-02 , -8.7961199999999995e-01 , 4.7512500000000002e-01 --4.1473975678178228e+01 , 1.8906115073847108e+01 , 2.6354254400000001e+00 , -8.8528200000000001e-01 , 4.2086099999999999e-01 , -1.9786999999999999e-01 --4.1694609683778360e+01 , 1.9167957274733137e+01 , 4.2726912000000006e+00 , 7.8635200000000005e-01 , -3.7577899999999997e-01 , 4.9034800000000001e-01 --3.5282579302223853e+00 , 4.6878956553571554e+00 , 3.3526552000000001e+00 , 6.2836000000000003e-01 , -7.6910699999999999e-01 , 1.1678100000000000e-01 --3.5185972301130741e+00 , 4.6960935523239371e+00 , 3.4639144000000002e+00 , -6.0360899999999995e-01 , 7.8629700000000002e-01 , -1.3188300000000000e-01 --3.5267534337673681e+00 , 4.7116733229470782e+00 , 3.5763696000000000e+00 , 6.3011399999999995e-01 , -7.6104799999999995e-01 , 1.5415000000000001e-01 --3.5139628754626937e+00 , 4.7186698799299602e+00 , 3.6876080000000000e+00 , 7.1916300000000000e-01 , -6.9204100000000002e-01 , 6.2323499999999997e-02 --3.5085367114871477e+00 , 4.7293308009347559e+00 , 3.7996784000000003e+00 , 7.4396099999999998e-01 , -6.5772699999999995e-01 , 1.1797400000000000e-01 --3.5010742022418517e+00 , 4.7388976731552814e+00 , 3.9119983999999999e+00 , 7.6294300000000004e-01 , -6.3969100000000001e-01 , 9.3349100000000004e-02 --3.5021425953899925e+00 , 4.7512875896393023e+00 , 4.0259511999999997e+00 , -8.3574199999999998e-01 , 5.1875499999999997e-01 , -1.8007899999999999e-01 --3.5192743293380824e+00 , 4.7704704189554334e+00 , 4.1438664000000003e+00 , -8.6677499999999996e-01 , 4.9144199999999999e-01 , -8.4766099999999997e-02 --3.5535903350872635e+00 , 4.7976833274508923e+00 , 4.2663264000000005e+00 , -8.8768400000000003e-01 , 4.5732000000000000e-01 , -5.3624800000000000e-02 --3.5860761862706720e+00 , 4.8230918642259502e+00 , 4.3907728000000006e+00 , -9.2307200000000000e-01 , 3.5366900000000001e-01 , -1.5118200000000001e-01 --1.0296962828616289e+01 , 7.5379774667780373e+00 , 6.0987336000000001e+00 , 2.9654799999999998e-01 , 8.0909399999999998e-01 , 5.0737200000000005e-01 --1.0293698592837844e+01 , 7.5642766020821250e+00 , 6.3512143999999999e+00 , -2.9654799999999998e-01 , -8.0909399999999998e-01 , -5.0737200000000005e-01 --1.0210136944603807e+01 , 7.5577533072266938e+00 , 6.5844448000000000e+00 , 5.3001399999999999e-01 , 3.2894099999999998e-01 , -7.8159000000000001e-01 --7.2742610389113516e+00 , 6.3848563586839351e+00 , 5.9691912000000009e+00 , -2.3038400000000001e-03 , -3.3276600000000001e-01 , 9.4300700000000004e-01 --7.3021219380177698e+00 , 6.4184394790181445e+00 , 6.1773680000000004e+00 , 6.5668900000000002e-02 , -3.0576700000000001e-01 , 9.4983899999999999e-01 --4.7479412888535117e+00 , 5.3832646626954270e+00 , 5.5160528000000006e+00 , -8.7535300000000005e-01 , 3.4653699999999998e-01 , -3.3715000000000001e-01 --3.2894442358508513e+00 , 4.7931090757276564e+00 , 5.1432440000000001e+00 , -2.8835200000000000e-01 , 9.4810099999999997e-01 , 1.3400599999999999e-01 --3.3329383937885675e+00 , 4.8249769563953295e+00 , 5.2816160000000005e+00 , 3.6875700000000000e-01 , -9.2928100000000002e-01 , 2.1336399999999998e-02 --7.5341704271337164e+00 , 6.6061915012946733e+00 , 7.0966448000000000e+00 , 8.1573999999999994e-02 , -2.1410499999999999e-01 , 9.7339900000000001e-01 --5.6493194071451436e+00 , 5.8315923808118040e+00 , 6.5159712000000001e+00 , -3.3103399999999999e-01 , -8.6062000000000005e-01 , 3.8697500000000001e-01 --3.2488363451246247e+00 , 4.8310211352914276e+00 , 5.6246703999999994e+00 , 5.2419899999999997e-01 , -6.7345800000000000e-01 , -5.2122000000000002e-01 --2.9917670563579319e+00 , 4.7345703241220747e+00 , 5.6329903999999997e+00 , -4.6812500000000001e-01 , -4.8609900000000000e-01 , -7.3794700000000002e-01 --2.9279589620030446e+00 , 4.7209548321780499e+00 , 5.7266007999999999e+00 , 9.7824699999999998e-01 , -6.1496500000000003e-02 , 1.9811699999999999e-01 --3.0437097189769986e+00 , 4.7846116040581617e+00 , 5.9124280000000002e+00 , 6.8688800000000005e-01 , -6.7143600000000003e-01 , -2.7813500000000002e-01 --2.9669415581495855e+00 , 4.7653780935107761e+00 , 6.0019928000000000e+00 , -2.7271299999999998e-01 , 9.4086300000000000e-01 , 2.0100799999999999e-01 --2.8041499954031801e+00 , 4.7091028256697136e+00 , 6.0420015999999999e+00 , -4.8830899999999999e-01 , 6.5437200000000003e-03 , 8.7264600000000003e-01 --2.6260869397397224e+00 , 4.6438685514504634e+00 , 6.0671696000000006e+00 , 4.9138399999999999e-01 , 2.3529400000000000e-01 , 8.3855700000000000e-01 --2.6223544311193363e+00 , 4.6563933485074527e+00 , 6.1934047999999997e+00 , 6.8786499999999995e-01 , -2.7819400000000000e-01 , -6.7040999999999995e-01 --2.8295510140388993e+00 , 4.7630069152699264e+00 , 6.4569719999999995e+00 , -7.4085199999999996e-01 , -4.8738399999999998e-01 , -4.6216400000000002e-01 --2.5266260780055427e+00 , 4.6418840157026438e+00 , 6.3947592000000002e+00 , -1.5192799999999999e-02 , -8.7935799999999997e-01 , 4.7591800000000001e-01 --2.9001625403957947e+00 , 4.8264651095583684e+00 , 6.7885240000000007e+00 , -9.5635999999999999e-01 , 1.4891199999999999e-01 , 2.5139600000000001e-01 --5.0669780843644610e+00 , 5.8289645602462627e+00 , 8.4981384000000002e+00 , 3.9863599999999999e-01 , 5.0814199999999998e-01 , 7.6346700000000001e-01 --2.7291374091827167e+00 , 4.7805072607232706e+00 , 6.9605712000000004e+00 , -4.5315800000000001e-01 , 8.2138699999999998e-01 , 3.4636800000000001e-01 --2.7455173975769362e+00 , 4.8047237774415192e+00 , 7.1246728000000008e+00 , -4.5315800000000001e-01 , 8.2138699999999998e-01 , 3.4636800000000001e-01 --2.1120961430516774e+00 , 4.5272868875406118e+00 , 6.7682232000000004e+00 , -9.2213500000000004e-01 , 3.2474500000000001e-01 , -2.1025800000000000e-01 --2.0024070716389870e+00 , 4.4910206313591203e+00 , 6.8171864000000006e+00 , 5.0479499999999999e-01 , -2.3997299999999999e-01 , 8.2921299999999998e-01 --2.1070458603074469e+00 , 4.5561871040498936e+00 , 7.0497719999999999e+00 , -9.1948300000000005e-01 , 3.8434400000000002e-01 , -8.2649299999999995e-02 --2.0965613586409297e+00 , 4.5668122484689020e+00 , 7.1890592000000009e+00 , -9.2315999999999998e-01 , 2.9401200000000000e-01 , 2.4765499999999999e-01 --2.1252645166411250e+00 , 4.5980068259594820e+00 , 7.3694160000000002e+00 , -9.8844500000000002e-01 , -3.4106800000000000e-02 , 1.4769199999999999e-01 --1.6359923738526971e+00 , 4.3782684574805577e+00 , 7.0524655999999997e+00 , 4.5451300000000000e-01 , 8.1735500000000005e-01 , 3.5404700000000000e-01 --1.3732913710347834e+00 , 4.2668085117576986e+00 , 6.9347688000000005e+00 , -7.0408599999999999e-01 , 1.7374300000000001e-01 , 6.8853200000000003e-01 --1.2999541478092631e+00 , 4.2461260975240993e+00 , 7.0006008000000008e+00 , 5.7592500000000002e-01 , -1.0950500000000001e-01 , -8.1013500000000005e-01 --1.1717073820782176e+00 , 4.1984047468189249e+00 , 7.0071944000000004e+00 , 5.7592500000000002e-01 , -1.0950500000000001e-01 , -8.1013500000000005e-01 --1.0978587342967625e+00 , 4.1779215071911064e+00 , 7.0688768000000000e+00 , -5.7592500000000002e-01 , 1.0950500000000001e-01 , 8.1013500000000005e-01 --5.0214796671825601e-01 , 3.8934557915334427e+00 , 6.5219199999999997e+00 , 1.2482799999999999e-01 , -3.9565000000000000e-01 , 9.0987899999999999e-01 --3.4854741708440873e-01 , 3.8295447440488344e+00 , 6.4640751999999999e+00 , 8.1828899999999996e-02 , -5.2768199999999998e-01 , 8.4549099999999999e-01 --2.5265004741472685e-01 , 3.7939951859571170e+00 , 6.4715008000000003e+00 , -1.7574999999999999e-01 , -1.1542100000000000e-01 , 9.7764499999999999e-01 --1.3501568100998762e-01 , 3.7463828500169880e+00 , 6.4447416000000004e+00 , 4.4371899999999999e-02 , -2.6927899999999999e-01 , 9.6204000000000001e-01 --6.5015819805506414e-01 , 4.0310828767122864e+00 , 7.2682864000000000e+00 , -2.6213599999999998e-01 , -9.2125800000000002e-01 , -2.8734900000000002e-01 --5.9052607463750917e-01 , 4.0162388586877249e+00 , 7.3443416000000008e+00 , 1.1732400000000000e-01 , 7.9277299999999995e-01 , 5.9811899999999996e-01 --2.0675072152688267e+00 , 4.8253091434233157e+00 , 9.6588408000000001e+00 , -1.7513500000000001e-01 , 8.1343299999999996e-01 , 5.5466599999999999e-01 --2.1316967301507805e-01 , 3.8489860822697208e+00 , 7.1112152000000002e+00 , -8.5952899999999999e-01 , -4.2329600000000002e-02 , -5.0933099999999998e-01 --2.7864593301409535e-01 , 3.9024492616370310e+00 , 7.3731808000000001e+00 , -6.1679300000000004e-01 , 5.9435199999999999e-01 , -5.1605299999999998e-01 --3.8904576967172355e-01 , 3.9821635791106758e+00 , 7.7241599999999995e+00 , -4.2284300000000002e-01 , 7.5347299999999995e-01 , 5.0346999999999997e-01 --2.9987136186583774e-01 , 3.9530294562635802e+00 , 7.7619640000000008e+00 , 4.2284300000000002e-01 , -7.5347299999999995e-01 , -5.0346999999999997e-01 --1.5247626727410584e+00 , 4.6722055601199752e+00 , 1.0126778400000001e+01 , -4.8077599999999998e-01 , 7.2120399999999996e-01 , 4.9871799999999999e-01 --1.3767622701683120e+00 , 4.6197976316947367e+00 , 1.0151208000000000e+01 , -7.9561800000000005e-01 , 2.2735900000000001e-01 , 5.6151499999999999e-01 -1.0407945602428368e+00 , 3.2330853071741261e+00 , 5.7974975999999998e+00 , -3.5990600000000000e-01 , -6.6575499999999999e-01 , -6.5363499999999997e-01 -1.1000277351120529e+00 , 3.2104882864322830e+00 , 5.7981423999999997e+00 , -6.3837100000000002e-01 , -3.9830900000000002e-01 , -6.5865899999999999e-01 -7.0995146036304191e-01 , 3.4610735151190282e+00 , 6.7425664000000003e+00 , -2.1503000000000000e-01 , 7.7461800000000003e-01 , 5.9475100000000003e-01 -8.7148316233393208e-01 , 3.3794996642451887e+00 , 6.5566352000000006e+00 , -5.6390899999999999e-01 , 2.9598900000000001e-02 , -8.2530599999999998e-01 -9.3342683927875703e-01 , 3.3589164797855977e+00 , 6.5783504000000006e+00 , 8.5702400000000001e-01 , -2.8290900000000002e-01 , 4.3066599999999999e-01 -1.0738534500259576e+00 , 3.2875915914591247e+00 , 6.4124080000000001e+00 , 4.7086299999999998e-01 , 4.6076000000000000e-01 , -7.5232200000000005e-01 -1.1108139814175451e+00 , 3.2818512916776594e+00 , 6.4866847999999999e+00 , 4.4418700000000000e-01 , 8.1585600000000003e-01 , -3.7023899999999998e-01 -1.1861110025890163e+00 , 3.2510925739797223e+00 , 6.4659991999999997e+00 , -3.0004900000000001e-01 , 9.1188499999999995e-01 , 2.8006700000000001e-01 -1.2124296310281759e+00 , 3.2532653899369217e+00 , 6.5772583999999998e+00 , 6.6425900000000004e-01 , -5.7991000000000004e-01 , -4.7166100000000000e-01 -1.3128371953779561e+00 , 3.2053444655367480e+00 , 6.4768048000000000e+00 , -8.7780300000000000e-01 , 1.2169099999999999e-01 , -4.6330600000000000e-01 -1.0444629971215516e+00 , 3.4209631616616658e+00 , 7.5266120000000001e+00 , -7.7664699999999998e-01 , -4.2766999999999999e-01 , -4.6251300000000001e-01 -1.2406293190734976e+00 , 3.3049614831392766e+00 , 7.1455663999999999e+00 , -6.8504100000000001e-01 , 2.6569599999999999e-01 , -6.7832499999999996e-01 -1.3738938342434865e+00 , 3.2312827866251022e+00 , 6.9347895999999993e+00 , -9.1681900000000005e-01 , -3.1306299999999998e-01 , -2.4785900000000000e-01 -1.4334564181075595e+00 , 3.2137717912383383e+00 , 6.9765351999999998e+00 , -9.5547199999999999e-01 , -1.4407500000000001e-01 , 2.5751900000000000e-01 -1.5295448110893866e+00 , 3.1655695728000923e+00 , 6.8684687999999996e+00 , -3.7156700000000001e-02 , -2.9442400000000002e-01 , 9.5495200000000002e-01 -1.5995068361438649e+00 , 3.1380907342086575e+00 , 6.8576944000000006e+00 , -3.9249299999999998e-01 , -5.7062500000000005e-01 , 7.2134399999999999e-01 -1.5957412132905953e+00 , 3.1766537125636205e+00 , 7.1958608000000002e+00 , -5.3913800000000001e-01 , -8.2713199999999998e-01 , 1.5869100000000000e-01 -1.6700380393513843e+00 , 3.1476447656929603e+00 , 7.1836720000000005e+00 , -9.5540300000000000e-01 , -3.1799300000000003e-02 , 2.9358899999999999e-01 -1.7389643376825874e+00 , 3.1215795380707432e+00 , 7.1902344000000005e+00 , -5.4923599999999995e-01 , -4.2230299999999998e-01 , 7.2111000000000003e-01 -1.4468593147687865e+00 , 3.4860744597960567e+00 , 9.5167664000000016e+00 , 2.4593999999999999e-01 , 5.1848200000000000e-01 , 8.1895700000000005e-01 -1.6067280584063584e+00 , 3.3855721205535163e+00 , 9.1521840000000019e+00 , 5.9750700000000001e-01 , 8.0152299999999999e-01 , 2.3365000000000000e-02 --4.6455455027039738e-01 , 3.3322456109725254e+00 , 5.1367359999999995e-01 , -5.7220899999999998e-02 , -7.5889799999999993e-02 , 9.9547300000000005e-01 --5.5696011900182363e-01 , 3.3717182839246043e+00 , 5.2124479999999984e-01 , -2.4285399999999999e-02 , -2.9726099999999998e-02 , 9.9926300000000001e-01 --6.4318682231783919e-01 , 3.4085065995051234e+00 , 5.3790559999999976e-01 , -9.1949400000000001e-02 , -1.0822900000000001e-01 , 9.8986499999999999e-01 --7.6104914593929252e-01 , 3.4559347764179211e+00 , 5.3207119999999986e-01 , -1.0420300000000000e-01 , -1.7251200000000001e-02 , 9.9440600000000001e-01 --9.0313891394018198e-01 , 3.5131063218468630e+00 , 5.1142719999999997e-01 , -1.1057800000000000e-01 , 6.3956899999999999e-03 , 9.9384700000000004e-01 --1.0717482335666917e+00 , 3.5782938312961852e+00 , 4.7754399999999997e-01 , -1.0569199999999999e-01 , 3.2771099999999997e-02 , 9.9385900000000005e-01 --1.2333789840582718e+00 , 3.6422961433657384e+00 , 4.5500719999999983e-01 , -9.9097199999999996e-02 , 2.9576499999999999e-02 , 9.9463800000000002e-01 --1.4043181874658792e+00 , 3.7108633451984847e+00 , 4.3212719999999982e-01 , -9.3764899999999998e-02 , -3.1827299999999999e-03 , 9.9558899999999995e-01 --1.5693243930910321e+00 , 3.7771738684024969e+00 , 4.2036479999999998e-01 , -8.3978200000000003e-02 , -2.5318299999999998e-02 , 9.9614599999999998e-01 --1.7359958747371116e+00 , 3.8446324368034102e+00 , 4.1392720000000005e-01 , -9.3535900000000005e-02 , -5.8775599999999997e-02 , 9.9387999999999999e-01 --1.9033188710823241e+00 , 3.9132110964670392e+00 , 4.1297040000000007e-01 , -1.1885400000000000e-01 , -8.6530700000000002e-02 , 9.8913399999999996e-01 --2.1228287953181759e+00 , 4.0003183524222754e+00 , 3.8737599999999994e-01 , -1.4381900000000000e-01 , -7.5235300000000005e-02 , 9.8673999999999995e-01 --2.3277094049746312e+00 , 4.0838331954311613e+00 , 3.7869199999999981e-01 , 1.2834499999999999e-01 , 5.0858100000000003e-02 , -9.9042500000000000e-01 --2.5686229779232601e+00 , 4.1803118059875199e+00 , 3.5816240000000010e-01 , -9.7387799999999997e-02 , -4.4266899999999998e-02 , 9.9426199999999998e-01 --2.8193421033293609e+00 , 4.2811378124775139e+00 , 3.4134559999999992e-01 , 1.3556699999999999e-01 , 3.7004200000000001e-02 , -9.9007699999999998e-01 --3.1250802390602628e+00 , 4.4040462065594159e+00 , 3.0642239999999976e-01 , -1.2602700000000000e-01 , 2.0225600000000000e-02 , 9.9182099999999995e-01 --3.5139004418430959e+00 , 4.5568674065675197e+00 , 2.4410559999999992e-01 , -1.1583599999999999e-01 , -8.8767299999999993e-03 , 9.9322900000000003e-01 --3.8156164527506791e+00 , 4.6797740383681479e+00 , 2.3638879999999984e-01 , -1.2721199999999999e-01 , 3.1194800000000002e-02 , 9.9138499999999996e-01 --4.4816277776762865e+00 , 4.9364912670377432e+00 , 8.2510400000000095e-02 , 1.7349200000000001e-01 , -1.0694700000000000e-01 , -9.7901099999999996e-01 --5.2526960456032574e+00 , 5.2356770467013156e+00 , -8.8569600000000026e-02 , -1.0153500000000000e-01 , 1.4065700000000000e-01 , 9.8483799999999999e-01 --5.9298323712143173e+00 , 5.5029366240157183e+00 , -1.9248639999999995e-01 , -7.2516200000000003e-02 , 1.8216499999999999e-01 , 9.8058999999999996e-01 --6.8600128278181671e+00 , 5.8662638501641755e+00 , -3.6371200000000004e-01 , -6.9284999999999999e-02 , 1.6780300000000001e-01 , 9.8338300000000001e-01 --8.0468952551086144e+00 , 6.3306686903336331e+00 , -5.8874720000000025e-01 , 7.3206599999999997e-02 , -1.9753100000000001e-01 , -9.7755899999999996e-01 --9.6883963721208453e+00 , 6.9700204300532356e+00 , -9.1730400000000012e-01 , -7.1174100000000004e-02 , 2.0327799999999999e-01 , 9.7653100000000004e-01 --1.7819696234150090e+01 , 1.0154403377578074e+01 , -2.3890184000000003e+00 , -3.8900299999999999e-02 , -5.1171699999999998e-01 , 8.5827299999999995e-01 --2.4688310371924143e+01 , 1.2835618190093189e+01 , -3.7123040000000005e+00 , -6.6646899999999995e-02 , 8.4933499999999995e-01 , -5.2362900000000001e-01 --2.4833228029672281e+01 , 1.2946420158418631e+01 , -3.2194791999999994e+00 , -1.4329100000000000e-01 , 8.6788399999999999e-01 , -4.7565299999999999e-01 --2.5245220139712096e+01 , 1.3161831853887900e+01 , -2.7810255999999995e+00 , -1.7681400000000000e-01 , 8.4813899999999998e-01 , -4.9939600000000001e-01 --2.5183868528790850e+01 , 1.3193156953813808e+01 , -2.2383848000000004e+00 , 1.7041799999999999e-01 , -8.5550800000000005e-01 , 4.8894199999999999e-01 --2.0047521036980822e+01 , 1.1232982691670564e+01 , -8.2085439999999998e-01 , 9.4984299999999999e-01 , 2.3133000000000001e-01 , 2.1043999999999999e-01 --2.0148397755518740e+01 , 1.1318118632148259e+01 , -4.0926400000000029e-01 , -9.8071399999999997e-01 , -1.9357400000000000e-01 , -2.7013200000000001e-02 --2.0176893651255767e+01 , 1.1373889067238411e+01 , 1.4452799999999932e-02 , 9.0605400000000003e-01 , 1.0833900000000000e-01 , 4.0905900000000001e-01 --3.3838872214112188e+00 , 4.8098102628005668e+00 , 3.1664015999999999e+00 , -5.8192400000000000e-01 , 8.0885099999999999e-01 , -8.4413299999999997e-02 --3.3677331961316748e+00 , 4.8151859275880948e+00 , 3.2755912000000000e+00 , -5.8231100000000002e-01 , 7.9613199999999995e-01 , -1.6458200000000001e-01 --3.3505176060699906e+00 , 4.8194078956159316e+00 , 3.3845000000000001e+00 , 5.8045999999999998e-01 , -7.9653799999999997e-01 , 1.6909399999999999e-01 --3.3888462345140411e+00 , 4.8468897806691427e+00 , 3.4969239999999999e+00 , -6.7476800000000003e-01 , 7.0892999999999995e-01 , -2.0519899999999999e-01 --3.4053652964843879e+00 , 4.8649870910090769e+00 , 3.6095768000000001e+00 , -7.6746099999999995e-01 , 6.0330799999999996e-01 , -2.1684800000000001e-01 --3.4303656895757157e+00 , 4.8880185759564068e+00 , 3.7238416000000001e+00 , -8.1395899999999999e-01 , 5.5615199999999998e-01 , -1.6782700000000000e-01 --3.4429460907794303e+00 , 4.9052695061421545e+00 , 3.8384184000000001e+00 , -8.8923099999999999e-01 , 4.0246199999999999e-01 , -2.1746599999999999e-01 --3.4736438011818294e+00 , 4.9293426731604439e+00 , 3.9566144000000003e+00 , -9.0399200000000002e-01 , 3.9424199999999998e-01 , -1.6544500000000001e-01 --3.5480616212586993e+00 , 4.9741488755950041e+00 , 4.0840768000000001e+00 , -8.9578800000000003e-01 , 4.0075400000000000e-01 , -1.9225100000000001e-01 --1.1059466807201716e+01 , 8.2177837778078420e+00 , 5.6051392000000000e+00 , 6.5830200000000005e-01 , 7.4530700000000005e-01 , 1.0562199999999999e-01 --1.0509756804718192e+01 , 8.0082275228362398e+00 , 5.7574784000000001e+00 , -4.9634400000000001e-01 , -5.9899899999999995e-01 , -6.2836499999999995e-01 --1.0754981185246677e+01 , 8.1411530192986596e+00 , 6.0699256000000004e+00 , 8.5007100000000002e-01 , 4.6455600000000002e-01 , 2.4812699999999999e-01 --1.0927656698896888e+01 , 8.2444075058268318e+00 , 6.3768504000000004e+00 , 7.4791900000000000e-01 , 4.0198000000000000e-01 , -5.2823200000000003e-01 --9.0490995309657105e+00 , 7.4492938653807848e+00 , 6.1462408000000002e+00 , 2.6032499999999997e-01 , 7.6611399999999996e-01 , -5.8762199999999998e-01 --9.2653401700890239e+00 , 7.5693759287788698e+00 , 6.4431608000000002e+00 , 1.1335900000000000e-01 , 8.1339600000000001e-01 , 5.7055800000000001e-01 --9.3469810183098012e+00 , 7.6309167145602670e+00 , 6.7100976000000010e+00 , 3.6643399999999998e-01 , 9.2237999999999998e-01 , -1.2223299999999999e-01 --9.0874028522163410e+00 , 7.5406728663841394e+00 , 6.8709440000000006e+00 , 2.6032499999999997e-01 , 7.6611399999999996e-01 , -5.8762300000000001e-01 --6.1576242915746207e+00 , 6.2561482407688374e+00 , 6.0904240000000005e+00 , 2.4757499999999999e-01 , 9.2903999999999998e-01 , 2.7494000000000002e-01 --3.1821280302166848e+00 , 4.9372670767769389e+00 , 5.1701592000000005e+00 , -1.9668900000000000e-01 , 9.5041299999999995e-01 , 2.4089200000000000e-01 --3.0184506313043356e+00 , 4.8760460107306214e+00 , 5.2279727999999999e+00 , -1.4300199999999999e-01 , 9.7111499999999995e-01 , 1.9101499999999999e-01 --3.1647338941327279e+00 , 4.9559462989741512e+00 , 5.4088808000000004e+00 , 1.7475599999999999e-01 , -9.6825300000000003e-01 , 1.7873300000000000e-01 --2.9633049279352619e+00 , 4.8773664924344331e+00 , 5.4466120000000000e+00 , 8.5723000000000005e-01 , 4.4342399999999998e-01 , 2.6178600000000002e-01 --3.1470682678065831e+00 , 4.9737573523810958e+00 , 5.6539048000000003e+00 , -5.8778600000000003e-01 , 8.0801299999999998e-01 , 4.0276800000000001e-02 --3.0662176214931245e+00 , 4.9501411443337417e+00 , 5.7436775999999998e+00 , -6.3006499999999999e-01 , 6.6617199999999999e-01 , 3.9904000000000001e-01 --3.0271972933746136e+00 , 4.9460493228024687e+00 , 5.8529192000000005e+00 , 7.0710099999999998e-01 , -5.2746099999999996e-01 , -4.7094900000000001e-01 --3.0194003588588867e+00 , 4.9564267930605554e+00 , 5.9798720000000003e+00 , 1.7363799999999999e-01 , -6.6954300000000000e-01 , -7.2219199999999995e-01 --2.5052642891628478e+00 , 4.7284641871037216e+00 , 5.8276888000000007e+00 , 5.6702500000000000e-01 , -7.1078100000000000e-01 , 4.1626200000000002e-01 --2.7141787965730719e+00 , 4.8407780820045048e+00 , 6.0718079999999999e+00 , -3.6526999999999998e-01 , 1.4773200000000000e-01 , 9.1910499999999995e-01 --3.1241102700842847e+00 , 5.0481182699877447e+00 , 6.4495256000000003e+00 , -9.5547099999999996e-01 , -2.2525000000000001e-01 , 1.9062499999999999e-01 --3.0718756106341756e+00 , 5.0386722023714707e+00 , 6.5613256000000000e+00 , -8.9500800000000003e-01 , -2.3095800000000000e-01 , -3.8160100000000002e-01 --2.7849795203878402e+00 , 4.9157963197877592e+00 , 6.5186440000000001e+00 , 5.8261399999999997e-01 , 5.8778399999999997e-01 , 5.6131200000000003e-01 --2.4852262463209422e+00 , 4.7860824610440780e+00 , 6.4552768000000000e+00 , 5.6529500000000003e-02 , 5.6402900000000000e-01 , 8.2381800000000005e-01 --2.3393541662901969e+00 , 4.7301445352764588e+00 , 6.4880888000000008e+00 , -1.5265000000000001e-01 , 7.1220099999999997e-01 , 6.8517700000000004e-01 --4.7091349672982661e+00 , 5.9014605051173357e+00 , 8.3756887999999989e+00 , 5.7261100000000002e-02 , 6.4587399999999995e-01 , 7.6129400000000003e-01 --4.2935514001980994e+00 , 5.7190570900059345e+00 , 8.2652304000000001e+00 , -4.9275800000000002e-02 , 6.5979500000000002e-01 , 7.4982800000000005e-01 --4.1739694672364278e+00 , 5.6809442329328963e+00 , 8.3703743999999993e+00 , -8.8555499999999995e-02 , 6.4804099999999998e-01 , 7.5643899999999997e-01 --2.1461197384220636e+00 , 4.6928272281100103e+00 , 6.8921912000000010e+00 , -9.2057800000000001e-01 , 3.7618600000000002e-01 , -1.0497600000000000e-01 --2.0726800302904431e+00 , 4.6711681053405520e+00 , 6.9742679999999995e+00 , 9.6893799999999997e-01 , -2.2955300000000001e-01 , 9.2007199999999997e-02 --1.6861481834269472e+00 , 4.4924684326729878e+00 , 6.7759191999999997e+00 , -3.3548699999999998e-01 , 7.0438599999999996e-01 , 6.2553000000000003e-01 --1.4942507436369792e+00 , 4.4093460551758561e+00 , 6.7362848000000000e+00 , -6.0649799999999997e-02 , 6.3579500000000000e-01 , 7.6947100000000002e-01 --1.4174881845948266e+00 , 4.3836489909820600e+00 , 6.7990592000000003e+00 , 8.3216100000000004e-01 , -1.9944700000000001e-01 , -5.1742500000000002e-01 --1.3535231779903247e+00 , 4.3661708774223547e+00 , 6.8735024000000005e+00 , -7.7559900000000004e-01 , 2.4040600000000001e-01 , 5.8365400000000001e-01 --1.2955198136664201e+00 , 4.3502008292850300e+00 , 6.9541855999999997e+00 , -7.0408599999999999e-01 , 1.7374300000000001e-01 , 6.8853299999999995e-01 --1.2423963016922945e+00 , 4.3377833183712067e+00 , 7.0409424000000005e+00 , -5.7592500000000002e-01 , 1.0950500000000001e-01 , 8.1013500000000005e-01 --1.1749891703497641e+00 , 4.3174587090275836e+00 , 7.1125256000000006e+00 , -5.7592500000000002e-01 , 1.0950500000000001e-01 , 8.1013500000000005e-01 --1.8727202877427134e+00 , 4.7040616545817873e+00 , 8.0656128000000002e+00 , 7.6886699999999997e-01 , 4.8868699999999998e-01 , -4.1234399999999999e-01 --2.8615981437085392e-01 , 3.8726676341019792e+00 , 6.3541264000000002e+00 , -1.5619100000000000e-01 , 1.3536500000000001e-01 , 9.7840700000000003e-01 --2.0565360366074881e-01 , 3.8419037190016505e+00 , 6.3767048000000006e+00 , 2.8525699999999998e-01 , -1.1654299999999999e-01 , -9.5133900000000005e-01 --1.9835500617075619e-01 , 3.8517557103840603e+00 , 6.4904495999999998e+00 , -3.0406200000000000e-03 , 9.9590999999999996e-01 , 9.0302999999999994e-02 --6.9484486253602817e-02 , 3.7939949609321824e+00 , 6.4473311999999998e+00 , 6.2754799999999999e-01 , -6.6217300000000001e-01 , 4.0952300000000003e-01 --5.9183861232756119e-01 , 4.0973101254893001e+00 , 7.2984672000000002e+00 , 1.1504399999999999e-01 , 9.3943500000000002e-01 , 3.2284000000000002e-01 --5.7737370680439426e-01 , 4.1059406953827580e+00 , 7.4392832000000002e+00 , 2.6826100000000003e-01 , 9.5609900000000003e-01 , -1.1794300000000001e-01 --8.7363857791883692e-01 , 4.2917856781989290e+00 , 8.0507823999999992e+00 , 2.5985999999999998e-01 , -1.3668800000000000e-01 , 9.5592299999999997e-01 --3.7026531711958421e-01 , 4.0245752895805076e+00 , 7.4643680000000003e+00 , 2.3431399999999999e-01 , 9.5945700000000000e-01 , -1.5665200000000001e-01 --9.7420712298039724e-02 , 3.8839100041131434e+00 , 7.1985752000000005e+00 , 1.0579900000000000e-01 , -6.3296699999999997e-02 , 9.9237100000000000e-01 --3.2458966368940079e-01 , 4.0345557865403645e+00 , 7.7449912000000003e+00 , -4.2284300000000002e-01 , 7.5347299999999995e-01 , 5.0346999999999997e-01 --2.1154546721959022e-01 , 3.9881246703632254e+00 , 7.7389384000000003e+00 , 4.2284300000000002e-01 , -7.5347299999999995e-01 , -5.0346999999999997e-01 -1.7428869149999260e-01 , 3.7758042111270242e+00 , 7.2312311999999999e+00 , 2.3545199999999999e-01 , 3.8613300000000003e-02 , -9.7111899999999995e-01 -1.0352511246799665e+00 , 3.2694096653058304e+00 , 5.7710608000000008e+00 , -4.2006700000000002e-01 , -6.4824599999999999e-01 , -6.3507599999999997e-01 -3.4489717102836548e-01 , 3.7089208697028928e+00 , 7.2571376000000001e+00 , 2.2734099999999999e-01 , -4.5006099999999999e-01 , -8.6357499999999998e-01 -4.1897175964302491e-01 , 3.6815647169096191e+00 , 7.2900119999999999e+00 , -9.0071400000000001e-01 , 9.4907300000000000e-02 , 4.2391899999999999e-01 -8.1380654103269268e-01 , 3.4505248637748864e+00 , 6.6280728000000000e+00 , 6.7336200000000002e-01 , -8.7141899999999994e-02 , 7.3415900000000001e-01 -9.0918902512526523e-01 , 3.4055327921006486e+00 , 6.5779448000000000e+00 , -9.0537100000000004e-01 , -1.1405800000000001e-01 , -4.0901500000000002e-01 -1.0451121176501101e+00 , 3.3334435567712313e+00 , 6.4230575999999999e+00 , 4.3414100000000000e-01 , 3.4975899999999999e-01 , -8.3017500000000000e-01 -1.0628765054626874e+00 , 3.3391774927769742e+00 , 6.5448832000000001e+00 , 6.5487399999999996e-01 , -4.6862199999999998e-01 , -5.9290299999999996e-01 -1.1709377709023026e+00 , 3.2837988665312006e+00 , 6.4406648000000004e+00 , -3.2868900000000001e-01 , 9.4425300000000001e-01 , 1.8716300000000002e-02 -1.1342009287417278e+00 , 3.3285606379703050e+00 , 6.7235240000000003e+00 , -8.8958999999999999e-01 , 2.8747200000000001e-01 , 3.5494900000000001e-01 -9.9073114975321985e-01 , 3.4523793231114031e+00 , 7.3443519999999998e+00 , -4.2710300000000001e-01 , -7.7693800000000002e-01 , 4.6254800000000001e-01 -1.0179418845841970e+00 , 3.4589457530099588e+00 , 7.5092336000000000e+00 , 9.9635399999999996e-01 , 8.3601099999999998e-02 , -1.7017100000000000e-02 -1.1736682903090951e+00 , 3.3693612888800772e+00 , 7.2664455999999999e+00 , 6.7325500000000005e-01 , -4.5045600000000002e-01 , 5.8635999999999999e-01 -1.3357532650118333e+00 , 3.2719186368163493e+00 , 6.9702224000000008e+00 , -8.2502200000000003e-01 , -5.0785000000000002e-01 , -2.4784400000000001e-01 -1.4257975570985231e+00 , 3.2263432016784543e+00 , 6.8949992000000009e+00 , 6.5826799999999996e-01 , 7.3018600000000000e-01 , 1.8306200000000000e-01 -1.5009146537903475e+00 , 3.1930118572498731e+00 , 6.8668047999999997e+00 , 1.7851200000000000e-01 , -1.2488299999999999e-01 , 9.7597999999999996e-01 -1.5120713399677819e+00 , 3.2129840630360111e+00 , 7.1053704000000009e+00 , -5.8216699999999999e-01 , -1.7498500000000000e-02 , 8.1288099999999996e-01 -1.5704955326716632e+00 , 3.1959744994918715e+00 , 7.1651600000000002e+00 , 6.2040899999999999e-01 , 7.4779200000000001e-01 , 2.3643000000000000e-01 -1.6154758981969688e+00 , 3.1913823819929936e+00 , 7.2942448000000004e+00 , -3.9743899999999999e-01 , 2.2066200000000000e-01 , 8.9070199999999999e-01 -1.7022675490960459e+00 , 3.1465377134868082e+00 , 7.2114295999999998e+00 , -4.6992699999999998e-01 , -4.7658600000000001e-01 , 7.4299000000000004e-01 -1.4541983574364277e+00 , 3.4522045594698358e+00 , 9.1499480000000002e+00 , -5.6585799999999997e-01 , -8.2132499999999997e-01 , 7.2317099999999995e-02 -1.6061022273454111e+00 , 3.3541200395061583e+00 , 8.8167424000000008e+00 , -8.7669799999999998e-01 , -2.3155100000000001e-01 , -4.2164499999999999e-01 -1.7948584340119469e+00 , 3.2030307828310556e+00 , 8.1123816000000009e+00 , 6.0209999999999997e-01 , -7.7887899999999999e-01 , 1.7556800000000000e-01 --4.2869096888557978e-01 , 3.4313052013194199e+00 , 5.4394799999999988e-01 , -6.6599300000000000e-02 , -1.0726400000000000e-01 , 9.9199700000000002e-01 --5.2107768253456888e-01 , 3.4729358357553686e+00 , 5.5171680000000012e-01 , -9.1277800000000006e-02 , -5.8018300000000002e-02 , 9.9413399999999996e-01 --6.5914960720868354e-01 , 3.5317495372187651e+00 , 5.2425039999999989e-01 , -8.9654100000000000e-02 , 4.6023700000000001e-02 , 9.9490900000000004e-01 --7.8365624599244921e-01 , 3.5859380490954456e+00 , 5.1367359999999995e-01 , -9.7407900000000006e-02 , 5.5132300000000002e-02 , 9.9371600000000004e-01 --9.3347778171093321e-01 , 3.6499996722337569e+00 , 4.8876560000000002e-01 , -9.2646099999999995e-02 , 7.7772200000000000e-02 , 9.9265700000000001e-01 --1.0762933302189603e+00 , 3.7117462228447122e+00 , 4.7489199999999987e-01 , -4.8407600000000002e-02 , 5.1447399999999997e-02 , 9.9750200000000000e-01 --1.2283189845898321e+00 , 3.7778865917217317e+00 , 4.5977040000000002e-01 , -9.9820000000000006e-02 , 3.9993700000000000e-02 , 9.9420100000000000e-01 --1.3983072678377879e+00 , 3.8509760564006617e+00 , 4.3842960000000009e-01 , -8.4362099999999995e-02 , -6.0146699999999997e-03 , 9.9641700000000000e-01 --1.5362212306683203e+00 , 3.9133554158027808e+00 , 4.4456559999999978e-01 , -4.7169500000000003e-02 , -4.3643099999999997e-02 , 9.9793299999999996e-01 --1.7095706440353582e+00 , 3.9887347723923909e+00 , 4.3389519999999981e-01 , -5.2136399999999999e-02 , -4.9693500000000002e-02 , 9.9740300000000004e-01 --1.8825178742176871e+00 , 4.0663179603471322e+00 , 4.2891360000000001e-01 , -8.8069700000000001e-02 , -4.9245299999999999e-02 , 9.9489600000000000e-01 --2.0659913050679819e+00 , 4.1477204467476243e+00 , 4.2488879999999996e-01 , -9.7763500000000003e-02 , -6.2721900000000004e-03 , 9.9519000000000002e-01 --2.3281702818300118e+00 , 4.2600077960219513e+00 , 3.8340320000000006e-01 , -8.8132000000000002e-02 , 1.9254500000000001e-02 , 9.9592300000000000e-01 --2.5572973954311706e+00 , 4.3605840955331265e+00 , 3.6993520000000002e-01 , 7.5896099999999994e-02 , -2.6515700000000000e-02 , -9.9676299999999995e-01 --2.8667256339407894e+00 , 4.4930588700654654e+00 , 3.2373839999999987e-01 , 1.1711100000000001e-01 , -8.3742399999999995e-02 , -9.8958199999999996e-01 --3.1873120366402787e+00 , 4.6315805960207896e+00 , 2.8406240000000005e-01 , -8.4737099999999996e-02 , 7.5841500000000006e-02 , 9.9351299999999998e-01 --3.5279552770574023e+00 , 4.7800013652575828e+00 , 2.4713200000000013e-01 , -6.9288199999999994e-02 , 5.2300899999999997e-02 , 9.9622500000000003e-01 --3.8977614513773613e+00 , 4.9403697099981700e+00 , 2.1050320000000000e-01 , -1.3781499999999999e-01 , 1.1652300000000000e-01 , 9.8358000000000001e-01 --4.6735695093232188e+00 , 5.2652932810109805e+00 , 1.3350399999999985e-02 , -1.5607900000000000e-01 , 1.6938000000000000e-01 , 9.7311300000000001e-01 --5.4925246874256155e+00 , 5.6117876217967293e+00 , -1.7026160000000035e-01 , -4.9478200000000000e-02 , 1.8970300000000001e-01 , 9.8059399999999997e-01 --6.2536078681180776e+00 , 5.9371493074434625e+00 , -2.9884719999999998e-01 , -4.7089100000000002e-02 , 2.2503100000000001e-01 , 9.7321299999999999e-01 --7.3028638331586055e+00 , 6.3837804134208147e+00 , -5.0366479999999969e-01 , 6.6737800000000000e-02 , -2.1468599999999999e-01 , -9.7440000000000004e-01 --8.9188602044045098e+00 , 7.0656653970199423e+00 , -8.6333840000000039e-01 , -6.6425600000000001e-02 , 2.1024599999999999e-01 , 9.7538899999999995e-01 --1.2370056084854491e+01 , 8.5107366360656531e+00 , -1.7582792000000000e+00 , -1.0338899999999999e-01 , 1.8504000000000001e-01 , 9.7727699999999995e-01 --1.5133994533640454e+01 , 9.6852092933787457e+00 , -2.3057144000000003e+00 , 3.3857800000000001e-03 , -3.5486899999999999e-01 , 9.3491000000000002e-01 --1.5688036149115991e+01 , 9.9517309041821846e+00 , -2.1125552000000001e+00 , -6.6432000000000005e-02 , -1.7657900000000001e-01 , 9.8204199999999997e-01 --1.5736562094219881e+01 , 1.0007897887328637e+01 , -1.7653408000000002e+00 , 1.3503799999999999e-01 , 2.1660099999999999e-01 , -9.6687599999999996e-01 --2.3428461825743025e+01 , 1.3274581498606931e+01 , -3.3041456000000000e+00 , 4.7712299999999999e-02 , -8.8125799999999999e-01 , 4.7022000000000003e-01 --2.3780632278000745e+01 , 1.3474423566842312e+01 , -2.8772360000000008e+00 , 1.4354000000000000e-02 , -8.4121100000000004e-01 , 5.4051700000000003e-01 --2.4125924016355746e+01 , 1.3672264331741200e+01 , -2.4381895999999994e+00 , 5.8129000000000000e-02 , -8.2500099999999998e-01 , 5.6213400000000002e-01 --2.4728597536626292e+01 , 1.3980818119695117e+01 , -2.0368536000000006e+00 , -6.8120600000000003e-02 , 8.5679099999999997e-01 , -5.1114400000000004e-01 --2.4948524129771855e+01 , 1.4127668684921765e+01 , -1.5499567999999999e+00 , -1.2938500000000000e-01 , 8.4917900000000002e-01 , -5.1200999999999997e-01 --2.4885344684548116e+01 , 1.4154164658450219e+01 , -1.0145648000000005e+00 , -1.2938500000000000e-01 , 8.4917900000000002e-01 , -5.1200999999999997e-01 --5.3716840576535816e+01 , 2.6868968210639949e+01 , -2.1159455999999999e+00 , 5.6919900000000001e-01 , 8.2213999999999998e-01 , 9.8670600000000004e-03 --3.2807136076654624e+00 , 4.9461885822133009e+00 , 2.9851254400000000e+00 , -5.8084300000000000e-01 , 8.1321800000000000e-01 , -3.6033000000000003e-02 --3.2302791820828372e+00 , 4.9341067229925235e+00 , 3.0940488000000004e+00 , -5.8084300000000000e-01 , 8.1321800000000000e-01 , -3.6033000000000003e-02 --3.2150457972346453e+00 , 4.9382133892788076e+00 , 3.2020112000000003e+00 , 5.8296099999999995e-01 , -8.0003800000000003e-01 , 1.4175900000000000e-01 --3.2467302818141963e+00 , 4.9636994789146902e+00 , 3.3112424000000003e+00 , -6.7899699999999996e-01 , 6.8610899999999997e-01 , -2.6118500000000000e-01 --3.2943613028039449e+00 , 4.9957687052769550e+00 , 3.4233232000000000e+00 , -7.7106699999999995e-01 , 5.2707099999999996e-01 , -3.5728399999999999e-01 --3.3506080824334088e+00 , 5.0319171575685049e+00 , 3.5380456000000002e+00 , 8.2992400000000000e-01 , -4.6143000000000001e-01 , 3.1354399999999999e-01 --3.3850521901670856e+00 , 5.0597620129933549e+00 , 3.6530904000000000e+00 , 8.3645700000000001e-01 , -4.7788999999999998e-01 , 2.6825599999999999e-01 --1.1939644774128741e+01 , 8.9776444333669865e+00 , 4.7724215999999995e+00 , -7.5635699999999995e-01 , 3.2435300000000000e-01 , 5.6808400000000003e-01 --1.1458864453660757e+01 , 8.7856635009209150e+00 , 4.9866512000000007e+00 , -8.7550300000000003e-01 , -4.6182299999999998e-01 , 1.4217900000000000e-01 --1.0752677186554125e+01 , 8.4883728322913292e+00 , 5.1480904000000010e+00 , 8.2372899999999999e-02 , 7.0142899999999997e-01 , 7.0796300000000001e-01 --1.1034797953710726e+01 , 8.6446985957135247e+00 , 5.4579792000000005e+00 , -9.7034900000000002e-01 , -2.1745700000000001e-01 , 1.0552800000000000e-01 --1.0204340496129259e+01 , 8.2861148213105444e+00 , 5.5629151999999999e+00 , 5.2755799999999997e-01 , 5.8087000000000000e-01 , 6.1989799999999995e-01 --1.0884862431482938e+01 , 8.6284968289197046e+00 , 5.9629408000000002e+00 , -8.2683700000000004e-01 , -5.5726299999999995e-01 , -7.6150300000000004e-02 --1.0817214509653855e+01 , 8.6245733886887272e+00 , 6.2160976000000003e+00 , 6.7793899999999996e-01 , 6.4543899999999998e-01 , -3.5186299999999998e-01 --1.1086159114228797e+01 , 8.7776700851587321e+00 , 6.5549296000000004e+00 , -8.9644599999999997e-01 , -3.6469699999999999e-01 , 2.5175399999999998e-01 --9.9424380542032935e+00 , 8.2651260256572083e+00 , 6.5159712000000001e+00 , -1.2344500000000000e-01 , 6.5095599999999998e-01 , 7.4901099999999998e-01 --7.6812768439405748e+00 , 7.2175092221142219e+00 , 6.0993264000000007e+00 , -4.0074199999999999e-01 , -5.9107900000000002e-01 , 7.0002200000000003e-01 --8.6700953418172801e+00 , 7.7104970473018719e+00 , 6.6276463999999997e+00 , 3.9090799999999998e-01 , 7.3630899999999999e-01 , 5.5230500000000005e-01 --4.6766866048881406e+00 , 5.8207477174934343e+00 , 5.5049663999999998e+00 , -7.6131000000000004e-01 , 4.9426799999999999e-01 , -4.1965100000000000e-01 --4.6316336944497039e+00 , 5.8145361308824146e+00 , 5.6418719999999993e+00 , -8.4644100000000000e-01 , 3.9524199999999998e-01 , -3.5682100000000000e-01 --4.6726681264638978e+00 , 5.8495555036762337e+00 , 5.8121720000000003e+00 , -8.7249200000000005e-01 , 3.6106500000000002e-01 , -3.2922699999999999e-01 --2.8654424967376499e+00 , 4.9879114963816615e+00 , 5.2361576000000003e+00 , -1.9000700000000001e-01 , 9.8177599999999998e-01 , -3.5198899999999999e-03 --3.3578200631352164e+00 , 5.2401919883150851e+00 , 5.5663263999999995e+00 , 6.5828600000000004e-01 , -7.2129299999999996e-01 , -2.1539500000000000e-01 --5.6585392791969937e+00 , 6.3816606173768218e+00 , 6.7355464000000005e+00 , 7.5118600000000004e-03 , -3.0120599999999997e-01 , 9.5352999999999999e-01 --3.0169573180358604e+00 , 5.0991164433835445e+00 , 5.6714599999999997e+00 , 3.0331700000000000e-01 , -9.5226900000000003e-01 , -3.4382200000000002e-02 --2.8862407164933090e+00 , 5.0467491640495377e+00 , 5.7345672000000008e+00 , -4.2757899999999999e-01 , 7.5026499999999996e-01 , 5.0426099999999996e-01 --2.8392057112999893e+00 , 5.0367796505336067e+00 , 5.8374231999999999e+00 , -2.6971100000000001e-02 , 7.9387799999999997e-01 , 6.0747799999999996e-01 --2.5143801704979136e+00 , 4.8877629097470781e+00 , 5.7890008000000002e+00 , 2.5327699999999997e-01 , 4.0276000000000001e-01 , 8.7956500000000004e-01 --2.5569390922950390e+00 , 4.9215606620999512e+00 , 5.9371488000000001e+00 , -8.9819899999999997e-01 , -2.6411000000000001e-01 , -3.5140399999999999e-01 --2.7118179162686520e+00 , 5.0126646031031301e+00 , 6.1559856000000002e+00 , -6.6691299999999998e-01 , -6.9479800000000003e-01 , -2.6922600000000002e-01 --2.5774082287743312e+00 , 4.9574168081498566e+00 , 6.2055831999999995e+00 , 9.8989300000000002e-01 , 8.5144800000000007e-02 , -1.1340799999999999e-01 --3.1564107042139700e+00 , 5.2662484452233453e+00 , 6.7136648000000001e+00 , -9.6270199999999995e-01 , -2.5822299999999998e-01 , -8.0785200000000001e-02 --3.0618166401681375e+00 , 5.2330451289032363e+00 , 6.8009416000000007e+00 , -9.3125999999999998e-01 , -3.3940100000000001e-01 , 1.3251900000000000e-01 --3.2244766871423556e+00 , 5.3320159942644381e+00 , 7.0677016000000004e+00 , 9.2614399999999997e-01 , 3.3077699999999999e-01 , -1.8122900000000000e-01 --2.1105767985245549e+00 , 4.7701212546554173e+00 , 6.4137912000000004e+00 , 1.1781700000000001e-01 , 9.9224000000000001e-01 , 3.9750899999999999e-02 --2.0684354071826618e+00 , 4.7619399757865928e+00 , 6.5139848000000002e+00 , 3.0250300000000002e-01 , -9.5084999999999997e-01 , 6.6157300000000002e-02 --1.9415421701960263e+00 , 4.7092221230471889e+00 , 6.5481696000000005e+00 , -5.6499199999999999e-02 , -7.0827899999999999e-01 , 7.0366799999999996e-01 --1.6805997354291682e+00 , 4.5853934527785327e+00 , 6.4688591999999998e+00 , 4.2045700000000003e-01 , 8.8068800000000003e-01 , 2.1818599999999999e-01 --1.5856513744633980e+00 , 4.5477202237330427e+00 , 6.5181864000000003e+00 , -2.0592400000000000e-01 , 7.8105999999999998e-01 , 5.8952599999999999e-01 --1.5274299583279323e+00 , 4.5302557059080106e+00 , 6.5967583999999997e+00 , -2.3384500000000000e-01 , 7.7873499999999996e-01 , 5.8214100000000002e-01 --1.4670288086650216e+00 , 4.5114609174378328e+00 , 6.6744671999999996e+00 , -3.3548600000000001e-01 , 7.0438699999999999e-01 , 6.2553000000000003e-01 --1.4346369016760931e+00 , 4.5064605209074990e+00 , 6.7777704000000005e+00 , -2.0407800000000000e-02 , 7.1639100000000000e-01 , 6.9740100000000005e-01 --1.4061379458086729e+00 , 4.5051172126678063e+00 , 6.8878752000000008e+00 , -7.9567100000000002e-01 , 1.8087800000000001e-01 , 5.7809299999999997e-01 --2.2985471471023757e+00 , 5.0087663242117193e+00 , 7.9429656000000000e+00 , -7.3720699999999995e-01 , -5.1277399999999995e-01 , 4.3998700000000002e-01 --2.2302098676692070e+00 , 4.9891926759919096e+00 , 8.0500959999999999e+00 , 8.0947599999999997e-01 , 4.4550499999999998e-01 , -3.8245800000000002e-01 --6.9611019377984196e-02 , 3.8065545788470883e+00 , 5.8561328000000001e+00 , -3.3863799999999999e-01 , -2.9367399999999999e-01 , 8.9391299999999996e-01 -4.7403846841133745e-02 , 3.7516857198828104e+00 , 5.8248183999999998e+00 , 6.7007799999999995e-01 , 2.1990000000000001e-01 , -7.0897100000000002e-01 --7.2626914410801779e-01 , 4.1981514136703995e+00 , 6.8427496000000003e+00 , -3.1728400000000001e-01 , -9.0830999999999995e-01 , -2.7258900000000003e-01 --6.5083051358426225e-01 , 4.1694057565949336e+00 , 6.8900696000000003e+00 , -4.2892599999999997e-01 , -8.4943299999999999e-01 , -3.0738500000000002e-01 --5.8132157719763144e-01 , 4.1432145705019110e+00 , 6.9435463999999998e+00 , 5.1539800000000002e-01 , 8.0234799999999995e-01 , 3.0100399999999999e-01 --1.0743753244776544e-01 , 3.8847976632414403e+00 , 6.4630144000000005e+00 , 6.3307199999999997e-01 , -4.2961500000000002e-01 , 6.4393400000000001e-01 --1.1450890768981958e-01 , 3.9012552539577654e+00 , 6.6011784000000002e+00 , -8.8747600000000004e-01 , 4.4911299999999998e-01 , -1.0336300000000000e-01 --1.8789393182238445e+00 , 4.9531905146985444e+00 , 9.2481240000000007e+00 , -2.4182899999999999e-01 , 6.8098099999999995e-01 , 6.9121900000000003e-01 --1.8261717605231587e+00 , 4.9458792719871578e+00 , 9.4075455999999988e+00 , -4.8077599999999998e-01 , 7.2120399999999996e-01 , 4.9871799999999999e-01 --2.0021425939577497e-01 , 3.9955151514174938e+00 , 7.1561328000000000e+00 , -1.9020999999999999e-01 , -9.1038400000000005e-02 , 9.7751299999999997e-01 --1.2237894843534702e-01 , 3.9643689909938793e+00 , 7.1920544000000000e+00 , -3.4880100000000003e-01 , -2.4191699999999999e-01 , 9.0543600000000002e-01 --3.3055760448255267e-01 , 4.1089637449844005e+00 , 7.7019767999999997e+00 , -2.9521700000000001e-01 , 9.2742500000000005e-01 , 2.2963100000000000e-01 --2.1363241739575312e-01 , 4.0556366011861709e+00 , 7.6888208000000002e+00 , -2.9521700000000001e-01 , 9.2742500000000005e-01 , 2.2963100000000000e-01 -1.2790067030536267e-01 , 3.8607903995713029e+00 , 7.2636896000000002e+00 , 1.5049199999999999e-01 , 3.0978800000000001e-01 , -9.3881999999999999e-01 -1.0359600551735064e+00 , 3.3026294929000386e+00 , 5.7358463999999998e+00 , -4.2006700000000002e-01 , -6.4824599999999999e-01 , -6.3507599999999997e-01 -3.3547169786183217e-01 , 3.7638986117990085e+00 , 7.2223287999999997e+00 , -8.5634900000000000e-02 , 3.3898800000000001e-01 , 9.3688499999999997e-01 -1.1636190313526782e+00 , 3.2433073223995779e+00 , 5.7110944000000003e+00 , 6.9638699999999998e-01 , 3.5270899999999999e-01 , 6.2501300000000004e-01 -7.7833729126180429e-01 , 3.5101768804909232e+00 , 6.6530431999999999e+00 , -7.2656799999999999e-01 , 8.0264699999999994e-02 , -6.8239000000000005e-01 -8.9452212984966128e-01 , 3.4490063057313285e+00 , 6.5586840000000004e+00 , 4.7576200000000002e-01 , 4.7704200000000000e-03 , 8.7956100000000004e-01 -1.0027225545617466e+00 , 3.3914911375731913e+00 , 6.4702215999999995e+00 , 7.6881800000000000e-01 , 2.2331000000000001e-01 , -5.9921000000000002e-01 -1.0542463801374571e+00 , 3.3726583394039817e+00 , 6.5089407999999995e+00 , 5.8852800000000005e-01 , 1.2306700000000000e-01 , -7.9905499999999996e-01 -1.0782094580344661e+00 , 3.3731863939885272e+00 , 6.6220824000000000e+00 , -5.9018099999999996e-01 , 7.2165699999999999e-01 , 3.6179899999999998e-01 -1.2235699618223936e+00 , 3.2877402336135075e+00 , 6.4134584000000006e+00 , -2.9333199999999998e-01 , -1.5953499999999999e-02 , -9.5587699999999998e-01 -1.2274530046152070e+00 , 3.3023754041594620e+00 , 6.5818240000000001e+00 , -7.1896899999999997e-01 , 6.3299899999999998e-01 , -2.8704700000000000e-01 -1.0656002240627878e+00 , 3.4437968336154339e+00 , 7.2702936000000005e+00 , -5.2719800000000006e-01 , -1.9332400000000000e-01 , -8.2745899999999994e-01 -1.2515256137147412e+00 , 3.3262391800182529e+00 , 6.9214880000000001e+00 , -3.0930999999999997e-01 , 1.9002500000000000e-01 , 9.3178200000000000e-01 -1.2543806308839751e+00 , 3.3479454649088964e+00 , 7.1510264000000001e+00 , 3.5384900000000002e-01 , 9.1786500000000004e-01 , 1.7976400000000001e-01 -1.4071749470974810e+00 , 3.2513678878456513e+00 , 6.8624056000000007e+00 , -9.0102899999999997e-01 , -3.0669999999999997e-01 , 3.0672800000000000e-01 -1.4481590037982341e+00 , 3.2423471487633448e+00 , 6.9633896000000002e+00 , -5.6098000000000003e-01 , -4.7410400000000003e-01 , -6.7862100000000003e-01 -1.5254849177427861e+00 , 3.2047414255841082e+00 , 6.9250031999999999e+00 , -4.0677700000000000e-01 , 3.6552699999999999e-01 , -8.3721100000000004e-01 -1.5908000114600762e+00 , 3.1763524419482678e+00 , 6.9350392000000003e+00 , -9.6587199999999995e-01 , -9.0853600000000007e-02 , 2.4256300000000000e-01 -1.6239481968362406e+00 , 3.1781693877007449e+00 , 7.0934727999999998e+00 , -5.9963000000000000e-01 , -5.5174400000000001e-01 , -5.7967400000000002e-01 -1.6723435994265294e+00 , 3.1671916459869847e+00 , 7.2021424000000005e+00 , 9.6634900000000001e-01 , 4.5236199999999997e-02 , -2.5322699999999998e-01 -1.4228330727249392e+00 , 3.4655521015368107e+00 , 9.0566911999999995e+00 , -8.5469499999999998e-01 , -5.1912899999999995e-01 , 1.6051500000000001e-03 -1.6012292283136484e+00 , 3.3350714198728610e+00 , 8.5525304000000002e+00 , 7.6605400000000001e-01 , 6.2917699999999999e-01 , 1.3151900000000000e-01 -1.6148974895097754e+00 , 3.3853923525727572e+00 , 9.1108544000000009e+00 , -3.8904600000000000e-01 , -9.0454599999999996e-01 , 1.7447099999999999e-01 --3.0836673244990420e-01 , 3.4872123578023930e+00 , 5.6251199999999990e-01 , -9.2995800000000003e-02 , -1.3954599999999999e-02 , 9.9556900000000004e-01 --4.0589570090078597e-01 , 3.5336900013978565e+00 , 5.6161759999999994e-01 , -8.0442500000000000e-02 , -2.0583299999999999e-02 , 9.9654699999999996e-01 --5.2637706592120326e-01 , 3.5905833279317916e+00 , 5.4421839999999988e-01 , -9.2801400000000006e-02 , 6.2441600000000000e-02 , 9.9372499999999997e-01 --6.6348980579150618e-01 , 3.6538785214717331e+00 , 5.1818720000000007e-01 , -9.3732800000000005e-02 , 9.9361800000000000e-02 , 9.9062700000000004e-01 --7.9463056704517232e-01 , 3.7148294344733346e+00 , 5.0285760000000002e-01 , -1.0312200000000001e-01 , 9.8002500000000006e-02 , 9.8982899999999996e-01 --9.5869965825901637e-01 , 3.7901799311784212e+00 , 4.6763279999999985e-01 , -7.6779500000000001e-02 , 7.0808099999999999e-02 , 9.9453100000000005e-01 --1.0843242338091956e+00 , 3.8507209709256656e+00 , 4.6725839999999996e-01 , -4.7273500000000003e-02 , 4.7827300000000003e-02 , 9.9773599999999996e-01 --1.2267345993669498e+00 , 3.9190014627711909e+00 , 4.5956240000000004e-01 , -4.7818399999999997e-02 , 4.0625900000000000e-02 , 9.9802999999999997e-01 --1.3870891364652178e+00 , 3.9941923458100295e+00 , 4.4544959999999989e-01 , -4.4613899999999998e-02 , 2.7033100000000001e-02 , 9.9863900000000005e-01 --1.5480870617312497e+00 , 4.0705155789650336e+00 , 4.3678639999999991e-01 , -6.6441399999999998e-03 , 1.4737699999999999e-02 , 9.9986900000000001e-01 --1.6856557436891664e+00 , 4.1373687127198657e+00 , 4.4941199999999992e-01 , -1.3403699999999999e-02 , 4.5490900000000001e-02 , 9.9887499999999996e-01 --1.8905453970471284e+00 , 4.2337535010764018e+00 , 4.2555440000000000e-01 , -4.6023300000000003e-02 , 3.4438900000000001e-02 , 9.9834699999999998e-01 --2.0973092793858310e+00 , 4.3316366041554666e+00 , 4.0875839999999997e-01 , -8.3601200000000001e-02 , 6.8932700000000000e-02 , 9.9411200000000000e-01 --2.3565944099578315e+00 , 4.4518961857889536e+00 , 3.7056960000000005e-01 , -3.2501799999999997e-02 , 7.3488999999999999e-02 , 9.9676600000000004e-01 --2.5320794106945934e+00 , 4.5382818602454202e+00 , 3.8772959999999990e-01 , -7.5612600000000002e-02 , 9.3020199999999997e-02 , 9.9278900000000003e-01 --2.9411542780160680e+00 , 4.7252730035081898e+00 , 2.9041680000000003e-01 , -1.0984400000000000e-01 , -2.8643700000000001e-02 , 9.9353599999999997e-01 --3.2589549765252510e+00 , 4.8741326332512322e+00 , 2.5523359999999995e-01 , 2.3791799999999999e-01 , 9.2837900000000001e-02 , -9.6683799999999998e-01 --3.6567532621602972e+00 , 5.0605127067395177e+00 , 1.9421679999999997e-01 , -5.0724300000000000e-02 , 9.1913599999999998e-02 , 9.9447399999999997e-01 --4.2259800446853015e+00 , 5.3216428195619017e+00 , 7.2328799999999971e-02 , -1.4274300000000001e-01 , 1.6984099999999999e-01 , 9.7507900000000003e-01 --5.1012034596774196e+00 , 5.7195724691030394e+00 , -1.5783360000000002e-01 , -8.7792099999999998e-02 , 2.0668100000000000e-01 , 9.7446200000000005e-01 --5.9120749103143195e+00 , 6.0931943431880695e+00 , -3.2631360000000020e-01 , -5.2508399999999997e-02 , 2.2621900000000000e-01 , 9.7265999999999997e-01 --6.7664655116152890e+00 , 6.4879189463411144e+00 , -4.7840320000000025e-01 , -4.7989499999999997e-02 , 2.3885300000000001e-01 , 9.6986899999999998e-01 --8.1482480139933475e+00 , 7.1217140465846471e+00 , -7.8962319999999986e-01 , -6.4345299999999994e-02 , 2.1921199999999999e-01 , 9.7355300000000000e-01 --1.1307479777435992e+01 , 8.5544901165771225e+00 , -1.6570248000000003e+00 , -5.8946300000000000e-02 , 2.4418000000000001e-01 , 9.6793700000000005e-01 --1.4254310376046597e+01 , 9.9051272742315764e+00 , -2.3280536000000005e+00 , 8.8679300000000003e-02 , 3.6373499999999998e-01 , -9.2727199999999999e-01 --1.4626227139637216e+01 , 1.0106060098509445e+01 , -2.1003976000000000e+00 , -1.6286200000000001e-02 , -5.1385800000000004e-01 , 8.5772099999999996e-01 --1.4629723205795756e+01 , 1.0140581670452436e+01 , -1.7558248000000001e+00 , -5.9418400000000003e-02 , -5.4222499999999996e-01 , 8.3813000000000004e-01 --2.2184560008444521e+01 , 1.3610563919661184e+01 , -3.4002936000000004e+00 , -4.6071599999999997e-02 , 9.0140799999999999e-01 , -4.3051299999999998e-01 --2.2423091110455896e+01 , 1.3766483108259759e+01 , -2.9670504000000006e+00 , -4.6071599999999997e-02 , 9.0140799999999999e-01 , -4.3051299999999998e-01 --2.2858478460719105e+01 , 1.4013549881029354e+01 , -2.5714759999999997e+00 , 3.1707899999999997e-02 , -8.9346899999999996e-01 , 4.4800400000000001e-01 --2.2860544898301203e+01 , 1.4063005156134434e+01 , -2.0734095999999997e+00 , -3.2470799999999998e-03 , -8.6580199999999996e-01 , 5.0037699999999996e-01 --3.4008251489416395e+01 , 1.9266337977539475e+01 , -3.6283136000000002e+00 , 2.1484200000000001e-01 , -9.5543699999999998e-01 , 2.0244599999999999e-01 --3.4147271307462908e+01 , 1.9399346314655286e+01 , -2.9395943999999998e+00 , 2.1484200000000001e-01 , -9.5543699999999998e-01 , 2.0244599999999999e-01 --3.4341713462637131e+01 , 1.9558154206559959e+01 , -2.2561064000000002e+00 , 2.1484200000000001e-01 , -9.5543599999999995e-01 , 2.0244599999999999e-01 --3.4496928723208228e+01 , 1.9699340010852907e+01 , -1.5624056000000004e+00 , 2.1484200000000001e-01 , -9.5543599999999995e-01 , 2.0244599999999999e-01 --3.4621761363014613e+01 , 1.9827796164582374e+01 , -8.6145600000000000e-01 , 1.7353199999999999e-01 , -9.5854600000000001e-01 , 2.2600100000000001e-01 --3.4744959028651728e+01 , 1.9954992015385638e+01 , -1.5681440000000002e-01 , 1.7353199999999999e-01 , -9.5854600000000001e-01 , 2.2600100000000001e-01 --3.4857272500840580e+01 , 2.0077178365117859e+01 , 5.5245520000000004e-01 , 1.7353199999999999e-01 , -9.5854600000000001e-01 , 2.2600100000000001e-01 --3.5015535956547474e+01 , 2.0221884764021677e+01 , 1.2631298399999999e+00 , 1.7353199999999999e-01 , -9.5854600000000001e-01 , 2.2600100000000001e-01 --3.1307132345297317e+00 , 5.0703267545585611e+00 , 2.9165540800000000e+00 , 5.8951600000000004e-01 , -8.0769100000000005e-01 , -1.0295100000000000e-02 --3.0905694727873190e+00 , 5.0616874785027557e+00 , 3.0245196000000001e+00 , 5.7981099999999997e-01 , -8.0926600000000004e-01 , 9.4378199999999995e-02 --3.1147441086190062e+00 , 5.0832627895634390e+00 , 3.1317072000000001e+00 , 6.4684900000000001e-01 , -7.1170599999999995e-01 , 2.7397199999999999e-01 --3.1463609623353967e+00 , 5.1086246388421586e+00 , 3.2403247999999998e+00 , -6.6617800000000005e-01 , 6.5574200000000005e-01 , -3.5526000000000002e-01 --3.2136222527331260e+00 , 5.1520482647574628e+00 , 3.3519272000000000e+00 , 6.7509600000000003e-01 , -6.3236000000000003e-01 , 3.7995499999999999e-01 --1.1819761886601432e+01 , 9.3510225908436588e+00 , 4.0423727999999999e+00 , 4.7430400000000000e-01 , -7.8087899999999999e-01 , -4.0652800000000000e-01 --1.1857331974468753e+01 , 9.3965917152227991e+00 , 4.3237863999999995e+00 , 4.7430299999999997e-01 , -7.8087799999999996e-01 , -4.0652800000000000e-01 --1.1815358036195347e+01 , 9.4025853225556286e+00 , 4.5996672000000007e+00 , 4.7562399999999999e-01 , -5.3182900000000000e-01 , -7.0067100000000004e-01 --1.1074140633926312e+01 , 9.0654502317484820e+00 , 4.7867112000000009e+00 , -2.4252299999999999e-01 , 4.1425499999999998e-01 , 8.7725399999999998e-01 --1.1211199454973821e+01 , 9.1589461409190260e+00 , 5.0740943999999999e+00 , -8.7475800000000004e-01 , -4.4087900000000002e-01 , 2.0105999999999999e-01 --1.1407379626889179e+01 , 9.2818318909826552e+00 , 5.3786792000000005e+00 , -9.1868499999999997e-01 , -3.0040600000000001e-01 , 2.5646500000000000e-01 --1.1597155605846289e+01 , 9.4040102571946385e+00 , 5.6915320000000005e+00 , -9.1868499999999997e-01 , -3.0040600000000001e-01 , 2.5646500000000000e-01 --1.0016515507316962e+01 , 8.6405077500021612e+00 , 5.6491103999999996e+00 , 2.8713800000000000e-01 , 9.5303300000000002e-01 , 9.6337400000000004e-02 --1.3827010672243716e+01 , 1.0578456373625007e+01 , 6.7656440000000000e+00 , -6.7114799999999997e-01 , -7.4132200000000004e-01 , 1.5469200000000000e-03 --1.4099086891922582e+01 , 1.0747525295326357e+01 , 7.1668968000000000e+00 , 6.4287600000000000e-01 , 7.6504099999999997e-01 , -3.7722600000000002e-02 --1.1610456534530842e+01 , 9.5209271238545412e+00 , 6.8434256000000007e+00 , 9.1930900000000004e-01 , 3.6262499999999998e-01 , -1.5288199999999999e-01 --1.0693876349809736e+01 , 9.0840322865419623e+00 , 6.8733568000000007e+00 , 6.1374799999999996e-01 , 7.2940499999999997e-01 , -3.0212899999999998e-01 --4.4964537282144708e+00 , 5.9490724128146928e+00 , 5.2317064000000002e+00 , -7.3264600000000002e-01 , 6.0040000000000004e-01 , -3.2054500000000002e-01 --4.4121169987374618e+00 , 5.9198277889887372e+00 , 5.3522320000000008e+00 , -7.7602800000000005e-01 , 5.1551300000000000e-01 , -3.6335400000000001e-01 --2.8250322289820966e+00 , 5.1189314533473267e+00 , 4.9411616000000000e+00 , -1.9820199999999999e-01 , 9.5901899999999995e-01 , 2.0247899999999999e-01 --4.5188437757981301e+00 , 6.0043508861908768e+00 , 5.6910015999999999e+00 , 7.3991099999999999e-01 , -5.4401500000000003e-01 , 3.9570100000000002e-01 --5.8473241433805745e+00 , 6.7075052534339248e+00 , 6.3730752000000006e+00 , -2.4207999999999999e-01 , 8.0943100000000001e-01 , 5.3499399999999997e-01 --4.7589858701305445e+00 , 6.1593704881835327e+00 , 6.1034968000000003e+00 , 6.5434599999999998e-01 , -6.7420599999999997e-01 , 3.4245999999999999e-01 --4.7478421471027374e+00 , 6.1698321407164505e+00 , 6.2632199999999996e+00 , 2.1041599999999999e-01 , -9.0104499999999998e-01 , 3.7926599999999999e-01 --4.9294151189197715e+00 , 6.2803877107648676e+00 , 6.5149832000000005e+00 , -3.3270100000000002e-01 , -8.8582200000000000e-01 , 3.2346399999999997e-01 --2.7834147700953613e+00 , 5.1654737125547490e+00 , 5.6395320000000009e+00 , 1.9813000000000001e-03 , -9.8719400000000002e-01 , 1.5951099999999999e-01 --4.7216593966354381e+00 , 6.2049898639699155e+00 , 6.7595495999999997e+00 , -3.8444499999999998e-01 , 6.4335799999999999e-01 , -6.6203699999999999e-01 --2.7079758192574523e+00 , 5.1499182447264999e+00 , 5.8525032000000001e+00 , 2.7252799999999999e-01 , 9.1571199999999997e-01 , 2.9529800000000000e-01 --2.4616931500960995e+00 , 5.0311932626058047e+00 , 5.8427792000000007e+00 , 2.4707399999999999e-01 , 2.9511799999999999e-01 , 9.2296199999999995e-01 --2.2352337098728778e+00 , 4.9219477715551223e+00 , 5.8337728000000002e+00 , 2.6926599999999998e-02 , 8.0315400000000003e-01 , 5.9516199999999997e-01 --2.1555799562797961e+00 , 4.8895784991040356e+00 , 5.9061880000000002e+00 , 5.4901599999999995e-01 , -6.1882199999999998e-01 , -5.6181999999999999e-01 --2.0903121743792639e+00 , 4.8668252556494309e+00 , 5.9863511999999997e+00 , -6.5683999999999998e-01 , 4.2755399999999999e-01 , 6.2109499999999995e-01 --2.0327870157985108e+00 , 4.8472989135890430e+00 , 6.0703936000000001e+00 , -3.5546299999999997e-01 , 7.7564299999999997e-01 , 5.2155899999999999e-01 --1.9661441706197222e+00 , 4.8228400542747583e+00 , 6.1476552000000000e+00 , 5.1888500000000004e-01 , -5.4390899999999998e-01 , -6.5948600000000002e-01 --1.8824659387550242e+00 , 4.7887822642959907e+00 , 6.2125512000000001e+00 , 5.4765200000000003e-01 , -4.5465400000000000e-01 , -7.0240100000000005e-01 --1.7915588449822675e+00 , 4.7506293986019017e+00 , 6.2692104000000004e+00 , 5.5298099999999994e-01 , -3.9135700000000001e-01 , -7.3556200000000005e-01 --1.7142477754132273e+00 , 4.7202895602501389e+00 , 6.3353647999999998e+00 , 6.0961600000000005e-01 , -3.1770900000000002e-01 , -7.2624299999999997e-01 --1.6446957203394983e+00 , 4.6932051352087809e+00 , 6.4054919999999997e+00 , 7.2542200000000001e-01 , -2.2178300000000001e-01 , -6.5159400000000001e-01 --1.5878408044891970e+00 , 4.6741583966119720e+00 , 6.4864664000000003e+00 , 8.2207399999999997e-01 , -9.8330899999999999e-02 , -5.6082500000000002e-01 --1.5448310785900610e+00 , 4.6622693200926957e+00 , 6.5789848000000006e+00 , -1.4717000000000000e-01 , 8.5449100000000000e-01 , 4.9818400000000002e-01 --1.5147205502962509e+00 , 4.6576872216970191e+00 , 6.6838584000000001e+00 , -3.0879699999999999e-01 , 7.7849500000000005e-01 , 5.4643399999999998e-01 --7.6667415530464993e+00 , 8.1842897836979915e+00 , 1.2619128000000000e+01 , -6.7588700000000002e-02 , -6.7986599999999997e-01 , 7.3021499999999995e-01 --2.4449329787481657e+00 , 5.2188916661478375e+00 , 7.8689488000000010e+00 , 5.5688099999999996e-01 , 6.3001399999999996e-01 , -5.4126399999999997e-01 --2.3108164982312420e+00 , 5.1579709390084361e+00 , 7.9114431999999999e+00 , -7.3720699999999995e-01 , -5.1277399999999995e-01 , 4.3998700000000002e-01 --1.4858241566329022e-01 , 3.9175874494789387e+00 , 5.8158744000000002e+00 , -3.3863799999999999e-01 , -2.9367399999999999e-01 , 8.9391299999999996e-01 --7.6560795472802479e-02 , 3.8851779034010141e+00 , 5.8390768000000000e+00 , -3.3863799999999999e-01 , -2.9367399999999999e-01 , 8.9391299999999996e-01 --7.4468322200503199e+00 , 8.2390652869502148e+00 , 1.4281776000000001e+01 , -1.7688200000000001e-01 , -5.8005600000000002e-01 , 7.9514099999999999e-01 -7.2185021746863587e-02 , 3.8175237566996199e+00 , 5.8722943999999995e+00 , 6.7007799999999995e-01 , 2.1990000000000001e-01 , -7.0897100000000002e-01 --3.6250414860234459e-01 , 4.0870587040138346e+00 , 6.5059871999999999e+00 , 1.8807399999999999e-01 , -1.0673700000000000e-01 , 9.7633800000000004e-01 --3.3632305517229932e-01 , 4.0836962592949995e+00 , 6.6003151999999998e+00 , -2.2616300000000000e-01 , 4.0935199999999999e-01 , 8.8390100000000005e-01 --8.3009737291837471e-02 , 3.9422234085825325e+00 , 6.4001568000000004e+00 , -8.9182700000000004e-01 , 2.4469500000000000e-01 , -3.8048399999999999e-01 --1.7877843624959366e-01 , 4.0137296697401297e+00 , 6.6555704000000002e+00 , 4.2767200000000000e-01 , 7.8481999999999996e-01 , 4.4850200000000001e-01 --1.0331442062633123e-01 , 3.9791528202860240e+00 , 6.6845448000000003e+00 , 4.6490599999999999e-01 , -8.4418400000000005e-01 , 2.6686500000000002e-01 --2.1425815598331788e-02 , 3.9423022159945296e+00 , 6.7035144000000004e+00 , 4.6490500000000001e-01 , -8.4418400000000005e-01 , 2.6686500000000002e-01 --1.5607417851617211e+00 , 4.9205756803917611e+00 , 9.1857864000000014e+00 , -3.1207400000000002e-01 , 6.9852700000000001e-01 , 6.4394799999999996e-01 --1.2243178526977472e-01 , 4.0347763536176053e+00 , 7.1515256000000003e+00 , -1.9020999999999999e-01 , -9.1038400000000005e-02 , 9.7751299999999997e-01 --1.9001548528317214e-01 , 4.0923540660113709e+00 , 7.4228719999999999e+00 , -1.5743900000000000e-01 , 5.4370399999999997e-01 , 8.2437800000000006e-01 --2.2287263785241862e-01 , 4.1311109141133660e+00 , 7.6556864000000004e+00 , -2.3942500000000000e-01 , -9.5855599999999996e-01 , -1.5442500000000001e-01 --7.3834901807408038e-03 , 4.0090301106826320e+00 , 7.4593655999999999e+00 , -2.2445399999999999e-01 , -5.0927000000000000e-01 , -8.3082100000000003e-01 -2.1412642848080909e-01 , 3.8799670699107924e+00 , 7.2297023999999999e+00 , 3.2061099999999999e-03 , 8.5446700000000000e-02 , 9.9633799999999995e-01 -3.1371585663163937e-01 , 3.8309677100297632e+00 , 7.2132912000000005e+00 , 2.8458799999999999e-02 , 2.9019800000000001e-01 , 9.5654300000000003e-01 -3.8541598437659608e-01 , 3.7998300462292001e+00 , 7.2479544000000002e+00 , -2.5658700000000001e-01 , 3.1054500000000002e-01 , 9.1527300000000000e-01 -4.3214771695122867e-01 , 3.7857030080508336e+00 , 7.3353767999999997e+00 , -9.0071400000000001e-01 , 9.4907300000000000e-02 , 4.2391899999999999e-01 -8.8514025057943013e-01 , 3.4903782994718915e+00 , 6.5301152000000000e+00 , 4.7576200000000002e-01 , 4.7706500000000004e-03 , 8.7956100000000004e-01 -9.2153627534392202e-01 , 3.4801516206491989e+00 , 6.6083544000000005e+00 , 4.7576200000000002e-01 , 4.7704200000000000e-03 , 8.7956100000000004e-01 -1.0361316284904030e+00 , 3.4153055996593267e+00 , 6.5006624000000004e+00 , -3.4879399999999999e-01 , -4.7837999999999999e-02 , 9.3597799999999998e-01 -1.1024349465849703e+00 , 3.3829890561910005e+00 , 6.5020040000000003e+00 , -2.2472400000000001e-01 , 1.5317000000000000e-01 , 9.6230899999999997e-01 -1.1966073868855922e+00 , 3.3307693137130281e+00 , 6.4262920000000001e+00 , 3.4921000000000002e-01 , -8.9145600000000003e-01 , 2.8871900000000000e-01 -1.2538477163887611e+00 , 3.3050942191714481e+00 , 6.4428384000000003e+00 , -5.8030199999999998e-01 , -1.1166800000000000e-01 , 8.0670900000000001e-01 -9.6296175512739279e-01 , 3.5459785489468159e+00 , 7.4920423999999999e+00 , 7.9207399999999994e-01 , -4.2920199999999997e-01 , -4.3405500000000002e-01 -1.2589288699650640e+00 , 3.3393701246458134e+00 , 6.8195888000000000e+00 , 6.5291999999999994e-01 , 7.3848100000000005e-01 , -1.6834700000000000e-01 -1.1701080596812803e+00 , 3.4320434502277393e+00 , 7.3396616000000003e+00 , 6.8627400000000005e-01 , 4.4459599999999999e-01 , 5.7564099999999996e-01 -1.3297901196402870e+00 , 3.3264734059600660e+00 , 7.0447280000000001e+00 , -7.4179200000000001e-01 , 6.4608299999999996e-01 , -1.7978000000000000e-01 -1.4272974542552614e+00 , 3.2695071912694180e+00 , 6.9408839999999996e+00 , 5.2185999999999999e-01 , 7.9666899999999996e-01 , 3.0492799999999998e-01 -1.5033888315264783e+00 , 3.2289877225964583e+00 , 6.9036000000000000e+00 , -2.7371800000000002e-01 , 6.9846100000000000e-01 , -6.6123399999999999e-01 -1.4645891871528316e+00 , 3.2920500716394567e+00 , 7.3611687999999997e+00 , 8.4535099999999996e-01 , 4.8169600000000001e-01 , 2.3097799999999999e-01 -1.5650351551233608e+00 , 3.2321246868848847e+00 , 7.2327392000000001e+00 , 6.8633299999999997e-01 , -5.7187500000000002e-01 , -4.4934000000000002e-01 -1.6312395654173237e+00 , 3.2013692108869067e+00 , 7.2523432000000003e+00 , -2.8451700000000002e-01 , 8.9883100000000005e-01 , -3.3339500000000000e-01 -1.7089891860187592e+00 , 3.1608357044867139e+00 , 7.2100152000000000e+00 , -4.6322500000000000e-01 , -4.7220699999999999e-01 , 7.4996200000000002e-01 -1.5035873996517741e+00 , 3.4201839674570023e+00 , 8.8856216000000003e+00 , 7.8340799999999999e-01 , 5.2129199999999998e-01 , 3.3841800000000000e-01 -1.6141994789609553e+00 , 3.3580429113259567e+00 , 8.7852408000000004e+00 , 7.3405699999999996e-01 , 4.3369900000000000e-01 , 5.2255700000000005e-01 -1.7947730230831906e+00 , 3.2071625750577235e+00 , 8.1223136000000018e+00 , 6.0209999999999997e-01 , -7.7887899999999999e-01 , 1.7556700000000000e-01 --2.0336186966521730e-01 , 3.5446195249191303e+00 , 5.6944879999999998e-01 , -6.6712300000000002e-02 , 4.3547799999999998e-02 , 9.9682199999999999e-01 --3.0603309291799086e-01 , 3.5959441776741081e+00 , 5.5989120000000003e-01 , -1.0499100000000000e-01 , 5.4463800000000000e-02 , 9.9298100000000000e-01 --4.1659226685815920e-01 , 3.6522596200613213e+00 , 5.4698479999999994e-01 , -5.1021999999999998e-02 , 7.0120699999999994e-02 , 9.9623300000000004e-01 --5.2860969190768925e-01 , 3.7093300011891275e+00 , 5.3759359999999989e-01 , 8.6118200000000006e-02 , -8.8136199999999998e-02 , -9.9237900000000001e-01 --6.6479189700315988e-01 , 3.7771433252531716e+00 , 5.1310159999999994e-01 , -1.0463699999999999e-01 , 9.6392500000000006e-02 , 9.8982800000000004e-01 --8.0908256850449423e-01 , 3.8492554352371005e+00 , 4.8707040000000013e-01 , -1.2233600000000000e-01 , 9.2846100000000001e-02 , 9.8813600000000001e-01 --9.6359986944630105e-01 , 3.9268499098830367e+00 , 4.5978079999999988e-01 , -5.7447600000000001e-02 , 4.9883999999999998e-02 , 9.9710100000000002e-01 --1.0883156656727122e+00 , 3.9908647407553621e+00 , 4.6103919999999987e-01 , -1.3644200000000000e-02 , 3.0228999999999999e-02 , 9.9944999999999995e-01 --1.2287552893786930e+00 , 4.0636619930587452e+00 , 4.5511119999999994e-01 , -5.4427200000000002e-02 , 3.6852500000000003e-02 , 9.9783699999999997e-01 --1.3871698008152080e+00 , 4.1434164676954088e+00 , 4.4294319999999998e-01 , -3.1243600000000000e-02 , 5.1171800000000003e-02 , 9.9820100000000000e-01 --1.5462018126463426e+00 , 4.2253272464624407e+00 , 4.3614159999999980e-01 , 1.1728000000000001e-03 , 5.6313500000000002e-02 , 9.9841199999999997e-01 --1.7145895228718482e+00 , 4.3119312876719107e+00 , 4.2950639999999995e-01 , -1.0486400000000000e-02 , 6.9949200000000003e-02 , 9.9749500000000002e-01 --1.9176362656677872e+00 , 4.4141439758234302e+00 , 4.0862319999999985e-01 , -4.0903000000000002e-02 , 1.0822500000000000e-01 , 9.9328499999999997e-01 --2.1719861111992174e+00 , 4.5416753999392823e+00 , 3.6545279999999991e-01 , -2.7244100000000000e-02 , 1.2388299999999999e-01 , 9.9192300000000000e-01 --2.4284560533443447e+00 , 4.6711328175204914e+00 , 3.3135119999999985e-01 , -2.9082700000000000e-02 , 1.1380100000000000e-01 , 9.9307800000000002e-01 --2.7377869283409586e+00 , 4.8257417446037261e+00 , 2.7910159999999995e-01 , -9.3961799999999998e-02 , 9.3954200000000002e-02 , 9.9113300000000004e-01 --3.0582911267495190e+00 , 4.9875193717261634e+00 , 2.3366400000000009e-01 , -1.5342300000000000e-01 , -2.4960900000000000e-01 , 9.5611500000000005e-01 --3.2959543801266529e+00 , 5.1109415995950354e+00 , 2.4216079999999995e-01 , 2.7741600000000000e-01 , 3.0145899999999998e-01 , -9.1222999999999999e-01 --3.7498486488202420e+00 , 5.3374375687524385e+00 , 1.5747359999999988e-01 , -1.9825100000000001e-01 , 5.8231100000000001e-02 , 9.7841999999999996e-01 --4.5911519326224122e+00 , 5.7489496524515786e+00 , -8.2392000000000021e-02 , -1.3190499999999999e-01 , 2.0139699999999999e-01 , 9.7058800000000001e-01 --5.5450227817003137e+00 , 6.2188849886439961e+00 , -3.3562160000000008e-01 , -5.5040899999999997e-02 , 2.3509300000000000e-01 , 9.7041299999999997e-01 --6.3221887056698662e+00 , 6.6070432776514476e+00 , -4.7746719999999998e-01 , -2.8428499999999999e-02 , 2.3984000000000000e-01 , 9.7039600000000004e-01 --7.4593020839241539e+00 , 7.1707478856802318e+00 , -7.2602719999999987e-01 , -5.4577000000000001e-02 , 2.2936100000000001e-01 , 9.7180999999999995e-01 --8.7121566893697597e+00 , 7.7944502215960574e+00 , -9.7025039999999985e-01 , -6.1079000000000001e-02 , 2.2103900000000001e-01 , 9.7335099999999997e-01 --1.3139585381546402e+01 , 9.9622638708097657e+00 , -2.2491800000000000e+00 , -1.5609100000000001e-01 , 2.9366400000000001e-02 , 9.8730600000000002e-01 --1.4718366929899460e+01 , 1.0760046943914174e+01 , -2.4315959999999999e+00 , 1.6286200000000001e-02 , 5.1385800000000004e-01 , -8.5772000000000004e-01 --2.1003479428044951e+01 , 1.3907813611783848e+01 , -3.4855007999999996e+00 , 9.0763200000000002e-02 , -8.3642499999999997e-01 , 5.4051300000000002e-01 --2.1157069216417085e+01 , 1.4027893637149450e+01 , -3.0490544000000002e+00 , 9.0763200000000002e-02 , -8.3642499999999997e-01 , 5.4051300000000002e-01 --2.1542184384437800e+01 , 1.4260956811075271e+01 , -2.6645456000000003e+00 , 9.0763200000000002e-02 , -8.3642499999999997e-01 , 5.4051400000000005e-01 --2.1481606755071784e+01 , 1.4276207731191555e+01 , -2.1701920000000001e+00 , -1.2087100000000001e-01 , 8.3960400000000002e-01 , -5.2958099999999997e-01 --3.2953723547693876e+01 , 2.0031370045195761e+01 , -3.9802704000000002e+00 , 2.1484200000000001e-01 , -9.5543599999999995e-01 , 2.0244599999999999e-01 --3.2985811856693495e+01 , 2.0111667689155876e+01 , -3.2828048000000001e+00 , 2.1484200000000001e-01 , -9.5543599999999995e-01 , 2.0244599999999999e-01 --2.2205810649365624e+01 , 1.4815757705568013e+01 , -3.7395599999999973e-01 , -8.0564300000000005e-02 , 9.2745000000000000e-01 , -3.6516599999999999e-01 --3.2851667075697172e+01 , 2.0237229009838035e+01 , -1.1712720000000001e+00 , 2.1484200000000001e-01 , -9.5543699999999998e-01 , 2.0244599999999999e-01 --3.6924634770361608e+00 , 5.5196715901077038e+00 , 2.4603414400000001e+00 , 4.3466800000000000e-01 , 8.4292500000000004e-01 , 3.1708100000000000e-01 --3.6038383365330375e+00 , 5.4852901476562668e+00 , 2.5878922400000000e+00 , 4.6246900000000002e-01 , 8.3234799999999998e-01 , 3.0548300000000000e-01 --3.0325260461152403e+00 , 5.2049726918841897e+00 , 2.7414659200000000e+00 , -5.7338299999999998e-01 , 8.1611800000000001e-01 , 7.1998199999999998e-02 --3.0049141141205231e+00 , 5.2011999319184383e+00 , 2.8498349599999999e+00 , 5.7101599999999997e-01 , -8.1579699999999999e-01 , -9.1740100000000005e-02 --2.9854671143820442e+00 , 5.2006958053752461e+00 , 2.9568863200000002e+00 , 5.9726400000000002e-01 , -8.0199200000000004e-01 , 9.2105899999999994e-03 --2.9825319505020440e+00 , 5.2092494355401264e+00 , 3.0632231999999999e+00 , 5.9954200000000002e-01 , -7.9641700000000004e-01 , 7.9172699999999999e-02 --3.0243529821130473e+00 , 5.2400875891105247e+00 , 3.1704783999999999e+00 , -4.1707000000000000e-01 , 8.9065700000000003e-01 , -1.8105900000000000e-01 --1.1623647150759352e+01 , 9.7184396535925579e+00 , 3.5889432000000001e+00 , 4.7430400000000000e-01 , -7.8087799999999996e-01 , -4.0652800000000000e-01 --1.1566895090064955e+01 , 9.7138249608942679e+00 , 3.8626608000000004e+00 , 4.7430400000000000e-01 , -7.8087799999999996e-01 , -4.0652800000000000e-01 --1.1560302357344023e+01 , 9.7362676951891416e+00 , 4.1388847999999996e+00 , 4.7430299999999997e-01 , -7.8087899999999999e-01 , -4.0652800000000000e-01 --1.1559124855722860e+01 , 9.7602974233643032e+00 , 4.4165960000000002e+00 , 4.7430299999999997e-01 , -7.8087799999999996e-01 , -4.0652800000000000e-01 --1.1645335687445744e+01 , 9.8317143590468792e+00 , 4.7052271999999995e+00 , -6.4615000000000000e-01 , 6.7686400000000002e-01 , 3.5262700000000002e-01 --4.9796056218264466e+00 , 6.3335113327232291e+00 , 4.0853560000000000e+00 , 6.5602400000000005e-01 , 7.5440300000000005e-01 , -2.2544800000000000e-02 --5.0114463446841642e+00 , 6.3649506508210836e+00 , 4.2398375999999995e+00 , 6.5602400000000005e-01 , 7.5440300000000005e-01 , -2.2544900000000000e-02 --5.0690317259729767e+00 , 6.4083831602017547e+00 , 4.4009960000000001e+00 , 6.5602400000000005e-01 , 7.5440300000000005e-01 , -2.2544900000000000e-02 --5.1312848466500505e+00 , 6.4561540109110078e+00 , 4.5668135999999997e+00 , 6.5602400000000005e-01 , 7.5440300000000005e-01 , -2.2544900000000000e-02 --5.2099482850690482e+00 , 6.5123771171540872e+00 , 4.7395160000000001e+00 , 6.5602400000000005e-01 , 7.5440300000000005e-01 , -2.2544800000000000e-02 --5.2752703950742852e+00 , 6.5630382673674763e+00 , 4.9137784000000000e+00 , 7.1244700000000005e-01 , 6.9457199999999997e-01 , 9.9946900000000005e-02 --5.3828897756695717e+00 , 6.6355273525815051e+00 , 5.1030168000000007e+00 , 7.8691900000000004e-01 , 6.1615200000000003e-01 , 3.3397299999999998e-02 --4.2705395462315794e+00 , 6.0476173704076643e+00 , 4.9573752000000004e+00 , -2.1481600000000001e-01 , -8.3175200000000005e-01 , -5.1190100000000005e-01 --4.2257970681536570e+00 , 6.0368647929191450e+00 , 5.0874791999999998e+00 , -1.3463500000000000e-02 , 9.8336900000000005e-01 , 1.8111800000000000e-01 --2.6689197867702807e+00 , 5.2002495558363941e+00 , 4.7298232000000002e+00 , -1.9459000000000001e-01 , 9.6286799999999995e-01 , 1.8713700000000000e-01 --2.5864047593245614e+00 , 5.1656482384529170e+00 , 4.8128672000000003e+00 , -1.9317400000000001e-01 , 9.5961799999999997e-01 , 2.0449100000000001e-01 --2.5546507104608871e+00 , 5.1588737554613182e+00 , 4.9125095999999999e+00 , -6.1585899999999999e-02 , 9.8626800000000003e-01 , 1.5324299999999999e-01 --2.5653190012211784e+00 , 5.1741777543457239e+00 , 5.0283552000000000e+00 , 5.0140100000000000e-02 , -9.8160599999999998e-01 , -1.8421899999999999e-01 --2.5391266101963890e+00 , 5.1703931388032247e+00 , 5.1311071999999998e+00 , -8.5418499999999994e-02 , 9.6826400000000001e-01 , 2.3488000000000001e-01 --2.4342576436029963e+00 , 5.1225701095872305e+00 , 5.2007040000000000e+00 , 2.6844699999999999e-01 , -8.1574899999999995e-01 , -5.1233799999999996e-01 --2.3804897379557062e+00 , 5.1031522796182500e+00 , 5.2897280000000002e+00 , -4.3086000000000002e-01 , 6.8253500000000000e-01 , 5.9034399999999998e-01 --2.3167392750346059e+00 , 5.0779903786299441e+00 , 5.3734167999999993e+00 , 3.5343200000000002e-01 , -8.4725099999999998e-01 , -3.9655000000000001e-01 --2.2595300788568755e+00 , 5.0568294822694870e+00 , 5.4597888000000001e+00 , -4.8862499999999998e-01 , 7.7604700000000004e-01 , 3.9874300000000001e-01 --2.2021745940528259e+00 , 5.0343187419633040e+00 , 5.5447568000000000e+00 , 5.8010399999999995e-01 , -7.0936900000000003e-01 , -4.0034399999999998e-01 --2.1591845574437132e+00 , 5.0213751333525973e+00 , 5.6372648000000005e+00 , -6.0056799999999999e-01 , 7.1324500000000002e-01 , 3.6138500000000001e-01 --2.1072542367987710e+00 , 5.0026990164812171e+00 , 5.7243232000000006e+00 , 5.4447000000000001e-01 , -7.2205399999999997e-01 , -4.2683800000000000e-01 --2.0541640043185065e+00 , 4.9826981313530165e+00 , 5.8102896000000008e+00 , -6.1565099999999995e-01 , 6.2438700000000003e-01 , 4.8074400000000000e-01 --2.0077625591613870e+00 , 4.9669548580983598e+00 , 5.9001456000000001e+00 , -6.6539199999999998e-01 , 5.4230699999999998e-01 , 5.1298800000000000e-01 --1.9680921802760856e+00 , 4.9544737546192321e+00 , 5.9942032000000003e+00 , 7.1958999999999995e-01 , -3.8290999999999997e-01 , -5.7928400000000002e-01 --1.9183887005241380e+00 , 4.9372032514491533e+00 , 6.0825199999999997e+00 , 7.9668300000000003e-01 , -1.8014300000000000e-01 , -5.7692699999999997e-01 --1.8595880576717634e+00 , 4.9150491283261868e+00 , 6.1642640000000002e+00 , 7.5462700000000005e-01 , -1.7762100000000000e-01 , -6.3165600000000000e-01 --1.7927460157638482e+00 , 4.8869378378403265e+00 , 6.2393104000000008e+00 , -8.4398899999999999e-01 , -1.3574400000000000e-01 , 5.1889900000000000e-01 --1.7544015266302133e+00 , 4.8760768144723130e+00 , 6.3358640000000008e+00 , -9.4157800000000003e-01 , -2.3949999999999999e-01 , 2.3679200000000000e-01 --1.8618735468818657e+00 , 4.9515033286793768e+00 , 6.5502808000000003e+00 , -7.5148899999999996e-01 , 6.5974500000000003e-01 , 7.2805700000000005e-04 --1.8553918729636734e+00 , 4.9602028497247117e+00 , 6.6791368000000002e+00 , -8.1426100000000001e-01 , 5.4053700000000005e-01 , 2.1165600000000001e-01 --1.8379397682230194e+00 , 4.9621063918023331e+00 , 6.8029904000000005e+00 , 6.1316800000000005e-01 , -7.7390599999999998e-01 , -1.5841000000000000e-01 --1.8184459539370819e+00 , 4.9639887364108937e+00 , 6.9271872000000005e+00 , -5.1785000000000003e-01 , 8.3027600000000001e-01 , 2.0608799999999999e-01 --7.9998030408912548e+00 , 8.6998038401094906e+00 , 1.2851048000000000e+01 , -6.7588700000000002e-02 , -6.7986599999999997e-01 , 7.3021499999999995e-01 --7.7277514773483276e+00 , 8.5699607245433249e+00 , 1.2955048000000000e+01 , -6.7588899999999993e-02 , -6.7986599999999997e-01 , 7.3021499999999995e-01 --7.5181318733228402e+00 , 8.4758930197249427e+00 , 1.3112608000000000e+01 , -6.7588599999999999e-02 , -6.7986599999999997e-01 , 7.3021499999999995e-01 --6.4987282370819717e+00 , 7.8861521032954869e+00 , 1.2421528000000000e+01 , 2.4117900000000000e-01 , -7.7664699999999998e-01 , 5.8193799999999996e-01 --6.7163651870463799e+00 , 8.0521218613425187e+00 , 1.3003824000000002e+01 , -7.5990100000000005e-02 , -6.9423100000000004e-01 , 7.1572999999999998e-01 --5.5746699383794063e-02 , 3.9580749128046753e+00 , 5.8943528000000001e+00 , -3.3863799999999999e-01 , -2.9367399999999999e-01 , 8.9391299999999996e-01 --6.8703443380723916e-01 , 4.3615635096038829e+00 , 6.7346208000000010e+00 , -7.1225799999999995e-01 , 1.6446500000000000e-01 , -6.8237800000000004e-01 --3.7498397145736018e-01 , 4.1784621290161148e+00 , 6.4932264000000002e+00 , -3.2783000000000001e-01 , -5.7497100000000001e-01 , -7.4962399999999996e-01 --2.6472877729234767e-01 , 4.1206100650436390e+00 , 6.4825768000000004e+00 , 3.5115800000000003e-01 , 8.3720099999999997e-01 , 4.1926400000000003e-01 --1.3886007426714109e-01 , 4.0524782151146068e+00 , 6.4453135999999995e+00 , -9.1579100000000002e-01 , 1.4047499999999999e-01 , -3.7629000000000001e-01 --2.4045392164939727e-03 , 3.9768253239288649e+00 , 6.3888312000000003e+00 , 2.8367099999999999e-02 , -6.4791899999999999e-02 , 9.9749600000000005e-01 --9.6152052126577736e-02 , 4.0483592849184102e+00 , 6.6447960000000004e+00 , -9.4185500000000000e-01 , 2.8322000000000003e-01 , 1.8081800000000001e-01 --9.9337238243084158e-02 , 4.0629729872214959e+00 , 6.7851856000000002e+00 , 7.6120500000000002e-01 , -6.2899600000000000e-01 , -1.5789700000000001e-01 --1.0365341547118545e-01 , 4.0795540117415792e+00 , 6.9350807999999997e+00 , -6.7067800000000000e-01 , 7.1398600000000001e-01 , -2.0103699999999999e-01 --2.0977579072910801e-01 , 4.1638176123910693e+00 , 7.2516256000000006e+00 , -6.8955999999999995e-01 , 7.0497500000000002e-01 , -1.6588300000000000e-01 --4.9952533085648732e-02 , 4.0717740488229826e+00 , 7.1556439999999997e+00 , 8.3601400000000003e-01 , -2.3419599999999999e-01 , -4.9621900000000002e-01 --7.5211660422914495e-02 , 4.1033059740759663e+00 , 7.3594216000000001e+00 , -1.0666600000000000e-01 , 8.3950599999999997e-01 , 5.3277699999999995e-01 --1.0805953757301534e-02 , 4.0755921820015679e+00 , 7.4200847999999997e+00 , -6.3069500000000001e-02 , 7.2715300000000005e-01 , 6.8357199999999996e-01 -6.8305277936469455e-02 , 4.0385181450304675e+00 , 7.4532192000000004e+00 , 1.5584899999999999e-01 , 6.0216999999999998e-01 , 7.8300800000000004e-01 --1.1690077551876108e+00 , 4.9113672626990876e+00 , 1.0003652800000001e+01 , 2.2039600000000001e-01 , -8.4875100000000003e-01 , -4.8067300000000002e-01 -3.7495619873647579e-01 , 3.8588108978300606e+00 , 7.2222456000000008e+00 , -3.5086000000000001e-01 , 2.1267500000000002e-02 , 9.3618599999999996e-01 -3.5894436262994311e-01 , 3.8865507880075203e+00 , 7.4355912000000002e+00 , -8.3038699999999999e-01 , -4.9300699999999997e-01 , 2.5961800000000002e-01 -4.9974975214841755e-01 , 3.8040969126085402e+00 , 7.3251120000000007e+00 , -9.0071400000000001e-01 , 9.4907500000000006e-02 , 4.2391899999999999e-01 -7.0834636650007510e-01 , 3.6709199905792862e+00 , 7.0459240000000003e+00 , 5.7553500000000002e-01 , -1.0913800000000000e-02 , 8.1770399999999999e-01 -1.0001374661220961e+00 , 3.4732807057739685e+00 , 6.5383312000000000e+00 , 3.9372600000000002e-01 , -3.9972200000000002e-01 , 8.2776899999999998e-01 -1.0852609058758975e+00 , 3.4246809634033495e+00 , 6.4944743999999996e+00 , -2.7658899999999997e-01 , 2.0112700000000000e-01 , 9.3970600000000004e-01 -1.1357632800601674e+00 , 3.4025637648299680e+00 , 6.5324656000000001e+00 , 5.2906399999999998e-01 , -7.4809499999999995e-01 , -4.0055700000000000e-01 -1.2491313916541384e+00 , 3.3316114084203710e+00 , 6.3994911999999999e+00 , -5.1288500000000004e-01 , -2.2381899999999999e-01 , 8.2876700000000003e-01 -1.2818809820760109e+00 , 3.3224070737445119e+00 , 6.4820152000000002e+00 , -9.5001400000000003e-01 , 5.2891800000000003e-02 , 3.0769400000000002e-01 -1.2082679120975868e+00 , 3.3992746482061933e+00 , 6.9005632000000006e+00 , -9.6372899999999995e-01 , 2.7977499999999999e-02 , -2.6541199999999998e-01 -1.3158725477775470e+00 , 3.3316638750840539e+00 , 6.7724144000000006e+00 , -8.8426300000000002e-01 , -3.1490299999999999e-01 , 3.4484100000000001e-01 -1.3492469668050098e+00 , 3.3241460934631668e+00 , 6.8844848000000001e+00 , 6.8607799999999997e-01 , 2.5274999999999999e-02 , 7.2708899999999999e-01 -1.3803470618881586e+00 , 3.3206029005814992e+00 , 7.0158784000000001e+00 , -2.1760099999999999e-01 , -2.7218599999999998e-01 , 9.3731799999999998e-01 -1.3871054963314757e+00 , 3.3389407299233209e+00 , 7.2558688000000000e+00 , 3.1007800000000002e-01 , 9.2299799999999999e-01 , 2.2787399999999999e-01 -1.5521120338700767e+00 , 3.2176838027947983e+00 , 6.8631440000000001e+00 , -4.4457000000000002e-01 , -2.8069600000000000e-01 , 8.5062800000000005e-01 -1.5530950594541719e+00 , 3.2439449748588816e+00 , 7.1518167999999998e+00 , 3.6726100000000000e-01 , 8.2864199999999999e-01 , 4.2245899999999997e-01 -1.6395803285786072e+00 , 3.1912811756574992e+00 , 7.0617111999999995e+00 , 9.9839999999999995e-01 , -6.3095900000000003e-03 , -5.6193399999999998e-02 -1.6756917937655453e+00 , 3.1867058136579507e+00 , 7.2206336000000002e+00 , -6.1567099999999997e-01 , -6.0237900000000000e-01 , 5.0802499999999995e-01 -1.7410578252865798e+00 , 3.1545388415626183e+00 , 7.2382928000000000e+00 , -2.8485899999999997e-01 , -5.9717699999999996e-01 , 7.4982300000000002e-01 -1.6253585549166234e+00 , 3.3242363979760410e+00 , 8.4300807999999989e+00 , -5.8817399999999997e-01 , -7.6440399999999997e-01 , 2.6407900000000001e-01 -1.7209667914812199e+00 , 3.2693895367131898e+00 , 8.3680136000000012e+00 , 8.4421200000000002e-02 , -7.7062600000000003e-01 , 6.3167099999999998e-01 --1.1658301677196281e-02 , 3.5500322383848730e+00 , 5.7927679999999993e-01 , -8.3128099999999996e-02 , 1.2742399999999999e-02 , 9.9645700000000004e-01 --9.6606305569646445e-02 , 3.5970545917190928e+00 , 5.7846559999999991e-01 , -8.2577600000000001e-02 , 1.7226600000000002e-02 , 9.9643599999999999e-01 --1.9043452565329444e-01 , 3.6478903323031990e+00 , 5.7358799999999999e-01 , -9.8247000000000001e-02 , 6.0263999999999998e-02 , 9.9333600000000000e-01 --3.1250905001022389e-01 , 3.7142657576158058e+00 , 5.4494639999999994e-01 , 7.6657100000000006e-02 , -7.3255799999999996e-02 , -9.9436300000000000e-01 --4.1567244499063039e-01 , 3.7697458633413414e+00 , 5.4003760000000001e-01 , -6.6929500000000003e-02 , 7.4408000000000002e-02 , 9.9497899999999995e-01 --5.4078234211707477e-01 , 3.8378511349332705e+00 , 5.1935200000000004e-01 , -9.4793299999999997e-02 , 8.3702100000000002e-02 , 9.9197199999999996e-01 --6.5985882824684250e-01 , 3.9035184637069253e+00 , 5.0896240000000015e-01 , -9.9852999999999997e-02 , 9.5415299999999995e-02 , 9.9041699999999999e-01 --8.0322103113438503e-01 , 3.9801588969073656e+00 , 4.8456399999999999e-01 , -1.2320200000000001e-01 , 7.7024899999999993e-02 , 9.8938800000000005e-01 --9.4815705756758772e-01 , 4.0588572816541566e+00 , 4.6480399999999977e-01 , -6.3513100000000003e-02 , 5.8897600000000001e-02 , 9.9624199999999996e-01 --1.0861149126117269e+00 , 4.1341738029287098e+00 , 4.5607839999999999e-01 , -3.7885400000000000e-03 , 4.7678800000000000e-02 , 9.9885599999999997e-01 --1.2332571238583587e+00 , 4.2149611261066173e+00 , 4.4619839999999988e-01 , -2.6676399999999999e-02 , 6.6831699999999994e-02 , 9.9740799999999996e-01 --1.3897262453575876e+00 , 4.3003520436563161e+00 , 4.3609999999999993e-01 , -3.0394700000000000e-02 , 7.9396099999999997e-02 , 9.9638000000000004e-01 --1.5708371594083133e+00 , 4.3995196084965942e+00 , 4.1532079999999993e-01 , 1.5964099999999998e-02 , 8.5243799999999995e-02 , 9.9623200000000001e-01 --1.7296641186228245e+00 , 4.4872764571079244e+00 , 4.1642319999999988e-01 , -1.2382700000000000e-02 , 8.4162799999999996e-02 , 9.9637500000000001e-01 --1.9539448806015325e+00 , 4.6081269113376475e+00 , 3.8341359999999991e-01 , 6.6338900000000006e-02 , -1.3612600000000000e-01 , -9.8846800000000001e-01 --2.2141815171274946e+00 , 4.7483661202654446e+00 , 3.3883920000000001e-01 , -2.4513899999999999e-03 , 1.0423100000000000e-01 , 9.9455000000000005e-01 --2.3764070846470693e+00 , 4.8402728918048243e+00 , 3.5984719999999992e-01 , 2.8350400000000001e-02 , -1.2787899999999999e-01 , -9.9138499999999996e-01 --2.6728731465926776e+00 , 4.9999939652594652e+00 , 3.1457599999999997e-01 , -3.1182000000000001e-02 , -3.8574100000000000e-01 , 9.2208000000000001e-01 --2.8201860481830838e+00 , 5.0852353624383904e+00 , 3.5839119999999980e-01 , 8.9778200000000002e-02 , 6.4036400000000004e-01 , -7.6280700000000001e-01 --2.8994336079477803e+00 , 5.1370636172558246e+00 , 4.4064480000000006e-01 , 1.6575200000000001e-01 , 8.3781600000000001e-01 , -5.2018299999999995e-01 --3.0457326156344386e+00 , 5.2230092825313879e+00 , 4.9341440000000003e-01 , 1.8939800000000001e-01 , 8.8336199999999998e-01 , -4.2871900000000002e-01 --3.0547579493377066e+00 , 5.2379035186200449e+00 , 6.1284799999999984e-01 , 2.5497100000000000e-01 , 8.6313099999999998e-01 , -4.3588500000000002e-01 --5.9060296819858937e+00 , 6.7205527445130357e+00 , -4.7879840000000007e-01 , -3.1020900000000001e-02 , 2.4162100000000000e-01 , 9.6987500000000004e-01 --6.8303699644556701e+00 , 7.2167210106791151e+00 , -6.6928479999999979e-01 , -4.3859200000000001e-02 , 2.4270800000000001e-01 , 9.6910799999999997e-01 --7.9635332797370566e+00 , 7.8229720714797830e+00 , -9.0083040000000025e-01 , -6.1454300000000003e-02 , 2.3176200000000000e-01 , 9.7082900000000005e-01 --1.1097095044669132e+01 , 9.4791670870584994e+00 , -1.8079184000000001e+00 , -1.4485500000000000e-02 , 2.0069100000000001e-01 , 9.7954699999999995e-01 --1.3039246256781251e+01 , 1.0522093497872644e+01 , -2.1792607999999998e+00 , -1.0430700000000000e-01 , 4.0814400000000001e-02 , 9.9370700000000001e-01 --1.3035603239560983e+01 , 1.0548617977312077e+01 , -1.8517543999999999e+00 , -1.0430700000000000e-01 , 4.0814400000000001e-02 , 9.9370700000000001e-01 --1.3231074110638120e+01 , 1.0679521260572452e+01 , -1.5861592000000004e+00 , -1.5609100000000001e-01 , 2.9366300000000001e-02 , 9.8730600000000002e-01 --2.0506927312612962e+01 , 1.4601760014869861e+01 , -2.8024183999999996e+00 , 9.0763300000000005e-02 , -8.3642499999999997e-01 , 5.4051300000000002e-01 --2.0667183729580472e+01 , 1.4728553405946581e+01 , -2.3705167999999999e+00 , 1.4754999999999999e-01 , -8.5124599999999995e-01 , 5.0359699999999996e-01 --2.1126211552444442e+01 , 1.5015290303182988e+01 , -1.9991639999999999e+00 , -1.7936400000000000e-01 , 8.9896500000000001e-01 , -3.9961200000000002e-01 --3.2834024718782659e+00 , 5.4820985061116785e+00 , 1.9605500960000000e+00 , 3.3273300000000000e-01 , 9.4055800000000001e-01 , 6.8109900000000001e-02 --3.2684019886531113e+00 , 5.4840038215322462e+00 , 2.0786583200000002e+00 , -3.3408300000000002e-01 , -9.2918699999999999e-01 , -1.5811400000000000e-01 --3.1789443233635515e+00 , 5.4455677536628482e+00 , 2.2073583200000000e+00 , 2.6248800000000000e-01 , 9.3706800000000001e-01 , 2.3022500000000001e-01 --2.9695366388784219e+00 , 5.3428086985771959e+00 , 2.3480880000000002e+00 , 1.2211600000000000e-01 , 9.7367300000000001e-01 , 1.9248100000000001e-01 --2.9208404457395627e+00 , 5.3254295120178963e+00 , 2.4619659199999999e+00 , -2.9285200000000000e-01 , 9.5432600000000001e-01 , 5.9158000000000002e-02 --2.8985229462455759e+00 , 5.3230666140649721e+00 , 2.5709184000000000e+00 , -3.1396900000000000e-01 , 9.4585300000000005e-01 , 8.2377000000000006e-02 --2.8832911910967036e+00 , 5.3238833775587588e+00 , 2.6783753600000000e+00 , 4.0096900000000002e-01 , -9.1500800000000004e-01 , -4.4555999999999998e-02 --2.8937371706722326e+00 , 5.3391899950553725e+00 , 2.7837679199999998e+00 , -3.9167999999999997e-01 , 9.1741899999999998e-01 , 7.0211200000000001e-02 --2.8753419407693475e+00 , 5.3376449653404441e+00 , 2.8906965599999999e+00 , 4.3076300000000001e-01 , -9.0239899999999995e-01 , 1.0918100000000000e-02 --2.8547636792245248e+00 , 5.3358527089879901e+00 , 2.9968659999999998e+00 , 2.8773900000000002e-01 , -9.5008700000000001e-01 , -1.2058900000000000e-01 --2.8787301963039882e+00 , 5.3581811799154817e+00 , 3.1025352000000002e+00 , -1.4351300000000000e-01 , 9.7892699999999999e-01 , 1.4527599999999999e-01 --2.7467647716313435e+00 , 5.2946278267041151e+00 , 3.2052976000000002e+00 , -4.2318500000000002e-02 , 8.7913100000000000e-01 , 4.7469899999999998e-01 --2.5673324034912302e+00 , 5.2032696541850090e+00 , 3.3013311999999999e+00 , 2.4955700000000000e-01 , -9.5080200000000004e-01 , -1.8356600000000001e-01 --2.5594885991196801e+00 , 5.2081810790557403e+00 , 3.4011920000000000e+00 , 2.8017300000000001e-01 , -9.5596700000000001e-01 , -8.7349599999999999e-02 --2.5778721006550604e+00 , 5.2263673558406882e+00 , 3.5033512000000000e+00 , -5.0067399999999995e-01 , 8.5914299999999999e-01 , -1.0582400000000000e-01 --2.5932249252558455e+00 , 5.2446267935313049e+00 , 3.6064879999999997e+00 , -4.8734400000000000e-01 , 8.6748999999999998e-01 , -9.9790100000000007e-02 --2.5897828668878571e+00 , 5.2512033175943156e+00 , 3.7083664000000001e+00 , -5.0507400000000002e-01 , 8.6194000000000004e-01 , -4.4259600000000003e-02 --2.5757911839856646e+00 , 5.2527980238257204e+00 , 3.8088927999999997e+00 , -5.3364699999999998e-01 , 8.4562499999999996e-01 , -1.1784899999999999e-02 --2.5692294601147223e+00 , 5.2581711417437926e+00 , 3.9107504000000000e+00 , -5.7032000000000005e-01 , 8.2142199999999999e-01 , -1.1677899999999999e-03 --2.5521091509706180e+00 , 5.2574712712912692e+00 , 4.0110480000000006e+00 , -6.1820900000000001e-01 , 7.8591200000000005e-01 , 1.2641700000000001e-02 --2.5509677628419070e+00 , 5.2656082274899738e+00 , 4.1149024000000001e+00 , -6.6504099999999999e-01 , 7.4571500000000002e-01 , 4.0363200000000002e-02 --2.5392377693448100e+00 , 5.2686757639474671e+00 , 4.2169992000000001e+00 , 7.0915600000000001e-01 , -7.0265200000000005e-01 , -5.8115500000000000e-02 --2.5179538530445962e+00 , 5.2645540658064736e+00 , 4.3169952000000000e+00 , -7.1523400000000004e-01 , 6.9561200000000001e-01 , 6.7568299999999998e-02 --2.5030993656276674e+00 , 5.2653474109648579e+00 , 4.4189672000000000e+00 , -7.6504899999999998e-01 , 6.3754000000000000e-01 , 9.0787199999999998e-02 --2.4958202916607233e+00 , 5.2701655823631945e+00 , 4.5234768000000001e+00 , 6.0108899999999998e-01 , -7.9899799999999999e-01 , -1.7140900000000001e-02 --2.4605925676614149e+00 , 5.2593943430552725e+00 , 4.6198639999999997e+00 , 5.9286399999999995e-01 , -7.9924399999999995e-01 , -9.8593500000000001e-02 --2.4491412241483328e+00 , 5.2629465820879684e+00 , 4.7242800000000003e+00 , 7.3289300000000002e-01 , -6.4716499999999999e-01 , -2.0986900000000000e-01 --2.4117513897505631e+00 , 5.2497803473510594e+00 , 4.8197104000000000e+00 , 6.0873299999999997e-01 , -7.2349699999999995e-01 , -3.2557100000000000e-01 --2.3721457413597964e+00 , 5.2363098621442461e+00 , 4.9141735999999998e+00 , -7.1900100000000000e-01 , 5.6627499999999997e-01 , 4.0295199999999998e-01 --2.3390691008589508e+00 , 5.2268322550339139e+00 , 5.0112160000000001e+00 , 6.3864799999999999e-01 , -6.4793199999999995e-01 , -4.1510599999999998e-01 --2.2971996969020489e+00 , 5.2118787469086030e+00 , 5.1040152000000001e+00 , 6.8216299999999996e-01 , -6.3371100000000002e-01 , -3.6477900000000002e-01 --2.2531505594177039e+00 , 5.1955949681381464e+00 , 5.1959616000000004e+00 , -7.0781400000000005e-01 , 5.9416700000000000e-01 , 3.8205400000000000e-01 --2.2089640940459931e+00 , 5.1790525159609544e+00 , 5.2866808000000001e+00 , -8.5232699999999995e-01 , 3.8439600000000002e-01 , 3.5465200000000002e-01 --2.1791484411447550e+00 , 5.1710043441640270e+00 , 5.3848567999999997e+00 , 7.2192199999999995e-01 , -5.0773699999999999e-01 , -4.7014000000000000e-01 --2.1472165532571532e+00 , 5.1617297566942977e+00 , 5.4826896000000005e+00 , 7.8672799999999998e-01 , -4.2040200000000000e-01 , -4.5201900000000000e-01 --2.1141604362539184e+00 , 5.1523010468849701e+00 , 5.5799295999999998e+00 , 7.4381399999999998e-01 , -5.3730000000000000e-01 , -3.9755600000000002e-01 --2.0878680297607728e+00 , 5.1461385010604639e+00 , 5.6814752000000004e+00 , 8.7895900000000005e-01 , -3.1495899999999999e-01 , -3.5809500000000000e-01 --2.0683095899080737e+00 , 5.1443517470963336e+00 , 5.7874200000000000e+00 , 9.7468500000000002e-01 , 3.9345900000000003e-02 , -2.2009400000000001e-01 --2.0535203964985191e+00 , 5.1459383323272068e+00 , 5.8986168000000001e+00 , 9.7251399999999999e-01 , 1.0683200000000000e-01 , -2.0689199999999999e-01 --2.0534339713921250e+00 , 5.1566098216469314e+00 , 6.0201095999999996e+00 , 9.5391599999999999e-01 , 1.6478699999999999e-01 , -2.5077700000000003e-01 --2.0267364813456403e+00 , 5.1515374851027058e+00 , 6.1271464000000000e+00 , -9.1287900000000000e-01 , -6.3309199999999996e-02 , 4.0328999999999998e-01 --1.9605280326589454e+00 , 5.1223639448015827e+00 , 6.2072471999999994e+00 , -8.9308299999999996e-01 , -1.7992200000000000e-01 , 4.1234900000000002e-01 --1.8714463533703469e+00 , 5.0779304304116168e+00 , 6.2692623999999997e+00 , 8.9936899999999997e-01 , 2.3263700000000001e-01 , -3.7015399999999998e-01 --1.8858800567804903e+00 , 5.0980421924574459e+00 , 6.4081544000000008e+00 , -9.6430199999999999e-01 , -2.4819099999999999e-01 , 9.2322100000000004e-02 --1.8310325267603562e+00 , 5.0752352950277082e+00 , 6.4963984000000004e+00 , -9.5421999999999996e-01 , -2.7079500000000001e-01 , 1.2702300000000000e-01 --1.7888883344467721e+00 , 5.0604966621197498e+00 , 6.5956039999999998e+00 , 8.9789799999999997e-01 , -4.1196300000000002e-01 , -1.5513299999999999e-01 --1.7595437607318778e+00 , 5.0539871725382888e+00 , 6.7065511999999998e+00 , -6.3596100000000000e-01 , 7.5106899999999999e-01 , 1.7733900000000000e-01 --1.7211367343158668e+00 , 5.0426082499056371e+00 , 6.8111440000000005e+00 , 5.4499900000000001e-01 , -8.1815300000000002e-01 , -1.8330600000000000e-01 --1.7016167339078554e+00 , 5.0422674826665821e+00 , 6.9348416000000004e+00 , -4.9802700000000000e-01 , 8.3097900000000002e-01 , 2.4787600000000001e-01 --1.6800788455666629e+00 , 5.0408713712518551e+00 , 7.0589968000000001e+00 , -5.0408200000000003e-01 , 8.1507399999999997e-01 , 2.8558099999999997e-01 --8.0328092087892884e+00 , 9.1270395975351608e+00 , 1.3557312000000000e+01 , -1.7688200000000001e-01 , -5.8005600000000002e-01 , 7.9514099999999999e-01 --7.9355287101491836e+00 , 9.0984344506302293e+00 , 1.3847160000000001e+01 , -1.7688200000000001e-01 , -5.8005600000000002e-01 , 7.9513999999999996e-01 --1.0166259195623617e-01 , 4.0685289603125696e+00 , 5.9268528000000007e+00 , -7.0918700000000001e-01 , -3.1195200000000001e-01 , 6.3224899999999995e-01 -1.9590484291784227e-02 , 3.9980395323013282e+00 , 5.8927408000000003e+00 , 6.7692600000000003e-01 , 2.4668499999999999e-01 , -6.9348299999999996e-01 --2.3657197183650132e+00 , 5.5780620055810806e+00 , 8.8569592000000004e+00 , -9.2235800000000001e-01 , -2.7293299999999998e-01 , 2.7342899999999998e-01 --3.2891259343303325e-01 , 4.2471621248768106e+00 , 6.5383520000000006e+00 , -3.2783000000000001e-01 , -5.7497100000000001e-01 , -7.4962399999999996e-01 --1.2535716605552549e-01 , 4.1234899354525112e+00 , 6.4054088000000000e+00 , 9.6702600000000005e-01 , -2.0164299999999999e-01 , 1.5556900000000001e-01 --1.9031534846562836e+00 , 5.3266890055514828e+00 , 8.9096352000000003e+00 , 8.7072799999999995e-01 , -1.4463999999999999e-02 , -4.9155199999999999e-01 --4.1020392331821753e-02 , 4.0879632983952696e+00 , 6.5422000000000002e+00 , -9.2725599999999997e-01 , 3.0604799999999999e-01 , -2.1570900000000001e-01 -1.2529802466402029e-01 , 3.9869113559704110e+00 , 6.4345184000000000e+00 , -2.3125499999999999e-01 , 9.0829499999999996e-01 , -3.4859800000000002e-01 --3.7114530666885415e-02 , 4.1091079587598731e+00 , 6.8060792000000001e+00 , 7.6120500000000002e-01 , -6.2899600000000000e-01 , -1.5789600000000001e-01 --1.5213987754163183e-01 , 4.2012233245453068e+00 , 7.1280840000000003e+00 , -8.7848899999999996e-01 , 4.7028100000000000e-01 , -8.4217399999999998e-02 --1.0861262800037608e-01 , 4.1840591126002948e+00 , 7.2155480000000001e+00 , 8.3487000000000000e-01 , 3.1615900000000002e-01 , -4.5059399999999999e-01 --1.2469412662961421e-02 , 4.1316446206567168e+00 , 7.2183560000000000e+00 , -8.1564099999999995e-01 , 3.1347199999999997e-01 , 4.8627700000000001e-01 --9.9385479062417126e-03 , 4.1450718770340700e+00 , 7.3803984000000007e+00 , -7.9257999999999995e-01 , 4.1606500000000002e-01 , 4.4576700000000002e-01 -3.8965924220982995e-02 , 4.1252518141028505e+00 , 7.4663648000000000e+00 , 2.5024999999999997e-01 , 4.6476899999999999e-01 , 8.4933199999999998e-01 --1.3006185856982566e+00 , 5.1042514693960026e+00 , 1.0184550400000001e+01 , -3.1679400000000002e-01 , 8.0959999999999999e-01 , 4.9415500000000001e-01 -2.3257068162894989e-01 , 4.0170078694509561e+00 , 7.4605616000000001e+00 , -4.3602299999999999e-01 , -8.4516400000000003e-01 , 3.0916300000000002e-01 -4.4452734608611943e-01 , 3.8784316600531277e+00 , 7.2132392000000003e+00 , -2.6468799999999998e-01 , 2.3427600000000001e-01 , 9.3544400000000005e-01 -6.1037448783554038e-01 , 3.7715539624531425e+00 , 7.0396736000000004e+00 , -7.4514199999999997e-01 , -2.0719199999999999e-01 , -6.3390400000000002e-01 -7.2035655935687593e-01 , 3.7038414856155217e+00 , 6.9694528000000000e+00 , 3.8976699999999997e-01 , 2.4128300000000000e-01 , 8.8874299999999995e-01 -1.0000798149825081e+00 , 3.5075548533126675e+00 , 6.4923319999999993e+00 , -2.6878500000000000e-01 , -5.4144999999999999e-02 , -9.6167700000000000e-01 -1.0544923380488460e+00 , 3.4806592310646352e+00 , 6.5233240000000006e+00 , -2.7457800000000001e-02 , 2.8319800000000001e-01 , 9.5866799999999996e-01 -1.1122104894080171e+00 , 3.4504649828739384e+00 , 6.5438536000000003e+00 , 3.2026100000000002e-01 , -8.7966699999999998e-01 , -3.5159400000000002e-01 -1.1488456281373827e+00 , 3.4365302953600203e+00 , 6.6195655999999996e+00 , -2.6403399999999999e-01 , 8.3645099999999994e-01 , 4.8024600000000001e-01 -1.2473235971540464e+00 , 3.3737759384745178e+00 , 6.5240935999999996e+00 , -9.7358800000000001e-01 , -2.2601399999999999e-01 , 3.2307900000000001e-02 -1.2605376052163240e+00 , 3.3791180430388685e+00 , 6.6746335999999999e+00 , -6.1207699999999998e-01 , -7.6116399999999995e-01 , -2.1445700000000001e-01 -1.2080028796553433e+00 , 3.4415184580841451e+00 , 7.0469120000000007e+00 , 9.7780500000000004e-01 , -1.1710400000000000e-01 , -1.7373400000000000e-01 -1.3155485027103500e+00 , 3.3707228768384767e+00 , 6.9187839999999996e+00 , -3.2668599999999999e-02 , -2.1373500000000001e-01 , 9.7634500000000002e-01 -1.4138413928906266e+00 , 3.3058086978180006e+00 , 6.8072648000000004e+00 , -8.5834900000000003e-01 , -2.2828800000000000e-02 , 5.1255799999999996e-01 -1.3565612286398872e+00 , 3.3784953802446038e+00 , 7.2717912000000000e+00 , 3.0840899999999999e-01 , 9.1934800000000005e-01 , 2.4429899999999999e-01 -1.4815844935698117e+00 , 3.2900090329052434e+00 , 7.0489920000000001e+00 , 9.6870500000000004e-01 , -1.1649700000000000e-01 , 2.1917800000000001e-01 -1.4890472458240471e+00 , 3.3080970081479926e+00 , 7.3090023999999998e+00 , 6.9474599999999997e-01 , 7.1354700000000004e-01 , 9.0439300000000000e-02 -1.5404259567479794e+00 , 3.2882054759557917e+00 , 7.4004080000000005e+00 , 2.4564100000000000e-01 , 6.4508100000000002e-01 , 7.2355400000000003e-01 -1.6615610874091145e+00 , 3.1976894164742182e+00 , 7.1403767999999994e+00 , -7.9844899999999996e-01 , 5.2904799999999996e-01 , 2.8738100000000000e-01 -1.7019352086980317e+00 , 3.1888209369865930e+00 , 7.2894608000000005e+00 , -3.6357200000000001e-01 , -5.9894700000000001e-01 , 7.1349700000000005e-01 -1.5667322925161722e+00 , 3.3734109752665375e+00 , 8.5404352000000010e+00 , -6.4522299999999999e-01 , -7.4196899999999999e-01 , -1.8212300000000001e-01 -1.6173951967813442e+00 , 3.3672648267806133e+00 , 8.7948295999999999e+00 , 7.5753999999999999e-01 , 4.1908000000000001e-01 , 5.0050499999999998e-01 -1.7946896783154747e+00 , 3.2112841745919818e+00 , 8.1322456000000010e+00 , 6.0209999999999997e-01 , -7.7887899999999999e-01 , 1.7556700000000000e-01 -9.8829108287108447e-02 , 3.5917527303630328e+00 , 5.9907840000000001e-01 , 6.7570300000000000e-02 , -7.0315799999999999e-03 , -9.9768999999999997e-01 -8.7954535559304770e-03 , 3.6445992157310023e+00 , 5.8919839999999990e-01 , -8.9463100000000004e-02 , 3.6501100000000002e-02 , 9.9532100000000001e-01 --8.9088402981913450e-02 , 3.7012556521215734e+00 , 5.7547039999999994e-01 , -5.6497400000000003e-02 , 2.9465200000000000e-02 , 9.9796799999999997e-01 --1.8087948230407935e-01 , 3.7553906761063449e+00 , 5.7164319999999980e-01 , 9.6523899999999996e-02 , -8.7407200000000004e-02 , -9.9148499999999995e-01 --2.9552627955777355e-01 , 3.8219771703173357e+00 , 5.5089520000000003e-01 , -7.4265399999999995e-02 , 9.1897900000000005e-02 , 9.9299499999999996e-01 --4.0312520839820198e-01 , 3.8850473680065174e+00 , 5.4057840000000001e-01 , -6.4200199999999999e-02 , 7.8951499999999994e-02 , 9.9480900000000005e-01 --5.3481675635346360e-01 , 3.9609125489824235e+00 , 5.1483839999999992e-01 , -9.5148700000000003e-02 , 9.0298799999999999e-02 , 9.9135899999999999e-01 --6.6709149204990270e-01 , 4.0367231810945317e+00 , 4.9395519999999982e-01 , -8.7686500000000001e-02 , 9.3676300000000004e-02 , 9.9173400000000000e-01 --8.0847552264909783e-01 , 4.1189430333756309e+00 , 4.7131440000000002e-01 , -9.7478899999999993e-02 , 9.5718100000000000e-02 , 9.9062399999999995e-01 --9.5147565574262849e-01 , 4.2022253951050654e+00 , 4.5361359999999995e-01 , -5.1388200000000002e-02 , 7.9743499999999995e-02 , 9.9548999999999999e-01 --1.0798358451026333e+00 , 4.2786173145642845e+00 , 4.5231360000000009e-01 , -6.9527800000000004e-03 , 8.3609400000000000e-02 , 9.9647399999999997e-01 --1.2403253567980923e+00 , 4.3719583774881290e+00 , 4.3336479999999988e-01 , -2.9392100000000001e-02 , 8.3570300000000000e-02 , 9.9606799999999995e-01 --1.4101488114368559e+00 , 4.4710370422534336e+00 , 4.1458240000000002e-01 , -3.0263499999999999e-02 , 8.0789299999999994e-02 , 9.9627200000000005e-01 --1.5740753487587198e+00 , 4.5668330082147603e+00 , 4.0710479999999993e-01 , 7.6349399999999998e-03 , 7.7406400000000000e-02 , 9.9697000000000002e-01 --1.7463795058728482e+00 , 4.6684649286015656e+00 , 4.0043839999999986e-01 , -3.9975200000000002e-02 , 1.0811999999999999e-01 , 9.9333400000000005e-01 --1.9918836965960494e+00 , 4.8101518811629980e+00 , 3.5560399999999981e-01 , -2.6894600000000001e-02 , 1.2211000000000000e-01 , 9.9215200000000003e-01 --2.2405379983174782e+00 , 4.9537682634170732e+00 , 3.1971359999999982e-01 , -3.0345600000000000e-02 , 4.5364900000000000e-02 , 9.9850899999999998e-01 --2.5155616351989591e+00 , 5.1135064298310002e+00 , 2.7910159999999995e-01 , -4.9904400000000002e-02 , -2.6394699999999999e-01 , 9.6324500000000002e-01 --2.6106802778590890e+00 , 5.1758381573868331e+00 , 3.4684720000000002e-01 , -1.8764999999999999e-03 , -8.7185500000000005e-01 , 4.8975999999999997e-01 --2.6231656301241157e+00 , 5.1918349720678307e+00 , 4.6050879999999994e-01 , 1.5675300000000000e-02 , -9.1268300000000002e-01 , 4.0836699999999998e-01 --2.6324871098892642e+00 , 5.2076666596325829e+00 , 5.7395200000000002e-01 , 2.1544000000000001e-02 , -9.7989099999999996e-01 , 1.9836899999999999e-01 --2.6486074193713485e+00 , 5.2261525352992049e+00 , 6.8335999999999997e-01 , -8.9037800000000000e-02 , 9.7081399999999995e-01 , -2.2269500000000000e-01 --2.6636989464223548e+00 , 5.2435417380385134e+00 , 7.9279919999999993e-01 , -1.3514999999999999e-01 , 9.6269600000000000e-01 , -2.3441600000000001e-01 --2.6855581892544107e+00 , 5.2657349638321920e+00 , 8.9831759999999994e-01 , -1.6480600000000001e-01 , 9.5983099999999999e-01 , -2.2707600000000000e-01 --2.7044056102343088e+00 , 5.2858433890476713e+00 , 1.0046118399999999e+00 , -1.8322099999999999e-01 , 9.5783200000000002e-01 , -2.2133100000000000e-01 --2.7143145426446695e+00 , 5.3009086911026220e+00 , 1.1141799999999999e+00 , -1.8880800000000000e-01 , 9.5623999999999998e-01 , -2.2351199999999999e-01 --2.7311432414837995e+00 , 5.3188583427499907e+00 , 1.2207352800000000e+00 , -1.9570499999999999e-01 , 9.5240300000000000e-01 , -2.3372699999999999e-01 --2.7538223137871194e+00 , 5.3417979719453532e+00 , 1.3244992000000000e+00 , -2.0569200000000001e-01 , 9.4933199999999995e-01 , -2.3761299999999999e-01 --2.7766123897429384e+00 , 5.3627201330767473e+00 , 1.4287747999999998e+00 , -1.9648399999999999e-01 , 9.5779300000000001e-01 , -2.0982799999999999e-01 --2.7873083692735028e+00 , 5.3784748147010060e+00 , 1.5362920799999999e+00 , -1.7283399999999999e-01 , 9.6730000000000005e-01 , -1.8563099999999999e-01 --2.8060082696736277e+00 , 5.3983266326707895e+00 , 1.6413757599999999e+00 , 1.5108500000000000e-01 , -9.7144900000000001e-01 , 1.8292300000000000e-01 --2.8146712020489346e+00 , 5.4119042215031570e+00 , 1.7490490400000001e+00 , -1.4908500000000000e-01 , 9.7802699999999998e-01 , -1.4572800000000000e-01 --2.8303149354871859e+00 , 5.4306564883003468e+00 , 1.8546142400000001e+00 , 1.7435999999999999e-01 , -9.7981499999999999e-01 , 9.7784099999999999e-02 --2.8085920483802385e+00 , 5.4271437386225543e+00 , 1.9683275280000001e+00 , 2.2885300000000000e-01 , -9.7321999999999997e-01 , 2.1650200000000001e-02 --2.7937897619096486e+00 , 5.4276187679296193e+00 , 2.0792277200000000e+00 , 3.1198100000000001e-01 , -9.4850800000000002e-01 , -5.4776600000000002e-02 --2.7595375089619099e+00 , 5.4170530287617158e+00 , 2.1922398400000001e+00 , -3.1434899999999999e-01 , 9.4834799999999997e-01 , 4.2681999999999998e-02 --2.7322583282916124e+00 , 5.4094775603196146e+00 , 2.3027450400000000e+00 , 3.6504700000000001e-01 , -9.3059700000000001e-01 , -2.7021699999999999e-02 --2.7221128868912432e+00 , 5.4124573456930376e+00 , 2.4092649599999998e+00 , -4.7236899999999998e-01 , 8.8118399999999997e-01 , -1.9584899999999999e-02 --2.7272648317119081e+00 , 5.4241574350843562e+00 , 2.5136757599999999e+00 , -4.5317099999999999e-01 , 8.9132800000000001e-01 , 1.3050100000000000e-02 --2.7313981867939026e+00 , 5.4347587853873183e+00 , 2.6181125600000001e+00 , 4.6627099999999999e-01 , -8.8099499999999997e-01 , -8.0244899999999994e-02 --2.7067177504730120e+00 , 5.4296383636263279e+00 , 2.7244889600000000e+00 , 3.9850099999999999e-01 , -8.9256899999999995e-01 , -2.1099100000000001e-01 --2.6716295475732252e+00 , 5.4176185167328175e+00 , 2.8304181600000002e+00 , -4.4012099999999998e-01 , 8.5432600000000003e-01 , 2.7644400000000002e-01 --2.6167471635101540e+00 , 5.3939591511243847e+00 , 2.9355257600000000e+00 , -4.4257099999999999e-01 , 8.3686199999999999e-01 , 3.2217000000000001e-01 --2.5698850914921723e+00 , 5.3744254337776649e+00 , 3.0383016800000000e+00 , -5.9604699999999999e-01 , 7.3861299999999996e-01 , 3.1492500000000001e-01 --2.5301033995437701e+00 , 5.3591442291928661e+00 , 3.1395800000000000e+00 , -6.8369100000000005e-01 , 6.2407199999999996e-01 , 3.7828600000000001e-01 --2.4807501616632690e+00 , 5.3377385147934202e+00 , 3.2388687999999997e+00 , -8.9557299999999995e-01 , 3.9097300000000001e-01 , 2.1234200000000000e-01 --2.4561990592803271e+00 , 5.3321568032617925e+00 , 3.3376272000000000e+00 , -8.8299399999999995e-01 , 4.5894099999999999e-01 , 9.8461999999999994e-02 --2.4389181364954133e+00 , 5.3300887696397652e+00 , 3.4364064000000001e+00 , -8.1650699999999998e-01 , 5.7720300000000002e-01 , -1.2399500000000001e-02 --2.4561998604610196e+00 , 5.3481269844554449e+00 , 3.5380767999999998e+00 , -8.0720499999999995e-01 , 5.8665999999999996e-01 , -6.5186599999999997e-02 --2.4536247389298467e+00 , 5.3555252549762962e+00 , 3.6386240000000001e+00 , -8.3604800000000001e-01 , 5.4759300000000000e-01 , -3.4137800000000003e-02 --2.4490472864334372e+00 , 5.3607932638452240e+00 , 3.7395247999999999e+00 , -8.0943299999999996e-01 , 5.7967599999999997e-01 , 9.3779600000000005e-02 --2.4528843684024331e+00 , 5.3719746363568257e+00 , 3.8416319999999997e+00 , -5.3364699999999998e-01 , 8.4562499999999996e-01 , -1.1784899999999999e-02 --2.4547560340793320e+00 , 5.3811031564337011e+00 , 3.9444984000000001e+00 , -5.7032000000000005e-01 , 8.2142199999999999e-01 , -1.1679800000000001e-03 --2.4545614725040483e+00 , 5.3901942259787781e+00 , 4.0476247999999995e+00 , -6.1820900000000001e-01 , 7.8591200000000005e-01 , 1.2641599999999999e-02 --2.4449010043736275e+00 , 5.3922161689604504e+00 , 4.1493679999999999e+00 , -6.6504099999999999e-01 , 7.4571500000000002e-01 , 4.0363200000000002e-02 --2.4416884224630637e+00 , 5.3991918598500988e+00 , 4.2531704000000001e+00 , 7.0915700000000004e-01 , -7.0265200000000005e-01 , -5.8115399999999998e-02 --2.4364477599269119e+00 , 5.4051142727251165e+00 , 4.3574408000000009e+00 , -7.6504899999999998e-01 , 6.3754000000000000e-01 , 9.0787199999999998e-02 --2.4302150915200293e+00 , 5.4099643922669260e+00 , 4.4619295999999995e+00 , 8.1338400000000000e-01 , -5.7230000000000003e-01 , -1.0430200000000001e-01 --2.4219502101654760e+00 , 5.4137408484092848e+00 , 4.5667824000000001e+00 , -8.5521300000000000e-01 , 4.9777600000000000e-01 , 1.4432800000000001e-01 --2.4126627448629652e+00 , 5.4164512097015587e+00 , 4.6717599999999999e+00 , -8.8007299999999999e-01 , 4.2511300000000002e-01 , 2.1154400000000001e-01 --2.4013491269831135e+00 , 5.4180654560485220e+00 , 4.7770912000000001e+00 , -8.8075099999999995e-01 , 3.9649200000000001e-01 , 2.5898100000000002e-01 --2.3706173637184671e+00 , 5.4091100020451899e+00 , 4.8762135999999998e+00 , -8.8279399999999997e-01 , 3.2488400000000001e-01 , 3.3929999999999999e-01 --2.3311575674922995e+00 , 5.3936892652991943e+00 , 4.9714880000000008e+00 , 8.9234899999999995e-01 , -2.8196199999999999e-01 , -3.5243500000000000e-01 --2.2982165864636430e+00 , 5.3822634728107195e+00 , 5.0693520000000003e+00 , -9.3137999999999999e-01 , 1.9133300000000000e-01 , 3.0971399999999999e-01 --2.2729124512650101e+00 , 5.3749561688421323e+00 , 5.1702631999999999e+00 , -8.8686600000000004e-01 , 3.9053800000000000e-01 , 2.4687600000000001e-01 --2.2773476095025131e+00 , 5.3878839335138879e+00 , 5.2861608000000002e+00 , -9.2200199999999999e-01 , 2.8068399999999999e-01 , 2.6669900000000002e-01 --2.2489476304130314e+00 , 5.3783390766937487e+00 , 5.3871552000000005e+00 , -8.1248399999999998e-01 , 4.0381800000000001e-01 , 4.2047699999999999e-01 --3.3369767873254199e+00 , 6.0787482030030189e+00 , 6.0647880000000001e+00 , -9.6339399999999997e-01 , 2.6290999999999998e-01 , -5.2446699999999999e-02 --2.5203185159669079e+00 , 5.5710448908086976e+00 , 5.7692616000000001e+00 , 5.6196100000000004e-01 , -8.0898199999999998e-01 , 1.7247299999999999e-01 --2.4276656431662413e+00 , 5.5227617263438065e+00 , 5.8444640000000003e+00 , 3.7577500000000003e-01 , 9.2404800000000006e-03 , 9.2666499999999996e-01 --2.3347032660787486e+00 , 5.4738939985406576e+00 , 5.9169312000000005e+00 , -2.1140200000000001e-01 , -7.0429000000000004e-03 , 9.7737399999999997e-01 --2.1485292576629256e+00 , 5.3642498817365833e+00 , 5.9289224000000003e+00 , -9.0310800000000002e-01 , -4.1482200000000002e-01 , 1.1098800000000000e-01 --3.3761245662128223e+00 , 6.1670166318243327e+00 , 6.8476480000000004e+00 , -8.1928400000000001e-01 , 5.3292099999999998e-01 , -2.1158800000000000e-01 --3.4049576216638071e+00 , 6.1995325413444480e+00 , 7.0292007999999999e+00 , 7.3410900000000001e-01 , -6.5863200000000000e-01 , 1.6518900000000000e-01 --3.3926064429734053e+00 , 6.2052939870794814e+00 , 7.1869376000000003e+00 , -5.8514299999999997e-01 , 7.9592399999999996e-01 , -1.5528200000000000e-01 --3.4147230223309712e+00 , 6.2331016019862027e+00 , 7.3729312000000009e+00 , -7.4416700000000002e-01 , 6.5449599999999997e-01 , -1.3360600000000000e-01 --3.4329152659363968e+00 , 6.2600811559625154e+00 , 7.5609424000000001e+00 , -7.8770099999999998e-01 , 5.9304400000000002e-01 , -1.6681399999999999e-01 --3.4690238873842905e+00 , 6.2981788986926670e+00 , 7.7687136000000008e+00 , 6.3465400000000005e-01 , -7.5076699999999996e-01 , 1.8320200000000000e-01 --3.5072104646099964e+00 , 6.3392511066092752e+00 , 7.9854600000000007e+00 , 9.9130700000000005e-01 , -1.2330700000000000e-01 , 4.5879099999999999e-02 --3.4910279274142644e+00 , 6.3446431625723338e+00 , 8.1632792000000016e+00 , -9.3125400000000003e-01 , 3.6054300000000000e-01 , -5.2681400000000003e-02 --3.4788051379956153e+00 , 6.3527131177907581e+00 , 8.3482015999999994e+00 , -9.3910400000000005e-01 , 3.1082900000000002e-01 , 1.4652599999999999e-01 --1.6721500422539508e+00 , 5.1611579035278687e+00 , 6.8829768000000007e+00 , 4.9058299999999999e-01 , -8.4120099999999998e-01 , -2.2739500000000001e-01 --1.5978514187309885e+00 , 5.1237449940228181e+00 , 6.9555792000000007e+00 , -4.7490399999999999e-01 , 8.2503000000000004e-01 , 3.0625300000000000e-01 --1.5622896672071152e+00 , 5.1115876866599894e+00 , 7.0661936000000001e+00 , -5.5893599999999999e-01 , 7.0831900000000003e-01 , 4.3113200000000002e-01 --1.5306310594971597e+00 , 5.1030854014267613e+00 , 7.1835992000000006e+00 , 5.0965199999999999e-01 , -7.7407999999999999e-01 , -3.7557200000000002e-01 --3.5211628583742751e+00 , 6.4697990613713730e+00 , 9.4631752000000002e+00 , -8.8075400000000004e-01 , 4.6626499999999999e-01 , -8.2885000000000000e-02 --5.5893016929292383e-02 , 4.1199771088173787e+00 , 5.8599391999999995e+00 , -9.1400400000000004e-01 , 3.7726300000000001e-01 , 1.4922900000000000e-01 --9.8911328102990304e-02 , 4.1578732903084328e+00 , 6.0125175999999998e+00 , -7.8766999999999998e-01 , -3.4838400000000003e-01 , 5.0813799999999998e-01 --2.4289719561421084e+00 , 5.7760805123207035e+00 , 8.8987151999999998e+00 , 8.6486399999999997e-01 , 2.5352900000000000e-01 , -4.3328200000000000e-01 --2.2353996495512529e+00 , 5.6599350157159032e+00 , 8.8747640000000008e+00 , -8.4508399999999995e-01 , -2.7760000000000001e-01 , 4.5691500000000002e-01 -8.9632439816776488e-02 , 4.0545989433505509e+00 , 6.1093104000000000e+00 , 7.2602800000000001e-01 , 4.3411300000000003e-01 , -5.3332000000000002e-01 -9.0991316244210196e-02 , 4.0630240516617215e+00 , 6.2199768000000004e+00 , 8.2755999999999996e-01 , 4.2310500000000001e-01 , -3.6895299999999998e-01 --9.5785110933992001e-02 , 4.2042745088593740e+00 , 6.5966024000000001e+00 , -4.8837500000000000e-01 , 8.4061699999999995e-01 , 2.3420600000000000e-01 -1.4642036005950865e-01 , 4.0432638135345709e+00 , 6.3814264000000005e+00 , -3.4709499999999999e-01 , 9.2434099999999997e-01 , 1.5848999999999999e-01 -1.6602853695163988e-01 , 4.0396089020217030e+00 , 6.4781360000000001e+00 , 4.3444600000000000e-01 , -8.9164699999999997e-01 , 1.2736500000000001e-01 -8.2305694497067927e-02 , 4.1103735219825772e+00 , 6.7376887999999999e+00 , -8.5443899999999995e-01 , 5.1912300000000000e-01 , 2.1098400000000000e-02 --4.3035050248549522e-01 , 4.4945194003644442e+00 , 7.7022992000000006e+00 , 3.5973800000000000e-01 , -4.9800999999999998e-02 , 9.3172299999999997e-01 --5.7804973616160993e-02 , 4.2369848258819705e+00 , 7.2624520000000006e+00 , 7.2243800000000002e-01 , -1.6663500000000001e-01 , -6.7105599999999999e-01 --3.5830451324023294e-02 , 4.2355286632151206e+00 , 7.3916927999999995e+00 , 2.4305700000000000e-01 , -8.8854500000000003e-01 , -3.8911600000000002e-01 -1.8320690814416651e-01 , 4.0870971202318209e+00 , 7.1707656000000002e+00 , -1.4614300000000000e-01 , -1.7856000000000000e-02 , 9.8910200000000004e-01 -1.9618894545413679e-01 , 4.0910551499743235e+00 , 7.3144000000000009e+00 , 6.5172399999999997e-01 , 6.7907899999999999e-01 , 3.3779799999999999e-01 -3.0660978062883038e-01 , 4.0220733398620689e+00 , 7.2748591999999999e+00 , -6.0995600000000005e-01 , -1.1638500000000000e-01 , -7.8384200000000004e-01 -2.8011359187212093e-01 , 4.0571428144142896e+00 , 7.5065087999999998e+00 , -4.3602299999999999e-01 , -8.4516400000000003e-01 , 3.0916300000000002e-01 -3.4919616443192814e-01 , 4.0200202225796806e+00 , 7.5531112000000000e+00 , -1.0901200000000000e-01 , -5.7894999999999996e-01 , 8.0804299999999996e-01 -6.8733083762863734e-01 , 3.7744305695914400e+00 , 7.0018696000000000e+00 , -7.4514100000000005e-01 , -2.0719199999999999e-01 , -6.3390500000000005e-01 -7.6387904090933501e-01 , 3.7300137711158259e+00 , 7.0032840000000007e+00 , -3.4663100000000002e-01 , 7.3166299999999995e-01 , -5.8695500000000000e-01 -1.0553876843232475e+00 , 3.5139592931043508e+00 , 6.4779591999999999e+00 , -3.7027800000000000e-01 , -4.7489799999999999e-01 , -7.9835199999999995e-01 -1.1257248309728736e+00 , 3.4704906481078823e+00 , 6.4616624000000007e+00 , 1.8778900000000001e-01 , 4.7553099999999998e-01 , 8.5942200000000002e-01 -1.1538840360101870e+00 , 3.4617671289380443e+00 , 6.5561568000000001e+00 , 2.3999300000000001e-01 , -9.1717499999999996e-01 , -3.1810899999999998e-01 -1.2033114955152500e+00 , 3.4353572091607143e+00 , 6.5937320000000001e+00 , 4.9312800000000001e-01 , 8.0072699999999997e-01 , 3.4009000000000000e-01 -1.2933356675075303e+00 , 3.3755794763826414e+00 , 6.5165224000000004e+00 , 9.9579499999999999e-01 , 9.0629100000000004e-02 , -1.3337500000000000e-02 -1.1285268458253288e+00 , 3.5313427124104733e+00 , 7.2228487999999995e+00 , -9.4472400000000001e-01 , -2.2083300000000000e-02 , -3.2712100000000000e-01 -1.2528189604733702e+00 , 3.4432281182468922e+00 , 7.0491688000000003e+00 , 9.4078099999999998e-01 , -1.0637199999999999e-02 , 3.3884900000000001e-01 -1.3637751081861416e+00 , 3.3660566096001014e+00 , 6.9006255999999997e+00 , -3.5635400000000000e-01 , -4.2911699999999997e-02 , 9.3336500000000000e-01 -1.3707969837087421e+00 , 3.3803517928333271e+00 , 7.1206480000000001e+00 , 1.0052300000000000e-01 , -8.2316800000000001e-01 , 5.5882900000000002e-01 -1.4299507274780399e+00 , 3.3475303845345317e+00 , 7.1548120000000006e+00 , 7.0386700000000002e-01 , 6.5642400000000001e-01 , 2.7143800000000001e-01 -1.5598195901780834e+00 , 3.2494572105997741e+00 , 6.8907351999999999e+00 , -4.4457000000000002e-01 , -2.8069600000000000e-01 , 8.5062800000000005e-01 -1.5785839474228276e+00 , 3.2538021218465101e+00 , 7.0902488000000004e+00 , -3.8428800000000002e-01 , 9.2257100000000003e-01 , -3.4432100000000000e-02 -1.6539897661984584e+00 , 3.2054291056477360e+00 , 7.0401728000000006e+00 , 6.6228500000000001e-01 , -3.1937700000000002e-01 , -6.7777299999999996e-01 -1.6766555126431189e+00 , 3.2103950832539221e+00 , 7.2593632000000001e+00 , 7.3311300000000001e-01 , -5.8954899999999999e-01 , 3.3908300000000002e-01 -1.7477048826545654e+00 , 3.1667736904087715e+00 , 7.2372008000000001e+00 , -5.1700199999999996e-01 , -6.0726700000000000e-01 , 6.0327100000000000e-01 -1.6367461082019974e+00 , 3.3270647339822581e+00 , 8.3886159999999990e+00 , 5.2513900000000002e-01 , 7.7434300000000000e-01 , 3.5301700000000003e-01 -1.7102528575864011e+00 , 3.2892578501147396e+00 , 8.4590655999999989e+00 , -2.3714800000000000e-01 , -9.2114300000000005e-01 , 3.0863600000000002e-01 -2.6447641990010751e-01 , 3.5941013876871359e+00 , 5.9866240000000004e-01 , 3.6181900000000003e-02 , -2.4108299999999999e-02 , -9.9905400000000000e-01 -1.8988750620276185e-01 , 3.6419502496841565e+00 , 5.9890160000000003e-01 , -3.5181999999999998e-02 , 3.5394099999999998e-02 , 9.9875400000000003e-01 -1.1498592821688636e-01 , 3.6892476013887268e+00 , 6.0158479999999992e-01 , -4.1261600000000002e-02 , 4.3182800000000000e-02 , 9.9821499999999996e-01 -1.9512077155642293e-02 , 3.7485679324924499e+00 , 5.8576640000000002e-01 , 7.5210500000000000e-02 , -8.3176000000000000e-02 , -9.9369300000000005e-01 --7.7389308824942660e-02 , 3.8085963711967983e+00 , 5.7317200000000001e-01 , -8.7701399999999999e-02 , 9.5340200000000000e-02 , 9.9157399999999996e-01 --1.9507398700175127e-01 , 3.8810082515183386e+00 , 5.4381279999999999e-01 , -8.9793899999999996e-02 , 1.1052200000000000e-01 , 9.8980900000000005e-01 --2.9385979465548662e-01 , 3.9425329387841765e+00 , 5.3826960000000001e-01 , -3.3352600000000003e-02 , 8.7638099999999997e-02 , 9.9559399999999998e-01 --4.0805676550026293e-01 , 4.0133915577735229e+00 , 5.2300239999999998e-01 , -7.5347600000000001e-02 , 1.0133900000000000e-01 , 9.9199499999999996e-01 --5.3024210024665530e-01 , 4.0894222305846455e+00 , 5.0540559999999979e-01 , -7.4427499999999994e-02 , 1.0065600000000000e-01 , 9.9213399999999996e-01 --6.5399835817008167e-01 , 4.1663972328572694e+00 , 4.9212479999999981e-01 , -6.4968399999999996e-02 , 1.1385700000000000e-01 , 9.9137100000000000e-01 --7.9339732190301415e-01 , 4.2531155263724472e+00 , 4.7114799999999990e-01 , -7.5528899999999996e-02 , 1.0630299999999999e-01 , 9.9146100000000004e-01 --9.5620310505238582e-01 , 4.3532241171870201e+00 , 4.3789919999999993e-01 , -3.2562300000000002e-02 , 9.5491300000000001e-02 , 9.9489799999999995e-01 --1.0979004021688077e+00 , 4.4421718425532184e+00 , 4.2751999999999990e-01 , 4.5077499999999996e-03 , 6.9258100000000003e-02 , 9.9758899999999995e-01 --1.2412022390209114e+00 , 4.5332243506057317e+00 , 4.2196640000000007e-01 , -1.5494200000000000e-02 , 7.4104900000000001e-02 , 9.9712999999999996e-01 --1.4091369076855540e+00 , 4.6369623354098355e+00 , 4.0564880000000003e-01 , -2.4674100000000001e-02 , 8.0691899999999997e-02 , 9.9643400000000004e-01 --1.5777772311055900e+00 , 4.7430297620024788e+00 , 3.9540479999999989e-01 , -1.6613200000000002e-02 , 9.6876599999999993e-02 , 9.9515799999999999e-01 --1.8030005382993033e+00 , 4.8827686729875239e+00 , 3.5581199999999980e-01 , -4.2018000000000000e-02 , 1.3840600000000000e-01 , 9.8948400000000003e-01 --2.0215911207435431e+00 , 5.0186312340402583e+00 , 3.2998879999999997e-01 , -7.1665799999999997e-03 , 5.4500100000000003e-02 , 9.9848800000000004e-01 --2.2586270071948862e+00 , 5.1666508097958523e+00 , 3.0258479999999977e-01 , 9.6326700000000001e-02 , 5.1814400000000005e-01 , -8.4985200000000005e-01 --2.3113712407425178e+00 , 5.2065123246164529e+00 , 3.8905039999999991e-01 , 8.3347299999999999e-02 , -7.0566700000000004e-01 , 7.0362499999999994e-01 --2.3632145231488195e+00 , 5.2465883058468661e+00 , 4.7674320000000003e-01 , 1.1707700000000000e-01 , -8.9147200000000004e-01 , 4.3768899999999999e-01 --2.3898609062477520e+00 , 5.2704109536439709e+00 , 5.7878800000000008e-01 , 1.9357400000000000e-01 , -8.9420999999999995e-01 , 4.0362999999999999e-01 --2.4144431282555407e+00 , 5.2942063436016884e+00 , 6.8109279999999983e-01 , -2.6530100000000001e-01 , 8.9135600000000004e-01 , -3.6755900000000002e-01 --2.4370053961691092e+00 , 5.3169361966913229e+00 , 7.8384479999999979e-01 , -3.3939900000000001e-01 , 8.6532200000000004e-01 , -3.6881700000000001e-01 --2.4664349588703613e+00 , 5.3435479076324288e+00 , 8.8326879999999997e-01 , 3.1912299999999999e-01 , -9.0147800000000000e-01 , 2.9240100000000002e-01 --2.4949013038426573e+00 , 5.3691769933109743e+00 , 9.8334071999999995e-01 , 3.4590799999999999e-01 , -9.0297200000000000e-01 , 2.5492999999999999e-01 --2.5045623024590222e+00 , 5.3838044239306901e+00 , 1.0907841600000001e+00 , -3.8443899999999998e-01 , 8.9562299999999995e-01 , -2.2375300000000001e-01 --2.5210947281851528e+00 , 5.4023340977866967e+00 , 1.1950098400000000e+00 , -4.0445900000000001e-01 , 8.8537800000000000e-01 , -2.2916900000000001e-01 --2.5445579472400501e+00 , 5.4248494844665194e+00 , 1.2965232000000000e+00 , -3.9512000000000003e-01 , 8.9093400000000000e-01 , -2.2386700000000001e-01 --2.5670436235515002e+00 , 5.4463639266600019e+00 , 1.3984681600000000e+00 , -3.6657899999999999e-01 , 9.1156800000000004e-01 , -1.8618199999999999e-01 --2.5784856032070476e+00 , 5.4627101932515529e+00 , 1.5035300000000000e+00 , -3.4255300000000000e-01 , 9.2866099999999996e-01 , -1.4228600000000000e-01 --2.5809383904640830e+00 , 5.4717739717722216e+00 , 1.6112594400000000e+00 , 3.2546700000000001e-01 , -9.3843200000000004e-01 , 1.1582900000000000e-01 --2.5892845262287798e+00 , 5.4858826855122196e+00 , 1.7164003200000000e+00 , -3.8758500000000001e-01 , 9.0669299999999997e-01 , -1.6639300000000001e-01 --2.5966502188814005e+00 , 5.4978768326810314e+00 , 1.8217741599999999e+00 , 3.9392400000000000e-01 , -9.0349999999999997e-01 , 1.6885500000000001e-01 --2.6019005107552475e+00 , 5.5097479935694800e+00 , 1.9269935600000001e+00 , -4.7739399999999999e-01 , 8.6686700000000005e-01 , -1.4365600000000001e-01 --2.6061301467293845e+00 , 5.5205102226771645e+00 , 2.0322405200000002e+00 , -4.4010600000000000e-01 , 8.9483100000000004e-01 , -7.4728699999999995e-02 --2.6082682035368512e+00 , 5.5301153187978738e+00 , 2.1374380799999999e+00 , 5.3322499999999995e-01 , -8.4323400000000004e-01 , 6.8024000000000001e-02 --2.6093876706056482e+00 , 5.5386216758302265e+00 , 2.2426632000000000e+00 , 6.2395199999999995e-01 , -7.7847599999999995e-01 , 6.8253999999999995e-02 --2.6165214228939391e+00 , 5.5524031295724594e+00 , 2.3464115200000002e+00 , -6.6663399999999995e-01 , 7.4479300000000004e-01 , -2.9708399999999999e-02 --2.6145245225742739e+00 , 5.5586230364522553e+00 , 2.4515139200000000e+00 , -6.5642400000000001e-01 , 7.5437500000000002e-01 , -5.0274899999999999e-03 --2.6022271634678535e+00 , 5.5592057602356508e+00 , 2.5571768800000001e+00 , 6.4679500000000001e-01 , -7.6224099999999995e-01 , -2.5398500000000001e-02 --2.5960006935440925e+00 , 5.5640864578546889e+00 , 2.6617728000000000e+00 , -6.4145900000000000e-01 , 7.6085800000000003e-01 , 9.8114699999999999e-02 --2.5712571564279854e+00 , 5.5566655150288868e+00 , 2.7672444000000000e+00 , -7.7222299999999999e-01 , 6.3027900000000003e-01 , 8.0125000000000002e-02 --2.5546343445711903e+00 , 5.5535514846543368e+00 , 2.8712943200000001e+00 , -7.8444999999999998e-01 , 5.6739399999999995e-01 , 2.5040499999999999e-01 --2.5441274631015656e+00 , 5.5548005784791759e+00 , 2.9745788000000002e+00 , -8.4196199999999999e-01 , 4.4280100000000000e-01 , 3.0826599999999998e-01 --2.5149219795553091e+00 , 5.5445276374811314e+00 , 3.0774192000000000e+00 , -9.2223200000000005e-01 , 3.1688300000000003e-01 , 2.2152800000000000e-01 --2.4928707054249140e+00 , 5.5386620276793987e+00 , 3.1794744000000001e+00 , -9.7357099999999996e-01 , 1.6455300000000000e-01 , 1.5837200000000001e-01 --2.4780145495928112e+00 , 5.5372485140529069e+00 , 3.2810408000000000e+00 , -9.7441000000000000e-01 , 1.2615599999999999e-01 , 1.8603900000000001e-01 --2.4891832435398760e+00 , 5.5520372267540452e+00 , 3.3836784000000000e+00 , 9.9981500000000001e-01 , -5.1361799999999997e-03 , -1.8518600000000000e-02 --2.4973204263447579e+00 , 5.5657956709684147e+00 , 3.4870960000000002e+00 , 9.9551900000000004e-01 , 6.6489800000000002e-02 , 6.7234000000000002e-02 --2.5223279847087490e+00 , 5.5892289413545893e+00 , 3.5928431999999999e+00 , 9.9145200000000000e-01 , 1.1471500000000000e-01 , 6.2163499999999997e-02 --2.5622266137869829e+00 , 5.6235659617389731e+00 , 3.7020536000000002e+00 , 9.9554100000000001e-01 , -9.4181000000000001e-02 , -5.3374900000000003e-03 --2.9734283680047957e+00 , 5.8965356035127661e+00 , 3.8676632000000000e+00 , -6.6902499999999998e-01 , 6.8934799999999996e-01 , -2.7785900000000002e-01 --3.1310133547366856e+00 , 6.0070618663113882e+00 , 4.0084168000000000e+00 , -3.7678299999999998e-01 , 8.9211300000000004e-01 , -2.4933800000000000e-01 --3.1296247233779386e+00 , 6.0150260991902975e+00 , 4.1272991999999995e+00 , 3.1414799999999998e-01 , -9.1263399999999995e-01 , 2.6155400000000001e-01 --3.1346860444000875e+00 , 6.0279542726695921e+00 , 4.2483552000000007e+00 , -3.0213000000000001e-01 , 9.4600099999999998e-01 , -1.1747400000000000e-01 --3.1377336098111375e+00 , 6.0398474873580339e+00 , 4.3699728000000002e+00 , -3.5481600000000002e-01 , 9.2698300000000000e-01 , -1.2168600000000000e-01 --3.1313275275204999e+00 , 6.0446797020144416e+00 , 4.4902072000000004e+00 , 3.9941399999999999e-01 , -9.0717800000000004e-01 , 1.3227300000000000e-01 --3.1304061137207642e+00 , 6.0534830393162631e+00 , 4.6131456000000002e+00 , 4.7206399999999998e-01 , -8.7126000000000003e-01 , 1.3439300000000001e-01 --3.1456734081038213e+00 , 6.0725769021873823e+00 , 4.7415647999999999e+00 , 5.0771299999999997e-01 , -8.5509100000000005e-01 , 1.0510400000000000e-01 --3.1407457026742911e+00 , 6.0804096189778551e+00 , 4.8658136000000010e+00 , 6.1230700000000005e-01 , -7.8092700000000004e-01 , 1.2342000000000000e-01 --3.1434991881845002e+00 , 6.0913755748826128e+00 , 4.9934320000000003e+00 , -7.1754899999999999e-01 , 6.8745599999999996e-01 , -1.1192800000000000e-01 --3.1432334214059781e+00 , 6.1013193888319703e+00 , 5.1219239999999999e+00 , -8.2423400000000002e-01 , 5.5937400000000004e-01 , -8.7974100000000000e-02 --3.1409866813674157e+00 , 6.1102852678228503e+00 , 5.2511855999999995e+00 , -8.9545500000000000e-01 , 4.1624499999999998e-01 , -1.5780200000000000e-01 --3.1444306624109402e+00 , 6.1224589168999293e+00 , 5.3846696000000005e+00 , -9.2082299999999995e-01 , 3.7668800000000002e-01 , -1.0094900000000000e-01 --3.1545683973072771e+00 , 6.1400139926278090e+00 , 5.5223448000000008e+00 , -9.7123700000000002e-01 , 2.0799200000000001e-01 , -1.1592300000000000e-01 --3.1694938359833307e+00 , 6.1609811121592895e+00 , 5.6653864000000000e+00 , 9.9050499999999997e-01 , -1.2423800000000000e-01 , 5.8856600000000002e-02 --3.1748120460075961e+00 , 6.1746530759588971e+00 , 5.8059320000000003e+00 , -9.5805300000000004e-01 , 2.5266499999999997e-01 , -1.3526199999999999e-01 --3.1849003366825945e+00 , 6.1928018083459468e+00 , 5.9518231999999998e+00 , -9.4975100000000001e-01 , 3.0438599999999999e-01 , -7.2947899999999996e-02 --3.1610734679118986e+00 , 6.1872855178728114e+00 , 6.0823432000000004e+00 , -9.6339399999999997e-01 , 2.6290999999999998e-01 , -5.2446699999999999e-02 --2.3538936765871616e+00 , 5.6531057561474576e+00 , 5.7745968000000003e+00 , -8.7893600000000005e-01 , -4.7429500000000002e-01 , 5.0162499999999999e-02 --3.1928608353015369e+00 , 6.2311299116767636e+00 , 6.3933448000000004e+00 , -8.6650899999999997e-01 , 4.8843500000000001e-01 , -1.0292000000000000e-01 --3.1999882731172624e+00 , 6.2479687643343214e+00 , 6.5491576000000000e+00 , -9.4106100000000004e-01 , 3.1543500000000002e-01 , -1.2208600000000000e-01 --3.2041661556684584e+00 , 6.2639199080860548e+00 , 6.7064784000000000e+00 , -9.3197900000000000e-01 , 3.5192800000000002e-01 , -8.6954400000000001e-02 --3.2054542469199889e+00 , 6.2768701464270169e+00 , 6.8653903999999999e+00 , -8.3457400000000004e-01 , 5.3992099999999998e-01 , -1.0941400000000000e-01 --3.2342372946367961e+00 , 6.3081970908061296e+00 , 7.0463399999999998e+00 , -7.6437900000000003e-01 , 6.4473199999999997e-01 , -6.7981700000000001e-03 --3.2365191872253503e+00 , 6.3229090075804422e+00 , 7.2137487999999994e+00 , -7.7456899999999995e-01 , 5.9265500000000004e-01 , -2.2091200000000000e-01 --3.2427370059788831e+00 , 6.3413329703167332e+00 , 7.3881671999999998e+00 , -8.0869999999999997e-01 , 5.4299799999999998e-01 , -2.2618199999999999e-01 --3.2667531662316778e+00 , 6.3717585824011600e+00 , 7.5815240000000008e+00 , 8.0962400000000001e-01 , -5.7300899999999999e-01 , 1.2715699999999999e-01 --3.2879697557066212e+00 , 6.3993666194253986e+00 , 7.7772832000000003e+00 , 7.4170400000000003e-01 , -6.6621600000000003e-01 , 7.7664999999999998e-02 --3.3112109951107067e+00 , 6.4298432005027104e+00 , 7.9815183999999997e+00 , 9.8631500000000005e-01 , -4.4624600000000000e-02 , -1.5871600000000000e-01 --3.3087782011815854e+00 , 6.4433354691310187e+00 , 8.1702575999999993e+00 , -9.5932499999999998e-01 , 2.8228500000000001e-01 , -3.2347900000000000e-03 --3.3173381570388276e+00 , 6.4643619991281929e+00 , 8.3729328000000010e+00 , -9.5031200000000005e-01 , 2.1074000000000001e-01 , 2.2912199999999999e-01 --3.3209449947128524e+00 , 6.4834637952676459e+00 , 8.5776567999999997e+00 , -9.3698000000000004e-01 , 3.0214400000000002e-01 , 1.7543400000000001e-01 --3.8089864085185487e-01 , 4.4141017700476572e+00 , 5.8801775999999997e+00 , 2.3121200000000000e-01 , 9.1194399999999998e-01 , 3.3896700000000002e-01 --1.4684252185903182e+00 , 5.1972022653929644e+00 , 7.1000871999999999e+00 , -5.0093399999999999e-01 , 7.5190400000000002e-01 , 4.2860900000000002e-01 --1.4188039211640757e+00 , 5.1731131161648083e+00 , 7.1966512000000007e+00 , -5.1331899999999997e-01 , 7.6333399999999996e-01 , 3.9220500000000003e-01 --1.3790613371009743e+00 , 5.1564020398048811e+00 , 7.3066624000000004e+00 , -5.1836599999999999e-01 , 7.1460999999999997e-01 , 4.6971200000000002e-01 --3.2179103044200126e+00 , 6.4946298050230853e+00 , 9.5668112000000001e+00 , -9.1404399999999997e-01 , -3.5284300000000002e-01 , 2.0006299999999999e-01 --2.9326931822738800e-01 , 4.3940031955614618e+00 , 6.3366856000000000e+00 , 6.9602900000000001e-01 , -6.7564999999999997e-01 , 2.4298200000000000e-01 --2.7486580514237247e-02 , 4.2105426782589577e+00 , 6.1310672000000004e+00 , 6.9009299999999996e-01 , 2.7842000000000000e-01 , -6.6802300000000003e-01 -7.2591931263400689e-02 , 4.1460435202758248e+00 , 6.1168503999999997e+00 , -6.7056499999999997e-01 , -4.4208700000000001e-01 , 5.9573600000000004e-01 -1.2547080218531170e-01 , 4.1163539147340886e+00 , 6.1600000000000001e+00 , -6.7939499999999997e-01 , -2.6694600000000002e-01 , 6.8349199999999999e-01 --2.3342314837938805e-02 , 4.2349085111813976e+00 , 6.4795088000000005e+00 , 1.8245900000000001e-01 , 6.6554599999999997e-01 , 7.2371099999999999e-01 -1.9913884884512645e-01 , 4.0798531103214826e+00 , 6.2896464000000005e+00 , 3.0792399999999998e-01 , -9.0562699999999996e-01 , -2.9158499999999998e-01 -1.7901469504764456e-01 , 4.1038518348612421e+00 , 6.4413928000000000e+00 , -7.0755000000000001e-01 , 6.6026600000000002e-01 , -2.5183699999999998e-01 -2.6080095111656210e-02 , 4.2292324856798569e+00 , 6.8044359999999999e+00 , -8.5645400000000005e-01 , 5.0317500000000004e-01 , -1.1533300000000000e-01 --4.4991063919817442e-01 , 4.6003305800063945e+00 , 7.7067920000000001e+00 , 7.7593100000000004e-01 , -7.9966400000000007e-02 , 6.2572899999999998e-01 --3.5913827113495955e-01 , 4.5449915697713337e+00 , 7.7360784000000002e+00 , -6.8447800000000003e-01 , 6.2097300000000001e-02 , -7.2638400000000003e-01 --2.4855007691600450e-01 , 4.4751841515739050e+00 , 7.7294328000000005e+00 , -2.2236900000000001e-01 , 2.3238600000000002e-02 , -9.7468600000000005e-01 -7.4580499936366840e-02 , 4.2400402646708981e+00 , 7.3374984000000003e+00 , 4.8157800000000001e-01 , 7.8574299999999997e-01 , 3.8818900000000001e-01 -2.3185652377092292e-01 , 4.1314569500260037e+00 , 7.2168375999999999e+00 , -7.4757300000000004e-01 , -5.0062499999999999e-01 , -4.3647399999999997e-01 -9.7760439226117990e-02 , 4.2495460913537002e+00 , 7.6478552000000004e+00 , -6.6431700000000005e-01 , -6.1464499999999998e-02 , 7.4492000000000003e-01 -2.1922240222203637e-01 , 4.1685511519390790e+00 , 7.5932760000000004e+00 , -6.2651100000000004e-01 , -6.6800000000000004e-01 , 4.0157300000000001e-01 -6.1279126004831586e-01 , 3.8695107142583733e+00 , 6.9571912000000005e+00 , -9.3866700000000003e-01 , 3.3016699999999999e-01 , 9.9471900000000002e-02 -6.3571631308211929e-01 , 3.8652866185194368e+00 , 7.0781432000000004e+00 , -8.4779700000000002e-01 , 3.0977800000000000e-01 , 4.3043999999999999e-01 -7.1195735725965603e-01 , 3.8170298532716034e+00 , 7.0814919999999999e+00 , -2.5998100000000001e-03 , -2.3683799999999999e-01 , 9.7154600000000002e-01 -1.0615258505220222e+00 , 3.5441305753820833e+00 , 6.4234944000000000e+00 , -1.1573200000000000e-01 , -2.6069799999999999e-01 , 9.5845899999999995e-01 -1.0906673217602627e+00 , 3.5325924986162960e+00 , 6.5094920000000007e+00 , 4.8100799999999999e-01 , 4.6790599999999999e-01 , -7.4141400000000002e-01 -1.1641972119508379e+00 , 3.4849215883141467e+00 , 6.4835336000000003e+00 , -4.8809600000000002e-02 , 5.2489300000000005e-01 , 8.4976700000000005e-01 -1.2019043567894026e+00 , 3.4658241645350838e+00 , 6.5496464000000003e+00 , 5.1239400000000002e-01 , 7.8350600000000004e-01 , 3.5152499999999998e-01 -9.6577144012231964e-01 , 3.6833730905852917e+00 , 7.4209167999999996e+00 , 1.4975400000000000e-01 , 6.3313100000000000e-01 , 7.5941999999999998e-01 -1.0430154590600478e+00 , 3.6333565064490445e+00 , 7.4157688000000004e+00 , 1.0882699999999999e-01 , 6.7365399999999998e-01 , 7.3099000000000003e-01 -1.2742103612678723e+00 , 3.4479569962490588e+00 , 6.9085400000000003e+00 , -2.9360799999999998e-01 , 5.4405899999999996e-01 , 7.8599900000000000e-01 -1.3321830288861833e+00 , 3.4136227890832718e+00 , 6.9349664000000004e+00 , -5.4548600000000003e-01 , 1.9891400000000001e-01 , 8.1417300000000004e-01 -1.4065292349838998e+00 , 3.3634220271148489e+00 , 6.9019360000000001e+00 , -3.1562299999999999e-01 , -8.5154800000000004e-04 , 9.4888399999999995e-01 -1.4211817882730053e+00 , 3.3693104158089078e+00 , 7.0924120000000004e+00 , -9.7113300000000002e-01 , 1.2634400000000001e-01 , -2.0233000000000001e-01 -1.4738977694742723e+00 , 3.3395135102182043e+00 , 7.1455040000000007e+00 , -4.4497599999999998e-01 , -8.2471799999999995e-01 , 3.4905100000000000e-01 -1.5398961631591119e+00 , 3.2989748935656529e+00 , 7.1480832000000003e+00 , -6.0653299999999999e-01 , 2.6190300000000000e-02 , -7.9462699999999997e-01 -1.6027626628755243e+00 , 3.2592445778378369e+00 , 7.1593152000000009e+00 , -4.2259200000000002e-01 , -6.0016999999999998e-01 , -6.7912600000000001e-01 -1.6793444772472834e+00 , 3.2066212731014470e+00 , 7.0989328000000000e+00 , -8.7974399999999997e-01 , 4.3064599999999997e-01 , 2.0148099999999999e-01 -1.5035246468881438e+00 , 3.4239171148096075e+00 , 8.4561640000000011e+00 , -5.9210200000000002e-01 , -8.0461000000000005e-01 , 4.4917699999999998e-02 -1.5871268149028750e+00 , 3.3709023356076235e+00 , 8.4585872000000002e+00 , -2.2609599999999999e-01 , -9.6607299999999996e-01 , 1.2483400000000000e-01 -1.6289078832077373e+00 , 3.3669987404779977e+00 , 8.7432248000000001e+00 , -9.0550200000000003e-01 , -1.7215600000000000e-01 , -3.8785100000000000e-01 -1.7957975891614217e+00 , 3.2133233298407475e+00 , 8.1320687999999990e+00 , 6.0209999999999997e-01 , -7.7887899999999999e-01 , 1.7556700000000000e-01 -3.5931790337212610e-01 , 3.6334886037454819e+00 , 6.0886479999999987e-01 , -6.0377800000000002e-02 , 1.5165200000000000e-02 , 9.9805999999999995e-01 -2.8700746800127130e-01 , 3.6820327896926939e+00 , 6.0774159999999999e-01 , -3.6848199999999998e-02 , 4.5324600000000000e-02 , 9.9829299999999999e-01 -2.0700178184009799e-01 , 3.7351929780396120e+00 , 6.0155359999999991e-01 , -3.5597299999999998e-02 , 4.2271400000000001e-02 , 9.9847200000000003e-01 -1.2028774611687498e-01 , 3.7930737198533766e+00 , 5.9102879999999991e-01 , -3.9479300000000002e-02 , 7.7245099999999997e-02 , 9.9622999999999995e-01 -2.5733701279395671e-02 , 3.8547664788507818e+00 , 5.7664559999999976e-01 , -5.3907099999999999e-02 , 9.6919699999999998e-02 , 9.9383100000000002e-01 --6.9177651305257992e-02 , 3.9181695440119513e+00 , 5.6540319999999977e-01 , -9.3081100000000000e-02 , 1.2207200000000000e-01 , 9.8814700000000000e-01 --1.7842497337911878e-01 , 3.9907849246825098e+00 , 5.4415599999999986e-01 , -6.6368300000000005e-02 , 1.2889999999999999e-01 , 9.8943400000000004e-01 --2.9019141524968406e-01 , 4.0642585410840013e+00 , 5.2660079999999998e-01 , -3.5029600000000001e-02 , 8.5467100000000004e-02 , 9.9572499999999997e-01 --3.9491205486802405e-01 , 4.1342260536560929e+00 , 5.1947679999999985e-01 , -6.5794599999999995e-02 , 9.7991300000000003e-02 , 9.9300999999999995e-01 --5.3670717977148064e-01 , 4.2278442419505318e+00 , 4.8481360000000007e-01 , -8.4734199999999996e-02 , 1.3163000000000000e-01 , 9.8767099999999997e-01 --6.7368167490053210e-01 , 4.3171550813319959e+00 , 4.6144479999999999e-01 , -5.5114000000000003e-02 , 1.0946100000000000e-01 , 9.9246199999999996e-01 --7.9604501443782771e-01 , 4.3996651465138896e+00 , 4.5489280000000010e-01 , -5.6292500000000002e-02 , 1.1139499999999999e-01 , 9.9218099999999998e-01 --9.4933508778071651e-01 , 4.5009916950940703e+00 , 4.2968319999999993e-01 , -1.4163600000000000e-02 , 9.2197799999999996e-02 , 9.9563999999999997e-01 --1.0814728658395980e+00 , 4.5899989911620995e+00 , 4.2693760000000003e-01 , 1.1552700000000001e-02 , 6.9967000000000001e-02 , 9.9748199999999998e-01 --1.2304923170523310e+00 , 4.6891032842255989e+00 , 4.1797280000000003e-01 , -2.4226600000000001e-02 , 8.2037499999999999e-02 , 9.9633499999999997e-01 --1.4107405759209111e+00 , 4.8086712826484437e+00 , 3.9319999999999999e-01 , -6.6996699999999996e-03 , 9.8893599999999998e-02 , 9.9507599999999996e-01 --1.5841233354680990e+00 , 4.9250468083199603e+00 , 3.8047040000000010e-01 , 5.0920899999999998e-02 , -1.2547100000000000e-01 , -9.9078999999999995e-01 --1.8285426868755121e+00 , 5.0856193393914353e+00 , 3.2949999999999990e-01 , 2.4897800000000001e-02 , 8.5266200000000000e-02 , 9.9604700000000002e-01 --2.0288160010852296e+00 , 5.2201120745484531e+00 , 3.1660400000000011e-01 , 2.4443000000000001e-01 , -2.0633399999999999e-01 , 9.4745999999999997e-01 --2.1285495192775095e+00 , 5.2907615694382972e+00 , 3.7192159999999985e-01 , 3.9837299999999998e-01 , -2.9842000000000002e-01 , 8.6731999999999998e-01 --2.1636258667586716e+00 , 5.3209401370865592e+00 , 4.6674879999999996e-01 , 6.2619800000000003e-01 , -5.7042400000000004e-01 , 5.3150100000000000e-01 --2.2055129050643556e+00 , 5.3559776854605285e+00 , 5.5794640000000006e-01 , -7.5173400000000001e-01 , 4.9867800000000001e-01 , -4.3152900000000000e-01 --2.2542856954942954e+00 , 5.3949357962945683e+00 , 6.4602399999999993e-01 , -7.2606099999999996e-01 , 4.7866700000000001e-01 , -4.9367299999999997e-01 --2.2943712292631853e+00 , 5.4282056113956934e+00 , 7.3940560000000000e-01 , 7.1168699999999996e-01 , -5.2752299999999996e-01 , 4.6392000000000000e-01 --2.3236541055922517e+00 , 5.4556641444835439e+00 , 8.3782080000000003e-01 , 6.9777500000000003e-01 , -5.9504500000000005e-01 , 3.9878700000000000e-01 --2.3608371914621644e+00 , 5.4881215937349985e+00 , 9.3299120000000002e-01 , 6.8461700000000003e-01 , -6.4107800000000004e-01 , 3.4687000000000001e-01 --2.3793526566093739e+00 , 5.5076393952418909e+00 , 1.0364587199999999e+00 , 6.8380600000000002e-01 , -6.6835299999999997e-01 , 2.9277100000000000e-01 --2.4047341845908168e+00 , 5.5321322913002842e+00 , 1.1368041600000001e+00 , 6.6996900000000004e-01 , -7.0126400000000000e-01 , 2.4366199999999999e-01 --2.4201976150982354e+00 , 5.5505709270193995e+00 , 1.2408519999999998e+00 , 6.4612599999999998e-01 , -7.2887000000000002e-01 , 2.2642799999999999e-01 --2.4267476106016721e+00 , 5.5618390561713476e+00 , 1.3480739200000000e+00 , 6.2949699999999997e-01 , -7.5698500000000002e-01 , 1.7523300000000000e-01 --2.4391315883937699e+00 , 5.5780686509551005e+00 , 1.4523016799999999e+00 , 6.1701499999999998e-01 , -7.7435200000000004e-01 , 1.4025399999999999e-01 --2.4414929231755398e+00 , 5.5880423358252163e+00 , 1.5593208000000001e+00 , 6.3718500000000000e-01 , -7.4929400000000002e-01 , 1.8042800000000001e-01 --2.4507912497691970e+00 , 5.6020323115963784e+00 , 1.6636276000000001e+00 , 6.4351100000000006e-01 , -7.4394199999999999e-01 , 1.8012200000000000e-01 --2.4751091468074593e+00 , 5.6253613182026712e+00 , 1.7636963999999999e+00 , 6.4516300000000004e-01 , -7.4037500000000001e-01 , 1.8870400000000001e-01 --2.4823949497434699e+00 , 5.6372230984829512e+00 , 1.8684628800000000e+00 , 6.5045399999999998e-01 , -7.3706700000000003e-01 , 1.8341399999999999e-01 --2.4956417320503022e+00 , 5.6542540543397246e+00 , 1.9712470160000000e+00 , 6.7602600000000002e-01 , -7.2034299999999996e-01 , 1.5522700000000000e-01 --2.5069067068895095e+00 , 5.6692036458455828e+00 , 2.0746925919999999e+00 , -7.0709999999999995e-01 , 6.9606800000000002e-01 , -1.2449600000000000e-01 --2.5171396011831435e+00 , 5.6841396084317495e+00 , 2.1782643199999998e+00 , -6.8992699999999996e-01 , 7.1965299999999999e-01 , -7.8100500000000003e-02 --2.5091128586760423e+00 , 5.6861593360779157e+00 , 2.2848393599999999e+00 , 6.0467199999999999e-01 , -7.9612200000000000e-01 , 2.3694600000000000e-02 --2.5162499090788257e+00 , 5.6988577458125285e+00 , 2.3884888800000001e+00 , 4.9079499999999998e-01 , -8.6993699999999996e-01 , -4.8265200000000001e-02 --2.5050576256566730e+00 , 5.6985054875575702e+00 , 2.4945366400000002e+00 , 4.2018200000000000e-01 , -9.0741700000000003e-01 , -6.4948899999999997e-03 --2.4916966356070720e+00 , 5.6979243218888662e+00 , 2.5999240000000001e+00 , 4.7993599999999997e-01 , -8.7179799999999996e-01 , 9.8137100000000005e-02 --2.5203596746857322e+00 , 5.7238955505616733e+00 , 2.7016100000000001e+00 , -6.7521100000000001e-01 , 7.3589400000000005e-01 , -5.0508999999999998e-02 --2.5645491786969856e+00 , 5.7611829161714798e+00 , 2.8035081599999998e+00 , -9.0387399999999996e-01 , 3.7154199999999998e-01 , -2.1205599999999999e-01 --2.6336605229641794e+00 , 5.8156176828396795e+00 , 2.9060916799999998e+00 , -7.8153099999999998e-01 , 1.5514700000000001e-01 , -6.0426700000000000e-01 --2.7093766325158253e+00 , 5.8741573091080728e+00 , 3.0118596799999997e+00 , 8.7842200000000004e-01 , 8.1752599999999995e-02 , 4.7083999999999998e-01 --2.7750824960233871e+00 , 5.9265021816172876e+00 , 3.1206208000000002e+00 , -9.6723800000000004e-01 , -2.0518300000000000e-02 , -2.5303900000000001e-01 --2.8131292150847829e+00 , 5.9600791696802897e+00 , 3.2317136000000000e+00 , 9.7864899999999999e-01 , -1.0582200000000000e-01 , 1.7620700000000000e-01 --2.8409607293515693e+00 , 5.9870784902202177e+00 , 3.3439712000000004e+00 , -9.5606000000000002e-01 , 2.5059500000000001e-01 , -1.5215300000000001e-01 --2.8575441240705839e+00 , 6.0063830849249324e+00 , 3.4573312000000000e+00 , -9.2829899999999999e-01 , 3.3946300000000001e-01 , -1.5174299999999999e-01 --2.8825563782694958e+00 , 6.0316193624961008e+00 , 3.5719912000000003e+00 , -8.9383699999999999e-01 , 4.0607799999999999e-01 , -1.9014700000000001e-01 --2.8962734055550854e+00 , 6.0490855711759028e+00 , 3.6873583999999999e+00 , -8.8720800000000000e-01 , 4.2365900000000001e-01 , -1.8269099999999999e-01 --2.9164198617239627e+00 , 6.0714668231550828e+00 , 3.8046807999999999e+00 , -8.9194799999999996e-01 , 4.2088300000000001e-01 , -1.6518800000000000e-01 --2.9272336069029858e+00 , 6.0870172365927742e+00 , 3.9217431999999999e+00 , -8.0333299999999996e-01 , 5.5058099999999999e-01 , -2.2697300000000001e-01 --2.9360786376754202e+00 , 6.1015978416033585e+00 , 4.0396584000000004e+00 , -6.8263700000000005e-01 , 7.1821500000000005e-01 , -1.3480900000000001e-01 --2.9429263040122846e+00 , 6.1151719997392791e+00 , 4.1582392000000006e+00 , -7.4375100000000005e-01 , 6.5049599999999996e-01 , -1.5391700000000000e-01 --2.9478392702470737e+00 , 6.1267401365804410e+00 , 4.2778808000000001e+00 , -7.8898400000000002e-01 , 5.9118000000000004e-01 , -1.6736400000000001e-01 --2.9677744366003491e+00 , 6.1494401187493146e+00 , 4.4021191999999996e+00 , -7.3497999999999997e-01 , 6.7511800000000000e-01 , -6.3413100000000000e-02 --2.9772628555405474e+00 , 6.1651530738760654e+00 , 4.5254944000000004e+00 , -8.5264899999999999e-01 , 5.1563300000000001e-01 , -8.4337499999999996e-02 --2.9923322238637882e+00 , 6.1849980304529524e+00 , 4.6523952000000008e+00 , -8.2516299999999998e-01 , 5.5784999999999996e-01 , -8.8935100000000003e-02 --3.0065460799960748e+00 , 6.2029259377109298e+00 , 4.7805336000000000e+00 , 5.5659000000000003e-01 , -8.1328199999999995e-01 , 1.6964799999999999e-01 --3.0263990197769504e+00 , 6.2261625527065982e+00 , 4.9126864000000001e+00 , -6.4799899999999999e-01 , 7.4189300000000002e-01 , -1.7231399999999999e-01 --3.0691815289589846e+00 , 6.2651464629785192e+00 , 5.0549168000000000e+00 , 8.0905000000000005e-01 , -5.6626799999999999e-01 , 1.5741300000000000e-01 --3.0842547589095588e+00 , 6.2856909973479604e+00 , 5.1905432000000005e+00 , -8.9545500000000000e-01 , 4.1624499999999998e-01 , -1.5780200000000000e-01 --3.1137426105816610e+00 , 6.3158881991614404e+00 , 5.3341256000000001e+00 , -9.5444099999999998e-01 , 2.4862100000000001e-01 , -1.6501800000000000e-01 --3.1556772037762899e+00 , 6.3558716893842941e+00 , 5.4867248000000002e+00 , -9.7123700000000002e-01 , 2.0799200000000001e-01 , -1.1592300000000000e-01 --3.2122735182788560e+00 , 6.4048422890939829e+00 , 5.6492040000000001e+00 , -9.8905799999999999e-01 , 1.0995199999999999e-01 , -9.8356399999999997e-02 --4.7432928912718548e+00 , 7.4992322315565954e+00 , 6.5223879999999994e+00 , -9.4700099999999998e-01 , -2.1869099999999999e-02 , -3.2048500000000002e-01 --4.6396359434358994e+00 , 7.4390663766296212e+00 , 6.6516912000000001e+00 , -8.9607400000000004e-01 , 3.7383699999999997e-01 , -2.3937000000000000e-01 --4.5345678518561314e+00 , 7.3782209260182103e+00 , 6.7778848000000007e+00 , 6.2330300000000005e-01 , 6.0035899999999998e-01 , 5.0106099999999998e-01 --1.0045107865370934e+01 , 1.1323120171242644e+01 , 1.0019554400000001e+01 , 2.1931700000000001e-01 , 8.9564900000000003e-01 , -3.8692900000000002e-01 --5.2240973885904847e+00 , 7.8970612169437606e+00 , 7.5458727999999997e+00 , 3.6448700000000001e-01 , 3.1737300000000002e-01 , 8.7545600000000001e-01 --3.2356939008774477e+00 , 6.4860905328995910e+00 , 6.5429176000000000e+00 , -9.3197900000000000e-01 , 3.5192800000000002e-01 , -8.6954500000000004e-02 --3.2333759556356467e+00 , 6.4959091562947524e+00 , 6.6975552000000000e+00 , -9.3197900000000000e-01 , 3.5192800000000002e-01 , -8.6954400000000001e-02 --3.2202855056312041e+00 , 6.4981807070164317e+00 , 6.8486152000000002e+00 , -9.2386500000000005e-01 , 3.8083899999999998e-01 , -3.7875600000000002e-02 --3.2120319329330682e+00 , 6.5039498372902749e+00 , 7.0055304000000005e+00 , -9.4484500000000005e-01 , 3.0323600000000001e-01 , -1.2375600000000000e-01 --3.2154647766179867e+00 , 6.5188953517824206e+00 , 7.1738336000000009e+00 , -9.5136100000000001e-01 , 2.6738000000000001e-01 , -1.5304000000000001e-01 --3.2955281552102740e+00 , 6.5887251610027544e+00 , 7.4032160000000005e+00 , -9.2676700000000001e-01 , 3.1786100000000000e-01 , -2.0016800000000001e-01 --3.2981450310512619e+00 , 6.6036238498857687e+00 , 7.5819920000000005e+00 , -9.2322899999999997e-01 , 3.7340499999999999e-01 , -9.0649700000000000e-02 --3.5155199100975043e+00 , 6.7762577117820699e+00 , 7.9392216000000007e+00 , -8.6347900000000000e-01 , 2.5703300000000001e-01 , 4.3397999999999998e-01 --3.4603720851009001e+00 , 6.7501372225296876e+00 , 8.0848528000000002e+00 , -7.5224199999999997e-01 , 2.4861400000000000e-01 , 6.1018300000000003e-01 --3.3754003811166271e+00 , 6.7018462905634362e+00 , 8.2058672000000001e+00 , -9.6843900000000005e-01 , 1.9266700000000000e-01 , 1.5813400000000000e-01 --8.2251099848162923e-02 , 4.2790065674576008e+00 , 5.3945600000000002e+00 , -9.3441200000000002e-01 , 1.2382500000000000e-01 , 3.3398000000000000e-01 --9.8845792161922130e-02 , 4.2987333329859805e+00 , 5.4994960000000006e+00 , -9.4534300000000004e-01 , 1.3610900000000001e-01 , 2.9631299999999999e-01 --1.0762166729964839e-01 , 4.3118211201315226e+00 , 5.5994504000000003e+00 , -9.4534300000000004e-01 , 1.3610900000000001e-01 , 2.9631299999999999e-01 -2.0980622090200463e-02 , 4.2223518216055513e+00 , 5.5623224000000002e+00 , -9.4534300000000004e-01 , 1.3610900000000001e-01 , 2.9631299999999999e-01 --1.3996654985874843e+00 , 5.2957886775237029e+00 , 7.1613744000000006e+00 , -5.1331899999999997e-01 , 7.6333399999999996e-01 , 3.9220500000000003e-01 --1.3121222915006845e+00 , 5.2406227828234648e+00 , 7.2171912000000003e+00 , -5.3740800000000000e-01 , 7.3424900000000004e-01 , 4.1481400000000002e-01 --1.3234730537743733e-01 , 4.3593572519443473e+00 , 6.0251120000000000e+00 , -7.9339000000000004e-01 , -1.9834900000000000e-01 , 5.7549099999999997e-01 --1.1736964932066085e-01 , 4.3559309550271337e+00 , 6.1167464000000002e+00 , -7.9339000000000004e-01 , -1.9834900000000000e-01 , 5.7549099999999997e-01 --6.1579902394444126e+00 , 8.9707990181087567e+00 , 1.3635208000000000e+01 , -9.4188900000000006e-02 , 6.9083899999999998e-01 , -7.1684700000000001e-01 -3.4590672643228570e-02 , 4.2569240643506205e+00 , 6.1531776000000002e+00 , 8.1315800000000005e-01 , 3.2484800000000003e-01 , -4.8295800000000000e-01 -4.0730656621392525e-02 , 4.2597710408429528e+00 , 6.2581863999999996e+00 , 6.2475899999999995e-01 , 3.3251999999999998e-01 , -7.0647499999999996e-01 -9.5410634334230693e-02 , 4.2261170359359053e+00 , 6.3031144000000001e+00 , -5.3521099999999999e-01 , -1.9926400000000000e-01 , 8.2087900000000003e-01 -2.4256045300420870e-01 , 4.1212643184556583e+00 , 6.2145896000000000e+00 , 6.9054199999999999e-01 , -3.2774700000000001e-01 , -6.4477399999999996e-01 -2.5199917346270806e-01 , 4.1215010210249492e+00 , 6.3179552000000001e+00 , 5.0408200000000003e-01 , -8.5278799999999999e-01 , -1.3657700000000000e-01 -3.0114530915805493e-01 , 4.0919036745118831e+00 , 6.3659928000000008e+00 , -4.6575200000000000e-01 , 8.7848099999999996e-01 , -1.0651400000000000e-01 --4.7695066867885494e-02 , 4.3765595563144570e+00 , 7.0456016000000004e+00 , -7.0170500000000002e-01 , 4.8769299999999999e-01 , -5.1939000000000002e-01 --9.7392315267941232e-02 , 4.4282444949331978e+00 , 7.2810264000000000e+00 , -5.1333899999999999e-01 , 7.7204600000000001e-01 , 3.7473699999999999e-01 --2.5826231585249859e-01 , 4.5682203575333080e+00 , 7.7200831999999995e+00 , 5.5043600000000004e-01 , 1.0084700000000000e-02 , 8.3481700000000003e-01 -3.4271979884840520e-01 , 4.0985591162873760e+00 , 6.8347519999999999e+00 , 4.6127000000000001e-01 , 7.8381599999999996e-01 , 4.1576700000000000e-01 -2.3751633476745737e-01 , 4.1949363424160033e+00 , 7.1800215999999999e+00 , -6.9390900000000000e-01 , -3.4203400000000000e-01 , -6.3364299999999996e-01 -4.0229084354321554e-01 , 4.0727091781418228e+00 , 7.0301264000000003e+00 , 1.6483000000000000e-01 , 9.3261300000000003e-01 , 3.2103500000000001e-01 -5.9992422015738356e-01 , 3.9224219296472063e+00 , 6.7954088000000006e+00 , -8.9073100000000005e-01 , -2.4674499999999999e-01 , -3.8172600000000001e-01 -4.8263170621985707e-01 , 4.0310349332486872e+00 , 7.1988248000000006e+00 , -2.7119199999999999e-01 , 7.1597299999999997e-01 , 6.4330200000000004e-01 -6.6245053522088559e-01 , 3.8938814820269387e+00 , 6.9833472000000008e+00 , -8.4844399999999998e-01 , 3.7484499999999998e-01 , 3.7367600000000001e-01 -7.3339427691704162e-01 , 3.8477449691252090e+00 , 6.9961080000000004e+00 , 7.8095199999999998e-01 , 3.4842299999999998e-01 , 5.1837800000000001e-01 -1.0057934561819502e+00 , 3.6294615971755828e+00 , 6.5241560000000005e+00 , -8.6441999999999997e-01 , 4.6931200000000001e-01 , 1.8034300000000000e-01 -1.0536513653732671e+00 , 3.6007279357648048e+00 , 6.5656727999999998e+00 , -8.6442099999999999e-01 , 4.6931200000000001e-01 , 1.8034300000000000e-01 -1.0984206235689560e+00 , 3.5738194358421160e+00 , 6.6156240000000004e+00 , -8.3409199999999994e-01 , -1.6676199999999999e-01 , 5.2581400000000000e-01 -1.2089401567203346e+00 , 3.4900439453138254e+00 , 6.4868928000000006e+00 , -5.4470300000000005e-01 , -6.5372500000000000e-01 , -5.2530200000000005e-01 -9.8090608554417580e-01 , 3.7042471723470052e+00 , 7.3169376000000002e+00 , -4.0278000000000003e-01 , -8.0642999999999998e-01 , -4.3294199999999999e-01 -1.2161316562737328e+00 , 3.5104751393331055e+00 , 6.8269935999999998e+00 , 5.1613799999999999e-01 , -1.5723500000000001e-01 , -8.4194899999999995e-01 -1.2085139195335066e+00 , 3.5315334937411365e+00 , 7.0563864000000001e+00 , 4.8161199999999998e-01 , 2.6332200000000000e-01 , -8.3589000000000002e-01 -1.3275771222311210e+00 , 3.4392497701221076e+00 , 6.8819887999999994e+00 , -9.8864800000000003e-02 , 9.3481300000000003e-02 , 9.9070000000000003e-01 -1.3618590251824019e+00 , 3.4235646752215674e+00 , 6.9853752000000009e+00 , 5.8938800000000002e-01 , -8.5319900000000004e-02 , -8.0333200000000005e-01 -1.4297428681375126e+00 , 3.3764364867978278e+00 , 6.9714704000000003e+00 , -1.6132400000000000e-01 , 7.8876299999999999e-01 , 5.9315099999999998e-01 -1.4869657845253665e+00 , 3.3394353663484808e+00 , 6.9950472000000001e+00 , -2.3512800000000000e-01 , -5.9491700000000003e-01 , -7.6862799999999998e-01 -1.5652705838151761e+00 , 3.2823012499597852e+00 , 6.9284248000000002e+00 , -3.4085900000000002e-02 , -5.6125999999999998e-01 , 8.2693799999999995e-01 -1.5984649568427101e+00 , 3.2699081162696109e+00 , 7.0584768000000002e+00 , 6.7639099999999996e-01 , 3.1560100000000002e-01 , 6.6550100000000001e-01 -1.6615874497765342e+00 , 3.2279376037547109e+00 , 7.0586536000000004e+00 , 6.6228500000000001e-01 , -3.1937700000000002e-01 , -6.7777299999999996e-01 -1.6808327855478302e+00 , 3.2309368469133588e+00 , 7.2884311999999998e+00 , 6.9715499999999997e-01 , -4.8119299999999998e-01 , -5.3144000000000002e-01 -1.4975244764797222e+00 , 3.4629291074892472e+00 , 8.7697135999999993e+00 , -3.1561299999999998e-01 , -7.3222399999999999e-01 , 6.0352099999999997e-01 -1.6433164179272910e+00 , 3.3372466127054574e+00 , 8.3878152000000004e+00 , 5.2513900000000002e-01 , 7.7434400000000003e-01 , 3.5301600000000000e-01 -1.7265060399301828e+00 , 3.2795852509721874e+00 , 8.3670983999999997e+00 , 8.4421200000000002e-02 , -7.7062600000000003e-01 , 6.3167099999999998e-01 -4.4859706056464854e-01 , 3.6729898287527250e+00 , 6.1316000000000015e-01 , -7.8472899999999998e-02 , 2.9547299999999999e-02 , 9.9647799999999997e-01 -3.7755684458681738e-01 , 3.7232771142764345e+00 , 6.1043519999999996e-01 , -6.1606399999999999e-02 , 3.6379099999999998e-02 , 9.9743700000000002e-01 -2.9450914518044935e-01 , 3.7822830741187214e+00 , 5.9571919999999978e-01 , -5.7831500000000001e-02 , 5.9561799999999998e-02 , 9.9654799999999999e-01 -2.1543759025753073e-01 , 3.8377973711355429e+00 , 5.9086240000000001e-01 , -1.7220900000000001e-02 , 9.7704600000000003e-02 , 9.9506600000000001e-01 -1.3072791294472941e-01 , 3.8990344201823497e+00 , 5.8159600000000000e-01 , -5.1737900000000003e-02 , 8.8568700000000000e-02 , 9.9472499999999997e-01 -4.4591534920174425e-02 , 3.9598761474373427e+00 , 5.7533520000000005e-01 , -7.1429300000000001e-02 , 1.1040700000000001e-01 , 9.9131599999999997e-01 --6.9701363317571374e-02 , 4.0393743245551628e+00 , 5.4501920000000004e-01 , -1.0174800000000001e-01 , 1.2016499999999999e-01 , 9.8752600000000001e-01 --1.7803591185837497e-01 , 4.1154961405890713e+00 , 5.2549839999999981e-01 , -4.7306000000000001e-02 , 8.7734999999999994e-02 , 9.9502000000000002e-01 --2.8033291708042096e-01 , 4.1891596284198878e+00 , 5.1619040000000016e-01 , -3.2474299999999998e-02 , 9.4927899999999996e-02 , 9.9495400000000001e-01 --3.9063384317202710e-01 , 4.2669202525962291e+00 , 5.0443839999999995e-01 , -8.2480800000000007e-02 , 1.2487200000000000e-01 , 9.8873900000000003e-01 --5.3048894241373112e-01 , 4.3651020324884930e+00 , 4.7174080000000007e-01 , -6.7578899999999997e-02 , 1.2403800000000000e-01 , 9.8997400000000002e-01 --6.5693533648075020e-01 , 4.4545626686244386e+00 , 4.5663999999999993e-01 , -4.7652300000000002e-02 , 1.1427400000000000e-01 , 9.9230600000000002e-01 --8.0664683012169158e-01 , 4.5593842389837800e+00 , 4.2845599999999973e-01 , -3.1514700000000000e-02 , 9.9349499999999993e-02 , 9.9455300000000002e-01 --9.4388625244896485e-01 , 4.6564408450942150e+00 , 4.1714079999999987e-01 , 1.2688000000000000e-02 , 8.6726700000000004e-02 , 9.9615100000000001e-01 --1.0882896791386454e+00 , 4.7600993823323918e+00 , 4.0543039999999997e-01 , 1.7445900000000000e-02 , 9.9879099999999998e-02 , 9.9484700000000004e-01 --1.2496629333429494e+00 , 4.8740280542242065e+00 , 3.8832239999999985e-01 , -8.1326799999999998e-03 , 1.0459200000000000e-01 , 9.9448199999999998e-01 --1.4117737904461194e+00 , 4.9892397623445000e+00 , 3.7748559999999975e-01 , -2.1009600000000000e-02 , 1.2015000000000001e-01 , 9.9253400000000003e-01 --1.6359524711116782e+00 , 5.1468586170491610e+00 , 3.3196479999999995e-01 , -6.4387000000000000e-02 , 1.3548499999999999e-01 , 9.8868500000000004e-01 --1.8688776420753315e+00 , 5.3109814591050828e+00 , 2.9049999999999998e-01 , 6.6034999999999996e-02 , 1.2399300000000001e-01 , 9.9008300000000005e-01 --2.0586973806640962e+00 , 5.4468292092203248e+00 , 2.8655839999999988e-01 , -4.8477300000000001e-01 , -3.4301199999999997e-02 , -8.7396700000000005e-01 --2.1721306786355017e+00 , 5.5306719648657019e+00 , 3.3593759999999984e-01 , -8.4435199999999999e-01 , 1.3404099999999999e-01 , -5.1875099999999996e-01 --2.2142140133016834e+00 , 5.5682483223263990e+00 , 4.2915280000000000e-01 , -8.6873100000000003e-01 , 2.6149499999999998e-01 , -4.2062600000000000e-01 --2.2409411203248153e+00 , 5.5933067664044751e+00 , 5.3200880000000006e-01 , -9.0786199999999995e-01 , 3.6443999999999999e-01 , -2.0729400000000001e-01 --2.2489981427183388e+00 , 5.6076120361380468e+00 , 6.4344479999999993e-01 , -8.6484200000000000e-01 , 4.7211900000000001e-01 , -1.7073800000000000e-01 --2.2716485649926801e+00 , 5.6305150268858526e+00 , 7.4700799999999989e-01 , -8.3117700000000005e-01 , 5.3090300000000001e-01 , -1.6518900000000000e-01 --2.2776028432067443e+00 , 5.6425087707779618e+00 , 8.5799680000000000e-01 , -8.0447900000000006e-01 , 5.5866499999999997e-01 , -2.0176100000000000e-01 --2.2971962643116246e+00 , 5.6632087809607343e+00 , 9.6184391999999996e-01 , -7.9960900000000001e-01 , 5.7137400000000005e-01 , -1.8481600000000001e-01 --2.3068634614111101e+00 , 5.6778667896576778e+00 , 1.0693882399999999e+00 , -8.0345999999999995e-01 , 5.6764300000000001e-01 , -1.7953400000000000e-01 --2.3155234934177900e+00 , 5.6903307564051984e+00 , 1.1768618399999999e+00 , -8.0461000000000005e-01 , 5.6912600000000002e-01 , -1.6940900000000000e-01 --2.3299548433796353e+00 , 5.7087557632046195e+00 , 1.2810344800000000e+00 , -8.2098499999999996e-01 , 5.5421399999999998e-01 , -1.3722599999999999e-01 --2.3434200752438965e+00 , 5.7250845226566325e+00 , 1.3855420000000001e+00 , -8.4774799999999995e-01 , 5.1658300000000001e-01 , -1.2027400000000001e-01 --2.3468545375664602e+00 , 5.7351696310484597e+00 , 1.4928398400000000e+00 , -8.7666100000000002e-01 , 4.6913700000000003e-01 , -1.0665500000000000e-01 --2.3572320520712404e+00 , 5.7492485787954708e+00 , 1.5974253599999999e+00 , -8.8671400000000000e-01 , 4.3667499999999998e-01 , -1.5183400000000000e-01 --2.3745637837710243e+00 , 5.7684757587521531e+00 , 1.6997010399999999e+00 , -8.9878000000000002e-01 , 4.2595400000000000e-01 , -1.0372400000000000e-01 --2.3728025583919052e+00 , 5.7751254105358143e+00 , 1.8068262399999999e+00 , -9.0230900000000003e-01 , 4.1924899999999998e-01 , -1.0033900000000000e-01 --2.3870855535663908e+00 , 5.7921903806971020e+00 , 1.9095859360000000e+00 , -8.9687300000000003e-01 , 4.0515000000000001e-01 , -1.7740600000000001e-01 --2.4003704824998175e+00 , 5.8082055090710432e+00 , 2.0125751599999999e+00 , -8.9472700000000005e-01 , 4.2364800000000002e-01 , -1.4137400000000000e-01 --2.4196962805206788e+00 , 5.8295221799100112e+00 , 2.1142908000000000e+00 , -8.9758599999999999e-01 , 4.3335600000000002e-01 , 8.0882300000000004e-02 --2.3955580843426771e+00 , 5.8188056827289198e+00 , 2.2243259200000001e+00 , 6.9025999999999998e-01 , -7.1299100000000004e-01 , -1.2323000000000001e-01 --2.3610497323537176e+00 , 5.8023175694018585e+00 , 2.3343173600000000e+00 , -5.3684399999999999e-01 , 7.9052699999999998e-01 , 2.9473100000000002e-01 --2.3171976424749081e+00 , 5.7778972543019087e+00 , 2.4438397599999999e+00 , -3.4931600000000002e-01 , 9.2099200000000003e-01 , 1.7249000000000000e-01 --2.2965477171417792e+00 , 5.7705166402531853e+00 , 2.5486062399999998e+00 , 3.0045699999999997e-01 , -9.5365800000000001e-01 , 1.6157299999999999e-02 --2.3259125493484989e+00 , 5.7981177329219769e+00 , 2.6477328000000000e+00 , 1.7165100000000000e-01 , -9.6966200000000002e-01 , 1.7404200000000000e-01 --2.4046752022132853e+00 , 5.8603268499780894e+00 , 2.7446868000000002e+00 , 1.7081499999999999e-01 , -8.0229099999999998e-01 , 5.7197200000000004e-01 --2.5146370735695802e+00 , 5.9465180848539259e+00 , 2.8433776000000002e+00 , -6.9218500000000005e-01 , 2.0677400000000001e-01 , -6.9146600000000003e-01 --2.7849654649682574e+00 , 6.1469587935031509e+00 , 2.9425426400000001e+00 , 9.1103100000000004e-01 , 3.1435699999999997e-02 , 4.1113800000000000e-01 --2.7993199526332377e+00 , 6.1648475818141559e+00 , 3.0546328000000003e+00 , -9.7862700000000002e-01 , 7.9662299999999995e-03 , -2.0548800000000000e-01 --2.8033936708014853e+00 , 6.1760446549373285e+00 , 3.1672960000000003e+00 , -9.6745800000000004e-01 , 2.2855500000000001e-01 , -1.0857500000000000e-01 --2.8065135297255974e+00 , 6.1851536072444624e+00 , 3.2803960000000001e+00 , -9.5606000000000002e-01 , 2.5059500000000001e-01 , -1.5215300000000001e-01 --2.8158854149707908e+00 , 6.1999775938577502e+00 , 3.3941407999999997e+00 , -9.2829899999999999e-01 , 3.3946300000000001e-01 , -1.5174299999999999e-01 --2.8243403556449902e+00 , 6.2127908688721947e+00 , 3.5086240000000002e+00 , -9.0761700000000001e-01 , 3.8495800000000002e-01 , -1.6744899999999999e-01 --2.8391394712103297e+00 , 6.2314596716126944e+00 , 3.6244592000000000e+00 , -8.9728399999999997e-01 , 4.0786800000000001e-01 , -1.6889199999999999e-01 --2.8603782083513671e+00 , 6.2550414514915316e+00 , 3.7422599999999999e+00 , -8.9834700000000001e-01 , 4.0687899999999999e-01 , -1.6559699999999999e-01 --2.8713046255980617e+00 , 6.2707812556501334e+00 , 3.8602272000000002e+00 , -9.1171500000000005e-01 , 3.8119300000000000e-01 , -1.5318999999999999e-01 --2.8971405708955720e+00 , 6.2974635144155391e+00 , 3.9818760000000002e+00 , -9.3367699999999998e-01 , 3.2924300000000001e-01 , -1.4087700000000000e-01 --2.9136356786718594e+00 , 6.3173271934929076e+00 , 4.1032544000000000e+00 , -9.4967199999999996e-01 , 2.7643200000000001e-01 , -1.4734000000000000e-01 --2.9441589145348637e+00 , 6.3472402318723731e+00 , 4.2294584000000004e+00 , -9.7308700000000004e-01 , 1.5239000000000000e-01 , -1.7285300000000001e-01 --2.9643092323310736e+00 , 6.3703210616441073e+00 , 4.3555168000000002e+00 , -9.2340000000000000e-01 , 3.4083999999999998e-01 , -1.7652300000000001e-01 --3.0401231807314275e+00 , 6.4351016541485624e+00 , 4.4974976000000000e+00 , -9.0346599999999999e-01 , 4.0160200000000001e-01 , -1.4988299999999999e-01 --5.3194646789969093e+00 , 8.1198630644633365e+00 , 5.2635823999999998e+00 , -7.1694999999999998e-01 , -5.6602200000000003e-01 , 4.0694300000000000e-01 --5.2900676059867484e+00 , 8.1104248248713766e+00 , 5.4338408000000005e+00 , -8.1110800000000005e-01 , 5.6838800000000000e-01 , 1.3798299999999999e-01 --5.0799842975868756e+00 , 7.9667467392262656e+00 , 5.5455784000000001e+00 , -7.7484100000000000e-01 , -5.4351600000000000e-01 , 3.2281799999999999e-01 --4.1296220366292582e+00 , 7.2753592550257471e+00 , 5.3892767999999993e+00 , 1.8159100000000000e-01 , 9.5299999999999996e-01 , 2.4252099999999999e-01 --5.3872961916002700e+00 , 8.2193378970803366e+00 , 6.0169168000000006e+00 , -8.1110800000000005e-01 , 5.6838699999999998e-01 , 1.3798299999999999e-01 --4.4566402336707487e+00 , 7.5395228531827465e+00 , 5.8348335999999996e+00 , 8.0490899999999999e-01 , -4.1498800000000002e-01 , 4.2415399999999998e-01 --4.5136768062418655e+00 , 7.5946437842683103e+00 , 6.0277431999999997e+00 , -3.2734500000000000e-01 , -8.8775700000000002e-01 , -3.2362500000000000e-01 --4.5134688919724706e+00 , 7.6048729936051362e+00 , 6.1998008000000002e+00 , -3.9342600000000000e-01 , 9.1820500000000005e-01 , -4.5985800000000000e-02 --4.5793193150100988e+00 , 7.6673013448068579e+00 , 6.4059808000000000e+00 , -9.4700099999999998e-01 , -2.1869099999999999e-02 , -3.2048500000000002e-01 --4.7965378729737500e+00 , 7.8417814651572053e+00 , 6.6933743999999997e+00 , 9.9892999999999998e-01 , -1.2575299999999999e-02 , 4.4512400000000001e-02 --9.5539443924270415e+00 , 1.1431279270713448e+01 , 9.3751288000000006e+00 , 8.1374299999999999e-01 , 5.3875799999999996e-01 , 2.1808700000000000e-01 --5.3182257404136184e+00 , 8.2604834490527246e+00 , 7.3584752000000000e+00 , -6.2697700000000001e-01 , -9.4062900000000005e-02 , -7.7333799999999997e-01 --4.9949418920217488e+00 , 8.0299229756195203e+00 , 7.3793167999999998e+00 , 6.5837400000000001e-01 , 7.0071399999999995e-01 , 2.7485300000000001e-01 --5.1144833806912695e+00 , 8.1339522066421246e+00 , 7.6540743999999998e+00 , 6.2697800000000004e-01 , 9.4063099999999997e-02 , 7.7333799999999997e-01 --4.5689469223727857e+00 , 7.7350680433206360e+00 , 7.5193007999999999e+00 , 8.1941200000000003e-01 , 2.4284200000000000e-01 , 5.1922299999999999e-01 --4.3824723702509685e+00 , 7.6063522719926153e+00 , 7.5948048000000004e+00 , -7.9248799999999997e-01 , -6.0980900000000005e-01 , 9.7580900000000005e-03 --5.2832850849127144e-01 , 4.6789513350931449e+00 , 5.1341960000000002e+00 , 6.3712199999999997e-01 , -4.0390900000000002e-01 , -6.5645500000000001e-01 --3.2797008445894091e+00 , 6.7892441927222160e+00 , 7.2002183999999998e+00 , 9.8990100000000003e-01 , -1.0284699999999999e-01 , 9.7564799999999993e-02 --3.6700613992678779e+00 , 7.1004272661262791e+00 , 7.6653688000000004e+00 , 8.9493699999999998e-01 , -4.3607800000000002e-01 , 9.4466300000000003e-02 --3.5431764819175218e+00 , 7.0164461772462650e+00 , 7.7551832000000003e+00 , 9.9336599999999997e-01 , 6.6613800000000001e-02 , -9.3741300000000000e-02 --3.5210197065229547e+00 , 7.0115782138163780e+00 , 7.9254624000000007e+00 , -8.3737799999999996e-01 , 3.0049100000000001e-01 , 4.5662100000000000e-01 --3.3914706127030252e+00 , 6.9242958085596760e+00 , 8.0100663999999995e+00 , -8.3737799999999996e-01 , 3.0049100000000001e-01 , 4.5662100000000000e-01 --4.3637978668026447e+00 , 7.6917934583326844e+00 , 9.0558696000000012e+00 , -6.9356300000000004e-01 , -5.3162200000000004e-01 , -4.8615700000000001e-01 --4.4725029654842494e+00 , 7.7919389311097529e+00 , 9.3874320000000004e+00 , -4.1823600000000000e-01 , -4.6297700000000003e-01 , -7.8149199999999996e-01 --6.5608146437735382e-02 , 4.3691825273512350e+00 , 5.4609640000000006e+00 , -8.3684899999999995e-01 , 4.6920699999999999e-01 , 2.8200700000000001e-01 --6.8440400169711868e-02 , 4.3775008581980881e+00 , 5.5543664000000001e+00 , -8.3169199999999999e-01 , 4.2647600000000002e-01 , 3.5553600000000002e-01 --1.1665379408734466e-02 , 4.3397934764190440e+00 , 5.5901215999999998e+00 , -9.4655000000000000e-01 , 1.3579600000000000e-01 , 2.9258000000000001e-01 --1.1479612805431749e-02 , 4.3459964286104675e+00 , 5.6842208000000003e+00 , -9.2195499999999997e-01 , -2.1293300000000001e-01 , 3.2351099999999999e-01 --2.0781143240805466e-01 , 4.5075304431000589e+00 , 5.9960959999999996e+00 , -5.5914800000000002e-03 , 9.0521799999999997e-01 , 4.2491099999999998e-01 --1.2404158778860910e+00 , 5.3339383465558505e+00 , 7.2792792000000004e+00 , -5.3740900000000003e-01 , 7.3424900000000004e-01 , 4.1481400000000002e-01 --1.6730150157644585e-01 , 4.4906459583872138e+00 , 6.1686632000000001e+00 , 4.3326900000000002e-01 , 8.9238399999999996e-01 , -1.2621099999999999e-01 --5.1225108615083226e-02 , 4.4045481538124207e+00 , 6.1402608000000001e+00 , -6.8562299999999998e-01 , -3.2713399999999998e-01 , 6.5031099999999997e-01 --3.9205835979838177e-02 , 4.4038329583708453e+00 , 6.2394248000000001e+00 , 7.4387400000000004e-01 , 2.9518299999999997e-01 , -5.9959799999999996e-01 -4.7275590938441692e-02 , 4.3412890514834572e+00 , 6.2425552000000000e+00 , -8.1086700000000000e-01 , -2.3923300000000000e-01 , 5.3410000000000002e-01 -6.0373653738944100e-02 , 4.3382882179735640e+00 , 6.3411368000000001e+00 , -7.2087299999999999e-01 , -3.3574999999999999e-01 , -6.0631199999999996e-01 -2.0201858983101451e-01 , 4.2326379512700996e+00 , 6.2633448000000005e+00 , 2.1662000000000001e-02 , 1.6081900000000000e-02 , 9.9963599999999997e-01 -2.9138030592050779e-01 , 4.1668259246954618e+00 , 6.2509167999999997e+00 , 7.5505599999999995e-01 , -3.8957500000000000e-01 , -5.2737199999999995e-01 -2.7540226320127115e-01 , 4.1878555704476437e+00 , 6.3940312000000006e+00 , 9.8149600000000004e-01 , -1.8571199999999999e-01 , -4.6653000000000000e-02 -2.8373864257715620e-01 , 4.1900229567863754e+00 , 6.5067048000000005e+00 , -8.3994100000000005e-01 , 4.1022199999999998e-01 , -3.5527199999999998e-01 -2.0504592213499429e-03 , 4.4324215881559965e+00 , 7.1016056000000001e+00 , -4.2519600000000002e-01 , 8.2961700000000005e-01 , 3.6186099999999999e-01 --2.8312711094333709e-01 , 4.6801508429505105e+00 , 7.7433168000000006e+00 , 1.3542700000000000e-02 , 8.0010499999999996e-01 , 5.9970699999999999e-01 -3.4313032347649242e-01 , 4.1680417006268318e+00 , 6.8160736000000002e+00 , -5.7359100000000003e-02 , -3.8238600000000000e-01 , 9.2222000000000004e-01 -3.9338707042945176e-01 , 4.1356876479207774e+00 , 6.8717552000000000e+00 , 4.6127000000000001e-01 , 7.8381599999999996e-01 , 4.1576700000000000e-01 -4.1802566426339038e-01 , 4.1262716885768658e+00 , 6.9778456000000002e+00 , -4.0241900000000003e-01 , -7.9514600000000002e-01 , -4.5365400000000000e-01 -5.2736253018544610e-01 , 4.0439436918465184e+00 , 6.9193248000000009e+00 , -5.8081099999999997e-01 , -7.1548699999999998e-01 , -3.8824900000000001e-01 -6.5162125761481060e-01 , 3.9478955213400750e+00 , 6.8222200000000006e+00 , 9.9172700000000003e-01 , 1.8667000000000000e-02 , 1.2699700000000000e-01 -6.6105681803998384e-01 , 3.9509118026235939e+00 , 6.9603944000000002e+00 , 9.7777700000000001e-01 , 1.2428699999999999e-01 , 1.6883500000000001e-01 -6.8598640634448160e-01 , 3.9405785705723022e+00 , 7.0725792000000007e+00 , 9.8806600000000000e-01 , -6.6956300000000002e-03 , -1.5388499999999999e-01 -8.2066713976576278e-01 , 3.8341214469654332e+00 , 6.9312848000000002e+00 , 1.7942500000000000e-01 , 2.5401099999999999e-01 , 9.5041299999999995e-01 -7.2094338864447027e-01 , 3.9339121666079535e+00 , 7.3525992000000002e+00 , -5.6040100000000004e-01 , 2.6994600000000002e-01 , -7.8299399999999997e-01 -1.1119769954478369e+00 , 3.5988516488405682e+00 , 6.5424600000000002e+00 , -8.1423900000000005e-01 , -4.4231900000000002e-01 , 3.7599100000000002e-01 -9.8038514484295014e-01 , 3.7292378266691353e+00 , 7.0667032000000001e+00 , 5.1681600000000005e-01 , 7.7212700000000001e-01 , -3.6975799999999998e-01 -9.5885133885655915e-01 , 3.7611747316538531e+00 , 7.3259960000000000e+00 , 1.6099400000000000e-01 , 8.0042199999999997e-01 , 5.7741299999999995e-01 -1.0720934562032234e+00 , 3.6732077850421012e+00 , 7.2087048000000005e+00 , -9.2708100000000004e-01 , -3.6948900000000001e-01 , 6.3238000000000003e-02 -1.0832290444666575e+00 , 3.6770037515125633e+00 , 7.3933152000000000e+00 , 1.1453900000000000e-01 , 7.2393700000000005e-01 , 6.8029099999999998e-01 -1.3133110318409773e+00 , 3.4772334808319716e+00 , 6.8672312000000009e+00 , -3.7734400000000001e-01 , 2.2097900000000001e-01 , 8.9932199999999995e-01 -1.3626759983103580e+00 , 3.4450594470879956e+00 , 6.9130431999999997e+00 , -4.5862399999999998e-01 , 1.1888000000000000e-01 , 8.8064299999999995e-01 -1.4262032497220691e+00 , 3.3990961579673629e+00 , 6.9092887999999997e+00 , 3.4061500000000000e-01 , 7.9365300000000005e-01 , -5.0407999999999997e-01 -1.4168095592166581e+00 , 3.4238587224117607e+00 , 7.1882792000000002e+00 , 8.5497699999999999e-01 , -4.0293600000000002e-01 , 3.2658300000000001e-01 -1.5177932789015300e+00 , 3.3418854832406311e+00 , 7.0348480000000002e+00 , 4.6566900000000001e-02 , -9.0166100000000005e-01 , -4.2992799999999998e-01 -1.5751438415174799e+00 , 3.3024695874456147e+00 , 7.0570208000000001e+00 , 2.6166200000000001e-02 , 6.0011499999999995e-01 , 7.9948600000000003e-01 -1.6326368007444398e+00 , 3.2628066572490000e+00 , 7.0779768000000001e+00 , 1.1410800000000000e-01 , 1.4096700000000000e-02 , 9.9336800000000003e-01 -1.6598392619287123e+00 , 3.2554384790008974e+00 , 7.2580216000000002e+00 , 7.2862700000000002e-01 , -5.9163100000000002e-01 , -3.4507199999999999e-01 -1.5178581522806955e+00 , 3.4360122399697732e+00 , 8.4349375999999996e+00 , -5.9210200000000002e-01 , -8.0461000000000005e-01 , 4.4917800000000001e-02 -1.6075192711285373e+00 , 3.3684038886411187e+00 , 8.3767391999999994e+00 , 1.9416300000000000e-01 , -8.9624999999999999e-01 , 3.9879300000000001e-01 -1.6707077670955854e+00 , 3.3309672648220543e+00 , 8.4889864000000017e+00 , 7.4617500000000003e-01 , 6.3970600000000000e-01 , 1.8439100000000000e-01 -1.7957121782326655e+00 , 3.2174551220674159e+00 , 8.1420008000000017e+00 , 5.9842600000000001e-01 , -7.7842900000000004e-01 , 1.8956300000000001e-01 -4.6785542572559691e-01 , 3.7605761708028846e+00 , 6.1455360000000003e-01 , -7.6102299999999998e-02 , 3.8140599999999997e-02 , 9.9636999999999998e-01 -3.9882246852681469e-01 , 3.8131061414747887e+00 , 6.1287920000000007e-01 , -7.6102299999999998e-02 , 3.8140599999999997e-02 , 9.9636999999999998e-01 -3.1674168270976244e-01 , 3.8744091861546019e+00 , 5.9920320000000005e-01 , 7.5843700000000000e-02 , -1.0806800000000000e-01 , -9.9124599999999996e-01 -2.3333087481896397e-01 , 3.9373526963303496e+00 , 5.8812719999999996e-01 , -5.3852499999999998e-02 , 9.6233799999999994e-02 , 9.9390100000000003e-01 -1.4315235114711578e-01 , 4.0051002295604672e+00 , 5.7311999999999985e-01 , -1.6476800000000000e-02 , 9.4080200000000003e-02 , 9.9542799999999998e-01 -5.1546292555927131e-02 , 4.0735558703912096e+00 , 5.6133680000000008e-01 , -7.3240100000000002e-02 , 1.3754900000000000e-01 , 9.8778299999999997e-01 --5.9735518640312790e-02 , 4.1575164082775551e+00 , 5.3269519999999981e-01 , -6.3343300000000005e-02 , 1.2158800000000000e-01 , 9.9055700000000002e-01 --1.5321787237328222e-01 , 4.2274805565232381e+00 , 5.2796320000000008e-01 , -4.2858000000000000e-02 , 1.0419299999999999e-01 , 9.9363299999999999e-01 --2.6102353899614394e-01 , 4.3088455598394084e+00 , 5.1351759999999991e-01 , -4.1272999999999997e-02 , 1.0897000000000000e-01 , 9.9318799999999996e-01 --3.8984763689711732e-01 , 4.4051673861460170e+00 , 4.8453279999999999e-01 , -6.5973299999999999e-02 , 1.2051400000000000e-01 , 9.9051699999999998e-01 --5.1271545126218898e-01 , 4.4981230440611233e+00 , 4.6645759999999981e-01 , -7.7721899999999997e-02 , 1.2132900000000001e-01 , 9.8956500000000003e-01 --6.5128203954127439e-01 , 4.6019885068139299e+00 , 4.4117519999999999e-01 , -5.4896300000000002e-02 , 1.1888899999999999e-01 , 9.9138899999999996e-01 --7.9149751266575530e-01 , 4.7069735028474478e+00 , 4.2113439999999991e-01 , -4.2356999999999999e-02 , 1.1738899999999999e-01 , 9.9218200000000001e-01 --9.3994997958064541e-01 , 4.8186188239073271e+00 , 4.0078159999999996e-01 , 1.0938099999999999e-02 , 1.0311800000000000e-01 , 9.9460899999999997e-01 --1.0748750088828491e+00 , 4.9213760620358382e+00 , 3.9711040000000009e-01 , 2.0561099999999999e-02 , 1.1752899999999999e-01 , 9.9285699999999999e-01 --1.2551984396678977e+00 , 5.0557106752712588e+00 , 3.6660720000000002e-01 , 2.0746400000000002e-02 , 1.1069700000000000e-01 , 9.9363800000000002e-01 --1.4001261519956580e+00 , 5.1664575478125707e+00 , 3.6887439999999994e-01 , -2.0842099999999999e-02 , 1.3005300000000000e-01 , 9.9128799999999995e-01 --1.6423598588378878e+00 , 5.3469240544403460e+00 , 3.1169519999999995e-01 , -6.7211300000000002e-02 , 1.6630200000000001e-01 , 9.8378200000000005e-01 --1.8934432314482694e+00 , 5.5351364050706806e+00 , 2.5947679999999984e-01 , 1.4505799999999999e-01 , 7.5169799999999995e-02 , 9.8656400000000000e-01 --2.0496452439150392e+00 , 5.6550158636409096e+00 , 2.7830079999999979e-01 , 5.3466599999999997e-01 , -2.2845699999999999e-01 , 8.1359700000000001e-01 --2.1313233162195599e+00 , 5.7214516278091452e+00 , 3.4816799999999981e-01 , 7.6129700000000000e-01 , -5.1291500000000001e-01 , 3.9666699999999999e-01 --2.1503653651447818e+00 , 5.7418920033264751e+00 , 4.5608880000000007e-01 , -7.7889799999999998e-01 , 5.3777299999999995e-01 , -3.2267499999999999e-01 --2.1517366276349081e+00 , 5.7515358095866169e+00 , 5.7216320000000009e-01 , -8.3142600000000000e-01 , 5.3289399999999998e-01 , -1.5733800000000001e-01 --2.1676561106885481e+00 , 5.7696591568741606e+00 , 6.7985519999999977e-01 , -8.5970999999999997e-01 , 4.9109500000000000e-01 , -1.4044300000000001e-01 --2.1815004057510468e+00 , 5.7866538830909153e+00 , 7.8759920000000005e-01 , -8.4544500000000000e-01 , 4.9875799999999998e-01 , -1.9095400000000001e-01 --2.1942777717558739e+00 , 5.8035677638631906e+00 , 8.9516639999999992e-01 , -8.8553000000000004e-01 , 4.2573299999999997e-01 , -1.8597800000000000e-01 --2.2285789332244166e+00 , 5.8352617445659805e+00 , 9.9244383999999997e-01 , -9.3522200000000000e-01 , 3.0483900000000003e-01 , -1.8009400000000000e-01 --2.2462077722447882e+00 , 5.8550123317064644e+00 , 1.0972488000000000e+00 , -8.3140899999999995e-01 , 5.0911499999999998e-01 , -2.2262399999999999e-01 --2.2696685273927795e+00 , 5.8797141917863449e+00 , 1.1990596000000000e+00 , -8.7139500000000003e-01 , 4.2086000000000001e-01 , -2.5208500000000000e-01 --2.2921701971338946e+00 , 5.9034538119884843e+00 , 1.3015058399999999e+00 , -9.1255100000000000e-01 , 3.4295799999999999e-01 , -2.2278000000000001e-01 --2.3216620264227759e+00 , 5.9312626146019642e+00 , 1.4016443199999999e+00 , -9.3297900000000000e-01 , 2.9277500000000001e-01 , -2.0936199999999999e-01 --2.3412071082086516e+00 , 5.9529805184286104e+00 , 1.5052813600000001e+00 , -9.5443299999999998e-01 , 2.4360000000000001e-01 , -1.7238700000000001e-01 --2.3587724486879420e+00 , 5.9726272505967488e+00 , 1.6095808800000000e+00 , -9.6648400000000001e-01 , 1.9824600000000001e-01 , -1.6311600000000001e-01 --2.3753200336361493e+00 , 5.9922786730689737e+00 , 1.7141071200000000e+00 , 9.7788100000000000e-01 , -1.7349999999999999e-01 , 1.1681999999999999e-01 --2.3909301505157545e+00 , 6.0098704866413453e+00 , 1.8191689600000001e+00 , 9.8114199999999996e-01 , -1.6518800000000000e-01 , 1.0036299999999999e-01 --2.4044617812897240e+00 , 6.0274167231505507e+00 , 1.9244826879999999e+00 , 9.9108399999999996e-01 , -8.4229700000000005e-02 , 1.0323900000000000e-01 --2.4079752991213113e+00 , 6.0365307690384711e+00 , 2.0321883120000002e+00 , 9.9080400000000002e-01 , -1.3151700000000000e-01 , -3.1779200000000001e-02 --2.4184704522234313e+00 , 6.0519229222836488e+00 , 2.1379851200000002e+00 , 9.9314100000000005e-01 , -9.9778500000000006e-02 , -6.0947300000000003e-02 --2.3460060215640990e+00 , 6.0029854917673369e+00 , 2.2584035999999998e+00 , 8.4831199999999995e-01 , -3.2266699999999998e-01 , -4.1982399999999997e-01 --2.2456345126646076e+00 , 5.9348423053695800e+00 , 2.3790248800000002e+00 , -5.3698599999999996e-01 , 7.4681500000000001e-01 , 3.9231899999999997e-01 --2.1691837503602542e+00 , 5.8832005298427550e+00 , 2.4921332000000000e+00 , 4.4462800000000002e-01 , -8.3154600000000001e-01 , -3.3292300000000002e-01 --2.1320678258648869e+00 , 5.8624339772647698e+00 , 2.5972241600000001e+00 , -3.9165499999999998e-01 , 8.6188500000000001e-01 , 3.2212000000000002e-01 --2.1019401328690375e+00 , 5.8457794440288051e+00 , 2.7002091200000002e+00 , -3.4755399999999997e-01 , 9.0106399999999998e-01 , 2.5940500000000000e-01 --2.0952542735687043e+00 , 5.8465617125096632e+00 , 2.8003611199999998e+00 , 5.4577399999999998e-02 , -9.9829000000000001e-01 , -2.0926400000000001e-02 --2.1039276693311670e+00 , 5.8594580427732570e+00 , 2.8994065600000001e+00 , 2.9740299999999999e-03 , 9.9927200000000005e-01 , 3.8040699999999997e-02 --2.1600974044624062e+00 , 5.9083134954466940e+00 , 2.9981472800000000e+00 , -6.7983500000000002e-02 , -9.9000200000000005e-01 , 1.2359400000000000e-01 --1.0864596838197333e+01 , 1.2537879148940892e+01 , 3.1354304000000002e+00 , -3.5783999999999999e-01 , 6.1378500000000003e-01 , 7.0371700000000004e-01 --1.0497253968881186e+01 , 1.2276276270343235e+01 , 3.4178008000000002e+00 , 2.5015100000000001e-01 , 7.3649200000000004e-01 , 6.2849400000000000e-01 --9.8048300335056346e+00 , 1.1765196093284493e+01 , 3.6690231999999998e+00 , 7.5039400000000001e-01 , 6.5916799999999998e-01 , -4.9066300000000000e-02 --9.6131662849833486e+00 , 1.1635537257633443e+01 , 3.9256744000000001e+00 , 7.5039400000000001e-01 , 6.5916699999999995e-01 , -4.9066899999999997e-02 --9.1311735521197797e+00 , 1.1282676713122626e+01 , 4.1477456000000004e+00 , -8.2846200000000003e-01 , -4.9866400000000000e-01 , 2.5491999999999998e-01 --9.5015541203158058e+00 , 1.1582926458425819e+01 , 4.4470056000000007e+00 , -8.1121900000000002e-01 , -5.1254200000000005e-01 , 2.8146900000000002e-01 --8.6199210796642518e+00 , 1.0921421854080497e+01 , 4.5930631999999996e+00 , 7.9348099999999999e-01 , 5.8906999999999998e-01 , -1.5291900000000000e-01 --8.5899293997978869e+00 , 1.0913918717867318e+01 , 4.8363192000000002e+00 , -7.2260199999999997e-01 , -6.6966199999999998e-01 , 1.7146000000000000e-01 --8.6549987200961969e+00 , 1.0978723214946427e+01 , 5.0967351999999995e+00 , -6.6801400000000000e-01 , -7.1738000000000002e-01 , 1.9779800000000000e-01 --8.6496966694266941e+00 , 1.0990833978772795e+01 , 5.3477808000000007e+00 , 7.5485700000000000e-01 , 6.2142299999999995e-01 , -2.0982100000000001e-01 --8.4958563177448081e+00 , 1.0888101529204054e+01 , 5.5662016000000003e+00 , -7.1314200000000005e-01 , -6.5638900000000000e-01 , 2.4613299999999999e-01 --8.7429121848219502e+00 , 1.1094607475631271e+01 , 5.8797928000000006e+00 , 2.4455099999999999e-01 , 9.5835499999999996e-01 , 1.4748000000000000e-01 --5.1637933466024917e+00 , 8.3282602530305212e+00 , 5.1611735999999997e+00 , -8.1110800000000005e-01 , 5.6838699999999998e-01 , 1.3798299999999999e-01 --8.1795148919685232e+00 , 1.0689485776928292e+01 , 6.2344848000000006e+00 , 1.2832900000000000e-01 , 9.7620200000000001e-01 , 1.7481800000000000e-01 --8.3652913250155407e+00 , 1.0849307490993954e+01 , 6.5454863999999997e+00 , 1.6802900000000001e-01 , -9.7624000000000000e-01 , -1.3682700000000000e-01 --8.1580957085692738e+00 , 1.0703908608143738e+01 , 6.7322911999999997e+00 , 1.6802900000000001e-01 , -9.7624000000000000e-01 , -1.3682700000000000e-01 --5.0560899000380664e+00 , 8.2884929257612114e+00 , 5.8458367999999998e+00 , -8.1110800000000005e-01 , 5.6838699999999998e-01 , 1.3798299999999999e-01 --4.3949169640730235e+00 , 7.7805539484230222e+00 , 5.7689184000000004e+00 , 2.1723999999999999e-01 , 9.4489900000000004e-01 , 2.4489300000000000e-01 --4.8793266083690296e+00 , 8.1725586028244415e+00 , 6.1408639999999997e+00 , -8.5113200000000000e-01 , 6.0024399999999999e-02 , 5.2150900000000000e-01 --4.5380275101264012e+00 , 7.9148447471927961e+00 , 6.1730727999999999e+00 , 7.2028499999999995e-01 , 3.7605200000000000e-01 , 5.8290200000000003e-01 --4.2901156062194463e+00 , 7.7297141529485485e+00 , 6.2346615999999999e+00 , -3.0120000000000002e-01 , -9.4400600000000001e-01 , -1.3465299999999999e-01 --3.9289068648358407e+00 , 7.4551845371497558e+00 , 6.2298256000000007e+00 , 1.8076200000000001e-01 , 9.0085599999999999e-01 , 3.9469500000000002e-01 --1.1040770763871443e+01 , 1.3106493217293560e+01 , 1.0094215999999999e+01 , 7.6424099999999995e-02 , 9.2268799999999995e-01 , -3.7789699999999998e-01 --4.8546283006640030e+00 , 8.2114796283200260e+00 , 7.0718616000000001e+00 , -3.7782900000000003e-01 , 8.1895799999999996e-01 , -4.3191700000000000e-01 --4.8443923735779100e+00 , 8.2157405274045132e+00 , 7.2638664000000004e+00 , -4.2594199999999999e-01 , -5.9900100000000001e-01 , -6.7806500000000003e-01 --5.5600059167711349e+00 , 8.7993399982953271e+00 , 7.8943976000000005e+00 , -2.8803800000000002e-01 , 3.5052800000000001e-01 , -8.9115900000000003e-01 --7.1164766925062350e-01 , 4.9360588732004649e+00 , 5.0694248000000002e+00 , 5.5256799999999995e-01 , -1.5001800000000001e-01 , -8.1985500000000000e-01 --6.1675389554825966e-01 , 4.8653090700241695e+00 , 5.0969327999999994e+00 , 6.0501000000000005e-01 , -1.1743800000000000e-01 , -7.8751000000000004e-01 --5.5746137915905924e-01 , 4.8226682980677849e+00 , 5.1456464000000004e+00 , -6.8051600000000001e-01 , 9.8599499999999993e-03 , 7.3266699999999996e-01 --5.1934860378357639e-01 , 4.7974029120406918e+00 , 5.2075263999999999e+00 , 7.8520800000000002e-01 , -2.7170500000000000e-02 , -6.1863599999999996e-01 --4.5961229370160339e-01 , 4.7550855550472511e+00 , 5.2527144000000003e+00 , 7.8109099999999998e-01 , -4.3061299999999997e-02 , -6.2293100000000001e-01 --4.4071783725703062e-01 , 4.7451100582764552e+00 , 5.3284056000000000e+00 , -7.0881600000000000e-01 , -1.0984900000000000e-01 , 6.9678799999999996e-01 --3.3956054666417508e+00 , 7.1477003570724262e+00 , 7.8110000000000008e+00 , -7.2026299999999999e-01 , 5.6736299999999995e-01 , 3.9915000000000000e-01 --3.3586914845388351e+00 , 7.1292910731660459e+00 , 7.9698912000000002e+00 , -7.2026299999999999e-01 , 5.6736299999999995e-01 , 3.9915000000000000e-01 --4.8604991491132701e+00 , 8.3660773320812574e+00 , 9.4769968000000002e+00 , 9.9592099999999996e-03 , 8.2974899999999996e-01 , 5.5804799999999999e-01 --1.0922764489473380e-01 , 4.4985130711099304e+00 , 5.4084751999999998e+00 , -8.5390400000000000e-01 , 4.2144799999999999e-01 , 3.0533600000000000e-01 --6.8791880316069420e-02 , 4.4709489705459928e+00 , 5.4594560000000003e+00 , -6.6385899999999998e-01 , 5.4073599999999999e-01 , 5.1661999999999997e-01 --1.6171220521919105e-01 , 4.5530074582574933e+00 , 5.6413936000000007e+00 , -9.5903000000000005e-01 , -1.9651700000000000e-01 , 2.0406600000000000e-01 --1.0277356442017549e-02 , 4.4341353912281249e+00 , 5.5843807999999999e+00 , 7.6545399999999997e-01 , -6.0769499999999999e-01 , -2.1163100000000001e-01 --8.5638439952034240e-02 , 4.5020214568029999e+00 , 5.7576344000000006e+00 , -7.6462399999999997e-01 , -2.1964400000000001e-01 , 6.0589300000000001e-01 -2.8407878635370309e-03 , 4.4351710075560407e+00 , 5.7609208000000001e+00 , -9.7196899999999997e-01 , 1.0638000000000000e-01 , 2.0966599999999999e-01 --3.4393543489723530e+00 , 7.3032151376703576e+00 , 9.7698712000000008e+00 , -9.3408899999999995e-01 , -3.5547299999999998e-01 , 3.3419400000000002e-02 --3.3474370459364087e+00 , 7.2413380649403196e+00 , 9.9092623999999994e+00 , -5.0326499999999996e-01 , -3.3486300000000002e-01 , 7.9661199999999999e-01 --1.0991350679523930e+00 , 5.3767119345054049e+00 , 7.4163408000000004e+00 , 7.3109599999999997e-02 , -7.7744300000000000e-01 , 6.2468999999999997e-01 --6.4372704920931501e-02 , 4.5174106657491064e+00 , 6.2654871999999999e+00 , -7.0093000000000005e-01 , -4.1332600000000003e-01 , 5.8125599999999999e-01 --2.3422212141003484e-02 , 4.4903435321446565e+00 , 6.3295720000000006e+00 , -6.4895899999999995e-01 , -3.0309900000000001e-01 , 6.9784199999999996e-01 -1.0122109746743457e-01 , 4.3922934616038614e+00 , 6.2805984000000006e+00 , -3.4003000000000000e-01 , -2.6447999999999999e-01 , 9.0245799999999998e-01 -1.4255271960664118e-01 , 4.3645501685422605e+00 , 6.3414488000000002e+00 , 3.6934800000000001e-01 , 6.8874500000000005e-01 , -6.2386900000000001e-01 -2.5282478028288624e-01 , 4.2782944738666373e+00 , 6.3005247999999998e+00 , -9.6309100000000003e-01 , -2.6915000000000000e-01 , -3.7221699999999999e-03 -2.4281900899837994e-01 , 4.2945180248725716e+00 , 6.4368895999999998e+00 , -9.1347900000000004e-01 , -4.0630699999999997e-01 , 2.1689500000000000e-02 -3.5157111549047637e-01 , 4.2084317388097388e+00 , 6.3911711999999996e+00 , 9.8743700000000001e-01 , -1.1245800000000000e-01 , -1.1099800000000000e-01 --1.3310578425077826e+00 , 5.6681215836458039e+00 , 9.2717320000000001e+00 , -1.8558100000000000e-01 , 7.2726199999999996e-01 , 6.6079500000000002e-01 -9.0461591425357035e-02 , 4.4512347799193730e+00 , 7.0926407999999999e+00 , -4.2202699999999999e-01 , 9.0085800000000005e-01 , -1.0172900000000000e-01 -1.6757023820977768e-01 , 4.3936777955060515e+00 , 7.1132951999999996e+00 , -2.1427800000000000e-01 , 3.0081900000000000e-01 , 9.2929700000000004e-01 -4.0913688460472852e-01 , 4.1921076976322418e+00 , 6.8283975999999997e+00 , -5.7359000000000000e-02 , -3.8238600000000000e-01 , 9.2222099999999996e-01 -5.0368522272917549e-01 , 4.1192929046880522e+00 , 6.7981336000000008e+00 , -4.1050799999999998e-01 , -7.3526499999999995e-01 , -5.3932199999999997e-01 -5.5625095984231443e-01 , 4.0814007848824936e+00 , 6.8426248000000003e+00 , 7.5094000000000005e-01 , 5.6839600000000001e-01 , 3.3617700000000000e-01 -5.8927737172338901e-01 , 4.0614500332752996e+00 , 6.9298495999999998e+00 , 7.0694699999999999e-01 , -7.9186800000000002e-02 , -7.0281899999999997e-01 -6.6904881661488269e-01 , 4.0007294028892151e+00 , 6.9195120000000001e+00 , -5.6499000000000001e-02 , 3.2776499999999997e-01 , 9.4306900000000005e-01 -6.3668157622269450e-01 , 4.0393308845303224e+00 , 7.1569127999999997e+00 , 3.9091100000000001e-01 , -3.1205300000000002e-01 , 8.6591700000000005e-01 -7.2920974480329037e-01 , 3.9668812241972442e+00 , 7.1174656000000001e+00 , -1.6896700000000001e-01 , -5.0002700000000000e-01 , 8.4936699999999998e-01 -8.7651090162343137e-01 , 3.8438604208404188e+00 , 6.9388456000000005e+00 , 2.1994700000000000e-01 , 9.3069800000000003e-01 , -2.9227500000000001e-01 -8.8802358914966661e-01 , 3.8442204146760077e+00 , 7.0854023999999995e+00 , -8.6799499999999996e-01 , -3.3416299999999999e-01 , 3.6731399999999997e-01 -9.4146959646742867e-01 , 3.8054774166481096e+00 , 7.1311416000000003e+00 , -8.3606400000000003e-01 , -2.5156499999999998e-01 , 4.8755799999999999e-01 -9.8239291700943610e-01 , 3.7798373306966444e+00 , 7.2128752000000000e+00 , -9.4464000000000004e-01 , -1.7776500000000001e-01 , -2.7578000000000003e-01 -1.1019018442767392e+00 , 3.6796959284544104e+00 , 7.0680656000000006e+00 , 5.2588699999999999e-01 , 1.2612300000000001e-01 , 8.4115200000000001e-01 -1.0823042134180656e+00 , 3.7114098471767498e+00 , 7.3372488000000002e+00 , -3.3302999999999999e-02 , 6.4440600000000003e-01 , 7.6395800000000003e-01 -1.1425545777298534e+00 , 3.6674988502965062e+00 , 7.3693431999999994e+00 , 5.2008100000000002e-02 , 5.8977999999999997e-01 , 8.0588800000000005e-01 -1.3397377082556401e+00 , 3.4903899034770944e+00 , 6.9275927999999993e+00 , -5.0937399999999999e-01 , 4.8255300000000001e-01 , 7.1251699999999996e-01 -1.4031047272431461e+00 , 3.4425158938902944e+00 , 6.9248576000000002e+00 , -2.6604899999999998e-01 , -2.6223299999999999e-01 , 9.2760600000000004e-01 -1.4417138867389738e+00 , 3.4173511299058630e+00 , 7.0084735999999994e+00 , -6.6639400000000004e-01 , -6.8035500000000004e-01 , -3.0501699999999998e-01 -1.4955719219022701e+00 , 3.3793814031163438e+00 , 7.0423359999999997e+00 , -6.2331199999999998e-01 , -1.0421800000000001e-01 , -7.7499700000000005e-01 -1.5374707742718017e+00 , 3.3527293535217133e+00 , 7.1245064000000005e+00 , 3.0783500000000003e-01 , -8.9646999999999999e-01 , 3.1871500000000003e-01 -1.6114478558247018e+00 , 3.2923303724197357e+00 , 7.0671295999999995e+00 , -7.9380900000000004e-02 , 5.2188299999999999e-01 , 8.4931599999999996e-01 -1.6679478551186393e+00 , 3.2515217336449620e+00 , 7.0874616000000001e+00 , -8.2016100000000003e-01 , 1.4457700000000001e-01 , 5.5356399999999994e-01 -1.6916852737666843e+00 , 3.2451490003392838e+00 , 7.2875264000000000e+00 , -8.6358500000000005e-01 , 3.0531300000000000e-01 , 4.0125499999999997e-01 -1.5428504683651842e+00 , 3.4372264500432821e+00 , 8.5569400000000009e+00 , 6.2514400000000003e-01 , 7.6361800000000002e-01 , 1.6150100000000001e-01 -1.6463830741384284e+00 , 3.3495833771769865e+00 , 8.4075440000000015e+00 , -1.9979500000000001e-02 , 8.9658899999999997e-01 , 4.4241200000000003e-01 -1.7251000059977399e+00 , 3.2889142745163893e+00 , 8.3972896000000006e+00 , -2.2245799999999999e-01 , 9.7419599999999995e-01 , 3.8136799999999998e-02 -4.9121676115434543e-01 , 3.8492276796294433e+00 , 6.1684159999999988e-01 , -2.1095900000000001e-02 , 1.0761500000000000e-01 , 9.9396899999999999e-01 -4.1782899401974039e-01 , 3.9081119459840226e+00 , 6.0886479999999987e-01 , -7.9678499999999999e-02 , 9.2892500000000003e-02 , 9.9248300000000000e-01 -3.1864720703712823e-01 , 3.9861952338782682e+00 , 5.7473200000000002e-01 , -5.5888599999999997e-02 , 1.1399200000000000e-01 , 9.9190900000000004e-01 -2.4890982703640585e-01 , 4.0421478830387407e+00 , 5.7932879999999987e-01 , -2.8163299999999999e-02 , 1.0295400000000000e-01 , 9.9428700000000003e-01 -1.6072133676048872e-01 , 4.1132700427256790e+00 , 5.6568399999999985e-01 , -1.4273800000000000e-02 , 1.1970300000000000e-01 , 9.9270700000000001e-01 -6.4695301277220896e-02 , 4.1903906929963188e+00 , 5.4848239999999993e-01 , -6.1985600000000002e-02 , 1.5145500000000001e-01 , 9.8651900000000003e-01 --3.8215254376849472e-02 , 4.2725251424270567e+00 , 5.2836879999999997e-01 , 6.0127100000000003e-02 , -1.3517899999999999e-01 , -9.8899499999999996e-01 --1.5659304132646801e-01 , 4.3651600371764472e+00 , 4.9912400000000012e-01 , -3.7257899999999997e-02 , 1.1925500000000000e-01 , 9.9216400000000005e-01 --2.5498174294189369e-01 , 4.4457174036628881e+00 , 4.9322719999999998e-01 , -4.6113599999999998e-02 , 1.3210700000000000e-01 , 9.9016199999999999e-01 --3.8191828682219908e-01 , 4.5456053133082674e+00 , 4.6650959999999997e-01 , -7.6524099999999998e-02 , 1.1545800000000001e-01 , 9.9036000000000002e-01 --5.1039877226573171e-01 , 4.6486077727524675e+00 , 4.4440959999999996e-01 , -6.4106700000000003e-02 , 1.2448200000000000e-01 , 9.9014899999999995e-01 --6.4603016901063404e-01 , 4.7571006074006004e+00 , 4.2162319999999998e-01 , -5.8343899999999997e-02 , 1.3520399999999999e-01 , 9.8909800000000003e-01 --7.9743899743270763e-01 , 4.8777288504749938e+00 , 3.9254479999999980e-01 , -3.8367399999999999e-03 , 1.2253500000000001e-01 , 9.9245700000000003e-01 --9.4301977135449544e-01 , 4.9941053984025441e+00 , 3.7518720000000005e-01 , 1.3148999999999999e-02 , 1.1764400000000000e-01 , 9.9296899999999999e-01 --1.0761010558870883e+00 , 5.1015871069336010e+00 , 3.7428239999999979e-01 , 1.2447500000000000e-02 , 1.4802499999999999e-01 , 9.8890500000000003e-01 --1.2458930874956113e+00 , 5.2371545609311214e+00 , 3.5214079999999992e-01 , 4.6929300000000000e-02 , 1.4236799999999999e-01 , 9.8870100000000005e-01 --1.4098898469549099e+00 , 5.3685273436141774e+00 , 3.4202160000000004e-01 , 5.5039199999999998e-03 , 1.3867499999999999e-01 , 9.9032299999999995e-01 --1.6901538044094178e+00 , 5.5911270649586964e+00 , 2.5925840000000000e-01 , -2.8195499999999998e-02 , 1.7712000000000000e-01 , 9.8378500000000002e-01 --1.9231383583427060e+00 , 5.7772673932885530e+00 , 2.2167279999999989e-01 , -4.4487800000000000e-01 , -1.0311500000000000e-01 , -8.8963499999999995e-01 --2.0179925270169692e+00 , 5.8570874662867309e+00 , 2.8134799999999993e-01 , 6.2345200000000001e-01 , -1.9006499999999999e-02 , 7.8163000000000005e-01 --2.0447642774987456e+00 , 5.8844077268210224e+00 , 3.8490079999999982e-01 , -8.2449300000000003e-01 , 3.6566599999999999e-01 , -4.3185499999999999e-01 --2.0860286169012499e+00 , 5.9223411102724732e+00 , 4.8006079999999995e-01 , -9.2049199999999998e-01 , 3.0769200000000002e-01 , -2.4087200000000000e-01 --2.1175572279216039e+00 , 5.9545440571551289e+00 , 5.8044160000000011e-01 , -9.0268400000000004e-01 , 3.4025300000000003e-01 , -2.6341799999999999e-01 --2.1559695249051742e+00 , 5.9906573738054476e+00 , 6.7771279999999989e-01 , -9.3717300000000003e-01 , 1.3064999999999999e-01 , -3.2347599999999999e-01 --2.2002587792208743e+00 , 6.0317871137589067e+00 , 7.7229039999999993e-01 , -9.5485699999999996e-01 , 1.1780400000000001e-01 , -2.7270800000000001e-01 --2.2582892580567870e+00 , 6.0840112429774456e+00 , 8.6102319999999999e-01 , -9.7072499999999995e-01 , 7.0110900000000004e-02 , -2.2973299999999999e-01 --8.6059461812594886e+00 , 1.1057110986554461e+01 , -1.8556856000000002e+00 , -2.2405600000000001e-01 , -1.3420600000000000e-02 , 9.7448400000000002e-01 --1.0591014201443530e+01 , 1.2628355124110193e+01 , -2.4229744000000002e+00 , 1.9166100000000000e-01 , -1.9336900000000001e-01 , -9.6222399999999997e-01 --1.4473205260347637e+01 , 1.5717255173101904e+01 , -3.2459160000000002e+00 , 5.1543800000000001e-04 , -9.2775099999999999e-01 , 3.7320100000000000e-01 --1.4641081612861623e+01 , 1.5872216193938117e+01 , -2.9027056000000009e+00 , -1.4237800000000000e-02 , -9.2559499999999995e-01 , 3.7824799999999997e-01 --1.4906754778143966e+01 , 1.6104448263870022e+01 , -2.5868783999999998e+00 , 4.1294299999999999e-02 , -8.2687900000000003e-01 , 5.6086199999999997e-01 --1.4963304112490228e+01 , 1.6171404308563503e+01 , -2.1981576000000000e+00 , 1.0970500000000000e-01 , -6.6568799999999995e-01 , 7.3812199999999994e-01 --1.5060773267673085e+01 , 1.6271662668952743e+01 , -1.8212616000000001e+00 , 1.0970500000000000e-01 , -6.6568799999999995e-01 , 7.3812199999999994e-01 --2.5249955814491090e+00 , 6.3519114439935516e+00 , 1.8017749599999999e+00 , 9.9592400000000003e-01 , 7.8982100000000000e-02 , -4.3567000000000002e-02 --2.4658317360880817e+00 , 6.3124704924206441e+00 , 1.9295693279999999e+00 , 9.9681100000000000e-01 , 5.9630700000000002e-02 , -5.3028300000000000e-02 --2.4456290296133369e+00 , 6.3021659457166255e+00 , 2.0461112080000001e+00 , 9.9359399999999998e-01 , -4.2491700000000000e-02 , -1.0471500000000000e-01 --2.4403766330207191e+00 , 6.3043660922830718e+00 , 2.1583067200000001e+00 , 9.8934000000000000e-01 , -6.6631999999999997e-02 , -1.2948399999999999e-01 --2.4492518164703334e+00 , 6.3172109066334494e+00 , 2.2676013600000000e+00 , -9.8436699999999999e-01 , 7.9120599999999999e-02 , 1.5735600000000000e-01 --2.4641925248270722e+00 , 6.3354265461346815e+00 , 2.3759256799999999e+00 , -9.7076899999999999e-01 , 9.6454499999999999e-03 , 2.3982200000000001e-01 --2.0740624465805908e+00 , 6.0297253568423352e+00 , 2.5334815200000000e+00 , -7.3902599999999996e-01 , 3.5559499999999999e-01 , 5.7218199999999997e-01 --1.9890865051883417e+00 , 5.9664942580669624e+00 , 2.6435759200000000e+00 , -3.7138300000000002e-01 , 8.7040899999999999e-01 , 3.2320700000000002e-01 --1.9353198479288909e+00 , 5.9287606846350078e+00 , 2.7470777599999998e+00 , -3.2404800000000000e-01 , 9.1176500000000005e-01 , 2.5234299999999998e-01 --1.8874097626167514e+00 , 5.8960476668282764e+00 , 2.8478880800000002e+00 , 2.6473600000000003e-01 , -9.2165900000000001e-01 , -2.8365200000000002e-01 --1.8793610988916116e+00 , 5.8951324459808232e+00 , 2.9452341600000000e+00 , 1.7604100000000000e-01 , -9.6399000000000001e-01 , -1.9933000000000001e-01 --1.8857051743858175e+00 , 5.9064317056611646e+00 , 3.0421008000000000e+00 , 1.4012300000000000e-02 , 9.9982000000000004e-01 , -1.2812499999999999e-02 --1.9076269545002487e+00 , 5.9291428307194831e+00 , 3.1395904000000003e+00 , 9.9646600000000002e-02 , 9.9500800000000000e-01 , 5.4909199999999998e-03 --1.9348587627992098e+00 , 5.9576856618917517e+00 , 3.2385672000000003e+00 , 5.0696199999999997e-02 , 9.9444500000000002e-01 , 9.2246099999999998e-02 --3.1558465619825711e+00 , 6.9534253321260620e+00 , 3.4089296000000000e+00 , -9.4985900000000001e-01 , -2.7149899999999999e-01 , -1.5509999999999999e-01 --3.2440134791669086e+00 , 7.0319268740663965e+00 , 3.5425696000000002e+00 , -9.5589400000000002e-01 , -2.8108800000000000e-01 , -8.5189699999999993e-02 --3.3139211572963774e+00 , 7.0953155149742653e+00 , 3.6789136000000005e+00 , 1.6643400000000000e-01 , -8.1386599999999998e-01 , 5.5670699999999995e-01 --3.3810944316042493e+00 , 7.1581972945791659e+00 , 3.8185647999999999e+00 , 1.6643500000000000e-01 , -8.1386599999999998e-01 , 5.5670699999999995e-01 --3.4550384491129194e+00 , 7.2254792456385513e+00 , 3.9628231999999999e+00 , 1.6643400000000000e-01 , -8.1386599999999998e-01 , 5.5670699999999995e-01 --3.5421330674332152e+00 , 7.3041875417957041e+00 , 4.1135400000000004e+00 , 1.5797200000000000e-01 , -8.2998499999999997e-01 , 5.3494799999999998e-01 --3.6509206523202913e+00 , 7.4015466860304233e+00 , 4.2731383999999997e+00 , 1.8206200000000000e-01 , -8.4075400000000000e-01 , 5.0988900000000004e-01 --8.5220527292134651e+00 , 1.1404029311965562e+01 , 5.4809216000000003e+00 , 7.5485700000000000e-01 , 6.2142299999999995e-01 , -2.0982100000000001e-01 --9.4762530175968980e+00 , 1.2201719678047047e+01 , 5.9691808000000002e+00 , -8.3684000000000003e-01 , -5.0486500000000001e-01 , 2.1168400000000001e-01 --7.9489194812135828e+00 , 1.0960981858883450e+01 , 5.8446928000000007e+00 , 1.1934699999999999e-01 , 9.5845300000000000e-01 , 2.5908500000000001e-01 --8.1772108224819657e+00 , 1.1163545150492869e+01 , 6.1584295999999998e+00 , 1.1854500000000000e-01 , 9.2562100000000003e-01 , 3.5940600000000000e-01 --7.8934277841264660e+00 , 1.0943791698484215e+01 , 6.3246112000000005e+00 , 1.6802900000000001e-01 , -9.7624000000000000e-01 , -1.3682700000000000e-01 --7.8879562971899890e+00 , 1.0953496158225176e+01 , 6.5737432000000000e+00 , 1.6802900000000001e-01 , -9.7624000000000000e-01 , -1.3682700000000000e-01 --4.2144094096594040e+00 , 7.9247985520398450e+00 , 5.4957208000000008e+00 , -4.0200799999999998e-01 , 8.7480599999999997e-01 , -2.7037699999999998e-01 --5.0889357577006828e+00 , 8.6596580523590738e+00 , 5.9998400000000007e+00 , -8.1110800000000005e-01 , 5.6838699999999998e-01 , 1.3798299999999999e-01 --4.9822726670714168e+00 , 8.5823591046375611e+00 , 6.1448992000000002e+00 , -8.6428600000000000e-01 , 1.1654100000000001e-01 , 4.8931300000000000e-01 --4.0333893788821440e+00 , 7.8025749456713562e+00 , 5.9184808000000002e+00 , 1.2047300000000000e-01 , 8.7934400000000001e-01 , 4.6069599999999999e-01 --3.7866417123956237e+00 , 7.6071167895062644e+00 , 5.9707304000000008e+00 , 2.0769099999999999e-01 , 8.9757299999999995e-01 , 3.8887899999999997e-01 --3.8696626899793856e+00 , 7.6856215356949926e+00 , 6.1740295999999999e+00 , -5.7650399999999997e-02 , -4.5036700000000002e-01 , 8.9098100000000002e-01 --3.6588434137526775e+00 , 7.5185775009581413e+00 , 6.2331744000000002e+00 , 2.2477800000000001e-01 , 8.5478200000000004e-01 , 4.6778500000000001e-01 --4.4654994786863300e+00 , 8.2032923913240445e+00 , 6.8349703999999996e+00 , 3.1312899999999999e-01 , -8.3410099999999998e-01 , 4.5412100000000000e-01 --5.2116918012082083e+00 , 8.8412638156913488e+00 , 7.4494856000000000e+00 , -2.8803800000000002e-01 , 3.5052800000000001e-01 , -8.9115900000000003e-01 --4.5743236800557430e+00 , 8.3170601406388194e+00 , 7.2815152000000003e+00 , -4.4701900000000000e-01 , 8.1660999999999995e-01 , -3.6513200000000001e-01 --6.8222004123532631e-01 , 5.0472374090553371e+00 , 5.0425512000000001e+00 , -6.1939000000000000e-01 , 1.2323199999999999e-01 , 7.7535100000000001e-01 --5.8864689240602974e-01 , 4.9737368053510806e+00 , 5.0718584000000000e+00 , 5.9877300000000000e-01 , -8.5142999999999996e-02 , -7.9638100000000001e-01 --4.9670636982855410e-01 , 4.9005950009805233e+00 , 5.0973800000000002e+00 , 7.5762099999999999e-01 , -1.5966600000000000e-01 , -6.3286399999999998e-01 --5.7138619476979580e-01 , 4.9684706031682424e+00 , 5.2391839999999998e+00 , -8.4362300000000001e-01 , 1.2530300000000000e-01 , 5.2210999999999996e-01 --4.2258958491152132e-01 , 4.8468565416445664e+00 , 5.2206928000000001e+00 , -8.2068399999999997e-01 , -5.3949299999999999e-02 , 5.6882900000000003e-01 --3.9111642333259189e-01 , 4.8257632317424530e+00 , 5.2860568000000008e+00 , -8.2068399999999997e-01 , -5.3949299999999999e-02 , 5.6882900000000003e-01 --3.5168918285130601e-01 , 4.7977824627431769e+00 , 5.3453368000000001e+00 , -7.0881600000000000e-01 , -1.0984900000000000e-01 , 6.9678799999999996e-01 --6.3332157395243218e+00 , 9.9176621069459898e+00 , 1.0465735199999999e+01 , -7.5031599999999998e-01 , -5.8134900000000000e-01 , -3.1473600000000002e-01 --3.3707854891536071e+00 , 7.3952049387021965e+00 , 8.1698832000000010e+00 , -7.5281299999999995e-01 , 4.3494500000000003e-01 , 4.9406000000000000e-01 --5.5825588496861034e-02 , 4.5592654242192419e+00 , 5.3577544000000001e+00 , -8.5390400000000000e-01 , 4.2144799999999999e-01 , 3.0533600000000000e-01 --3.5170807092673062e-02 , 4.5468877667467957e+00 , 5.4272055999999997e+00 , -9.4218299999999999e-01 , 3.3506200000000003e-01 , -4.8584800000000001e-03 -1.7036528464254852e-02 , 4.5056440344369486e+00 , 5.4655088000000003e+00 , -8.8659800000000000e-01 , 3.5341699999999998e-01 , 2.9839599999999999e-01 --3.7452028668499473e+00 , 7.7660943847393087e+00 , 9.3827208000000013e+00 , -8.3251699999999995e-01 , -4.2819299999999999e-01 , -3.5152000000000000e-01 --1.5315469225237699e-01 , 4.6637012803173654e+00 , 5.8289576000000007e+00 , 8.0208299999999999e-01 , 5.9476000000000001e-02 , -5.9424399999999999e-01 --4.0325188324184413e-02 , 4.5720533861931791e+00 , 5.8092288000000005e+00 , -8.4337600000000001e-01 , -2.8966300000000000e-01 , 4.5256200000000002e-01 -1.6212964258651041e-02 , 4.5281857510405974e+00 , 5.8460136000000000e+00 , 7.8355300000000006e-01 , 9.5868499999999995e-02 , -6.1388399999999999e-01 -9.0928123793121207e-02 , 4.4694538336826684e+00 , 5.8603240000000003e+00 , -4.3514500000000000e-01 , -6.0695299999999996e-01 , 6.6502399999999995e-01 --5.9464959440651617e+00 , 9.7678214324946744e+00 , 1.3335687999999999e+01 , 3.9071599999999998e-02 , -6.6247400000000001e-01 , 7.4806499999999998e-01 --6.8340995199127219e-01 , 5.1618871724152022e+00 , 7.0501568000000008e+00 , -4.0450900000000001e-01 , 1.3610300000000000e-01 , 9.0434999999999999e-01 --5.4977617378417643e-01 , 5.0513658372722681e+00 , 7.0202152000000009e+00 , 3.1443800000000000e-01 , -1.6784299999999999e-01 , -9.3432199999999999e-01 --4.9395442663114730e-01 , 5.0108229478934465e+00 , 7.0891568000000005e+00 , -3.9007900000000001e-01 , 4.7635300000000003e-01 , 7.8798900000000005e-01 --4.5812331723804078e-01 , 4.9876524225550085e+00 , 7.1873224000000002e+00 , -4.4471200000000000e-01 , 7.6297000000000004e-02 , 8.9241800000000004e-01 -2.8626832405108260e-01 , 4.3323375436512519e+00 , 6.2491592000000002e+00 , -8.0679999999999996e-01 , -5.9060900000000005e-01 , -1.5983799999999999e-02 -3.3703129705141777e-01 , 4.2951305263431250e+00 , 6.2913727999999995e+00 , -9.4029200000000002e-01 , 3.0342000000000002e-01 , 1.5423200000000001e-01 -2.4593019368017077e-01 , 4.3827149891738202e+00 , 6.5538480000000003e+00 , -8.1667900000000004e-01 , -2.6830100000000001e-01 , 5.1093100000000002e-01 --1.7597223116291305e-01 , 4.7703483767263446e+00 , 7.3758848000000006e+00 , -1.2137900000000000e-01 , 6.4605999999999997e-01 , 7.5357399999999997e-01 -9.5817825765312614e-02 , 4.5341672268873463e+00 , 7.0784967999999999e+00 , -1.4281400000000000e-01 , 9.6749799999999997e-02 , 9.8501000000000005e-01 --9.1794805783423250e-02 , 4.7129933678904958e+00 , 7.5623879999999994e+00 , 3.3632099999999998e-01 , 5.6028599999999995e-01 , 7.5694700000000004e-01 -3.5943419955388944e-01 , 4.3116628416106471e+00 , 6.9105160000000003e+00 , -6.8158399999999997e-01 , 6.6372900000000001e-01 , -3.0807000000000001e-01 -4.8025857527742311e-01 , 4.2099947464178173e+00 , 6.8322248000000005e+00 , -3.9926200000000001e-01 , -3.4218999999999999e-02 , -9.1619799999999996e-01 -5.8405979551431453e-01 , 4.1218437136276540e+00 , 6.7752224000000005e+00 , 6.0884700000000003e-01 , 4.6350799999999998e-01 , 6.4378999999999997e-01 -6.7384390900202473e-01 , 4.0473415809070374e+00 , 6.7407984000000001e+00 , -7.7109000000000005e-01 , 1.0754000000000000e-02 , -6.3663499999999995e-01 -6.9671295753594231e-01 , 4.0352536047432732e+00 , 6.8438104000000006e+00 , 9.2739300000000002e-01 , -1.9423199999999999e-01 , -3.1971200000000000e-01 -5.9083285878863867e-01 , 4.1439622109198400e+00 , 7.2395719999999999e+00 , -8.1421500000000002e-01 , -5.6314600000000004e-01 , -1.4113600000000001e-01 -5.8718782480536635e-01 , 4.1573684874268491e+00 , 7.4265536000000001e+00 , 1.5740399999999999e-01 , 9.5805899999999999e-01 , 2.3947199999999999e-01 -8.7474427557559276e-01 , 3.8960611863210652e+00 , 6.9182328000000002e+00 , 7.3021699999999995e-02 , -9.0529700000000002e-01 , 4.1845599999999999e-01 -8.6000878557082738e-01 , 3.9200592601188902e+00 , 7.1290823999999997e+00 , -1.8384800000000001e-01 , -1.7967500000000000e-01 , 9.6639399999999998e-01 -9.4379889702988407e-01 , 3.8497009026478377e+00 , 7.0928800000000001e+00 , 2.4350700000000000e-01 , 2.4336800000000000e-01 , -9.3886999999999998e-01 -9.8574217740843006e-01 , 3.8200866323400238e+00 , 7.1656279999999999e+00 , -8.9596600000000004e-01 , -1.7601300000000000e-01 , 4.0775600000000001e-01 -1.0297830503751149e+00 , 3.7881810149594628e+00 , 7.2380224000000002e+00 , -7.9360500000000000e-01 , -4.6606599999999998e-01 , -3.9111899999999999e-01 -1.1675540812103522e+00 , 3.6651702683155269e+00 , 7.0257792000000006e+00 , -1.4411099999999999e-01 , -6.1971300000000000e-02 , 9.8761900000000002e-01 -1.1254871292969457e+00 , 3.7195586007206449e+00 , 7.3711215999999995e+00 , 1.6878899999999999e-01 , 5.0551999999999997e-01 , 8.4614400000000001e-01 -1.2888849149285273e+00 , 3.5687408148506705e+00 , 7.0473800000000004e+00 , -7.1014400000000005e-02 , -2.6217099999999999e-01 , 9.6240499999999995e-01 -1.3357722478235647e+00 , 3.5336345009237498e+00 , 7.1045280000000002e+00 , -2.2392999999999999e-01 , -1.7822900000000000e-01 , 9.5816999999999997e-01 -1.3936299010824547e+00 , 3.4878589793826498e+00 , 7.1215424000000001e+00 , -5.9513499999999997e-01 , 4.3317400000000000e-01 , 6.7688599999999999e-01 -1.4712915194527501e+00 , 3.4219885378131494e+00 , 7.0588928000000006e+00 , -9.2792799999999998e-01 , -1.5402099999999999e-01 , -3.3945100000000000e-01 -1.5471216960587029e+00 , 3.3568504431132551e+00 , 6.9941632000000000e+00 , -3.3231800000000000e-01 , -5.8724799999999999e-01 , -7.3804099999999995e-01 -1.6024602820005862e+00 , 3.3123045712808077e+00 , 7.0062480000000003e+00 , -3.1847999999999999e-01 , -5.6910799999999995e-01 , -7.5808100000000000e-01 -1.6589723258298101e+00 , 3.2674978295109645e+00 , 7.0172512000000005e+00 , -7.8254199999999996e-01 , -4.3600600000000000e-01 , -4.4443899999999997e-01 -1.6751593625017072e+00 , 3.2665026601225873e+00 , 7.2371176000000004e+00 , -8.0779800000000002e-01 , 4.9265999999999999e-01 , 3.2364999999999999e-01 -1.6950980165710532e+00 , 3.2652917210232220e+00 , 7.4777943999999996e+00 , -2.1396299999999999e-01 , 9.6995399999999998e-01 , 1.1579600000000000e-01 -1.6115455226166016e+00 , 3.3848296020086792e+00 , 8.4064207999999994e+00 , -5.5074100000000004e-01 , -6.9324600000000003e-01 , 4.6486000000000000e-01 -1.6702494496717577e+00 , 3.3444040523647161e+00 , 8.5292344000000000e+00 , 7.3174399999999995e-01 , 5.2660099999999999e-01 , 4.3271500000000002e-01 -1.7847309850451349e+00 , 3.2362929991214093e+00 , 8.2437128000000008e+00 , 6.8853799999999998e-01 , -2.0071100000000000e-01 , -6.9687200000000005e-01 -2.6214772492912464e-01 , 4.1522624066389540e+00 , 5.6476879999999996e-01 , -4.1496500000000004e-03 , 1.3324300000000000e-01 , 9.9107500000000004e-01 -1.6948678612004442e-01 , 4.2310520675067345e+00 , 5.4602799999999996e-01 , -2.9318500000000001e-02 , 1.5722600000000000e-01 , 9.8712699999999998e-01 -6.8951525543264225e-02 , 4.3158645985523236e+00 , 5.2392799999999995e-01 , -4.6581499999999998e-02 , 1.4164099999999999e-01 , 9.8882199999999998e-01 --2.6598099663145192e-02 , 4.3972309278461701e+00 , 5.1210319999999987e-01 , -2.1067499999999999e-02 , 1.3048000000000001e-01 , 9.9122699999999997e-01 --1.2260047930128426e-01 , 4.4793650127160625e+00 , 5.0402239999999998e-01 , -2.7382400000000001e-02 , 1.2683100000000000e-01 , 9.9154600000000004e-01 --2.3950545814816104e-01 , 4.5774026034861910e+00 , 4.8078880000000002e-01 , -3.5866599999999998e-02 , 1.1946200000000000e-01 , 9.9219100000000005e-01 --3.5694598151200641e-01 , 4.6774539388057459e+00 , 4.6221439999999991e-01 , -5.1656899999999999e-02 , 1.2635299999999999e-01 , 9.9063999999999997e-01 --4.8898846774975935e-01 , 4.7893908317709917e+00 , 4.3624560000000012e-01 , -5.3665299999999999e-02 , 1.3676500000000000e-01 , 9.8914899999999994e-01 --6.2922910505653062e-01 , 4.9079534774760827e+00 , 4.0976720000000011e-01 , -3.8597199999999998e-02 , 1.4208399999999999e-01 , 9.8910200000000004e-01 --7.7117799342769899e-01 , 5.0277191260494085e+00 , 3.8892559999999987e-01 , -2.1250700000000001e-02 , 1.4223400000000000e-01 , 9.8960499999999996e-01 --9.3450842156140901e-01 , 5.1663791479466337e+00 , 3.5717440000000011e-01 , 2.5287000000000000e-02 , 1.6677300000000000e-01 , 9.8567099999999996e-01 --1.0986380230868180e+00 , 5.3064688979753578e+00 , 3.3230799999999983e-01 , 5.7198800000000001e-02 , 1.5199399999999999e-01 , 9.8672499999999996e-01 --1.2656513444798878e+00 , 5.4480115016528901e+00 , 3.1406639999999997e-01 , 8.5221400000000003e-02 , 1.5704299999999999e-01 , 9.8390800000000000e-01 --1.4334678334739461e+00 , 5.5909511892236532e+00 , 3.0259519999999984e-01 , 7.3546000000000002e-03 , 1.8126100000000001e-01 , 9.8340799999999995e-01 --1.7365149282177872e+00 , 5.8466883423463809e+00 , 2.0550080000000004e-01 , 1.4873300000000000e-01 , 9.6500799999999998e-02 , 9.8415799999999998e-01 --1.9581408230667123e+00 , 6.0343777666594551e+00 , 1.7802399999999996e-01 , 5.2967799999999998e-01 , 1.6262599999999999e-01 , 8.3246299999999995e-01 --2.0590526884656608e+00 , 6.1228279895237554e+00 , 2.3712719999999976e-01 , -7.7261000000000002e-01 , 2.9204299999999999e-02 , -6.3420799999999999e-01 --2.5366091807871110e+00 , 6.5242123241677881e+00 , 7.2048000000000112e-02 , -9.0203400000000000e-03 , 2.3920600000000000e-01 , 9.7092699999999998e-01 --3.0487246627145801e+00 , 6.9544793789269876e+00 , -8.8840000000000252e-02 , -4.4588500000000003e-02 , 3.0497500000000000e-01 , 9.5131600000000005e-01 --3.9422297875880519e+00 , 7.7027141941521826e+00 , -4.3412000000000006e-01 , -5.6311300000000002e-02 , 2.7810600000000002e-01 , 9.5889899999999995e-01 --4.7563032432889019e+00 , 8.3863818005037452e+00 , -6.9289280000000009e-01 , -7.6086899999999999e-02 , 2.6007999999999998e-01 , 9.6258500000000002e-01 --5.9449613026740282e+00 , 9.3837618978343826e+00 , -1.0978064000000001e+00 , -7.7575599999999995e-02 , 2.3069100000000001e-01 , 9.6992999999999996e-01 --7.2115035485134893e+00 , 1.0448283148924734e+01 , -1.4812023999999999e+00 , -1.0915500000000000e-01 , 2.1076000000000000e-01 , 9.7142399999999995e-01 --9.3272796085119847e+00 , 1.2225232822980443e+01 , -2.1829423999999999e+00 , 2.3123099999999999e-01 , -2.9495799999999999e-02 , -9.7245199999999998e-01 --1.0284919364463505e+01 , 1.3039628873808388e+01 , -2.2926728000000010e+00 , 1.9166100000000000e-01 , -1.9336900000000001e-01 , -9.6222399999999997e-01 --1.0110847125791949e+01 , 1.2909905865486682e+01 , -1.9087255999999999e+00 , 1.9166200000000000e-01 , -1.9336900000000001e-01 , -9.6222399999999997e-01 --1.3993207898769860e+01 , 1.6197100895056760e+01 , -2.6486440000000000e+00 , -6.8583100000000003e-03 , -9.3953399999999998e-01 , 3.4238800000000003e-01 --1.4112120434902842e+01 , 1.6315721128265189e+01 , -2.2909775999999997e+00 , -5.0985700000000002e-02 , -7.7428600000000003e-01 , 6.3077799999999995e-01 --1.4085805333823270e+01 , 1.6314157972747640e+01 , -1.8873120000000001e+00 , -2.3639500000000001e-02 , -7.9877399999999998e-01 , 6.0116700000000001e-01 --2.2142339854144662e+01 , 2.3149013715992393e+01 , -3.1432888000000005e+00 , -3.8414500000000001e-01 , -8.6044600000000004e-01 , 3.3476099999999998e-01 --2.9258090182978027e+01 , 2.9188340816711804e+01 , -4.2000328000000007e+00 , -9.0122200000000000e-02 , -9.6511299999999994e-02 , 9.9124299999999999e-01 --2.4012696607320418e+01 , 2.4789458877422010e+01 , -2.3780984000000007e+00 , -5.1179300000000005e-01 , -7.5536300000000001e-01 , 4.0926099999999999e-01 --2.5390621124783976e+00 , 6.6320056925888462e+00 , 2.1665528800000002e+00 , -9.6862400000000004e-01 , 1.6873199999999999e-01 , 1.8247400000000000e-01 --2.4290525757745485e+00 , 6.5447417445105902e+00 , 2.2997415200000000e+00 , -9.3260299999999996e-01 , 1.7421900000000001e-01 , 3.1606699999999999e-01 --2.3965262577012689e+00 , 6.5233737898954232e+00 , 2.4167071999999998e+00 , -8.7936199999999998e-01 , 1.7345300000000000e-01 , 4.4343700000000003e-01 --2.3862117667181160e+00 , 6.5201801017831515e+00 , 2.5295440800000000e+00 , -8.1057100000000004e-01 , 6.9506200000000004e-02 , 5.8150100000000005e-01 --2.1054121983765999e+00 , 6.2861436160422768e+00 , 2.6663602399999999e+00 , 6.2718799999999997e-01 , 1.0173800000000000e-01 , -7.7219499999999996e-01 --1.8230017647651633e+00 , 6.0514892432225915e+00 , 2.7899153600000002e+00 , -8.4851500000000002e-01 , 3.0382199999999998e-01 , 4.3325999999999998e-01 --1.7689294371920354e+00 , 6.0099444259753785e+00 , 2.8903908000000000e+00 , -7.2799199999999997e-01 , 5.6077500000000002e-01 , 3.9440900000000001e-01 --1.7207545904486481e+00 , 5.9734649293323177e+00 , 2.9883764800000003e+00 , 2.9507200000000000e-01 , -9.1518100000000002e-01 , -2.7454699999999999e-01 --1.6795122054492011e+00 , 5.9431780042979483e+00 , 3.0840544000000003e+00 , 2.6728400000000002e-01 , -8.9665600000000001e-01 , -3.5294199999999998e-01 --1.6453182523758616e+00 , 5.9181899975855625e+00 , 3.1781224000000003e+00 , -2.5683400000000001e-01 , 8.2693399999999995e-01 , 5.0021700000000002e-01 --1.6016309746718589e+00 , 5.8850029891621860e+00 , 3.2704119999999999e+00 , -3.9302500000000001e-01 , 7.2071900000000000e-01 , 5.7104699999999997e-01 --1.5722553145171374e+00 , 5.8649913310780999e+00 , 3.3618176000000002e+00 , -2.1998400000000001e-01 , 8.0656000000000005e-01 , 5.4869699999999999e-01 --1.5260911959651042e+00 , 5.8299506448257770e+00 , 3.4507167999999999e+00 , -3.9131899999999997e-02 , 8.0355699999999997e-01 , 5.9394100000000005e-01 --1.4713191469557931e+00 , 5.7875714079288993e+00 , 3.5366936000000000e+00 , 7.6601799999999998e-02 , 8.4438299999999999e-01 , 5.3023600000000004e-01 --1.4236447033991797e+00 , 5.7505766251025694e+00 , 3.6214744000000003e+00 , -1.1674500000000000e-01 , 7.9311500000000001e-01 , 5.9777899999999995e-01 --1.3820747655838739e+00 , 5.7190402693366984e+00 , 3.7056832000000002e+00 , -2.3323800000000000e-01 , 6.5356999999999998e-01 , 7.2003200000000001e-01 --3.3795107216178106e+00 , 7.4538476525797579e+00 , 4.1690448000000000e+00 , 1.8206200000000000e-01 , -8.4075400000000000e-01 , 5.0988900000000004e-01 --3.4302411499349379e+00 , 7.5051852054489885e+00 , 4.3181495999999999e+00 , 1.8206200000000000e-01 , -8.4075400000000000e-01 , 5.0988900000000004e-01 --3.4951542596092606e+00 , 7.5679627323356788e+00 , 4.4735984000000002e+00 , 2.7058399999999999e-01 , -8.4026999999999996e-01 , 4.6981899999999999e-01 --3.5414639155425771e+00 , 7.6150286079499478e+00 , 4.6288184000000001e+00 , 2.6758999999999999e-01 , -8.5027200000000003e-01 , 4.5324799999999998e-01 --3.5934782198266033e+00 , 7.6675172389666608e+00 , 4.7886559999999996e+00 , 4.9311100000000002e-01 , 8.1460800000000000e-01 , -3.0537700000000001e-01 --1.0989878743244796e+00 , 5.5010982217391513e+00 , 4.1706152000000003e+00 , 6.6910700000000004e-02 , 9.2901599999999995e-01 , 3.6393900000000001e-01 --3.7118807070007307e+00 , 7.7860816913578432e+00 , 5.1252208000000001e+00 , -7.8198799999999999e-02 , -9.6485799999999999e-01 , 2.5086799999999998e-01 --3.8020206532732237e+00 , 7.8719084699644766e+00 , 5.3106632000000005e+00 , -1.4240700000000001e-01 , -9.8978500000000003e-01 , 6.7793999999999997e-03 --7.7150505318199922e+00 , 1.1306891611684636e+01 , 6.9632440000000004e+00 , 1.6802900000000001e-01 , -9.7624000000000000e-01 , -1.3682700000000000e-01 --4.7630594432461058e+00 , 8.7313405593469113e+00 , 6.0193816000000000e+00 , -8.1476899999999997e-01 , -9.1316099999999997e-02 , 5.7254899999999997e-01 --3.1877275116939563e+00 , 7.3574164915102003e+00 , 5.5232391999999999e+00 , 8.0977699999999997e-01 , 5.7822399999999996e-01 , 9.9587999999999996e-02 --2.9596311354356866e+00 , 7.1639289776418220e+00 , 5.5654944000000004e+00 , -3.7825799999999998e-01 , 5.8356400000000003e-02 , 9.2385899999999999e-01 --3.0181635864766143e+00 , 7.2232884114162577e+00 , 5.7369383999999997e+00 , 8.0977699999999997e-01 , 5.7822399999999996e-01 , 9.9587999999999996e-02 --3.4443152425596351e+00 , 7.6072802178685555e+00 , 6.1025608000000000e+00 , -2.5502399999999997e-01 , -9.2530599999999996e-01 , -2.8066400000000002e-01 --3.5517851140039456e+00 , 7.7100742880239057e+00 , 6.3210544000000004e+00 , 2.7926200000000001e-01 , 6.5119400000000005e-01 , -7.0566200000000001e-01 --4.3074324103633099e+00 , 8.3869410155643749e+00 , 6.9158408000000007e+00 , 2.0119799999999999e-01 , -7.6915800000000001e-01 , 6.0655999999999999e-01 --3.2416504905103727e+00 , 7.4520385916621432e+00 , 6.4715216000000009e+00 , -1.8113099999999999e-01 , -6.4409099999999997e-01 , 7.4319500000000005e-01 --6.6976257226860314e-01 , 5.1766446553491328e+00 , 5.0287296000000001e+00 , -6.1939000000000000e-01 , 1.2323199999999999e-01 , 7.7535100000000001e-01 --6.3448887330213655e-01 , 5.1505703065146351e+00 , 5.0965375999999996e+00 , -6.1939000000000000e-01 , 1.2323199999999999e-01 , 7.7535100000000001e-01 --5.2958834493321394e-01 , 5.0608699900090564e+00 , 5.1164120000000004e+00 , 7.1470599999999995e-01 , -5.9297299999999997e-02 , -6.9690700000000005e-01 --5.1423475802571694e-01 , 5.0517153944268403e+00 , 5.1954832000000000e+00 , -7.9008699999999998e-01 , -1.1803300000000000e-01 , 6.0152399999999995e-01 --9.1769980091023529e-01 , 5.4177034589530395e+00 , 5.5872615999999997e+00 , -7.9959800000000003e-01 , -4.5304000000000000e-01 , 3.9420600000000000e-01 --4.5317778435481992e-01 , 5.0066520763839861e+00 , 5.3326799999999999e+00 , 7.5184499999999999e-01 , -4.8783600000000003e-02 , -6.5753300000000003e-01 --3.4256209392045553e+00 , 7.6780709032218430e+00 , 7.8282328000000003e+00 , 7.6200299999999999e-01 , -4.8689600000000000e-01 , -4.2694700000000002e-01 --3.1290840856034627e+00 , 7.4214703544173561e+00 , 7.7720832000000009e+00 , 7.4961500000000003e-01 , -6.1429800000000001e-01 , -2.4640500000000001e-01 --1.0473752845271664e+00 , 5.5558637242970050e+00 , 6.1399488000000000e+00 , 7.5605400000000000e-01 , 6.4716399999999996e-01 , -9.7778400000000001e-02 --9.7213242525067711e-01 , 5.4942144926361127e+00 , 6.1925520000000001e+00 , 4.3880099999999998e-02 , -4.6721400000000002e-01 , 8.8305500000000003e-01 --3.2246240338779986e-01 , 4.9124645335927726e+00 , 5.6994672000000000e+00 , -3.3480999999999997e-02 , 1.8759999999999999e-01 , 9.8167499999999996e-01 --3.2215473328312116e-01 , 4.9180661169320334e+00 , 5.8010751999999997e+00 , -5.2955700000000006e-01 , 1.0962100000000000e-01 , 8.4116100000000005e-01 --3.8627403417602872e+00 , 8.1375264045088773e+00 , 9.5094759999999994e+00 , 4.8360599999999998e-01 , 6.1750600000000000e-01 , 6.2033199999999999e-01 -1.5046483057904680e-02 , 4.6213094816360183e+00 , 5.6544352000000000e+00 , -9.8962799999999995e-01 , 1.3521100000000000e-01 , 4.8513399999999998e-02 --3.2518404344168861e-02 , 4.6702750486041236e+00 , 5.8030200000000001e+00 , -9.4595399999999996e-01 , -4.8222700000000000e-03 , 3.2426400000000000e-01 -2.2782311196703375e-02 , 4.6246072900426665e+00 , 5.8410944000000002e+00 , -5.6450299999999998e-01 , -8.2455399999999998e-02 , 8.2130199999999998e-01 -4.4532544636426197e-02 , 4.6105946749934485e+00 , 5.9185016000000008e+00 , -6.8481899999999996e-01 , 1.9507400000000000e-01 , 7.0211699999999999e-01 -5.5315777950136091e-02 , 4.6051933049503866e+00 , 6.0099280000000004e+00 , -6.8481899999999996e-01 , 1.9507400000000000e-01 , 7.0211699999999999e-01 -2.8071045546428319e-01 , 4.4035708899826709e+00 , 5.8320568000000002e+00 , -1.4015100000000000e-01 , 1.6900200000000001e-01 , 9.7560000000000002e-01 -3.2999895194670192e-01 , 4.3631680354386830e+00 , 5.8686647999999995e+00 , -2.9130000000000000e-01 , 5.2642800000000001e-01 , 7.9876000000000003e-01 -3.5740852183787775e-01 , 4.3431186229430327e+00 , 5.9331240000000003e+00 , -2.9130000000000000e-01 , 5.2642800000000001e-01 , 7.9876000000000003e-01 -3.8082556160091019e-01 , 4.3258041335351241e+00 , 6.0049880000000000e+00 , -1.9409199999999999e-01 , 9.6885299999999996e-01 , 1.5379399999999999e-01 -1.7178095715540542e-01 , 4.5264432051802626e+00 , 6.4186687999999998e+00 , 6.9362100000000004e-01 , 9.4489600000000007e-02 , -7.1411599999999997e-01 -1.9780031007708376e-01 , 4.5084359055065981e+00 , 6.5035015999999999e+00 , -7.1277999999999997e-01 , -2.3651800000000001e-01 , 6.6030599999999995e-01 --2.5359665116047525e-01 , 4.9366644333199350e+00 , 7.3415751999999994e+00 , -9.2525299999999999e-01 , -2.0091500000000001e-01 , -3.2177699999999998e-01 --1.7486373110365561e-01 , 4.8717751850804412e+00 , 7.3735656000000009e+00 , -3.0128400000000000e-01 , 4.5750099999999999e-01 , 8.3661300000000005e-01 -1.1245785684189058e-01 , 4.6090195537567924e+00 , 7.0477856000000010e+00 , -1.4281400000000000e-01 , 9.6749600000000005e-02 , 9.8501000000000005e-01 -1.6164538212808321e-01 , 4.5697953335486083e+00 , 7.1112880000000001e+00 , -1.4281400000000000e-01 , 9.6749699999999994e-02 , 9.8501000000000005e-01 -2.0380264000664661e-01 , 4.5382931412617147e+00 , 7.1905359999999998e+00 , 8.2289500000000004e-01 , -2.6890799999999998e-01 , -5.0053199999999998e-01 -4.1913143983392165e-01 , 4.3407318981634155e+00 , 6.9410504000000000e+00 , 6.1173999999999995e-01 , -7.3780299999999999e-01 , -2.8534500000000002e-01 -6.2313574119551984e-01 , 4.1531738218804062e+00 , 6.6913672000000002e+00 , 6.6080799999999995e-01 , -2.1259100000000000e-01 , 7.1981799999999996e-01 -7.2726105869468305e-01 , 4.0615760724179601e+00 , 6.6226127999999997e+00 , -1.8198800000000001e-01 , 2.3561499999999999e-01 , -9.5465500000000003e-01 -6.2002279058154097e-01 , 4.1709856242409895e+00 , 6.9951927999999999e+00 , -2.4706800000000001e-02 , -9.9224000000000001e-01 , 1.2186200000000000e-01 -6.4568199616337041e-01 , 4.1549957893127925e+00 , 7.1005136000000002e+00 , -9.1278899999999996e-01 , -3.9065000000000000e-01 , -1.1920000000000000e-01 -3.0864942021809050e-01 , 4.4919406164776952e+00 , 8.0527063999999999e+00 , -6.7315100000000005e-01 , 7.3350800000000005e-01 , -9.3985299999999994e-02 -2.4234119878735316e-01 , 4.5672540611874712e+00 , 8.4281775999999997e+00 , 8.1067599999999995e-01 , 5.2796500000000002e-01 , -2.5309700000000002e-01 -8.6146298681465971e-01 , 3.9701963694734275e+00 , 7.0989120000000003e+00 , -3.4452900000000002e-02 , -1.9262099999999999e-01 , 9.8066799999999998e-01 -9.0625868806332788e-01 , 3.9358757745557620e+00 , 7.1647336000000008e+00 , 1.4247699999999999e-01 , 1.0431699999999999e-01 , -9.8428599999999999e-01 -9.7431878458974186e-01 , 3.8766755656301108e+00 , 7.1647752000000002e+00 , 5.1251000000000002e-01 , -2.3147200000000001e-01 , -8.2689400000000002e-01 -1.0013443109259197e+00 , 3.8603790638112372e+00 , 7.2846456000000002e+00 , -7.0957300000000001e-01 , 6.7461700000000002e-01 , 2.0346600000000001e-01 -1.1259744723863283e+00 , 3.7438834993188062e+00 , 7.1124840000000003e+00 , -5.5758399999999997e-01 , -1.2224900000000000e-01 , -8.2106900000000005e-01 -1.1244574295059810e+00 , 3.7570313919186713e+00 , 7.3249872000000007e+00 , 1.4548400000000000e-01 , 5.2829999999999999e-01 , 8.3650100000000005e-01 -1.1814590485423520e+00 , 3.7090661540923242e+00 , 7.3573312000000000e+00 , 1.5493799999999999e-01 , 5.9742799999999996e-01 , 7.8681199999999996e-01 -1.3290600225857161e+00 , 3.5684273277324756e+00 , 7.0702496000000004e+00 , -2.2392999999999999e-01 , -1.7822900000000000e-01 , 9.5816999999999997e-01 -1.4160914821318857e+00 , 3.4885177379713896e+00 , 6.9715120000000006e+00 , 6.1762899999999998e-01 , 5.6240100000000004e-01 , -5.4976400000000003e-01 -1.4807808580122552e+00 , 3.4321572761077013e+00 , 6.9480184000000005e+00 , 1.7948200000000000e-01 , 2.8231800000000001e-01 , -9.4238100000000002e-01 -1.5326135831336773e+00 , 3.3890867050452522e+00 , 6.9718967999999997e+00 , 7.4297400000000000e-02 , 6.8669800000000003e-01 , 7.2313600000000000e-01 -1.5569138044683839e+00 , 3.3760685167122051e+00 , 7.1232688000000000e+00 , 4.7559099999999999e-01 , -7.5680800000000004e-01 , 4.4839099999999998e-01 -1.6254638822440650e+00 , 3.3147286003416521e+00 , 7.0759176000000004e+00 , -2.4591099999999999e-01 , 4.1260799999999997e-01 , 8.7708699999999995e-01 -1.6787149324087371e+00 , 3.2698656792975545e+00 , 7.0964888000000004e+00 , 7.0132499999999998e-01 , 3.1271899999999998e-02 , -7.1215499999999998e-01 -1.6957024542609878e+00 , 3.2677593934100244e+00 , 7.3268383999999998e+00 , 8.5522500000000001e-01 , -4.5959000000000000e-01 , -2.3951400000000000e-01 -1.7361067632041802e+00 , 3.2392338793142383e+00 , 7.4468440000000005e+00 , 5.0963199999999997e-01 , 8.5857399999999995e-01 , -5.5904200000000001e-02 -1.6482699457965182e+00 , 3.3639836881851384e+00 , 8.4372880000000006e+00 , 7.3986099999999999e-01 , 4.8247499999999999e-01 , -4.6885300000000002e-01 -1.7354187411555353e+00 , 3.2845647906262858e+00 , 8.3462671999999998e+00 , -1.6888800000000001e-01 , 9.0573300000000001e-01 , -3.8874799999999998e-01 -1.8236800045950785e-01 , 4.3520347690022003e+00 , 5.2736000000000005e-01 , -6.7118100000000003e-03 , 1.6323900000000000e-01 , 9.8656400000000000e-01 -9.0203995424896322e-02 , 4.4350212115921810e+00 , 5.1378799999999991e-01 , 1.4299800000000000e-02 , 1.4917400000000000e-01 , 9.8870800000000003e-01 --8.8030850394300586e-03 , 4.5251203248327130e+00 , 4.9718960000000001e-01 , -1.2896200000000000e-02 , 1.4664700000000000e-01 , 9.8910500000000001e-01 --1.1578503859847089e-01 , 4.6214766020636819e+00 , 4.7825119999999988e-01 , -2.5030899999999999e-04 , 1.3609399999999999e-01 , 9.9069600000000002e-01 --2.1679541128674096e-01 , 4.7132919326638421e+00 , 4.6972320000000001e-01 , -6.6058100000000002e-03 , 1.1666600000000001e-01 , 9.9314899999999995e-01 --3.4532611447812034e-01 , 4.8277446583729731e+00 , 4.4119599999999992e-01 , 3.9892499999999997e-02 , -1.5164600000000000e-01 , -9.8763000000000001e-01 --4.8748690042442355e-01 , 4.9552562117880630e+00 , 4.0601279999999984e-01 , -4.0820299999999997e-02 , 1.5156400000000000e-01 , 9.8760400000000004e-01 --6.3789171285184310e-01 , 5.0905620976991823e+00 , 3.7092320000000001e-01 , -2.5281499999999998e-02 , 1.4172399999999999e-01 , 9.8958299999999999e-01 --7.7697993512990671e-01 , 5.2161603363715781e+00 , 3.5327439999999988e-01 , 7.5011399999999999e-03 , 1.6404099999999999e-01 , 9.8642500000000000e-01 --9.4305833532382755e-01 , 5.3652356325578605e+00 , 3.1990079999999987e-01 , 3.7918599999999997e-02 , 1.7764199999999999e-01 , 9.8336500000000004e-01 --1.1119688179519129e+00 , 5.5178647200444439e+00 , 2.9305840000000005e-01 , 8.0282000000000006e-02 , 1.6312800000000000e-01 , 9.8333300000000001e-01 --1.2619674363928239e+00 , 5.6530513265972315e+00 , 2.8903360000000000e-01 , -7.5627100000000003e-02 , -1.8629499999999999e-01 , -9.7957899999999998e-01 --1.4809485292788840e+00 , 5.8503603433433158e+00 , 2.4139119999999981e-01 , 3.2994600000000002e-03 , 2.0269100000000001e-01 , 9.7923700000000002e-01 --1.7573643615881380e+00 , 6.0974780974324592e+00 , 1.6513840000000002e-01 , 7.2791900000000007e-02 , 1.8134900000000001e-01 , 9.8072099999999995e-01 --2.0161938217160156e+00 , 6.3309701167913897e+00 , 1.1462560000000011e-01 , 4.9879300000000001e-02 , 2.4189800000000000e-01 , 9.6901899999999996e-01 --2.2908033431949484e+00 , 6.5783903590691644e+00 , 6.6640000000000033e-02 , 1.6128500000000000e-02 , 2.3240300000000000e-01 , 9.7248599999999996e-01 --2.6467654890394368e+00 , 6.8965038890534540e+00 , -1.6757600000000039e-02 , -2.0255100000000002e-02 , 2.8754600000000002e-01 , 9.5755299999999999e-01 --3.4914775986505378e+00 , 7.6481352854547771e+00 , -3.6639520000000037e-01 , -5.1223999999999999e-02 , 2.8821700000000000e-01 , 9.5619399999999999e-01 --4.2521299434447117e+00 , 8.3272876234093829e+00 , -6.2563600000000008e-01 , -6.6559900000000005e-02 , 2.6601900000000001e-01 , 9.6166700000000005e-01 --5.3458697836376992e+00 , 9.3032664594511782e+00 , -1.0216784000000003e+00 , -8.1470100000000004e-02 , 2.3977599999999999e-01 , 9.6740400000000004e-01 --6.3787871704204697e+00 , 1.0227120220484087e+01 , -1.3313696000000004e+00 , -8.4870200000000007e-02 , 2.2424500000000000e-01 , 9.7082999999999997e-01 --8.0281694110226027e+00 , 1.1701306532618849e+01 , -1.8819144000000003e+00 , -1.1190400000000000e-01 , 1.2045000000000000e-01 , 9.8639200000000005e-01 --9.7887361987049069e+00 , 1.3276143803236565e+01 , -2.3991167999999998e+00 , 2.2009000000000001e-01 , 2.4438499999999998e-02 , -9.7517299999999996e-01 --1.1585623444571034e+01 , 1.4888186953233177e+01 , -2.8448088000000009e+00 , 1.6806099999999999e-01 , 1.5879900000000000e-01 , 9.7290200000000004e-01 --1.3046029995255514e+01 , 1.6204462844130624e+01 , -3.0689392000000009e+00 , 4.5507900000000001e-01 , -8.6658299999999999e-01 , 2.0478299999999999e-01 --1.3144530849830588e+01 , 1.6309287254493764e+01 , -2.7170448000000000e+00 , 6.3957299999999995e-01 , -4.6736199999999999e-02 , 7.6730900000000002e-01 --1.3224490506190611e+01 , 1.6398026601949034e+01 , -2.3570592000000001e+00 , 6.7239700000000002e-01 , -1.8320000000000000e-01 , 7.1716100000000005e-01 --1.3284678935606845e+01 , 1.6468277344666866e+01 , -1.9896479999999999e+00 , 6.7239700000000002e-01 , -1.8320000000000000e-01 , 7.1716100000000005e-01 --1.4058519751771779e+01 , 1.7177312402714904e+01 , -1.8346672000000002e+00 , -6.9427700000000003e-01 , 2.0094699999999999e-01 , -6.9108499999999995e-01 --1.4679551666759394e+01 , 1.7752844736742119e+01 , -1.6032256000000005e+00 , 3.9876800000000001e-01 , -4.3322800000000000e-01 , 8.0826799999999999e-01 --1.5094791518055594e+01 , 1.8142369882538269e+01 , -1.2922967999999999e+00 , 3.4900100000000001e-01 , -3.1686900000000001e-01 , 8.8192499999999996e-01 --2.0877703226663822e+01 , 2.3354963512714502e+01 , -2.1725631999999999e+00 , 4.1230900000000001e-02 , -9.8706199999999999e-01 , 1.5494900000000000e-01 --2.0976755094388544e+01 , 2.3467740985412934e+01 , -1.6341239999999999e+00 , 3.0755299999999999e-02 , -9.8402400000000001e-01 , 1.7535800000000001e-01 --2.1083129237729860e+01 , 2.3588372300470009e+01 , -1.0947488000000001e+00 , 6.8407599999999999e-02 , -9.7061799999999998e-01 , 2.3069500000000001e-01 --2.1167566883727226e+01 , 2.3689256088991378e+01 , -5.4891520000000016e-01 , 7.9705700000000004e-02 , -9.7003399999999995e-01 , 2.2952500000000001e-01 --2.3592895973435555e+00 , 6.7460070143391349e+00 , 2.4545392800000001e+00 , -8.4751299999999996e-01 , 2.3976600000000001e-01 , 4.7353400000000001e-01 --2.2800230608180163e+00 , 6.6790611846195374e+00 , 2.5765936800000002e+00 , -7.9661400000000004e-01 , 1.0173699999999999e-01 , 5.9586600000000001e-01 --2.2217321462940935e+00 , 6.6309965081116813e+00 , 2.6930247999999999e+00 , 6.7882699999999996e-01 , 2.0526600000000000e-03 , -7.3429599999999995e-01 --1.8387026840112983e+00 , 6.2887636428789104e+00 , 2.8258598400000001e+00 , -5.6984699999999999e-01 , -2.4803100000000002e-02 , 8.2137700000000002e-01 --1.8537345796793936e+00 , 6.3075338200923383e+00 , 2.9263633599999999e+00 , -5.6984699999999999e-01 , -2.4803100000000002e-02 , 8.2137700000000002e-01 --1.8070922111375149e+00 , 6.2697674145317919e+00 , 3.0281762400000001e+00 , 7.5572300000000003e-01 , -3.3609200000000000e-01 , -5.6207200000000002e-01 --1.5971862828602523e+00 , 6.0829918078149063e+00 , 3.1262368000000000e+00 , -7.7915900000000005e-01 , 1.5825100000000000e-01 , 6.0652099999999998e-01 --1.5402719397936235e+00 , 6.0356455697128775e+00 , 3.2195872000000003e+00 , -4.5949499999999999e-01 , 6.9378600000000001e-01 , 5.5454999999999999e-01 --1.4664605985840904e+00 , 5.9731012981065188e+00 , 3.3096304000000001e+00 , -1.9439400000000001e-01 , 7.5271800000000000e-01 , 6.2898900000000002e-01 --1.3683579442042340e+00 , 5.8872544656490167e+00 , 3.3946192000000002e+00 , -2.4404400000000001e-01 , 7.9532599999999998e-01 , 5.5488700000000002e-01 --1.3082947220928296e+00 , 5.8368855611543182e+00 , 3.4789111999999998e+00 , -1.5530900000000000e-01 , 7.9971499999999995e-01 , 5.7994400000000002e-01 --1.2552819980685723e+00 , 5.7918257676740108e+00 , 3.5617056000000002e+00 , 2.4246599999999999e-01 , -7.7308100000000002e-01 , -5.8613599999999999e-01 --1.1999161321639535e+00 , 5.7462030503170656e+00 , 3.6422223999999996e+00 , -2.6612300000000000e-01 , 6.5196399999999999e-01 , 7.1001499999999995e-01 --1.1526861507407249e+00 , 5.7060089940275898e+00 , 3.7216263999999999e+00 , -3.0414200000000002e-01 , 5.8284599999999998e-01 , 7.5351699999999999e-01 --1.1041823534610495e+00 , 5.6653940154604143e+00 , 3.7991272000000000e+00 , -4.5485999999999999e-01 , 6.0103300000000004e-01 , 6.5716200000000002e-01 --1.0692726855218639e+00 , 5.6373464110897071e+00 , 3.8781984000000000e+00 , -2.8238400000000002e-01 , 7.4513799999999997e-01 , 6.0417699999999996e-01 --1.0192892794276283e+00 , 5.5948241670884924e+00 , 3.9518824000000001e+00 , -2.0979600000000001e-02 , 8.6337399999999997e-01 , 5.0412800000000002e-01 --9.8295414273014092e-01 , 5.5660786478095705e+00 , 4.0277399999999997e+00 , 4.1417900000000001e-02 , 8.8431599999999999e-01 , 4.6504800000000002e-01 --9.4646045855288374e-01 , 5.5359751580535530e+00 , 4.1021831999999998e+00 , -1.1722600000000000e-01 , -9.2056099999999996e-01 , -3.7259300000000001e-01 --9.3027601527412518e-01 , 5.5249727958382540e+00 , 4.1827936000000001e+00 , 1.5126800000000001e-01 , 8.9629499999999995e-01 , 4.1686200000000001e-01 --9.2156617448526257e-01 , 5.5200106617658342e+00 , 4.2654528000000003e+00 , 1.7622599999999999e-01 , 9.1107000000000005e-01 , 3.7268699999999999e-01 --3.6490585492983119e+00 , 8.0460861051305557e+00 , 5.3803847999999999e+00 , 4.0272799999999997e-01 , 9.1364299999999998e-01 , 5.5378499999999997e-02 --3.2413035872086429e+00 , 7.6759483994327260e+00 , 5.3746960000000001e+00 , -6.1043300000000000e-01 , -9.8501800000000000e-02 , 7.8591900000000003e-01 --3.2447807428182562e+00 , 7.6851971545958033e+00 , 5.5252464000000003e+00 , -8.4260299999999999e-01 , -4.7195999999999999e-01 , 2.5937300000000002e-01 --2.9772708984838996e+00 , 7.4439568107348979e+00 , 5.5549695999999997e+00 , 8.0977699999999997e-01 , 5.7822399999999996e-01 , 9.9587999999999996e-02 --2.9639352105712566e+00 , 7.4374280626361742e+00 , 5.6940799999999996e+00 , 8.0977699999999997e-01 , 5.7822399999999996e-01 , 9.9587999999999996e-02 --3.2755667845682019e+00 , 7.7345715121974026e+00 , 6.0009112000000000e+00 , -4.6538400000000002e-01 , -8.8472899999999999e-01 , -2.5919700000000000e-02 --3.7580595513174835e+00 , 8.1909310035103644e+00 , 6.4185960000000000e+00 , 7.4567000000000005e-01 , 5.7264500000000003e-02 , -6.6385000000000005e-01 --3.7106548080676021e+00 , 8.1549002560280677e+00 , 6.5660992000000000e+00 , 7.8057399999999999e-01 , -3.7250299999999997e-01 , 5.0194200000000000e-01 --3.5712137142442115e+00 , 8.0316444140924563e+00 , 6.6586696000000005e+00 , -6.1260199999999998e-01 , -1.5184900000000001e-01 , 7.7566800000000002e-01 --4.0177626497551833e+00 , 8.4575767244608748e+00 , 7.1122032000000006e+00 , 3.1055700000000003e-01 , -6.9877100000000003e-01 , 6.4441700000000002e-01 --4.2970569869891557e+00 , 8.7284219781696226e+00 , 7.4851472000000001e+00 , 2.1417600000000001e-01 , -5.3551099999999996e-01 , 8.1691899999999995e-01 --1.0448333938191956e+00 , 5.6856591877910301e+00 , 5.4671208000000000e+00 , -8.5118499999999997e-01 , -4.4148300000000001e-01 , 2.8386099999999997e-01 --9.6417759052119267e-01 , 5.6146866976493310e+00 , 5.5168327999999995e+00 , -8.5118499999999997e-01 , -4.4148300000000001e-01 , 2.8386000000000000e-01 --9.1025825826197870e-01 , 5.5684524076861379e+00 , 5.5834136000000001e+00 , -6.5825100000000003e-01 , 1.1894100000000001e-01 , 7.4334299999999998e-01 --4.0193635245784254e-01 , 5.0935058707164593e+00 , 5.2951256000000004e+00 , -4.5151200000000002e-01 , -5.4024099999999999e-02 , 8.9062799999999998e-01 --3.1221262518773045e+00 , 7.6655344961586609e+00 , 7.5883360000000000e+00 , -7.7101600000000003e-01 , 4.6923100000000001e-01 , 4.3053000000000002e-01 --5.5265890632019277e-01 , 5.2450890941905985e+00 , 5.6095072000000004e+00 , 6.0908099999999998e-01 , -6.9044700000000003e-01 , 3.9026200000000000e-01 --5.7437588792023675e-01 , 5.2706113417237477e+00 , 5.7315616000000000e+00 , -6.1731100000000005e-01 , -7.7411300000000005e-01 , -1.4027500000000001e-01 --5.6405077331378939e-01 , 5.2649048759415216e+00 , 5.8266384000000002e+00 , -6.1731100000000005e-01 , -7.7411300000000005e-01 , -1.4027500000000001e-01 --5.5760015249227957e-01 , 5.2628167938413384e+00 , 5.9283191999999998e+00 , -6.1731100000000005e-01 , -7.7411300000000005e-01 , -1.4027400000000001e-01 --5.1181906922442666e-01 , 5.2252684234998448e+00 , 5.9941719999999998e+00 , 7.0720799999999995e-01 , 6.7219600000000002e-01 , -2.1911200000000000e-01 --4.7874905244862642e-01 , 5.1979727249191479e+00 , 6.0712672000000003e+00 , 7.7204099999999998e-01 , 4.9816400000000000e-01 , -3.9469700000000002e-01 --7.3301831846674492e-02 , 4.8164479586793760e+00 , 5.7556168000000003e+00 , -8.9465300000000003e-01 , 1.1959800000000000e-01 , -4.3045499999999998e-01 --5.4971669344986207e-02 , 4.8030791129512771e+00 , 5.8354783999999995e+00 , -9.6578799999999998e-01 , -1.9951500000000000e-02 , 2.5856600000000002e-01 --7.0230969778629415e-02 , 4.8214530126450228e+00 , 5.9550576000000000e+00 , -9.4189900000000004e-01 , 3.1370900000000002e-01 , 1.2005500000000000e-01 --5.3820911669779647e-02 , 4.8107510613956403e+00 , 6.0424800000000003e+00 , 7.5307199999999996e-01 , 1.0837700000000000e-01 , -6.4895099999999994e-01 -1.0958867152801433e-01 , 4.6589275722319297e+00 , 5.9509287999999998e+00 , 4.2579099999999998e-01 , -8.1788400000000006e-01 , -3.8700000000000001e-01 -2.5871432594680033e-01 , 4.5198287506676600e+00 , 5.8668136000000004e+00 , -1.6887600000000000e-01 , -4.6196399999999999e-02 , 9.8455400000000004e-01 -3.5062861831363268e-01 , 4.4356138096513256e+00 , 5.8479064000000003e+00 , -2.9130000000000000e-01 , 5.2642800000000001e-01 , 7.9876000000000003e-01 -4.1486098868532895e-01 , 4.3773461375829026e+00 , 5.8622687999999998e+00 , -2.9129899999999997e-01 , 5.2642800000000001e-01 , 7.9876000000000003e-01 -4.2631955831027679e-01 , 4.3718588229837367e+00 , 5.9481415999999996e+00 , -2.9130000000000000e-01 , 5.2642800000000001e-01 , 7.9876100000000005e-01 -1.5649207229763773e-01 , 4.6384047493831080e+00 , 6.4493383999999994e+00 , 6.0275199999999995e-01 , -5.3713900000000003e-01 , -5.9006099999999995e-01 --3.3203854180829229e-01 , 5.1208331481395692e+00 , 7.3166359999999999e+00 , -3.4107799999999999e-01 , 6.2085199999999996e-01 , 7.0583899999999999e-01 --1.3792196146602897e-01 , 4.9366719972872097e+00 , 7.1660024000000009e+00 , -2.5280100000000000e-02 , 4.4373899999999999e-01 , 8.9580000000000004e-01 --1.8869223800994339e-01 , 4.9939120913819472e+00 , 7.4024047999999993e+00 , 3.8507400000000003e-01 , 9.7982799999999995e-02 , 9.1766899999999996e-01 -7.6540310331969508e-02 , 4.7405586634313970e+00 , 7.1132328000000005e+00 , -1.4944299999999999e-01 , -3.6962299999999998e-01 , 9.1708500000000004e-01 -2.3214362249443732e-01 , 4.5936894635651573e+00 , 6.9919376000000009e+00 , 4.2145100000000002e-01 , -6.4945400000000000e-02 , 9.0452299999999997e-01 -2.6677006583856633e-02 , 4.8035324370591814e+00 , 7.5153176000000004e+00 , 2.9072799999999999e-01 , 4.3295699999999998e-01 , 8.5324400000000000e-01 -5.3423981386088615e-01 , 4.3075803785649001e+00 , 6.7220160000000000e+00 , 7.0325400000000005e-01 , -5.7979700000000001e-01 , -4.1142299999999998e-01 -6.5605157155272931e-01 , 4.1925190733780813e+00 , 6.6249008000000007e+00 , 1.7050299999999999e-01 , 1.5277199999999999e-01 , 9.7344200000000003e-01 -6.9419386988063625e-01 , 4.1606168579336185e+00 , 6.6854912000000004e+00 , 4.4161499999999998e-01 , -2.5971400000000000e-01 , 8.5879300000000003e-01 -6.3243580728298165e-01 , 4.2285756767918548e+00 , 6.9622039999999998e+00 , 8.2795700000000005e-01 , -3.6196800000000001e-01 , -4.2832900000000002e-01 -7.2001208696326646e-01 , 4.1477896558086744e+00 , 6.9277488000000007e+00 , -8.7642200000000003e-01 , 4.1408800000000001e-01 , -2.4579699999999999e-01 -2.9582565890252144e-01 , 4.5838367324737552e+00 , 8.0686704000000002e+00 , -6.7315100000000005e-01 , 7.3350800000000005e-01 , -9.3985299999999994e-02 -2.4627229590295840e-01 , 4.6429258472783754e+00 , 8.3987976000000000e+00 , 8.1067599999999995e-01 , 5.2796500000000002e-01 , -2.5309700000000002e-01 -8.3787038639857836e-01 , 4.0498285859250167e+00 , 7.1412608000000004e+00 , 4.7323299999999999e-02 , 2.9753200000000000e-02 , 9.9843700000000002e-01 -9.0867922008895752e-01 , 3.9850096666468158e+00 , 7.1350831999999995e+00 , 1.2952400000000000e-01 , 7.8853400000000004e-02 , 9.8843599999999998e-01 -1.0501970985759113e+00 , 3.8490483546316998e+00 , 6.9331256000000003e+00 , -7.0123800000000000e-02 , 6.1438499999999996e-01 , 7.8588400000000003e-01 -1.0458138236411370e+00 , 3.8604585771154110e+00 , 7.1258792000000000e+00 , -4.2119699999999999e-01 , 9.0261899999999995e-01 , 8.8722999999999996e-02 -1.1396861654048631e+00 , 3.7719290357114490e+00 , 7.0384983999999999e+00 , 2.9387500000000000e-01 , 2.2386300000000001e-01 , 9.2925899999999995e-01 -1.1914949418630627e+00 , 3.7263068442576546e+00 , 7.0708111999999996e+00 , -2.4811199999999999e-02 , 1.0463400000000000e-01 , 9.9420100000000000e-01 -1.1782356907207370e+00 , 3.7496915754247881e+00 , 7.3210872000000000e+00 , 3.4690799999999999e-01 , 3.7638400000000000e-01 , 8.5906400000000005e-01 -1.3019254396237194e+00 , 3.6269886457685998e+00 , 7.1126816000000002e+00 , 3.7951400000000002e-01 , 3.6178599999999998e-02 , -9.2447900000000005e-01 -1.3714060135532504e+00 , 3.5639166644647169e+00 , 7.0832287999999997e+00 , -2.2392999999999999e-01 , -1.7822900000000000e-01 , 9.5816999999999997e-01 -1.4336417072879180e+00 , 3.5067829169824742e+00 , 7.0711544000000002e+00 , 9.8467499999999997e-01 , 1.0112300000000000e-01 , -1.4208699999999999e-01 -1.5234396597406157e+00 , 3.4191359113385675e+00 , 6.9399168000000007e+00 , -6.7286399999999996e-02 , 4.0153400000000000e-01 , 9.1336899999999999e-01 -1.5676421159346963e+00 , 3.3811826452549960e+00 , 6.9928424000000007e+00 , -9.8652599999999993e-02 , 6.3870600000000000e-01 , 7.6310100000000003e-01 -1.6097388281521292e+00 , 3.3451264474883837e+00 , 7.0547432000000008e+00 , -8.5309000000000001e-01 , 2.3783299999999999e-01 , 4.6440599999999999e-01 -1.6796911790283766e+00 , 3.2784466782345234e+00 , 6.9864360000000003e+00 , -9.5990500000000001e-01 , 1.8781300000000001e-02 , -2.7969600000000000e-01 -1.6881204036032273e+00 , 3.2816940376255737e+00 , 7.2362544000000000e+00 , 6.6619499999999998e-01 , -6.8022099999999996e-01 , -3.0575100000000000e-01 -1.7219497604708711e+00 , 3.2575341031423131e+00 , 7.3765087999999999e+00 , 7.3110399999999998e-01 , -6.4525299999999997e-01 , -2.2166400000000000e-01 -1.6131403586785991e+00 , 3.4044234188445346e+00 , 8.4565488000000002e+00 , 7.9414799999999997e-01 , 5.6758900000000001e-01 , -2.1719400000000000e-01 -1.6873622317477708e+00 , 3.3368051655081512e+00 , 8.4477296000000006e+00 , 8.2278499999999999e-01 , 5.6369800000000003e-01 , -7.2590699999999994e-02 -1.7880631770151920e+00 , 3.2362256611948643e+00 , 8.2335415999999988e+00 , 8.3124200000000004e-01 , 4.2047500000000002e-02 , -5.5431900000000001e-01 -9.4377500704131845e-01 , 3.7645067453366527e+00 , 6.5657999999999994e-01 , -1.0758300000000000e-01 , 7.4224700000000005e-02 , 9.9142100000000000e-01 -8.7286260839964624e-01 , 3.8311086300377553e+00 , 6.2944639999999996e-01 , -1.5154100000000001e-01 , 9.8062899999999995e-02 , 9.8357499999999998e-01 -8.0686811207120424e-01 , 3.8932530995618828e+00 , 6.1288959999999992e-01 , -1.7596899999999999e-01 , 8.9272599999999994e-02 , 9.8033899999999996e-01 -7.3535556823456605e-01 , 3.9620041949425051e+00 , 5.9100799999999998e-01 , -1.5044500000000000e-01 , 9.1781399999999999e-02 , 9.8434900000000003e-01 -6.7305773219797072e-01 , 4.0222451336088092e+00 , 5.8682720000000010e-01 , -1.1453099999999999e-01 , 8.5269300000000006e-02 , 9.8975400000000002e-01 -1.0363307381585662e-01 , 4.5649225355385115e+00 , 4.9207280000000009e-01 , 6.5589100000000003e-03 , 1.5570999999999999e-01 , 9.8778100000000002e-01 --5.3439515696598328e-03 , 4.6692362725907541e+00 , 4.6483519999999978e-01 , 3.3936600000000002e-03 , 1.3600899999999999e-01 , 9.9070199999999997e-01 --1.0398935998584058e-01 , 4.7637806482678133e+00 , 4.5452880000000007e-01 , 7.2921799999999997e-03 , 1.1955900000000000e-01 , 9.9280000000000002e-01 --2.0960414481910350e-01 , 4.8645950047707611e+00 , 4.4221519999999992e-01 , -1.8358500000000000e-02 , 1.5146899999999999e-01 , 9.8829199999999995e-01 --3.3517583486419600e-01 , 4.9847092490818312e+00 , 4.1606959999999993e-01 , -4.2804700000000001e-02 , 1.4569199999999999e-01 , 9.8840399999999995e-01 --4.6793811313963429e-01 , 5.1114518702757881e+00 , 3.8963280000000000e-01 , -9.8702600000000001e-02 , 1.0424700000000001e-01 , 9.8964200000000002e-01 --6.1441862853076934e-01 , 5.2514264568338760e+00 , 3.5745519999999997e-01 , 1.2846299999999999e-01 , -1.4605099999999999e-01 , -9.8090100000000002e-01 --7.8336483812523650e-01 , 5.4115082034689692e+00 , 3.1484639999999997e-01 , -1.4735600000000000e-02 , 1.7070099999999999e-01 , 9.8521300000000001e-01 --9.4002174324377563e-01 , 5.5619521435331709e+00 , 2.9032319999999978e-01 , 4.2250700000000002e-02 , 1.6517999999999999e-01 , 9.8535799999999996e-01 --1.1238704869142055e+00 , 5.7373390988827762e+00 , 2.5198879999999990e-01 , 7.9018900000000003e-02 , 1.8534700000000001e-01 , 9.7949100000000000e-01 --1.2974961533608917e+00 , 5.9031256981932883e+00 , 2.3149039999999999e-01 , 8.1906300000000001e-02 , 2.0145399999999999e-01 , 9.7606700000000002e-01 --1.5051289179677902e+00 , 6.1020347743846379e+00 , 1.9414400000000009e-01 , 1.1847300000000000e-02 , 1.8076800000000001e-01 , 9.8345400000000005e-01 --1.7890490857330317e+00 , 6.3720908871579613e+00 , 1.1419920000000006e-01 , 3.0266899999999999e-02 , 2.0799200000000001e-01 , 9.7766200000000003e-01 --2.0631806114824798e+00 , 6.6333287244827241e+00 , 5.5834399999999729e-02 , 4.8259000000000002e-03 , 1.7078499999999999e-01 , 9.8529699999999998e-01 --2.3321388955452687e+00 , 6.8903519139157412e+00 , 1.4546399999999959e-02 , 2.8850199999999999e-03 , 2.3783199999999999e-01 , 9.7130200000000000e-01 --3.0948955040758603e+00 , 7.6115556270151323e+00 , -3.1572639999999996e-01 , -5.3915800000000000e-02 , 3.0294599999999999e-01 , 9.5148100000000002e-01 --3.8102261055174731e+00 , 8.2893472823305849e+00 , -5.7735920000000007e-01 , -6.2319100000000002e-02 , 2.5607500000000000e-01 , 9.6464600000000000e-01 --4.7653743869864904e+00 , 9.1949450755595556e+00 , -9.3472400000000011e-01 , -7.9404799999999998e-02 , 2.5071300000000002e-01 , 9.6479899999999996e-01 --5.7648605604391436e+00 , 1.0143901780959931e+01 , -1.2655479999999999e+00 , -8.1640900000000002e-02 , 2.0759800000000000e-01 , 9.7480199999999995e-01 --7.0451622296091863e+00 , 1.1358853653712265e+01 , -1.6851568000000001e+00 , -1.0801400000000000e-01 , 2.0608099999999999e-01 , 9.7255499999999995e-01 --8.5433954924735644e+00 , 1.2781641688544847e+01 , -2.1424760000000003e+00 , -1.8301799999999999e-01 , -1.3687500000000000e-01 , 9.7353500000000004e-01 --8.4295610166647226e+00 , 1.2686292471478911e+01 , -1.8006487999999998e+00 , -1.8301799999999999e-01 , -1.3687500000000000e-01 , 9.7353500000000004e-01 --8.5138071283484287e+00 , 1.2776285216220788e+01 , -1.5511216000000001e+00 , -1.8301799999999999e-01 , -1.3687500000000000e-01 , 9.7353500000000004e-01 --1.2984396033753194e+01 , 1.7020142917260728e+01 , -3.0387896000000003e+00 , 3.0776900000000001e-01 , -9.2912999999999996e-02 , 9.4691300000000000e-01 --1.3402363272930915e+01 , 1.7430974933576589e+01 , -2.7967192000000001e+00 , -8.6099499999999995e-01 , 7.3617700000000001e-03 , -5.0856100000000004e-01 --1.3686834083754121e+01 , 1.7715107033047214e+01 , -2.4905432000000003e+00 , 7.6024000000000003e-01 , -1.3401099999999999e-01 , 6.3566999999999996e-01 --1.3776288191770487e+01 , 1.7815610625813822e+01 , -2.1110160000000002e+00 , -7.7264900000000003e-01 , 5.3403500000000000e-02 , -6.3258400000000004e-01 --1.3647003969682290e+01 , 1.7708643209022313e+01 , -1.6654384000000002e+00 , -7.6730100000000001e-01 , -5.4577800000000003e-02 , -6.3896100000000000e-01 --1.4111227139075442e+01 , 1.8165490839295877e+01 , -1.3889648000000001e+00 , 3.3638899999999999e-01 , -3.1451899999999999e-01 , 8.8764900000000002e-01 --1.4698930275703383e+01 , 1.8740457299616541e+01 , -1.1221216000000003e+00 , 6.1902800000000002e-01 , -2.6274900000000001e-01 , 7.4011300000000002e-01 --1.4852324773536665e+01 , 1.8903023008283764e+01 , -7.3270400000000047e-01 , 6.1902800000000002e-01 , -2.6274900000000001e-01 , 7.4011300000000002e-01 --2.0015898158672389e+01 , 2.3845777348232907e+01 , -1.3184215999999997e+00 , 7.2176599999999994e-02 , -9.7089599999999998e-01 , 2.2836699999999999e-01 --2.0109171847049048e+01 , 2.3956224312956312e+01 , -7.8479760000000010e-01 , 7.1968699999999997e-02 , -9.7046600000000005e-01 , 2.3025399999999999e-01 --2.0159240562601919e+01 , 2.4025236850794634e+01 , -2.4222959999999993e-01 , 7.1968699999999997e-02 , -9.7046600000000005e-01 , 2.3025399999999999e-01 --2.0262204269715607e+01 , 2.4144224960223291e+01 , 2.9488880000000006e-01 , 7.1968699999999997e-02 , -9.7046600000000005e-01 , 2.3025399999999999e-01 --2.2605327123110390e+00 , 6.9187789138092581e+00 , 2.6163955200000002e+00 , -9.0527199999999997e-01 , -3.9063199999999999e-02 , 4.2303200000000002e-01 --1.6258896192703407e+00 , 6.3155187937527320e+00 , 2.7774332799999999e+00 , -1.3908700000000000e-02 , -9.9656299999999998e-01 , 8.1660700000000003e-02 --1.6345130072986254e+00 , 6.3272261588753205e+00 , 2.8758744800000002e+00 , -1.3908700000000000e-02 , -9.9656299999999998e-01 , 8.1660700000000003e-02 --1.6420879236058075e+00 , 6.3388913831620286e+00 , 2.9743396000000000e+00 , -3.5781599999999999e-03 , -9.9715799999999999e-01 , 7.5259000000000006e-02 --1.6559590732309943e+00 , 6.3552333627261968e+00 , 3.0735608000000001e+00 , -1.1983600000000000e-01 , 8.9448799999999995e-01 , 4.3073299999999998e-01 --2.1478427792598991e+00 , 6.8329496769846809e+00 , 3.1841543999999997e+00 , -5.6772999999999996e-01 , 7.7744300000000000e-01 , -2.7067400000000003e-01 --2.1591005888264423e+00 , 6.8474974830516944e+00 , 3.2961312000000000e+00 , 5.9500399999999998e-01 , -7.4372400000000005e-01 , 3.0470500000000000e-01 --2.1912260441618496e+00 , 6.8825400587945351e+00 , 3.4104999999999999e+00 , 5.9500500000000001e-01 , -7.4372300000000002e-01 , 3.0470500000000000e-01 --2.2433910511506978e+00 , 6.9372902300418779e+00 , 3.5288104000000002e+00 , 5.7872500000000004e-01 , -7.6729700000000001e-01 , 2.7628300000000000e-01 --2.2874821418968541e+00 , 6.9845617660323045e+00 , 3.6486391999999999e+00 , 5.5645299999999998e-01 , -7.6151500000000005e-01 , 3.3234799999999998e-01 --1.2141891516136538e+00 , 5.9505209949393336e+00 , 3.6097847999999999e+00 , -2.7484999999999998e-01 , 7.6121499999999997e-01 , 5.8737499999999998e-01 --1.1379974824271217e+00 , 5.8801079703236416e+00 , 3.6876080000000000e+00 , -3.5476300000000000e-01 , 6.0811499999999996e-01 , 7.1016900000000005e-01 --1.0465607328936652e+00 , 5.7959978455383574e+00 , 3.7587336000000002e+00 , -4.8939100000000002e-01 , 4.8176099999999999e-01 , 7.2691300000000003e-01 --9.8430161805817784e-01 , 5.7380942044972150e+00 , 3.8324487999999999e+00 , -3.3194499999999999e-01 , 6.3263800000000003e-01 , 6.9970200000000005e-01 --9.2908847124189053e-01 , 5.6876759551781131e+00 , 3.9049576000000004e+00 , -4.2385000000000000e-01 , 6.3566199999999995e-01 , 6.4520100000000002e-01 --8.7259447587844852e-01 , 5.6357027761116427e+00 , 3.9752720000000004e+00 , -3.5034500000000002e-01 , 6.8964999999999999e-01 , 6.3375099999999995e-01 --8.2326861719949296e-01 , 5.5903519135577309e+00 , 4.0452848000000001e+00 , 2.6149099999999997e-01 , -7.3960000000000004e-01 , -6.2017299999999997e-01 --7.8013198239533255e-01 , 5.5516626301069811e+00 , 4.1154536000000004e+00 , -2.2252600000000000e-01 , 6.7224600000000001e-01 , 7.0609299999999997e-01 --7.2824402887620243e-01 , 5.5053985741508011e+00 , 4.1814727999999999e+00 , 5.8759400000000003e-02 , 8.4282299999999999e-01 , 5.3497399999999995e-01 --6.9869959536428183e-01 , 5.4793195018271978e+00 , 4.2533056000000000e+00 , 6.7339499999999997e-02 , 8.0328900000000003e-01 , 5.9177100000000005e-01 --6.6698768717836732e-01 , 5.4519182853898176e+00 , 4.3243792000000001e+00 , 9.5642699999999997e-02 , 9.1307000000000005e-01 , 3.9642899999999998e-01 --6.3511806572026996e-01 , 5.4242625278677830e+00 , 4.3941423999999998e+00 , -2.7302099999999999e-02 , 8.9971599999999996e-01 , 4.3562099999999998e-01 --6.2384859399813797e-01 , 5.4162007269930381e+00 , 4.4725064000000003e+00 , 2.4369600000000000e-01 , 9.0277200000000002e-01 , 3.5442299999999999e-01 --6.1153601483043651e-01 , 5.4070239339671984e+00 , 4.5507872000000003e+00 , 1.4308799999999999e-01 , 8.8201200000000002e-01 , 4.4897700000000001e-01 --2.7129295693897157e+00 , 7.4709277487816186e+00 , 5.7030656000000004e+00 , 3.2258799999999999e-01 , 1.7179600000000000e-01 , 9.3081800000000003e-01 --3.7441006752615626e+00 , 8.4893976660599613e+00 , 6.4009263999999995e+00 , -6.3804600000000000e-01 , 2.7249699999999999e-01 , -7.2016899999999995e-01 --3.6297542886575362e+00 , 8.3838802632297043e+00 , 6.5129552000000004e+00 , -6.3804600000000000e-01 , 2.7249800000000002e-01 , -7.2016899999999995e-01 --3.4396266585725019e+00 , 8.2026457685726193e+00 , 6.5763224000000005e+00 , -9.7436999999999996e-01 , -2.2484799999999999e-01 , 6.8171200000000003e-03 --3.9677366965475178e+00 , 8.7299813025602582e+00 , 7.0782992000000000e+00 , 3.2635999999999998e-01 , -7.6168800000000003e-01 , 5.5974999999999997e-01 --1.0535664830687681e+00 , 5.8624384055709458e+00 , 5.3676864000000002e+00 , -1.6011100000000000e-01 , 6.5075899999999998e-01 , 7.4221099999999995e-01 --1.0091057539792354e+00 , 5.8228184271092260e+00 , 5.4440640000000000e+00 , -1.6011100000000000e-01 , 6.5075899999999998e-01 , 7.4221099999999995e-01 --9.1736031224319170e-01 , 5.7360861617624810e+00 , 5.4863712000000007e+00 , -8.5118499999999997e-01 , -4.4148300000000001e-01 , 2.8386099999999997e-01 --9.1195609698174396e-01 , 5.7340300278057708e+00 , 5.5880311999999996e+00 , -8.5118499999999997e-01 , -4.4148300000000001e-01 , 2.8386000000000000e-01 --3.3472120627320807e+00 , 8.1526589052346257e+00 , 7.5917159999999999e+00 , -9.3865900000000002e-01 , -2.2986000000000001e-01 , 2.5706899999999999e-01 --3.9507541749628716e-01 , 5.2298964592536938e+00 , 5.3885592000000004e+00 , 1.4275299999999999e-01 , -8.5841199999999995e-01 , 4.9269600000000002e-01 --4.9120573904090836e-01 , 5.3290467165389259e+00 , 5.5649847999999995e+00 , -1.1035100000000000e-01 , -9.4898000000000005e-01 , 2.9539799999999999e-01 --3.8685355023475498e+00 , 8.6930003811068879e+00 , 8.6340040000000009e+00 , 8.1350400000000000e-01 , -5.4142199999999996e-01 , -2.1230499999999999e-01 --6.0973017396310514e-01 , 5.4544945510135552e+00 , 5.8777647999999996e+00 , -6.1731000000000003e-01 , -7.7411300000000005e-01 , -1.4027500000000001e-01 --8.2881379062924543e-01 , 5.6778552995975522e+00 , 6.1965351999999996e+00 , 4.3879700000000001e-02 , -4.6721400000000002e-01 , 8.8305500000000003e-01 --4.6244017649841718e-01 , 5.3161802794775621e+00 , 5.9552344000000002e+00 , 3.6130499999999999e-01 , 9.3128900000000003e-01 , 4.6465800000000002e-02 --2.1598046285612060e-01 , 5.0730922903457323e+00 , 5.8132120000000000e+00 , 1.0079600000000000e-01 , -9.4954099999999997e-01 , -2.9700599999999999e-01 --1.3235026058357402e-01 , 4.9940425141040947e+00 , 5.8287080000000007e+00 , 3.1633099999999997e-01 , 4.0493200000000001e-01 , 8.5788399999999998e-01 --8.4814885072251212e-02 , 4.9501432732455379e+00 , 5.8791896000000001e+00 , -9.5076799999999995e-01 , 2.9459999999999997e-01 , 9.6180799999999997e-02 --8.8398497673906284e-02 , 4.9571950860905627e+00 , 5.9872040000000002e+00 , 8.9008699999999996e-01 , -8.2529500000000006e-02 , -4.4825700000000002e-01 --1.0962883551687952e-02 , 4.8837340376368763e+00 , 6.0027416000000002e+00 , -6.7055799999999999e-01 , 3.5574200000000000e-01 , 6.5099899999999999e-01 -1.4997349397735538e-01 , 4.7261034428705386e+00 , 5.9134887999999997e+00 , -4.3871199999999999e-01 , 8.2100300000000004e-01 , 3.6535699999999999e-01 -1.8154174321083016e-01 , 4.6982592558863008e+00 , 5.9770432000000007e+00 , 5.5808199999999997e-01 , -8.1797500000000001e-01 , 1.3950399999999999e-01 --5.8454373835914053e-01 , 5.4767164824608292e+00 , 7.0949184000000001e+00 , -6.6305100000000006e-02 , 2.0034600000000000e-02 , 9.9759799999999998e-01 -4.3138751901748407e-01 , 4.4527060329117871e+00 , 5.8498304000000001e+00 , -2.9129899999999997e-01 , 5.2642800000000001e-01 , 7.9876000000000003e-01 -4.2571755341189910e-01 , 4.4620408596820855e+00 , 5.9581984000000006e+00 , -2.9130000000000000e-01 , 5.2642800000000001e-01 , 7.9876000000000003e-01 --3.2327370005014577e-01 , 5.2271015462274049e+00 , 7.1660544000000002e+00 , 4.9689699999999998e-01 , 4.7715200000000002e-01 , 7.2485800000000000e-01 --2.4451578710884903e-01 , 5.1533991878628918e+00 , 7.1965471999999995e+00 , 2.1451200000000000e-02 , 7.3324999999999996e-01 , 6.7962100000000003e-01 --1.8662524371083355e-01 , 5.1000855399280294e+00 , 7.2552136000000003e+00 , 9.8299300000000001e-01 , 1.4868999999999999e-01 , 1.0777299999999999e-01 --1.4165818364615346e-01 , 5.0602710771646127e+00 , 7.3359800000000002e+00 , -9.4825499999999996e-01 , 2.2983699999999999e-02 , 3.1667800000000002e-01 --7.7404444507585435e-02 , 4.9992805750949234e+00 , 7.3842672000000000e+00 , -1.0644500000000000e-01 , 1.8434200000000001e-01 , 9.7708099999999998e-01 -3.3762656272249281e-02 , 4.8920151006276642e+00 , 7.3499368000000000e+00 , 7.9927199999999998e-01 , 6.0091399999999995e-01 , 8.1830600000000007e-03 -5.5713787101104439e-01 , 4.3579683244525196e+00 , 6.5501040000000001e+00 , 8.4577000000000002e-01 , -4.9248100000000000e-01 , -2.0527000000000001e-01 -5.8058754121687883e-01 , 4.3386973176251633e+00 , 6.6386287999999993e+00 , 7.8034000000000003e-01 , -4.9246800000000002e-01 , -3.8541700000000001e-01 -2.4831010478880411e-01 , 4.6882575126286010e+00 , 7.4331264000000008e+00 , -4.4422899999999998e-01 , -8.1006699999999998e-01 , 3.8269100000000000e-01 -6.6853839268006321e-01 , 4.2574035922820883e+00 , 6.7388016000000004e+00 , -3.0212800000000001e-01 , -2.1114200000000000e-01 , 9.2959000000000003e-01 -7.3224863480189861e-01 , 4.1971730628798039e+00 , 6.7485879999999998e+00 , 3.0041000000000001e-01 , -3.2880100000000001e-01 , 8.9534499999999995e-01 --1.6696270616147535e-01 , 5.1421242586316254e+00 , 8.8910504000000010e+00 , -8.9931799999999995e-01 , -4.3725000000000003e-01 , -6.2418600000000001e-03 --9.5458200489319633e-02 , 5.0764594873147253e+00 , 8.9651087999999994e+00 , -9.2945199999999994e-01 , -3.6878200000000000e-01 , -1.0861200000000000e-02 -2.6162851185183866e-01 , 4.7102914841022887e+00 , 8.3517375999999999e+00 , 8.1067599999999995e-01 , 5.2796500000000002e-01 , -2.5309700000000002e-01 -3.3968216775817117e-01 , 4.6360325163337031e+00 , 8.3792664000000006e+00 , -3.1326700000000002e-01 , -9.0802600000000000e-01 , 2.7812399999999998e-01 -3.9393333432979039e-01 , 4.5869048773232795e+00 , 8.4684984000000014e+00 , -3.1326700000000002e-01 , -9.0802600000000000e-01 , 2.7812399999999998e-01 -9.7577076458773382e-01 , 3.9762194804011051e+00 , 7.1162695999999999e+00 , -2.5813300000000000e-01 , -3.3339700000000000e-01 , -9.0676000000000001e-01 -1.0827458816742679e+00 , 3.8687833863057186e+00 , 6.9958583999999995e+00 , -5.4349300000000000e-01 , -2.0581300000000000e-01 , -8.1379100000000004e-01 -1.1300753316455228e+00 , 3.8256382665726774e+00 , 7.0395279999999998e+00 , 5.8028199999999996e-01 , 3.5424400000000000e-01 , 7.3333700000000002e-01 -1.1838816659288254e+00 , 3.7750197344269592e+00 , 7.0632712000000000e+00 , 1.2414400000000000e-01 , 2.3314799999999999e-01 , 9.6448500000000004e-01 -1.1685666205334952e+00 , 3.7995264064462395e+00 , 7.3133911999999999e+00 , -2.6813599999999999e-01 , 8.5155499999999995e-01 , 4.5050800000000002e-01 -1.2416171892066608e+00 , 3.7268000284439387e+00 , 7.2789776000000002e+00 , 2.3192500000000001e-02 , 5.9213300000000002e-01 , 8.0550699999999997e-01 -1.2741578129997513e+00 , 3.7003308307038081e+00 , 7.3864200000000002e+00 , -4.2566599999999999e-01 , 8.7905999999999995e-01 , 2.1462100000000001e-01 -1.4223776438033884e+00 , 3.5448764270455664e+00 , 7.0575720000000004e+00 , -2.9245300000000002e-01 , -1.3887400000000000e-01 , -9.4614299999999996e-01 -1.4466942066309700e+00 , 3.5271500346467199e+00 , 7.1908792000000004e+00 , -8.9627400000000002e-01 , 5.5704600000000000e-02 , 4.3998900000000002e-01 -1.5595805688775632e+00 , 3.4081889920067510e+00 , 6.9512527999999998e+00 , -3.7605000000000000e-01 , 3.0537999999999998e-01 , 8.7483100000000003e-01 -1.5619081764839524e+00 , 3.4150807934396621e+00 , 7.1914823999999999e+00 , 2.4096599999999999e-02 , -3.4596900000000003e-01 , 9.3793599999999999e-01 -1.6894186065172487e+00 , 3.2806413674099364e+00 , 6.8465559999999996e+00 , 5.7136100000000001e-01 , -8.1462900000000005e-01 , 9.9631999999999998e-02 -1.6836915043261194e+00 , 3.2965649799411061e+00 , 7.1457536000000008e+00 , 5.3602000000000005e-01 , -8.3134100000000000e-01 , 1.4681700000000000e-01 -1.6950762246811228e+00 , 3.2956256506683839e+00 , 7.3964768000000003e+00 , 7.0864499999999997e-01 , 6.8971600000000000e-01 , 1.4870900000000001e-01 -1.7354892274884568e+00 , 3.2609153804214595e+00 , 7.5068624000000002e+00 , -2.1396299999999999e-01 , 9.6995399999999998e-01 , 1.1579600000000000e-01 -1.6487574825741131e+00 , 3.3815384737418901e+00 , 8.4876032000000006e+00 , -7.3279499999999997e-01 , -6.7026300000000005e-01 , 1.1730000000000000e-01 -1.7479755392837144e+00 , 3.2780797727074571e+00 , 8.2851672000000001e+00 , -8.6191300000000004e-01 , -1.4194699999999999e-01 , -4.8678300000000002e-01 -1.0665820210105259e+00 , 3.7422751814710731e+00 , 6.5149440000000003e-01 , -1.0758300000000000e-01 , 7.4224799999999994e-02 , 9.9142200000000003e-01 -1.0086200955806239e+00 , 3.8002858762021177e+00 , 6.3717359999999990e-01 , -1.0758300000000000e-01 , 7.4224700000000005e-02 , 9.9142200000000003e-01 -9.6509832058376110e-01 , 3.8458900821784185e+00 , 6.4870719999999982e-01 , -1.0758300000000000e-01 , 7.4224700000000005e-02 , 9.9142100000000000e-01 -9.0245561518425754e-01 , 3.9097220881395707e+00 , 6.3069439999999988e-01 , -1.2699099999999999e-01 , 8.6812600000000004e-02 , 9.8809800000000003e-01 -8.3748050408621544e-01 , 3.9751611507602806e+00 , 6.1486559999999990e-01 , -1.7842000000000000e-01 , 1.0316599999999999e-01 , 9.7853100000000004e-01 -7.6796392419930082e-01 , 4.0461844762858039e+00 , 5.9414879999999992e-01 , -1.5522300000000000e-01 , 1.0395900000000000e-01 , 9.8239399999999999e-01 -7.0661234843787368e-01 , 4.1076465492328662e+00 , 5.9099759999999990e-01 , -1.1478700000000000e-01 , 8.8908799999999996e-02 , 9.8940300000000003e-01 -6.3968617645020220e-01 , 4.1747169133129489e+00 , 5.8283360000000006e-01 , -8.0135899999999996e-02 , 1.2788400000000000e-01 , 9.8854600000000004e-01 -5.4591507927961769e-01 , 4.2701856916517595e+00 , 5.4126479999999999e-01 , -9.2006800000000000e-02 , 1.5332699999999999e-01 , 9.8388299999999995e-01 -3.0583552979846140e-01 , 4.5135695208324318e+00 , 5.0171359999999998e-01 , 4.0764599999999996e-03 , 1.7342800000000000e-01 , 9.8483799999999999e-01 -2.1257283529490145e-01 , 4.6080483705232256e+00 , 4.8168319999999976e-01 , 2.9326300000000000e-02 , 1.2436200000000000e-01 , 9.9180400000000002e-01 -1.2425776764790974e-01 , 4.6980121613563561e+00 , 4.7192799999999990e-01 , 1.0048300000000000e-03 , 1.0980300000000000e-01 , 9.9395299999999998e-01 -3.4461859232905789e-02 , 4.7887899809234966e+00 , 4.6589599999999987e-01 , -1.2265399999999999e-02 , 1.1752500000000000e-01 , 9.9299400000000004e-01 --7.3081200771258459e-02 , 4.8985409862829954e+00 , 4.4487760000000010e-01 , -3.4208300000000001e-03 , 1.2370299999999999e-01 , 9.9231300000000000e-01 --1.8869954708435976e-01 , 5.0147304198224685e+00 , 4.2243439999999977e-01 , -2.1017399999999999e-02 , 1.3580500000000001e-01 , 9.9051299999999998e-01 --3.1141096878221219e-01 , 5.1384805881401396e+00 , 3.9908640000000006e-01 , -4.3767899999999998e-02 , 7.1683700000000003e-02 , 9.9646699999999999e-01 --4.5322421996266282e-01 , 5.2829136904319292e+00 , 3.6365359999999991e-01 , -1.6156100000000001e-01 , 9.0869000000000005e-02 , 9.8267000000000004e-01 --6.0887857301889126e-01 , 5.4407660826477171e+00 , 3.2338479999999992e-01 , 1.2891800000000000e-01 , -1.7588100000000001e-01 , -9.7593300000000005e-01 --7.7948077205033917e-01 , 5.6133096415340287e+00 , 2.7908079999999980e-01 , -5.7506799999999997e-02 , 1.6804800000000000e-01 , 9.8409999999999997e-01 --9.5755924198685749e-01 , 5.7941002873480993e+00 , 2.3721039999999993e-01 , 2.2430300000000000e-02 , 1.8834400000000001e-01 , 9.8184700000000003e-01 --1.1452600997972420e+00 , 5.9833078375102575e+00 , 1.9812720000000006e-01 , 5.4510000000000003e-02 , 1.9087999999999999e-01 , 9.8009900000000005e-01 --1.3339670177980993e+00 , 6.1742851926371358e+00 , 1.6765519999999978e-01 , 4.6888600000000002e-02 , 1.8476200000000001e-01 , 9.8166399999999998e-01 --1.5369297835926612e+00 , 6.3805184503699799e+00 , 1.3609120000000008e-01 , 1.5245600000000000e-02 , 1.7923000000000000e-01 , 9.8368900000000004e-01 --1.7752705785036116e+00 , 6.6215594154585231e+00 , 9.0487199999999879e-02 , 2.8179300000000002e-03 , 1.8276500000000001e-01 , 9.8315300000000005e-01 --2.0615513242747490e+00 , 6.9114793068642726e+00 , 2.4332799999999821e-02 , 1.0697200000000000e-02 , 2.4050900000000000e-01 , 9.7058800000000001e-01 --2.7047426890518791e+00 , 7.5586892172192766e+00 , -2.5774640000000026e-01 , 4.6035600000000003e-02 , -3.0581999999999998e-01 , -9.5097600000000004e-01 --3.3020701417600611e+00 , 8.1616080066820320e+00 , -4.7578239999999994e-01 , -6.4594600000000002e-02 , 2.5671400000000000e-01 , 9.6432600000000002e-01 --4.0414379631269854e+00 , 8.9068870583628978e+00 , -7.4488240000000028e-01 , -7.0447499999999996e-02 , 2.5793500000000003e-01 , 9.6358999999999995e-01 --4.9520886896429648e+00 , 9.8245080138248753e+00 , -1.0699760000000005e+00 , -8.3605899999999997e-02 , 2.1944400000000000e-01 , 9.7203600000000001e-01 --5.9407392580121314e+00 , 1.0822351910660995e+01 , -1.3877064000000003e+00 , 8.8327000000000003e-02 , -2.1550900000000001e-01 , -9.7249900000000000e-01 --7.1797324863430134e+00 , 1.2074063245588906e+01 , -1.7797760000000000e+00 , -1.6914300000000000e-02 , 1.2343200000000000e-01 , 9.9220900000000001e-01 --8.5555860962425285e+00 , 1.3464462749927510e+01 , -2.1712008000000003e+00 , 2.5334000000000001e-01 , -4.2103000000000002e-01 , -8.7094899999999997e-01 --8.5161604854605617e+00 , 1.3433192078135738e+01 , -1.8540528000000003e+00 , -2.5334000000000001e-01 , 4.2102899999999999e-01 , 8.7094899999999997e-01 --8.4584760333695890e+00 , 1.3384611839219030e+01 , -1.5345856000000002e+00 , -3.6862099999999998e-01 , -8.3808200000000006e-03 , 9.2954199999999998e-01 --8.4384877767121473e+00 , 1.3372852488694607e+01 , -1.2357104000000003e+00 , -3.6862099999999998e-01 , -8.3807799999999991e-03 , 9.2954199999999998e-01 --1.3177353378448842e+01 , 1.8159438265865298e+01 , -2.7009872000000001e+00 , 4.3241400000000002e-01 , -1.9165499999999999e-01 , 8.8107100000000005e-01 --1.3737976989720684e+01 , 1.8736922791015985e+01 , -2.4839808000000003e+00 , -7.7295800000000003e-01 , 5.6401300000000001e-02 , -6.3194499999999998e-01 --1.4075516482372173e+01 , 1.9090732687933208e+01 , -2.1703168000000002e+00 , 9.1435699999999998e-01 , 9.9195699999999998e-02 , 3.9256999999999997e-01 --1.4217063977835775e+01 , 1.9246680107482177e+01 , -1.7848616000000002e+00 , -8.8342900000000002e-01 , 9.8657800000000004e-02 , -4.5806000000000002e-01 --1.4080880269617730e+01 , 1.9121904427351861e+01 , -1.3209072000000002e+00 , 7.7480800000000005e-01 , -1.3098899999999999e-01 , 6.1847700000000005e-01 --1.4183615317889071e+01 , 1.9239241044384592e+01 , -9.2397040000000041e-01 , 7.1038800000000002e-01 , -5.1803500000000002e-01 , 4.7643400000000002e-01 --1.8955757768208219e+01 , 2.4084766603879444e+01 , -1.5291984000000003e+00 , -5.5581600000000002e-02 , 9.7454099999999999e-01 , -2.1721199999999999e-01 --1.9015699694735908e+01 , 2.4162177036278113e+01 , -9.9977599999999978e-01 , 5.5581600000000002e-02 , -9.7454099999999999e-01 , 2.1721199999999999e-01 --1.9111919651324282e+01 , 2.4276165257222793e+01 , -4.7537680000000027e-01 , -5.5581600000000002e-02 , 9.7454099999999999e-01 , -2.1721199999999999e-01 --1.9230799261620692e+01 , 2.4413468447046522e+01 , 4.8928799999999883e-02 , -5.6313799999999997e-02 , 9.7486700000000004e-01 , -2.1555400000000000e-01 --9.3002739351104289e+00 , 1.4343143224164018e+01 , 1.7310788800000001e+00 , 8.5411199999999998e-01 , -4.9920100000000001e-01 , 1.4591199999999999e-01 --9.1292482339049297e+00 , 1.4177147931526765e+01 , 2.0398431280000002e+00 , -2.9886000000000001e-01 , 6.0631000000000002e-01 , 7.3693399999999998e-01 --1.4301349618048280e+00 , 6.3544468091154478e+00 , 2.8279595999999998e+00 , 7.6171299999999997e-02 , 9.8681099999999999e-01 , -1.4283399999999999e-01 --1.4385104160391173e+00 , 6.3657163028028032e+00 , 2.9242760800000003e+00 , 6.7036299999999993e-02 , 9.8781200000000002e-01 , -1.4047299999999999e-01 --1.4448619219698977e+00 , 6.3759529038603446e+00 , 3.0211510399999999e+00 , 5.0618099999999999e-02 , 9.8742099999999999e-01 , -1.4979500000000001e-01 --1.4512698937510500e+00 , 6.3851593524205636e+00 , 3.1182287999999998e+00 , 5.0618099999999999e-02 , 9.8742099999999999e-01 , -1.4979500000000001e-01 --2.0815345545120660e+00 , 7.0309466447664892e+00 , 3.2376623999999996e+00 , -6.1104400000000003e-01 , 7.1474300000000002e-01 , -3.4024599999999999e-01 --2.0774695872272311e+00 , 7.0301577027830575e+00 , 3.3505544000000000e+00 , 5.9500399999999998e-01 , -7.4372300000000002e-01 , 3.0470500000000000e-01 --2.0858896793893287e+00 , 7.0429037612727141e+00 , 3.4647360000000003e+00 , -6.1444200000000004e-01 , 7.3070800000000002e-01 , -2.9753499999999999e-01 --2.1152409158613734e+00 , 7.0762484444105427e+00 , 3.5818088000000001e+00 , 5.7431800000000000e-01 , -7.5851000000000002e-01 , 3.0792999999999998e-01 --2.1208257545259315e+00 , 7.0850062819227846e+00 , 3.6978936000000000e+00 , -5.2452500000000002e-01 , 7.8722700000000001e-01 , -3.2426300000000002e-01 --2.1547225617209529e+00 , 7.1235523815986745e+00 , 3.8187104000000001e+00 , -4.8101800000000000e-01 , 8.0799900000000002e-01 , -3.4023399999999998e-01 --2.2152211472721177e+00 , 7.1891560741928293e+00 , 3.9469424000000002e+00 , -4.6541300000000002e-01 , 7.9216200000000003e-01 , -3.9480399999999999e-01 --2.2593271265456041e+00 , 7.2382285512072073e+00 , 4.0757048000000005e+00 , 2.3779800000000001e-01 , -8.6095800000000000e-01 , 4.4966899999999999e-01 --2.3164861937851224e+00 , 7.2996597312146632e+00 , 4.2103223999999999e+00 , 3.3983600000000003e-01 , -8.3941900000000003e-01 , 4.2413099999999998e-01 --2.3709067248809648e+00 , 7.3605636645343306e+00 , 4.3481535999999998e+00 , -2.7771800000000002e-01 , 8.7793500000000002e-01 , -3.9000400000000002e-01 --5.4740009203661142e+00 , 1.0554114004433718e+01 , 5.3703072000000001e+00 , -5.9407699999999997e-01 , -7.8420699999999996e-02 , -8.0057699999999998e-01 --7.7579373635597149e-01 , 5.7263057414091509e+00 , 4.0977423999999996e+00 , -2.2892999999999999e-01 , 7.3650899999999997e-01 , 6.3651000000000002e-01 --6.9202258760929158e-01 , 5.6416922632909356e+00 , 4.1541727999999996e+00 , -5.7781899999999997e-01 , 3.5946200000000000e-01 , 7.3274300000000003e-01 --6.2071281481023144e-01 , 5.5717009619755107e+00 , 4.2119864000000007e+00 , 4.1144700000000001e-01 , -6.3322400000000001e-01 , -6.5554500000000004e-01 --5.6310584921004381e-01 , 5.5144990698157343e+00 , 4.2723896000000003e+00 , 3.9849299999999999e-01 , -5.9651600000000005e-01 , -6.9668699999999995e-01 --5.1921768423839287e-01 , 5.4723117648202599e+00 , 4.3358816000000004e+00 , 1.9348899999999999e-01 , -6.2433899999999998e-01 , -7.5681100000000001e-01 --4.6759512187526608e-01 , 5.4214415676228338e+00 , 4.3948080000000003e+00 , -1.1163500000000000e-01 , 7.4208099999999999e-01 , 6.6094900000000001e-01 --4.3638994241036499e-01 , 5.3920381693946808e+00 , 4.4611079999999994e+00 , 1.2678800000000001e-01 , 8.5833899999999996e-01 , 4.9717200000000000e-01 --4.0405556730016245e-01 , 5.3613568340496762e+00 , 4.5265240000000002e+00 , 1.0315299999999999e-01 , 8.4917600000000004e-01 , 5.1793900000000004e-01 --3.7160768591470017e-01 , 5.3293826785913208e+00 , 4.5908271999999997e+00 , -3.8976499999999997e-01 , 7.2616800000000004e-01 , 5.6635999999999997e-01 --3.5886603581458187e-01 , 5.3183509536597358e+00 , 4.6652703999999998e+00 , -1.2154300000000000e-01 , 8.5052799999999995e-01 , 5.1169200000000004e-01 --3.3074940791674923e-01 , 5.2923007965290250e+00 , 4.7316952000000008e+00 , 2.3437800000000000e-01 , 8.3145899999999995e-01 , 5.0372899999999998e-01 --3.0921455789885188e-01 , 5.2724930750975556e+00 , 4.8013960000000004e+00 , -3.6298399999999997e-01 , -8.3189500000000005e-01 , -4.1975400000000002e-01 --2.3417338675445309e-01 , 5.1966577977530557e+00 , 4.8362775999999998e+00 , -2.6574700000000001e-01 , -8.6054399999999998e-01 , -4.3456099999999998e-01 --2.5719324857830017e-01 , 5.2227966948807278e+00 , 4.9347344000000000e+00 , 4.3592900000000001e-01 , 8.5160999999999998e-01 , 2.9107600000000000e-01 --2.0081919548296545e-01 , 5.1667562116736354e+00 , 4.9795791999999999e+00 , 3.3514400000000000e-01 , 8.8793400000000000e-01 , 3.1504300000000002e-01 --1.8253887494847998e-01 , 5.1505970431938994e+00 , 5.0508191999999994e+00 , 5.4012300000000002e-01 , 8.3275800000000000e-01 , 1.2157600000000000e-01 --1.5646135457623389e-01 , 5.1267015273092174e+00 , 5.1169840000000004e+00 , 5.8887900000000004e-01 , 7.8417800000000004e-01 , 1.9566900000000001e-01 --1.9296227039619485e-01 , 5.1666298223510063e+00 , 5.2335680000000000e+00 , 5.5798199999999998e-01 , 8.0044599999999999e-01 , 2.1895700000000001e-01 --6.6397823077211093e-02 , 5.0365403683982741e+00 , 5.2157008000000005e+00 , -5.4841200000000001e-01 , -7.7819300000000002e-01 , -3.0603900000000001e-01 --3.5598346474970741e+00 , 8.6949322827672617e+00 , 8.3879920000000006e+00 , -3.7286999999999998e-01 , -4.1718300000000003e-01 , 8.2881000000000005e-01 --3.1397971642473488e-01 , 5.3017063038637016e+00 , 5.6199592000000003e+00 , 5.9717900000000002e-01 , 7.9841600000000001e-01 , 7.6866199999999996e-02 --2.9298217710957148e+00 , 8.0487119363413022e+00 , 8.2189088000000012e+00 , 5.0071399999999999e-01 , -3.2966699999999999e-01 , 8.0037800000000003e-01 --6.9715317519913000e-01 , 5.7109748111628420e+00 , 6.2045639999999995e+00 , -1.4044699999999999e-01 , 4.4738299999999998e-01 , -8.8324599999999998e-01 --9.1014457293502993e-02 , 5.0766811411205488e+00 , 5.6995712000000003e+00 , -6.8496299999999996e-02 , 4.0989099999999999e-03 , 9.9764299999999995e-01 --1.7361983877892229e-02 , 5.0023046507440672e+00 , 5.7202984000000008e+00 , 5.7861000000000003e-02 , 2.2081100000000001e-01 , 9.7359899999999999e-01 --2.2790910267397546e-02 , 5.0122825839257104e+00 , 5.8266384000000002e+00 , 3.8749000000000000e-01 , 8.7511700000000003e-01 , 2.8986400000000001e-01 --2.4653875835176375e-01 , 5.2503816784466588e+00 , 6.1859479999999998e+00 , 6.2275700000000001e-01 , 7.0950400000000002e-01 , -3.2981500000000002e-01 -1.4354028975919864e-02 , 4.9788093071914217e+00 , 5.9899392000000002e+00 , 2.5870500000000002e-01 , 7.4980300000000000e-01 , 6.0898900000000000e-01 -2.0327310971582180e-01 , 4.7815504912844258e+00 , 5.8627783999999998e+00 , 2.0741100000000001e-01 , 2.7369800000000000e-01 , 9.3918599999999997e-01 -2.6052635297058480e-01 , 4.7254653867420338e+00 , 5.8917944000000002e+00 , -3.2299099999999997e-01 , 3.4936399999999999e-02 , -9.4575699999999996e-01 -1.6913068345924609e-01 , 4.8243444687265171e+00 , 6.1153424000000003e+00 , -5.5088800000000004e-01 , -5.5882200000000004e-01 , 6.1987199999999998e-01 -2.2347265065802846e-01 , 4.7708951226036085e+00 , 6.1515032000000005e+00 , -6.9661600000000001e-01 , 5.8974000000000004e-01 , -4.0857399999999999e-01 --3.9958797547055580e-01 , 5.4369994231912697e+00 , 7.1533559999999996e+00 , 3.8262699999999999e-01 , 4.6637200000000001e-01 , 7.9755500000000001e-01 --2.7358440245968119e-01 , 5.3069023896274974e+00 , 7.1142728000000011e+00 , -4.8809500000000000e-01 , -4.7224600000000000e-01 , -7.3399400000000004e-01 --1.9311337132125406e-01 , 5.2254294816632036e+00 , 7.1381200000000007e+00 , -1.6830399999999999e-02 , 8.8280400000000003e-01 , 4.6944100000000000e-01 --1.8126435547672219e+00 , 6.9595159821904033e+00 , 9.8604032000000004e+00 , 3.7024200000000002e-01 , 5.6600899999999998e-01 , -7.3658400000000002e-01 --1.3282931854994207e-01 , 5.1701497600573063e+00 , 7.3404104000000006e+00 , 2.8788300000000000e-01 , -6.4010299999999998e-01 , -7.1231500000000003e-01 --3.0084885515503501e-01 , 5.3550274767337340e+00 , 7.7847400000000002e+00 , -7.2539400000000004e-03 , -9.8774200000000001e-01 , 1.5592700000000001e-01 -5.9826766074203430e-01 , 4.3951903138830231e+00 , 6.3641416000000008e+00 , 2.8488100000000000e-01 , -9.1527000000000003e-01 , -2.8482299999999999e-01 -6.2170440365380619e-01 , 4.3730515750868353e+00 , 6.4437432000000001e+00 , -6.5090099999999995e-01 , 6.6757000000000000e-01 , 3.6149399999999998e-01 --2.5572620881841557e-01 , 5.3236064337710900e+00 , 8.2444616000000011e+00 , -2.2981399999999999e-01 , -9.4214500000000001e-01 , -2.4402499999999999e-01 -2.8532589719387214e-01 , 4.7450939602387816e+00 , 7.3700608000000001e+00 , -4.7439300000000001e-01 , -7.8243499999999999e-01 , 4.0342000000000000e-01 -5.7365783543894033e-01 , 4.4385902047044627e+00 , 6.9432239999999998e+00 , 9.9095299999999997e-02 , 8.0464500000000005e-01 , 5.8542899999999998e-01 -7.1379052435689294e-01 , 4.2909937701961214e+00 , 6.7939632000000003e+00 , 6.7558399999999996e-01 , -4.3074800000000002e-01 , 5.9836599999999995e-01 -8.1445394785224723e-01 , 4.1851645669933175e+00 , 6.7170448000000000e+00 , -4.7157200000000003e-02 , -5.7695399999999997e-01 , 8.1541399999999997e-01 -3.0227044817940252e-02 , 5.0458764666285036e+00 , 8.6767584000000006e+00 , -8.9938300000000004e-01 , -4.2439700000000002e-01 , -1.0487200000000001e-01 --2.7995501820763202e-01 , 5.3902591287304160e+00 , 9.6505728000000008e+00 , -2.6169100000000001e-01 , -9.6428599999999998e-01 , -4.0863600000000000e-02 -3.4144712708100733e-01 , 4.7187781635387900e+00 , 8.3686895999999997e+00 , -3.1326700000000002e-01 , -9.0802600000000000e-01 , 2.7812399999999998e-01 -4.1744108018976500e-01 , 4.6412683964383383e+00 , 8.3954799999999992e+00 , -3.1326700000000002e-01 , -9.0802600000000000e-01 , 2.7812399999999998e-01 -9.6873252211424554e-01 , 4.0406478758851190e+00 , 7.1236224000000004e+00 , -1.6043199999999999e-01 , 7.0389100000000004e-01 , 6.9195300000000004e-01 -1.0649364299329611e+00 , 3.9406530018331418e+00 , 7.0325704000000000e+00 , -9.6545999999999998e-01 , -2.4598200000000001e-01 , 8.5905499999999996e-02 -1.0667396967510268e+00 , 3.9429073933836190e+00 , 7.2075296000000009e+00 , 5.7566200000000001e-01 , -8.5788199999999995e-02 , -8.1317499999999998e-01 -1.1032553352997183e+00 , 3.9090730975554546e+00 , 7.2898040000000002e+00 , 2.1873699999999999e-01 , -3.7998999999999999e-01 , -8.9875499999999997e-01 -1.1727096928140728e+00 , 3.8368805028159541e+00 , 7.2677871999999999e+00 , 1.4248900000000000e-01 , 4.8728399999999999e-01 , 8.6153999999999997e-01 -1.2243410225582476e+00 , 3.7849933765518617e+00 , 7.3006304000000002e+00 , -5.5241700000000005e-01 , 1.0343800000000000e-01 , 8.2712500000000000e-01 -1.2503324160465299e+00 , 3.7628419148653793e+00 , 7.4281032000000007e+00 , -5.2671400000000002e-01 , 7.2588000000000000e-02 , 8.4693799999999997e-01 -1.4003688636918001e+00 , 3.5994257113415102e+00 , 7.0917048000000005e+00 , -3.5653200000000002e-01 , -2.4956300000000001e-01 , 9.0033500000000000e-01 -1.4408724719127122e+00 , 3.5610834434695287e+00 , 7.1577447999999997e+00 , -8.4881300000000004e-01 , 4.8672399999999998e-02 , 5.2644899999999994e-01 -1.4956112580522962e+00 , 3.5048494250516056e+00 , 7.1643800000000004e+00 , 2.8370699999999999e-02 , 4.9458000000000002e-01 , 8.6866900000000002e-01 -1.5913194391928553e+00 , 3.4013689860751208e+00 , 6.9821616000000004e+00 , 2.9721399999999998e-01 , -2.1463599999999999e-01 , -9.3037400000000003e-01 -1.6523371012511037e+00 , 3.3392131455541758e+00 , 6.9448984000000005e+00 , 6.9544600000000001e-01 , 3.3946300000000001e-01 , 6.3334000000000001e-01 -1.6801567198900134e+00 , 3.3134529619576245e+00 , 7.0654136000000003e+00 , -7.9996199999999995e-01 , -1.7624600000000001e-01 , 5.7358399999999998e-01 -1.6930528152054936e+00 , 3.3073762917512779e+00 , 7.2857376000000000e+00 , -8.4578500000000001e-01 , 5.3200800000000004e-01 , 4.0196999999999997e-02 -1.7405940279431869e+00 , 3.2612710371677096e+00 , 7.3358135999999998e+00 , -9.0800700000000001e-01 , 3.6438300000000001e-01 , 2.0675499999999999e-01 -1.8518981664125871e+00 , 3.1361635352206072e+00 , 6.9704823999999999e+00 , -1.1543700000000000e-01 , -9.0881299999999998e-01 , 4.0091599999999999e-01 -1.7032396998219295e+00 , 3.3302716970808417e+00 , 8.3765415999999995e+00 , 5.2860399999999996e-01 , 1.7330899999999999e-01 , 8.3098799999999995e-01 -1.7950498119371621e+00 , 3.2319435338267555e+00 , 8.1927008000000008e+00 , -2.0035300000000000e-01 , -9.2629399999999995e-01 , 3.1912200000000002e-01 -9.9044839400849094e-01 , 3.9262751130570637e+00 , 6.4204079999999997e-01 , -1.2699099999999999e-01 , 8.6812600000000004e-02 , 9.8809800000000003e-01 -9.3297498026980175e-01 , 3.9874091183467866e+00 , 6.3278480000000004e-01 , -1.5411900000000001e-01 , 6.7535899999999996e-02 , 9.8574099999999998e-01 -8.7000811959749114e-01 , 4.0551016786564125e+00 , 6.1801679999999992e-01 , -1.6576199999999999e-01 , 8.6284100000000002e-02 , 9.8238400000000003e-01 -7.9721618561520513e-01 , 4.1334621461234509e+00 , 5.9089359999999980e-01 , 9.4367999999999994e-02 , -1.1238600000000000e-01 , -9.8917299999999997e-01 -7.2733142852021393e-01 , 4.2084113829772987e+00 , 5.7380640000000005e-01 , -8.0135899999999996e-02 , 1.2788400000000000e-01 , 9.8854600000000004e-01 -6.6235408549415675e-01 , 4.2778399261830584e+00 , 5.6720239999999977e-01 , -1.0743900000000001e-01 , 1.6041500000000000e-01 , 9.8118499999999997e-01 -5.5987360875869663e-01 , 4.3870997200465247e+00 , 5.1320559999999982e-01 , -1.0678700000000001e-01 , 1.3923199999999999e-01 , 9.8448500000000005e-01 -5.0916389726546551e-01 , 4.4422297864873599e+00 , 5.3357919999999992e-01 , -8.6724999999999997e-02 , 1.3764299999999999e-01 , 9.8667800000000006e-01 -4.1009813272334261e-01 , 4.5489877080605865e+00 , 4.9418399999999996e-01 , -4.5833499999999999e-02 , 1.4560699999999999e-01 , 9.8828000000000005e-01 -3.3095432821780602e-01 , 4.6345922529141710e+00 , 4.8587440000000015e-01 , -2.5371999999999999e-02 , 1.3395000000000001e-01 , 9.9066299999999996e-01 -2.4498453555287969e-01 , 4.7262305567327685e+00 , 4.7435119999999986e-01 , 2.0948200000000000e-02 , 9.8404500000000006e-02 , 9.9492599999999998e-01 -1.5862671895075842e-01 , 4.8196259978550966e+00 , 4.6625999999999990e-01 , -3.5393199999999999e-03 , 1.0123300000000000e-01 , 9.9485699999999999e-01 -5.4508121839782264e-02 , 4.9309625442242124e+00 , 4.4327600000000000e-01 , -5.9590499999999996e-03 , 1.4763000000000001e-01 , 9.8902500000000004e-01 --5.1167907641324728e-02 , 5.0443285302234893e+00 , 4.2472239999999983e-01 , 1.9875399999999999e-04 , 1.3784399999999999e-01 , 9.9045399999999995e-01 --1.5738691207597322e-01 , 5.1586456021493925e+00 , 4.1082799999999997e-01 , 3.9691999999999998e-02 , 5.4569800000000002e-02 , 9.9772099999999997e-01 --2.8261146510107826e-01 , 5.2934847292446934e+00 , 3.8403760000000009e-01 , 1.5355799999999999e-02 , 9.5857600000000005e-04 , 9.9988200000000005e-01 --3.3099745264372604e-01 , 5.3476002244918286e+00 , 4.3675519999999990e-01 , 1.5355799999999999e-02 , 9.5856800000000003e-04 , 9.9988200000000005e-01 --5.7329327200077929e-01 , 5.6051680851058698e+00 , 3.1426399999999988e-01 , 3.0836900000000000e-01 , -4.4725700000000000e-02 , -9.5021500000000003e-01 --7.6307616829165248e-01 , 5.8098814826787875e+00 , 2.5163519999999995e-01 , -7.0881100000000002e-02 , 1.8375400000000000e-01 , 9.8041299999999998e-01 --9.5601744022491442e-01 , 6.0165650807139857e+00 , 1.9806480000000004e-01 , 9.7930900000000008e-03 , 1.8295100000000000e-01 , 9.8307299999999997e-01 --1.1444897275064809e+00 , 6.2184774214533638e+00 , 1.5862799999999977e-01 , 4.5430600000000002e-02 , 1.8038699999999999e-01 , 9.8254600000000003e-01 --1.3405866404804794e+00 , 6.4299968857586327e+00 , 1.2314319999999990e-01 , 2.1727199999999999e-02 , 1.9001399999999999e-01 , 9.8154100000000000e-01 --1.5709257906965783e+00 , 6.6772122083179859e+00 , 7.3046399999999956e-02 , 8.0727699999999999e-03 , 1.9006700000000001e-01 , 9.8173800000000000e-01 --1.8480875572351465e+00 , 6.9742333127015304e+00 , 1.9000000000000128e-03 , 1.8451700000000001e-02 , 2.3695800000000000e-01 , 9.7134500000000001e-01 --2.2949730895797344e+00 , 7.4534415225984549e+00 , -1.7091680000000009e-01 , -3.7304900000000002e-02 , 3.0602499999999999e-01 , 9.5129200000000003e-01 --2.8581666793406804e+00 , 8.0560106946999319e+00 , -3.9394480000000032e-01 , -6.1083999999999999e-02 , 2.5822699999999998e-01 , 9.6415099999999998e-01 --3.5118613130058751e+00 , 8.7561865195881996e+00 , -6.4202640000000022e-01 , -6.6574999999999995e-02 , 2.5192799999999999e-01 , 9.6545300000000001e-01 --4.3385750016684677e+00 , 9.6406192349895985e+00 , -9.5582560000000028e-01 , -8.7384100000000006e-02 , 2.3297599999999999e-01 , 9.6854799999999996e-01 --5.1857226246409507e+00 , 1.0549741297515192e+01 , -1.2357728000000003e+00 , -8.6901800000000001e-02 , 2.1306600000000001e-01 , 9.7316599999999998e-01 --6.3424089610289762e+00 , 1.1788032171879228e+01 , -1.6344048000000000e+00 , -9.3388600000000002e-02 , 2.1158399999999999e-01 , 9.7288799999999998e-01 --7.6709074879188250e+00 , 1.3211588610028242e+01 , -2.0569151999999997e+00 , -1.9219800000000001e-01 , -2.6027499999999998e-01 , -9.4621200000000005e-01 --9.5304051593664791e+00 , 1.5205158114563488e+01 , -2.6619039999999998e+00 , -7.7660099999999996e-02 , 2.3048700000000000e-01 , 9.6997199999999995e-01 --1.1195592572565454e+01 , 1.6992671708619731e+01 , -3.0780704000000005e+00 , -3.1649099999999999e-02 , -2.2747400000000001e-01 , 9.7326999999999997e-01 --1.1692198009338789e+01 , 1.7533046966975739e+01 , -2.9106200000000007e+00 , -3.7984299999999999e-02 , -2.3530699999999999e-01 , 9.7117900000000001e-01 --1.2222870766822270e+01 , 1.8110872607808197e+01 , -2.7330192000000002e+00 , 6.3229099999999999e-04 , -2.7513100000000001e-01 , 9.6140599999999998e-01 --1.2774230187641498e+01 , 1.8710184742430787e+01 , -2.5373847999999999e+00 , -1.2257300000000000e-01 , 1.8823699999999999e-01 , -9.7444500000000001e-01 --1.4278281573528069e+01 , 2.0330759460102481e+01 , -2.6410520000000002e+00 , 9.8828899999999997e-01 , 9.4569899999999998e-02 , 1.1975900000000000e-01 --1.4615708256157220e+01 , 2.0703905198400381e+01 , -2.2998383999999996e+00 , -9.1546300000000003e-01 , -1.1507600000000000e-01 , -3.8559599999999999e-01 --1.4650997401791145e+01 , 2.0752356120129772e+01 , -1.8563512000000002e+00 , -9.1546300000000003e-01 , -1.1507600000000000e-01 , -3.8559599999999999e-01 --1.5490183156394689e+01 , 2.1663346809850850e+01 , -1.6245455999999998e+00 , -9.7897999999999996e-01 , -4.0152199999999999e-02 , -1.9996300000000000e-01 --1.5278787652900391e+01 , 2.1448126536497263e+01 , -1.1035160000000004e+00 , -9.7897999999999996e-01 , -4.0152199999999999e-02 , -1.9996300000000000e-01 --1.8013842279680244e+01 , 2.4397628736620213e+01 , -1.2139432000000001e+00 , 5.8371699999999999e-02 , -9.7040899999999997e-01 , 2.3430400000000001e-01 --1.8105014063615869e+01 , 2.4507652856548507e+01 , -6.9804079999999979e-01 , -5.8371699999999999e-02 , 9.7040999999999999e-01 , -2.3430400000000001e-01 --1.8146997405095167e+01 , 2.4565570552067516e+01 , -1.7169679999999987e-01 , 6.1424399999999997e-02 , -9.7195600000000004e-01 , 2.2700000000000001e-01 --2.7419943554635655e+01 , 3.4558661037353545e+01 , -8.6357760000000017e-01 , -1.1482400000000000e-01 , -4.9292000000000002e-02 , 9.9216199999999999e-01 --2.7516450066822198e+01 , 3.4680868159312901e+01 , -1.0378480000000012e-01 , -9.5949999999999994e-02 , 1.8243900000000000e-02 , 9.9521899999999996e-01 --1.2213480270000279e+00 , 6.3631633196154169e+00 , 2.7840643200000001e+00 , 1.1039599999999999e-01 , 9.8493799999999998e-01 , -1.3307700000000000e-01 --1.2304613548279302e+00 , 6.3750366571235144e+00 , 2.8779253599999999e+00 , 1.1039599999999999e-01 , 9.8493799999999998e-01 , -1.3307700000000000e-01 --1.2447093744391959e+00 , 6.3935518844447481e+00 , 2.9720515999999999e+00 , 1.0978700000000000e-01 , 9.7322399999999998e-01 , -2.0194699999999999e-01 --1.2591032462150595e+00 , 6.4101168602268013e+00 , 3.0669880000000003e+00 , 9.4530400000000001e-02 , 9.7429200000000005e-01 , -2.0449899999999999e-01 --1.2787198260222676e+00 , 6.4334438338570745e+00 , 3.1628031999999999e+00 , -2.5634400000000002e-01 , -9.6478100000000000e-01 , -5.9041600000000000e-02 --1.0990079728999298e+00 , 6.2426062207469357e+00 , 3.2500280000000004e+00 , 1.8208800000000000e-01 , 9.2349800000000004e-01 , 3.3763300000000002e-01 --1.2011960243542572e+00 , 6.3550981378217521e+00 , 3.3491192000000001e+00 , 5.4821100000000000e-01 , 8.3612500000000001e-01 , -1.8964200000000001e-02 --1.2738701816580367e+00 , 6.4360080225124721e+00 , 3.4506231999999999e+00 , -5.4971400000000004e-01 , -8.1123699999999999e-01 , 1.9927000000000000e-01 --2.0270503172333392e+00 , 7.2533514812207249e+00 , 3.6416816000000001e+00 , -6.0642799999999997e-01 , 7.4501300000000004e-01 , -2.7785100000000001e-01 --2.0400860748884808e+00 , 7.2692367232055490e+00 , 3.7599087999999998e+00 , 7.4764299999999995e-01 , -6.0444100000000001e-01 , 2.7510299999999999e-01 --2.0438386928262267e+00 , 7.2761799963049816e+00 , 3.8778655999999998e+00 , -6.8886999999999998e-01 , 6.3285499999999995e-01 , -3.5348600000000002e-01 --2.0602935878148800e+00 , 7.2970493101727740e+00 , 3.9990360000000003e+00 , 6.9042899999999996e-01 , -6.4146199999999998e-01 , 3.3441599999999999e-01 --2.1096928063514993e+00 , 7.3541216474773847e+00 , 4.1294832000000001e+00 , 5.9614500000000004e-01 , -7.0242300000000002e-01 , 3.8886199999999999e-01 --2.1436262575249145e+00 , 7.3934243487782032e+00 , 4.2593271999999995e+00 , 4.3271199999999999e-01 , -8.5949600000000004e-01 , 2.7207900000000002e-01 --2.1831627118813657e+00 , 7.4390617779919559e+00 , 4.3930920000000002e+00 , 3.2950699999999999e-01 , -8.9265300000000003e-01 , 3.0756400000000000e-01 --2.2209325102131254e+00 , 7.4829986904576531e+00 , 4.5293216000000003e+00 , 2.1808300000000000e-01 , -9.0133700000000005e-01 , 3.7420700000000001e-01 --2.2633748763500234e+00 , 7.5323447294060974e+00 , 4.6703144000000005e+00 , -1.2920200000000001e-01 , 9.0629400000000004e-01 , -4.0241600000000000e-01 --2.3309789563755281e+00 , 7.6087113195485490e+00 , 4.8241303999999996e+00 , 2.2377700000000000e-01 , -8.9781200000000005e-01 , 3.7928600000000001e-01 --2.3765353530450994e+00 , 7.6610128083648785e+00 , 4.9738696000000004e+00 , 1.6221500000000000e-01 , -9.2039000000000004e-01 , 3.5576400000000002e-01 --5.1174563541378415e-01 , 5.6332751835373172e+00 , 4.3247847999999998e+00 , -3.4261799999999998e-01 , 5.7819100000000001e-01 , 7.4047799999999997e-01 --4.5497445399866931e-01 , 5.5735481112105063e+00 , 4.3830456000000000e+00 , 5.1624599999999998e-01 , -4.0610800000000002e-01 , -7.5403299999999995e-01 --3.8481463232141166e-01 , 5.4987076903278345e+00 , 4.4323312000000001e+00 , -6.2364600000000003e-01 , 2.9869299999999999e-01 , 7.2239100000000001e-01 --3.3397454829468698e-01 , 5.4452063918299896e+00 , 4.4886055999999996e+00 , -6.1520100000000000e-01 , 4.2470599999999997e-01 , 6.6419300000000003e-01 --2.8945082333771044e-01 , 5.3986274120030817e+00 , 4.5462319999999998e+00 , 4.5623900000000001e-01 , -6.1206799999999995e-01 , -6.4592499999999997e-01 --2.5795223241258114e-01 , 5.3654208964910417e+00 , 4.6095056000000003e+00 , -3.4202700000000003e-01 , 7.1304900000000004e-01 , 6.1202800000000002e-01 --2.1198664752177399e-01 , 5.3181154898397285e+00 , 4.6638248000000004e+00 , -1.6137199999999999e-01 , 6.7168499999999998e-01 , 7.2304800000000002e-01 --1.6688219873052690e-01 , 5.2694045854765603e+00 , 4.7162927999999997e+00 , 1.0228100000000000e-02 , 7.0847000000000004e-01 , 7.0566700000000004e-01 --1.3277853792175165e-01 , 5.2352299188909148e+00 , 4.7752607999999999e+00 , -3.0358499999999999e-01 , 6.7077500000000001e-01 , 6.7668099999999998e-01 --9.9607776397779624e-02 , 5.1997943803353941e+00 , 4.8331055999999997e+00 , -3.1236700000000001e-01 , 6.7854800000000004e-01 , 6.6483099999999995e-01 --6.4208942027359495e-02 , 5.1640464647786022e+00 , 4.8898792000000002e+00 , -6.8186499999999997e-02 , 7.8957299999999997e-01 , 6.0985599999999995e-01 --2.9728681927251532e-02 , 5.1270193580281562e+00 , 4.9453112000000008e+00 , -2.3686900000000000e-02 , 7.5850499999999998e-01 , 6.5123600000000004e-01 -2.1343788645311612e-04 , 5.0962563264385725e+00 , 5.0045807999999994e+00 , 2.0838499999999999e-01 , 8.1722200000000000e-01 , 5.3732999999999997e-01 -3.0284620943360041e-02 , 5.0652753922118894e+00 , 5.0627376000000002e+00 , 9.4585900000000001e-02 , 8.4146799999999999e-01 , 5.3196399999999999e-01 -6.7261411181521291e-02 , 5.0274491397239292e+00 , 5.1147895999999999e+00 , 1.4547399999999999e-01 , 8.3301000000000003e-01 , 5.3378999999999999e-01 -9.7558772581360698e-02 , 4.9949859946629900e+00 , 5.1709183999999997e+00 , 1.8120900000000001e-01 , 8.1336500000000000e-01 , 5.5281199999999997e-01 -1.2422391136579392e-01 , 4.9678775763954679e+00 , 5.2318312000000002e+00 , -3.5162500000000002e-01 , 7.5076100000000001e-01 , 5.5921200000000004e-01 -1.5681091610491316e-01 , 4.9349553624302338e+00 , 5.2861919999999998e+00 , -2.6234299999999999e-01 , 7.9783400000000004e-01 , 5.4280499999999998e-01 -1.7198673035852141e-01 , 4.9188778514792215e+00 , 5.3571512000000006e+00 , 4.0286099999999998e-02 , 9.1865600000000003e-01 , 3.9299899999999999e-01 -1.9409610572756830e-01 , 4.8969687835887195e+00 , 5.4217975999999997e+00 , 5.1381599999999999e-02 , 8.6311099999999996e-01 , 5.0239400000000001e-01 -2.0071506344455581e-01 , 4.8921133827339265e+00 , 5.5045088000000000e+00 , -4.0828799999999998e-01 , -8.7785199999999997e-01 , -2.5035200000000002e-01 -1.7993774312527511e-01 , 4.9170833023595470e+00 , 5.6187632000000001e+00 , -2.9012500000000002e-01 , -9.5255500000000004e-01 , 9.2016500000000001e-02 -1.1202966673210435e-01 , 4.9942690258784683e+00 , 5.7923704000000003e+00 , 6.6342500000000004e-01 , 7.1806400000000004e-01 , 2.1036199999999999e-01 -1.5569238264063889e-01 , 4.9478020220244368e+00 , 5.8398256000000002e+00 , 7.6635100000000000e-01 , 5.8720200000000000e-01 , 2.6057700000000000e-01 -2.4286259274661437e-01 , 4.8533827705315336e+00 , 5.8325040000000001e+00 , 5.0658800000000004e-01 , 5.9213300000000002e-01 , 6.2669600000000003e-01 -2.6627637311101005e-01 , 4.8294884755386311e+00 , 5.9033800000000003e+00 , -6.6350399999999998e-01 , -1.4530899999999999e-01 , -7.3392599999999997e-01 -1.1976164983607940e-01 , 4.9959106571159388e+00 , 6.2026920000000008e+00 , -3.9648200000000000e-01 , -9.1439199999999998e-01 , -8.1790199999999993e-02 --3.8237512649010785e-01 , 5.5566105474132925e+00 , 7.0128832000000001e+00 , 5.4642599999999997e-01 , 5.3325900000000004e-01 , 6.4579600000000004e-01 --9.4173685000983554e-02 , 5.2387366197344241e+00 , 6.7403928000000004e+00 , 1.3602700000000001e-01 , 9.7583699999999995e-01 , 1.7099400000000001e-01 --1.7312290027705313e-01 , 5.3295059758635324e+00 , 6.9896392000000001e+00 , 1.3602700000000001e-01 , 9.7583699999999995e-01 , 1.7099400000000001e-01 --1.4970044646095770e-01 , 5.3061970728856380e+00 , 7.0950224000000004e+00 , -1.4025800000000000e-02 , 9.5589500000000005e-01 , 2.9337400000000002e-01 --1.1522047364810639e-01 , 5.2708465286891890e+00 , 7.1851696000000000e+00 , -1.0661700000000000e-01 , 9.0616900000000000e-01 , 4.0925699999999998e-01 --1.1172892128125111e-01 , 5.2709494445261740e+00 , 7.3287000000000004e+00 , 2.5860800000000000e-01 , -7.7686299999999997e-01 , -5.7411299999999998e-01 -6.1005097058022884e-01 , 4.4670631681081527e+00 , 6.2437927999999996e+00 , -2.5409300000000001e-01 , 9.6408799999999995e-01 , 7.7272800000000003e-02 -6.0816418992794485e-01 , 4.4710314235699613e+00 , 6.3632264000000003e+00 , -6.1308499999999999e-01 , 7.9001399999999999e-01 , -1.9876899999999999e-03 --1.4632043376338011e-01 , 5.3217171459139525e+00 , 7.8790056000000002e+00 , -1.3733899999999999e-01 , 9.8760000000000003e-01 , -7.6048000000000004e-02 -9.1962981124518439e-01 , 4.1275774776261347e+00 , 6.0162304000000004e+00 , 2.8415000000000001e-01 , 1.2218300000000000e-01 , -9.5096300000000000e-01 --1.4255094963065051e-01 , 5.3255267655607277e+00 , 8.2360271999999988e+00 , -2.2981399999999999e-01 , -9.4214500000000001e-01 , -2.4402499999999999e-01 -6.7726078664089284e-01 , 4.4062049854408620e+00 , 6.7413808000000008e+00 , 3.6505900000000002e-01 , -8.7902199999999997e-01 , -3.0667800000000001e-01 -7.8859011985730709e-01 , 4.2828534921797399e+00 , 6.6430384000000000e+00 , 1.6247200000000000e-02 , -1.4112900000000000e-01 , 9.8985800000000002e-01 -8.4407169364047396e-01 , 4.2245204011860977e+00 , 6.6604480000000006e+00 , -1.1315799999999999e-01 , 3.6687399999999998e-01 , -9.2336300000000004e-01 -8.9457192734528235e-01 , 4.1699421168386266e+00 , 6.6849504000000000e+00 , 3.5421599999999998e-01 , -1.2509000000000001e-01 , -9.2676000000000003e-01 --1.8465038297051839e-01 , 5.3998263441790630e+00 , 9.4285016000000006e+00 , -3.4133799999999997e-01 , -9.3945500000000004e-01 , -3.0210799999999999e-02 --2.6819919303637763e-01 , 5.5000944443646098e+00 , 9.8978120000000001e+00 , 2.5175700000000001e-01 , 9.6773799999999999e-01 , 1.0086400000000001e-02 -8.9852648478356234e-01 , 4.1766968102742865e+00 , 7.1356760000000001e+00 , 4.7556900000000002e-01 , 8.9436699999999994e-02 , 8.7512000000000001e-01 -9.8053345253737922e-01 , 4.0865685143064940e+00 , 7.0852776000000004e+00 , -4.3596099999999999e-01 , 5.6498300000000001e-01 , 7.0052300000000001e-01 -1.0482729903809092e+00 , 4.0134022284953739e+00 , 7.0686064000000002e+00 , -9.7032200000000002e-01 , 1.7504700000000001e-01 , 1.6683400000000001e-01 -1.0710725795268512e+00 , 3.9911767783326382e+00 , 7.1792520000000009e+00 , -8.5623600000000000e-01 , 1.9009100000000001e-01 , 4.8033900000000002e-01 -1.1782522936001083e+00 , 3.8721413162855303e+00 , 7.0381656000000001e+00 , 2.2403899999999999e-01 , 3.7341299999999999e-01 , 9.0020500000000003e-01 -1.1853532717387187e+00 , 3.8689859659296149e+00 , 7.2032136000000007e+00 , 8.2018300000000002e-02 , 8.8505500000000004e-01 , 4.5820400000000000e-01 -1.2817582767438755e+00 , 3.7614764512164225e+00 , 7.0749399999999998e+00 , 2.4321300000000001e-01 , 2.1264800000000000e-01 , 9.4637700000000002e-01 -1.2437815363366012e+00 , 3.8096903047095099e+00 , 7.4115568000000005e+00 , -6.1741000000000001e-01 , -8.5616100000000007e-03 , 7.8659500000000004e-01 -1.3137935722701746e+00 , 3.7336420470108882e+00 , 7.3757704000000004e+00 , 7.7805899999999995e-01 , -3.9506100000000000e-01 , -4.8841800000000002e-01 -1.4361537467176810e+00 , 3.5959620270230981e+00 , 7.1243296000000003e+00 , 9.8373900000000003e-01 , 4.1108600000000002e-02 , -1.7483599999999999e-01 -1.4516540559478015e+00 , 3.5825501178372057e+00 , 7.2876719999999997e+00 , 1.4378400000000000e-02 , 2.6141399999999998e-01 , 9.6511999999999998e-01 -1.5886107240659102e+00 , 3.4272532085881395e+00 , 6.9308480000000001e+00 , 3.7605000000000000e-01 , -3.0537999999999998e-01 , -8.7483100000000003e-01 -1.6032187196875884e+00 , 3.4154007084129261e+00 , 7.1017824000000003e+00 , -3.5951899999999998e-01 , 8.4511400000000003e-01 , 3.9563700000000002e-01 -1.6965477897054886e+00 , 3.3093369179867853e+00 , 6.8956648000000005e+00 , 7.3553100000000005e-01 , 5.0864100000000001e-01 , -4.4752500000000001e-01 -1.6907303007230874e+00 , 3.3232366301746703e+00 , 7.1952783999999994e+00 , -3.6425800000000003e-01 , 7.3763000000000001e-01 , 5.6852300000000000e-01 -1.7272058132487049e+00 , 3.2846826837485441e+00 , 7.2857896000000002e+00 , -6.6363899999999998e-01 , 6.7248200000000002e-01 , 3.2764500000000002e-01 -1.7588602294172719e+00 , 3.2552748465926573e+00 , 7.4259088000000002e+00 , -5.7201700000000000e-01 , -8.1710899999999997e-01 , -7.1614600000000000e-02 -1.6655501817562346e+00 , 3.3780768663695442e+00 , 8.4265863999999997e+00 , 7.7787499999999998e-01 , 6.2466100000000002e-01 , -6.8623900000000002e-02 -1.7607228388692209e+00 , 3.2705722189470685e+00 , 8.2137087999999991e+00 , -9.4288600000000000e-01 , -3.2245499999999999e-01 , -8.3596299999999998e-02 -7.5839112769724659e-01 , 4.3041732544380356e+00 , 5.6560079999999990e-01 , -1.0743900000000001e-01 , 1.6041500000000000e-01 , 9.8118499999999997e-01 -6.9015318095873179e-01 , 4.3831066805293810e+00 , 5.5279839999999991e-01 , -9.5184099999999994e-02 , 1.3257900000000000e-01 , 9.8659200000000002e-01 -6.1514751843916682e-01 , 4.4668441296750991e+00 , 5.3606480000000012e-01 , -1.2661300000000000e-01 , 1.2650500000000001e-01 , 9.8385199999999995e-01 -5.4088033994329199e-01 , 4.5532674311764652e+00 , 5.2228479999999999e-01 , -8.1039200000000006e-02 , 1.2392400000000001e-01 , 9.8897699999999999e-01 -4.3836422740538050e-01 , 4.6687701889337241e+00 , 4.7811599999999999e-01 , -4.2567300000000002e-02 , 1.4760799999999999e-01 , 9.8812999999999995e-01 -3.5578643845702729e-01 , 4.7631016639797696e+00 , 4.6493919999999989e-01 , 1.7947999999999999e-02 , 1.0924499999999999e-01 , 9.9385299999999999e-01 -2.7814576049838746e-01 , 4.8518654076216574e+00 , 4.6203759999999994e-01 , 4.6565400000000000e-02 , 1.4639900000000000e-01 , 9.8812900000000004e-01 -1.8289841883965186e-01 , 4.9604797372798757e+00 , 4.4323439999999992e-01 , 4.2092400000000002e-02 , 1.5629000000000001e-01 , 9.8681399999999997e-01 -8.7130691886025513e-02 , 5.0699860628713029e+00 , 4.2877839999999989e-01 , 3.9685600000000001e-02 , 1.3562399999999999e-01 , 9.8996499999999998e-01 --2.1043309700256252e-02 , 5.1933192590319930e+00 , 4.0648079999999998e-01 , 1.4959699999999999e-02 , 1.3855300000000001e-01 , 9.9024199999999996e-01 --1.3526191495018702e-01 , 5.3241710491349963e+00 , 3.8330959999999981e-01 , -9.7925600000000002e-02 , -2.4699900000000000e-02 , -9.9488699999999997e-01 --2.5215405515451295e-01 , 5.4572186600612067e+00 , 3.6524479999999993e-01 , 1.2522600000000000e-01 , 3.5767599999999997e-02 , 9.9148300000000000e-01 --2.7019048588182049e-01 , 5.4799745777526336e+00 , 4.4800799999999996e-01 , 1.2696399999999999e-01 , -6.4271900000000007e-02 , 9.8982300000000001e-01 --5.1643944035258516e-01 , 5.7596089324002255e+00 , 3.1824719999999984e-01 , -2.9180299999999998e-01 , -2.9853000000000002e-01 , 9.0869800000000001e-01 --7.4301879645472724e-01 , 6.0174869548381595e+00 , 2.2170399999999990e-01 , -5.1608299999999996e-01 , 8.0748199999999999e-03 , 8.5650000000000004e-01 --9.3667282773496563e-01 , 6.2378422736324017e+00 , 1.6736399999999985e-01 , -1.3248500000000000e-02 , 1.6801400000000000e-01 , 9.8569600000000002e-01 --1.1380429371829011e+00 , 6.4668948096430876e+00 , 1.1758960000000007e-01 , 2.4868100000000001e-02 , 1.7346700000000001e-01 , 9.8452600000000001e-01 --1.3537585790876969e+00 , 6.7135302150796985e+00 , 6.7731999999999903e-02 , 2.4026300000000000e-02 , 1.7950900000000000e-01 , 9.8346299999999998e-01 --1.5962510816475666e+00 , 6.9894479771048568e+00 , 9.9495999999998919e-03 , 2.7376500000000002e-02 , 2.3061899999999999e-01 , 9.7265900000000005e-01 --1.9771582161792729e+00 , 7.4236566769106123e+00 , -1.3500560000000039e-01 , -2.5666899999999999e-02 , 2.8372399999999998e-01 , 9.5856200000000003e-01 --2.4685761140637652e+00 , 7.9833034881453298e+00 , -3.3439440000000031e-01 , -6.2203000000000001e-02 , 2.5823099999999999e-01 , 9.6407900000000002e-01 --3.0421960938234003e+00 , 8.6359466013299198e+00 , -5.5883680000000036e-01 , -6.8355200000000005e-02 , 2.5227699999999997e-01 , 9.6523800000000004e-01 --3.7674247123408557e+00 , 9.4608767988952067e+00 , -8.4592880000000026e-01 , -8.9746500000000007e-02 , 2.3777100000000001e-01 , 9.6716599999999997e-01 --4.6274846596390971e+00 , 1.0441863690565707e+01 , -1.1724784000000001e+00 , -9.6096600000000004e-02 , 2.0619499999999999e-01 , 9.7378100000000001e-01 --5.5998054914956557e+00 , 1.1549122417220037e+01 , -1.5131200000000002e+00 , -9.8529699999999998e-02 , 2.1166800000000000e-01 , 9.7236199999999995e-01 --6.5822137411037698e+00 , 1.2667929685291604e+01 , -1.8035608000000001e+00 , -3.9025400000000002e-02 , 1.7162100000000000e-01 , 9.8438999999999999e-01 --8.3794183726954294e+00 , 1.4715087096739321e+01 , -2.4559008000000002e+00 , 1.4621600000000001e-01 , 3.3678100000000000e-01 , 9.3016100000000002e-01 --1.0238568443955938e+01 , 1.6833624700652415e+01 , -3.0360959999999997e+00 , -7.9077099999999997e-02 , -2.7740299999999999e-02 , 9.9648199999999998e-01 --1.0830999250494605e+01 , 1.7512686902312748e+01 , -2.9384192000000002e+00 , -1.3636900000000000e-02 , -2.2979900000000000e-01 , 9.7314199999999995e-01 --1.1344766806188352e+01 , 1.8103489768788933e+01 , -2.7772191999999993e+00 , -5.9366799999999997e-03 , -2.5230900000000001e-01 , 9.6762800000000004e-01 --1.1851600789704984e+01 , 1.8686890575017806e+01 , -2.5879080000000005e+00 , -6.7349500000000000e-03 , -2.6571499999999998e-01 , 9.6402800000000000e-01 --1.2384877076024303e+01 , 1.9301116557903612e+01 , -2.3831736000000001e+00 , 2.0226200000000000e-02 , -3.1067200000000000e-01 , 9.5030199999999998e-01 --1.4866164155656072e+01 , 2.2133655100840045e+01 , -2.8148256000000007e+00 , -9.4621999999999995e-01 , -1.0089300000000000e-01 , -3.0739000000000000e-01 --1.5062506240326357e+01 , 2.2364130105843468e+01 , -2.3978896000000001e+00 , -9.5397699999999996e-01 , -8.0861199999999994e-02 , -2.8877399999999998e-01 --1.4849731822830012e+01 , 2.2128496880420791e+01 , -1.8566736000000001e+00 , -9.7897999999999996e-01 , -4.0152199999999999e-02 , -1.9996300000000000e-01 --1.5169924568519516e+01 , 2.2501952653491472e+01 , -1.4678488000000001e+00 , 9.8856800000000000e-01 , 3.1385600000000000e-02 , 1.4747099999999999e-01 --1.7005012289331816e+01 , 2.4602871506465075e+01 , -1.4138312000000002e+00 , -7.3276099999999997e-02 , 9.6997000000000000e-01 , -2.3192599999999999e-01 --1.5080257049376264e+01 , 2.2413483343407719e+01 , -4.9624960000000007e-01 , 9.8856800000000000e-01 , 3.1385600000000000e-02 , 1.4747099999999999e-01 --1.7197329669282425e+01 , 2.4838619199579838e+01 , -4.0027839999999992e-01 , -7.9017400000000002e-02 , 9.7080699999999998e-01 , -2.2647200000000001e-01 --1.7271913384787467e+01 , 2.4930676724234065e+01 , 1.1454239999999993e-01 , 8.2910499999999998e-02 , -9.7148000000000001e-01 , 2.2215499999999999e-01 --1.7339546733663155e+01 , 2.5016715091163356e+01 , 6.3237919999999992e-01 , 6.7619399999999996e-02 , -9.7357199999999999e-01 , 2.1814200000000000e-01 --1.7421827396027869e+01 , 2.5119521735271721e+01 , 1.1511540800000000e+00 , 6.8018899999999993e-02 , -9.7460599999999997e-01 , 2.1334600000000001e-01 --1.0433155833894401e+00 , 6.4005256654599023e+00 , 2.8335745599999997e+00 , 1.1669100000000000e-01 , 9.8223099999999997e-01 , -1.4698700000000001e-01 --1.0379128707761915e+00 , 6.3966971023954287e+00 , 2.9264008000000001e+00 , 1.3149300000000000e-01 , 9.8372400000000004e-01 , -1.2245900000000000e-01 --1.0448169808400829e+00 , 6.4061001014183834e+00 , 3.0190013599999999e+00 , 1.2960099999999999e-01 , 9.7093300000000005e-01 , -2.0122799999999999e-01 --1.0784431430621755e+00 , 6.4464519650042629e+00 , 3.1119991999999996e+00 , 4.9482400000000003e-02 , 9.7731500000000004e-01 , 2.0593100000000000e-01 --8.0394856418397627e+00 , 1.4417366718917364e+01 , 3.4538888000000001e+00 , -3.2125999999999999e-01 , 5.5333699999999997e-01 , 7.6851199999999997e-01 --9.3136644057680140e-01 , 6.2796131260532899e+00 , 3.2902551999999998e+00 , -3.0446700000000000e-02 , 9.7085200000000005e-01 , 2.3773700000000000e-01 --9.4113238800617172e-01 , 6.2930307918088078e+00 , 3.3811616000000004e+00 , 1.6473599999999999e-01 , -9.8583600000000005e-01 , -3.1442299999999999e-02 --9.7077977607093358e-01 , 6.3280981780766412e+00 , 3.4750736000000000e+00 , -4.4737199999999996e-03 , -9.9106499999999997e-01 , 1.3330200000000000e-01 --9.9859081108680181e-01 , 6.3613306145468442e+00 , 3.5708679999999999e+00 , 2.7759699999999998e-01 , 9.5332300000000003e-01 , -1.1880300000000001e-01 --1.0119021968370498e+00 , 6.3788896623606659e+00 , 3.6657367999999999e+00 , 2.7759699999999998e-01 , 9.5332300000000003e-01 , -1.1880300000000001e-01 --2.0276989228740367e+00 , 7.5454613729609443e+00 , 3.9583095999999998e+00 , 6.9626500000000002e-01 , -6.6260799999999997e-01 , 2.7598200000000001e-01 --2.0225430336216137e+00 , 7.5408611926930913e+00 , 4.0788456000000002e+00 , 7.8756000000000004e-01 , -5.7962300000000000e-01 , 2.0925299999999999e-01 --2.0163038241359876e+00 , 7.5361516550645709e+00 , 4.1991111999999999e+00 , 5.8806599999999998e-01 , -7.8469699999999998e-01 , 1.9603400000000001e-01 --2.0292749783477131e+00 , 7.5515088050923458e+00 , 4.3252527999999995e+00 , 6.7394799999999999e-01 , -6.9393800000000005e-01 , 2.5346500000000000e-01 --2.0264438792956012e+00 , 7.5506819761153929e+00 , 4.4482640000000000e+00 , 5.7886700000000002e-01 , -7.5129900000000005e-01 , 3.1695800000000002e-01 --2.0557688247177985e+00 , 7.5864620277059798e+00 , 4.5826943999999994e+00 , -5.8176600000000001e-01 , 7.5978599999999996e-01 , -2.9029899999999997e-01 --2.0897212967406249e+00 , 7.6275860554155708e+00 , 4.7215655999999999e+00 , 4.7735300000000003e-01 , -8.4816899999999995e-01 , 2.2965800000000000e-01 --2.1229207359477620e+00 , 7.6669844906882014e+00 , 4.8626000000000005e+00 , 2.9340699999999997e-01 , -9.1559299999999999e-01 , 2.7495799999999998e-01 --2.1597913786044849e+00 , 7.7118252546638546e+00 , 5.0088032000000000e+00 , 2.0894499999999999e-01 , -9.2822499999999997e-01 , 3.0780000000000002e-01 --2.2014124126219174e+00 , 7.7621973193183784e+00 , 5.1603727999999993e+00 , 1.6535100000000000e-01 , -9.3335800000000002e-01 , 3.1859399999999999e-01 --2.2402913140322527e+00 , 7.8098781154309167e+00 , 5.3149480000000002e+00 , 3.0702600000000002e-01 , -9.0274299999999996e-01 , 3.0131300000000000e-01 --6.1533986049622200e+00 , 1.2320843485681328e+01 , 7.4326688000000001e+00 , -9.9602099999999999e-02 , -5.9334200000000004e-01 , 7.9876499999999995e-01 --3.0073953824959032e-01 , 5.5769684375157720e+00 , 4.5541359999999997e+00 , -6.1555000000000004e-01 , 3.1087599999999999e-01 , 7.2419299999999998e-01 --2.4424684105151639e-01 , 5.5137467798715214e+00 , 4.6055016000000002e+00 , -5.9607699999999997e-01 , 3.4133300000000000e-01 , 7.2676300000000005e-01 --1.8744684384044641e-01 , 5.4500037812045123e+00 , 4.6543296000000005e+00 , 3.8012699999999999e-01 , -3.9322000000000001e-01 , -8.3718700000000001e-01 --1.3036406432327974e-01 , 5.3857556945774796e+00 , 4.7007344000000000e+00 , -7.7308100000000002e-01 , 1.2758300000000000e-01 , 6.2134400000000001e-01 --8.6252019148627568e-02 , 5.3359204174550499e+00 , 4.7526823999999994e+00 , -7.8764400000000001e-01 , 1.7008300000000001e-01 , 5.9218999999999999e-01 --5.4264156864493263e-02 , 5.2996720710572998e+00 , 4.8115047999999998e+00 , 3.2677899999999999e-01 , -6.6935900000000004e-01 , -6.6721399999999997e-01 --2.1116382745037132e-02 , 5.2620989564027294e+00 , 4.8692560000000000e+00 , -5.5537700000000001e-01 , 5.3249400000000002e-01 , 6.3875400000000004e-01 -6.5136421835281233e-03 , 5.2318010540877689e+00 , 4.9302936000000006e+00 , -5.2312000000000003e-01 , 5.3602600000000000e-01 , 6.6258700000000004e-01 -4.6664138583967452e-02 , 5.1861183129747594e+00 , 4.9809104000000000e+00 , -4.8893300000000001e-01 , 5.6281999999999999e-01 , 6.6646700000000003e-01 -8.8027018460812512e-02 , 5.1401083118639832e+00 , 5.0301439999999999e+00 , -3.8741999999999999e-01 , 6.1031800000000003e-01 , 6.9095399999999996e-01 -1.1709767136975602e-01 , 5.1079907460245897e+00 , 5.0877704000000001e+00 , -2.9346000000000000e-01 , 6.8206800000000001e-01 , 6.6982399999999997e-01 -1.5881096441585907e-01 , 5.0613514165966285e+00 , 5.1339672000000007e+00 , -6.5834400000000004e-01 , 4.5366800000000002e-01 , 6.0063999999999995e-01 -1.8812418684326482e-01 , 5.0277231280067891e+00 , 5.1893784000000007e+00 , -4.1612600000000000e-01 , 6.4693999999999996e-01 , 6.3898999999999995e-01 -2.2537593120508359e-01 , 4.9861324628435391e+00 , 5.2385912000000001e+00 , -4.3451299999999998e-01 , 6.0250000000000004e-01 , 6.6947199999999996e-01 -2.5598969146966755e-01 , 4.9520037765977634e+00 , 5.2917976000000007e+00 , -3.8634499999999999e-01 , 6.1871900000000002e-01 , 6.8405000000000005e-01 -2.8768430806054845e-01 , 4.9155792595912597e+00 , 5.3444320000000003e+00 , -1.2768800000000000e-01 , 7.6747799999999999e-01 , 6.2822999999999996e-01 -3.2059047392024831e-01 , 4.8799309119794287e+00 , 5.3958600000000008e+00 , -1.8649700000000000e-01 , 6.4072899999999999e-01 , 7.4477199999999999e-01 -3.5357942986518731e-01 , 4.8430365753942173e+00 , 5.4463936000000004e+00 , -1.1123100000000000e-01 , 6.5398400000000001e-01 , 7.4828600000000001e-01 -3.8669339959892324e-01 , 4.8059129037828745e+00 , 5.4958039999999997e+00 , 5.1565799999999995e-01 , -5.3063800000000005e-01 , -6.7269599999999996e-01 -4.1017639360856206e-01 , 4.7801119532487402e+00 , 5.5572472000000008e+00 , -2.7931000000000000e-01 , 7.5827500000000003e-01 , 5.8907100000000001e-01 -4.3374236276509359e-01 , 4.7541686497497668e+00 , 5.6179728000000004e+00 , -2.1534800000000001e-01 , 7.4123499999999998e-01 , 6.3576400000000000e-01 -4.5347093787148163e-01 , 4.7328699567241852e+00 , 5.6851047999999995e+00 , -4.0798499999999999e-01 , -8.8011899999999998e-01 , -2.4277399999999999e-01 -4.1803150946519740e-01 , 4.7748067734711608e+00 , 5.8276992000000005e+00 , 5.7471399999999995e-01 , 7.9056199999999999e-01 , 2.1146100000000001e-01 -4.9505414563972328e-01 , 4.6868409491441714e+00 , 5.8185992000000004e+00 , 5.5212600000000001e-01 , 6.5299900000000000e-01 , 5.1841099999999996e-01 --1.3774882776096664e-01 , 5.4262166947649373e+00 , 6.8342216000000002e+00 , -7.7739000000000003e-01 , -5.8550100000000005e-01 , -2.2989999999999999e-01 -6.1335727491418246e-01 , 4.5516068747734089e+00 , 5.8419784000000003e+00 , 4.0067000000000003e-01 , 7.3465100000000005e-01 , 5.4749499999999995e-01 --6.2244383489316490e-02 , 5.3424424038740606e+00 , 6.9931960000000002e+00 , 2.6173300000000000e-02 , 9.7466600000000003e-01 , 2.2212799999999999e-01 --7.8577285851957335e-03 , 5.2804492280636532e+00 , 7.0449047999999994e+00 , -1.1011300000000001e-03 , 9.2548699999999995e-01 , 3.7877699999999997e-01 --3.1982204682738526e+00 , 9.0165341556589418e+00 , 1.2517416000000001e+01 , -2.7804699999999999e-01 , 8.8968199999999997e-01 , -3.6215500000000000e-01 -6.4738583020815366e-01 , 4.5188601508084751e+00 , 6.2031808000000002e+00 , 2.4173099999999999e-02 , 9.9206499999999997e-01 , 1.2338100000000000e-01 --1.6602187251961538e+00 , 7.2248650357825168e+00 , 1.0456312799999999e+01 , 2.6406200000000001e-02 , -7.0113300000000001e-01 , 7.1254099999999998e-01 -8.7957280525761994e-01 , 4.2485679328745789e+00 , 6.0021279999999999e+00 , -2.8721999999999998e-01 , -7.3952199999999996e-02 , 9.5500600000000002e-01 --5.0443985811547964e-02 , 5.3427546042048100e+00 , 7.9037056000000003e+00 , 1.8991000000000000e-01 , 9.8043199999999997e-01 , 5.1831799999999997e-02 --1.0940192285876282e-02 , 5.2994769241620769e+00 , 8.0030359999999998e+00 , -1.8991000000000000e-01 , -9.8043199999999997e-01 , -5.1831799999999997e-02 -7.1441033821895861e-01 , 4.4492735661941474e+00 , 6.6837336000000001e+00 , 2.2173100000000001e-02 , -9.9557200000000001e-01 , 9.1354699999999997e-02 -7.6015954527583962e-01 , 4.3965548664468184e+00 , 6.7217144000000006e+00 , 1.8257799999999999e-01 , 5.1986100000000000e-02 , 9.8181600000000002e-01 -7.4163161958939128e-01 , 4.4212485657832037e+00 , 6.9035376000000008e+00 , 1.5037200000000001e-01 , 9.6056900000000001e-01 , -2.3386999999999999e-01 -4.7634648861016249e-01 , 4.7362973466921412e+00 , 7.6675215999999997e+00 , -5.5114799999999997e-01 , -7.9794900000000002e-01 , -2.4395400000000000e-01 -7.2640457111573853e-01 , 4.4444678582111532e+00 , 7.2474656000000000e+00 , -1.5920100000000001e-01 , -1.8046000000000001e-01 , 9.7061299999999995e-01 -8.4871177951315357e-01 , 4.3016729584355353e+00 , 7.1076168000000006e+00 , -9.1845699999999997e-01 , -1.7721400000000001e-01 , -3.5359900000000000e-01 -9.6758340139099164e-01 , 4.1643044801352636e+00 , 6.9624015999999997e+00 , 5.6336100000000000e-01 , -6.7269599999999996e-01 , -4.7969299999999998e-01 -1.0090065369395416e+00 , 4.1170863681952881e+00 , 7.0109176000000009e+00 , -6.8903999999999999e-01 , 2.5419100000000000e-01 , 6.7868300000000004e-01 -1.0515506863569066e+00 , 4.0685992721342439e+00 , 7.0586639999999994e+00 , 7.4911300000000003e-01 , -1.2909000000000001e-01 , -6.4974299999999996e-01 -1.0449165638553803e+00 , 4.0792773256041013e+00 , 7.2525824000000005e+00 , -9.1858399999999996e-01 , 3.0888100000000002e-01 , 2.4656700000000001e-01 -1.0601344360771963e+00 , 4.0642801041480423e+00 , 7.3921711999999999e+00 , 5.3484799999999999e-01 , -3.6404500000000001e-01 , 7.6250200000000001e-01 -1.2487419935394659e+00 , 3.8413631434887945e+00 , 6.9794992000000002e+00 , 1.4835400000000001e-01 , 5.6260699999999997e-01 , 8.1330400000000003e-01 -1.2803717470222331e+00 , 3.8071326750687193e+00 , 7.0588200000000008e+00 , -1.7265200000000000e-01 , 5.9406000000000003e-01 , 7.8567399999999998e-01 -1.3526398705756417e+00 , 3.7231480334976004e+00 , 6.9946728000000000e+00 , -5.0364799999999998e-01 , -5.3713400000000000e-01 , -6.7662800000000001e-01 -1.2984656241532986e+00 , 3.7909038780680939e+00 , 7.3984736000000000e+00 , 7.8048300000000004e-01 , -4.2915399999999998e-01 , -4.5461299999999999e-01 -1.4248588205708344e+00 , 3.6431645800199828e+00 , 7.1296024000000005e+00 , 5.0746800000000002e-02 , -3.0036499999999999e-01 , 9.5247300000000001e-01 -1.4947094943523536e+00 , 3.5613321665926234e+00 , 7.0598184000000002e+00 , 1.3910700000000001e-01 , 8.4791499999999997e-01 , 5.1155600000000001e-01 -1.5628428706974253e+00 , 3.4822183701732987e+00 , 6.9873304000000003e+00 , -6.1350099999999996e-01 , -2.1308199999999999e-01 , 7.6040300000000005e-01 -1.6082531301148266e+00 , 3.4308953526481947e+00 , 7.0110944000000002e+00 , 7.6900400000000002e-01 , 3.5398099999999999e-01 , -5.3228799999999998e-01 -1.6616052565616213e+00 , 3.3699340158439925e+00 , 6.9939448000000004e+00 , -8.0663099999999999e-01 , -1.4801900000000001e-01 , 5.7222099999999998e-01 -1.6860484209884343e+00 , 3.3432241029945291e+00 , 7.1248496000000001e+00 , -9.2345100000000002e-01 , 3.1773400000000002e-01 , 2.1513800000000000e-01 -1.7079878620832925e+00 , 3.3205059464701936e+00 , 7.2855295999999994e+00 , -9.8163800000000001e-01 , 1.4876400000000001e-01 , -1.1940300000000000e-01 -1.7398490697054401e+00 , 3.2860571080272463e+00 , 7.4059720000000002e+00 , -5.7201700000000000e-01 , -8.1711000000000000e-01 , -7.1614700000000003e-02 -1.8581455854694378e+00 , 3.1443168288272738e+00 , 6.9806536000000001e+00 , -1.1543700000000000e-01 , -9.0881299999999998e-01 , 4.0091599999999999e-01 -1.7120452239722859e+00 , 3.3321521689099196e+00 , 8.3561368000000016e+00 , 3.9105000000000001e-01 , 1.3383000000000000e-01 , 9.1058799999999995e-01 -1.7983820039072191e+00 , 3.2318761959002105e+00 , 8.1825296000000005e+00 , 1.4585300000000001e-01 , -9.4486800000000004e-01 , 2.9317399999999999e-01 -2.8941213716573899e-01 , 5.0094488687913801e+00 , 4.1916880000000001e-01 , 7.0445400000000005e-02 , 1.5406100000000000e-01 , 9.8554699999999995e-01 -2.0679748046148139e-01 , 5.1089300710311889e+00 , 4.1570559999999990e-01 , 5.0025899999999998e-02 , 1.6024200000000000e-01 , 9.8580900000000005e-01 -1.0850919174402907e-01 , 5.2284626967774450e+00 , 3.9771360000000011e-01 , 4.3347499999999997e-02 , 1.4370600000000000e-01 , 9.8867099999999997e-01 -8.6192636595230354e-03 , 5.3489864831251701e+00 , 3.8434959999999996e-01 , 2.9387300000000002e-02 , 1.6113800000000000e-01 , 9.8649399999999998e-01 --1.0816164644425141e-01 , 5.4910127677543699e+00 , 3.5814159999999995e-01 , 1.2980800000000001e-01 , 7.5728699999999996e-02 , 9.8864300000000005e-01 --2.2661472714686903e-01 , 5.6352680754270477e+00 , 3.3736239999999995e-01 , 3.7318600000000002e-01 , -2.2048499999999999e-01 , 9.0117599999999998e-01 --2.7886188896536357e-01 , 5.6988516040714394e+00 , 3.8884239999999992e-01 , 3.6457899999999999e-01 , -2.3620600000000000e-01 , 9.0071599999999996e-01 --3.3136441501442748e-01 , 5.7618103455282643e+00 , 4.4244400000000006e-01 , 2.6608700000000002e-01 , 6.6408999999999996e-01 , -6.9870100000000002e-01 --3.9962942353225417e-01 , 5.8460440479190581e+00 , 4.8231759999999979e-01 , 3.8127699999999998e-01 , 6.7935000000000001e-01 , -6.2698699999999996e-01 --4.5718867969631916e-01 , 5.9154694753698109e+00 , 5.3527439999999982e-01 , 4.0124399999999999e-01 , 8.0346600000000001e-01 , -4.3982599999999999e-01 --5.3173436456420564e-01 , 6.0054548505143179e+00 , 5.7600080000000009e-01 , 4.4146900000000000e-01 , 8.6129599999999995e-01 , -2.5154500000000002e-01 --4.6441950836848234e-01 , 5.9250184757318287e+00 , 7.3395600000000005e-01 , 4.2775000000000002e-01 , 8.8926000000000005e-01 , -1.6200999999999999e-01 --4.7710389712649670e-01 , 5.9414736853456729e+00 , 8.2345840000000003e-01 , 2.2478799999999999e-01 , 9.6958400000000000e-01 , -9.6836500000000006e-02 --2.1105821440114143e+00 , 7.9148665277821140e+00 , -2.8147920000000015e-01 , -6.3031900000000002e-02 , 2.5631199999999998e-01 , 9.6453699999999998e-01 --2.6122793090606882e+00 , 8.5221340067617817e+00 , -4.8389440000000006e-01 , -6.9396500000000000e-02 , 2.4396599999999999e-01 , 9.6729799999999999e-01 --3.2426752272258117e+00 , 9.2841014911005502e+00 , -7.4178319999999998e-01 , 7.4437699999999996e-02 , -2.3388000000000000e-01 , -9.6941200000000005e-01 --3.9276260267319234e+00 , 1.0114702698650802e+01 , -9.9739440000000013e-01 , -8.5656200000000002e-02 , 2.1463099999999999e-01 , 9.7293200000000002e-01 --4.6946292164445937e+00 , 1.1042691888513200e+01 , -1.2614087999999999e+00 , 9.0014899999999995e-02 , -2.1458600000000000e-01 , -9.7254799999999997e-01 --5.9366820223660692e+00 , 1.2545063904380440e+01 , -1.7537344000000004e+00 , -8.7178300000000000e-02 , 2.0868400000000001e-01 , 9.7409000000000001e-01 --7.4775440288926678e+00 , 1.4410624895495065e+01 , -2.3358743999999998e+00 , 2.4867899999999998e-02 , 3.2597700000000002e-01 , 9.4505099999999997e-01 --8.9774624038741120e+00 , 1.6225909959203676e+01 , -2.8057359999999996e+00 , -4.3091600000000001e-02 , 1.4941599999999999e-01 , 9.8783500000000002e-01 --1.0047229183224294e+01 , 1.7521624126537951e+01 , -2.9799983999999995e+00 , -5.5681200000000000e-02 , -1.0363799999999999e-01 , 9.9305500000000002e-01 --1.0512173217163069e+01 , 1.8086881520724866e+01 , -2.8191936000000002e+00 , -1.9507199999999999e-02 , -2.3546200000000000e-01 , 9.7168800000000000e-01 --1.1015920113361222e+01 , 1.8698816418620517e+01 , -2.6509216000000002e+00 , -2.3645299999999999e-04 , -2.5541599999999998e-01 , 9.6683100000000000e-01 --1.1525501152084177e+01 , 1.9318906818386708e+01 , -2.4593639999999999e+00 , 3.0490900000000000e-03 , -2.5682100000000002e-01 , 9.6645400000000004e-01 --1.5247208390685373e+01 , 2.3826521926763139e+01 , -3.4213952000000001e+00 , -4.6553699999999998e-01 , -6.6216700000000003e-02 , -8.8254800000000000e-01 --1.5541869684745961e+01 , 2.4186052438122800e+01 , -3.0121343999999999e+00 , -9.2942300000000000e-01 , -1.8331600000000001e-01 , -3.2026300000000002e-01 --1.5546423415185323e+01 , 2.4195953105730876e+01 , -2.5000903999999995e+00 , -9.4898899999999997e-01 , -1.9678300000000001e-01 , -2.4636800000000000e-01 --1.6001844352969609e+01 , 2.4750194867812805e+01 , -2.1179215999999998e+00 , -1.0026500000000001e-02 , -9.1640699999999997e-01 , 4.0012100000000000e-01 --1.6080670493630056e+01 , 2.4850093859982799e+01 , -1.6180560000000002e+00 , 2.1001100000000002e-02 , -9.2926500000000001e-01 , 3.6881599999999998e-01 --1.6147832768850236e+01 , 2.4935378796350530e+01 , -1.1138015999999999e+00 , 3.1900800000000000e-02 , -9.4318999999999997e-01 , 3.3072000000000001e-01 --1.6249162938230931e+01 , 2.5061489415622979e+01 , -6.1503840000000043e-01 , 7.3778700000000003e-02 , -9.7109699999999999e-01 , 2.2699700000000000e-01 --1.6311701266721400e+01 , 2.5141238642764176e+01 , -1.0619759999999978e-01 , 9.4154399999999999e-02 , -9.6810300000000005e-01 , 2.3218700000000000e-01 --8.5897909953194791e+00 , 1.5786652473612932e+01 , 1.5106051199999999e+00 , 5.0132500000000002e-01 , -6.9059000000000004e-01 , -5.2130399999999999e-01 --8.9147028472941212e+00 , 1.6182603104493104e+01 , 1.7781368000000000e+00 , 5.0132500000000002e-01 , -6.9059000000000004e-01 , -5.2130399999999999e-01 --8.5872743740425772e-01 , 6.4181636543745473e+00 , 2.7918279200000002e+00 , 3.5676000000000002e-01 , 9.2782399999999998e-01 , -1.0892400000000001e-01 --8.4096829212555768e-01 , 6.3977178979891729e+00 , 2.8838783200000000e+00 , 3.4131800000000001e-01 , 9.3747100000000005e-01 , -6.8190500000000001e-02 --8.5573903388750150e-01 , 6.4164561215282916e+00 , 2.9737280799999999e+00 , 2.9982399999999998e-01 , 9.4596499999999994e-01 , -1.2351500000000000e-01 --8.6242799250845792e-01 , 6.4254782729483866e+00 , 3.0645024000000003e+00 , 2.2934499999999999e-01 , 9.4763699999999995e-01 , -2.2222700000000001e-01 --9.0206390988209861e-01 , 6.4732815139517950e+00 , 3.1563240000000001e+00 , 8.9960999999999999e-02 , 9.8757300000000003e-01 , 1.2886900000000001e-01 --8.7390645590626015e-01 , 6.4393871049261380e+00 , 3.2470328000000004e+00 , -1.9373199999999999e-01 , -8.8680400000000004e-01 , -4.1957899999999998e-01 --8.2433340914751119e-01 , 6.3821377738668597e+00 , 3.6059264000000000e+00 , -1.4438200000000001e-01 , 9.8600399999999999e-01 , -8.3361599999999994e-02 --8.5011223121570856e-01 , 6.4142965469376128e+00 , 3.7020743999999999e+00 , 1.7462000000000000e-01 , -9.8084499999999997e-01 , 8.6324100000000001e-02 --4.1633996670394291e+00 , 1.0438248686066730e+01 , 4.5109551999999997e+00 , -1.8588499999999999e-01 , -8.3892800000000003e-02 , 9.7898300000000005e-01 --2.2576438644196077e+00 , 8.1252899327666910e+00 , 4.2310288000000007e+00 , -9.4484400000000002e-01 , -1.9756000000000001e-01 , 2.6122800000000002e-01 --2.2178136008570624e+00 , 8.0780460523615165e+00 , 4.3529168000000000e+00 , -9.5044700000000004e-01 , -1.0314600000000000e-01 , 2.9327599999999998e-01 --2.0981378114036744e+00 , 7.9341977728829338e+00 , 4.4497511999999997e+00 , -9.6846600000000005e-01 , -3.9472199999999999e-02 , 2.4599900000000000e-01 --1.9979857570926383e+00 , 7.8124855738453727e+00 , 4.5468872000000005e+00 , -9.5940999999999999e-01 , 2.8199800000000003e-01 , 3.1246199999999998e-03 --1.9807037458397754e+00 , 7.7927707964756951e+00 , 4.6687647999999999e+00 , -8.1168300000000004e-01 , 5.8350900000000006e-01 , 2.6243699999999998e-02 --1.9816848739849728e+00 , 7.7943652595084130e+00 , 4.7976728000000000e+00 , -8.5412699999999997e-01 , 4.9277300000000002e-01 , -1.6625999999999999e-01 --1.9861527703268433e+00 , 7.8010680347812604e+00 , 4.9301376000000001e+00 , -6.5748399999999996e-01 , 7.0609000000000000e-01 , -2.6296799999999998e-01 --2.0026330116991469e+00 , 7.8222717794503192e+00 , 5.0687696000000004e+00 , 6.5804700000000005e-01 , -7.1079700000000001e-01 , 2.4847900000000001e-01 --2.0367675821191007e+00 , 7.8643988233381261e+00 , 5.2178952000000001e+00 , 5.8395300000000006e-01 , -7.6153099999999996e-01 , 2.8119300000000003e-01 --2.0681332979512232e+00 , 7.9037551233057100e+00 , 5.3696207999999999e+00 , 4.8880600000000002e-01 , -8.4443500000000005e-01 , 2.1908700000000000e-01 --2.0922137743601770e+00 , 7.9330322647931890e+00 , 5.5203375999999995e+00 , 4.8772300000000002e-01 , -8.2238199999999995e-01 , 2.9294100000000001e-01 --2.1628859432943424e+00 , 8.0213409669250897e+00 , 5.7011520000000004e+00 , -2.6197399999999998e-01 , 8.4314000000000000e-01 , -4.6955700000000000e-01 --2.2564148909738009e+00 , 8.1358216247613093e+00 , 5.9015599999999999e+00 , 2.6197399999999998e-01 , -8.4314000000000000e-01 , 4.6955700000000000e-01 --2.3099730706091401e+00 , 8.2015800474545912e+00 , 6.0847768000000002e+00 , 2.6197399999999998e-01 , -8.4314000000000000e-01 , 4.6955700000000000e-01 --6.0852669038996776e-01 , 6.1310746020715872e+00 , 5.1094856000000002e+00 , 6.0019500000000003e-01 , 6.5078400000000003e-01 , -4.6502199999999999e-01 --9.6351995367557564e-02 , 5.5073502450629004e+00 , 4.8530215999999999e+00 , -9.1459999999999997e-01 , -3.6087399999999999e-02 , 4.0274500000000002e-01 --1.0518750741903116e-01 , 5.5198423093882329e+00 , 4.9447600000000005e+00 , 8.0417899999999998e-01 , 3.2818500000000000e-01 , -4.9557200000000001e-01 --2.2687625146095103e-01 , 5.6683336281886945e+00 , 5.1234840000000004e+00 , -8.9215100000000003e-01 , -2.9019299999999998e-01 , -3.4620000000000001e-01 --2.7974628348043584e-01 , 5.7337858613021533e+00 , 5.2578832000000002e+00 , -9.5194599999999996e-01 , -2.5921100000000002e-01 , -1.6312399999999999e-01 --3.0147126456073137e-01 , 5.7608133236665857e+00 , 5.3716071999999997e+00 , -9.5388200000000001e-01 , 3.0011300000000002e-01 , -6.4050899999999996e-03 --2.4126311820029045e-01 , 5.6876908547706320e+00 , 5.4167952000000001e+00 , -9.5388200000000001e-01 , 3.0011300000000002e-01 , -6.4050799999999996e-03 --2.5435521465468680e-01 , 5.7040634179428658e+00 , 5.5268896000000005e+00 , -9.5014799999999999e-01 , 5.5666599999999997e-02 , 3.0679099999999998e-01 --3.0584068126746411e-01 , 5.7680772494731265e+00 , 5.6755367999999997e+00 , -8.5474200000000000e-01 , 4.7980699999999998e-01 , 1.9799300000000000e-01 -2.0554118248999731e-01 , 5.1449137612417104e+00 , 5.2793592000000000e+00 , 6.7776000000000003e-01 , -3.0568400000000001e-01 , -6.6873000000000005e-01 -2.6954668964376349e-01 , 5.0680299347443958e+00 , 5.3013968000000000e+00 , 5.1084499999999999e-01 , -4.0741699999999997e-01 , -7.5699899999999998e-01 -3.1642142410814533e-01 , 5.0107429818555076e+00 , 5.3379944000000004e+00 , -4.8430499999999999e-01 , 3.4246100000000002e-01 , 8.0508999999999997e-01 -3.4710853310547152e-01 , 4.9742946288567254e+00 , 5.3902960000000002e+00 , -2.2372300000000001e-01 , 5.8167999999999997e-01 , 7.8204700000000005e-01 -3.8371603579725999e-01 , 4.9298568193008947e+00 , 5.4357544000000004e+00 , -5.9807100000000002e-01 , 3.6902299999999999e-01 , 7.1143100000000004e-01 -4.2635276748099016e-01 , 4.8783217601619979e+00 , 5.4736624000000003e+00 , 5.2790599999999999e-01 , -4.3171900000000002e-01 , -7.3139200000000004e-01 -4.6432739198131934e-01 , 4.8332697119015808e+00 , 5.5164168000000000e+00 , 4.3379800000000002e-01 , -5.6302799999999997e-01 , -7.0343299999999997e-01 -4.9654202374378431e-01 , 4.7937459269447826e+00 , 5.5642880000000003e+00 , -2.7417700000000000e-01 , 6.2478900000000004e-01 , 7.3107100000000003e-01 -5.2502294516226344e-01 , 4.7597791382040722e+00 , 5.6178480000000004e+00 , -9.7877000000000006e-02 , 6.7127700000000001e-01 , 7.3471600000000004e-01 -5.5852987774030405e-01 , 4.7197851204363594e+00 , 5.6636287999999997e+00 , 3.2845100000000002e-02 , 7.0875999999999995e-01 , 7.0468500000000001e-01 -5.8719604099672651e-01 , 4.6843914917649361e+00 , 5.7154728000000006e+00 , -3.1239699999999998e-01 , -7.9015400000000002e-01 , -5.2731899999999998e-01 -6.1206700628400545e-01 , 4.6546697334387712e+00 , 5.7735047999999995e+00 , 1.8406300000000000e-01 , 6.5196399999999999e-01 , 7.3556999999999995e-01 -6.4296720056322587e-01 , 4.6178507255295393e+00 , 5.8239863999999999e+00 , -9.6436700000000000e-02 , 6.0717100000000002e-01 , 7.8869699999999998e-01 -7.2062805401951624e-01 , 4.5236898059539170e+00 , 5.8000976000000000e+00 , -1.3822799999999999e-01 , 7.2831599999999996e-01 , 6.7115499999999995e-01 -7.0113201314665097e-01 , 4.5485056043461096e+00 , 5.9296192000000003e+00 , 6.4106700000000003e-02 , 9.4981599999999999e-01 , 3.0617000000000000e-01 -7.1042191486000861e-01 , 4.5377504355833160e+00 , 6.0152527999999998e+00 , 1.6486700000000001e-01 , 8.2375200000000004e-01 , 5.4244999999999999e-01 -7.9675355373118495e-01 , 4.4336532717929309e+00 , 5.9702728000000000e+00 , -1.2131699999999999e-01 , 2.7554400000000001e-01 , 9.5360299999999998e-01 -8.4129684099031610e-01 , 4.3787800456828494e+00 , 5.9919880000000001e+00 , -8.9625299999999997e-01 , 4.0679100000000001e-01 , 1.7678199999999999e-01 -8.0659086380288869e-01 , 4.4222025923748554e+00 , 6.1632239999999996e+00 , 3.6657499999999998e-01 , 9.2689800000000000e-01 , -8.0514900000000000e-02 -6.5862907639660806e-01 , 4.6046625749473034e+00 , 6.5629584000000003e+00 , 4.6727299999999999e-01 , 3.7108500000000000e-01 , 8.0246600000000001e-01 -4.0276324316460999e-02 , 5.3645720437401430e+00 , 7.9365071999999994e+00 , -1.8991000000000000e-01 , -9.8043199999999997e-01 , -5.1831799999999997e-02 -7.8903992840872084e-01 , 4.4461074657172528e+00 , 6.5521840000000005e+00 , -6.1298500000000000e-01 , -5.9728400000000004e-01 , -5.1720500000000003e-01 -7.8193683156612170e-01 , 4.4567328994777293e+00 , 6.6982728000000007e+00 , 1.9780699999999998e-02 , -9.6527200000000002e-01 , -2.6049600000000001e-01 -8.3689589044686019e-01 , 4.3887541294049992e+00 , 6.7099207999999999e+00 , 3.6561700000000003e-02 , -2.9284600000000000e-01 , 9.5545999999999998e-01 -6.4525714492197994e-01 , 4.6254989219712774e+00 , 7.2959711999999994e+00 , -1.5532499999999999e-01 , -8.0465500000000001e-01 , 5.7306599999999996e-01 -8.7255988126059991e-01 , 4.3479133745863638e+00 , 6.9100688000000003e+00 , 6.6838900000000007e-02 , 9.3654499999999996e-01 , 3.4411599999999998e-01 -9.3621121307795963e-01 , 4.2699708814632036e+00 , 6.9004176000000008e+00 , 7.0699699999999999e-01 , 5.0748199999999999e-01 , 4.9256200000000000e-01 -1.0333084318091363e+00 , 4.1519795499076153e+00 , 6.7992983999999996e+00 , -4.2421300000000001e-01 , 8.7875599999999998e-01 , 2.1870300000000001e-01 -1.0093447791162391e+00 , 4.1822141868456146e+00 , 7.0180312000000002e+00 , 5.7996099999999995e-01 , -3.8656400000000002e-01 , -7.1708700000000003e-01 -1.0465754475609046e+00 , 4.1369688851307878e+00 , 7.0754912000000001e+00 , 5.4709799999999997e-01 , -4.4901600000000003e-01 , -7.0644700000000005e-01 -1.0818030088432806e+00 , 4.0945434367841305e+00 , 7.1412087999999994e+00 , -8.3817100000000000e-01 , 4.3441900000000000e-01 , 3.2977200000000001e-01 -1.1160237033501548e+00 , 4.0549806168700142e+00 , 7.2156312000000007e+00 , 6.5868000000000004e-01 , -4.1649599999999998e-01 , -6.2663500000000005e-01 -1.2484890237640953e+00 , 3.8918969988245271e+00 , 6.9720320000000005e+00 , 1.4492700000000000e-01 , 8.2750500000000005e-01 , 5.4243200000000003e-01 -1.2895765048541810e+00 , 3.8423824263200062e+00 , 7.0143600000000008e+00 , 7.6568899999999995e-01 , 5.9592699999999998e-01 , 2.4205499999999999e-01 -1.3329652196963839e+00 , 3.7895247998796178e+00 , 7.0458927999999998e+00 , 4.8427999999999999e-01 , 7.2591000000000006e-01 , 4.8839300000000002e-01 -1.2853694723657867e+00 , 3.8511224362994962e+00 , 7.4205215999999998e+00 , 6.3588800000000001e-01 , -7.4430900000000000e-01 , 2.0408699999999999e-01 -1.4146730195626604e+00 , 3.6913135474442536e+00 , 7.1344903999999998e+00 , -1.9815900000000000e-01 , 3.0303799999999997e-01 , 9.3214900000000001e-01 -1.4930747519405880e+00 , 3.5961779899184796e+00 , 7.0268711999999995e+00 , -2.5095000000000001e-01 , -6.7807799999999996e-01 , -6.9082200000000005e-01 -1.5305307921431566e+00 , 3.5505433008372167e+00 , 7.0824072000000005e+00 , -5.0795199999999996e-01 , -7.5975599999999999e-01 , -4.0590199999999999e-01 -1.5625894066395474e+00 , 3.5129722446005145e+00 , 7.1663144000000001e+00 , -2.9283399999999998e-01 , -1.5319600000000000e-01 , -9.4381099999999996e-01 -1.6256078407647485e+00 , 3.4345618879961064e+00 , 7.1015328000000002e+00 , -7.5981299999999996e-01 , -5.9239799999999998e-01 , -2.6786199999999999e-01 -1.6666949141471377e+00 , 3.3850472328451437e+00 , 7.1438607999999997e+00 , -3.2675799999999999e-01 , 5.2344900000000005e-01 , 7.8691199999999994e-01 -1.6909475304710087e+00 , 3.3582774709349921e+00 , 7.2849159999999999e+00 , -9.3337000000000003e-01 , -1.5247800000000001e-02 , -3.5859300000000000e-01 -1.7717685351755690e+00 , 3.2580188279991269e+00 , 7.1049856000000000e+00 , 9.7218800000000005e-01 , -1.5844700000000000e-01 , -1.7246800000000001e-01 -1.8110718506346857e+00 , 3.2098404310541806e+00 , 7.1535640000000003e+00 , 7.1236600000000005e-01 , 5.8777100000000004e-01 , -3.8348300000000002e-01 -1.6833624711540716e+00 , 3.3746203212102701e+00 , 8.3657880000000002e+00 , 5.4660699999999995e-01 , -4.5290599999999998e-01 , 7.0434200000000002e-01 -1.7696137739483335e+00 , 3.2683208985494780e+00 , 8.1833616000000013e+00 , -9.1428699999999996e-01 , -2.7506000000000003e-01 , -2.9735699999999998e-01 -3.0127511635726911e-02 , 5.5273435796573640e+00 , 3.4662879999999996e-01 , 1.5279300000000001e-01 , 1.2655000000000000e-01 , 9.8012200000000005e-01 --8.3824680518415740e-02 , 5.6741560488255702e+00 , 3.2371759999999994e-01 , 1.1045600000000000e-01 , -2.5432500000000002e-01 , 9.6079000000000003e-01 --1.4030945013711493e-01 , 5.7460807631393749e+00 , 3.6826079999999983e-01 , -1.1795600000000001e-01 , -4.6807900000000002e-01 , 8.7577899999999997e-01 --1.7957114932190343e-01 , 5.7966445774939430e+00 , 4.3165920000000013e-01 , -1.0291500000000001e-01 , -7.4263299999999999e-01 , 6.6174299999999997e-01 --2.2895031400765431e-01 , 5.8616796229059167e+00 , 4.8563519999999993e-01 , 7.3646199999999995e-02 , 6.9108199999999997e-01 , -7.1901499999999996e-01 --2.4545286328218863e-01 , 5.8820511466683048e+00 , 5.7269360000000002e-01 , -3.0530600000000001e-02 , -8.3256399999999997e-01 , 5.5308800000000002e-01 --2.6095114783254347e-01 , 5.9013422505661168e+00 , 6.5988720000000001e-01 , 2.7097199999999999e-01 , -9.2035000000000000e-01 , 2.8201199999999998e-01 --2.6982480651061191e-01 , 5.9128184874086180e+00 , 7.5182320000000002e-01 , 3.7337300000000001e-01 , -9.0742199999999995e-01 , 1.9281699999999999e-01 --2.8887569465450857e-01 , 5.9366527588035805e+00 , 8.3445119999999995e-01 , 1.5847800000000001e-01 , -9.6087699999999998e-01 , 2.2715700000000000e-01 --2.9466700024862869e-01 , 5.9448063326258698e+00 , 9.2637679999999989e-01 , 3.3878799999999998e-01 , -9.3053799999999998e-01 , 1.3900000000000001e-01 --3.1167464854485782e-01 , 5.9664655773899824e+00 , 1.0091566400000000e+00 , 3.5046200000000000e-01 , -9.3293099999999995e-01 , 8.2561999999999997e-02 --3.1644982830721480e-01 , 5.9713339387238591e+00 , 1.1008055999999999e+00 , 5.9031599999999995e-01 , -7.8524300000000002e-01 , 1.8687100000000001e-01 --3.3142236328714558e-01 , 5.9908058980036731e+00 , 1.1837456000000000e+00 , 5.5693099999999995e-01 , -8.1289500000000003e-01 , 1.7037900000000000e-01 --3.4541115704050851e-01 , 6.0092463347199185e+00 , 1.2670152799999999e+00 , 5.3288800000000003e-01 , -8.2292200000000004e-01 , 1.9705300000000001e-01 --3.5273880799430835e-01 , 6.0175978290711880e+00 , 1.3543305600000000e+00 , 5.0822400000000001e-01 , -8.4128800000000004e-01 , 1.8423400000000001e-01 --3.6473063505796688e-01 , 6.0328351528203017e+00 , 1.4379611200000000e+00 , -4.7853000000000001e-01 , 8.5226000000000002e-01 , -2.1133500000000000e-01 --3.7572439588056739e-01 , 6.0470226347820679e+00 , 1.5218215200000000e+00 , -4.5190300000000000e-01 , 8.5462099999999996e-01 , -2.5574799999999998e-01 --3.8568730811104901e-01 , 6.0601032511241115e+00 , 1.6057100000000000e+00 , -4.3781300000000001e-01 , 8.6343700000000001e-01 , -2.5059100000000001e-01 --4.0720954577632451e-01 , 6.0883815253479643e+00 , 1.6834947200000001e+00 , 3.9800099999999999e-01 , -8.8260099999999997e-01 , 2.5022200000000000e-01 --4.2205424946650538e-01 , 6.1065423452906504e+00 , 1.7652231199999999e+00 , 3.6886700000000000e-01 , -8.9826700000000004e-01 , 2.3885999999999999e-01 --4.3005091119730299e-01 , 6.1164666798055292e+00 , 1.8496742399999999e+00 , -3.2042999999999999e-01 , 9.2661099999999996e-01 , -1.9676399999999999e-01 --4.4289741624432821e-01 , 6.1325176234811138e+00 , 1.9318616959999999e+00 , -3.0551200000000001e-01 , 9.3036799999999997e-01 , -2.0267900000000000e-01 --4.4788142191538016e-01 , 6.1392537280253530e+00 , 2.0169009359999999e+00 , -3.0512299999999998e-01 , 9.2860900000000002e-01 , -2.1115000000000000e-01 --4.6563920265867198e-01 , 6.1615249431415773e+00 , 2.0973300639999999e+00 , 3.0373899999999998e-01 , -9.2972600000000005e-01 , 2.0821400000000001e-01 --4.7553035170391134e-01 , 6.1744609337416385e+00 , 2.1805096800000001e+00 , -2.7178500000000000e-01 , 9.4091400000000003e-01 , -2.0202500000000001e-01 --4.8442550066913270e-01 , 6.1863572752467615e+00 , 2.2640206400000000e+00 , 2.1960099999999999e-01 , -9.4838000000000000e-01 , 2.2880400000000001e-01 --4.9927310472794195e-01 , 6.2056317172742981e+00 , 2.3459476800000001e+00 , 1.5545200000000001e-01 , -9.6062400000000003e-01 , 2.3029600000000000e-01 --5.1917743890175094e-01 , 6.2313728452957600e+00 , 2.4273318399999999e+00 , -1.0637400000000000e-01 , 9.6361699999999995e-01 , -2.4520700000000001e-01 --5.3217146452854891e-01 , 6.2476803962170395e+00 , 2.5107325600000001e+00 , 4.6219000000000003e-02 , -9.7482599999999997e-01 , 2.1812500000000001e-01 --5.4421246511879851e-01 , 6.2630032557147182e+00 , 2.5947687200000003e+00 , -5.7197799999999998e-03 , -9.7560700000000000e-01 , 2.1945200000000001e-01 --5.6236899835035281e-01 , 6.2848859055042547e+00 , 2.6784387999999999e+00 , 3.5587700000000000e-02 , 9.7202400000000000e-01 , -2.3216899999999999e-01 --5.7852280287080315e-01 , 6.3068349597343358e+00 , 2.7628649599999999e+00 , 5.7406400000000003e-02 , 9.7292500000000004e-01 , -2.2387599999999999e-01 --5.9482245955585311e-01 , 6.3268337624252347e+00 , 2.8481075200000001e+00 , 2.5074800000000003e-01 , 9.4529700000000005e-01 , -2.0865900000000001e-01 --6.0305273006615590e-01 , 6.3371776491515686e+00 , 2.9345824800000000e+00 , -2.6203399999999999e-01 , -9.4666799999999995e-01 , 1.8750200000000000e-01 --6.2358529318565292e-01 , 6.3629293786729795e+00 , 3.0211291999999998e+00 , -3.2338099999999997e-01 , -9.0123699999999995e-01 , 2.8843800000000003e-01 --6.4323039597072240e-01 , 6.3878104644355433e+00 , 3.1088168000000000e+00 , -3.5654900000000000e-01 , -9.2227199999999998e-01 , 1.4928800000000000e-01 --7.2467637905269688e-01 , 6.4935665256956456e+00 , 3.1999832000000001e+00 , -2.6894899999999999e-01 , -9.4579999999999997e-01 , -1.8201400000000001e-01 --6.2098654883624604e-01 , 6.3604743319918695e+00 , 3.2835264000000000e+00 , 3.1331700000000001e-01 , 9.0049400000000002e-01 , 3.0156899999999998e-01 --3.9702487993078242e+00 , 1.0667953441564668e+01 , 4.6118872000000000e+00 , -1.8588499999999999e-01 , -8.3892800000000003e-02 , 9.7898300000000005e-01 --4.0481658567647321e+00 , 1.0767293907344010e+01 , 4.8195023999999993e+00 , -1.8368399999999999e-01 , -1.9129000000000000e-02 , 9.8279899999999998e-01 --2.3327163568289615e+00 , 8.5608601356729110e+00 , 4.5007008000000006e+00 , -9.3530000000000002e-01 , -1.9476900000000000e-01 , 2.9543199999999997e-01 --2.3671816511281492e+00 , 8.6046710399693360e+00 , 4.6528527999999998e+00 , -9.3427899999999997e-01 , -2.1198800000000001e-01 , 2.8667900000000002e-01 --7.5374767633385193e+00 , 1.5255887066948398e+01 , 6.6372143999999995e+00 , 4.9215500000000001e-01 , -6.6283800000000004e-01 , -5.6429600000000002e-01 --7.4856865876707701e+00 , 1.5187647947310584e+01 , 6.9160903999999999e+00 , -5.4213400000000000e-01 , 3.3802100000000002e-01 , 7.6930600000000005e-01 --2.0013361777831529e+00 , 8.1325291109430573e+00 , 4.9330080000000001e+00 , -8.6314299999999999e-01 , 4.9976500000000001e-01 , -7.2244900000000001e-02 --1.9556906212474092e+00 , 8.0741865155295649e+00 , 5.0484584000000003e+00 , -9.2115700000000000e-01 , 3.8711800000000002e-01 , -4.0114200000000003e-02 --1.9401693327000276e+00 , 8.0546772327690732e+00 , 5.1762952000000002e+00 , -7.9205300000000001e-01 , 6.0966600000000004e-01 , -3.0983100000000000e-02 --1.9301539322359518e+00 , 8.0402383697243511e+00 , 5.3070231999999997e+00 , -5.9355500000000005e-01 , 7.9389100000000001e-01 , -1.3201900000000000e-01 --1.9476381676376877e+00 , 8.0632017266657208e+00 , 5.4541623999999995e+00 , 6.8834499999999998e-01 , -6.9050000000000000e-01 , 2.2223999999999999e-01 --1.9522148688890599e+00 , 8.0686090632130103e+00 , 5.5959664000000000e+00 , 5.1055600000000001e-01 , -7.7280499999999996e-01 , 3.7696800000000003e-01 --2.0442416568111650e+00 , 8.1866201271991486e+00 , 5.7931400000000002e+00 , 4.0881699999999999e-01 , -7.8729700000000002e-01 , 4.6155499999999999e-01 --2.1095613860301707e+00 , 8.2708247873459335e+00 , 5.9810992000000009e+00 , 5.0989399999999996e-01 , -7.0898899999999998e-01 , 4.8717899999999997e-01 --3.2427371140985128e-01 , 5.9736529999296657e+00 , 4.9369079999999999e+00 , 8.0752100000000004e-01 , 5.7688200000000001e-01 , 1.2295100000000000e-01 --2.2130771705978036e-01 , 5.8428228933768507e+00 , 4.9577912000000000e+00 , -8.6880599999999997e-01 , -3.1270199999999998e-01 , -3.8391900000000001e-01 --3.1166081514233213e-01 , 5.9580216084655380e+00 , 5.1150184000000003e+00 , -9.6519600000000005e-01 , 1.0743800000000001e-01 , -2.3844199999999999e-01 --2.9590260310844174e-01 , 5.9368200625394767e+00 , 5.1975840000000009e+00 , 9.8631000000000002e-01 , -1.3534900000000000e-01 , 9.4201400000000005e-02 --4.3724346399332426e-02 , 5.6124927957137052e+00 , 5.0909735999999999e+00 , 5.1913600000000004e-01 , 2.4920700000000001e-01 , -8.1755400000000000e-01 --4.0231900343321136e-01 , 6.0728931906075792e+00 , 5.4813688000000003e+00 , 9.9869699999999995e-01 , -4.7202700000000000e-02 , -1.9383399999999999e-02 --2.7442004237214324e-01 , 5.9096797899945788e+00 , 5.4732880000000002e+00 , 9.9232299999999996e-01 , -1.1533599999999999e-01 , 4.4635200000000000e-02 --2.9431291729147562e+00 , 9.3388906404974783e+00 , 8.0160776000000009e+00 , 5.3584800000000002e-02 , -6.3957100000000000e-01 , 7.6686299999999996e-01 --3.4851910469882936e+00 , 1.0034933282550307e+01 , 8.7357680000000002e+00 , -7.5143700000000002e-01 , -5.4519799999999996e-01 , 3.7162000000000001e-01 --3.3361797657630010e+00 , 9.8442074352412536e+00 , 8.8169920000000008e+00 , -7.5143700000000002e-01 , -5.4519799999999996e-01 , 3.7162000000000001e-01 --3.2363884001180585e+00 , 9.7153230114438180e+00 , 8.9417504000000001e+00 , 8.2398899999999997e-01 , 5.6530700000000000e-01 , -3.8335300000000003e-02 --3.1303273573688681e+00 , 9.5778620198545141e+00 , 9.0568367999999992e+00 , 7.3815799999999998e-01 , 3.7608799999999998e-01 , -5.6007200000000001e-01 --2.0143352450147756e-01 , 5.8137754713873599e+00 , 6.0300000000000002e+00 , -7.1915000000000007e-02 , 9.8168599999999995e-01 , -1.7641000000000001e-01 --2.4284906944056495e-01 , 5.8666935104012774e+00 , 6.1889744000000002e+00 , -7.1591100000000005e-02 , 9.8595900000000003e-01 , -1.5086400000000000e-01 -3.6750345788338001e-01 , 5.0828356692945666e+00 , 5.5750000000000002e+00 , -2.5460700000000003e-01 , -9.5295700000000005e-01 , -1.6446500000000000e-01 -4.7585916851205301e-01 , 4.9433779563475202e+00 , 5.5330880000000002e+00 , 3.8544699999999998e-01 , -4.6056799999999998e-01 , -7.9956700000000003e-01 -5.2246174705905135e-01 , 4.8836906879217423e+00 , 5.5629879999999998e+00 , -5.3689799999999999e-01 , 4.9642300000000000e-01 , 6.8213299999999999e-01 -5.6438459529366591e-01 , 4.8294217055906028e+00 , 5.5977344000000002e+00 , -5.8190799999999998e-01 , 5.4223800000000000e-01 , 6.0610299999999995e-01 -6.0057736039540788e-01 , 4.7817269788909389e+00 , 5.6375144000000006e+00 , 6.2590800000000002e-01 , -3.1906499999999999e-01 , -7.1164400000000005e-01 -6.3309194460197027e-01 , 4.7405873765147275e+00 , 5.6826608000000007e+00 , 4.8071100000000000e-01 , -4.5254299999999997e-01 , -7.5107999999999997e-01 -6.7062723093767795e-01 , 4.6923264819470667e+00 , 5.7199343999999996e+00 , -2.5086300000000000e-01 , 6.4737800000000001e-01 , 7.1970100000000004e-01 -6.9946323650319608e-01 , 4.6555453378018417e+00 , 5.7701560000000001e+00 , -1.8127099999999999e-01 , 5.6306999999999996e-01 , 8.0628400000000000e-01 -7.2837382275490903e-01 , 4.6175377636036394e+00 , 5.8195768000000001e+00 , -2.5181199999999998e-01 , 4.2389399999999999e-01 , 8.7000299999999997e-01 -7.5345439014793603e-01 , 4.5852586703508633e+00 , 5.8754976000000010e+00 , -7.8582600000000002e-02 , 7.7403299999999997e-01 , 6.2824999999999998e-01 -7.7068421151613520e-01 , 4.5636550738220460e+00 , 5.9459055999999997e+00 , -2.7301900000000001e-01 , -6.9726699999999997e-01 , -6.6278099999999995e-01 -8.0089200986797526e-01 , 4.5240746638849041e+00 , 5.9930279999999998e+00 , 1.6486700000000001e-01 , 8.2375200000000004e-01 , 5.4244999999999999e-01 -7.6185980065371695e-02 , 5.4537722565147462e+00 , 7.4224559999999995e+00 , -6.9684599999999997e-01 , 7.0317600000000002e-01 , 1.4124400000000001e-01 -6.1495196551587861e-01 , 4.7627705046673245e+00 , 6.5584031999999999e+00 , -6.4478400000000002e-01 , -8.9866500000000002e-02 , 7.5906399999999996e-01 -7.0106903031567680e-01 , 4.6513927851999117e+00 , 6.5140576000000001e+00 , -6.2056599999999995e-01 , -5.1714199999999999e-01 , 5.8945899999999996e-01 --1.3319395591597187e+00 , 7.2588861961651752e+00 , 1.0769019999999999e+01 , -2.7592899999999998e-01 , 6.3964299999999996e-01 , -7.1743999999999997e-01 -8.2201938152946186e-01 , 4.4950902664441461e+00 , 6.5124872000000007e+00 , -9.5724900000000002e-01 , -2.4326300000000001e-01 , -1.5651499999999999e-01 -9.1642381800877892e-01 , 4.3741548764815175e+00 , 6.4330416000000010e+00 , 5.3980399999999995e-01 , 8.2692500000000002e-01 , 1.5750300000000000e-01 -8.6671860595241079e-01 , 4.4379035035608663e+00 , 6.6703592000000000e+00 , -4.2724800000000000e-02 , -9.9783999999999995e-01 , -4.9897499999999997e-02 -8.8399581091174406e-01 , 4.4161185047297167e+00 , 6.7661639999999998e+00 , 3.6327999999999999e-01 , -8.9116499999999998e-01 , -2.7175800000000000e-01 -8.9199677623080920e-01 , 4.4053248976284038e+00 , 6.8882079999999997e+00 , 4.1088999999999998e-01 , -3.6247299999999999e-01 , -8.3653000000000000e-01 -9.4932813875115518e-01 , 4.3306005694752834e+00 , 6.8879480000000006e+00 , -8.2089999999999996e-01 , -5.5958900000000000e-01 , -1.1394500000000000e-01 -1.0409585939084600e+00 , 4.2128381221039310e+00 , 6.7973536000000001e+00 , -6.4016799999999999e-02 , -9.3422700000000003e-01 , 3.5088799999999998e-01 -1.0160236991492146e+00 , 4.2451785792334356e+00 , 7.0157536000000000e+00 , 4.1990000000000000e-01 , -4.0363900000000003e-01 , -8.1287100000000001e-01 -1.0521062892435848e+00 , 4.1990638590762099e+00 , 7.0739000000000001e+00 , 3.3014300000000002e-01 , -5.5249599999999999e-01 , -7.6534500000000005e-01 -1.0976552721007180e+00 , 4.1394283043304121e+00 , 7.1038727999999995e+00 , -5.9145000000000003e-01 , 5.4509700000000005e-01 , 5.9418499999999996e-01 -1.0668054169947516e+00 , 4.1788467283481641e+00 , 7.3719640000000002e+00 , 6.2406799999999996e-01 , 1.0087699999999999e-01 , 7.7483100000000005e-01 -1.0323038985863806e+00 , 4.2224698937463438e+00 , 7.6707144000000005e+00 , 4.9798799999999999e-01 , -6.9140800000000002e-01 , 5.2341400000000005e-01 -1.2035585960468889e+00 , 4.0030071054796750e+00 , 7.2978328000000001e+00 , -1.0453600000000000e-01 , 3.1823699999999999e-01 , 9.4223000000000001e-01 -1.3080713964100017e+00 , 3.8691373104486733e+00 , 7.1247559999999996e+00 , -6.7271400000000003e-01 , -7.1508700000000003e-01 , 1.9001599999999999e-01 -9.6337336799853901e-01 , 4.3096778646629987e+00 , 8.5948168000000003e+00 , 4.3425900000000001e-01 , 7.9102899999999998e-01 , 4.3092000000000003e-01 -1.3410587696361089e+00 , 3.8261940843576601e+00 , 7.3982448000000005e+00 , 4.9106699999999998e-01 , -2.7192499999999997e-01 , 8.2759300000000002e-01 -1.4956978562731749e+00 , 3.6278333193458918e+00 , 6.9842936000000000e+00 , 1.6922499999999999e-01 , 5.9342600000000001e-01 , 7.8689799999999999e-01 -1.5375497727647163e+00 , 3.5729981591912514e+00 , 7.0109279999999998e+00 , -3.2550299999999999e-01 , -5.9645199999999998e-01 , -7.3368500000000003e-01 -1.5806194093856385e+00 , 3.5189191962786719e+00 , 7.0362624000000000e+00 , 8.1377999999999995e-01 , 1.8373100000000001e-01 , -5.5136700000000005e-01 -1.6184087012143984e+00 , 3.4698078116345998e+00 , 7.0799320000000003e+00 , -9.1180700000000003e-01 , 2.8307800000000001e-02 , 4.0964200000000001e-01 -1.6673208267721131e+00 , 3.4068746781697872e+00 , 7.0731511999999999e+00 , -4.2873800000000001e-01 , -8.3811700000000000e-01 , -3.3726000000000000e-01 -1.6749749433317906e+00 , 3.3959683152481928e+00 , 7.2841256000000003e+00 , 6.9350299999999998e-01 , -4.1882300000000000e-01 , 5.8620899999999998e-01 -1.7341553104582883e+00 , 3.3200058472383591e+00 , 7.2254384000000007e+00 , -3.8426600000000000e-01 , 9.0890899999999997e-01 , 1.6193900000000000e-01 -1.7984022851021797e+00 , 3.2384594519741419e+00 , 7.1242463999999996e+00 , -9.3362400000000001e-01 , -1.0524200000000000e-01 , -3.4244900000000000e-01 -1.8493388614332367e+00 , 3.1723818344617039e+00 , 7.0917256000000002e+00 , 8.9710599999999996e-01 , 4.0648800000000002e-01 , 1.7311299999999999e-01 -1.7384217253101744e+00 , 3.3129969415458378e+00 , 8.2139688000000000e+00 , -9.4244600000000001e-01 , 3.2993200000000000e-01 , 5.4222899999999997e-02 -1.8017141958772762e+00 , 3.2318088579736655e+00 , 8.1723479999999995e+00 , 1.4585300000000001e-01 , -9.4486800000000004e-01 , 2.9317399999999999e-01 --1.7328341452444329e-01 , 6.0207717796971485e+00 , 5.8622400000000008e-01 , -7.2235199999999999e-01 , 6.3275800000000004e-01 , -2.7897100000000002e-01 --1.8335099934234611e-01 , 6.0325365719288175e+00 , 6.7935600000000007e-01 , 7.0438800000000001e-01 , -6.8294900000000003e-01 , 1.9343800000000000e-01 --1.9131667418837717e-01 , 6.0430932677114626e+00 , 7.7222799999999991e-01 , -6.9454800000000005e-01 , 6.9629700000000005e-01 , -1.8103700000000000e-01 --1.9923853978334938e-01 , 6.0524915764303326e+00 , 8.6460079999999984e-01 , 6.6105899999999995e-01 , -7.2580800000000001e-01 , 1.9027500000000000e-01 --2.1072403587186095e-01 , 6.0675344158777511e+00 , 9.5261599999999991e-01 , -6.4136599999999999e-01 , 7.4607900000000005e-01 , -1.7892800000000000e-01 --2.2119630649723598e-01 , 6.0804056649216038e+00 , 1.0406520000000001e+00 , 6.0996899999999998e-01 , -7.7422899999999995e-01 , 1.6883899999999999e-01 --2.2598581127408268e-01 , 6.0852923454792585e+00 , 1.1324018400000000e+00 , 5.9031599999999995e-01 , -7.8524300000000002e-01 , 1.8687100000000001e-01 --2.3431526304515593e-01 , 6.0969107330951617e+00 , 1.2198856000000000e+00 , 5.5693099999999995e-01 , -8.1289500000000003e-01 , 1.7037900000000000e-01 --2.4837085345409315e-01 , 6.1143719807761316e+00 , 1.3035640000000002e+00 , 5.3288800000000003e-01 , -8.2292200000000004e-01 , 1.9705300000000001e-01 --2.4898159185275182e-01 , 6.1147150850290997e+00 , 1.3947148000000000e+00 , 5.0664699999999996e-01 , -8.4191300000000002e-01 , 1.8571799999999999e-01 --2.6673937259604408e-01 , 6.1369863001453240e+00 , 1.4751442400000001e+00 , -4.8361500000000002e-01 , 8.4798700000000005e-01 , -2.1687500000000001e-01 --2.7095685464450314e-01 , 6.1430819224212634e+00 , 1.5624366400000000e+00 , 4.4927800000000001e-01 , -8.6624999999999996e-01 , 2.1854199999999999e-01 --2.8673076175912815e-01 , 6.1632615804941633e+00 , 1.6434256000000000e+00 , -4.1513800000000001e-01 , 8.7945099999999998e-01 , -2.3286799999999999e-01 --2.9574188090651443e-01 , 6.1742642687125757e+00 , 1.7277488000000001e+00 , 3.6460199999999998e-01 , -9.0796600000000005e-01 , 2.0655200000000001e-01 --3.0368607099622835e-01 , 6.1851861114865088e+00 , 1.8118941600000000e+00 , 3.3294699999999999e-01 , -9.2440000000000000e-01 , 1.8609600000000001e-01 --3.1167170582702930e-01 , 6.1940090827699876e+00 , 1.8961461200000000e+00 , 3.2918599999999998e-01 , -9.2585600000000001e-01 , 1.8554699999999999e-01 --3.2349962113538444e-01 , 6.2089612873572175e+00 , 1.9783607200000000e+00 , 6.3663700000000001e-01 , -7.1761200000000003e-01 , 2.8235800000000000e-01 --3.3532753644374003e-01 , 6.2239134919444483e+00 , 2.0605753199999999e+00 , 6.5756899999999996e-01 , -7.1532499999999999e-01 , 2.3646000000000000e-01 --3.4517364428446839e-01 , 6.2367843321807621e+00 , 2.1434513599999998e+00 , 6.3666900000000004e-01 , -7.4069600000000002e-01 , 2.1453000000000000e-01 --3.5500542711070704e-01 , 6.2496368531932980e+00 , 2.2262270399999999e+00 , 5.9485699999999997e-01 , -7.7641300000000002e-01 , 2.0815400000000001e-01 --3.5797110838685731e-01 , 6.2520175180769586e+00 , 2.3112252000000000e+00 , 5.7310099999999997e-01 , -8.0160100000000001e-01 , 1.7026800000000000e-01 --3.7177959920938619e-01 , 6.2701443237151322e+00 , 2.3929775200000001e+00 , -4.7926900000000000e-01 , 8.3671700000000004e-01 , -2.6496399999999998e-01 --3.7866139030937296e-01 , 6.2788090403369354e+00 , 2.4766476000000002e+00 , 6.3476999999999995e-01 , -7.5751900000000005e-01 , 1.5241900000000000e-01 --3.9155913504402884e-01 , 6.2949557124534943e+00 , 2.5593400800000001e+00 , 6.0989899999999997e-01 , -7.7960700000000005e-01 , 1.4225299999999999e-01 --3.9644066133981815e-01 , 6.3015003601157833e+00 , 2.6434688000000000e+00 , -5.3536799999999996e-01 , 8.2626299999999997e-01 , -1.7512800000000001e-01 --4.1346263465053790e-01 , 6.3231779241036747e+00 , 2.7263536799999999e+00 , -4.4263200000000003e-01 , 8.7014400000000003e-01 , -2.1662600000000001e-01 --4.2344193805654973e-01 , 6.3362870523619073e+00 , 2.8103430400000002e+00 , 3.3088200000000001e-01 , -9.1931600000000002e-01 , 2.1301400000000001e-01 --4.3856612593833422e-01 , 6.3560360042722346e+00 , 2.8945976000000000e+00 , 2.9141899999999998e-01 , -9.3381099999999995e-01 , 2.0753700000000000e-01 --4.4665493623919383e-01 , 6.3661008322070156e+00 , 2.9797569600000000e+00 , 4.3264200000000003e-01 , -8.7188200000000005e-01 , 2.2944100000000001e-01 --4.5991535299655739e-01 , 6.3828849591721282e+00 , 3.0654903999999998e+00 , 3.8350499999999998e-01 , -8.6298500000000000e-01 , 3.2890799999999998e-01 --4.5993187675404323e-01 , 6.3821812490574938e+00 , 3.1515816000000001e+00 , 4.7882900000000000e-01 , -8.2629300000000006e-01 , 2.9658499999999999e-01 --5.7311809220592291e-01 , 6.5277801027958411e+00 , 3.9660368000000004e+00 , 2.8359200000000001e-01 , -9.4301800000000002e-01 , 1.7404600000000001e-01 --5.8875466590234771e-01 , 6.5469158358080950e+00 , 4.0629752000000003e+00 , -4.9756299999999998e-01 , 8.3310499999999998e-01 , -2.4159400000000000e-01 --6.1420706218036614e-01 , 6.5813904217476935e+00 , 4.1654152000000000e+00 , -4.9756299999999998e-01 , 8.3310499999999998e-01 , -2.4159400000000000e-01 --6.2705026358206073e-01 , 6.5977391577769859e+00 , 4.2648600000000005e+00 , -4.7505799999999998e-01 , 8.4752200000000000e-01 , -2.3669799999999999e-01 --6.4545955349364981e-01 , 6.6203452125020164e+00 , 4.3679135999999996e+00 , 4.1694300000000001e-01 , -8.8607800000000003e-01 , 2.0254300000000000e-01 --6.6194117599387114e-01 , 6.6420792534019544e+00 , 4.4722360000000005e+00 , -3.7589200000000000e-01 , 9.0412599999999999e-01 , -2.0313000000000001e-01 --6.7654746461101789e-01 , 6.6618907425946592e+00 , 4.5780247999999997e+00 , 3.2126100000000002e-01 , -9.2449899999999996e-01 , 2.0516499999999999e-01 --6.9133858622694389e-01 , 6.6798395821577854e+00 , 4.6850304000000005e+00 , -3.0734400000000001e-01 , 9.2986199999999997e-01 , -2.0222999999999999e-01 --7.0421759739944534e-01 , 6.6958414904195713e+00 , 4.7933047999999996e+00 , 2.8059499999999998e-01 , -9.4270399999999999e-01 , 1.8048500000000001e-01 --7.2171877089704228e-01 , 6.7182602261155688e+00 , 4.9061240000000002e+00 , 2.4110999999999999e-01 , -9.5115600000000000e-01 , 1.9279199999999999e-01 --6.4203953219736043e-02 , 5.8246572903708511e+00 , 4.6112527999999999e+00 , -6.5884299999999996e-01 , 6.5915299999999999e-01 , -3.6255100000000001e-01 --6.6136719742726502e-02 , 5.8259208969423781e+00 , 4.6961791999999996e+00 , -7.4986299999999995e-01 , 6.1164099999999999e-01 , -2.5219200000000003e-01 --7.7064682744289215e-01 , 6.7815933681207312e+00 , 5.2574775999999996e+00 , -9.7272700000000001e-01 , -1.0609499999999999e-01 , 2.0626900000000001e-01 --1.3417395340332305e-01 , 5.9166738012148770e+00 , 4.9160351999999996e+00 , 4.3024299999999999e-01 , -7.8026399999999996e-01 , 4.5395999999999997e-01 --1.4927347993457962e-01 , 5.9355682187854679e+00 , 5.0171440000000000e+00 , -8.8681200000000004e-01 , 7.4557700000000005e-02 , -4.5607599999999998e-01 --4.2041887360176533e-01 , 6.3024760740497934e+00 , 5.3205328000000005e+00 , 3.4779900000000002e-01 , 4.8264399999999999e-02 , -9.3632599999999999e-01 --2.5289158568164449e-01 , 6.0740125483246370e+00 , 5.2868784000000000e+00 , -8.6648099999999995e-01 , -3.1695400000000001e-01 , 3.8568200000000002e-01 -5.5950257679432625e-02 , 5.6537404903128170e+00 , 5.1219967999999998e+00 , -3.6875700000000000e-01 , -2.5778800000000002e-01 , 8.9306399999999997e-01 --2.2326081524046693e-01 , 6.0320124683339733e+00 , 5.4589672000000000e+00 , 5.9061600000000003e-01 , -7.7505699999999997e-02 , 8.0322199999999999e-01 --1.5057439892511360e-01 , 5.9315161953872053e+00 , 5.4921432000000001e+00 , 5.9415799999999996e-01 , 7.4025199999999999e-02 , 8.0093499999999995e-01 --2.1662544592905713e+00 , 8.6615835722421544e+00 , 7.5395496000000000e+00 , -7.7032100000000006e-02 , -4.6920200000000001e-01 , 8.7972499999999998e-01 --3.1180965106351275e+00 , 9.9477759648175237e+00 , 8.6766752000000000e+00 , -7.5143700000000002e-01 , -5.4519799999999996e-01 , 3.7162000000000001e-01 --2.6769081344167276e+00 , 9.3489458304047552e+00 , 8.4389831999999991e+00 , -7.9456700000000002e-01 , -3.1729099999999999e-01 , 5.1767700000000005e-01 --9.3123588482418196e-02 , 5.8489104951560629e+00 , 5.8427792000000007e+00 , 5.5254900000000003e-02 , -9.9847100000000000e-01 , -1.5755400000000001e-03 --9.0055687464079437e-02 , 5.8440886776748968e+00 , 5.9460096000000000e+00 , 1.2203600000000001e-01 , -9.8970899999999995e-01 , 7.4719999999999995e-02 --2.5627665790377350e+00 , 9.1865940298490969e+00 , 8.9487495999999993e+00 , 7.7290400000000004e-01 , 4.3513099999999999e-01 , -4.6182400000000001e-01 --2.4619320451080204e+00 , 9.0479568457075512e+00 , 9.0463535999999998e+00 , -4.9426199999999998e-01 , -5.1353700000000002e-01 , 7.0141600000000004e-01 --2.6092702387224556e+00 , 9.2431497274967054e+00 , 9.4514440000000004e+00 , -6.2790100000000004e-01 , -4.3368600000000002e-01 , 6.4626399999999995e-01 -5.8928363785208360e-01 , 4.9200933784459888e+00 , 5.5102184000000003e+00 , -5.4364199999999996e-01 , 4.1337000000000002e-01 , 7.3046400000000000e-01 -5.9992851304239059e-01 , 4.9047740214665732e+00 , 5.5840168000000006e+00 , 6.1836999999999998e-01 , -4.5326899999999998e-01 , -6.4200100000000004e-01 -6.0182801936619823e-01 , 4.9010099645818519e+00 , 5.6711792000000001e+00 , -6.5723299999999996e-01 , 4.2777500000000002e-01 , 6.2052700000000005e-01 -6.3793225998386038e-01 , 4.8512811035232719e+00 , 5.7113648000000001e+00 , -6.5222999999999998e-01 , 2.5769700000000001e-01 , 7.1287400000000001e-01 -6.8894327475600514e-01 , 4.7826611981489098e+00 , 5.7295128000000002e+00 , 7.1378299999999995e-01 , -1.0815600000000000e-01 , -6.9196599999999997e-01 -7.2437502142052224e-01 , 4.7323184972377756e+00 , 5.7665367999999999e+00 , -6.2065999999999999e-01 , 2.4083299999999999e-01 , 7.4617699999999998e-01 -7.6594786255962344e-01 , 4.6757819794904876e+00 , 5.7951992000000008e+00 , -4.0769400000000000e-01 , 5.1320399999999999e-01 , 7.5525299999999995e-01 -7.9885339869456717e-01 , 4.6317610118010801e+00 , 5.8367056000000002e+00 , -2.2354900000000000e-01 , 6.9254599999999999e-01 , 6.8586199999999997e-01 -8.2686587892846219e-01 , 4.5924465609574519e+00 , 5.8846912000000007e+00 , -7.6533100000000007e-02 , 5.5906800000000001e-01 , 8.2558200000000004e-01 -8.5994721554885234e-01 , 4.5459250755577045e+00 , 5.9243880000000004e+00 , -5.6997899999999997e-02 , -6.7082900000000001e-01 , -7.3941900000000005e-01 -8.8126805500821215e-01 , 4.5170541766490357e+00 , 5.9858936000000007e+00 , -5.3682900000000004e-03 , 7.7790099999999995e-01 , 6.2836400000000003e-01 -8.9061880629409163e-01 , 4.5029050435052973e+00 , 6.0705184000000001e+00 , -9.3334500000000001e-02 , 9.3337599999999998e-01 , 3.4655100000000000e-01 -8.2474251185445624e-01 , 4.5893632521456347e+00 , 6.3063696000000000e+00 , -3.8546500000000000e-01 , -8.4806700000000002e-01 , 3.6359200000000003e-01 -7.7147666910173740e-01 , 4.6591708674780339e+00 , 6.5308016000000002e+00 , -8.5337900000000000e-01 , -5.1185400000000003e-01 , -9.8743700000000004e-02 -8.2277556252618367e-01 , 4.5900469072241705e+00 , 6.5465264000000003e+00 , -9.3256300000000000e-02 , -2.0989700000000000e-01 , 9.7326599999999996e-01 -9.0763713625577602e-01 , 4.4744035310501022e+00 , 6.4860192000000003e+00 , 1.1497400000000001e-01 , -5.3119499999999997e-01 , 8.3941200000000005e-01 -9.3918810775293404e-01 , 4.4316572620170289e+00 , 6.5388720000000005e+00 , 7.9513799999999996e-02 , 9.8231100000000005e-01 , -1.6954000000000000e-01 -9.2798678616011054e-01 , 4.4440942139657249e+00 , 6.6930832000000002e+00 , 1.9924800000000001e-01 , -9.7316000000000003e-01 , 1.1515000000000000e-01 -9.0538871947415900e-01 , 4.4727380406699009e+00 , 6.8831328000000003e+00 , 4.4679600000000003e-01 , -6.6446300000000003e-01 , -5.9905100000000000e-01 -9.3483005774477790e-01 , 4.4325990236709574e+00 , 6.9536864000000005e+00 , -7.2237799999999996e-01 , 3.4843099999999999e-01 , 5.9729900000000002e-01 -1.0538699780236112e+00 , 4.2705504217788999e+00 , 6.7861008000000007e+00 , -4.3355300000000002e-01 , -6.6330999999999996e-01 , 6.0995999999999995e-01 -1.0734318432632963e+00 , 4.2439546190925741e+00 , 6.8796384000000002e+00 , 2.7076899999999998e-01 , 9.5360400000000001e-01 , -1.3161600000000001e-01 -1.0680846048537389e+00 , 4.2488025221136496e+00 , 7.0448735999999998e+00 , -2.0410400000000001e-01 , 4.9402200000000002e-01 , 8.4515300000000004e-01 -1.1124844900913353e+00 , 4.1882973423093492e+00 , 7.0755432000000003e+00 , -5.8275700000000000e-02 , 6.8031900000000001e-01 , 7.3059600000000002e-01 -1.1235835920052195e+00 , 4.1704702382682886e+00 , 7.2055015999999998e+00 , 5.4159800000000002e-01 , -7.6120800000000000e-01 , -3.5670000000000002e-01 -8.3195086154795161e-01 , 4.5563370040089497e+00 , 8.3259040000000013e+00 , -3.4308699999999998e-01 , -9.1189500000000001e-01 , -2.2525500000000001e-01 -1.1981819557940656e+00 , 4.0676980437409291e+00 , 7.3174056000000007e+00 , -4.0400600000000002e-02 , 3.8314300000000001e-01 , 9.2280499999999999e-01 -1.2653416842712932e+00 , 3.9763427994020546e+00 , 7.2682967999999999e+00 , 1.5552199999999999e-01 , 5.2729199999999998e-01 , 8.3533000000000002e-01 -1.3168308854919109e+00 , 3.9061962640495711e+00 , 7.2736735999999995e+00 , 1.2513600000000000e-01 , 3.6672900000000003e-01 , 9.2187300000000005e-01 -1.3257009781261568e+00 , 3.8925651649647621e+00 , 7.4398032000000001e+00 , 3.0521399999999999e-01 , 2.8732500000000000e-01 , 9.0790300000000002e-01 -1.4939117509489814e+00 , 3.6687182516111809e+00 , 6.9707320000000008e+00 , -6.3634599999999997e-01 , -2.7694699999999999e-02 , -7.7090599999999998e-01 -1.5335835085446552e+00 , 3.6130273019338364e+00 , 6.9979176000000001e+00 , 9.8482000000000000e-02 , 5.4796800000000001e-01 , 8.3068200000000003e-01 -1.5679256563589665e+00 , 3.5663793807524335e+00 , 7.0530792000000009e+00 , -2.7895399999999998e-01 , -6.0699700000000001e-01 , -7.4413700000000005e-01 -1.6067466848656529e+00 , 3.5132749759879731e+00 , 7.0876488000000002e+00 , 7.7524599999999999e-01 , 4.5717700000000000e-01 , 4.3586999999999998e-01 -1.6534213616984250e+00 , 3.4484981795703309e+00 , 7.0817312000000001e+00 , -8.1274699999999995e-03 , 5.2504400000000000e-02 , 9.9858800000000003e-01 -1.6857635181687043e+00 , 3.4042568939292197e+00 , 7.1536888000000003e+00 , -5.9704699999999999e-01 , 2.3233599999999999e-01 , 7.6782499999999998e-01 -1.6199597051324535e+00 , 3.4863790704425819e+00 , 7.7843760000000000e+00 , 9.9556000000000000e-01 , 3.1552200000000002e-02 , -8.8678900000000005e-02 -1.7948058456399900e+00 , 3.2565446496326960e+00 , 7.0446136000000008e+00 , -6.8037499999999995e-01 , 2.4133599999999999e-01 , -6.9198800000000005e-01 -1.8251023958516261e+00 , 3.2137032696761025e+00 , 7.1335752000000001e+00 , 7.1236600000000005e-01 , 5.8777100000000004e-01 , -3.8348300000000002e-01 -1.8939823027760003e+00 , 3.1212641670330328e+00 , 6.9582103999999996e+00 , 3.9600900000000000e-01 , -6.7906200000000005e-01 , 6.1810299999999996e-01 -1.7762781578884475e+00 , 3.2681862226963880e+00 , 8.1630088000000001e+00 , -8.1718199999999996e-01 , -3.8756699999999999e-01 , -4.2662000000000000e-01 --1.1554629657872471e+00 , 7.7189933938818465e+00 , -1.4339840000000015e-01 , -3.6580500000000002e-02 , 2.4929299999999999e-01 , 9.6773699999999996e-01 --1.4725916507530217e+00 , 8.1830772292716585e+00 , -2.7396000000000020e-01 , -4.1998800000000003e-02 , 2.3456099999999999e-01 , 9.7119400000000000e-01 --1.8842185782481748e+00 , 8.7845359129008003e+00 , -4.5964160000000032e-01 , -6.3197299999999998e-02 , 2.3588899999999999e-01 , 9.6972300000000000e-01 --2.3755167947626274e+00 , 9.5026264263580096e+00 , -6.7902960000000023e-01 , 6.8978899999999996e-02 , -2.3873300000000000e-01 , -9.6863200000000005e-01 --2.9257367736751467e+00 , 1.0308171052457137e+01 , -9.0898400000000024e-01 , -6.4426100000000000e-02 , 2.1100099999999999e-01 , 9.7536100000000003e-01 --3.5375534200063692e+00 , 1.1202325404944455e+01 , -1.1445127999999998e+00 , -7.9431699999999994e-02 , 2.0644599999999999e-01 , 9.7522900000000001e-01 --4.4024843109067024e+00 , 1.2466936592330160e+01 , -1.5084192000000001e+00 , -9.0285199999999996e-02 , 2.1003200000000000e-01 , 9.7351699999999997e-01 --5.6183008304308082e+00 , 1.4245475504998728e+01 , -2.0366248000000002e+00 , -8.4683400000000006e-02 , 2.1710900000000000e-01 , 9.7246699999999997e-01 --7.0137138632523417e+00 , 1.6285686110885280e+01 , -2.5906535999999996e+00 , -7.8157699999999997e-02 , 1.5150900000000000e-01 , 9.8536100000000004e-01 --8.2052882650979377e+00 , 1.8024570743342231e+01 , -2.9366512000000000e+00 , -2.3152499999999999e-02 , -2.4184900000000001e-01 , 9.7003799999999996e-01 --8.5924561169436799e+00 , 1.8583734410748932e+01 , -2.7785920000000006e+00 , -2.3152499999999999e-02 , -2.4184900000000001e-01 , 9.7003799999999996e-01 --9.0033591587949253e+00 , 1.9175863742341917e+01 , -2.6100288000000003e+00 , -1.6692800000000001e-02 , -2.6609100000000002e-01 , 9.6380299999999997e-01 --9.4071514855399236e+00 , 1.9759141308978815e+01 , -2.4150704000000003e+00 , -1.7605599999999999e-02 , -2.6694499999999999e-01 , 9.6355100000000005e-01 --1.2983130822964975e+01 , 2.4968643085218197e+01 , -3.0563240000000000e+00 , 1.2308900000000000e-01 , -3.1234299999999998e-01 , 9.4196100000000005e-01 --3.0964949420622689e-01 , 6.4395452094681183e+00 , 2.0717646799999998e+00 , -9.3452299999999999e-01 , 3.3330700000000002e-01 , -1.2479000000000000e-01 --3.1391118325160861e-01 , 6.4446025527153648e+00 , 2.1591616000000000e+00 , -9.3545400000000001e-01 , 3.3969100000000002e-01 , -9.7648100000000002e-02 --3.1815977923595362e-01 , 6.4485483400388031e+00 , 2.2463583200000001e+00 , -9.2845500000000003e-01 , 3.6000100000000002e-01 , -9.1491199999999995e-02 --3.3226537737906980e-01 , 6.4671985528607783e+00 , 2.3306399199999999e+00 , -9.2239400000000005e-01 , 3.7327500000000002e-01 , -9.9271600000000002e-02 --3.2854126582667575e-01 , 6.4594536369319044e+00 , 2.4194808800000001e+00 , -9.1396299999999997e-01 , 3.9391199999999998e-01 , -9.7494200000000003e-02 --3.4164673156769299e-01 , 6.4770438152741212e+00 , 2.5039923200000000e+00 , -9.0522300000000000e-01 , 4.1461700000000001e-01 , -9.3085500000000002e-02 --3.4782259721754016e-01 , 6.4840582825151190e+00 , 2.5902218399999999e+00 , -8.9068499999999995e-01 , 4.4608100000000001e-01 , -8.7700700000000006e-02 --3.4699723770376689e-01 , 6.4804054425360045e+00 , 2.6776619200000003e+00 , -8.5617600000000005e-01 , 5.1151800000000003e-01 , -7.2878899999999996e-02 --3.5217420290496859e-01 , 6.4852666385972171e+00 , 2.7639215999999998e+00 , -8.3201300000000000e-01 , 5.4845200000000005e-01 , -8.3395499999999997e-02 --3.4315438818253563e-01 , 6.4717083357781702e+00 , 2.8513804000000000e+00 , -7.9764000000000002e-01 , 5.7281899999999997e-01 , -1.8880800000000000e-01 --3.6452193999537430e-01 , 6.4993282173174816e+00 , 2.9364804800000002e+00 , 8.0413500000000004e-01 , -5.5974299999999999e-01 , 2.0013600000000001e-01 --3.9515161088519735e-01 , 6.5434815684879322e+00 , 3.0226319999999998e+00 , -5.9196199999999999e-01 , 7.7708800000000000e-01 , -2.1380900000000000e-01 --4.0256038350906120e-01 , 6.5508721930277041e+00 , 3.1104599999999998e+00 , 4.6134999999999998e-01 , -8.1449300000000002e-01 , 3.5179100000000002e-01 --4.8127670822376700e-01 , 6.6454134033303509e+00 , 4.0214064000000000e+00 , -4.9756299999999998e-01 , 8.3310499999999998e-01 , -2.4159400000000000e-01 --5.0133628623201743e-01 , 6.6728102941826162e+00 , 4.1214648000000000e+00 , -4.9756299999999998e-01 , 8.3310499999999998e-01 , -2.4159400000000000e-01 --5.1517342155268908e-01 , 6.6901884866144359e+00 , 4.2205767999999999e+00 , -4.7505799999999998e-01 , 8.4752200000000000e-01 , -2.3669799999999999e-01 --5.2172118512811183e-01 , 6.6974671351813324e+00 , 4.3185760000000002e+00 , 4.5705699999999999e-01 , -8.6236400000000002e-01 , 2.1777800000000000e-01 --5.3276204778542668e-01 , 6.7109447085453446e+00 , 4.4199967999999998e+00 , 3.9657300000000001e-01 , -8.9488500000000004e-01 , 2.0472099999999999e-01 --5.4286627658172382e-01 , 6.7234661024019440e+00 , 4.5221559999999998e+00 , 3.4916900000000001e-01 , -9.1224799999999995e-01 , 2.1420800000000001e-01 --5.5754142801548445e-01 , 6.7423085952517807e+00 , 4.6283608000000003e+00 , 3.2126100000000002e-01 , -9.2449899999999996e-01 , 2.0516499999999999e-01 --5.7129840292479850e-01 , 6.7602336132028045e+00 , 4.7354912000000002e+00 , -3.0734400000000001e-01 , 9.2986199999999997e-01 , -2.0222999999999999e-01 --5.8321213020730278e-01 , 6.7752427035096190e+00 , 4.8443064000000007e+00 , 2.8059499999999998e-01 , -9.4270399999999999e-01 , 1.8048500000000001e-01 -4.7604216538574828e-03 , 5.9268931062534191e+00 , 4.5853359999999999e+00 , -5.9134500000000001e-01 , 7.3104000000000002e-01 , -3.4042899999999998e-01 --5.9884469310192889e-01 , 6.7920553257984091e+00 , 5.0614480000000004e+00 , -5.4304699999999995e-01 , 8.1518500000000005e-01 , -2.0142800000000000e-01 -2.3927611513869351e-02 , 5.8959939123598843e+00 , 4.7417104000000005e+00 , -7.9688400000000004e-01 , 2.0865700000000001e-01 , -5.6695499999999999e-01 --6.3661618750304605e-01 , 6.8421253553185366e+00 , 5.3019271999999997e+00 , -9.7272700000000001e-01 , -1.0609499999999999e-01 , 2.0626900000000001e-01 --6.4767826422193053e-01 , 6.8559169740989949e+00 , 5.4207160000000005e+00 , 9.7588399999999997e-01 , 1.2375400000000000e-01 , -1.7981800000000001e-01 --4.4053183662976725e-01 , 6.5563332881616532e+00 , 5.3693192000000005e+00 , 1.2355900000000000e-01 , 2.9625000000000001e-01 , 9.4708499999999995e-01 -3.0723781548220619e-01 , 5.4811048011876178e+00 , 4.8563080000000003e+00 , -1.9872100000000001e-01 , 8.0355900000000002e-01 , 5.6107300000000004e-01 --2.8914970174361976e-01 , 6.3339669535725509e+00 , 5.4521239999999995e+00 , -1.6996900000000001e-01 , -9.5914799999999995e-02 , -9.8077099999999995e-01 -3.7946458561658192e-01 , 5.3742333311466490e+00 , 4.9526432000000007e+00 , 8.1403000000000003e-01 , 5.6795099999999998e-01 , 1.2160000000000000e-01 -3.0324254798699157e-01 , 5.4813666842945228e+00 , 5.1044416000000004e+00 , 5.6238600000000005e-01 , 5.7396300000000000e-01 , -5.9522100000000000e-01 --7.6284505518798396e-01 , 7.0046904288882876e+00 , 6.2347136000000001e+00 , 8.1037899999999996e-01 , -5.6398499999999996e-01 , 1.5876499999999999e-01 --7.8372720833082443e-01 , 7.0315385606422645e+00 , 6.3845983999999998e+00 , 7.1855100000000005e-01 , -6.7357299999999998e-01 , 1.7315800000000001e-01 -5.1115907357344925e-01 , 5.1782038485053867e+00 , 5.1408936000000001e+00 , -7.4623600000000001e-01 , 2.0844300000000000e-02 , 6.6535500000000003e-01 -5.7747415935225055e-01 , 5.0826343959759273e+00 , 5.1497440000000001e+00 , 5.3603599999999996e-01 , 2.2446199999999999e-01 , 8.1380699999999995e-01 -6.3247804310462952e-02 , 5.8127902959382487e+00 , 5.8181000000000003e+00 , -2.8549799999999997e-01 , -9.4435300000000000e-01 , 1.6336800000000001e-01 --2.2580467622064671e-02 , 5.9346682962216306e+00 , 6.0252575999999998e+00 , 1.2203600000000001e-01 , -9.8970899999999995e-01 , 7.4720099999999998e-02 --8.9070793578349772e-01 , 7.1689298496765295e+00 , 7.2070408000000006e+00 , 4.3090099999999998e-01 , -8.8532200000000005e-01 , 1.7472599999999999e-01 --9.1809639669900012e-01 , 7.2035849981800348e+00 , 7.3943136000000003e+00 , 4.3090000000000001e-01 , -8.8532200000000005e-01 , 1.7472599999999999e-01 --2.0627376395333297e-02 , 5.9224683284405231e+00 , 6.3603664000000002e+00 , 1.4856800000000001e-01 , -9.8870599999999997e-01 , 1.9700900000000000e-02 --9.7326300535153853e-01 , 7.2760740396217436e+00 , 7.7897528000000005e+00 , -1.5176500000000001e-01 , 9.7029399999999999e-01 , -1.8840899999999999e-01 --1.0147315965062234e+00 , 7.3313476954846006e+00 , 8.0183552000000002e+00 , -5.5339600000000000e-01 , -7.7247299999999997e-01 , 3.1150899999999998e-01 --1.0486628821216635e+00 , 7.3760839360472961e+00 , 8.2437128000000008e+00 , -5.0988800000000001e-01 , -7.2607299999999997e-01 , 4.6133700000000000e-01 --2.2102576981763988e-04 , 5.8833098826318793e+00 , 6.8239048000000002e+00 , 4.8512300000000003e-01 , -4.8295500000000002e-01 , -7.2897900000000004e-01 -1.9307449454147863e-02 , 5.8530887817745816e+00 , 6.9257727999999998e+00 , 4.8512300000000003e-01 , -4.8295500000000002e-01 , -7.2897900000000004e-01 -7.5072388477203900e-01 , 4.8145083329800418e+00 , 5.8638496000000000e+00 , 6.9871399999999995e-01 , 2.4525900000000000e-02 , -7.1497999999999995e-01 -8.2063081464326149e-01 , 4.7126421544144481e+00 , 5.8422383999999994e+00 , -6.1067000000000005e-01 , 2.7380800000000000e-02 , 7.9141099999999998e-01 -8.6033390995233150e-01 , 4.6547079141207721e+00 , 5.8688312000000007e+00 , 6.0518700000000003e-01 , -1.9116900000000001e-01 , -7.7278899999999995e-01 -8.9625822609034689e-01 , 4.6024064263315481e+00 , 5.9015079999999998e+00 , -3.3399200000000001e-01 , 4.0374399999999999e-01 , 8.5172800000000004e-01 -9.3528780817703039e-01 , 4.5438581395692150e+00 , 5.9249288000000000e+00 , -7.0570499999999994e-02 , 6.7357599999999995e-01 , 7.3574200000000001e-01 -9.5160270698345739e-01 , 4.5187901181433094e+00 , 5.9937144000000000e+00 , -9.0851899999999999e-02 , 7.9758300000000004e-01 , 5.9632799999999997e-01 -9.7598556941868697e-01 , 4.4826555596981770e+00 , 6.0461720000000003e+00 , -2.9429300000000003e-01 , -7.6853600000000000e-01 , -5.6810600000000000e-01 -9.9338746778941545e-01 , 4.4552823412835512e+00 , 6.1142816000000000e+00 , -3.2676800000000000e-01 , -7.8750200000000004e-01 , -5.2255499999999999e-01 -9.6759962144088929e-01 , 4.4897313742233944e+00 , 6.2797559999999999e+00 , 5.9313199999999999e-01 , 8.0495200000000000e-01 , 1.5710600000000002e-02 -8.6588591667804882e-01 , 4.6295804512564871e+00 , 6.6201999999999996e+00 , 9.1142599999999996e-01 , 4.0844500000000000e-01 , -4.9762000000000001e-02 -9.7300641395976917e-01 , 4.4776797071065104e+00 , 6.5004232000000002e+00 , -4.3887599999999999e-01 , -8.5804000000000002e-01 , 2.6674999999999999e-01 -9.3950413850079295e-01 , 4.5213674792666065e+00 , 6.7048871999999999e+00 , 7.5317900000000004e-01 , -5.0007699999999999e-01 , -4.2736900000000000e-01 -3.8672205123725645e-01 , 5.2906319044534262e+00 , 8.2126272000000000e+00 , -7.1390600000000004e-01 , -5.8490200000000003e-01 , -3.8500499999999999e-01 -8.3253836858440877e-01 , 4.6628047909827774e+00 , 7.2523016000000009e+00 , 3.5694799999999999e-01 , -6.1175800000000002e-01 , 7.0593200000000000e-01 -9.8163020539125578e-01 , 4.4517211470427354e+00 , 7.0111568000000002e+00 , -6.5031499999999998e-01 , 1.6531000000000001e-01 , 7.4146000000000001e-01 -1.0873681730393328e+00 , 4.3016518435351205e+00 , 6.8686144000000002e+00 , 3.9488499999999999e-01 , 7.4677099999999996e-01 , -5.3516300000000006e-01 -1.1254597539325482e+00 , 4.2465425557212386e+00 , 6.9088624000000003e+00 , -6.6517899999999996e-01 , 2.7816100000000000e-02 , 7.4616600000000000e-01 -1.1470554259952834e+00 , 4.2116045187986355e+00 , 6.9930295999999998e+00 , -2.8174700000000003e-01 , -9.2133900000000002e-01 , -2.6786700000000002e-01 -1.1592886320736016e+00 , 4.1917895005396533e+00 , 7.1133679999999995e+00 , -4.5713499999999997e-02 , 9.2969400000000002e-01 , 3.6548500000000000e-01 -1.0634627762271398e+00 , 4.3212655424894013e+00 , 7.5932656000000005e+00 , 4.9008200000000002e-01 , -7.4475899999999995e-01 , 4.5293899999999998e-01 -1.2097271987805598e+00 , 4.1158589409342206e+00 , 7.2901160000000003e+00 , 2.5054000000000000e-02 , 4.4429700000000000e-01 , 8.9552900000000002e-01 -1.2725057351398130e+00 , 4.0257166667350441e+00 , 7.2513552000000008e+00 , 3.7992700000000001e-01 , 4.1447499999999998e-01 , 8.2696199999999997e-01 -1.3005496746390106e+00 , 3.9825459982687934e+00 , 7.3329535999999997e+00 , 1.4660400000000001e-02 , 5.0449800000000000e-01 , 8.6328800000000006e-01 -1.3424874528822306e+00 , 3.9205866875093722e+00 , 7.3664000000000005e+00 , 4.0696199999999999e-01 , 5.2866400000000002e-01 , 7.4491300000000005e-01 -1.4673930909722355e+00 , 3.7456986907717735e+00 , 7.0625536000000002e+00 , 4.7114800000000001e-01 , 7.3966600000000005e-01 , -4.8053600000000002e-01 -1.5361027634041098e+00 , 3.6477495335111922e+00 , 6.9652824000000004e+00 , 9.8482000000000000e-02 , 5.4796800000000001e-01 , 8.3068200000000003e-01 -1.5682739533682806e+00 , 3.6002370764274034e+00 , 7.0209016000000002e+00 , 1.2915199999999999e-01 , 5.2167900000000000e-01 , 8.4331000000000000e-01 -1.6070979272914510e+00 , 3.5431433357091655e+00 , 7.0462463999999994e+00 , 2.5467400000000001e-01 , 5.2839400000000003e-01 , 8.0990200000000001e-01 -1.5621776543238495e+00 , 3.5982372657045434e+00 , 7.4840032000000001e+00 , -8.9075099999999996e-01 , -4.2397899999999999e-01 , -1.6372000000000000e-01 -1.6929513171953199e+00 , 3.4177686241748075e+00 , 7.0536095999999997e+00 , 7.1844600000000003e-01 , 5.9873200000000004e-01 , -3.5405500000000001e-01 -1.6244401156387829e+00 , 3.5040428909914993e+00 , 7.6727528000000005e+00 , 9.9219599999999997e-01 , 9.1204999999999994e-02 , 8.5024799999999998e-02 -1.7580638649913276e+00 , 3.3205865185337826e+00 , 7.1754351999999999e+00 , -5.0331500000000001e-02 , -8.0142800000000003e-01 , 5.9597000000000000e-01 -1.8204917771310618e+00 , 3.2328774889476408e+00 , 7.0538176000000004e+00 , -5.2759000000000000e-01 , -8.2782900000000004e-01 , -1.9064999999999999e-01 -1.8672365617598299e+00 , 3.1647934970757614e+00 , 7.0210056000000005e+00 , 9.0434099999999995e-01 , -4.2163499999999998e-01 , -6.6278299999999998e-02 -1.7425302334009016e+00 , 3.3191249278365031e+00 , 8.2242023999999994e+00 , -9.6163799999999999e-01 , 1.8884300000000001e-01 , 1.9897300000000001e-01 -1.8110852043337644e+00 , 3.2233516080189406e+00 , 8.1112792000000002e+00 , 6.0209999999999997e-01 , -7.7887899999999999e-01 , 1.7556700000000000e-01 --1.1481789834452396e+00 , 8.0829489780862396e+00 , -2.1685360000000031e-01 , -4.1998800000000003e-02 , 2.3456099999999999e-01 , 9.7119400000000000e-01 --1.4831775524945496e+00 , 8.6060820693084583e+00 , -3.6385760000000023e-01 , -5.0572800000000001e-02 , 2.2694600000000001e-01 , 9.7259300000000004e-01 --1.8894370084198333e+00 , 9.2399540121008901e+00 , -5.4566000000000026e-01 , -6.1937899999999997e-02 , 2.4205199999999999e-01 , 9.6828400000000003e-01 --2.4430418014251192e+00 , 1.0105436138955035e+01 , -8.1619520000000012e-01 , -7.5573899999999999e-02 , 2.2883500000000001e-01 , 9.7052700000000003e-01 --3.0459660504596568e+00 , 1.1045919024265205e+01 , -1.0833400000000002e+00 , -6.7380399999999993e-02 , 2.0752699999999999e-01 , 9.7590600000000005e-01 --3.7585432860173640e+00 , 1.2159956766350945e+01 , -1.3874880000000003e+00 , -6.5831100000000004e-02 , 2.1164700000000000e-01 , 9.7512699999999997e-01 --4.5955423107502655e+00 , 1.3464759922374233e+01 , -1.7251864000000001e+00 , -9.5174300000000003e-02 , 1.9963900000000001e-01 , 9.7523599999999999e-01 --5.8695055733755375e+00 , 1.5453717218979962e+01 , -2.2861728000000001e+00 , 1.0420400000000000e-01 , -1.9802700000000001e-01 , -9.7464200000000001e-01 --7.3966088580425797e+00 , 1.7835558886841017e+01 , -2.9114416000000007e+00 , -1.2413900000000000e-01 , -2.0374000000000000e-02 , 9.9205600000000005e-01 --7.8367460064473775e+00 , 1.8512384586508766e+01 , -2.8084816000000004e+00 , -2.3152499999999999e-02 , -2.4184900000000001e-01 , 9.7003799999999996e-01 --8.2138333961168062e+00 , 1.9089296720262503e+01 , -2.6444632000000006e+00 , -1.5808200000000001e-02 , -2.6369399999999998e-01 , 9.6447700000000003e-01 --8.5904830524637976e+00 , 1.9666509817433329e+01 , -2.4581992000000001e+00 , -1.5716700000000000e-02 , -2.6703399999999999e-01 , 9.6355900000000005e-01 --9.0112306887621436e+00 , 2.0310868438511928e+01 , -2.2698136000000009e+00 , -1.5716700000000000e-02 , -2.6703399999999999e-01 , 9.6355900000000005e-01 --1.1945370737283804e+01 , 2.4877003496355034e+01 , -3.1424256000000002e+00 , 7.7287599999999998e-02 , -1.8210699999999999e-01 , 9.8023700000000002e-01 --1.2519660762719388e+01 , 2.5756374555883241e+01 , -2.8790768000000000e+00 , 1.2308900000000000e-01 , -3.1234299999999998e-01 , 9.4196100000000005e-01 --1.3143873822841055e+01 , 2.6711472944335497e+01 , -2.5988487999999998e+00 , -2.0560200000000001e-01 , 2.8018100000000001e-01 , -9.3767100000000003e-01 --1.3755726295851844e+01 , 2.7646792747466396e+01 , -2.2767504000000001e+00 , -2.9687999999999998e-01 , 2.3928400000000000e-01 , -9.2444899999999997e-01 --1.6148883469055772e+01 , 3.1353227746926809e+01 , -2.4468632000000001e+00 , -4.8797400000000002e-01 , 3.8674600000000003e-02 , -8.7200100000000003e-01 --7.0093652364756398e+00 , 1.7118086640825354e+01 , 5.8253199999999983e-01 , 6.4901799999999998e-01 , -7.5895800000000002e-01 , 5.2518900000000000e-02 --1.6375565801992224e+01 , 3.1642813351649298e+01 , -6.5206240000000015e-01 , 5.3807099999999997e-01 , -2.5652100000000000e-01 , 8.0291800000000002e-01 --7.1878283167197878e+00 , 1.7363540230117366e+01 , 1.4836795199999999e+00 , 6.4901799999999998e-01 , -7.5895800000000002e-01 , 5.2518900000000000e-02 --7.1382346799352607e+00 , 1.7277240720185471e+01 , 1.8034764000000001e+00 , -9.6772800000000003e-01 , 2.4645600000000001e-01 , -5.2557500000000000e-02 --6.9744338013912195e+00 , 1.7011199825647132e+01 , 2.1305595199999998e+00 , -9.9106200000000000e-01 , 4.8124800000000002e-02 , 1.2441900000000000e-01 --6.6929910199712186e+00 , 1.6566219902019096e+01 , 2.4540400800000000e+00 , -7.3497099999999996e-02 , 5.0948800000000005e-01 , 8.5733300000000001e-01 --6.2734170900367374e+00 , 1.5906554994819713e+01 , 2.7637458399999999e+00 , -7.3497999999999994e-02 , 5.0948700000000002e-01 , 8.5733400000000004e-01 --2.8355443249484145e+00 , 1.0512304198056269e+01 , 5.1144256000000006e+00 , 6.3040499999999999e-01 , 1.6627000000000000e-01 , -7.5824999999999998e-01 --2.6302811863147593e+00 , 1.0190288003701481e+01 , 5.2042712000000009e+00 , 6.8816800000000000e-01 , -1.6084600000000001e-02 , -7.2537300000000005e-01 --2.5451135554291735e+00 , 1.0055022291387766e+01 , 5.3363303999999996e+00 , 6.8816800000000000e-01 , -1.6084399999999999e-02 , -7.2537300000000005e-01 --2.4150501467976087e+00 , 9.8509263716117488e+00 , 5.4420256000000000e+00 , 6.8816800000000000e-01 , -1.6084500000000002e-02 , -7.2537300000000005e-01 --2.4664045393145111e+00 , 9.9225646243516081e+00 , 5.6338016000000000e+00 , 6.8816800000000000e-01 , -1.6084500000000002e-02 , -7.2537300000000005e-01 --1.6307767385140037e+00 , 8.6414867747357675e+00 , 5.3405319999999996e+00 , 7.0784300000000000e-01 , -6.9437300000000002e-01 , -1.2963500000000000e-01 --1.5787325906471517e+00 , 8.5563949800995420e+00 , 5.4510528000000003e+00 , 6.8786899999999995e-01 , -7.1724200000000005e-01 , -1.1136000000000000e-01 --1.6001994618335513e+00 , 8.5853423921515137e+00 , 5.6059920000000005e+00 , 5.8996700000000002e-01 , -8.0735100000000004e-01 , -1.1135600000000001e-02 --4.6528005458170130e+00 , 1.3232221174093263e+01 , 7.7598735999999997e+00 , -7.3660699999999996e-02 , -8.7349399999999999e-01 , 4.8122900000000002e-01 -5.1466458611509003e-02 , 6.0604626616960813e+00 , 4.7470144000000003e+00 , 4.5369300000000001e-01 , -7.5982099999999997e-01 , 4.6565499999999999e-01 --5.9132046608682653e-01 , 7.0347911138811421e+00 , 5.3033935999999997e+00 , -9.7272700000000001e-01 , -1.0609499999999999e-01 , 2.0626900000000001e-01 --6.1272288300427613e-01 , 7.0648339669069733e+00 , 5.4321351999999994e+00 , -9.7272700000000001e-01 , -1.0609499999999999e-01 , 2.0626900000000001e-01 -3.3887972426457558e-01 , 5.6141038032860102e+00 , 4.7800864000000001e+00 , 9.7755599999999998e-01 , -2.0405999999999999e-01 , 5.2389199999999997e-02 -3.6459916361613698e-01 , 5.5726372977297061e+00 , 4.8379727999999993e+00 , 8.7663599999999997e-01 , -4.4932200000000000e-01 , -1.7210000000000000e-01 -4.6318338043342067e-01 , 5.4205342233178548e+00 , 4.8314000000000004e+00 , -6.8607300000000004e-01 , -5.3127500000000005e-01 , -4.9704199999999998e-01 -1.9318861140844801e-02 , 6.0906937286396117e+00 , 5.3171320000000009e+00 , -3.4521000000000002e-01 , 4.1724400000000000e-01 , -8.4067700000000001e-01 -2.5248673298911539e-01 , 5.7343180467891752e+00 , 5.1896696000000002e+00 , 2.1354500000000001e-01 , 1.2293500000000000e-01 , -9.6916700000000000e-01 -4.9258084327269103e-01 , 5.3674826991600018e+00 , 5.0381415999999994e+00 , -8.2096000000000002e-01 , -3.6440400000000001e-01 , 4.3958399999999997e-01 -5.7580518893976396e-01 , 5.2406518513881464e+00 , 5.0324527999999997e+00 , -7.4623600000000001e-01 , 2.0844300000000000e-02 , 6.6535500000000003e-01 -5.6864842718685948e-01 , 5.2476054309570994e+00 , 5.1181592000000000e+00 , -7.4623600000000001e-01 , 2.0844200000000000e-02 , 6.6535500000000003e-01 -6.4584354109657283e-01 , 5.1282644585952655e+00 , 5.1114928000000006e+00 , -7.4623600000000001e-01 , 2.0844200000000000e-02 , 6.6535500000000003e-01 --7.4575480106349268e-01 , 7.2230593787013042e+00 , 6.8162400000000005e+00 , -5.4329300000000003e-01 , 8.1683600000000001e-01 , -1.9393800000000000e-01 --7.5948090507748489e-01 , 7.2385287809275409e+00 , 6.9744448000000006e+00 , -5.4329300000000003e-01 , 8.1683600000000001e-01 , -1.9393700000000000e-01 --7.7514847118951380e-01 , 7.2578174043259382e+00 , 7.1406159999999996e+00 , 4.3090000000000001e-01 , -8.8532200000000005e-01 , 1.7472599999999999e-01 --7.9381409765205113e-01 , 7.2809551308789295e+00 , 7.3147327999999998e+00 , 4.3090000000000001e-01 , -8.8532200000000005e-01 , 1.7472599999999999e-01 --8.1555077960379219e-01 , 7.3069933496284696e+00 , 7.4972840000000005e+00 , 3.7631999999999999e-01 , -9.0490899999999996e-01 , 1.9880500000000001e-01 --8.3832507214361351e-01 , 7.3359516338751334e+00 , 7.6888415999999999e+00 , 2.0808299999999999e-01 , -9.5903400000000005e-01 , 1.9223799999999999e-01 --8.5452237650451890e-01 , 7.3542415059993509e+00 , 7.8763328000000001e+00 , -3.0154399999999998e-01 , -9.4117799999999996e-01 , 1.5249499999999999e-01 --8.8048715859717719e-01 , 7.3881028730408733e+00 , 8.0862776000000007e+00 , -5.0988900000000004e-01 , -7.2607299999999997e-01 , 4.6133700000000000e-01 -4.5097269345039992e-02 , 5.9999592592640880e+00 , 6.8222616000000009e+00 , 4.8512200000000000e-01 , -4.8295500000000002e-01 , -7.2897900000000004e-01 -9.2640998152034859e-02 , 5.9238769594486431e+00 , 6.8763936000000001e+00 , 4.8512300000000003e-01 , -4.8295500000000002e-01 , -7.2897900000000004e-01 -1.4927023343470225e-01 , 5.8356397828341340e+00 , 6.9143328000000004e+00 , 4.8512300000000003e-01 , -4.8295500000000002e-01 , -7.2897900000000004e-01 -1.9734078632647889e-01 , 5.7597173331675604e+00 , 6.9641175999999998e+00 , 4.8512300000000003e-01 , -4.8295500000000002e-01 , -7.2897900000000004e-01 -8.6343300962252867e-01 , 4.7651654059944324e+00 , 5.9118040000000001e+00 , 6.4862200000000003e-01 , 1.4014499999999999e-01 , -7.4809700000000001e-01 -9.0992239689895738e-01 , 4.6933368321685816e+00 , 5.9235664000000003e+00 , -6.3014400000000004e-01 , 1.9726600000000000e-02 , 7.7622800000000003e-01 -9.5164907871610938e-01 , 4.6270688974022054e+00 , 5.9408928000000003e+00 , -6.5350500000000000e-01 , 5.5950600000000003e-02 , 7.5485100000000005e-01 -9.9861096495940727e-01 , 4.5555058882425037e+00 , 5.9488072000000001e+00 , -4.7644799999999998e-01 , 3.2279400000000003e-01 , 8.1780299999999995e-01 -1.0248465247018244e+00 , 4.5124355501069875e+00 , 5.9936103999999997e+00 , -2.0684800000000000e-01 , 5.1812999999999998e-01 , 8.2991300000000001e-01 -1.0562599335673102e+00 , 4.4641646263224963e+00 , 6.0295215999999998e+00 , -6.9940499999999999e-03 , 6.3370199999999999e-01 , 7.7354599999999996e-01 -1.0837332839457365e+00 , 4.4196261338848011e+00 , 6.0725360000000004e+00 , 2.4704899999999999e-01 , 7.1317799999999998e-01 , 6.5600700000000001e-01 -1.0891866092872782e+00 , 4.4069365964748197e+00 , 6.1635672000000001e+00 , -3.7476799999999999e-01 , -7.5331700000000001e-01 , -5.4042900000000005e-01 -1.1037213364049707e+00 , 4.3821019617259740e+00 , 6.2383952000000003e+00 , -4.8586499999999999e-01 , -8.0164500000000005e-01 , -3.4828199999999998e-01 -1.0331662756138258e+00 , 4.4818311796161598e+00 , 6.5233344000000004e+00 , -2.6022400000000001e-01 , -9.5274000000000003e-01 , 1.5674800000000000e-01 -9.5386714145100626e-01 , 4.5930098449709700e+00 , 6.8474295999999999e+00 , 7.5465899999999997e-01 , -6.3789200000000001e-01 , -1.5356700000000001e-01 -1.0055421618811242e+00 , 4.5137750664078888e+00 , 6.8499048000000000e+00 , 7.1191599999999999e-01 , -6.1662200000000000e-01 , -3.3608399999999999e-01 -9.0895098118050255e-01 , 4.6496963372494307e+00 , 7.2509703999999999e+00 , 2.3550499999999999e-01 , -6.3028700000000004e-01 , 7.3978100000000002e-01 -1.0520324082539054e+00 , 4.4373094307470007e+00 , 7.0073608000000007e+00 , -1.2910700000000000e-01 , 3.4051900000000002e-01 , 9.3133200000000005e-01 -1.1032111329621901e+00 , 4.3571569607134952e+00 , 7.0051559999999995e+00 , 4.2127500000000001e-01 , -4.6233200000000002e-01 , 7.8024099999999996e-01 -1.1732818641301077e+00 , 4.2511324343395511e+00 , 6.9471136000000007e+00 , 6.0231199999999996e-01 , 3.2191100000000000e-01 , -7.3047499999999999e-01 -1.2125600042995810e+00 , 4.1895571908386646e+00 , 6.9766496000000000e+00 , 5.7162299999999999e-02 , 9.7380999999999995e-01 , 2.2005800000000000e-01 -1.1704494420238625e+00 , 4.2442444171813234e+00 , 7.2707199999999998e+00 , -4.9095400000000000e-01 , -7.2643999999999997e-01 , -4.8088300000000000e-01 -1.2390905417234224e+00 , 4.1393414228519871e+00 , 7.2073736000000004e+00 , -4.4390299999999999e-01 , -5.3399600000000003e-01 , -7.1958200000000005e-01 -1.2838864559409264e+00 , 4.0708729869138267e+00 , 7.2249808000000000e+00 , -4.3026900000000001e-01 , -2.9840699999999998e-01 , -8.5195200000000004e-01 -1.3119172278392917e+00 , 4.0237521623194343e+00 , 7.2974480000000002e+00 , 1.3005000000000000e-01 , 7.2273299999999996e-01 , 6.7878099999999997e-01 -1.3538768996779920e+00 , 3.9588685089910118e+00 , 7.3216799999999997e+00 , 1.2513600000000000e-01 , 3.6672900000000003e-01 , 9.2187399999999997e-01 -1.3970016349433354e+00 , 3.8926399086370527e+00 , 7.3447160000000000e+00 , -2.3684200000000000e-01 , -5.6174100000000005e-01 , -7.9268700000000003e-01 -1.4985970327314733e+00 , 3.7433968739120527e+00 , 7.1157807999999996e+00 , -4.6984900000000003e-02 , -2.1936400000000002e-02 , 9.9865499999999996e-01 -1.5707561173233042e+00 , 3.6350260699741170e+00 , 6.9885576000000000e+00 , -4.9763700000000000e-01 , 2.8295900000000002e-01 , 8.1993400000000005e-01 -1.5800783799478091e+00 , 3.6144299668324753e+00 , 7.1413336000000003e+00 , -8.8283699999999998e-01 , 4.2871500000000001e-01 , 1.9183700000000001e-01 -1.6386774179468904e+00 , 3.5271544997678861e+00 , 7.0684503999999997e+00 , 4.0821499999999999e-01 , 4.1809600000000002e-01 , 8.1151499999999999e-01 -1.6555526030217496e+00 , 3.4967987882817688e+00 , 7.2007175999999999e+00 , 8.6986200000000000e-02 , -5.8590299999999998e-02 , 9.9448499999999995e-01 -1.7180968965272689e+00 , 3.4037014731328497e+00 , 7.0945440000000000e+00 , 7.8112700000000002e-01 , -2.9737799999999998e-01 , -5.4900499999999997e-01 -1.7417670990890592e+00 , 3.3635174105521086e+00 , 7.1953199999999997e+00 , 4.6630800000000000e-01 , -4.4656600000000002e-01 , -7.6363400000000003e-01 -1.7971680049486265e+00 , 3.2812602038172223e+00 , 7.1150424000000001e+00 , -9.4120199999999998e-01 , 1.1974500000000000e-01 , 3.1591000000000002e-01 -1.8439154292131064e+00 , 3.2091868140067339e+00 , 7.0730056000000001e+00 , -7.9483499999999996e-01 , -5.8780600000000005e-01 , -1.5073800000000001e-01 -1.8874853727195895e+00 , 3.1430909079270943e+00 , 7.0493560000000004e+00 , -8.7029199999999995e-01 , 4.6952300000000002e-01 , -1.4879400000000001e-01 -1.7817514900687468e+00 , 3.2701340324520105e+00 , 8.1527752000000007e+00 , 8.9814600000000000e-01 , 3.5907200000000000e-01 , 2.5377200000000000e-01 --8.7475425227790593e-01 , 8.0445372084296416e+00 , -1.9635520000000017e-01 , -4.1998800000000003e-02 , 2.3456199999999999e-01 , 9.7119400000000000e-01 --1.1737035275405909e+00 , 8.5437375266565390e+00 , -3.3320879999999997e-01 , -5.0572800000000001e-02 , 2.2694600000000001e-01 , 9.7259300000000004e-01 --1.5054340323691418e+00 , 9.0971816853137568e+00 , -4.7667679999999990e-01 , -6.1550800000000003e-02 , 2.4447900000000000e-01 , 9.6769899999999998e-01 --2.0686794722653667e+00 , 1.0040741670207197e+01 , -7.9387680000000005e-01 , -7.1452199999999993e-02 , 2.3058400000000001e-01 , 9.7042600000000001e-01 --2.5124339662942834e+00 , 1.0781426444126264e+01 , -9.6998000000000006e-01 , -6.2613600000000005e-02 , 2.0889500000000000e-01 , 9.7593200000000002e-01 --3.0557641002669440e+00 , 1.1686418192581270e+01 , -1.1897424000000001e+00 , -6.3246800000000006e-02 , 2.1439300000000000e-01 , 9.7469799999999995e-01 --3.8530825592692191e+00 , 1.3018684086389738e+01 , -1.5565504000000003e+00 , -7.8172199999999997e-02 , 2.1361600000000000e-01 , 9.7378500000000001e-01 --4.8447440653508176e+00 , 1.4675317736511570e+01 , -1.9993616000000003e+00 , -9.8397499999999999e-02 , 2.0553800000000000e-01 , 9.7369000000000006e-01 --6.1199088514263451e+00 , 1.6804528049849054e+01 , -2.5549192000000005e+00 , -1.0388100000000000e-01 , 1.2655500000000000e-01 , 9.8650499999999997e-01 --7.1392802004103686e+00 , 1.8500961959398218e+01 , -2.8585992000000005e+00 , -2.3152499999999999e-02 , -2.4184900000000001e-01 , 9.7003799999999996e-01 --7.4743805750216143e+00 , 1.9045955376073358e+01 , -2.6913672000000002e+00 , -2.1269199999999999e-02 , -2.4537800000000001e-01 , 9.6919400000000000e-01 --7.8347076427455296e+00 , 1.9632738024916119e+01 , -2.5172400000000001e+00 , -1.4736800000000000e-02 , -2.6779700000000001e-01 , 9.6336299999999997e-01 --8.2273644120261942e+00 , 2.0271118270259212e+01 , -2.3367168000000005e+00 , -1.5716700000000000e-02 , -2.6703399999999999e-01 , 9.6355900000000005e-01 --1.1530973381607520e+01 , 2.5750715614180319e+01 , -2.9965343999999998e+00 , 1.2308900000000000e-01 , -3.1234299999999998e-01 , 9.4196100000000005e-01 --6.5648722527235321e+00 , 1.7384447242775622e+01 , 7.5051279999999987e-01 , 6.4901799999999998e-01 , -7.5895800000000002e-01 , 5.2518900000000000e-02 --6.7237064171915577e+00 , 1.7634728732200596e+01 , 1.0260275200000000e+00 , 6.4901799999999998e-01 , -7.5895800000000002e-01 , 5.2518900000000000e-02 --6.7414412878039212e+00 , 1.7650552784845942e+01 , 1.3376416799999999e+00 , 6.4901799999999998e-01 , -7.5895800000000002e-01 , 5.2518900000000000e-02 --6.7621136150635035e+00 , 1.7670450456104476e+01 , 1.6484633600000000e+00 , 6.4901799999999998e-01 , -7.5895800000000002e-01 , 5.2518900000000000e-02 --6.7748363603036577e+00 , 1.7676572877634740e+01 , 1.9604291439999999e+00 , -9.6772800000000003e-01 , 2.4645600000000001e-01 , -5.2557500000000000e-02 --6.6778220361427429e+00 , 1.7500349921923057e+01 , 2.2817141599999999e+00 , -9.6772800000000003e-01 , 2.4645600000000001e-01 , -5.2557500000000000e-02 --5.7473078739026917e+00 , 1.5949321238299605e+01 , 2.6403321599999998e+00 , 1.9255600000000000e-01 , -3.8277699999999998e-01 , -9.0355099999999999e-01 --3.1844496588692044e+00 , 1.1590932971550034e+01 , 5.4502103999999996e+00 , 5.6933900000000004e-01 , 3.0182399999999998e-01 , -7.6469299999999996e-01 --2.3877600201377636e+00 , 1.0283964821035919e+01 , 5.2835400000000003e+00 , 6.8816800000000000e-01 , -1.6084600000000001e-02 , -7.2537300000000005e-01 --1.4516211047944507e+00 , 8.7284310005524670e+00 , 5.5520472000000005e+00 , -5.8830600000000000e-01 , 7.9979800000000001e-01 , 1.1924600000000000e-01 --1.4623441819282661e+00 , 8.7389274848468510e+00 , 5.7020152000000000e+00 , -5.8830600000000000e-01 , 7.9979800000000001e-01 , 1.1924600000000000e-01 --4.1479304130529737e+00 , 1.3073944387502870e+01 , 7.7459376000000004e+00 , -1.0081800000000000e-01 , -7.9532099999999994e-01 , 5.9774600000000000e-01 --4.1756831812213395e+00 , 1.3106732339716343e+01 , 8.0134048000000000e+00 , -1.8642700000000001e-01 , -9.1761599999999999e-01 , 3.5103499999999999e-01 -4.3078867887156225e-01 , 5.6658532371025956e+00 , 4.6612456000000000e+00 , 9.2977600000000005e-01 , 2.3533399999999999e-01 , -2.8308100000000003e-01 -4.4876859686288517e-01 , 5.6330791965923437e+00 , 4.7238015999999998e+00 , 9.7755599999999998e-01 , -2.0405999999999999e-01 , 5.2389199999999997e-02 --3.2359005745281886e+00 , 1.1560235343793934e+01 , 7.9691840000000003e+00 , -7.7993100000000004e-01 , -3.9389000000000002e-01 , -4.8637300000000000e-01 --3.8956609087483773e-02 , 6.4100557581227466e+00 , 5.3192328000000000e+00 , -1.5071300000000001e-01 , -1.2971299999999999e-01 , -9.8003099999999999e-01 --3.0485094878269781e-02 , 6.3908789283377399e+00 , 5.4103575999999993e+00 , -1.5071300000000001e-01 , -1.2971299999999999e-01 , -9.8003099999999999e-01 -2.9305587413267786e-01 , 5.8685536661811808e+00 , 5.1952648000000003e+00 , -1.7789400000000000e-01 , -4.6729999999999999e-01 , 8.6601600000000001e-01 -3.6895951043597952e-01 , 5.7423186958557739e+00 , 5.2067671999999998e+00 , -4.6408700000000003e-01 , -2.6412200000000002e-01 , 8.4549600000000003e-01 --1.5100613737640471e+00 , 8.7437819075341796e+00 , 7.2917280000000000e+00 , 4.0786799999999998e-02 , -9.7997599999999996e-01 , 1.9489300000000001e-01 -5.8132263851672983e-01 , 5.3932497987077799e+00 , 5.1480383999999999e+00 , -9.4322099999999998e-01 , 1.6770800000000000e-01 , 2.8671799999999997e-01 -5.6179007242033352e-01 , 5.4215175498905026e+00 , 5.2525688000000006e+00 , -9.6269800000000005e-01 , 2.2016100000000000e-01 , 1.5729899999999999e-01 -4.0315957950426373e-01 , 5.6703441007007847e+00 , 5.5261616000000000e+00 , 8.4456500000000001e-01 , 3.6963400000000002e-01 , 3.8740200000000002e-01 -4.4267359630007075e-01 , 5.6031713409979069e+00 , 5.5701432000000004e+00 , 6.8457800000000002e-01 , 1.1574600000000000e-01 , 7.1969099999999997e-01 -5.7366278598751030e-01 , 5.3901477872274324e+00 , 5.4946704000000004e+00 , -1.2319600000000000e-02 , -9.5043500000000003e-01 , 3.1067899999999998e-01 --2.3513008511992881e+00 , 1.0030609093047945e+01 , 9.4832992000000012e+00 , 5.1399899999999998e-01 , 2.5768099999999999e-01 , -8.1817200000000001e-01 --2.6581424136380329e+00 , 1.0505140112312557e+01 , 1.0139320800000000e+01 , -8.8146000000000002e-01 , -4.7211999999999998e-01 , -1.1444899999999999e-02 --2.0671258147650358e+00 , 9.5577547521686519e+00 , 9.5475400000000015e+00 , -5.0087099999999996e-01 , 5.7278299999999997e-03 , 8.6550300000000002e-01 --2.6510034184363649e+00 , 1.0470550522822212e+01 , 1.0643751999999999e+01 , 7.9416699999999996e-01 , 5.0630699999999995e-01 , 3.3608300000000002e-01 --9.5564902594283474e-01 , 7.7820259501480606e+00 , 8.3073399999999999e+00 , 1.3755100000000001e-01 , -3.3947300000000002e-01 , 9.3050400000000000e-01 --7.3943832221282957e-01 , 7.4338006643404730e+00 , 8.1481992000000005e+00 , -5.0988800000000001e-01 , -7.2607299999999997e-01 , 4.6133700000000000e-01 -1.7495644415923262e-01 , 5.9866595866328911e+00 , 6.8208576000000001e+00 , 4.8512300000000003e-01 , -4.8295500000000002e-01 , -7.2897900000000004e-01 --1.9585402098793971e+00 , 9.3312018061101654e+00 , 1.0575434399999999e+01 , -3.6464700000000000e-01 , 7.8694100000000000e-01 , 4.9775199999999997e-01 -2.4879585309622509e-01 , 5.8581279369589945e+00 , 6.9523136000000001e+00 , 4.8512200000000000e-01 , -4.8295500000000002e-01 , -7.2897900000000004e-01 -2.5072969419682312e-01 , 5.8490120204644640e+00 , 7.0814192000000000e+00 , 7.6003699999999996e-01 , -5.6479999999999997e-01 , -3.2147199999999998e-01 -2.2710093359242967e-01 , 5.8802695805484806e+00 , 7.2631071999999994e+00 , 7.7716700000000005e-01 , -5.2054599999999995e-01 , -3.5361399999999998e-01 -9.5649640469698594e-01 , 4.7358539712117906e+00 , 5.9864448000000001e+00 , 6.6818000000000000e-01 , 1.1904099999999999e-01 , -7.3441500000000004e-01 -1.0010974037451588e+00 , 4.6615627434396059e+00 , 5.9961479999999998e+00 , 5.9862800000000005e-01 , -2.7519600000000002e-02 , -8.0055399999999999e-01 -1.0419966682153772e+00 , 4.5938643115189546e+00 , 6.0114255999999999e+00 , -5.6338100000000002e-01 , 1.2158099999999999e-03 , 8.2619600000000004e-01 -1.0860946344028952e+00 , 4.5208506120560861e+00 , 6.0168440000000007e+00 , -5.6894000000000000e-01 , 2.0029300000000000e-01 , 7.9761499999999996e-01 -1.1154270380107252e+00 , 4.4704600037839386e+00 , 6.0522976000000002e+00 , -1.8454200000000001e-01 , 6.1355300000000002e-01 , 7.6778700000000000e-01 -1.1419277293076968e+00 , 4.4258304588291777e+00 , 6.0946776000000007e+00 , -1.8949099999999999e-01 , 5.5411999999999995e-01 , 8.1058300000000005e-01 -1.1714914628497795e+00 , 4.3739374609540587e+00 , 6.1280200000000002e+00 , 1.0478100000000000e-01 , 6.2278400000000000e-01 , 7.7534599999999998e-01 -1.1921385598732814e+00 , 4.3378839357646672e+00 , 6.1853656000000008e+00 , 4.6646700000000002e-01 , 6.9400799999999996e-01 , 5.4841700000000004e-01 -1.1966749710318059e+00 , 4.3268018782019571e+00 , 6.2841864000000003e+00 , 5.4059000000000001e-01 , 7.5676399999999999e-01 , 3.6751899999999998e-01 -1.1248450695525118e+00 , 4.4316527157525867e+00 , 6.5889792000000007e+00 , 4.6047600000000000e-01 , 8.7107199999999996e-01 , 1.7086699999999999e-01 -1.0257678054768578e+00 , 4.5753257982070874e+00 , 6.9858120000000001e+00 , 6.1737399999999998e-01 , -4.5737600000000000e-01 , -6.4004399999999995e-01 -9.9862060752331994e-01 , 4.6101465798980401e+00 , 7.2055743999999997e+00 , 2.3874699999999999e-01 , -7.2830300000000003e-01 , 6.4232000000000000e-01 -1.1017917017551251e+00 , 4.4471626853717972e+00 , 7.0563032000000003e+00 , -2.6853700000000003e-01 , -4.6372500000000000e-01 , 8.4430300000000003e-01 -1.1695117936654438e+00 , 4.3383907946971760e+00 , 6.9999560000000001e+00 , 3.6306800000000000e-02 , -1.5271399999999999e-01 , 9.8760300000000001e-01 -1.2324632219401355e+00 , 4.2362925453185687e+00 , 6.9493495999999997e+00 , 5.7162400000000002e-02 , 9.7380999999999995e-01 , 2.2005800000000000e-01 -1.2416030038826904e+00 , 4.2154366095076741e+00 , 7.0691264000000000e+00 , 1.4492500000000000e-01 , 9.8204999999999998e-01 , 1.2072200000000000e-01 -1.2778188918628215e+00 , 4.1545564457311848e+00 , 7.1067016000000001e+00 , -8.9707999999999993e-03 , 6.9835100000000006e-01 , 7.1570000000000000e-01 -1.2847568643862175e+00 , 4.1364588612989408e+00 , 7.2449903999999998e+00 , -1.4215900000000001e-01 , 1.3407300000000000e-01 , -9.8072199999999998e-01 -1.3370311461210584e+00 , 4.0514986092991681e+00 , 7.2244504000000003e+00 , 2.7722200000000002e-01 , 4.9772499999999997e-01 , 8.2183799999999996e-01 -1.3661851638162541e+00 , 3.9991193199986572e+00 , 7.2869128000000005e+00 , 5.1122199999999995e-01 , 6.0033999999999998e-01 , 6.1501600000000001e-01 -1.4157402202462563e+00 , 3.9186271045868191e+00 , 7.2721760000000000e+00 , 1.3788700000000001e-01 , 4.5159700000000003e-01 , 8.8150300000000004e-01 -1.4483924832636856e+00 , 3.8626062198849671e+00 , 7.3225536000000000e+00 , -7.6880599999999993e-02 , 5.2595599999999998e-01 , 8.4702999999999995e-01 -1.5741575063285249e+00 , 3.6717841356932772e+00 , 6.9661872000000002e+00 , -4.9763700000000000e-01 , 2.8295900000000002e-01 , 8.1993400000000005e-01 -1.6065070971955131e+00 , 3.6170920059514096e+00 , 7.0020360000000004e+00 , -7.4524900000000005e-01 , 3.3917599999999998e-01 , 5.7407699999999995e-01 -1.6114632630840704e+00 , 3.6005664328874998e+00 , 7.1740832000000001e+00 , 9.2398899999999995e-01 , -1.3365099999999999e-01 , -3.5830299999999998e-01 -1.5718023581529836e+00 , 3.6474307945513611e+00 , 7.5932136000000003e+00 , -8.2755100000000004e-01 , -3.8224399999999997e-01 , 4.1115600000000002e-01 -1.7017182318980393e+00 , 3.4536405923369764e+00 , 7.1333983999999999e+00 , 6.6212000000000004e-01 , 6.5940200000000004e-01 , -3.5607000000000000e-01 -1.6645978096149232e+00 , 3.4940481640689027e+00 , 7.5737240000000003e+00 , 8.8713200000000003e-01 , 4.5208399999999999e-01 , -9.2834100000000003e-02 -1.7659845635551714e+00 , 3.3431180489240422e+00 , 7.2256983999999997e+00 , 5.4157600000000000e-02 , 8.1513599999999997e-01 , 5.7673200000000002e-01 -1.8377915077508711e+00 , 3.2345909704020039e+00 , 7.0238552000000007e+00 , -4.1749399999999998e-01 , -2.7468199999999998e-01 , -8.6616899999999997e-01 -1.8779466918481009e+00 , 3.1687048378601892e+00 , 7.0110839999999994e+00 , 7.8275899999999998e-01 , -4.7280200000000000e-01 , 4.0465499999999999e-01 -1.7594062365799694e+00 , 3.3115417126652549e+00 , 8.1532432000000004e+00 , -5.2034899999999995e-01 , 3.3071800000000001e-01 , -7.8731399999999996e-01 -1.8108092817549883e+00 , 3.2285059340210074e+00 , 8.1315592000000017e+00 , 6.0209999999999997e-01 , -7.7887899999999999e-01 , 1.7556700000000000e-01 --2.7686880593239520e+00 , 1.1398123905798309e+01 , 6.4474976000000002e+00 , 2.2093800000000000e-01 , -3.7319900000000000e-01 , 9.0105999999999997e-01 --1.3153158268227219e+00 , 8.8851081915007661e+00 , 5.6525943999999999e+00 , -5.8830600000000000e-01 , 7.9979800000000001e-01 , 1.1924600000000000e-01 --1.3207543270834305e+00 , 8.8854489201820872e+00 , 5.8006904000000006e+00 , -5.5908300000000000e-01 , 8.1781599999999999e-01 , 1.3639299999999999e-01 --3.7307791169112425e+00 , 1.3011641649570791e+01 , 7.7786872000000002e+00 , -1.0081800000000000e-01 , -7.9532099999999994e-01 , 5.9774600000000000e-01 --3.7043129204374496e+00 , 1.2952064086394957e+01 , 7.9998952000000001e+00 , -1.0081800000000000e-01 , -7.9532099999999994e-01 , 5.9774600000000000e-01 --4.2077237359091662e+00 , 1.3799112367547254e+01 , 8.6661087999999999e+00 , 7.1122200000000002e-01 , 5.2762900000000001e-01 , -4.6451199999999998e-01 --1.0145072106322530e+00 , 8.3274757144012561e+00 , 6.1270320000000007e+00 , -1.4298800000000000e-01 , 4.6376299999999998e-01 , 8.7434400000000001e-01 --1.0196506697334153e+00 , 8.3273032285911874e+00 , 6.2725903999999995e+00 , -3.0311600000000001e-02 , 4.6319500000000002e-01 , 8.8573800000000003e-01 --4.0247290499777764e+00 , 1.3438699538262737e+01 , 9.3032648000000009e+00 , -8.5233599999999998e-01 , -4.0748299999999998e-01 , 3.2784200000000002e-01 -4.2665917019831467e-01 , 5.8500068419249507e+00 , 5.1106192000000004e+00 , -2.5198199999999998e-01 , -6.4164899999999997e-02 , 9.6560199999999996e-01 -4.6594162784639659e-01 , 5.7777678920129798e+00 , 5.1557240000000002e+00 , -3.0336400000000002e-01 , -8.4542400000000004e-02 , 9.4911699999999999e-01 -5.2879262917464875e-01 , 5.6660670789238825e+00 , 5.1733728000000001e+00 , 6.1253299999999999e-01 , -8.2325300000000004e-02 , -7.8614600000000001e-01 -5.5470343707289782e-01 , 5.6176888174807331e+00 , 5.2286488000000002e+00 , 7.5609000000000004e-01 , 1.0269200000000001e-01 , -6.4636099999999996e-01 -6.6692389669699303e-01 , 5.4227522277586475e+00 , 5.1810064000000002e+00 , -9.3264199999999997e-01 , -7.3830099999999997e-03 , 3.6072799999999999e-01 -6.2106667456500508e-01 , 5.4950166819990098e+00 , 5.3191079999999999e+00 , 7.3081600000000002e-01 , -6.6678700000000002e-01 , -1.4595600000000000e-01 -6.2482252990453979e-01 , 5.4821316117204724e+00 , 5.3982104000000000e+00 , -5.9657000000000004e-01 , 7.9246600000000000e-01 , 1.2689100000000000e-01 -6.3061164508354461e-01 , 5.4681624787339675e+00 , 5.4776767999999993e+00 , -5.9657000000000004e-01 , 7.9246600000000000e-01 , 1.2689100000000000e-01 -6.3262096182225336e-01 , 5.4598258916358127e+00 , 5.5632376000000008e+00 , 4.1837000000000002e-01 , -1.3467699999999999e-01 , 8.9823699999999995e-01 --2.4964773967953180e+00 , 1.0699726362900940e+01 , 1.0080342400000001e+01 , 6.8693700000000002e-01 , 2.2486999999999999e-01 , 6.9105000000000005e-01 --1.9660294891471022e+00 , 9.7978747038914378e+00 , 9.5540088000000001e+00 , -7.2140800000000005e-01 , -4.6121000000000002e-02 , 6.9097299999999995e-01 --1.0629844564383863e+00 , 8.2748844485133546e+00 , 8.4117248000000000e+00 , 5.7620600000000000e-01 , -3.7042000000000003e-01 , 7.2854399999999997e-01 --1.4272746198314055e+00 , 8.8703292174890578e+00 , 9.1707999999999998e+00 , -4.5486100000000002e-01 , -8.2070299999999996e-01 , 3.4575699999999998e-01 --1.8747832730039997e+00 , 9.6021033352524903e+00 , 1.0109129600000001e+01 , -8.8441099999999995e-01 , 6.1362800000000002e-02 , -4.6265800000000001e-01 --1.7560995606897203e+00 , 9.3912225737092427e+00 , 1.0152352000000000e+01 , -8.7985800000000003e-01 , -3.9605699999999999e-01 , -2.6266000000000000e-01 --4.7467309145936021e-01 , 7.2541556557572608e+00 , 8.1668048000000013e+00 , 3.7979099999999999e-01 , 9.1787799999999997e-01 , -1.1514900000000000e-01 --1.6868849628882572e+00 , 9.2462393803362772e+00 , 1.0517360799999999e+01 , -3.9717500000000003e-02 , 9.8107500000000003e-01 , 1.8950900000000001e-01 -3.0035030831174114e-01 , 5.9532266692537590e+00 , 7.0769783999999998e+00 , 7.7716700000000005e-01 , -5.2054599999999995e-01 , -3.5361399999999998e-01 -2.9132687786283129e-01 , 5.9599504176808864e+00 , 7.2296296000000000e+00 , -7.7716700000000005e-01 , 5.2054599999999995e-01 , 3.5361399999999998e-01 -7.3194958005404964e-01 , 5.2290407031588204e+00 , 6.4943808000000001e+00 , 4.3264799999999998e-01 , -3.0761100000000002e-01 , -8.4746200000000005e-01 -7.1632174058527798e-01 , 5.2479553646829373e+00 , 6.6428928000000003e+00 , 6.0252399999999995e-01 , 7.8165499999999999e-01 , -1.6118399999999999e-01 -1.0515015989342666e+00 , 4.6939794878177930e+00 , 6.0518400000000003e+00 , 6.6481699999999999e-01 , 1.4078399999999999e-01 , -7.3362000000000005e-01 -1.0972192751728420e+00 , 4.6122531013996326e+00 , 6.0512264000000000e+00 , -6.3938700000000004e-01 , -4.6905400000000000e-02 , 7.6745300000000005e-01 -1.1322907309803814e+00 , 4.5491035371312218e+00 , 6.0720368000000002e+00 , -6.1198799999999998e-01 , 4.5105400000000004e-03 , 7.9085499999999997e-01 -1.1705475551374123e+00 , 4.4806678370850941e+00 , 6.0830920000000006e+00 , 5.6090099999999998e-01 , -1.8708500000000000e-01 , -8.0646700000000004e-01 -1.2060320884477034e+00 , 4.4178885189195922e+00 , 6.1005640000000003e+00 , -2.6674500000000001e-01 , 4.3768699999999999e-01 , 8.5864799999999997e-01 -1.2316160313286328e+00 , 4.3708871659194610e+00 , 6.1415088000000004e+00 , -1.7601200000000000e-01 , 4.7456300000000001e-01 , 8.6244399999999999e-01 -1.2562990230682334e+00 , 4.3236713465095171e+00 , 6.1812160000000009e+00 , -3.5726300000000002e-02 , 5.5086599999999997e-01 , 8.3382900000000004e-01 -1.2790487897313998e+00 , 4.2802445834267147e+00 , 6.2287856000000001e+00 , 5.0741000000000003e-01 , 7.4930500000000000e-01 , 4.2553200000000002e-01 -1.2774863328843158e+00 , 4.2759803708204522e+00 , 6.3442983999999996e+00 , -5.7433299999999998e-01 , -7.6323399999999997e-01 , -2.9599999999999999e-01 -1.2052698576363279e+00 , 4.3839893608048577e+00 , 6.6699848000000008e+00 , 2.7408300000000002e-01 , 7.7131400000000006e-01 , 5.7441600000000004e-01 -1.0851830786167014e+00 , 4.5673883706667695e+00 , 7.1593984000000006e+00 , -3.4345799999999999e-01 , -7.1195600000000003e-01 , 6.1249900000000002e-01 -1.1793091858372780e+00 , 4.4092243920423968e+00 , 7.0163047999999995e+00 , 1.2876199999999999e-01 , 1.6659599999999999e-01 , -9.7758199999999995e-01 -1.2461446708645612e+00 , 4.2951372050652097e+00 , 6.9491832000000002e+00 , 5.1808000000000000e-02 , -1.7907100000000001e-01 , 9.8247099999999998e-01 -1.2541816835906598e+00 , 4.2744185186828609e+00 , 7.0694384000000001e+00 , 8.6006199999999999e-01 , -5.9970500000000003e-02 , -5.0665199999999999e-01 -1.2767274444973764e+00 , 4.2290509387921817e+00 , 7.1442144000000001e+00 , -2.0872199999999999e-01 , 8.5441699999999998e-01 , 4.7582300000000000e-01 -1.3014129940732313e+00 , 4.1824192717006223e+00 , 7.2184392000000006e+00 , -3.4343899999999999e-01 , 6.0821800000000004e-01 , 7.1562599999999998e-01 -1.3514515874633979e+00 , 4.0956051020707793e+00 , 7.1987520000000007e+00 , -9.8231299999999994e-02 , -1.5428400000000000e-01 , 9.8313099999999998e-01 -1.3837833552444403e+00 , 4.0361660081881636e+00 , 7.2426400000000006e+00 , 3.5901800000000000e-01 , 6.5367200000000003e-01 , 6.6619799999999996e-01 -1.4119440052989169e+00 , 3.9826409276630517e+00 , 7.3044783999999998e+00 , 1.3678399999999999e-01 , 6.7842199999999997e-01 , 7.2182700000000000e-01 -1.4520031682003283e+00 , 3.9113340649516424e+00 , 7.3175096000000002e+00 , 4.9423800000000001e-01 , 5.3775200000000002e-02 , -8.6766200000000004e-01 -1.5224840821280814e+00 , 3.7942611980767396e+00 , 7.1941448000000001e+00 , -6.2356599999999995e-01 , -5.9632799999999997e-01 , 5.0552799999999998e-01 -1.5903395007046166e+00 , 3.6818875982717465e+00 , 7.0672440000000005e+00 , -8.1706199999999995e-01 , 5.1236199999999998e-01 , 2.6437600000000000e-01 -1.6061841587594761e+00 , 3.6468767600660970e+00 , 7.1814256000000007e+00 , 7.9937400000000003e-01 , -1.2912899999999999e-01 , -5.8679400000000004e-01 -1.5490999759594202e+00 , 3.7187118018845871e+00 , 7.6786496000000000e+00 , -8.4482400000000002e-01 , -2.8916900000000001e-01 , 4.5017000000000001e-01 -1.6486059470040040e+00 , 3.5607151730601077e+00 , 7.3794312000000000e+00 , -9.1445299999999996e-01 , -3.9186900000000002e-01 , 1.0106300000000000e-01 -1.7291179636413552e+00 , 3.4323370257195123e+00 , 7.1547080000000003e+00 , 5.5950599999999995e-01 , -4.2346800000000001e-01 , -7.1248000000000000e-01 -1.7641738525191202e+00 , 3.3703091274208763e+00 , 7.1758199999999999e+00 , -3.1054100000000001e-01 , 1.5536700000000001e-01 , 9.3777699999999997e-01 -1.8097293058120878e+00 , 3.2923700054191114e+00 , 7.1254528000000006e+00 , -1.4964700000000000e-01 , -2.3026300000000000e-01 , 9.6155299999999999e-01 -1.8613310919282078e+00 , 3.2078146195319457e+00 , 7.0330176000000000e+00 , -9.3511100000000003e-01 , -3.4641600000000000e-01 , -7.4584800000000007e-02 -1.9077364157795442e+00 , 3.1302812283489683e+00 , 6.9585016000000000e+00 , 3.9600900000000000e-01 , -6.7906200000000005e-01 , 6.1810299999999996e-01 -1.7847521280842966e+00 , 3.2742228717585551e+00 , 8.1631959999999992e+00 , 8.8226099999999996e-01 , 3.0673499999999998e-01 , 3.5711100000000001e-01 -1.2408845951198986e+00 , 4.6479015907597088e+00 , 3.6447495999999999e+00 , 8.5035799999999995e-01 , -4.2815300000000001e-01 , 3.0590299999999998e-01 -1.2393649807027050e+00 , 4.6467658507962248e+00 , 3.6915184000000001e+00 , 8.5035799999999995e-01 , -4.2815300000000001e-01 , 3.0590299999999998e-01 -1.2334612875627511e+00 , 4.6538248786123804e+00 , 3.7411056000000000e+00 , 8.5035799999999995e-01 , -4.2815300000000001e-01 , 3.0590299999999998e-01 -1.2426493867325883e+00 , 4.6332121907160655e+00 , 3.7830072000000001e+00 , 8.5035799999999995e-01 , -4.2815300000000001e-01 , 3.0590299999999998e-01 --2.1434688595279976e+00 , 1.0860198695515590e+01 , 5.9295360000000006e+00 , -4.1384199999999999e-01 , 5.2459599999999995e-01 , -7.4399899999999997e-01 --2.0963529142334760e+00 , 1.0759633786042137e+01 , 6.0781520000000002e+00 , -4.1384199999999999e-01 , 5.2459599999999995e-01 , -7.4399899999999997e-01 --2.7469001367393480e+00 , 1.1938974296969551e+01 , 6.7120839999999999e+00 , -9.4074599999999997e-01 , -3.3850900000000000e-01 , -2.0217099999999998e-02 --1.1620529138197786e+00 , 9.0221003544798659e+00 , 5.7486280000000001e+00 , 5.1332900000000004e-01 , -8.4916100000000005e-01 , -1.2417200000000000e-01 --1.1532226664887788e+00 , 8.9944009090689292e+00 , 5.8870936000000000e+00 , -5.1332900000000004e-01 , 8.4916100000000005e-01 , 1.2417200000000000e-01 --3.3007483176687957e+00 , 1.2902606129628241e+01 , 7.7932056000000003e+00 , 2.9860300000000001e-01 , 5.8838399999999999e-02 , 9.5256200000000002e-01 --3.4990054969043012e+00 , 1.3245811771449905e+01 , 8.2001887999999994e+00 , -3.2212000000000002e-01 , -9.3588199999999999e-01 , 1.4270400000000000e-01 --4.2715125398302805e+00 , 1.4633087466272819e+01 , 9.1446336000000006e+00 , -7.7717099999999995e-01 , -5.1087800000000005e-01 , 3.6743599999999998e-01 --8.1789246650302427e-01 , 8.3408026861967492e+00 , 6.1665935999999997e+00 , 1.6944600000000001e-01 , 9.8023400000000005e-01 , -1.0212300000000001e-01 --8.1837847830526833e-01 , 8.3308460609427755e+00 , 6.3068168000000000e+00 , 1.6944600000000001e-01 , 9.8023400000000005e-01 , -1.0212300000000001e-01 --4.2220346682707168e+00 , 1.4477683468410167e+01 , 9.9543880000000016e+00 , -9.4674400000000003e-01 , -3.1383800000000001e-01 , 7.1975200000000003e-02 --3.3947759057793814e+00 , 1.2961858840930475e+01 , 9.3585200000000004e+00 , 6.2153700000000001e-01 , 7.4739100000000003e-01 , -2.3473100000000000e-01 --4.6920155791649831e+00 , 1.5281421933485937e+01 , 1.1071160799999999e+01 , -7.8254400000000002e-01 , -5.8479899999999996e-01 , 2.1362100000000001e-01 -5.4258002317247778e-01 , 5.8389009824246658e+00 , 5.3015735999999993e+00 , 7.5080999999999998e-01 , -6.0019100000000003e-01 , -2.7578100000000000e-01 -5.1138103373631782e-01 , 5.8890299417811329e+00 , 5.4277984000000004e+00 , 4.4809500000000002e-01 , 4.0027200000000002e-01 , 7.9937100000000005e-01 -5.9754952369652470e-01 , 5.7277566493971257e+00 , 5.4099000000000004e+00 , -1.9963100000000000e-01 , -4.3030900000000000e-01 , 8.8032999999999995e-01 -6.1974875791845663e-01 , 5.6827008399334140e+00 , 5.4703552000000002e+00 , 2.9504300000000000e-01 , 2.4552199999999999e-01 , 9.2340100000000003e-01 -7.0491606581934696e-01 , 5.5228906071646318e+00 , 5.4437104000000005e+00 , 5.0369100000000000e-02 , 2.8224199999999999e-01 , 9.5801999999999998e-01 --2.1403528932024978e+00 , 1.0582405166778980e+01 , 9.5213008000000006e+00 , 5.9872999999999998e-01 , -8.8529500000000001e-03 , 8.0090200000000000e-01 --3.6698506842165530e+00 , 1.3283762561537090e+01 , 1.1977666400000000e+01 , 8.3643400000000001e-01 , 5.2553799999999995e-01 , -1.5552299999999999e-01 --1.2045084488681832e+00 , 8.8877688552600862e+00 , 8.5828464000000011e+00 , 4.3638100000000002e-01 , -8.9184300000000005e-01 , 1.1910700000000000e-01 --1.2801387690434010e+00 , 9.0081273875985701e+00 , 8.8953144000000002e+00 , 3.4816100000000000e-01 , 2.6542600000000000e-01 , 8.9907300000000001e-01 --1.0794530604665611e+00 , 8.6385456543098549e+00 , 8.7744560000000007e+00 , -2.8820200000000001e-01 , -6.7543799999999998e-01 , 6.7876599999999998e-01 --1.7261956680968091e+00 , 9.7620024722851380e+00 , 1.0049048800000000e+01 , -8.3163200000000004e-01 , -1.1206000000000001e-01 , 5.4390400000000005e-01 --1.4815193369801536e+00 , 9.3140264602852838e+00 , 9.8646776000000003e+00 , -4.4936199999999998e-01 , -7.8602399999999994e-01 , 4.2454599999999998e-01 --1.4416020125812490e+00 , 9.2263066524494661e+00 , 1.0022840800000001e+01 , -3.5413699999999998e-01 , -8.7290999999999996e-01 , 3.3557999999999999e-01 --3.1006553924178304e-01 , 7.2320568226302040e+00 , 8.1713184000000005e+00 , -4.6804000000000001e-01 , -8.8054299999999996e-01 , 7.4713699999999994e-02 --1.5251529662398617e+00 , 9.3375784684821728e+00 , 1.0657386400000000e+01 , 1.6321900000000000e-01 , -9.4301699999999999e-01 , -2.8996300000000003e-01 -3.6077372083956738e-01 , 6.0394374235449275e+00 , 7.1962767999999997e+00 , -7.7716700000000005e-01 , 5.2054699999999998e-01 , 3.5361399999999998e-01 -3.9659032053602927e-01 , 5.9681937532824971e+00 , 7.2614016000000010e+00 , -7.7716700000000005e-01 , 5.2054699999999998e-01 , 3.5361399999999998e-01 -4.5022790955906333e-01 , 5.8648972442776444e+00 , 7.2871312000000001e+00 , -7.7716700000000005e-01 , 5.2054699999999998e-01 , 3.5361399999999998e-01 --2.0729419746599849e+00 , 1.0200387530028665e+01 , 1.2904608000000001e+01 , -6.0413600000000001e-01 , 5.2283999999999997e-01 , -6.0138000000000003e-01 -1.1454447395744873e+00 , 4.6405247733109309e+00 , 6.1069808000000005e+00 , 6.5887300000000004e-01 , 7.6199199999999995e-02 , -7.4838499999999997e-01 -1.1794426977179255e+00 , 4.5752793605471425e+00 , 6.1276767999999997e+00 , -7.6222100000000004e-01 , 4.4089799999999998e-02 , 6.4581400000000000e-01 -1.2196475084276031e+00 , 4.4997361894651888e+00 , 6.1302664000000000e+00 , -6.8166199999999999e-01 , -1.2440500000000000e-01 , 7.2101300000000001e-01 -1.2600520710513679e+00 , 4.4238514952372867e+00 , 6.1311400000000003e+00 , -3.4225400000000000e-01 , 2.9146800000000000e-01 , 8.9325699999999997e-01 -1.2866299561791550e+00 , 4.3707271560088259e+00 , 6.1629952000000001e+00 , 1.4962200000000000e-01 , -5.2104200000000001e-01 , -8.4031500000000003e-01 -1.3173585211689907e+00 , 4.3113132571230617e+00 , 6.1856255999999998e+00 , -5.3873999999999998e-02 , 4.4348700000000002e-01 , 8.9466000000000001e-01 -1.3381260549961065e+00 , 4.2677817982233224e+00 , 6.2322384000000008e+00 , 4.5096100000000000e-02 , 5.8949300000000004e-01 , 8.0651399999999995e-01 -1.3599889828482219e+00 , 4.2230292194230037e+00 , 6.2782584000000003e+00 , 1.8980400000000000e-01 , 6.4283100000000004e-01 , 7.4212000000000000e-01 -1.3533044493990647e+00 , 4.2256535189054372e+00 , 6.4110872000000008e+00 , 6.7710999999999999e-01 , 7.2707100000000002e-01 , 1.1353000000000001e-01 -1.2046149116082487e+00 , 4.4616072329278449e+00 , 6.9971376000000003e+00 , 1.2876199999999999e-01 , 1.6659599999999999e-01 , -9.7758199999999995e-01 -1.2547692459671085e+00 , 4.3691181367726468e+00 , 6.9756511999999997e+00 , 4.1410599999999997e-01 , 3.2416299999999998e-01 , -8.5055000000000003e-01 -1.3124766030692954e+00 , 4.2639725065548095e+00 , 6.9246287999999998e+00 , 3.2826499999999997e-01 , -6.5342100000000003e-01 , 6.8211599999999994e-01 -1.3351458751166096e+00 , 4.2166031625302347e+00 , 6.9894728000000006e+00 , 5.8320499999999997e-02 , 9.8028599999999999e-01 , 1.8878200000000001e-01 -1.3411394104536889e+00 , 4.1965844527924734e+00 , 7.1179959999999998e+00 , -1.1493200000000001e-01 , 7.6515999999999995e-01 , 6.3349800000000001e-01 -1.3438121610412752e+00 , 4.1805934917866372e+00 , 7.2658216000000007e+00 , -1.8400700000000000e-01 , -2.8111100000000000e-01 , 9.4186999999999999e-01 -1.3981669095361968e+00 , 4.0803393042523526e+00 , 7.2172536000000003e+00 , 8.3087700000000000e-02 , 2.2183900000000001e-01 , 9.7153699999999998e-01 -1.4401727690262665e+00 , 4.0012455714812782e+00 , 7.2130936000000005e+00 , -5.4908199999999996e-01 , -2.5828000000000001e-01 , -7.9485799999999995e-01 -1.4331655112097501e+00 , 4.0001328641961074e+00 , 7.4168919999999998e+00 , -1.3597600000000001e-01 , -7.5611899999999999e-01 , 6.4015200000000005e-01 -1.4936432421404773e+00 , 3.8916331642040798e+00 , 7.3339728000000006e+00 , -3.6212100000000003e-01 , 3.9778300000000000e-01 , 8.4299299999999999e-01 -1.5210551602337374e+00 , 3.8354413770115121e+00 , 7.3929615999999996e+00 , -3.4612700000000002e-01 , 3.2529599999999997e-01 , 8.7998799999999999e-01 -1.6216205982077967e+00 , 3.6671116579224634e+00 , 7.1007112000000001e+00 , -9.5484199999999997e-01 , 2.6852599999999999e-01 , 1.2716200000000000e-01 -1.5484155539769728e+00 , 3.7638312124864335e+00 , 7.6652960000000006e+00 , -9.3213199999999996e-01 , -1.7639200000000000e-03 , 3.6211599999999999e-01 -1.5757478193608647e+00 , 3.7069759759270910e+00 , 7.7420480000000005e+00 , 9.2080300000000004e-01 , 3.8021899999999997e-01 , 8.6926500000000004e-02 -1.6398651005838594e+00 , 3.5946935400854159e+00 , 7.6200352000000002e+00 , -8.7965599999999999e-01 , -3.2034800000000002e-01 , 3.5154200000000002e-01 -1.6877923196481928e+00 , 3.5070163012075284e+00 , 7.5745248000000007e+00 , 8.8713200000000003e-01 , 4.5208399999999999e-01 , -9.2834100000000003e-02 -1.6768907775041031e+00 , 3.5036391815737877e+00 , 7.8874712000000002e+00 , -9.7265999999999997e-01 , 9.4654500000000003e-02 , 2.1206900000000001e-01 -1.8354144956896485e+00 , 3.2625267874408950e+00 , 7.1251303999999998e+00 , -2.0848300000000000e-01 , -1.3417899999999999e-01 , 9.6877800000000003e-01 -1.8910406858362694e+00 , 3.1684409527499495e+00 , 6.9809344000000007e+00 , -4.9707299999999999e-01 , 5.0889600000000002e-01 , -7.0281099999999996e-01 -1.7633222076304063e+00 , 3.3187024336883728e+00 , 8.1738248000000002e+00 , 7.4557300000000004e-01 , -2.3260200000000000e-01 , 6.2451400000000001e-01 -1.8082511766614826e+00 , 3.2347787557985965e+00 , 8.1621352000000016e+00 , 2.2048300000000001e-01 , -9.5464899999999997e-01 , 2.0008000000000001e-01 -1.2469621152486121e+00 , 4.7933760106413761e+00 , 3.6513328000000000e+00 , 8.5035799999999995e-01 , -4.2815300000000001e-01 , 3.0590299999999998e-01 -1.2408566040335307e+00 , 4.8007867542958902e+00 , 3.7026463999999999e+00 , 8.5035799999999995e-01 , -4.2815300000000001e-01 , 3.0590299999999998e-01 -1.2487257632747357e+00 , 4.7806919568148762e+00 , 3.7468463999999999e+00 , 8.5035799999999995e-01 , -4.2815300000000001e-01 , 3.0590299999999998e-01 --2.7790109636583873e+00 , 1.2713154929856744e+01 , 6.1895255999999996e+00 , -8.5663500000000004e-01 , 4.3841000000000002e-01 , 2.7198000000000000e-01 --1.6973445322002818e+00 , 1.0565190187955565e+01 , 5.7146616000000003e+00 , -2.4226900000000001e-01 , 9.3980399999999997e-01 , -2.4098600000000001e-01 --2.0476761878896950e+00 , 1.1237617816147385e+01 , 6.1209376000000004e+00 , 8.0456700000000003e-01 , -5.6732800000000005e-01 , 1.7553099999999999e-01 --1.8542097670334625e+00 , 1.0842611839624952e+01 , 6.1674983999999995e+00 , 5.9233500000000001e-02 , -5.9619299999999997e-01 , 8.0065299999999995e-01 --2.8024016180311024e+00 , 1.2680398986151578e+01 , 7.0656216000000009e+00 , -1.5540500000000000e-02 , -7.0227899999999999e-01 , 7.1173200000000003e-01 --1.0184215539124901e+00 , 9.1780766418160589e+00 , 5.8577760000000003e+00 , 4.1962500000000003e-01 , -9.0321099999999999e-01 , -9.0131900000000001e-02 --9.8391618462221064e-01 , 9.0961678784837918e+00 , 5.9750776000000005e+00 , 4.1962500000000003e-01 , -9.0321099999999999e-01 , -9.0132100000000007e-02 --1.0011373214770360e+00 , 9.1167863637197968e+00 , 6.1369432000000002e+00 , 4.1521599999999997e-01 , -8.9799099999999998e-01 , -1.4562900000000001e-01 --2.1827071166763092e+00 , 1.1395915526985615e+01 , 7.3837783999999997e+00 , -9.3196000000000001e-01 , -3.3030900000000002e-01 , 1.4949100000000001e-01 --2.0991165462954244e+00 , 1.1213830430568255e+01 , 7.5044599999999999e+00 , -3.4452300000000002e-01 , -9.3645500000000004e-01 , -6.6007399999999994e-02 --6.2350545815545599e-01 , 8.3456982075543209e+00 , 6.2060304000000004e+00 , 1.6944600000000001e-01 , 9.8023400000000005e-01 , -1.0212300000000001e-01 --6.2487809608453926e-01 , 8.3355087966667547e+00 , 6.3449120000000008e+00 , 1.6944600000000001e-01 , 9.8023400000000005e-01 , -1.0212300000000001e-01 --3.2437586024722238e+00 , 1.3359630293809932e+01 , 9.3834280000000003e+00 , -8.6309199999999997e-01 , -4.4461299999999998e-01 , 2.3956500000000000e-01 -5.6421715200077438e-01 , 6.0272908715190709e+00 , 5.2556992000000005e+00 , 4.7906799999999999e-01 , -6.2359100000000001e-01 , -6.1775999999999998e-01 -6.2500353381093854e-01 , 5.9024801566452325e+00 , 5.2711120000000005e+00 , -4.0281699999999998e-01 , -3.6019899999999999e-01 , -8.4142499999999998e-01 -6.7333887868006381e-01 , 5.8028097346660772e+00 , 5.2979336000000004e+00 , -1.2983300000000000e-01 , -4.5236700000000002e-01 , -8.8233099999999998e-01 -7.2936927831105614e-01 , 5.6872432205516876e+00 , 5.3107671999999999e+00 , 2.4488599999999999e-01 , 4.6136800000000000e-01 , 8.5274300000000003e-01 -7.2452810847815430e-01 , 5.6900395693824670e+00 , 5.4026200000000006e+00 , -8.2287200000000001e-03 , 4.1834100000000002e-01 , 9.0825299999999998e-01 -7.7274541423865561e-01 , 5.5898783126359675e+00 , 5.4217247999999998e+00 , -1.3453499999999999e-01 , 2.9301199999999999e-01 , 9.4659599999999999e-01 -8.1294391603822880e-01 , 5.5065768386398410e+00 , 5.4490144000000003e+00 , 5.2536700000000003e-01 , -6.9195499999999999e-01 , -4.9516399999999999e-01 --1.3364293509734826e+00 , 9.5528985284877095e+00 , 8.7517944000000014e+00 , 6.5239599999999998e-01 , -1.7034099999999999e-01 , 7.3848800000000003e-01 --8.9404169887660823e-01 , 8.7026910425418986e+00 , 8.2680176000000003e+00 , -8.4698300000000004e-01 , 1.9226499999999999e-01 , -4.9563400000000002e-01 --1.0654004619240003e+00 , 9.0067490279451885e+00 , 8.7234751999999993e+00 , -1.9035400000000000e-01 , 7.6346400000000003e-01 , 6.1716099999999996e-01 --9.9490692150028481e-01 , 8.8570270612785365e+00 , 8.8017248000000006e+00 , -1.9035400000000000e-01 , 7.6346400000000003e-01 , 6.1716099999999996e-01 --1.5838943359522273e+00 , 9.9399827384958535e+00 , 1.0008852800000000e+01 , 7.5181100000000001e-01 , 5.8902299999999996e-01 , -2.9636400000000002e-01 --1.2978640630999636e+00 , 9.3852121041345349e+00 , 9.7354368000000004e+00 , -3.6721599999999999e-01 , -8.4502800000000000e-01 , 3.8868999999999998e-01 --1.4855267753906247e+00 , 9.7124833138522746e+00 , 1.0302621600000000e+01 , -2.6468000000000003e-01 , 6.6780799999999996e-01 , 6.9568500000000000e-01 --1.4310778423628290e+00 , 9.5889877578876366e+00 , 1.0439100800000000e+01 , -4.6167000000000002e-01 , 7.5940300000000005e-01 , 4.5844099999999999e-01 --1.6128391825652022e-01 , 7.2242695405242632e+00 , 8.1960183999999998e+00 , 5.1060399999999995e-01 , 8.3528999999999998e-01 , -2.0389900000000000e-01 --1.3754357729979683e+00 , 9.4404468009703066e+00 , 1.0820447999999999e+01 , 4.2707299999999998e-01 , -8.7065099999999995e-01 , -2.4408299999999999e-01 --1.3337584771386206e+00 , 9.3418461531090884e+00 , 1.0988220799999999e+01 , 8.0575799999999997e-01 , -1.6537299999999999e-01 , -5.6868799999999997e-01 --1.5477001937670356e+00 , 9.7085073070072418e+00 , 1.1708368800000001e+01 , -9.4118100000000005e-01 , 2.9099100000000000e-01 , -1.7176400000000000e-01 --1.4752048361133934e+00 , 9.5513704356036460e+00 , 1.1829331200000000e+01 , -5.9077500000000005e-01 , 7.4747600000000003e-01 , -3.0375099999999999e-01 --2.9610023941589514e+00 , 1.2179325772188303e+01 , 1.5939120000000001e+01 , 4.7142800000000001e-01 , -8.6599099999999996e-01 , 1.6677800000000001e-01 -9.1612795281430692e-01 , 5.1682931914255503e+00 , 6.8488024000000003e+00 , -8.5512100000000002e-01 , -5.0218700000000005e-01 , 1.2875000000000000e-01 -9.6587314593241813e-01 , 5.0680490263920319e+00 , 6.8467327999999998e+00 , -8.0853200000000000e-02 , -9.9594800000000006e-01 , 3.9372499999999998e-02 -1.2466422019834429e+00 , 4.5547959363475048e+00 , 6.2353896000000004e+00 , -7.7733500000000000e-01 , -1.9889100000000001e-01 , 5.9681899999999999e-01 -1.3089810716941663e+00 , 4.4337698946949917e+00 , 6.1697135999999997e+00 , -3.4780800000000001e-01 , 2.3509500000000000e-01 , 9.0761199999999997e-01 -1.3405478489520419e+00 , 4.3685091757469969e+00 , 6.1845648000000004e+00 , -1.8134700000000001e-01 , 3.5124100000000003e-01 , 9.1855500000000001e-01 -1.3692530042940685e+00 , 4.3079635277885338e+00 , 6.2064360000000001e+00 , -6.0362399999999997e-02 , 3.9564300000000002e-01 , 9.1641899999999998e-01 -1.3951110477963897e+00 , 4.2532182676043675e+00 , 6.2353271999999995e+00 , 1.5394900000000000e-02 , 5.8189299999999999e-01 , 8.1311999999999995e-01 -1.4129171680168096e+00 , 4.2123866844073374e+00 , 6.2894800000000002e+00 , 8.0176499999999998e-02 , 6.1027299999999995e-01 , 7.8812400000000005e-01 -1.4338953232189144e+00 , 4.1662980971970924e+00 , 6.3339711999999997e+00 , -5.5178899999999997e-01 , -7.1097600000000005e-01 , -4.3593799999999999e-01 -1.4096168765350756e+00 , 4.1971905058651515e+00 , 6.5295432000000009e+00 , -6.6553399999999996e-01 , -7.4589099999999997e-01 , 2.6672399999999999e-02 -1.2899269135959577e+00 , 4.3899444262938108e+00 , 7.0601616000000007e+00 , -5.0616200000000000e-01 , 2.0829000000000000e-01 , 8.3690799999999999e-01 -1.3611233905761742e+00 , 4.2561655111387093e+00 , 6.9542168000000002e+00 , -6.2527600000000003e-02 , -9.5951500000000001e-01 , 2.7462799999999998e-01 -1.3545920044440649e+00 , 4.2536318198893870e+00 , 7.1194520000000008e+00 , -1.1493200000000001e-01 , 7.6516099999999998e-01 , 6.3349800000000001e-01 -1.3656781156173898e+00 , 4.2223891161747868e+00 , 7.2302640000000000e+00 , 3.1773000000000001e-01 , -8.1354300000000002e-01 , -4.8702699999999999e-01 -1.4009298412972422e+00 , 4.1479748213720242e+00 , 7.2478608000000007e+00 , 7.3673600000000006e-02 , -2.0280500000000001e-01 , 9.7644399999999998e-01 -1.4459809044538097e+00 , 4.0598525066397810e+00 , 7.2259479999999998e+00 , -7.5225500000000001e-02 , -1.3865300000000000e-01 , 9.8748000000000002e-01 -1.4806599278713639e+00 , 3.9868395672712884e+00 , 7.2398736000000001e+00 , 3.7987900000000002e-01 , -7.6959200000000005e-01 , -5.1324499999999995e-01 -1.4821764514855640e+00 , 3.9691922832403117e+00 , 7.4055456000000000e+00 , 6.0212399999999999e-01 , 4.0507700000000002e-01 , -6.8801100000000004e-01 -1.5267194420789103e+00 , 3.8801711128016825e+00 , 7.3790464000000000e+00 , -3.5427500000000001e-01 , 2.2663500000000000e-01 , 9.0726300000000004e-01 -1.5629064273895958e+00 , 3.8063071963274671e+00 , 7.3890511999999999e+00 , 2.6859600000000000e-01 , 6.7182900000000004e-02 , -9.6090699999999996e-01 -1.6112673765782444e+00 , 3.7134863975726979e+00 , 7.3392039999999996e+00 , 9.9900999999999995e-01 , 4.1815199999999997e-02 , 1.5162699999999999e-02 -1.5816951277790396e+00 , 3.7407695451929897e+00 , 7.6896944000000005e+00 , -8.4482400000000002e-01 , -2.8916900000000001e-01 , 4.5017000000000001e-01 -1.6146820363410777e+00 , 3.6703211547345953e+00 , 7.7265208000000003e+00 , 9.2702200000000001e-01 , 3.6370700000000000e-01 , -9.1368500000000005e-02 -1.6432812603524594e+00 , 3.6068676989077666e+00 , 7.7918536000000005e+00 , -9.5557400000000003e-01 , 1.5675400000000000e-01 , 2.4961400000000000e-01 -1.7263911792289284e+00 , 3.4637886355004079e+00 , 7.5263207999999997e+00 , 9.9991300000000005e-01 , -1.2906200000000000e-02 , 2.9035900000000002e-03 -1.8255156317633021e+00 , 3.3003134033355961e+00 , 7.1260976000000005e+00 , 6.8324300000000004e-01 , -2.8613300000000003e-01 , 6.7179400000000000e-01 -1.8636926115502574e+00 , 3.2263541370849209e+00 , 7.0939199999999998e+00 , -7.8498000000000001e-01 , -5.5803599999999998e-01 , -2.6907599999999998e-01 -1.9139189659620148e+00 , 3.1363627367302529e+00 , 6.9688808000000009e+00 , 3.9600900000000000e-01 , -6.7906200000000005e-01 , 6.1810299999999996e-01 -1.7805323027531759e+00 , 3.2887754036455310e+00 , 8.2345192000000011e+00 , 6.8583000000000005e-01 , 8.9588500000000001e-02 , -7.2222699999999995e-01 --2.0227778494131092e+00 , 1.2660269060223282e+01 , -1.2899568000000001e+00 , -1.4058599999999999e-02 , -5.8175900000000003e-02 , 9.9820699999999996e-01 --3.1005724741241414e+00 , 1.5068778151894927e+01 , -1.7719551999999998e+00 , 2.0600199999999999e-01 , -3.2026399999999999e-01 , -9.2465900000000001e-01 --4.1628525225062232e+00 , 1.7452523895798283e+01 , -2.3678336000000000e+00 , -1.2738800000000000e-01 , 1.8759899999999999e-01 , 9.7394999999999998e-01 --1.3557274711222204e+01 , 3.7758099945944132e+01 , -5.5559200000000031e-01 , -8.7841000000000002e-01 , 4.4194200000000000e-01 , -1.8188699999999999e-01 --4.5713541757592058e+00 , 1.7882253119752882e+01 , 1.7862238399999999e+00 , 6.2315500000000003e-02 , 9.8727900000000002e-01 , 1.4627499999999999e-01 --1.3476742024730902e+01 , 3.7429762430572019e+01 , 8.2496640000000010e-01 , -8.7841100000000005e-01 , 4.4194099999999997e-01 , -1.8188699999999999e-01 --4.5470219529158307e+00 , 1.7761014485299416e+01 , 2.3858441600000000e+00 , 1.0755500000000000e-01 , -5.1952100000000001e-01 , -8.4766100000000000e-01 --4.5458699297859031e+00 , 1.7725911637070986e+01 , 2.6811043200000002e+00 , -4.7385200000000002e-02 , 3.9559899999999998e-01 , 9.1720000000000002e-01 -1.3215150252796195e+00 , 4.8118206522130764e+00 , 3.6270280000000001e+00 , 8.5035799999999995e-01 , -4.2815300000000001e-01 , 3.0590299999999998e-01 -1.3412403963906123e+00 , 4.7643426800285873e+00 , 3.6643848000000001e+00 , 8.5035799999999995e-01 , -4.2815300000000001e-01 , 3.0590299999999998e-01 -1.3385795691799598e+00 , 4.7634212887866862e+00 , 3.7119336000000001e+00 , 8.5035799999999995e-01 , -4.2815300000000001e-01 , 3.0590299999999998e-01 --1.7379000511602474e+00 , 1.1266020598580425e+01 , 5.6376080000000002e+00 , -4.3311699999999997e-01 , -8.9976500000000001e-02 , -8.9683500000000005e-01 --2.1158425679176824e+00 , 1.2044399568300145e+01 , 6.0630096000000000e+00 , -8.4761600000000006e-02 , 8.1858600000000004e-01 , 5.6809600000000005e-01 --1.8106865548448332e+00 , 1.1379103073310036e+01 , 6.0463176000000001e+00 , -8.2727399999999995e-01 , 1.7280200000000001e-01 , -5.3456199999999998e-01 --1.9582915160029768e+00 , 1.1667326167058304e+01 , 6.3386200000000006e+00 , -1.0209500000000001e-01 , 7.1348500000000004e-01 , 6.9319299999999995e-01 --1.8601746570220419e+00 , 1.1442110457965633e+01 , 6.4538935999999998e+00 , -2.1023000000000000e-01 , -2.4888199999999999e-01 , 9.4544200000000000e-01 --1.8761289498719265e+00 , 1.1454804260200588e+01 , 6.6558200000000003e+00 , -6.4192799999999994e-02 , 9.9503399999999997e-01 , 7.6075699999999996e-02 --2.8036830300946125e+00 , 1.3368190446408946e+01 , 7.6540743999999998e+00 , 2.1132500000000001e-01 , -4.1979400000000000e-01 , 8.8267499999999999e-01 --8.1865257768275113e-01 , 9.2106025635665922e+00 , 6.0723696000000000e+00 , 4.1478199999999998e-01 , -8.9800199999999997e-01 , -1.4679400000000001e-01 --8.3151873883477823e-01 , 9.2208874652272801e+00 , 6.2313232000000003e+00 , 3.6839800000000000e-01 , -9.2251300000000003e-01 , -1.1512500000000001e-01 --1.8493267750694771e+00 , 1.1312429412386170e+01 , 7.4041831999999994e+00 , -3.4452300000000002e-01 , -9.3645500000000004e-01 , -6.6007300000000005e-02 --1.7749459128055722e+00 , 1.1136934800327341e+01 , 7.5240327999999996e+00 , -3.2318999999999998e-01 , -9.4564099999999995e-01 , 3.6202999999999999e-02 --4.2311464994077275e-01 , 8.3282001185242045e+00 , 6.2357223999999993e+00 , 1.8997900000000001e-01 , 9.7755000000000003e-01 , -9.1127500000000000e-02 --4.6517508585394873e-01 , 8.4000563402712025e+00 , 6.4199999999999999e+00 , 1.7458199999999999e-01 , 8.0325400000000002e-01 , -5.6947700000000001e-01 -6.6223878859471741e-01 , 6.0743581769333233e+00 , 5.2150976000000000e+00 , -3.3981800000000000e-02 , 2.7219300000000002e-01 , 9.6164200000000000e-01 -7.0688201986407706e-01 , 5.9724961592129731e+00 , 5.2461000000000002e+00 , -3.3981800000000000e-02 , 2.7219300000000002e-01 , 9.6164200000000000e-01 -7.4363449114647029e-01 , 5.8872758149897955e+00 , 5.2841743999999995e+00 , 1.8979699999999999e-01 , 4.0237899999999999e-01 , 8.9558300000000002e-01 -7.7710487396008898e-01 , 5.8111952066609174e+00 , 5.3247863999999998e+00 , -2.0637800000000001e-01 , 8.3508499999999997e-01 , 5.0994300000000004e-01 -8.0240011240388420e-01 , 5.7489608510721180e+00 , 5.3744047999999998e+00 , -3.3484500000000000e-01 , 4.9485800000000002e-01 , 8.0186999999999997e-01 --7.1384431687418148e-01 , 8.8054878275474202e+00 , 7.6467216000000002e+00 , 8.4239600000000003e-01 , 1.0859000000000001e-02 , 5.3874900000000003e-01 --1.4937954131320064e+00 , 1.0359362301063317e+01 , 8.9790968000000007e+00 , 4.2550900000000003e-01 , -3.9572499999999999e-01 , 8.1384500000000004e-01 --8.9244732212705191e-01 , 9.1265944417139977e+00 , 8.2590111999999998e+00 , 5.9906199999999998e-01 , -7.2947399999999996e-01 , 3.3014100000000002e-01 --1.1619184692376749e+00 , 9.6463186717320379e+00 , 8.8732247999999991e+00 , -2.8567799999999999e-01 , 7.6243900000000003e-02 , -9.5528800000000003e-01 --5.7562486924842782e-01 , 8.4527435929681545e+00 , 8.1020128000000007e+00 , 4.0000599999999997e-01 , 8.5369300000000004e-01 , 3.3347199999999999e-01 --4.7724706637501013e-01 , 8.2377572313250980e+00 , 8.1047688000000004e+00 , -1.4958099999999999e-01 , -7.1913000000000005e-01 , 6.7858499999999999e-01 --7.5572618369299205e-01 , 8.7711907265000821e+00 , 8.7692872000000008e+00 , 1.8847600000000000e-01 , 7.2205799999999998e-01 , 6.6566499999999995e-01 --8.3489651170163892e-01 , 8.9069187340898317e+00 , 9.1045832000000004e+00 , 3.8786700000000002e-01 , 8.9827999999999997e-01 , -2.0652200000000001e-01 --9.7475572793790777e-01 , 9.1593912382026090e+00 , 9.5689536000000004e+00 , -1.2300400000000000e-01 , -8.6017399999999999e-01 , 4.9494500000000002e-01 --9.5293406237252043e-01 , 9.0944577880226571e+00 , 9.7414376000000011e+00 , -2.0858299999999999e-01 , -8.5969099999999998e-01 , 4.6628900000000001e-01 --1.1644701766992873e+00 , 9.4827022913357268e+00 , 1.0384823200000000e+01 , 4.5768300000000001e-01 , -8.8876100000000002e-01 , 2.5115499999999999e-02 --1.1645142122402747e+00 , 9.4573212110358043e+00 , 1.0622463200000000e+01 , 4.2707200000000001e-01 , -8.7065099999999995e-01 , -2.4408299999999999e-01 --1.2333673862487431e+00 , 9.5637729443725590e+00 , 1.1014938400000000e+01 , -9.6915899999999999e-01 , 1.9407500000000000e-01 , 1.5187200000000001e-01 --1.4649989215395878e+00 , 9.9837790206938521e+00 , 1.1785266400000001e+01 , -8.3492100000000002e-01 , 5.3771199999999997e-01 , 1.1736199999999999e-01 --1.3055938937632532e+00 , 9.6450919178875800e+00 , 1.1698270400000000e+01 , -5.9077500000000005e-01 , 7.4747600000000003e-01 , -3.0375099999999999e-01 --9.2090221258556104e-01 , 8.8752969078385657e+00 , 1.1063766399999999e+01 , -7.5451500000000005e-01 , -2.0488000000000001e-01 , 6.2348300000000001e-01 --2.6902957260477098e+00 , 1.2226772663702397e+01 , 1.5641888000000002e+01 , 4.7142800000000001e-01 , -8.6599099999999996e-01 , 1.6677800000000001e-01 -9.0419518955868061e-01 , 5.3476284834182746e+00 , 6.9826816000000003e+00 , -8.5931199999999996e-01 , -5.1123499999999999e-01 , -1.4859900000000001e-02 -1.0197739427592256e+00 , 5.1150756634358352e+00 , 6.8070256000000002e+00 , 8.4412200000000007e-02 , 9.7590399999999999e-01 , 2.0121300000000000e-01 -1.0566484943083929e+00 , 5.0315354638499024e+00 , 6.8271288000000006e+00 , 2.7157100000000001e-01 , 7.1050199999999997e-01 , 6.4918100000000001e-01 -9.8690068080249360e-01 , 5.1490540602089974e+00 , 7.1425919999999996e+00 , -6.8585799999999997e-01 , -6.0906000000000005e-01 , 3.9830199999999999e-01 -1.3297302108722118e+00 , 4.4948006643870126e+00 , 6.2926415999999996e+00 , 7.1027099999999999e-01 , 3.7723699999999999e-01 , -5.9431299999999998e-01 -1.3943944426239669e+00 , 4.3631251198176244e+00 , 6.2062384000000002e+00 , -4.4331500000000001e-01 , 1.3965600000000000e-01 , 8.8541999999999998e-01 -1.4241470035006181e+00 , 4.2974648064306082e+00 , 6.2187080000000003e+00 , -3.0201899999999998e-01 , 1.8879499999999999e-01 , 9.3442000000000003e-01 -1.4490032937318860e+00 , 4.2415826666944056e+00 , 6.2470791999999999e+00 , -8.1619499999999998e-02 , 4.6561399999999997e-01 , 8.8121600000000000e-01 -1.4699030412040037e+00 , 4.1905544383202820e+00 , 6.2828552000000002e+00 , 1.7471000000000000e-01 , 6.3246599999999997e-01 , 7.5462799999999997e-01 -1.4867785700059535e+00 , 4.1473800755343309e+00 , 6.3356664000000009e+00 , 1.6463300000000000e-01 , 6.3127100000000003e-01 , 7.5788699999999998e-01 -1.4862373364683052e+00 , 4.1365421113134460e+00 , 6.4504095999999995e+00 , 6.0291200000000000e-01 , 7.8823900000000002e-01 , 1.2319300000000000e-01 -1.4192517217083884e+00 , 4.2427251146885583e+00 , 6.8103328000000003e+00 , 6.5892700000000004e-01 , -2.6493200000000000e-01 , 7.0400700000000005e-01 -1.3785547366954090e+00 , 4.2993224504984120e+00 , 7.0930672000000001e+00 , -8.9036599999999999e-01 , -4.5107799999999998e-01 , -6.1458199999999998e-02 -1.3236064725776528e+00 , 4.3796021650793122e+00 , 7.4534584000000006e+00 , -4.0722500000000000e-01 , -5.8439200000000002e-01 , 7.0189299999999999e-01 -1.4395583997457946e+00 , 4.1611746489643977e+00 , 7.1477088000000002e+00 , -7.7024499999999996e-01 , 8.4546700000000002e-02 , 6.3211899999999999e-01 -1.4655320599311088e+00 , 4.0988443627431890e+00 , 7.1917631999999996e+00 , -4.1574800000000001e-01 , -8.3206600000000006e-02 , 9.0566599999999997e-01 -1.5023124906468981e+00 , 4.0177681805328298e+00 , 7.1871872000000003e+00 , 9.6521999999999997e-02 , 4.3173400000000001e-01 , 8.9682200000000001e-01 -1.5039427127944240e+00 , 3.9981277547779763e+00 , 7.3430208000000006e+00 , -4.9997900000000001e-01 , -8.5204100000000005e-01 , 1.5507099999999999e-01 -1.5291075353224453e+00 , 3.9361216391499565e+00 , 7.3937520000000001e+00 , 2.0149200000000000e-01 , 1.1058300000000000e-01 , 9.7322799999999998e-01 -1.5673968452736824e+00 , 3.8541946657883677e+00 , 7.3852552000000005e+00 , -3.5427500000000001e-01 , 2.2663500000000000e-01 , 9.0726300000000004e-01 -9.9572585128928637e-01 , 4.7587578110217308e+00 , 1.0472308000000000e+01 , -3.4556700000000001e-01 , 1.4061799999999999e-01 , 9.2779900000000004e-01 -1.5763931475451298e+00 , 3.7972729097470772e+00 , 7.7159960000000005e+00 , -3.4824100000000002e-01 , 2.3714299999999999e-01 , 9.0691299999999997e-01 -1.6127332981322702e+00 , 3.7176567608383642e+00 , 7.7238895999999997e+00 , 9.2080300000000004e-01 , 3.8021800000000000e-01 , 8.6926699999999996e-02 -1.6504299411383903e+00 , 3.6356733170832101e+00 , 7.7202495999999998e+00 , -9.6571600000000002e-01 , -1.3664299999999999e-01 , 2.2072800000000001e-01 -1.7063894830003710e+00 , 3.5262471233006338e+00 , 7.6054544000000002e+00 , -8.5115099999999999e-01 , -3.9949699999999999e-01 , 3.4050500000000000e-01 -1.6933469739218099e+00 , 3.5208548911094626e+00 , 7.9184632000000006e+00 , -9.8435600000000001e-01 , 7.8024999999999997e-02 , 1.5797400000000000e-01 -1.8340801178922963e+00 , 3.2904298918567285e+00 , 7.2264368000000010e+00 , 8.2625400000000004e-01 , 5.6138900000000003e-01 , 4.6340899999999997e-02 -1.8992894908934823e+00 , 3.1744744046748181e+00 , 6.9915631999999999e+00 , -6.3688699999999998e-01 , 3.9225100000000002e-01 , -6.6371300000000000e-01 -1.7624345742693426e+00 , 3.3331876276488037e+00 , 8.2349768000000001e+00 , 6.5112400000000004e-01 , -2.3532300000000000e-01 , -7.2156799999999999e-01 -1.8113793197598644e+00 , 3.2357630420887293e+00 , 8.1624055999999996e+00 , 8.6492299999999994e-02 , -9.8186499999999999e-01 , 1.6870399999999999e-01 --3.5531016753403311e-01 , 9.4537353587671813e+00 , -1.0056079999999978e-01 , -5.8037200000000000e-01 , -4.0484100000000001e-01 , -7.0659200000000000e-01 --3.7248441523835707e-01 , 9.4739707225170164e+00 , 4.3635199999999985e-02 , -5.8037200000000000e-01 , -4.0484100000000001e-01 , -7.0659200000000000e-01 --3.9477220703451366e-01 , 9.5099569505104675e+00 , 1.8057199999999995e-01 , -5.8037200000000000e-01 , -4.0484100000000001e-01 , -7.0659200000000000e-01 --4.2307383646351981e-01 , 9.5385163717312000e+00 , 4.6915119999999999e-01 , 5.8037200000000000e-01 , 4.0484100000000001e-01 , 7.0659200000000000e-01 --4.5073109176703996e-01 , 9.5863177687550767e+00 , 6.0033679999999978e-01 , 5.8037200000000000e-01 , 4.0484100000000001e-01 , 7.0659200000000000e-01 --1.2163197713449627e+01 , 3.8059475741122114e+01 , -5.6455288000000001e+00 , -7.9026500000000000e-01 , 5.7416400000000001e-01 , -2.1404699999999999e-01 --1.2257074842528455e+01 , 3.8190174508415140e+01 , -4.9748328000000006e+00 , -7.9026500000000000e-01 , 5.7416400000000001e-01 , -2.1404699999999999e-01 --1.2368899728865792e+01 , 3.8367533708897213e+01 , -4.3130288000000006e+00 , -7.9026500000000000e-01 , 5.7416400000000001e-01 , -2.1404699999999999e-01 --1.2488782753560663e+01 , 3.8561192919405400e+01 , -3.6515680000000001e+00 , -7.9026500000000000e-01 , 5.7416500000000004e-01 , -2.1404699999999999e-01 --1.2580295979023040e+01 , 3.8688762955528738e+01 , -2.9750167999999997e+00 , -7.9026500000000000e-01 , 5.7416500000000004e-01 , -2.1404699999999999e-01 --1.2679726302502718e+01 , 3.8833298283409803e+01 , -2.2995263999999995e+00 , -7.9026500000000000e-01 , 5.7416400000000001e-01 , -2.1404699999999999e-01 --1.2751424822987955e+01 , 3.8910023380067869e+01 , -1.6125128000000002e+00 , 8.7326899999999996e-01 , -4.5084600000000002e-01 , 1.8476799999999999e-01 --1.2854390132463024e+01 , 3.9060951851883821e+01 , -9.3306000000000022e-01 , -8.7651199999999996e-01 , 4.4502000000000003e-01 , -1.8353100000000000e-01 --1.2944012157663781e+01 , 3.9182856684606548e+01 , -2.4700319999999998e-01 , -8.7841000000000002e-01 , 4.4194200000000000e-01 , -1.8188699999999999e-01 --4.1149168472990105e+00 , 1.8049801021403365e+01 , 1.9615022160000000e+00 , 2.3153799999999999e-01 , -1.6769400000000001e-01 , -9.5826299999999998e-01 --4.0628193984818273e+00 , 1.7887075510388954e+01 , 2.2664708800000000e+00 , 5.7967199999999997e-01 , 2.1525200000000001e-02 , -8.1456600000000001e-01 --1.3273067105149218e+01 , 3.9681642057805405e+01 , 1.8267796800000000e+00 , -8.7841000000000002e-01 , 4.4194200000000000e-01 , -1.8188699999999999e-01 --1.3364765981225453e+01 , 3.9806097118729873e+01 , 2.5303355199999999e+00 , -8.7841000000000002e-01 , 4.4194200000000000e-01 , -1.8188699999999999e-01 -1.2732443035315999e+00 , 5.1080295981938386e+00 , 3.6639584000000003e+00 , 5.9243100000000004e-01 , -1.0696300000000000e-01 , 7.9848900000000000e-01 --1.3140642145837771e+00 , 1.1020188301644962e+01 , 5.1139472000000001e+00 , 1.2756000000000001e-01 , -8.7085299999999999e-01 , 4.7470299999999999e-01 --1.2912051704091994e+00 , 1.0946158831982777e+01 , 5.2679088000000007e+00 , -3.4150199999999997e-01 , -9.3268600000000002e-01 , 1.1607700000000000e-01 --1.5102526920728927e+00 , 1.1422707248201101e+01 , 5.5731800000000007e+00 , 4.1324899999999998e-01 , -1.1363900000000000e-01 , 9.0349900000000005e-01 --1.6630700914545065e+00 , 1.1745857406253236e+01 , 5.8532728000000001e+00 , -9.5767400000000003e-01 , -2.8102199999999999e-01 , -6.2346600000000002e-02 --1.4379445591078110e+00 , 1.1212156458817676e+01 , 5.8769431999999995e+00 , 3.3391900000000002e-01 , 8.9458099999999996e-01 , 2.9702200000000001e-01 --1.3859496008856866e+00 , 1.1070771169717714e+01 , 6.0137239999999998e+00 , 1.0265299999999999e-01 , 9.9087099999999995e-01 , 8.7389099999999997e-02 --1.6100545321666657e+00 , 1.1552480916737585e+01 , 6.3699344000000000e+00 , -1.6864100000000001e-01 , 8.4815300000000005e-01 , 5.0219100000000005e-01 --1.4436213413852257e+00 , 1.1152843955105769e+01 , 6.4140512000000003e+00 , -6.6910800000000004e-01 , -7.0520600000000000e-01 , 2.3447799999999999e-01 --2.0008114071919065e+00 , 1.2378422961326203e+01 , 7.0973103999999996e+00 , -6.7277600000000004e-01 , -4.4580100000000000e-01 , 5.9045199999999998e-01 --2.0376843149616652e+00 , 1.2431964715810370e+01 , 7.3396304000000008e+00 , -5.3322599999999998e-01 , 2.0446800000000001e-01 , 8.2089100000000004e-01 --6.4817198601748860e-01 , 9.3095089718161184e+00 , 6.1674983999999995e+00 , 3.6839800000000000e-01 , -9.2251200000000000e-01 , -1.1512500000000001e-01 --6.4515999270939473e-01 , 9.2830813699666894e+00 , 6.3109976000000003e+00 , 3.5171599999999997e-01 , -9.3573700000000004e-01 , -2.6293600000000000e-02 --1.5736587238146051e+00 , 1.1318754275823546e+01 , 7.4733223999999998e+00 , -1.0135399999999999e-02 , -9.4030199999999997e-01 , 3.4018999999999999e-01 --1.6527239042163764e+00 , 1.1466579512186067e+01 , 7.7580223999999998e+00 , -1.0763700000000000e-01 , 7.8707300000000002e-01 , -6.0739600000000005e-01 --2.3054087719967020e-01 , 8.3107834472216862e+00 , 6.2693976000000005e+00 , 1.9512099999999999e-01 , 9.7379499999999997e-01 , -1.1683900000000000e-01 --6.4719951394085928e-01 , 9.2070820531832709e+00 , 6.9188983999999998e+00 , -7.2384099999999996e-01 , 6.4460300000000004e-01 , 2.4605199999999999e-01 --4.5197681716829363e-01 , 8.7587590030859914e+00 , 6.8224176000000005e+00 , -9.8219199999999995e-01 , 1.6143299999999999e-01 , -9.6120200000000003e-02 -8.8513909094148602e-01 , 5.8218041650987864e+00 , 5.1791552000000003e+00 , -2.4588299999999999e-01 , -8.5887000000000002e-01 , -4.4931500000000002e-01 -8.5551313499521831e-01 , 5.8764435461048654e+00 , 5.3017400000000006e+00 , 4.0461900000000001e-01 , 7.8001100000000001e-01 , 4.7735200000000000e-01 -8.8595340715250126e-01 , 5.7981145292431879e+00 , 5.3410728000000001e+00 , 4.6055400000000002e-01 , -8.8626300000000002e-01 , 4.9271700000000002e-02 -8.7629748558766241e-01 , 5.8076600690422397e+00 , 5.4390928000000001e+00 , 4.5842699999999997e-01 , -5.1122000000000001e-01 , -7.2697900000000004e-01 --6.0277012381214723e-01 , 8.9821466786079274e+00 , 7.8199231999999999e+00 , 5.5020999999999998e-01 , -7.1871900000000000e-01 , 4.2510300000000001e-01 --6.9586563673259150e-01 , 9.1596627583127237e+00 , 8.1383088000000008e+00 , -6.9265900000000002e-01 , 6.4041300000000001e-01 , -3.3180599999999999e-01 --1.4770438178944527e+00 , 1.0806436446965442e+01 , 9.6153271999999994e+00 , 6.3346199999999997e-01 , 5.2765499999999999e-01 , 5.6595499999999999e-01 --7.4426623657698610e-01 , 9.2154731353376338e+00 , 8.5789256000000016e+00 , 3.4923100000000001e-01 , 8.4055000000000002e-01 , 4.1414099999999998e-01 --3.1006763310971674e-01 , 8.2685476151743096e+00 , 7.9928336000000000e+00 , -1.3672100000000000e-02 , 7.7695800000000004e-01 , 6.2940399999999996e-01 --6.7690195733452541e-01 , 9.0213018534818872e+00 , 8.8311567999999987e+00 , 3.6552600000000002e-01 , 8.2583899999999999e-01 , 4.2939699999999997e-01 --6.5690518698714939e-01 , 8.9545871460371700e+00 , 8.9839120000000001e+00 , 4.4149699999999997e-01 , 8.8264699999999996e-01 , 1.6129199999999999e-01 --8.3374558036027091e-01 , 9.3006061258272972e+00 , 9.5251903999999996e+00 , 7.6355399999999995e-01 , 6.1949299999999996e-01 , 1.8224699999999999e-01 --5.9379972960646299e-01 , 8.7690710952672841e+00 , 9.2465639999999993e+00 , 6.0799999999999998e-01 , 4.3518400000000002e-01 , 6.6404200000000002e-01 --4.1678984987258749e-01 , 8.3744220230572033e+00 , 9.0752759999999988e+00 , 4.9717499999999998e-01 , 4.6906500000000001e-01 , 7.2992800000000002e-01 --1.3134246262518823e+00 , 1.0209194282070438e+01 , 1.1202512800000001e+01 , -9.2788599999999999e-01 , 3.1383200000000000e-01 , -2.0133999999999999e-01 --1.2158877120478726e+00 , 9.9732813229360140e+00 , 1.1243499200000000e+01 , -9.2788599999999999e-01 , 3.1383200000000000e-01 , -2.0133999999999999e-01 --1.0606498822021106e+00 , 9.6198165562938236e+00 , 1.1145479200000000e+01 , -9.2505700000000002e-01 , 3.7980700000000001e-01 , 4.0066800000000003e-03 --1.3134970073095853e+00 , 1.0101504475803631e+01 , 1.1996147199999999e+01 , 5.5520999999999998e-01 , -1.5219500000000000e-01 , -8.1766700000000003e-01 --1.2062099401538755e+00 , 9.8457082311062436e+00 , 1.2014263999999999e+01 , 7.9955600000000004e-01 , -6.0042899999999999e-01 , -1.3971000000000001e-02 --2.8460544784116903e-01 , 7.9432980332589116e+00 , 9.9730039999999995e+00 , -2.9685099999999998e-01 , -8.6235899999999999e-01 , -4.1014099999999998e-01 -1.0599301835133086e+00 , 5.2081503744200468e+00 , 6.6978152000000000e+00 , 4.6728300000000000e-01 , 4.9094300000000002e-01 , 7.3526999999999998e-01 -1.0905099767701141e+00 , 5.1310699651439577e+00 , 6.7276008000000003e+00 , 2.5509399999999999e-01 , 6.6925800000000002e-01 , 6.9786800000000004e-01 -1.1104290311918597e+00 , 5.0765745910586544e+00 , 6.7881391999999998e+00 , 1.1615000000000000e-01 , 7.8631399999999996e-01 , 6.0681099999999999e-01 -1.0637640008690799e+00 , 5.1520179245280051e+00 , 7.0366575999999998e+00 , -2.9779499999999998e-01 , -9.3549400000000005e-01 , 1.9018099999999999e-01 -1.1086001364550970e+00 , 5.0481363747949812e+00 , 7.0313328000000004e+00 , 3.9440100000000000e-01 , 8.4835499999999997e-01 , -3.5318899999999998e-01 -1.3855457040123798e+00 , 4.4895504360390763e+00 , 6.3153760000000005e+00 , -7.0719799999999999e-01 , -3.2733899999999999e-01 , 6.2667399999999995e-01 -1.4310564820145237e+00 , 4.3878855017957106e+00 , 6.2789967999999998e+00 , 6.6917300000000002e-01 , 2.7909899999999999e-01 , -6.8870299999999995e-01 -1.4718757517314287e+00 , 4.2949472616177511e+00 , 6.2480568000000005e+00 , -2.7941400000000000e-01 , 9.7378800000000001e-02 , 9.5521999999999996e-01 -1.4977466563158965e+00 , 4.2329144915246681e+00 , 6.2671200000000002e+00 , 2.7253300000000003e-01 , -2.2150900000000001e-01 , -9.3630100000000005e-01 -1.5196653543171432e+00 , 4.1757152887320643e+00 , 6.2935983999999996e+00 , 6.2844999999999998e-02 , 5.8967999999999998e-01 , 8.0518800000000001e-01 -1.5355809182213429e+00 , 4.1324312236195020e+00 , 6.3456815999999998e+00 , 1.1218700000000000e-01 , 6.8265200000000004e-01 , 7.2208099999999997e-01 -1.5442912967558131e+00 , 4.1011844536367539e+00 , 6.4243576000000004e+00 , 4.6438099999999999e-01 , 7.6982099999999998e-01 , 4.3786500000000000e-01 -1.5052662541647974e+00 , 4.1574415714191382e+00 , 6.6846904000000000e+00 , -8.5146999999999995e-01 , -4.5672400000000002e-01 , 2.5768500000000000e-01 -1.3633571579987351e+00 , 4.4016778511198549e+00 , 7.3712672000000001e+00 , 3.5619699999999999e-01 , 6.2673000000000001e-01 , -6.9306000000000001e-01 -1.4203043751812272e+00 , 4.2786674993769527e+00 , 7.2893256000000006e+00 , -3.2513300000000001e-01 , -5.2889200000000003e-01 , 7.8393999999999997e-01 -1.4650070262491286e+00 , 4.1777195061850030e+00 , 7.2510952000000000e+00 , -6.7617200000000000e-01 , -2.8735500000000003e-01 , 6.7839400000000005e-01 -1.5005165428756206e+00 , 4.0937964850815511e+00 , 7.2479128000000008e+00 , 2.3043200000000000e-01 , 1.7672499999999999e-01 , -9.5690600000000003e-01 -4.4185665074547820e-01 , 5.9297663960791773e+00 , 1.2213569600000001e+01 , -7.9991299999999999e-01 , 5.2850500000000000e-01 , -2.8429100000000002e-01 -1.5422160796557458e+00 , 3.9785508645419583e+00 , 7.3699568000000006e+00 , -1.5349800000000000e-01 , -4.1843700000000000e-01 , 8.9518100000000000e-01 -1.5761569886704332e+00 , 3.8988728262483949e+00 , 7.3717144000000001e+00 , 2.2729500000000000e-01 , 3.8751700000000000e-02 , 9.7305500000000000e-01 -1.5568518238995031e+00 , 3.9088605720356582e+00 , 7.6438200000000007e+00 , -7.3114400000000002e-01 , 5.5368600000000001e-01 , 3.9857300000000001e-01 -1.0733251396254562e+00 , 4.6835365934198983e+00 , 1.0400131999999999e+01 , 3.4556700000000001e-01 , -1.4061799999999999e-01 , -9.2779900000000004e-01 -1.3050752637106733e+00 , 4.2642018592005559e+00 , 9.4222928000000010e+00 , -4.6034500000000000e-01 , 4.2539199999999999e-01 , -7.7918200000000004e-01 -1.6517529464266241e+00 , 3.6768701515515234e+00 , 7.6984304000000003e+00 , 9.0763300000000002e-01 , 3.4414000000000000e-01 , -2.4035500000000001e-01 -1.6390956964495367e+00 , 3.6687227383418595e+00 , 7.9820176000000007e+00 , -4.7892299999999999e-01 , 8.7783699999999998e-01 , -5.9842200000000002e-03 -1.7917201004419234e+00 , 3.4058918066277855e+00 , 7.2476216000000004e+00 , 7.7129599999999998e-01 , -2.1523700000000001e-01 , 5.9897900000000004e-01 -1.8344667519168900e+00 , 3.3166550615585075e+00 , 7.1669695999999998e+00 , 7.8768300000000002e-01 , 5.4000300000000001e-01 , -2.9656600000000000e-01 -1.8868352634362662e+00 , 3.2145444650701096e+00 , 7.0138919999999993e+00 , 6.7015899999999995e-01 , -2.9098700000000000e-01 , 6.8279800000000002e-01 -1.7368980554699098e+00 , 3.3942058056495314e+00 , 8.3163152000000000e+00 , -5.4824699999999997e-05 , 9.2260200000000003e-01 , 3.8575300000000001e-01 -1.7799226581319285e+00 , 3.2980960789114864e+00 , 8.2753911999999996e+00 , -2.0213400000000001e-01 , 5.6735200000000000e-02 , -9.7771300000000005e-01 -1.5017815868251483e+00 , 5.0309762096039643e+00 , 1.8861917600000000e+00 , -9.8392900000000005e-01 , -1.6884099999999999e-01 , -5.8111599999999999e-02 -1.4919605960597231e+00 , 5.0486909962617545e+00 , 1.9351457040000000e+00 , -9.8392900000000005e-01 , -1.6884099999999999e-01 , -5.8111599999999999e-02 -1.4892193722632567e+00 , 5.0475092427733799e+00 , 1.9919375664000001e+00 , -9.8392900000000005e-01 , -1.6884099999999999e-01 , -5.8111599999999999e-02 -1.4793772652308710e+00 , 5.0641692080771943e+00 , 2.0408939440000000e+00 , -9.8392900000000005e-01 , -1.6884099999999999e-01 , -5.8111599999999999e-02 -1.4668850611412254e+00 , 5.0888660834942385e+00 , 2.0870223120000002e+00 , -9.8392900000000005e-01 , -1.6884099999999999e-01 , -5.8111599999999999e-02 --1.9512494142072616e+00 , 1.4281671669273965e+01 , -5.8984959999999997e-01 , 6.9743699999999997e-01 , 4.0293299999999999e-01 , -5.9264300000000003e-01 -1.4293267026639453e+00 , 5.1270731878912059e+00 , 2.4531290399999999e+00 , -9.8254200000000003e-01 , -1.7713599999999999e-01 , -5.6864100000000001e-02 -1.4298206638245510e+00 , 5.1168270828879070e+00 , 2.5077914400000001e+00 , -9.8254200000000003e-01 , -1.7713599999999999e-01 , -5.6864100000000001e-02 -1.4200230228880530e+00 , 5.1345041566943994e+00 , 2.5565424800000001e+00 , 9.9697700000000000e-01 , -2.2141600000000002e-03 , 7.7661200000000000e-02 -1.4177491564289653e+00 , 5.1314115631948631e+00 , 2.6091893600000002e+00 , 9.9726400000000004e-01 , -1.7951600000000001e-03 , 7.3902399999999993e-02 -1.4193671061313793e+00 , 5.1187934785718774e+00 , 2.6628699999999998e+00 , 9.9726400000000004e-01 , -1.7951600000000001e-03 , 7.3902399999999993e-02 -1.4220568961760174e+00 , 5.1049919455763879e+00 , 2.7161731200000001e+00 , 9.9726400000000004e-01 , -1.7951600000000001e-03 , 7.3902399999999993e-02 --1.0915135776399647e+00 , 1.1209660721486753e+01 , 4.8897024000000009e+00 , -2.9403900000000000e-02 , -7.5224700000000000e-01 , 6.5822499999999995e-01 --2.0750737445085194e+00 , 1.3619667565158709e+01 , 5.6055136000000001e+00 , 4.6140500000000001e-01 , 4.7815999999999997e-02 , 8.8590000000000002e-01 --1.0610393764001378e+00 , 1.1081888880609371e+01 , 5.2054255999999999e+00 , 2.0758399999999999e-01 , 8.6702299999999999e-01 , -4.5296900000000001e-01 --1.1584185550504942e+00 , 1.1294828030318820e+01 , 5.4351824000000004e+00 , -7.6950499999999999e-01 , 6.3485700000000000e-01 , 6.9417699999999999e-02 --1.4327599484034188e+00 , 1.1940500062485288e+01 , 5.7985375999999995e+00 , 9.9884300000000004e-01 , 3.9595800000000000e-02 , -2.7300200000000000e-02 --1.1296853872261252e+00 , 1.1168316216142053e+01 , 5.7567503999999996e+00 , -2.4856900000000001e-01 , 9.5836699999999997e-01 , 1.4052300000000001e-01 --1.0980668810545735e+00 , 1.1064790216141475e+01 , 5.9031928000000002e+00 , 4.9151600000000001e-01 , -8.3524500000000002e-01 , 2.4653200000000000e-01 --1.3897432988490648e+00 , 1.1747399394327774e+01 , 6.3198271999999998e+00 , -1.4165200000000000e-01 , 9.5712799999999998e-01 , 2.5266899999999998e-01 --1.3025960307940423e+00 , 1.1507512721431787e+01 , 6.4284032000000000e+00 , 2.9022700000000001e-01 , -6.3000500000000004e-01 , -7.2031999999999996e-01 --1.6796580102397729e+00 , 1.2387919592132185e+01 , 6.9654696000000005e+00 , 3.8886600000000000e-02 , -8.6470000000000002e-01 , 5.0078100000000003e-01 --1.1762713888401928e+00 , 1.1142934257071600e+01 , 6.6696415999999994e+00 , -2.1182599999999999e-01 , 5.9614299999999998e-01 , 7.7443099999999998e-01 --1.1355937500472404e+00 , 1.1017018524903179e+01 , 6.8070256000000002e+00 , 1.6348399999999999e-01 , -9.8649500000000001e-01 , -1.0066400000000000e-02 --4.9117078015454041e-01 , 9.4474074856094354e+00 , 6.2846336000000003e+00 , 3.7805200000000000e-01 , -9.1783499999999996e-01 , -1.2106200000000000e-01 --4.7440233384219832e-01 , 9.3832854908250862e+00 , 6.4126367999999996e+00 , 3.7805200000000000e-01 , -9.1783499999999996e-01 , -1.2106200000000000e-01 --4.9268830320568036e-01 , 9.4035713970615902e+00 , 6.5832072000000004e+00 , 3.7953100000000001e-01 , -9.1486000000000001e-01 , -1.3779600000000000e-01 --7.2469264096116426e-02 , 8.3850069573766923e+00 , 6.2130504000000002e+00 , 5.4729200000000000e-03 , -9.1411800000000001e-02 , 9.9579799999999996e-01 --5.0718295434618366e-02 , 8.3135437004965844e+00 , 6.3162184000000003e+00 , 1.6795800000000000e-01 , 2.5065900000000002e-01 , 9.5339399999999996e-01 -9.5747799837417702e-01 , 5.9197366163221634e+00 , 5.0903808000000001e+00 , -5.4997300000000005e-01 , -5.1099000000000006e-01 , -6.6061999999999999e-01 -8.8490855447497196e-01 , 6.0783016369625757e+00 , 5.2716424000000002e+00 , -2.7689999999999998e-01 , -6.0089599999999999e-01 , 7.4983299999999997e-01 -9.7678703824111723e-01 , 5.8488607314161154e+00 , 5.2223152000000006e+00 , -1.7743600000000001e-01 , -9.7479800000000005e-01 , -1.3522500000000001e-01 -9.3094648885133058e-01 , 5.9436992769098174e+00 , 5.3723248000000003e+00 , -4.1383900000000001e-01 , -2.2849900000000001e-01 , -8.8120699999999996e-01 --4.1345479805940544e-01 , 9.0474123967976432e+00 , 7.5571256000000009e+00 , 5.6384100000000004e-01 , -7.1650599999999998e-01 , 4.1073399999999999e-01 --5.5488736034108710e-01 , 9.3475725023966341e+00 , 7.9468864000000004e+00 , -7.6171800000000001e-01 , 4.1982000000000003e-01 , -4.9349399999999999e-01 --5.4049346612562799e-01 , 9.2887099965495814e+00 , 8.0952216000000004e+00 , -8.0080499999999999e-01 , 5.1213299999999995e-01 , -3.1053199999999997e-01 --5.1227820611515140e-01 , 9.1946387413307917e+00 , 8.2193248000000008e+00 , -5.6747300000000001e-01 , 7.7318799999999999e-01 , -2.8311799999999998e-01 --6.1772789510564108e-01 , 9.4086584677433862e+00 , 8.5845104000000010e+00 , -9.7375299999999998e-01 , 2.2071199999999999e-01 , 5.5598000000000002e-02 --2.2362463958523549e-01 , 8.4842831340215596e+00 , 8.0385312000000013e+00 , 8.2959300000000000e-03 , -7.4822200000000005e-01 , 6.6339700000000001e-01 --4.0430821417166207e-01 , 8.8665360580794825e+00 , 8.5480376000000007e+00 , -7.0408700000000002e-01 , -6.2919499999999995e-01 , -3.2920500000000003e-01 --2.3067886636988710e-01 , 8.4479518690650384e+00 , 8.3837592000000001e+00 , 7.9557100000000006e-02 , -8.9713699999999996e-01 , 4.3453100000000000e-01 --3.8184606599010174e-01 , 8.7592969557278302e+00 , 8.8638231999999988e+00 , -1.3492599999999999e-01 , 1.7164499999999999e-01 , 9.7587599999999997e-01 --3.2565740308492863e-01 , 8.6044998844140341e+00 , 8.9296760000000006e+00 , 6.9452199999999997e-01 , 1.7548000000000000e-01 , 6.9774300000000000e-01 --2.6901593050291028e-01 , 8.4489138456749551e+00 , 8.9916912000000018e+00 , -3.6368499999999998e-01 , 6.8601599999999999e-02 , -9.2899200000000004e-01 --1.1094118827709218e+00 , 1.0278001725101060e+01 , 1.1060552800000002e+01 , 3.0918699999999999e-01 , -6.9998800000000005e-01 , 6.4375499999999997e-01 --1.3958890985722356e+00 , 1.0868898891010263e+01 , 1.1971707199999999e+01 , -1.7356300000000000e-01 , -1.1664300000000001e-02 , 9.8475400000000002e-01 --1.1915203410819877e+00 , 1.0376556221008350e+01 , 1.1758829600000000e+01 , 8.5336100000000004e-01 , -2.4437700000000001e-01 , -4.6049400000000001e-01 -3.6324545244196194e-01 , 6.9507149606593757e+00 , 8.2098088000000011e+00 , -1.5794600000000000e-01 , -1.8625100000000000e-01 , 9.6972400000000003e-01 --1.0118650233390336e+00 , 9.9012228010315528e+00 , 1.1846439200000001e+01 , 7.9955600000000004e-01 , -6.0042899999999999e-01 , -1.3971000000000001e-02 --1.9361855706534925e-01 , 8.0980894608328562e+00 , 9.9807208000000003e+00 , 2.8698000000000001e-01 , 7.5397400000000003e-01 , 5.9090299999999996e-01 --9.1004507940342094e-02 , 7.8451342625480285e+00 , 9.9171040000000001e+00 , 2.8698000000000001e-01 , 7.5397400000000003e-01 , 5.9090299999999996e-01 -1.1494763787861606e+00 , 5.1748788416005880e+00 , 6.6888399999999999e+00 , 2.5509399999999999e-01 , 6.6925800000000002e-01 , 6.9786800000000004e-01 -1.1583812041011867e+00 , 5.1385142872737601e+00 , 6.7737352000000008e+00 , -1.0103900000000000e-01 , -7.9436600000000002e-01 , -5.9897800000000001e-01 -1.1316408492484666e+00 , 5.1749243765503365e+00 , 6.9645648000000007e+00 , 1.2897000000000000e-01 , -9.7435000000000005e-01 , 1.8441700000000000e-01 -1.2031346078338736e+00 , 5.0080553224233766e+00 , 6.8683752000000000e+00 , 4.6794300000000000e-01 , -4.2152000000000001e-01 , -7.7675700000000003e-01 -1.2322482914109023e+00 , 4.9288737589241842e+00 , 6.8926592000000007e+00 , 5.8499500000000004e-01 , 3.7184799999999997e-02 , -8.1018400000000002e-01 -1.2676054742979832e+00 , 4.8382452096549393e+00 , 6.8983375999999996e+00 , 8.1360900000000003e-01 , 2.7880600000000000e-01 , -5.1020299999999996e-01 -1.4656396104335068e+00 , 4.4166919192556193e+00 , 6.3608240000000000e+00 , 7.3930700000000005e-01 , 4.0999900000000000e-01 , -5.3415900000000005e-01 -1.5164967612763012e+00 , 4.2953970536172408e+00 , 6.2861416000000006e+00 , -4.4202700000000000e-01 , 1.9951500000000000e-01 , 8.7453199999999998e-01 -1.5454094678926591e+00 , 4.2221490380761137e+00 , 6.2871503999999998e+00 , -4.1138999999999998e-01 , 1.2994600000000001e-01 , 9.0214899999999998e-01 -1.5663219541346149e+00 , 4.1638332749991411e+00 , 6.3130984000000003e+00 , 1.1988300000000000e-01 , -5.3179200000000004e-01 , -8.3834699999999995e-01 -1.5801887229791156e+00 , 4.1194653725560713e+00 , 6.3646304000000002e+00 , 2.4794900000000000e-01 , 7.6978800000000003e-01 , 5.8817299999999995e-01 -1.5930812939172301e+00 , 4.0789960386799375e+00 , 6.4247528000000003e+00 , 2.9942800000000003e-01 , 7.1963600000000005e-01 , 6.2647200000000003e-01 -1.5664427725796619e+00 , 4.1107364770295600e+00 , 6.6398663999999998e+00 , -7.1472300000000000e-01 , -6.9862100000000005e-01 , 3.3161900000000001e-02 -1.2819114473333051e+00 , 4.6369370063436133e+00 , 7.9471048000000000e+00 , -3.5493900000000000e-01 , 9.2995600000000000e-01 , 9.5919599999999994e-02 -1.4445292887952885e+00 , 4.3024348106014427e+00 , 7.4124511999999996e+00 , -7.9317499999999996e-01 , -5.9366799999999997e-01 , 1.3575999999999999e-01 -1.4977512915189333e+00 , 4.1798790342378727e+00 , 7.3267655999999999e+00 , -8.0086999999999997e-01 , -2.3703900000000000e-01 , 5.4992700000000005e-01 -1.5450745192532835e+00 , 4.0681715967124514e+00 , 7.2567528000000001e+00 , -9.3056399999999995e-01 , 1.3744400000000001e-01 , 3.3935199999999999e-01 -9.3508941039728510e-01 , 5.1498208342200149e+00 , 1.0323879199999999e+01 , 3.1276999999999999e-01 , -1.3215499999999999e-01 , -9.4059000000000004e-01 -1.5891752845923082e+00 , 3.9403605547948097e+00 , 7.3485328000000010e+00 , -2.0149200000000000e-01 , -1.1058300000000000e-01 , -9.7322799999999998e-01 -1.5852256865821581e+00 , 3.9225390471661568e+00 , 7.5332680000000005e+00 , -8.9826600000000001e-01 , 4.0173199999999998e-01 , 1.7812700000000001e-01 -1.0736391400994636e+00 , 4.7759841723013370e+00 , 1.0437416000000001e+01 , -3.4556700000000001e-01 , 1.4061799999999999e-01 , 9.2779900000000004e-01 -1.1104747027395687e+00 , 4.6662998856913269e+00 , 1.0522779199999999e+01 , -3.4556700000000001e-01 , 1.4061799999999999e-01 , 9.2779900000000004e-01 -1.3623153200383005e+00 , 4.2029993269737753e+00 , 9.3731632000000005e+00 , -4.6294900000000000e-01 , 4.3873800000000002e-01 , -7.7018600000000004e-01 -1.6561215532038236e+00 , 3.6880701133021945e+00 , 7.8708832000000006e+00 , 6.0225700000000004e-01 , -7.9493300000000000e-01 , -7.3268899999999998e-02 -1.7973628893926490e+00 , 3.4318560111828562e+00 , 7.1879776000000000e+00 , -3.1114300000000001e-02 , 6.5422800000000003e-01 , 7.5565700000000002e-01 -1.7188809861390479e+00 , 3.5224548080489484e+00 , 7.8897176000000000e+00 , 9.7703200000000001e-01 , -1.0700600000000000e-01 , -1.8427700000000000e-01 -1.8777147480226049e+00 , 3.2534545087023075e+00 , 7.0258415999999997e+00 , 9.3931899999999999e-02 , 3.3771200000000001e-01 , 9.3655100000000002e-01 -1.8958765436203373e+00 , 3.1962683853411651e+00 , 7.0831976000000001e+00 , -9.2635000000000001e-01 , 2.6352900000000001e-01 , -2.6912500000000000e-01 -1.7685748264438894e+00 , 3.3382418554966109e+00 , 8.2455536000000009e+00 , -7.9917000000000005e-01 , 2.8223199999999998e-01 , 5.3072799999999998e-01 -1.8025919884568320e+00 , 3.2514483303315060e+00 , 8.2542375999999997e+00 , 4.2842400000000003e-01 , -9.0255399999999997e-01 , 4.2993299999999998e-02 -7.6370814828107259e-02 , 9.6833509552693329e+00 , -2.5488639999999974e-01 , -5.8037099999999997e-01 , -4.0484100000000001e-01 , -7.0659200000000000e-01 --5.1392283321076260e-01 , 1.1450315358632615e+01 , -8.7061840000000013e-01 , -6.5264699999999995e-02 , 1.9512900000000000e-01 , 9.7860400000000003e-01 --8.2717215545976419e-01 , 1.2365474988657336e+01 , -1.0593680000000001e+00 , -9.7642099999999996e-02 , 1.8752199999999999e-01 , 9.7739500000000001e-01 --1.2134725806136646e+00 , 1.3491788218805706e+01 , -1.2959575999999999e+00 , -1.7906100000000000e-01 , 2.8903000000000002e-02 , 9.8341299999999998e-01 --1.5379994707914406e+00 , 1.4422425463790020e+01 , -1.4154744000000004e+00 , -2.9143500000000000e-01 , -1.1001000000000000e-01 , -9.5024399999999998e-01 --2.1231497393254077e+00 , 1.6126551107391293e+01 , -1.7731304000000003e+00 , 1.7880299999999999e-01 , -2.5055800000000000e-01 , -9.5144600000000001e-01 --3.0246914997950123e+00 , 1.8766252695279519e+01 , -2.3766216000000000e+00 , -8.4319900000000003e-02 , 1.9369700000000001e-01 , 9.7743100000000005e-01 --3.9594672665436832e+00 , 2.1483685147514432e+01 , -2.9019463999999999e+00 , -7.1055900000000005e-02 , 1.5571599999999999e-01 , 9.8524299999999998e-01 -1.3180923942915896e+00 , 5.7015928859656579e+00 , 2.4297498399999999e+00 , 9.9726400000000004e-01 , -1.7951600000000001e-03 , 7.3902399999999993e-02 -1.3174241675370393e+00 , 5.6911960860007103e+00 , 2.4939282399999998e+00 , 9.9726400000000004e-01 , -1.7951600000000001e-03 , 7.3902399999999993e-02 --2.5499784603415483e+00 , 1.6443160438478881e+01 , 2.9276488000000001e+00 , 7.7988299999999999e-01 , -6.0056900000000002e-01 , 1.7635200000000001e-01 --2.5299854242541375e+00 , 1.6339506259062091e+01 , 3.1867128000000000e+00 , 7.7988299999999999e-01 , -6.0056900000000002e-01 , 1.7635200000000001e-01 --2.5577613124089744e+00 , 1.6369424413145694e+01 , 3.4454544000000000e+00 , 7.7988299999999999e-01 , -6.0056900000000002e-01 , 1.7635200000000001e-01 --1.6740511275789300e+00 , 1.3590811255087194e+01 , 5.0526080000000002e+00 , 3.4528500000000001e-01 , 1.9689100000000001e-02 , 9.3829099999999999e-01 --1.4717983557130219e+00 , 1.3005623891158070e+01 , 5.1529679999999995e+00 , -3.7091400000000002e-01 , -1.5403699999999999e-02 , -9.2854000000000003e-01 --1.4734639629516506e+00 , 1.2975573988690899e+01 , 5.3515975999999998e+00 , 1.1729299999999999e-01 , -6.3677800000000007e-02 , 9.9105399999999999e-01 --1.3157619038198591e+00 , 1.2513893682803985e+01 , 5.4493056000000006e+00 , 8.9768400000000004e-01 , -3.5227700000000001e-01 , -2.6469799999999999e-01 --9.8917528891091111e-01 , 1.1606860144605507e+01 , 5.4178351999999999e+00 , -8.6830800000000000e-02 , -8.3501999999999998e-01 , 5.4332499999999995e-01 --8.7873362983406000e-01 , 1.1280064968909612e+01 , 5.5111752000000003e+00 , 3.5422999999999999e-01 , -8.3526699999999998e-01 , 4.2053499999999999e-01 --9.6565400104338472e-01 , 1.1479037153481924e+01 , 5.7476088000000001e+00 , 4.7228300000000001e-01 , -8.7931999999999999e-01 , 6.1195199999999998e-02 --1.0372342123577449e+00 , 1.1635245324213779e+01 , 5.9806832000000005e+00 , 8.7099099999999996e-01 , 8.9098000000000007e-03 , 4.9121799999999999e-01 --1.2055897781758951e+00 , 1.2047035422486733e+01 , 6.3072432000000003e+00 , -5.2772500000000000e-01 , 5.8441100000000001e-01 , 6.1641599999999996e-01 --1.1443789792493377e+00 , 1.1849717305623907e+01 , 6.4373056000000002e+00 , -1.9433300000000001e-01 , 2.2280900000000001e-01 , 9.5529600000000003e-01 --1.7821611205221646e+00 , 1.3485171350318335e+01 , 7.2509079999999999e+00 , 7.8785599999999997e-02 , 2.6838600000000001e-01 , 9.6008400000000005e-01 --9.4241345338743354e-01 , 1.1253435729100227e+01 , 6.5987032000000001e+00 , -7.3262999999999995e-02 , -5.6926500000000002e-01 , -8.1888300000000003e-01 --1.0215358290775165e+00 , 1.1425570984382919e+01 , 6.8616880000000000e+00 , 3.6233300000000002e-01 , -9.2786199999999996e-01 , -8.8247099999999995e-02 --1.0155462987584007e+00 , 1.1375764914955223e+01 , 7.0374168000000008e+00 , -6.4152399999999998e-01 , 7.5730500000000001e-01 , -1.2221400000000000e-01 --1.5264439735213617e+00 , 1.2658798057070779e+01 , 7.8312280000000003e+00 , 2.8023599999999999e-01 , -2.7905600000000003e-01 , -9.1847400000000001e-01 --3.1940790337933977e-01 , 9.5207135419618680e+00 , 6.5375304000000005e+00 , 6.7982900000000002e-01 , -5.6421600000000005e-01 , -4.6850100000000000e-01 --3.0626598943538186e-01 , 9.4597614534997057e+00 , 6.6700055999999996e+00 , 5.0620500000000002e-01 , -8.4935799999999995e-01 , -1.4949200000000001e-01 -1.1560688515248341e-01 , 8.3551650691299866e+00 , 6.2473704000000003e+00 , 5.5336499999999997e-02 , 1.8783500000000000e-01 , 9.8064099999999998e-01 -1.0527002576746769e+00 , 5.9538846459445391e+00 , 5.0536063999999996e+00 , 5.8279400000000003e-01 , 6.7374699999999998e-01 , 4.5433099999999998e-01 -1.0608110252705127e+00 , 5.9201181243859793e+00 , 5.1195839999999997e+00 , 2.7742699999999998e-01 , 8.1313100000000005e-01 , 5.1171500000000003e-01 -1.0555393481954090e+00 , 5.9174896085127484e+00 , 5.2055607999999998e+00 , -4.2572300000000002e-01 , -8.6990699999999999e-01 , -2.4904000000000001e-01 -1.0843852374854817e+00 , 5.8307089668691052e+00 , 5.2394959999999999e+00 , 1.9733899999999999e-01 , 8.1091199999999997e-01 , 5.5088899999999996e-01 --5.0601833429526533e-01 , 9.7842211815544804e+00 , 7.9215832000000006e+00 , -8.9651000000000003e-01 , 3.8185300000000000e-01 , -2.2462799999999999e-01 --3.9696251695176699e-01 , 9.4797157933527814e+00 , 7.9091344000000010e+00 , -7.6171800000000001e-01 , 4.1982000000000003e-01 , -4.9349399999999999e-01 --3.4677275073566438e-01 , 9.3238936929099019e+00 , 7.9896824000000004e+00 , -7.6171800000000001e-01 , 4.1982000000000003e-01 , -4.9349399999999999e-01 --5.8703945883753539e-01 , 9.8838662358956189e+00 , 8.5938911999999998e+00 , 2.0452699999999999e-01 , -9.7882800000000003e-01 , -7.9729699999999994e-03 --5.5909939592803015e-01 , 9.7811226379849590e+00 , 8.7275519999999993e+00 , -1.4805900000000000e-02 , -3.3510200000000001e-01 , 9.4206599999999996e-01 --5.7048547467046795e-02 , 8.5211907906700013e+00 , 7.9410832000000005e+00 , 7.9557100000000006e-02 , -8.9713699999999996e-01 , 4.3453100000000000e-01 --8.4605991658541768e-02 , 8.5604276975021438e+00 , 8.1562488000000002e+00 , 7.9557000000000003e-02 , -8.9713600000000004e-01 , 4.3453100000000000e-01 --6.1455729172645412e-02 , 8.4732565248738734e+00 , 8.2713768000000005e+00 , 3.2408599999999999e-01 , -9.3452299999999999e-01 , 1.4709000000000000e-01 --2.4508559425225407e-01 , 8.8817699734933839e+00 , 8.8263208000000013e+00 , -6.3250899999999999e-01 , -7.5729900000000006e-01 , -1.6257700000000000e-01 --1.7836943766508506e-01 , 8.6881995058262991e+00 , 8.8600479999999990e+00 , 4.9593999999999999e-02 , -9.9863199999999999e-02 , 9.9376399999999998e-01 --1.7015988156275816e+00 , 1.2276189463180437e+01 , 1.2493079999999999e+01 , -9.8906700000000003e-01 , 8.6572499999999997e-02 , -1.1938200000000000e-01 --1.5670937783156522e+00 , 1.1903188299265745e+01 , 1.2467808000000002e+01 , -9.3951600000000002e-01 , -3.4195700000000001e-01 , 1.9365100000000000e-02 --1.2633238159145774e+00 , 1.1137310713165947e+01 , 1.2025225600000001e+01 , -1.8034600000000001e-01 , -3.2868199999999997e-01 , 9.2706200000000005e-01 --1.6891050315283000e+00 , 1.2079968234315055e+01 , 1.3350976000000001e+01 , 5.2647999999999995e-01 , -3.8448500000000002e-01 , 7.5828099999999998e-01 --1.0106852774667052e+00 , 1.0447520360226244e+01 , 1.1928297600000001e+01 , -3.0774499999999999e-01 , -2.8889200000000000e-02 , 9.5103000000000004e-01 -5.0122692995646112e-01 , 6.9086172979771536e+00 , 8.2147800000000011e+00 , -1.5794800000000001e-01 , -1.8625300000000000e-01 , 9.6972300000000000e-01 --3.5795436086965005e-03 , 8.0374157497645804e+00 , 9.7359048000000001e+00 , 2.7555099999999999e-01 , 6.9654499999999997e-01 , 6.6249300000000000e-01 -3.4464518915258369e-02 , 7.9116665258403209e+00 , 9.8261143999999998e+00 , 2.8698000000000001e-01 , 7.5397400000000003e-01 , 5.9090299999999996e-01 -1.2152554991984106e+00 , 5.2036526968367358e+00 , 6.6348536000000005e+00 , 1.9969100000000001e-01 , 8.4248999999999996e-01 , 5.0033399999999995e-01 -1.2280136650760078e+00 , 5.1553460360512933e+00 , 6.7035248000000003e+00 , 1.6800899999999999e-01 , 7.8706600000000004e-01 , 5.9354899999999999e-01 -1.2408763212447913e+00 , 5.1068589375407285e+00 , 6.7712808000000004e+00 , 1.7225499999999999e-01 , 7.5223499999999999e-01 , 6.3597999999999999e-01 -1.2389200177580348e+00 , 5.0901418512988590e+00 , 6.8881456000000005e+00 , -7.1725099999999997e-01 , -1.1944299999999999e-01 , 6.8650199999999995e-01 -1.2816824570659371e+00 , 4.9750692456724650e+00 , 6.8637160000000010e+00 , -8.6765700000000001e-01 , 6.3903100000000004e-02 , 4.9303900000000001e-01 -1.2828033357771278e+00 , 4.9499667512779153e+00 , 6.9712312000000001e+00 , 7.7541899999999997e-01 , 1.9055600000000000e-01 , -6.0200699999999996e-01 -1.3281383667644362e+00 , 4.8310861340153490e+00 , 6.9336768000000006e+00 , -8.0244700000000002e-01 , -2.6576499999999997e-01 , 5.3427400000000003e-01 -1.4435248172972321e+00 , 4.5624575968911305e+00 , 6.6421856000000004e+00 , 3.2468100000000000e-01 , 8.0682799999999999e-01 , -4.9357000000000001e-01 -1.5630869391147828e+00 , 4.2887118337604040e+00 , 6.3155736000000005e+00 , -7.4652600000000002e-01 , -1.9147300000000000e-01 , 6.3721099999999997e-01 -1.5899624134662886e+00 , 4.2143611017353493e+00 , 6.3159272000000009e+00 , 3.5496499999999997e-01 , -2.7101500000000001e-01 , -8.9473499999999995e-01 -1.6108741784801184e+00 , 4.1498692854975374e+00 , 6.3323592000000000e+00 , -1.8993800000000000e-01 , 4.1110700000000000e-01 , 8.9158000000000004e-01 -1.6258018595028216e+00 , 4.1003576209861521e+00 , 6.3743752000000002e+00 , 2.9429300000000003e-01 , 6.7303800000000003e-01 , 6.7853600000000003e-01 -1.6366707048196627e+00 , 4.0587564739863282e+00 , 6.4337488000000000e+00 , 3.1805299999999997e-01 , 6.6664100000000004e-01 , 6.7411600000000005e-01 -1.6225163691091939e+00 , 4.0680056084854543e+00 , 6.6031336000000005e+00 , -7.6324300000000000e-01 , -6.4590400000000003e-01 , -1.6364199999999999e-02 -1.4747270592905175e+00 , 4.3399663127334831e+00 , 7.3680640000000004e+00 , -8.3382299999999998e-01 , -5.5201900000000004e-01 , -3.7941300000000002e-03 -1.5246669128643089e+00 , 4.2156097787325510e+00 , 7.2832208000000005e+00 , -5.3661599999999998e-01 , -2.9817300000000002e-01 , 7.8938900000000001e-01 -1.5145055189814403e+00 , 4.2066949177218849e+00 , 7.4686943999999995e+00 , -8.7946599999999997e-01 , -2.9979299999999998e-01 , 3.6968200000000001e-01 -6.6715583415183599e-01 , 5.7847795500661476e+00 , 1.1726485600000000e+01 , -1.8662500000000001e-01 , -8.9736800000000005e-01 , 3.9987800000000001e-01 -9.8038043206061487e-01 , 5.1453765820298063e+00 , 1.0459058400000002e+01 , -3.3747400000000000e-01 , 2.0247200000000001e-01 , 9.1930199999999995e-01 -1.0394351336939307e+00 , 4.9884757699595497e+00 , 1.0414941600000001e+01 , -3.3747400000000000e-01 , 2.0247200000000001e-01 , 9.1930199999999995e-01 -1.5963579640990755e+00 , 3.9399913738868433e+00 , 7.6855551999999996e+00 , -3.7765199999999999e-01 , 6.2086399999999997e-01 , 6.8695399999999995e-01 -1.1250223868119280e+00 , 4.7339897550932601e+00 , 1.0482396000000001e+01 , -3.4556700000000001e-01 , 1.4061799999999999e-01 , 9.2779800000000001e-01 -1.2953672866597978e+00 , 4.3896677463924014e+00 , 9.7794391999999988e+00 , -5.1113299999999995e-01 , -8.4338999999999997e-01 , 1.6563700000000001e-01 -1.6584269022290594e+00 , 3.7333180619117385e+00 , 7.8588088000000003e+00 , -8.6667099999999997e-01 , 3.9812300000000000e-01 , 3.0063299999999998e-01 -1.6581700709156080e+00 , 3.6982585819926750e+00 , 8.0536320000000003e+00 , 7.4911399999999995e-01 , -6.6235599999999994e-01 , 1.0616000000000000e-02 -1.8446388304168668e+00 , 3.3636780710869996e+00 , 7.0388416000000005e+00 , 9.9575999999999998e-01 , -3.1439500000000002e-02 , 8.6445099999999997e-02 -1.8685047357728597e+00 , 3.2954025293360534e+00 , 7.0476295999999996e+00 , -5.1385000000000003e-01 , 1.2426700000000000e-01 , -8.4883200000000003e-01 -1.8937610735479797e+00 , 3.2257852790200907e+00 , 7.0447800000000003e+00 , 1.9987200000000000e-02 , 9.1000400000000004e-01 , 4.1411700000000001e-01 -1.7579767224960647e+00 , 3.3824340387219474e+00 , 8.2360375999999995e+00 , -7.7071599999999996e-01 , 3.2724500000000001e-01 , -5.4672500000000002e-01 -1.7781198955898261e+00 , 3.3095094324785634e+00 , 8.3263719999999992e+00 , 5.0062700000000004e-01 , -8.5685999999999996e-01 , 1.2314500000000000e-01 -3.9930169992741704e-01 , 9.4896788706826385e+00 , -3.4614640000000030e-01 , -2.9530699999999999e-01 , -4.2675000000000002e-01 , -8.5479700000000003e-01 -1.8464461407530530e-01 , 1.0190882478622287e+01 , -5.1649839999999969e-01 , 9.8557599999999995e-02 , 2.7894099999999999e-01 , 9.5523700000000000e-01 --9.9702947724689128e-02 , 1.1120368781675822e+01 , -7.5974399999999997e-01 , -5.2333299999999999e-02 , 2.0206700000000000e-01 , 9.7797199999999995e-01 --3.3727968162684840e-01 , 1.1882494953663475e+01 , -8.9608800000000022e-01 , -6.8353999999999998e-02 , 1.8690300000000001e-01 , 9.7999800000000004e-01 --6.7806847257768466e-01 , 1.2987398379045613e+01 , -1.1396768000000002e+00 , -7.1664300000000000e-02 , 1.6761799999999999e-01 , 9.8324400000000001e-01 --9.4105686542624278e-01 , 1.3820044130299971e+01 , -1.2374472000000001e+00 , 6.5303399999999998e-02 , -2.4878300000000000e-01 , 9.6635499999999996e-01 --1.3464413600543357e+00 , 1.5120762431035702e+01 , -1.4715824000000000e+00 , 5.5919400000000001e-02 , -3.9174300000000001e-01 , -9.1837400000000002e-01 --1.9375761770502362e+00 , 1.7027840668123112e+01 , -1.8610831999999999e+00 , -6.0769299999999998e-02 , 2.6921899999999999e-01 , 9.6116000000000001e-01 --2.8400184572734810e+00 , 1.9950262941123871e+01 , -2.5004023999999996e+00 , 8.1893400000000005e-02 , -1.5385599999999999e-01 , -9.8469399999999996e-01 --3.7134774178406875e+00 , 2.2751540481752226e+01 , -2.9914695999999994e+00 , 6.6980599999999996e-03 , -2.6276600000000000e-01 , 9.6483600000000003e-01 --2.0255170614433027e+00 , 1.6315914384310052e+01 , 2.5767132799999999e+00 , 5.0127299999999997e-01 , -8.3256900000000000e-01 , 2.3569999999999999e-01 --2.0325705972212473e+00 , 1.6224498838408991e+01 , 3.0857600000000001e+00 , 5.0127299999999997e-01 , -8.3256900000000000e-01 , 2.3569999999999999e-01 --2.0318013385226292e+00 , 1.6167989236774449e+01 , 3.3377312000000003e+00 , -9.1159100000000004e-01 , -3.9657399999999998e-01 , 1.0830700000000000e-01 --2.0750878255477607e+00 , 1.6244637399551014e+01 , 3.5932279999999999e+00 , -9.0427199999999996e-01 , -4.1810000000000003e-01 , 8.6518600000000001e-02 --2.2856851254442700e+00 , 1.6830786124903600e+01 , 3.8799872000000000e+00 , -8.0229300000000003e-01 , 5.9638199999999997e-01 , -2.5605099999999999e-02 --2.2270172565485984e+00 , 1.6592565070307916e+01 , 4.1281832000000005e+00 , 8.3971300000000004e-01 , -5.4015899999999994e-01 , -5.5769300000000001e-02 --1.5317564700929882e+00 , 1.4243188959657809e+01 , 5.0586503999999994e+00 , -4.5238200000000001e-01 , -4.5445900000000000e-01 , -7.6734500000000005e-01 --1.2685221268070497e+00 , 1.3417915016576643e+01 , 5.1295992000000004e+00 , -1.8294099999999999e-01 , 3.2391100000000000e-01 , 9.2823199999999995e-01 --4.8022349337804560e-01 , 1.1048645325588220e+01 , 4.8533752000000003e+00 , -1.2154700000000000e-01 , -9.1451499999999997e-01 , 3.8586100000000001e-01 --4.8028250298458186e-01 , 1.1013742672878251e+01 , 5.0121624000000002e+00 , -1.2154700000000000e-01 , -9.1451499999999997e-01 , 3.8586100000000001e-01 --5.0301870967376283e-01 , 1.1044523248110895e+01 , 5.1864559999999997e+00 , 4.1798299999999997e-02 , -8.6973400000000001e-01 , 4.9174699999999999e-01 --5.2069119770905337e-01 , 1.1062238186076424e+01 , 5.3601983999999998e+00 , 6.8409899999999996e-02 , 8.8012100000000004e-01 , -4.6979500000000002e-01 --6.9572050532667085e-01 , 1.1532418329961230e+01 , 5.6643880000000006e+00 , 2.6164599999999999e-01 , 8.6077099999999995e-01 , -4.3659500000000001e-01 --6.9852516390147201e-01 , 1.1502731775700548e+01 , 5.8379224000000001e+00 , -2.9642800000000002e-01 , 1.6364500000000001e-01 , -9.4093099999999996e-01 --1.0202365089134120e+00 , 1.2391918124955346e+01 , 6.3088448000000001e+00 , 1.1956600000000001e-01 , 9.3036800000000003e-02 , -9.8845700000000003e-01 --9.0083810237645023e-01 , 1.2006081481787460e+01 , 6.3799496000000007e+00 , -3.0653300000000000e-01 , 1.3565900000000000e-01 , 9.4214299999999995e-01 --8.2512661524085518e-01 , 1.1751185278646309e+01 , 6.4854471999999994e+00 , 1.1743800000000000e-01 , 5.1635100000000000e-01 , 8.4828700000000001e-01 --7.5286550372360672e-01 , 1.1505044517613811e+01 , 6.5861816000000006e+00 , -3.5495700000000002e-01 , 7.6775700000000002e-01 , -5.3343799999999997e-01 --6.5329626265215257e-01 , 1.1185394146310863e+01 , 6.6494032000000001e+00 , 3.5842800000000002e-01 , -7.6788400000000001e-01 , 5.3092600000000001e-01 --9.1223973269524494e-01 , 1.1874978190265747e+01 , 7.1339912000000005e+00 , -4.6714699999999998e-01 , 8.8351800000000003e-01 , -3.4202900000000001e-02 --7.9509146672668995e-01 , 1.1505366736731510e+01 , 7.1743224000000003e+00 , -4.5158999999999999e-01 , 8.2071600000000000e-01 , -3.4998899999999999e-01 --7.7738903533214065e-01 , 1.1413504538961531e+01 , 7.3335048000000009e+00 , 5.9769300000000003e-01 , -7.4683400000000000e-01 , 2.9155300000000001e-01 --1.0003196670441836e+00 , 1.1994479070139027e+01 , 7.8242392000000001e+00 , -1.0641200000000000e-02 , -4.9298199999999998e-01 , 8.6997500000000005e-01 --1.3711474863783524e-01 , 9.5627915599184163e+00 , 6.7853000000000003e+00 , 7.0509400000000000e-01 , -3.8490200000000002e-01 , -5.9555999999999998e-01 -2.9908810508986217e-01 , 8.3295064971613648e+00 , 6.2856320000000006e+00 , 1.1687100000000000e-01 , 4.9987399999999999e-01 , 8.5817600000000005e-01 -3.9499186035993494e-01 , 8.0405125945801466e+00 , 6.2630848000000006e+00 , 5.0210400000000002e-02 , 5.2116300000000004e-01 , 8.5197900000000004e-01 -4.1156450484728491e-01 , 7.9673841710315525e+00 , 6.3569032000000005e+00 , 2.3094300000000001e-01 , -4.6238499999999999e-01 , -8.5607599999999995e-01 -1.1800184838995367e+00 , 5.8553793245912269e+00 , 5.1978960000000001e+00 , -4.2572399999999999e-01 , -8.6990699999999999e-01 , -2.4904000000000001e-01 -1.1997574495996812e+00 , 5.7844738632022334e+00 , 5.2402031999999998e+00 , -1.9733899999999999e-01 , -8.1091199999999997e-01 , -5.5088899999999996e-01 -5.0938032402304345e-01 , 7.6243831910331954e+00 , 6.5515184000000000e+00 , 9.4882500000000003e-01 , 8.7131399999999994e-03 , -3.1568200000000002e-01 -3.5907830671700314e-01 , 7.9962726187978692e+00 , 6.9475608000000006e+00 , -2.9065800000000003e-01 , -9.2294100000000001e-01 , 2.5238300000000002e-01 --4.2209945783300684e-01 , 1.0045414158455788e+01 , 8.5718432000000000e+00 , 8.6435799999999996e-01 , -3.1812200000000002e-01 , -3.8946599999999998e-01 --1.7581017538795067e+00 , 1.3539179781446391e+01 , 1.1392562399999999e+01 , -2.7223000000000001e-02 , -6.0773500000000003e-01 , 7.9367299999999996e-01 --3.8825310478868946e-01 , 9.8758797906408820e+00 , 8.8707184000000012e+00 , -5.2066199999999996e-01 , 1.6499700000000000e-01 , 8.3766799999999997e-01 --3.6603777726578368e-01 , 9.7753077499487659e+00 , 9.0087159999999997e+00 , 2.9369400000000001e-01 , 7.4364100000000000e-01 , 6.0061699999999996e-01 -1.3728289633514779e-01 , 8.4244697063573657e+00 , 8.1032712000000000e+00 , 3.2408599999999999e-01 , -9.3452299999999999e-01 , 1.4709000000000000e-01 --1.4012621098692168e-02 , 8.7827341638318082e+00 , 8.6001311999999999e+00 , -8.0003299999999999e-01 , -4.7972700000000001e-01 , 3.6029200000000000e-01 --1.1294999175534581e-01 , 8.9999522422708687e+00 , 8.9983576000000003e+00 , 5.6414900000000001e-01 , -3.3978899999999999e-02 , -8.2497399999999999e-01 -5.0999721005425380e-02 , 8.5393261679931847e+00 , 8.7866759999999999e+00 , 5.5910800000000005e-01 , 6.9984599999999997e-01 , -4.4453799999999999e-01 -9.4807372857167449e-02 , 8.3902220495313635e+00 , 8.8518216000000010e+00 , 3.5532000000000002e-01 , -9.3326100000000001e-01 , 5.2646800000000001e-02 --5.6048065119577029e-01 , 1.0004873138102333e+01 , 1.0675825600000001e+01 , -1.9569500000000001e-01 , -4.0487299999999998e-01 , 8.9318600000000004e-01 --1.0167667899599246e+00 , 1.1099628496992313e+01 , 1.2085805599999999e+01 , -1.7356300000000000e-01 , -1.1664300000000001e-02 , 9.8475400000000002e-01 --8.9287942791457375e-01 , 1.0732677731789561e+01 , 1.2019588799999999e+01 , -1.7356300000000000e-01 , -1.1664300000000001e-02 , 9.8475400000000002e-01 --8.7284836119001508e-01 , 1.0626951402863055e+01 , 1.2226372000000000e+01 , -1.7356300000000000e-01 , -1.1664300000000001e-02 , 9.8475400000000002e-01 -6.4187593189580538e-01 , 6.8494027933507962e+00 , 8.2038183999999994e+00 , -1.2534200000000001e-01 , -1.4016999999999999e-01 , 9.8216199999999998e-01 -1.4287861582447503e-01 , 8.0325001087409404e+00 , 9.8060320000000001e+00 , -4.7455999999999998e-02 , -7.6824199999999998e-01 , -6.3839800000000002e-01 -1.5653014242368846e-01 , 7.9552140732217564e+00 , 9.9576536000000004e+00 , 9.1664099999999998e-02 , 6.4482200000000001e-01 , 7.5881600000000005e-01 -1.9277061772055015e-01 , 7.8257672255346105e+00 , 1.0044888800000001e+01 , 2.8176099999999998e-01 , 9.0842900000000004e-01 , 3.0881500000000001e-01 -1.8026835800063856e-01 , 7.8094909684591807e+00 , 1.0282924000000000e+01 , -1.6032800000000000e-01 , -9.5390900000000001e-01 , -2.5367899999999999e-01 --1.3553326793346221e-01 , 8.5087935646371911e+00 , 1.1520357600000001e+01 , 6.0329900000000002e-03 , -3.8379799999999997e-01 , 9.2339700000000002e-01 -1.2936203580225429e+00 , 5.1133166850378498e+00 , 6.9674144000000009e+00 , 6.2605900000000003e-01 , -3.8871800000000001e-01 , -6.7597900000000000e-01 -1.3014706449457627e+00 , 5.0704351199476640e+00 , 7.0513840000000005e+00 , -3.9663700000000002e-01 , 4.7323399999999999e-01 , 7.8659299999999999e-01 -1.3703475442370117e+00 , 4.8875640002066518e+00 , 6.9226008000000006e+00 , -6.9782000000000000e-01 , 2.2709199999999999e-01 , 6.7932099999999995e-01 -1.3926214091124178e+00 , 4.8107205817351550e+00 , 6.9517832000000004e+00 , -6.4704200000000001e-01 , -4.9773800000000001e-01 , 5.7757599999999998e-01 -1.4292564458410681e+00 , 4.7033195702637514e+00 , 6.9271872000000005e+00 , 5.4276199999999997e-01 , 3.7102000000000002e-01 , -7.5349500000000003e-01 -1.5841939117962744e+00 , 4.3355744747035398e+00 , 6.4420064000000004e+00 , -7.8671199999999997e-01 , -4.3961400000000000e-01 , 4.3338700000000002e-01 -1.6334232350451305e+00 , 4.2044947642030284e+00 , 6.3447871999999998e+00 , -3.2460800000000001e-01 , 3.7222699999999997e-01 , 8.6952700000000005e-01 -1.6533728670732457e+00 , 4.1399034176694052e+00 , 6.3604808000000004e+00 , -2.4681500000000001e-01 , 2.7926800000000002e-01 , 9.2795099999999997e-01 -1.6703993895603544e+00 , 4.0801420162544826e+00 , 6.3837039999999998e+00 , -1.9836699999999999e-01 , -5.9846900000000003e-01 , -7.7619899999999997e-01 -1.6802505724426740e+00 , 4.0374432108514808e+00 , 6.4426512000000002e+00 , 2.1589600000000000e-01 , 6.1916199999999999e-01 , 7.5500100000000003e-01 -1.6744069340124945e+00 , 4.0272388513085193e+00 , 6.5752303999999997e+00 , -7.7044999999999997e-01 , -6.2658499999999995e-01 , -1.1746400000000000e-01 -1.5304269101023906e+00 , 4.2992819869791568e+00 , 7.3519232000000008e+00 , -8.7946599999999997e-01 , -2.9979299999999998e-01 , 3.6968200000000001e-01 -1.5530641315040863e+00 , 4.2229048509095390e+00 , 7.3781727999999998e+00 , -8.7946599999999997e-01 , -2.9979299999999998e-01 , 3.6968200000000001e-01 -1.4456664910645447e+00 , 4.4069766137098521e+00 , 8.0475792000000013e+00 , -1.3638600000000001e-02 , 3.0849399999999999e-01 , 9.5112799999999997e-01 -6.9927176463457452e-01 , 5.8270081612162468e+00 , 1.2011466400000000e+01 , -7.7534300000000000e-01 , 5.5014099999999999e-01 , -3.1014300000000000e-01 -1.0591649344006888e+00 , 5.0708625262562341e+00 , 1.0411686400000001e+01 , 3.3747400000000000e-01 , -2.0247200000000001e-01 , -9.1930199999999995e-01 -1.1012367402206085e+00 , 4.9374723817005712e+00 , 1.0433183200000000e+01 , 3.2885999999999999e-01 , -1.1780500000000001e-01 , -9.3700200000000000e-01 -1.6326712034760253e+00 , 3.9068376333465307e+00 , 7.6920864000000000e+00 , -3.6131700000000000e-01 , 5.4475399999999996e-01 , 7.5676500000000002e-01 -1.1919874789210771e+00 , 4.6598069479168451e+00 , 1.0428867200000001e+01 , -3.4556700000000001e-01 , 1.4061799999999999e-01 , 9.2779800000000001e-01 -1.3367699400971369e+00 , 4.3483561013839109e+00 , 9.8204256000000001e+00 , 4.0021099999999998e-01 , 9.1274500000000003e-01 , -8.2024200000000005e-02 -1.6796142643396590e+00 , 3.7123469142235423e+00 , 7.9226128000000005e+00 , -6.7042100000000004e-01 , 7.2164700000000004e-01 , 1.7251500000000000e-01 -1.6703498700648225e+00 , 3.6866036110834868e+00 , 8.1670440000000006e+00 , 7.9007600000000000e-01 , -5.6528599999999996e-01 , -2.3713200000000001e-01 -1.8636748963718479e+00 , 3.3361373732139965e+00 , 7.0590592000000010e+00 , -7.1550199999999997e-01 , -9.3517600000000006e-02 , -6.9232400000000005e-01 -1.9086824901708124e+00 , 3.2322056875895084e+00 , 6.9059191999999996e+00 , -6.4346000000000003e-01 , 1.6431000000000001e-01 , -7.4763700000000000e-01 -1.8947127838266495e+00 , 3.2159078639804415e+00 , 7.1646295999999996e+00 , 3.7092700000000001e-01 , 7.9102600000000001e-01 , -4.8650800000000000e-01 -1.7722865447688028e+00 , 3.3464541594131862e+00 , 8.2765768000000008e+00 , -7.8621399999999997e-01 , -3.7221700000000002e-01 , -4.9327599999999999e-01 -1.8059241804268891e+00 , 3.2513809924049610e+00 , 8.2440560000000005e+00 , 4.2842400000000003e-01 , -9.0255399999999997e-01 , 4.2993499999999997e-02 -7.1703645401829696e-01 , 9.1926371639083158e+00 , -2.2959359999999984e-01 , 8.5692099999999993e-02 , 2.3719599999999999e-01 , 9.6767499999999995e-01 -5.6294238072918557e-01 , 9.7498946461327911e+00 , -3.4254800000000030e-01 , 5.3057300000000002e-02 , 2.6350899999999999e-01 , 9.6319699999999997e-01 -2.7868441474757244e-01 , 1.0801527140728707e+01 , -6.5409040000000029e-01 , -5.7253600000000002e-02 , 2.0490200000000000e-01 , 9.7710699999999995e-01 -6.8209060913528186e-02 , 1.1558715906352694e+01 , -7.9862960000000038e-01 , 5.9759100000000002e-02 , -1.7647099999999999e-01 , -9.8248999999999997e-01 --1.8049097728601637e-01 , 1.2453374850619056e+01 , -9.6976160000000000e-01 , -7.0870699999999995e-02 , 1.8551400000000001e-01 , 9.8008300000000004e-01 --5.0878274791293032e-01 , 1.3638668298930279e+01 , -1.2178848000000002e+00 , -4.0771699999999998e-03 , -9.8088900000000007e-02 , 9.9516899999999997e-01 --7.0741680538509133e-01 , 1.4321578541827387e+01 , -1.2385600000000001e+00 , -5.1686299999999998e-02 , 4.5903699999999999e-02 , 9.9760800000000005e-01 --1.0892049081804727e+00 , 1.5684912873720668e+01 , -1.4675680000000000e+00 , -1.1640399999999999e-01 , 2.3424900000000001e-01 , 9.6518300000000001e-01 --1.1224164875494447e+00 , 1.5734846091380140e+01 , -1.2214936000000001e+00 , -1.1640399999999999e-01 , 2.3424900000000001e-01 , 9.6518300000000001e-01 --7.8619481381665635e-01 , 1.4412785841213543e+01 , -5.6008479999999983e-01 , -1.8170700000000001e-01 , -8.6573000000000000e-01 , 4.6636200000000000e-01 --5.0063744344501302e+00 , 2.9762701937802156e+01 , -4.1584120000000002e+00 , 6.1067000000000003e-02 , 2.5367699999999999e-01 , 9.6535899999999997e-01 --4.1045740343842771e+00 , 2.5837254417203823e+01 , -9.1943600000000014e-01 , 1.9422400000000001e-01 , 6.1241100000000000e-02 , 9.7904400000000003e-01 --4.1624623129855056e+00 , 2.5921023598079525e+01 , -4.9983760000000022e-01 , 1.9422400000000001e-01 , 6.1241100000000000e-02 , 9.7904400000000003e-01 --2.3345875456732692e+00 , 1.8616555202708383e+01 , 3.5626832000000004e+00 , 7.4215100000000001e-01 , 6.2233799999999995e-01 , 2.4881200000000001e-01 --2.3960080566581849e+00 , 1.8749906988332388e+01 , 3.8638775999999999e+00 , -7.6092700000000002e-01 , -6.4706399999999997e-01 , -4.7933099999999999e-02 --1.2918009560961261e+00 , 1.4967996658897002e+01 , 3.9116240000000002e+00 , 2.9370099999999999e-01 , 2.2459599999999999e-01 , 9.2913800000000002e-01 --1.3031654599430627e+00 , 1.4947547253900217e+01 , 4.1396440000000005e+00 , -7.6671999999999996e-01 , 1.3087399999999999e-01 , 6.2850099999999998e-01 --1.4059899649290828e+00 , 1.5230405511362395e+01 , 4.3988952000000001e+00 , -5.8850999999999998e-01 , 6.1593600000000004e-01 , 5.2371599999999996e-01 --1.1799895216741390e+00 , 1.4420292544416833e+01 , 4.5369551999999995e+00 , 6.0212699999999997e-01 , 4.7874499999999998e-01 , 6.3894200000000001e-01 --1.1424021548687557e+00 , 1.4240830712978971e+01 , 4.7347320000000002e+00 , -5.1169699999999996e-01 , -3.5260700000000000e-01 , -7.8347599999999995e-01 --1.0200222968342412e+00 , 1.3784299610278754e+01 , 4.8825680000000000e+00 , 2.6971499999999998e-01 , 6.0835200000000000e-01 , 7.4643300000000001e-01 --9.3811059436829458e-01 , 1.3464094163034495e+01 , 5.0389840000000001e+00 , 3.4593699999999999e-01 , -8.3029200000000003e-01 , 4.3697000000000003e-01 --9.5404959255385346e-01 , 1.3464258855822294e+01 , 5.2476392000000001e+00 , -3.4593699999999999e-01 , 8.3029200000000003e-01 , -4.3697100000000000e-01 --1.0863136849703898e+00 , 1.3839836586553782e+01 , 5.5389119999999998e+00 , 6.1914999999999998e-01 , 6.2092499999999995e-01 , -4.8073399999999999e-01 --2.5459418440318204e-01 , 1.1108167020481932e+01 , 5.1179304000000005e+00 , -1.4787400000000001e-01 , 8.6728300000000003e-01 , -4.7534599999999999e-01 --3.1796259926281856e-01 , 1.1272088373437521e+01 , 5.3277192000000007e+00 , 1.7361799999999999e-01 , -8.3000799999999997e-01 , 5.3004200000000001e-01 --3.5145525949581646e-01 , 1.1335186572073351e+01 , 5.5177999999999994e+00 , 1.5933400000000000e-01 , -7.5260600000000000e-01 , 6.3890300000000000e-01 --4.0209992332527822e-01 , 1.1451876663455268e+01 , 5.7278280000000006e+00 , -2.3288700000000001e-01 , 6.0411800000000004e-01 , -7.6210599999999995e-01 --1.2554425324083067e+00 , 1.4100977299692996e+01 , 6.7359624000000009e+00 , 2.8866999999999998e-01 , 7.9274999999999995e-01 , 5.3685899999999998e-01 --1.1217651464286225e+00 , 1.3626786654187416e+01 , 6.8139623999999994e+00 , -5.0039800000000001e-01 , -5.3180300000000003e-01 , -6.8321799999999999e-01 --8.3265147587408661e-01 , 1.2666156017622910e+01 , 6.7033168000000005e+00 , 3.4151999999999999e-01 , -8.3037499999999997e-01 , 4.4027500000000003e-01 --4.7947237861012093e-01 , 1.1518707700823018e+01 , 6.4857072000000002e+00 , 4.7087800000000002e-01 , -5.0175800000000004e-01 , -7.2561299999999995e-01 --4.5283856842058245e-01 , 1.1390857734722635e+01 , 6.6263152000000005e+00 , 1.1506200000000000e-01 , -5.5155799999999999e-01 , 8.2616199999999995e-01 --5.4551072325335070e-01 , 1.1630579494782587e+01 , 6.9161944000000002e+00 , -3.2359599999999999e-01 , 8.6826499999999995e-01 , -3.7603399999999998e-01 --9.4950996655611908e-01 , 1.2820741231815392e+01 , 7.6354272000000005e+00 , 3.5170099999999999e-01 , 2.8444999999999998e-01 , 8.9184900000000000e-01 --1.4004317592015258e-01 , 1.0303062708547529e+01 , 6.7064576000000002e+00 , 6.6856300000000002e-01 , -4.8006900000000002e-01 , -5.6794199999999995e-01 --6.5985319104175533e-01 , 1.1836790443112424e+01 , 7.6201808000000000e+00 , 1.3626099999999999e-01 , -8.1201599999999996e-01 , 5.6750599999999995e-01 --3.5011946547882644e-02 , 9.9023969529485889e+00 , 6.8588904000000008e+00 , 6.8669999999999998e-01 , -4.3421399999999999e-01 , -5.8301099999999995e-01 -3.3746823243864910e-02 , 9.6587296892967647e+00 , 6.9026848000000003e+00 , -5.6001599999999996e-01 , 6.4688400000000001e-01 , 5.1761299999999999e-01 -5.2390972102707822e-01 , 8.1568328810624990e+00 , 6.2460288000000004e+00 , 7.9265299999999997e-02 , 5.4850299999999996e-01 , 8.3238299999999998e-01 -1.1534004135772347e-01 , 9.3390327043735013e+00 , 7.0619296000000000e+00 , 6.7391299999999998e-01 , 1.1900300000000000e-01 , -7.2916300000000001e-01 -8.4760695814062315e-02 , 9.3877486007872495e+00 , 7.2603511999999997e+00 , 4.1272500000000001e-01 , -9.0191900000000003e-01 , -1.2728300000000001e-01 -5.2703431246392163e-01 , 8.0507567818864327e+00 , 6.6003360000000004e+00 , -7.7742299999999998e-01 , 5.5108400000000002e-01 , 3.0318299999999998e-01 -6.0725342811548155e-01 , 7.7879985899442445e+00 , 6.5728800000000005e+00 , -8.5613700000000004e-01 , 4.6345399999999998e-01 , 2.2856199999999999e-01 -5.2852598178080856e-01 , 7.9831347931833534e+00 , 6.8447464000000000e+00 , 2.7303100000000002e-01 , -9.5094400000000001e-01 , 1.4546300000000001e-01 -5.5429370850929827e-01 , 7.8757486774292973e+00 , 6.9180663999999998e+00 , 2.1310200000000001e-01 , -9.5890900000000001e-01 , 1.8729899999999999e-01 -4.2284430802117079e-01 , 8.2212274879784921e+00 , 7.3187888000000010e+00 , 2.9088900000000001e-01 , 9.4516299999999998e-01 , -1.4849499999999999e-01 --1.8620944288245855e-01 , 9.9195632301849557e+00 , 8.7669680000000003e+00 , 3.7168800000000002e-02 , 5.7851300000000005e-01 , 8.1482600000000005e-01 --1.8431797154659169e-01 , 9.8675893910528387e+00 , 8.9415839999999989e+00 , 2.9369499999999998e-01 , 7.4364100000000000e-01 , 6.0061699999999996e-01 --8.9171741166618901e-01 , 1.1809303831329263e+01 , 1.0744070400000000e+01 , 8.1555000000000000e-01 , 5.7482000000000000e-01 , -6.6791299999999998e-02 --7.0656039698908213e-02 , 9.4531909519615525e+00 , 9.0382312000000002e+00 , 1.1310199999999999e-01 , 3.7070500000000001e-01 , 9.2183800000000005e-01 --1.0197126441789406e-01 , 9.4931305092797942e+00 , 9.2929999999999993e+00 , -8.8153199999999998e-01 , -2.8991800000000001e-01 , 3.7262499999999998e-01 --2.3656469648301925e-02 , 9.2293283778967847e+00 , 9.2810400000000008e+00 , -8.8917199999999996e-01 , 2.3661399999999999e-02 , 4.5696199999999998e-01 -1.1300720906090667e-01 , 8.8067102336078715e+00 , 9.1099183999999997e+00 , 7.6274500000000001e-01 , 2.8000000000000003e-01 , -5.8294100000000004e-01 -1.2709306870571657e-01 , 8.7235910113708215e+00 , 9.2484672000000003e+00 , 7.9979299999999998e-01 , 2.2149500000000000e-01 , -5.5791700000000000e-01 --7.6278661407696902e-01 , 1.1078402665102461e+01 , 1.1855445600000001e+01 , 2.8748299999999999e-01 , -3.9870100000000003e-01 , 8.7085699999999999e-01 --3.4862541677289371e-01 , 9.9052418839003415e+00 , 1.0943303200000001e+01 , 2.5787600000000001e-02 , -3.7256699999999998e-01 , 9.2764700000000000e-01 --6.6944211882623694e-01 , 1.0696824392717263e+01 , 1.2089570400000001e+01 , 9.8191000000000001e-02 , -3.6940899999999999e-01 , 9.2406500000000003e-01 -2.5447192363858973e-01 , 8.1970078793658399e+00 , 9.6028367999999986e+00 , 1.4683299999999999e-01 , 5.6711000000000000e-01 , 8.1044799999999995e-01 -7.6862076708296900e-01 , 6.8047196163077688e+00 , 8.2146343999999996e+00 , 4.9393300000000001e-01 , 8.5312100000000002e-01 , -1.6797400000000001e-01 -2.9944478583201950e-01 , 7.9826774692555587e+00 , 9.8293175999999995e+00 , -1.4199500000000001e-01 , -6.9124200000000002e-01 , -7.0853500000000003e-01 -3.1602284170188910e-01 , 7.8922003009291286e+00 , 9.9634879999999999e+00 , -5.2362699999999998e-02 , 6.7805899999999997e-01 , 7.3314000000000001e-01 -3.7160513915350202e-01 , 7.6996518491934296e+00 , 9.9683343999999998e+00 , -1.3888400000000000e-02 , 6.8450299999999997e-01 , 7.2887800000000003e-01 -1.3143055476116969e+00 , 5.2736901906003526e+00 , 6.9509407999999997e+00 , -5.2280400000000005e-01 , -2.7387099999999998e-01 , 8.0726100000000001e-01 -1.3463906750063275e+00 , 5.1652076939864777e+00 , 6.9463439999999999e+00 , 3.9837400000000001e-01 , -1.5233200000000000e-01 , -9.0448499999999998e-01 -1.3620423660580832e+00 , 5.0993843198693511e+00 , 6.9971687999999999e+00 , 2.1529100000000001e-01 , 8.5348599999999997e-01 , 4.7456500000000001e-01 -1.3728211974495377e+00 , 5.0433014189487047e+00 , 7.0636871999999995e+00 , -9.7621899999999998e-02 , 6.4453300000000002e-01 , 7.5831899999999997e-01 -1.3956581829900858e+00 , 4.9578070318736511e+00 , 7.0869312000000004e+00 , 5.7922300000000004e-01 , -6.5184500000000006e-02 , -8.1255900000000003e-01 -1.4238182883323500e+00 , 4.8628756743311170e+00 , 7.0908207999999995e+00 , -5.8387500000000003e-01 , -3.4239100000000000e-01 , 7.3611099999999996e-01 -1.4967674668659829e+00 , 4.6605302010720573e+00 , 6.9083944000000006e+00 , -7.2091799999999995e-01 , -6.5220299999999998e-01 , 2.3432400000000000e-01 -1.6224365802372331e+00 , 4.3389440879743617e+00 , 6.4985200000000001e+00 , -7.6555300000000004e-01 , -4.9212499999999998e-01 , 4.1441800000000001e-01 -1.6768678135546897e+00 , 4.1884916731728472e+00 , 6.3642247999999997e+00 , 4.0167199999999997e-01 , -2.4346799999999999e-01 , -8.8282700000000003e-01 -1.6947794794440993e+00 , 4.1227974613917002e+00 , 6.3792631999999996e+00 , 3.5869499999999999e-01 , -2.0795800000000000e-01 , -9.0999600000000003e-01 -1.7107909152923473e+00 , 4.0619283121892433e+00 , 6.4020600000000005e+00 , 5.7774899999999997e-02 , 5.6803000000000003e-01 , 8.2097799999999999e-01 -1.7217276415055216e+00 , 4.0140376800798165e+00 , 6.4513040000000004e+00 , 1.9904100000000000e-01 , 6.7202700000000004e-01 , 7.1327600000000002e-01 -1.7264436182718086e+00 , 3.9782565598532296e+00 , 6.5276607999999996e+00 , 6.0843499999999995e-01 , 7.1767000000000003e-01 , 3.3875800000000000e-01 -1.7067936871647369e+00 , 3.9924614737351556e+00 , 6.7257392000000005e+00 , -7.8934300000000002e-01 , -6.0830300000000004e-01 , -8.3099199999999998e-02 -1.5782288479377291e+00 , 4.2322824356382860e+00 , 7.4827968000000000e+00 , 8.3284800000000003e-01 , 5.3593599999999997e-01 , -1.3833300000000001e-01 -1.5045456767764191e+00 , 4.3486743382637041e+00 , 8.0026304000000010e+00 , -9.4138200000000005e-01 , -3.0468400000000001e-01 , 1.4480199999999999e-01 -1.0853091870648908e+00 , 5.1509522497052558e+00 , 1.0398436799999999e+01 , -3.3747400000000000e-01 , 2.0247200000000001e-01 , 9.1930199999999995e-01 -1.6266399842086521e+00 , 4.0259815612636274e+00 , 7.6391816000000006e+00 , 9.8898100000000003e-02 , 3.3700599999999997e-01 , 9.3629399999999996e-01 -1.6455580003728343e+00 , 3.9525327037918734e+00 , 7.6792424000000006e+00 , 2.8736099999999998e-01 , -6.1825799999999997e-01 , -7.3156100000000002e-01 -1.1862261843036803e+00 , 4.7719489288177099e+00 , 1.0536288799999999e+01 , -3.4556700000000001e-01 , 1.4061799999999999e-01 , 9.2779900000000004e-01 -1.3340413942959604e+00 , 4.4362818847745125e+00 , 9.8820143999999992e+00 , 5.3624200000000000e-01 , 8.2368500000000000e-01 , -1.8435399999999999e-01 -1.6816856524351929e+00 , 3.7637764011853161e+00 , 7.9306312000000005e+00 , 5.5386700000000000e-01 , 4.2149700000000001e-01 , -7.1803300000000003e-01 -1.8641233355843887e+00 , 3.4082911357410488e+00 , 6.9113375999999995e+00 , 2.2339600000000001e-01 , 7.3885699999999999e-01 , 6.3575499999999996e-01 -1.8712457049294662e+00 , 3.3601154253188676e+00 , 7.0004863999999998e+00 , -9.3688600000000000e-01 , 8.4099800000000002e-02 , -3.3936899999999998e-01 -1.8945410626459627e+00 , 3.2845826721921472e+00 , 6.9784176000000002e+00 , -8.5564700000000005e-01 , 4.5480999999999999e-01 , 2.4701300000000001e-01 -1.9168738158289971e+00 , 3.2129296146774253e+00 , 6.9648560000000002e+00 , 7.6250899999999999e-01 , -6.0718499999999997e-01 , 2.2339800000000001e-01 -1.7708362483729458e+00 , 3.3821756821924804e+00 , 8.2164336000000002e+00 , -2.7066400000000002e-01 , 4.2697600000000002e-01 , 8.6280500000000004e-01 -1.7773041359358628e+00 , 3.3198919246536063e+00 , 8.3776960000000003e+00 , -2.0459400000000000e-01 , 9.7702199999999995e-01 , 5.9745600000000003e-02 -1.6131913269476197e+00 , 6.1951478325434470e+00 , 1.2163059199999999e+00 , 7.6642999999999994e-01 , 2.9878900000000003e-01 , 5.6860400000000000e-01 -1.5335340822756902e+00 , 6.5197896025024553e+00 , 1.1452084000000000e+00 , -7.2809500000000005e-01 , -9.8680199999999996e-02 , -6.7833699999999997e-01 -1.4969644713808865e+00 , 6.6522682961051736e+00 , 1.1730772800000000e+00 , -7.2444500000000001e-01 , -8.5586499999999996e-02 , -6.8399900000000002e-01 -1.4534921313919857e+00 , 6.8131979542246421e+00 , 1.1930816800000001e+00 , 7.4897700000000000e-01 , 6.7118999999999998e-02 , 6.5918800000000000e-01 -1.4069450427240664e+00 , 6.9851027256484235e+00 , 1.2141988800000001e+00 , 7.4897700000000000e-01 , 6.7118999999999998e-02 , 6.5918800000000000e-01 -1.3727070448963632e+00 , 7.0994414475448862e+00 , 1.2631943200000000e+00 , -7.8481000000000001e-01 , -6.5953999999999999e-02 , -6.1621800000000004e-01 --2.3860686769372785e-01 , 1.4025788592488105e+01 , -1.1835648000000001e+00 , 9.3617900000000004e-02 , -1.8319400000000000e-03 , 9.9560700000000002e-01 --5.4836047202309324e-01 , 1.5272672718879036e+01 , -1.3850544000000000e+00 , 1.6521700000000000e-01 , 2.4542500000000000e-01 , 9.5523300000000000e-01 --9.8331233119806827e-01 , 1.7039504120296481e+01 , -1.7102727999999998e+00 , -5.7771000000000003e-02 , 3.2135100000000000e-01 , 9.4519600000000004e-01 --6.5064637396056391e-01 , 1.5532294803812059e+01 , -9.6145199999999997e-01 , -5.7205399999999995e-01 , 4.3226100000000001e-01 , 6.9706800000000002e-01 --2.6355195003080114e+00 , 2.3786397909841916e+01 , -3.0904255999999997e+00 , 4.9690699999999997e-02 , -3.1938299999999997e-01 , 9.4632200000000000e-01 --5.3326963013873563e-01 , 1.4792482981587602e+01 , -2.3517599999999916e-02 , -9.4346099999999999e-01 , 3.1672899999999998e-01 , -9.7796599999999997e-02 --5.6628315449576672e-01 , 1.4848717146138135e+01 , 1.9615120000000008e-01 , -9.7341299999999997e-01 , 2.2824100000000000e-01 , -1.9294800000000001e-02 --5.9313116624042816e-01 , 1.4880415118679897e+01 , 4.2161280000000012e-01 , 4.6823199999999998e-01 , -8.5328499999999996e-01 , 2.2948499999999999e-01 --6.1900915873858375e-01 , 1.4910081303820210e+01 , 6.4720960000000005e-01 , 4.6823199999999998e-01 , -8.5328499999999996e-01 , 2.2948499999999999e-01 --6.4947947340011547e-01 , 1.4954097173713558e+01 , 8.6991520000000011e-01 , 4.6823100000000001e-01 , -8.5328599999999999e-01 , 2.2948499999999999e-01 --6.7804195851284277e-01 , 1.4995104092126525e+01 , 1.0935807199999998e+00 , 4.6822999999999998e-01 , -8.5328599999999999e-01 , 2.2948499999999999e-01 --7.1409620701549326e-01 , 1.5062288432523781e+01 , 1.3139484000000001e+00 , 4.6823100000000001e-01 , -8.5328599999999999e-01 , 2.2948499999999999e-01 --7.4378702734189694e-01 , 1.5105613391822491e+01 , 1.5388026400000001e+00 , -7.9746799999999995e-01 , -6.0055999999999998e-01 , 5.8078499999999998e-02 --7.7263403634879424e-01 , 1.5146032058187398e+01 , 1.7647020800000000e+00 , -7.9746799999999995e-01 , -6.0055999999999998e-01 , 5.8078499999999998e-02 --1.7066877447485136e+00 , 1.8375616911287352e+01 , 2.8697447199999999e+00 , -7.8651000000000004e-01 , -5.4712499999999997e-01 , -2.8645300000000001e-01 --1.7320674605446538e+00 , 1.8381402057904129e+01 , 3.1567504000000000e+00 , -7.8651000000000004e-01 , -5.4712499999999997e-01 , -2.8645300000000001e-01 --1.6022967780063766e+00 , 1.7798288054973732e+01 , 3.4311440000000002e+00 , 7.5870300000000002e-01 , 6.1680800000000002e-01 , 2.0956600000000000e-01 --1.6634167538345506e+00 , 1.7945071282314139e+01 , 3.7146271999999998e+00 , 7.5870300000000002e-01 , 6.1680800000000002e-01 , 2.0956600000000000e-01 --1.6418060098730036e+00 , 1.7776696386475269e+01 , 3.9851000000000001e+00 , 6.3770199999999999e-01 , -7.6973899999999995e-01 , -2.8935499999999999e-02 --9.2844818318538991e-01 , 1.5028493622651549e+01 , 4.0518680000000007e+00 , 6.6444999999999999e-01 , 2.5897399999999998e-01 , -7.0102699999999996e-01 --7.4465737850753699e-01 , 1.4275085210893657e+01 , 4.2096776000000009e+00 , -5.3185800000000005e-01 , -4.2834000000000000e-01 , -7.3051500000000003e-01 --7.6052862977723956e-01 , 1.4270382335626973e+01 , 4.4255712000000003e+00 , -5.3185800000000005e-01 , -4.2834000000000000e-01 , -7.3051500000000003e-01 --7.2152848651030954e-01 , 1.4061812966710731e+01 , 4.6157560000000002e+00 , 5.4758799999999996e-01 , 5.1580199999999998e-01 , 6.5885899999999997e-01 --6.1047333117130576e-01 , 1.3593435861536335e+01 , 4.7600143999999993e+00 , 6.6435300000000003e-02 , 7.3324400000000001e-01 , 6.7671199999999998e-01 --6.1043177540236204e-01 , 1.3528926219464411e+01 , 4.9566680000000005e+00 , -4.9587700000000001e-01 , -5.1054999999999995e-01 , -7.0245700000000000e-01 --6.3363860542661232e-01 , 1.3551281348293992e+01 , 5.1679232000000006e+00 , -5.6825800000000004e-01 , -8.0430100000000004e-01 , -1.7373200000000000e-01 --6.6042039952120746e-01 , 1.3588722966771142e+01 , 5.3851583999999999e+00 , -5.6825800000000004e-01 , -8.0430100000000004e-01 , -1.7373200000000000e-01 --9.8302471993044049e-01 , 1.4679028910992205e+01 , 5.8423320000000007e+00 , -9.1502499999999998e-01 , 4.0258200000000000e-01 , -2.5618800000000001e-02 --9.0724898106691043e-02 , 1.1439621850991422e+01 , 5.2854744000000000e+00 , 1.7361799999999999e-01 , -8.3000700000000005e-01 , 5.3004200000000001e-01 --8.3102774107467070e-01 , 1.4006402298849292e+01 , 6.1357992000000001e+00 , -9.7517399999999999e-01 , -1.8679799999999999e-01 , -1.1891800000000000e-01 --2.7843687695373998e-01 , 1.1999211780063648e+01 , 5.7935560000000006e+00 , 6.7509500000000000e-01 , -7.3396799999999995e-01 , 7.4419500000000000e-02 --2.9626917194993707e-01 , 1.2005455100696052e+01 , 5.9840840000000002e+00 , 7.4259699999999995e-01 , -6.4854899999999993e-02 , 6.6659100000000004e-01 --4.2739163885453513e-01 , 1.2410223099337188e+01 , 6.3050280000000001e+00 , 2.4703600000000001e-01 , 7.4810600000000005e-01 , 6.1588200000000004e-01 --3.5567590771282642e-01 , 1.2103698327981030e+01 , 6.4010616000000002e+00 , -1.3800299999999999e-01 , 7.5405599999999995e-01 , 6.4214800000000005e-01 --3.8394416101645490e-01 , 1.2145677481197383e+01 , 6.6138767999999999e+00 , -2.0551800000000001e-01 , 6.4835399999999999e-01 , 7.3307500000000003e-01 --2.6314927761842410e-01 , 1.1678648636728420e+01 , 6.6353111999999994e+00 , 5.9189700000000001e-01 , -4.2885699999999999e-01 , -6.8245100000000003e-01 --3.2276479272064496e-01 , 1.1826904100994621e+01 , 6.8893936000000000e+00 , -6.6165900000000000e-01 , 5.6166499999999997e-01 , 4.9672899999999998e-01 --5.9828289142994917e-01 , 1.2699233209074853e+01 , 7.4603328000000007e+00 , 5.1228799999999997e-01 , 2.0364399999999999e-01 , 8.3431999999999995e-01 -1.7775920298299952e-01 , 1.0036871798708653e+01 , 6.4913439999999998e+00 , -6.9911999999999996e-01 , 3.8725599999999999e-01 , 6.0105200000000003e-01 --4.3882859919852191e-01 , 1.2046391313497402e+01 , 7.6009200000000003e+00 , -8.4947300000000003e-02 , -2.8744499999999999e-02 , -9.9597100000000005e-01 --4.6636998918439909e-01 , 1.2082596578817741e+01 , 7.8327464000000004e+00 , 8.3565899999999999e-02 , 4.0901100000000001e-01 , 9.0869500000000003e-01 --1.3365585705770320e+00 , 1.4890585626797515e+01 , 9.4943024000000005e+00 , -7.4045899999999998e-01 , 6.7199600000000004e-01 , -1.1876400000000000e-02 -6.5007669638000953e-01 , 8.3068495349164166e+00 , 6.2480880000000001e+00 , 2.6770499999999999e-02 , 9.8117699999999997e-01 , -1.9124700000000000e-01 -6.5341406684360237e-01 , 8.2591375040191046e+00 , 6.3597840000000003e+00 , -2.2570200000000001e-01 , 9.6775100000000003e-01 , 1.1188200000000000e-01 --9.3314914161483387e-01 , 1.3354421704109864e+01 , 9.4764352000000009e+00 , -9.8067800000000005e-01 , 1.6624800000000000e-03 , -1.9562299999999999e-01 -4.9291395996262488e-01 , 8.6986561662330910e+00 , 6.9101935999999995e+00 , -1.3164100000000001e-01 , -9.8719100000000004e-01 , 9.0133900000000003e-02 -7.4676004703612664e-01 , 7.8486006836849276e+00 , 6.5292415999999998e+00 , 2.4218999999999999e-01 , -9.0285099999999996e-01 , 3.5525099999999998e-01 -6.6202930730998633e-01 , 8.0810504027056922e+00 , 6.8216584000000005e+00 , -5.0278599999999996e-01 , 7.8564800000000001e-01 , 3.6050500000000002e-01 -6.8977826072608872e-01 , 7.9566523906205271e+00 , 6.8847240000000003e+00 , 2.0569499999999999e-01 , -9.5198400000000005e-01 , -2.2675100000000001e-01 -6.8505652157998798e-01 , 7.9309385612479817e+00 , 7.0143392000000002e+00 , -2.8073700000000001e-01 , -9.1188000000000002e-01 , 2.9943399999999998e-01 -6.2554675911038227e-01 , 8.0797035927375127e+00 , 7.2762424000000001e+00 , -3.0320799999999998e-01 , -9.4475799999999999e-01 , 1.2449300000000001e-01 -6.0283515576119484e-01 , 8.1100434713066107e+00 , 7.4588559999999999e+00 , 2.9492099999999999e-01 , 8.9175800000000005e-01 , 3.4320299999999998e-01 -6.1940714023068688e-01 , 8.0171987023972058e+00 , 7.5496896000000007e+00 , 6.9766699999999999e-03 , 8.4697699999999998e-01 , 5.3158399999999995e-01 -1.1792598137052290e-01 , 9.5000774237225443e+00 , 8.9422704000000000e+00 , 1.1310400000000000e-01 , 3.7070500000000001e-01 , 9.2183800000000005e-01 -1.2392952474948160e-01 , 9.4280536636531167e+00 , 9.0972512000000005e+00 , -8.8917199999999996e-01 , 2.3661499999999999e-02 , 4.5696199999999998e-01 -1.4379414680287250e-01 , 9.3145790167825737e+00 , 9.2181719999999991e+00 , 9.4002500000000000e-01 , 1.0018299999999999e-01 , -3.2606299999999999e-01 -2.4934918361722747e-01 , 8.9473396275292174e+00 , 9.1044271999999999e+00 , -6.7320000000000002e-01 , 1.6368099999999999e-01 , 7.2111800000000004e-01 -1.9546510267244410e-01 , 9.0536529005802180e+00 , 9.4255688000000006e+00 , 7.1815799999999996e-01 , 3.9235899999999997e-02 , -6.9477299999999997e-01 -2.3098914520156555e-01 , 8.8923005334870275e+00 , 9.4966527999999997e+00 , -6.9255400000000000e-01 , -9.9915199999999996e-02 , 7.1441299999999996e-01 --3.3145613201408830e-01 , 1.0468384656842309e+01 , 1.1344056800000001e+01 , 3.9659800000000001e-01 , 8.3387100000000003e-01 , -3.8388800000000001e-01 --3.0589028935126716e-01 , 1.0323785448634311e+01 , 1.1490894400000000e+01 , -5.1274600000000004e-01 , 5.1237999999999995e-01 , -6.8888199999999999e-01 --1.4301299087473707e-01 , 9.7893829009384135e+00 , 1.1207941600000000e+01 , -3.0586000000000002e-01 , 8.5954600000000003e-01 , -4.0942600000000001e-01 -3.9688515584232897e-01 , 8.1988913652228348e+00 , 9.6899992000000008e+00 , 1.5870600000000001e-01 , 5.7180799999999998e-01 , 8.0488999999999999e-01 -9.0097346161910252e-01 , 6.7369577108932752e+00 , 8.2016759999999991e+00 , -4.9664100000000000e-01 , -8.2376099999999997e-01 , 2.7343299999999998e-01 -4.4914185725770572e-01 , 7.9425196025475948e+00 , 9.8674543999999997e+00 , 1.5064900000000001e-01 , 6.9201199999999996e-01 , 7.0599100000000004e-01 -4.7722475896052896e-01 , 7.8119497090269068e+00 , 9.9526719999999997e+00 , 1.5340799999999999e-01 , 7.7871599999999996e-01 , 6.0833099999999996e-01 -4.6181390810363432e-01 , 7.7964951840291405e+00 , 1.0188908000000000e+01 , -1.6325700000000001e-01 , -9.7004699999999999e-01 , -1.7987700000000001e-01 -1.3778352522903052e+00 , 5.2818780056891832e+00 , 7.0156495999999997e+00 , -1.5654100000000001e-01 , 3.3320300000000003e-01 , 9.2976899999999996e-01 -1.4265575219324467e+00 , 5.1202192134422715e+00 , 6.9351535999999996e+00 , -4.0323300000000001e-01 , -9.1508599999999996e-01 , -4.5311199999999996e-03 -1.4471722634842770e+00 , 5.0361313719071479e+00 , 6.9596560000000007e+00 , -5.9641900000000003e-01 , -7.0025599999999999e-01 , -3.9233400000000002e-01 -1.4431120137501003e+00 , 5.0140428244686328e+00 , 7.0757720000000006e+00 , -3.6089800000000000e-01 , 4.9485699999999999e-01 , 7.9048700000000005e-01 -1.3658756609226741e+00 , 5.1781348454667970e+00 , 7.4942679999999999e+00 , -1.6295200000000001e-01 , -4.8646299999999998e-01 , 8.5837100000000000e-01 -1.5405146673373302e+00 , 4.7011691004512501e+00 , 6.8822799999999997e+00 , -4.0801300000000001e-01 , -5.8252099999999996e-01 , 7.0299000000000000e-01 -1.5378651636010985e+00 , 4.6762042912358295e+00 , 6.9949848000000010e+00 , -7.2091799999999995e-01 , -6.5220299999999998e-01 , 2.3432400000000000e-01 -1.6433070186463972e+00 , 4.3858224501906786e+00 , 6.6355088000000002e+00 , -7.9012899999999997e-01 , 6.1106499999999997e-01 , 4.7902500000000001e-02 -1.7182007918381745e+00 , 4.1754986733577706e+00 , 6.3928456000000002e+00 , -4.7750700000000001e-01 , 1.5325100000000000e-01 , 8.6516000000000004e-01 -1.7361800416735091e+00 , 4.1046079032428953e+00 , 6.3979520000000001e+00 , 4.4845900000000000e-01 , -1.2600300000000000e-01 , -8.8487700000000002e-01 -1.7511868426742709e+00 , 4.0426119018879270e+00 , 6.4202184000000004e+00 , -4.5883199999999999e-02 , 5.1222299999999998e-01 , 8.5762600000000000e-01 -1.7590414119584494e+00 , 3.9936614131544976e+00 , 6.4687760000000001e+00 , 3.3767599999999998e-01 , 7.4364399999999997e-01 , 5.7703400000000005e-01 -1.7627414866704827e+00 , 3.9567723798474921e+00 , 6.5447167999999998e+00 , -3.7952799999999998e-01 , -7.2479000000000005e-01 , -5.7501199999999997e-01 -1.7600161791249671e+00 , 3.9330337527457253e+00 , 6.6582328000000004e+00 , -7.6287000000000005e-01 , -6.3706900000000000e-01 , -1.1032900000000000e-01 -1.5145076436270366e+00 , 4.4314474264617552e+00 , 8.0625032000000001e+00 , -8.1632800000000005e-02 , -5.2196900000000002e-01 , -8.4904900000000005e-01 -6.4594155335492798e-01 , 6.2238180631216160e+00 , 1.2957647999999999e+01 , 9.2051899999999998e-01 , -6.3432299999999997e-02 , 3.8551500000000000e-01 -1.6427371220222158e+00 , 4.0764977289572437e+00 , 7.6351360000000001e+00 , 2.4403400000000000e-01 , 1.0901900000000000e-01 , 9.6361900000000000e-01 -1.6594176894614554e+00 , 4.0012052085326593e+00 , 7.6760704000000004e+00 , -6.2991599999999995e-02 , 3.8723099999999999e-01 , 9.1982799999999998e-01 -1.6675148529174315e+00 , 3.9421592791404656e+00 , 7.7641584000000003e+00 , 2.0561800000000000e-01 , -8.6073500000000003e-01 , -4.6567900000000001e-01 -1.6400121732923632e+00 , 3.9501881837289163e+00 , 8.0774895999999998e+00 , -9.9655199999999999e-01 , -1.2430099999999999e-02 , 8.2040900000000000e-02 -1.6814005485270331e+00 , 3.8244165249698305e+00 , 7.9679880000000001e+00 , 5.6125400000000003e-01 , -2.6526200000000000e-01 , 7.8398400000000001e-01 -1.6916980455753639e+00 , 3.7574229098042498e+00 , 8.0540272000000002e+00 , -6.8057100000000004e-01 , 7.0188600000000001e-01 , 2.1018800000000001e-01 -1.8775437389599758e+00 , 3.3892049043917716e+00 , 6.9617568000000007e+00 , 5.3016200000000002e-01 , 5.0997199999999998e-01 , 6.7739000000000005e-01 -1.8951369757740386e+00 , 3.3200822907374521e+00 , 6.9703056000000005e+00 , 9.1185400000000005e-01 , 2.7011900000000000e-01 , 3.0912400000000001e-01 -1.9152885231694066e+00 , 3.2475838430085400e+00 , 6.9572951999999999e+00 , 8.0583000000000005e-01 , -3.9589600000000003e-01 , 4.4034499999999999e-01 -1.7689058421467914e+00 , 3.4230207516928215e+00 , 8.1868248000000001e+00 , 9.9840899999999999e-01 , 5.5611200000000000e-02 , 9.3176700000000001e-03 -1.7948920517582840e+00 , 3.3284233649205905e+00 , 8.1655879999999996e+00 , 4.3251600000000001e-01 , -8.2615300000000003e-01 , 3.6110999999999999e-01 -1.8067953531466601e+00 , 3.2534358276036879e+00 , 8.2544247999999989e+00 , 4.2842400000000003e-01 , -9.0255399999999997e-01 , 4.2993299999999998e-02 -1.2481672955060281e+00 , 8.8077794412953985e+00 , -9.7544800000000098e-02 , 6.4514600000000005e-02 , 2.0300900000000000e-01 , 9.7704899999999995e-01 -1.1489785860207469e+00 , 9.2663799645926446e+00 , -1.7722959999999999e-01 , 4.7867399999999997e-02 , 2.1037500000000001e-01 , 9.7644799999999998e-01 -9.2989412548737915e-01 , 1.0344848979592005e+01 , -5.2084560000000035e-01 , -1.6997000000000002e-02 , 2.3383599999999999e-01 , 9.7212699999999996e-01 -7.8007945436644377e-01 , 1.1041783284860976e+01 , -6.5636800000000006e-01 , -6.8519800000000006e-02 , 1.8518499999999999e-01 , 9.8031199999999996e-01 -6.0985378325955897e-01 , 1.1839570493929246e+01 , -8.0689760000000010e-01 , -6.2947400000000001e-02 , 1.7378500000000000e-01 , 9.8277000000000003e-01 -3.9266721915135738e-01 , 1.2853418035633602e+01 , -1.0122976000000001e+00 , -7.1386099999999994e-02 , 1.8529200000000001e-01 , 9.8008700000000004e-01 -1.4834869015574381e-01 , 1.3992170674053229e+01 , -1.2255183999999999e+00 , -2.9110199999999999e-02 , 1.4065600000000000e-01 , 9.8963100000000004e-01 --1.8088337318585168e-02 , 1.4725327056872509e+01 , -1.2534215999999998e+00 , 2.5337900000000002e-01 , 6.6570900000000002e-02 , 9.6507399999999999e-01 --3.6609208361259826e-01 , 1.6343501132457089e+01 , -1.5492392000000001e+00 , -8.3879700000000001e-02 , -2.4146599999999999e-01 , -9.6677700000000000e-01 --1.0820643742747609e+00 , 1.9738052420466886e+01 , -2.3403256000000008e+00 , 7.0214399999999996e-02 , -1.6615199999999999e-01 , -9.8359700000000005e-01 --1.5744571961885940e+00 , 2.1995907853570476e+01 , -2.6699432000000005e+00 , 6.5731700000000004e-02 , -1.6372800000000001e-01 , -9.8431299999999999e-01 --1.0364070552588251e+00 , 1.7524723918067338e+01 , 3.0535095999999999e+00 , -9.0610299999999999e-01 , 2.1627399999999999e-01 , 3.6359700000000000e-01 --1.1831253897525071e+00 , 1.8054422183887464e+01 , 3.3319800000000002e+00 , 7.5870300000000002e-01 , 6.1680800000000002e-01 , 2.0956600000000000e-01 --1.1297674391379489e+00 , 1.7621039981839132e+01 , 3.8695976000000001e+00 , -8.6043700000000001e-01 , -5.0955600000000001e-01 , -9.9227600000000005e-05 --1.1937398703607536e+00 , 1.7792606530175068e+01 , 4.1545679999999994e+00 , 7.8835299999999997e-01 , 5.8656399999999997e-01 , -1.8558700000000000e-01 --4.1133312720235127e-01 , 1.4410248789511295e+01 , 4.1344855999999996e+00 , 6.1670799999999998e-02 , -3.2296500000000000e-01 , -9.4439899999999999e-01 --1.3120715146675037e+00 , 1.8087920275136362e+01 , 4.7412320000000001e+00 , 7.5053700000000001e-01 , 6.2635399999999997e-01 , -2.1065700000000001e-01 --6.6143235041112458e-01 , 1.5291985779865772e+01 , 4.6789775999999996e+00 , 6.7426299999999995e-01 , -3.6533300000000002e-01 , -6.4179600000000003e-01 --6.3993787021937454e-01 , 1.5117857093240808e+01 , 4.8892552000000000e+00 , 6.3774699999999995e-01 , -1.2034599999999999e-01 , -7.6078599999999996e-01 --6.5572010921824608e-01 , 1.5101287354788832e+01 , 5.1196983999999999e+00 , 6.9553200000000004e-01 , -6.5916100000000000e-01 , -2.8590599999999999e-01 --1.5326626168066593e-01 , 1.2980874438625763e+01 , 4.9742128000000001e+00 , -8.3831000000000000e-01 , -5.1897700000000002e-01 , 1.6702700000000001e-01 --1.5158395413350023e-01 , 1.2903645218900577e+01 , 5.1554016000000003e+00 , -8.9949500000000004e-01 , -1.1343900000000001e-02 , -4.3678499999999998e-01 --1.4547606368180510e-01 , 1.2813836473779133e+01 , 5.3325760000000004e+00 , 9.7623099999999996e-01 , 1.9009300000000001e-01 , 1.0410100000000000e-01 --2.3300546522055354e-01 , 1.3094489440210522e+01 , 5.5951344000000001e+00 , -9.5372199999999996e-01 , -2.7505800000000002e-01 , -1.2147600000000000e-01 --8.8366199555691249e-02 , 1.2448491884331997e+01 , 5.6345399999999994e+00 , 5.0001399999999996e-01 , 6.2715500000000002e-01 , 5.9721299999999999e-01 --1.3904635665717135e-01 , 1.2585294230351574e+01 , 5.8650143999999997e+00 , -6.0793699999999995e-01 , -7.2847499999999998e-01 , -3.1581100000000001e-01 --1.5236984425222344e-01 , 1.2571769671240945e+01 , 6.0585480000000000e+00 , -2.9784100000000002e-01 , -9.5415799999999995e-01 , -2.9548399999999999e-02 --7.8544807752603862e-02 , 1.2216923136050726e+01 , 6.1471663999999997e+00 , 3.1872899999999998e-01 , -6.0308799999999996e-01 , 7.3123000000000005e-01 --1.9220511523783923e-01 , 1.2590860163452666e+01 , 6.4662800000000002e+00 , -5.9843199999999996e-01 , 5.8675200000000005e-01 , -5.4552900000000004e-01 --3.2296858027610398e-01 , 1.3024044315945188e+01 , 6.8230936000000009e+00 , 2.0789500000000000e-01 , -9.4749300000000003e-01 , 2.4297700000000000e-01 --3.3846279439423022e-01 , 1.3011034765942853e+01 , 7.0345464000000000e+00 , -2.4572500000000000e-01 , 9.6360699999999999e-01 , 1.0526400000000000e-01 --3.5304894041412194e-01 , 1.2994919718020865e+01 , 7.2467376000000003e+00 , 8.2993300000000006e-02 , 9.4872599999999996e-01 , 3.0501099999999998e-01 --3.2739441284133397e-01 , 1.2825666693863440e+01 , 7.3977143999999999e+00 , 5.1494700000000004e-01 , 3.8465100000000002e-01 , 7.6607700000000001e-01 --1.8355566829320846e-01 , 1.2218345042114755e+01 , 7.3548560000000007e+00 , 3.3456500000000000e-01 , 3.0541900000000000e-01 , -8.9150799999999997e-01 --1.0115718148590735e-01 , 1.1847302955802151e+01 , 7.3963104000000008e+00 , -1.2113000000000000e-01 , -9.0611699999999995e-01 , 4.0531400000000001e-01 --1.7180328533687916e-01 , 1.2042485599664980e+01 , 7.6964855999999999e+00 , -9.3267400000000000e-02 , 3.5464299999999999e-01 , -9.3033900000000003e-01 --5.7136513468265981e-01 , 1.3430305718758529e+01 , 8.6073799999999991e+00 , -6.1037599999999997e-02 , 9.6270699999999998e-01 , -2.6357100000000000e-01 -8.0900874391181099e-01 , 8.3557691946712040e+00 , 6.1980328000000000e+00 , -1.6298199999999999e-01 , -9.7840000000000005e-01 , 1.2716700000000000e-01 -8.2435055527102574e-01 , 8.2549286448161396e+00 , 6.2805359999999997e+00 , 3.5608800000000002e-01 , 9.2975200000000002e-01 , -9.3609899999999996e-02 -3.7612217698597594e-01 , 9.8125685057787724e+00 , 7.3071200000000003e+00 , -6.1441000000000001e-01 , 2.2058800000000001e-01 , 7.5752299999999995e-01 -7.8426121106490854e-01 , 8.3121372856189488e+00 , 6.5928168000000005e+00 , -4.0507399999999999e-02 , 9.6827900000000000e-01 , 2.4656800000000001e-01 -7.8492433308563792e-01 , 8.2666209309135716e+00 , 6.7096192000000006e+00 , -2.2636500000000001e-01 , 8.9510000000000001e-01 , 3.8412800000000002e-01 -8.1995453916503291e-01 , 8.0989819397314768e+00 , 6.7493471999999999e+00 , -1.4231600000000000e-01 , 7.9085499999999997e-01 , 5.9522699999999995e-01 -7.9521297676141267e-01 , 8.1428432562240118e+00 , 6.9248680000000000e+00 , 5.0362200000000001e-01 , -8.1963799999999998e-01 , -2.7305200000000002e-01 -7.8916614561831167e-01 , 8.1165636947340545e+00 , 7.0566879999999994e+00 , 4.9384000000000000e-01 , -8.6936899999999995e-01 , -1.7907200000000002e-02 -7.7011187459124120e-01 , 8.1353143603946894e+00 , 7.2247104000000002e+00 , -1.4486299999999999e-01 , 9.8450400000000005e-01 , -9.8825600000000000e-02 -7.8359902915253010e-01 , 8.0457917524283644e+00 , 7.3155543999999999e+00 , -2.1453600000000000e-01 , -9.6426199999999995e-01 , -1.5547500000000000e-01 -7.6362484592854529e-01 , 8.0672422771794672e+00 , 7.4915744000000002e+00 , 6.9766699999999999e-03 , 8.4697699999999998e-01 , 5.3158399999999995e-01 -7.7995363979051469e-01 , 7.9653708618000483e+00 , 7.5744000000000007e+00 , -7.7854800000000002e-02 , 7.8664599999999996e-01 , 6.1247600000000002e-01 -7.9378227105980725e-01 , 7.8697734022006305e+00 , 7.6615207999999999e+00 , -7.7854800000000002e-02 , 7.8664599999999996e-01 , 6.1247600000000002e-01 --1.0940425866428720e+00 , 1.3991288036519451e+01 , 1.3151296000000000e+01 , -6.6171599999999997e-01 , -6.9433999999999996e-01 , -2.8288500000000000e-01 -2.2930856059083160e-01 , 9.6041416830104964e+00 , 9.5668632000000002e+00 , 8.7115900000000002e-01 , -4.1980000000000001e-01 , -2.5465700000000002e-01 -2.9961624435418477e-01 , 9.3123786273343896e+00 , 9.5303280000000008e+00 , 3.5770200000000002e-01 , -6.7903599999999995e-02 , -9.3136399999999997e-01 --1.4321144048762813e-01 , 1.0656930262895225e+01 , 1.1065721600000002e+01 , -1.6629099999999999e-01 , 9.7444699999999995e-01 , 1.5100000000000000e-01 -2.3805445325988916e-01 , 9.3774166172035613e+00 , 1.0071928800000000e+01 , 9.7862499999999997e-01 , -1.1533800000000000e-02 , -2.0533000000000001e-01 -4.8092554283193722e-01 , 8.5504767118040554e+00 , 9.4660872000000005e+00 , 2.5003399999999999e-02 , 3.7655800000000000e-01 , 9.2605599999999999e-01 -1.1723056537090537e-01 , 9.6132038629619530e+00 , 1.0842277600000001e+01 , -7.1050599999999997e-01 , 4.2402000000000001e-01 , -5.6159400000000004e-01 -6.2312627434986356e-01 , 7.9925698428287344e+00 , 9.3150064000000015e+00 , -6.3730900000000001e-01 , -7.8993099999999997e-02 , -7.6654900000000004e-01 -5.7765521711578072e-01 , 8.0688812865405470e+00 , 9.6313744000000003e+00 , 4.8665399999999998e-01 , 7.9014300000000004e-01 , 3.7261600000000000e-01 -1.0185550806912822e+00 , 6.6907247921818387e+00 , 8.2186799999999991e+00 , -4.9664100000000000e-01 , -8.2376099999999997e-01 , 2.7343299999999998e-01 -5.5331151853833971e-01 , 8.0163645009780531e+00 , 1.0055933599999999e+01 , 8.0704100000000001e-02 , 7.5312699999999999e-01 , 6.5290700000000002e-01 -6.0026614388945299e-01 , 7.8140660444380128e+00 , 1.0052688800000000e+01 , 1.0887900000000000e-01 , 7.8876999999999997e-01 , 6.0496799999999995e-01 -1.4990877400769838e+00 , 5.1556991805051089e+00 , 6.7578544000000003e+00 , -5.3522999999999998e-01 , -6.6793800000000003e-01 , -5.1709600000000000e-01 -1.5135179303657516e+00 , 5.0789848373655921e+00 , 6.7912280000000003e+00 , 6.1128099999999996e-01 , 6.1239699999999997e-01 , 5.0130399999999997e-01 -1.5242743040603113e+00 , 5.0149811871498198e+00 , 6.8394944000000004e+00 , -6.0964700000000005e-01 , -6.0861600000000005e-01 , -5.0785599999999997e-01 -1.4945434987928483e+00 , 5.0621075782111795e+00 , 7.0565216000000008e+00 , -1.3313400000000000e-01 , 7.3847099999999999e-01 , 6.6101100000000002e-01 -1.4136890486658134e+00 , 5.2471773526554628e+00 , 7.4993224000000005e+00 , -1.1388700000000000e-01 , 5.3829000000000005e-01 , 8.3502900000000002e-01 -1.4309700428526342e+00 , 5.1598775728406157e+00 , 7.5335072000000007e+00 , -1.1187400000000000e-01 , -6.0441800000000001e-01 , 7.8877299999999995e-01 -1.5725421299480027e+00 , 4.7431038786521889e+00 , 7.0129352000000003e+00 , 7.2912999999999994e-01 , 5.9298600000000001e-01 , -3.4166800000000003e-01 -1.6073050184079021e+00 , 4.6140048122480852e+00 , 6.9487776000000006e+00 , -8.2967599999999997e-01 , -5.3920500000000005e-01 , 1.4455299999999999e-01 -1.5944310512600310e+00 , 4.6100580778879916e+00 , 7.1056408000000006e+00 , -7.3984700000000003e-01 , -5.7080100000000000e-01 , 3.5610900000000001e-01 -1.7574312773422680e+00 , 4.1604134678907085e+00 , 6.4212167999999998e+00 , 6.5227700000000000e-01 , -3.4693900000000000e-02 , -7.5718600000000003e-01 -1.7743925589623089e+00 , 4.0884249773878221e+00 , 6.4258968000000003e+00 , 3.3123399999999997e-01 , -2.1795900000000001e-01 , -9.1802899999999998e-01 -1.7863747986439222e+00 , 4.0263570548238095e+00 , 6.4471856000000001e+00 , -1.1753400000000000e-01 , 4.7783700000000001e-01 , 8.7055000000000005e-01 -1.7953167459435893e+00 , 3.9722151112929422e+00 , 6.4860400000000009e+00 , -3.8199300000000003e-01 , -6.9191199999999997e-01 , -6.1265000000000003e-01 -1.7979978331710880e+00 , 3.9342281509818235e+00 , 6.5615544000000003e+00 , -4.2733900000000002e-01 , -6.8757500000000005e-01 , -5.8704599999999996e-01 -1.7942443094727523e+00 , 3.9094109491802413e+00 , 6.6747376000000003e+00 , -7.6966900000000005e-01 , -6.1903799999999998e-01 , -1.5621099999999999e-01 -9.1153678302780028e-01 , 5.8433484278037051e+00 , 1.1716262400000002e+01 , 3.6004700000000001e-01 , -8.3748400000000001e-01 , 4.1108099999999997e-01 -1.6597627878586279e+00 , 4.1289742431052359e+00 , 7.6409495999999999e+00 , 6.6810999999999998e-01 , 1.9617499999999999e-01 , 7.1773500000000001e-01 -1.6776630361580327e+00 , 4.0435827283434218e+00 , 7.6531072000000000e+00 , 2.4449499999999999e-01 , 2.6512400000000003e-01 , 9.3270100000000000e-01 -1.6902068697960435e+00 , 3.9712611875745720e+00 , 7.7026631999999999e+00 , 3.6367899999999997e-01 , -6.3305100000000003e-01 , -6.8336200000000002e-01 -1.6762666175991507e+00 , 3.9514463086529314e+00 , 7.9175272000000003e+00 , 9.8987899999999995e-01 , -1.4023900000000000e-01 , -2.1756100000000000e-02 -1.6831581838977137e+00 , 3.8890255930418691e+00 , 8.0150375999999994e+00 , -9.6117799999999998e-01 , 9.8875000000000005e-02 , -2.5760699999999997e-01 -1.7070920482423610e+00 , 3.7900752998883993e+00 , 7.9927608000000001e+00 , 4.4527499999999998e-01 , -3.8146799999999997e-01 , 8.1006999999999996e-01 -1.8597001900148553e+00 , 3.4639857771703313e+00 , 7.1025311999999996e+00 , -4.7405900000000001e-01 , 5.0967799999999996e-01 , -7.1798099999999998e-01 -1.8979810294897725e+00 , 3.3534378065642003e+00 , 6.9519912000000001e+00 , -6.8699699999999997e-01 , -2.3925900000000000e-02 , -7.2626700000000000e-01 -1.9090133627185142e+00 , 3.2915487317689536e+00 , 6.9897016000000001e+00 , -8.5564700000000005e-01 , 4.5480999999999999e-01 , 2.4701300000000001e-01 -1.9283340068253836e+00 , 3.2158257326965582e+00 , 6.9658232000000000e+00 , 7.6250899999999999e-01 , -6.0718499999999997e-01 , 2.2339700000000001e-01 -1.7800415351517622e+00 , 3.3861321564277969e+00 , 8.2274992000000005e+00 , -2.7066400000000002e-01 , 4.2697600000000002e-01 , 8.6280500000000004e-01 -1.7801120942134285e+00 , 3.3250134697663483e+00 , 8.3984544000000003e+00 , -2.0570500000000000e-01 , 9.5908800000000005e-01 , -1.9451499999999999e-01 -1.4490604258688575e+00 , 8.8899086614834850e+00 , -1.6875360000000006e-01 , 7.2007600000000005e-02 , 2.0022699999999999e-01 , 9.7709999999999997e-01 -1.3364101348996109e+00 , 9.5271101090166077e+00 , -3.3459200000000022e-01 , 2.4133399999999999e-02 , 2.2784699999999999e-01 , 9.7339799999999999e-01 -1.2353302962629629e+00 , 1.0079058872837027e+01 , -4.3624160000000023e-01 , -9.0111199999999992e-03 , 2.0961600000000000e-01 , 9.7774200000000000e-01 -1.1153903516971715e+00 , 1.0738998132169968e+01 , -5.6456720000000038e-01 , -7.9499600000000004e-02 , 1.9131300000000001e-01 , 9.7830399999999995e-01 -9.6812582502481836e-01 , 1.1547679371746465e+01 , -7.2991679999999981e-01 , -6.3909300000000002e-02 , 1.8474199999999999e-01 , 9.8070700000000000e-01 -8.0931788866262444e-01 , 1.2411651833110350e+01 , -8.8668639999999987e-01 , -6.5403400000000000e-02 , 1.7796899999999999e-01 , 9.8185999999999996e-01 -6.2723637727805759e-01 , 1.3399178609214591e+01 , -1.0574752000000003e+00 , -6.2343099999999999e-02 , 1.6282500000000000e-01 , 9.8468299999999997e-01 -3.7905844287638257e-01 , 1.4761688755000451e+01 , -1.3255040000000000e+00 , -1.7984300000000002e-02 , 1.6029399999999999e-01 , 9.8690500000000003e-01 -8.9276991298615327e-02 , 1.6339350260756532e+01 , -1.6151751999999999e+00 , 8.3879800000000004e-02 , 2.4146599999999999e-01 , 9.6677700000000000e-01 --3.0130593628229008e-01 , 1.8477983695001701e+01 , -2.0244879999999998e+00 , -4.2421199999999999e-02 , 2.1088000000000001e-01 , 9.7659099999999999e-01 --7.8065832700510152e-01 , 2.1085054927803178e+01 , -2.4943911999999999e+00 , -6.3141600000000006e-02 , 1.6463500000000000e-01 , 9.8433199999999998e-01 --3.4853386313835744e+00 , 3.5721030991296828e+01 , -4.9810832000000005e+00 , -8.0792299999999997e-02 , 1.6234399999999999e-01 , 9.8342099999999999e-01 --3.6050464756475753e+00 , 3.6074535263886439e+01 , -4.4431640000000003e+00 , -8.0792299999999997e-02 , 1.6234399999999999e-01 , 9.8342099999999999e-01 --4.1298281539298909e-01 , 1.6200184593071892e+01 , 4.1959288000000008e+00 , 7.0021100000000003e-01 , -5.4263300000000003e-01 , -4.6395500000000001e-01 --2.6651975122863858e-01 , 1.5295529438919809e+01 , 4.5858248000000001e+00 , -9.0351300000000001e-01 , 3.5628900000000002e-01 , 2.3816499999999999e-01 --4.5876783928356213e-01 , 1.6101023901080090e+01 , 4.9274439999999995e+00 , 7.0021100000000003e-01 , -5.4263300000000003e-01 , -4.6395500000000001e-01 --9.2843270418678880e-01 , 1.8185212916168208e+01 , 5.4953360000000000e+00 , -9.1600400000000004e-01 , -3.1832899999999997e-01 , 2.4413799999999999e-01 --8.8738570172642506e-01 , 1.7875187835872822e+01 , 5.7309688000000003e+00 , -9.2010400000000003e-01 , -2.1914700000000001e-01 , 3.2462800000000003e-01 -2.6935704881236222e-01 , 1.2436856591490972e+01 , 4.9835311999999998e+00 , 7.5536400000000004e-01 , 6.0042399999999996e-01 , 2.6251900000000000e-01 -2.9742546866247221e-01 , 1.2230793380707125e+01 , 5.1263439999999996e+00 , -7.2200399999999998e-01 , -6.6650600000000004e-01 , -1.8568899999999999e-01 -4.2020025401295458e-02 , 1.3311428916548698e+01 , 5.5550736000000001e+00 , -6.8368200000000004e-02 , -6.0580999999999996e-01 , 7.9266599999999998e-01 -2.1658783652359381e-01 , 1.2444411563852460e+01 , 5.5475440000000003e+00 , -7.3399599999999998e-01 , -6.3310299999999997e-01 , -2.4582499999999999e-01 -1.9411458480094357e-01 , 1.2465854243966868e+01 , 5.7441040000000001e+00 , -2.8664200000000001e-01 , 9.0839999999999999e-01 , -3.0437799999999998e-01 -2.4119535712986928e-01 , 1.2180662910247726e+01 , 5.8563512000000006e+00 , -4.8737000000000003e-01 , -8.6650199999999999e-01 , -1.0791400000000000e-01 -2.1083241427727439e-01 , 1.2235174119659829e+01 , 6.0624792000000003e+00 , 6.5091900000000003e-01 , 4.3536700000000000e-01 , 6.2190000000000001e-01 -1.6710764942691214e-01 , 1.2353627735825089e+01 , 6.2934735999999996e+00 , -2.8747000000000000e-01 , 7.3505600000000004e-01 , -6.1404700000000001e-01 --6.0210963817820318e-02 , 1.3254414257057135e+01 , 6.7998599999999998e+00 , -4.9452000000000002e-01 , 7.2261699999999995e-01 , -4.8298500000000000e-01 --6.4930996470518521e-01 , 1.5697044329184189e+01 , 7.9043400000000004e+00 , 5.2201799999999998e-01 , -7.9921399999999998e-01 , 2.9791499999999999e-01 --1.7815658427914549e-02 , 1.2905187622063387e+01 , 7.1044760000000000e+00 , -3.1653300000000001e-01 , -8.0773200000000001e-01 , -4.9736900000000001e-01 --8.9657234073217573e-02 , 1.3122592528077639e+01 , 7.4092272000000001e+00 , -3.1653300000000001e-01 , -8.0773200000000001e-01 , -4.9736900000000001e-01 -2.1056219557583611e-01 , 1.1781731369732109e+01 , 7.0635728000000002e+00 , 2.9621700000000001e-01 , 7.4837900000000002e-01 , -5.9345099999999995e-01 -7.1905585203365208e-02 , 1.2283924583065740e+01 , 7.4870919999999996e+00 , -1.0052400000000000e-01 , -7.8908400000000001e-01 , 6.0600399999999999e-01 -1.8405197795739592e-01 , 1.1743482981264400e+01 , 7.4478424000000008e+00 , -2.1099000000000001e-01 , -7.5739000000000001e-01 , 6.1793500000000001e-01 --1.5947806758197958e-01 , 1.3068645929485127e+01 , 8.3020671999999998e+00 , -9.0383400000000003e-01 , -3.1616699999999998e-01 , 2.8830800000000001e-01 --1.6059505229252169e-01 , 1.2983633428815557e+01 , 8.4963183999999998e+00 , -8.5293600000000003e-01 , -3.0199399999999998e-01 , 4.2579200000000000e-01 -9.9054825005591907e-01 , 8.2722768384868672e+00 , 6.2176472000000000e+00 , 3.3422600000000002e-01 , 5.7435700000000001e-01 , 7.4726599999999999e-01 -9.7430957279155339e-01 , 8.2860908723096642e+00 , 6.3617911999999999e+00 , 5.6039499999999998e-01 , 8.2725300000000002e-01 , 4.0135299999999999e-02 -1.0352555005556265e+00 , 7.9986060017031821e+00 , 6.3339608000000007e+00 , 3.9976099999999998e-01 , 3.1864900000000002e-01 , 8.5945000000000005e-01 -9.4172488561354295e-01 , 8.3145991620890385e+00 , 6.6597200000000001e+00 , -4.1730800000000001e-01 , 9.0681299999999998e-01 , -5.9538899999999999e-02 -9.6053406689136955e-01 , 8.1893546171591378e+00 , 6.7272576000000006e+00 , 5.4085399999999999e-02 , 9.0803299999999998e-01 , 4.1539199999999998e-01 -9.2483960534571796e-01 , 8.2775272037623644e+00 , 6.9306087999999999e+00 , 5.0012699999999999e-01 , -8.6362200000000000e-01 , -6.3488299999999998e-02 -8.6470846133810575e-01 , 8.4514747596881854e+00 , 7.2014560000000003e+00 , 6.5379100000000001e-01 , -7.3941400000000002e-01 , -1.6070000000000001e-01 -9.4476285940832971e-01 , 8.0961188540972451e+00 , 7.1096136000000003e+00 , 3.7618600000000002e-01 , -8.5579200000000000e-01 , -3.5511100000000001e-01 -9.8442421832833915e-01 , 7.8936684197584057e+00 , 7.1146264000000006e+00 , 3.2566499999999998e-01 , 9.0552999999999995e-01 , -2.7195100000000000e-01 -8.9607150803906488e-01 , 8.1691989115416312e+00 , 7.4777840000000007e+00 , -1.3244000000000001e-02 , 9.1769999999999996e-01 , 3.9705299999999999e-01 -9.2057382195268489e-01 , 8.0268990465681291e+00 , 7.5303768000000000e+00 , -1.1626499999999999e-01 , 8.5908700000000005e-01 , 4.9845000000000000e-01 -9.2240195781227730e-01 , 7.9636110956527997e+00 , 7.6435079999999997e+00 , -1.1626499999999999e-01 , 8.5908700000000005e-01 , 4.9845000000000000e-01 -1.5927081047296854e-01 , 1.0656169035401970e+01 , 1.0104054400000001e+01 , -5.4542000000000002e-01 , 3.6866500000000002e-01 , -7.5273100000000004e-01 -4.2169413990011684e-01 , 9.6387788342648228e+00 , 9.4636224000000002e+00 , -6.9855800000000001e-01 , -3.7703999999999999e-01 , 6.0815900000000001e-01 -3.5120941638198033e-01 , 9.8117418257390963e+00 , 9.8538200000000007e+00 , -3.5775400000000002e-01 , -4.5074900000000001e-01 , 8.1782500000000002e-01 -5.3088046945708878e-01 , 9.1076059152559701e+00 , 9.4329111999999995e+00 , -1.3304800000000000e-01 , -1.2856500000000001e-01 , 9.8273600000000005e-01 -5.1055032350001395e-01 , 9.1042700434221828e+00 , 9.6597559999999998e+00 , 1.3304800000000000e-01 , 1.2856500000000001e-01 , -9.8273600000000005e-01 -6.0851088634334483e-01 , 8.6957085746517713e+00 , 9.4815936000000001e+00 , -1.8297500000000001e-02 , -1.3424000000000000e-01 , 9.9077999999999999e-01 -6.3114976426469971e-01 , 8.5475129800286673e+00 , 9.5572015999999991e+00 , 2.1123900000000001e-01 , -1.7867600000000001e-02 , 9.7727100000000000e-01 -7.4912449704230943e-01 , 8.0827457396319335e+00 , 9.2835463999999988e+00 , 2.5537799999999999e-01 , 5.3064199999999999e-02 , 9.6538400000000002e-01 -8.3568083416594163e-02 , 1.0206684663540234e+01 , 1.1915048000000001e+01 , -6.7400099999999996e-01 , -7.2821700000000000e-01 , 1.2418700000000001e-01 -7.1366513677981080e-01 , 8.0602877884361526e+00 , 9.7179128000000006e+00 , 4.2962699999999998e-01 , 8.1588200000000000e-01 , 3.8698600000000000e-01 -1.1330258475222001e+00 , 6.6412932836971654e+00 , 8.2348935999999995e+00 , 4.5768199999999998e-01 , 8.0243900000000001e-01 , -3.8290800000000003e-01 -7.4447773549196783e-01 , 7.8195399790847580e+00 , 9.9103440000000003e+00 , 4.0165000000000001e-01 , -5.9951499999999998e-02 , 9.1382900000000000e-01 -1.5723055235499099e+00 , 5.1573828702484104e+00 , 6.6816848000000002e+00 , 4.3474900000000000e-01 , 6.3371000000000000e-01 , 6.3984799999999997e-01 -1.5759577893972596e+00 , 5.1067422220410794e+00 , 6.7473088000000008e+00 , 4.3474900000000000e-01 , 6.3371000000000000e-01 , 6.3984799999999997e-01 -1.5689721573417699e+00 , 5.0898863969174100e+00 , 6.8624264000000004e+00 , -5.4145200000000004e-01 , -6.2915399999999999e-01 , -5.5766899999999997e-01 -1.5451682481632822e+00 , 5.1210447834838284e+00 , 7.0541608000000000e+00 , -1.2135100000000000e-01 , 8.4909500000000004e-01 , 5.1411300000000004e-01 -1.5527115785967920e+00 , 5.0568991703059112e+00 , 7.1115896000000003e+00 , -1.9817299999999999e-01 , 8.2725099999999996e-01 , 5.2572200000000002e-01 -1.5623885075441986e+00 , 4.9864265181785417e+00 , 7.1591488000000005e+00 , 2.5193399999999999e-01 , -8.7781299999999995e-01 , -4.0739900000000001e-01 -1.5491408138510643e+00 , 4.9842292078230184e+00 , 7.3193504000000003e+00 , 5.1507400000000003e-01 , -7.5619700000000001e-01 , -4.0356500000000001e-01 -1.5579110765529800e+00 , 4.9153448898547243e+00 , 7.3745952000000008e+00 , -5.8874200000000002e-02 , -9.3750999999999995e-01 , 3.4294100000000000e-01 -1.6736581207437615e+00 , 4.5496515581031662e+00 , 6.9017904000000003e+00 , 6.6715000000000002e-01 , 2.1795400000000001e-01 , 7.1232499999999999e-01 -1.6742436954028788e+00 , 4.5080669706926733e+00 , 6.9853855999999999e+00 , 7.7827999999999997e-01 , 5.0476500000000002e-01 , 3.7348700000000001e-01 -1.7966111446821058e+00 , 4.1432275313882556e+00 , 6.4496920000000006e+00 , 6.7477299999999996e-01 , 1.8226900000000001e-03 , -7.3802299999999998e-01 -1.8126491065142583e+00 , 4.0670831647270980e+00 , 6.4441175999999993e+00 , -3.4127700000000000e-01 , 2.7521200000000001e-01 , 8.9876999999999996e-01 -1.8225812698124475e+00 , 4.0039417566193878e+00 , 6.4648447999999998e+00 , -1.4449300000000001e-01 , 4.5229599999999998e-01 , 8.8008500000000001e-01 -1.8305175629953874e+00 , 3.9486727543199063e+00 , 6.5031791999999999e+00 , 3.7063200000000002e-01 , 6.8330800000000003e-01 , 6.2906499999999999e-01 -1.8311393727937353e+00 , 3.9096210548447714e+00 , 6.5782359999999995e+00 , 5.5617600000000000e-01 , 7.2999700000000001e-01 , 3.9720600000000000e-01 -1.8296091847521505e+00 , 3.8765212612514963e+00 , 6.6719087999999998e+00 , 6.8543200000000004e-01 , 7.0091199999999998e-01 , 1.9724500000000000e-01 -7.4684376037050670e-01 , 6.3293763754675023e+00 , 1.3160656000000001e+01 , 9.2187799999999998e-01 , 6.1629900000000001e-02 , 3.8254700000000003e-01 -1.6903007469844713e+00 , 4.1074260701809644e+00 , 7.6881240000000002e+00 , -8.7505600000000003e-02 , 3.9411200000000002e-01 , 9.1488700000000001e-01 -1.7115759298160294e+00 , 4.0095497872496537e+00 , 7.6706519999999996e+00 , -3.6565399999999998e-02 , 6.2159299999999995e-01 , 7.8248600000000001e-01 -1.7209887768660985e+00 , 3.9402333168060597e+00 , 7.7291624000000008e+00 , 1.1758299999999999e-02 , 9.5374199999999998e-01 , 3.0039800000000000e-01 -1.6636016965990150e+00 , 4.0031463357387835e+00 , 8.2188879999999997e+00 , 4.3929200000000002e-01 , -8.9817300000000000e-01 , 1.7565100000000000e-02 -1.7154489286130117e+00 , 3.8423226236809942e+00 , 8.0009143999999992e+00 , 5.6125300000000000e-01 , -2.6526200000000000e-01 , 7.8398400000000001e-01 -1.7362350262786856e+00 , 3.7453022354372036e+00 , 7.9875920000000002e+00 , -9.6526100000000007e-03 , -7.1138100000000004e-01 , 7.0274000000000003e-01 -1.8867927646280498e+00 , 3.4168551664787339e+00 , 7.0535576000000004e+00 , -4.4230000000000003e-01 , 5.3390199999999999e-01 , -7.2063800000000000e-01 -1.9140162535753555e+00 , 3.3218082280614327e+00 , 6.9618088000000000e+00 , -5.6537300000000001e-01 , 5.4277499999999999e-02 , -8.2304699999999997e-01 -1.9182861358383956e+00 , 3.2681836003713514e+00 , 7.0391224000000001e+00 , 4.1199700000000000e-01 , 2.1727800000000000e-01 , 8.8490000000000002e-01 -1.7896317370245542e+00 , 3.4143503199827396e+00 , 8.1271288000000013e+00 , -9.6642099999999997e-01 , -2.2106500000000001e-01 , -1.3099900000000000e-01 -1.8056105393518469e+00 , 3.3261498813705654e+00 , 8.1460568000000002e+00 , -1.2033099999999999e-01 , 6.3131300000000001e-01 , -7.6613600000000004e-01 -1.8099233943181177e+00 , 3.2544200932322100e+00 , 8.2547056000000012e+00 , 4.0714400000000001e-01 , -9.1321300000000005e-01 , 1.6617099999999999e-02 -1.7287855977712625e+00 , 8.4411105928252717e+00 , -1.0733119999999996e-01 , 3.1310200000000003e-02 , 1.8963200000000000e-01 , 9.8135600000000001e-01 -1.6690714740536685e+00 , 8.8261422259141185e+00 , -1.6952319999999999e-01 , 2.5762799999999999e-02 , 1.8212400000000001e-01 , 9.8293799999999998e-01 -1.6006285683889341e+00 , 9.2692216080214234e+00 , -2.4591120000000011e-01 , 2.4393399999999999e-02 , 1.9638400000000000e-01 , 9.8022399999999998e-01 -1.5172869066488990e+00 , 9.8209140951029958e+00 , -3.5556879999999991e-01 , 8.1767599999999999e-03 , 2.1049200000000001e-01 , 9.7756100000000001e-01 -1.4335688998778919e+00 , 1.0358915707994154e+01 , -4.3839439999999996e-01 , -6.0413500000000002e-02 , 1.8170700000000001e-01 , 9.8149500000000001e-01 -1.3204566469832320e+00 , 1.1111232827140046e+01 , -5.9161760000000019e-01 , -5.9486799999999999e-02 , 1.9973199999999999e-01 , 9.7804300000000000e-01 -1.1938063764667866e+00 , 1.1946981840554690e+01 , -7.4997840000000027e-01 , -6.0483000000000002e-02 , 1.8408200000000000e-01 , 9.8104800000000003e-01 -1.0398786697038129e+00 , 1.2953310295993914e+01 , -9.4260719999999987e-01 , -6.3072900000000001e-02 , 1.8167100000000000e-01 , 9.8133499999999996e-01 -8.6573015721078650e-01 , 1.4095145000763667e+01 , -1.1463952000000002e+00 , -4.1698199999999998e-02 , 1.6222900000000001e-01 , 9.8587199999999997e-01 -6.4793145092909321e-01 , 1.5519842167613865e+01 , -1.4048768000000003e+00 , -1.6887200000000002e-02 , 1.7945200000000000e-01 , 9.8362200000000000e-01 -3.7348214391495738e-01 , 1.7308809753571424e+01 , -1.7282544000000000e+00 , -2.2790399999999999e-02 , 1.8624700000000000e-01 , 9.8223899999999997e-01 -1.5776818326940223e-03 , 1.9752596781462906e+01 , -2.1844815999999998e+00 , -7.0068199999999997e-02 , 1.7498100000000000e-01 , 9.8207500000000003e-01 --4.7867681891741798e-01 , 2.2887726811600899e+01 , -2.7476415999999997e+00 , -6.1365000000000003e-02 , 1.7127000000000001e-01 , 9.8331100000000005e-01 --2.5325463795276582e+00 , 3.5988664440894397e+01 , -4.5985296000000000e+00 , -1.3759800000000000e-01 , 1.6848800000000000e-01 , 9.7605299999999995e-01 -4.0400306416354637e-01 , 1.3622186302787608e+01 , 4.5135032000000006e+00 , 1.2976800000000000e-02 , 9.4442800000000005e-01 , 3.2846199999999998e-01 --9.8636709178277826e-02 , 1.6244168268808146e+01 , 5.0983263999999995e+00 , 7.0021100000000003e-01 , -5.4263300000000003e-01 , -4.6395500000000001e-01 --4.0499585094557755e-02 , 1.5799763831077701e+01 , 5.2763016000000000e+00 , -1.7631200000000000e-01 , 6.5335500000000002e-01 , 7.3623499999999997e-01 -4.2989688197817943e-01 , 1.3169972440419953e+01 , 5.0415112000000004e+00 , -1.9243700000000000e-01 , 9.8102900000000004e-01 , 2.3468099999999999e-02 -5.6684696474274054e-01 , 1.2349978945207615e+01 , 5.0745832000000002e+00 , 8.0798999999999999e-01 , -3.0840000000000001e-01 , -5.0203799999999998e-01 -5.6828359377361504e-01 , 1.2251020580475432e+01 , 5.2371560000000006e+00 , 8.0798899999999996e-01 , -3.0840000000000001e-01 , -5.0203900000000001e-01 -5.0468524609928034e-01 , 1.2487955666395159e+01 , 5.4770631999999999e+00 , 6.8940900000000005e-01 , 7.1225000000000005e-01 , -1.3196600000000000e-01 -5.7993968534537665e-01 , 1.2006410777929357e+01 , 5.5433736000000007e+00 , -1.8523400000000001e-01 , 9.5193700000000003e-01 , 2.4393400000000001e-01 -5.5621384002923069e-01 , 1.2038529414458958e+01 , 5.7345983999999994e+00 , 6.4066800000000002e-01 , 4.1245799999999999e-01 , 6.4762900000000001e-01 -3.8739056489603607e-01 , 1.2802580357361286e+01 , 6.1444000000000001e+00 , -1.7812800000000001e-01 , 9.0547800000000001e-01 , -3.8520199999999999e-01 -3.6574848175229424e-01 , 1.2813049423501083e+01 , 6.3495400000000002e+00 , 2.9774600000000001e-01 , -8.5462000000000005e-01 , 4.2540800000000001e-01 -1.9788124826671916e-01 , 1.3546764811128028e+01 , 6.7984560000000007e+00 , 6.6516399999999998e-01 , -2.4999299999999999e-01 , 7.0360599999999995e-01 -2.7735293205154732e-01 , 1.3053733598055089e+01 , 6.8456095999999995e+00 , -7.4007100000000003e-01 , 3.8386999999999998e-02 , -6.7143200000000003e-01 -3.1070528277374754e-01 , 1.2792341243092981e+01 , 6.9623287999999999e+00 , -7.0002399999999998e-01 , -7.1411500000000006e-01 , -2.4172000000000000e-03 -3.9770508497406110e-01 , 1.2275071274929980e+01 , 6.9697336000000005e+00 , 1.6686100000000001e-01 , -2.7562500000000001e-01 , 9.4667199999999996e-01 -4.9426438165939879e-01 , 1.1722237986462050e+01 , 6.9447840000000003e+00 , 5.4623999999999995e-01 , -3.0593799999999999e-01 , 7.7975899999999998e-01 -4.8452990220270920e-01 , 1.1679718076629916e+01 , 7.1216464000000004e+00 , 4.1513800000000001e-01 , -3.5860999999999998e-01 , 8.3609800000000001e-01 -3.5034088121067541e-01 , 1.2218789981482740e+01 , 7.5656536000000001e+00 , -2.8592900000000001e-02 , 9.7823099999999996e-01 , 2.0553700000000000e-01 -3.6167827219009641e-01 , 1.2071879545624087e+01 , 7.7085080000000001e+00 , 9.3944799999999995e-02 , -9.2472600000000005e-01 , 3.6885800000000002e-01 -3.2395562788812593e-01 , 1.2152138651769677e+01 , 7.9617896000000004e+00 , 9.3944799999999995e-02 , -9.2472600000000005e-01 , 3.6885800000000002e-01 -1.1594061079329170e+00 , 8.2655455382617120e+00 , 6.1464800000000004e+00 , -2.7514000000000000e-01 , -1.6403499999999999e-01 , -9.4730700000000001e-01 -1.1608473468809950e+00 , 8.2004494810497661e+00 , 6.2452904000000009e+00 , -2.4054800000000001e-01 , -9.6821400000000002e-01 , -6.8541299999999999e-02 -1.1528370233301066e+00 , 8.1788123738381149e+00 , 6.3681143999999996e+00 , 3.1574099999999999e-01 , 9.0964900000000004e-01 , -2.6989999999999997e-01 -1.1156970140967712e+00 , 8.2867477137544068e+00 , 6.5691464000000002e+00 , -3.1405300000000003e-01 , 9.2256199999999999e-01 , -2.2416500000000000e-01 -1.0443349836515139e+00 , 8.5365619189347868e+00 , 6.8662848000000007e+00 , 6.9061700000000004e-01 , -6.8978600000000001e-01 , 2.1735699999999999e-01 -1.1132845207099975e+00 , 8.1757927124255971e+00 , 6.7874008000000003e+00 , 1.2639400000000001e-01 , 9.3882600000000005e-01 , 3.2035999999999998e-01 -1.0411238113452983e+00 , 8.4233227125763772e+00 , 7.0993592000000003e+00 , -8.3330599999999999e-01 , 2.0285200000000000e-01 , 5.1424999999999998e-01 -1.0159276161759803e+00 , 8.4686729875189535e+00 , 7.2874536000000001e+00 , -8.6582000000000003e-01 , 3.1749800000000000e-01 , 3.8671800000000001e-01 -1.0875789073185782e+00 , 8.1042705132250585e+00 , 7.1858040000000001e+00 , 3.7550400000000000e-01 , -2.7772200000000002e-01 , -8.8423300000000005e-01 -1.0591996115517219e+00 , 8.1614759169896232e+00 , 7.3846623999999998e+00 , -2.4920000000000000e-01 , 9.6673900000000001e-01 , 5.7583400000000000e-02 --3.1927873658581207e-01 , 1.3731413666610864e+01 , 1.1868497600000000e+01 , -9.3578700000000004e-01 , 3.3405600000000002e-01 , 1.1273300000000000e-01 -1.0479742315644394e+00 , 8.0774280159669889e+00 , 7.6449640000000008e+00 , 2.7735500000000002e-01 , 7.1758000000000000e-01 , 6.3886900000000002e-01 -3.7462404401151472e-01 , 1.0700884449418213e+01 , 1.0003039200000000e+01 , -4.9077900000000002e-01 , 5.5942099999999995e-01 , -6.6796999999999995e-01 -3.7032866173476831e-01 , 1.0624120112766569e+01 , 1.0190280800000000e+01 , -4.9077900000000002e-01 , 5.5942099999999995e-01 , -6.6796999999999995e-01 --2.7919689438683948e-01 , 1.3061037814512657e+01 , 1.2634312000000001e+01 , -9.2493599999999998e-01 , 3.5356799999999999e-01 , 1.3958400000000001e-01 -6.7936035938449746e-01 , 9.2385774260395941e+00 , 9.4295624000000018e+00 , 4.2606699999999997e-01 , 7.8235200000000005e-01 , -4.5430399999999999e-01 -7.3340490075115827e-01 , 8.9492691141919369e+00 , 9.3806615999999998e+00 , 7.0970500000000003e-01 , -1.1787100000000000e-02 , 7.0440100000000005e-01 -6.7976149153806587e-01 , 9.0692882051899808e+00 , 9.7277616000000009e+00 , 5.2557699999999996e-01 , -8.5962100000000000e-02 , -8.4639200000000003e-01 -7.8589718403160447e-01 , 8.5883473143812417e+00 , 9.4714431999999995e+00 , -4.8752700000000003e-02 , -4.1619900000000001e-02 , -9.9794300000000002e-01 -8.5986500886848294e-01 , 8.2386126438098994e+00 , 9.3271536000000008e+00 , -3.6378199999999999e-01 , -8.4365899999999994e-02 , 9.2765600000000004e-01 -8.6824560168924880e-01 , 8.1274791395202790e+00 , 9.4308520000000016e+00 , -4.3063400000000002e-01 , 2.9435600000000001e-01 , 8.5317600000000005e-01 -9.2638990081068551e-01 , 7.8416441591855301e+00 , 9.3315839999999994e+00 , -4.5633600000000002e-01 , 2.2674900000000001e-01 , 8.6043099999999995e-01 -9.2913856983361898e-01 , 7.7569165236941293e+00 , 9.4597224000000004e+00 , 6.3244100000000003e-01 , -4.8842999999999998e-01 , -6.0121100000000005e-01 -8.5148428229212936e-01 , 7.9471130663324399e+00 , 9.9286792000000013e+00 , 4.7363000000000000e-01 , -1.0461500000000000e-01 , 8.7448899999999996e-01 -9.2344189504482932e-01 , 7.6182363996688593e+00 , 9.7610415999999987e+00 , 7.8554199999999996e-01 , 1.3836399999999999e-01 , 6.0314100000000004e-01 -9.6970943871708104e-01 , 7.3838049199553240e+00 , 9.6982879999999998e+00 , -1.6722500000000001e-01 , 4.0730600000000000e-01 , 8.9785099999999995e-01 -1.6430043674210704e+00 , 5.0795849841414498e+00 , 6.7691591999999998e+00 , 4.3474900000000000e-01 , 6.3371000000000000e-01 , 6.3984799999999997e-01 -1.6476696267526656e+00 , 5.0205967915454437e+00 , 6.8251944000000000e+00 , 4.3474900000000000e-01 , 6.3371000000000000e-01 , 6.3984799999999997e-01 -1.6160523225577139e+00 , 5.0747157795134612e+00 , 7.0501671999999997e+00 , -1.3016500000000000e-02 , 9.4538400000000000e-01 , 3.2569900000000002e-01 -1.6117738089567464e+00 , 5.0435525808854909e+00 , 7.1580880000000002e+00 , 2.5193399999999999e-01 , -8.7781299999999995e-01 , -4.0739900000000001e-01 -1.1097277226093625e+00 , 6.5429768784000339e+00 , 9.7288536000000008e+00 , -6.4276800000000001e-01 , 5.1943799999999996e-01 , -5.6305700000000003e-01 -1.6101025699876292e+00 , 4.9526232236943821e+00 , 7.3388400000000003e+00 , 7.3992700000000000e-01 , -6.6584900000000002e-01 , -9.5669400000000002e-02 -1.6938224503980690e+00 , 4.6531478267972544e+00 , 6.9928944000000000e+00 , -2.7097700000000002e-01 , -6.1052099999999998e-01 , 7.4420100000000000e-01 -1.7216907669045909e+00 , 4.5246991855972318e+00 , 6.9252215999999995e+00 , -5.5990399999999996e-01 , -5.5513400000000002e-01 , -6.1508799999999997e-01 -1.7284533757521359e+00 , 4.4627298475961279e+00 , 6.9721671999999995e+00 , 3.9493100000000003e-02 , 9.3684599999999996e-01 , 3.4750599999999998e-01 -1.8264545636272076e+00 , 4.1433134154214049e+00 , 6.5144527999999999e+00 , -7.9725299999999999e-01 , -1.5534000000000001e-01 , 5.8331599999999995e-01 -1.8487764945512011e+00 , 4.0437074099433881e+00 , 6.4622864000000000e+00 , -2.0105899999999999e-01 , 4.6154499999999998e-01 , 8.6403200000000002e-01 -1.8556583109194511e+00 , 3.9845212327397599e+00 , 6.4914687999999998e+00 , 2.3365500000000000e-01 , -4.3019200000000002e-01 , -8.7197499999999994e-01 -1.8636478354112673e+00 , 3.9240845972549456e+00 , 6.5199648000000003e+00 , -3.1238199999999999e-01 , -6.5981299999999998e-01 , -6.8342099999999995e-01 -1.8643794528590978e+00 , 3.8808529933933307e+00 , 6.5848920000000000e+00 , 3.4678399999999998e-01 , 6.8024700000000005e-01 , 6.4575899999999997e-01 -1.8564240207043810e+00 , 3.8569349240372706e+00 , 6.7069048000000002e+00 , -6.7999299999999996e-01 , -7.1900500000000001e-01 , -1.4366999999999999e-01 -1.7386602773940489e+00 , 4.0940110178230675e+00 , 7.5211728000000004e+00 , 4.9283399999999999e-01 , 6.0287100000000005e-01 , 6.2742399999999998e-01 -1.7383049561484061e+00 , 4.0405311904122208e+00 , 7.6193071999999997e+00 , 2.0918300000000001e-01 , 6.2168400000000001e-01 , 7.5481900000000002e-01 -1.7445610655832846e+00 , 3.9713812933976014e+00 , 7.6779424000000001e+00 , 2.7822100000000000e-01 , 5.1556199999999996e-01 , 8.1042599999999998e-01 -1.7375525291807024e+00 , 3.9288621603314144e+00 , 7.8237920000000001e+00 , -3.6347000000000002e-01 , -9.1320299999999999e-01 , -1.8425400000000000e-01 -1.6934042821467139e+00 , 3.9597060825602153e+00 , 8.2257104000000005e+00 , -4.6951999999999999e-01 , -5.9263100000000002e-01 , 6.5447699999999998e-01 -1.7524887306048385e+00 , 3.7800283584689507e+00 , 7.9367880000000000e+00 , -2.5925599999999999e-01 , -4.0431699999999998e-01 , 8.7710600000000005e-01 -1.7304584765666911e+00 , 3.7587539508945893e+00 , 8.2007088000000010e+00 , 9.0544100000000005e-01 , -2.5002999999999997e-01 , -3.4301799999999999e-01 -1.9108361773475213e+00 , 3.3697007054146826e+00 , 7.0038143999999996e+00 , -8.9388599999999996e-01 , -3.1371100000000002e-01 , 3.2023900000000000e-01 -1.9198772424614605e+00 , 3.3037363932895412e+00 , 7.0314368000000007e+00 , -8.5191399999999995e-01 , 5.2235600000000004e-01 , -3.7234099999999999e-02 -1.9455561462620659e+00 , 3.2093101660731955e+00 , 6.9266464000000001e+00 , -6.4346000000000003e-01 , 1.6431000000000001e-01 , -7.4763700000000000e-01 -1.7916636808657485e+00 , 3.3869494110199945e+00 , 8.2182224000000001e+00 , -6.7898599999999998e-01 , 3.6799700000000002e-01 , 6.3526000000000005e-01 -1.7876910695749186e+00 , 3.3217746183366703e+00 , 8.3787464000000007e+00 , -3.3049800000000001e-01 , 9.4105300000000003e-01 , 7.2041900000000006e-02 -2.4635350294761875e+00 , 4.0103089306910906e+00 , 7.2520959999999990e-01 , -7.5108900000000006e-02 , 4.3734299999999997e-02 , 9.9621599999999999e-01 -2.4550503223662523e+00 , 4.0799727172747176e+00 , 7.1078479999999988e-01 , -7.4895600000000001e-03 , 3.3975300000000000e-02 , 9.9939500000000003e-01 -2.4462482524623232e+00 , 4.1395336695430345e+00 , 7.1465359999999989e-01 , -7.4895700000000001e-03 , 3.3975300000000000e-02 , 9.9939500000000003e-01 -2.0245505100809256e+00 , 7.6128062702894610e+00 , 6.6119999999999957e-02 , -4.3915799999999998e-02 , 1.6820099999999999e-01 , 9.8477400000000004e-01 -1.9872808643089230e+00 , 7.9079556723358646e+00 , 2.1077600000000141e-02 , -2.8851999999999999e-02 , 1.6777400000000001e-01 , 9.8540300000000003e-01 -1.9469840494142394e+00 , 8.2330101798096464e+00 , -2.9008800000000168e-02 , -3.3633099999999999e-02 , 1.8390500000000001e-01 , 9.8236800000000002e-01 -1.9022055984831334e+00 , 8.5990186768135963e+00 , -8.7644000000000055e-02 , -2.8476300000000000e-02 , 1.7511599999999999e-01 , 9.8413600000000001e-01 -1.8468577999102822e+00 , 9.0519790163798977e+00 , -1.7543039999999976e-01 , -1.3093400000000000e-02 , 1.8482999999999999e-01 , 9.8268299999999997e-01 -1.7859500722785522e+00 , 9.5558193815914390e+00 , -2.7011200000000013e-01 , -3.7965400000000003e-02 , 1.9277900000000001e-01 , 9.8050700000000002e-01 -1.7115014595251807e+00 , 1.0178650276682474e+01 , -3.9897839999999984e-01 , -3.7768400000000001e-02 , 1.7969199999999999e-01 , 9.8299800000000004e-01 -1.6331745520406162e+00 , 1.0816739626779766e+01 , -5.1092400000000016e-01 , -4.0601100000000001e-02 , 1.9017899999999999e-01 , 9.8090900000000003e-01 -1.5380698031443276e+00 , 1.1605178311101998e+01 , -6.6018480000000013e-01 , -4.5071899999999998e-02 , 1.8887699999999999e-01 , 9.8096600000000000e-01 -1.4298102928276506e+00 , 1.2487303031075085e+01 , -8.1633040000000001e-01 , -4.7848500000000002e-02 , 1.8408900000000000e-01 , 9.8174399999999995e-01 -1.2963872164245891e+00 , 1.3581194559403528e+01 , -1.0176951999999999e+00 , -4.8507599999999998e-02 , 1.7723500000000000e-01 , 9.8297299999999999e-01 -1.1434029587713441e+00 , 1.4831418521339648e+01 , -1.2325904000000003e+00 , -3.8875800000000002e-02 , 1.8168200000000001e-01 , 9.8258900000000005e-01 -9.4482051458182670e-01 , 1.6454626367289599e+01 , -1.5241440000000002e+00 , -3.4542600000000000e-02 , 1.8032699999999999e-01 , 9.8299999999999998e-01 -6.8255583645183471e-01 , 1.8604627295334780e+01 , -1.9186264000000004e+00 , -5.9541700000000003e-02 , 1.8503400000000000e-01 , 9.8092699999999999e-01 -3.5499657305575649e-01 , 2.1277911008484505e+01 , -2.3859088000000002e+00 , -6.9020200000000004e-02 , 1.6489300000000001e-01 , 9.8389400000000005e-01 --2.2536312453757219e+00 , 4.2093984240933366e+01 , -5.4729200000000002e+00 , 5.2586400000000002e-03 , 1.4093500000000000e-01 , 9.9000500000000002e-01 -8.0121784943864571e-01 , 1.3495781008261222e+01 , 4.0285408000000000e+00 , -3.3399299999999998e-01 , 8.7387400000000004e-01 , -3.5326000000000002e-01 -7.8752768272095230e-01 , 1.3454379926765663e+01 , 4.2210343999999997e+00 , -1.5456000000000000e-01 , -9.8792000000000002e-01 , -1.1230900000000000e-02 -7.6470196276130209e-01 , 1.3470975972236909e+01 , 4.4197367999999999e+00 , -4.4023800000000002e-01 , 8.1189299999999998e-01 , 3.8343200000000000e-01 -7.4790973691900353e-01 , 1.3453777038356542e+01 , 4.6153399999999998e+00 , -1.3757500000000000e-01 , 9.2215100000000005e-01 , 3.6153999999999997e-01 -7.8679886406621335e-01 , 1.3076780279678875e+01 , 4.7551888000000009e+00 , -3.4278100000000000e-01 , 9.3034099999999997e-01 , 1.3025700000000001e-01 -7.2798006036033192e-01 , 1.3326749529899823e+01 , 4.9922255999999994e+00 , -2.3667700000000000e-01 , 9.7092900000000004e-01 , -3.5794500000000000e-02 -6.9610606312846679e-01 , 1.3400723702613556e+01 , 5.2051552000000001e+00 , -3.0126999999999998e-01 , 9.5044600000000001e-01 , -7.6741100000000007e-02 -6.8346446488989221e-01 , 1.3349454228683612e+01 , 5.3959847999999999e+00 , -3.5606400000000003e-02 , 9.9121800000000004e-01 , -1.2735099999999999e-01 -6.9193018792310057e-01 , 1.3174700671790012e+01 , 5.5582456000000002e+00 , -8.3538699999999999e-01 , 5.3232299999999999e-01 , 1.3697100000000001e-01 -7.6867963910026904e-01 , 1.2589009606637982e+01 , 5.6135527999999999e+00 , -7.6846800000000004e-01 , 2.5044899999999998e-01 , 5.8884000000000003e-01 -8.0906159498444485e-01 , 1.2234005414356815e+01 , 5.7100232000000002e+00 , 1.9885500000000000e-01 , -9.5981700000000003e-01 , 1.9801199999999999e-01 -6.6520161597320060e-01 , 1.2973606019693509e+01 , 6.1089152000000002e+00 , 2.5568200000000002e-01 , -7.5386300000000003e-02 , 9.6381700000000003e-01 -7.0242417961629022e-01 , 1.2631926152466372e+01 , 6.2074968000000004e+00 , 8.8153499999999996e-02 , -5.9485900000000003e-01 , 7.9898100000000005e-01 -8.5632920724539874e-02 , 1.6086906222100211e+01 , 7.5296799999999999e+00 , 6.6359400000000002e-01 , 6.3149999999999995e-01 , 4.0106199999999997e-01 --2.4133010964539903e-02 , 1.6557560855404070e+01 , 7.9605623999999997e+00 , 6.6359400000000002e-01 , 6.3149999999999995e-01 , 4.0106199999999997e-01 --2.2648127678507546e-02 , 1.6389563085707724e+01 , 8.1812192000000010e+00 , 6.6359299999999999e-01 , 6.3150099999999998e-01 , 4.0106199999999997e-01 --6.1780382498362929e-02 , 1.6448377070824332e+01 , 8.4859080000000002e+00 , -5.9842700000000004e-01 , -2.2683700000000001e-01 , -7.6839400000000002e-01 -7.9635231299540199e-01 , 1.1548938338580653e+01 , 6.7867872000000009e+00 , -5.0159900000000002e-01 , -1.3070100000000001e-01 , -8.5516999999999999e-01 -8.1077312629529086e-01 , 1.1368144267363084e+01 , 6.8991591999999997e+00 , -5.0159900000000002e-01 , -1.3070100000000001e-01 , -8.5516999999999999e-01 -6.3473437170362734e-01 , 1.2215338240919621e+01 , 7.4669056000000005e+00 , -2.7161099999999999e-01 , -8.6778200000000005e-01 , -4.1615099999999999e-01 -5.9884783737836167e-01 , 1.2293072598935231e+01 , 7.7133440000000002e+00 , 8.2145300000000004e-02 , 3.0396400000000001e-01 , 9.4913499999999995e-01 -6.0357490264284563e-01 , 1.2153576691005775e+01 , 7.8599736000000000e+00 , 8.2145399999999993e-02 , 3.0396400000000001e-01 , 9.4913499999999995e-01 -1.3261305965094903e+00 , 8.2717098567980756e+00 , 6.0861808000000002e+00 , 3.7830799999999998e-01 , 8.9348700000000003e-01 , -2.4199999999999999e-01 -1.3324651871635029e+00 , 8.1716432762909363e+00 , 6.1653247999999996e+00 , 1.6480900000000001e-01 , 3.7850600000000001e-01 , 9.1080799999999995e-01 -1.2369680336438571e+00 , 8.5903605896813477e+00 , 6.5314256000000004e+00 , 6.3379700000000005e-01 , -5.9199100000000004e-01 , 4.9784400000000001e-01 -1.2751258438883373e+00 , 8.3234374853853659e+00 , 6.5217744000000000e+00 , 2.6760200000000001e-01 , 9.5453900000000003e-01 , 1.3131999999999999e-01 -1.1381279593395472e+00 , 8.9370271491416222e+00 , 7.0346191999999999e+00 , -8.0720499999999995e-01 , 2.8645100000000001e-01 , -5.1610599999999995e-01 -1.0747888707081354e+00 , 9.1691759345328983e+00 , 7.3406392000000000e+00 , 8.8931600000000000e-01 , -4.4973000000000002e-01 , -8.2826999999999998e-02 -9.4248096482037891e-01 , 9.7264246860221579e+00 , 7.8752928000000004e+00 , 3.0043599999999998e-01 , 3.8290500000000000e-01 , -8.7356800000000001e-01 -1.1801062241327609e+00 , 8.4969343881216020e+00 , 7.2256048000000002e+00 , -3.9716200000000000e-02 , 6.5576500000000004e-01 , 7.5392000000000003e-01 -1.1803250140580164e+00 , 8.4219340413963089e+00 , 7.3329535999999997e+00 , 4.3874600000000002e-01 , -1.7274899999999999e-02 , -8.9844500000000005e-01 -1.2247018860395307e+00 , 8.1400253601011805e+00 , 7.2871623999999997e+00 , -4.1857299999999997e-01 , 3.5770099999999999e-01 , -8.3477400000000002e-01 -1.2295882332149382e+00 , 8.0396121484871301e+00 , 7.3695200000000005e+00 , -2.4323300000000000e-01 , 9.2458799999999997e-01 , -2.9321599999999998e-01 -8.9787621153446739e-02 , 1.3159180031532232e+01 , 1.1571702399999999e+01 , -3.4862700000000002e-01 , -9.2047900000000005e-01 , 1.7657100000000001e-01 -4.0053932973203921e-02 , 1.3237386393410310e+01 , 1.1949180800000001e+01 , 3.4862700000000002e-01 , 9.2047900000000005e-01 , -1.7657100000000001e-01 --6.5948938375825161e-02 , 1.3563956534381465e+01 , 1.2551112000000002e+01 , -8.7816099999999997e-01 , 3.8265100000000002e-01 , 2.8707400000000000e-01 --1.1429264780749016e-02 , 1.3170921385912095e+01 , 1.2551527999999999e+01 , -9.2493599999999998e-01 , 3.5356799999999999e-01 , 1.3958400000000001e-01 -6.3509518412834365e-01 , 1.0237624928925609e+01 , 1.0220503200000000e+01 , 3.3774199999999999e-01 , -3.0396600000000001e-01 , 8.9080599999999999e-01 -9.1428195945739943e-01 , 8.9402839329912389e+00 , 9.2534279999999995e+00 , 4.5447100000000001e-01 , 2.0160200000000000e-01 , -8.6764799999999997e-01 -8.7278004987162161e-01 , 9.0208805426316427e+00 , 9.5550488000000016e+00 , -4.3855600000000000e-01 , -8.6056100000000002e-01 , 2.5904199999999999e-01 -9.3920596754830599e-01 , 8.6466431023593557e+00 , 9.4087415999999990e+00 , 4.8784899999999998e-01 , 1.0758200000000001e-02 , -8.7286200000000003e-01 -9.8628523166657023e-01 , 8.3643802435312971e+00 , 9.3406736000000006e+00 , -3.7779699999999999e-01 , -3.5256700000000002e-02 , 9.2521699999999996e-01 -1.0068858826073739e+00 , 8.1914923129614472e+00 , 9.3776352000000003e+00 , -4.3230600000000002e-01 , 4.3127900000000002e-01 , 7.9190300000000002e-01 -1.0223853836255423e+00 , 8.0386023686526471e+00 , 9.4337015999999991e+00 , 6.0263800000000001e-01 , -2.4813600000000000e-01 , -7.5845700000000005e-01 -1.0216645399874675e+00 , 7.9523967868754575e+00 , 9.5643048000000004e+00 , -7.9554300000000000e-01 , 1.4066400000000001e-01 , 5.8934299999999995e-01 -9.8827025465158380e-01 , 7.9879037416749892e+00 , 9.8441272000000009e+00 , -5.3648499999999999e-01 , -2.6425900000000002e-01 , -8.0146799999999996e-01 -1.0440563958068356e+00 , 7.6834131984647831e+00 , 9.7097384000000009e+00 , -3.8211800000000001e-01 , 4.2145800000000000e-01 , 8.2241100000000000e-01 -1.0648025149302141e+00 , 7.5161470288967402e+00 , 9.7377456000000002e+00 , -6.7025799999999996e-02 , 2.8664099999999998e-01 , 9.5569099999999996e-01 -1.7043592958147356e+00 , 5.1092447472862927e+00 , 6.7344544000000006e+00 , 4.3474900000000000e-01 , 6.3371000000000000e-01 , 6.3984799999999997e-01 -1.7156281798310098e+00 , 5.0203548490657335e+00 , 6.7489103999999998e+00 , 4.3474900000000000e-01 , 6.3371000000000000e-01 , 6.3984799999999997e-01 -1.2389499314637129e+00 , 6.6355147649145607e+00 , 9.2407192000000009e+00 , 9.0153899999999998e-01 , -7.2491600000000003e-02 , 4.2658099999999999e-01 -1.6043084109877979e+00 , 5.3033162134155960e+00 , 7.4655120000000004e+00 , -2.5384000000000001e-03 , 5.9085900000000002e-01 , 8.0677100000000002e-01 -1.6013629249151000e+00 , 5.2544791457825406e+00 , 7.5598088000000008e+00 , -6.3308799999999998e-02 , 5.4652299999999998e-01 , 8.3504800000000001e-01 -1.6123826570426423e+00 , 5.1590551008174756e+00 , 7.5839264000000002e+00 , 4.0445599999999998e-02 , 4.8250100000000001e-01 , 8.7496099999999999e-01 -1.7545068463564815e+00 , 4.6422842059923379e+00 , 6.8886656000000004e+00 , 2.5342399999999998e-01 , -2.3609500000000000e-01 , 9.3810199999999999e-01 -1.7731922097536510e+00 , 4.5352133255738245e+00 , 6.8566440000000002e+00 , 8.1889400000000001e-02 , 4.6669300000000002e-01 , 8.8061999999999996e-01 -1.7594410109142016e+00 , 4.5270351653831993e+00 , 7.0028472000000006e+00 , -1.7075600000000000e-02 , 9.8051699999999997e-01 , 1.9569000000000000e-01 -1.7672016197908895e+00 , 4.4538607437169979e+00 , 7.0312704000000004e+00 , 7.2960400000000003e-01 , 2.2439700000000001e-01 , -6.4600599999999997e-01 -1.8593818991436595e+00 , 4.1332112973490904e+00 , 6.5609304000000002e+00 , -7.9576899999999995e-01 , -2.8694300000000000e-01 , 5.3330599999999995e-01 -1.8817723863655820e+00 , 4.0233366221768811e+00 , 6.4894096000000001e+00 , -2.4086099999999999e-01 , 4.4148999999999999e-01 , 8.6433400000000005e-01 -1.8887064147734676e+00 , 3.9589826051718155e+00 , 6.5087640000000002e+00 , -2.4595100000000000e-01 , 3.8836799999999999e-01 , 8.8807599999999998e-01 -1.8925909497536797e+00 , 3.9025633135795785e+00 , 6.5457776000000001e+00 , -1.9280600000000001e-01 , -6.9452400000000003e-01 , -6.9315400000000005e-01 -1.8944201931545250e+00 , 3.8541211092323309e+00 , 6.6008975999999997e+00 , 2.8382499999999999e-01 , 6.8685300000000005e-01 , 6.6908599999999996e-01 -1.8843551250078503e+00 , 3.8332029177373572e+00 , 6.7320935999999998e+00 , -6.9153399999999998e-01 , -7.1602399999999999e-01 , -9.5344499999999999e-02 -1.7594302748434467e+00 , 4.0879069034278084e+00 , 7.6164991999999998e+00 , 6.0074300000000003e-01 , 7.2566399999999998e-01 , 3.3543899999999999e-01 -1.7558344646386681e+00 , 4.0354255941270214e+00 , 7.7241912000000008e+00 , -4.9936599999999998e-01 , -3.5453400000000002e-01 , -7.9053099999999998e-01 -1.7755928395555614e+00 , 3.9290709655391796e+00 , 7.6748327999999999e+00 , -3.8633899999999999e-01 , -4.8434199999999999e-01 , -7.8495599999999999e-01 -1.7003772295375821e+00 , 4.0292031068765031e+00 , 8.2823072000000000e+00 , -3.5919699999999999e-01 , -7.0124600000000004e-01 , 6.1581799999999998e-01 -1.7550363894026673e+00 , 3.8457419978528367e+00 , 7.9947160000000004e+00 , 6.8319500000000000e-01 , -1.2260800000000001e-02 , 7.3013300000000003e-01 -1.7741390896757880e+00 , 3.7405384518371472e+00 , 7.9509216000000000e+00 , 2.5925599999999999e-01 , 4.0431699999999998e-01 , -8.7710600000000005e-01 -1.7418341333457206e+00 , 3.7347857772914272e+00 , 8.2843976000000001e+00 , -6.3354900000000003e-01 , 7.6360600000000001e-02 , 7.6992499999999997e-01 -1.9188447361679666e+00 , 3.3485517901806130e+00 , 7.0639576000000002e+00 , 4.9757099999999999e-01 , 3.2288999999999998e-02 , 8.6682199999999998e-01 -1.9341533045635471e+00 , 3.2658395961376581e+00 , 7.0203192000000003e+00 , 1.1729700000000000e-01 , 4.8516999999999999e-01 , 8.6651699999999998e-01 -1.9566894449348231e+00 , 3.1744372750106065e+00 , 6.9245768000000005e+00 , 6.2079300000000004e-01 , 3.0217600000000001e-02 , 7.8339199999999998e-01 -1.8034414674396968e+00 , 3.3406936605964250e+00 , 8.2177335999999990e+00 , -8.6377999999999999e-01 , -1.3649200000000000e-01 , -4.8503000000000002e-01 -1.8107829940503493e+00 , 3.2564938055181969e+00 , 8.2651680000000010e+00 , 4.0714400000000001e-01 , -9.1321300000000005e-01 , 1.6617500000000000e-02 -2.5240641733039042e+00 , 4.0022789501978426e+00 , 7.0877759999999990e-01 , -7.6006000000000004e-02 , 6.4799899999999994e-02 , 9.9500000000000000e-01 -2.5174254872331634e+00 , 4.0546487563328721e+00 , 7.1962479999999984e-01 , 4.6254900000000002e-02 , -6.9418400000000005e-02 , -9.9651500000000004e-01 -2.5108453607015195e+00 , 4.1197748733830046e+00 , 7.1469519999999997e-01 , -7.4895700000000001e-03 , 3.3975300000000000e-02 , 9.9939500000000003e-01 -2.5029913769270284e+00 , 4.1794643430803609e+00 , 7.1940639999999978e-01 , -2.8738099999999999e-02 , 6.3344100000000000e-02 , 9.9757799999999996e-01 -2.2499167289351494e+00 , 6.9733784413180988e+00 , 1.9225119999999984e-01 , -6.8939899999999998e-02 , 1.8222200000000000e-01 , 9.8083799999999999e-01 -2.2266891388347370e+00 , 7.2171069752968000e+00 , 1.5317840000000005e-01 , -5.5318699999999998e-02 , 1.7455999999999999e-01 , 9.8309100000000005e-01 -2.2008495232754357e+00 , 7.4911006681133827e+00 , 1.0573359999999998e-01 , -4.9716499999999997e-02 , 1.7217199999999999e-01 , 9.8381200000000002e-01 -2.1749867545446424e+00 , 7.7669360727235546e+00 , 6.7409599999999958e-02 , -3.8311100000000001e-02 , 1.6840500000000000e-01 , 9.8497299999999999e-01 -2.1449497879032151e+00 , 8.0831510962180460e+00 , 1.7801599999999862e-02 , -1.4633000000000000e-02 , 1.7861800000000000e-01 , 9.8380999999999996e-01 -2.1086350997980996e+00 , 8.4940429624656861e+00 , -6.9204800000000066e-02 , -3.4581800000000003e-02 , 1.9046700000000000e-01 , 9.8108399999999996e-01 -2.0690963220158851e+00 , 8.9282208714959452e+00 , -1.5199920000000011e-01 , 2.6149599999999999e-02 , -1.9292100000000001e-01 , -9.8086600000000002e-01 -2.0259017097035792e+00 , 9.3956145829384390e+00 , -2.3406560000000010e-01 , -1.9664999999999998e-02 , 1.9019200000000000e-01 , 9.8155000000000003e-01 -1.9735229170686843e+00 , 9.9803988754318951e+00 , -3.5204320000000022e-01 , -2.6241700000000000e-02 , 1.8353100000000000e-01 , 9.8266399999999998e-01 -1.9188906664878342e+00 , 1.0571326737305263e+01 , -4.5060400000000023e-01 , -2.8427800000000000e-02 , 1.8358400000000000e-01 , 9.8259300000000005e-01 -1.8501035546370215e+00 , 1.1330602206284491e+01 , -5.9672400000000003e-01 , -3.1831300000000000e-02 , 1.8736500000000000e-01 , 9.8177499999999995e-01 -1.7733862678260084e+00 , 1.2164333553157544e+01 , -7.4386319999999984e-01 , -4.1034099999999997e-02 , 1.7956300000000000e-01 , 9.8289000000000004e-01 -1.6809121764982113e+00 , 1.3171435985253652e+01 , -9.2461519999999986e-01 , -5.2040400000000001e-02 , 1.8442000000000000e-01 , 9.8146900000000004e-01 -1.5753141613022044e+00 , 1.4294058608923969e+01 , -1.1091736000000001e+00 , -5.6093700000000003e-02 , 1.7493700000000001e-01 , 9.8297999999999996e-01 -1.4345988093065296e+00 , 1.5829885061145109e+01 , -1.3901712000000002e+00 , -6.2289999999999998e-02 , 1.8297600000000000e-01 , 9.8114199999999996e-01 -1.2596702872788312e+00 , 1.7733256841969130e+01 , -1.7302616000000004e+00 , -5.9808699999999999e-02 , 1.9087699999999999e-01 , 9.7979000000000005e-01 -1.0211555456157706e+00 , 2.0338000737544117e+01 , -2.2077568000000003e+00 , -7.4087600000000003e-02 , 1.7144000000000001e-01 , 9.8240499999999997e-01 -7.5420669820261343e-01 , 2.3182319189121262e+01 , -2.6562984000000007e+00 , -7.0286600000000005e-02 , 1.7275199999999999e-01 , 9.8245400000000005e-01 --8.1937513007884366e-01 , 3.9772377373778461e+01 , -5.1687824000000004e+00 , -8.0792400000000000e-02 , 1.6234399999999999e-01 , 9.8342099999999999e-01 --9.8885422892134711e-01 , 4.0867725103331480e+01 , -4.7120144000000002e+00 , -2.9597399999999999e-02 , 1.7928800000000000e-01 , 9.8335099999999998e-01 -1.1422008389465086e+00 , 1.3570101328926031e+01 , 3.7694456000000001e+00 , -1.9702500000000001e-01 , 9.3037199999999998e-01 , -3.0917499999999998e-01 -1.1283047191926887e+00 , 1.3513802365100863e+01 , 3.9610760000000003e+00 , -1.9702500000000001e-01 , 9.3037199999999998e-01 , -3.0917499999999998e-01 -1.0917119578918117e+00 , 1.3647730144670218e+01 , 4.1702512000000000e+00 , 1.9702500000000001e-01 , -9.3037199999999998e-01 , 3.0917499999999998e-01 -1.0312647038387603e+00 , 1.3973984494852413e+01 , 4.4066016000000001e+00 , 5.1337900000000003e-01 , -8.5268900000000003e-01 , -9.6767900000000004e-02 -1.0504825170951866e+00 , 1.3639372523262331e+01 , 4.5680928000000005e+00 , -4.2939400000000000e-01 , 8.5814599999999996e-01 , 2.8143800000000002e-01 -1.0501599707898457e+00 , 1.3477375283841775e+01 , 4.7442272000000001e+00 , -3.7735900000000000e-01 , 8.0863799999999997e-01 , 4.5133600000000001e-01 -1.0311834426363005e+00 , 1.3464827101476279e+01 , 4.9411823999999998e+00 , 1.3024200000000000e-01 , -9.6841800000000000e-01 , -2.1261300000000000e-01 -1.0197678763415032e+00 , 1.3388020153235844e+01 , 5.1267391999999994e+00 , -1.2509400000000001e-01 , 9.9097400000000002e-01 , -4.8190100000000000e-02 -1.0029076993218902e+00 , 1.3357755270465423e+01 , 5.3209591999999999e+00 , -1.2924700000000000e-03 , 9.8558000000000001e-01 , 1.6920499999999999e-01 -8.3044440640017614e-01 , 1.4482953147774495e+01 , 5.7723816000000001e+00 , 8.3943900000000005e-01 , -4.4578200000000001e-01 , 3.1083800000000000e-01 -8.7126374022770103e-01 , 1.4010525599755416e+01 , 5.8819248000000002e+00 , -8.0236099999999999e-01 , 5.4573799999999995e-01 , -2.4163499999999999e-01 -9.1278051378586311e-01 , 1.3548320377556923e+01 , 5.9784576000000005e+00 , -8.2874099999999995e-01 , 5.4813100000000003e-01 , -1.1287100000000000e-01 -8.6209653419035392e-01 , 1.3751762319359399e+01 , 6.2451552000000001e+00 , 8.1644200000000000e-01 , -4.4541100000000000e-01 , 3.6746499999999999e-01 -1.0149770969492695e+00 , 1.2517859084368146e+01 , 6.0932111999999998e+00 , 5.4127099999999995e-01 , 6.0484599999999999e-01 , -5.8411299999999999e-01 --9.5674086345869824e-02 , 2.0082638702706465e+01 , 8.6875016000000009e+00 , -9.3806199999999995e-01 , 1.4090400000000000e-01 , 3.1652100000000000e-01 -4.0267614909174432e-01 , 1.6425057500294805e+01 , 7.7999552000000003e+00 , 6.6359400000000002e-01 , 6.3149999999999995e-01 , 4.0106199999999997e-01 -1.0419431071365002e+00 , 1.1912791332636335e+01 , 6.4685264000000000e+00 , -4.1965200000000003e-01 , 7.3143400000000003e-01 , -5.3749100000000005e-01 -1.0284265310995839e+00 , 1.1869738207399848e+01 , 6.6419464000000001e+00 , -1.8441299999999999e-01 , 8.7102700000000000e-01 , -4.5530599999999999e-01 -1.0172802340225098e+00 , 1.1814060329371049e+01 , 6.8111959999999998e+00 , -1.8777199999999999e-01 , 9.7592900000000005e-01 , -1.1092500000000000e-01 -8.7244530825068134e-01 , 1.2620231012143933e+01 , 7.3402128000000006e+00 , 1.8254600000000001e-01 , 7.4892099999999995e-01 , 6.3702000000000003e-01 -1.4100955735177105e+00 , 9.0434219862519605e+00 , 5.9869336000000004e+00 , -6.2632300000000002e-02 , 9.9770700000000001e-01 , 2.5643800000000001e-02 -1.3988488546139104e+00 , 9.0282597733429242e+00 , 6.1201160000000003e+00 , 2.0178499999999999e-01 , -9.5157800000000003e-01 , -2.3191200000000001e-01 -9.3342649747725148e-01 , 1.1820354630610744e+01 , 7.6045495999999995e+00 , 1.1333400000000000e-01 , 6.8572599999999995e-01 , -7.1898200000000001e-01 -1.4091255075763962e+00 , 8.7768548690191253e+00 , 6.2816488000000001e+00 , 7.0094100000000004e-01 , -6.2166200000000005e-01 , -3.4959800000000002e-01 -1.4517710283709677e+00 , 8.4278805741547043e+00 , 6.2398823999999999e+00 , -8.6726300000000001e-01 , 2.7771000000000001e-01 , -4.1319699999999998e-01 -1.5017422529345361e+00 , 8.0458507623824715e+00 , 6.1673216000000002e+00 , -5.3225699999999998e-01 , -2.9754700000000001e-01 , 7.9257100000000003e-01 -1.4740395473027181e+00 , 8.1322476704348041e+00 , 6.3478240000000001e+00 , 7.2263500000000003e-01 , 6.5172699999999995e-01 , -2.3032700000000000e-01 -1.2974626537748966e+00 , 9.0642884188715147e+00 , 7.0362103999999999e+00 , 9.0732400000000002e-01 , -2.1724599999999999e-01 , 3.5995300000000002e-01 -1.3135411110365998e+00 , 8.8786201104424958e+00 , 7.0825424000000003e+00 , -8.4000799999999998e-01 , 4.5694299999999999e-01 , 2.9255799999999998e-01 -1.9271460713110655e-01 , 1.5070062901908313e+01 , 1.1222626400000001e+01 , 8.1461399999999995e-01 , -3.6962000000000000e-01 , -4.4697199999999998e-01 -1.7498767604528642e-01 , 1.4983381242257195e+01 , 1.1484311199999999e+01 , -9.4545100000000004e-01 , 3.1713799999999998e-01 , 7.4467500000000006e-02 -1.3994981584542154e+00 , 8.1324816465402208e+00 , 7.0551176000000000e+00 , -5.1215500000000003e-01 , -4.6994700000000000e-01 , -7.1892100000000003e-01 -1.3650270436803447e+00 , 8.2282560039342556e+00 , 7.2754312000000008e+00 , 5.7521500000000003e-01 , -3.3526699999999998e-01 , 7.4613900000000000e-01 -1.2929510603342651e+00 , 8.5243084550456310e+00 , 7.6543344000000006e+00 , 4.5740199999999998e-01 , -8.6191600000000002e-01 , -2.1882299999999999e-01 -8.6547138178577288e-01 , 1.0652024413820094e+01 , 9.4752392000000007e+00 , 9.5872100000000005e-03 , -4.3586300000000000e-01 , 8.9996200000000004e-01 -1.3340402138966212e-01 , 1.4271513893021394e+01 , 1.2622040000000000e+01 , -8.7816099999999997e-01 , 3.8265100000000002e-01 , 2.8707400000000000e-01 -1.9980255254891577e-01 , 1.3753123959382505e+01 , 1.2540088000000001e+01 , -8.7816099999999997e-01 , 3.8265100000000002e-01 , 2.8707400000000000e-01 -1.9249673011717650e-01 , 1.3607432384869339e+01 , 1.2758904000000001e+01 , -8.7816099999999997e-01 , 3.8265100000000002e-01 , 2.8707400000000000e-01 -1.7876639536453953e-01 , 1.3496093217833103e+01 , 1.3009855999999999e+01 , 3.1334400000000001e-01 , -5.9773799999999999e-01 , 7.3791899999999999e-01 -1.7032938566625400e-01 , 1.3356751485181148e+01 , 1.3238968000000000e+01 , 3.1334400000000001e-01 , -5.9773799999999999e-01 , 7.3791899999999999e-01 -9.9420333586393062e-01 , 9.2840413204832153e+00 , 9.6907584000000000e+00 , 2.8952600000000001e-01 , -5.5634600000000001e-01 , -7.7888000000000002e-01 -1.0215212451320397e+00 , 9.0423198144108383e+00 , 9.6878880000000009e+00 , -2.2226299999999999e-01 , -1.4333000000000000e-02 , 9.7488100000000000e-01 -1.0157481739192264e+00 , 8.9530208482250337e+00 , 9.8337168000000013e+00 , -4.1341299999999997e-01 , 6.3857800000000006e-02 , 9.0830200000000005e-01 -1.0595167081206152e+00 , 8.6435156151535466e+00 , 9.7456600000000009e+00 , 6.2319899999999995e-01 , 1.1204000000000000e-01 , -7.7399600000000002e-01 -1.1205529621248949e+00 , 8.2626145858734681e+00 , 9.5651264000000005e+00 , 3.6522900000000003e-01 , -3.3517300000000000e-01 , -8.6848599999999998e-01 -1.1446607392776307e+00 , 8.0533078625506995e+00 , 9.5591359999999987e+00 , -3.1191300000000000e-01 , 4.0324800000000000e-01 , 8.6029100000000003e-01 -1.1426538872996992e+00 , 7.9581083097356515e+00 , 9.6817312000000015e+00 , -2.2244900000000001e-01 , -6.9574499999999995e-01 , -6.8297500000000000e-01 -1.1640176589473303e+00 , 7.7631757632097615e+00 , 9.6832392000000009e+00 , -4.0926000000000001e-03 , 3.2873000000000002e-01 , 9.4441500000000000e-01 -1.1746740814106520e+00 , 7.6142066023573118e+00 , 9.7366536000000004e+00 , 1.8700400000000000e-01 , -1.4240200000000000e-03 , 9.8235799999999995e-01 -1.1980294499416169e+00 , 7.4157833432029907e+00 , 9.7212719999999990e+00 , -4.0144000000000002e-01 , -5.0339699999999998e-01 , -7.6513900000000001e-01 -1.3559012512757671e+00 , 6.6931470132941282e+00 , 8.9772768000000003e+00 , -3.3749200000000001e-01 , 8.1978300000000004e-01 , -4.6266099999999999e-01 -1.2968023565991194e+00 , 6.8313838078211715e+00 , 9.3977904000000017e+00 , -2.1485299999999999e-01 , 9.7589800000000004e-01 , 3.8236399999999997e-02 -1.6584377365874172e+00 , 5.3788917289651756e+00 , 7.4885688000000004e+00 , 5.2122599999999998e-02 , 6.1382000000000003e-01 , 7.8772399999999998e-01 -1.6651295713523584e+00 , 5.2900608886591804e+00 , 7.5234192000000002e+00 , 7.1992700000000007e-02 , 5.5366199999999999e-01 , 8.2962400000000003e-01 -1.6630341393606065e+00 , 5.2280892844388749e+00 , 7.6001192000000009e+00 , 1.9649100000000000e-01 , 4.3885400000000002e-01 , 8.7681100000000001e-01 -1.3399853542423199e+00 , 6.2920946669541342e+00 , 9.5552152000000010e+00 , 8.4368500000000002e-01 , 4.0811700000000001e-01 , 3.4876400000000002e-01 -1.3775689785547316e+00 , 6.0690399363351997e+00 , 9.4363847999999990e+00 , 6.5481599999999995e-01 , 5.0799000000000005e-01 , 5.5960900000000002e-01 -1.8170303226495559e+00 , 4.5122439559854470e+00 , 6.8890088000000000e+00 , -2.2161000000000000e-01 , -3.6792599999999998e-01 , -9.0306100000000000e-01 -1.7878732831603255e+00 , 4.5516871849973546e+00 , 7.1259624000000006e+00 , -6.1602900000000005e-01 , -4.3733399999999999e-02 , 7.8650900000000001e-01 -1.8038227704756771e+00 , 4.4429475050224720e+00 , 7.0903320000000001e+00 , 6.9174899999999995e-01 , 3.3572500000000000e-01 , -6.3935299999999995e-01 -1.8932629724472148e+00 , 4.1108870284322201e+00 , 6.5891040000000007e+00 , 7.7767100000000000e-01 , 3.1516800000000000e-01 , -5.4396400000000000e-01 -1.9136855794701351e+00 , 4.0008787322946802e+00 , 6.5165224000000004e+00 , 5.6655699999999998e-01 , -1.3577800000000001e-01 , -8.1276000000000004e-01 -1.9186158598976768e+00 , 3.9364581042329645e+00 , 6.5351072000000006e+00 , -2.0475099999999999e-01 , 3.9456300000000000e-01 , 8.9576599999999995e-01 -1.9204946083590633e+00 , 3.8799717883518698e+00 , 6.5713720000000002e+00 , 8.6771699999999993e-02 , 6.4676900000000004e-01 , 7.5773400000000002e-01 -1.9191491125645479e+00 , 3.8335176904584722e+00 , 6.6356544000000008e+00 , 2.9274899999999998e-01 , 7.9441099999999998e-01 , 5.3217400000000004e-01 -1.9037013690946090e+00 , 3.8228308727521316e+00 , 6.7954191999999995e+00 , 7.4679600000000002e-01 , 6.4725299999999997e-01 , 1.5283900000000000e-01 -1.7912159351336800e+00 , 4.0478504776411715e+00 , 7.6247775999999998e+00 , -6.5476400000000001e-01 , -5.4733699999999996e-01 , -5.2125500000000002e-01 -1.7933539150786806e+00 , 3.9787571624663709e+00 , 7.6828096000000006e+00 , 3.8633899999999999e-01 , 4.8434199999999999e-01 , 7.8495599999999999e-01 -1.7497049580328765e+00 , 4.0117184853440104e+00 , 8.0637095999999993e+00 , 7.9964199999999996e-01 , 5.4801400000000000e-01 , -2.4546799999999999e-01 -1.7414579294951520e+00 , 3.9568405486235214e+00 , 8.2006464000000001e+00 , -9.8028999999999999e-01 , -1.9245499999999999e-01 , -4.4640600000000003e-02 -1.7821393058827366e+00 , 3.7969899203913702e+00 , 7.9798647999999996e+00 , 4.4527499999999998e-01 , -3.8146799999999997e-01 , 8.1006999999999996e-01 -1.9348518341993066e+00 , 3.4224799508709309e+00 , 6.9178063999999999e+00 , -2.1193300000000001e-01 , 5.9671399999999997e-01 , -7.7396200000000004e-01 -1.7753430572006468e+00 , 3.6639550744681708e+00 , 8.1877399999999998e+00 , -9.3204200000000004e-01 , -3.3535300000000001e-01 , 1.3724200000000000e-01 -1.9400352529662368e+00 , 3.2992379014089508e+00 , 7.0028888000000000e+00 , -5.5219600000000001e-02 , 8.3403499999999997e-01 , 5.4894100000000001e-01 -1.9450481411827825e+00 , 3.2320750225383579e+00 , 7.0290032000000000e+00 , 2.6744500000000001e-02 , -7.9621699999999995e-01 , 6.0441900000000004e-01 -1.7996201164210546e+00 , 3.3920003941258474e+00 , 8.2397191999999997e+00 , 6.6847000000000001e-01 , -6.7241300000000004e-01 , -3.1781900000000002e-01 -1.8085522668907412e+00 , 3.2996443668006417e+00 , 8.2470096000000002e+00 , 1.1425200000000001e-01 , 9.5959899999999998e-01 , -2.5713100000000000e-01 -2.5776563333629903e+00 , 4.0284126018842583e+00 , 7.2872479999999995e-01 , 9.8221600000000006e-02 , -9.1593499999999994e-02 , -9.9094099999999996e-01 -2.5743527927852963e+00 , 4.0990417707277125e+00 , 7.1492400000000011e-01 , -8.1953499999999999e-02 , 4.9355799999999998e-02 , 9.9541299999999999e-01 -2.5687414609423551e+00 , 4.1653511439144193e+00 , 7.1082639999999997e-01 , -4.9601100000000002e-02 , 9.7314999999999999e-02 , 9.9401700000000004e-01 -2.4168798673466361e+00 , 6.6427919767352499e+00 , 2.6824399999999993e-01 , -8.8998900000000006e-02 , 1.9745799999999999e-01 , 9.7626299999999999e-01 -2.4032211879736067e+00 , 6.8829740670457991e+00 , 2.1894799999999992e-01 , -7.7429799999999993e-02 , 1.9277900000000001e-01 , 9.7818300000000002e-01 -2.3879249600657815e+00 , 7.1183567582360219e+00 , 1.8231919999999979e-01 , -6.5858899999999998e-02 , 1.8133400000000000e-01 , 9.8121400000000003e-01 -2.3712641487012416e+00 , 7.3733488306176458e+00 , 1.4265359999999982e-01 , 4.9362299999999998e-02 , -1.7956300000000000e-01 , -9.8250700000000002e-01 -2.3534231281355744e+00 , 7.6758322976454751e+00 , 8.5453599999999907e-02 , -4.4249499999999997e-02 , 1.8202399999999999e-01 , 9.8229800000000000e-01 -2.3329275767142890e+00 , 8.0006242757741504e+00 , 2.7712799999999760e-02 , -2.6926700000000001e-02 , 1.7764300000000000e-01 , 9.8372700000000002e-01 -2.3113679079524485e+00 , 8.3565257654497049e+00 , -3.3907200000000248e-02 , -2.1560699999999999e-02 , 1.7977799999999999e-01 , 9.8347099999999998e-01 -2.2856026398987064e+00 , 8.7719118633357560e+00 , -1.1215680000000017e-01 , -2.3575200000000001e-02 , 1.9197800000000001e-01 , 9.8111599999999999e-01 -2.2570122607879313e+00 , 9.2570902984194898e+00 , -2.0825280000000035e-01 , -2.2456899999999998e-02 , 1.8393000000000001e-01 , 9.8268299999999997e-01 -2.2258856578594917e+00 , 9.7661398976061058e+00 , -2.9706879999999991e-01 , -3.4215299999999997e-02 , 1.8503600000000001e-01 , 9.8213600000000001e-01 -2.1902277589706625e+00 , 1.0346174644166236e+01 , -3.9819840000000006e-01 , -3.9410700000000000e-02 , 1.7738699999999999e-01 , 9.8335200000000000e-01 -2.1485418070392308e+00 , 1.1028396745137151e+01 , -5.2039839999999993e-01 , -4.2158099999999997e-02 , 1.8500800000000001e-01 , 9.8183200000000004e-01 -2.0985287999248468e+00 , 1.1851316297319025e+01 , -6.7338239999999994e-01 , -4.2912100000000002e-02 , 1.7570500000000000e-01 , 9.8350700000000002e-01 -2.0415519843611230e+00 , 1.2769993940795375e+01 , -8.3190959999999992e-01 , -5.8485299999999997e-02 , 1.8053000000000000e-01 , 9.8182899999999995e-01 -1.9734481890211746e+00 , 1.3862864454668477e+01 , -1.0191615999999999e+00 , -6.5638699999999994e-02 , 1.6916999999999999e-01 , 9.8339900000000002e-01 -1.8904046393129885e+00 , 1.5190510782960475e+01 , -1.2459752000000002e+00 , -6.1665600000000001e-02 , 1.8152900000000000e-01 , 9.8145000000000004e-01 -1.7858147016361956e+00 , 1.6885405012220616e+01 , -1.5413456000000001e+00 , -6.0007800000000000e-02 , 1.7984500000000000e-01 , 9.8186300000000004e-01 -1.6379432436185462e+00 , 1.9320699236465209e+01 , -1.9973024000000001e+00 , -7.0796200000000004e-02 , 1.8057000000000001e-01 , 9.8101099999999997e-01 -1.4854600210835418e+00 , 2.1674623257936332e+01 , -2.3415423999999998e+00 , -7.6192399999999993e-02 , 1.7438300000000001e-01 , 9.8172599999999999e-01 -7.9665654055832325e-01 , 3.1829871991545300e+01 , -3.5694704000000002e+00 , -4.7601599999999999e-01 , 2.9186100000000000e-02 , 8.7895299999999998e-01 -7.5075777097121632e-01 , 3.1621283429849342e+01 , -2.9916152000000000e+00 , -1.6939499999999999e-01 , 1.4437200000000000e-01 , 9.7491600000000000e-01 -1.4545363414453154e+00 , 1.3593940000495099e+01 , 3.9015152000000000e+00 , 5.5110300000000001e-02 , -9.5555900000000005e-01 , 2.8960200000000003e-01 -1.3757073552502379e+00 , 1.3745834883384868e+01 , 4.5120887999999999e+00 , -6.3272899999999999e-01 , 7.5681299999999996e-01 , -1.6397700000000001e-01 -1.3491211668889322e+00 , 1.3788834145580600e+01 , 4.7198600000000006e+00 , -6.7976700000000001e-01 , 6.4091399999999998e-01 , 3.5657499999999998e-01 -1.3052645785459536e+00 , 1.4002149287296216e+01 , 4.9575519999999997e+00 , -6.7781599999999997e-01 , 7.2169399999999995e-01 , -1.4043800000000001e-01 -1.3481220379401322e+00 , 1.3354089704832353e+01 , 5.0496232000000001e+00 , 4.8838900000000002e-01 , -8.4549399999999997e-01 , -2.1590999999999999e-01 -1.2407618770358981e+00 , 1.4190056206703845e+01 , 5.4129160000000001e+00 , -5.5882699999999996e-01 , 7.1544099999999999e-01 , -4.1935299999999998e-01 -1.1804466858334879e+00 , 1.4540001025843058e+01 , 5.7033047999999997e+00 , 7.7763199999999999e-01 , -4.4163200000000002e-01 , 4.4749299999999997e-01 -1.1958372676920774e+00 , 1.4167366786844688e+01 , 5.8390456000000004e+00 , -8.2980900000000002e-01 , 4.6078599999999997e-01 , -3.1479200000000002e-01 -1.3072286571732339e+00 , 1.2723328209064821e+01 , 5.8840360000000000e+00 , 1.2604199999999999e-01 , 8.7576299999999996e-01 , 4.6599600000000002e-01 -1.3125428913200878e+00 , 1.2491906967093751e+01 , 6.0118936000000005e+00 , -1.5345300000000001e-01 , 6.4220299999999997e-01 , 7.5101799999999996e-01 -1.2937935801998939e+00 , 1.2467297095031544e+01 , 6.1966079999999994e+00 , 2.0144200000000001e-01 , 6.5552500000000002e-01 , 7.2780999999999996e-01 -1.3633727997248017e+00 , 1.1692859153589275e+01 , 6.1358928000000006e+00 , 5.5039600000000000e-01 , -7.1726900000000005e-01 , 4.2730499999999999e-01 -1.3500124841210233e+00 , 1.1636796140930235e+01 , 6.2974775999999997e+00 , -2.3725700000000000e-01 , 8.4533700000000001e-01 , -4.7865900000000000e-01 -1.3351292088785722e+00 , 1.1596935940393140e+01 , 6.4653752000000004e+00 , -2.3725700000000000e-01 , 8.4533700000000001e-01 , -4.7865900000000000e-01 -1.2846921683170844e+00 , 1.1843393999840906e+01 , 6.7450520000000003e+00 , -1.0847400000000000e-01 , -9.1629200000000000e-01 , 3.8554200000000000e-01 -1.6328758027994636e+00 , 8.9070610451120285e+00 , 5.7371151999999999e+00 , 2.7467399999999999e-02 , -9.9892899999999996e-01 , -3.7235100000000000e-02 -1.6132440001339314e+00 , 8.9444558137234260e+00 , 5.8868960000000001e+00 , 2.7467399999999999e-02 , -9.9892899999999996e-01 , -3.7235100000000000e-02 -1.5870208922233744e+00 , 9.0344316119944779e+00 , 6.0643719999999997e+00 , 2.7467399999999999e-02 , -9.9892899999999996e-01 , -3.7234999999999997e-02 -1.5648588212459840e+00 , 9.0832302112643699e+00 , 6.2280680000000004e+00 , 2.0178499999999999e-01 , -9.5157800000000003e-01 , -2.3191200000000001e-01 -1.5767621529661153e+00 , 8.8779968346748124e+00 , 6.2713215999999994e+00 , 2.0178499999999999e-01 , -9.5157800000000003e-01 , -2.3191200000000001e-01 -1.5496157418918046e+00 , 8.9575453494809238e+00 , 6.4548088000000003e+00 , 1.5936700000000001e-01 , -9.7886099999999998e-01 , 1.2819200000000000e-01 -1.5020616202702857e+00 , 9.1871955177140503e+00 , 6.7254583999999999e+00 , -3.0123200000000000e-01 , 9.3418999999999996e-01 , -1.9117700000000001e-01 -1.6644360409428522e+00 , 7.9241356292385285e+00 , 6.1724072000000003e+00 , -7.5382600000000000e-01 , -6.2507500000000005e-01 , 2.0255600000000001e-01 -1.6294060457731634e+00 , 8.0731726616242447e+00 , 6.3881760000000005e+00 , 7.6024000000000003e-01 , 5.2114400000000005e-01 , -3.8787100000000002e-01 -1.5971085266298199e+00 , 8.1903347770168313e+00 , 6.5938567999999993e+00 , 8.3275200000000005e-01 , 4.2733900000000002e-01 , -3.5200100000000001e-01 -1.5547341880583285e+00 , 8.3709697690834552e+00 , 6.8489480000000000e+00 , -8.1998300000000002e-01 , -5.1594099999999998e-01 , 2.4785699999999999e-01 -1.5518641973295431e+00 , 8.2770914742637967e+00 , 6.9357776000000007e+00 , 8.6043700000000001e-01 , -2.6518999999999998e-01 , 4.3511300000000003e-01 -1.4946950600704474e+00 , 8.5401289572136179e+00 , 7.2646776000000006e+00 , 4.9312600000000001e-01 , -5.5709600000000004e-01 , 6.6818500000000003e-01 -1.4495818815387631e+00 , 8.7174922087938889e+00 , 7.5503760000000000e+00 , -2.1994600000000000e-01 , 9.6228000000000002e-01 , 1.6012899999999999e-01 -1.5885279267842496e+00 , 7.7396218234110448e+00 , 7.0006528000000001e+00 , 7.4144500000000002e-01 , -2.5410199999999999e-01 , -6.2104099999999995e-01 -1.4473503714706053e+00 , 8.4978906659211901e+00 , 7.7248152000000001e+00 , -1.4963899999999999e-01 , 8.8303699999999996e-01 , 4.4480799999999998e-01 -1.4400232790996821e+00 , 8.4308473955724192e+00 , 7.8437391999999999e+00 , 2.5076700000000002e-01 , -4.3627600000000000e-01 , -8.6416400000000004e-01 -1.4311047289608165e+00 , 8.3702835076389128e+00 , 7.9680816000000005e+00 , 2.8421500000000000e-01 , -2.9585099999999998e-01 , -9.1197300000000003e-01 -1.0008823469589312e+00 , 1.0726450792070777e+01 , 1.0147588800000001e+01 , -5.3733200000000003e-01 , 5.2288999999999997e-01 , -6.6171000000000002e-01 -1.4807734718469627e+00 , 7.8678895323500866e+00 , 7.8883863999999999e+00 , 3.5592600000000002e-01 , -7.6308399999999998e-03 , -9.3448299999999995e-01 -1.0768090612333223e+00 , 9.9910871884336530e+00 , 9.9975584000000008e+00 , -4.5954699999999998e-01 , -9.0983800000000004e-02 , 8.8348099999999996e-01 -1.5168685888681808e+00 , 7.4629911139890570e+00 , 7.8574983999999999e+00 , -6.8731799999999998e-01 , 2.4624900000000000e-01 , 6.8334099999999998e-01 -1.1587066933422088e+00 , 9.2631841373913524e+00 , 9.7909936000000002e+00 , -5.1557900000000001e-01 , -1.3713200000000000e-02 , 8.5673200000000005e-01 -1.1669032353980815e+00 , 9.0860627025830247e+00 , 9.8517399999999995e+00 , -4.4545099999999999e-01 , -2.0539700000000001e-02 , 8.9507099999999995e-01 -1.2070802766203008e+00 , 8.7447376725591539e+00 , 9.7366951999999998e+00 , -6.0741999999999996e-01 , -2.2593400000000000e-01 , 7.6157399999999997e-01 -1.2688664094121545e+00 , 8.3053705927283978e+00 , 9.4980983999999999e+00 , -2.5136999999999998e-01 , 4.2453200000000002e-01 , 8.6981900000000001e-01 -1.2767203387637751e+00 , 8.1438953739119508e+00 , 9.5468016000000002e+00 , -2.6319599999999999e-01 , 3.3410299999999998e-01 , 9.0504300000000004e-01 -1.2822984745814026e+00 , 7.9955734141832355e+00 , 9.6076000000000015e+00 , -1.4498100000000000e-01 , 3.2528699999999999e-01 , 9.3443500000000002e-01 -1.2890895961041329e+00 , 7.8396448110792063e+00 , 9.6572911999999995e+00 , -9.3678600000000001e-02 , 3.6768600000000001e-01 , 9.2522000000000004e-01 -1.5527220495458007e+00 , 6.5153703727469940e+00 , 8.2370464000000005e+00 , 1.6739399999999999e-01 , 8.2554799999999995e-01 , -5.3893400000000002e-01 -1.3198909930905520e+00 , 7.4601596664144711e+00 , 9.6565528000000000e+00 , 3.2245200000000002e-01 , 5.2798599999999996e-01 , 7.8565600000000002e-01 -1.4631937550330645e+00 , 6.7175809961093931e+00 , 8.9001087999999999e+00 , 4.0361799999999998e-01 , -8.9932800000000002e-01 , 1.6823199999999999e-01 -1.2365448572410047e+00 , 7.5793255288231940e+00 , 1.0325096000000000e+01 , 9.0589200000000003e-01 , 4.2338399999999998e-01 , 1.0239399999999999e-02 -1.7303036843668744e+00 , 5.4011636442062576e+00 , 7.4352480000000005e+00 , 6.7834599999999995e-02 , 4.3688600000000000e-01 , 8.9695499999999995e-01 -1.7299609149192741e+00 , 5.3295512666763916e+00 , 7.4960776000000005e+00 , -6.3478900000000005e-02 , -5.6233400000000000e-01 , -8.2447000000000004e-01 -1.7346221306119243e+00 , 5.2345255189330206e+00 , 7.5208504000000005e+00 , 1.6359599999999999e-01 , 4.5019599999999999e-01 , 8.7781500000000001e-01 -1.3682761200715645e+00 , 6.5660782039771401e+00 , 9.8723632000000006e+00 , 7.1370900000000004e-01 , -2.0651300000000000e-01 , -6.6930699999999999e-01 -1.8498892139852356e+00 , 4.6529389424995795e+00 , 6.8986704000000003e+00 , 2.4024600000000000e-02 , -9.2054199999999997e-01 , 3.8990500000000000e-01 -1.8319822582322116e+00 , 4.6561322327869235e+00 , 7.0635208000000000e+00 , 6.0270800000000002e-01 , 7.2855300000000001e-01 , 3.2550600000000002e-01 -1.8414460579356544e+00 , 4.5570713776968672e+00 , 7.0482120000000004e+00 , -8.5662600000000000e-01 , 4.8291000000000001e-01 , -1.8163000000000001e-01 -1.8315733002996941e+00 , 4.5245725507061589e+00 , 7.1588471999999994e+00 , 7.7186399999999999e-01 , 3.5745500000000001e-03 , -6.3577799999999995e-01 -1.8528588363444238e+00 , 4.3882634265927365e+00 , 7.0665680000000002e+00 , 7.2087400000000001e-01 , 6.3098900000000002e-01 , -2.8669200000000000e-01 -1.9334413482104185e+00 , 4.0650719889339904e+00 , 6.5705816000000006e+00 , -7.3009999999999997e-01 , -2.7463300000000002e-01 , 6.2572399999999995e-01 -1.9456716655510300e+00 , 3.9743183472431935e+00 , 6.5337968000000002e+00 , -2.2902400000000001e-01 , 3.7354599999999999e-01 , 8.9889500000000000e-01 -1.9485775170615216e+00 , 3.9087657634926765e+00 , 6.5516328000000001e+00 , 1.2546499999999999e-01 , -4.8285600000000001e-01 , -8.6666500000000002e-01 -1.9483589160069583e+00 , 3.8552605930166806e+00 , 6.5969768000000002e+00 , 1.2919900000000001e-01 , 7.1721199999999996e-01 , 6.8477299999999997e-01 -1.9417458615690786e+00 , 3.8159520276898817e+00 , 6.6797816000000001e+00 , -4.7187099999999998e-01 , -7.9137599999999997e-01 , -3.8866699999999998e-01 -1.9240763763177682e+00 , 3.8062792309384079e+00 , 6.8493536000000006e+00 , 7.7378499999999995e-01 , 5.5551899999999999e-01 , 3.0439300000000002e-01 -1.7200717744251239e+00 , 4.2672643848837968e+00 , 8.3718615999999990e+00 , -9.5412600000000003e-01 , 4.5460199999999999e-02 , 2.9593399999999997e-01 -1.8199713361307353e+00 , 3.9406030863887400e+00 , 7.6993872000000003e+00 , 5.6315099999999996e-01 , 5.8379899999999996e-01 , 5.8484199999999997e-01 -1.7492089577048058e+00 , 4.0314402679083354e+00 , 8.2774399999999986e+00 , -3.5919699999999999e-01 , -7.0124600000000004e-01 , 6.1581799999999998e-01 -1.7626057446152426e+00 , 3.9196151411387827e+00 , 8.2364847999999995e+00 , 1.8151800000000001e-01 , -3.1828499999999998e-01 , 9.3045500000000003e-01 -1.9252269403996374e+00 , 3.5011658590871972e+00 , 7.0691160000000002e+00 , 6.8285399999999996e-01 , -4.7722199999999998e-01 , 5.5314600000000003e-01 -1.9544214725344387e+00 , 3.3795864230244299e+00 , 6.8882496000000000e+00 , 6.6012899999999997e-01 , -1.6528000000000001e-02 , 7.5097100000000006e-01 -1.9538799427245594e+00 , 3.3200733382160399e+00 , 6.9353304000000007e+00 , -7.4781500000000002e-03 , -3.2738699999999998e-01 , 9.4486099999999995e-01 -1.9627749402875199e+00 , 3.2436270656048753e+00 , 6.9109007999999994e+00 , 4.8309200000000002e-01 , -3.6315599999999998e-01 , 7.9670600000000003e-01 -1.7943870802058584e+00 , 3.4504596432141081e+00 , 8.2915944000000010e+00 , 1.6428400000000001e-01 , -9.6597400000000000e-01 , 1.9976400000000000e-01 -1.8237900040505677e+00 , 3.3237334150124234e+00 , 8.1168431999999999e+00 , -2.0998000000000000e-01 , -7.4008499999999999e-01 , 6.3889200000000002e-01 -1.8116561310042367e+00 , 3.2585384273629039e+00 , 8.2755367999999994e+00 , 4.0714400000000001e-01 , -9.1321300000000005e-01 , 1.6617500000000000e-02 -2.6367317535736232e+00 , 4.0002125525965937e+00 , 7.3841760000000001e-01 , 1.5085799999999999e-01 , -9.1479099999999994e-02 , -9.8431400000000002e-01 -2.6334394940614128e+00 , 4.0649440008882438e+00 , 7.3223999999999978e-01 , -1.0731800000000000e-01 , 1.3141200000000000e-01 , 9.8550199999999999e-01 -2.6309979928946996e+00 , 4.1299752447221687e+00 , 7.2771600000000003e-01 , -9.4511399999999995e-02 , 1.3098399999999999e-01 , 9.8686900000000000e-01 -2.6284644591157451e+00 , 4.2021506113134848e+00 , 7.1647360000000004e-01 , 5.1640100000000001e-02 , -1.0627700000000000e-01 , -9.9299499999999996e-01 -2.6257416616670000e+00 , 4.2757307795218615e+00 , 7.0693679999999981e-01 , -9.5821100000000006e-02 , 1.6386899999999999e-01 , 9.8181700000000005e-01 -2.6239250966725676e+00 , 4.3623770402639215e+00 , 6.8337040000000004e-01 , -9.0347600000000000e-02 , 1.8807499999999999e-01 , 9.7799000000000003e-01 -2.5671335268612410e+00 , 6.1629947704571926e+00 , 3.6431919999999995e-01 , -9.7103099999999998e-02 , 1.8151500000000001e-01 , 9.7858199999999995e-01 -2.5605168935152482e+00 , 6.3462940298572370e+00 , 3.3455439999999981e-01 , -9.0999800000000006e-02 , 1.8521799999999999e-01 , 9.7847499999999998e-01 -2.5541134061322293e+00 , 6.5401631278784933e+00 , 3.0465439999999999e-01 , -8.0867900000000006e-02 , 1.9470000000000001e-01 , 9.7752399999999995e-01 -2.5474722547630884e+00 , 6.7626351637906312e+00 , 2.6380320000000013e-01 , -7.9737799999999998e-02 , 2.0660400000000001e-01 , 9.7516999999999998e-01 -2.5394219648138501e+00 , 7.0139926326124931e+00 , 2.1318640000000011e-01 , -6.0448300000000003e-02 , 1.8668699999999999e-01 , 9.8055800000000004e-01 -2.5315210958384502e+00 , 7.2690625893888914e+00 , 1.7047359999999978e-01 , -5.3495200000000000e-02 , 1.7926400000000001e-01 , 9.8234500000000002e-01 -2.5218882313020137e+00 , 7.5524644026215215e+00 , 1.2042880000000000e-01 , -4.2819500000000003e-02 , 1.7776600000000001e-01 , 9.8314100000000004e-01 -2.5125503192736129e+00 , 7.8674952895500097e+00 , 6.4091999999999816e-02 , -3.9369700000000001e-02 , 1.7754200000000001e-01 , 9.8332500000000000e-01 -2.5019303264283557e+00 , 8.2221443929751938e+00 , -1.4280000000002069e-03 , -4.3438200000000003e-02 , 1.7830199999999999e-01 , 9.8301700000000003e-01 -2.4892760987210809e+00 , 8.5715953392609538e+00 , -5.1046400000000158e-02 , -5.5999800000000002e-02 , 1.8602600000000000e-01 , 9.8094800000000004e-01 -2.4749020010917668e+00 , 9.0269508403394649e+00 , -1.3931120000000030e-01 , -5.8296199999999999e-02 , 1.9715199999999999e-01 , 9.7863800000000001e-01 -2.4595572273264894e+00 , 9.5253090897766466e+00 , -2.3036320000000021e-01 , -6.0852099999999999e-02 , 1.8873000000000001e-01 , 9.8014199999999996e-01 -2.4425997095462000e+00 , 1.0075909909650802e+01 , -3.2599120000000026e-01 , -6.2797400000000003e-02 , 1.8765399999999999e-01 , 9.8022600000000004e-01 -2.4215350608893491e+00 , 1.0707705253301643e+01 , -4.3587759999999998e-01 , 6.3387200000000005e-02 , -1.8649199999999999e-01 , -9.8041000000000000e-01 -2.3977570500677903e+00 , 1.1481505784458303e+01 , -5.7936640000000006e-01 , -6.0059500000000002e-02 , 1.8750400000000000e-01 , 9.8042600000000002e-01 -2.3701321452638098e+00 , 1.2329772828193759e+01 , -7.2298000000000018e-01 , -6.8416800000000000e-02 , 1.7429500000000001e-01 , 9.8231400000000002e-01 -2.3369956221170241e+00 , 1.3351333619835952e+01 , -8.9842800000000000e-01 , -7.1316199999999996e-02 , 1.7429100000000000e-01 , 9.8210799999999998e-01 -2.2994205149346261e+00 , 1.4461534705356259e+01 , -1.0668456000000002e+00 , -6.7228099999999999e-02 , 1.7288300000000001e-01 , 9.8264499999999999e-01 -2.2487339829317947e+00 , 1.6044262017640904e+01 , -1.3486336000000003e+00 , -6.2705300000000005e-02 , 1.8007799999999999e-01 , 9.8165199999999997e-01 -2.1864263976079217e+00 , 1.7977572913614726e+01 , -1.6798112000000001e+00 , -6.7899600000000004e-02 , 1.8576599999999999e-01 , 9.8024500000000003e-01 -1.9984587120190018e+00 , 2.3665766666708915e+01 , -2.6211256000000001e+00 , 2.3101300000000000e-01 , -1.9534000000000001e-01 , -9.5313999999999999e-01 -1.8762630537200364e+00 , 2.6947971715905851e+01 , -3.0475776000000003e+00 , -1.7222700000000001e-02 , -1.4562400000000000e-02 , 9.9974600000000002e-01 -1.7838908401677871e+00 , 2.8568302936308672e+01 , -2.9724896000000003e+00 , -2.6214700000000001e-02 , 7.6417100000000002e-02 , 9.9673100000000003e-01 -1.7459675380049047e+00 , 2.7956183096058986e+01 , -2.3662736000000004e+00 , -3.0168299999999998e-01 , 1.0690000000000000e-01 , 9.4739700000000004e-01 -1.6474847770664818e+00 , 1.4267091142977664e+01 , 4.7172807999999993e+00 , 5.5285300000000004e-01 , -7.9481199999999996e-01 , 2.5025700000000001e-01 -1.6165477448500862e+00 , 1.4379138388537928e+01 , 4.9455504000000001e+00 , -6.0092100000000004e-01 , 6.5481800000000001e-01 , -4.5837499999999998e-01 -1.5349498215754862e+00 , 1.5171301913692369e+01 , 5.2970912000000006e+00 , -7.2016000000000002e-01 , 4.6146700000000002e-01 , -5.1809099999999997e-01 -1.4922832369058054e+00 , 1.5393665846004392e+01 , 5.5695088000000004e+00 , 6.7819300000000005e-01 , -4.8914400000000002e-01 , 5.4844499999999996e-01 -1.4611601125573668e+00 , 1.5447948678330565e+01 , 5.8162280000000006e+00 , 7.2191000000000005e-01 , -4.8805900000000002e-01 , 4.9055500000000002e-01 -1.5044901392491963e+00 , 1.4547961195299914e+01 , 5.8487904000000004e+00 , -7.5712599999999997e-01 , 4.0374599999999999e-01 , -5.1356500000000005e-01 -1.3596920481396109e+00 , 1.6026400612477524e+01 , 6.4365047999999998e+00 , 5.9206199999999998e-01 , -7.8991000000000000e-01 , 1.5970100000000001e-01 -1.3360432067575365e+00 , 1.5963561718790208e+01 , 6.6730007999999996e+00 , -8.2576499999999997e-01 , -5.6332400000000005e-01 , 2.7894700000000001e-02 -1.5840617936477916e+00 , 1.2424054514127931e+01 , 6.1124407999999999e+00 , -1.6163400000000000e-01 , -7.4828300000000003e-01 , -6.4338700000000004e-01 -1.5752476350356741e+00 , 1.2279553409616303e+01 , 6.2576664000000006e+00 , -1.7835100000000001e-01 , 7.1832200000000002e-01 , 6.7246099999999998e-01 -1.5726647477425089e+00 , 1.2064475428940385e+01 , 6.3754360000000005e+00 , 8.2413599999999998e-01 , -5.2821899999999999e-01 , -2.0441200000000001e-01 -1.5664914855354783e+00 , 1.1897418984436250e+01 , 6.5041359999999999e+00 , -8.0859000000000003e-01 , 5.5140100000000003e-01 , 2.0527899999999999e-01 -1.5296693414851510e+00 , 1.2057553176165115e+01 , 6.7535384000000001e+00 , -2.6835700000000001e-03 , 9.2774599999999996e-01 , 3.7320100000000000e-01 -1.5159672311716965e+00 , 1.1971400876928019e+01 , 6.9132823999999999e+00 , 1.1276899999999999e-01 , 9.7937500000000000e-01 , 1.6765200000000000e-01 -1.4977075671911508e+00 , 1.1929508584963537e+01 , 7.0914656000000003e+00 , -4.0818100000000002e-01 , -8.9999499999999999e-01 , 1.5296100000000001e-01 -1.4777446406410979e+00 , 1.1904132736199067e+01 , 7.2774695999999999e+00 , -6.5999200000000002e-01 , -7.3894899999999997e-01 , 1.3552000000000000e-01 -1.4573247886213787e+00 , 1.1885041789972837e+01 , 7.4682160000000009e+00 , -1.5096699999999999e-01 , -9.6304599999999996e-01 , 2.2305200000000000e-01 -1.7427824276791712e+00 , 9.0104547103036303e+00 , 6.2790384000000001e+00 , 4.7676200000000002e-01 , -8.7148199999999998e-01 , -1.1496400000000000e-01 -1.7282548026722688e+00 , 8.9890988208045037e+00 , 6.4123768000000005e+00 , 4.6025199999999999e-01 , -8.7345700000000004e-01 , 1.5887299999999999e-01 -1.5202446200450592e+00 , 1.0695563661083762e+01 , 7.4594072000000002e+00 , -8.1909699999999996e-01 , -6.0672900000000002e-02 , 5.7043699999999997e-01 -1.6904230416326484e+00 , 9.0302005074268443e+00 , 6.7295351999999999e+00 , -4.4514399999999998e-01 , 8.5716099999999995e-01 , -2.5907999999999998e-01 -1.8070302310388193e+00 , 7.8874722958581396e+00 , 6.2264040000000005e+00 , 7.3336999999999997e-01 , 6.3068299999999999e-01 , -2.5378499999999998e-01 -1.7981354167840899e+00 , 7.8401139552668608e+00 , 6.3267432000000001e+00 , -7.3336999999999997e-01 , -6.3068299999999999e-01 , 2.5378499999999998e-01 -1.7148508506508084e+00 , 8.3972935625783975e+00 , 6.8029488000000002e+00 , -1.0923200000000000e-01 , 8.7090500000000004e-01 , 4.7915900000000000e-01 -1.7145768036792353e+00 , 8.2605297469775341e+00 , 6.8619479999999999e+00 , -5.4126099999999999e-01 , -4.3201400000000001e-01 , -7.2138800000000003e-01 -1.6955492620963637e+00 , 8.2785324127616473e+00 , 7.0210472000000008e+00 , 7.8631499999999999e-01 , 1.2483800000000000e-01 , 6.0508200000000001e-01 -1.7158095083841611e+00 , 7.9955339750032817e+00 , 6.9751935999999999e+00 , 2.2475300000000000e-02 , 1.8686300000000000e-01 , 9.8212900000000003e-01 -1.7333901315033029e+00 , 7.7421290788614296e+00 , 6.9386375999999998e+00 , -5.2458899999999997e-01 , 3.9867200000000003e-01 , 7.5224199999999997e-01 -1.7350787799860150e+00 , 7.6063149205731415e+00 , 6.9816416000000006e+00 , 7.6432900000000004e-01 , -3.0814599999999998e-01 , -5.6643500000000002e-01 -1.7526493705223860e+00 , 7.3653765314112611e+00 , 6.9384399999999999e+00 , 7.5414099999999995e-01 , -1.3168400000000000e-01 , -6.4337400000000000e-01 -1.7205307843068818e+00 , 7.4733535039589611e+00 , 7.1670943999999999e+00 , 7.5414099999999995e-01 , -1.3168400000000000e-01 , -6.4337400000000000e-01 -1.5967849265103489e+00 , 8.2014218917358654e+00 , 7.9242559999999997e+00 , -1.0403100000000000e-01 , 1.6767199999999999e-01 , 9.8033899999999996e-01 -1.6140206830320007e+00 , 7.9512154370619070e+00 , 7.8823960000000008e+00 , 1.2501499999999999e-01 , -7.5819700000000004e-02 , -9.8925399999999997e-01 -1.5926989293892964e+00 , 7.9651663479301700e+00 , 8.0683480000000003e+00 , -1.4504600000000001e-01 , 2.6534099999999999e-01 , 9.5318199999999997e-01 -1.6299327604605274e+00 , 7.5960579752163921e+00 , 7.9043919999999996e+00 , 5.8697800000000000e-01 , -3.4785899999999997e-01 , -7.3106199999999999e-01 -1.6337656642338267e+00 , 7.4506081427301671e+00 , 7.9369128000000000e+00 , 4.8793100000000000e-01 , 5.7995900000000003e-02 , -8.7095400000000001e-01 -1.3171039733903966e+00 , 9.2440816408912596e+00 , 9.8986023999999997e+00 , -4.4545099999999999e-01 , -2.0539900000000000e-02 , 8.9507099999999995e-01 -1.3566961561968442e+00 , 8.8426511090964528e+00 , 9.7275847999999989e+00 , -1.9418700000000000e-01 , -4.2419800000000002e-01 , 8.8450399999999996e-01 -1.3330418065477350e+00 , 8.8226498211652178e+00 , 9.9447576000000009e+00 , -2.4423200000000000e-01 , -2.1269700000000000e-01 , 9.4610300000000003e-01 -1.4011904203864138e+00 , 8.2854290114792200e+00 , 9.5959624000000012e+00 , -2.3809900000000001e-01 , 2.7184100000000000e-01 , 9.3242199999999997e-01 -1.4074830918491332e+00 , 8.1020004126103906e+00 , 9.6197264000000011e+00 , -3.4265499999999999e-01 , 3.5696000000000000e-01 , 8.6900299999999997e-01 -1.4117823625394703e+00 , 7.9395923983307437e+00 , 9.6630736000000006e+00 , -2.9216700000000001e-01 , 3.1339299999999998e-01 , 9.0356199999999998e-01 -1.4554466997421389e+00 , 7.5690710036024367e+00 , 9.4460776000000006e+00 , -4.4059900000000002e-01 , -8.5975900000000005e-01 , -2.5823900000000000e-01 -1.6054242372761980e+00 , 6.6799950135782504e+00 , 8.5436384000000007e+00 , -8.2170600000000005e-01 , 5.4272699999999996e-01 , -1.7391699999999999e-01 -1.5265564295027061e+00 , 6.9501686848318984e+00 , 9.1035848000000001e+00 , 1.5215500000000000e-02 , 9.7304800000000002e-01 , -2.3010200000000000e-01 -1.4104550602634300e+00 , 7.3829929727524233e+00 , 9.9252991999999995e+00 , 5.7213599999999998e-01 , 8.1912099999999999e-01 , -4.1257200000000001e-02 -1.5613622510363729e+00 , 6.5453697051523774e+00 , 8.9886128000000003e+00 , -3.5408200000000001e-01 , 1.7884100000000000e-02 , -9.3504299999999996e-01 -1.7948627813900995e+00 , 5.3728973120773915e+00 , 7.4773472000000005e+00 , -1.2737499999999999e-01 , -4.5403800000000000e-01 , -8.8183100000000003e-01 -1.4985629540176553e+00 , 6.5870979985270708e+00 , 9.5196056000000002e+00 , -3.8504300000000002e-01 , 9.1986400000000001e-01 , -7.4774800000000002e-02 -1.8000250253489389e+00 , 5.1779064565905788e+00 , 7.5172727999999998e+00 , 1.8313900000000000e-01 , 3.0585800000000002e-01 , 9.3429700000000004e-01 -1.9083629972246272e+00 , 4.6470390855454635e+00 , 6.8133488000000000e+00 , 3.5694599999999999e-01 , 4.6129900000000001e-01 , 8.1227600000000000e-01 -1.9026485957881456e+00 , 4.6017792253357772e+00 , 6.8878752000000008e+00 , 1.3001199999999999e-01 , 4.8202099999999998e-01 , 8.6646000000000001e-01 -1.9009718487101175e+00 , 4.5341092121760713e+00 , 6.9258144000000001e+00 , -7.6477700000000004e-01 , -7.5220899999999993e-02 , -6.3988900000000004e-01 -1.9066273573833794e+00 , 4.4418317833550809e+00 , 6.9169951999999997e+00 , 1.5951399999999999e-01 , 7.2393600000000002e-01 , 6.7117199999999999e-01 -1.8939159569082069e+00 , 4.4212791332787571e+00 , 7.0441768000000007e+00 , 6.2827599999999995e-01 , 7.5173500000000004e-01 , 2.0041100000000001e-01 -1.7701784302699444e+00 , 4.7800363405319732e+00 , 7.9604584000000003e+00 , 6.7715800000000004e-01 , -6.6276700000000000e-01 , 3.1968099999999999e-01 -1.9621163228732084e+00 , 4.0497889843791661e+00 , 6.6167784000000003e+00 , 7.5985499999999995e-01 , 3.1233100000000003e-01 , -5.7014900000000002e-01 -1.9745211121459210e+00 , 3.9456895781518249e+00 , 6.5506968000000008e+00 , -2.0560600000000001e-01 , 4.0222799999999997e-01 , 8.9215400000000000e-01 -1.9764553238441991e+00 , 3.8800461485003455e+00 , 6.5679088000000005e+00 , -1.5200300000000000e-01 , 5.6468799999999997e-01 , 8.1118599999999996e-01 -1.9731505080783547e+00 , 3.8305632188371153e+00 , 6.6219887999999996e+00 , 1.6867399999999999e-01 , 7.6677499999999998e-01 , 6.1935899999999999e-01 -1.9655205046944220e+00 , 3.7901571397384108e+00 , 6.7043775999999999e+00 , 3.6558000000000002e-01 , 8.1994999999999996e-01 , 4.4049300000000002e-01 -1.9489959461512107e+00 , 3.7712085056278903e+00 , 6.8545119999999997e+00 , -7.8330900000000003e-01 , -5.0439000000000001e-01 , -3.6334200000000000e-01 -1.8909878108517182e+00 , 3.8583172434520359e+00 , 7.3271920000000001e+00 , -6.6569100000000006e-02 , -4.0547000000000000e-01 , 9.1168099999999996e-01 -1.7747902122055725e+00 , 4.0727899186655625e+00 , 8.2457303999999993e+00 , -6.7712200000000000e-01 , 7.3573000000000000e-01 , -1.4405899999999999e-02 -1.7622039556519826e+00 , 4.0139762579715299e+00 , 8.3832807999999996e+00 , 4.8221300000000000e-01 , -8.6232200000000003e-01 , 1.5450400000000000e-01 -1.9213052143942009e+00 , 3.5734312285225487e+00 , 7.1898080000000002e+00 , 3.2963999999999999e-01 , -9.3952000000000002e-01 , 9.2952099999999996e-02 -1.9596870419424781e+00 , 3.4241079975144624e+00 , 6.9206143999999998e+00 , 7.5935399999999997e-01 , -3.5734399999999999e-01 , 5.4377100000000000e-01 -1.9639177142527391e+00 , 3.3522554348871161e+00 , 6.9179936000000000e+00 , -5.6539499999999998e-01 , 4.4695000000000001e-01 , 6.9322700000000004e-01 -1.9648757560708576e+00 , 3.2843448786270266e+00 , 6.9342696000000004e+00 , -4.0895100000000001e-01 , -5.1966999999999997e-01 , 7.5013500000000000e-01 -1.9586577279677790e+00 , 3.2308014432435952e+00 , 7.0202880000000007e+00 , 6.7741099999999999e-02 , -8.8372600000000001e-01 , 4.6307700000000002e-01 -1.8099859337931496e+00 , 3.3928282664549343e+00 , 8.2407696000000001e+00 , 3.2815400000000000e-01 , 6.8749199999999999e-01 , -6.4781900000000003e-01 -1.8135961812068806e+00 , 3.3026405623124231e+00 , 8.2576800000000006e+00 , 1.1425200000000001e-01 , 9.5959899999999998e-01 , -2.5713100000000000e-01 -2.6924878221680069e+00 , 4.0346161549617285e+00 , 7.4183920000000003e-01 , -1.0204600000000000e-01 , 9.8423099999999999e-02 , 9.8989899999999997e-01 -2.6921945317536875e+00 , 4.0994567827582955e+00 , 7.3685759999999978e-01 , -1.0157600000000000e-01 , 1.1945200000000000e-01 , 9.8763000000000001e-01 -2.6918297046021800e+00 , 4.1714032419358649e+00 , 7.2494959999999997e-01 , 8.6710599999999999e-02 , -1.4428199999999999e-01 , -9.8573000000000000e-01 -2.6901572185875233e+00 , 4.2379698709769293e+00 , 7.2297359999999999e-01 , -7.0788199999999996e-02 , 1.7145800000000000e-01 , 9.8264499999999999e-01 -2.6915619642637210e+00 , 4.3243246980845385e+00 , 6.9866880000000009e-01 , -6.5165299999999995e-02 , 1.7260700000000001e-01 , 9.8283299999999996e-01 -2.6894931896677083e+00 , 4.3926892351989739e+00 , 7.0023919999999995e-01 , -9.1820899999999997e-02 , 1.7185300000000001e-01 , 9.8083399999999998e-01 -2.6904176247238576e+00 , 4.4809947226533042e+00 , 6.8018800000000001e-01 , -1.1046900000000000e-01 , 1.7261399999999999e-01 , 9.7877499999999995e-01 -2.6890322023537188e+00 , 4.5649906071432982e+00 , 6.6994400000000009e-01 , -7.4251100000000000e-02 , 2.1228400000000000e-01 , 9.7438300000000000e-01 -2.6894655263378766e+00 , 4.6633093238147669e+00 , 6.4679359999999986e-01 , -9.1223200000000004e-02 , 2.1751699999999999e-01 , 9.7178399999999998e-01 -2.6906475408019754e+00 , 4.7701841345580238e+00 , 6.1887999999999987e-01 , -1.1015800000000001e-01 , 2.1247300000000000e-01 , 9.7093799999999997e-01 -2.6902996201390375e+00 , 5.3360580163674705e+00 , 5.1820799999999978e-01 , 1.0767599999999999e-01 , -2.1518000000000001e-01 , -9.7062000000000004e-01 -2.6883309213762119e+00 , 5.4521416401809155e+00 , 5.0896240000000015e-01 , -1.0731400000000001e-01 , 2.0045800000000000e-01 , 9.7380699999999998e-01 -2.6886823498475474e+00 , 5.6006999334143437e+00 , 4.7693039999999987e-01 , -8.5099499999999995e-02 , 1.8284100000000000e-01 , 9.7945300000000002e-01 -2.6886864368160648e+00 , 5.7440093933335579e+00 , 4.5567279999999988e-01 , -9.1466000000000006e-02 , 1.8913900000000000e-01 , 9.7768100000000002e-01 -2.6879693284956314e+00 , 5.9057958843280058e+00 , 4.2580400000000007e-01 , -8.2228099999999998e-02 , 1.9473299999999999e-01 , 9.7740400000000005e-01 -2.6868040677122917e+00 , 6.0603181401053110e+00 , 4.0721919999999989e-01 , 9.2046199999999995e-02 , -1.9245899999999999e-01 , -9.7697800000000001e-01 -2.6867570527897207e+00 , 6.2428268222917671e+00 , 3.7497920000000007e-01 , -8.4537000000000001e-02 , 1.8476899999999999e-01 , 9.7913899999999998e-01 -2.6858610831893261e+00 , 6.4349154033897475e+00 , 3.4267680000000000e-01 , -7.5551900000000005e-02 , 1.7774599999999999e-01 , 9.8117200000000004e-01 -2.6851487753153371e+00 , 6.6387138909489352e+00 , 3.1055119999999992e-01 , -7.6002200000000006e-02 , 1.9261000000000000e-01 , 9.7832799999999998e-01 -2.6858347442559269e+00 , 6.8890620678358729e+00 , 2.5678320000000010e-01 , -6.1839800000000000e-02 , 2.1459900000000001e-01 , 9.7474300000000003e-01 -2.6863957048436808e+00 , 7.1506012851298353e+00 , 2.0582319999999976e-01 , -5.8406899999999998e-02 , 1.8952600000000000e-01 , 9.8013700000000004e-01 -2.6858246300985855e+00 , 7.4254725551571612e+00 , 1.5753599999999990e-01 , -5.1653699999999997e-02 , 1.8438499999999999e-01 , 9.8149600000000004e-01 -2.6847264244970228e+00 , 7.7202715277580456e+00 , 1.0795920000000003e-01 , -6.0334499999999999e-02 , 1.7401400000000000e-01 , 9.8289300000000002e-01 -2.6840966516572906e+00 , 8.0372586493224567e+00 , 5.7903999999999956e-02 , -6.3449000000000005e-02 , 1.8197099999999999e-01 , 9.8125499999999999e-01 -2.6829060704051155e+00 , 8.4035499566029337e+00 , -5.8063999999999893e-03 , -5.7427400000000003e-02 , 1.8006600000000000e-01 , 9.8197699999999999e-01 -2.6822202895094573e+00 , 8.8109571321928630e+00 , -7.6141600000000143e-02 , 5.4205900000000001e-02 , -1.8882499999999999e-01 , -9.8051400000000000e-01 -2.6818384215445419e+00 , 9.2880587343890166e+00 , -1.6413600000000006e-01 , 6.6390199999999996e-02 , -1.8716300000000000e-01 , -9.8008300000000004e-01 -2.6813806301018723e+00 , 9.8084081294308820e+00 , -2.5360719999999981e-01 , -6.8710099999999996e-02 , 1.8890299999999999e-01 , 9.7958900000000004e-01 -2.6804556092478968e+00 , 1.0429058440826873e+01 , -3.6703999999999981e-01 , -7.0178000000000004e-02 , 1.8240799999999999e-01 , 9.8071500000000000e-01 -2.6784213359827556e+00 , 1.1074654430525296e+01 , -4.6759759999999995e-01 , -8.1211900000000004e-02 , 1.7882200000000001e-01 , 9.8052399999999995e-01 -2.6766354424537626e+00 , 1.1910724567242534e+01 , -6.1879280000000003e-01 , -7.8305100000000002e-02 , 1.8253900000000001e-01 , 9.8007500000000003e-01 -2.6729869873142063e+00 , 1.2793150295670017e+01 , -7.5616640000000013e-01 , -7.7587100000000006e-02 , 1.7718700000000001e-01 , 9.8111400000000004e-01 -2.6704851559465319e+00 , 1.3879050975173463e+01 , -9.3242560000000019e-01 , -7.3813599999999993e-02 , 1.7391200000000001e-01 , 9.8199099999999995e-01 -2.6662597077539356e+00 , 1.5231269858052197e+01 , -1.1573776000000002e+00 , -6.3933500000000004e-02 , 1.8398000000000000e-01 , 9.8084899999999997e-01 -2.6615298150723454e+00 , 1.6941631534784889e+01 , -1.4444800000000000e+00 , -6.6775399999999999e-02 , 1.8093500000000001e-01 , 9.8122600000000004e-01 -2.6560065179708960e+00 , 1.9164156758590572e+01 , -1.8193999999999999e+00 , -9.6443500000000001e-02 , 1.7750700000000000e-01 , 9.7938300000000000e-01 -2.6460714386146282e+00 , 2.1855029260581034e+01 , -2.2419935999999998e+00 , 2.5761800000000001e-01 , -1.2858700000000001e-01 , -9.5765299999999998e-01 -2.5912432168611659e+00 , 2.7330391277001940e+01 , -2.8200567999999997e+00 , -3.0833500000000000e-02 , 2.2492900000000000e-02 , 9.9927100000000002e-01 -2.5388334379739996e+00 , 2.7836230161328913e+01 , -2.4762640000000005e+00 , -2.6214700000000001e-02 , 7.6417100000000002e-02 , 9.9673100000000003e-01 -2.4848432402609326e+00 , 2.8224491338838927e+01 , -2.0941784000000006e+00 , -2.6214700000000001e-02 , 7.6417100000000002e-02 , 9.9673100000000003e-01 -1.9864015762986498e+00 , 1.4551313031568363e+01 , 4.6876303999999998e+00 , 6.8515199999999998e-01 , -6.6882799999999998e-01 , 2.8850599999999998e-01 -2.0436415547307369e+00 , 1.2506477081540886e+01 , 4.5957983999999996e+00 , 7.8564099999999994e-03 , -9.7467700000000002e-01 , 2.2348000000000001e-01 -2.0316291562894291e+00 , 1.2293891426780064e+01 , 4.7397343999999997e+00 , -5.8971400000000000e-02 , -9.9166200000000004e-01 , 1.1458400000000001e-01 -1.9985521657646321e+00 , 1.2548622505333551e+01 , 4.9640520000000006e+00 , -6.2063999999999997e-01 , 7.7128600000000003e-01 , 1.4115400000000000e-01 -1.9798553487251176e+00 , 1.2482712611465400e+01 , 5.1335720000000000e+00 , 1.3123800000000000e-02 , 9.9510900000000002e-01 , -9.7912500000000000e-02 -1.9587212347102212e+00 , 1.2475520956890453e+01 , 5.3147192000000008e+00 , -2.0378700000000000e-01 , -9.7894400000000004e-01 , 1.1773199999999999e-02 -1.9293337012793723e+00 , 1.2636355742978942e+01 , 5.5375912000000005e+00 , 7.3950400000000005e-01 , 6.7176000000000002e-01 , 4.3270200000000002e-02 -1.9091876545505317e+00 , 1.2581050110844057e+01 , 5.7120096000000000e+00 , 1.6916799999999999e-02 , -9.6734799999999999e-01 , 2.5288800000000000e-01 -1.8801956421797399e+00 , 1.2692610874955331e+01 , 5.9326040000000004e+00 , 1.8586900000000001e-01 , -9.7502699999999998e-01 , -1.2155199999999999e-01 -1.8666347661020488e+00 , 1.2540483526113629e+01 , 6.0812927999999999e+00 , 3.1519700000000000e-01 , -8.9864400000000000e-01 , -3.0510799999999999e-01 -1.6611527250007978e+00 , 1.5585690747624925e+01 , 7.2333216000000009e+00 , -2.7724200000000001e-02 , -8.7882899999999997e-01 , 4.7633100000000000e-01 -1.8289781164386594e+00 , 1.2399229835274030e+01 , 6.4209567999999999e+00 , -2.6334200000000002e-01 , 8.4629100000000002e-01 , 4.6307900000000002e-01 -1.6257364367471052e+00 , 1.5185672892562312e+01 , 7.6014711999999998e+00 , 8.5171600000000003e-01 , 5.1281900000000002e-01 , -1.0768400000000000e-01 -1.7367366144805727e+00 , 1.3081305989739876e+01 , 7.0672128000000001e+00 , -4.9392399999999997e-01 , -8.6912100000000003e-01 , 2.5842600000000000e-02 -1.7231120797837864e+00 , 1.2912898270384568e+01 , 7.2138216000000002e+00 , 4.8852299999999999e-01 , 8.4265400000000001e-01 , 2.2645000000000001e-01 -1.7809847216205250e+00 , 1.1763813803637882e+01 , 6.9513775999999998e+00 , -5.6294599999999995e-01 , -8.1038200000000005e-01 , -1.6239999999999999e-01 -1.7519608884736269e+00 , 1.1836689112424473e+01 , 7.1751336000000006e+00 , -4.6873599999999999e-01 , -8.6046299999999998e-01 , 1.9972400000000001e-01 -1.7053019056252599e+00 , 1.2140833236753773e+01 , 7.5100448000000002e+00 , 3.8176000000000002e-02 , -9.2575900000000000e-01 , 3.7618099999999999e-01 -1.6892995008531719e+00 , 1.2042000780635805e+01 , 7.6695704000000005e+00 , 1.4932699999999999e-01 , -8.1332099999999996e-01 , 5.6232599999999999e-01 -1.8927551387500652e+00 , 9.2485868774672575e+00 , 6.4863520000000001e+00 , -3.6384000000000000e-01 , 9.3137000000000003e-01 , 1.3028300000000000e-02 -1.8161975164897002e+00 , 9.9419176814979444e+00 , 6.9967944000000006e+00 , -5.5188099999999997e-02 , -6.4239599999999997e-01 , 7.6438399999999995e-01 -1.7740474772946748e+00 , 1.0200104712503025e+01 , 7.3048527999999999e+00 , 9.9827299999999997e-01 , 5.0944200000000002e-02 , 2.9239899999999999e-02 -1.9006178536740577e+00 , 8.5437715768482487e+00 , 6.5472232000000004e+00 , 3.8327800000000001e-01 , -5.5653300000000006e-01 , -7.3713600000000001e-01 -1.9480552850961668e+00 , 7.8561574366649092e+00 , 6.2855175999999995e+00 , 7.3854299999999995e-01 , 6.7217700000000002e-01 , 5.2276000000000003e-02 -1.9457345787054015e+00 , 7.7103515736587598e+00 , 6.3255160000000004e+00 , 6.2392300000000001e-01 , 7.3670300000000000e-01 , 2.6074599999999998e-01 -1.6326644373442210e+00 , 1.0747905380545230e+01 , 8.3862136000000014e+00 , -5.4866400000000003e-02 , 2.0761499999999999e-01 , 9.7667099999999996e-01 -1.8092635064347777e+00 , 8.7599163753326099e+00 , 7.2790296000000003e+00 , 3.2720300000000002e-01 , 8.3721000000000001e-01 , -4.3819799999999998e-01 -1.7395438013926698e+00 , 9.2398029906807366e+00 , 7.7697952000000008e+00 , 4.5379799999999998e-01 , 1.4696600000000001e-02 , -8.9098299999999997e-01 -1.8622710329027381e+00 , 7.9078809635865550e+00 , 6.9982711999999996e+00 , 5.5445100000000003e-01 , -3.2301600000000003e-01 , -7.6697099999999996e-01 -1.8503260513437609e+00 , 7.8546197845270065e+00 , 7.1055680000000008e+00 , -5.2458899999999997e-01 , 3.9867200000000003e-01 , 7.5224199999999997e-01 -1.8464819957698371e+00 , 7.7333891471042735e+00 , 7.1618008000000000e+00 , 5.3523600000000005e-01 , -4.5049299999999998e-01 , -7.1454799999999996e-01 -1.8488833568087895e+00 , 7.5631683407006314e+00 , 7.1765064000000001e+00 , 7.5635399999999997e-01 , -2.5520100000000001e-01 , -6.0233000000000003e-01 -1.8448034384672485e+00 , 7.4416564380001766e+00 , 7.2260312000000004e+00 , 7.5635399999999997e-01 , -2.5520100000000001e-01 , -6.0233000000000003e-01 -1.1113618149826561e+00 , 1.3221628300689991e+01 , 1.2305037600000000e+01 , 1.1669200000000000e-01 , 9.6750999999999998e-01 , -2.2429399999999999e-01 -1.7521692324616291e+00 , 7.8903904671238312e+00 , 7.9262112000000000e+00 , -3.2815100000000003e-01 , 1.2017300000000000e-01 , 9.3694999999999995e-01 -1.7368836276254211e+00 , 7.8495573423255580e+00 , 8.0628360000000008e+00 , -5.1965399999999995e-01 , 6.0102900000000004e-01 , 6.0722600000000004e-01 -1.7431191814845390e+00 , 7.6481200204626623e+00 , 8.0498984000000000e+00 , 7.4185800000000002e-01 , -4.3655400000000000e-01 , -5.0898600000000005e-01 -1.7296391031434701e+00 , 7.5898785913254567e+00 , 8.1690616000000009e+00 , -7.6736000000000004e-01 , 1.0087200000000000e-01 , 6.3323300000000005e-01 -1.7343465457725942e+00 , 7.4046642603532185e+00 , 8.1625407999999986e+00 , 6.3461599999999996e-01 , -2.3802699999999999e-01 , -7.3525900000000000e-01 -1.4932168101796397e+00 , 8.8966630182496687e+00 , 9.9141504000000005e+00 , 1.3061500000000000e-02 , -2.3591500000000001e-01 , 9.7168600000000005e-01 -1.5505021769869205e+00 , 8.3278249748791566e+00 , 9.5378784000000003e+00 , 5.2427500000000005e-01 , -3.8704899999999998e-01 , -7.5850399999999996e-01 -1.5290616581955681e+00 , 8.2879195496718978e+00 , 9.7252240000000008e+00 , -3.8036100000000000e-01 , 1.6380600000000001e-01 , 9.1021600000000003e-01 -1.6090571041497379e+00 , 7.6196284630313231e+00 , 9.1816783999999991e+00 , 6.3763000000000003e-01 , 7.5320100000000001e-01 , -1.6160300000000000e-01 -1.6837396073125359e+00 , 7.0111493142084891e+00 , 8.6650272000000008e+00 , -6.7119200000000001e-01 , 7.4126300000000001e-01 , 5.5114500000000002e-03 -1.6854568479401928e+00 , 6.8600497457690901e+00 , 8.6796600000000002e+00 , 8.2745400000000002e-01 , -4.0008600000000000e-01 , 3.9401799999999998e-01 -1.6675711065649872e+00 , 6.8237724671906292e+00 , 8.8383327999999999e+00 , -8.4831999999999996e-01 , 5.2828600000000003e-01 , -3.5579199999999998e-02 -1.6458531889428756e+00 , 6.8022748621945937e+00 , 9.0221632000000014e+00 , 2.3375199999999999e-01 , 8.5081300000000004e-01 , -4.7061300000000000e-01 -1.5490506308644421e+00 , 7.1771566394883237e+00 , 9.7712024000000000e+00 , -3.3092199999999999e-01 , -3.8245499999999999e-01 , -8.6268100000000003e-01 -1.8647892420053800e+00 , 5.4080192557428148e+00 , 7.4505464000000003e+00 , 1.2647600000000001e-01 , 4.4073000000000001e-01 , 8.8868499999999995e-01 -1.8592849676930043e+00 , 5.3365066339691696e+00 , 7.5107416000000002e+00 , -4.4480499999999999e-02 , -3.7501400000000001e-01 , -9.2595099999999997e-01 -1.8567635670130009e+00 , 5.2466146542020216e+00 , 7.5436576000000004e+00 , 1.2424900000000000e-01 , 3.0178700000000003e-01 , 9.4524399999999997e-01 -1.4498010435867235e+00 , 7.0291052189350811e+00 , 1.0633206399999999e+01 , -9.6679099999999996e-01 , -2.3771800000000001e-01 , 9.3837799999999999e-02 -1.9570432413386394e+00 , 4.6060248020388581e+00 , 6.8204000000000002e+00 , 4.0985300000000002e-01 , 2.1218999999999999e-01 , 8.8712800000000003e-01 -1.9482918263400262e+00 , 4.5646910409687536e+00 , 6.9032672000000010e+00 , 6.4215000000000000e-01 , 2.0289699999999999e-01 , 7.3924000000000001e-01 -1.9579302361199868e+00 , 4.4483157393741291e+00 , 6.8494368000000003e+00 , 1.0514400000000000e-01 , 2.8067599999999998e-01 , 9.5402600000000004e-01 -1.8422248741167699e+00 , 4.8293299496372093e+00 , 7.7461456000000002e+00 , -9.7872499999999996e-01 , -1.8558300000000000e-01 , -8.7504299999999993e-02 -1.8387773471147240e+00 , 4.7465403517497702e+00 , 7.7877456000000009e+00 , -9.7872499999999996e-01 , -1.8558300000000000e-01 , -8.7504499999999999e-02 -1.8397156446190763e+00 , 4.6501869088329357e+00 , 7.7998512000000009e+00 , -6.1568900000000004e-01 , 7.7759900000000004e-01 , -1.2753999999999999e-01 -1.9939644789645419e+00 , 4.0151040467322217e+00 , 6.6253479999999998e+00 , 7.8065600000000002e-01 , 2.1224399999999999e-01 , -5.8781799999999995e-01 -2.0033631835493551e+00 , 3.9159769385884200e+00 , 6.5675032000000000e+00 , 5.3220599999999996e-01 , -2.7285900000000002e-01 , -8.0143900000000001e-01 -2.0000955863680439e+00 , 3.8584686298473283e+00 , 6.6028424000000001e+00 , -1.3840300000000000e-01 , 6.2321899999999997e-01 , 7.6970300000000003e-01 -1.9958231885722710e+00 , 3.8038127568463684e+00 , 6.6468655999999999e+00 , 2.0535100000000001e-01 , 8.0607300000000004e-01 , 5.5504799999999999e-01 -1.9849486384469173e+00 , 3.7694872932944925e+00 , 6.7482448000000002e+00 , 1.6989399999999999e-01 , 7.7202499999999996e-01 , 6.1246500000000004e-01 -1.9751622729220810e+00 , 3.7288775514773582e+00 , 6.8397128000000000e+00 , -7.2887199999999996e-01 , -4.8855300000000002e-01 , -4.7964800000000002e-01 -1.9664907587333773e+00 , 3.6819252678659646e+00 , 6.9210824000000004e+00 , 6.2267099999999997e-01 , 6.6781999999999997e-01 , 4.0779500000000002e-01 -1.8002095113492147e+00 , 4.0243969156572135e+00 , 8.2533744000000002e+00 , -3.5919699999999999e-01 , -7.0124600000000004e-01 , 6.1581799999999998e-01 -1.8154135262917355e+00 , 3.8960764205302558e+00 , 8.1520056000000007e+00 , -9.2736700000000005e-01 , 3.3805000000000002e-01 , -1.6035500000000000e-01 -1.9624709862058047e+00 , 3.4809346311360692e+00 , 6.9924784000000004e+00 , 7.9165600000000003e-01 , -4.5505299999999999e-01 , 4.0768500000000002e-01 -1.9702987454269885e+00 , 3.3937241637592823e+00 , 6.9407592000000005e+00 , 6.9409399999999999e-01 , 6.6860600000000003e-01 , 2.6683200000000001e-01 -1.9689584262390589e+00 , 3.3280536452748297e+00 , 6.9676328000000005e+00 , -9.2093899999999995e-01 , 3.8836100000000001e-01 , 3.2360800000000002e-02 -1.9784518012164998e+00 , 3.2423056364698009e+00 , 6.9024352000000002e+00 , -2.3814500000000000e-01 , -2.1823300000000001e-01 , 9.4639399999999996e-01 -1.7886672710447993e+00 , 3.4826522003883289e+00 , 8.4554152000000009e+00 , 3.1450299999999998e-01 , -7.8195400000000004e-01 , 5.3817899999999996e-01 -1.8260277060133343e+00 , 3.3330370306622354e+00 , 8.1687392000000010e+00 , 1.9829700000000000e-01 , 9.6291599999999999e-01 , -1.8295300000000000e-01 -1.8135164747001116e+00 , 3.2595522291387962e+00 , 8.2862384000000002e+00 , -9.3453699999999995e-01 , 2.4612899999999999e-01 , 2.5702500000000000e-01 -2.7493506823483167e+00 , 4.0023384563480651e+00 , 7.5189600000000012e-01 , -1.2709899999999999e-01 , 1.5011300000000000e-01 , 9.8046500000000003e-01 -2.7501776268403417e+00 , 4.0669923175667666e+00 , 7.4622800000000011e-01 , -1.2428699999999999e-01 , 1.0855300000000000e-01 , 9.8629100000000003e-01 -2.7519005559440282e+00 , 4.1329844599725387e+00 , 7.4209919999999996e-01 , -1.1715500000000000e-01 , 1.4991499999999999e-01 , 9.8173299999999997e-01 -2.7545838575582864e+00 , 4.2108333443861694e+00 , 7.2323359999999992e-01 , -7.3497699999999999e-02 , 1.5263099999999999e-01 , 9.8554600000000003e-01 -2.7548989410326556e+00 , 4.2785881264839976e+00 , 7.2231840000000003e-01 , 6.2344799999999999e-02 , -1.8488399999999999e-01 , -9.8078100000000001e-01 -2.7582469110881633e+00 , 4.3651458572427657e+00 , 6.9938639999999985e-01 , -1.0960399999999999e-01 , 1.4635400000000001e-01 , 9.8314199999999996e-01 -2.7592131721968793e+00 , 4.4405243755170716e+00 , 6.9430079999999994e-01 , -7.4912000000000006e-02 , 1.2942699999999999e-01 , 9.8875500000000005e-01 -2.7610129800318166e+00 , 4.5232028061973724e+00 , 6.8342239999999999e-01 , -7.4557100000000001e-02 , 2.0414800000000000e-01 , 9.7609699999999999e-01 -2.7646921323935034e+00 , 4.6212138361716537e+00 , 6.5944000000000003e-01 , -6.6547800000000004e-02 , 1.9094500000000000e-01 , 9.7934200000000005e-01 -2.7670594935699606e+00 , 4.7138654213942512e+00 , 6.4550399999999986e-01 , 1.2399200000000000e-01 , -1.9757500000000000e-01 , -9.7241500000000003e-01 -2.7701190793759873e+00 , 4.8140429481913110e+00 , 6.2688799999999989e-01 , -1.3290500000000000e-01 , 2.1125500000000000e-01 , 9.6835300000000002e-01 -2.7728909163462490e+00 , 4.9158493777256496e+00 , 6.1099679999999990e-01 , -1.2150300000000000e-01 , 1.9670199999999999e-01 , 9.7290600000000005e-01 -2.7753608175790481e+00 , 5.0192499995979585e+00 , 5.9772639999999977e-01 , -9.2034800000000000e-02 , 1.7559600000000000e-01 , 9.8015099999999999e-01 -2.7774803056425887e+00 , 5.1232799497874524e+00 , 5.8750319999999978e-01 , -6.8289199999999994e-02 , 1.7208999999999999e-01 , 9.8271100000000000e-01 -2.7811969801207019e+00 , 5.2523054589624358e+00 , 5.5937119999999996e-01 , -7.7942700000000004e-02 , 2.0877999999999999e-01 , 9.7485200000000005e-01 -2.7864547564744937e+00 , 5.3902705339551069e+00 , 5.2850399999999986e-01 , -8.0558400000000002e-02 , 2.0569799999999999e-01 , 9.7529399999999999e-01 -2.7893072287174436e+00 , 5.5229834553957229e+00 , 5.0794320000000015e-01 , -9.1006400000000001e-02 , 1.9117200000000001e-01 , 9.7732900000000000e-01 -2.7927266301079952e+00 , 5.6565116596471485e+00 , 4.9156319999999987e-01 , -6.7857100000000004e-02 , 1.8214300000000000e-01 , 9.8092800000000002e-01 -2.7965606280838835e+00 , 5.8094050458721931e+00 , 4.6599999999999975e-01 , -7.5578300000000001e-02 , 1.8620000000000000e-01 , 9.7960100000000006e-01 -2.8025464827684958e+00 , 5.9881174004249074e+00 , 4.2669839999999981e-01 , -6.3691100000000000e-02 , 1.8734000000000001e-01 , 9.8022799999999999e-01 -2.8070369452225514e+00 , 6.1607008972963886e+00 , 3.9884719999999985e-01 , -7.0653499999999994e-02 , 1.8141599999999999e-01 , 9.8086499999999999e-01 -2.8117897271661723e+00 , 6.3437686970405167e+00 , 3.7036160000000007e-01 , -6.0585100000000003e-02 , 1.8613700000000000e-01 , 9.8065400000000003e-01 -2.8184756179121582e+00 , 6.5552003345693715e+00 , 3.3025919999999998e-01 , -5.1874200000000002e-02 , 1.8666300000000000e-01 , 9.8105399999999998e-01 -2.8242175050416312e+00 , 6.7774659865144979e+00 , 2.9100959999999998e-01 , -4.7785899999999999e-02 , 2.0761199999999999e-01 , 9.7704299999999999e-01 -2.8334860744902328e+00 , 7.0380325503210930e+00 , 2.3711680000000013e-01 , -5.4970800000000000e-02 , 1.9921400000000000e-01 , 9.7841299999999998e-01 -2.8399914962221611e+00 , 7.2929136302700170e+00 , 1.9656719999999983e-01 , -5.4486899999999998e-02 , 1.8251200000000001e-01 , 9.8169300000000004e-01 -2.8479497161364060e+00 , 7.5781092083503880e+00 , 1.4864400000000000e-01 , -5.4384500000000002e-02 , 1.7505000000000001e-01 , 9.8305600000000004e-01 -2.8545603515290008e+00 , 7.8748210206745117e+00 , 1.0492239999999997e-01 , -5.3337000000000002e-02 , 1.7494000000000001e-01 , 9.8313300000000003e-01 -2.8646203924473590e+00 , 8.2301073139424634e+00 , 4.1711199999999948e-02 , -4.8496800000000000e-02 , 1.8446899999999999e-01 , 9.8164099999999999e-01 -2.8755873562258643e+00 , 8.6177728133533371e+00 , -2.4027199999999915e-02 , -3.9784300000000002e-02 , 1.7967200000000000e-01 , 9.8292199999999996e-01 -2.8876233755879137e+00 , 9.0554442916083353e+00 , -9.9531199999999931e-02 , -5.5261699999999997e-02 , 1.8230199999999999e-01 , 9.8168800000000001e-01 -2.9014831130485139e+00 , 9.5446860590629985e+00 , -1.8216960000000038e-01 , -6.6803899999999999e-02 , 1.8642800000000001e-01 , 9.8019500000000004e-01 -2.9175169814606763e+00 , 1.0124025310849499e+01 , -2.8625279999999975e-01 , 6.7512699999999995e-02 , -1.8541500000000000e-01 , -9.8033800000000004e-01 -2.9324004014501108e+00 , 1.0710453306746674e+01 , -3.7119999999999997e-01 , -7.7592999999999995e-02 , 1.7228099999999999e-01 , 9.8198700000000005e-01 -2.9525106715896490e+00 , 1.1445154509900416e+01 , -4.9384720000000026e-01 , -7.9819000000000001e-02 , 1.8918699999999999e-01 , 9.7869200000000001e-01 -2.9764839267988430e+00 , 1.2323968633392450e+01 , -6.4346160000000019e-01 , 7.6225500000000002e-02 , -1.8333600000000000e-01 , -9.8009100000000005e-01 -3.0031751383969882e+00 , 1.3327626494384885e+01 , -8.0518160000000050e-01 , -7.6802099999999998e-02 , 1.8157899999999999e-01 , 9.8037300000000005e-01 -3.0349390111193526e+00 , 1.4527012876814531e+01 , -9.9612560000000006e-01 , -6.3381300000000002e-02 , 1.8063199999999999e-01 , 9.8150599999999999e-01 -3.0776452747630811e+00 , 1.6102355266532218e+01 , -1.2628127999999998e+00 , -6.5146800000000005e-02 , 1.7927100000000001e-01 , 9.8164099999999999e-01 -3.1310762642008028e+00 , 1.8058915302625937e+01 , -1.5857848000000003e+00 , -8.4333099999999994e-02 , 1.7413100000000001e-01 , 9.8110500000000000e-01 -3.1919355684300479e+00 , 2.0440699285491242e+01 , -1.9567215999999998e+00 , -1.0663000000000000e-01 , 1.7817300000000000e-01 , 9.7820499999999999e-01 -2.3006092370280355e+00 , 1.5825887079832805e+01 , 5.0201808000000003e+00 , 1.1946500000000000e-01 , -7.1625700000000003e-01 , 6.8753500000000001e-01 -2.3099090839833343e+00 , 1.2936450311295621e+01 , 4.7891760000000003e+00 , -2.5603799999999999e-01 , -9.3220899999999995e-01 , -2.5579499999999999e-01 -2.2923061077700377e+00 , 1.2628320661400329e+01 , 4.9216096000000000e+00 , -2.5603700000000001e-01 , -9.3220899999999995e-01 , -2.5579499999999999e-01 -2.2703012564464444e+00 , 1.2574856039433401e+01 , 5.0942495999999995e+00 , 3.6712499999999998e-01 , 8.7855200000000000e-01 , 3.0555700000000002e-01 -2.2495738341933555e+00 , 1.2496872456648163e+01 , 5.2614295999999996e+00 , -3.2265600000000000e-01 , -8.5994000000000004e-01 , -3.9546999999999999e-01 -2.2279451237341505e+00 , 1.2427418234892304e+01 , 5.4285472000000006e+00 , 5.7006999999999997e-01 , 8.0301500000000003e-01 , 1.7374700000000001e-01 -2.2015059136143789e+00 , 1.2586272075374939e+01 , 5.6527088000000001e+00 , 6.0627599999999997e-02 , 9.2771199999999998e-01 , -3.6834000000000000e-01 -2.1877979328765331e+00 , 1.2238459627662886e+01 , 5.7469847999999999e+00 , -2.6693000000000000e-01 , -9.4503000000000004e-01 , 1.8885700000000000e-01 -2.1493338785169129e+00 , 1.2758840572786109e+01 , 6.0819168000000001e+00 , -2.3286299999999999e-02 , -9.8223400000000005e-01 , -1.8621199999999999e-01 -2.1285461731909350e+00 , 1.2654666140340138e+01 , 6.2455088000000005e+00 , -2.9291700000000000e-02 , 8.6549900000000002e-01 , 5.0005400000000000e-01 -2.1085108102748125e+00 , 1.2529453001847967e+01 , 6.3996472000000004e+00 , -4.0144700000000000e-03 , 8.3919900000000003e-01 , 5.4381000000000002e-01 -2.0874027558052455e+00 , 1.2459785976566637e+01 , 6.5711536000000006e+00 , 8.3926100000000000e-03 , 8.6690699999999998e-01 , 4.9839899999999998e-01 -2.0900566733740082e+00 , 1.1761873443441333e+01 , 6.5122895999999999e+00 , -3.6144599999999999e-01 , 6.3166000000000000e-01 , 6.8583000000000005e-01 -2.0679088367531753e+00 , 1.1749212981223193e+01 , 6.6924176000000006e+00 , -6.5374500000000002e-02 , 9.3976099999999996e-01 , 3.3552399999999999e-01 -2.0452660661488742e+00 , 1.1741768564437374e+01 , 6.8772880000000001e+00 , 5.3216799999999997e-01 , 8.2547400000000004e-01 , 1.8812300000000001e-01 -2.0192431330400340e+00 , 1.1798740654452862e+01 , 7.0912264000000000e+00 , 5.1609400000000005e-01 , 7.9659500000000005e-01 , 3.1477600000000000e-01 -1.9985220750370412e+00 , 1.1716747205697752e+01 , 7.2490671999999998e+00 , -2.5843400000000000e-01 , 2.3819799999999999e-01 , 9.3620199999999998e-01 -2.0656280141531145e+00 , 9.9302113237782468e+00 , 6.6072208000000003e+00 , 3.5298200000000002e-01 , -4.7584100000000001e-01 , 8.0559300000000000e-01 -2.0639868607813354e+00 , 9.5963160005004102e+00 , 6.6044752000000004e+00 , -5.5596100000000004e-01 , 1.0853000000000000e-01 , 8.2409299999999996e-01 -2.0393963624352152e+00 , 9.7000357114342997e+00 , 6.8136191999999998e+00 , -1.1833600000000000e-01 , -6.8178199999999994e-02 , 9.9063000000000001e-01 -1.9963374046967597e+00 , 1.0091849813010134e+01 , 7.1838696000000004e+00 , 8.0374599999999996e-01 , 5.6893099999999996e-01 , -1.7410100000000001e-01 -2.0678613681614517e+00 , 8.5934210172058680e+00 , 6.5236567999999995e+00 , -4.5639200000000002e-01 , 4.6898899999999999e-01 , 7.5614499999999996e-01 -1.9310497818017491e+00 , 1.0428424244899068e+01 , 7.7284968000000003e+00 , -9.5304599999999995e-01 , 2.5934400000000002e-01 , 1.5634600000000001e-01 -2.0956764046603280e+00 , 7.6596211856387342e+00 , 6.2480464000000007e+00 , 6.3157799999999997e-01 , 6.8606299999999998e-01 , 3.6114499999999999e-01 -2.0815973962322376e+00 , 7.6383031776022934e+00 , 6.3605847999999998e+00 , 6.3157799999999997e-01 , 6.8606299999999998e-01 , 3.6114499999999999e-01 -1.9201865604848776e+00 , 9.6070125090938010e+00 , 7.7705127999999997e+00 , 4.6984100000000001e-03 , -2.9727400000000001e-02 , 9.9954699999999996e-01 -1.8991636546053106e+00 , 9.5923622731128049e+00 , 7.9410312000000003e+00 , 4.6983099999999998e-03 , -2.9727099999999999e-02 , 9.9954699999999996e-01 -1.9374378451220595e+00 , 8.8261481105633735e+00 , 7.5876912000000001e+00 , -6.1542500000000000e-01 , 2.2699200000000000e-01 , 7.5480199999999997e-01 -1.9310770208454331e+00 , 8.6535780989679569e+00 , 7.6310280000000006e+00 , -4.8266399999999998e-01 , 5.2784500000000001e-01 , 6.9886700000000002e-01 -1.9810931603073356e+00 , 7.8357208786863453e+00 , 7.1819768000000002e+00 , 6.7821699999999996e-01 , -6.6837599999999997e-02 , -7.3181600000000002e-01 -1.8968427729706550e+00 , 8.5718696753505093e+00 , 7.9085520000000002e+00 , -8.2825800000000005e-02 , 6.9764400000000004e-01 , 7.1164099999999997e-01 -1.8922244185457708e+00 , 8.3896568242844936e+00 , 7.9360184000000000e+00 , -4.4132399999999999e-01 , 4.0172400000000003e-01 , 8.0240400000000001e-01 -1.9722626409568598e+00 , 7.3427446214670136e+00 , 7.2313352000000002e+00 , -6.8266600000000000e-01 , 4.4190400000000002e-01 , 5.8196899999999996e-01 -1.8882001589811452e+00 , 7.9887335545407723e+00 , 7.9426743999999996e+00 , 3.5125899999999999e-01 , 1.0945100000000001e-01 , 9.2985899999999999e-01 -1.8868588464247358e+00 , 7.7942283219596771e+00 , 7.9414264000000001e+00 , 2.3333200000000001e-01 , -2.5404700000000002e-01 , 9.3862500000000004e-01 -1.8624583332379643e+00 , 7.8293087615455867e+00 , 8.1472423999999997e+00 , -9.7928599999999999e-01 , -9.9093299999999992e-03 , -2.0223800000000000e-01 -1.8395708578503276e+00 , 7.8292852535315678e+00 , 8.3267048000000017e+00 , 8.2034200000000002e-01 , -7.2819900000000007e-02 , -5.6721699999999997e-01 -1.8556762924283694e+00 , 7.4938619756412903e+00 , 8.1778808000000005e+00 , -7.4194000000000004e-01 , 1.7331700000000000e-03 , 6.7046399999999995e-01 -1.6904833830182662e+00 , 8.6765518677795850e+00 , 9.5857288000000000e+00 , 1.2100600000000000e-01 , -3.9534000000000002e-01 , 9.1052900000000003e-01 -1.6689304906346711e+00 , 8.6179261580516755e+00 , 9.7539383999999991e+00 , 1.2100600000000000e-01 , -3.9534100000000000e-01 , 9.1052900000000003e-01 -1.8399177634325627e+00 , 7.0868141837569585e+00 , 8.2886407999999996e+00 , -7.3729299999999998e-01 , -5.6657400000000002e-01 , -3.6795899999999998e-01 -1.8251551599277838e+00 , 7.0217654635980562e+00 , 8.4000664000000000e+00 , -7.9916600000000004e-01 , 3.4382000000000001e-01 , -4.9307400000000001e-01 -1.7332708125611884e+00 , 7.5126731315831119e+00 , 9.1780071999999997e+00 , -9.1092600000000001e-01 , -1.1941900000000000e-01 , 3.9490799999999998e-01 -1.7032504798371766e+00 , 7.5284368367606778e+00 , 9.4184656000000011e+00 , -4.1571500000000000e-01 , -8.8689499999999999e-01 , -2.0149000000000000e-01 -1.6782404385878504e+00 , 7.5054441863962555e+00 , 9.6204959999999993e+00 , 1.6650799999999999e-01 , 9.1467600000000004e-01 , 3.6829800000000001e-01 -1.7605469964246057e+00 , 6.7924271046651761e+00 , 8.9133896000000004e+00 , -1.7170299999999999e-01 , 8.5821099999999995e-01 , 4.8372700000000002e-01 -1.7304412880932927e+00 , 6.8166945571122275e+00 , 9.1644871999999999e+00 , -6.1540399999999995e-01 , -7.8212499999999996e-01 , 9.7766300000000000e-02 -1.6718372911334263e+00 , 6.9939759654067286e+00 , 9.6471304000000018e+00 , 3.3091399999999999e-01 , -5.1290300000000000e-01 , 7.9210300000000000e-01 -1.9308884274505034e+00 , 5.3526661600572005e+00 , 7.4586480000000002e+00 , -4.4480499999999999e-02 , -3.7501400000000001e-01 , -9.2595099999999997e-01 -1.9243631078204328e+00 , 5.2749722741460499e+00 , 7.5090984000000001e+00 , 4.4480499999999999e-02 , 3.7501400000000001e-01 , 9.2595099999999997e-01 -1.5112237968480109e+00 , 7.3205225815341723e+00 , 1.0964883199999999e+01 , -9.6679099999999996e-01 , -2.3771800000000001e-01 , 9.3837799999999999e-02 -1.4926008453582162e+00 , 7.2180285147217234e+00 , 1.1110961600000001e+01 , -9.5775299999999997e-01 , -2.4182400000000001e-01 , 1.5566099999999999e-01 -2.0026299231724720e+00 , 4.5679382829483641e+00 , 6.8360935999999999e+00 , 6.4215000000000000e-01 , 2.0289699999999999e-01 , 7.3924000000000001e-01 -1.9928873448385964e+00 , 4.5214798559932259e+00 , 6.9091120000000004e+00 , 3.0302099999999998e-01 , 3.0570300000000000e-01 , 9.0262100000000001e-01 -1.6503356906219977e+00 , 5.9461437754277124e+00 , 9.7594607999999994e+00 , -2.2667399999999999e-01 , -1.6515400000000000e-01 , 9.5986600000000000e-01 -1.8864068481996397e+00 , 4.7972831504851214e+00 , 7.7915416000000004e+00 , -9.7872499999999996e-01 , -1.8558300000000000e-01 , -8.7504499999999999e-02 -1.8883324227445299e+00 , 4.6828780172739233e+00 , 7.7669664000000003e+00 , -6.1568900000000004e-01 , 7.7759900000000004e-01 , -1.2753999999999999e-01 -1.8714860570357212e+00 , 4.6433945198497657e+00 , 7.8993896000000001e+00 , -6.1568900000000004e-01 , 7.7759900000000004e-01 , -1.2753999999999999e-01 -2.0248759819001796e+00 , 3.9762923646915054e+00 , 6.6237568000000007e+00 , -7.1880400000000000e-01 , -2.0851400000000000e-01 , 6.6320699999999999e-01 -2.0269387155786660e+00 , 3.8934100382077172e+00 , 6.6028424000000001e+00 , 4.5488699999999999e-01 , -4.0168799999999999e-01 , -7.9481100000000005e-01 -2.0216220889057297e+00 , 3.8348178446144150e+00 , 6.6376303999999999e+00 , -6.2836100000000006e-02 , 6.8262100000000003e-01 , 7.2806599999999999e-01 -2.0141473404495356e+00 , 3.7872698470321504e+00 , 6.7004464000000006e+00 , 1.4337400000000000e-01 , 8.7024299999999999e-01 , 4.7129599999999999e-01 -2.0045348722506620e+00 , 3.7405831181314015e+00 , 6.7723416000000007e+00 , 3.3521600000000001e-01 , 8.0094600000000005e-01 , 4.9610100000000001e-01 -1.9937326046715722e+00 , 3.6988654632338482e+00 , 6.8633936000000002e+00 , -5.9503399999999995e-01 , -5.8816900000000005e-01 , -5.4771499999999995e-01 -1.9819060129549730e+00 , 3.6549664240923541e+00 , 6.9539152000000000e+00 , 6.5204200000000001e-01 , 6.5308600000000006e-01 , 3.8512400000000002e-01 -1.6843590408891789e+00 , 4.3213384409997442e+00 , 9.3968336000000008e+00 , 6.7363499999999998e-01 , -4.3946200000000002e-01 , 5.9421299999999999e-01 -1.9892377091289608e+00 , 3.4868698676416674e+00 , 6.8853688000000002e+00 , 7.0537799999999995e-01 , -5.7546799999999998e-01 , 4.1385699999999997e-01 -1.9914940680127904e+00 , 3.4091309339680640e+00 , 6.8636432000000003e+00 , -5.0374799999999997e-01 , -7.5825500000000004e-02 , -8.6051699999999998e-01 -1.9741090447341740e+00 , 3.3716817730942559e+00 , 7.0008087999999997e+00 , -5.7676400000000005e-01 , -3.5844300000000001e-01 , -7.3407299999999998e-01 -1.9802297544564369e+00 , 3.2871707770373080e+00 , 6.9462920000000006e+00 , -2.0632200000000001e-01 , -5.3812000000000004e-01 , 8.1722600000000001e-01 -1.9854001737438047e+00 , 3.2065101382117547e+00 , 6.9001784000000006e+00 , 5.9299999999999997e-01 , -3.8593400000000000e-01 , 7.0668600000000004e-01 -1.8177496896104715e+00 , 3.3989119553669846e+00 , 8.2726040000000012e+00 , -7.6492499999999997e-01 , -4.6578399999999999e-02 , 6.4243399999999995e-01 -1.8163274937686786e+00 , 3.3057091579638214e+00 , 8.2787503999999998e+00 , -4.0115200000000001e-01 , -5.4594100000000001e-01 , -7.3554399999999998e-01 -2.8029203803374929e+00 , 3.9634825818487252e+00 , 7.7072000000000007e-01 , -1.3583300000000001e-01 , 1.6048399999999999e-01 , 9.7764700000000004e-01 -2.8080877267883011e+00 , 4.0335792414171907e+00 , 7.5610800000000000e-01 , -1.3426600000000000e-01 , 1.4921000000000001e-01 , 9.7964700000000005e-01 -2.8108948103327780e+00 , 4.0983585970698542e+00 , 7.5150079999999986e-01 , -1.3180100000000000e-01 , 1.2712499999999999e-01 , 9.8309100000000005e-01 -2.8135535390898943e+00 , 4.1644979893606529e+00 , 7.4830799999999997e-01 , -9.1009300000000001e-02 , 1.9266600000000000e-01 , 9.7703499999999999e-01 -2.8182244101931779e+00 , 4.2435350268310472e+00 , 7.3050320000000002e-01 , -5.5027699999999999e-02 , 1.9340199999999999e-01 , 9.7957499999999997e-01 -2.8237134423525512e+00 , 4.3240325196846339e+00 , 7.1485120000000002e-01 , 8.3140800000000001e-02 , -1.5797400000000000e-01 , -9.8393699999999995e-01 -2.8268245884766099e+00 , 4.3981479838385793e+00 , 7.0920399999999995e-01 , -6.3481300000000004e-02 , 1.3959500000000000e-01 , 9.8817200000000005e-01 -2.8297423386087979e+00 , 4.4736886349944047e+00 , 7.0528320000000000e-01 , -8.8363200000000003e-02 , 1.6011900000000001e-01 , 9.8313499999999998e-01 -2.8366395035266208e+00 , 4.5703251873266169e+00 , 6.8046879999999987e-01 , -5.5913499999999998e-02 , 2.0417199999999999e-01 , 9.7733700000000001e-01 -2.8422084860836843e+00 , 4.6616308068233341e+00 , 6.6579439999999979e-01 , -1.0290299999999999e-01 , 1.5276200000000001e-01 , 9.8289099999999996e-01 -2.8464945539325530e+00 , 4.7545015487598272e+00 , 6.5331439999999996e-01 , 1.0286200000000000e-01 , -1.7185200000000000e-01 , -9.7973800000000000e-01 -2.8525410074221158e+00 , 4.8559106235263325e+00 , 6.3618559999999991e-01 , 9.9413399999999999e-02 , -2.0479300000000000e-01 , -9.7374400000000005e-01 -2.8592488312384354e+00 , 4.9649455006303551e+00 , 6.1487599999999998e-01 , -5.9418499999999999e-02 , 1.6454099999999999e-01 , 9.8457899999999998e-01 -2.8656518189486642e+00 , 5.0766881921571958e+00 , 5.9640559999999998e-01 , -6.0975500000000002e-02 , 1.7633299999999999e-01 , 9.8243999999999998e-01 -2.8716859361530642e+00 , 5.1890989166098187e+00 , 5.8116959999999995e-01 , -5.5317499999999999e-02 , 1.8095000000000000e-01 , 9.8193500000000000e-01 -2.8783491771918177e+00 , 5.3113361037017155e+00 , 5.6215839999999995e-01 , -5.6817800000000002e-02 , 2.1377499999999999e-01 , 9.7522900000000001e-01 -2.8875439458970660e+00 , 5.4506616573250799e+00 , 5.3361039999999993e-01 , -6.0790600000000000e-02 , 2.0584400000000000e-01 , 9.7669499999999998e-01 -2.8961984300037322e+00 , 5.6000859759141495e+00 , 5.0237919999999980e-01 , -6.5772800000000006e-02 , 1.8416299999999999e-01 , 9.8069300000000004e-01 -2.9044088939695722e+00 , 5.7422256739012543e+00 , 4.8232799999999987e-01 , -4.9058200000000003e-02 , 1.7493300000000001e-01 , 9.8335700000000004e-01 -2.9130959946603241e+00 , 5.8955722565505866e+00 , 4.6001999999999987e-01 , -5.6659399999999999e-02 , 1.8581800000000001e-01 , 9.8094899999999996e-01 -2.9230686229825174e+00 , 6.0674949189539698e+00 , 4.3005760000000004e-01 , -5.5434200000000003e-02 , 1.8708100000000000e-01 , 9.8077899999999996e-01 -2.9341773303081311e+00 , 6.2582074314264178e+00 , 3.9348080000000007e-01 , -4.6175200000000000e-02 , 1.8229100000000001e-01 , 9.8216000000000003e-01 -2.9465188671760481e+00 , 6.4595373097548414e+00 , 3.5709119999999994e-01 , -4.4526999999999997e-02 , 1.8394099999999999e-01 , 9.8192800000000002e-01 -2.9571226687430006e+00 , 6.6632102587914988e+00 , 3.2675440000000000e-01 , -4.1004400000000003e-02 , 1.9059000000000001e-01 , 9.8081300000000005e-01 -2.9732183589075096e+00 , 6.9133925683788231e+00 , 2.7548239999999979e-01 , -4.2679099999999998e-02 , 2.0581300000000000e-01 , 9.7765999999999997e-01 -2.9874074354860825e+00 , 7.1673268826135237e+00 , 2.3186480000000009e-01 , -4.7907600000000002e-02 , 1.8652700000000000e-01 , 9.8128099999999996e-01 -3.0040780926780513e+00 , 7.4504790220523560e+00 , 1.8090479999999975e-01 , -4.3466499999999998e-02 , 1.8220300000000000e-01 , 9.8229999999999995e-01 -3.0214981087905741e+00 , 7.7450631140631758e+00 , 1.3419839999999983e-01 , -4.1141700000000003e-02 , 1.7142199999999999e-01 , 9.8433800000000005e-01 -3.0391290553724408e+00 , 8.0714290320432056e+00 , 8.1907200000000069e-02 , -3.4884100000000001e-02 , 1.8065000000000001e-01 , 9.8292900000000005e-01 -3.0613084946948854e+00 , 8.4470736899587173e+00 , 1.6875999999999891e-02 , -3.8182800000000003e-02 , 1.8262900000000001e-01 , 9.8243999999999998e-01 -3.0849858340852361e+00 , 8.8639081891735927e+00 , -5.4135200000000161e-02 , -4.4494100000000002e-02 , 1.7786600000000000e-01 , 9.8304800000000003e-01 -3.1119793670016813e+00 , 9.3223329505912620e+00 , -1.2884880000000010e-01 , -5.7068399999999998e-02 , 1.7522900000000000e-01 , 9.8287199999999997e-01 -3.1389747999959434e+00 , 9.8238833306585214e+00 , -2.0563200000000004e-01 , 6.1080599999999999e-02 , -1.8543799999999999e-01 , -9.8075599999999996e-01 -3.1768540386474058e+00 , 1.0453704872327197e+01 , -3.1800400000000018e-01 , 7.1288900000000002e-02 , -1.7468700000000001e-01 , -9.8204000000000002e-01 -3.2083329627185924e+00 , 1.1061600203368553e+01 , -3.9826080000000008e-01 , -7.4372499999999994e-02 , 1.7036599999999999e-01 , 9.8257000000000005e-01 -3.2558914789130990e+00 , 1.1878088018256157e+01 , -5.3595679999999968e-01 , 7.3892600000000003e-02 , -1.8900000000000000e-01 , -9.7919299999999998e-01 -3.3108549546166710e+00 , 1.2837443615308777e+01 , -6.9556559999999967e-01 , 7.3767500000000000e-02 , -1.7941799999999999e-01 , -9.8100299999999996e-01 -3.3752539838230855e+00 , 1.3972889448475993e+01 , -8.8016560000000021e-01 , -5.9324000000000002e-02 , 1.8270500000000001e-01 , 9.8137600000000003e-01 -3.4579461534002860e+00 , 1.5403637552426780e+01 , -1.1186688000000000e+00 , -5.9265199999999997e-02 , 1.8445800000000001e-01 , 9.8105200000000004e-01 -3.5540144202578934e+00 , 1.7113845671123336e+01 , -1.3902232000000003e+00 , -6.6542000000000004e-02 , 1.7835100000000001e-01 , 9.8171399999999998e-01 -3.6712762746455190e+00 , 1.9226600437947344e+01 , -1.7145368000000003e+00 , -1.0545900000000000e-01 , 1.6250400000000001e-01 , 9.8105600000000004e-01 -3.8093725965990606e+00 , 2.1766235560849129e+01 , -2.0761447999999998e+00 , -3.1352300000000000e-01 , 7.5316099999999997e-02 , 9.4658900000000001e-01 -6.7214827316997594e+00 , 7.8394522073780479e+01 , -8.8768400000000014e+00 , 6.6710300000000000e-02 , 2.5950299999999998e-01 , 9.6343500000000004e-01 -4.8816427584459490e+00 , 5.6476884780637377e+01 , -6.7567040000000045e-01 , -5.2856999999999998e-01 , 6.1502900000000005e-01 , -5.8511000000000002e-01 -4.7627143124783498e+00 , 5.6507638370147099e+01 , 2.6348079999999996e-01 , -5.5840400000000001e-01 , -8.2274800000000003e-01 , 1.0616000000000000e-01 -2.6134314466508366e+00 , 1.2534253741960752e+01 , 4.6708031999999999e+00 , -2.4759100000000001e-01 , 4.1555500000000001e-01 , 8.7522200000000006e-01 -2.5886018883375348e+00 , 1.2454101563006676e+01 , 4.8368704000000005e+00 , -6.5396299999999996e-01 , -6.0160899999999995e-01 , -4.5869300000000002e-01 -2.5663879007458963e+00 , 1.2524791823767819e+01 , 5.0301439999999999e+00 , 5.5181400000000003e-01 , 7.5982400000000005e-01 , 3.4375600000000001e-01 -2.5414447100549622e+00 , 1.2326945420894285e+01 , 5.1706896000000002e+00 , -3.1899600000000000e-01 , -9.4692100000000001e-01 , -3.9779599999999998e-02 -2.5183300424911144e+00 , 1.2339365622479320e+01 , 5.3538648000000002e+00 , 1.9922500000000001e-01 , 9.3951600000000002e-01 , -2.7860200000000002e-01 -2.4971465529932702e+00 , 1.2712937274237929e+01 , 5.6277280000000003e+00 , 3.1545699999999999e-01 , 8.2337499999999997e-01 , -4.7174300000000002e-01 -2.4727553017863038e+00 , 1.2727624242216329e+01 , 5.8217295999999994e+00 , -3.0408900000000000e-01 , -9.2652699999999999e-01 , 2.2153400000000001e-01 -2.4480982942299900e+00 , 1.2809109939836269e+01 , 6.0367288000000006e+00 , -3.2237800000000000e-01 , -9.3547700000000000e-01 , -1.4476100000000000e-01 -2.4232133199765316e+00 , 1.2696199364489916e+01 , 6.1982303999999999e+00 , 8.9756199999999994e-02 , 8.7528600000000001e-01 , 4.7520299999999999e-01 -2.3994494984320518e+00 , 1.2491906771465883e+01 , 6.3280640000000004e+00 , 1.9986100000000001e-01 , 7.5918099999999999e-01 , 6.1943499999999996e-01 -2.3746670250447051e+00 , 1.2453976779520650e+01 , 6.5087223999999999e+00 , -2.5701700000000000e-01 , -8.2873300000000005e-01 , -4.9713499999999999e-01 -2.3518787622545609e+00 , 1.2334805968517422e+01 , 6.6607495999999999e+00 , 2.8630699999999998e-01 , 9.4637700000000002e-01 , 1.4966399999999999e-01 -2.3267099777500118e+00 , 1.2270565980135077e+01 , 6.8319336000000002e+00 , -3.3395300000000000e-01 , -9.4258799999999998e-01 , 1.8557500000000000e-03 -2.2977388742960279e+00 , 1.2542471110143062e+01 , 7.1371007999999998e+00 , 3.3395300000000000e-01 , 9.4258799999999998e-01 , -1.8557900000000000e-03 -2.2762616081481273e+00 , 1.2306796841358514e+01 , 7.2434304000000003e+00 , -7.5897400000000004e-01 , 5.1537800000000000e-01 , 3.9792400000000000e-01 -2.2656776937198391e+00 , 1.1548081549960100e+01 , 7.1118600000000010e+00 , 5.8409400000000000e-01 , -4.6115600000000001e-01 , -6.6795899999999997e-01 -2.2463811555431077e+00 , 1.1306779544899239e+01 , 7.1907544000000003e+00 , -3.7122500000000003e-01 , 3.4501700000000002e-01 , 8.6206400000000005e-01 -2.2238955296416854e+00 , 1.1242913675308811e+01 , 7.3485952000000001e+00 , -3.7122600000000000e-01 , 3.4501700000000002e-01 , 8.6206400000000005e-01 -2.2374528598311354e+00 , 9.9233386550764742e+00 , 6.8732632000000002e+00 , -3.1544299999999997e-01 , -4.6384500000000001e-01 , 8.2785500000000001e-01 -2.2337017823122154e+00 , 9.3595732573445378e+00 , 6.7410480000000002e+00 , -6.7099699999999995e-01 , -2.2165699999999999e-01 , 7.0755299999999999e-01 -2.2183059839329542e+00 , 9.2212615589090667e+00 , 6.8207120000000003e+00 , 7.2067199999999998e-01 , 4.0191600000000000e-01 , -5.6488600000000000e-01 -2.1479321659599688e+00 , 1.0599164357770317e+01 , 7.7631600000000001e+00 , -8.7858199999999997e-01 , 4.6548200000000001e-01 , -1.0686700000000000e-01 -2.2419024331683040e+00 , 7.6486842013421050e+00 , 6.1985944000000002e+00 , 4.4835300000000000e-01 , 5.9301300000000001e-01 , 6.6881599999999997e-01 -2.2303356505914995e+00 , 7.5492758885225975e+00 , 6.2613792000000004e+00 , 4.0777900000000000e-01 , 9.1289299999999995e-01 , -1.8529199999999999e-02 -2.1262064429639720e+00 , 9.4603990329625134e+00 , 7.6138471999999995e+00 , -3.3665499999999998e-01 , 7.6452399999999998e-01 , -5.4969699999999999e-01 -2.1112098779395123e+00 , 9.2933155294128582e+00 , 7.6772664000000006e+00 , -1.8425200000000000e-01 , 9.5832200000000006e-02 , -9.7819599999999995e-01 -2.0891108997457062e+00 , 9.3057506139943840e+00 , 7.8607744000000004e+00 , 4.6984100000000001e-03 , -2.9727400000000001e-02 , 9.9954699999999996e-01 -2.0818986854872796e+00 , 9.0191781992928099e+00 , 7.8334847999999999e+00 , -6.3735399999999998e-01 , 2.5996799999999998e-01 , 7.2539399999999998e-01 -2.0749634083928776e+00 , 8.7601882157568767e+00 , 7.8166783999999998e+00 , -9.1468300000000002e-01 , 3.9493800000000001e-01 , 8.5904200000000000e-02 -2.0956454255166230e+00 , 8.0685618172813882e+00 , 7.4555800000000003e+00 , -8.5653400000000002e-01 , 4.6784300000000001e-01 , 2.1788099999999999e-01 -2.0427994050516647e+00 , 8.5578644088821854e+00 , 8.0072271999999991e+00 , -6.7934600000000001e-01 , -6.8637000000000004e-01 , -2.5958700000000001e-01 -2.0262872771657130e+00 , 8.4714926711747758e+00 , 8.1125895999999997e+00 , -2.9183900000000002e-01 , 2.5353799999999999e-01 , 9.2225199999999996e-01 -2.0314487658350471e+00 , 8.0825760617136773e+00 , 7.9594183999999997e+00 , -2.6141700000000000e-02 , -8.9265399999999995e-02 , 9.9566500000000002e-01 -2.0406518532313438e+00 , 7.6861805131158949e+00 , 7.7805695999999998e+00 , 5.1320399999999999e-01 , -1.1041700000000000e-01 , 8.5113499999999997e-01 -2.0450764953033129e+00 , 7.3671718188196191e+00 , 7.6527432000000006e+00 , -5.6891899999999995e-01 , 8.1986400000000004e-01 , 6.4459799999999998e-02 -2.0326393120082251e+00 , 7.2714814963429726e+00 , 7.7232136000000002e+00 , 4.2131200000000002e-01 , 4.8921599999999998e-01 , 7.6365200000000000e-01 -2.0094218280043279e+00 , 7.2928369822491472e+00 , 7.9085935999999997e+00 , -9.6811899999999995e-01 , -1.2225400000000000e-01 , -2.1862899999999999e-01 -1.9756483267713256e+00 , 7.4250017188497406e+00 , 8.2148007999999990e+00 , 7.4448899999999996e-01 , 1.7975400000000000e-01 , -6.4298100000000002e-01 -1.9698397779541532e+00 , 7.2490843022124336e+00 , 8.2100375999999997e+00 , -6.0499700000000001e-01 , -4.7875600000000001e-01 , -6.3621600000000000e-01 -1.9613639532202862e+00 , 7.1019352312325079e+00 , 8.2315240000000003e+00 , -5.4358499999999998e-01 , 2.4531300000000000e-03 , -8.3935099999999996e-01 -1.9414838913585175e+00 , 7.0725438008567361e+00 , 8.3818040000000007e+00 , 7.6423300000000005e-01 , -3.1353599999999998e-01 , 5.6359899999999996e-01 -1.9114337205825171e+00 , 7.1201254179999021e+00 , 8.6273479999999996e+00 , -5.5190300000000003e-01 , 8.0388700000000002e-01 , -2.2174099999999999e-01 -1.8667327136348706e+00 , 7.2856767025067457e+00 , 9.0284240000000011e+00 , -9.7181799999999996e-01 , -1.6627500000000001e-01 , -1.6710200000000000e-01 -1.8035094760196371e+00 , 7.5669272705032977e+00 , 9.5992592000000005e+00 , 1.6650799999999999e-01 , 9.1467600000000004e-01 , 3.6829800000000001e-01 -1.9042748723021639e+00 , 6.5706845373780647e+00 , 8.5338832000000018e+00 , 5.3851700000000002e-01 , 8.1371300000000002e-01 , -2.1879299999999999e-01 -1.8247037815991338e+00 , 6.9601377370781625e+00 , 9.2640984000000000e+00 , -5.2410800000000002e-01 , 7.5751100000000004e-03 , 8.5161799999999999e-01 -1.8193044347986633e+00 , 6.7911689258160308e+00 , 9.2569952000000004e+00 , 5.5920099999999995e-01 , -7.2992100000000004e-01 , -3.9307799999999998e-01 -1.8023855853321753e+00 , 6.7055106058616412e+00 , 9.3658000000000001e+00 , -4.5191500000000001e-01 , 8.8639500000000004e-01 , -1.0038200000000000e-01 -1.8345396273625112e+00 , 6.3039517864043484e+00 , 8.9975672000000007e+00 , 3.1857700000000000e-01 , 8.8510299999999997e-01 , 3.3926499999999998e-01 -1.8359531177131077e+00 , 6.1226433050873315e+00 , 8.9412096000000005e+00 , 7.2036500000000003e-01 , 4.3785499999999998e-02 , 6.9221200000000005e-01 -1.8047416709142512e+00 , 6.1266520559621744e+00 , 9.1810752000000004e+00 , 3.5199300000000000e-01 , 8.6360899999999996e-01 , 3.6094500000000002e-01 -1.5716125252251623e+00 , 7.2348408394522057e+00 , 1.1316704800000000e+01 , -9.5775299999999997e-01 , -2.4182400000000001e-01 , 1.5566099999999999e-01 -1.6400519571485006e+00 , 6.6474334154301911e+00 , 1.0613456800000002e+01 , -8.5083900000000001e-01 , -3.9045999999999997e-01 , 3.5158800000000001e-01 -1.7314768557224400e+00 , 5.9930575892542297e+00 , 9.7197847999999993e+00 , -1.2497200000000000e-01 , -7.7855500000000000e-01 , 6.1500800000000000e-01 -1.8815364016138489e+00 , 5.1042104536268234e+00 , 8.2914695999999992e+00 , 3.9694600000000002e-04 , 9.0257500000000002e-01 , 4.3053300000000000e-01 -1.8680644084493740e+00 , 5.0362080613676534e+00 , 8.3832495999999992e+00 , -1.5269600000000000e-01 , 8.7840200000000002e-01 , 4.5287400000000000e-01 -1.8989693611737111e+00 , 4.7696717467640166e+00 , 8.0629816000000005e+00 , -9.8136100000000004e-01 , 1.8849299999999999e-01 , 3.7434500000000002e-02 -1.8348312490840624e+00 , 4.9076510710774270e+00 , 8.6023671999999998e+00 , -8.5781700000000005e-01 , 4.5560000000000000e-01 , 2.3786299999999999e-01 -2.0515540728990649e+00 , 3.9446023936052832e+00 , 6.6408231999999998e+00 , 7.0570200000000005e-01 , 1.4599500000000001e-01 , -6.9330400000000003e-01 -2.0516345737415005e+00 , 3.8616153713045600e+00 , 6.6189520000000002e+00 , 3.2841999999999999e-01 , -5.2461599999999997e-01 , -7.8544199999999997e-01 -2.0443141990882205e+00 , 3.8029565666546077e+00 , 6.6529704000000001e+00 , -1.0610500000000000e-01 , 7.9878099999999996e-01 , 5.9219200000000005e-01 -2.0326173059020411e+00 , 3.7625113409547466e+00 , 6.7343504000000003e+00 , 1.0090100000000000e-01 , 7.4656800000000001e-01 , 6.5761400000000003e-01 -2.0219756022811066e+00 , 3.7147458307380790e+00 , 6.8059232000000005e+00 , -3.5481499999999999e-01 , -8.0548500000000001e-01 , -4.7465900000000000e-01 -2.0091243052103924e+00 , 3.6719442909883151e+00 , 6.8964240000000006e+00 , 5.6353200000000003e-01 , 7.0845300000000000e-01 , 4.2488199999999998e-01 -1.8089125147168246e+00 , 4.1258245350684462e+00 , 8.5847288000000006e+00 , -9.9980899999999998e-02 , -8.2222200000000001e-01 , 5.6031600000000004e-01 -1.8844910083207989e+00 , 3.8229266728567963e+00 , 7.9090720000000001e+00 , 4.5227000000000003e-02 , -4.4995400000000002e-01 , 8.9190599999999998e-01 -1.9951166995952363e+00 , 3.4669764998449004e+00 , 6.9459800000000005e+00 , 7.0537899999999998e-01 , -5.7546699999999995e-01 , 4.1385699999999997e-01 -1.9988593243618145e+00 , 3.3808586205594802e+00 , 6.8935431999999999e+00 , -5.3281299999999998e-01 , -6.9796499999999995e-01 , -4.7849199999999997e-01 -1.9851974403468373e+00 , 3.3329053504273891e+00 , 6.9899200000000006e+00 , -5.7960500000000004e-01 , 2.6996100000000001e-01 , -7.6888199999999995e-01 -1.9716820107251556e+00 , 3.2796229484569324e+00 , 7.0756680000000003e+00 , -3.3751700000000001e-01 , -2.4782999999999999e-01 , 9.0810900000000006e-01 -1.8009259175134213e+00 , 3.4855297774368053e+00 , 8.4670632000000001e+00 , 1.8838600000000000e-01 , -7.2602000000000000e-01 , 6.6136700000000004e-01 -1.8320606893786533e+00 , 3.3349921720895725e+00 , 8.1797320000000013e+00 , 5.4014600000000002e-01 , 7.7499300000000004e-01 , 3.2806700000000000e-01 -1.8166559869321846e+00 , 3.2605175970184490e+00 , 8.2864152000000004e+00 , -9.3453699999999995e-01 , 2.4612899999999999e-01 , 2.5702500000000000e-01 -2.8501172981276133e+00 , 3.8655020751176785e+00 , 7.8989759999999998e-01 , -1.1387899999999999e-01 , 1.8649499999999999e-01 , 9.7583399999999998e-01 -2.8554823441901851e+00 , 3.9293886227528931e+00 , 7.8139040000000004e-01 , -1.1184900000000000e-01 , 1.7352000000000001e-01 , 9.7845800000000005e-01 -2.8606023568273891e+00 , 3.9925994197384940e+00 , 7.7471359999999989e-01 , -1.2414900000000000e-01 , 1.8332799999999999e-01 , 9.7518099999999996e-01 -2.8655781469993125e+00 , 4.0571498679774098e+00 , 7.6945120000000000e-01 , 9.2533500000000005e-02 , -1.6159899999999999e-01 , -9.8250899999999997e-01 -2.8715144809796196e+00 , 4.1287925186776340e+00 , 7.5738719999999993e-01 , -7.9291500000000001e-02 , 1.7271200000000000e-01 , 9.8177599999999998e-01 -2.8793643838048579e+00 , 4.2065426804155646e+00 , 7.3915599999999992e-01 , -7.5579800000000003e-02 , 1.9063099999999999e-01 , 9.7874799999999995e-01 -2.8848757791748287e+00 , 4.2800198776367147e+00 , 7.3082559999999996e-01 , -5.4061499999999998e-02 , 1.6811100000000001e-01 , 9.8428499999999997e-01 -2.8912020374863960e+00 , 4.3538744862334386e+00 , 7.2454400000000008e-01 , -7.9704999999999998e-02 , 1.8737200000000001e-01 , 9.7904999999999998e-01 -2.8995142520220560e+00 , 4.4428498518573756e+00 , 7.0415999999999990e-01 , -5.1463099999999998e-02 , 1.2278100000000000e-01 , 9.9109899999999995e-01 -2.9043527749876952e+00 , 4.5185994670346883e+00 , 7.0169520000000007e-01 , -5.6183499999999997e-02 , 1.7524999999999999e-01 , 9.8292000000000002e-01 -2.9141822697869300e+00 , 4.6154802517697000e+00 , 6.7867999999999995e-01 , -8.3838800000000005e-02 , 1.7808199999999999e-01 , 9.8043800000000003e-01 -2.9206594074738428e+00 , 4.7011017906600099e+00 , 6.7287679999999983e-01 , -8.7638099999999997e-02 , 1.6348399999999999e-01 , 9.8264600000000002e-01 -2.9279003948627746e+00 , 4.7941576750058879e+00 , 6.6198799999999980e-01 , -8.0039500000000000e-02 , 1.8693499999999999e-01 , 9.7910600000000003e-01 -2.9378909617297642e+00 , 4.9028074561955259e+00 , 6.3944080000000003e-01 , -3.3202900000000000e-02 , 2.0836099999999999e-01 , 9.7748800000000002e-01 -2.9475570032006400e+00 , 5.0131105197165509e+00 , 6.1982639999999978e-01 , -4.3055200000000002e-02 , 1.9086500000000001e-01 , 9.8067199999999999e-01 -2.9588788847759075e+00 , 5.1321535656419455e+00 , 5.9646800000000000e-01 , 4.1855999999999997e-02 , -1.6368800000000000e-01 , -9.8562399999999994e-01 -2.9698167366232684e+00 , 5.2529863931093397e+00 , 5.7665599999999984e-01 , -2.3237200000000000e-02 , 2.0397100000000001e-01 , 9.7870100000000004e-01 -2.9823290968912888e+00 , 5.3918596342935343e+00 , 5.4655839999999989e-01 , -4.9355599999999999e-02 , 1.9977300000000001e-01 , 9.7859799999999997e-01 -2.9933796814874007e+00 , 5.5234435645716804e+00 , 5.2742240000000007e-01 , -5.9024199999999999e-02 , 1.7831800000000000e-01 , 9.8220099999999999e-01 -3.0069077918065403e+00 , 5.6732721822840304e+00 , 4.9923839999999986e-01 , -4.9331399999999997e-02 , 1.8250400000000000e-01 , 9.8196700000000003e-01 -3.0199752807956566e+00 , 5.8261059924345302e+00 , 4.7530799999999984e-01 , -4.3007299999999998e-02 , 1.7403600000000000e-01 , 9.8380000000000001e-01 -3.0353182371259027e+00 , 5.9964537816982837e+00 , 4.4396239999999998e-01 , -4.6059200000000002e-02 , 1.8192800000000001e-01 , 9.8223300000000002e-01 -3.0500846019439587e+00 , 6.1689131101134791e+00 , 4.1768159999999988e-01 , -4.9955199999999998e-02 , 1.7853800000000000e-01 , 9.8266399999999998e-01 -3.0661453667971510e+00 , 6.3518431124816264e+00 , 3.9097439999999994e-01 , -4.4393200000000001e-02 , 1.8952600000000000e-01 , 9.8087199999999997e-01 -3.0841616919985677e+00 , 6.5631308922641702e+00 , 3.5256719999999975e-01 , -4.7528200000000000e-02 , 1.8362200000000001e-01 , 9.8184700000000003e-01 -3.1042976109819191e+00 , 6.7852157939131930e+00 , 3.1548080000000001e-01 , -3.6408299999999998e-02 , 2.0448800000000000e-01 , 9.7819199999999995e-01 -3.1279805976692185e+00 , 7.0456057397457643e+00 , 2.6374079999999989e-01 , -4.3124900000000001e-02 , 1.9433700000000001e-01 , 9.7998700000000005e-01 -3.1506998031147200e+00 , 7.3087609326410687e+00 , 2.2029999999999994e-01 , -3.9863900000000001e-02 , 1.8683800000000000e-01 , 9.8158199999999995e-01 -3.1769154443360712e+00 , 7.6022522631294374e+00 , 1.7003680000000010e-01 , -3.9820599999999998e-02 , 1.8018600000000001e-01 , 9.8282599999999998e-01 -3.2036077829634126e+00 , 7.9178909718116968e+00 , 1.1910799999999977e-01 , -3.7987300000000002e-02 , 1.7987500000000001e-01 , 9.8295600000000005e-01 -3.2359450276255726e+00 , 8.2815875071449589e+00 , 5.4971199999999998e-02 , -4.3553099999999997e-02 , 1.8572700000000000e-01 , 9.8163599999999995e-01 -3.2694221797334668e+00 , 8.6680858246781973e+00 , -6.4824000000003323e-03 , -5.0787400000000003e-02 , 1.7664800000000000e-01 , 9.8296300000000003e-01 -3.3039408922339124e+00 , 9.0775569959085445e+00 , -6.4327200000000140e-02 , -5.8114800000000001e-02 , 1.7557100000000000e-01 , 9.8275000000000001e-01 -3.3466132111091689e+00 , 9.5664210097082609e+00 , -1.4273280000000010e-01 , 6.2224599999999998e-02 , -1.8111400000000000e-01 , -9.8149200000000003e-01 -3.3959255132401638e+00 , 1.0135548918643732e+01 , -2.3768479999999981e-01 , 7.0558899999999994e-02 , -1.8574700000000000e-01 , -9.8006099999999996e-01 -3.4487903522784116e+00 , 1.0748713203378337e+01 , -3.2934000000000019e-01 , -7.0030300000000004e-02 , 1.7228700000000000e-01 , 9.8255400000000004e-01 -3.5098386629232694e+00 , 1.1464260945621193e+01 , -4.3818639999999975e-01 , -6.0974199999999999e-02 , 1.8437600000000001e-01 , 9.8096300000000003e-01 -3.5875478808508667e+00 , 1.2360982105379632e+01 , -5.8762400000000037e-01 , -7.2583599999999998e-02 , 1.8136300000000000e-01 , 9.8073399999999999e-01 -3.6739332447863440e+00 , 1.3362786416068611e+01 , -7.4073280000000041e-01 , -6.4395999999999995e-02 , 1.8207400000000001e-01 , 9.8117399999999999e-01 -3.7916473405064011e+00 , 1.4706721828623010e+01 , -9.7013600000000011e-01 , -5.8232399999999997e-02 , 1.8410199999999999e-01 , 9.8118099999999997e-01 -3.9272073196555000e+00 , 1.6270219293984354e+01 , -1.2180720000000003e+00 , -5.9463400000000000e-02 , 1.7672299999999999e-01 , 9.8246299999999998e-01 -4.0840988614879938e+00 , 1.8124552028834184e+01 , -1.4940463999999998e+00 , -1.1239499999999999e-01 , 1.4708599999999999e-01 , 9.8271699999999995e-01 -4.1857379207512428e+00 , 1.9512662382401249e+01 , -1.5760399999999999e+00 , -1.1665800000000000e-01 , 1.5797900000000001e-01 , 9.8052700000000004e-01 -4.3150250714771721e+00 , 2.2744611581905755e+01 , -9.5953840000000001e-01 , -1.0548200000000001e-01 , 1.6241100000000000e-01 , 9.8106899999999997e-01 -8.4950582388851927e+00 , 7.0121568864078895e+01 , -9.1477599999999999e+00 , -1.7944499999999999e-01 , 1.5299599999999999e-01 , 9.7179800000000005e-01 -7.8187312686444512e+00 , 6.4189729580892859e+01 , -6.9701976000000005e+00 , -5.6724500000000000e-01 , -2.6076199999999999e-01 , -7.8117599999999998e-01 -6.4488550217575673e+00 , 5.5563425421166095e+01 , -8.8025920000000024e-01 , -5.2080099999999996e-01 , -7.9954999999999998e-01 , 2.9914200000000002e-01 -5.9506436043812698e+00 , 5.7346933511979231e+01 , 3.7602416000000001e+00 , -1.6970099999999999e-01 , -9.8197400000000001e-01 , -8.3243300000000006e-02 -2.8561027428556329e+00 , 1.2394083003476416e+01 , 4.9544528000000003e+00 , -3.7101699999999999e-01 , -9.2808599999999997e-01 , -3.1664400000000002e-02 -2.9663039503871160e+00 , 1.5913927142791502e+01 , 5.8576303999999997e+00 , 2.8766199999999997e-01 , -8.9405400000000002e-01 , 3.4339100000000000e-01 -2.9375615787832272e+00 , 1.6036924676829969e+01 , 6.1296632000000004e+00 , -2.8766199999999997e-01 , 8.9405400000000002e-01 , -3.4339100000000000e-01 -2.7909015129888677e+00 , 1.2608992602535789e+01 , 5.5486984000000001e+00 , 1.9953899999999999e-01 , 8.8588800000000001e-01 , -4.1879300000000003e-01 -2.7652783108520023e+00 , 1.2586098500309818e+01 , 5.7300015999999996e+00 , -5.1367499999999999e-01 , -8.4111800000000003e-01 , -1.6928900000000000e-01 -2.7382571579036719e+00 , 1.2509481384624722e+01 , 5.8973272000000003e+00 , 6.6223900000000002e-01 , 7.4763400000000002e-01 , 4.9827900000000001e-02 -2.7198765768046504e+00 , 1.2777930435129996e+01 , 6.1667079999999999e+00 , -6.9145000000000001e-01 , -6.8109900000000001e-01 , -2.4083599999999999e-01 -2.6911676193321936e+00 , 1.2654726162992846e+01 , 6.3235815999999998e+00 , 3.7387100000000001e-01 , 6.9539200000000001e-01 , 6.1371900000000001e-01 -2.6600104388044130e+00 , 1.2420580869812483e+01 , 6.4407480000000001e+00 , -4.8330699999999999e-01 , -7.8250399999999998e-01 , -3.9255800000000002e-01 -2.6339480341981725e+00 , 1.2351745341688840e+01 , 6.6099975999999998e+00 , -4.0813700000000003e-01 , -7.6777899999999999e-01 , -4.9390299999999998e-01 -2.6077519751253329e+00 , 1.2328745727137020e+01 , 6.7959600000000009e+00 , -2.4165600000000001e-01 , -9.6890299999999996e-01 , 5.3189599999999997e-02 -2.5833729429490893e+00 , 1.2485969162234175e+01 , 7.0545872000000003e+00 , -2.0539299999999999e-01 , -9.7821100000000005e-01 , 3.0290899999999999e-02 -2.5553063629244099e+00 , 1.2329129237124407e+01 , 7.1925016000000008e+00 , -9.7238599999999997e-01 , -4.4587500000000002e-02 , -2.2908100000000001e-01 -2.5237408696288282e+00 , 1.1770135483214359e+01 , 7.1517960000000000e+00 , 4.1351399999999999e-01 , -2.4659900000000001e-01 , -8.7646800000000002e-01 -2.4986216829440475e+00 , 1.1841128198979114e+01 , 7.3775800000000000e+00 , -2.7927800000000003e-01 , 1.2031300000000000e-01 , 9.5264300000000002e-01 -2.4714037605132564e+00 , 1.1521329347022213e+01 , 7.4235376000000004e+00 , -3.7122600000000000e-01 , 3.4501700000000002e-01 , 8.6206400000000005e-01 -2.4472176249828888e+00 , 9.8902211350867475e+00 , 6.8063808000000003e+00 , -9.5126299999999997e-02 , 6.2578599999999995e-01 , 7.7417300000000000e-01 -2.4254886346820381e+00 , 9.7237890909278626e+00 , 6.8821344000000000e+00 , 3.8558599999999998e-01 , -2.8843400000000002e-01 , -8.7643000000000004e-01 -2.4065716077013142e+00 , 9.4182157351354920e+00 , 6.8793055999999995e+00 , 3.6299799999999999e-01 , 1.2766800000000000e-01 , -9.2300199999999999e-01 -2.3887881744843793e+00 , 9.0344954540043823e+00 , 6.8208055999999999e+00 , 6.7280600000000002e-01 , 4.8678500000000002e-01 , 5.5711100000000002e-01 -2.3632478694126262e+00 , 9.4449503493944125e+00 , 7.2135304000000007e+00 , -4.1111700000000001e-01 , 9.1153300000000004e-01 , -9.4716499999999999e-03 -2.3711606736172586e+00 , 7.5344638469281904e+00 , 6.2126239999999999e+00 , 2.9355700000000001e-01 , 9.5594100000000004e-01 , -4.0988500000000002e-04 -2.3543233397260361e+00 , 7.5854878684325326e+00 , 6.3673967999999999e+00 , 2.9355700000000001e-01 , 9.5594100000000004e-01 , -4.0999199999999997e-04 -2.3136135792745431e+00 , 8.6736713074427669e+00 , 7.2115544000000007e+00 , 7.4982199999999999e-01 , 2.4657000000000001e-01 , 6.1397900000000005e-01 -2.3004995198854044e+00 , 8.3860086447450541e+00 , 7.1723568000000002e+00 , 5.7722799999999996e-01 , 2.7097900000000003e-01 , 7.7031000000000005e-01 -2.2820286989874607e+00 , 8.3053733211723415e+00 , 7.2688272000000005e+00 , 8.3032099999999998e-01 , -3.7212099999999998e-01 , -4.1484100000000002e-01 -2.2392270309978333e+00 , 9.0111072344612708e+00 , 7.9429656000000000e+00 , 7.1448900000000004e-01 , -5.9019400000000000e-01 , -3.7573600000000001e-01 -2.2372057450823668e+00 , 8.3799166791392441e+00 , 7.6398264000000005e+00 , -9.6416299999999999e-01 , -2.0021500000000000e-01 , -1.7408199999999999e-01 -2.2376340747280641e+00 , 7.8184098218723763e+00 , 7.3616055999999999e+00 , -3.7337599999999999e-01 , -4.2942300000000000e-01 , 8.2230599999999998e-01 -2.2264143803424634e+00 , 7.6233240863742271e+00 , 7.3553552000000000e+00 , 4.0159800000000001e-01 , -8.0495300000000003e-01 , -4.3677100000000002e-01 -2.1740243888772617e+00 , 8.2922873285443455e+00 , 8.0767927999999998e+00 , -3.9134900000000000e-01 , 2.8004700000000000e-02 , 9.1981599999999997e-01 -2.1768630330939134e+00 , 7.7677833202703468e+00 , 7.7930288000000001e+00 , 4.8388799999999998e-01 , -3.7910899999999997e-01 , 7.8875099999999998e-01 -2.1693022340012935e+00 , 7.5155958623117058e+00 , 7.7308056000000001e+00 , 8.1656200000000001e-01 , -2.0992400000000000e-01 , 5.3773400000000005e-01 -2.1522675716968607e+00 , 7.4419050880385731e+00 , 7.8251544000000006e+00 , -7.8724700000000003e-01 , 3.1292500000000001e-01 , -5.3133799999999998e-01 -2.1396504726295040e+00 , 7.2915607808662530e+00 , 7.8457464000000003e+00 , -9.8769799999999996e-01 , 1.1782700000000000e-02 , -1.5592900000000001e-01 -2.0893953689640101e+00 , 7.6968359541719611e+00 , 8.4235912000000006e+00 , 2.8573500000000002e-01 , -1.8938500000000000e-01 , -9.3940900000000005e-01 -1.9936363250971227e+00 , 8.6660154327025047e+00 , 9.6245000000000012e+00 , 2.8443400000000002e-01 , -6.5868800000000005e-02 , 9.5643000000000000e-01 -2.0815595740310289e+00 , 7.1414427345250449e+00 , 8.2055655999999999e+00 , -3.5561299999999997e-02 , -2.6407300000000000e-01 , 9.6384700000000001e-01 -2.0753403649853972e+00 , 6.9270283561038983e+00 , 8.1466080000000005e+00 , 3.6901600000000001e-01 , -3.5791899999999999e-01 , 8.5774200000000000e-01 -2.0647077084955097e+00 , 6.7837715754689762e+00 , 8.1606167999999997e+00 , -7.8684799999999999e-01 , 6.1684899999999998e-01 , 1.9177199999999998e-02 -1.9217961345504164e+00 , 8.0492487188415414e+00 , 9.8629303999999998e+00 , -3.6766700000000002e-01 , -8.0683299999999999e-02 , 9.2645100000000002e-01 -2.0354067800040658e+00 , 6.5777410869078432e+00 , 8.2754016000000004e+00 , -9.6633100000000005e-01 , -1.2393500000000000e-01 , -2.2548499999999999e-01 -1.9158428361658797e+00 , 7.4723455261508223e+00 , 9.6176048000000005e+00 , 8.3592100000000003e-01 , 2.9319800000000001e-01 , 4.6397300000000002e-01 -1.9435519951912474e+00 , 6.9468768982399549e+00 , 9.1551375999999998e+00 , -9.2437099999999994e-02 , -9.3295799999999995e-01 , 3.4791400000000000e-01 -1.9364812735682884e+00 , 6.7492895711018193e+00 , 9.1057480000000002e+00 , -5.3190000000000004e-01 , -8.4368900000000002e-01 , 7.2600899999999996e-02 -1.9148879004993553e+00 , 6.6846707560038592e+00 , 9.2389408000000000e+00 , 3.7123099999999998e-01 , -5.9243900000000002e-02 , 9.2664899999999994e-01 -1.9338355469472235e+00 , 6.3116539712000002e+00 , 8.9146792000000001e+00 , 1.1804199999999999e-01 , 2.9540299999999999e-02 , 9.9256900000000003e-01 -1.9223935850543066e+00 , 6.1807653460672007e+00 , 8.9371536000000003e+00 , 3.3044899999999999e-01 , -2.5581699999999999e-02 , 9.4347700000000001e-01 -1.8854057651507299e+00 , 6.2200855876135162e+00 , 9.2298720000000003e+00 , 1.8013600000000001e-02 , 9.9979399999999996e-01 , -9.3276599999999998e-03 -1.8586295983310321e+00 , 6.1860597327406968e+00 , 9.4188919999999996e+00 , -4.8831100000000000e-01 , 8.1390799999999996e-01 , 3.1481100000000001e-01 -1.7414626032559148e+00 , 6.6881628782036087e+00 , 1.0552648000000000e+01 , 8.3364700000000003e-01 , 4.5458399999999999e-01 , -3.1366600000000000e-01 -1.8357946464808754e+00 , 5.9176177609898497e+00 , 9.4624576000000005e+00 , 7.2484300000000002e-01 , -1.2833600000000001e-01 , 6.7685499999999998e-01 -1.9398796598738655e+00 , 5.1613484250065511e+00 , 8.3028992000000006e+00 , 3.9694900000000001e-04 , 9.0257500000000002e-01 , 4.3053300000000000e-01 -1.9262929811185008e+00 , 5.0743387684137424e+00 , 8.3582895999999991e+00 , 2.3507900000000001e-01 , -9.0144800000000003e-01 , -3.6349500000000001e-01 -1.8897431874503354e+00 , 5.0997512021344260e+00 , 8.6452776000000000e+00 , -4.4915300000000002e-01 , 7.3962099999999997e-01 , -5.0122100000000003e-01 -1.8835886584575856e+00 , 4.9756221695698084e+00 , 8.6339520000000007e+00 , -6.5996100000000002e-01 , 5.9604199999999996e-01 , -4.5736800000000000e-01 -1.8756230647258076e+00 , 4.8612387983676157e+00 , 8.6389960000000006e+00 , -7.8612400000000004e-01 , 3.1775500000000001e-01 , 5.3013299999999997e-01 -2.0794141158010482e+00 , 3.8996010998994128e+00 , 6.6289256000000005e+00 , 5.7633400000000001e-01 , -2.0357900000000001e-01 , -7.9145100000000002e-01 -2.0721885553421489e+00 , 3.8339048515865568e+00 , 6.6438808000000007e+00 , -4.0133999999999997e-01 , 5.5635100000000004e-01 , 7.2759900000000000e-01 -2.0604805607161771e+00 , 3.7894992770661453e+00 , 6.7161296000000004e+00 , 7.0708300000000002e-02 , -7.9592900000000000e-01 , -6.0124599999999995e-01 -2.0500014872144381e+00 , 3.7356757188379537e+00 , 6.7682440000000001e+00 , -2.1023900000000001e-01 , -7.4341100000000004e-01 , -6.3493299999999997e-01 -2.0362067722266484e+00 , 3.6909532603987749e+00 , 6.8489687999999997e+00 , 3.9473200000000003e-01 , 7.2414100000000003e-01 , 5.6551499999999999e-01 -2.0167350119620786e+00 , 3.6594586229128674e+00 , 6.9783656000000001e+00 , -6.4998800000000001e-01 , -6.5346300000000002e-01 , -3.8794600000000001e-01 -1.7378603591244506e+00 , 4.3224423160985541e+00 , 9.4137127999999990e+00 , 6.7363499999999998e-01 , -4.3946200000000002e-01 , 5.9421299999999999e-01 -1.9055377585050641e+00 , 3.7649883067199204e+00 , 7.8737015999999995e+00 , -2.1516199999999999e-01 , -6.5537500000000004e-01 , 7.2400900000000001e-01 -2.0116989951957525e+00 , 3.4159856717114927e+00 , 6.8966735999999997e+00 , -3.7918900000000000e-01 , -6.4389300000000005e-01 , 6.6454299999999999e-01 -2.0006289886380735e+00 , 3.3588164221303822e+00 , 6.9531456000000000e+00 , -7.7709399999999995e-01 , -5.7797100000000001e-01 , -2.4914900000000001e-01 -1.9919732663513705e+00 , 3.2952284700837797e+00 , 6.9887760000000005e+00 , -6.6910599999999998e-01 , -5.3882500000000000e-01 , -5.1182399999999995e-01 -1.8062531023356503e+00 , 3.5426915555346277e+00 , 8.5094431999999998e+00 , -8.8420299999999993e-02 , 8.2878499999999999e-01 , -5.5253799999999997e-01 -1.8244497968238862e+00 , 3.4039735562097264e+00 , 8.3044176000000007e+00 , -8.0590200000000001e-01 , 1.7765800000000002e-02 , -5.9178299999999995e-01 -1.8239179401907841e+00 , 3.3024514087852737e+00 , 8.2589383999999999e+00 , -3.5109699999999999e-01 , 1.5657399999999999e-01 , -9.2315499999999995e-01 -2.8918127585054387e+00 , 3.7693245368557688e+00 , 8.1157119999999994e-01 , -1.2447200000000000e-01 , 1.2559799999999999e-01 , 9.8424199999999995e-01 -2.8994239370051629e+00 , 3.8306633367886445e+00 , 8.0141039999999997e-01 , -1.0960600000000000e-01 , 1.6210300000000000e-01 , 9.8066799999999998e-01 -2.9046843491961694e+00 , 3.8877372987361096e+00 , 8.0124400000000007e-01 , -1.1937700000000000e-01 , 1.9222600000000001e-01 , 9.7406300000000001e-01 -2.9131311405831548e+00 , 3.9563658183825710e+00 , 7.8529039999999983e-01 , 9.2652999999999999e-02 , -1.6575899999999999e-01 , -9.8180400000000001e-01 -2.9202312922728106e+00 , 4.0197021098021342e+00 , 7.7967439999999999e-01 , -9.4296000000000005e-02 , 1.6466400000000000e-01 , 9.8183200000000004e-01 -2.9293684134261357e+00 , 4.0911022241689157e+00 , 7.6706959999999991e-01 , -7.9642800000000000e-02 , 1.8857900000000000e-01 , 9.7882300000000000e-01 -2.9372439775764647e+00 , 4.1629151342820290e+00 , 7.5627440000000012e-01 , -3.7454300000000003e-02 , 1.7099300000000001e-01 , 9.8455999999999999e-01 -2.9449023241228187e+00 , 4.2351190846904103e+00 , 7.4739280000000008e-01 , 7.3776499999999995e-02 , -1.7735699999999999e-01 , -9.8137700000000005e-01 -2.9544918626430867e+00 , 4.3144952709203386e+00 , 7.3233360000000003e-01 , -4.9668100000000000e-02 , 1.7394599999999999e-01 , 9.8350199999999999e-01 -2.9649213176705085e+00 , 4.3963762519324820e+00 , 7.1933360000000013e-01 , -6.7485000000000003e-02 , 1.4685999999999999e-01 , 9.8685299999999998e-01 -2.9719088579735704e+00 , 4.4708424276046159e+00 , 7.1621359999999989e-01 , -7.0217799999999997e-02 , 1.3793600000000000e-01 , 9.8794899999999997e-01 -2.9829415490622013e+00 , 4.5615259172418305e+00 , 6.9963599999999992e-01 , -7.5570300000000007e-02 , 1.6290099999999999e-01 , 9.8374399999999995e-01 -2.9936267273502009e+00 , 4.6517251131113815e+00 , 6.8579360000000000e-01 , -7.2921899999999998e-02 , 1.7368500000000001e-01 , 9.8209800000000003e-01 -3.0051192662423478e+00 , 4.7514473332345446e+00 , 6.6676160000000007e-01 , -4.3360400000000000e-02 , 1.9550799999999999e-01 , 9.7974300000000003e-01 -3.0173119298473781e+00 , 4.8517465481465987e+00 , 6.5069360000000009e-01 , -1.3561800000000001e-02 , 1.9641400000000001e-01 , 9.8042700000000005e-01 -3.0322554048839203e+00 , 4.9687328966024431e+00 , 6.2316480000000007e-01 , -3.1358700000000003e-02 , 1.8085000000000001e-01 , 9.8301099999999997e-01 -3.0437990176967231e+00 , 5.0723386761772726e+00 , 6.1284799999999984e-01 , -6.3013600000000003e-02 , 1.5265500000000001e-01 , 9.8626899999999995e-01 -3.0560011004676548e+00 , 5.1846838801744681e+00 , 5.9856880000000001e-01 , -2.9663499999999999e-02 , 2.0250099999999999e-01 , 9.7883299999999995e-01 -3.0748476306666039e+00 , 5.3301574946879597e+00 , 5.6048399999999998e-01 , -3.3072200000000003e-02 , 1.9405500000000001e-01 , 9.8043300000000000e-01 -3.0872634671600432e+00 , 5.4450079022749076e+00 , 5.5340159999999994e-01 , -5.7963199999999999e-02 , 1.6723800000000000e-01 , 9.8421099999999995e-01 -3.1032067594991188e+00 , 5.5861152987992249e+00 , 5.2987679999999981e-01 , -6.1858099999999999e-02 , 1.9438200000000000e-01 , 9.7897400000000001e-01 -3.1225559467780792e+00 , 5.7445519740199700e+00 , 4.9826079999999995e-01 , -5.4347600000000003e-02 , 1.8981300000000001e-01 , 9.8031500000000005e-01 -3.1405072546720785e+00 , 5.8977921494547907e+00 , 4.7738799999999992e-01 , -5.1570699999999997e-02 , 1.8803400000000001e-01 , 9.8080800000000001e-01 -3.1587872809653508e+00 , 6.0602991507050676e+00 , 4.5516319999999988e-01 , -5.2809700000000001e-02 , 1.8622500000000000e-01 , 9.8108700000000004e-01 -3.1831003146623500e+00 , 6.2581133181478679e+00 , 4.1450959999999992e-01 , -4.7577200000000000e-02 , 1.8747500000000000e-01 , 9.8111599999999999e-01 -3.2067641594543290e+00 , 6.4592870798765318e+00 , 3.7980480000000005e-01 , -5.6608800000000001e-02 , 1.9052300000000000e-01 , 9.8004899999999995e-01 -3.2315626248482214e+00 , 6.6711962493352122e+00 , 3.4591119999999997e-01 , -3.4430099999999998e-02 , 1.9280600000000001e-01 , 9.8063299999999998e-01 -3.2620440822224479e+00 , 6.9212385793960713e+00 , 2.9699999999999993e-01 , -3.5393899999999999e-02 , 2.0258300000000001e-01 , 9.7862499999999997e-01 -3.2934510691259806e+00 , 7.1824196163356646e+00 , 2.5082399999999994e-01 , -4.1222300000000003e-02 , 1.8919700000000000e-01 , 9.8107400000000000e-01 -3.3265655942484820e+00 , 7.4653820668627819e+00 , 2.0248479999999991e-01 , -4.5653899999999997e-02 , 1.8726999999999999e-01 , 9.8124699999999998e-01 -3.3621979904635997e+00 , 7.7683270616453477e+00 , 1.5372959999999991e-01 , -5.2834199999999998e-02 , 1.7699100000000001e-01 , 9.8279300000000003e-01 -3.4003200054882221e+00 , 8.0934879052233875e+00 , 1.0506799999999994e-01 , -5.2116000000000003e-02 , 1.8469400000000000e-01 , 9.8141299999999998e-01 -3.4440893904545673e+00 , 8.4688930488524914e+00 , 4.3489600000000017e-02 , -5.7759100000000001e-02 , 1.8261400000000000e-01 , 9.8148700000000000e-01 -3.4923800600996318e+00 , 8.8844455064407377e+00 , -2.3392799999999880e-02 , 6.5341499999999997e-02 , -1.7691399999999999e-01 , -9.8205500000000001e-01 -3.5443141225874788e+00 , 9.3318601161765269e+00 , -8.9474400000000287e-02 , -7.0421499999999998e-02 , 1.7747199999999999e-01 , 9.8160300000000000e-01 -3.6028469723195009e+00 , 9.8416816868563171e+00 , -1.6585200000000011e-01 , -2.4884700000000001e-01 , 2.1793799999999999e-01 , 9.4370399999999999e-01 -3.6726202341465157e+00 , 1.0440743240947663e+01 , -2.6073119999999994e-01 , -7.0656700000000003e-02 , 1.7177899999999999e-01 , 9.8259799999999997e-01 -3.7451481688742501e+00 , 1.1075370612514924e+01 , -3.4712399999999999e-01 , -6.5601400000000004e-02 , 1.7747299999999999e-01 , 9.8193699999999995e-01 -3.8455570048842498e+00 , 1.1926383977436672e+01 , -4.9192320000000000e-01 , -6.5481800000000007e-02 , 1.8444700000000000e-01 , 9.8065899999999995e-01 -3.9508564213207222e+00 , 1.2834725292939373e+01 , -6.2522000000000011e-01 , -6.4999100000000004e-02 , 1.7907200000000001e-01 , 9.8168699999999998e-01 -4.0914168333476626e+00 , 1.4034337920872613e+01 , -8.2327759999999994e-01 , -6.0936799999999999e-02 , 1.8331900000000001e-01 , 9.8116300000000001e-01 -4.2605507688741771e+00 , 1.5479637411551954e+01 , -1.0550416000000000e+00 , -5.8901500000000002e-02 , 1.8121599999999999e-01 , 9.8167800000000005e-01 -4.4583489013181881e+00 , 1.7184362845904847e+01 , -1.3109128000000001e+00 , -7.9192299999999993e-02 , 1.6436100000000001e-01 , 9.8321599999999998e-01 -4.6106908042654382e+00 , 1.8624136118266300e+01 , -1.4313760000000002e+00 , -1.0594500000000000e-01 , 1.4463300000000001e-01 , 9.8379700000000003e-01 -7.9021135780912690e+00 , 5.6302532254555480e+01 , 6.7945999999999995e-01 , -5.2856999999999998e-01 , 6.1502800000000002e-01 , -5.8511000000000002e-01 -7.7866708003093201e+00 , 5.7775037381474228e+01 , 2.5405483200000001e+00 , -1.6970099999999999e-01 , -9.8197400000000001e-01 , -8.3243399999999995e-02 -3.0983200100062818e+00 , 1.2748540088562425e+01 , 5.5321727999999997e+00 , -9.1863500000000001e-02 , -8.9645500000000000e-01 , -4.3350899999999998e-01 -3.0591942597946797e+00 , 1.2525279861595644e+01 , 5.6647520000000000e+00 , -9.1863600000000004e-02 , -8.9645500000000000e-01 , -4.3351000000000001e-01 -3.0315658650398056e+00 , 1.2500132881529066e+01 , 5.8449944000000000e+00 , 7.7281799999999998e-02 , 8.8238899999999998e-01 , 4.6412999999999999e-01 -3.0009002750274369e+00 , 1.2403018344212796e+01 , 6.0046863999999998e+00 , 1.2079500000000000e-01 , 9.0784399999999998e-01 , 4.0153100000000003e-01 -2.9716240121523638e+00 , 1.2351974163455441e+01 , 6.1772640000000010e+00 , -2.6034600000000002e-01 , -9.3704299999999996e-01 , -2.3274600000000001e-01 -2.9399030395647157e+00 , 1.2219181976334008e+01 , 6.3230304000000004e+00 , 4.8135000000000000e-01 , 8.5258100000000003e-01 , 2.0348900000000000e-01 -2.9206778470723651e+00 , 1.2369459668893986e+01 , 6.5641335999999999e+00 , -4.8881400000000003e-01 , -7.7526799999999996e-01 , -4.0002500000000002e-01 -2.8093062458213707e+00 , 1.0456461752344470e+01 , 6.0523287999999997e+00 , -3.7464900000000001e-01 , 8.8841499999999995e-01 , -2.6524700000000001e-01 -2.7856836344918157e+00 , 1.0424274257027612e+01 , 6.1984800000000000e+00 , 7.9463300000000003e-01 , -5.4975499999999999e-01 , 2.5754300000000002e-01 -2.7668282080264577e+00 , 1.0505407933902321e+01 , 6.3915872000000009e+00 , 7.9463300000000003e-01 , -5.4975499999999999e-01 , 2.5754300000000002e-01 -2.7322463666022405e+00 , 1.0160898327180373e+01 , 6.4082167999999999e+00 , 8.1968500000000000e-01 , 1.2368200000000000e-01 , 5.5930299999999999e-01 -2.7047519252953940e+00 , 1.0008355320781442e+01 , 6.4990192000000002e+00 , -6.3395000000000001e-01 , -8.4156099999999998e-02 , -7.6878199999999997e-01 -2.7298395818013899e+00 , 1.1539218817049244e+01 , 7.3777255999999998e+00 , -1.1263300000000000e-01 , -3.0663499999999999e-01 , -9.4513899999999995e-01 -2.6288860346400602e+00 , 8.8236290460785511e+00 , 6.2365024000000000e+00 , 3.6489800000000000e-01 , -8.2111999999999996e-01 , 4.3887500000000002e-01 -2.6126114969418617e+00 , 8.9538017826772318e+00 , 6.4417048000000001e+00 , 5.3355200000000003e-01 , -6.0483900000000002e-01 , 5.9117799999999998e-01 -2.5973967942970515e+00 , 9.1524002346681534e+00 , 6.6915856000000007e+00 , 5.9358999999999995e-01 , 4.1125600000000001e-01 , 6.9175100000000000e-01 -2.5738666309933587e+00 , 8.9797773479968264e+00 , 6.7468095999999997e+00 , -5.2392099999999997e-01 , -7.8070099999999998e-01 , 3.4060600000000002e-01 -2.5808606983020983e+00 , 1.0787149159994991e+01 , 7.9453367999999998e+00 , 1.8815000000000001e-01 , 3.9888400000000002e-01 , 8.9749199999999996e-01 -2.5152500755907181e+00 , 7.6038474445349067e+00 , 6.2188119999999998e+00 , -1.3796700000000001e-01 , 7.4381399999999998e-01 , 6.5399200000000002e-01 -2.4976310487418982e+00 , 7.5407346298835174e+00 , 6.3023552000000000e+00 , -4.7051700000000002e-02 , 9.3666600000000000e-01 , 3.4704800000000002e-01 -2.4908642795139908e+00 , 9.3667310376252573e+00 , 7.6167487999999999e+00 , 2.8627300000000000e-01 , 5.8777000000000001e-01 , 7.5668700000000000e-01 -2.4679947536203786e+00 , 9.6577958826518611e+00 , 7.9866663999999998e+00 , 4.9857800000000002e-01 , 5.5658399999999997e-02 , 8.6505600000000005e-01 -2.4454753398730427e+00 , 7.5464932797033217e+00 , 6.6887256000000006e+00 , -6.1930700000000005e-01 , -7.6090300000000000e-01 , 1.9361200000000001e-01 -2.4267808027997049e+00 , 7.6848875193363861e+00 , 6.9236928000000004e+00 , -7.2802199999999995e-01 , 6.7046700000000004e-01 , 1.4302899999999999e-01 -2.4035088773862565e+00 , 8.0826863943990865e+00 , 7.3647360000000006e+00 , 8.4852200000000000e-01 , 2.8702299999999997e-01 , 4.4455499999999998e-01 -2.3836480166637126e+00 , 7.9593868689985419e+00 , 7.4231423999999997e+00 , -2.1518800000000001e-02 , -6.8821400000000005e-02 , 9.9739699999999998e-01 -2.3618795523354734e+00 , 7.9803993942953770e+00 , 7.5965727999999997e+00 , 5.0196700000000005e-01 , -1.9034499999999999e-01 , 8.4368100000000001e-01 -2.3323028195492572e+00 , 8.3877333645748209e+00 , 8.0994752000000005e+00 , -7.4070599999999998e-01 , -2.6278299999999999e-01 , 6.1830499999999999e-01 -2.3098627048153357e+00 , 8.2766342157629218e+00 , 8.1809176000000008e+00 , 7.4070599999999998e-01 , 2.6278299999999999e-01 , -6.1830399999999996e-01 -2.2933238895567909e+00 , 8.0094260879881745e+00 , 8.1212736000000003e+00 , 6.3404400000000005e-01 , -6.7220800000000003e-01 , -3.8226199999999999e-01 -2.3079670196882378e+00 , 6.7874637374568874e+00 , 7.1610000000000005e+00 , 6.9658399999999998e-01 , -1.6806099999999999e-01 , -6.9751399999999997e-01 -2.2901232397129729e+00 , 6.7385990859022682e+00 , 7.2571896000000002e+00 , 6.9658399999999998e-01 , -1.6806099999999999e-01 , -6.9751399999999997e-01 -2.2769174118002584e+00 , 6.5926771697514033e+00 , 7.2574392000000003e+00 , -6.6310599999999997e-01 , 1.1840299999999999e-01 , 7.3910200000000004e-01 -2.1669200694667654e+00 , 8.5077785965785608e+00 , 9.3820239999999995e+00 , -4.4077400000000003e-02 , 3.3929999999999999e-01 , 9.3964499999999995e-01 -2.2100534614718295e+00 , 7.0912459351614299e+00 , 8.0892312000000004e+00 , -8.8403500000000002e-01 , -3.6168800000000001e-01 , -2.9608200000000001e-01 -2.1841746018119284e+00 , 7.1289236451298335e+00 , 8.3075896000000000e+00 , -4.9027399999999999e-01 , 3.8882000000000001e-03 , 8.7156000000000000e-01 -2.1849766237426240e+00 , 6.7035110535096720e+00 , 8.0039720000000010e+00 , 7.2368299999999997e-01 , -3.0267899999999998e-01 , 6.2021700000000002e-01 -2.1655202219051257e+00 , 6.6308786508319564e+00 , 8.0925799999999999e+00 , 8.0069299999999999e-01 , -4.4504999999999996e-03 , 5.9905900000000001e-01 -2.1403803408992963e+00 , 6.6479500182702340e+00 , 8.2931544000000006e+00 , 7.6160600000000001e-01 , -6.3116099999999997e-01 , -1.4694199999999999e-01 -2.1168569108305104e+00 , 6.6144880220638083e+00 , 8.4382967999999998e+00 , 7.4405699999999997e-01 , -6.2354500000000002e-01 , -2.3993800000000001e-01 -2.0696885342060600e+00 , 6.8530451726364934e+00 , 8.9482192000000005e+00 , -1.1513700000000000e-01 , 6.0271100000000000e-01 , 7.8961000000000003e-01 -2.0332927824273606e+00 , 6.9222932032140001e+00 , 9.2578063999999998e+00 , -9.2437099999999994e-02 , -9.3295799999999995e-01 , 3.4791400000000000e-01 -2.0022864049008877e+00 , 6.9219609642815394e+00 , 9.4867312000000013e+00 , 4.7766900000000001e-01 , -6.3138799999999995e-01 , 6.1088600000000004e-01 -2.0358010571178209e+00 , 6.3022291213591082e+00 , 8.8158583999999998e+00 , 4.9760199999999997e-02 , 1.0832000000000000e-01 , 9.9287000000000003e-01 -2.0175116221510736e+00 , 6.1965873699247132e+00 , 8.8726216000000004e+00 , 8.0787100000000001e-02 , 8.4181800000000001e-02 , 9.9317000000000000e-01 -2.0069835058247767e+00 , 6.0343359296446657e+00 , 8.8397888000000009e+00 , 4.4808300000000002e-02 , 1.2023800000000000e-01 , 9.9173299999999998e-01 -1.9873627145103521e+00 , 5.9437685626035215e+00 , 8.9183920000000008e+00 , -2.0573500000000000e-01 , 6.2188600000000005e-01 , 7.5560000000000005e-01 -1.8849012278392581e+00 , 6.4427828704763987e+00 , 1.0008332800000000e+01 , -1.9885300000000000e-01 , 7.0403300000000002e-01 , -6.8175900000000000e-01 -1.9018134212038729e+00 , 6.0732585197331161e+00 , 9.6324351999999998e+00 , 2.6343699999999998e-01 , -8.0258300000000005e-01 , 5.3522099999999995e-01 -1.8929629420724303e+00 , 5.8953237521274531e+00 , 9.5748192000000003e+00 , 6.1820200000000003e-01 , -3.0904100000000001e-01 , 7.2271700000000005e-01 -1.9907191307683447e+00 , 5.0971187514693970e+00 , 8.3059152000000012e+00 , 3.9693600000000002e-04 , 9.0257500000000002e-01 , 4.3053300000000000e-01 -1.9720733462630859e+00 , 5.0292348474224351e+00 , 8.3971647999999988e+00 , 2.3507900000000001e-01 , -9.0144899999999994e-01 , -3.6349500000000001e-01 -1.9280311417246394e+00 , 5.0820130625632300e+00 , 8.7498704000000007e+00 , 1.6853899999999999e-01 , -6.4788800000000002e-01 , -7.4285699999999999e-01 -1.9253016615142635e+00 , 4.9232207238329284e+00 , 8.6620840000000001e+00 , -6.5329199999999998e-01 , 2.0805599999999999e-01 , 7.2795799999999999e-01 -2.1038195698697257e+00 , 3.9609061342572991e+00 , 6.6959952000000005e+00 , 6.5654400000000002e-01 , 3.0257099999999999e-02 , -7.5368000000000002e-01 -2.0987160314338520e+00 , 3.8780567458569788e+00 , 6.6736976000000006e+00 , -7.0837499999999998e-01 , 2.0290900000000001e-01 , 6.7604200000000003e-01 -2.0893797880911951e+00 , 3.8153707747137231e+00 , 6.6978463999999995e+00 , 2.7337400000000001e-01 , -7.3745700000000003e-01 , -6.1759500000000001e-01 -2.0778401414539993e+00 , 3.7627117257859437e+00 , 6.7502312000000000e+00 , 2.4608900000000000e-02 , 6.8805099999999997e-01 , 7.2524500000000003e-01 -2.0642101227464451e+00 , 3.7119210266428317e+00 , 6.8114872000000002e+00 , -1.6664999999999999e-01 , -7.9592600000000002e-01 , -5.8200499999999999e-01 -2.0495033551775341e+00 , 3.6630237529732903e+00 , 6.8818536000000003e+00 , 2.3011300000000001e-01 , 7.2883200000000004e-01 , 6.4486600000000005e-01 -2.0358610527593899e+00 , 3.6118591604592094e+00 , 6.9517520000000008e+00 , 6.0866500000000001e-01 , 6.7273499999999997e-01 , 4.2065999999999998e-01 -1.9062059314868101e+00 , 3.8667184827440320e+00 , 8.0730903999999999e+00 , -3.1839099999999998e-01 , -8.3865599999999996e-01 , 4.4190900000000000e-01 -2.0195692255850242e+00 , 3.4706598893780805e+00 , 6.9694839999999996e+00 , -2.5159199999999998e-01 , -5.4753399999999997e-01 , 7.9806500000000002e-01 -2.0239810822039423e+00 , 3.3711373654973040e+00 , 6.8664408000000003e+00 , -1.3726800000000000e-01 , 4.9734099999999998e-01 , 8.5662700000000003e-01 -2.0109495513694773e+00 , 3.3149181588067931e+00 , 6.9219559999999998e+00 , 3.4081200000000000e-01 , -1.0277600000000001e-01 , 9.3449700000000002e-01 -1.9896686656339257e+00 , 3.2720632545814894e+00 , 7.0472760000000001e+00 , 1.0608900000000000e-01 , 9.2246499999999998e-01 , 3.7121900000000002e-01 -1.8189102004803790e+00 , 3.4779802142689400e+00 , 8.4386711999999999e+00 , 1.8316299999999999e-01 , -7.7873800000000004e-01 , 6.0001499999999997e-01 -1.8222534476230581e+00 , 3.3621115560624597e+00 , 8.3333295999999990e+00 , -5.2014300000000002e-01 , 7.9532199999999997e-01 , 3.1130900000000000e-01 -1.8186763211115431e+00 , 3.2594627487214263e+00 , 8.2868728000000011e+00 , -9.3453699999999995e-01 , 2.4612899999999999e-01 , 2.5702500000000000e-01 -2.9443439007659653e+00 , 3.7893537137735627e+00 , 8.2207520000000001e-01 , -1.1016600000000000e-01 , 1.2159700000000000e-01 , 9.8644699999999996e-01 -2.9529093362556900e+00 , 3.8508010589828667e+00 , 8.1264239999999988e-01 , -1.1382299999999999e-01 , 1.5013000000000001e-01 , 9.8209199999999996e-01 -2.9634682303069577e+00 , 3.9182235483413446e+00 , 7.9642879999999994e-01 , 1.0725800000000001e-01 , -2.0451500000000000e-01 , -9.7296899999999997e-01 -2.9727609102361638e+00 , 3.9823650790537726e+00 , 7.9005359999999980e-01 , 8.6104700000000006e-02 , -1.3010600000000000e-01 , -9.8775400000000002e-01 -2.9829944446837304e+00 , 4.0525442801360771e+00 , 7.7686639999999985e-01 , 9.7112799999999999e-02 , -1.8731900000000001e-01 , -9.7748699999999999e-01 -2.9940347155415235e+00 , 4.1230886337405046e+00 , 7.6573840000000004e-01 , 8.3006899999999995e-02 , -2.0034500000000000e-01 , -9.7620300000000004e-01 -3.0038698952466936e+00 , 4.1950759355885880e+00 , 7.5620160000000003e-01 , 7.3078900000000002e-02 , -1.8057899999999999e-01 , -9.8084199999999999e-01 -3.0156281403944081e+00 , 4.2742232144047687e+00 , 7.4048719999999979e-01 , 7.6586500000000002e-02 , -1.7956600000000000e-01 , -9.8075999999999997e-01 -3.0281922877447629e+00 , 4.3548390751355122e+00 , 7.2692559999999995e-01 , -1.1010800000000000e-01 , 1.4740100000000000e-01 , 9.8292900000000005e-01 -3.0394722884334699e+00 , 4.4359268216060030e+00 , 7.1545440000000005e-01 , -1.0872999999999999e-01 , 1.5240500000000001e-01 , 9.8231900000000005e-01 -3.0494630875955986e+00 , 4.5115960333313936e+00 , 7.1372800000000014e-01 , 7.8858899999999996e-02 , -1.5851599999999999e-01 , -9.8420200000000002e-01 -3.0623497548621064e+00 , 4.6015092979548200e+00 , 6.9891839999999994e-01 , 7.2064699999999995e-02 , -1.8620400000000001e-01 , -9.7986499999999999e-01 -3.0739451544409953e+00 , 4.6860142205255553e+00 , 6.9395759999999984e-01 , -5.0528299999999998e-02 , 1.9964199999999999e-01 , 9.7856500000000002e-01 -3.0924967321319086e+00 , 4.7998587613431898e+00 , 6.6215440000000014e-01 , -3.2587699999999997e-02 , 2.2152800000000000e-01 , 9.7460899999999995e-01 -3.1096607612430622e+00 , 4.9084558389128539e+00 , 6.4088639999999986e-01 , -3.7130099999999999e-02 , 1.9017999999999999e-01 , 9.8104700000000000e-01 -3.1234467719168029e+00 , 5.0117309222626307e+00 , 6.2941519999999995e-01 , -5.8213200000000000e-02 , 1.6573299999999999e-01 , 9.8445099999999996e-01 -3.1399194712870537e+00 , 5.1226391223970538e+00 , 6.1422079999999979e-01 , -4.7821900000000001e-02 , 1.8726400000000001e-01 , 9.8114500000000004e-01 -3.1590261776990625e+00 , 5.2504442321809961e+00 , 5.8857439999999994e-01 , -4.5544700000000000e-02 , 1.9514000000000001e-01 , 9.7971699999999995e-01 -3.1767658590289223e+00 , 5.3729529814159580e+00 , 5.7327599999999990e-01 , -6.7940700000000007e-02 , 1.7803400000000000e-01 , 9.8167599999999999e-01 -3.1970329357031977e+00 , 5.5125704825672077e+00 , 5.4853439999999987e-01 , -6.4815999999999999e-02 , 1.7301000000000000e-01 , 9.8278500000000002e-01 -3.2178641792692373e+00 , 5.6540638589910257e+00 , 5.2797359999999993e-01 , -5.9317700000000001e-02 , 1.8939200000000000e-01 , 9.8010799999999998e-01 -3.2420849265996319e+00 , 5.8129150260274605e+00 , 4.9940479999999998e-01 , -6.2449299999999999e-02 , 1.9418800000000000e-01 , 9.7897500000000004e-01 -3.2696267126236318e+00 , 5.9903516534261136e+00 , 4.6364959999999988e-01 , -5.2131100000000000e-02 , 1.8276999999999999e-01 , 9.8177300000000001e-01 -3.2917310592006883e+00 , 6.1544085240279909e+00 , 4.4466960000000011e-01 , -4.8841500000000003e-02 , 1.8560199999999999e-01 , 9.8141000000000000e-01 -3.3218813345849840e+00 , 6.3538410314239799e+00 , 4.0798879999999982e-01 , -5.3536500000000001e-02 , 1.8743599999999999e-01 , 9.8081700000000005e-01 -3.3513402802283778e+00 , 6.5555846613847280e+00 , 3.7738159999999987e-01 , -4.7412500000000003e-02 , 1.9988100000000000e-01 , 9.7867199999999999e-01 -3.3875479149563246e+00 , 6.7942873698031452e+00 , 3.3139279999999993e-01 , -3.4826099999999999e-02 , 2.0634100000000000e-01 , 9.7785999999999995e-01 -3.4257378155788420e+00 , 7.0440458734947766e+00 , 2.8794159999999991e-01 , -5.0821800000000000e-02 , 1.9381799999999999e-01 , 9.7972000000000004e-01 -3.4657089456538177e+00 , 7.3154840019626262e+00 , 2.4182799999999993e-01 , -5.0740199999999999e-02 , 1.9303899999999999e-01 , 9.7987800000000003e-01 -3.5083037243111668e+00 , 7.6077962618115960e+00 , 1.9448719999999997e-01 , -6.3506000000000007e-02 , 1.7836600000000000e-01 , 9.8191300000000004e-01 -3.5526287027470098e+00 , 7.9116225737538333e+00 , 1.5193039999999991e-01 , -6.4987000000000003e-02 , 1.8343899999999999e-01 , 9.8088100000000000e-01 -3.6047738900741049e+00 , 8.2654438929485678e+00 , 9.5687199999999972e-02 , -6.7708599999999994e-02 , 1.8600600000000000e-01 , 9.8021300000000000e-01 -3.6608419544355861e+00 , 8.6495392323232032e+00 , 3.7717599999999907e-02 , -7.5983200000000001e-02 , 1.8156800000000001e-01 , 9.8043800000000003e-01 -3.7224965641182841e+00 , 9.0759078989973787e+00 , -2.5337600000000293e-02 , 1.9320599999999999e-01 , -1.6279500000000000e-01 , -9.6755800000000003e-01 -3.7904067298991966e+00 , 9.5429770528074851e+00 , -9.0597600000000167e-02 , 2.7194200000000002e-01 , -5.1584400000000002e-02 , -9.6092999999999995e-01 -3.8719805444255297e+00 , 1.0100785499195405e+01 , -1.7684480000000002e-01 , -4.5273099999999999e-01 , 3.3248600000000000e-01 , 8.2733800000000002e-01 -3.9641896788382738e+00 , 1.0728780311938289e+01 , -2.7088160000000006e-01 , -7.0060100000000000e-02 , 1.7461399999999999e-01 , 9.8214100000000004e-01 -4.0723562209071638e+00 , 1.1468968979656285e+01 , -3.8439759999999978e-01 , -6.2368899999999998e-02 , 1.8348300000000001e-01 , 9.8104199999999997e-01 -4.2001747424815363e+00 , 1.2342177432524293e+01 , -5.1857839999999999e-01 , -6.4345899999999998e-02 , 1.8144399999999999e-01 , 9.8129400000000000e-01 -4.3548736023214385e+00 , 1.3396190233608186e+01 , -6.8275279999999983e-01 , -6.4457100000000003e-02 , 1.8259000000000000e-01 , 9.8107400000000000e-01 -4.5387381344572981e+00 , 1.4655696752313629e+01 , -8.7440400000000018e-01 , -6.1552999999999997e-02 , 1.8358500000000000e-01 , 9.8107500000000003e-01 -4.7738061928484878e+00 , 1.6260164090966818e+01 , -1.1245240000000001e+00 , -6.9646200000000005e-02 , 1.7702100000000001e-01 , 9.8173999999999995e-01 -5.0359440518107448e+00 , 1.8074496701852073e+01 , -1.3756944000000000e+00 , -1.0903400000000001e-01 , 1.4960200000000001e-01 , 9.8271600000000003e-01 -5.2591841947354556e+00 , 1.9713494506817167e+01 , -1.5147216000000001e+00 , -1.2654499999999999e-01 , 1.6499400000000000e-01 , 9.7814299999999998e-01 -6.1586331799123712e+00 , 2.5634215669200646e+01 , -2.6513480000000005e+00 , 1.8297000000000001e-02 , 1.2941700000000000e-01 , 9.9142100000000000e-01 -1.0363229504168860e+01 , 5.4534803627615474e+01 , -6.9054888000000005e+00 , -8.0694200000000005e-01 , 2.3865000000000000e-01 , -5.4026900000000000e-01 -8.3049071850077407e+00 , 5.5930433795215457e+01 , 8.8427943999999989e+00 , 5.0456299999999998e-01 , 8.5048000000000001e-01 , -1.4865900000000001e-01 -7.6630792824946647e+00 , 5.9259473427715449e+01 , 1.6301352000000001e+01 , -5.0456299999999998e-01 , -8.5048000000000001e-01 , 1.4865900000000001e-01 -3.3585479898311776e+00 , 1.2585781470933210e+01 , 5.6336664000000001e+00 , -1.3212800000000000e-02 , -9.4154499999999997e-01 , -3.3662900000000001e-01 -3.3369721090943205e+00 , 1.2642487755454319e+01 , 5.8367368000000006e+00 , -1.0070900000000001e-01 , 8.7605999999999995e-01 , 4.7156900000000002e-01 -3.2973834221877558e+00 , 1.2496735761493433e+01 , 5.9850095999999997e+00 , 7.6368400000000003e-02 , -9.5274099999999995e-01 , -2.9402899999999998e-01 -3.2564989100295683e+00 , 1.2327747141317081e+01 , 6.1230592000000001e+00 , -9.0465000000000004e-02 , 9.1319499999999998e-01 , 3.9735500000000001e-01 -3.2378290512155177e+00 , 1.2423774568199319e+01 , 6.3427280000000001e+00 , -6.5404500000000004e-02 , 9.8246599999999995e-01 , 1.7459300000000000e-01 -3.0583370796734712e+00 , 1.0417307258395915e+01 , 5.8426232000000002e+00 , 2.2128800000000001e-02 , -9.9027900000000002e-01 , 1.3732300000000000e-01 -3.0354220067427402e+00 , 1.0408693433177159e+01 , 5.9952120000000004e+00 , 2.2128800000000001e-02 , -9.9027900000000002e-01 , 1.3732300000000000e-01 -3.0065022675010318e+00 , 1.0310818587313927e+01 , 6.1146351999999995e+00 , -3.7464900000000001e-01 , 8.8841499999999995e-01 , -2.6524700000000001e-01 -3.0022731763916086e+00 , 1.0576671352003984e+01 , 6.3791799999999999e+00 , -3.7464900000000001e-01 , 8.8841499999999995e-01 , -2.6524700000000001e-01 -2.9694226050400818e+00 , 1.0424167425836172e+01 , 6.4796128000000000e+00 , -8.3082299999999998e-01 , -9.4152000000000000e-02 , -5.4851499999999997e-01 -2.9036296483052784e+00 , 9.7393545183662766e+00 , 6.3394208000000001e+00 , -9.7115799999999997e-01 , -2.3801700000000001e-01 , -1.4138599999999999e-02 -2.8864337358394474e+00 , 9.8160706326364053e+00 , 6.5267976000000001e+00 , -7.5839500000000004e-01 , -4.8183199999999998e-01 , -4.3894800000000000e-01 -2.8442418977751807e+00 , 9.4575392510161631e+00 , 6.5090655999999996e+00 , -8.5885599999999995e-01 , 3.6493900000000001e-01 , -3.5942400000000002e-01 -2.8010611149193236e+00 , 9.0370377192315168e+00 , 6.4470504000000002e+00 , -4.1565500000000000e-01 , 6.8727300000000002e-01 , -5.9572300000000000e-01 -2.8096255516959650e+00 , 9.6313955966383009e+00 , 6.9060855999999999e+00 , 6.3513100000000000e-01 , 7.6617000000000002e-01 , -9.7938999999999998e-02 -2.7908543572829676e+00 , 9.7021152201157292e+00 , 7.1055264000000005e+00 , 2.0809200000000000e-01 , 9.7477899999999995e-01 , 8.0648399999999995e-02 -2.7687583621040899e+00 , 9.7408144312531064e+00 , 7.2929136000000003e+00 , -3.1542300000000001e-01 , -8.5796700000000004e-01 , -4.0546300000000002e-01 -2.6637338369034866e+00 , 7.7229560562692932e+00 , 6.2567096000000006e+00 , 3.6487300000000000e-01 , -8.5093600000000003e-01 , -3.7785600000000003e-01 -2.6437192346784535e+00 , 7.6422412462566705e+00 , 6.3314232000000006e+00 , -2.4789900000000001e-01 , 9.0410800000000002e-01 , 3.4804400000000002e-01 -2.6223178131534759e+00 , 7.5505170633032623e+00 , 6.3986280000000004e+00 , 5.3142800000000001e-01 , -6.1985299999999999e-01 , -5.7737899999999998e-01 -2.6050868371054126e+00 , 7.5796121617019798e+00 , 6.5446232000000002e+00 , -6.4112400000000000e-02 , 9.1496599999999995e-01 , 3.9840599999999998e-01 -2.5929757069788320e+00 , 7.7933669153270113e+00 , 6.8229584000000001e+00 , 7.4014000000000002e-01 , -6.7234000000000005e-01 , 1.2328600000000000e-02 -2.5699834854127248e+00 , 7.6694963008025994e+00 , 6.8725560000000003e+00 , -7.1867700000000001e-01 , -2.1585199999999999e-02 , 6.9500899999999999e-01 -2.5513141019343770e+00 , 7.7371486088978783e+00 , 7.0620648000000008e+00 , 5.1382799999999995e-01 , -6.6545799999999999e-01 , -5.4142999999999997e-01 -2.5292832364190181e+00 , 7.6028295123333010e+00 , 7.1021776000000001e+00 , 6.1337500000000000e-01 , 7.8971899999999995e-01 , 1.0751500000000001e-02 -2.5085319367710857e+00 , 7.5903990845545914e+00 , 7.2363480000000004e+00 , -6.3844599999999996e-01 , -4.7356199999999998e-01 , -6.0673299999999997e-01 -2.4897817065832624e+00 , 7.8136105573896213e+00 , 7.5707392000000002e+00 , 6.6341300000000003e-01 , 5.5067500000000003e-01 , 5.0659799999999999e-01 -2.4675869136653210e+00 , 8.2489166733104184e+00 , 8.1033648000000014e+00 , -9.2336799999999997e-01 , -3.5812300000000002e-01 , 1.3834900000000000e-01 -2.4443651988946695e+00 , 7.4629253335892285e+00 , 7.5807336000000003e+00 , 7.2290500000000002e-01 , 1.5489300000000000e-01 , 6.7336200000000002e-01 -2.4247043610515289e+00 , 6.9644534781636027e+00 , 7.2791024000000002e+00 , 6.2255199999999999e-01 , -1.9744400000000001e-01 , -7.5726199999999999e-01 -2.4040659161470024e+00 , 6.9063420933602542e+00 , 7.3709864000000005e+00 , -6.3327299999999997e-01 , 2.7381000000000000e-01 , 7.2387299999999999e-01 -2.3858045075845631e+00 , 6.7210240895379716e+00 , 7.3379456000000003e+00 , -6.8023500000000003e-01 , 6.7653500000000005e-02 , 7.2986499999999999e-01 -2.3673415094963461e+00 , 6.6248550806097599e+00 , 7.3889784000000001e+00 , 5.5364000000000002e-01 , -3.3575599999999997e-02 , -8.3207900000000001e-01 -2.3512601384992422e+00 , 6.4145962269019225e+00 , 7.3169896000000003e+00 , 6.2673199999999996e-01 , -1.9654199999999999e-01 , -7.5404199999999999e-01 -2.3036029524003805e+00 , 7.2672492992787365e+00 , 8.3977472000000013e+00 , 8.3627300000000004e-01 , 3.1201899999999999e-01 , -4.5087899999999997e-01 -2.2943111596187786e+00 , 6.8033718397951093e+00 , 8.0591960000000000e+00 , -3.3687200000000000e-01 , 1.6823600000000001e-02 , -9.4140000000000001e-01 -2.2683750662709565e+00 , 6.8316998068117005e+00 , 8.2680488000000008e+00 , 3.1435200000000003e-02 , -9.9949600000000005e-01 , 4.3542299999999997e-03 -2.2429997536813939e+00 , 6.8146498463817773e+00 , 8.4309544000000010e+00 , -8.5072800000000004e-01 , 3.4313700000000003e-01 , 3.9814300000000002e-01 -2.2198448741205334e+00 , 6.7281731045529929e+00 , 8.5133328000000006e+00 , 4.1174300000000003e-01 , -8.0871300000000002e-01 , -4.2006100000000002e-01 -2.2036393951900970e+00 , 6.5381571037374959e+00 , 8.4626848000000017e+00 , 9.1710700000000001e-01 , 2.5617000000000001e-02 , -3.9781600000000000e-01 -2.1906960033888891e+00 , 6.3274944205531201e+00 , 8.3735048000000010e+00 , -8.0733999999999995e-01 , -5.9001899999999996e-01 , -8.8968499999999996e-03 -2.1320814776346277e+00 , 6.7363171479601505e+00 , 9.1410976000000002e+00 , 1.9601900000000000e-01 , 5.6035999999999997e-01 , 8.0471899999999996e-01 -2.1147588214474449e+00 , 6.5660667952955087e+00 , 9.1198088000000013e+00 , -9.7733800000000004e-01 , -2.0771600000000001e-01 , -4.0808700000000003e-02 -2.1082705204871117e+00 , 6.2662387702882247e+00 , 8.8951272000000010e+00 , 4.9760100000000002e-02 , 1.0832000000000000e-01 , 9.9287000000000003e-01 -2.0879689430793222e+00 , 6.1594463307090397e+00 , 8.9510272000000004e+00 , -1.5664800000000001e-01 , 4.2812799999999998e-02 , 9.8672599999999999e-01 -2.0714523768269770e+00 , 6.0031225271753543e+00 , 8.9252456000000002e+00 , 4.4808199999999999e-02 , 1.2023800000000000e-01 , 9.9173299999999998e-01 -1.9120906659588488e+00 , 7.1067395058605332e+00 , 1.1022301600000000e+01 , -9.3717300000000003e-01 , -2.9798400000000003e-01 , 1.8142100000000000e-01 -1.9831615196724521e+00 , 6.1679767504972727e+00 , 9.6930151999999996e+00 , -2.3993700000000001e-01 , 9.0653099999999998e-01 , -3.4732200000000002e-01 -1.9888436527953777e+00 , 5.8391526259925559e+00 , 9.3639280000000014e+00 , -6.6264100000000004e-01 , 3.4793000000000002e-01 , -6.6321399999999997e-01 -2.0550863340051504e+00 , 5.1268691682792724e+00 , 8.2722920000000002e+00 , 3.7470799999999999e-02 , 9.1254599999999997e-01 , 4.0725499999999998e-01 -1.9439242794285470e+00 , 5.6284598970339212e+00 , 9.4944063999999990e+00 , 7.2516999999999998e-01 , -1.8565799999999999e-01 , 6.6306799999999999e-01 -2.0073513238341802e+00 , 5.0175718154789060e+00 , 8.5102024000000007e+00 , 2.3408999999999999e-01 , -8.9399899999999999e-01 , -3.8205699999999998e-01 -1.9115626185577186e+00 , 5.3520594201343759e+00 , 9.4858887999999997e+00 , 3.5904500000000000e-01 , -2.2776700000000000e-02 , 9.3304200000000004e-01 -1.9650190321551684e+00 , 4.8605884721658636e+00 , 8.6706223999999992e+00 , 7.5276700000000002e-02 , -9.9247700000000005e-01 , -9.6556799999999998e-02 -2.1284907612460704e+00 , 3.9190042963129827e+00 , 6.6935511999999999e+00 , 6.6144400000000003e-01 , -3.6117699999999998e-03 , -7.4998600000000004e-01 -2.1192318747357857e+00 , 3.8442368688303414e+00 , 6.6894120000000008e+00 , -4.4709700000000002e-01 , 5.1047900000000002e-01 , 7.3451699999999998e-01 -2.1067045479394744e+00 , 3.7886398340336900e+00 , 6.7322392000000004e+00 , 7.6653899999999997e-02 , 5.9516700000000000e-01 , 7.9993800000000004e-01 -2.0932228067140675e+00 , 3.7318200120274501e+00 , 6.7741304000000007e+00 , -1.4584600000000000e-01 , -7.6117199999999996e-01 , -6.3193800000000000e-01 -2.0774810858535151e+00 , 3.6840393834378338e+00 , 6.8445799999999997e+00 , -8.6190400000000000e-02 , 8.5396700000000003e-01 , 5.1313900000000001e-01 -2.0617594354995914e+00 , 3.6340344033039775e+00 , 6.9145200000000004e+00 , 2.3013200000000000e-01 , 7.0249499999999998e-01 , 6.7345400000000000e-01 -2.0416015386299655e+00 , 3.5911100175199140e+00 , 7.0133720000000004e+00 , 6.4304099999999997e-01 , 7.2015600000000002e-01 , 2.6052700000000001e-01 -1.9393530597633735e+00 , 3.7643937177995817e+00 , 7.8885008000000001e+00 , -2.1516199999999999e-01 , -6.5537400000000001e-01 , 7.2401000000000004e-01 -1.9811713334019527e+00 , 3.5462722183070774e+00 , 7.3998151999999999e+00 , -2.7777399999999999e-03 , -9.9612400000000001e-01 , 8.7920200000000004e-02 -2.0212307182325771e+00 , 3.3574109378506583e+00 , 6.9558600000000004e+00 , 5.8165500000000003e-01 , -2.8282600000000002e-01 , 7.6268400000000003e-01 -2.0120241099738427e+00 , 3.2876309124443299e+00 , 6.9606440000000003e+00 , -2.1976899999999999e-01 , -8.3276799999999995e-01 , -5.0813299999999995e-01 -1.8560874936246663e+00 , 3.4818130028107364e+00 , 8.2284664000000003e+00 , -5.1072899999999999e-01 , 3.0289500000000003e-01 , -8.0461800000000006e-01 -1.8309896077730448e+00 , 3.4111037451405517e+00 , 8.3464752000000004e+00 , -7.8107199999999999e-01 , 1.1922700000000000e-01 , -6.1295299999999997e-01 -1.8278424726003610e+00 , 3.3034273467971600e+00 , 8.2698895999999991e+00 , 4.8852400000000001e-01 , 4.3044399999999999e-01 , 7.5898800000000000e-01 -2.9926688203312937e+00 , 3.7618183185469718e+00 , 8.1689600000000007e-01 , -6.4025399999999996e-02 , 1.1059200000000000e-01 , 9.9180100000000004e-01 -3.0000169887774941e+00 , 3.8129379637226402e+00 , 8.2451919999999990e-01 , -8.0871299999999993e-02 , 1.3470900000000000e-01 , 9.8758000000000001e-01 -3.0105482383051809e+00 , 3.8745291225896858e+00 , 8.1624079999999988e-01 , -8.0326700000000001e-02 , 1.7409400000000000e-01 , 9.8144699999999996e-01 -3.0230791448775305e+00 , 3.9420648475286764e+00 , 8.0099440000000000e-01 , -7.5512700000000002e-02 , 1.8786200000000000e-01 , 9.7928800000000005e-01 -3.0343498976981484e+00 , 4.0063420653674768e+00 , 7.9566959999999987e-01 , 8.1806900000000002e-02 , -1.2137800000000000e-01 , -9.8923000000000005e-01 -3.0443456027088667e+00 , 4.0699469687839480e+00 , 7.9205040000000015e-01 , -9.6407800000000002e-02 , 1.9347500000000001e-01 , 9.7635700000000003e-01 -3.0606417781293160e+00 , 4.1530914735631939e+00 , 7.6546800000000004e-01 , 7.2749099999999997e-02 , -1.9814999999999999e-01 , -9.7746800000000000e-01 -3.0713278129063744e+00 , 4.2194679716999843e+00 , 7.6520799999999989e-01 , 8.6708499999999994e-02 , -1.7686099999999999e-01 , -9.8040899999999997e-01 -3.0860675614620918e+00 , 4.2987739471704014e+00 , 7.5088719999999998e-01 , 8.1388900000000000e-02 , -1.7648000000000000e-01 , -9.8093399999999997e-01 -3.0974211650490280e+00 , 4.3727456695674807e+00 , 7.4624880000000005e-01 , -1.0040000000000000e-01 , 1.6253899999999999e-01 , 9.8158100000000004e-01 -3.1117031926433487e+00 , 4.4539432153912006e+00 , 7.3596320000000004e-01 , -8.8774400000000003e-02 , 1.4754900000000001e-01 , 9.8506300000000002e-01 -3.1278180651584018e+00 , 4.5424840685335983e+00 , 7.2033199999999997e-01 , -7.9682799999999998e-02 , 1.6463800000000001e-01 , 9.8312999999999995e-01 -3.1457765111452547e+00 , 4.6405139316250938e+00 , 6.9952159999999997e-01 , -4.0059600000000001e-02 , 1.8766900000000000e-01 , 9.8141500000000004e-01 -3.1623829531592431e+00 , 4.7321787151744807e+00 , 6.8896559999999996e-01 , -5.3701300000000000e-02 , 2.0642400000000000e-01 , 9.7698799999999997e-01 -3.1817758893244310e+00 , 4.8393599863504324e+00 , 6.6643919999999990e-01 , -4.8394800000000002e-02 , 2.1812899999999999e-01 , 9.7471900000000000e-01 -3.2018599894635473e+00 , 4.9482094228542657e+00 , 6.4707439999999994e-01 , 7.5816800000000004e-02 , -1.8202599999999999e-01 , -9.8036699999999999e-01 -3.2185218641683271e+00 , 5.0506985861095206e+00 , 6.3759999999999994e-01 , -6.0987100000000002e-02 , 1.7155200000000001e-01 , 9.8328599999999999e-01 -3.2419741103665984e+00 , 5.1780581399194157e+00 , 6.1063279999999986e-01 , -4.7100200000000002e-02 , 1.9893500000000000e-01 , 9.7887999999999997e-01 -3.2660036165176725e+00 , 5.3061820130780717e+00 , 5.8764879999999997e-01 , -6.5021300000000004e-02 , 1.9526499999999999e-01 , 9.7859300000000005e-01 -3.2885740373517987e+00 , 5.4361642543697588e+00 , 5.6827359999999993e-01 , -5.0823000000000000e-02 , 1.8800900000000001e-01 , 9.8085199999999995e-01 -3.3137188725606279e+00 , 5.5761656692594705e+00 , 5.4648560000000002e-01 , -4.4040900000000001e-02 , 1.8885600000000000e-01 , 9.8101700000000003e-01 -3.3403711930864883e+00 , 5.7262671031916845e+00 , 5.2247199999999983e-01 , -6.7137299999999997e-02 , 1.7077800000000001e-01 , 9.8302000000000000e-01 -3.3664620813222363e+00 , 5.8773583276591221e+00 , 5.0322159999999982e-01 , -5.8838099999999997e-02 , 1.9892899999999999e-01 , 9.7824599999999995e-01 -3.3969811500968969e+00 , 6.0479598018347209e+00 , 4.7638960000000008e-01 , -4.5827399999999997e-02 , 1.9198599999999999e-01 , 9.8032699999999995e-01 -3.4306745711929767e+00 , 6.2362999142257944e+00 , 4.4337999999999989e-01 , -4.8047300000000001e-02 , 1.8055599999999999e-01 , 9.8239100000000001e-01 -3.4647128754158061e+00 , 6.4269171348771144e+00 , 4.1647519999999982e-01 , -4.7546499999999998e-02 , 1.9336999999999999e-01 , 9.7997299999999998e-01 -3.5085353021737835e+00 , 6.6637040812384418e+00 , 3.6781360000000007e-01 , -3.0868099999999999e-02 , 2.0905499999999999e-01 , 9.7741699999999998e-01 -3.5533365643097392e+00 , 6.9115238133451191e+00 , 3.2148159999999981e-01 , -4.7951500000000001e-02 , 1.9098699999999999e-01 , 9.8042099999999999e-01 -3.5972674257274120e+00 , 7.1630615357946565e+00 , 2.8283520000000006e-01 , -5.5177700000000003e-02 , 1.8835499999999999e-01 , 9.8055000000000003e-01 -3.6477898707169891e+00 , 7.4437482427550608e+00 , 2.3743919999999985e-01 , -6.4601199999999998e-02 , 1.8077099999999999e-01 , 9.8140099999999997e-01 -3.6990596084660803e+00 , 7.7358770949798608e+00 , 1.9629680000000005e-01 , -6.9110199999999997e-02 , 1.7937700000000001e-01 , 9.8134999999999994e-01 -3.7602801151072751e+00 , 8.0767562195605773e+00 , 1.4102079999999995e-01 , -6.7483600000000005e-02 , 1.8491900000000000e-01 , 9.8043400000000003e-01 -3.8237873479684881e+00 , 8.4402239140082571e+00 , 8.7647999999999948e-02 , -8.0298700000000001e-02 , 1.7937800000000001e-01 , 9.8049799999999998e-01 -3.8931894703851695e+00 , 8.8340788642163499e+00 , 3.3516000000000101e-02 , 3.0839899999999998e-01 , -2.1320100000000000e-01 , -9.2705800000000005e-01 -3.9708455352754202e+00 , 9.2789823925096648e+00 , -2.9019200000000023e-02 , -3.0189800000000000e-01 , 3.0155399999999999e-02 , 9.5286300000000002e-01 -4.0539920746084146e+00 , 9.7560588257833167e+00 , -8.8788000000000089e-02 , -7.9942000000000002e-01 , -2.1257899999999998e-03 , 6.0077000000000003e-01 -4.0355847348684204e+00 , 9.7755667108233837e+00 , 5.6812000000000085e-02 , -8.8161000000000000e-01 , -1.3823199999999999e-01 , 4.5128200000000002e-01 -4.0205349507493064e+00 , 9.8113859809160040e+00 , 1.9451839999999998e-01 , 9.7725899999999999e-01 , 1.2043099999999999e-02 , -2.1170600000000001e-01 -4.0037075943222380e+00 , 9.8343020979098661e+00 , 3.3629120000000001e-01 , 9.9802700000000000e-01 , 6.2637600000000002e-02 , -4.4252299999999996e-03 -4.0096255698885379e+00 , 9.9701619703470072e+00 , 4.3742079999999994e-01 , 9.9802700000000000e-01 , 6.2637600000000002e-02 , -4.4252400000000004e-03 -3.9840078535474870e+00 , 9.9506434447748866e+00 , 5.9332719999999983e-01 , 9.8885800000000001e-01 , -6.2574299999999999e-02 , -1.3507000000000000e-01 -3.9834455586049815e+00 , 1.0054554231595496e+01 , 7.0842399999999994e-01 , 9.8477599999999998e-01 , -9.7363699999999997e-02 , -1.4400199999999999e-01 -5.5896607382937002e+00 , 1.8531827391100652e+01 , -1.3013864000000002e+00 , -1.0903400000000001e-01 , 1.4960200000000001e-01 , 9.8271600000000003e-01 -6.5670680252970124e+00 , 2.3855748203823619e+01 , -2.3426552000000003e+00 , -4.4742299999999999e-02 , 2.0199900000000001e-01 , 9.7836299999999998e-01 -1.1256515384007235e+01 , 5.1043657648961272e+01 , -5.6230752000000006e+00 , 7.7982799999999997e-01 , -1.8002700000000000e-02 , 6.2573500000000004e-01 -1.2813285661267384e+01 , 6.0490659228770987e+01 , -6.2612711999999995e+00 , 4.0702300000000002e-01 , 1.4833199999999999e-01 , 9.0129300000000001e-01 -1.2692708760120281e+01 , 6.0676643601527843e+01 , -5.2423416000000005e+00 , 2.2992699999999999e-01 , 4.6726099999999998e-01 , 8.5369799999999996e-01 -1.2555072165384662e+01 , 6.0764090548264605e+01 , -4.2104016000000000e+00 , 2.2992599999999999e-01 , 4.6726200000000001e-01 , 8.5369799999999996e-01 -1.1073191536095742e+01 , 5.2963579434235591e+01 , -2.3358640000000008e+00 , 6.6038699999999995e-01 , 6.6397399999999995e-01 , -3.5075299999999998e-01 -1.1007066690200476e+01 , 5.4968593242017306e+01 , 2.3393439999999988e-01 , -5.2080199999999999e-01 , -7.9954999999999998e-01 , 2.9914200000000002e-01 -9.2339519756745219e+00 , 5.7073691541345752e+01 , 1.4572976000000001e+01 , 9.9769799999999997e-01 , -2.3902300000000001e-02 , -6.3457399999999997e-02 -3.7056205903896835e+00 , 1.2735542604114139e+01 , 5.4391448000000002e+00 , 2.7266899999999999e-01 , 8.9591500000000002e-01 , 3.5069600000000001e-01 -3.6031681057209628e+00 , 1.2570532011748421e+01 , 5.9632632000000001e+00 , -1.8142800000000001e-01 , -9.4973900000000000e-01 , -2.5510899999999997e-01 -3.5720779356538932e+00 , 1.2541680233796955e+01 , 6.1454712000000002e+00 , 2.3310800000000001e-01 , 8.8855300000000004e-01 , 3.9513900000000002e-01 -3.3290853631911141e+00 , 1.0540401528752620e+01 , 5.6944336000000000e+00 , 3.3299599999999999e-02 , -9.9460099999999996e-01 , 9.8288700000000007e-02 -3.2973921342077337e+00 , 1.0458040927526264e+01 , 5.8217712000000006e+00 , -3.3299599999999999e-02 , 9.9460099999999996e-01 , -9.8288600000000004e-02 -3.4186381934017787e+00 , 1.1872707139790680e+01 , 6.4868407999999995e+00 , 7.0449799999999996e-01 , 4.9040600000000001e-01 , 5.1301500000000000e-01 -3.4106209459110479e+00 , 1.2067522495321686e+01 , 6.7458320000000001e+00 , 7.0449799999999996e-01 , 4.9040600000000001e-01 , 5.1301500000000000e-01 -3.3679478122634365e+00 , 1.1909451353618300e+01 , 6.8744696000000003e+00 , 6.9746300000000006e-01 , -7.1570100000000003e-01 , 3.6282500000000002e-02 -3.3232905510430455e+00 , 1.1730858559864087e+01 , 6.9904399999999995e+00 , -9.8151200000000005e-01 , 1.2191000000000000e-01 , -1.4755099999999999e-01 -3.1274412792136204e+00 , 9.8714619790878722e+00 , 6.3629975999999999e+00 , -1.6496500000000000e-01 , -1.1443500000000000e-01 , -9.7963800000000001e-01 -3.0481764721040987e+00 , 9.2235310113950710e+00 , 6.2185207999999994e+00 , -2.0315100000000000e-01 , 5.6220500000000000e-02 , 9.7753199999999996e-01 -3.0173036749788036e+00 , 9.1135663616648017e+00 , 6.3091048000000001e+00 , -7.4609499999999995e-02 , -1.0770299999999999e-01 , 9.9138000000000004e-01 -2.9911216760727921e+00 , 9.0499274603782034e+00 , 6.4198648000000000e+00 , 1.5270800000000001e-01 , -7.4333600000000000e-01 , -6.5125400000000000e-01 -3.0043914753323016e+00 , 9.4806225903646144e+00 , 6.7895744000000002e+00 , -8.1355500000000003e-01 , -5.7904900000000004e-01 , 5.3196199999999999e-02 -2.9913819967165867e+00 , 9.6179832744580889e+00 , 7.0206104000000007e+00 , -8.0818500000000004e-01 , -5.8785299999999996e-01 , 3.5577100000000000e-02 -2.9670496202747811e+00 , 9.6045828614236246e+00 , 7.1755184000000005e+00 , 4.6721099999999999e-01 , -3.3767399999999997e-01 , 8.1712300000000004e-01 -2.9047275091009919e+00 , 9.0437263802941636e+00 , 7.0083175999999998e+00 , -1.8285799999999999e-01 , 7.3875999999999997e-02 , 9.8036000000000001e-01 -2.7959566749008573e+00 , 7.7211078376888480e+00 , 6.3495400000000002e+00 , -2.8656599999999999e-01 , 8.8004899999999997e-01 , 3.7867299999999998e-01 -2.7791477758103591e+00 , 7.7439852500741129e+00 , 6.4911047999999996e+00 , -3.0976100000000001e-01 , 6.6214200000000001e-01 , 6.8236100000000000e-01 -2.7488146450949373e+00 , 7.5552439268187088e+00 , 6.4964816000000010e+00 , -4.1695800000000000e-01 , 6.5283899999999995e-01 , 6.3241400000000003e-01 -2.7212115094953222e+00 , 7.3857004486160092e+00 , 6.5081400000000000e+00 , 2.9259299999999999e-01 , -9.3808899999999995e-01 , -1.8541500000000000e-01 -2.7285561992033975e+00 , 7.9111651223767971e+00 , 7.0097008000000001e+00 , -4.4377600000000000e-01 , 7.7346700000000002e-01 , 4.5256099999999999e-01 -2.7038761944458889e+00 , 7.8354576534080795e+00 , 7.0976952000000004e+00 , -8.7138300000000002e-01 , 4.7925000000000001e-01 , 1.0493000000000000e-01 -2.6695878692515471e+00 , 7.5113816714272996e+00 , 6.9944648000000003e+00 , 7.5584099999999999e-01 , 5.7851699999999995e-01 , 3.0663099999999999e-01 -2.6601294681928325e+00 , 7.8021938593289288e+00 , 7.3660152000000005e+00 , -9.3416399999999999e-01 , -3.3109499999999997e-01 , -1.3309099999999999e-01 -2.6311756988447228e+00 , 7.6077472469363840e+00 , 7.3591512000000003e+00 , -9.5509299999999997e-01 , 5.1778200000000003e-02 , -2.9174800000000001e-01 -2.5995665487896442e+00 , 7.3215987596507874e+00 , 7.2654991999999998e+00 , -5.8554200000000001e-01 , -2.7098200000000000e-01 , -7.6400900000000005e-01 -2.5775565707002448e+00 , 7.2724519886998475e+00 , 7.3700191999999998e+00 , -7.8281999999999996e-01 , -3.5313000000000000e-01 , -5.1233899999999999e-01 -2.5532197144423954e+00 , 7.1910732448985035e+00 , 7.4457416000000007e+00 , -8.5022500000000001e-01 , -7.9623500000000000e-02 , 5.2036300000000002e-01 -2.5311751416268833e+00 , 7.1841851612911727e+00 , 7.5913415999999998e+00 , -8.5773500000000003e-01 , -1.3849500000000001e-01 , 4.9508600000000003e-01 -2.5044077031420739e+00 , 6.8535265341959741e+00 , 7.4253680000000006e+00 , 2.6230799999999999e-01 , -2.7416299999999999e-01 , -9.2521900000000001e-01 -2.4798609620592558e+00 , 6.5527968783869515e+00 , 7.2714271999999998e+00 , 3.8994699999999999e-01 , -3.2318599999999997e-01 , -8.6226000000000003e-01 -2.4587019880580856e+00 , 6.5159940325184893e+00 , 7.3793688000000000e+00 , -5.5223900000000004e-01 , 8.2056900000000002e-02 , 8.2963799999999999e-01 -2.4365141521385070e+00 , 6.7457987851529051e+00 , 7.7774184000000002e+00 , 2.3266500000000001e-01 , -8.9258899999999997e-01 , 3.8620100000000002e-01 -2.4120172835197984e+00 , 6.7759783914915870e+00 , 7.9747167999999995e+00 , -2.3527200000000001e-01 , 8.8864799999999999e-01 , -3.9363900000000002e-01 -2.3769261529099346e+00 , 7.4383355039999692e+00 , 8.9147520000000000e+00 , 4.4913199999999998e-01 , -4.2174200000000001e-01 , -7.8766400000000003e-01 -2.3522000586189424e+00 , 7.1986388120431686e+00 , 8.8317808000000007e+00 , -7.0019699999999996e-01 , 3.7565900000000002e-01 , 6.0712800000000000e-01 -2.3236540622303838e+00 , 7.1318996583180558e+00 , 8.9529512000000011e+00 , 6.3219300000000000e-01 , -4.7592600000000002e-01 , -6.1141400000000001e-01 -2.2975060671997096e+00 , 6.9925544263082164e+00 , 8.9830383999999999e+00 , -4.6217700000000000e-01 , 7.2689499999999996e-01 , 5.0795299999999999e-01 -2.2809424532684668e+00 , 6.6283625538729076e+00 , 8.7107975999999994e+00 , -9.7470599999999996e-01 , 1.8476000000000001e-01 , 1.2574299999999999e-01 -2.2587179544096343e+00 , 6.4704996802543331e+00 , 8.6972775999999996e+00 , -7.4637500000000001e-01 , 6.3047299999999995e-01 , 2.1313699999999999e-01 -2.2322272579283222e+00 , 6.3906899094584277e+00 , 8.7909192000000012e+00 , 6.5631799999999996e-01 , -7.5382600000000000e-01 , -3.1495700000000001e-02 -2.2044993837218732e+00 , 6.3504862344185593e+00 , 8.9437992000000008e+00 , -4.6867300000000001e-01 , 8.5987000000000002e-01 , 2.0241000000000001e-01 -2.1832393594025907e+00 , 6.1931159921397922e+00 , 8.9223752000000012e+00 , -1.4309700000000000e-01 , 3.0022900000000002e-01 , 9.4307300000000005e-01 -2.1375077055802381e+00 , 6.3506907186232997e+00 , 9.3995895999999988e+00 , -8.3236200000000005e-01 , 5.4623400000000000e-01 , -9.3819100000000002e-02 -2.1218682473662689e+00 , 6.1183751945097447e+00 , 9.2603647999999996e+00 , -2.5822699999999998e-01 , -5.2135100000000002e-03 , 9.6606999999999998e-01 -2.0679327797555596e+00 , 6.2964968453145129e+00 , 9.8167128000000012e+00 , -4.6950399999999998e-01 , 4.4094600000000000e-01 , -7.6493999999999995e-01 -2.0785176487486288e+00 , 5.8323827520020934e+00 , 9.2545719999999996e+00 , 5.5113000000000001e-01 , -4.0186899999999998e-01 , 7.3127100000000000e-01 -2.0579742202935183e+00 , 5.6915844100288755e+00 , 9.2470216000000001e+00 , -9.4672900000000004e-01 , -2.1965799999999999e-01 , -2.3549000000000000e-01 -2.0914191334989769e+00 , 5.1405268250793172e+00 , 8.4321815999999998e+00 , 2.2457400000000000e-01 , -9.7394000000000003e-01 , -3.1757199999999999e-02 -2.0643181900728460e+00 , 5.0890640699617213e+00 , 8.5609439999999992e+00 , -4.0032299999999998e-01 , 7.9578800000000005e-01 , 4.5438099999999998e-01 -2.0350197739059688e+00 , 5.0465258407476830e+00 , 8.7177552000000009e+00 , -3.5453499999999999e-01 , -7.3289099999999996e-01 , -5.8066799999999996e-01 -1.9633283238153039e+00 , 5.2419210433966414e+00 , 9.4140456000000015e+00 , 5.3844000000000003e-01 , -2.7563700000000002e-01 , 7.9630800000000002e-01 -1.9553690838728210e+00 , 5.0507009149786226e+00 , 9.2695895999999998e+00 , -7.5295699999999993e-02 , -9.1194399999999998e-01 , 4.0334599999999998e-01 -2.1499646790135198e+00 , 3.8791284429666977e+00 , 6.7004776000000001e+00 , 5.2290800000000004e-01 , -2.1461300000000000e-01 , -8.2493000000000005e-01 -2.1375815057051550e+00 , 3.8124291408659365e+00 , 6.7146112000000002e+00 , -2.1770400000000001e-01 , 4.8197800000000002e-01 , 8.4870599999999996e-01 -2.1231553272934316e+00 , 3.7536881935541788e+00 , 6.7467367999999999e+00 , 8.6266499999999996e-02 , 6.4160499999999998e-01 , 7.6216899999999999e-01 -2.1063653197734307e+00 , 3.7070533418089879e+00 , 6.8173632000000000e+00 , 8.6960999999999997e-02 , -8.7179200000000001e-01 , -4.8209700000000000e-01 -2.0897002791249899e+00 , 3.6551168370611000e+00 , 6.8775376000000001e+00 , -1.2724199999999999e-01 , 6.7637400000000003e-01 , 7.2548400000000002e-01 -2.0708964718420706e+00 , 3.6040520003032404e+00 , 6.9468016000000006e+00 , 3.5451899999999997e-01 , 7.9803599999999997e-01 , 4.8729400000000000e-01 -1.9581783793619183e+00 , 3.8236444003139818e+00 , 7.9494656000000008e+00 , -3.8495699999999999e-01 , -7.7971500000000005e-01 , 4.9381500000000000e-01 -1.9471930636314168e+00 , 3.7261260811654302e+00 , 7.9215935999999996e+00 , 2.1516199999999999e-01 , 6.5537500000000004e-01 , -7.2400900000000001e-01 -2.0419315128770310e+00 , 3.3790525421033593e+00 , 6.9095800000000001e+00 , -3.9799299999999999e-01 , 4.2815399999999998e-01 , 8.1134799999999996e-01 -2.0271123274691840e+00 , 3.3177169971444509e+00 , 6.9445552000000008e+00 , 5.1486699999999996e-01 , -7.3402599999999998e-02 , 8.5412200000000005e-01 -2.0076079728703751e+00 , 3.2634964796028942e+00 , 7.0190920000000006e+00 , -9.7189600000000001e-02 , 9.8851100000000003e-01 , 1.1575900000000000e-01 -1.8502200221763498e+00 , 3.4463802195577995e+00 , 8.2885367999999993e+00 , 5.6232400000000005e-01 , 4.7782000000000002e-01 , 6.7489299999999997e-01 -1.8341016388625917e+00 , 3.3556632923238574e+00 , 8.3038768000000012e+00 , -8.8211200000000001e-01 , 4.4164900000000001e-01 , 1.6378100000000001e-01 -1.8338628432230182e+00 , 3.2426021555855939e+00 , 8.1853480000000012e+00 , 6.0581399999999996e-01 , 7.8765700000000005e-01 , -1.1218800000000000e-01 -3.0332878877644784e+00 , 3.7186924350497219e+00 , 8.3817439999999999e-01 , 3.9914999999999999e-02 , -1.3150600000000001e-01 , -9.9051199999999995e-01 -3.0461136090483212e+00 , 3.7787537398583022e+00 , 8.2803439999999995e-01 , -3.9395399999999997e-02 , 1.1234600000000000e-01 , 9.9288799999999999e-01 -3.0587849151744742e+00 , 3.8401526297591575e+00 , 8.1929840000000009e-01 , -9.5322500000000004e-02 , 7.2933999999999999e-02 , 9.9277099999999996e-01 -3.0690938922332558e+00 , 3.8962444084366208e+00 , 8.2058799999999987e-01 , -5.5126900000000000e-02 , 1.9518700000000000e-01 , 9.7921599999999998e-01 -3.0857983886404572e+00 , 3.9706216729721069e+00 , 7.9799920000000002e-01 , -6.6049600000000000e-02 , 1.4954700000000001e-01 , 9.8654600000000003e-01 -3.0957950991565748e+00 , 4.0283586074495883e+00 , 8.0210719999999980e-01 , 6.5087199999999998e-02 , -1.1984300000000001e-01 , -9.9065700000000001e-01 -3.1109719568408165e+00 , 4.0988076746056006e+00 , 7.9138479999999989e-01 , -4.1453499999999997e-02 , 2.0024000000000000e-01 , 9.7886899999999999e-01 -3.1270765759823815e+00 , 4.1764059680552963e+00 , 7.7415199999999995e-01 , -5.9704399999999998e-02 , 1.9633700000000001e-01 , 9.7871699999999995e-01 -3.1439510168610330e+00 , 4.2544468232443116e+00 , 7.5926960000000010e-01 , -7.8743900000000006e-02 , 1.6310900000000000e-01 , 9.8346100000000003e-01 -3.1584713933164732e+00 , 4.3271397964402976e+00 , 7.5430879999999978e-01 , -6.4136799999999994e-02 , 1.4327899999999999e-01 , 9.8760199999999998e-01 -3.1770520797795605e+00 , 4.4149283349851469e+00 , 7.3548479999999983e-01 , -6.9902000000000006e-02 , 1.4899599999999999e-01 , 9.8636400000000002e-01 -3.1911351206584229e+00 , 4.4895170108565168e+00 , 7.3445519999999997e-01 , -6.2964500000000007e-02 , 1.4462700000000001e-01 , 9.8748100000000005e-01 -3.2102246020035627e+00 , 4.5792975384997279e+00 , 7.2040479999999985e-01 , -4.2166099999999998e-02 , 2.0777000000000001e-01 , 9.7726800000000003e-01 -3.2310670385528235e+00 , 4.6765537403501511e+00 , 7.0160160000000005e-01 , -2.0085400000000000e-02 , 1.7227700000000001e-01 , 9.8484400000000005e-01 -3.2495799283857734e+00 , 4.7684458071448041e+00 , 6.9260560000000004e-01 , -5.7487099999999999e-02 , 2.0131900000000000e-01 , 9.7783699999999996e-01 -3.2749443624591832e+00 , 4.8828649064986083e+00 , 6.6511840000000011e-01 , -4.3153299999999999e-02 , 1.8818900000000000e-01 , 9.8118399999999995e-01 -3.2969081884365279e+00 , 4.9920211016259435e+00 , 6.4762560000000002e-01 , -6.0897399999999997e-02 , 1.7825600000000000e-01 , 9.8209800000000003e-01 -3.3195509195343509e+00 , 5.1028535886125290e+00 , 6.3338800000000006e-01 , 5.3884200000000000e-02 , -1.7523100000000000e-01 , -9.8305200000000004e-01 -3.3448693124286875e+00 , 5.2224205556151588e+00 , 6.1563519999999983e-01 , -6.0777499999999998e-02 , 1.9445499999999999e-01 , 9.7902699999999998e-01 -3.3717697160811326e+00 , 5.3508823234565499e+00 , 5.9493919999999978e-01 , 5.5432599999999999e-02 , -1.7887000000000000e-01 , -9.8231000000000002e-01 -3.3982287899477113e+00 , 5.4812071497350567e+00 , 5.7809119999999981e-01 , -4.2539500000000001e-02 , 1.8088199999999999e-01 , 9.8258400000000001e-01 -3.4292582006574426e+00 , 5.6297127671608189e+00 , 5.5236159999999979e-01 , -5.9633899999999997e-02 , 1.7633599999999999e-01 , 9.8252200000000001e-01 -3.4607644581057535e+00 , 5.7791639681248821e+00 , 5.3140560000000003e-01 , -5.7696400000000002e-02 , 1.8551300000000001e-01 , 9.8094599999999998e-01 -3.5005154046287084e+00 , 5.9636384701963863e+00 , 4.9104320000000001e-01 , -5.0354500000000003e-02 , 1.9599400000000000e-01 , 9.7931100000000004e-01 -3.5357859309505564e+00 , 6.1337811682857835e+00 , 4.6818399999999993e-01 , -3.0684699999999999e-02 , 1.8378400000000000e-01 , 9.8248800000000003e-01 -3.5752867117515001e+00 , 6.3226830223775732e+00 , 4.3916800000000000e-01 , -3.1805600000000003e-02 , 1.7247799999999999e-01 , 9.8450000000000004e-01 -3.6189370231073399e+00 , 6.5315798287527258e+00 , 4.0491039999999989e-01 , -2.7059199999999999e-02 , 1.9467000000000001e-01 , 9.8049600000000003e-01 -3.6694685949190977e+00 , 6.7680395538321418e+00 , 3.6138640000000000e-01 , -4.4956400000000001e-02 , 1.9603400000000001e-01 , 9.7956600000000005e-01 -3.7191748072170823e+00 , 7.0081521188906741e+00 , 3.2524639999999994e-01 , -5.0038699999999998e-02 , 1.8946399999999999e-01 , 9.8061200000000004e-01 -3.7773599858098281e+00 , 7.2857442913453925e+00 , 2.7668879999999985e-01 , -5.5656700000000003e-02 , 1.8123800000000001e-01 , 9.8186300000000004e-01 -3.8327307769982690e+00 , 7.5577467083834149e+00 , 2.4190080000000003e-01 , -6.7882799999999993e-02 , 1.7128199999999999e-01 , 9.8288100000000000e-01 -3.8973175738674959e+00 , 7.8677283183893207e+00 , 1.9734720000000006e-01 , -6.2176099999999998e-02 , 1.7995000000000000e-01 , 9.8170900000000005e-01 -3.9699677569059708e+00 , 8.2181295778658185e+00 , 1.4433840000000009e-01 , -7.1886400000000003e-02 , 1.7538100000000001e-01 , 9.8187300000000000e-01 -4.0468733805710517e+00 , 8.5901495987821725e+00 , 9.4095999999999957e-02 , -2.1865999999999999e-01 , 2.5895000000000001e-01 , 9.4081499999999996e-01 -4.1359087331291740e+00 , 9.0216335443333975e+00 , 3.0656000000000017e-02 , -1.7417900000000000e-01 , 1.6049299999999999e-02 , 9.8458299999999999e-01 -4.1936422784687855e+00 , 9.3363700038670814e+00 , 3.4566399999999886e-02 , -9.7243299999999999e-01 , -1.0634800000000000e-01 , 2.0752100000000001e-01 -4.1616195406508636e+00 , 9.2982987781604578e+00 , 1.9718079999999993e-01 , -9.6357400000000004e-01 , -2.4852900000000000e-01 , 9.8785600000000001e-02 -4.1616817181126091e+00 , 9.3879787598493678e+00 , 3.0502879999999988e-01 , 5.4260299999999995e-01 , 7.8866000000000003e-01 , -2.8913400000000000e-01 -4.1483487480509842e+00 , 9.4193071904422929e+00 , 4.3658880000000000e-01 , 9.7737499999999999e-01 , 1.8914600000000001e-01 , 9.4671699999999998e-02 -4.1242292855932607e+00 , 9.4103006620439338e+00 , 5.8174159999999997e-01 , 9.9835600000000002e-01 , 4.7450500000000000e-02 , 3.2144699999999998e-02 -4.1028567122586370e+00 , 9.4077403514502524e+00 , 7.2256800000000010e-01 , 9.9884899999999999e-01 , -4.7093299999999998e-02 , -9.1340399999999995e-03 -4.0942842763144771e+00 , 9.4601850741352216e+00 , 8.4402960000000005e-01 , 9.8662600000000000e-01 , -7.1961200000000003e-02 , -1.4625900000000000e-01 -4.0966401520058700e+00 , 9.5603791246897671e+00 , 9.5179440000000004e-01 , 9.8197299999999998e-01 , -4.6385299999999997e-02 , -1.8324099999999999e-01 -4.1262339172249032e+00 , 9.7855378827996855e+00 , 1.0269000799999999e+00 , 9.7231699999999999e-01 , -5.6015099999999998e-02 , -2.2685400000000000e-01 -4.1466831747844823e+00 , 9.9711083781380925e+00 , 1.1195838399999998e+00 , 9.7231699999999999e-01 , -5.6015099999999998e-02 , -2.2685400000000000e-01 -7.4156099656305043e+00 , 2.4846010785346738e+01 , -2.3109768000000006e+00 , 2.7929500000000002e-03 , 1.4632899999999999e-01 , 9.8923200000000000e-01 -1.2129771653783191e+01 , 4.7881653320544096e+01 , -5.3144343999999997e+00 , -9.2452999999999996e-01 , 3.4883699999999997e-02 , -3.7951000000000001e-01 -1.6965130602593351e+01 , 7.2415698323361241e+01 , -7.2952288000000003e+00 , -1.7944499999999999e-01 , 1.5299599999999999e-01 , 9.7179800000000005e-01 -1.6853152741326078e+01 , 7.2800587923483164e+01 , -6.0834311999999997e+00 , -1.7944499999999999e-01 , 1.5299599999999999e-01 , 9.7179800000000005e-01 -1.0088164866664776e+01 , 4.0744761998782771e+01 , -5.3941999999999979e-01 , -8.2775299999999996e-01 , -5.6052500000000005e-01 , 2.5224600000000000e-02 -9.9865215146781523e+00 , 4.0748352145983588e+01 , 1.4154080000000002e-01 , 8.2104500000000002e-01 , 5.6943800000000000e-01 , 4.0323100000000001e-02 -9.9373163311804653e+00 , 4.1026162292027543e+01 , 8.0367760000000010e-01 , 7.6400900000000005e-01 , 6.4113399999999998e-01 , -7.2366299999999995e-02 -9.8642845009361686e+00 , 4.1180187353764808e+01 , 1.4789433599999999e+00 , 7.4286300000000005e-01 , 6.3371500000000003e-01 , -2.1577600000000000e-01 -9.6915730597898531e+00 , 4.0810914005794537e+01 , 2.1704892800000000e+00 , -7.6194300000000004e-01 , -5.5964499999999995e-01 , 3.2594600000000001e-01 -9.6269209482095128e+00 , 4.1013116195664487e+01 , 2.8441773599999998e+00 , -7.7538700000000005e-01 , -5.2133900000000000e-01 , 3.5634399999999999e-01 -9.7914912091756499e+00 , 4.2472134486814248e+01 , 3.5385448000000004e+00 , -9.2288899999999996e-01 , -3.5327500000000001e-01 , 1.5320600000000001e-01 -9.7237605729536707e+00 , 4.2681671271835313e+01 , 4.2476687999999996e+00 , -8.8206499999999999e-01 , -4.4957300000000000e-01 , 1.4087200000000000e-01 -3.9625849361904582e+00 , 1.2597940252977322e+01 , 5.5540960000000004e+00 , -2.7027000000000001e-01 , -9.3778300000000003e-01 , -2.1798300000000001e-01 -3.9258549701037428e+00 , 1.2538646814045272e+01 , 5.7263096000000004e+00 , 2.5820500000000002e-01 , 9.3054999999999999e-01 , 2.5962800000000003e-01 -3.8967097754774604e+00 , 1.2535168829600785e+01 , 5.9136655999999999e+00 , 3.6095300000000002e-01 , 8.5880900000000004e-01 , 3.6353799999999997e-01 -3.7704820550475731e+00 , 1.2241512884940857e+01 , 6.3897152000000004e+00 , 1.7276200000000000e-01 , 6.4744800000000002e-01 , 7.4226899999999996e-01 -3.6847976343852875e+00 , 1.1808522232971823e+01 , 6.4253248000000003e+00 , -3.8459700000000002e-01 , 9.1750799999999999e-01 , -1.0131400000000000e-01 -3.6495207208993756e+00 , 1.1743421716091330e+01 , 6.5847984000000004e+00 , -4.3480400000000002e-01 , 8.9587099999999997e-01 , -9.1441800000000004e-02 -3.6513903570754751e+00 , 1.1983324029550305e+01 , 6.8641943999999997e+00 , -1.3738600000000001e-01 , 9.8669300000000004e-01 , 8.6965399999999998e-02 -3.6002159490727479e+00 , 1.1806519321268738e+01 , 6.9823383999999997e+00 , -9.8151200000000005e-01 , 1.2191000000000000e-01 , -1.4755099999999999e-01 -3.4993823824104631e+00 , 1.1201596604164804e+01 , 6.9097048000000001e+00 , -9.5728199999999997e-01 , -9.0676300000000001e-02 , -2.7456900000000001e-01 -3.5356589106100547e+00 , 1.1749808986597477e+01 , 7.3405975999999997e+00 , -8.3191999999999999e-01 , 1.1912100000000000e-01 , 5.4196000000000000e-01 -3.2295930495145466e+00 , 9.2975418099155505e+00 , 6.3663672000000000e+00 , 2.5636300000000001e-01 , 8.7170400000000003e-01 , -4.1762400000000000e-01 -3.1954813185896391e+00 , 9.1868038690358915e+00 , 6.4576896000000001e+00 , 5.8840300000000001e-01 , -6.8149800000000005e-01 , -4.3513400000000002e-01 -3.1961569017329094e+00 , 9.4058990024746247e+00 , 6.7178352000000006e+00 , 6.3874100000000000e-01 , 7.3827299999999996e-01 , -2.1670900000000001e-01 -3.1718968519891857e+00 , 9.3905713418980064e+00 , 6.8631960000000003e+00 , -8.1191899999999995e-01 , -1.6300999999999999e-01 , -5.6054899999999996e-01 -3.1060652879871036e+00 , 8.9657011114666432e+00 , 6.7799544000000003e+00 , -3.6240499999999998e-01 , 8.4604800000000002e-01 , 3.9097999999999999e-01 -3.0625491721711091e+00 , 8.7514832997844927e+00 , 6.8036768000000007e+00 , -8.8609000000000004e-01 , -2.9794599999999999e-01 , -3.5506700000000002e-01 -2.9866580517505525e+00 , 8.1763202946865352e+00 , 6.5994520000000003e+00 , -3.9436800000000000e-01 , -7.9328299999999996e-01 , 4.6387099999999998e-01 -2.9269243476413855e+00 , 7.7313145523399909e+00 , 6.4544863999999995e+00 , -2.5875599999999999e-01 , 8.6775500000000005e-01 , 4.2431999999999997e-01 -2.9347780825422820e+00 , 8.0472305352510602e+00 , 6.7909368000000008e+00 , -4.1146500000000003e-01 , -8.9990000000000003e-01 , -1.4448400000000000e-01 -2.9227803047762815e+00 , 8.1642099447241705e+00 , 7.0105848000000002e+00 , -3.0171300000000001e-01 , 1.9116900000000001e-01 , 9.3403599999999998e-01 -2.9646486246856858e+00 , 8.9876196694751727e+00 , 7.7387096000000000e+00 , 8.1295899999999999e-01 , 2.8973599999999999e-01 , 5.0512500000000005e-01 -2.9280199564308078e+00 , 8.8416612251772371e+00 , 7.8022743999999999e+00 , 3.7370500000000001e-01 , 3.8753500000000002e-01 , 8.4271099999999999e-01 -2.8096333030897345e+00 , 7.5139736714801240e+00 , 6.9634000000000000e+00 , 7.4210900000000002e-01 , 6.3743000000000005e-01 , 2.0726100000000000e-01 -2.7929424289645199e+00 , 7.5784615712168675e+00 , 7.1534600000000008e+00 , -9.3123900000000004e-01 , -3.1842199999999998e-01 , -1.7720600000000000e-01 -2.7584383989273302e+00 , 7.3724481256793677e+00 , 7.1301640000000006e+00 , -8.4894199999999997e-01 , -1.4249300000000001e-01 , -5.0891399999999998e-01 -2.7407190130657844e+00 , 7.4387118907511596e+00 , 7.3288248000000005e+00 , -6.8563799999999997e-01 , -1.6309899999999999e-01 , -7.0943599999999996e-01 -2.7379927217095226e+00 , 7.8127884869842852e+00 , 7.8041256000000008e+00 , 7.5652900000000001e-01 , 5.0460700000000003e-01 , -4.1597600000000001e-01 -2.6849241335927316e+00 , 7.2238196210539281e+00 , 7.4361215999999999e+00 , -2.2022200000000000e-01 , 8.7441100000000005e-01 , 4.3232799999999999e-01 -2.6572726637305761e+00 , 7.1112077827274787e+00 , 7.4826303999999997e+00 , 8.2374099999999995e-01 , -2.9958499999999999e-01 , -4.8135200000000000e-01 -2.6253977905111707e+00 , 6.8871465151599525e+00 , 7.4178176000000002e+00 , -1.2461300000000000e-02 , 1.7373400000000000e-01 , 9.8471399999999998e-01 -2.5998536443577023e+00 , 6.8064886902638504e+00 , 7.4863119999999999e+00 , 1.2081900000000000e-01 , 4.8343500000000000e-01 , 8.6700200000000005e-01 -2.5722553261132899e+00 , 6.6374449302148024e+00 , 7.4635568000000001e+00 , 4.6271899999999999e-01 , -1.6506199999999999e-02 , -8.8635100000000000e-01 -2.5517162377169380e+00 , 6.7682918705682047e+00 , 7.7555575999999995e+00 , 1.6098799999999999e-01 , -9.1431499999999999e-01 , 3.7163400000000002e-01 -2.5245449242439020e+00 , 6.5974033713058198e+00 , 7.7289648000000000e+00 , -7.9246099999999997e-01 , -5.3932500000000005e-01 , -2.8484100000000001e-01 -2.5024053061230456e+00 , 6.8259232922454673e+00 , 8.1522968000000002e+00 , 6.2176500000000003e-02 , -9.8050700000000002e-01 , 1.8638600000000000e-01 -2.4791544215758630e+00 , 7.4631118021344127e+00 , 9.0858840000000001e+00 , -2.1168900000000001e-02 , 1.3938800000000001e-01 , 9.9001200000000000e-01 -2.4476526678063095e+00 , 7.1631370463501254e+00 , 8.9289376000000011e+00 , 4.6391500000000002e-01 , -7.0246500000000001e-01 , -5.3974699999999998e-01 -2.4171599717790500e+00 , 7.1398182596160531e+00 , 9.1070792000000012e+00 , -5.1285400000000003e-01 , 6.3095800000000002e-01 , 5.8212900000000001e-01 -2.3871362236720506e+00 , 6.9677679094084235e+00 , 9.0952440000000010e+00 , -3.9985199999999999e-01 , 7.0811700000000000e-01 , 5.8196999999999999e-01 -2.3682700967876973e+00 , 6.2996409314992965e+00 , 8.3996607999999995e+00 , -8.9303299999999997e-01 , -4.4532800000000000e-01 , -6.4619099999999999e-02 -2.3381538835879527e+00 , 6.3291165127819031e+00 , 8.6343888000000000e+00 , -9.4936799999999999e-01 , -3.1410100000000002e-01 , -6.3890800000000001e-03 -2.3029388264590107e+00 , 6.4383970969664936e+00 , 9.0006351999999996e+00 , 1.6696400000000000e-01 , -9.6821000000000002e-01 , 1.8625700000000001e-01 -2.2709908460610579e+00 , 6.4052966070412358e+00 , 9.1720792000000007e+00 , -9.1023399999999999e-01 , -3.8209799999999999e-01 , -1.5961000000000000e-01 -2.2264414918571407e+00 , 6.5901491606422455e+00 , 9.6953239999999994e+00 , 7.3286899999999999e-01 , -5.8562599999999998e-01 , 3.4633100000000000e-01 -2.2062400253966752e+00 , 6.2875095047975327e+00 , 9.4537735999999999e+00 , -8.4721299999999999e-01 , 5.2581400000000000e-01 , -7.5825400000000001e-02 -2.1681856883246313e+00 , 6.2879876052966628e+00 , 9.7062856000000011e+00 , 5.4714300000000005e-01 , -2.7805299999999999e-01 , 7.8950699999999996e-01 -2.1536466271217654e+00 , 5.9855725732358795e+00 , 9.4354279999999999e+00 , -6.2129199999999996e-01 , 7.7324999999999999e-01 , 1.2680900000000001e-01 -2.1403638827739386e+00 , 5.7031602553499203e+00 , 9.1744920000000008e+00 , -8.5826000000000002e-01 , 4.8934299999999997e-01 , 1.5470600000000001e-01 -2.1649436371325477e+00 , 5.1145023318022780e+00 , 8.2976367999999994e+00 , 1.4762500000000000e-02 , 9.5421599999999995e-01 , 2.9875499999999999e-01 -2.1286318304668250e+00 , 5.1319406957422133e+00 , 8.5556087999999999e+00 , 4.7139900000000001e-01 , -5.7775399999999999e-01 , -6.6632100000000005e-01 -2.1036175496766014e+00 , 5.0459677911151539e+00 , 8.6189552000000003e+00 , 2.3299000000000000e-01 , -7.9100199999999998e-01 , -5.6571400000000005e-01 -2.0733773370905864e+00 , 4.9942294664502569e+00 , 8.7562768000000002e+00 , -3.8198300000000002e-01 , -6.1705500000000002e-01 , -6.8799100000000002e-01 -2.0464640416833935e+00 , 4.9086993113737769e+00 , 8.8266847999999989e+00 , 4.4961200000000001e-01 , 8.1174100000000005e-01 , -3.7272800000000000e-01 -2.1795675776608161e+00 , 3.9261427878139070e+00 , 6.7399040000000001e+00 , -6.5512099999999995e-01 , -7.3592099999999994e-02 , 7.5193100000000002e-01 -2.1672484278170159e+00 , 3.8473911611382601e+00 , 6.7258535999999998e+00 , -4.9585899999999999e-01 , 3.0458099999999999e-01 , 8.1323699999999999e-01 -2.1529047495011060e+00 , 3.7816421085442036e+00 , 6.7390200000000000e+00 , -9.7322900000000004e-02 , 5.2085300000000001e-01 , 8.4807999999999995e-01 -2.1362630194632519e+00 , 3.7289781339358852e+00 , 6.7902711999999994e+00 , -6.7655199999999999e-02 , 9.0763300000000002e-01 , 4.1427599999999998e-01 -2.1152436577887839e+00 , 3.6843828957084206e+00 , 6.8701224000000005e+00 , 2.9543100000000000e-01 , -7.3175299999999999e-01 , -6.1421300000000001e-01 -2.0988147810539344e+00 , 3.6251723122045445e+00 , 6.9100272000000009e+00 , -3.8072500000000002e-02 , 6.8429499999999999e-01 , 7.2821000000000002e-01 -2.0767551598228264e+00 , 3.5802070300656044e+00 , 6.9983856000000007e+00 , 4.8880699999999999e-01 , 7.9267900000000002e-01 , 3.6431799999999998e-01 -1.9693923992883307e+00 , 3.7761813817625702e+00 , 7.9534280000000006e+00 , -7.6176500000000003e-01 , -4.7467500000000001e-01 , 4.4090600000000002e-01 -1.9648667288177917e+00 , 3.6547064589200673e+00 , 7.8344208000000002e+00 , -7.6723399999999997e-01 , -5.2394200000000002e-01 , 3.6991400000000002e-01 -2.0442440251189629e+00 , 3.3467104793730309e+00 , 6.9287160000000005e+00 , 4.2607899999999999e-01 , -1.4872199999999999e-01 , 8.9237800000000000e-01 -2.0297731094141205e+00 , 3.2800867125643540e+00 , 6.9428080000000003e+00 , 5.5923000000000000e-01 , 4.8969400000000002e-01 , 6.6892600000000002e-01 -1.8881362109489095e+00 , 3.4492167450680027e+00 , 8.0893143999999992e+00 , 2.2652600000000001e-01 , 6.3594399999999995e-01 , 7.3774099999999998e-01 -1.8460383254526809e+00 , 3.4015371692147456e+00 , 8.3074648000000000e+00 , -5.8260599999999996e-01 , 2.2663000000000000e-01 , -7.8051899999999996e-01 -1.8353888606342750e+00 , 3.2991525717623751e+00 , 8.2502856000000016e+00 , -6.3875199999999999e-01 , 4.3993300000000002e-01 , -6.3123300000000004e-01 -3.0911011594255928e+00 , 3.7436018897173424e+00 , 8.3183039999999986e-01 , -4.1730299999999998e-02 , 1.0598500000000000e-01 , 9.9349200000000004e-01 -3.1026880846629012e+00 , 3.7992523607322859e+00 , 8.3121679999999976e-01 , -6.6777600000000006e-02 , 9.2265200000000006e-02 , 9.9349299999999996e-01 -3.1151452448515182e+00 , 3.8551641292970089e+00 , 8.3203839999999984e-01 , -5.9358399999999999e-02 , 1.0800800000000001e-01 , 9.9237600000000004e-01 -3.1318106720892764e+00 , 3.9226147604799930e+00 , 8.1729120000000011e-01 , -7.4207899999999993e-02 , 1.9767799999999999e-01 , 9.7745400000000005e-01 -3.1482928960275736e+00 , 3.9914926448258976e+00 , 8.0425999999999997e-01 , -7.5950299999999998e-02 , 1.4281500000000000e-01 , 9.8683100000000001e-01 -3.1624046643671289e+00 , 4.0550511590949609e+00 , 8.0124400000000007e-01 , 4.4855500000000000e-02 , -1.6095599999999999e-01 , -9.8594199999999999e-01 -3.1816739902161588e+00 , 4.1313808960359717e+00 , 7.8368879999999996e-01 , -3.7747099999999999e-02 , 1.9274400000000000e-01 , 9.8052300000000003e-01 -3.1954243184864595e+00 , 4.1966701018536181e+00 , 7.8390720000000003e-01 , -5.2905000000000001e-02 , 1.8572600000000000e-01 , 9.8117600000000005e-01 -3.2173803330319997e+00 , 4.2806329555792750e+00 , 7.6262879999999988e-01 , -3.2347099999999997e-02 , 1.8234800000000001e-01 , 9.8270199999999996e-01 -3.2359800845911906e+00 , 4.3603181544840677e+00 , 7.5103279999999994e-01 , -5.1706000000000002e-02 , 1.4767200000000000e-01 , 9.8768400000000001e-01 -3.2522380305806209e+00 , 4.4346473448644605e+00 , 7.4925440000000010e-01 , 4.8335599999999999e-02 , -1.4064699999999999e-01 , -9.8887899999999995e-01 -3.2745229348232456e+00 , 4.5231124848590198e+00 , 7.3456959999999993e-01 , -4.7273400000000000e-02 , 1.6743200000000000e-01 , 9.8475000000000001e-01 -3.2975451048999505e+00 , 4.6190384160642957e+00 , 7.1490319999999996e-01 , -3.8972600000000003e-02 , 1.8522700000000000e-01 , 9.8192299999999999e-01 -3.3192936304180201e+00 , 4.7106207300007217e+00 , 7.0507520000000001e-01 , -4.0291399999999998e-02 , 1.7521500000000001e-01 , 9.8370500000000005e-01 -3.3458546645518381e+00 , 4.8166764462414884e+00 , 6.8373439999999985e-01 , -1.5102700000000000e-02 , 1.9222300000000000e-01 , 9.8123499999999997e-01 -3.3690233552337538e+00 , 4.9174284874861485e+00 , 6.7228399999999988e-01 , -5.6142499999999998e-02 , 1.9746800000000000e-01 , 9.7870000000000001e-01 -3.3969300290903397e+00 , 5.0338591492388929e+00 , 6.5002800000000005e-01 , -4.6439700000000000e-02 , 1.6102800000000000e-01 , 9.8585699999999998e-01 -3.4234724401206127e+00 , 5.1439328579809001e+00 , 6.3811999999999980e-01 , -5.5881599999999997e-02 , 1.9532900000000000e-01 , 9.7914500000000004e-01 -3.4566885563674168e+00 , 5.2790337037601871e+00 , 6.0953040000000014e-01 , -4.7384599999999999e-02 , 1.8461500000000000e-01 , 9.8166799999999999e-01 -3.4874632880378251e+00 , 5.4078563758121767e+00 , 5.9146560000000004e-01 , -4.0497300000000000e-02 , 1.9702600000000001e-01 , 9.7956200000000004e-01 -3.5227558849103016e+00 , 5.5538623307523665e+00 , 5.6472720000000010e-01 , -4.6632399999999997e-02 , 1.6359699999999999e-01 , 9.8542500000000000e-01 -3.5536595140569376e+00 , 5.6864463880598999e+00 , 5.5477439999999989e-01 , -6.1343700000000001e-02 , 1.6421700000000000e-01 , 9.8451500000000003e-01 -3.5909418072605588e+00 , 5.8445707968961056e+00 , 5.3067759999999997e-01 , -2.7850400000000001e-02 , 2.0051400000000000e-01 , 9.7929500000000003e-01 -3.6335970413954781e+00 , 6.0212615347865084e+00 , 4.9974799999999986e-01 , -1.8769000000000001e-02 , 1.9445699999999999e-01 , 9.8073100000000002e-01 -3.6814600727529410e+00 , 6.2157104841929636e+00 , 4.6319199999999983e-01 , -1.1873800000000000e-02 , 1.8288699999999999e-01 , 9.8306199999999999e-01 -3.7286535298205652e+00 , 6.4135148955632015e+00 , 4.3260560000000003e-01 , -1.5297300000000000e-02 , 1.7209800000000000e-01 , 9.8496099999999998e-01 -3.7838804303939249e+00 , 6.6397418646199000e+00 , 3.9196239999999993e-01 , -3.0995100000000001e-02 , 1.8953500000000001e-01 , 9.8138499999999995e-01 -3.8411367042274058e+00 , 6.8769492858936569e+00 , 3.5356560000000004e-01 , -3.8991600000000001e-02 , 1.8230900000000000e-01 , 9.8246800000000001e-01 -3.9003875028089068e+00 , 7.1252043759092594e+00 , 3.1772719999999999e-01 , -3.9123900000000003e-02 , 1.7568800000000001e-01 , 9.8366799999999999e-01 -3.9672660978299659e+00 , 7.4025744361312098e+00 , 2.7515999999999985e-01 , -5.4355500000000001e-02 , 1.6619600000000001e-01 , 9.8459399999999997e-01 -4.0359744716361536e+00 , 7.6923807136493290e+00 , 2.3676319999999995e-01 , -5.2941000000000002e-02 , 1.6836400000000001e-01 , 9.8430200000000001e-01 -4.1109916467081487e+00 , 8.0118410636383341e+00 , 1.9406079999999992e-01 , -5.8984900000000000e-02 , 1.6841600000000001e-01 , 9.8394999999999999e-01 -4.1932320649941843e+00 , 8.3622550626766987e+00 , 1.4837359999999999e-01 , 1.9176900000000000e-01 , -1.4428400000000000e-01 , -9.7077700000000000e-01 -4.2907677530883124e+00 , 8.7697610004488062e+00 , 8.8958399999999882e-02 , -1.6623800000000000e-01 , 1.7062500000000000e-01 , 9.7121199999999996e-01 -4.4006078822827233e+00 , 9.2283831748234810e+00 , 2.2367199999999920e-02 , 6.1453199999999997e-01 , 4.3327300000000002e-01 , -6.5925999999999996e-01 -4.3538773879830028e+00 , 9.1449268894245748e+00 , 2.0427359999999983e-01 , -9.5223000000000002e-01 , -8.5740899999999995e-02 , -2.9309700000000000e-01 -4.2714765317779344e+00 , 8.9273790944279980e+00 , 4.3501839999999992e-01 , -9.8363199999999995e-01 , -5.5065900000000001e-02 , -1.7156600000000000e-01 -4.2454386997125866e+00 , 8.9094095818765489e+00 , 5.7740480000000005e-01 , 9.7786700000000004e-01 , -4.6327399999999998e-03 , 2.0917500000000000e-01 -4.2319809644968158e+00 , 8.9369562418291117e+00 , 7.0075919999999980e-01 , 9.9830500000000000e-01 , 2.6686700000000001e-02 , 5.1728099999999999e-02 -4.2147080797498839e+00 , 8.9516005607671580e+00 , 8.2772240000000008e-01 , 9.9943499999999996e-01 , 3.2525900000000003e-02 , 8.4512100000000007e-03 -4.2054346242041749e+00 , 8.9936312245240124e+00 , 9.4473279999999993e-01 , 9.9801200000000001e-01 , 5.0730699999999997e-02 , -3.7400700000000002e-02 -4.2133888623939235e+00 , 9.1010192995361887e+00 , 1.0420445599999999e+00 , 9.6735099999999996e-01 , 3.4440999999999999e-02 , -2.5108999999999998e-01 -4.2677483547443575e+00 , 9.5514404994305568e+00 , 1.3181354400000000e+00 , 9.5162000000000002e-01 , -5.3352900000000002e-02 , -3.0260999999999999e-01 -1.0817987032891168e+01 , 3.6896828803322563e+01 , -2.8494992000000003e+00 , -1.1323999999999999e-01 , -8.7387199999999998e-01 , 4.7278399999999998e-01 -1.1111072659093439e+01 , 3.9851912866695656e+01 , -6.4193280000000019e-01 , -7.6293999999999995e-01 , -6.3757299999999995e-01 , -1.0687700000000000e-01 -1.1055472707966741e+01 , 4.0063378087123766e+01 , 1.0916799999999949e-02 , -8.2775299999999996e-01 , -5.6052500000000005e-01 , 2.5224600000000000e-02 -1.0858242565951437e+01 , 3.9655920482349202e+01 , 7.0811200000000007e-01 , -8.2775299999999996e-01 , -5.6052500000000005e-01 , 2.5224600000000000e-02 -1.0869696109627117e+01 , 4.0168444303908039e+01 , 1.3464515200000000e+00 , -7.8651800000000005e-01 , -6.0568400000000000e-01 , 1.2056699999999999e-01 -1.0836036628559297e+01 , 4.0969476510465448e+01 , 2.6748081600000000e+00 , -7.9566300000000001e-01 , -5.0878900000000005e-01 , 3.2871600000000001e-01 -1.0859145031898965e+01 , 4.1572650768615688e+01 , 3.3598416000000002e+00 , -8.8206499999999999e-01 , -4.4957300000000000e-01 , 1.4087200000000000e-01 -1.0270897139872996e+01 , 4.0289322836118700e+01 , 5.3551231999999995e+00 , -8.6590400000000001e-01 , -4.7762399999999999e-01 , -1.4861199999999999e-01 -1.0410643846790146e+01 , 4.3142863042442379e+01 , 8.4120056000000005e+00 , -9.5164700000000002e-01 , 2.1026800000000001e-01 , -2.2395599999999999e-01 -9.9309692883115801e+00 , 4.1810765149248191e+01 , 9.6456119999999999e+00 , -8.1703099999999995e-01 , -6.1440000000000002e-02 , -5.7331100000000002e-01 -9.8811522114191170e+00 , 4.2135566424864372e+01 , 1.0414494399999999e+01 , -8.1703099999999995e-01 , -6.1440000000000002e-02 , -5.7331100000000002e-01 -4.3378306200679937e+00 , 1.2645938837933970e+01 , 5.1556823999999999e+00 , 5.2554400000000001e-01 , 8.5068500000000002e-01 , -1.1813700000000000e-02 -4.2926273765420451e+00 , 1.2719269674311676e+01 , 5.5468784000000007e+00 , -2.1337600000000001e-01 , -9.7685699999999998e-01 , 1.4858200000000000e-02 -4.2231868851584329e+00 , 1.2492856794849923e+01 , 5.6784591999999998e+00 , -2.4759300000000001e-01 , -9.2400700000000002e-01 , -2.9139100000000001e-01 -4.2123412297611704e+00 , 1.2599755349773570e+01 , 5.8957359999999994e+00 , -1.7693700000000001e-01 , -8.5185800000000000e-01 , -4.9298199999999998e-01 -4.1666263586195758e+00 , 1.2506158705493405e+01 , 6.0591200000000001e+00 , 1.7273300000000000e-01 , 7.4928300000000003e-01 , 6.3932699999999998e-01 -4.0555730879078888e+00 , 1.2194599791151614e+01 , 6.3389319999999998e+00 , 2.4572500000000000e-01 , 5.9007699999999996e-01 , 7.6904399999999995e-01 -4.0162749942648528e+00 , 1.2132270835806418e+01 , 6.5060288000000002e+00 , 4.1053899999999999e-01 , 3.4106300000000001e-01 , 8.4565599999999996e-01 -3.8489371556981338e+00 , 1.1257397112132074e+01 , 6.3705688000000000e+00 , 7.5615500000000002e-01 , 1.0865800000000000e-01 , 6.4530799999999999e-01 -3.7244614927409785e+00 , 1.0629334579874513e+01 , 6.2992872000000002e+00 , -7.1555400000000002e-01 , 3.5550999999999999e-01 , -6.0132799999999997e-01 -3.7051918786559455e+00 , 1.0672150975835569e+01 , 6.4813391999999999e+00 , -7.1100900000000000e-01 , 3.1947900000000001e-01 , -6.2641800000000003e-01 -3.7340400016731357e+00 , 1.1042642578655370e+01 , 6.8085648000000001e+00 , 6.9880100000000001e-01 , 6.9752999999999998e-01 , -1.5851999999999999e-01 -3.7154526183191328e+00 , 1.1103870313938421e+01 , 7.0136215999999996e+00 , 5.5497700000000005e-01 , 7.4440899999999999e-01 , -3.7128899999999998e-01 -3.4851066533357260e+00 , 9.6785913478997774e+00 , 6.5202559999999998e+00 , -3.3181600000000000e-01 , 4.5786600000000000e-01 , 8.2477699999999998e-01 -3.4119232958210906e+00 , 9.3261613227645661e+00 , 6.4998616000000000e+00 , -4.5514500000000002e-01 , -3.9119999999999999e-01 , 7.9987900000000001e-01 -3.3712360299041855e+00 , 9.1957749645509601e+00 , 6.5818552000000006e+00 , 7.2442899999999999e-01 , 6.5017599999999998e-01 , -2.2907100000000000e-01 -3.3487193336810726e+00 , 9.2017902936754616e+00 , 6.7333936000000003e+00 , -6.9655699999999998e-01 , 7.1223899999999996e-01 , 8.6737599999999998e-02 -3.3024605712064203e+00 , 9.0241356308996323e+00 , 6.7851544000000006e+00 , -9.1707099999999997e-01 , 1.3663400000000001e-01 , -3.7458200000000003e-01 -3.2827884425608520e+00 , 9.0531285095561600e+00 , 6.9512111999999995e+00 , -5.9249700000000005e-01 , 6.1897000000000001e-02 , -8.0319099999999999e-01 -3.2199963275513768e+00 , 8.7322518726231522e+00 , 6.9104432000000005e+00 , 3.9520200000000000e-01 , 1.7116200000000002e-02 , 9.1843500000000000e-01 -3.0872386044751092e+00 , 7.8015888864304035e+00 , 6.4738408000000005e+00 , -1.6534599999999999e-01 , -1.7393600000000001e-01 , 9.7077700000000000e-01 -3.1421047188794171e+00 , 8.4647146667866302e+00 , 7.0363768000000002e+00 , 5.0428099999999998e-01 , -1.0693499999999999e-03 , 8.6353899999999995e-01 -3.0685467849365411e+00 , 8.0039393320070271e+00 , 6.8733776000000004e+00 , 6.1930200000000002e-01 , 7.5566199999999994e-01 , -2.1316700000000000e-01 -3.0519515619787132e+00 , 8.0598937328614717e+00 , 7.0527047999999999e+00 , 6.0505500000000001e-01 , 7.7767100000000000e-01 , 1.7069500000000001e-01 -3.1143454673090236e+00 , 8.8899897424709824e+00 , 7.8026072000000006e+00 , -6.9740199999999997e-01 , -6.8125300000000000e-01 , -2.2254299999999999e-01 -3.0491004496855649e+00 , 8.4967758601673751e+00 , 7.6763304000000003e+00 , -9.1238500000000000e-01 , 3.2085200000000003e-01 , -2.5418099999999999e-01 -2.9200290464573877e+00 , 7.3896264543645689e+00 , 6.9759007999999998e+00 , -3.9455800000000002e-01 , -3.1067299999999998e-01 , -8.6475800000000003e-01 -2.8927342652049517e+00 , 7.3240959716629916e+00 , 7.0611600000000001e+00 , 7.8682200000000002e-01 , 1.1143900000000000e-01 , 6.0703600000000002e-01 -2.8733440846578922e+00 , 7.3536871917519386e+00 , 7.2249808000000000e+00 , 6.6458200000000001e-01 , -8.3805500000000005e-02 , 7.4250099999999997e-01 -2.8295853610819517e+00 , 7.0877420792235730e+00 , 7.1394096000000005e+00 , 7.4415500000000001e-01 , 1.4703500000000000e-01 , 6.5162500000000001e-01 -2.8585624232920734e+00 , 7.7689652416624835e+00 , 7.8916416000000007e+00 , 1.4684900000000001e-01 , -6.1675400000000002e-01 , 7.7333700000000005e-01 -2.8022089363633147e+00 , 7.3300035228742395e+00 , 7.6509024000000005e+00 , 6.1569200000000002e-01 , 3.9122499999999999e-01 , 6.8400799999999995e-01 -2.7620989754365270e+00 , 7.0962081621547162e+00 , 7.5833959999999996e+00 , 1.3063200000000000e-01 , -3.2227800000000001e-01 , 9.3758900000000001e-01 -2.7160675859655217e+00 , 6.7474569312999302e+00 , 7.3920463999999999e+00 , 4.8968299999999998e-01 , 4.6202399999999999e-01 , 7.3942200000000002e-01 -2.6908881004059646e+00 , 6.6967232437422926e+00 , 7.4879655999999999e+00 , 5.8418099999999995e-01 , 5.3415599999999996e-01 , 6.1107199999999995e-01 -2.6628761735403579e+00 , 6.6222716580904342e+00 , 7.5604432000000008e+00 , 6.7974299999999999e-01 , 5.6181599999999998e-01 , 4.7149999999999997e-01 -2.6514757193747069e+00 , 6.9030336855092731e+00 , 8.0239504000000004e+00 , 2.2319599999999998e-02 , -9.3457999999999997e-01 , 3.5505300000000001e-01 -2.6551933498934224e+00 , 7.6785558758909325e+00 , 9.0755048000000009e+00 , -8.9719099999999996e-02 , 6.6841499999999998e-02 , 9.9372199999999999e-01 -2.6157149822387300e+00 , 7.4559881995568320e+00 , 9.0216744000000002e+00 , -8.9719099999999996e-02 , 6.6841499999999998e-02 , 9.9372199999999999e-01 -2.5797200562214133e+00 , 7.3290467338679255e+00 , 9.0743296000000004e+00 , 2.5380900000000001e-01 , 1.8524599999999999e-01 , 9.4935000000000003e-01 -2.5439886323439564e+00 , 7.1620152874628564e+00 , 9.0756504000000007e+00 , 2.7605099999999999e-01 , -6.4302199999999998e-01 , -7.1436599999999995e-01 -2.5100241731111734e+00 , 7.0863570637634812e+00 , 9.1882927999999993e+00 , -8.0593100000000001e-02 , 6.6462500000000002e-01 , 7.4281799999999998e-01 -2.4752706119750680e+00 , 6.9706713855686466e+00 , 9.2496736000000013e+00 , -5.3369600000000003e-02 , 5.7472900000000005e-01 , 8.1660100000000002e-01 -2.4403308360797671e+00 , 6.9319664008738267e+00 , 9.4190272000000004e+00 , -6.4125799999999999e-01 , 6.6620400000000002e-01 , 3.8073699999999999e-01 -2.4069517258802939e+00 , 6.7059554231566123e+00 , 9.3231288000000010e+00 , 9.9742100000000000e-01 , -5.8322899999999997e-02 , 4.1820900000000001e-02 -2.3707905337106303e+00 , 6.6984554022240665e+00 , 9.5416951999999995e+00 , 6.2394200000000000e-01 , 1.2545999999999999e-01 , 7.7133399999999996e-01 -2.3380021628929399e+00 , 6.5150208807814494e+00 , 9.4990760000000005e+00 , 7.3319000000000001e-01 , -5.5325899999999995e-01 , 3.9539500000000000e-01 -2.3099355340394774e+00 , 6.2477786502088062e+00 , 9.3103264000000010e+00 , 8.0465799999999998e-01 , -5.2150099999999999e-01 , -2.8383399999999998e-01 -2.2780462024330048e+00 , 6.1208947884576261e+00 , 9.3378031999999997e+00 , 7.8848099999999999e-01 , -6.0837500000000000e-01 , -9.0433600000000003e-02 -2.2401364193601911e+00 , 6.1120746619181601e+00 , 9.5705448000000004e+00 , -8.2240199999999997e-01 , 3.4129199999999998e-01 , -4.5516400000000001e-01 -2.2152276604254375e+00 , 5.8716405814217687e+00 , 9.3942752000000009e+00 , 6.6667699999999996e-01 , -6.7609399999999997e-01 , 3.1374900000000000e-01 -2.2322543297010928e+00 , 5.1480434921593154e+00 , 8.2834615999999990e+00 , 2.1089800000000000e-01 , 8.6393399999999998e-01 , -4.5731899999999998e-01 -2.1949495281252522e+00 , 5.1857289727894571e+00 , 8.5785096000000003e+00 , 2.0283200000000001e-01 , 9.2401800000000001e-01 , 3.2411299999999998e-01 -2.0585316769557034e+00 , 6.1259740312725315e+00 , 1.0754990400000001e+01 , -8.9333300000000004e-01 , 4.0942899999999999e-01 , -1.8526799999999999e-01 -2.1430556129861760e+00 , 4.9754582278703321e+00 , 8.6199952000000000e+00 , -6.8297300000000005e-01 , -5.6827700000000003e-01 , -4.5892200000000000e-01 -2.0965119808838408e+00 , 5.0242594101969518e+00 , 8.9840264000000012e+00 , -4.1951500000000003e-01 , -9.0764400000000001e-01 , 1.3753500000000000e-02 -2.0999808521610617e+00 , 4.7166872018591128e+00 , 8.5385840000000002e+00 , 2.7624700000000002e-01 , 7.0127700000000004e-01 , -6.5719000000000005e-01 -2.1999774391166622e+00 , 3.8852447637518721e+00 , 6.7467992000000008e+00 , -4.4324000000000002e-01 , 3.6733300000000002e-01 , 8.1768200000000002e-01 -2.1846265847411468e+00 , 3.8115132993802536e+00 , 6.7411935999999999e+00 , -5.1720800000000000e-01 , 3.4137899999999999e-01 , 7.8482900000000000e-01 -2.1682894063824194e+00 , 3.7456784900413513e+00 , 6.7535072000000005e+00 , 1.6648499999999999e-01 , -6.8035400000000001e-01 , -7.1372300000000000e-01 -2.1426906612081251e+00 , 3.7196589459108491e+00 , 6.8824255999999995e+00 , 4.7650799999999999e-01 , -6.9715400000000005e-01 , -5.3564699999999998e-01 -2.1242307565618210e+00 , 3.6575429445298866e+00 , 6.9127520000000002e+00 , 2.4406700000000001e-01 , -5.7534099999999999e-01 , -7.8064999999999996e-01 -2.1057971125773864e+00 , 3.5982655433532571e+00 , 6.9518976000000006e+00 , 1.8771900000000000e-01 , 7.7322900000000006e-01 , 6.0570400000000002e-01 -2.0697648262118298e+00 , 3.5894333778504528e+00 , 7.1691536000000005e+00 , -5.6955100000000003e-01 , -8.0883600000000000e-01 , -1.4627399999999999e-01 -1.9824628207734183e+00 , 3.7121374591051897e+00 , 7.8965712000000003e+00 , -6.8728900000000004e-01 , -4.4983400000000001e-01 , 5.7033699999999998e-01 -2.0622945401112425e+00 , 3.3776729511276162e+00 , 6.9228503999999997e+00 , 6.2195000000000000e-01 , 1.1277300000000000e-01 , -7.7489300000000005e-01 -2.0468699861743569e+00 , 3.3091368053931021e+00 , 6.9272704000000003e+00 , -4.5700499999999999e-01 , -6.6137500000000002e-02 , -8.8700199999999996e-01 -2.0243248641425224e+00 , 3.2559765145672301e+00 , 7.0011311999999997e+00 , 1.0055200000000000e-01 , 9.8368599999999995e-01 , 1.4916599999999999e-01 -1.8623252752865123e+00 , 3.4451518770219782e+00 , 8.3008088000000004e+00 , 6.6000300000000001e-01 , 4.5413900000000001e-01 , 5.9845899999999996e-01 -1.8374586946068785e+00 , 3.3608112528116769e+00 , 8.3459760000000003e+00 , 7.3213700000000004e-01 , -2.4990599999999999e-01 , 6.3365800000000005e-01 -1.8369603632279397e+00 , 3.2425403049165999e+00 , 8.1857223999999995e+00 , -6.3573999999999997e-01 , -7.6475300000000002e-01 , 1.0482500000000000e-01 -3.1307550700198989e+00 , 3.7029862978597965e+00 , 8.4424800000000011e-01 , -3.2920199999999997e-02 , 6.6259399999999996e-02 , 9.9725900000000001e-01 -3.1476845957791291e+00 , 3.7630093400523372e+00 , 8.3481519999999998e-01 , -5.5313700000000000e-02 , 3.6700099999999999e-02 , 9.9779399999999996e-01 -3.1612074530719658e+00 , 3.8177470264725502e+00 , 8.3535599999999999e-01 , -8.6728000000000000e-02 , 4.8397099999999998e-02 , 9.9505600000000005e-01 -3.1767967640650410e+00 , 3.8794084679999843e+00 , 8.2852320000000002e-01 , -3.5468300000000001e-02 , 1.5106300000000000e-01 , 9.8788799999999999e-01 -3.1932480453652636e+00 , 3.9413719778468366e+00 , 8.2333360000000000e-01 , -7.2199899999999997e-02 , 1.8176100000000001e-01 , 9.8068900000000003e-01 -3.2116375513301092e+00 , 4.0093737160455687e+00 , 8.1166479999999996e-01 , -3.8126800000000002e-02 , 1.5202499999999999e-01 , 9.8764099999999999e-01 -3.2308985241997155e+00 , 4.0787299884941106e+00 , 8.0164959999999996e-01 , -1.8002899999999999e-02 , 1.8721900000000000e-01 , 9.8215300000000005e-01 -3.2521029478966863e+00 , 4.1552503702328298e+00 , 7.8545679999999996e-01 , -7.2466299999999997e-02 , 1.6206499999999999e-01 , 9.8411599999999999e-01 -3.2709873214749603e+00 , 4.2274590828461713e+00 , 7.7896720000000008e-01 , 5.4926999999999997e-02 , -1.7158499999999999e-01 , -9.8363699999999998e-01 -3.2917462830639841e+00 , 4.3058629084068247e+00 , 7.6671599999999995e-01 , -5.0222999999999997e-02 , 1.4332500000000001e-01 , 9.8840099999999997e-01 -3.3132988880021976e+00 , 4.3857434424134105e+00 , 7.5671120000000003e-01 , -6.3184500000000005e-02 , 1.4568600000000001e-01 , 9.8731100000000005e-01 -3.3346035591464163e+00 , 4.4660618478552312e+00 , 7.4883839999999990e-01 , -2.7575300000000001e-02 , 1.5424800000000000e-01 , 9.8764700000000005e-01 -3.3587928450469624e+00 , 4.5547644637874667e+00 , 7.3572400000000004e-01 , -4.1563299999999997e-02 , 1.9051599999999999e-01 , 9.8080400000000001e-01 -3.3878520777340091e+00 , 4.6578141755058411e+00 , 7.1058719999999997e-01 , -6.4543100000000006e-02 , 1.6607400000000000e-01 , 9.8399899999999996e-01 -3.4083498467010251e+00 , 4.7417467163181790e+00 , 7.0989039999999992e-01 , -9.7869800000000007e-03 , 2.1175400000000000e-01 , 9.7727399999999998e-01 -3.4439767806667936e+00 , 4.8619707723091450e+00 , 6.7653760000000007e-01 , -4.9842400000000002e-02 , 1.8532999999999999e-01 , 9.8141100000000003e-01 -3.4669854654674324e+00 , 4.9560263416918495e+00 , 6.7393759999999991e-01 , -7.3677500000000007e-02 , 1.6574100000000000e-01 , 9.8341299999999998e-01 -3.4987631692274879e+00 , 5.0717348636475741e+00 , 6.5420879999999992e-01 , -6.0589799999999999e-02 , 1.8241599999999999e-01 , 9.8135300000000003e-01 -3.5312475939294146e+00 , 5.1901864684074290e+00 , 6.3773519999999984e-01 , -4.4782599999999999e-02 , 1.8996900000000000e-01 , 9.8076799999999997e-01 -3.5653160955504903e+00 , 5.3175226813136351e+00 , 6.1823519999999998e-01 , -3.7843099999999998e-02 , 1.9914299999999999e-01 , 9.7923899999999997e-01 -3.6059892131234292e+00 , 5.4619558292752366e+00 , 5.9010319999999994e-01 , -4.3708200000000003e-02 , 1.8368100000000001e-01 , 9.8201400000000005e-01 -3.6401608625603794e+00 , 5.5919764437996964e+00 , 5.7871519999999999e-01 , -5.4068999999999999e-02 , 1.6572300000000001e-01 , 9.8468900000000004e-01 -3.6828380014789532e+00 , 5.7485097264335341e+00 , 5.5312080000000008e-01 , -1.7404900000000001e-02 , 1.8303700000000001e-01 , 9.8295200000000005e-01 -3.7308847832143330e+00 , 5.9225262941139496e+00 , 5.2059999999999995e-01 , -1.5866600000000002e-02 , 2.0412600000000000e-01 , 9.7881600000000002e-01 -3.7841816411209290e+00 , 6.1152965154084322e+00 , 4.8215119999999989e-01 , -1.2679899999999999e-02 , 1.9347800000000001e-01 , 9.8102299999999998e-01 -3.8349215420148299e+00 , 6.3030915757813748e+00 , 4.5532960000000000e-01 , -3.0598500000000001e-02 , 1.7265800000000001e-01 , 9.8450599999999999e-01 -3.8878412371172537e+00 , 6.5004968590408332e+00 , 4.2923599999999995e-01 , -3.2014599999999997e-02 , 1.6939699999999999e-01 , 9.8502800000000001e-01 -3.9487717860667613e+00 , 6.7263837899801668e+00 , 3.9339759999999990e-01 , -3.8084699999999999e-02 , 1.9419900000000001e-01 , 9.8022299999999996e-01 -4.0185064344666781e+00 , 6.9800324109528420e+00 , 3.4966560000000002e-01 , -3.7194800000000000e-02 , 1.8821199999999999e-01 , 9.8142399999999996e-01 -4.0883535891672915e+00 , 7.2374709290972508e+00 , 3.1423279999999987e-01 , -5.4211799999999997e-02 , 1.7345800000000000e-01 , 9.8334800000000000e-01 -4.1628893877490096e+00 , 7.5146528913909503e+00 , 2.7763519999999997e-01 , -4.8675799999999998e-02 , 1.7418500000000001e-01 , 9.8350899999999997e-01 -4.2477031545395203e+00 , 7.8308570159853073e+00 , 2.3141759999999989e-01 , -5.0194500000000003e-02 , 1.7002300000000001e-01 , 9.8416099999999995e-01 -4.3379343399529997e+00 , 8.1673449410702919e+00 , 1.8687440000000000e-01 , 1.7165900000000001e-01 , -2.4344099999999999e-01 , -9.5460400000000001e-01 -4.4362959182049693e+00 , 8.5349704035372191e+00 , 1.4050080000000009e-01 , -5.7463999999999996e-03 , 2.7175199999999999e-01 , 9.6235000000000004e-01 -4.5508856655498313e+00 , 8.9609486767077655e+00 , 8.1522400000000106e-02 , 4.5385599999999998e-01 , 1.7062900000000000e-01 , 8.7458599999999997e-01 -4.3916794373927708e+00 , 8.5310197266414534e+00 , 4.1175359999999994e-01 , 9.9363199999999996e-01 , 1.0690400000000000e-01 , 3.5595799999999997e-02 -4.3652196941368340e+00 , 8.5152886122108136e+00 , 5.4935599999999996e-01 , 9.8600500000000002e-01 , 8.1594100000000003e-02 , 1.4538599999999999e-01 -4.3361442298778972e+00 , 8.4873864230686102e+00 , 6.8926719999999975e-01 , 9.9272000000000005e-01 , 6.3890600000000006e-02 , 1.0210600000000000e-01 -4.3298320194064903e+00 , 8.5310891248423530e+00 , 7.9944480000000007e-01 , 9.9860400000000005e-01 , 1.8528900000000001e-02 , 4.9466000000000003e-02 -4.3197133217939498e+00 , 8.5640453809244050e+00 , 9.1341839999999985e-01 , 9.9870700000000001e-01 , 3.3420999999999999e-02 , -3.8295400000000000e-02 -4.3111631441326166e+00 , 8.6048113276765630e+00 , 1.0243572799999998e+00 , 9.9340799999999996e-01 , 5.9928599999999999e-02 , -9.7715600000000000e-02 -4.3229705184021050e+00 , 8.7097333457001422e+00 , 1.1154696000000000e+00 , -9.5031900000000002e-01 , -1.3936300000000000e-02 , 3.1096600000000002e-01 -4.4016538842498338e+00 , 9.2660963356908059e+00 , 1.4746356800000000e+00 , -9.0422300000000000e-01 , 2.8724800000000002e-02 , 4.2609399999999997e-01 -1.3571861938913399e+01 , 4.2806564545388618e+01 , -4.0978216000000005e+00 , -6.6526700000000005e-01 , -2.5989400000000001e-01 , -6.9991099999999995e-01 -1.8419205440349064e+01 , 6.1689643417773006e+01 , -5.2696312000000001e+00 , -2.3607600000000001e-01 , 3.4536200000000000e-01 , 9.0829099999999996e-01 -1.1979920363811589e+01 , 3.8969961958988208e+01 , -8.0156000000000116e-02 , 6.8147300000000000e-01 , 6.9940800000000003e-01 , 2.1546199999999999e-01 -1.1901737440021099e+01 , 3.9073493140588575e+01 , 5.6977119999999992e-01 , 7.5385999999999997e-01 , 6.5078000000000003e-01 , 9.0446899999999997e-02 -1.1690023444317685e+01 , 3.9920034529624758e+01 , 3.1874304000000002e+00 , 8.5563199999999995e-01 , 5.1748200000000000e-01 , -1.0302800000000001e-02 -1.1657867403160472e+01 , 4.0229951822683880e+01 , 3.8597071999999999e+00 , 6.1827799999999999e-01 , 6.4105100000000004e-01 , 4.5473700000000000e-01 -1.1130394420559323e+01 , 3.8917452515443742e+01 , 5.1278728000000005e+00 , -4.1050100000000000e-01 , -8.4094500000000005e-01 , -3.5256199999999999e-01 -1.1017679871353096e+01 , 3.8880384703028710e+01 , 5.7732760000000010e+00 , 7.2283200000000003e-01 , 6.8099699999999996e-01 , 1.1729100000000001e-01 -1.0987241395498407e+01 , 3.9196486502004355e+01 , 6.4502432000000010e+00 , -8.3449200000000001e-01 , -4.7731499999999999e-01 , 2.7530700000000002e-01 -1.1246874229438927e+01 , 4.0790122196440194e+01 , 7.2796015999999995e+00 , -9.2579100000000003e-01 , 3.4544300000000000e-01 , 1.5355900000000000e-01 -1.1156372014420427e+01 , 4.0877997844333940e+01 , 7.9758816000000001e+00 , -8.6091600000000001e-01 , 2.4591600000000000e-01 , -4.4536300000000001e-01 -1.1047439478578877e+01 , 4.0884567240891393e+01 , 8.6654015999999991e+00 , 7.3180500000000004e-01 , 1.4408399999999999e-01 , 6.6610899999999995e-01 -1.0616433176688112e+01 , 3.9433829336231000e+01 , 9.1201207999999987e+00 , -9.7240099999999996e-01 , -1.5379599999999999e-01 , -1.7544999999999999e-01 -1.0544983893060582e+01 , 3.9598892835276409e+01 , 9.8183351999999999e+00 , 9.4624900000000001e-01 , 3.2263900000000001e-01 , -2.2739599999999999e-02 -4.5908024744564813e+00 , 1.2505574648307521e+01 , 5.2771336000000000e+00 , 7.1716700000000000e-01 , 6.7140400000000000e-01 , 1.8678300000000000e-01 -4.5559109327942879e+00 , 1.2482807338680878e+01 , 5.4571056000000002e+00 , -6.9741600000000004e-01 , -6.8047199999999997e-01 , -2.2487499999999999e-01 -4.5575738872869422e+00 , 1.2635260632604345e+01 , 5.6818392000000006e+00 , 6.0329800000000000e-01 , 7.7364400000000000e-01 , 1.9366900000000001e-01 -4.5231780474457652e+00 , 1.2615596867999875e+01 , 5.8667824000000000e+00 , -4.6478100000000000e-01 , -7.5369100000000000e-01 , -4.6468100000000001e-01 -4.4288002204680943e+00 , 1.2298727395303855e+01 , 5.9656760000000002e+00 , -4.1092299999999998e-01 , -6.3892199999999999e-01 , -6.5032400000000001e-01 -4.4091524436043263e+00 , 1.2351261570514966e+01 , 6.1695263999999996e+00 , 3.3736800000000000e-01 , 5.2873099999999995e-01 , 7.7886299999999997e-01 -4.3183845754284009e+00 , 1.2041501398612253e+01 , 6.2570112000000000e+00 , -4.0323999999999999e-01 , -5.1006600000000002e-01 , -7.5975700000000002e-01 -4.2753891972995985e+00 , 1.1971918102393396e+01 , 6.4189704000000001e+00 , -3.4072400000000003e-01 , -4.0954499999999999e-01 , -8.4627399999999997e-01 -4.0828147273462907e+00 , 1.1102709968645740e+01 , 6.2851328000000004e+00 , -4.1755300000000001e-01 , -8.3021199999999995e-01 , 3.6931900000000001e-01 -4.0138366029814687e+00 , 1.0879669776530886e+01 , 6.3703192000000000e+00 , -2.2323799999999999e-01 , -7.0924600000000004e-02 , 9.7218000000000004e-01 -3.9788898275804789e+00 , 1.0837387289382271e+01 , 6.5219199999999997e+00 , -3.8470700000000002e-01 , 9.2030900000000004e-01 , 7.0936899999999997e-02 -3.9421726396133603e+00 , 1.0782585115349962e+01 , 6.6689448000000002e+00 , 1.0397900000000000e-01 , -9.9030899999999999e-01 , 9.2071399999999998e-02 -3.9027689287167071e+00 , 1.0716170536640368e+01 , 6.8104680000000002e+00 , 3.4222799999999998e-01 , 8.7470999999999999e-01 , -3.4316600000000003e-01 -4.0591594935820501e+00 , 1.1790995893081709e+01 , 7.4880903999999999e+00 , 7.7092499999999997e-01 , 3.6068900000000001e-02 , -6.3590400000000002e-01 -3.5716524615187244e+00 , 9.0799450768500094e+00 , 6.3554160000000000e+00 , 7.5768300000000000e-01 , 5.0662099999999999e-01 , 4.1140199999999999e-01 -3.5340888328744677e+00 , 8.9906854867947317e+00 , 6.4524896000000007e+00 , 7.1113099999999996e-01 , 4.0623700000000001e-01 , 5.7381499999999996e-01 -3.5716113514705592e+00 , 9.3627763037905360e+00 , 6.7947328000000002e+00 , -1.0161900000000000e-01 , 5.8426999999999996e-01 , 8.0517200000000000e-01 -3.4013229415466113e+00 , 8.4374939760947942e+00 , 6.4347887999999998e+00 , 1.0412700000000000e-01 , -4.3903599999999998e-01 , 8.9241499999999996e-01 -3.4179684957117420e+00 , 8.6864294735628249e+00 , 6.7146944000000000e+00 , -2.4608600000000000e-01 , -5.5303100000000005e-01 , 7.9598899999999995e-01 -3.3680626442176993e+00 , 8.5127894719887198e+00 , 6.7539752000000002e+00 , -4.8772700000000002e-01 , -8.7003600000000003e-01 , 7.1827799999999997e-02 -3.2527320527490877e+00 , 7.8833760572531428e+00 , 6.5040320000000005e+00 , 2.8956900000000002e-01 , 6.6135600000000005e-01 , -6.9192399999999998e-01 -3.2317957100887069e+00 , 7.8793442809687839e+00 , 6.6323888000000002e+00 , 9.9100400000000005e-02 , 9.2407799999999995e-01 , -3.6913299999999999e-01 -3.2334099550125512e+00 , 8.0442350186110350e+00 , 6.8766744000000006e+00 , -3.7700499999999998e-01 , -9.0971500000000005e-01 , 1.7402999999999999e-01 -3.2142701721663940e+00 , 8.0755748406648031e+00 , 7.0386752000000001e+00 , 5.6748699999999996e-01 , 6.3806799999999997e-01 , 5.2041099999999996e-01 -3.1619855068795992e+00 , 7.8512707327259443e+00 , 7.0210056000000005e+00 , -6.8905300000000003e-01 , -6.3970099999999996e-01 , -3.4057199999999999e-01 -3.1505179261056671e+00 , 7.9432295296480078e+00 , 7.2325208000000005e+00 , -6.0314000000000001e-01 , -7.8052400000000000e-01 , -1.6433100000000000e-01 -3.1221935280564406e+00 , 7.8994774109908610e+00 , 7.3466192000000001e+00 , 2.5001600000000002e-01 , 6.3282799999999995e-01 , 7.3281799999999997e-01 -3.0251801218598011e+00 , 7.2804729451682260e+00 , 6.9994048000000006e+00 , 5.6111100000000003e-01 , -2.4027299999999999e-01 , 7.9210000000000003e-01 -2.9927571955917065e+00 , 7.1916611817308649e+00 , 7.0628864000000000e+00 , -8.1889699999999999e-01 , -5.2546400000000000e-02 , -5.7152999999999998e-01 -2.9566406588911072e+00 , 7.0628592706862152e+00 , 7.0904672000000000e+00 , -9.0089100000000000e-01 , -1.6191500000000000e-01 , -4.0271400000000002e-01 -2.9307308570675050e+00 , 7.0348878209815302e+00 , 7.2043680000000005e+00 , 2.5451499999999999e-01 , 1.8996499999999999e-01 , 9.4822799999999996e-01 -2.9027107924507316e+00 , 6.9815727415087236e+00 , 7.2973856000000001e+00 , 9.5021900000000006e-02 , 5.0487700000000002e-01 , 8.5794499999999996e-01 -2.8674077541563205e+00 , 6.8513227831087935e+00 , 7.3179880000000006e+00 , -6.9454199999999999e-01 , -2.4053200000000000e-02 , -7.1904999999999997e-01 -2.8302970904318339e+00 , 6.6922993511795088e+00 , 7.3060488000000001e+00 , -7.8580700000000003e-01 , -4.0952600000000000e-01 , -4.6346100000000001e-01 -2.8072220280542113e+00 , 6.6942115608617438e+00 , 7.4529176000000001e+00 , -5.2976699999999999e-01 , -5.1799200000000001e-01 , -6.7158799999999996e-01 -2.7810919424910310e+00 , 6.6717240614298170e+00 , 7.5781648000000006e+00 , 3.5066900000000001e-01 , 5.2491299999999996e-01 , 7.7556300000000000e-01 -2.7484725267575283e+00 , 6.5542001297920223e+00 , 7.6044767999999996e+00 , -5.3853700000000004e-01 , -6.3028899999999999e-01 , -5.5920800000000004e-01 -2.7462654386783587e+00 , 6.8996459667820371e+00 , 8.1486048000000011e+00 , 2.2319499999999999e-02 , -9.3457999999999997e-01 , 3.5505300000000001e-01 -2.7493647421813199e+00 , 7.4231252366117753e+00 , 8.9345432000000002e+00 , 6.6678199999999999e-01 , -1.7985100000000000e-02 , 7.4503500000000000e-01 -2.7137112458384607e+00 , 7.3780996666590282e+00 , 9.0828784000000002e+00 , -3.1339699999999998e-01 , -2.9141600000000001e-01 , -9.0380199999999999e-01 -2.6719442566261487e+00 , 7.1869238587778561e+00 , 9.0526663999999997e+00 , 2.2053500000000001e-01 , -5.1141599999999998e-01 , -8.3055299999999999e-01 -2.6348314818614309e+00 , 7.1125056796709787e+00 , 9.1655376000000004e+00 , -1.2362500000000000e-01 , -6.4951800000000004e-01 , -7.5022900000000003e-01 -2.5971616117696374e+00 , 7.0100025945198130e+00 , 9.2442655999999985e+00 , 3.0881700000000001e-01 , 7.3028199999999999e-01 , 6.0936100000000004e-01 -2.5409000945301905e+00 , 6.1465136672231182e+00 , 8.2666968000000001e+00 , 7.4482300000000001e-01 , 5.9731800000000002e-01 , 2.9740600000000000e-01 -2.5206601429517099e+00 , 6.7122602755666954e+00 , 9.2679880000000008e+00 , -8.2368300000000005e-01 , 1.1401100000000000e-01 , -5.5547100000000005e-01 -2.4838696167759005e+00 , 6.7247733548434789e+00 , 9.5119615999999994e+00 , 2.0189799999999999e-01 , 4.7432099999999999e-01 , 8.5688799999999998e-01 -2.4466175576342808e+00 , 6.0679346703957755e+00 , 8.7367248000000011e+00 , -2.7060099999999998e-01 , -2.4601100000000001e-01 , -9.3072699999999997e-01 -2.4091368707762020e+00 , 6.3470072795511827e+00 , 9.3970935999999998e+00 , 9.8358100000000004e-01 , -1.5165999999999999e-01 , 9.7817600000000005e-02 -2.3750250025291249e+00 , 6.1384310596712224e+00 , 9.2926983999999990e+00 , 6.7104299999999995e-01 , -6.7770799999999998e-01 , -3.0068800000000001e-01 -2.3353389009089063e+00 , 6.1538165335667401e+00 , 9.5608520000000006e+00 , -8.5199100000000005e-01 , 4.3596699999999999e-01 , -2.8990199999999999e-01 -2.2976758590249888e+00 , 6.0596554904159214e+00 , 9.6494080000000011e+00 , 6.4266599999999996e-01 , -4.8804199999999998e-01 , 5.9058900000000003e-01 -2.3016431851692012e+00 , 5.1844041214126646e+00 , 8.2784592000000004e+00 , -1.8021300000000001e-01 , -9.1892900000000000e-01 , 3.5084700000000002e-01 -2.2705114213130795e+00 , 5.1394143955219125e+00 , 8.4069096000000005e+00 , 2.3990000000000000e-01 , 9.7029399999999999e-01 , 3.1258500000000002e-02 -2.2340640547302280e+00 , 5.1407700443133120e+00 , 8.6377376000000012e+00 , -5.7354799999999995e-01 , -1.4642700000000000e-02 , 8.1904100000000002e-01 -2.2039461300071106e+00 , 5.0377710131943978e+00 , 8.6629368000000007e+00 , -3.0017700000000003e-01 , 3.1489600000000001e-01 , 9.0040799999999999e-01 -2.1751360437728335e+00 , 4.9302937428396341e+00 , 8.6767168000000012e+00 , 1.2635500000000000e-01 , 1.8530400000000000e-01 , 9.7452399999999995e-01 -2.1623887910195285e+00 , 4.7003153992556275e+00 , 8.4021256000000015e+00 , 2.7994400000000003e-01 , 7.1348699999999998e-01 , -6.4231400000000005e-01 -2.2303891816900014e+00 , 3.9423872904042083e+00 , 6.8155536000000003e+00 , 2.9113200000000000e-01 , -1.3494800000000001e-01 , -9.4711699999999999e-01 -2.2162321182650722e+00 , 3.8484494127148752e+00 , 6.7626176000000005e+00 , -4.0982600000000002e-01 , 2.6099800000000001e-01 , 8.7402700000000000e-01 -2.1978083825460830e+00 , 3.7787110573915204e+00 , 6.7656648000000006e+00 , 5.1713299999999995e-01 , -5.4541200000000001e-01 , -6.5961999999999998e-01 -2.1746318410523844e+00 , 3.7404911355662045e+00 , 6.8555936000000006e+00 , -3.4250300000000000e-01 , 9.1278700000000002e-01 , 2.2251000000000001e-01 -2.1528384563414158e+00 , 3.6857111049334446e+00 , 6.9058152000000002e+00 , 4.8870799999999998e-01 , -6.2196600000000002e-01 , -6.1181900000000000e-01 -2.1335230478320382e+00 , 3.6204186230455901e+00 , 6.9254712000000005e+00 , -8.7881200000000007e-02 , 5.7528500000000005e-01 , 8.1321800000000000e-01 -2.1106935275586309e+00 , 3.5703416929423368e+00 , 6.9935184000000001e+00 , -3.8805499999999998e-01 , -7.4810500000000002e-01 , -5.3828600000000004e-01 -1.9994294406733570e+00 , 3.7818032844328595e+00 , 8.0088287999999999e+00 , -7.6176500000000003e-01 , -4.7467500000000001e-01 , 4.4090600000000002e-01 -2.0810952924783570e+00 , 3.4126819328304654e+00 , 6.9372856000000001e+00 , 1.2037900000000000e-01 , -2.4755900000000000e-01 , 9.6136600000000005e-01 -2.0648846333852946e+00 , 3.3401662870563698e+00 , 6.9217063999999997e+00 , -4.6940599999999999e-01 , 8.7134600000000006e-02 , -8.7867300000000004e-01 -2.0463296024950877e+00 , 3.2746353149551632e+00 , 6.9350807999999997e+00 , -4.6424100000000001e-01 , -3.8713799999999998e-01 , -7.9662100000000002e-01 -1.9058852103891870e+00 , 3.4416725451880268e+00 , 8.0714784000000002e+00 , -8.8872700000000004e-01 , -4.2355199999999998e-01 , -1.7540700000000001e-01 -1.8599068508715733e+00 , 3.3940340571791205e+00 , 8.2784696000000011e+00 , -6.3049900000000003e-01 , -4.9316999999999998e-03 , -7.7617499999999995e-01 -1.8415377760948861e+00 , 3.2980220372605604e+00 , 8.2512424000000006e+00 , -6.3875199999999999e-01 , 4.3993300000000002e-01 , -6.3123300000000004e-01 -3.1927268110096434e+00 , 3.7303622791627555e+00 , 8.2996880000000006e-01 , 5.7237600000000000e-02 , -3.6270499999999997e-02 , -9.9770199999999998e-01 -3.2029763666991817e+00 , 3.7748117822421721e+00 , 8.4723280000000001e-01 , -2.9830599999999999e-02 , 2.4588400000000000e-02 , 9.9925299999999995e-01 -3.2206819126786197e+00 , 3.8352468080968043e+00 , 8.4003600000000000e-01 , -7.5332200000000002e-02 , 1.2843199999999999e-01 , 9.8885299999999998e-01 -3.2414109316041309e+00 , 3.9016535418733254e+00 , 8.2620399999999994e-01 , -4.9684699999999998e-02 , 1.4134400000000000e-01 , 9.8871299999999995e-01 -3.2598035092354154e+00 , 3.9637771184406576e+00 , 8.2227279999999991e-01 , -4.5265899999999998e-02 , 1.5825900000000001e-01 , 9.8635899999999999e-01 -3.2801608953992627e+00 , 4.0319124776047213e+00 , 8.1167520000000004e-01 , -1.3580399999999999e-02 , 2.0243800000000001e-01 , 9.7920099999999999e-01 -3.3045320919647390e+00 , 4.1071541101423463e+00 , 7.9504560000000013e-01 , -7.1549100000000004e-02 , 1.4275299999999999e-01 , 9.8716899999999996e-01 -3.3213643368572647e+00 , 4.1724207484246882e+00 , 7.9584640000000006e-01 , -7.6282000000000003e-02 , 1.5490300000000001e-01 , 9.8497999999999997e-01 -3.3484263544413322e+00 , 4.2552751123621393e+00 , 7.7539999999999987e-01 , -6.1536700000000000e-02 , 1.9599300000000000e-01 , 9.7867300000000002e-01 -3.3690122170880414e+00 , 4.3280940219846453e+00 , 7.7230080000000001e-01 , -6.2541500000000000e-02 , 1.8102599999999999e-01 , 9.8148800000000003e-01 -3.3956115471810433e+00 , 4.4139637710526589e+00 , 7.5620160000000003e-01 , -3.5938999999999999e-02 , 1.6667100000000001e-01 , 9.8535700000000004e-01 -3.4219477842579726e+00 , 4.5013931401721248e+00 , 7.4253599999999986e-01 , -5.8203299999999999e-02 , 1.4920200000000000e-01 , 9.8709199999999997e-01 -3.4459606731017112e+00 , 4.5834277961585936e+00 , 7.3846959999999995e-01 , -6.7852899999999994e-02 , 1.9247000000000000e-01 , 9.7895399999999999e-01 -3.4748414425709111e+00 , 4.6798197406236106e+00 , 7.2239119999999990e-01 , -4.4402299999999999e-02 , 2.1767100000000000e-01 , 9.7501199999999999e-01 -3.5106165048759870e+00 , 4.7917225543374222e+00 , 6.9516399999999989e-01 , 6.4185599999999995e-02 , -1.9258200000000000e-01 , -9.7918000000000005e-01 -3.5367948629137578e+00 , 4.8833857524341839e+00 , 6.9192959999999992e-01 , -8.5286600000000004e-02 , 1.6743100000000000e-01 , 9.8218799999999995e-01 -3.5729160402990363e+00 , 4.9986589111082704e+00 , 6.7098400000000002e-01 , -8.6692900000000003e-02 , 1.8476899999999999e-01 , 9.7895100000000002e-01 -3.6045501293533455e+00 , 5.1076424492858514e+00 , 6.6001199999999982e-01 , 6.3843399999999995e-02 , -2.0780699999999999e-01 , -9.7608399999999995e-01 -3.6459324098098378e+00 , 5.2405678983426061e+00 , 6.3294079999999986e-01 , -4.4616700000000002e-02 , 2.0775600000000000e-01 , 9.7716300000000000e-01 -3.6848589806754450e+00 , 5.3672334928958430e+00 , 6.1639439999999990e-01 , -5.5183299999999998e-02 , 1.9877400000000001e-01 , 9.7849100000000000e-01 -3.7293879689297764e+00 , 5.5120662496766410e+00 , 5.9109119999999993e-01 , -6.5308400000000003e-02 , 1.7988699999999999e-01 , 9.8151699999999997e-01 -3.7693786291655069e+00 , 5.6507051144019060e+00 , 5.7626079999999980e-01 , -3.3768699999999999e-02 , 1.8060200000000001e-01 , 9.8297599999999996e-01 -3.8238265875010589e+00 , 5.8220399433229684e+00 , 5.4236719999999994e-01 , -1.4466600000000000e-02 , 2.0086000000000001e-01 , 9.7951299999999997e-01 -3.8766384557033202e+00 , 5.9966298154627555e+00 , 5.1370479999999996e-01 , -2.8762900000000001e-02 , 2.0438999999999999e-01 , 9.7846699999999998e-01 -3.9396724616777172e+00 , 6.1972208041048669e+00 , 4.7393519999999989e-01 , -4.3113800000000001e-02 , 1.8396899999999999e-01 , 9.8198600000000003e-01 -3.9951331039287861e+00 , 6.3846039195315747e+00 , 4.5138799999999990e-01 , -4.8221699999999999e-02 , 1.8554399999999999e-01 , 9.8145199999999999e-01 -4.0596457794242591e+00 , 6.5993108535563882e+00 , 4.1881520000000005e-01 , -4.7431800000000003e-02 , 1.9577000000000000e-01 , 9.7950199999999998e-01 -4.1340199868302001e+00 , 6.8406461662396714e+00 , 3.7817199999999995e-01 , -4.5961500000000002e-02 , 1.9349400000000000e-01 , 9.8002400000000001e-01 -4.2114499854173708e+00 , 7.0951225167669287e+00 , 3.4019119999999980e-01 , -6.1414900000000001e-02 , 1.7620100000000000e-01 , 9.8243599999999998e-01 -4.2878759899751095e+00 , 7.3513584795664944e+00 , 3.1070719999999996e-01 , -6.2710900000000000e-02 , 1.8160299999999999e-01 , 9.8136999999999996e-01 -4.3767773193980677e+00 , 7.6463510588054149e+00 , 2.7072959999999990e-01 , -2.7067099999999999e-01 , 6.8750199999999997e-02 , 9.6021400000000001e-01 -4.4739684233468715e+00 , 7.9700197755567448e+00 , 2.2730959999999989e-01 , -1.2093800000000000e-01 , 3.7600599999999998e-02 , 9.9194800000000005e-01 -4.5737653263010127e+00 , 8.3065366932663327e+00 , 1.9020239999999999e-01 , 2.3554400000000000e-02 , 1.1899899999999999e-01 , 9.9261500000000003e-01 -4.6975766815862947e+00 , 8.7182229278771359e+00 , 1.3077679999999980e-01 , 7.1305099999999999e-01 , 1.6506699999999999e-01 , 6.8140400000000001e-01 -4.4774189879764652e+00 , 8.1573653350495086e+00 , 5.2020480000000013e-01 , 9.8711599999999999e-01 , 9.2516100000000004e-02 , 1.3054800000000000e-01 -4.4570514693269141e+00 , 8.1589031884301004e+00 , 6.4469279999999984e-01 , 9.9041400000000002e-01 , 9.2590400000000003e-02 , 1.0250900000000000e-01 -4.4394853776025860e+00 , 8.1678745751820188e+00 , 7.6456319999999978e-01 , 9.9435799999999996e-01 , 8.6966100000000005e-02 , 6.0739399999999999e-02 -4.4219257827103089e+00 , 8.1735683179948904e+00 , 8.8392399999999993e-01 , 9.9930500000000000e-01 , 3.2067499999999999e-02 , -1.8982300000000001e-02 -4.4151178704178857e+00 , 8.2141674747464606e+00 , 9.8912311999999991e-01 , 9.9437200000000003e-01 , 2.9182500000000000e-02 , -1.0184900000000000e-01 -4.4118874052708925e+00 , 8.2626121485314528e+00 , 1.0918387199999999e+00 , -9.7536800000000001e-01 , -4.3952100000000001e-02 , 2.1616299999999999e-01 -4.4264392434724309e+00 , 8.3662971493822802e+00 , 1.1774338400000000e+00 , -9.5200499999999999e-01 , -4.5224000000000000e-02 , 3.0272300000000002e-01 -4.4962249033725570e+00 , 8.8282497152464217e+00 , 1.5351668000000001e+00 , -9.0368800000000005e-01 , 2.0529400000000000e-02 , 4.2769900000000000e-01 -1.4329163478079263e+01 , 4.0859419878740297e+01 , -3.9776288000000006e+00 , -9.5250699999999999e-01 , -1.6592599999999999e-01 , -2.5534099999999998e-01 -1.4227118936877286e+01 , 4.0915243514118849e+01 , -3.2687128000000003e+00 , -9.3538900000000003e-01 , -2.5192100000000001e-01 , -2.4815899999999999e-01 -1.3222335986341117e+01 , 3.8717552454066990e+01 , -8.9914560000000021e-01 , 2.6934100000000000e-01 , 9.6275900000000003e-01 , 2.3475200000000002e-02 -1.3026206985691248e+01 , 3.8419828989247570e+01 , -2.1040560000000008e-01 , 2.6934200000000003e-01 , 9.6275900000000003e-01 , 2.3475400000000000e-02 -1.2960186125779586e+01 , 3.8568059408718490e+01 , 4.3174239999999986e-01 , 2.5712400000000002e-01 , 9.4805399999999995e-01 , 1.8729899999999999e-01 -1.2889162725744837e+01 , 3.8694901637047643e+01 , 1.0779068800000000e+00 , 5.0938600000000004e-03 , 9.9787300000000001e-01 , 6.4983700000000005e-02 -1.2622986837806573e+01 , 3.8141248448786001e+01 , 1.7517135200000000e+00 , 2.1655400000000000e-01 , 9.7484400000000004e-01 , 5.2756499999999998e-02 -1.2552782996548340e+01 , 3.8266665081305732e+01 , 2.3905896800000002e+00 , 2.0670300000000000e-01 , 9.5089500000000005e-01 , -2.3037400000000000e-01 -1.2496867817987397e+01 , 3.8450370324362368e+01 , 3.0325619200000000e+00 , -6.7368499999999998e-02 , -8.4864099999999998e-01 , 5.2466199999999996e-01 -1.2525621534271936e+01 , 3.9337167712644387e+01 , 4.3516480000000008e+00 , -2.3883299999999999e-01 , -9.7059799999999996e-01 , 2.9967100000000000e-02 -8.2065013344992579e+00 , 2.3968843702566662e+01 , 4.5928447999999999e+00 , 6.5237500000000004e-01 , -7.3851100000000003e-01 , -1.7032000000000000e-01 -1.1920354330054781e+01 , 3.8284373898690703e+01 , 6.2383952000000003e+00 , -6.8901900000000005e-01 , -7.2472999999999999e-01 , 4.3971399999999999e-03 -1.1972429260320050e+01 , 3.8893844423502095e+01 , 6.9450960000000004e+00 , -8.6420100000000000e-01 , -4.9797599999999997e-01 , 7.1944499999999995e-02 -1.2596059704253117e+01 , 4.1729594877396060e+01 , 7.9510983999999993e+00 , -8.6097699999999999e-01 , -9.2223200000000005e-02 , -5.0021400000000005e-01 -1.1663401078627397e+01 , 3.8958857943386271e+01 , 8.9252871999999996e+00 , -9.8752300000000004e-01 , -5.3302700000000001e-02 , -1.4818100000000001e-01 -1.1595913133760410e+01 , 3.9130030207546191e+01 , 9.6180936000000017e+00 , -9.4413999999999998e-01 , -3.2944699999999999e-01 , 8.0625699999999998e-03 -4.8873630332058600e+00 , 1.2305655054391126e+01 , 5.0227496000000000e+00 , -5.9099000000000002e-01 , -7.6209099999999996e-01 , -2.6447500000000002e-01 -4.8843782639196380e+00 , 1.2417171374153879e+01 , 5.2278064000000004e+00 , -5.8648699999999998e-01 , -7.7330600000000005e-01 , -2.4089800000000000e-01 -4.8223571071533584e+00 , 1.2287384169298806e+01 , 5.3819968000000005e+00 , -5.2605500000000005e-01 , -8.5023700000000002e-01 , 1.9046899999999999e-02 -4.7727876579649049e+00 , 1.2205421646431134e+01 , 5.5443408000000005e+00 , 4.9938100000000002e-01 , 8.6467600000000000e-01 , 5.4359800000000000e-02 -4.7589712114344449e+00 , 1.2277506438843341e+01 , 5.7463296000000001e+00 , -7.0974000000000004e-01 , -6.8286199999999997e-01 , -1.7311599999999999e-01 -4.7622307504292216e+00 , 1.2423078151680491e+01 , 5.9741727999999998e+00 , 6.2401799999999996e-01 , 7.0819699999999997e-01 , 3.3023999999999998e-01 -4.6814345610109545e+00 , 1.2204943047682333e+01 , 6.0969344000000003e+00 , 6.7545400000000000e-01 , 1.8034800000000001e-01 , 7.1500799999999998e-01 -4.2473939443217184e+00 , 1.0410169306157540e+01 , 5.6972415999999999e+00 , -3.5548999999999997e-01 , -7.4365899999999996e-01 , 5.6621400000000000e-01 -4.2175173399069781e+00 , 1.0389150769793533e+01 , 5.8448279999999997e+00 , 2.5887000000000000e-02 , -8.6020600000000003e-01 , 5.0929000000000002e-01 -4.2174634585350477e+00 , 1.0510079386382980e+01 , 6.0444456000000004e+00 , -1.4903400000000000e-01 , -8.7117999999999995e-01 , 4.6779700000000002e-01 -4.2323462132463572e+00 , 1.0702066289286389e+01 , 6.2785080000000004e+00 , -5.4908500000000005e-01 , -6.1414299999999999e-01 , 5.6686400000000003e-01 -4.1527941568122220e+00 , 1.0454184605217275e+01 , 6.3435183999999998e+00 , -6.8322400000000005e-01 , -7.2593600000000003e-01 , 7.8884200000000002e-02 -4.2339937092192574e+00 , 1.0976357968035964e+01 , 6.7285367999999997e+00 , 7.3508599999999993e-02 , 9.1298900000000005e-01 , 4.0130800000000000e-01 -4.1838868152778925e+00 , 1.0872861832792809e+01 , 6.8576424000000005e+00 , -2.7481100000000003e-01 , -9.2974599999999996e-01 , 2.4505199999999999e-01 -4.1305616548362787e+00 , 1.0748126966097583e+01 , 6.9755680000000000e+00 , 8.3092800000000000e-01 , -1.6870199999999999e-01 , 5.3018699999999996e-01 -4.1581726287312595e+00 , 1.1036828836055799e+01 , 7.2918528000000009e+00 , -5.9134100000000001e-01 , -7.9432800000000003e-01 , 1.3914000000000001e-01 -3.7353410365055364e+00 , 9.0159991146413851e+00 , 6.4471439999999998e+00 , 9.2003500000000005e-01 , 3.5191099999999997e-01 , -1.7232000000000000e-01 -3.7908043286563400e+00 , 9.4333875496560040e+00 , 6.8125064000000002e+00 , 2.3680399999999999e-01 , -4.7137400000000002e-01 , -8.4954700000000005e-01 -3.6252369404228606e+00 , 8.6830063216360447e+00 , 6.5522255999999999e+00 , 6.0784700000000003e-01 , -5.8506400000000003e-01 , -5.3686299999999998e-01 -3.5462274284857553e+00 , 8.3779536102972649e+00 , 6.5180512000000004e+00 , -9.8245199999999999e-01 , 1.5713700000000000e-01 , 1.0047600000000000e-01 -3.5763049731046452e+00 , 8.6757932594202458e+00 , 6.8327344000000005e+00 , 1.5874800000000000e-01 , -3.4494100000000000e-01 , 9.2510300000000001e-01 -3.4329052650129501e+00 , 7.9954530262990673e+00 , 6.5558968000000002e+00 , -3.5846099999999997e-01 , -9.0083899999999995e-01 , 2.4493899999999999e-01 -3.3865465254695488e+00 , 7.8538360556772266e+00 , 6.5967896000000001e+00 , 1.8299499999999999e-01 , 9.5519900000000002e-01 , -2.3261200000000001e-01 -3.3971421508857267e+00 , 8.0449857490209524e+00 , 6.8573408000000002e+00 , 2.3119700000000001e-01 , 9.7206099999999995e-01 , -4.0568300000000002e-02 -3.3534779944331898e+00 , 7.9244164617767767e+00 , 6.9136568000000000e+00 , 8.4907300000000005e-02 , 7.3975400000000002e-01 , 6.6749800000000004e-01 -3.3273708962745259e+00 , 7.9040665384439031e+00 , 7.0389976000000001e+00 , -3.6203999999999997e-01 , 6.5464400000000000e-01 , 6.6360300000000005e-01 -3.2868300624694458e+00 , 7.7910703167322506e+00 , 7.0966864000000003e+00 , 5.6616599999999995e-01 , 7.7176199999999995e-01 , 2.8954900000000000e-01 -3.2134209076071096e+00 , 7.4642531852101746e+00 , 6.9872680000000003e+00 , 2.3560000000000000e-01 , -2.3268800000000001e-01 , 9.4358299999999995e-01 -3.1334366932466025e+00 , 7.0698342558425127e+00 , 6.8096984000000003e+00 , 2.7952100000000002e-01 , -2.5108100000000000e-01 , 9.2672900000000002e-01 -3.0993786381039246e+00 , 6.9846915799161700e+00 , 6.8699872000000006e+00 , -6.4469200000000004e-01 , 1.2124000000000000e-01 , -7.5476699999999997e-01 -3.0526931747376622e+00 , 6.8048493388379478e+00 , 6.8475336000000002e+00 , 6.4076000000000000e-01 , -4.1037799999999999e-02 , 7.6664399999999999e-01 -3.0137131047603494e+00 , 6.6666169498556114e+00 , 6.8540648000000006e+00 , -7.7310599999999996e-01 , -6.8494100000000002e-02 , -6.3056800000000002e-01 -3.0096968513101667e+00 , 6.8108092902637756e+00 , 7.1156456000000006e+00 , -9.0199399999999996e-01 , 8.2539199999999993e-02 , -4.2378500000000002e-01 -2.9760290907485558e+00 , 6.7144232348712753e+00 , 7.1623728000000000e+00 , -8.6479499999999998e-01 , 1.3697400000000001e-01 , -4.8308200000000001e-01 -2.9383182014738480e+00 , 6.5885134243278936e+00 , 7.1776296000000004e+00 , -8.9661199999999996e-01 , -1.2784899999999999e-01 , -4.2395899999999997e-01 -2.9287708573584612e+00 , 6.7176940722514198e+00 , 7.4478527999999997e+00 , -6.6760299999999995e-01 , -3.5753699999999999e-01 , -6.5304899999999999e-01 -2.8877835674760810e+00 , 6.5521439748188373e+00 , 7.4237663999999999e+00 , -8.7156400000000001e-01 , -1.1699800000000000e-01 , -4.7611700000000001e-01 -2.8448455565659008e+00 , 6.3751730732345449e+00 , 7.3794624000000004e+00 , -9.3062800000000001e-01 , -1.6341200000000000e-01 , -3.2745700000000000e-01 -2.8721176282171319e+00 , 6.9271312120539399e+00 , 8.1432280000000006e+00 , 3.5670800000000003e-01 , -9.3417200000000000e-01 , 9.0580699999999997e-03 -2.8724012531043757e+00 , 7.2567826407131868e+00 , 8.6990456000000016e+00 , -7.9407899999999998e-01 , 1.1808900000000000e-01 , -5.9623300000000001e-01 -2.8287812099407876e+00 , 7.1114443871648296e+00 , 8.7167568000000006e+00 , 7.6499399999999995e-02 , -9.8957499999999998e-01 , 1.2202200000000001e-01 -2.8043016931238185e+00 , 7.2203225727783300e+00 , 9.0464055999999999e+00 , -3.6547499999999999e-01 , -4.6101700000000001e-01 , -8.0863499999999999e-01 -2.7650542260361677e+00 , 7.1471695139528517e+00 , 9.1598280000000010e+00 , 1.2581300000000001e-01 , 3.8794400000000001e-01 , 9.1305599999999998e-01 -2.7223540553082599e+00 , 7.0143589301759270e+00 , 9.1977256000000001e+00 , -3.4916300000000000e-01 , -7.4265099999999995e-01 , -5.7145000000000001e-01 -2.6862244742172825e+00 , 7.0166491422426365e+00 , 9.4174880000000005e+00 , 3.1972299999999998e-01 , 6.7302700000000004e-01 , 6.6694299999999995e-01 -2.6284203437606339e+00 , 6.5347987061679635e+00 , 8.9582656000000007e+00 , 1.5060799999999999e-02 , -7.6529400000000003e-01 , 6.4350399999999996e-01 -2.5920310399852013e+00 , 6.4903667873435502e+00 , 9.1041568000000002e+00 , 1.1769900000000000e-01 , -6.0177800000000004e-01 , 7.8994299999999995e-01 -2.5441201849415376e+00 , 6.0652454466821055e+00 , 8.6756560000000000e+00 , 5.5954400000000004e-01 , 1.6651299999999999e-01 , 8.1190200000000001e-01 -2.5082056348800839e+00 , 5.9278042537345641e+00 , 8.6657031999999994e+00 , -5.4320900000000005e-01 , 2.9057800000000000e-01 , -7.8771100000000005e-01 -2.4721724342363078e+00 , 5.9157990572261596e+00 , 8.8566783999999998e+00 , -5.0853700000000002e-01 , 1.7807300000000001e-01 , -8.4242499999999998e-01 -2.4364774996319443e+00 , 5.7504197937809796e+00 , 8.7976896000000018e+00 , 4.8712299999999997e-01 , -3.7223400000000001e-01 , 7.9003400000000001e-01 -2.4022794600644604e+00 , 5.5733635554001175e+00 , 8.7073967999999997e+00 , -4.9701000000000001e-01 , 4.7677999999999998e-01 , -7.2502599999999995e-01 -2.3679972266861000e+00 , 5.4599593940131923e+00 , 8.7221855999999995e+00 , -9.0303500000000003e-01 , 2.6999000000000001e-01 , -3.3411600000000002e-01 -2.3476805701760597e+00 , 5.0104647305759471e+00 , 8.0890231999999997e+00 , 2.5967800000000002e-01 , -7.4047700000000005e-01 , 6.1988799999999999e-01 -2.3002555725104465e+00 , 5.2469218373587019e+00 , 8.7729479999999995e+00 , 7.4727399999999999e-01 , -1.8795700000000001e-01 , -6.3737999999999995e-01 -2.2711255274044375e+00 , 5.0755195567735836e+00 , 8.6591096000000007e+00 , -2.6619100000000001e-01 , 4.8844100000000001e-01 , 8.3100399999999996e-01 -2.2391044529768527e+00 , 4.9733762864170226e+00 , 8.6828424000000002e+00 , -1.4936400000000000e-01 , 6.2433299999999997e-02 , 9.8680900000000005e-01 -2.2085095187033477e+00 , 4.8495244197558796e+00 , 8.6571335999999999e+00 , 3.4060800000000001e-03 , 6.0340499999999998e-02 , 9.9817199999999995e-01 -2.1908336487863376e+00 , 4.6355572689633933e+00 , 8.4082615999999994e+00 , 2.1952400000000000e-01 , -6.1316400000000004e-01 , 7.5884099999999999e-01 -2.2510004857249553e+00 , 3.8801372684159627e+00 , 6.7744944000000000e+00 , -1.8602099999999999e-01 , 1.5853999999999999e-01 , 9.6967099999999995e-01 -2.2291805972799286e+00 , 3.8218288392465172e+00 , 6.8071712000000000e+00 , 4.9950600000000001e-01 , -6.2124900000000005e-01 , -6.0377400000000003e-01 -2.2087520943113548e+00 , 3.7520236662504094e+00 , 6.8094488000000002e+00 , -4.7657800000000000e-01 , 8.3450299999999999e-01 , 2.7654499999999999e-01 -2.1811807234204821e+00 , 3.7229938161899567e+00 , 6.9282896000000003e+00 , 7.3511499999999996e-01 , -5.0114199999999998e-01 , -4.5657700000000001e-01 -2.1609702170183542e+00 , 3.6517153853553772e+00 , 6.9285496000000002e+00 , 5.3440799999999999e-01 , -4.5679500000000001e-01 , -7.1115799999999996e-01 -2.1395349245794928e+00 , 3.5894419270168036e+00 , 6.9574824000000008e+00 , -5.8986700000000003e-02 , 6.8579599999999996e-01 , 7.2539900000000002e-01 -2.1099255621902908e+00 , 3.5527406732199847e+00 , 7.0746696000000000e+00 , 5.6116100000000002e-01 , 7.4608600000000003e-01 , 3.5840499999999997e-01 -1.8594241944002203e+00 , 4.1670918555897938e+00 , 9.6225136000000013e+00 , 4.7377700000000000e-01 , 8.8048499999999996e-01 , 1.6750500000000001e-02 -2.0849581602795175e+00 , 3.3700638417911852e+00 , 6.9162879999999998e+00 , 3.4193600000000002e-01 , -2.4852900000000000e-01 , 9.0626300000000004e-01 -2.0666511985623046e+00 , 3.3005189421136754e+00 , 6.9097880000000007e+00 , -5.7865100000000003e-01 , 2.2173800000000000e-02 , -8.1527400000000005e-01 -2.0327385560092113e+00 , 3.2640914148326683e+00 , 7.0537863999999999e+00 , -2.4922700000000000e-01 , 9.6452800000000005e-01 , 8.7011000000000005e-02 -1.8804383140819489e+00 , 3.4344874028524095e+00 , 8.2622768000000004e+00 , -8.8413799999999998e-01 , -4.5301800000000003e-02 , -4.6502399999999999e-01 -1.8650896172844029e+00 , 3.3282108317741770e+00 , 8.1742303999999990e+00 , 1.9366400000000000e-01 , 9.1952400000000004e-02 , 9.7674899999999998e-01 -1.8402160114091530e+00 , 3.2404200381903214e+00 , 8.1758528000000013e+00 , -6.5558899999999998e-01 , -7.5474600000000003e-01 , -2.3716999999999998e-02 -3.2480132176541630e+00 , 3.7410918700373808e+00 , 8.4229279999999984e-01 , -7.3170499999999999e-02 , -1.1612800000000000e-03 , 9.9731899999999996e-01 -3.2645717184112621e+00 , 3.7947789025860059e+00 , 8.4353039999999990e-01 , -8.3054000000000003e-02 , 3.0483099999999998e-03 , 9.9653999999999998e-01 -3.2842410122676204e+00 , 3.8553679347907890e+00 , 8.3749839999999987e-01 , -7.7984999999999999e-02 , 1.0607800000000001e-01 , 9.9129500000000004e-01 -3.3037156781786559e+00 , 3.9162889172974227e+00 , 8.3308879999999985e-01 , -4.8430399999999998e-02 , 1.7378500000000000e-01 , 9.8359200000000002e-01 -3.3272717853544815e+00 , 3.9841919328204538e+00 , 8.2205439999999985e-01 , -3.7269900000000002e-02 , 1.9553499999999999e-01 , 9.7998799999999997e-01 -3.3527435275362780e+00 , 4.0581922666887822e+00 , 8.0474879999999982e-01 , -9.2682600000000004e-02 , 1.5839900000000001e-01 , 9.8301600000000000e-01 -3.3695674194493810e+00 , 4.1164854404786535e+00 , 8.1307920000000000e-01 , -1.0050000000000001e-01 , 1.5913300000000000e-01 , 9.8212900000000003e-01 -3.3956463035664139e+00 , 4.1923066919482146e+00 , 7.9974639999999986e-01 , 7.8075099999999995e-02 , -1.9427400000000000e-01 , -9.7783500000000001e-01 -3.4247019510098351e+00 , 4.2763716604882891e+00 , 7.8046479999999985e-01 , -9.1817099999999999e-02 , 2.1318799999999999e-01 , 9.7268699999999997e-01 -3.4502760067999199e+00 , 4.3541598253673088e+00 , 7.7147919999999992e-01 , -7.4369599999999994e-02 , 1.7063000000000000e-01 , 9.8252499999999998e-01 -3.4767308879795880e+00 , 4.4344080200496174e+00 , 7.6432400000000000e-01 , -8.0180699999999994e-02 , 1.8153900000000001e-01 , 9.8011000000000004e-01 -3.5018368920030740e+00 , 4.5141387187439896e+00 , 7.5958159999999997e-01 , 6.6611000000000004e-02 , -1.6167599999999999e-01 , -9.8459300000000005e-01 -3.5349841457495121e+00 , 4.6091140447310543e+00 , 7.4269199999999991e-01 , -7.4444600000000000e-02 , 1.9059400000000001e-01 , 9.7884199999999999e-01 -3.5698793881704036e+00 , 4.7126888597025864e+00 , 7.2136160000000005e-01 , -4.3582999999999997e-02 , 2.0783199999999999e-01 , 9.7719299999999998e-01 -3.6023782872194090e+00 , 4.8099203505830754e+00 , 7.1023360000000002e-01 , -9.2103900000000002e-02 , 1.8842300000000001e-01 , 9.7775999999999996e-01 -3.6345567931943821e+00 , 4.9087847384101320e+00 , 7.0184080000000004e-01 , -9.5900100000000002e-02 , 1.8006200000000000e-01 , 9.7896899999999998e-01 -3.6735333111130886e+00 , 5.0233208742907030e+00 , 6.8309999999999982e-01 , -8.1728899999999993e-02 , 2.0090400000000000e-01 , 9.7619599999999995e-01 -3.7151969154741709e+00 , 5.1476867930483881e+00 , 6.6104159999999990e-01 , 6.8256700000000003e-02 , -2.2637399999999999e-01 , -9.7164600000000001e-01 -3.7604174434830728e+00 , 5.2799471261404998e+00 , 6.3670559999999998e-01 , 6.0842599999999997e-02 , -1.9906900000000000e-01 , -9.7809500000000005e-01 -3.8021964545134805e+00 , 5.4069893199850689e+00 , 6.2265519999999985e-01 , 8.0224100000000007e-02 , -2.0354700000000001e-01 , -9.7577300000000000e-01 -3.8515855781733830e+00 , 5.5511412657204868e+00 , 6.0030559999999999e-01 , -4.4544599999999997e-02 , 1.9211600000000001e-01 , 9.8036100000000004e-01 -3.9063812593232328e+00 , 5.7126990872852872e+00 , 5.7062399999999980e-01 , -3.4876900000000002e-02 , 1.9874700000000001e-01 , 9.7943000000000002e-01 -3.9646051986235644e+00 , 5.8845658919140789e+00 , 5.4017279999999990e-01 , -4.8543999999999997e-02 , 1.9805400000000001e-01 , 9.7898799999999997e-01 -4.0231850479506432e+00 , 6.0576084415717188e+00 , 5.1560799999999984e-01 , -6.6316200000000006e-02 , 2.0349900000000001e-01 , 9.7682700000000000e-01 -4.0841233260019036e+00 , 6.2421544418226791e+00 , 4.9065840000000005e-01 , -7.1003399999999994e-02 , 1.9791000000000000e-01 , 9.7764499999999999e-01 -4.1561941895642427e+00 , 6.4539684909161679e+00 , 4.5583920000000000e-01 , -6.6506999999999997e-02 , 1.8575300000000000e-01 , 9.8034299999999996e-01 -4.2274291031745328e+00 , 6.6672366477352636e+00 , 4.2809199999999992e-01 , -6.6512600000000005e-02 , 2.0113600000000001e-01 , 9.7730300000000003e-01 -4.3114536743537464e+00 , 6.9176060725012869e+00 , 3.8692879999999996e-01 , -7.6212299999999997e-02 , 1.9200200000000001e-01 , 9.7843100000000005e-01 -4.3955526052070635e+00 , 7.1707495669562080e+00 , 3.5429359999999988e-01 , -7.9927799999999993e-02 , 1.8890000000000001e-01 , 9.7873800000000000e-01 -4.4931114363597544e+00 , 7.4605147258944777e+00 , 3.1128959999999983e-01 , -3.0197499999999999e-01 , 1.7808800000000000e-01 , 9.3653399999999998e-01 -4.5906066032043888e+00 , 7.7543630276977336e+00 , 2.7800960000000008e-01 , 9.3532100000000007e-02 , -1.4784900000000001e-01 , -9.8457700000000004e-01 -4.7002501056112234e+00 , 8.0864347548716715e+00 , 2.3678399999999988e-01 , 1.8806899999999999e-01 , 3.2413399999999998e-01 , 9.2712799999999995e-01 -4.8200479491600561e+00 , 8.4486111267977400e+00 , 1.9426879999999991e-01 , 5.0882799999999995e-01 , 1.1540700000000000e-01 , 8.5309699999999999e-01 -4.5577865086356635e+00 , 7.8313607087548922e+00 , 6.1101759999999983e-01 , 9.9463599999999996e-01 , 6.9869799999999996e-02 , 7.6266500000000001e-02 -4.5407289410986422e+00 , 7.8416448921974382e+00 , 7.2692559999999995e-01 , 9.9423200000000000e-01 , 7.5315800000000002e-02 , 7.6359800000000005e-02 -4.5236697438623024e+00 , 7.8486391728474869e+00 , 8.4234480000000000e-01 , 9.9742799999999998e-01 , 5.7554899999999999e-02 , 4.2719899999999998e-02 -4.5120847349790711e+00 , 7.8729150889697568e+00 , 9.4981840000000006e-01 , 9.9783599999999995e-01 , 4.6887600000000001e-02 , -4.6102999999999998e-02 -4.5041680898578793e+00 , 7.9038027920055143e+00 , 1.0539983199999998e+00 , 9.9257799999999996e-01 , 5.0243200000000002e-02 , -1.1074600000000000e-01 -4.5051944023768424e+00 , 7.9600396825060873e+00 , 1.1488692000000000e+00 , 9.8536000000000001e-01 , 3.3169299999999999e-02 , -1.6722899999999999e-01 -4.5171320885936206e+00 , 8.0439030179061870e+00 , 1.2356852800000000e+00 , -9.5790100000000000e-01 , -2.5224799999999999e-02 , 2.8598699999999999e-01 -4.5402879733436308e+00 , 8.1636683142453368e+00 , 1.3133088000000002e+00 , -9.4029499999999999e-01 , 8.7581300000000003e-04 , 3.4036100000000002e-01 -4.5530950215882742e+00 , 8.2543931381650282e+00 , 1.4026603999999998e+00 , -9.2374599999999996e-01 , 5.5456300000000000e-02 , 3.7896999999999997e-01 -4.5655246750498524e+00 , 8.3435770700645868e+00 , 1.4948512000000000e+00 , -9.1482200000000002e-01 , 1.7773700000000000e-02 , 4.0346700000000002e-01 -4.6308757139942536e+00 , 8.6443966815477609e+00 , 1.6579637599999999e+00 , -9.0707899999999997e-01 , 1.8500200000000001e-02 , 4.2055300000000001e-01 -1.4839856445512856e+01 , 3.8543727229657975e+01 , -3.7727800000000000e+00 , 9.9347799999999997e-01 , 7.7193300000000006e-02 , 8.3925000000000000e-02 -1.4755234281458147e+01 , 3.8637145547726213e+01 , -3.1057136000000005e+00 , -9.6085299999999996e-01 , -2.1219600000000000e-01 , -1.7813999999999999e-01 -1.4434618030435619e+01 , 3.8711164380331567e+01 , -1.0885608000000002e+00 , -3.3452900000000002e-01 , -9.4237499999999996e-01 , 4.4863400000000001e-03 -1.4328935996525050e+01 , 3.8738342351347171e+01 , -4.2279440000000035e-01 , 2.7930899999999997e-01 , 9.3966400000000005e-01 , -1.9753000000000001e-01 -1.4307230420922741e+01 , 3.9021833059123942e+01 , 2.2057039999999994e-01 , 1.8547500000000000e-01 , 9.8123000000000005e-01 , -5.2788599999999998e-02 -1.4036277281055870e+01 , 3.8532578461716533e+01 , 9.1772399999999998e-01 , 2.6401800000000000e-02 , -9.7274400000000005e-01 , 2.3037199999999999e-01 -1.4142140454469699e+01 , 3.9579217321779900e+01 , 2.2037859200000001e+00 , -2.4758200000000000e-01 , 9.3810199999999999e-01 , -2.4221400000000001e-01 -1.3867235754354441e+01 , 3.9064436852563617e+01 , 2.8782810400000001e+00 , 9.0886700000000001e-02 , -9.1113599999999995e-01 , 4.0195900000000001e-01 -1.3908385997576143e+01 , 3.9561332984207631e+01 , 3.5455855999999999e+00 , -3.2543400000000000e-01 , -9.1230599999999995e-01 , 2.4857799999999999e-01 -1.1887402141372492e+01 , 3.3316276119049384e+01 , 4.0240271999999999e+00 , 8.5956299999999997e-01 , -1.5922000000000000e-01 , -4.8559300000000000e-01 -1.1821967044041896e+01 , 3.3411886004256587e+01 , 4.5849408000000000e+00 , 9.0833900000000001e-01 , -2.1166599999999999e-01 , -3.6071799999999998e-01 -8.9707915626322929e+00 , 2.4201555472677995e+01 , 4.5299144000000000e+00 , 6.5448499999999998e-01 , -7.2599700000000000e-01 , -2.1113499999999999e-01 -1.3324645809976346e+01 , 3.9131554761021597e+01 , 6.1844815999999998e+00 , -4.6409699999999998e-01 , -8.5766900000000001e-01 , -2.2140099999999999e-01 -1.2118325278128049e+01 , 3.5400180816159832e+01 , 6.4638360000000006e+00 , 9.9888600000000005e-01 , 2.3373100000000001e-02 , -4.0992199999999999e-02 -1.2050531939647342e+01 , 3.5516323479714785e+01 , 7.0732552000000002e+00 , 9.9763500000000005e-01 , -2.7365000000000000e-02 , 6.3051099999999999e-02 -1.1984044315389024e+01 , 3.5640158891437295e+01 , 7.6898920000000004e+00 , -9.9138700000000002e-01 , 1.2531800000000001e-01 , -3.8051099999999997e-02 -1.1862507756316145e+01 , 3.5575941226759085e+01 , 8.2830975999999996e+00 , 9.9357399999999996e-01 , -1.0252000000000000e-01 , -4.7960200000000001e-02 -1.0791763400745854e+01 , 3.2125347010983717e+01 , 8.2831080000000004e+00 , 7.7873599999999998e-01 , 4.8938300000000001e-01 , -3.9252399999999998e-01 -5.2101989810233196e+00 , 1.2344960957255743e+01 , 5.0021160000000000e+00 , 2.9750500000000002e-01 , 9.4877999999999996e-01 , -1.0633300000000000e-01 -5.1040364068856743e+00 , 1.2074239708762779e+01 , 5.1273008000000004e+00 , 2.9750500000000002e-01 , 9.4878099999999999e-01 , -1.0633300000000000e-01 -5.1700699801246213e+00 , 1.2428594865501575e+01 , 5.3876128000000003e+00 , -2.8965399999999999e-02 , -9.9768900000000005e-01 , 6.1460800000000003e-02 -1.2392339787555494e+01 , 3.9491076649019817e+01 , 1.2307440000000000e+01 , -9.6510099999999999e-01 , -2.5407400000000002e-01 , 6.3455700000000004e-02 -5.0858359187038182e+00 , 1.2352636429313907e+01 , 5.7410151999999997e+00 , -2.4828700000000001e-01 , -9.6156500000000000e-01 , -1.1724700000000000e-01 -4.4870932659523994e+00 , 1.0383650397373964e+01 , 5.6695048000000003e+00 , -3.4894500000000001e-01 , -8.0552699999999999e-01 , 4.7892000000000001e-01 -4.4130293082312395e+00 , 1.0192347641871912e+01 , 5.7582272000000003e+00 , -3.4894500000000001e-01 , -8.0552599999999996e-01 , 4.7892000000000001e-01 -4.5210347189744162e+00 , 1.0733622464081517e+01 , 6.1067520000000002e+00 , 1.4963199999999999e-01 , 8.7529299999999999e-01 , -4.5986100000000002e-01 -4.4653979220746063e+00 , 1.0622489886285042e+01 , 6.2284424000000005e+00 , -1.3932000000000000e-01 , -8.7284499999999998e-01 , 4.6768700000000002e-01 -4.4100966774709081e+00 , 1.0508602662925780e+01 , 6.3470024000000000e+00 , -2.9608400000000001e-01 , -9.5516199999999996e-01 , -4.9216799999999997e-04 -4.4490961483441165e+00 , 1.0786613978626292e+01 , 6.6284576000000008e+00 , -4.0114600000000000e-01 , -8.7302900000000005e-01 , 2.7731200000000000e-01 -4.4106507436388700e+00 , 1.0751644596341647e+01 , 6.7840104000000006e+00 , -2.6978600000000003e-01 , 3.8648500000000002e-01 , 8.8195500000000004e-01 -4.2894709425501132e+00 , 1.0353098294672481e+01 , 6.7721960000000001e+00 , -9.2411200000000004e-01 , -3.2007900000000000e-01 , 2.0872499999999999e-01 -4.2518241753779087e+00 , 1.0314555547786954e+01 , 6.9206767999999999e+00 , -2.8109699999999999e-01 , -1.0339600000000000e-01 , 9.5409299999999997e-01 -4.0781254706562198e+00 , 9.6641738085881279e+00 , 6.7596848000000005e+00 , -2.0052500000000001e-01 , 3.5639799999999999e-01 , 9.1256199999999998e-01 -4.0185465604862323e+00 , 9.5160568280736832e+00 , 6.8392759999999999e+00 , -1.4900200000000000e-01 , 3.3006099999999999e-01 , 9.3212600000000001e-01 -3.8276941408660821e+00 , 8.7593828028048808e+00 , 6.5792343999999998e+00 , 7.6953700000000003e-01 , -4.4861899999999999e-01 , -4.5448100000000002e-01 -3.7008954267596721e+00 , 8.2793045853499336e+00 , 6.4461248000000007e+00 , -9.7189300000000001e-01 , 1.3262800000000000e-01 , 1.9450899999999999e-01 -3.7907847106382113e+00 , 8.8159838842526224e+00 , 6.8997207999999999e+00 , 2.6054800000000000e-01 , -3.2367899999999999e-01 , -9.0958600000000001e-01 -3.6816600638563823e+00 , 8.4068609434085513e+00 , 6.7958248000000001e+00 , -8.2820400000000005e-01 , -8.2410899999999995e-02 , 5.5433500000000002e-01 -3.5537306241185371e+00 , 7.8910579687828895e+00 , 6.6063472000000001e+00 , 4.0333599999999997e-01 , 8.9925900000000003e-01 , -1.6927300000000001e-01 -3.5851818510458888e+00 , 8.1681440365523912e+00 , 6.9237656000000003e+00 , 1.4321000000000000e-01 , 3.6353000000000002e-01 , 9.2050900000000002e-01 -3.5108374097910597e+00 , 7.9051990834043453e+00 , 6.8834759999999999e+00 , 6.5892799999999996e-01 , 2.2534599999999999e-01 , 7.1765800000000002e-01 -3.5095923424117830e+00 , 8.0284966695368460e+00 , 7.1104664000000000e+00 , -4.6215800000000001e-01 , -6.7303800000000003e-01 , -5.7743299999999997e-01 -3.4720031131235141e+00 , 7.9561148246380444e+00 , 7.2016951999999996e+00 , -5.7384199999999996e-01 , -6.4235399999999998e-01 , -5.0802199999999997e-01 -3.4093483914226965e+00 , 7.7430260647994436e+00 , 7.1847640000000004e+00 , -2.0998100000000000e-01 , -8.8801699999999995e-01 , 4.0906500000000001e-01 -3.2745552432476623e+00 , 7.1130418591308064e+00 , 6.8276696000000001e+00 , 2.1354600000000001e-01 , -3.1614700000000001e-01 , 9.2436399999999996e-01 -3.2296289221907193e+00 , 6.9813717409397436e+00 , 6.8496759999999997e+00 , 2.2689300000000001e-01 , -4.2112900000000002e-02 , 9.7300900000000001e-01 -3.1776347013092363e+00 , 6.8029576810981283e+00 , 6.8279088000000003e+00 , 1.8504000000000001e-01 , 2.4288899999999999e-02 , 9.8243100000000005e-01 -3.1551840670891704e+00 , 6.7969210988799524e+00 , 6.9512632000000005e+00 , -7.0406199999999997e-01 , 6.1797100000000005e-01 , -3.4986800000000001e-01 -3.1673250038185721e+00 , 7.0251529729511537e+00 , 7.2908232000000002e+00 , -6.9734600000000002e-01 , -1.6593700000000000e-01 , 6.9726100000000002e-01 -3.1115011759676090e+00 , 6.8135444075632989e+00 , 7.2352663999999995e+00 , 1.6557100000000000e-01 , -6.1952499999999999e-01 , 7.6731600000000000e-01 -3.0471903439420265e+00 , 6.5323016877385580e+00 , 7.1010439999999999e+00 , 9.9826999999999999e-01 , 5.7991000000000001e-02 , -9.6619099999999992e-03 -3.0084599256351652e+00 , 6.4235138271002707e+00 , 7.1272935999999998e+00 , -8.2855999999999996e-01 , -1.8007100000000001e-01 , -5.3015299999999999e-01 -3.0020608970517131e+00 , 6.5514544304313018e+00 , 7.3972984000000004e+00 , -9.4981000000000004e-01 , 5.1191700000000000e-02 , 3.0861200000000000e-01 -2.9647128066927073e+00 , 6.4460029004487742e+00 , 7.4298504000000003e+00 , -9.0288199999999996e-01 , -3.9855400000000002e-01 , 1.6111900000000001e-01 -2.9386135642125417e+00 , 6.4445643052862938e+00 , 7.5752320000000006e+00 , -6.7579199999999995e-01 , -7.3607900000000004e-01 , -3.8626300000000002e-02 -3.0013993445200806e+00 , 7.2150393179333054e+00 , 8.6142648000000008e+00 , 3.5739500000000002e-01 , -8.3933599999999997e-01 , 4.0961399999999998e-01 -2.9759084090841901e+00 , 7.2846726820930474e+00 , 8.8859335999999995e+00 , -9.2171499999999995e-01 , -1.5766300000000000e-01 , -3.5437800000000003e-01 -2.8076508896089729e+00 , 5.9398509744713843e+00 , 7.4296112000000010e+00 , 3.3553099999999998e-03 , 6.7474599999999996e-01 , 7.3804300000000000e-01 -2.7722352231773342e+00 , 5.8426649170104348e+00 , 7.4561935999999998e+00 , 3.3553300000000001e-03 , 6.7474599999999996e-01 , 7.3804300000000000e-01 -2.8491282829988140e+00 , 7.0402271227564617e+00 , 9.1845591999999989e+00 , 1.5726599999999999e-01 , 3.7329600000000002e-01 , 9.1428500000000001e-01 -2.8010714133406727e+00 , 6.8904452309400597e+00 , 9.1950736000000006e+00 , 5.1645399999999997e-01 , 3.3218599999999998e-01 , 7.8925800000000002e-01 -2.7289740346522988e+00 , 6.3755606818846191e+00 , 8.6847664000000009e+00 , -5.7556600000000002e-01 , -2.7956900000000001e-01 , 7.6848200000000000e-01 -2.7011811690532470e+00 , 6.4887440231989348e+00 , 9.0508671999999990e+00 , -2.2021400000000000e-02 , -7.0893899999999999e-01 , 7.0492600000000005e-01 -2.6444502647437051e+00 , 6.1101172041802325e+00 , 8.6931799999999999e+00 , -2.5091499999999999e-02 , 2.2034100000000001e-01 , 9.7509999999999997e-01 -2.6044466991791344e+00 , 5.9850478625951702e+00 , 8.7015728000000010e+00 , -5.3451499999999996e-01 , 1.3359299999999999e-01 , -8.3453400000000000e-01 -2.5647545659496407e+00 , 5.8594367946025274e+00 , 8.7073344000000006e+00 , -5.5144899999999997e-01 , 3.5832500000000000e-01 , -7.5333099999999997e-01 -2.5241111094419173e+00 , 5.7083137876004670e+00 , 8.6653392000000000e+00 , 4.9456200000000000e-01 , -3.0599399999999999e-01 , 8.1349700000000003e-01 -2.4854618854966191e+00 , 5.4923872166494458e+00 , 8.5023815999999997e+00 , 4.5637100000000003e-01 , -3.5991400000000001e-01 , 8.1374899999999994e-01 -2.4489892249641354e+00 , 5.1580952343823245e+00 , 8.1055384000000004e+00 , 2.5580400000000000e-02 , -8.1511100000000003e-01 , 5.7873900000000000e-01 -2.4175347931242666e+00 , 4.9683838054570497e+00 , 7.9477288000000001e+00 , 1.5572400000000000e-01 , -9.1499100000000000e-01 , 3.7221199999999999e-01 -2.3828493147038099e+00 , 4.9957128255659669e+00 , 8.2024664000000005e+00 , -3.3554499999999998e-01 , -8.8308900000000001e-01 , 3.2796900000000001e-01 -2.3424898430937100e+00 , 5.0605494521999930e+00 , 8.5525927999999993e+00 , -9.5055100000000003e-01 , -2.9843199999999998e-01 , -8.5973800000000003e-02 -2.3051161103564191e+00 , 5.0091902735377598e+00 , 8.6797016000000013e+00 , -7.5251199999999997e-03 , 9.6301499999999998e-02 , 9.9532399999999999e-01 -2.2702236633763837e+00 , 4.8998433561810026e+00 , 8.6828839999999996e+00 , 3.4060800000000001e-03 , 6.0340499999999998e-02 , 9.9817199999999995e-01 -2.2354495620236579e+00 , 4.8022249396286494e+00 , 8.7127320000000008e+00 , -8.4301799999999996e-02 , 8.7570300000000004e-02 , 9.9258500000000005e-01 -2.2879757700435008e+00 , 3.9035816501661627e+00 , 6.7669648000000002e+00 , 3.1181399999999998e-01 , -4.9766499999999998e-02 , -9.4883899999999999e-01 -2.2651579811243905e+00 , 3.8423437748914235e+00 , 6.7901776000000007e+00 , -1.5041599999999999e-01 , 7.4481500000000000e-01 , 6.5009600000000001e-01 -2.1327367946820561e+00 , 4.4979065560665710e+00 , 8.7614560000000008e+00 , -8.2533699999999999e-01 , 7.9131199999999999e-02 , 5.5906800000000001e-01 -2.1111940461937118e+00 , 4.3249649546918922e+00 , 8.5677871999999997e+00 , -9.9129199999999995e-01 , -7.1929499999999993e-02 , -1.1030500000000000e-01 -2.1866645025851774e+00 , 3.7044847254064726e+00 , 7.0009648000000002e+00 , 7.9836099999999999e-01 , -1.7246000000000000e-01 , -5.7695399999999997e-01 -2.1680502078596975e+00 , 3.6166787626055732e+00 , 6.9511592000000002e+00 , 4.4379299999999999e-01 , -4.6055600000000002e-01 , -7.6872399999999996e-01 -2.1424832867961752e+00 , 3.5584703057639593e+00 , 6.9888176000000000e+00 , 1.8906999999999999e-01 , 7.4089899999999997e-01 , 6.4445500000000000e-01 -2.1107087589662084e+00 , 3.5237708017208602e+00 , 7.1154896000000001e+00 , 7.8876299999999999e-01 , 5.5645800000000001e-01 , 2.6116699999999998e-01 -1.9771802709976214e+00 , 3.7708519593975076e+00 , 8.3449880000000007e+00 , -7.9901400000000000e-01 , 1.8914500000000001e-01 , -5.7079000000000002e-01 -2.0866435761639055e+00 , 3.3294662329616118e+00 , 6.9048895999999997e+00 , 4.3548199999999998e-01 , -1.1468900000000000e-01 , 8.9286100000000002e-01 -2.0626814351428346e+00 , 3.2702354175929886e+00 , 6.9378159999999998e+00 , -5.2602099999999996e-01 , -1.5701200000000001e-01 , -8.3585200000000004e-01 -1.9226021016613344e+00 , 3.4341525801523627e+00 , 8.0535175999999993e+00 , 9.4306500000000004e-01 , 2.6485399999999998e-01 , 2.0119600000000001e-01 -1.8749256589462180e+00 , 3.3834214889254612e+00 , 8.2395631999999992e+00 , 1.9250600000000001e-01 , -7.8531600000000001e-01 , 5.8840400000000004e-01 -1.8466667955590095e+00 , 3.2968863785608429e+00 , 8.2519704000000011e+00 , -6.3875199999999999e-01 , 4.3993300000000002e-01 , -6.3123300000000004e-01 -3.3106435502804423e+00 , 3.7599317393766718e+00 , 8.3851759999999986e-01 , 5.8190400000000003e-02 , -4.9115199999999998e-02 , -9.9709700000000001e-01 -3.3217272604557362e+00 , 3.8036165198306255e+00 , 8.5741439999999991e-01 , -8.8231799999999999e-02 , 4.6291800000000001e-02 , 9.9502400000000002e-01 -3.3465465930497329e+00 , 3.8688998808224468e+00 , 8.4418560000000009e-01 , -7.9134599999999999e-02 , 1.5505800000000000e-01 , 9.8473100000000002e-01 -3.3711991135197987e+00 , 3.9355819830610015e+00 , 8.3256880000000000e-01 , -4.2097400000000000e-02 , 1.6886999999999999e-01 , 9.8473900000000003e-01 -3.3934811783911236e+00 , 3.9969447152227136e+00 , 8.3096720000000013e-01 , -5.6991600000000003e-02 , 2.0724000000000001e-01 , 9.7662899999999997e-01 -3.4209023434353520e+00 , 4.0711173746649720e+00 , 8.1493040000000017e-01 , 1.1282300000000001e-01 , -1.5700600000000001e-01 , -9.8113200000000000e-01 -3.4428188359153413e+00 , 4.1342311837600860e+00 , 8.1665680000000007e-01 , -9.7836900000000004e-02 , 1.3791800000000001e-01 , 9.8560000000000003e-01 -3.4708348840413552e+00 , 4.2102328873349464e+00 , 8.0458239999999992e-01 , -8.8614499999999999e-02 , 1.9888900000000001e-01 , 9.7600799999999999e-01 -3.4996854843989893e+00 , 4.2876665343768110e+00 , 7.9455679999999984e-01 , -7.3511999999999994e-02 , 2.2817200000000001e-01 , 9.7084199999999998e-01 -3.5314010102229276e+00 , 4.3724298598176592e+00 , 7.7929999999999988e-01 , -7.9171800000000001e-02 , 1.7797600000000000e-01 , 9.8084499999999997e-01 -3.5628113021949099e+00 , 4.4577043335888575e+00 , 7.6655999999999991e-01 , -7.7307399999999998e-02 , 1.8567800000000001e-01 , 9.7956500000000002e-01 -3.5939728261653094e+00 , 4.5445201081877293e+00 , 7.5614959999999987e-01 , -6.7080100000000004e-02 , 1.6927500000000001e-01 , 9.8328300000000002e-01 -3.6259176626796972e+00 , 4.6328635546945822e+00 , 7.4819360000000001e-01 , -7.5129500000000002e-02 , 2.1222600000000000e-01 , 9.7432799999999997e-01 -3.6647331085306494e+00 , 4.7356306941205277e+00 , 7.2897440000000002e-01 , -8.8224200000000003e-02 , 1.8018799999999999e-01 , 9.7966799999999998e-01 -3.7001398197541677e+00 , 4.8331226704665546e+00 , 7.1974960000000010e-01 , -8.0610399999999999e-02 , 1.6500899999999999e-01 , 9.8299199999999998e-01 -3.7382639358642176e+00 , 4.9382009324572618e+00 , 7.0660400000000001e-01 , -9.1213199999999994e-02 , 1.8567100000000000e-01 , 9.7836900000000004e-01 -3.7770968390771777e+00 , 5.0460120845596901e+00 , 6.9660959999999994e-01 , -5.6760300000000000e-02 , 2.1405099999999999e-01 , 9.7517200000000004e-01 -3.8296844517701683e+00 , 5.1837557326689652e+00 , 6.6420319999999999e-01 , 7.5666399999999995e-02 , -2.2004000000000001e-01 , -9.7255199999999997e-01 -3.8757594313143819e+00 , 5.3082412401955859e+00 , 6.4894639999999981e-01 , 7.8778899999999999e-02 , -2.0206299999999999e-01 , -9.7619900000000004e-01 -3.9284247017959681e+00 , 5.4498420020013807e+00 , 6.2516159999999998e-01 , -6.7032200000000000e-02 , 2.1388399999999999e-01 , 9.7455700000000001e-01 -3.9846145113201792e+00 , 5.6015908680664452e+00 , 5.9979600000000000e-01 , -4.3782900000000000e-02 , 2.0744799999999999e-01 , 9.7726599999999997e-01 -4.0442149558658880e+00 , 5.7625839924116598e+00 , 5.7357760000000013e-01 , -4.6676099999999998e-02 , 2.0053799999999999e-01 , 9.7857300000000003e-01 -4.1042606967525703e+00 , 5.9256729608275815e+00 , 5.5263200000000001e-01 , -6.5249799999999997e-02 , 1.9789699999999999e-01 , 9.7804899999999995e-01 -4.1745634239234874e+00 , 6.1146958292210423e+00 , 5.2027760000000001e-01 , 7.6256199999999996e-02 , -2.0202999999999999e-01 , -9.7640600000000000e-01 -4.2452307235111792e+00 , 6.3070503379661806e+00 , 4.9400719999999998e-01 , 7.7154299999999995e-02 , -2.0019100000000001e-01 , -9.7671399999999997e-01 -4.3230060696572545e+00 , 6.5174209195498660e+00 , 4.6378480000000000e-01 , 7.2928300000000001e-02 , -1.9264800000000001e-01 , -9.7855400000000003e-01 -4.4078026780671840e+00 , 6.7470209187072117e+00 , 4.3042160000000007e-01 , -7.6699299999999998e-02 , 1.9587499999999999e-01 , 9.7762499999999997e-01 -4.4956156990782965e+00 , 6.9876528915256673e+00 , 3.9973119999999995e-01 , -8.0626500000000004e-02 , 1.9197000000000000e-01 , 9.7808300000000004e-01 -4.5941289365535773e+00 , 7.2563248010847783e+00 , 3.6290479999999992e-01 , -2.0674899999999999e-01 , 3.1062099999999998e-01 , 9.2777699999999996e-01 -4.7003668591200904e+00 , 7.5458861670140607e+00 , 3.2599519999999993e-01 , -1.4942700000000000e-01 , 1.9622999999999999e-01 , 9.6910499999999999e-01 -4.8131445013769589e+00 , 7.8555343741636916e+00 , 2.9008400000000001e-01 , 2.3999500000000001e-01 , 2.6539699999999999e-01 , 9.3379100000000004e-01 -4.9170797924709264e+00 , 8.1513248452214526e+00 , 2.7310079999999992e-01 , 6.0092399999999997e-02 , 1.2965699999999999e-01 , 9.8973599999999995e-01 -4.6314963336261314e+00 , 7.5344827976266391e+00 , 6.9213759999999991e-01 , -9.0601500000000001e-01 , -1.4293900000000001e-01 , -3.9837800000000001e-01 -4.6148985532115478e+00 , 7.5428652180234712e+00 , 8.0401039999999990e-01 , 9.9418700000000004e-01 , 8.1575900000000007e-02 , 7.0266800000000004e-02 -4.6021220214143099e+00 , 7.5586756694033070e+00 , 9.1137999999999986e-01 , 9.9713799999999997e-01 , 6.7865900000000007e-02 , 3.3308100000000000e-02 -4.5872562749603691e+00 , 7.5723859952158907e+00 , 1.0183960000000001e+00 , 9.9750499999999998e-01 , 7.0455400000000001e-02 , 4.4376900000000002e-03 -4.5872918909937690e+00 , 7.6197948925949497e+00 , 1.1114447999999999e+00 , 9.9578500000000003e-01 , 4.1404799999999999e-02 , -8.1836500000000006e-02 -4.5798043168049940e+00 , 7.6488276637249610e+00 , 1.2117871199999999e+00 , 9.9574799999999997e-01 , 3.9411399999999999e-02 , -8.3267099999999997e-02 -4.5970009792508684e+00 , 7.7394129886684784e+00 , 1.2908864000000000e+00 , 9.9446000000000001e-01 , 2.9730500000000000e-02 , -1.0082800000000000e-01 -4.6861603839595816e+00 , 8.2172413830405038e+00 , 1.7157201600000000e+00 , -9.1173400000000004e-01 , 3.1444800000000002e-02 , 4.0957700000000002e-01 -1.5114022877465183e+01 , 3.5927534007269664e+01 , -3.4869048000000005e+00 , -8.7075800000000003e-01 , -7.6329400000000006e-02 , 4.8575099999999999e-01 -1.5340403397600543e+01 , 3.6834548782121352e+01 , -3.0051975999999998e+00 , -9.2777900000000002e-01 , -2.4974900000000000e-01 , 2.7722100000000000e-01 -1.5434151353286778e+01 , 3.8029945982789251e+01 , -1.1998928000000002e+00 , 5.8130700000000002e-01 , 7.6051800000000003e-01 , -2.8929899999999997e-01 -1.5414058819732160e+01 , 3.8297103577716584e+01 , -5.6344400000000050e-01 , 2.7930899999999997e-01 , 9.3966400000000005e-01 , -1.9753000000000001e-01 -1.5374962743541424e+01 , 3.8515097756415202e+01 , 8.3477599999999930e-02 , 2.7930899999999997e-01 , 9.3966400000000005e-01 , -1.9753000000000001e-01 -1.5400918252005788e+01 , 3.8917866887025234e+01 , 7.2331680000000009e-01 , -2.1267100000000000e-01 , -9.2618599999999995e-01 , 3.1136900000000001e-01 -1.2131561845330998e+01 , 2.9949814054528396e+01 , 1.8080336800000001e+00 , 6.4037400000000000e-01 , 6.6360100000000000e-01 , -3.8672299999999998e-01 -1.2126835693554114e+01 , 3.0190374302086845e+01 , 2.3053336000000000e+00 , 6.4037400000000000e-01 , 6.6360100000000000e-01 , -3.8672299999999998e-01 -1.2066852388497255e+01 , 3.0275841104872814e+01 , 2.8114787200000002e+00 , 1.1696500000000000e-01 , 9.7601400000000005e-01 , -1.8361900000000000e-01 -1.2017619418097354e+01 , 3.0392032107904900e+01 , 3.3198119999999998e+00 , 1.1696500000000000e-01 , 9.7601400000000005e-01 , -1.8361900000000000e-01 -1.2015099749324699e+01 , 3.0646834612895091e+01 , 3.8354856000000002e+00 , -2.9727500000000001e-01 , -9.4188600000000000e-01 , 1.5645600000000001e-01 -1.1911301071375172e+01 , 3.0608709025582495e+01 , 4.3462816000000002e+00 , -3.1319799999999998e-01 , -9.3991899999999995e-01 , 1.3586100000000001e-01 -1.1852119370431900e+01 , 3.0699644083560486e+01 , 4.8639000000000001e+00 , -4.7653499999999999e-01 , -8.7881799999999999e-01 , 2.4358100000000001e-02 -1.1756013274724829e+01 , 3.0683770331642819e+01 , 5.3759232000000008e+00 , 6.6073000000000004e-01 , 7.5039900000000004e-01 , -1.8358200000000002e-02 -1.1708981262817490e+01 , 3.0816324777030168e+01 , 5.9027247999999997e+00 , -7.0233100000000004e-01 , -7.0142400000000005e-01 , 1.2138699999999999e-01 -1.1633684390693984e+01 , 3.0861122571176942e+01 , 6.4249920000000005e+00 , -6.9276499999999996e-01 , -7.0447400000000004e-01 , 1.5425200000000000e-01 -1.1622401768704957e+01 , 3.1113087585210739e+01 , 6.9778352000000003e+00 , 8.3345400000000003e-01 , 5.2339300000000000e-01 , -1.7724200000000001e-01 -1.1620340577511451e+01 , 3.1395466875334620e+01 , 7.5459248000000008e+00 , -8.1667699999999999e-01 , -5.4171899999999995e-01 , 1.9894800000000001e-01 -1.1620943131698510e+01 , 3.1696637954637485e+01 , 8.1293544000000004e+00 , -7.7486200000000005e-01 , -5.9153900000000004e-01 , 2.2286900000000001e-01 -1.1577600929435544e+01 , 3.1861244357231659e+01 , 8.6997008000000005e+00 , 7.9881100000000005e-01 , 4.2389199999999999e-01 , -4.2686900000000000e-01 -1.2222698236655823e+01 , 3.4278052667887913e+01 , 9.7496536000000003e+00 , -8.5866900000000002e-01 , 2.7882299999999999e-01 , 4.3005399999999999e-01 -1.2145653137873763e+01 , 3.4367595055893048e+01 , 1.0362088799999999e+01 , 9.3535699999999999e-01 , -1.2227399999999999e-01 , -3.3189700000000000e-01 -1.1953767832890490e+01 , 3.4077204860405196e+01 , 1.0887964800000001e+01 , -9.1004399999999996e-01 , -1.3795700000000000e-01 , 3.9088200000000001e-01 -5.4098652071830493e+00 , 1.2376999143480491e+01 , 5.7255400000000005e+00 , -4.3595399999999999e-02 , -9.8674499999999998e-01 , 1.5631400000000001e-01 -4.6847568188675170e+00 , 1.0388191400894383e+01 , 5.9660712000000000e+00 , -3.4894500000000001e-01 , -8.0552599999999996e-01 , 4.7892000000000001e-01 -4.6714099269099805e+00 , 1.0440527826874321e+01 , 6.1439632000000000e+00 , 4.4741300000000001e-01 , 7.2207600000000005e-01 , -5.2766199999999996e-01 -5.1526721821559489e+00 , 1.2304033114657420e+01 , 7.0529648000000007e+00 , 1.2762600000000001e-02 , 5.8796899999999996e-01 , 8.0878300000000003e-01 -4.8488019699463081e+00 , 1.1306424876794807e+01 , 6.8325784000000001e+00 , 2.8214800000000001e-01 , 7.6068100000000000e-02 , -9.5635099999999995e-01 -4.8013477334881802e+00 , 1.1251037923879736e+01 , 6.9902215999999999e+00 , 1.7646300000000001e-01 , -2.2907000000000000e-01 , -9.5728100000000005e-01 -4.6358178988167804e+00 , 1.0742320544108475e+01 , 6.9386272000000000e+00 , -3.4112100000000001e-01 , -9.0499700000000005e-01 , -2.5419999999999998e-01 -4.5272044879099429e+00 , 1.0438408381001858e+01 , 6.9669984000000005e+00 , 5.8286300000000002e-01 , -1.2708100000000000e-01 , -8.0257199999999995e-01 -4.5255537127834087e+00 , 1.0551457886122586e+01 , 7.1957360000000001e+00 , -2.8562399999999999e-01 , 7.7671199999999996e-01 , 5.6137099999999995e-01 -4.2402307646899864e+00 , 9.5370017852440530e+00 , 6.8376640000000002e+00 , -2.5220500000000001e-01 , 3.1961600000000001e-01 , 9.1336600000000001e-01 -4.1451954561927034e+00 , 9.2666154593224448e+00 , 6.8456408000000009e+00 , 1.9075900000000001e-01 , -3.3389900000000000e-01 , -9.2310499999999995e-01 -4.1156389077872095e+00 , 9.2527078534510618e+00 , 6.9916984000000006e+00 , -9.5181300000000002e-01 , -2.7628399999999997e-01 , -1.3311300000000001e-01 -4.0258650394259279e+00 , 8.9912299904729274e+00 , 6.9922599999999999e+00 , 2.8615200000000002e-01 , -9.4510400000000006e-01 , 1.5778300000000001e-01 -4.0622406351105855e+00 , 9.2609842308779804e+00 , 7.3112383999999997e+00 , -4.0549400000000002e-01 , -8.9958199999999999e-01 , 1.6225400000000001e-01 -3.9991547647802639e+00 , 9.1100658841193898e+00 , 7.3761344000000006e+00 , -4.0549400000000002e-01 , -8.9958199999999999e-01 , 1.6225400000000001e-01 -3.6876084683289605e+00 , 7.8598966385498965e+00 , 6.7069256000000008e+00 , 2.0128299999999999e-01 , 9.6220200000000000e-01 , 1.8344700000000000e-01 -3.6808629604207086e+00 , 7.9384021974553631e+00 , 6.8948431999999995e+00 , 7.0768500000000001e-01 , 5.0125399999999998e-01 , 4.9792300000000000e-01 -3.6240154377142435e+00 , 7.7878040007302438e+00 , 6.9257624000000000e+00 , -4.7465700000000000e-01 , -8.7665099999999996e-01 , -7.8630000000000005e-02 -3.5974878922973326e+00 , 7.7769616662033201e+00 , 7.0560432000000004e+00 , 4.7823399999999999e-01 , -1.8054200000000001e-01 , 8.5947499999999999e-01 -3.4695476906652760e+00 , 7.2833027605953786e+00 , 6.8183720000000001e+00 , -2.8166700000000000e-01 , -3.3888600000000002e-01 , 8.9767500000000000e-01 -3.3902170451545239e+00 , 7.0067936209284820e+00 , 6.7308040000000000e+00 , 1.1531800000000000e-01 , -1.8736100000000000e-01 , 9.7549900000000000e-01 -3.3899931365067175e+00 , 7.1162591599483829e+00 , 6.9473007999999998e+00 , 2.8211199999999997e-01 , 3.8592500000000002e-01 , -8.7833600000000001e-01 -3.2963340521308888e+00 , 6.7575774177445718e+00 , 6.7755864000000008e+00 , -2.7792200000000000e-01 , -4.1396000000000002e-02 , -9.5971099999999998e-01 -3.2754206581591685e+00 , 6.7611799791366378e+00 , 6.9049312000000000e+00 , 2.3845200000000000e-01 , -8.9410500000000004e-02 , 9.6702999999999995e-01 -3.3577745256727298e+00 , 7.3335145535722193e+00 , 7.5549935999999995e+00 , -6.7362100000000003e-01 , 4.8239900000000002e-01 , -5.5993400000000004e-01 -3.2649644180980717e+00 , 6.9621119058412431e+00 , 7.3571544000000006e+00 , 1.0984800000000000e-01 , 7.5210200000000005e-01 , 6.4982799999999996e-01 -3.2378316311399908e+00 , 6.9534177489133162e+00 , 7.4926872000000007e+00 , -2.4624099999999999e-01 , 4.6152700000000002e-01 , 8.5226700000000000e-01 -3.1240312630309051e+00 , 6.4303130389193077e+00 , 7.1171639999999998e+00 , 9.6533599999999997e-01 , 1.9459699999999999e-01 , 1.7394699999999999e-01 -3.0903718165747356e+00 , 6.3659754713213310e+00 , 7.1859288000000001e+00 , -8.6892199999999997e-01 , -2.8454600000000002e-01 , -4.0498000000000001e-01 -3.0490414219650157e+00 , 6.2585494206641235e+00 , 7.2078416000000001e+00 , -8.6892199999999997e-01 , -2.8454499999999999e-01 , -4.0498000000000001e-01 -3.0678464620693147e+00 , 6.5452540089911944e+00 , 7.6651400000000010e+00 , 4.7188200000000002e-01 , -6.1215200000000003e-01 , -6.3450600000000001e-01 -3.0226553740502871e+00 , 6.4181356212903733e+00 , 7.6728048000000006e+00 , -9.3474299999999999e-01 , -3.2916600000000001e-01 , -1.3381100000000001e-01 -2.9817823688680143e+00 , 6.3167765760651440e+00 , 7.7091320000000003e+00 , -2.1699599999999999e-01 , -1.0727700000000000e-01 , 9.7026000000000001e-01 -2.9044664024599571e+00 , 5.9276737131289945e+00 , 7.3898728000000000e+00 , 1.3317399999999999e-01 , 3.9455499999999999e-01 , 9.0917000000000003e-01 -2.8764688111961410e+00 , 5.9103680901195723e+00 , 7.5140488000000003e+00 , 3.3553300000000001e-03 , 6.7474599999999996e-01 , 7.3804300000000000e-01 -2.8364700021475699e+00 , 5.7944362348811769e+00 , 7.5150991999999999e+00 , -6.6521200000000003e-02 , 7.7623799999999998e-01 , 6.2692000000000003e-01 -2.9345957496433059e+00 , 6.9864019676193641e+00 , 9.2834631999999999e+00 , -7.7000500000000005e-01 , -3.0946099999999999e-01 , -5.5796699999999999e-01 -2.8757615584998160e+00 , 6.7653543834240804e+00 , 9.1909136000000000e+00 , 6.1460000000000001e-02 , -2.6082100000000003e-01 , 9.6342899999999998e-01 -2.8366276523632932e+00 , 6.7613690348448614e+00 , 9.3999640000000007e+00 , -5.0261299999999998e-01 , -6.0324400000000000e-01 , -6.1925500000000000e-01 -2.7649402953131208e+00 , 6.3482684471853892e+00 , 9.0049823999999994e+00 , -3.2122900000000003e-02 , -6.8133299999999997e-01 , 7.3126899999999995e-01 -2.7031654111958678e+00 , 6.0041040990545875e+00 , 8.6854320000000005e+00 , 4.9132900000000002e-01 , 3.2399800000000001e-01 , -8.0846899999999999e-01 -2.6539741036115467e+00 , 5.7980952332044380e+00 , 8.5589472000000004e+00 , 1.3164699999999999e-01 , -2.4877099999999999e-01 , 9.5957400000000004e-01 -2.6143183763763469e+00 , 5.7250716464297025e+00 , 8.6413048000000003e+00 , 8.9830999999999994e-02 , -2.6175700000000002e-01 , 9.6094400000000002e-01 -2.5719752262664821e+00 , 5.5726490573183316e+00 , 8.5871936000000009e+00 , 3.6498000000000003e-01 , -4.4721600000000000e-01 , 8.1657100000000005e-01 -2.5288584869745439e+00 , 5.3875559444190380e+00 , 8.4656488000000003e+00 , 3.0484299999999998e-01 , -6.0292400000000003e-02 , 9.5049200000000000e-01 -2.4851561535566313e+00 , 4.9182736285712849e+00 , 7.7977920000000003e+00 , 1.5572400000000000e-01 , -9.1499100000000000e-01 , 3.7221199999999999e-01 -2.4519254174216272e+00 , 5.0401703186445017e+00 , 8.2270832000000009e+00 , 2.3436399999999999e-01 , 8.3326800000000001e-01 , -5.0073699999999999e-01 -2.4103975080861031e+00 , 5.3038210581811471e+00 , 8.9786807999999994e+00 , -9.0859599999999996e-01 , -1.9350999999999999e-01 , 3.7014500000000000e-01 -2.3730402562827235e+00 , 5.0832432473427307e+00 , 8.7613519999999987e+00 , 4.8466100000000001e-01 , -2.9185699999999998e-01 , -8.2457400000000003e-01 -2.3373180528089219e+00 , 4.9134546737692926e+00 , 8.6330367999999993e+00 , 1.4364299999999999e-01 , 2.8084300000000001e-01 , 9.4894400000000001e-01 -2.2995242241163854e+00 , 4.8099926468548766e+00 , 8.6437488000000009e+00 , 1.6852500000000001e-01 , -2.7138000000000001e-01 , 9.4760299999999997e-01 -2.3257052499641064e+00 , 3.9401249741982514e+00 , 6.7982792000000005e+00 , -1.3876800000000000e-01 , 2.8051000000000000e-02 , 9.8992800000000003e-01 -2.3020242727063622e+00 , 3.8637817077344812e+00 , 6.7832512000000005e+00 , -2.7251700000000001e-01 , 6.5663600000000000e-01 , 7.0325199999999999e-01 -2.2748137591404758e+00 , 3.8218895593345636e+00 , 6.8541167999999999e+00 , -3.0992100000000000e-01 , 6.8081800000000003e-01 , 6.6365300000000005e-01 -2.1637394748477470e+00 , 4.3387256169284747e+00 , 8.4997296000000002e+00 , -9.9129199999999995e-01 , -7.1929499999999993e-02 , -1.1030500000000000e-01 -2.1307795678793986e+00 , 4.2289851920510415e+00 , 8.4697671999999997e+00 , -9.9129199999999995e-01 , -7.1929599999999996e-02 , -1.1030500000000000e-01 -2.1951282606393283e+00 , 3.6561776900256175e+00 , 6.9843560000000000e+00 , -8.1445199999999995e-01 , 2.0696999999999999e-01 , 5.4206200000000004e-01 -2.1721017453665823e+00 , 3.5826730281908499e+00 , 6.9729784000000006e+00 , -1.1832300000000000e-01 , 6.9685100000000000e-01 , 7.0738800000000002e-01 -2.1442770765959298e+00 , 3.5295142841808085e+00 , 7.0299600000000000e+00 , 3.2221800000000000e-01 , 7.9269400000000001e-01 , 5.1750499999999999e-01 -1.8485608685139900e+00 , 4.3226725005821320e+00 , 1.0260647199999999e+01 , 8.0888400000000005e-01 , 5.3503100000000003e-01 , -2.4382000000000001e-01 -1.8070911408215689e+00 , 4.1912149384513100e+00 , 1.0237049600000001e+01 , 7.7406500000000000e-01 , 1.7198600000000000e-01 , -6.0929800000000001e-01 -2.0851833558728945e+00 , 3.2929955463815634e+00 , 6.9027368000000004e+00 , -5.7865100000000003e-01 , 2.2173800000000000e-02 , -8.1527400000000005e-01 -2.0397087526802902e+00 , 3.2743437431288598e+00 , 7.1272104000000001e+00 , 2.3484800000000000e-02 , 9.9832699999999996e-01 , -5.2839999999999998e-02 -1.8974327863862162e+00 , 3.4218028364758282e+00 , 8.2240256000000009e+00 , -8.5165000000000002e-01 , -4.8417700000000001e-02 , -5.2186999999999995e-01 -1.8722390728548091e+00 , 3.3260203454390478e+00 , 8.1754160000000002e+00 , 1.9366400000000000e-01 , 9.1953099999999996e-02 , 9.7674899999999998e-01 -1.8396591903890853e+00 , 3.2445729976245019e+00 , 8.2068967999999991e+00 , -6.3573999999999997e-01 , -7.6475300000000002e-01 , 1.0482500000000000e-01 -3.3677331298769291e+00 , 3.7666867381935765e+00 , 8.5260960000000008e-01 , -9.6066799999999994e-02 , 3.7759399999999999e-02 , 9.9465800000000004e-01 -3.3872239605154411e+00 , 3.8206180031450021e+00 , 8.5563600000000006e-01 , -1.1510800000000000e-01 , 5.5568100000000002e-02 , 9.9179799999999996e-01 -3.4107868739339207e+00 , 3.8804258055593461e+00 , 8.5183999999999993e-01 , -4.7596699999999999e-02 , 1.6178999999999999e-01 , 9.8567700000000003e-01 -3.4373711941374347e+00 , 3.9462155085879891e+00 , 8.4149199999999991e-01 , -6.2335300000000003e-02 , 1.8009400000000000e-01 , 9.8167199999999999e-01 -3.4637641845101177e+00 , 4.0134202059261028e+00 , 8.3285999999999993e-01 , -8.3739400000000005e-02 , 1.6803899999999999e-01 , 9.8221700000000001e-01 -3.4909979255975419e+00 , 4.0820262686539923e+00 , 8.2606880000000005e-01 , -7.9798099999999997e-02 , 1.3470699999999999e-01 , 9.8766699999999996e-01 -3.5179763024543966e+00 , 4.1500075441943167e+00 , 8.2140959999999996e-01 , -7.1344000000000005e-02 , 1.2898100000000001e-01 , 9.8907699999999998e-01 -3.5448014961070147e+00 , 4.2204196415269450e+00 , 8.1825839999999994e-01 , 5.9765499999999999e-02 , -1.8285699999999999e-01 , -9.8132100000000000e-01 -3.5818145812483642e+00 , 4.3096206885091375e+00 , 7.9457760000000000e-01 , -5.7075399999999998e-02 , 1.9605900000000001e-01 , 9.7892999999999997e-01 -3.6091861805509726e+00 , 4.3808969659535819e+00 , 7.9580479999999998e-01 , -6.0518900000000000e-02 , 1.9193099999999999e-01 , 9.7954100000000000e-01 -3.6466568208867445e+00 , 4.4721857304751111e+00 , 7.7730319999999997e-01 , -5.2742499999999998e-02 , 1.6763700000000001e-01 , 9.8443700000000001e-01 -3.6807711982361671e+00 , 4.5591968401757770e+00 , 7.6848399999999994e-01 , 8.8083499999999995e-02 , -1.7875099999999999e-01 , -9.7994400000000004e-01 -3.7228169154967050e+00 , 4.6605813754282845e+00 , 7.4832879999999991e-01 , -6.1409199999999997e-02 , 2.2188400000000000e-01 , 9.7313700000000003e-01 -3.7603898694407647e+00 , 4.7556579709605060e+00 , 7.3814720000000000e-01 , -6.8574300000000005e-02 , 1.7415600000000001e-01 , 9.8232699999999995e-01 -3.7986969624022220e+00 , 4.8523477741492709e+00 , 7.3081520000000011e-01 , -7.5633300000000001e-02 , 1.5688299999999999e-01 , 9.8471699999999995e-01 -3.8437898084539635e+00 , 4.9647174519229207e+00 , 7.1313519999999997e-01 , -5.7386899999999998e-02 , 1.7799899999999999e-01 , 9.8235600000000001e-01 -3.8895267111140814e+00 , 5.0788306380806079e+00 , 6.9902240000000004e-01 , -3.8717000000000001e-02 , 2.0250000000000001e-01 , 9.7851699999999997e-01 -3.9429482518447734e+00 , 5.2088483579254010e+00 , 6.7589279999999996e-01 , -6.4400700000000005e-02 , 1.9442899999999999e-01 , 9.7880000000000000e-01 -3.9918961950513987e+00 , 5.3336615674423467e+00 , 6.6284079999999990e-01 , -4.7396800000000003e-02 , 1.9810800000000001e-01 , 9.7903399999999996e-01 -4.0564368304862652e+00 , 5.4898622259610086e+00 , 6.2973759999999990e-01 , -3.4855499999999998e-02 , 2.0790000000000000e-01 , 9.7752899999999998e-01 -4.1214308887934745e+00 , 5.6481709874038266e+00 , 6.0192799999999980e-01 , -4.0175900000000001e-02 , 2.0957100000000001e-01 , 9.7696799999999995e-01 -4.1858340305740036e+00 , 5.8086096072218645e+00 , 5.7926639999999985e-01 , -5.7624300000000003e-02 , 1.8307399999999999e-01 , 9.8140899999999998e-01 -4.2546205217026021e+00 , 5.9783623259878844e+00 , 5.5637599999999998e-01 , -6.1115799999999998e-02 , 1.8352299999999999e-01 , 9.8111400000000004e-01 -4.3267790647643833e+00 , 6.1596435710361268e+00 , 5.3342320000000010e-01 , -5.2307399999999997e-02 , 1.8574900000000000e-01 , 9.8120399999999997e-01 -4.4100042308892569e+00 , 6.3661102464991837e+00 , 5.0080879999999994e-01 , -6.4293500000000003e-02 , 1.8075700000000000e-01 , 9.8142399999999996e-01 -4.4896034447827216e+00 , 6.5676927991775900e+00 , 4.8010239999999982e-01 , -5.6493300000000003e-02 , 1.8388800000000000e-01 , 9.8132200000000003e-01 -4.5850246615948782e+00 , 6.8042429219237164e+00 , 4.4655199999999984e-01 , -5.2126400000000003e-02 , 1.8230900000000000e-01 , 9.8185900000000004e-01 -4.6883311771390783e+00 , 7.0603143378705111e+00 , 4.1150399999999987e-01 , 1.9625500000000001e-01 , -1.7418200000000000e-01 , -9.6495900000000001e-01 -4.7983720403189558e+00 , 7.3361406447358046e+00 , 3.7573839999999992e-01 , 1.1918700000000000e-01 , -1.0705099999999999e-01 , -9.8708399999999996e-01 -4.9199231544877211e+00 , 7.6414550848714970e+00 , 3.3598960000000000e-01 , 2.4801999999999999e-01 , 3.4769800000000001e-01 , 9.0420800000000001e-01 -4.8607755631381799e+00 , 7.5634509838032358e+00 , 5.0013279999999982e-01 , 7.6589600000000002e-01 , 3.6573000000000000e-01 , 5.2881500000000004e-01 -4.7092606179513368e+00 , 7.2815732226268208e+00 , 7.5525519999999990e-01 , -9.6700600000000003e-01 , -1.3055700000000001e-01 , -2.1875500000000001e-01 -4.6844468149254759e+00 , 7.2721182102316018e+00 , 8.7165199999999987e-01 , -9.6243299999999998e-01 , -1.1200599999999999e-01 , -2.4734200000000001e-01 -4.6758676945751922e+00 , 7.2958043479145456e+00 , 9.7158247999999992e-01 , 9.9417400000000000e-01 , 7.0659799999999995e-02 , 8.1391099999999994e-02 -4.6652169826971921e+00 , 7.3184550848140786e+00 , 1.0711604000000001e+00 , 9.9819100000000005e-01 , 6.0000600000000001e-02 , 3.7454599999999999e-03 -4.6555025069343436e+00 , 7.3379529761137299e+00 , 1.1711761599999999e+00 , 9.9773999999999996e-01 , 6.6113400000000003e-02 , -1.2037000000000001e-02 -4.6559016291980395e+00 , 7.3836209892517957e+00 , 1.2608886400000001e+00 , -9.6331100000000003e-01 , -6.9429099999999994e-02 , -2.5925100000000001e-01 -4.5322967560117089e+00 , 7.1463876188913185e+00 , 1.4483975199999999e+00 , 8.3368900000000001e-01 , 2.4728300000000000e-01 , 4.9377500000000002e-01 -4.7643461379571903e+00 , 7.9074439718846561e+00 , 1.7494775200000001e+00 , -8.8865400000000005e-01 , -1.5788300000000002e-02 , 4.5830700000000002e-01 -1.5951447365285642e+01 , 3.5348220876661834e+01 , -2.9473216000000004e+00 , -9.1985099999999997e-01 , -5.3241799999999999e-02 , 3.8863900000000001e-01 -1.5847929220647313e+01 , 3.5374670222110034e+01 , -2.3167279999999995e+00 , -9.2861700000000003e-01 , -1.3241900000000001e-01 , 3.4660500000000000e-01 -2.1594218615822992e+01 , 5.0331935167297168e+01 , -2.9386272000000000e+00 , -2.2264700000000001e-01 , 1.7488799999999999e-02 , 9.7474200000000000e-01 -2.1553641200930816e+01 , 5.0640994285306434e+01 , -2.0672528000000003e+00 , -2.2264700000000001e-01 , 1.7488900000000002e-02 , 9.7474200000000000e-01 -1.4474872416286543e+01 , 3.3028576264360140e+01 , 3.8665839999999996e-01 , -6.2804300000000002e-01 , 2.5909600000000001e-02 , -7.7774799999999999e-01 -1.4316696360378288e+01 , 3.2889123767697981e+01 , 9.6786967999999995e-01 , -7.2808600000000001e-01 , 1.9283900000000000e-02 , -6.8521399999999999e-01 -1.4553410282045727e+01 , 3.3767672037657476e+01 , 1.4897000800000000e+00 , -6.2804300000000002e-01 , 2.5909700000000001e-02 , -7.7774799999999999e-01 -1.3656844057512291e+01 , 3.1697290027171039e+01 , 2.1369409600000000e+00 , -5.3055600000000003e-01 , -4.4021800000000000e-01 , -7.2437499999999999e-01 -1.3159090643658494e+01 , 3.0642308293268080e+01 , 2.6918038399999999e+00 , 2.8502499999999997e-01 , -7.1505600000000002e-01 , -6.3832299999999997e-01 -1.2926856530479517e+01 , 3.0275613005439109e+01 , 3.2096760000000000e+00 , -5.9417299999999995e-01 , -7.8919300000000003e-01 , 1.5534899999999999e-01 -1.2919547843327395e+01 , 3.0505356568892172e+01 , 3.7265455999999997e+00 , -6.0070699999999999e-01 , -7.8527800000000003e-01 , -1.4996399999999999e-01 -1.2767706559736890e+01 , 3.0345646800457089e+01 , 4.2351784000000006e+00 , 6.6503599999999996e-01 , 7.4644900000000003e-01 , 2.3275199999999999e-02 -1.3472021862803631e+01 , 3.2798547352605510e+01 , 5.4502520000000008e+00 , -4.7177599999999997e-01 , 3.0097400000000002e-01 , 8.2875900000000002e-01 -1.3241426811869326e+01 , 3.2436853389696800e+01 , 5.9724047999999996e+00 , -8.1961699999999998e-02 , 6.0264799999999996e-01 , 7.9378700000000002e-01 -1.2403206984011884e+01 , 3.0361320340972537e+01 , 6.2854967999999998e+00 , 6.4698000000000000e-01 , 7.6044199999999995e-01 , -5.6077099999999998e-02 -1.2334653641180227e+01 , 3.0432528312791749e+01 , 6.8083360000000006e+00 , 6.5056400000000003e-01 , 7.2740099999999996e-01 , -2.1830100000000000e-01 -1.2294956940270286e+01 , 3.0857643802305912e+01 , 7.9140847999999995e+00 , -7.5306300000000004e-01 , -6.4181400000000000e-01 , 1.4481100000000000e-01 -1.2174442468002567e+01 , 3.0784719644730849e+01 , 8.4276368000000002e+00 , -7.7678499999999995e-01 , -6.2363599999999997e-01 , 8.7654999999999997e-02 -1.2173315192660937e+01 , 3.1060921334577785e+01 , 9.0128343999999991e+00 , 8.1159099999999995e-01 , 5.5401800000000001e-01 , -1.8542900000000001e-01 -1.2544098151360194e+01 , 3.2454352386254982e+01 , 9.8631695999999991e+00 , 7.7708400000000000e-01 , 1.3112699999999999e-01 , -6.1558599999999997e-01 -1.3116734920681392e+01 , 3.4484750533422527e+01 , 1.0924427200000000e+01 , 3.7705200000000000e-01 , 8.7282800000000005e-01 , 3.0984400000000001e-01 -1.2617927323811372e+01 , 3.3302004587714507e+01 , 1.1219163200000001e+01 , -9.1004399999999996e-01 , -1.3795700000000000e-01 , 3.9088200000000001e-01 -1.2439763534145166e+01 , 3.3412964722050106e+01 , 1.2432864000000000e+01 , -7.6434199999999997e-01 , -6.4472600000000002e-01 , 1.0482800000000000e-02 -1.3143345404560353e+01 , 3.5959522472088196e+01 , 1.3848928000000001e+01 , -9.7871799999999998e-01 , 6.3632300000000001e-03 , 2.0510999999999999e-01 -4.9658873555484355e+00 , 1.0665326058609903e+01 , 6.3844320000000003e+00 , 2.4328000000000000e-01 , 9.0477099999999999e-01 , -3.4957800000000000e-01 -4.9322516253022259e+00 , 1.0656098942592196e+01 , 6.5475352000000004e+00 , -3.0201400000000000e-01 , -9.1256800000000005e-01 , 2.7569300000000002e-01 -4.9087105771609210e+00 , 1.0679521755122051e+01 , 6.7273095999999999e+00 , -1.3285200000000000e-01 , -9.4271700000000003e-01 , 3.0599700000000002e-01 -4.9024337562748608e+00 , 1.0763672148635834e+01 , 6.9380656000000007e+00 , -1.0850300000000000e-01 , 9.8880100000000004e-01 , 1.0246400000000000e-01 -4.7094873803351520e+00 , 1.0208765635462838e+01 , 6.8463896000000002e+00 , 5.8948899999999999e-02 , 2.1085699999999999e-01 , 9.7573799999999999e-01 -4.8099761258167595e+00 , 1.0665725644040757e+01 , 7.2438360000000008e+00 , 2.1050300000000000e-01 , -9.2937499999999995e-01 , -3.0323299999999997e-01 -4.7958181385207368e+00 , 1.0730334358969051e+01 , 7.4560896000000003e+00 , 2.1050300000000000e-01 , -9.2937499999999995e-01 , -3.0323400000000000e-01 -4.4316515724952570e+00 , 9.5397785800541754e+00 , 6.9871951999999995e+00 , -2.8193000000000001e-01 , 3.0070700000000000e-01 , 9.1109300000000004e-01 -4.2932579657494365e+00 , 9.1378914285648492e+00 , 6.9182223999999994e+00 , 4.5575599999999999e-01 , -5.8324900000000002e-01 , -6.7238900000000001e-01 -4.2617839426249855e+00 , 9.1248579026795991e+00 , 7.0629176000000005e+00 , 2.5391500000000000e-01 , 9.6266300000000005e-01 , 9.3847899999999998e-02 -4.2551614431204436e+00 , 9.2023378557481994e+00 , 7.2668824000000001e+00 , 3.8193199999999999e-01 , 9.2299100000000001e-01 , 4.7070200000000000e-02 -4.2380914838317691e+00 , 9.2510544671406478e+00 , 7.4575976000000006e+00 , 3.9364800000000000e-01 , 9.0728100000000000e-01 , 1.4792500000000000e-01 -3.9370861258200538e+00 , 8.1926711322791448e+00 , 6.9203128000000005e+00 , -1.0025400000000000e-01 , 1.6755100000000001e-01 , 9.8075299999999999e-01 -3.8456365069890150e+00 , 7.9332305592369581e+00 , 6.8832680000000002e+00 , 3.1542199999999998e-01 , -3.3410400000000001e-01 , -8.8819099999999995e-01 -3.7983476741889666e+00 , 7.8417448961262330e+00 , 6.9566608000000008e+00 , 6.7071199999999997e-02 , 7.9325500000000004e-01 , 6.0518400000000006e-01 -3.9342408483979270e+00 , 8.5051449351438180e+00 , 7.5852472000000004e+00 , -6.1785599999999996e-01 , -4.8260999999999998e-01 , -6.2075899999999995e-01 -3.8815582141041816e+00 , 8.4038856677190967e+00 , 7.6669808000000002e+00 , -6.1785599999999996e-01 , -4.8260999999999998e-01 , -6.2075899999999995e-01 -3.8415645643739396e+00 , 8.3572374984399627e+00 , 7.7905536000000009e+00 , -6.1785599999999996e-01 , -4.8260999999999998e-01 , -6.2075899999999995e-01 -3.4766043682746837e+00 , 6.8895388436258367e+00 , 6.7522696000000000e+00 , -4.6090500000000001e-01 , 2.3597099999999999e-01 , -8.5550300000000001e-01 -3.4302270440273439e+00 , 6.7855996273772181e+00 , 6.7903960000000003e+00 , -4.6090500000000001e-01 , 2.3597099999999999e-01 , -8.5550300000000001e-01 -3.4629386238165472e+00 , 7.0376751427061262e+00 , 7.1367576000000001e+00 , -8.3745599999999998e-01 , 5.3895899999999997e-01 , -9.0497700000000000e-02 -3.5850951476618094e+00 , 7.7276421001898319e+00 , 7.8995560000000005e+00 , 9.5882999999999996e-01 , -1.7161799999999999e-01 , 2.2625799999999999e-01 -3.3719804900987764e+00 , 6.9693416304016935e+00 , 7.4949544000000001e+00 , -9.1412199999999999e-01 , 3.4204699999999999e-01 , 2.1768199999999999e-01 -3.3173378372897373e+00 , 6.8273400333540879e+00 , 7.5005184000000007e+00 , 8.6157799999999995e-01 , 3.9107300000000000e-01 , -3.2364300000000001e-01 -3.2721793269808144e+00 , 6.7292189330155816e+00 , 7.5466736000000001e+00 , 1.5952400000000000e-01 , -3.9111300000000002e-02 , 9.8641900000000005e-01 -3.1759815828508469e+00 , 6.3491390997956847e+00 , 7.2892944000000002e+00 , -9.3545699999999998e-01 , -3.5295100000000001e-01 , -1.8610300000000000e-02 -3.3646200962968784e+00 , 7.5588159870944001e+00 , 8.7642848000000004e+00 , 2.5271300000000002e-01 , -8.6449299999999996e-01 , 4.3449599999999999e-01 -3.1213375092492877e+00 , 6.3306341309044010e+00 , 7.5546712000000005e+00 , 5.6276999999999999e-01 , 7.1011100000000005e-01 , 4.2312200000000000e-01 -3.0866020347255736e+00 , 6.2870998706376602e+00 , 7.6526808000000006e+00 , -1.1719100000000000e-01 , -7.2135099999999994e-02 , 9.9048599999999998e-01 -3.0286880031468959e+00 , 6.0964816553844905e+00 , 7.5743688000000002e+00 , 1.1518299999999999e-01 , -4.9741600000000002e-01 , 8.5983200000000004e-01 -2.9788833491390090e+00 , 5.9482024868382819e+00 , 7.5392583999999996e+00 , -6.7758900000000000e-01 , 4.4783000000000001e-01 , 5.8337099999999997e-01 -2.9304470295984371e+00 , 5.7953193923863333e+00 , 7.4921151999999998e+00 , 3.3553200000000002e-03 , 6.7474599999999996e-01 , 7.3804300000000000e-01 -2.9005314001028228e+00 , 5.7806704711632158e+00 , 7.6238416000000004e+00 , -2.4872400000000000e-01 , 7.0550500000000005e-01 , 6.6362600000000005e-01 -2.9928282607881767e+00 , 6.7430521877445457e+00 , 9.1210255999999994e+00 , -6.8371199999999999e-01 , 2.9882900000000000e-02 , 7.2914000000000001e-01 -2.8711956194624180e+00 , 6.0250072187944674e+00 , 8.2980216000000002e+00 , -9.7651200000000005e-01 , -1.4063400000000001e-01 , -1.6323699999999999e-01 -2.9538908799866812e+00 , 7.1146909568325940e+00 , 1.0108786400000000e+01 , -4.6179500000000001e-01 , -7.8262900000000002e-01 , 4.1741800000000001e-01 -2.8317951485256527e+00 , 6.3199369116758062e+00 , 9.1315920000000013e+00 , 5.2784200000000003e-01 , -7.8856599999999999e-01 , 3.1551099999999999e-01 -2.7484290659526946e+00 , 5.8214337539496004e+00 , 8.5526552000000002e+00 , 2.7373300000000000e-01 , -3.0624299999999999e-01 , 9.1174900000000003e-01 -2.7078780500425048e+00 , 5.7655997479431225e+00 , 8.6621360000000003e+00 , -3.8506499999999999e-01 , -2.5721100000000002e-01 , 8.8632299999999997e-01 -2.6577769851250754e+00 , 5.5776370633620074e+00 , 8.5459263999999990e+00 , 9.5121499999999998e-02 , -4.0870800000000002e-01 , 9.0769500000000003e-01 -2.6129481271361978e+00 , 5.4539665679514489e+00 , 8.5338935999999990e+00 , -3.2458599999999999e-01 , 1.9289500000000001e-01 , -9.2597799999999997e-01 -2.5563303098652010e+00 , 4.9966782224438600e+00 , 7.8964568000000002e+00 , 1.0392600000000000e-01 , -8.9960300000000004e-01 , 4.2416199999999998e-01 -2.5194180356839389e+00 , 4.9094925773645954e+00 , 7.9196280000000003e+00 , 1.5572400000000000e-01 , -9.1499100000000000e-01 , 3.7221199999999999e-01 -2.4890121425958189e+00 , 5.3125411972226892e+00 , 8.9281056000000003e+00 , -7.9750399999999999e-01 , -5.6448699999999996e-01 , 2.1293699999999999e-01 -2.4448239484441041e+00 , 5.2811934912037417e+00 , 9.1056439999999998e+00 , -1.3907200000000000e-01 , -3.6961300000000002e-01 , 9.1871899999999995e-01 -2.3966693650908812e+00 , 5.3741091800042744e+00 , 9.5670712000000009e+00 , -7.0075699999999996e-01 , 4.3305299999999998e-02 , -7.1208400000000005e-01 -2.3590591565029215e+00 , 4.9636399281526948e+00 , 8.9183504000000013e+00 , 4.0589600000000003e-02 , -8.8184899999999999e-01 , 4.6978300000000001e-01 -2.3288268930995746e+00 , 4.6398449628782359e+00 , 8.4115688000000013e+00 , -2.9008000000000000e-01 , -3.5695399999999999e-01 , 8.8793999999999995e-01 -2.3398968592231149e+00 , 3.8892331637709727e+00 , 6.7858824000000002e+00 , -2.6220900000000003e-01 , 5.1119199999999998e-01 , 8.1849200000000000e-01 -2.3117480324142377e+00 , 3.8403275999363595e+00 , 6.8375600000000007e+00 , -1.4429000000000000e-01 , 7.6305500000000004e-01 , 6.3002199999999997e-01 -2.1997668515873001e+00 , 4.4853155916050937e+00 , 8.8028480000000009e+00 , 4.3623200000000001e-01 , 1.3720399999999999e-01 , -8.8931300000000002e-01 -2.1723215702329521e+00 , 4.3033249598328887e+00 , 8.5788215999999995e+00 , -9.9129199999999995e-01 , -7.1929499999999993e-02 , -1.1030500000000000e-01 -2.1362887819211305e+00 , 4.1975776440037205e+00 , 8.5575016000000002e+00 , -9.9129199999999995e-01 , -7.1929499999999993e-02 , -1.1030500000000000e-01 -2.2003085187404348e+00 , 3.6140282661765788e+00 , 6.9870495999999997e+00 , -6.4844700000000000e-01 , 2.8486899999999998e-01 , 7.0595100000000000e-01 -2.1729437227885633e+00 , 3.5507120108301446e+00 , 7.0042720000000003e+00 , -9.3993800000000002e-02 , 7.5904199999999999e-01 , 6.4422000000000001e-01 -2.1406666290108900e+00 , 3.5057554031700100e+00 , 7.0904568000000001e+00 , -5.6647000000000003e-01 , -7.2152000000000005e-01 , -3.9814800000000000e-01 -2.0001887133585687e+00 , 3.7859046835491479e+00 , 8.4509639999999990e+00 , -9.6314000000000000e-01 , 2.6155400000000001e-01 , 6.2861700000000006e-02 -2.1063249968610065e+00 , 3.3188331743953614e+00 , 6.8879168000000002e+00 , -5.7865299999999997e-01 , 1.1286200000000000e-01 , -8.0772699999999997e-01 -1.9312964144787368e+00 , 3.6000010000292892e+00 , 8.4463880000000007e+00 , -8.2534700000000005e-01 , 4.6898499999999999e-01 , -3.1441300000000000e-01 -1.9307348950867320e+00 , 3.4412661138499150e+00 , 8.1169264000000005e+00 , -4.4435700000000000e-01 , -8.4439699999999995e-01 , -2.9923400000000000e-01 -1.8815043485672045e+00 , 3.3854129698193498e+00 , 8.2718968000000004e+00 , 2.4488799999999999e-01 , 8.5221599999999997e-01 , 4.6234100000000000e-01 -1.8555106606215310e+00 , 3.2874521263830436e+00 , 8.2123048000000001e+00 , 8.4057800000000005e-01 , -4.8810900000000002e-01 , 2.3490100000000000e-01 -3.4289340714364962e+00 , 3.7759836067019759e+00 , 8.5908880000000010e-01 , -7.4208399999999994e-02 , 9.9321099999999996e-02 , 9.9228400000000005e-01 -3.4504112396105802e+00 , 3.8300097880101354e+00 , 8.6307200000000006e-01 , -5.6582800000000003e-02 , 1.0046900000000000e-01 , 9.9333000000000005e-01 -3.4833415908526080e+00 , 3.9001950717442395e+00 , 8.4422719999999996e-01 , -6.4410400000000007e-02 , 1.8368999999999999e-01 , 9.8087199999999997e-01 -3.5076272186426234e+00 , 3.9605207789540584e+00 , 8.4318720000000003e-01 , -3.9023500000000003e-02 , 1.5841900000000000e-01 , 9.8660099999999995e-01 -3.5370017124233097e+00 , 4.0278841729464077e+00 , 8.3593840000000008e-01 , -9.6072099999999994e-02 , 1.4126100000000000e-01 , 9.8529999999999995e-01 -3.5661487959076110e+00 , 4.0956365410729845e+00 , 8.3061359999999995e-01 , -7.4346599999999999e-02 , 1.3925100000000001e-01 , 9.8746199999999995e-01 -3.5982108125923951e+00 , 4.1695296224575404e+00 , 8.1945439999999992e-01 , -5.4442800000000000e-02 , 1.2686800000000001e-01 , 9.9042399999999997e-01 -3.6269329574663605e+00 , 4.2391165371050441e+00 , 8.1787359999999998e-01 , -3.5868999999999998e-02 , 1.9867299999999999e-01 , 9.7940899999999997e-01 -3.6679023265033246e+00 , 4.3285359287168923e+00 , 7.9611679999999985e-01 , -5.9309599999999997e-02 , 1.8471199999999999e-01 , 9.8100100000000001e-01 -3.7002776759172509e+00 , 4.4058563788941001e+00 , 7.9155120000000001e-01 , -6.3777799999999996e-02 , 1.7166600000000001e-01 , 9.8308899999999999e-01 -3.7375555280206854e+00 , 4.4905056953860516e+00 , 7.8220160000000005e-01 , -8.8873199999999999e-02 , 1.4924200000000001e-01 , 9.8479899999999998e-01 -3.7704417384777056e+00 , 4.5698079419692128e+00 , 7.8231600000000001e-01 , -4.9668299999999999e-02 , 1.9351099999999999e-01 , 9.7984000000000004e-01 -3.8225698791478226e+00 , 4.6842722705759732e+00 , 7.5016959999999999e-01 , -5.3607599999999998e-02 , 1.9089400000000001e-01 , 9.8014599999999996e-01 -3.8640908523433359e+00 , 4.7796079815074890e+00 , 7.4210959999999981e-01 , -8.8012699999999999e-02 , 1.6632900000000000e-01 , 9.8213499999999998e-01 -3.9042212052926493e+00 , 4.8755743908224334e+00 , 7.3685759999999978e-01 , -5.2712299999999997e-02 , 1.8799600000000000e-01 , 9.8075400000000001e-01 -3.9573005368171650e+00 , 4.9952401746831114e+00 , 7.1497599999999983e-01 , -1.6798199999999999e-02 , 1.9334499999999999e-01 , 9.8098700000000005e-01 -4.0099065904123403e+00 , 5.1157226114208445e+00 , 6.9703599999999999e-01 , -3.1357799999999998e-02 , 1.8894400000000000e-01 , 9.8148700000000000e-01 -4.0631299786351605e+00 , 5.2380280319208481e+00 , 6.8297520000000000e-01 , -2.7328700000000001e-02 , 1.7074700000000001e-01 , 9.8493600000000003e-01 -4.1239315313440033e+00 , 5.3763967987516388e+00 , 6.6069840000000002e-01 , -3.8464600000000002e-02 , 1.9317899999999999e-01 , 9.8040899999999997e-01 -4.1892413643220374e+00 , 5.5238821472781332e+00 , 6.3719440000000005e-01 , -4.1363400000000002e-02 , 2.0725099999999999e-01 , 9.7741299999999998e-01 -4.2670322622214663e+00 , 5.6969563745426237e+00 , 6.0109600000000007e-01 , -4.2521000000000003e-02 , 1.9369800000000001e-01 , 9.8013899999999998e-01 -4.3322251250427737e+00 , 5.8486307870674867e+00 , 5.8782559999999995e-01 , -5.9639800000000000e-02 , 1.8264800000000000e-01 , 9.8136800000000002e-01 -4.4097760499126011e+00 , 6.0261344325133033e+00 , 5.6308399999999992e-01 , -4.6829099999999999e-02 , 1.8065899999999999e-01 , 9.8243000000000003e-01 -4.4916296002063012e+00 , 6.2141879731880723e+00 , 5.3891439999999990e-01 , -5.5907600000000002e-02 , 1.8523700000000001e-01 , 9.8110200000000003e-01 -4.5855264820989525e+00 , 6.4275294291837533e+00 , 5.0582159999999998e-01 , 4.9665800000000003e-02 , -1.8054000000000001e-01 , -9.8231299999999999e-01 -4.6835755684670737e+00 , 6.6527910097389311e+00 , 4.7480880000000014e-01 , 2.7769300000000002e-01 , -7.4546100000000004e-02 , -9.5777299999999999e-01 -4.7944411062857260e+00 , 6.9048661113619625e+00 , 4.3730639999999976e-01 , -1.4238300000000001e-01 , -1.6819199999999999e-02 , 9.8966900000000002e-01 -4.9004261675606813e+00 , 7.1513358784770062e+00 , 4.1311600000000004e-01 , -3.0547999999999999e-02 , 2.1956500000000001e-01 , 9.7511899999999996e-01 -5.0229427149520349e+00 , 7.4344557060021401e+00 , 3.7933679999999992e-01 , 3.7698099999999998e-02 , 2.5069999999999998e-01 , 9.6733000000000002e-01 -4.8499347570196605e+00 , 7.1383099320446695e+00 , 6.5389680000000006e-01 , -9.7572199999999998e-01 , -6.3841800000000004e-02 , -2.0949999999999999e-01 -4.7742504036134488e+00 , 7.0295971545132145e+00 , 8.2019279999999983e-01 , -9.6787599999999996e-01 , -7.8568100000000002e-02 , -2.3883799999999999e-01 -4.7498394853979296e+00 , 7.0205103220598657e+00 , 9.3326160000000002e-01 , 9.8796700000000004e-01 , 8.9902700000000002e-02 , 1.2585299999999999e-01 -4.7368524979926763e+00 , 7.0348986138575675e+00 , 1.0335176000000001e+00 , 9.9781799999999998e-01 , 5.4655799999999997e-02 , 3.7042300000000000e-02 -4.7276280890805635e+00 , 7.0557480064564446e+00 , 1.1297831199999999e+00 , 9.9795800000000001e-01 , 5.2741700000000002e-02 , -3.6041600000000000e-02 -4.7258507152502300e+00 , 7.0928888407156165e+00 , 1.2188632799999999e+00 , 9.8081399999999996e-01 , 9.1643299999999997e-02 , 1.7206500000000000e-01 -4.7286938960108946e+00 , 7.1367601998571137e+00 , 1.3054911200000001e+00 , -9.0287099999999998e-01 , -1.3575899999999999e-01 , -4.0791300000000003e-01 -4.6355445164170526e+00 , 6.9833343731759365e+00 , 1.4621764800000001e+00 , -8.9266900000000005e-01 , -2.9787700000000000e-01 , -3.3824700000000002e-01 -4.6328129243125744e+00 , 7.0148699005813056e+00 , 1.5496269599999999e+00 , -8.7002699999999999e-01 , -4.8198200000000002e-01 , -1.0366499999999999e-01 -4.8403671296009882e+00 , 7.6245536389906992e+00 , 1.7793442399999999e+00 , 7.8678400000000004e-01 , 6.5656500000000007e-02 , -6.1372700000000002e-01 -1.6433279152348980e+01 , 3.3714092300584866e+01 , -2.8497488000000004e+00 , -8.3033100000000004e-01 , -4.1195099999999998e-02 , 5.5574599999999996e-01 -1.6385569340065373e+01 , 3.3864124478852943e+01 , -2.2626064000000001e+00 , -9.6833899999999995e-01 , -1.9818500000000000e-01 , -1.5179799999999999e-01 -1.7211465180227385e+01 , 3.6004118047954279e+01 , -1.9739544000000002e+00 , -3.3969899999999997e-01 , 6.1620200000000000e-02 , 9.3851399999999996e-01 -2.2508798757454770e+01 , 4.8438107730193984e+01 , -2.9572640000000003e+00 , -2.4293200000000001e-01 , 1.0046400000000000e-01 , 9.6482699999999999e-01 -2.2356271606372715e+01 , 4.8463430023115251e+01 , -2.0789736000000003e+00 , -2.4293200000000001e-01 , 1.0046400000000000e-01 , 9.6482699999999999e-01 -1.5159396687305724e+01 , 3.2053975106888188e+01 , 3.2291680000000000e-01 , 5.0042200000000003e-01 , 2.8387899999999999e-01 , 8.1791800000000003e-01 -1.4613062525698252e+01 , 3.1013552073054040e+01 , 9.6086424000000004e-01 , -9.0242599999999995e-01 , -1.0528000000000000e-01 , -4.1778399999999999e-01 -1.4725739338821278e+01 , 3.1519323250509260e+01 , 1.4714376800000000e+00 , -9.0242599999999995e-01 , -1.0528000000000000e-01 , -4.1778399999999999e-01 -1.4804446035617893e+01 , 3.1950825167157806e+01 , 2.0014494375999998e+00 , -9.6490299999999996e-01 , -4.1864600000000002e-02 , -2.5924900000000001e-01 -1.3478764760019953e+01 , 2.9003535383811581e+01 , 2.6056169599999999e+00 , 6.2964299999999995e-01 , 4.7125600000000001e-01 , 6.1763000000000001e-01 -1.3580056308383577e+01 , 2.9471768394205018e+01 , 3.1015264000000000e+00 , 2.4447600000000000e-01 , 9.6291599999999999e-01 , 1.1412700000000001e-01 -1.3575849569739328e+01 , 2.9693014843121105e+01 , 3.6084432000000000e+00 , -8.2502900000000001e-01 , -5.4073700000000002e-01 , 1.6410400000000000e-01 -1.3415692982721716e+01 , 2.9530876672553934e+01 , 4.1081528000000000e+00 , -3.7145800000000001e-01 , -9.2326299999999994e-01 , 9.7997000000000001e-02 -1.3373856536995778e+01 , 2.9657692935994472e+01 , 4.6179400000000008e+00 , 1.5507099999999999e-01 , 9.8671299999999995e-01 , 4.8476900000000003e-02 -1.3403451748922150e+01 , 2.9970789686649976e+01 , 5.1454592000000003e+00 , -1.1196500000000000e-01 , -9.7755099999999995e-01 , 1.7848700000000001e-01 -1.3261808405711031e+01 , 2.9850287477027173e+01 , 5.6446696000000003e+00 , -2.4544700000000000e-01 , -9.6866300000000005e-01 , -3.8040600000000001e-02 -1.3243973899360546e+01 , 3.0049246236530831e+01 , 6.1751944000000005e+00 , -4.7588599999999998e-01 , -8.3204500000000003e-01 , -2.8501500000000002e-01 -1.3652880509579578e+01 , 3.1613716689127227e+01 , 7.4346031999999997e+00 , 2.4186099999999999e-01 , 8.1548100000000001e-01 , 5.2582700000000004e-01 -1.3138222584658125e+01 , 3.0525914319740423e+01 , 7.7963880000000003e+00 , -9.2114399999999996e-01 , -1.1277700000000000e-01 , -3.7252600000000002e-01 -1.3033496785879580e+01 , 3.0507019884628573e+01 , 8.3182599999999987e+00 , -8.2153900000000002e-01 , -2.1591600000000000e-01 , -5.2768800000000005e-01 -1.2892630241787890e+01 , 3.0393678745814533e+01 , 8.8218280000000000e+00 , -9.4677500000000003e-01 , -3.1945899999999999e-01 , 3.9540699999999998e-02 -1.2933100917928085e+01 , 3.0767767905097120e+01 , 9.4328591999999993e+00 , -9.4677500000000003e-01 , -3.1945899999999999e-01 , 3.9540699999999998e-02 -1.2865748544830522e+01 , 3.0855561072474359e+01 , 9.9910063999999998e+00 , -8.9940699999999996e-01 , -1.9318099999999999e-01 , 3.9210699999999998e-01 -1.3715047023887095e+01 , 3.3477923286009357e+01 , 1.1219287999999999e+01 , -3.9707700000000001e-01 , -7.1668299999999996e-01 , -5.7331900000000002e-01 -1.3666152483554209e+01 , 3.3652121813183484e+01 , 1.1862964800000000e+01 , 6.4321799999999996e-01 , 6.6234400000000004e-01 , 3.8414999999999999e-01 -1.3494242644940238e+01 , 3.3484099337652040e+01 , 1.2414976000000001e+01 , -7.9161999999999999e-01 , -6.0878600000000005e-01 , -5.2122599999999998e-02 -1.3475053697731669e+01 , 3.3748893332842684e+01 , 1.3103351999999999e+01 , -9.1412599999999999e-01 , -3.0645299999999998e-01 , 2.6544400000000001e-01 -1.3233781124761489e+01 , 3.3383337085224959e+01 , 1.3593192000000000e+01 , -7.4373699999999998e-01 , -4.6533200000000002e-01 , 4.7991800000000001e-01 -5.2436185954159473e+00 , 1.0692358384948097e+01 , 6.3881760000000005e+00 , -5.5842799999999998e-02 , -8.8125500000000001e-01 , 4.6933000000000002e-01 -5.1085383587849336e+00 , 1.0380916379765704e+01 , 6.4262087999999995e+00 , 1.5154599999999999e-01 , 9.6550100000000005e-01 , -2.1176000000000000e-01 -5.2276748146238790e+00 , 1.0835714012939377e+01 , 6.7905936000000002e+00 , -9.1755699999999996e-02 , -9.8849699999999996e-01 , 1.2022900000000000e-01 -5.1035899405443530e+00 , 1.0556457210306625e+01 , 6.8379240000000001e+00 , -6.0968000000000000e-01 , 7.9070099999999999e-01 , -5.5520800000000002e-02 -5.1420253886437974e+00 , 1.0773019584283535e+01 , 7.1146783999999998e+00 , -4.2243999999999998e-01 , -8.7466999999999995e-01 , -2.3769000000000001e-01 -4.9507776009295243e+00 , 1.0278571675378586e+01 , 7.0440624000000005e+00 , 3.0601499999999998e-01 , -9.5196400000000003e-01 , 1.0932300000000001e-02 -4.9953393596826210e+00 , 1.0522809220258218e+01 , 7.3435199999999998e+00 , 4.5726400000000000e-01 , 8.7726400000000004e-01 , 1.4600700000000000e-01 -4.9566195918626157e+00 , 1.0505473632303813e+01 , 7.5127176000000002e+00 , -8.7474099999999999e-02 , 9.8467700000000002e-01 , -1.5086600000000000e-01 -4.5889260883089005e+00 , 9.4106298262307497e+00 , 7.0701456000000000e+00 , -1.4214800000000000e-01 , 3.7450299999999997e-01 , 9.1626500000000000e-01 -4.5154887901989387e+00 , 9.2661235834172686e+00 , 7.1436008000000006e+00 , 1.7693100000000000e-01 , 4.3568600000000002e-01 , 8.8253800000000004e-01 -4.4249774897622292e+00 , 9.0598990022950936e+00 , 7.1758512000000003e+00 , -3.0623699999999998e-01 , -9.4827399999999995e-01 , 8.3640400000000004e-02 -4.3833149675476371e+00 , 9.0165629000670613e+00 , 7.3049672000000001e+00 , -4.1493400000000003e-01 , -8.8527400000000006e-02 , -9.0553499999999998e-01 -4.2002976549846229e+00 , 8.4827167932410852e+00 , 7.1090832000000006e+00 , -2.7931899999999998e-01 , 6.1941299999999999e-01 , -7.3369499999999999e-01 -4.0304974467544668e+00 , 7.9800418680098808e+00 , 6.9125960000000006e+00 , -1.6360100000000000e-01 , 2.8266700000000000e-01 , 9.4516400000000000e-01 -3.9561859804812354e+00 , 7.8070256534906575e+00 , 6.9286744000000002e+00 , 1.3892299999999999e-01 , -3.9941900000000002e-01 , -9.0618100000000001e-01 -3.9101479704441564e+00 , 7.7333450053817687e+00 , 7.0116871999999999e+00 , 2.6853599999999998e-02 , -4.6897000000000000e-01 , -8.8280599999999998e-01 -4.0726577557538519e+00 , 8.4344738121702765e+00 , 7.6856488000000001e+00 , 2.6813599999999999e-01 , 3.7652500000000000e-01 , 8.8675400000000004e-01 -3.9908873270793408e+00 , 8.2372157067368441e+00 , 7.6904536000000006e+00 , -6.1785599999999996e-01 , -4.8260999999999998e-01 , -6.2075899999999995e-01 -3.9346799437293036e+00 , 8.1360696361767779e+00 , 7.7667168000000002e+00 , -6.7879100000000003e-01 , -5.8384999999999998e-01 , -4.4537900000000002e-01 -3.9150814454780232e+00 , 8.1735984942150210e+00 , 7.9593351999999999e+00 , 5.9043400000000001e-01 , 6.5043300000000004e-01 , 4.7783199999999998e-01 -3.7775289211390182e+00 , 7.7455758706055118e+00 , 7.7502744000000003e+00 , 4.3839400000000001e-01 , 2.6391000000000001e-02 , 8.9839500000000005e-01 -3.8118686412006664e+00 , 8.0084125543864619e+00 , 8.1451728000000010e+00 , -7.0003700000000002e-01 , 6.8395399999999995e-01 , -2.0531400000000000e-01 -3.7993825591814510e+00 , 8.0889060639343100e+00 , 8.3891880000000008e+00 , 8.3896999999999999e-01 , -4.7701100000000002e-01 , 2.6189600000000002e-01 -3.7738595433363811e+00 , 8.1176042770538110e+00 , 8.5946920000000002e+00 , -8.5492199999999996e-01 , 4.6836000000000000e-01 , -2.2304199999999999e-01 -3.7370892977757437e+00 , 8.1058847466276216e+00 , 8.7658552000000007e+00 , 8.5992500000000005e-01 , -4.7729500000000002e-01 , 1.8087900000000001e-01 -3.3888761148583395e+00 , 6.6797929773288400e+00 , 7.4843776000000002e+00 , -7.9757000000000000e-01 , -1.3519500000000001e-01 , -5.8788099999999999e-01 -3.5979575018623731e+00 , 7.7885173066813040e+00 , 8.8105127999999997e+00 , -8.3138599999999996e-01 , 5.3123299999999996e-01 , -1.6305900000000001e-01 -3.5442340195471336e+00 , 7.7000355542777470e+00 , 8.9027400000000014e+00 , -7.8863000000000005e-01 , 5.4097399999999995e-01 , -2.9225200000000001e-01 -3.4742639552072476e+00 , 7.5273794208232072e+00 , 8.9004311999999999e+00 , -4.3072899999999997e-01 , 7.9654000000000003e-01 , -4.2425900000000000e-01 -3.1910219206242489e+00 , 6.2464653137134434e+00 , 7.5892511999999996e+00 , -2.4113200000000001e-02 , -1.0410700000000001e-01 , 9.9427399999999999e-01 -3.1478309147336851e+00 , 6.1627184233568366e+00 , 7.6386615999999998e+00 , -1.0606699999999999e-01 , -1.6499600000000000e-01 , 9.8057499999999997e-01 -3.0737412520732383e+00 , 5.9053218858121745e+00 , 7.4678936000000009e+00 , -5.3166800000000003e-01 , -8.3385699999999996e-01 , -1.4836500000000000e-01 -3.0300417828345712e+00 , 5.8116244305719231e+00 , 7.4941744000000003e+00 , 5.6032499999999996e-01 , 8.2154400000000005e-01 , 1.0536200000000000e-01 -3.0062814509282512e+00 , 5.8354484760894572e+00 , 7.6758832000000004e+00 , -3.9011299999999999e-01 , 6.9937300000000002e-01 , 5.9890699999999997e-01 -2.9629465541063573e+00 , 5.7450826612008843e+00 , 7.7082480000000002e+00 , -2.6154600000000000e-01 , -7.7263800000000005e-01 , -5.7846799999999998e-01 -2.9295799442196540e+00 , 5.7194516248763687e+00 , 7.8321224000000003e+00 , -5.4797399999999996e-01 , -5.0615600000000005e-01 , -6.6598100000000005e-01 -2.8903084344445578e+00 , 5.6570962237760281e+00 , 7.9042984000000001e+00 , 8.3918099999999995e-01 , 2.7715600000000001e-01 , 4.6793099999999999e-01 -2.8560318794925488e+00 , 5.6370534015041542e+00 , 8.0451872000000009e+00 , -8.3223300000000000e-01 , -3.7754799999999999e-01 , -4.0601199999999998e-01 -2.9275619722135384e+00 , 6.5537874846432755e+00 , 9.6802960000000002e+00 , -4.7616100000000000e-01 , -4.9733699999999997e-01 , -7.2520799999999996e-01 -2.8138901879042342e+00 , 5.8834208869309350e+00 , 8.8163160000000005e+00 , -7.0466099999999998e-01 , -9.4787700000000003e-02 , 7.0318400000000003e-01 -2.7573247847522149e+00 , 5.7090782303670018e+00 , 8.7294552000000003e+00 , -1.0129800000000000e-01 , -5.6581199999999998e-01 , 8.1828800000000002e-01 -2.6987219706183390e+00 , 5.4720223128206342e+00 , 8.5206128000000003e+00 , -3.2458599999999999e-01 , 1.9289500000000001e-01 , -9.2597799999999997e-01 -2.6407474134005819e+00 , 5.1918730120554084e+00 , 8.2139480000000002e+00 , -1.9679599999999998e-02 , 9.1919399999999996e-01 , 3.9331199999999999e-01 -2.6069795311778474e+00 , 5.2498325004419666e+00 , 8.5260728000000015e+00 , -5.6501999999999997e-01 , -4.4980300000000001e-02 , -8.2385100000000000e-01 -2.5642448151851083e+00 , 5.1913698625728113e+00 , 8.6272960000000012e+00 , -9.8949799999999999e-01 , 1.1972600000000000e-01 , -8.0994099999999999e-02 -2.5214604666063369e+00 , 5.1981686477268054e+00 , 8.8679936000000001e+00 , 5.8890799999999999e-01 , 7.2265999999999997e-01 , -3.6186900000000000e-01 -2.4763920105778792e+00 , 5.1625782901043964e+00 , 9.0348720000000000e+00 , -1.0506500000000001e-01 , 5.4381000000000002e-01 , -8.3260599999999996e-01 -2.4308238161382905e+00 , 4.8991102681016301e+00 , 8.6976936000000009e+00 , -5.5674800000000003e-02 , -4.6782299999999999e-01 , 8.8206700000000005e-01 -2.3890092583996907e+00 , 4.6913496171345042e+00 , 8.4586912000000005e+00 , -4.0899400000000002e-01 , -3.3604400000000001e-01 , 8.4841000000000000e-01 -2.3797129960590420e+00 , 3.9155455040171225e+00 , 6.7984976000000001e+00 , -2.3055200000000001e-01 , 3.8881800000000000e-01 , 8.9200100000000004e-01 -2.3506022747018398e+00 , 3.8596748022005092e+00 , 6.8311952000000007e+00 , -1.4304600000000001e-01 , 6.2366600000000005e-01 , 7.6849100000000004e-01 -2.2787147530226122e+00 , 4.2720995938568045e+00 , 8.1303424000000000e+00 , 7.4910800000000000e-01 , -6.2486399999999998e-01 , -2.1995999999999999e-01 -2.2298864997036549e+00 , 4.2771426426669343e+00 , 8.4031967999999999e+00 , 9.0119499999999997e-01 , 7.0146699999999998e-03 , 4.3335800000000002e-01 -2.1776457855089291e+00 , 4.2740340500486322e+00 , 8.6770080000000007e+00 , -9.4943800000000000e-01 , -5.8520299999999997e-02 , 3.0845200000000000e-01 -2.2291658040101909e+00 , 3.6575700607014987e+00 , 7.0406719999999998e+00 , 7.8786299999999998e-01 , -3.8361500000000000e-02 , -6.1465400000000003e-01 -2.2023698074017579e+00 , 3.5759475010480637e+00 , 6.9987808000000005e+00 , -3.9079199999999997e-01 , 5.9071200000000001e-01 , 7.0593200000000000e-01 -2.1715959341952042e+00 , 3.5208008140597511e+00 , 7.0452480000000008e+00 , -1.8777600000000000e-01 , -8.0066800000000005e-01 , -5.6892100000000001e-01 -2.1335587923713009e+00 , 3.4892249862423426e+00 , 7.1808015999999997e+00 , -7.1048699999999998e-01 , -7.0055599999999996e-01 , -6.6548999999999997e-02 -2.0463555954630577e+00 , 3.5892616586927026e+00 , 7.8695104000000002e+00 , -4.9560300000000002e-01 , -8.5576700000000006e-01 , -1.4846500000000001e-01 -1.9660882970004134e+00 , 3.6254009887448664e+00 , 8.3796096000000002e+00 , 5.8962400000000004e-01 , -4.3554300000000001e-01 , 6.8018100000000004e-01 -1.9561990109932523e+00 , 3.4794297852903004e+00 , 8.1115183999999996e+00 , -6.2177899999999997e-01 , -7.6107199999999997e-01 , -1.8482599999999999e-01 -1.9098156205284984e+00 , 3.4154098925990892e+00 , 8.2160176000000007e+00 , -7.0107500000000000e-01 , 4.4034299999999998e-01 , -5.6088400000000005e-01 -1.8829547526738208e+00 , 3.3175809972882710e+00 , 8.1463584000000004e+00 , -6.0027399999999997e-01 , 5.9046900000000002e-01 , -5.3946099999999997e-01 -1.8442585420750623e+00 , 3.2383001075806463e+00 , 8.1767679999999991e+00 , -6.5558899999999998e-01 , -7.5474600000000003e-01 , -2.3717200000000001e-02 -3.4685696904612069e+00 , 3.7314274315603861e+00 , 8.6248959999999997e-01 , -1.0576900000000000e-01 , 9.9296599999999999e-02 , 9.8942099999999999e-01 -3.4911125557395106e+00 , 3.7842795307240356e+00 , 8.6608799999999997e-01 , 8.9219599999999996e-02 , -1.5660600000000000e-01 , -9.8362300000000003e-01 -3.5177233714757028e+00 , 3.8430285527354227e+00 , 8.6297839999999981e-01 , -8.1833400000000001e-02 , 1.6410700000000000e-01 , 9.8304199999999997e-01 -3.5451716398121427e+00 , 3.9020958961289662e+00 , 8.6160559999999986e-01 , -5.3113300000000002e-02 , 1.8171599999999999e-01 , 9.8191600000000001e-01 -3.5798240036202165e+00 , 3.9728424795712280e+00 , 8.4594320000000001e-01 , -8.2294400000000004e-02 , 1.3621100000000000e-01 , 9.8725600000000002e-01 -3.6058746190197488e+00 , 4.0336745288178681e+00 , 8.4777360000000002e-01 , -8.4380499999999997e-02 , 1.3720700000000000e-01 , 9.8694199999999999e-01 -3.6411681390675721e+00 , 4.1072782427290147e+00 , 8.3588639999999992e-01 , 5.3171099999999999e-02 , -1.6750499999999999e-01 , -9.8443599999999998e-01 -3.6720249762644706e+00 , 4.1756000370951183e+00 , 8.3374400000000004e-01 , -3.8269200000000003e-02 , 1.4824599999999999e-01 , 9.8821000000000003e-01 -3.7109582100453515e+00 , 4.2558521763673092e+00 , 8.1876799999999994e-01 , -4.9299400000000000e-02 , 1.8617200000000000e-01 , 9.8128000000000004e-01 -3.7506985779823268e+00 , 4.3386661342540922e+00 , 8.0613199999999985e-01 , -6.5032099999999995e-02 , 1.8846299999999999e-01 , 9.7992500000000005e-01 -3.7891076918921023e+00 , 4.4220273209367802e+00 , 7.9589839999999978e-01 , -9.1817399999999993e-02 , 1.5787200000000001e-01 , 9.8318200000000000e-01 -3.8283021845069074e+00 , 4.5069059868350383e+00 , 7.8811919999999991e-01 , -7.4027800000000005e-02 , 1.7099700000000001e-01 , 9.8248700000000000e-01 -3.8723315489480585e+00 , 4.5992377594052005e+00 , 7.7616960000000002e-01 , -6.0832499999999998e-02 , 2.1360999999999999e-01 , 9.7502299999999997e-01 -3.9149744254650907e+00 , 4.6921798449739729e+00 , 7.6701759999999997e-01 , -9.0154100000000001e-02 , 1.8223300000000001e-01 , 9.7911400000000004e-01 -3.9634792878243732e+00 , 4.7936852230722149e+00 , 7.5412159999999995e-01 , -8.4503400000000006e-02 , 1.8586800000000001e-01 , 9.7893399999999997e-01 -4.0157082837012723e+00 , 4.9038829403506190e+00 , 7.3774159999999989e-01 , -4.4907599999999999e-02 , 2.0758299999999999e-01 , 9.7718600000000000e-01 -4.0756084268418409e+00 , 5.0289000811474684e+00 , 7.1224080000000001e-01 , -1.6067800000000000e-02 , 1.8081300000000000e-01 , 9.8338599999999998e-01 -4.1320527279894250e+00 , 5.1487174019205550e+00 , 6.9713999999999987e-01 , -2.8067300000000000e-02 , 1.9167699999999999e-01 , 9.8105699999999996e-01 -4.1981516135676245e+00 , 5.2845626846536708e+00 , 6.7398960000000008e-01 , -2.9560599999999999e-02 , 1.6995399999999999e-01 , 9.8500900000000002e-01 -4.2587386225930661e+00 , 5.4152476640558618e+00 , 6.6097919999999988e-01 , -5.3822299999999997e-02 , 1.8929199999999999e-01 , 9.8044500000000001e-01 -4.3329010436731021e+00 , 5.5703108016039824e+00 , 6.3481279999999995e-01 , -4.5791600000000002e-02 , 2.2176199999999999e-01 , 9.7402500000000003e-01 -4.4114447479401688e+00 , 5.7346982307924925e+00 , 6.0840719999999981e-01 , -7.1110000000000007e-02 , 1.8956600000000001e-01 , 9.7928999999999999e-01 -4.4893770121829437e+00 , 5.9012644156572307e+00 , 5.8746160000000014e-01 , -5.3477900000000002e-02 , 1.9552500000000000e-01 , 9.7924000000000000e-01 -4.5805384076331368e+00 , 6.0928177016002651e+00 , 5.5629280000000003e-01 , -6.2941600000000000e-02 , 1.8553900000000001e-01 , 9.8061900000000002e-01 -4.6631325054410224e+00 , 6.2721925707304225e+00 , 5.4191999999999996e-01 , 5.8948100000000003e-02 , -1.9244400000000000e-01 , -9.7953599999999996e-01 -4.7726089700664929e+00 , 6.5008105248886832e+00 , 5.0364799999999987e-01 , 3.0219499999999999e-01 , -1.6569500000000001e-01 , -9.3873499999999999e-01 -4.8821967090392073e+00 , 6.7321251395186463e+00 , 4.7349839999999999e-01 , -7.5224399999999997e-02 , 1.4436599999999999e-01 , 9.8666100000000001e-01 -4.9947537532475543e+00 , 6.9745470708658734e+00 , 4.4641679999999995e-01 , -1.9568300000000000e-02 , 2.6683499999999999e-02 , 9.9945200000000001e-01 -5.1171156370679434e+00 , 7.2356060227352286e+00 , 4.1910639999999999e-01 , 2.9694999999999999e-01 , 1.4254400000000000e-01 , 9.4419399999999998e-01 -4.8534827117130881e+00 , 6.7964573091816973e+00 , 7.7089680000000005e-01 , 9.9079600000000001e-01 , 9.2256800000000000e-02 , 9.9055900000000002e-02 -4.8282376390118138e+00 , 6.7881351993538122e+00 , 8.8231199999999999e-01 , 9.8787000000000003e-01 , 9.4017600000000007e-02 , 1.2358600000000000e-01 -4.8166294107451755e+00 , 6.8040975853919203e+00 , 9.8016144000000005e-01 , 9.8749399999999998e-01 , 9.8322499999999993e-02 , 1.2324499999999999e-01 -4.8001805486307934e+00 , 6.8093373473504464e+00 , 1.0816893599999999e+00 , 9.9420699999999995e-01 , 8.3689500000000000e-02 , 6.7444199999999996e-02 -4.7913385010314116e+00 , 6.8306038171922019e+00 , 1.1748161600000000e+00 , 9.9779899999999999e-01 , 6.4025899999999997e-02 , -1.7252799999999999e-02 -4.7861349352116367e+00 , 6.8574254756949724e+00 , 1.2646607200000000e+00 , 9.9243099999999995e-01 , 9.0659900000000002e-02 , 8.2829000000000000e-02 -4.7941781237282619e+00 , 6.9102989600598796e+00 , 1.3443767200000001e+00 , -9.5731800000000000e-01 , -1.6371100000000000e-01 , -2.3820300000000000e-01 -4.7292863343082745e+00 , 6.8207948280330726e+00 , 1.4765451199999999e+00 , -9.4070299999999996e-01 , -2.9394900000000002e-01 , -1.6932900000000001e-01 -4.7362248836023548e+00 , 6.8694332348747196e+00 , 1.5560458399999999e+00 , -9.1149400000000003e-01 , -3.5637099999999999e-01 , 2.0537300000000000e-01 -4.8736643550365804e+00 , 7.2539363047015835e+00 , 1.7335686400000001e+00 , 5.2080300000000002e-01 , 3.7303799999999998e-02 , -8.5286200000000001e-01 -4.9077849085876526e+00 , 7.3636361046653400e+00 , 1.8056926400000000e+00 , -4.1872999999999999e-01 , -2.9366300000000001e-02 , 9.0763600000000000e-01 -5.0317735569252786e+00 , 7.6547795312883844e+00 , 1.8384266400000000e+00 , -3.8423299999999999e-01 , 1.5963700000000001e-02 , 9.2309799999999997e-01 -1.4770778252005284e+01 , 2.7868326236470057e+01 , -1.9149864000000001e+00 , -2.7100500000000000e-01 , 8.3074499999999996e-01 , -4.8623000000000000e-01 -1.4758120141970446e+01 , 2.8045413411641903e+01 , -1.4396960000000001e+00 , 3.4387800000000002e-01 , -7.7979500000000002e-01 , 5.2313200000000004e-01 -1.4715504190177610e+01 , 2.8158276680196344e+01 , -9.5161359999999995e-01 , 3.1652199999999998e-02 , -8.8150799999999996e-01 , 4.7110800000000003e-01 -1.7050060296942824e+01 , 3.3549000962491363e+01 , -5.8088480000000020e-01 , 7.3124999999999996e-01 , 1.5787799999999999e-01 , 6.6358700000000004e-01 -1.6258905732354517e+01 , 3.2095611794747541e+01 , 1.6321439999999998e-01 , 3.6738399999999999e-01 , 3.7956099999999998e-01 , 8.4909500000000004e-01 -1.5201312535254580e+01 , 3.0040658204597168e+01 , 8.9538479999999998e-01 , -2.7768399999999999e-01 , -6.8267500000000003e-01 , -6.7590499999999998e-01 -1.5058208957419358e+01 , 2.9948298875048060e+01 , 1.4285823999999998e+00 , -4.3882100000000002e-01 , -7.6229199999999997e-01 , -4.7575899999999999e-01 -1.4911537992549169e+01 , 2.9847363872595757e+01 , 1.9560337919999999e+00 , 9.7687700000000000e-01 , 1.4890900000000001e-01 , 1.5341800000000000e-01 -1.4890727109714613e+01 , 3.0022267822704517e+01 , 2.4715432800000001e+00 , 8.7980299999999997e-02 , -9.8623899999999998e-01 , 1.3997499999999999e-01 -1.4890269624523571e+01 , 3.0244910974360483e+01 , 2.9917388000000003e+00 , -8.8674000000000003e-02 , 9.8702400000000001e-01 , -1.3386799999999999e-01 -1.4847568153416557e+01 , 3.0374947576151268e+01 , 3.5174327999999999e+00 , -9.0037000000000006e-02 , 9.8213700000000004e-01 , -1.6522999999999999e-01 -1.4633288978096269e+01 , 3.0115460408530094e+01 , 4.0335536000000003e+00 , -5.7431500000000003e-02 , 9.7097500000000003e-01 , 2.3218200000000000e-01 -1.4549508802714966e+01 , 3.0151853291860196e+01 , 4.5547392000000002e+00 , -1.8459199999999999e-02 , 9.9980400000000003e-01 , -7.0968699999999999e-03 -1.4510772758443883e+01 , 3.0294260286611955e+01 , 5.0843384000000000e+00 , 2.1984600000000001e-01 , 9.6055299999999999e-01 , -1.7031199999999999e-01 -1.4411647305362189e+01 , 3.0294328458073988e+01 , 5.6065952000000001e+00 , 1.2408000000000000e-01 , 8.9210500000000004e-01 , -4.3445600000000001e-01 -1.4704999283831588e+01 , 3.1220649242575821e+01 , 6.2295967999999995e+00 , -9.4594100000000003e-01 , -3.1578000000000001e-01 , 7.4014300000000005e-02 -1.4618417471511393e+01 , 3.1259869893658514e+01 , 6.7747544000000000e+00 , 8.2871499999999998e-01 , 9.5918799999999999e-02 , 5.5139000000000005e-01 -1.3724621282318592e+01 , 2.9371081996359184e+01 , 7.0386543999999995e+00 , -7.5017599999999995e-01 , -6.3365000000000005e-01 , -1.8900500000000001e-01 -1.3507277614869320e+01 , 2.9082216395423909e+01 , 7.4979496000000001e+00 , -7.9002600000000001e-01 , -5.6276199999999998e-01 , -2.4322199999999999e-01 -1.3386625306351634e+01 , 2.9023059278241327e+01 , 7.9900359999999999e+00 , -7.9982200000000003e-01 , -5.5024099999999998e-01 , -2.3983199999999999e-01 -1.3278315602311466e+01 , 2.8994100208457731e+01 , 8.4874992000000002e+00 , -7.6793599999999995e-01 , -6.3267600000000002e-01 , 9.9977999999999997e-02 -1.3280776652157044e+01 , 2.9239513061588244e+01 , 9.0472895999999992e+00 , -9.0631899999999999e-01 , -3.9561900000000000e-01 , 1.4856300000000000e-01 -1.3235926428876517e+01 , 2.9372297546945855e+01 , 9.5912927999999997e+00 , 8.9093900000000004e-01 , 4.0433000000000002e-01 , -2.0674899999999999e-01 -1.4671497848669738e+01 , 3.3245328317610209e+01 , 1.1117721599999999e+01 , -7.7846199999999999e-01 , -8.8636699999999999e-02 , 6.2140200000000001e-01 -1.4241991826206480e+01 , 3.2729982028414497e+01 , 1.2157139200000000e+01 , 7.1618300000000001e-01 , 6.3014499999999996e-01 , 2.9999900000000002e-01 -1.3906038754919892e+01 , 3.2153588970408840e+01 , 1.2566088000000001e+01 , -9.2909799999999998e-01 , -3.6794300000000002e-01 , -3.7347100000000001e-02 -1.3903655209419089e+01 , 3.2442269830472071e+01 , 1.3249888000000000e+01 , 7.7631899999999998e-01 , 5.0908600000000004e-01 , 3.7169900000000000e-01 -1.4458143905787789e+01 , 3.4212508646351814e+01 , 1.4481352000000001e+01 , -8.5413499999999998e-01 , -2.8074399999999999e-01 , 4.3776199999999998e-01 -5.4947276841854134e+00 , 1.0549091051327872e+01 , 6.1627976000000002e+00 , -1.1645000000000000e-01 , -8.5755899999999996e-01 , 5.0103100000000000e-01 -5.4583013826161659e+00 , 1.0536093578253992e+01 , 6.3223960000000003e+00 , -1.1644900000000000e-01 , -8.5755899999999996e-01 , 5.0103100000000000e-01 -5.5169992953081364e+00 , 1.0784406377135092e+01 , 6.5924216000000007e+00 , 4.7457199999999998e-02 , -8.9650600000000003e-01 , 4.4048300000000001e-01 -5.4308642393116635e+00 , 1.0637994697380762e+01 , 6.7011224000000000e+00 , 2.7489900000000001e-02 , -9.1646099999999997e-01 , 3.9917799999999998e-01 -4.9715973724475528e+00 , 9.4479091792465297e+00 , 6.3249336000000005e+00 , -8.9472200000000002e-01 , 2.8005700000000001e-02 , -4.4574599999999998e-01 -4.9777675414972951e+00 , 9.5456717450989963e+00 , 6.5216184000000004e+00 , -8.6873199999999995e-01 , -3.0974900000000000e-01 , -3.8647199999999998e-01 -4.9570613048609697e+00 , 9.5691916837902546e+00 , 6.6866455999999994e+00 , 9.9824999999999997e-01 , -7.0101100000000000e-03 , -5.8710300000000000e-02 -4.8368383727367146e+00 , 9.3083646999394141e+00 , 6.7050744000000009e+00 , -7.5084300000000004e-01 , -4.9693599999999999e-01 , -4.3507499999999999e-01 -4.9564588241525165e+00 , 9.7464836244495956e+00 , 7.0974456000000004e+00 , -5.7297699999999996e-01 , 3.1571500000000002e-01 , 7.5632100000000002e-01 -4.7693201386610014e+00 , 9.2820715858154266e+00 , 6.9975952000000010e+00 , -1.9814699999999999e-01 , -9.7944600000000004e-01 , -3.7717500000000001e-02 -4.7315506557450551e+00 , 9.2616708922835365e+00 , 7.1412400000000007e+00 , 1.0729700000000000e-01 , 9.7175400000000001e-01 , 2.1019299999999999e-01 -4.6463065185917642e+00 , 9.0926993148145705e+00 , 7.1961312000000000e+00 , 2.7903299999999998e-01 , 5.3455299999999997e-02 , 9.5879300000000001e-01 -4.5421459656925043e+00 , 8.8638218972886804e+00 , 7.2079248000000007e+00 , 9.8891300000000001e-02 , -6.3724900000000001e-02 , 9.9305600000000005e-01 -4.4048470591046831e+00 , 8.5279374897050744e+00 , 7.1400024000000002e+00 , 3.3705700000000000e-01 , -2.0359900000000000e-01 , 9.1920599999999997e-01 -4.2252681749449650e+00 , 8.0466999621691304e+00 , 6.9582416000000009e+00 , 2.7073999999999998e-01 , -1.7736900000000000e-01 , -9.4617200000000001e-01 -4.1650420091327947e+00 , 7.9403566846666704e+00 , 7.0236679999999998e+00 , -3.4924899999999998e-01 , 3.4228900000000001e-01 , 8.7227500000000002e-01 -4.0908754557306786e+00 , 7.7853139325033691e+00 , 7.0499488000000001e+00 , -3.1116500000000002e-01 , 4.7341100000000003e-01 , 8.2404999999999995e-01 -4.0157757710648685e+00 , 7.6228343543850841e+00 , 7.0654552000000006e+00 , -1.5264200000000000e-01 , 4.9853799999999998e-01 , 8.5332300000000005e-01 -4.1594346008773151e+00 , 8.2005500079775047e+00 , 7.6603767999999999e+00 , -3.9838400000000002e-01 , -5.4250200000000004e-01 , -7.3958199999999996e-01 -4.1065498637968556e+00 , 8.1244203071877958e+00 , 7.7561400000000003e+00 , 4.0460299999999999e-01 , 8.0157699999999998e-01 , 4.4019300000000000e-01 -4.0830837388424941e+00 , 8.1488345676063751e+00 , 7.9355088000000009e+00 , -3.6764300000000000e-01 , -8.2483399999999996e-01 , -4.2952000000000001e-01 -4.0444727097200754e+00 , 8.1226391764997761e+00 , 8.0766264000000003e+00 , 1.9344700000000001e-01 , 9.1820800000000002e-01 , 3.4564800000000001e-01 -3.8947159471650910e+00 , 7.6927368766714421e+00 , 7.8556056000000005e+00 , 4.8113899999999998e-01 , 4.9516800000000000e-01 , 7.2340400000000005e-01 -3.8329584688929490e+00 , 7.5760446850737786e+00 , 7.9062120000000000e+00 , -4.2643100000000000e-01 , -2.3043000000000000e-01 , -8.7467600000000001e-01 -3.8720607783295535e+00 , 7.8419797098375064e+00 , 8.3227215999999995e+00 , -8.8619800000000004e-01 , 3.5403299999999999e-01 , -2.9885299999999998e-01 -3.5286227844968123e+00 , 6.6248099548684865e+00 , 7.2834392000000001e+00 , -4.9476900000000001e-01 , -1.5640699999999999e-01 , -8.5483399999999998e-01 -3.4810501583544315e+00 , 6.5404826003106837e+00 , 7.3343680000000004e+00 , -6.3475700000000002e-01 , -2.7488000000000001e-01 , -7.2216599999999997e-01 -3.6663980811321211e+00 , 7.4175958161046296e+00 , 8.4070864000000007e+00 , -7.5280800000000003e-01 , 5.2843399999999996e-01 , -3.9247599999999999e-01 -3.7286100020026485e+00 , 7.8218463125959010e+00 , 9.0249191999999994e+00 , -7.6838700000000004e-01 , 6.2832200000000005e-01 , -1.2162500000000000e-01 -3.6324050363429055e+00 , 7.5674903517020224e+00 , 8.9330248000000001e+00 , -7.8863000000000005e-01 , 5.4097399999999995e-01 , -2.9225200000000001e-01 -3.3140775777084670e+00 , 6.2951797440622768e+00 , 7.6359159999999999e+00 , 1.7193500000000000e-01 , 8.5028500000000007e-02 , 9.8143199999999997e-01 -3.2689049963291668e+00 , 6.2196901720416964e+00 , 7.6942911999999994e+00 , 3.2777299999999998e-01 , 1.1662100000000000e-01 , 9.3753100000000000e-01 -3.1665908962538563e+00 , 5.8652813169229514e+00 , 7.4049008000000001e+00 , 1.4072599999999999e-01 , 9.6975199999999995e-01 , -1.9944200000000001e-01 -3.1161891490432669e+00 , 5.7551781016629064e+00 , 7.4063152000000008e+00 , 4.5001600000000003e-01 , -7.3453199999999998e-03 , 8.9298999999999995e-01 -3.1008380753458322e+00 , 5.8181866909340201e+00 , 7.6367168000000003e+00 , -8.2047199999999998e-01 , -3.8575799999999999e-01 , -4.2192000000000002e-01 -3.0663088190221552e+00 , 5.7910147570585346e+00 , 7.7527495999999996e+00 , -2.0898700000000001e-01 , -7.9053700000000005e-01 , -5.7565200000000005e-01 -3.0127981737336587e+00 , 5.6591856272717962e+00 , 7.7247111999999998e+00 , -3.1930199999999997e-01 , -7.0815799999999995e-01 , -6.2972899999999998e-01 -2.9845349258336795e+00 , 5.6749659424088374e+00 , 7.9076576000000003e+00 , 5.7767000000000002e-01 , 7.2298300000000004e-01 , 3.7893700000000002e-01 -2.9374074248925837e+00 , 5.5779207097436156e+00 , 7.9271680000000009e+00 , -8.1624799999999997e-01 , -2.2596200000000000e-01 , -5.3167699999999996e-01 -2.9045026349462142e+00 , 5.5746674893291202e+00 , 8.0937136000000010e+00 , -8.4383600000000003e-01 , -4.9380900000000000e-01 , -2.0998700000000001e-01 -2.8623881484189115e+00 , 5.5176994647913009e+00 , 8.1814376000000006e+00 , -9.6031299999999997e-01 , -1.1193200000000000e-01 , -2.5547999999999998e-01 -2.8273073263362933e+00 , 5.5182709734681286e+00 , 8.3665056000000000e+00 , -7.6876400000000000e-01 , -5.5811800000000002e-02 , -6.3709300000000002e-01 -2.7831860837035789e+00 , 5.4659154101749579e+00 , 8.4714312000000014e+00 , 3.8702300000000001e-01 , -2.4217400000000000e-01 , 8.8969900000000002e-01 -2.7166639347260491e+00 , 5.1722864697265560e+00 , 8.1382151999999994e+00 , -6.7236599999999994e-02 , 9.5463699999999996e-01 , 2.9008299999999998e-01 -2.6731705179204437e+00 , 5.0989306287702023e+00 , 8.1917544000000007e+00 , -1.9679599999999998e-02 , 9.1919399999999996e-01 , 3.9331199999999999e-01 -2.6319106760333626e+00 , 5.0654387559540535e+00 , 8.3276408000000011e+00 , -9.3844800000000006e-02 , 9.6546500000000002e-01 , 2.4304400000000001e-01 -2.5926461044503788e+00 , 5.0740334106745610e+00 , 8.5569503999999998e+00 , -9.4942400000000005e-01 , -6.0572099999999997e-02 , -3.0810100000000001e-01 -2.5480444903584130e+00 , 5.0322662759211285e+00 , 8.6932007999999996e+00 , 3.5956300000000002e-01 , 7.1863800000000000e-01 , 5.9521000000000002e-01 -2.5012217033706285e+00 , 5.0085235503931571e+00 , 8.8763448000000000e+00 , 9.4204500000000004e-03 , -8.3693200000000001e-01 , 5.4722499999999996e-01 -2.4531199866565072e+00 , 4.7608412588447866e+00 , 8.5537784000000006e+00 , 8.0763299999999996e-02 , 7.3340200000000000e-01 , -6.7498000000000002e-01 -2.4216918344288283e+00 , 3.9376696211094941e+00 , 6.8013368000000005e+00 , -1.8199399999999999e-01 , 4.3715599999999999e-01 , 8.8078000000000001e-01 -2.3915688599604943e+00 , 3.8788983983359828e+00 , 6.8246744000000001e+00 , -8.1188499999999997e-02 , 5.5389100000000002e-01 , 8.2862199999999997e-01 -2.3321239503420057e+00 , 4.2694177041059636e+00 , 8.0440848000000003e+00 , 4.5764500000000002e-01 , 2.6324599999999998e-01 , -8.4927200000000003e-01 -2.2946740657357343e+00 , 4.1529307775090505e+00 , 7.9638799999999996e+00 , 9.6284999999999998e-01 , -1.4581800000000000e-01 , -2.2728300000000001e-01 -2.2299988402057522e+00 , 4.2888274800762431e+00 , 8.6192983999999999e+00 , -9.9129199999999995e-01 , -7.1929499999999993e-02 , -1.1030500000000000e-01 -2.1890782360459644e+00 , 4.1791181282065057e+00 , 8.5772720000000007e+00 , -9.9129199999999995e-01 , -7.1929499999999993e-02 , -1.1030500000000000e-01 -2.2336419211606526e+00 , 3.6062050474061342e+00 , 7.0133304000000001e+00 , -6.9943699999999998e-01 , 2.3097300000000001e-01 , 6.7634200000000000e-01 -2.2021776381171270e+00 , 3.5440103052994631e+00 , 7.0299496000000010e+00 , -2.3108799999999999e-01 , 6.4411900000000000e-01 , 7.2918300000000003e-01 -2.1669523591727935e+00 , 3.4970659612771606e+00 , 7.1056200000000000e+00 , -5.6232300000000002e-01 , -7.3967300000000002e-01 , -3.6969700000000000e-01 -2.0781818878408895e+00 , 3.6197482693821570e+00 , 7.8537128000000003e+00 , 5.4828100000000002e-01 , 5.2753600000000000e-01 , -6.4891699999999997e-01 -1.8401062280545888e+00 , 4.1012152213835549e+00 , 1.0219016000000000e+01 , -9.5578099999999999e-01 , 2.9256100000000002e-01 , -2.9841699999999999e-02 -1.9678462856734895e+00 , 3.5518480861190489e+00 , 8.2679032000000010e+00 , -4.9096000000000001e-01 , 7.7420800000000001e-01 , -3.9944900000000000e-01 -1.9192602018993337e+00 , 3.4870102820493161e+00 , 8.3731615999999995e+00 , 1.0719099999999999e-01 , -8.9827400000000002e-01 , 4.2616300000000001e-01 -1.8868504019089212e+00 , 3.3884598004197475e+00 , 8.3145471999999998e+00 , -7.9503999999999997e-01 , 1.6150999999999999e-01 , -5.8465900000000004e-01 -1.8631866198993170e+00 , 3.2800626056394382e+00 , 8.1825608000000010e+00 , 8.1005400000000005e-01 , -4.8991200000000001e-01 , 3.2217800000000002e-01 -3.5222157256340152e+00 , 3.7274777222447839e+00 , 8.8598320000000008e-01 , 1.0047900000000000e-01 , -1.1213200000000000e-01 , -9.8860000000000003e-01 -3.5552134812911511e+00 , 3.7905775599827054e+00 , 8.7416880000000008e-01 , -8.6878200000000003e-02 , 1.2560700000000000e-01 , 9.8826899999999995e-01 -3.5837581629218316e+00 , 3.8484239900917716e+00 , 8.7221359999999981e-01 , -7.7287800000000004e-02 , 1.8838900000000000e-01 , 9.7904899999999995e-01 -3.6205308940383487e+00 , 3.9179237724764118e+00 , 8.5609360000000012e-01 , -6.7124699999999995e-02 , 1.4563499999999999e-01 , 9.8705900000000002e-01 -3.6487120694387332e+00 , 3.9775110868264707e+00 , 8.5747680000000015e-01 , -1.2648300000000001e-01 , 1.3220899999999999e-01 , 9.8311899999999997e-01 -3.6819092538038856e+00 , 4.0431344473779252e+00 , 8.5297359999999989e-01 , 9.7800899999999996e-02 , -1.8645900000000001e-01 , -9.7758299999999998e-01 -3.7232537637306766e+00 , 4.1216469564859235e+00 , 8.3510639999999992e-01 , -7.9718399999999995e-02 , 1.9554900000000000e-01 , 9.7744900000000001e-01 -3.7560600237900061e+00 , 4.1901410764259559e+00 , 8.3423279999999989e-01 , -5.9686799999999998e-02 , 1.7235500000000001e-01 , 9.8322500000000002e-01 -3.7927157847497952e+00 , 4.2638299228089647e+00 , 8.2835680000000012e-01 , -7.5192099999999998e-02 , 2.0459300000000000e-01 , 9.7595500000000002e-01 -3.8343531039081169e+00 , 4.3458186980106230e+00 , 8.1729120000000011e-01 , -9.5090800000000003e-02 , 1.7877299999999999e-01 , 9.7928400000000004e-01 -3.8767008785845238e+00 , 4.4283335045391272e+00 , 8.0899199999999993e-01 , -9.2336500000000002e-02 , 1.9134999999999999e-01 , 9.7716899999999995e-01 -3.9218963533441178e+00 , 4.5193099307752398e+00 , 7.9584640000000006e-01 , -7.1466799999999997e-02 , 2.0307500000000001e-01 , 9.7655199999999998e-01 -3.9728797249666052e+00 , 4.6167547722596574e+00 , 7.7916479999999999e-01 , -1.0159300000000000e-01 , 1.8769800000000000e-01 , 9.7695900000000002e-01 -4.0143550327636888e+00 , 4.7029977618234309e+00 , 7.7864479999999991e-01 , -9.4471500000000000e-02 , 1.8974600000000000e-01 , 9.7727799999999998e-01 -4.0698130680967211e+00 , 4.8107196382283668e+00 , 7.6121439999999985e-01 , -4.6994700000000000e-02 , 2.1153400000000000e-01 , 9.7624000000000000e-01 -4.1299318708083863e+00 , 4.9261776743060519e+00 , 7.4103840000000010e-01 , -2.4394800000000001e-02 , 2.2144900000000001e-01 , 9.7486700000000004e-01 -4.1947486152048992e+00 , 5.0515441565548453e+00 , 7.1829359999999998e-01 , -4.0816400000000003e-02 , 1.8391800000000000e-01 , 9.8209400000000002e-01 -4.2590654978041327e+00 , 5.1777537374358396e+00 , 6.9969840000000016e-01 , -5.4923399999999997e-02 , 1.8453700000000001e-01 , 9.8129000000000000e-01 -4.3189148432496287e+00 , 5.2987812595348469e+00 , 6.9127439999999996e-01 , -6.0362199999999998e-02 , 1.8667500000000001e-01 , 9.8056600000000005e-01 -4.3933787139860003e+00 , 5.4430393033904219e+00 , 6.6950719999999997e-01 , -5.9303799999999997e-02 , 2.0770400000000000e-01 , 9.7639299999999996e-01 -4.4762785871934607e+00 , 5.6036831472810196e+00 , 6.4129199999999997e-01 , -7.7171699999999996e-02 , 2.1326300000000001e-01 , 9.7394199999999997e-01 -4.5496220572565127e+00 , 5.7521072456071014e+00 , 6.2943599999999988e-01 , 6.8118200000000004e-02 , -2.0882400000000001e-01 , -9.7557799999999995e-01 -4.6472632870700359e+00 , 5.9397531892022206e+00 , 5.9609360000000011e-01 , -7.6080999999999996e-02 , 2.0425099999999999e-01 , 9.7595799999999999e-01 -4.7352989402125605e+00 , 6.1152649229813871e+00 , 5.7952640000000000e-01 , -7.8760600000000000e-02 , 1.9556899999999999e-01 , 9.7752200000000000e-01 -4.8413678801988276e+00 , 6.3232636956507227e+00 , 5.4885680000000003e-01 , -7.4152200000000001e-02 , 1.9931099999999999e-01 , 9.7712699999999997e-01 -4.9525808924185029e+00 , 6.5421633291694343e+00 , 5.2070399999999983e-01 , -3.1844699999999997e-02 , 2.6640900000000001e-01 , 9.6333400000000002e-01 -5.0786684568095239e+00 , 6.7878267743707505e+00 , 4.8621760000000003e-01 , 1.4972299999999999e-01 , 2.2739899999999999e-01 , 9.6222300000000005e-01 -5.1988515906426453e+00 , 7.0279107728372248e+00 , 4.6501199999999976e-01 , 9.2815199999999997e-03 , 7.1784299999999995e-02 , 9.9737699999999996e-01 -4.9071779553368753e+00 , 6.5723496752226049e+00 , 8.2950079999999993e-01 , 9.8718300000000003e-01 , 8.8234300000000002e-02 , 1.3298099999999999e-01 -4.8909983460058299e+00 , 6.5814960006298246e+00 , 9.2939279999999980e-01 , 9.8718300000000003e-01 , 8.8234300000000002e-02 , 1.3298099999999999e-01 -4.8748347301044488e+00 , 6.5884171480283875e+00 , 1.0287928799999999e+00 , 9.8889800000000005e-01 , 8.9214299999999996e-02 , 1.1883700000000000e-01 -4.8576508947650812e+00 , 6.5931471317228070e+00 , 1.1276656800000000e+00 , 9.9414999999999998e-01 , 8.2864099999999996e-02 , 6.9275500000000004e-02 -4.8501728835439586e+00 , 6.6138093489362815e+00 , 1.2180853599999999e+00 , 9.9798699999999996e-01 , 6.2533300000000000e-02 , -1.0521800000000000e-02 -4.8501365431290830e+00 , 6.6496901564948390e+00 , 1.3013207200000001e+00 , 9.9358800000000003e-01 , 7.6149700000000001e-02 , -8.3574200000000001e-02 -4.8499931932709988e+00 , 6.6835861402276979e+00 , 1.3851696800000000e+00 , 9.6968699999999997e-01 , 2.4257999999999999e-01 , -2.9375200000000001e-02 -4.8355062780364069e+00 , 6.6904545452904287e+00 , 1.4794280000000000e+00 , -9.0666199999999997e-01 , -3.4353699999999998e-01 , 2.4484000000000000e-01 -4.8237027533838326e+00 , 6.7038730231301873e+00 , 1.5698715999999999e+00 , -8.5612299999999997e-01 , -4.3285499999999999e-01 , 2.8229300000000002e-01 -4.9146569523083983e+00 , 6.9397404785254375e+00 , 1.6848508799999999e+00 , -6.5325400000000000e-01 , -7.4469199999999999e-02 , 7.5346700000000000e-01 -4.9443606173844659e+00 , 7.0302931096112804e+00 , 1.7559172000000001e+00 , -5.5313999999999997e-01 , -2.1131700000000000e-02 , 8.3282000000000000e-01 -5.0777095325840165e+00 , 7.3525793163715187e+00 , 1.8714102399999999e+00 , -4.1872999999999999e-01 , -2.9366300000000001e-02 , 9.0763600000000000e-01 -1.8062228252235457e+01 , 3.2503927808455373e+01 , -2.4266040000000002e+00 , 1.2289700000000001e-01 , 2.0214799999999999e-01 , 9.7161299999999995e-01 -1.7344760774591606e+01 , 3.1341905952594065e+01 , -1.6332711999999998e+00 , -8.6803600000000003e-01 , -6.9285600000000003e-03 , -4.9645400000000001e-01 -1.9945563322179364e+01 , 3.6656185430557279e+01 , -1.8169144000000004e+00 , -2.1513099999999999e-01 , 1.1103800000000000e-01 , 9.7025200000000000e-01 -2.3501904527500709e+01 , 4.3936286689653443e+01 , -2.0372696000000001e+00 , -9.9170800000000003e-01 , -9.9936999999999998e-02 , -8.0791600000000005e-02 -2.3428047503351490e+01 , 4.4109563565201867e+01 , -1.2403488000000000e+00 , -9.9170800000000003e-01 , -9.9936999999999998e-02 , -8.0791399999999999e-02 -1.6660976687007167e+01 , 3.0873277659911778e+01 , 6.8594960000000005e-01 , -3.6117700000000003e-01 , -4.9123699999999998e-01 , -7.9261400000000004e-01 -1.6492143604748343e+01 , 3.0753418501233824e+01 , 1.2456401599999998e+00 , -1.2417200000000000e-01 , -8.3886200000000000e-01 , -5.2999300000000005e-01 -1.6055330224115000e+01 , 3.0083572761305845e+01 , 1.8229451999999999e+00 , 2.1640999999999999e-01 , 9.2569199999999996e-01 , 3.1026100000000001e-01 -1.5932231503493929e+01 , 3.0047477315090912e+01 , 2.3554137600000002e+00 , 3.3568199999999998e-01 , 8.8405299999999998e-01 , -3.2522099999999998e-01 -1.5049823007884918e+01 , 2.8438064708873029e+01 , 2.8958518400000002e+00 , -1.9389500000000001e-01 , 4.6069800000000000e-01 , 8.6611899999999997e-01 -1.5019024888850389e+01 , 2.8579003458775016e+01 , 3.3939744000000003e+00 , 5.8399999999999996e-01 , -1.9614799999999999e-01 , -7.8769999999999996e-01 -1.5713261862907911e+01 , 3.0241955376428518e+01 , 3.9433856000000000e+00 , 5.0997300000000002e-02 , 5.8483799999999997e-01 , 8.0954499999999996e-01 -1.6250390059506305e+01 , 3.1598433527430938e+01 , 4.5398464000000001e+00 , -1.1952500000000001e-01 , -9.8315300000000005e-01 , 1.3829200000000000e-01 -1.4997441181192571e+01 , 2.9160278233493255e+01 , 4.9253327999999996e+00 , 5.5803199999999997e-01 , 7.9319300000000004e-01 , 2.4381400000000000e-01 -1.4895939753531298e+01 , 2.9156362968148056e+01 , 5.4320103999999994e+00 , -5.7038900000000003e-01 , -6.4775899999999997e-01 , -5.0504000000000004e-01 -1.5354311033371486e+01 , 3.0366885132912369e+01 , 6.0680120000000004e+00 , -7.0409200000000005e-01 , -4.0818900000000002e-01 , 5.8106500000000005e-01 -1.4724551701565986e+01 , 2.9218716334533013e+01 , 6.4536959999999999e+00 , 6.4329000000000003e-01 , 4.2294300000000001e-01 , 6.3819800000000004e-01 -1.4534665710399256e+01 , 2.9022112831108917e+01 , 6.9338432000000001e+00 , -6.0320300000000004e-01 , -7.4937900000000002e-01 , -2.7308600000000000e-01 -1.4468750037442824e+01 , 2.9098630670876521e+01 , 7.4522624000000004e+00 , 4.5418599999999998e-01 , 8.8710900000000004e-01 , 8.2181299999999999e-02 -1.4230977010314541e+01 , 2.8791192161092440e+01 , 7.9048496000000004e+00 , -2.9535099999999997e-01 , -9.3907200000000002e-01 , -1.7581800000000000e-01 -1.4456382182341732e+01 , 2.9524510805900686e+01 , 8.5572207999999996e+00 , -8.0394900000000005e-02 , -9.9676299999999995e-01 , -6.5620399999999997e-04 -1.3999674711269517e+01 , 2.8716714901472578e+01 , 8.8984656000000015e+00 , 4.1184700000000002e-01 , 8.9649000000000001e-01 , -1.6336300000000001e-01 -1.4039339971762571e+01 , 2.9039811595021149e+01 , 9.4827271999999994e+00 , -2.1855400000000000e-01 , -9.4740599999999997e-01 , 2.3378499999999999e-01 -1.4037477497064149e+01 , 2.9269385777515602e+01 , 1.0057795200000001e+01 , -2.1855400000000000e-01 , -9.4740599999999997e-01 , 2.3378499999999999e-01 -1.4606407718862103e+01 , 3.1101870454617416e+01 , 1.1653789600000000e+01 , -3.9487699999999998e-01 , -7.6506799999999997e-01 , 5.0866800000000001e-01 -1.5144365140551200e+01 , 3.2648993553441045e+01 , 1.2711895999999999e+01 , -4.6304000000000001e-01 , -7.3080599999999996e-01 , -5.0151500000000004e-01 -1.4902100367814757e+01 , 3.2351149930492753e+01 , 1.3211200000000000e+01 , 3.3222000000000002e-01 , 8.5043500000000005e-01 , 4.0791100000000002e-01 -1.4488865530259337e+01 , 3.1634087330331134e+01 , 1.3553464000000000e+01 , -5.7648600000000005e-01 , -7.4718200000000001e-01 , 3.3073300000000000e-01 -6.5576189720374556e+00 , 1.2474363419070135e+01 , 6.8911408000000005e+00 , 7.1711400000000003e-01 , -5.3452900000000003e-01 , -4.4724300000000000e-01 -5.7416485916766318e+00 , 1.0554162147070713e+01 , 6.3302584000000000e+00 , -3.2627000000000003e-02 , -9.2730299999999999e-01 , 3.7288600000000000e-01 -6.0526871847181942e+00 , 1.1412705687025307e+01 , 6.8580480000000001e+00 , 2.5838800000000001e-01 , -7.4351699999999998e-01 , 6.1678100000000002e-01 -5.1711767275587359e+00 , 9.2783638576974994e+00 , 6.1057535999999999e+00 , 5.7176600000000000e-01 , 7.5587800000000005e-01 , 3.1895600000000002e-01 -5.1583799096154888e+00 , 9.3191921704342207e+00 , 6.2687736000000003e+00 , 8.5545199999999999e-01 , 5.1203299999999996e-01 , 7.7613600000000005e-02 -5.2296248332424549e+00 , 9.5779539597180836e+00 , 6.5405879999999996e+00 , -8.8321300000000003e-01 , -4.6228500000000000e-01 , 7.8913499999999998e-02 -5.0635462603311190e+00 , 9.2235442422631948e+00 , 6.5169176000000002e+00 , -7.1585399999999999e-01 , -6.1738999999999999e-01 , -3.2616400000000001e-01 -5.0564054418508508e+00 , 9.2823277368479182e+00 , 6.6964632000000002e+00 , 8.0605400000000005e-01 , 5.8907500000000002e-01 , -5.7160400000000000e-02 -5.0104776673124736e+00 , 9.2415014897978658e+00 , 6.8265880000000001e+00 , -4.6678399999999998e-01 , -8.7021199999999999e-01 , -1.5762200000000001e-01 -5.1240240313024312e+00 , 9.6295442909163249e+00 , 7.2009984000000005e+00 , 4.2537999999999999e-02 , -7.4977199999999994e-02 , 9.9627800000000000e-01 -4.9525767050902436e+00 , 9.2486953424833107e+00 , 7.1398256000000000e+00 , -2.6837800000000001e-01 , -9.6218800000000004e-01 , -4.6556100000000003e-02 -4.9561208885436994e+00 , 9.3444930389640106e+00 , 7.3577783999999999e+00 , 9.4753100000000007e-02 , 2.8515300000000000e-02 , -9.9509199999999998e-01 -4.6928037449717515e+00 , 8.6979530435934613e+00 , 7.1071904000000004e+00 , 2.3115800000000000e-01 , -2.6620100000000002e-01 , 9.3579000000000001e-01 -4.5677249037882266e+00 , 8.4244372072867009e+00 , 7.0774151999999999e+00 , 3.2901300000000000e-01 , -1.9092999999999999e-01 , 9.2482200000000003e-01 -4.5278018072549973e+00 , 8.3929884306745919e+00 , 7.2026728000000002e+00 , -3.8567299999999999e-01 , 5.3823000000000003e-02 , -9.2106399999999999e-01 -4.4272676262982333e+00 , 8.1876290571348562e+00 , 7.2054495999999997e+00 , -7.1271499999999999e-01 , 1.2658000000000000e-01 , -6.8993800000000005e-01 -4.3106467088038372e+00 , 7.9275640723694991e+00 , 7.1598975999999999e+00 , 4.2797900000000000e-01 , -7.4659900000000001e-01 , -5.0933700000000004e-01 -4.3083718152465975e+00 , 8.0045882767716421e+00 , 7.3625416000000001e+00 , -1.0605900000000000e-01 , -9.1217099999999995e-01 , 3.9584799999999998e-01 -4.3338350434222122e+00 , 8.1727004910096248e+00 , 7.6437160000000004e+00 , -7.0072599999999996e-01 , -6.6879699999999997e-01 , -2.4838399999999999e-01 -4.3064780060113232e+00 , 8.1851096435713124e+00 , 7.8101472000000003e+00 , 4.0460299999999999e-01 , 8.0157800000000001e-01 , 4.4019300000000000e-01 -4.1250480183881724e+00 , 7.7074549772338576e+00 , 7.5667144000000004e+00 , -5.9256900000000001e-01 , -1.2703700000000001e-01 , -7.9543900000000001e-01 -4.0934363303115706e+00 , 7.7034239521945365e+00 , 7.7139056000000004e+00 , 6.7737800000000004e-01 , 1.5215899999999999e-01 , 7.1972700000000001e-01 -3.9599774722732892e+00 , 7.3653997918922327e+00 , 7.5624192000000008e+00 , -9.6305200000000002e-01 , 1.8847100000000000e-01 , -1.9237799999999999e-01 -3.9225546017384714e+00 , 7.3364315796426949e+00 , 7.6846815999999993e+00 , -9.0597200000000000e-01 , -3.9067400000000002e-01 , -1.6305700000000001e-01 -3.9372821239932616e+00 , 7.4893472186197290e+00 , 7.9830160000000010e+00 , 6.4369500000000002e-01 , -2.2906899999999999e-01 , 7.3019500000000004e-01 -3.8695182937699610e+00 , 7.3662696670229098e+00 , 8.0217248000000012e+00 , 8.9623500000000000e-01 , 5.2550800000000002e-02 , 4.4045699999999999e-01 -3.6069799617513567e+00 , 6.5389504490610353e+00 , 7.3325376000000002e+00 , 2.7431299999999997e-01 , 3.6658099999999999e-01 , 8.8902800000000004e-01 -3.5503982276305126e+00 , 6.4343115831189861e+00 , 7.3597751999999996e+00 , 1.2065800000000000e-01 , 4.3471199999999999e-01 , 8.9244999999999997e-01 -3.4988002227970121e+00 , 6.3426209336035528e+00 , 7.3995655999999999e+00 , 3.5244199999999998e-01 , 3.4296900000000002e-01 , 8.7072200000000000e-01 -3.4777599641669603e+00 , 6.3667416886958064e+00 , 7.5675256000000006e+00 , -4.6280100000000002e-01 , -3.8812099999999999e-01 , -7.9698000000000002e-01 -3.4013705201506932e+00 , 6.1802626842540054e+00 , 7.4952664000000002e+00 , -5.0702300000000000e-01 , 5.9686400000000001e-02 , -8.5986300000000004e-01 -3.3781410701114405e+00 , 6.1991644824836394e+00 , 7.6631952000000005e+00 , -4.6606599999999998e-01 , -2.4804000000000001e-01 , -8.4926900000000005e-01 -3.3084925754906740e+00 , 6.0338212053216669e+00 , 7.6076800000000002e+00 , -4.6103699999999997e-01 , -4.3805100000000002e-01 , 7.7172300000000005e-01 -3.2282954678463116e+00 , 5.8080717402243636e+00 , 7.4661152000000008e+00 , -1.5221699999999999e-01 , 8.1705700000000003e-01 , 5.5610000000000004e-01 -3.1903196562717202e+00 , 5.7674354916547532e+00 , 7.5567304000000002e+00 , 3.1450600000000001e-01 , 9.0561699999999995e-02 , -9.4492600000000004e-01 -3.1359306769966047e+00 , 5.6509848089199117e+00 , 7.5468919999999997e+00 , 9.2098000000000002e-01 , 1.1995300000000000e-01 , 3.7068499999999999e-01 -3.1146283306977542e+00 , 5.6903754768493062e+00 , 7.7536856000000007e+00 , 4.7881899999999999e-01 , -5.9853500000000004e-01 , -6.4225200000000005e-01 -3.0700665483981915e+00 , 5.6254832941074184e+00 , 7.8173127999999998e+00 , 1.0118600000000000e-01 , 7.6993199999999995e-01 , 6.3005199999999995e-01 -3.0256286031790900e+00 , 5.5592473277901373e+00 , 7.8796295999999995e+00 , -4.2741099999999999e-01 , -6.3447200000000004e-01 , -6.4402199999999998e-01 -2.9789474260495883e+00 , 5.4748672253656672e+00 , 7.9146464000000005e+00 , -1.3573499999999999e-01 , 5.6856600000000002e-01 , 8.1136299999999995e-01 -2.9337732756520487e+00 , 5.4070282440842492e+00 , 7.9741136000000008e+00 , -3.1330700000000000e-01 , 4.9984800000000001e-01 , 8.0745999999999996e-01 -2.8853350054655085e+00 , 5.3159781044912995e+00 , 7.9967231999999999e+00 , 1.4104300000000000e-01 , 3.8241900000000001e-01 , 9.1316100000000000e-01 -2.8393331312023502e+00 , 5.2354709600185476e+00 , 8.0352968000000011e+00 , 2.3137900000000000e-01 , 2.7807700000000002e-01 , 9.3227499999999996e-01 -2.7946584448562248e+00 , 5.1645922140124600e+00 , 8.0903127999999995e+00 , 3.0165599999999998e-01 , 6.6849700000000001e-01 , 6.7979000000000001e-01 -2.7665155143724989e+00 , 5.2485122911722693e+00 , 8.4376104000000005e+00 , 4.4419399999999998e-01 , 6.2582400000000006e-05 , 8.9593100000000003e-01 -2.7089762809299005e+00 , 5.0760945342330306e+00 , 8.3073712000000004e+00 , 2.6123900000000000e-01 , -8.8041199999999997e-01 , -3.9576400000000000e-01 -2.6635624944094221e+00 , 5.0235194054184245e+00 , 8.4056719999999991e+00 , 2.7315000000000000e-01 , -9.6191000000000004e-01 , 1.0846000000000000e-02 -2.6221152280911633e+00 , 5.0431957210619434e+00 , 8.6631135999999991e+00 , -7.6787300000000003e-01 , 1.0758600000000000e-01 , 6.3150300000000004e-01 -2.5725074886324850e+00 , 4.9610556519884401e+00 , 8.7138968000000006e+00 , 2.4541199999999999e-01 , -9.4172500000000003e-01 , 2.3005800000000001e-01 -2.5205970023443132e+00 , 4.8037436641521492e+00 , 8.5913535999999997e+00 , -1.7461700000000000e-02 , -6.7398499999999995e-01 , 7.3853899999999995e-01 -2.4656451519920206e+00 , 3.9617008213554814e+00 , 6.8140664000000006e+00 , -1.9812600000000000e-01 , 3.3146999999999999e-01 , 9.2242800000000003e-01 -2.4335148690619830e+00 , 3.8960072212841643e+00 , 6.8183927999999998e+00 , -1.0273599999999999e-01 , 5.7333100000000004e-01 , 8.1285700000000005e-01 -2.3963721892111147e+00 , 3.9450586732334623e+00 , 7.1224472000000008e+00 , 5.9617900000000001e-02 , 9.7998200000000002e-01 , -1.8995000000000001e-01 -2.3428251344179634e+00 , 4.1952794725166758e+00 , 8.0051784000000001e+00 , 4.5764500000000002e-01 , 2.6324599999999998e-01 , -8.4927200000000003e-01 -2.3018509563220513e+00 , 4.1041824852703099e+00 , 7.9922200000000005e+00 , 7.8562500000000002e-01 , -3.5460900000000001e-01 , -5.0699700000000003e-01 -2.2444075433839084e+00 , 4.1612371352882320e+00 , 8.4212616000000011e+00 , -8.8139400000000001e-01 , -1.7014599999999999e-01 , -4.4067699999999999e-01 -2.2538524907879034e+00 , 3.7154409123599690e+00 , 7.2857376000000000e+00 , 1.0394800000000000e-01 , 9.8954100000000000e-01 , -1.0001400000000001e-01 -2.2334878239628200e+00 , 3.5702219670884183e+00 , 7.0349624000000004e+00 , 5.0880899999999996e-01 , -5.3479699999999997e-01 , -6.7461499999999996e-01 -2.1999149241965776e+00 , 3.5110273094589375e+00 , 7.0607544000000004e+00 , -1.1146200000000000e-03 , 7.4591399999999997e-01 , 6.6604200000000002e-01 -2.1513870874692484e+00 , 3.5033125347502589e+00 , 7.2861432000000006e+00 , 7.9431700000000005e-01 , 6.0662700000000003e-01 , -3.2630800000000001e-02 -2.0707396012634791e+00 , 3.5785313204449771e+00 , 7.8741800000000000e+00 , 4.9093100000000001e-01 , 8.4775699999999998e-01 , 2.0073500000000000e-01 -1.9884513570599318e+00 , 3.6157253748245006e+00 , 8.3838112000000002e+00 , 5.8962400000000004e-01 , -4.3554300000000001e-01 , 6.8018100000000004e-01 -1.9588861719121737e+00 , 3.5021525849092345e+00 , 8.2564735999999996e+00 , -1.7861900000000000e-02 , -2.0988999999999999e-01 , 9.7756200000000004e-01 -1.9267770977974930e+00 , 3.4016893199709601e+00 , 8.1778703999999998e+00 , -9.0159500000000004e-01 , 2.0011300000000001e-01 , -3.8351099999999999e-01 -1.8912534716307385e+00 , 3.3122808481190020e+00 , 8.1376328000000004e+00 , 6.5505999999999998e-01 , -4.5188600000000001e-01 , 6.0555400000000004e-01 -1.8473234747524077e+00 , 3.2372023333065458e+00 , 8.1772464000000014e+00 , -6.5558899999999998e-01 , -7.5474600000000003e-01 , -2.3717100000000001e-02 -3.6538870909479222e+00 , 3.8574932384482423e+00 , 8.7422079999999980e-01 , -4.6004400000000001e-02 , 1.4906200000000000e-01 , 9.8775700000000000e-01 -3.6883638919067767e+00 , 3.9204684325522985e+00 , 8.6741919999999983e-01 , -1.2170400000000001e-01 , 1.4702899999999999e-01 , 9.8161600000000004e-01 -3.7185129475061633e+00 , 3.9801893678676894e+00 , 8.6986319999999995e-01 , -1.1286000000000000e-01 , 1.0087800000000000e-01 , 9.8847700000000005e-01 -3.7536296727513143e+00 , 4.0449284557406013e+00 , 8.6661839999999990e-01 , 8.7267999999999998e-02 , -1.7127000000000001e-01 , -9.8135200000000000e-01 -3.7927274260470329e+00 , 4.1168308408194498e+00 , 8.5765359999999990e-01 , -7.9984700000000006e-02 , 2.2484499999999999e-01 , 9.7110600000000002e-01 -3.8409124368799001e+00 , 4.2017492389550508e+00 , 8.3617760000000008e-01 , -8.3047200000000002e-02 , 1.6195999999999999e-01 , 9.8329699999999998e-01 -3.8753718466886617e+00 , 4.2698356622603750e+00 , 8.3889199999999997e-01 , -9.4587099999999993e-02 , 1.7690900000000001e-01 , 9.7967199999999999e-01 -3.9199157460680434e+00 , 4.3509916862275428e+00 , 8.2962559999999996e-01 , -9.2081800000000005e-02 , 1.8925800000000001e-01 , 9.7760000000000002e-01 -3.9631263252591848e+00 , 4.4327051316830257e+00 , 8.2276159999999998e-01 , -9.5393199999999997e-02 , 1.8852600000000000e-01 , 9.7742399999999996e-01 -4.0122604607854102e+00 , 4.5228351777649545e+00 , 8.1153999999999993e-01 , -7.7433699999999994e-02 , 2.2434000000000001e-01 , 9.7143000000000002e-01 -4.0661442141458366e+00 , 4.6194778460921109e+00 , 7.9676159999999996e-01 , 8.1321900000000003e-02 , -1.7002999999999999e-01 , -9.8207800000000001e-01 -4.1146054772677303e+00 , 4.7118803101302014e+00 , 7.9140560000000004e-01 , -7.7652299999999994e-02 , 1.9356899999999999e-01 , 9.7800900000000002e-01 -4.1779819694645086e+00 , 4.8248258668868598e+00 , 7.6999199999999979e-01 , -1.5816299999999998e-02 , 2.3335400000000001e-01 , 9.7226299999999999e-01 -4.2511032666137156e+00 , 4.9536160552529669e+00 , 7.3970720000000001e-01 , -5.0465299999999998e-02 , 2.0260800000000001e-01 , 9.7795900000000002e-01 -4.3095770903540114e+00 , 5.0632120335875257e+00 , 7.3219840000000014e-01 , -6.3590900000000006e-02 , 1.9611700000000001e-01 , 9.7851600000000005e-01 -4.3827945026283857e+00 , 5.1958206310415527e+00 , 7.1034799999999976e-01 , -6.9067500000000004e-02 , 1.9520299999999999e-01 , 9.7832799999999998e-01 -4.4514837795765683e+00 , 5.3222374026010879e+00 , 6.9896000000000003e-01 , -7.1700700000000006e-02 , 1.8167900000000001e-01 , 9.8073999999999995e-01 -4.5287270953390451e+00 , 5.4659234347899490e+00 , 6.8019840000000009e-01 , -6.5171300000000001e-02 , 2.0740800000000001e-01 , 9.7608099999999998e-01 -4.6124351469238540e+00 , 5.6177643667787738e+00 , 6.6116639999999993e-01 , 6.7146499999999998e-02 , -2.1051300000000001e-01 , -9.7528199999999998e-01 -4.7105048234758744e+00 , 5.7943975067366598e+00 , 6.3122480000000003e-01 , -7.6061900000000002e-02 , 2.0792500000000000e-01 , 9.7518300000000002e-01 -4.7979675590013446e+00 , 5.9588632346583204e+00 , 6.1771519999999991e-01 , -8.5149600000000006e-02 , 2.0170700000000000e-01 , 9.7573799999999999e-01 -4.9055613590203500e+00 , 6.1546282904059444e+00 , 5.8986399999999994e-01 , -7.2889499999999996e-02 , 1.9984700000000000e-01 , 9.7711199999999998e-01 -5.0134336432563966e+00 , 6.3538879314710064e+00 , 5.6890799999999997e-01 , 4.3851099999999997e-02 , 3.3264600000000000e-01 , 9.4203199999999998e-01 -5.1412058471133797e+00 , 6.5870529259735466e+00 , 5.3602320000000003e-01 , 1.9705400000000001e-01 , 2.9388300000000001e-01 , 9.3530899999999995e-01 -5.2728881223890918e+00 , 6.8303486723011213e+00 , 5.0685119999999984e-01 , -8.8966299999999998e-02 , 1.9482700000000000e-01 , 9.7679499999999997e-01 -4.9569995558176974e+00 , 6.3679795023160652e+00 , 8.7982639999999979e-01 , 9.8902400000000001e-01 , 8.1525700000000006e-02 , 1.2323099999999999e-01 -4.9421306770162401e+00 , 6.3766274962283873e+00 , 9.7752295999999994e-01 , 9.8902400000000001e-01 , 8.1525700000000006e-02 , 1.2323099999999999e-01 -4.9311145972297350e+00 , 6.3915532605913059e+00 , 1.0703148800000002e+00 , 9.9094099999999996e-01 , 9.1600899999999999e-02 , 9.8209599999999994e-02 -4.9131650724753619e+00 , 6.3958202971615865e+00 , 1.1667353599999999e+00 , 9.9419199999999996e-01 , 8.8248400000000005e-02 , 6.1597199999999998e-02 -4.9059657112382560e+00 , 6.4159978117998584e+00 , 1.2548275200000001e+00 , 9.9615799999999999e-01 , 8.5593400000000000e-02 , 1.8544000000000001e-02 -4.9024334818097364e+00 , 6.4416938766515877e+00 , 1.3394356800000000e+00 , 9.8390800000000000e-01 , 2.1203600000000000e-02 , -1.7741199999999999e-01 -4.8989012523812168e+00 , 6.4673899415033178e+00 , 1.4240428000000001e+00 , 9.6287999999999996e-01 , 3.2388100000000003e-02 , -2.6797900000000002e-01 -4.9285542799983482e+00 , 6.5507589176525878e+00 , 1.4857907200000000e+00 , -9.2552999999999996e-01 , -1.8928900000000001e-01 , 3.2796999999999998e-01 -4.9284154989240667e+00 , 6.5813344205157200e+00 , 1.5690406399999999e+00 , -8.6553100000000005e-01 , -1.8449299999999999e-01 , 4.6563800000000000e-01 -4.9575374126952418e+00 , 6.6634496899677789e+00 , 1.6349423199999999e+00 , -8.4365599999999996e-01 , -1.4430899999999999e-01 , 5.1712499999999995e-01 -4.9654891874524578e+00 , 6.7099165064058619e+00 , 1.7144721599999999e+00 , -8.4355300000000000e-01 , -9.3533800000000000e-02 , 5.2883800000000003e-01 -4.9976574345231057e+00 , 6.7986235861941280e+00 , 1.7821501600000000e+00 , -7.0482800000000001e-01 , -8.7729600000000005e-02 , 7.0393200000000000e-01 -5.1654364854666426e+00 , 7.1602967212510835e+00 , 1.8791322399999999e+00 , -3.9446799999999999e-01 , -3.5708600000000000e-02 , 9.1821600000000003e-01 -5.2955596708605981e+00 , 7.4258365244105526e+00 , 1.9178762960000000e+00 , -3.1441000000000002e-01 , 7.2025300000000004e-03 , 9.4925999999999999e-01 -1.7467763882929820e+01 , 2.9308098148259752e+01 , -2.0307072000000002e+00 , -9.1527700000000001e-01 , -3.7940900000000000e-01 , -1.3533700000000001e-01 -1.7815801783967316e+01 , 3.0138964617233807e+01 , -1.6215712000000000e+00 , -9.1527700000000001e-01 , -3.7940900000000000e-01 , -1.3533700000000001e-01 -1.7759578615461919e+01 , 3.0245143302529932e+01 , -1.0751968000000005e+00 , -8.7192999999999998e-01 , -4.6011000000000002e-01 , -1.6744600000000001e-01 -1.7594991768310816e+01 , 3.0358749504125001e+01 , 2.8211999999999904e-02 , 8.1760699999999997e-01 , 5.1070099999999996e-01 , 2.6590100000000000e-01 -1.7368311593981897e+01 , 3.0146304346575551e+01 , 6.0156399999999999e-01 , -8.4524900000000003e-01 , -3.9650400000000002e-01 , -3.5824400000000001e-01 -1.7534676328853259e+01 , 3.0665717600791481e+01 , 1.1123267200000000e+00 , 6.8863200000000002e-01 , 3.9333699999999999e-01 , 6.0915600000000003e-01 -1.6774001835138534e+01 , 2.9444108049268628e+01 , 1.7273754399999999e+00 , -7.1408199999999999e-01 , -6.4213299999999995e-01 , -2.7884100000000001e-01 -1.6737899427975652e+01 , 2.9577710767583213e+01 , 2.2509821600000000e+00 , 6.3397400000000004e-01 , 7.0652099999999995e-01 , -3.1449199999999999e-01 -1.6721071981948327e+01 , 2.9750238743112387e+01 , 2.7771472799999999e+00 , -6.5490199999999998e-01 , -7.3766299999999996e-01 , 1.6418900000000000e-01 -1.6932541506941561e+01 , 3.0368038107669474e+01 , 3.3114920000000003e+00 , -3.4329999999999999e-01 , -9.2917700000000003e-01 , 1.3702000000000000e-01 -1.6414775499027286e+01 , 2.9573014336920121e+01 , 3.8294432000000000e+00 , -2.1040400000000001e-01 , -9.6773500000000001e-01 , -1.3863200000000001e-01 -1.6341405459949438e+01 , 2.9637621808358919e+01 , 4.3556416000000002e+00 , 1.4189900000000000e-01 , 9.5009699999999997e-01 , 2.7781499999999998e-01 -1.6112758565790344e+01 , 2.9397188014595645e+01 , 4.8633487999999998e+00 , -2.2474500000000000e-01 , -8.7027200000000005e-01 , -4.3830999999999998e-01 -1.5994997169750924e+01 , 2.9371406523505215e+01 , 5.3795631999999998e+00 , 4.9791700000000000e-01 , 8.3655199999999996e-01 , 2.2860100000000000e-01 -1.5900710345037007e+01 , 2.9393148005270898e+01 , 5.8993240000000000e+00 , 4.3534000000000000e-01 , 6.8291999999999997e-01 , 5.8659899999999998e-01 -1.5311445170127547e+01 , 2.8414270713002395e+01 , 6.2963856000000007e+00 , 3.5758800000000002e-01 , 8.6331100000000005e-01 , 3.5612500000000002e-01 -1.5303198755589994e+01 , 2.8604667666190398e+01 , 6.8233120000000005e+00 , -2.7631800000000001e-01 , -9.5271499999999998e-01 , -1.2642400000000001e-01 -1.5859067582744805e+01 , 3.0181738166140711e+01 , 8.1179768000000010e+00 , -5.3458499999999998e-01 , -8.4494199999999997e-01 , 1.7076999999999998e-02 -1.5462016309065111e+01 , 2.9578528216735588e+01 , 8.5338728000000010e+00 , 1.5769400000000000e-01 , 9.8616300000000001e-01 , -5.1144799999999997e-02 -1.4877061179270674e+01 , 2.8573677458177297e+01 , 8.8392480000000013e+00 , -1.8055300000000000e-02 , -9.9231899999999995e-01 , 1.2238300000000001e-01 -1.5325565104497919e+01 , 2.9743361233343794e+01 , 9.6286392000000003e+00 , 9.6401600000000004e-02 , -9.4200399999999995e-01 , 3.2145899999999999e-01 -1.4788353926445227e+01 , 2.8825971123765960e+01 , 9.9252056000000017e+00 , -1.3819000000000001e-01 , -9.3191100000000004e-01 , 3.3533000000000002e-01 -1.5700372216414429e+01 , 3.1024807521276617e+01 , 1.1056881599999999e+01 , 1.2346299999999999e-02 , -7.4219199999999996e-01 , 6.7007399999999995e-01 -1.5455403534971078e+01 , 3.0739255732923077e+01 , 1.1537039200000001e+01 , -1.9724300000000000e-01 , -7.6010200000000006e-01 , 6.1914499999999995e-01 -1.5753026942282158e+01 , 3.1646598829060661e+01 , 1.2388820000000001e+01 , -3.8334300000000002e-02 , -8.5538499999999995e-01 , 5.1657200000000003e-01 -1.5893000448113364e+01 , 3.2220299081109872e+01 , 1.3168455999999999e+01 , -3.8215600000000002e-02 , 7.1847899999999998e-01 , 6.9449799999999995e-01 -6.8258856779460659e+00 , 1.2196252891453826e+01 , 6.5904456000000007e+00 , 8.1151499999999999e-01 , -3.3908199999999999e-01 , -4.7588500000000000e-01 -6.4052250756275457e+00 , 1.1337262717328288e+01 , 6.4639608000000006e+00 , -4.5808100000000002e-01 , 8.0237899999999995e-01 , -3.8255699999999998e-01 -6.3103846425401171e+00 , 1.1207412472200952e+01 , 6.5950527999999995e+00 , -4.5808100000000002e-01 , 8.0237899999999995e-01 , -3.8255699999999998e-01 -6.4401760037345941e+00 , 1.1591744691447902e+01 , 6.9386896000000000e+00 , 7.6282200000000000e-01 , -5.8499699999999999e-01 , -2.7546500000000002e-01 -5.3908584742205061e+00 , 9.2411868176610241e+00 , 6.0945423999999999e+00 , 3.1756000000000001e-01 , 8.1932199999999999e-01 , 4.7735499999999997e-01 -5.3530818260318966e+00 , 9.2211879095679805e+00 , 6.2296592000000004e+00 , 4.7691899999999998e-01 , 7.9704500000000000e-01 , 3.7049500000000002e-01 -5.3208567975369387e+00 , 9.2153665450046525e+00 , 6.3730855999999996e+00 , -5.5804200000000004e-01 , -7.5815100000000002e-01 , -3.3733700000000000e-01 -5.2629116012960990e+00 , 9.1471353300322491e+00 , 6.4858631999999998e+00 , 6.1695800000000001e-01 , 7.2150700000000001e-01 , 3.1430900000000001e-01 -5.2541438579043307e+00 , 9.1986066478266864e+00 , 6.6604168000000001e+00 , -5.6884199999999996e-01 , -8.1557000000000002e-01 , 1.0613499999999999e-01 -5.2699754838392590e+00 , 9.3144572044082423e+00 , 6.8751352000000008e+00 , 3.3608600000000000e-01 , 9.3146799999999996e-01 , -1.3933599999999999e-01 -5.2050404044343601e+00 , 9.2306108508763245e+00 , 6.9827232000000006e+00 , -4.2986300000000000e-01 , -9.0077499999999999e-01 , -6.1826100000000002e-02 -5.1965333563636751e+00 , 9.2884913170970016e+00 , 7.1733032000000003e+00 , -1.9861500000000001e-01 , -8.8636599999999999e-01 , 4.1821999999999998e-01 -5.1121432118443781e+00 , 9.1573425396124506e+00 , 7.2527591999999999e+00 , 2.4197600000000000e-01 , 9.6439600000000003e-01 , -1.0671100000000000e-01 -4.7766783417807286e+00 , 8.3778377605355416e+00 , 6.9117743999999997e+00 , -4.0898900000000002e-02 , -3.0505199999999999e-01 , 9.5145700000000000e-01 -4.5970875239800524e+00 , 7.9873263440229847e+00 , 6.7956168000000003e+00 , 5.0454900000000003e-01 , -5.6761700000000004e-01 , 6.5056999999999998e-01 -4.5967054825071001e+00 , 8.0588342412013603e+00 , 6.9817767999999996e+00 , 6.3709199999999999e-01 , -4.7837600000000002e-01 , 6.0437500000000000e-01 -4.5564281056464413e+00 , 8.0294996223528976e+00 , 7.1016472000000004e+00 , -3.3209200000000000e-01 , -9.4309799999999999e-01 , -1.6779700000000002e-02 -4.5048299017028208e+00 , 7.9660780323782490e+00 , 7.1974935999999996e+00 , 1.8548799999999999e-01 , 8.6427100000000001e-01 , 4.6757799999999999e-01 -4.4513015664409288e+00 , 7.9013419828286322e+00 , 7.2916759999999998e+00 , -5.9855999999999999e-02 , 9.2061599999999999e-01 , 3.8585399999999997e-01 -4.3917799116078360e+00 , 7.8181685238243919e+00 , 7.3720679999999996e+00 , -3.5310500000000000e-01 , 8.8995999999999997e-01 , 2.8859699999999999e-01 -4.1111783266936355e+00 , 7.1061322756012837e+00 , 6.9349872000000010e+00 , 6.8673499999999998e-01 , -4.0883500000000000e-01 , 6.0104100000000005e-01 -4.0813797280358273e+00 , 7.0982347839114572e+00 , 7.0580711999999997e+00 , -9.6300100000000000e-01 , 2.3659100000000000e-01 , -1.2905400000000000e-01 -4.1239431890650806e+00 , 7.2999819496545504e+00 , 7.3675648000000002e+00 , -1.0824499999999999e-01 , -9.6035000000000004e-01 , 2.5692700000000002e-01 -4.2043813074807161e+00 , 7.6281920880561422e+00 , 7.8068816000000005e+00 , 5.8937399999999995e-01 , 1.7153900000000000e-01 , 7.8943799999999997e-01 -4.1021432288569777e+00 , 7.4121835275680779e+00 , 7.7617248000000005e+00 , 2.9206399999999999e-01 , -2.4401999999999999e-01 , -9.2474500000000004e-01 -4.0188112738898640e+00 , 7.2506350090216083e+00 , 7.7589687999999999e+00 , -6.4785300000000001e-01 , -6.6577200000000003e-01 , -3.7018099999999998e-01 -3.9663299077008736e+00 , 7.1840843895283450e+00 , 7.8443528000000002e+00 , 8.4870999999999996e-01 , 5.2528799999999998e-01 , 6.1361300000000001e-02 -3.7339033013213943e+00 , 6.5341921753163890e+00 , 7.3307383999999995e+00 , -6.9469900000000001e-02 , 2.6169999999999999e-01 , 9.6264600000000000e-01 -3.6633226695644123e+00 , 6.3962711300176203e+00 , 7.3215032000000004e+00 , 2.5924300000000000e-01 , 5.3909300000000004e-01 , 8.0135599999999996e-01 -3.6374033929502936e+00 , 6.4032627312162589e+00 , 7.4666664000000003e+00 , 3.7791799999999998e-01 , 6.3319899999999996e-01 , 6.7545299999999997e-01 -3.5731840176658185e+00 , 6.2787707598844822e+00 , 7.4674880000000003e+00 , 1.5509100000000000e-02 , 5.3360200000000002e-01 , 8.4559399999999996e-01 -3.5166129733801847e+00 , 6.1817743581502285e+00 , 7.4957136000000002e+00 , -2.2219700000000001e-01 , 8.9184200000000002e-01 , 3.9401300000000000e-01 -3.4626280775257197e+00 , 6.0910748637054271e+00 , 7.5294616000000003e+00 , 6.9228999999999996e-01 , -7.1411300000000000e-01 , 1.0381300000000000e-01 -3.3852124420363983e+00 , 5.9093964792757312e+00 , 7.4491424000000004e+00 , -4.4832200000000000e-01 , 5.4976000000000003e-01 , -7.0482000000000000e-01 -3.3519413395153284e+00 , 5.8956484870705950e+00 , 7.5740983999999996e+00 , -3.0387500000000001e-01 , 8.6152399999999996e-01 , -4.0673900000000002e-01 -3.2471901192932853e+00 , 5.5944080800445910e+00 , 7.3214408000000004e+00 , 7.9925700000000000e-01 , 5.5303600000000001e-02 , 5.9843999999999997e-01 -3.2154768468882118e+00 , 5.5808273143017626e+00 , 7.4422680000000003e+00 , -8.9962799999999998e-01 , -3.3154400000000001e-02 , -4.3539800000000001e-01 -3.2337032465442874e+00 , 5.7889848326122406e+00 , 7.8837584000000005e+00 , 4.0311900000000001e-01 , -7.5538700000000003e-01 , -5.1661000000000001e-01 -3.1775976851905741e+00 , 5.6832009433622002e+00 , 7.8895824000000001e+00 , 4.6882699999999999e-01 , -7.2691399999999995e-01 , -5.0179300000000004e-01 -3.1275561734337209e+00 , 5.6055040650333465e+00 , 7.9359768000000006e+00 , 3.9696300000000001e-01 , -5.9751100000000001e-01 , -6.9670699999999997e-01 -3.0776324660411829e+00 , 5.5225146933136848e+00 , 7.9719192000000003e+00 , -2.7680700000000003e-01 , 6.7204299999999995e-01 , 6.8683099999999997e-01 -3.0325712859021214e+00 , 5.4708175171742175e+00 , 8.0588528000000004e+00 , 6.7171599999999998e-01 , 6.9791499999999995e-01 , 2.4842100000000000e-01 -2.9953919515171834e+00 , 5.4595456365372979e+00 , 8.2162983999999994e+00 , -9.2748100000000000e-01 , -1.8932099999999999e-01 , -3.2239200000000001e-01 -2.9304628115948299e+00 , 5.2951059623138805e+00 , 8.1135775999999993e+00 , 1.1010499999999999e-01 , 2.8915900000000000e-01 , 9.5092800000000000e-01 -2.8967872053095243e+00 , 5.3152859075159133e+00 , 8.3330280000000005e+00 , 3.1295099999999998e-01 , 4.4852399999999998e-01 , 8.3718999999999999e-01 -2.8488782863714199e+00 , 5.2606238732462103e+00 , 8.4256816000000008e+00 , -2.4032800000000001e-01 , -7.2772000000000003e-01 , -6.4239199999999996e-01 -2.7913605097147061e+00 , 5.1316540450171697e+00 , 8.3793703999999991e+00 , -4.7503299999999998e-01 , 8.7832399999999999e-01 , -5.3758599999999997e-02 -2.7426868351242426e+00 , 5.0612911044604978e+00 , 8.4414064000000018e+00 , 6.7237699999999997e-02 , -9.6699400000000002e-01 , -2.4576899999999999e-01 -2.7084070032323417e+00 , 5.1544938019134312e+00 , 8.8492424000000014e+00 , -1.3400999999999999e-01 , -5.0117299999999998e-01 , 8.5490699999999997e-01 -2.6543220310703166e+00 , 5.0748100059436538e+00 , 8.9112784000000005e+00 , 1.2549900000000000e-01 , -6.1996799999999996e-01 , 7.7452500000000002e-01 -2.5875069347484638e+00 , 4.7777578290246812e+00 , 8.4766520000000014e+00 , 6.1217800000000000e-01 , -7.6689099999999999e-01 , 1.9265599999999999e-01 -2.5106940293471878e+00 , 3.9805316138082460e+00 , 6.8169784000000000e+00 , 1.1427900000000001e-01 , -1.6880500000000001e-01 , -9.7900200000000004e-01 -2.4764053153497878e+00 , 3.9150371695378645e+00 , 6.8218664000000002e+00 , -8.9373599999999997e-02 , 4.6567399999999998e-01 , 8.8043199999999999e-01 -2.4420882799021904e+00 , 3.8655073278263274e+00 , 6.8638615999999999e+00 , 1.0355600000000000e-01 , -5.3007099999999996e-01 , -8.4160599999999997e-01 -2.3938521084860072e+00 , 4.2466154694051905e+00 , 8.0758463999999996e+00 , -5.6549499999999997e-01 , -2.3487600000000000e-01 , 7.9059999999999997e-01 -2.3497554004689514e+00 , 4.1527313746381926e+00 , 8.0536943999999995e+00 , 5.8697999999999995e-01 , -6.6426900000000000e-01 , -4.6281899999999998e-01 -2.3026468813135370e+00 , 4.1024337529358661e+00 , 8.1576216000000006e+00 , -9.6216500000000005e-01 , 1.6231000000000001e-01 , 2.1884700000000001e-01 -2.2504266217023376e+00 , 4.0816823422758901e+00 , 8.3597143999999997e+00 , 9.8551000000000000e-01 , 8.8556599999999999e-02 , -1.4466499999999999e-01 -2.2644739622288967e+00 , 3.6045600376992661e+00 , 7.0696880000000002e+00 , 6.4502400000000004e-01 , -2.5224999999999997e-01 , -7.2132700000000005e-01 -2.2313496680746674e+00 , 3.5352268078054836e+00 , 7.0558351999999998e+00 , -3.1151600000000002e-01 , 5.1784799999999997e-01 , 7.9673799999999995e-01 -2.1946350241483370e+00 , 3.4790562628814010e+00 , 7.0906856000000005e+00 , 2.5947999999999999e-01 , 6.9764899999999996e-01 , 6.6779999999999995e-01 -2.1068956140927639e+00 , 3.6017247354505990e+00 , 7.8389031999999998e+00 , 2.3566500000000001e-01 , 7.9782399999999998e-01 , 5.5492200000000003e-01 -2.0158965455285518e+00 , 3.6701018002955035e+00 , 8.4593048000000000e+00 , -9.4024200000000002e-01 , 3.3291599999999999e-01 , -7.1498300000000001e-02 -1.9770158802416455e+00 , 3.5692739606490589e+00 , 8.3932336000000003e+00 , -7.5600199999999995e-01 , -9.2595700000000003e-02 , -6.4798699999999998e-01 -1.9295403249523013e+00 , 3.4899643111253820e+00 , 8.4268984000000007e+00 , 2.5569700000000001e-01 , -5.4521299999999995e-01 , 7.9835000000000000e-01 -1.9105487628427500e+00 , 3.3590627541947882e+00 , 8.1842247999999991e+00 , 3.5271300000000000e-01 , -6.4197700000000002e-01 , 6.8077799999999999e-01 -1.8743106013155280e+00 , 3.2695200503785253e+00 , 8.1325991999999996e+00 , 7.4749699999999997e-01 , -4.3838700000000003e-01 , 4.9906299999999998e-01 -3.7259146386105355e+00 , 3.8635304453347108e+00 , 8.7740319999999983e-01 , -1.0442100000000000e-01 , 1.4265900000000001e-01 , 9.8424800000000001e-01 -3.7623408624318211e+00 , 3.9266779650126962e+00 , 8.7185999999999986e-01 , 9.9876000000000006e-02 , -1.3172000000000000e-01 , -9.8624299999999998e-01 -3.7944094589112058e+00 , 3.9855146276495454e+00 , 8.7557280000000004e-01 , -8.4476599999999999e-02 , 1.2048600000000000e-01 , 9.8911400000000005e-01 -3.8355935652108544e+00 , 4.0551339988031216e+00 , 8.6625439999999987e-01 , -7.1373699999999998e-02 , 1.7413600000000001e-01 , 9.8213200000000001e-01 -3.8766120913400242e+00 , 4.1272453479034574e+00 , 8.5876639999999993e-01 , -5.5314500000000003e-02 , 2.0488000000000001e-01 , 9.7722299999999995e-01 -3.9183500337262362e+00 , 4.1987915577916493e+00 , 8.5382639999999999e-01 , -6.8448200000000001e-02 , 1.8193100000000001e-01 , 9.8092599999999996e-01 -3.9650716004720215e+00 , 4.2786275038060815e+00 , 8.4369679999999980e-01 , -9.3740799999999999e-02 , 1.6084000000000001e-01 , 9.8251900000000003e-01 -4.0114715421903195e+00 , 4.3590031100670519e+00 , 8.3619840000000001e-01 , -5.9710100000000002e-02 , 1.7788699999999999e-01 , 9.8223800000000006e-01 -4.0575845692804400e+00 , 4.4399041896728617e+00 , 8.3123759999999991e-01 , -6.6270200000000001e-02 , 1.8911300000000000e-01 , 9.7971699999999995e-01 -4.1136706458269625e+00 , 4.5351574973614550e+00 , 8.1528399999999990e-01 , -5.4233600000000000e-02 , 1.9824800000000001e-01 , 9.7865000000000002e-01 -4.1653260998928872e+00 , 4.6251513370508635e+00 , 8.0919999999999992e-01 , -6.2788700000000003e-02 , 1.8088199999999999e-01 , 9.8149799999999998e-01 -4.2268541902009904e+00 , 4.7296786690125945e+00 , 7.9304880000000000e-01 , -1.6885200000000000e-02 , 2.0103099999999999e-01 , 9.7943899999999995e-01 -4.2991463712949871e+00 , 4.8479014937260683e+00 , 7.6806799999999997e-01 , -2.0311800000000001e-02 , 2.0783599999999999e-01 , 9.7795299999999996e-01 -4.3659403047559184e+00 , 4.9619960956541904e+00 , 7.5312319999999988e-01 , -5.4918799999999997e-02 , 1.9600300000000001e-01 , 9.7906400000000005e-01 -4.4323031011233942e+00 , 5.0779558221804688e+00 , 7.4201600000000001e-01 , -5.9100300000000001e-02 , 1.8909899999999999e-01 , 9.8017799999999999e-01 -4.5093185481625424e+00 , 5.2088936688794281e+00 , 7.2320239999999991e-01 , -5.7808199999999997e-02 , 1.7821500000000001e-01 , 9.8229200000000005e-01 -4.5818317476486436e+00 , 5.3346636436980974e+00 , 7.1464320000000003e-01 , -5.4280799999999997e-02 , 1.8813099999999999e-01 , 9.8064300000000004e-01 -4.6738966855144390e+00 , 5.4909788196863785e+00 , 6.8796719999999989e-01 , 5.7266299999999999e-02 , -1.9552100000000000e-01 , -9.7902599999999995e-01 -4.7613630949350449e+00 , 5.6422870025990903e+00 , 6.7237760000000013e-01 , -5.6122199999999997e-02 , 1.8989100000000000e-01 , 9.8019999999999996e-01 -4.8591665903701680e+00 , 5.8091354174768828e+00 , 6.5179600000000004e-01 , -6.9613999999999995e-02 , 1.9360900000000000e-01 , 9.7860599999999998e-01 -4.9623047917747343e+00 , 5.9865200986639326e+00 , 6.3191120000000001e-01 , -5.8703699999999998e-02 , 1.9478500000000001e-01 , 9.7908799999999996e-01 -5.0865540643231881e+00 , 6.1963896365906637e+00 , 5.9861039999999988e-01 , 9.2213299999999998e-02 , 3.7864900000000001e-01 , 9.2093499999999995e-01 -5.2049665371769045e+00 , 6.4005554874253914e+00 , 5.7789359999999990e-01 , -9.4577400000000006e-02 , 1.9494200000000000e-01 , 9.7624400000000000e-01 -5.3393389485962102e+00 , 6.6313655998896435e+00 , 5.5055199999999993e-01 , -9.7661700000000004e-02 , 2.0843600000000001e-01 , 9.7314800000000001e-01 -5.0090182642254231e+00 , 6.1791018462495195e+00 , 9.2315280000000000e-01 , 9.8925500000000000e-01 , 8.1702499999999997e-02 , 1.2124200000000000e-01 -4.9943891926865911e+00 , 6.1872997098731570e+00 , 1.0187256800000000e+00 , 9.8925500000000000e-01 , 8.1702499999999997e-02 , 1.2124200000000000e-01 -4.9777663531756140e+00 , 6.1943399985172594e+00 , 1.1133407200000001e+00 , 9.9219900000000005e-01 , 6.9357100000000005e-02 , 1.0358700000000000e-01 -4.9718503043925688e+00 , 6.2151490568082206e+00 , 1.1995317600000002e+00 , 9.9621499999999996e-01 , 6.0608799999999997e-02 , 6.2301799999999997e-02 -4.9590408853164973e+00 , 6.2263580517200579e+00 , 1.2893492800000002e+00 , 9.9781399999999998e-01 , 6.0945500000000000e-02 , 2.5553099999999999e-02 -4.9558233863375474e+00 , 6.2525954341718277e+00 , 1.3714240000000000e+00 , 9.8050400000000004e-01 , 2.1324300000000001e-02 , -1.9533700000000001e-01 -4.9477345373208310e+00 , 6.2681570236839823e+00 , 1.4574808799999999e+00 , -9.4295300000000004e-01 , -5.5679199999999998e-02 , 3.2823799999999997e-01 -4.9960976300600670e+00 , 6.3747590297434185e+00 , 1.5067987199999999e+00 , -9.2596299999999998e-01 , -4.2170199999999998e-02 , 3.7525300000000000e-01 -4.9972728776298663e+00 , 6.4059192451192732e+00 , 1.5879457600000000e+00 , -9.0385099999999996e-01 , -1.9528899999999998e-02 , 4.2740099999999998e-01 -5.0125257359073272e+00 , 6.4612835197241818e+00 , 1.6604108799999999e+00 , -9.3484199999999995e-01 , -5.2029100000000002e-02 , 3.5123100000000002e-01 -5.0426330593202451e+00 , 6.5401604078277957e+00 , 1.7263448000000001e+00 , -9.2640599999999995e-01 , -3.5380099999999998e-02 , 3.7485900000000000e-01 -5.6684773871529899e+00 , 7.5767194506125177e+00 , 1.5025388799999999e+00 , -5.7984899999999995e-01 , -3.6940899999999999e-01 , -7.2616199999999997e-01 -5.7231972725086999e+00 , 7.7047294918090499e+00 , 1.5803641600000000e+00 , -5.7984899999999995e-01 , -3.6940899999999999e-01 , -7.2616300000000000e-01 -5.3320017141291380e+00 , 7.1398999462361372e+00 , 1.9452067680000000e+00 , -3.0343700000000001e-01 , -7.7519800000000000e-02 , 9.4969300000000001e-01 -1.8631496279931117e+01 , 2.9594084776998951e+01 , -1.7173031999999999e+00 , -2.2090799999999999e-01 , -4.2995699999999998e-01 , 8.7540700000000005e-01 -1.8846088746892828e+01 , 3.0156170000860325e+01 , -1.2427096000000000e+00 , -2.4857199999999999e-01 , -4.0006700000000001e-01 , 8.8213299999999994e-01 -2.0742060938154701e+01 , 3.3591209622208765e+01 , -1.1382832000000001e+00 , 6.5246199999999999e-01 , -1.9863500000000001e-01 , -7.3132600000000003e-01 -2.4628777968988029e+01 , 4.0495780826351584e+01 , -1.2972783999999997e+00 , -9.9006000000000005e-01 , -1.0645200000000000e-01 , -9.1917899999999997e-02 -1.8037976519931849e+01 , 2.9371689504615727e+01 , 5.2578959999999997e-01 , -9.0573700000000001e-01 , -3.9650099999999999e-01 , -1.4976000000000000e-01 -1.7828091968798532e+01 , 2.9202548318633227e+01 , 1.0797965599999999e+00 , -6.8759000000000003e-01 , -6.5696699999999997e-01 , -3.0921700000000002e-01 -1.7717009354963917e+01 , 2.9204543378449280e+01 , 1.6143524000000000e+00 , 5.8278700000000005e-01 , 7.9921500000000001e-01 , 1.4701800000000001e-01 -1.7530752348504802e+01 , 2.9071177382929847e+01 , 2.1511390399999999e+00 , 6.1050800000000005e-01 , 7.8922800000000004e-01 , -6.6330899999999998e-02 -1.7539053783763123e+01 , 2.9282543881156631e+01 , 2.6748237600000002e+00 , -6.0380199999999995e-01 , -7.7768199999999998e-01 , 1.7502599999999999e-01 -1.7542216223776308e+01 , 2.9485758932403243e+01 , 3.2049128000000002e+00 , 6.3326800000000005e-01 , 5.6109200000000004e-01 , -5.3305499999999995e-01 -1.7841227827407540e+01 , 3.0228162001382536e+01 , 3.7540016000000000e+00 , -5.7755599999999996e-01 , -5.6338900000000003e-01 , 5.9077999999999997e-01 -1.7785624395016242e+01 , 3.0542770529280794e+01 , 4.8613520000000001e+00 , 4.8542500000000000e-01 , 7.4355300000000002e-01 , -4.5988200000000001e-01 -1.7013958256417499e+01 , 2.9328271002142106e+01 , 5.3092176000000002e+00 , -5.9669099999999997e-01 , -7.2474400000000005e-01 , -3.4453800000000001e-01 -1.6502354379831239e+01 , 2.8579276988479837e+01 , 5.7568128000000005e+00 , -6.2149200000000004e-01 , -7.5713600000000003e-01 , -2.0122999999999999e-01 -1.6462881533841980e+01 , 2.8706996838266427e+01 , 6.2817736000000002e+00 , 4.2257499999999998e-01 , 8.9839000000000002e-01 , 1.1969500000000000e-01 -1.6448927322171812e+01 , 2.8880531708193665e+01 , 6.8188712000000002e+00 , 4.1294500000000001e-01 , 9.0560300000000005e-01 , -9.6744600000000000e-02 -1.6379751368772236e+01 , 2.8955858080197501e+01 , 7.3468584000000003e+00 , 2.5123200000000001e-01 , 9.4534600000000002e-01 , -2.0785300000000001e-01 -1.6367398984201323e+01 , 2.9140859756739665e+01 , 7.8985783999999999e+00 , -6.8216299999999996e-01 , -7.3107299999999997e-01 , 1.3629400000000000e-02 -1.6199590640386759e+01 , 2.9026938545781334e+01 , 8.3986727999999999e+00 , 4.5348800000000000e-01 , 8.9038099999999998e-01 , -3.9639000000000001e-02 -1.6069365321846512e+01 , 2.8986215009452938e+01 , 8.9120063999999992e+00 , 2.7159499999999998e-01 , 9.4501199999999996e-01 , -1.8217900000000001e-01 -1.6128915945125247e+01 , 2.9317481159952973e+01 , 9.5147800000000000e+00 , -7.0803300000000000e-02 , -8.6037100000000000e-01 , 5.0472700000000004e-01 -1.6540112738811569e+01 , 3.0355023113548150e+01 , 1.0314893600000001e+01 , 3.7709800000000002e-03 , -7.3027600000000004e-01 , 6.8314200000000003e-01 -1.6583906067384675e+01 , 3.0675030344048469e+01 , 1.0958757600000000e+01 , 8.3637699999999995e-02 , -7.7769299999999997e-01 , 6.2305600000000005e-01 -1.7210066130852624e+01 , 3.2429873167653426e+01 , 1.2650120000000001e+01 , 7.1341500000000002e-02 , -9.9674799999999997e-01 , 3.7468300000000003e-02 -1.7417116501625319e+01 , 3.3115539400739820e+01 , 1.3488984000000000e+01 , -2.7676000000000001e-01 , 9.1830599999999996e-01 , 2.8305000000000002e-01 -1.6555647828360048e+01 , 3.1602797880582933e+01 , 1.3570416000000002e+01 , 1.4182500000000001e-01 , -8.6438999999999999e-01 , -4.8240600000000000e-01 -1.6353190131406521e+01 , 3.1440467954468634e+01 , 1.4107783999999999e+01 , 1.4182500000000001e-01 , -8.6438999999999999e-01 , -4.8240600000000000e-01 -6.8828546615323658e+00 , 1.1744194204654486e+01 , 6.8200880000000002e+00 , 8.1151499999999999e-01 , -3.3908300000000002e-01 , -4.7588500000000000e-01 -6.9079671176668356e+00 , 1.1885664057815129e+01 , 7.0743368000000002e+00 , 7.1711400000000003e-01 , -5.3452900000000003e-01 , -4.4724300000000000e-01 -6.9905048096729319e+00 , 1.2153262314878337e+01 , 7.3924728000000002e+00 , 7.1711400000000003e-01 , -5.3452900000000003e-01 , -4.4724300000000000e-01 -6.8989974862422363e+00 , 1.2049109698090136e+01 , 7.5516864000000004e+00 , 7.1711400000000003e-01 , -5.3452900000000003e-01 , -4.4724300000000000e-01 -5.5548382175197339e+00 , 9.1985759837860606e+00 , 6.3765592000000009e+00 , 2.6778000000000002e-01 , 8.1311299999999997e-01 , 5.1685700000000001e-01 -5.4467300537021845e+00 , 9.0288003988195591e+00 , 6.4384287999999996e+00 , -6.2243000000000004e-01 , -7.0641500000000002e-01 , -3.3698499999999998e-01 -5.4087419499309988e+00 , 9.0124620484294589e+00 , 6.5758751999999996e+00 , 7.3133499999999996e-01 , 6.7337199999999997e-01 , 1.0825500000000000e-01 -5.4339063088210011e+00 , 9.1379190215785648e+00 , 6.7928087999999995e+00 , 7.8609099999999998e-01 , 6.1218799999999995e-01 , -8.5360699999999998e-02 -5.3999115968816049e+00 , 9.1333943221634097e+00 , 6.9422880000000005e+00 , 7.0103400000000005e-01 , 6.3647399999999998e-01 , -3.2163999999999998e-01 -5.4438378956788096e+00 , 9.3091542269300511e+00 , 7.2021424000000005e+00 , -5.7896000000000003e-01 , -7.4488299999999996e-01 , 3.3159499999999997e-01 -4.6115542404586662e+00 , 7.4455056972174889e+00 , 6.2070080000000001e+00 , -6.2133600000000000e-01 , -7.4395400000000000e-01 , -2.4591299999999999e-01 -4.5616665801885379e+00 , 7.3878321173212100e+00 , 6.2895736000000007e+00 , -6.2133700000000003e-01 , -7.4395400000000000e-01 , -2.4591399999999999e-01 -4.6659856522808880e+00 , 7.6975908695382724e+00 , 6.6160087999999995e+00 , -9.5468699999999995e-01 , 2.9743700000000001e-01 , 1.0203500000000001e-02 -4.7163926416142328e+00 , 7.8847772576735968e+00 , 6.8759775999999997e+00 , 6.3049999999999995e-01 , -6.7481599999999997e-01 , 3.8352599999999998e-01 -4.4380202115348446e+00 , 7.2730367107035461e+00 , 6.5735560000000000e+00 , 3.8971299999999998e-01 , 8.7052700000000005e-01 , 3.0051099999999997e-01 -4.4444093716896331e+00 , 7.3532815960515636e+00 , 6.7571056000000000e+00 , -1.5182399999999999e-01 , 9.6850499999999995e-01 , -1.9735200000000000e-01 -4.3953693567121626e+00 , 7.2959284036984826e+00 , 6.8414184000000002e+00 , 7.6303699999999997e-01 , 2.6878299999999999e-01 , 5.8781799999999995e-01 -4.3260346252770505e+00 , 7.1902324366722006e+00 , 6.8870432000000008e+00 , -5.6534099999999998e-01 , 1.1888899999999999e-01 , -8.1624399999999997e-01 -4.3031884315973192e+00 , 7.1998101145592583e+00 , 7.0245416000000001e+00 , 4.1089300000000001e-01 , -9.0636200000000000e-01 , -9.8357000000000000e-02 -4.2002045073957763e+00 , 7.0015626161783429e+00 , 6.9883496000000003e+00 , 7.8205199999999997e-01 , -3.0942799999999998e-01 , 5.4097099999999998e-01 -4.2142736538747849e+00 , 7.1128112908918517e+00 , 7.2167544000000001e+00 , 8.7684600000000001e-01 , -3.5180699999999998e-01 , -3.2767800000000002e-01 -4.1047841845235400e+00 , 6.8923191279195084e+00 , 7.1530752000000000e+00 , -9.7090100000000001e-01 , -1.6030100000000000e-01 , 1.7791599999999999e-01 -4.2345196816219683e+00 , 7.3270765964656208e+00 , 7.6943120000000000e+00 , -4.0123199999999998e-01 , 1.2516400000000000e-01 , 9.0738399999999997e-01 -4.1519414498763796e+00 , 7.1831155990914297e+00 , 7.7052320000000005e+00 , 1.8506600000000002e-02 , 5.9975199999999995e-01 , 7.9997200000000002e-01 -4.1094667163592931e+00 , 7.1540465261042749e+00 , 7.8259552000000010e+00 , 1.2348100000000001e-02 , 9.0374599999999999e-02 , 9.9583100000000002e-01 -3.9225324978482137e+00 , 6.7004041857302177e+00 , 7.5108456000000006e+00 , 4.9414100000000000e-01 , 8.3957999999999999e-01 , -2.2567899999999999e-01 -3.7784295796274083e+00 , 6.3597660720788998e+00 , 7.2914056000000000e+00 , -5.2033599999999998e-03 , 6.0903600000000002e-01 , 7.9312499999999997e-01 -3.7442371682343740e+00 , 6.3418732228723185e+00 , 7.4060968000000003e+00 , 2.0042299999999999e-01 , 6.7431200000000002e-01 , 7.1072800000000003e-01 -3.7065622260526432e+00 , 6.3141485190967463e+00 , 7.5134248000000001e+00 , -2.2145500000000001e-01 , 9.2700300000000002e-01 , 3.0269200000000002e-01 -3.6479612669592694e+00 , 6.2243915420546427e+00 , 7.5508232000000000e+00 , -3.5325499999999999e-01 , 8.3169099999999996e-01 , 4.2837100000000000e-01 -3.6223510249852366e+00 , 6.2388101853233939e+00 , 7.7118048000000003e+00 , -2.9198999999999999e-02 , 7.9410099999999995e-01 , 6.0708499999999999e-01 -3.4648295853104782e+00 , 5.8143375133520756e+00 , 7.3316016000000008e+00 , 1.4250599999999999e-01 , -6.4012500000000006e-01 , 7.5493800000000000e-01 -3.4967312855965123e+00 , 6.0233995241170639e+00 , 7.7383872000000009e+00 , 2.5014399999999998e-01 , -4.7312100000000001e-01 , 8.4473900000000002e-01 -3.3266965790708962e+00 , 5.5301000970288623e+00 , 7.2352768000000003e+00 , -7.7420800000000001e-01 , -2.6316899999999999e-01 , -5.7562599999999997e-01 -3.2697019221526014e+00 , 5.4226822003990831e+00 , 7.2223080000000000e+00 , 6.5876800000000002e-01 , 2.0422499999999999e-01 , 7.2409800000000002e-01 -3.2440221489213421e+00 , 5.4332559888247669e+00 , 7.3746680000000007e+00 , 9.4235800000000003e-01 , 9.7925899999999996e-02 , 3.1995800000000002e-01 -3.2205929386401224e+00 , 5.4575928400261517e+00 , 7.5537352000000002e+00 , 8.6786200000000002e-01 , 3.8524199999999997e-01 , -3.1369599999999997e-01 -3.2448539479031835e+00 , 5.6886954238665268e+00 , 8.0524464000000009e+00 , 4.2396800000000001e-01 , -7.0622799999999997e-01 , -5.6700399999999995e-01 -3.1781704823942163e+00 , 5.5548963918083150e+00 , 8.0118240000000007e+00 , -5.9164499999999998e-01 , 5.5375600000000003e-01 , 5.8592699999999998e-01 -3.3058426832641183e+00 , 6.2971183664727661e+00 , 9.3830120000000008e+00 , 4.2882799999999999e-01 , 6.5647400000000000e-01 , -6.2060300000000002e-01 -3.0658727299394388e+00 , 5.3617114351832065e+00 , 8.0356088000000003e+00 , 8.4819599999999995e-02 , 2.5940800000000003e-01 , 9.6203600000000000e-01 -3.0035551564165335e+00 , 5.2321824893964930e+00 , 7.9855223999999998e+00 , 4.2477000000000001e-02 , 9.1183399999999998e-02 , 9.9492800000000003e-01 -2.9579874795353489e+00 , 5.1846590854513623e+00 , 8.0771984000000003e+00 , 1.6352000000000000e-01 , 2.1462800000000001e-01 , 9.6291000000000004e-01 -2.9244583938552537e+00 , 5.2096651406927803e+00 , 8.3048648000000007e+00 , -2.9849100000000001e-01 , -9.0172699999999995e-01 , -3.1271800000000000e-01 -2.8735301564165021e+00 , 5.1458700065007266e+00 , 8.3778936000000002e+00 , 4.7947600000000003e-03 , 8.5683900000000002e-01 , 5.1556199999999996e-01 -2.8248831981178100e+00 , 5.0957911039444070e+00 , 8.4773175999999992e+00 , -3.1043100000000001e-01 , 3.3477299999999999e-01 , 8.8969600000000004e-01 -2.7865263117016843e+00 , 5.1458698069162345e+00 , 8.7914911999999994e+00 , 5.1372099999999998e-01 , -3.3520699999999998e-01 , 7.8976400000000002e-01 -2.7314930103380330e+00 , 5.0653676951850661e+00 , 8.8439695999999994e+00 , -1.2238400000000001e-01 , -5.8104400000000000e-01 , 8.0461800000000006e-01 -2.6648603651218576e+00 , 4.8736824900350193e+00 , 8.6477943999999987e+00 , -4.4135400000000002e-01 , -4.6904000000000001e-01 , 7.6498900000000003e-01 -2.5577184051650028e+00 , 4.0012696960307306e+00 , 6.8297911999999998e+00 , -2.2369500000000000e-01 , -3.2113399999999998e-01 , 9.2023600000000005e-01 -2.5214131816601717e+00 , 3.9288616208422251e+00 , 6.8157720000000008e+00 , -9.3199799999999999e-02 , 2.5361499999999998e-01 , 9.6280500000000002e-01 -2.4850045118007862e+00 , 3.8805101239668991e+00 , 6.8579128000000003e+00 , 2.9407499999999998e-03 , 5.2232800000000001e-01 , 8.5274000000000005e-01 -2.4475310556366647e+00 , 4.2672274981846030e+00 , 8.0684000000000005e+00 , -4.6741100000000002e-01 , -8.8140399999999997e-01 , -6.8227399999999994e-02 -2.3932554891642632e+00 , 4.4365363117714329e+00 , 8.7812160000000006e+00 , -3.0639000000000000e-02 , -7.8853799999999996e-01 , 6.1422200000000005e-01 -2.3523371379032874e+00 , 4.1203908289362392e+00 , 8.1309040000000010e+00 , -4.6698299999999998e-01 , 8.2806900000000006e-01 , 3.1020799999999998e-01 -2.2985884825402554e+00 , 4.1171463458939623e+00 , 8.3826567999999995e+00 , 9.8551000000000000e-01 , 8.8556599999999999e-02 , -1.4466499999999999e-01 -2.2507926530898654e+00 , 4.0225866827577752e+00 , 8.3563551999999994e+00 , -8.7492599999999998e-01 , 2.2068900000000000e-01 , -4.3104500000000001e-01 -2.2636599863224593e+00 , 3.5603784351146821e+00 , 7.0610767999999995e+00 , -5.1286100000000001e-01 , 4.0724300000000002e-01 , 7.5572899999999998e-01 -2.2272870131047284e+00 , 3.4971462061525473e+00 , 7.0662144000000007e+00 , -1.6321200000000000e-01 , 6.5139400000000003e-01 , 7.4097800000000003e-01 -2.1845470541986138e+00 , 3.4594917040315041e+00 , 7.1706095999999997e+00 , 5.8599100000000004e-01 , 7.6256400000000002e-01 , 2.7406300000000000e-01 -2.0948859515954084e+00 , 3.5678164761927187e+00 , 7.8893952000000009e+00 , 4.9093100000000001e-01 , 8.4775699999999998e-01 , 2.0073500000000000e-01 -2.0095333862760603e+00 , 3.6061084288160052e+00 , 8.3985479999999999e+00 , 5.8962400000000004e-01 , -4.3554300000000001e-01 , 6.8018100000000004e-01 -1.9562479685958400e+00 , 3.5373786304588002e+00 , 8.4729495999999997e+00 , -8.3811800000000003e-01 , 5.3468199999999999e-01 , -1.0804900000000001e-01 -1.9329751718261363e+00 , 3.4057259510620872e+00 , 8.2309000000000001e+00 , -2.1833700000000000e-01 , 8.7810999999999995e-01 , -4.2573600000000000e-01 -1.9021541502155053e+00 , 3.3017248617051607e+00 , 8.0981231999999999e+00 , -5.8967400000000003e-01 , 3.3992899999999998e-01 , -7.3262000000000005e-01 -1.8493437070048422e+00 , 3.2361474643479129e+00 , 8.1777040000000003e+00 , -6.5558899999999998e-01 , -7.5474600000000003e-01 , -2.3716999999999998e-02 -3.7893817832087580e+00 , 3.8563082575617242e+00 , 8.9727759999999979e-01 , -1.1524000000000000e-01 , 1.5942700000000001e-01 , 9.8046100000000003e-01 -3.8319409527866628e+00 , 3.9242220128556200e+00 , 8.8505759999999989e-01 , 9.7954899999999998e-02 , -1.5904099999999999e-01 , -9.8240099999999997e-01 -3.8711274682026877e+00 , 3.9878866252448404e+00 , 8.8262399999999985e-01 , 7.4660900000000002e-02 , -1.4686800000000000e-01 , -9.8633400000000004e-01 -3.9090646854691657e+00 , 4.0519559068490230e+00 , 8.8198960000000004e-01 , -4.2226100000000003e-02 , 1.6088900000000000e-01 , 9.8606899999999997e-01 -3.9623121884384327e+00 , 4.1336771363983758e+00 , 8.6155359999999992e-01 , -5.4234600000000001e-02 , 1.6880400000000001e-01 , 9.8415699999999995e-01 -4.0008073741135544e+00 , 4.1996528713523551e+00 , 8.6518319999999993e-01 , 9.0216299999999999e-02 , -1.7041300000000001e-01 , -9.8123400000000005e-01 -4.0494156993882768e+00 , 4.2786615685206213e+00 , 8.5662400000000005e-01 , -5.2624100000000000e-02 , 1.7412000000000000e-01 , 9.8331700000000000e-01 -4.1038590288914438e+00 , 4.3640633378810367e+00 , 8.4412319999999985e-01 , -7.5596200000000002e-02 , 1.6696700000000000e-01 , 9.8306000000000004e-01 -4.1528724377195045e+00 , 4.4441622443295863e+00 , 8.4105519999999978e-01 , -3.2108499999999998e-02 , 1.7494299999999999e-01 , 9.8405500000000001e-01 -4.2169425358318939e+00 , 4.5445251847051491e+00 , 8.2060879999999981e-01 , -4.9879600000000003e-02 , 1.7324200000000001e-01 , 9.8361500000000002e-01 -4.2714676554457380e+00 , 4.6337636823772641e+00 , 8.1662559999999984e-01 , -2.0998400000000000e-02 , 1.7785799999999999e-01 , 9.8383200000000004e-01 -4.3408978114420584e+00 , 4.7435432066069065e+00 , 7.9657439999999990e-01 , -1.1480699999999999e-03 , 2.0659300000000000e-01 , 9.7842600000000002e-01 -4.4159839006894419e+00 , 4.8611226708067994e+00 , 7.7429759999999992e-01 , -4.5705099999999999e-02 , 2.0349600000000001e-01 , 9.7800799999999999e-01 -4.4866426655707228e+00 , 4.9745257110151284e+00 , 7.6198399999999999e-01 , -4.4423999999999998e-02 , 1.7544100000000001e-01 , 9.8348700000000000e-01 -4.5618740434698637e+00 , 5.0958380485543771e+00 , 7.4772559999999988e-01 , -4.3758900000000003e-02 , 1.7902999999999999e-01 , 9.8287000000000002e-01 -4.6426486825523980e+00 , 5.2251397167847848e+00 , 7.3213599999999990e-01 , -5.2306400000000003e-02 , 1.7080999999999999e-01 , 9.8391499999999998e-01 -4.7289997629152483e+00 , 5.3645703579664428e+00 , 7.1534000000000009e-01 , -4.3326200000000002e-02 , 1.8372900000000000e-01 , 9.8202199999999995e-01 -4.8207534784596344e+00 , 5.5111659592383768e+00 , 6.9833599999999985e-01 , 5.4828500000000002e-02 , -1.8549800000000000e-01 , -9.8111400000000004e-01 -4.9179688970556263e+00 , 5.6680901168748807e+00 , 6.8101999999999996e-01 , -5.1797599999999999e-02 , 1.8528700000000001e-01 , 9.8131800000000002e-01 -5.0265158714437694e+00 , 5.8416686865433158e+00 , 6.5924239999999990e-01 , -2.1968299999999999e-01 , 1.3062699999999999e-01 , 9.6678600000000003e-01 -5.1462456490908366e+00 , 6.0310650387893494e+00 , 6.3402240000000010e-01 , -7.1351399999999995e-02 , 5.9827900000000001e-01 , 7.9810400000000004e-01 -5.2701345257912919e+00 , 6.2313005377482993e+00 , 6.1079919999999999e-01 , -1.3227900000000001e-01 , 3.1044899999999997e-01 , 9.4134099999999998e-01 -5.3617062091504657e+00 , 6.3890543970761993e+00 , 6.2279039999999997e-01 , -1.0519800000000000e-01 , 2.0265900000000001e-01 , 9.7358199999999995e-01 -5.0623840707574219e+00 , 6.0086535780340018e+00 , 9.5812799999999987e-01 , -9.3655100000000002e-01 , -2.3146000000000000e-01 , -2.6324399999999998e-01 -5.0410464619243438e+00 , 6.0091140279080903e+00 , 1.0560055199999998e+00 , -9.7580299999999998e-01 , -1.9147600000000001e-01 , -1.0557500000000000e-01 -5.0197698877254417e+00 , 6.0072841494097764e+00 , 1.1530780800000000e+00 , 9.6557099999999996e-01 , 1.6586500000000001e-01 , 2.0040500000000000e-01 -5.0141283566043313e+00 , 6.0276288905103543e+00 , 1.2370435199999998e+00 , 9.7926100000000005e-01 , 1.2022500000000000e-01 , 1.6307800000000000e-01 -5.0015546124688059e+00 , 6.0384081405183254e+00 , 1.3247363200000000e+00 , 9.9822299999999997e-01 , 2.2496599999999999e-02 , -5.5171900000000003e-02 -4.9996499101804837e+00 , 6.0641369987827893e+00 , 1.4046103999999999e+00 , 9.7509900000000005e-01 , -2.5877500000000002e-03 , -2.2175700000000001e-01 -5.0130422347669388e+00 , 6.1126086488088722e+00 , 1.4741094399999999e+00 , -9.3305899999999997e-01 , -3.0096800000000000e-02 , 3.5846200000000000e-01 -5.0436154443884798e+00 , 6.1841094638352567e+00 , 1.5351033599999999e+00 , -9.1501500000000002e-01 , -5.8562200000000002e-02 , 3.9914600000000000e-01 -5.0555941613242190e+00 , 6.2310742361457176e+00 , 1.6074166400000001e+00 , -9.0310900000000005e-01 , -2.7531199999999999e-02 , 4.2852800000000002e-01 -5.0616358311179717e+00 , 6.2685372976610720e+00 , 1.6839866400000001e+00 , -9.0738799999999997e-01 , -3.7498200000000002e-02 , 4.1861700000000002e-01 -5.8068540821956516e+00 , 7.4463079076745187e+00 , 1.4908409599999999e+00 , -6.6386299999999998e-01 , -2.9415400000000003e-01 , -6.8757500000000005e-01 -5.4410332942255373e+00 , 6.9950612463394508e+00 , 1.9399775440000000e+00 , 2.8422700000000001e-01 , 6.3818799999999995e-02 , -9.5663100000000001e-01 -1.9076984567675481e+01 , 2.8491548312203985e+01 , -1.7133200000000000e+00 , -4.2204100000000000e-01 , -3.6297799999999998e-02 , 9.0585000000000004e-01 -2.0191007549384846e+01 , 3.0439303947817280e+01 , -1.4792888000000004e+00 , -1.6495299999999999e-01 , -4.0040399999999997e-02 , 9.8548800000000003e-01 -2.1133913237090432e+01 , 3.2141839754777138e+01 , -1.1338424000000003e+00 , -7.5471999999999995e-01 , 3.0023800000000000e-01 , 5.8331299999999997e-01 -2.5164698922323428e+01 , 3.8815208322318483e+01 , -1.3234864000000002e+00 , 9.9434699999999998e-01 , 7.8271400000000005e-02 , 7.1752899999999994e-02 -1.8683919873892446e+01 , 2.8613064648970902e+01 , 4.5031679999999996e-01 , -7.8541700000000003e-01 , -5.3803599999999996e-01 , -3.0600200000000000e-01 -1.8697853476098089e+01 , 2.8823344423922215e+01 , 9.6977183999999994e-01 , -7.7021499999999998e-01 , -6.0793299999999995e-01 , -1.9283600000000001e-01 -1.8527495412128125e+01 , 2.8732994518552012e+01 , 1.5124771200000000e+00 , 6.8607399999999996e-01 , 7.1753299999999998e-01 , 1.2020500000000001e-01 -1.8416825975193198e+01 , 2.8740803556425266e+01 , 2.0443849119999999e+00 , -5.9792699999999999e-01 , -8.0152599999999996e-01 , 6.3181399999999999e-03 -1.8330128424669727e+01 , 2.8785306508206354e+01 , 2.5734903199999999e+00 , -6.3122100000000003e-01 , -7.6924099999999995e-01 , 9.9134000000000000e-02 -1.8354979090851828e+01 , 2.9017112255241035e+01 , 3.1021608000000001e+00 , -5.0258100000000006e-01 , -6.6056800000000004e-01 , 5.5772999999999995e-01 -1.8336974043648283e+01 , 2.9179745032365446e+01 , 3.6365544000000001e+00 , 5.8990799999999999e-01 , 5.3490800000000005e-01 , -6.0488200000000003e-01 -1.8750575374714778e+01 , 3.0077171716985440e+01 , 4.2057984000000008e+00 , 5.7821299999999998e-01 , 5.9619400000000000e-01 , -5.5697600000000003e-01 -1.8745647082067816e+01 , 3.0270045245857560e+01 , 4.7664936000000004e+00 , -5.7157899999999995e-01 , -7.6847799999999999e-01 , 2.8764400000000001e-01 -1.7550567997519167e+01 , 2.8416961380907473e+01 , 5.1694519999999997e+00 , 1.7738899999999999e-01 , 8.5271399999999997e-01 , 4.9133800000000000e-01 -1.7509665467645100e+01 , 2.8537600044071077e+01 , 5.6961392000000002e+00 , -7.0572999999999997e-02 , -9.9600999999999995e-01 , -5.4629299999999999e-02 -1.7371219922270612e+01 , 2.8489267731836286e+01 , 6.2068624000000003e+00 , 5.4618999999999995e-01 , 8.3505700000000005e-01 , 6.6002099999999994e-02 -1.7313921079513086e+01 , 2.8585571880338041e+01 , 6.7355776000000001e+00 , -3.6815700000000001e-01 , -9.1800300000000001e-01 , 1.4741199999999999e-01 -1.7242473840713870e+01 , 2.8655874884683286e+01 , 7.2644384000000004e+00 , -4.0516200000000002e-01 , -8.9715400000000001e-01 , 1.7595100000000000e-01 -1.7254947318912151e+01 , 2.8878592506630088e+01 , 7.8242288000000002e+00 , -4.0894000000000003e-01 , -9.0666100000000005e-01 , 1.0360999999999999e-01 -1.7196806874639787e+01 , 2.8976954474096239e+01 , 8.3688560000000010e+00 , -3.6269899999999999e-01 , -9.2791599999999996e-01 , 8.6151400000000003e-02 -1.7172071888190104e+01 , 2.9139284177395830e+01 , 8.9322240000000015e+00 , -3.6269800000000002e-01 , -9.2791599999999996e-01 , 8.6151599999999995e-02 -1.6872947250140577e+01 , 2.8800520567685840e+01 , 9.3844887999999997e+00 , -5.1640200000000003e-01 , -8.5572999999999999e-01 , 3.2486000000000001e-02 -1.7905438414196102e+01 , 3.0915964942068509e+01 , 1.0460046400000001e+01 , 3.3840099999999998e-02 , -8.2583300000000004e-01 , 5.6289800000000001e-01 -1.8384220547549944e+01 , 3.2034696414827337e+01 , 1.1345138400000000e+01 , 8.0394599999999997e-02 , -7.9010000000000002e-01 , 6.0768299999999997e-01 -1.9379183323055848e+01 , 3.4142108947275034e+01 , 1.2573368000000000e+01 , 3.8990000000000002e-01 , -8.3917200000000003e-01 , 3.7916699999999998e-01 -1.8728454665863786e+01 , 3.3174860549781911e+01 , 1.2908768000000000e+01 , -3.3249200000000001e-01 , 9.0058400000000005e-01 , -2.7999400000000002e-01 -1.7992365273031126e+01 , 3.2537623854643243e+01 , 1.4564344000000000e+01 , 2.2475899999999999e-01 , -9.7398700000000005e-01 , -2.8869100000000002e-02 -1.7957970376116780e+01 , 3.2736090768264262e+01 , 1.5273000000000000e+01 , 2.2475899999999999e-01 , -9.7398700000000005e-01 , -2.8869100000000002e-02 -1.7958259083997508e+01 , 3.3008971573964772e+01 , 1.6026896000000001e+01 , 2.2475899999999999e-01 , -9.7398700000000005e-01 , -2.8869100000000002e-02 -7.2097253340409733e+00 , 1.1969743756860137e+01 , 7.5350048000000003e+00 , 7.1711400000000003e-01 , -5.3452900000000003e-01 , -4.4724300000000000e-01 -5.7915442463775779e+00 , 9.1834731611959270e+00 , 6.3837456000000001e+00 , 1.8012400000000001e-01 , 8.1636500000000001e-01 , 5.4872900000000002e-01 -5.6491198454644556e+00 , 8.9564214838410621e+00 , 6.4174832000000004e+00 , -2.9633999999999999e-01 , -7.6132400000000000e-01 , -5.7668799999999998e-01 -5.6398690955668425e+00 , 9.0014810345970524e+00 , 6.5864623999999994e+00 , -4.1367599999999999e-01 , -7.9225199999999996e-01 , -4.4856400000000002e-01 -5.5710519206426214e+00 , 8.9249549456709278e+00 , 6.6926152000000005e+00 , -8.1106100000000003e-01 , -5.5176099999999995e-01 , -1.9426700000000000e-01 -5.5261095777112086e+00 , 8.8973275723814673e+00 , 6.8252568000000000e+00 , -3.5767700000000002e-01 , -8.9836899999999997e-01 , 2.5495200000000001e-01 -5.6114901857884316e+00 , 9.1485979593504911e+00 , 7.1261495999999998e+00 , 4.4233899999999998e-01 , 7.3981699999999995e-01 , -5.0695900000000005e-01 -4.7850417324837338e+00 , 7.4392777978113971e+00 , 6.2183751999999997e+00 , 8.5424299999999997e-01 , 5.1749199999999995e-01 , 4.9706300000000002e-02 -4.6969928644436418e+00 , 7.3017314180667503e+00 , 6.2494503999999997e+00 , 2.3354800000000001e-01 , 8.5741599999999996e-01 , 4.5857799999999999e-01 -5.1363958434817114e+00 , 8.3289570357511948e+00 , 7.0568440000000008e+00 , -1.4352500000000001e-01 , -1.2009100000000000e-01 , 9.8233300000000001e-01 -5.0492704166865403e+00 , 8.2057005621933357e+00 , 7.1169352000000003e+00 , -9.0286400000000003e-02 , -9.8582400000000001e-02 , 9.9102500000000004e-01 -4.5777559261741967e+00 , 7.2089467799737532e+00 , 6.5435103999999997e+00 , 4.0306900000000001e-01 , 8.3369499999999996e-01 , 3.7747599999999998e-01 -4.8784885368660760e+00 , 7.9577791176001975e+00 , 7.2255112000000006e+00 , 1.5488199999999999e-01 , -7.8419899999999998e-01 , 6.0086899999999999e-01 -4.4575951934769087e+00 , 7.0542370329208577e+00 , 6.6722624000000001e+00 , -8.1385600000000002e-01 , -2.2727400000000000e-01 , -5.3477500000000000e-01 -4.4638175802236217e+00 , 7.1303838979382332e+00 , 6.8565296000000000e+00 , 5.9221000000000001e-01 , -1.0537299999999999e-01 , 7.9886500000000005e-01 -4.3481274291666994e+00 , 6.9201695211314442e+00 , 6.8109359999999999e+00 , -7.0662599999999998e-01 , -2.5093400000000001e-03 , -7.0758299999999996e-01 -4.4810930985940267e+00 , 7.3089441301004747e+00 , 7.2669240000000004e+00 , -2.0838899999999999e-01 , -9.7758800000000001e-01 , -2.9940200000000000e-02 -4.4257957704516553e+00 , 7.2452395975835895e+00 , 7.3499992000000001e+00 , 2.8770800000000002e-01 , -8.3778300000000006e-01 , 4.6405200000000002e-01 -4.2751233716039723e+00 , 6.9444955549721294e+00 , 7.2164632000000006e+00 , 3.7813500000000000e-01 , 4.9745499999999998e-01 , 7.8073899999999996e-01 -4.2291541412628337e+00 , 6.9031409397394441e+00 , 7.3123824000000006e+00 , 9.0613200000000005e-01 , 3.9047599999999999e-01 , 1.6264700000000001e-01 -4.3449726139564753e+00 , 7.2770959207071968e+00 , 7.8123728000000003e+00 , 9.3517000000000003e-02 , -4.0213600000000002e-02 , 9.9480500000000005e-01 -4.2549420380038168e+00 , 7.1274963755430738e+00 , 7.8148064000000002e+00 , 1.2348100000000001e-02 , 9.0374499999999997e-02 , 9.9583100000000002e-01 -4.0069718568236983e+00 , 6.5518750017433343e+00 , 7.3713504000000007e+00 , 4.6945500000000001e-01 , 2.4516199999999999e-01 , -8.4823800000000005e-01 -3.9526078588970144e+00 , 6.4869164973653275e+00 , 7.4379000000000000e+00 , 3.9044499999999999e-01 , -8.4459799999999996e-01 , -3.6634200000000000e-01 -3.9968778915138161e+00 , 6.6912380223328833e+00 , 7.8026592000000008e+00 , 6.1508799999999997e-01 , -7.1847799999999995e-01 , 3.2474199999999998e-01 -3.8804639877111873e+00 , 6.4519286961437174e+00 , 7.6810000000000009e+00 , 6.5150799999999998e-01 , -7.5034900000000004e-01 , -1.1186599999999999e-01 -3.8359150938317068e+00 , 6.4149792686727167e+00 , 7.7832216000000001e+00 , -5.8943599999999996e-01 , 7.0598000000000005e-01 , 3.9262999999999998e-01 -3.7438739887978136e+00 , 6.2385494743585479e+00 , 7.7206240000000008e+00 , 5.7425400000000004e-01 , -6.0273800000000000e-01 , -5.5402099999999999e-01 -3.5238001294944783e+00 , 5.6650811620411750e+00 , 7.1515152000000004e+00 , 1.0357500000000000e-01 , -5.5651899999999999e-01 , 8.2435300000000000e-01 -3.4447840698409218e+00 , 5.5074211915993878e+00 , 7.0794120000000005e+00 , 8.5033999999999998e-01 , 2.0670899999999999e-04 , 5.2623399999999998e-01 -3.4326807195423696e+00 , 5.5552981793027767e+00 , 7.2722799999999994e+00 , 5.6056300000000003e-01 , 6.2747299999999995e-01 , 5.4041399999999995e-01 -3.3794813901251315e+00 , 5.4785741312899390e+00 , 7.3017432000000007e+00 , 1.0048200000000000e-01 , 7.5391399999999997e-01 , 6.4924300000000001e-01 -3.3343703624880301e+00 , 5.4248718840527452e+00 , 7.3628848000000007e+00 , -1.6209299999999999e-01 , 8.2578600000000002e-01 , 5.4018800000000000e-01 -3.2769648874910571e+00 , 5.3287462641901300e+00 , 7.3636752000000003e+00 , -8.5789000000000004e-01 , -4.2851499999999998e-01 , -2.8354900000000000e-01 -3.2412139775414142e+00 , 5.3078103300210397e+00 , 7.4734680000000004e+00 , -8.9668800000000004e-01 , -3.9217600000000002e-01 , 2.0530100000000001e-01 -3.5653958141203841e+00 , 6.6714844096666308e+00 , 9.7523368000000019e+00 , -4.1784600000000000e-01 , -5.1059399999999999e-01 , 7.5146400000000002e-01 -3.3994914681257886e+00 , 6.2016247942014724e+00 , 9.2188896000000007e+00 , -9.1745800000000000e-01 , 3.1553300000000001e-01 , -2.4229999999999999e-01 -3.1531179343426126e+00 , 5.3559666687015808e+00 , 8.0152143999999996e+00 , -1.6654600000000000e-01 , 1.2871600000000000e-01 , 9.7759700000000005e-01 -3.0964483329901284e+00 , 5.2694026395883835e+00 , 8.0372208000000001e+00 , 2.5835399999999997e-01 , 1.2964600000000000e-02 , 9.6596300000000002e-01 -3.0388735819623189e+00 , 5.1724892875724420e+00 , 8.0393216000000010e+00 , 9.5707899999999999e-02 , 1.4501099999999999e-02 , 9.9530399999999997e-01 -3.0086492929747637e+00 , 5.2144857821613568e+00 , 8.2940176000000001e+00 , -8.4114000000000000e-01 , -5.0792199999999998e-01 , -1.8573700000000001e-01 -2.9663655631272707e+00 , 5.2107533007207820e+00 , 8.4773072000000003e+00 , 2.6003900000000002e-01 , 7.0687199999999994e-01 , 6.5780799999999995e-01 -2.9407469895065406e+00 , 5.3129487815048124e+00 , 8.8842072000000005e+00 , 2.1380900000000000e-01 , -3.5066700000000001e-01 , 9.1176699999999999e-01 -2.8707929680576001e+00 , 5.1701567286057761e+00 , 8.8088072000000004e+00 , -6.9940799999999997e-02 , 4.9187199999999998e-01 , -8.6785400000000001e-01 -2.8105588800387680e+00 , 5.0739034045045299e+00 , 8.8241575999999995e+00 , 2.5354100000000002e-01 , -3.8328400000000001e-01 , 8.8815000000000000e-01 -2.7485342481712243e+00 , 4.9681612085669773e+00 , 8.8183752000000002e+00 , 1.2619200000000000e-01 , -7.1190100000000001e-01 , 6.9084900000000005e-01 -2.6086351380137596e+00 , 4.0440304575839345e+00 , 6.9000744000000003e+00 , -1.0361300000000000e-01 , -3.1302500000000000e-01 , 9.4407600000000003e-01 -2.5673274130700730e+00 , 3.9486530820212193e+00 , 6.8289591999999999e+00 , -2.6325299999999999e-02 , 1.3253200000000001e-01 , 9.9082899999999996e-01 -2.5290050362845893e+00 , 3.8903314513863387e+00 , 6.8422608000000000e+00 , 4.4514400000000003e-02 , 3.9514100000000002e-01 , 9.1754100000000005e-01 -2.5098186468947055e+00 , 4.4998943794227557e+00 , 8.6251536000000009e+00 , 6.8456799999999995e-01 , 5.5647800000000003e-01 , 4.7084900000000002e-01 -2.4541835840211137e+00 , 4.4711075792729318e+00 , 8.8024216000000006e+00 , -4.0440999999999999e-01 , 6.6630199999999995e-01 , 6.2649400000000000e-01 -2.4026754504304164e+00 , 4.1902422863891706e+00 , 8.2617048000000004e+00 , -4.8359099999999999e-01 , 8.6894400000000005e-01 , 1.0524200000000000e-01 -2.3520484637908798e+00 , 4.1125858992858682e+00 , 8.2870704000000011e+00 , -6.9239799999999996e-01 , 6.1016899999999996e-01 , -3.8507100000000000e-01 -2.3008472805687252e+00 , 4.0294649086832726e+00 , 8.2905024000000012e+00 , 7.1733999999999998e-01 , 4.6500300000000000e-01 , 5.1883999999999997e-01 -2.2936538644258206e+00 , 3.6162477657588834e+00 , 7.1761112000000002e+00 , -9.1151300000000002e-01 , -2.0902499999999999e-01 , 3.5419299999999998e-01 -2.2594000461107573e+00 , 3.5244332041807969e+00 , 7.0820015999999999e+00 , 3.4395100000000001e-01 , -4.6931299999999998e-01 , -8.1329099999999999e-01 -2.2197804599905653e+00 , 3.4672917834579002e+00 , 7.1061296000000000e+00 , 1.2432300000000000e-01 , 6.5637599999999996e-01 , 7.4412000000000000e-01 -2.1308495904674811e+00 , 3.5920426589893699e+00 , 7.8644664000000004e+00 , 2.3566599999999999e-01 , 7.9782399999999998e-01 , 5.5492200000000003e-01 -2.0477087509708687e+00 , 3.6355156903310935e+00 , 8.3734528000000008e+00 , -4.8260100000000000e-01 , 6.4671100000000004e-01 , -5.9064499999999998e-01 -1.9961930996660109e+00 , 3.5576261043619928e+00 , 8.3974767999999997e+00 , -7.5600199999999995e-01 , -9.2595700000000003e-02 , -6.4798699999999998e-01 -1.9486522172791469e+00 , 3.4720742477994611e+00 , 8.3790688000000006e+00 , 2.8743800000000003e-01 , -8.8549999999999995e-01 , 3.6506100000000002e-01 -1.9208786754780971e+00 , 3.3526887350099650e+00 , 8.1758632000000002e+00 , 3.5271300000000000e-01 , -6.4197700000000002e-01 , 6.8077799999999999e-01 -1.8783760741026680e+00 , 3.2673623242711103e+00 , 8.1333167999999993e+00 , 6.2449699999999997e-01 , -5.3184900000000002e-01 , 5.7196199999999997e-01 -3.8279271267412698e+00 , 3.8020019240957224e+00 , 8.9946159999999997e-01 , 1.1280600000000000e-01 , -1.3439000000000001e-01 , -9.8448700000000000e-01 -3.8632104376622980e+00 , 3.8583810650828823e+00 , 9.0223840000000011e-01 , -5.2063499999999999e-02 , 1.7027700000000001e-01 , 9.8402000000000001e-01 -3.9076706907836307e+00 , 3.9254492523068336e+00 , 8.9149519999999982e-01 , -6.7073900000000006e-02 , 1.6870900000000000e-01 , 9.8338099999999995e-01 -3.9528864406275588e+00 , 3.9929783204938838e+00 , 8.8319600000000009e-01 , -6.8816799999999997e-02 , 1.4741899999999999e-01 , 9.8667700000000003e-01 -3.9937908362875501e+00 , 4.0572246179760807e+00 , 8.8404879999999997e-01 , -5.5568899999999997e-02 , 1.9555200000000000e-01 , 9.7911800000000004e-01 -4.0447608664357251e+00 , 4.1323825546362514e+00 , 8.7271279999999996e-01 , -8.7881799999999996e-02 , 1.4080100000000001e-01 , 9.8612999999999995e-01 -4.0903063401843260e+00 , 4.2033104796997653e+00 , 8.7080959999999985e-01 , -8.3622000000000002e-02 , 1.5645300000000001e-01 , 9.8413899999999999e-01 -4.1469117800859543e+00 , 4.2863172536311929e+00 , 8.5745600000000000e-01 , -8.0009899999999995e-02 , 1.7696000000000001e-01 , 9.8096099999999997e-01 -4.1980783385735174e+00 , 4.3651123351897443e+00 , 8.5362880000000008e-01 , -4.7446099999999998e-02 , 1.8301200000000001e-01 , 9.8196499999999998e-01 -4.2591982572274567e+00 , 4.4572051127396470e+00 , 8.3892319999999998e-01 , -5.4385999999999997e-02 , 1.7868000000000001e-01 , 9.8240300000000003e-01 -4.3108039135728724e+00 , 4.5381266164461334e+00 , 8.4047279999999991e-01 , -3.3868400000000000e-02 , 1.7127500000000001e-01 , 9.8464099999999999e-01 -4.3895767632377876e+00 , 4.6513386694192542e+00 , 8.1312080000000009e-01 , 6.0407200000000003e-03 , 1.9164300000000001e-01 , 9.8144600000000004e-01 -4.4628111524820024e+00 , 4.7594168648165995e+00 , 7.9601279999999996e-01 , -2.6715900000000001e-02 , 1.9622300000000001e-01 , 9.8019500000000004e-01 -4.5356668762738455e+00 , 4.8703576930711545e+00 , 7.8244079999999983e-01 , -4.9470500000000001e-02 , 1.9104199999999999e-01 , 9.8033499999999996e-01 -4.6151315583532986e+00 , 4.9881137698723599e+00 , 7.6726720000000004e-01 , -4.2963399999999999e-02 , 1.8980100000000000e-01 , 9.8088200000000003e-01 -4.6941847926293185e+00 , 5.1087895033631519e+00 , 7.5594159999999988e-01 , -5.7820900000000001e-02 , 1.7660899999999999e-01 , 9.8258100000000004e-01 -4.7787750896056096e+00 , 5.2374851456223324e+00 , 7.4338879999999996e-01 , -5.2287300000000002e-02 , 1.7377799999999999e-01 , 9.8339600000000005e-01 -4.8748924045269639e+00 , 5.3813998202191549e+00 , 7.2456480000000001e-01 , -5.7396200000000001e-02 , 1.8781100000000001e-01 , 9.8052700000000004e-01 -4.9774088905685288e+00 , 5.5335834422806949e+00 , 7.0596959999999997e-01 , -2.1568300000000001e-01 , 1.1725400000000000e-01 , 9.6939799999999998e-01 -5.0843282771353948e+00 , 5.6961887250047347e+00 , 6.8734319999999993e-01 , -1.4617700000000000e-01 , 2.7118399999999998e-01 , 9.5136299999999996e-01 -5.1975157054182279e+00 , 5.8672910505230007e+00 , 6.7004799999999998e-01 , 3.3360499999999998e-01 , -2.7569100000000002e-01 , -9.0149999999999997e-01 -5.3001555588935112e+00 , 6.0261424944175159e+00 , 6.6878959999999976e-01 , -1.9273999999999999e-01 , 2.7521299999999999e-01 , 9.4186499999999995e-01 -5.2074325758371387e+00 , 5.9376713487284967e+00 , 8.3177840000000014e-01 , -9.4675799999999999e-01 , 1.5168000000000001e-01 , -2.8397499999999998e-01 -5.1013114119905660e+00 , 5.8303865754468749e+00 , 9.9868175999999997e-01 , 9.8014000000000001e-01 , -3.2421300000000000e-02 , 1.9563900000000001e-01 -5.1322907051400080e+00 , 5.8978948824684636e+00 , 1.0557382400000002e+00 , 9.7734200000000004e-01 , 1.5573899999999999e-01 , 1.4334500000000000e-01 -5.1336122413361265e+00 , 5.9277052538985942e+00 , 1.1354719200000001e+00 , -9.4729600000000003e-01 , -2.9681000000000002e-01 , -1.2055600000000000e-01 -5.0468749762746938e+00 , 5.8417951368632721e+00 , 1.2755474400000000e+00 , -9.1615899999999995e-01 , -2.1289700000000000e-01 , -3.3960099999999999e-01 -5.0462741099380439e+00 , 5.8681066414794181e+00 , 1.3533176000000000e+00 , -9.6001499999999995e-01 , -1.3699000000000000e-01 , -2.4414000000000000e-01 -5.0455888238168356e+00 , 5.8923742322764472e+00 , 1.4314985600000001e+00 , 9.7475100000000003e-01 , -1.4028100000000000e-02 , -2.2285300000000000e-01 -5.0544380196219976e+00 , 5.9317965171316143e+00 , 1.5025440800000001e+00 , -9.4270299999999996e-01 , 2.0070600000000001e-02 , 3.3302900000000002e-01 -5.0863711332997168e+00 , 6.0027134649145371e+00 , 1.5609317599999999e+00 , -9.0051999999999999e-01 , 4.4433800000000002e-02 , 4.3253900000000001e-01 -5.1006443219916120e+00 , 6.0481483831665335e+00 , 1.6313751200000000e+00 , -9.0390400000000004e-01 , 1.7835399999999999e-03 , 4.2773299999999997e-01 -5.1310347647754133e+00 , 6.1177763558709328e+00 , 1.6935889600000000e+00 , -9.0390400000000004e-01 , 1.7834900000000000e-03 , 4.2773299999999997e-01 -5.9526988885851200e+00 , 7.2927702671540962e+00 , 1.3712690400000001e+00 , 7.1067700000000000e-01 , 2.6454400000000000e-01 , 6.5188500000000005e-01 -5.9465833502548557e+00 , 7.3196935708245414e+00 , 1.4772335999999999e+00 , 7.1067700000000000e-01 , 2.6454400000000000e-01 , 6.5188500000000005e-01 -5.6248847382057292e+00 , 6.9642992987938488e+00 , 1.9055741360000000e+00 , -4.9793900000000002e-01 , -5.0845099999999999e-01 , -7.0252000000000003e-01 -5.6559614833615619e+00 , 7.0413777319037623e+00 , 1.9891002799999999e+00 , -4.9793900000000002e-01 , -5.0845099999999999e-01 , -7.0252000000000003e-01 -1.9885870398520577e+01 , 2.8172374900551262e+01 , -1.2964256000000001e+00 , -5.7605499999999998e-01 , 7.2051500000000004e-02 , 8.1422899999999998e-01 -2.0521131187896497e+01 , 2.9299162468736796e+01 , -9.1229119999999986e-01 , -1.9484799999999999e-01 , 2.4241299999999999e-01 , 9.5040500000000006e-01 -2.1558848029568274e+01 , 3.1044899492295258e+01 , -5.6396399999999991e-01 , -9.0567100000000000e-01 , 2.4685299999999999e-01 , 3.4470800000000001e-01 -2.5577087149021313e+01 , 3.7312168487801458e+01 , -6.2672799999999995e-01 , 9.9625799999999998e-01 , 5.5677900000000002e-02 , 6.6104899999999994e-02 -2.5519078518711940e+01 , 3.7469557248650602e+01 , 8.9083199999999918e-02 , 9.9584300000000003e-01 , 5.9414900000000000e-02 , 6.9045499999999996e-02 -2.5317748204554299e+01 , 3.7406885834104713e+01 , 8.2092080000000012e-01 , 9.9569900000000000e-01 , 6.0325799999999999e-02 , 7.0322899999999994e-02 -2.1348264624545990e+01 , 3.1535653433631669e+01 , 1.8006236799999999e+00 , 4.3177500000000002e-01 , -8.8006799999999996e-01 , -1.9761200000000001e-01 -2.1365284816927311e+01 , 3.1766826902203007e+01 , 2.3929775200000001e+00 , -4.7998700000000000e-01 , 8.7059200000000003e-01 , 1.0808500000000000e-01 -2.0826683231801059e+01 , 3.1132694864100930e+01 , 2.9941952800000000e+00 , 2.0473000000000002e-02 , 8.7240099999999998e-01 , 4.8836200000000002e-01 -1.9529208688942536e+01 , 2.9485834910251164e+01 , 4.0982728000000002e+00 , -5.7495900000000000e-01 , -6.9923999999999997e-01 , 4.2483700000000002e-01 -1.9336640334031909e+01 , 2.9371563667118799e+01 , 4.6388128000000002e+00 , -5.7495900000000000e-01 , -6.9923999999999997e-01 , 4.2483700000000002e-01 -1.9452071440167295e+01 , 2.9751722147198308e+01 , 5.2117696000000002e+00 , -5.7157899999999995e-01 , -7.6847799999999999e-01 , 2.8764299999999998e-01 -1.9031967278481517e+01 , 2.9267993976699330e+01 , 5.7146720000000002e+00 , -8.1846500000000003e-02 , 8.7416700000000003e-01 , 4.7867900000000002e-01 -2.2358029720649220e+01 , 3.4890267732534546e+01 , 6.9189088000000005e+00 , -3.7233099999999998e-02 , 4.4513500000000000e-01 , 8.9468899999999996e-01 -1.9961068578451226e+01 , 3.1188345079428874e+01 , 7.0592880000000005e+00 , 3.5097099999999998e-01 , -8.9867399999999997e-01 , 2.6306700000000000e-01 -1.9494012401241854e+01 , 3.0626336588757635e+01 , 7.5486496000000001e+00 , 4.2023199999999999e-01 , -8.7096499999999999e-01 , 2.5460700000000003e-01 -1.9549780900539176e+01 , 3.0929670563363398e+01 , 8.1699039999999989e+00 , -4.0741800000000000e-01 , 8.8224000000000002e-01 , -2.3593000000000000e-01 -1.9584991870221710e+01 , 3.1420269213143452e+01 , 9.4266296000000018e+00 , -2.6449600000000001e-01 , -9.5452099999999995e-01 , 1.3758999999999999e-01 -1.9178135391104139e+01 , 3.0948140160997692e+01 , 9.9005575999999991e+00 , 4.8426900000000002e-02 , -9.5911500000000005e-01 , 2.7884399999999998e-01 -1.9235553891052746e+01 , 3.1267938123754885e+01 , 1.0561997600000000e+01 , 6.9043300000000002e-02 , -9.4600200000000001e-01 , 3.1672200000000000e-01 -1.9323700236855920e+01 , 3.1646067512014447e+01 , 1.1255646400000002e+01 , 2.0749500000000001e-01 , -7.1056500000000000e-01 , 6.7234099999999997e-01 -2.1177160337460631e+01 , 3.5114935601905785e+01 , 1.2894416000000001e+01 , -2.7642400000000000e-01 , 7.6156599999999997e-01 , -5.8617900000000001e-01 -2.0439763852440144e+01 , 3.4078971220336875e+01 , 1.3234287999999999e+01 , -4.9046800000000002e-01 , 8.1565299999999996e-01 , -3.0684200000000000e-01 -1.9404436627539539e+01 , 3.2747037455387733e+01 , 1.4065352000000001e+01 , 3.1825799999999999e-01 , -9.4463399999999997e-01 , 7.9870200000000002e-02 -6.0246992668911856e+00 , 9.3375410126163310e+00 , 6.9452311999999994e+00 , 3.0775799999999998e-01 , 9.4887999999999995e-01 , -7.0089899999999997e-02 -5.8613156575915717e+00 , 9.0870444464920190e+00 , 6.9582519999999999e+00 , 2.1517500000000001e-01 , 8.7125900000000001e-01 , -4.4114399999999998e-01 -5.8163088161445158e+00 , 9.0646036454599823e+00 , 7.1008255999999994e+00 , 2.5949699999999998e-01 , 6.9336299999999995e-01 , -6.7224200000000001e-01 -5.2439697691666103e+00 , 8.1783791428714636e+00 , 7.1229672000000006e+00 , -2.6981600000000000e-01 , 2.7916000000000000e-02 , 9.6250700000000000e-01 -4.7487710958831331e+00 , 7.2670541275861149e+00 , 6.7313656000000002e+00 , 4.5713100000000001e-01 , 8.4256399999999998e-01 , -2.8481200000000001e-01 -4.7676118865002790e+00 , 7.3669606946269290e+00 , 6.9361519999999999e+00 , -4.6273300000000001e-01 , -8.5187100000000004e-01 , -2.4534600000000001e-01 -4.5118261966877959e+00 , 6.8758038868085372e+00 , 6.6730632000000005e+00 , 1.4886199999999999e-01 , 3.3248600000000000e-01 , 9.3128599999999995e-01 -4.5323939276847991e+00 , 6.9806447003576269e+00 , 6.8816351999999998e+00 , 3.3939799999999998e-01 , 8.2064399999999996e-02 , 9.3705600000000000e-01 -4.4120821778156216e+00 , 6.7750645291848786e+00 , 6.8316632000000004e+00 , -8.0004099999999995e-02 , 5.5422800000000005e-01 , 8.2851100000000000e-01 -4.3494996491240618e+00 , 6.6963641318460470e+00 , 6.8861904000000003e+00 , 5.5048100000000003e-02 , 7.4118899999999999e-01 , 6.6903500000000005e-01 -4.2942276673653410e+00 , 6.6323251685278946e+00 , 6.9518040000000001e+00 , -3.6285400000000001e-01 , -9.3178300000000003e-01 , 1.0827399999999999e-02 -4.3289751016029534e+00 , 6.7769896767484763e+00 , 7.2134783999999996e+00 , -7.9379100000000002e-01 , -5.5369199999999996e-01 , -2.5163500000000000e-01 -4.2846811354923204e+00 , 6.7439651319499481e+00 , 7.3141711999999997e+00 , -8.9270400000000005e-01 , -3.9458199999999999e-01 , -2.1767900000000001e-01 -4.2756107934533123e+00 , 6.7933695319282430e+00 , 7.4994888000000000e+00 , 9.9620500000000001e-01 , 6.7751599999999995e-02 , 5.4640800000000003e-02 -4.2829162406420309e+00 , 6.8867356055940716e+00 , 7.7378360000000006e+00 , -5.6516500000000003e-01 , 4.0529199999999999e-01 , -7.1855899999999995e-01 -4.0962530145978429e+00 , 6.5028977452817047e+00 , 7.4740920000000006e+00 , -4.2383999999999999e-01 , -8.8295500000000005e-01 , -2.0186699999999999e-01 -4.0922569869288381e+00 , 6.5719752073519668e+00 , 7.6896216000000006e+00 , 6.4092899999999997e-01 , 6.3576999999999995e-01 , 4.3012400000000001e-01 -4.0289021725932859e+00 , 6.4906457748737578e+00 , 7.7414968000000002e+00 , -2.1680300000000000e-01 , 9.4033900000000004e-01 , -2.6221899999999998e-01 -3.9774201265640285e+00 , 6.4405758054022115e+00 , 7.8297928000000008e+00 , 5.2962299999999995e-01 , -6.1191399999999996e-01 , 5.8741900000000002e-01 -3.8581613013684355e+00 , 6.2089667738066217e+00 , 7.6983056000000003e+00 , 4.9757400000000002e-01 , -8.3986499999999997e-01 , -2.1690400000000001e-01 -3.6223722825063938e+00 , 5.6456515265892264e+00 , 7.1393576000000003e+00 , -3.0226100000000000e-01 , -5.7366200000000001e-01 , 7.6128200000000001e-01 -3.5310916573172744e+00 , 5.4662030434991662e+00 , 7.0355656000000009e+00 , -3.5785099999999997e-01 , 4.9495899999999998e-01 , -7.9180700000000004e-01 -3.4780099277815197e+00 , 5.3936625515655363e+00 , 7.0647064000000004e+00 , -3.5975099999999999e-01 , -9.2243699999999995e-01 , 1.4031800000000000e-01 -3.4716435715648934e+00 , 5.4589381172436902e+00 , 7.2819208000000000e+00 , 3.8398599999999999e-01 , 8.6567099999999997e-01 , 3.2119999999999999e-01 -3.4775983515038487e+00 , 5.5712690900924944e+00 , 7.5772288000000003e+00 , 3.0394100000000002e-01 , 8.3760699999999999e-01 , -4.5390999999999998e-01 -3.3863677948881117e+00 , 5.3819938736684128e+00 , 7.4457519999999997e+00 , 1.4516500000000000e-02 , 7.8567799999999999e-01 , 6.1846599999999996e-01 -3.4851162419230386e+00 , 5.8140884858755424e+00 , 8.2412063999999994e+00 , -2.7360499999999999e-01 , 7.0948500000000003e-01 , 6.4944000000000002e-01 -3.6203486319158014e+00 , 6.4062043089657594e+00 , 9.3380112000000004e+00 , 7.7796299999999996e-01 , -5.8203600000000000e-01 , 2.3665900000000001e-01 -3.6183970090453803e+00 , 6.5619360478508435e+00 , 9.7996048000000009e+00 , -4.1784600000000000e-01 , -5.1059399999999999e-01 , 7.5146500000000005e-01 -3.4033106858227304e+00 , 5.9498341055326041e+00 , 9.0029232000000015e+00 , -9.1745800000000000e-01 , 3.1553300000000001e-01 , -2.4229999999999999e-01 -3.3544559123353288e+00 , 5.9341262490431026e+00 , 9.1780800000000013e+00 , -9.1745800000000000e-01 , 3.1553300000000001e-01 , -2.4229999999999999e-01 -3.1250980309107237e+00 , 5.1819879826419726e+00 , 8.0468928000000002e+00 , 4.0217599999999998e-01 , -5.6955100000000002e-02 , 9.1378899999999996e-01 -3.0657630543202341e+00 , 5.0929205232819683e+00 , 8.0559408000000001e+00 , 8.5457499999999997e-01 , 4.6942200000000001e-01 , 2.2213400000000000e-01 -3.0451058139074796e+00 , 5.1806395025991590e+00 , 8.4025935999999994e+00 , -9.5040199999999997e-01 , -2.9010700000000000e-01 , 1.1212999999999999e-01 -2.9922141267826121e+00 , 5.1330215579198137e+00 , 8.5028287999999996e+00 , -1.2724900000000000e-01 , 3.8511299999999998e-01 , 9.1405499999999995e-01 -2.9330704191837498e+00 , 5.0511768724433566e+00 , 8.5372424000000002e+00 , 6.7474299999999998e-01 , 4.3966899999999998e-01 , 5.9280100000000002e-01 -2.8792654888790836e+00 , 5.0080640978090321e+00 , 8.6542944000000013e+00 , -3.9853899999999998e-01 , -8.9997600000000000e-01 , -1.7666200000000001e-01 -2.8234187551630350e+00 , 4.9587435370355699e+00 , 8.7612687999999999e+00 , 1.3858700000000000e-02 , -7.4953199999999998e-01 , 6.6182300000000005e-01 -2.6578497606185789e+00 , 4.0453053058100448e+00 , 6.8747191999999995e+00 , 1.2024700000000001e-01 , -2.5186399999999998e-01 , 9.6026299999999998e-01 -2.6143197469099406e+00 , 3.9582001227305090e+00 , 6.8231143999999997e+00 , -3.0098099999999999e-03 , 1.8322800000000000e-01 , 9.8306600000000000e-01 -2.5749255297822327e+00 , 3.9010619404681321e+00 , 6.8368007999999998e+00 , 3.0620999999999999e-02 , -2.4729799999999999e-01 , -9.6845599999999998e-01 -2.5369664710204747e+00 , 3.8872762435498993e+00 , 6.9658024000000003e+00 , -8.9106599999999994e-02 , 9.4760699999999998e-01 , 3.0675999999999998e-01 -2.5182085227433770e+00 , 4.4983585766377994e+00 , 8.8142880000000012e+00 , -1.9460500000000000e-01 , 6.0103600000000001e-01 , 7.7516700000000005e-01 -2.4577220695813611e+00 , 4.1477701462796297e+00 , 8.0784567999999997e+00 , 3.8505600000000001e-01 , -6.7352800000000002e-01 , -6.3094499999999998e-01 -2.4040205963766743e+00 , 4.1181868134736614e+00 , 8.2310976000000000e+00 , -4.3794600000000000e-01 , 8.8642399999999999e-01 , -1.4985100000000001e-01 -2.3473927844305713e+00 , 4.1099443025194411e+00 , 8.4626951999999989e+00 , 9.5882599999999996e-01 , -2.6058200000000000e-02 , 2.8279599999999999e-01 -2.2965492959876572e+00 , 3.9858079993590785e+00 , 8.3364288000000002e+00 , 8.3209400000000000e-01 , -3.4277800000000003e-01 , 4.3603100000000000e-01 -2.2926662345186077e+00 , 3.5475077298307811e+00 , 7.0876800000000006e+00 , 4.8294500000000001e-01 , -3.1737599999999999e-01 , -8.1611100000000003e-01 -2.2532721831578755e+00 , 3.4863902596757628e+00 , 7.0921311999999999e+00 , -1.3960000000000000e-01 , 6.0966799999999999e-01 , 7.8026700000000004e-01 -2.2075121653779997e+00 , 3.4508507229779402e+00 , 7.1958400000000005e+00 , 5.5786199999999997e-01 , 7.8306200000000004e-01 , 2.7496100000000001e-01 -2.1116686008010861e+00 , 3.5757708313997210e+00 , 7.9851896000000009e+00 , -3.7324000000000002e-01 , -8.1652499999999995e-01 , -4.4043100000000002e-01 -2.0345978911355891e+00 , 3.5819545069008329e+00 , 8.3525071999999998e+00 , 7.8495899999999996e-01 , -2.2912700000000000e-01 , 5.7562199999999997e-01 -1.9785403179876269e+00 , 3.5153050342831857e+00 , 8.4155727999999996e+00 , -5.9845999999999999e-01 , 5.1652200000000004e-01 , -6.1241400000000001e-01 -1.9514622383128100e+00 , 3.3857567088542391e+00 , 8.1620519999999992e+00 , -9.1948799999999997e-01 , 6.6126500000000005e-02 , -3.8751600000000003e-01 -1.9092161005710726e+00 , 3.2975004476272201e+00 , 8.0997248000000006e+00 , 5.8363200000000004e-01 , -3.8824500000000001e-01 , 7.1318999999999999e-01 -1.8525687320925954e+00 , 3.2329810606625080e+00 , 8.1679488000000013e+00 , -6.5558899999999998e-01 , -7.5474600000000003e-01 , -2.3717100000000001e-02 -3.8215616172170233e+00 , 3.6883992015515124e+00 , 9.0870719999999983e-01 , -1.8540100000000001e-01 , 1.0387500000000000e-01 , 9.7715700000000005e-01 -3.8528659662485230e+00 , 3.7376048526403256e+00 , 9.1720399999999991e-01 , 2.0562500000000000e-01 , -1.2874900000000000e-01 , -9.7012500000000002e-01 -3.8954913082880829e+00 , 3.7973399252380089e+00 , 9.1181679999999998e-01 , -7.8406299999999998e-02 , 1.3544800000000001e-01 , 9.8767700000000003e-01 -3.9368652860170550e+00 , 3.8574898597430645e+00 , 9.0821839999999998e-01 , 8.1534999999999996e-02 , -1.5420600000000001e-01 , -9.8466900000000002e-01 -3.9842464443739374e+00 , 3.9237069765087473e+00 , 8.9917040000000004e-01 , 1.0663300000000001e-01 , -1.4866299999999999e-01 , -9.8312200000000005e-01 -4.0262194375067768e+00 , 3.9856655697615859e+00 , 8.9944080000000004e-01 , -7.6289599999999999e-02 , 1.7526100000000000e-01 , 9.8156200000000005e-01 -4.0844823252468920e+00 , 4.0642649737808449e+00 , 8.8034640000000008e-01 , 8.9932999999999999e-02 , -2.0101100000000000e-01 , -9.7545199999999999e-01 -4.1219103554162881e+00 , 4.1233603485402863e+00 , 8.9179680000000006e-01 , -8.9791700000000002e-02 , 1.6565800000000000e-01 , 9.8208700000000004e-01 -4.1796192413028628e+00 , 4.2040122017175694e+00 , 8.7755920000000009e-01 , -8.0454899999999996e-02 , 1.7517300000000000e-01 , 9.8124500000000003e-01 -4.2278171629954073e+00 , 4.2745758250590580e+00 , 8.7968080000000004e-01 , -7.0241499999999998e-02 , 2.0409200000000000e-01 , 9.7642899999999999e-01 -4.2982818414789836e+00 , 4.3700909386600291e+00 , 8.5757039999999995e-01 , -3.2058999999999997e-02 , 1.9021399999999999e-01 , 9.8121899999999995e-01 -4.3622672933587623e+00 , 4.4614487595774559e+00 , 8.4505920000000012e-01 , -4.6171700000000003e-02 , 1.8850300000000000e-01 , 9.8098700000000005e-01 -4.4269057625858732e+00 , 4.5534589183399294e+00 , 8.3592800000000000e-01 , -1.4108100000000000e-02 , 1.8690999999999999e-01 , 9.8227600000000004e-01 -4.5033733236083027e+00 , 4.6590408874789873e+00 , 8.1767600000000007e-01 , -2.8900700000000001e-02 , 2.0368000000000000e-01 , 9.7861100000000001e-01 -4.5743875400893863e+00 , 4.7604825130920361e+00 , 8.0926239999999994e-01 , -5.2622599999999999e-02 , 1.8801799999999999e-01 , 9.8075500000000004e-01 -4.6571325013126046e+00 , 4.8756670205787982e+00 , 7.9255999999999993e-01 , -6.0422099999999999e-02 , 1.9875999999999999e-01 , 9.7818400000000005e-01 -4.7454452414261139e+00 , 4.9988246056939820e+00 , 7.7443279999999981e-01 , -6.8260500000000002e-02 , 1.9474200000000000e-01 , 9.7847600000000001e-01 -4.8282719927600102e+00 , 5.1178458414924428e+00 , 7.6623759999999996e-01 , -7.2152800000000003e-02 , 1.8749099999999999e-01 , 9.7961299999999996e-01 -4.9226347227779250e+00 , 5.2509949390895585e+00 , 7.5157359999999995e-01 , -6.6494200000000003e-02 , 1.9287599999999999e-01 , 9.7896799999999995e-01 -5.0164557097957498e+00 , 5.3861883593133291e+00 , 7.4166239999999983e-01 , -2.5087799999999999e-01 , 1.4129200000000000e-01 , 9.5765199999999995e-01 -5.1347296175940631e+00 , 5.5511483750593165e+00 , 7.1607840000000000e-01 , -3.2401400000000002e-01 , 2.9036499999999998e-01 , 9.0039100000000005e-01 -5.2354166894113430e+00 , 5.6978039558406213e+00 , 7.1177279999999987e-01 , 7.2034100000000001e-01 , -2.9160999999999998e-01 , -6.2934199999999996e-01 -5.1646838406071689e+00 , 5.6402555718712524e+00 , 8.5375359999999989e-01 , 9.9674200000000002e-01 , 3.9400699999999997e-02 , 7.0381200000000005e-02 -5.1457616015262237e+00 , 5.6444527677737035e+00 , 9.4964160000000009e-01 , 9.8830300000000004e-01 , 4.3565100000000002e-02 , 1.4614600000000000e-01 -5.1367087005729637e+00 , 5.6621004119408571e+00 , 1.0352627200000000e+00 , 9.9969900000000000e-01 , -1.1057800000000000e-03 , 2.4504700000000001e-02 -5.1157808711281447e+00 , 5.6618480639102362e+00 , 1.1296988799999998e+00 , 9.2178700000000002e-01 , -1.8105499999999999e-01 , -3.4282299999999999e-01 -5.1480040981515991e+00 , 5.7278788504016518e+00 , 1.1849613600000000e+00 , -9.7167499999999996e-01 , 9.7962300000000002e-02 , -2.1506000000000000e-01 -5.2034019000311469e+00 , 5.8219208739853361e+00 , 1.2261588799999998e+00 , -9.1747800000000002e-01 , -3.0623200000000000e-01 , -2.5388200000000000e-01 -5.0835292363256510e+00 , 5.6983506751670578e+00 , 1.3830428800000001e+00 , 9.9054500000000001e-01 , 1.0410100000000000e-01 , 8.9353799999999997e-02 -5.0821019442887501e+00 , 5.7232424951696483e+00 , 1.4588692800000000e+00 , 9.7362400000000004e-01 , 2.2818399999999999e-02 , -2.2701399999999999e-01 -5.0932653011400912e+00 , 5.7621894580577813e+00 , 1.5280417600000000e+00 , -9.3900499999999998e-01 , -1.1724999999999999e-03 , 3.4390100000000001e-01 -5.1148445398818989e+00 , 5.8153980196993453e+00 , 1.5912186400000001e+00 , -8.7156599999999995e-01 , 3.0558999999999999e-02 , 4.8932399999999998e-01 -5.1362360452562994e+00 , 5.8678575537961803e+00 , 1.6559170400000001e+00 , -8.3470100000000003e-01 , 2.8373900000000001e-02 , 5.4997300000000005e-01 -5.1747223474660533e+00 , 5.9435091978590782e+00 , 1.7128185600000001e+00 , -8.3968799999999999e-01 , 1.6096800000000001e-02 , 5.4283099999999995e-01 -6.0318988112889445e+00 , 7.1597754203708135e+00 , 1.5871324800000000e+00 , 7.1067700000000000e-01 , 2.6454400000000000e-01 , 6.5188500000000005e-01 -5.7150203260243373e+00 , 6.8323751764836587e+00 , 1.9973249016000001e+00 , -4.1683999999999999e-01 , -7.3129699999999997e-01 , -5.3986100000000004e-01 -1.9930262321215757e+01 , 2.6617977759715163e+01 , -1.2174168000000001e+00 , 6.3628399999999996e-01 , -3.8101200000000002e-02 , -7.7051400000000003e-01 -2.0805211038389650e+01 , 2.8006113532202765e+01 , -9.0293120000000027e-01 , -4.0390100000000001e-01 , 8.1565799999999994e-02 , 9.1115900000000005e-01 -2.0770344184467177e+01 , 2.8135191523764259e+01 , -3.6455440000000028e-01 , -4.0390100000000001e-01 , 8.1565899999999997e-02 , 9.1115900000000005e-01 -2.5972842946851380e+01 , 3.5671839660317197e+01 , -6.5754320000000011e-01 , 9.9329900000000004e-01 , 5.6079499999999997e-02 , 1.0105400000000000e-01 -2.5891854187429878e+01 , 3.5787642014901920e+01 , 4.2439199999999788e-02 , 9.9329900000000004e-01 , 5.6079499999999997e-02 , 1.0105400000000000e-01 -2.5827243841537271e+01 , 3.5926820218610821e+01 , 7.4059119999999989e-01 , 9.9612699999999998e-01 , 5.7784400000000000e-02 , 6.6276100000000004e-02 -2.5678876469169012e+01 , 3.5944708751712724e+01 , 1.4460003200000000e+00 , 9.9680299999999999e-01 , 5.7871600000000002e-02 , 5.5090100000000003e-02 -2.5706269507400002e+01 , 3.6218414806626519e+01 , 2.1407941600000000e+00 , 9.9732600000000005e-01 , 6.5929799999999997e-02 , 3.1544000000000003e-02 -2.1297466191489580e+01 , 2.9997508857758842e+01 , 2.8886238400000002e+00 , -1.7840400000000001e-01 , 8.9232699999999998e-01 , 4.1463899999999998e-01 -2.1737581340130721e+01 , 3.0840567279231866e+01 , 3.4723592000000001e+00 , -1.7840300000000001e-01 , 8.9232599999999995e-01 , 4.1463899999999998e-01 -2.5501120493072193e+01 , 3.6627394351152070e+01 , 4.2589632000000002e+00 , 9.9877000000000005e-01 , 3.7652499999999998e-02 , 3.2268800000000000e-02 -2.1748614083839609e+01 , 3.1256228701649501e+01 , 4.6681407999999998e+00 , -6.7106299999999994e-02 , 9.1121700000000005e-01 , 4.0642400000000001e-01 -2.0580701975010335e+01 , 2.9700999341164703e+01 , 5.1428799999999999e+00 , -2.0050799999999999e-01 , 9.7853100000000004e-01 , -4.7686300000000001e-02 -2.5314637640591201e+01 , 3.7074114590768048e+01 , 6.4101511999999996e+00 , 9.9815500000000001e-01 , 3.7768799999999998e-02 , 4.7538799999999999e-02 -2.5240497154949850e+01 , 3.7207434675634744e+01 , 7.1349999999999998e+00 , 9.9768699999999999e-01 , 4.2532000000000000e-02 , 5.3026700000000003e-02 -2.5158325159223725e+01 , 3.7331168049816434e+01 , 7.8630416000000007e+00 , 9.9776600000000004e-01 , 4.5677099999999998e-02 , 4.8744700000000002e-02 -2.5074588460927032e+01 , 3.7452674168766748e+01 , 8.5958255999999995e+00 , 9.9838899999999997e-01 , 3.7747799999999998e-02 , 4.2371600000000002e-02 -2.5020437806017821e+01 , 3.7624533845889985e+01 , 9.3423376000000005e+00 , 9.9870300000000001e-01 , 4.1077599999999999e-02 , 3.0078199999999999e-02 -2.4980912145317482e+01 , 3.7819520051684663e+01 , 1.0101506400000000e+01 , 9.9621000000000004e-01 , 6.3032500000000005e-02 , 5.9942700000000002e-02 -2.4892642433500196e+01 , 3.7942972394779851e+01 , 1.0853873600000000e+01 , 9.9621000000000004e-01 , 6.3032500000000005e-02 , 5.9942700000000002e-02 -2.4704718078537653e+01 , 3.7909441197427029e+01 , 1.1574978399999999e+01 , 9.9461800000000000e-01 , 6.9582800000000000e-02 , 7.6767199999999994e-02 -2.0046726643752756e+01 , 3.0689352071661439e+01 , 1.0429813599999999e+01 , -2.6449600000000001e-01 , -9.5452099999999995e-01 , 1.3758999999999999e-01 -5.9987111969929794e+00 , 8.9425753631316098e+00 , 7.0558144000000009e+00 , 2.1517500000000001e-01 , 8.7125900000000001e-01 , -4.4114399999999998e-01 -4.9297056068718419e+00 , 7.2207386396280144e+00 , 6.5980584000000002e+00 , 8.0887900000000001e-01 , 5.7438599999999995e-01 , -1.2567700000000001e-01 -4.8763971408530278e+00 , 7.1702559903995828e+00 , 6.6839832000000001e+00 , -8.1618900000000005e-01 , -2.7968399999999999e-01 , 5.0558099999999995e-01 -4.7829978605429604e+00 , 7.0423002215250161e+00 , 6.7088080000000003e+00 , 2.8426499999999999e-01 , -7.8677900000000001e-01 , -5.4788000000000003e-01 -4.7219601351182749e+00 , 6.9750338484500487e+00 , 6.7782591999999999e+00 , 3.0575900000000000e-01 , -7.9920300000000000e-01 , -5.1748099999999997e-01 -4.7846293698820279e+00 , 7.1614057328319101e+00 , 7.0579048000000002e+00 , -8.9706799999999998e-01 , -3.2876200000000000e-01 , 2.9526999999999998e-01 -4.7476183668617313e+00 , 7.1481517850942886e+00 , 7.1792207999999995e+00 , 7.2485100000000002e-01 , 4.3659399999999998e-01 , 5.3289500000000001e-01 -4.5219001743587235e+00 , 6.7386333999893768e+00 , 6.9483512000000003e+00 , -3.5267300000000001e-01 , 6.8938100000000002e-01 , 6.3275300000000001e-01 -4.4256628784534060e+00 , 6.5961481828293067e+00 , 6.9425895999999998e+00 , 1.6278000000000001e-01 , 9.6483699999999994e-01 , 2.0637900000000001e-01 -4.4646452465706492e+00 , 6.7405463331043425e+00 , 7.2038583999999997e+00 , 6.6051199999999999e-01 , 6.7891699999999999e-01 , 3.2061699999999999e-01 -4.3911183462857082e+00 , 6.6453230674761965e+00 , 7.2425464000000002e+00 , -6.4423100000000000e-01 , -5.7484400000000002e-01 , -5.0450099999999998e-01 -4.3808435153227734e+00 , 6.6888910323205995e+00 , 7.4197312000000002e+00 , -9.2090300000000003e-01 , -2.7670000000000000e-01 , -2.7454400000000001e-01 -4.3486010901468868e+00 , 6.6889661486124528e+00 , 7.5555240000000001e+00 , 6.3645799999999999e-03 , 5.3634199999999999e-01 , 8.4397699999999998e-01 -4.2467477368714768e+00 , 6.5288521919870703e+00 , 7.5243136000000002e+00 , 4.7189599999999998e-01 , -1.3175600000000001e-02 , 8.8155600000000001e-01 -4.1904316476926242e+00 , 6.4710109381050929e+00 , 7.5994328000000007e+00 , -3.4886399999999998e-02 , -9.8582499999999995e-01 , 1.6411200000000001e-01 -3.9396500949919000e+00 , 5.9505089489703984e+00 , 7.1443704000000006e+00 , -3.7273099999999998e-01 , -4.4013300000000000e-01 , -8.1691800000000003e-01 -3.8544969183856628e+00 , 5.8131781515995709e+00 , 7.1086048000000002e+00 , -1.2171200000000000e-01 , 4.8013400000000001e-01 , 8.6870999999999998e-01 -3.8350552661720814e+00 , 5.8366891461443817e+00 , 7.2633048000000002e+00 , -1.2171200000000000e-01 , 4.8013400000000001e-01 , 8.6870999999999998e-01 -3.7539333960453378e+00 , 5.7060118732462239e+00 , 7.2298479999999996e+00 , -2.5018299999999999e-01 , 1.4512300000000000e-01 , 9.5726000000000000e-01 -3.6210121757067508e+00 , 5.4403505643312435e+00 , 7.0160136000000000e+00 , 1.4587500000000000e-01 , 9.9871199999999993e-02 , -9.8424900000000004e-01 -3.5737039184643411e+00 , 5.3884313366400889e+00 , 7.0696984000000009e+00 , 1.5970400000000001e-01 , 9.6919699999999998e-01 , 1.8748999999999999e-01 -3.5469346597017779e+00 , 5.3944335505802066e+00 , 7.2044824000000007e+00 , 2.9507600000000000e-01 , 9.5359099999999997e-01 , -5.9955099999999997e-02 -3.5347446576906525e+00 , 5.4442561050495302e+00 , 7.4069808000000004e+00 , -3.2402900000000001e-01 , -9.4050199999999995e-01 , 1.0228100000000000e-01 -3.5123594884595244e+00 , 5.4718182666616704e+00 , 7.5864744000000011e+00 , -4.5734500000000000e-01 , 3.2342900000000002e-01 , -8.2838900000000004e-01 -3.4497397026573235e+00 , 5.3831460959084598e+00 , 7.5967703999999996e+00 , 1.2439799999999999e-01 , 1.8182999999999999e-01 , 9.7543000000000002e-01 -3.3763585774215166e+00 , 5.2617100815248889e+00 , 7.5527991999999999e+00 , 7.5503699999999996e-01 , 6.3194300000000003e-01 , 1.7483299999999999e-01 -3.5802891881926611e+00 , 6.0206637840467412e+00 , 8.9284488000000017e+00 , -9.1745800000000000e-01 , 3.1553300000000001e-01 , -2.4229999999999999e-01 -3.5719859658416100e+00 , 6.1412466169318121e+00 , 9.3249279999999999e+00 , -9.1745900000000002e-01 , 3.1553300000000001e-01 , -2.4229999999999999e-01 -3.4911697714012564e+00 , 6.0255511102891646e+00 , 9.3342671999999993e+00 , -9.1745800000000000e-01 , 3.1553300000000001e-01 , -2.4229999999999999e-01 -3.4367003712910873e+00 , 6.0041952149429543e+00 , 9.5117432000000015e+00 , -9.1745900000000002e-01 , 3.1553300000000001e-01 , -2.4229999999999999e-01 -3.1486993297305190e+00 , 5.0915762210729234e+00 , 8.0458944000000017e+00 , -5.6986099999999995e-01 , -2.2804099999999999e-01 , -7.8946600000000000e-01 -3.0319790601519148e+00 , 4.7788154915696524e+00 , 7.6228432000000002e+00 , -9.2184900000000003e-01 , -3.7873299999999999e-01 , 8.2196599999999995e-02 -3.0551178178088727e+00 , 5.0422042932444633e+00 , 8.3079327999999997e+00 , 8.7548599999999999e-01 , 4.7723100000000002e-01 , 7.5991699999999995e-02 -3.0004206595921072e+00 , 4.9923951793301384e+00 , 8.3968632000000003e+00 , 6.5594600000000003e-01 , 6.1775800000000003e-01 , 4.3371500000000002e-01 -2.9643326223229036e+00 , 5.0413845182909434e+00 , 8.7008343999999997e+00 , -2.1556400000000001e-01 , -9.1168700000000003e-01 , 3.4979800000000000e-01 -2.8941451189874523e+00 , 4.9201077530127746e+00 , 8.6478047999999994e+00 , -1.3421600000000000e-01 , 9.6793399999999996e-01 , -2.1234200000000000e-01 -2.7050279331523743e+00 , 4.0273531131403058e+00 , 6.8115080000000008e+00 , 1.0696500000000000e-01 , -6.9434200000000001e-02 , 9.9183500000000002e-01 -2.6633471857382265e+00 , 3.9706534077813007e+00 , 6.8268583999999999e+00 , 3.6790400000000001e-02 , -8.2450599999999999e-02 , 9.9591600000000002e-01 -2.6208488960259455e+00 , 3.9106894133896946e+00 , 6.8311327999999998e+00 , -7.5324100000000005e-02 , 1.8147400000000000e-01 , 9.8050700000000002e-01 -2.5741861847822682e+00 , 3.7937675101162753e+00 , 6.6887984000000005e+00 , 8.3015600000000001e-01 , -1.3762700000000000e-01 , 5.4027800000000004e-01 -2.5375129023814762e+00 , 3.7827998302507906e+00 , 6.8163023999999997e+00 , 6.9708199999999998e-01 , -1.7864500000000000e-01 , 6.9438000000000000e-01 -2.5125221850215116e+00 , 4.1999452774575747e+00 , 8.1699248000000004e+00 , 5.7058100000000000e-01 , -7.8613599999999995e-01 , -2.3754300000000000e-01 -2.4563074998215830e+00 , 3.5671179288751489e+00 , 6.5295016000000006e+00 , -9.3925700000000001e-01 , 1.4418400000000001e-01 , 3.1146099999999999e-01 -2.4032963107907284e+00 , 4.0552303830354637e+00 , 8.2188984000000005e+00 , -8.6235300000000004e-01 , 3.3915299999999998e-01 , -3.7592900000000001e-01 -2.3505443525196315e+00 , 3.9363419331257652e+00 , 8.0918519999999994e+00 , 9.9037200000000003e-01 , 1.1815700000000000e-01 , 7.2129200000000004e-02 -2.3223410645356664e+00 , 3.6330777110107038e+00 , 7.3131728000000003e+00 , -8.3183900000000000e-01 , 4.8880800000000002e-01 , -2.6288899999999998e-01 -2.2865045699454241e+00 , 3.5095216025420197e+00 , 7.0981112000000000e+00 , 4.5995799999999998e-01 , -4.0937600000000002e-01 , -7.8793999999999997e-01 -2.2438639056822303e+00 , 3.4544949406262395e+00 , 7.1215527999999999e+00 , -9.0723600000000001e-02 , 6.8157100000000004e-01 , 7.2610600000000003e-01 -2.1533025505765355e+00 , 3.5885717871958853e+00 , 7.9205328000000002e+00 , -6.4192000000000005e-01 , -7.4225099999999999e-01 , -1.9235900000000000e-01 -2.0762210459899317e+00 , 3.6020327799135048e+00 , 8.2976784000000006e+00 , -1.8374399999999999e-01 , 8.2177199999999995e-01 , -5.3937900000000005e-01 -2.0040650871535930e+00 , 3.5740355227115188e+00 , 8.5333424000000004e+00 , 8.4668600000000005e-01 , -5.1918600000000004e-01 , 1.1648600000000001e-01 -1.9716191820934856e+00 , 3.4427517822448848e+00 , 8.2806119999999996e+00 , 4.2638799999999999e-01 , -8.9575199999999999e-01 , 1.2578200000000000e-01 -1.9325203158521762e+00 , 3.3411262928721204e+00 , 8.1473359999999992e+00 , 3.1172800000000001e-01 , -6.1250400000000005e-01 , 7.2640499999999997e-01 -1.8858463260554346e+00 , 3.2610347030830340e+00 , 8.1140144000000003e+00 , 5.7642599999999999e-01 , -6.3043499999999997e-01 , 5.1988900000000005e-01 -3.8589865545453792e+00 , 3.6390441742099271e+00 , 9.0364240000000007e-01 , 1.7335800000000001e-01 , -1.3665200000000000e-01 , -9.7533199999999998e-01 -3.8767173532004930e+00 , 3.6733375239304169e+00 , 9.3532079999999995e-01 , 1.7335800000000001e-01 , -1.3665200000000000e-01 , -9.7533199999999998e-01 -3.9256165653474584e+00 , 3.7354161368830758e+00 , 9.2184240000000006e-01 , -1.4444499999999999e-01 , 1.4832100000000001e-01 , 9.7833300000000001e-01 -3.9743101226491033e+00 , 3.7989280633689839e+00 , 9.1019439999999996e-01 , 1.0440700000000000e-01 , -1.9162599999999999e-01 , -9.7589899999999996e-01 -4.0072176136958575e+00 , 3.8489149829640925e+00 , 9.2288239999999999e-01 , 7.9957299999999995e-02 , -1.9384599999999999e-01 , -9.7776799999999997e-01 -4.0617104925062586e+00 , 3.9199906275593750e+00 , 9.0778159999999986e-01 , -1.0725500000000000e-01 , 1.7606600000000000e-01 , 9.7851800000000000e-01 -4.1004025823014132e+00 , 3.9753629183951684e+00 , 9.1683999999999988e-01 , 9.9052000000000001e-02 , -2.0225499999999999e-01 , -9.7431100000000004e-01 -4.1605686197459963e+00 , 4.0531065616520738e+00 , 8.9921200000000012e-01 , -8.7901400000000005e-02 , 1.9306400000000001e-01 , 9.7724100000000003e-01 -4.2101424389243842e+00 , 4.1208611397414439e+00 , 8.9822400000000013e-01 , -1.0184600000000001e-01 , 1.7145800000000000e-01 , 9.7991300000000003e-01 -4.2656508413378527e+00 , 4.1959309552258617e+00 , 8.9268079999999994e-01 , -6.2534400000000004e-02 , 1.8204000000000001e-01 , 9.8130099999999998e-01 -4.3270127053163359e+00 , 4.2773551382938297e+00 , 8.8299839999999996e-01 , -4.7430399999999998e-02 , 1.8969700000000000e-01 , 9.8069600000000001e-01 -4.3890543086228844e+00 , 4.3593521838286104e+00 , 8.7636320000000012e-01 , -3.5328499999999999e-02 , 2.0591000000000001e-01 , 9.7793300000000005e-01 -4.4620197821485492e+00 , 4.4547799883380694e+00 , 8.5958800000000002e-01 , -1.4546600000000000e-02 , 1.9950999999999999e-01 , 9.7978799999999999e-01 -4.5406965609349896e+00 , 4.5578916189919845e+00 , 8.4008799999999995e-01 , -3.0946399999999999e-02 , 2.0876000000000000e-01 , 9.7747700000000004e-01 -4.6209806140587641e+00 , 4.6617641327673773e+00 , 8.2467519999999994e-01 , -6.8837499999999996e-02 , 2.0481900000000000e-01 , 9.7637600000000002e-01 -4.6948317137367050e+00 , 4.7625074401955079e+00 , 8.1866400000000006e-01 , -7.2287900000000002e-02 , 1.8453700000000001e-01 , 9.8016400000000004e-01 -4.7742966058298268e+00 , 4.8700022158727858e+00 , 8.1053119999999979e-01 , -7.3036299999999998e-02 , 2.0002500000000001e-01 , 9.7706499999999996e-01 -4.8664156453522729e+00 , 4.9914482794632624e+00 , 7.9524320000000004e-01 , -7.8921300000000000e-02 , 2.0686499999999999e-01 , 9.7518099999999996e-01 -4.9590721297857527e+00 , 5.1148496937045440e+00 , 7.8452079999999991e-01 , -7.6929899999999996e-02 , 1.9596300000000000e-01 , 9.7758900000000004e-01 -5.0632576983253355e+00 , 5.2534599475910584e+00 , 7.6743359999999994e-01 , -1.3331100000000001e-01 , 1.6950299999999999e-01 , 9.7647200000000001e-01 -5.1678340254037654e+00 , 5.3931787299816349e+00 , 7.5592079999999995e-01 , 4.7362199999999999e-01 , -2.2278000000000001e-01 , -8.5208700000000004e-01 -5.2419174410685558e+00 , 5.5010470166912970e+00 , 7.7486959999999994e-01 , 9.9050300000000002e-01 , -5.6236300000000003e-02 , 1.2546599999999999e-01 -5.1813362762364417e+00 , 5.4597440885115152e+00 , 9.0475519999999987e-01 , 9.9732200000000004e-01 , 2.8965700000000000e-02 , 6.7160700000000004e-02 -5.1735318392251415e+00 , 5.4780904928561442e+00 , 9.8888183999999990e-01 , 9.9851900000000005e-01 , 4.8293700000000002e-02 , 2.5053800000000001e-02 -5.1726227392709720e+00 , 5.5005830359332020e+00 , 1.0686872800000000e+00 , 9.9435600000000002e-01 , 1.0607700000000000e-01 , 1.8433300000000000e-03 -5.1755861276217789e+00 , 5.5304078815522884e+00 , 1.1435860000000000e+00 , 9.9835099999999999e-01 , 3.7982799999999997e-02 , -4.3045699999999999e-02 -5.1597574949728315e+00 , 5.5371422568421496e+00 , 1.2316209599999999e+00 , 9.8620699999999994e-01 , -1.0711500000000001e-02 , -1.6517200000000001e-01 -5.2921842903230463e+00 , 5.7161981973049905e+00 , 1.2210462399999999e+00 , -7.7005000000000001e-01 , -4.1883799999999999e-01 , 4.8124499999999998e-01 -5.1309753865495082e+00 , 5.5524459904045216e+00 , 1.4015600799999999e+00 , 9.5152599999999998e-01 , 1.7162900000000000e-01 , 2.5522699999999998e-01 -5.1317782335200945e+00 , 5.5770152407134290e+00 , 1.4762216800000001e+00 , 9.7436500000000004e-01 , 1.9096900000000000e-02 , -2.2416200000000000e-01 -5.1304059157470405e+00 , 5.5995942807977599e+00 , 1.5511432800000000e+00 , 9.4219699999999995e-01 , 8.4587599999999996e-04 , -3.3505800000000002e-01 -5.1601252209117243e+00 , 5.6598647928265144e+00 , 1.6089038400000000e+00 , -8.7960600000000000e-01 , 2.1456000000000001e-03 , 4.7569800000000001e-01 -5.1827340762921983e+00 , 5.7108732521483256e+00 , 1.6719091200000000e+00 , -7.9149000000000003e-01 , 3.8295000000000003e-02 , 6.0998200000000002e-01 -5.2428521830671926e+00 , 5.8078034262706826e+00 , 1.7178771200000000e+00 , -8.0181300000000000e-01 , 8.0193699999999996e-03 , 5.9752099999999997e-01 -6.0795640415856065e+00 , 6.9250542434672244e+00 , 1.6075580800000000e+00 , 4.1520499999999999e-01 , 6.5179799999999999e-01 , 6.3463700000000001e-01 -1.7230357908756396e+01 , 2.1474829001457586e+01 , -8.9083600000000018e-01 , -1.0044500000000001e-01 , 1.8603900000000001e-01 , 9.7739500000000001e-01 -2.0117148965567818e+01 , 2.5358390520089884e+01 , -1.1788536000000001e+00 , -5.6136799999999998e-01 , -6.9361099999999995e-02 , 8.2465500000000003e-01 -2.0696256308115871e+01 , 2.6274829146311486e+01 , -8.1281519999999974e-01 , 2.8432900000000000e-01 , 1.4176400000000000e-01 , -9.4818800000000003e-01 -2.1086363623030511e+01 , 2.6952079421139103e+01 , -3.7713840000000021e-01 , -4.4166100000000003e-01 , -6.9404900000000005e-02 , 8.9449400000000001e-01 -2.1187737598183528e+01 , 2.7255532172745802e+01 , 1.2802080000000005e-01 , -4.8038399999999998e-01 , 5.7672200000000000e-03 , 8.7703900000000001e-01 -2.6279470415347379e+01 , 3.4226204681975936e+01 , -4.0384000000002196e-03 , 9.9702800000000003e-01 , 5.3064399999999998e-02 , 5.5857700000000003e-02 -2.6215795366434563e+01 , 3.4358674989177018e+01 , 6.7669359999999990e-01 , 9.9575599999999997e-01 , 6.5539000000000000e-02 , 6.4616499999999993e-02 -2.6137971866171689e+01 , 3.4472996668760707e+01 , 1.3591842400000000e+00 , 9.9645700000000004e-01 , 6.9183099999999997e-02 , 4.7827900000000000e-02 -2.6078504714216336e+01 , 3.4610882914218038e+01 , 2.0417205360000001e+00 , 9.9745399999999995e-01 , 6.2437899999999998e-02 , 3.4451599999999999e-02 -2.6028439533655185e+01 , 3.4764682245293891e+01 , 2.7258503200000002e+00 , 9.9811899999999998e-01 , 5.5288200000000003e-02 , 2.6478399999999999e-02 -2.2374638766763130e+01 , 2.9938371196471302e+01 , 3.3621088000000001e+00 , -1.7840300000000001e-01 , 8.9232599999999995e-01 , 4.1464000000000001e-01 -2.5901521893211733e+01 , 3.5035865207060048e+01 , 4.1026304000000007e+00 , 9.9766600000000005e-01 , 5.4652300000000001e-02 , 4.0948800000000000e-02 -2.5810866704844539e+01 , 3.5135488637346846e+01 , 4.7936063999999998e+00 , 9.9767399999999995e-01 , 5.4223500000000001e-02 , 4.1308900000000003e-02 -2.5743398317001869e+01 , 3.5267826688118014e+01 , 5.4888671999999996e+00 , 9.9776600000000004e-01 , 5.5416699999999999e-02 , 3.7303000000000003e-02 -2.5715634249973764e+01 , 3.5457662904952571e+01 , 6.1933944000000007e+00 , 9.9826999999999999e-01 , 5.0566500000000000e-02 , 2.9994000000000000e-02 -2.5650191970461744e+01 , 3.5595186854009718e+01 , 6.8986392000000007e+00 , 9.9809000000000003e-01 , 4.4923600000000001e-02 , 4.2399100000000002e-02 -2.5576858668754010e+01 , 3.5724001492605808e+01 , 7.6070768000000006e+00 , 9.9767499999999998e-01 , 4.6724500000000002e-02 , 4.9605799999999999e-02 -2.5489239190063003e+01 , 3.5832729510898766e+01 , 8.3176775999999997e+00 , 9.9777800000000005e-01 , 4.9414899999999998e-02 , 4.4690800000000003e-02 -2.5445949249427454e+01 , 3.6008594722875927e+01 , 9.0443359999999995e+00 , 9.9829000000000001e-01 , 4.7970499999999999e-02 , 3.3407300000000001e-02 -2.5381987589608102e+01 , 3.6157136447630805e+01 , 9.7732303999999992e+00 , 9.9882800000000005e-01 , 3.6840199999999997e-02 , 3.1404099999999997e-02 -2.5316154065317981e+01 , 3.6303919228553987e+01 , 1.0508687200000001e+01 , 9.9770999999999999e-01 , 3.9347500000000001e-02 , 5.5018400000000002e-02 -2.5251467868006618e+01 , 3.6456558691883089e+01 , 1.1252786400000000e+01 , 9.9493600000000004e-01 , 6.2113500000000002e-02 , 7.9027899999999998e-02 -2.5133426158308222e+01 , 3.6530574819122215e+01 , 1.1984613600000001e+01 , 9.9493600000000004e-01 , 6.2113500000000002e-02 , 7.9027799999999995e-02 -4.9568616475052201e+00 , 7.0959869846438881e+00 , 6.9070008000000005e+00 , 3.0162699999999998e-01 , 9.5279800000000003e-01 , 3.4598600000000000e-02 -4.8914095194776568e+00 , 7.0281971712001026e+00 , 6.9781784000000000e+00 , -4.6142000000000000e-01 , -8.6975000000000002e-01 , 1.7500299999999999e-01 -4.8322796670884181e+00 , 6.9739240336329136e+00 , 7.0598080000000003e+00 , 7.2459300000000004e-01 , 6.8890700000000005e-01 , -1.9292699999999999e-02 -4.6468439388635225e+00 , 6.6732322248365614e+00 , 6.9191792000000003e+00 , -4.5476100000000003e-01 , 6.3683199999999995e-01 , 6.2260499999999996e-01 -4.6093296710036817e+00 , 6.6550798514231468e+00 , 7.0265800000000000e+00 , 1.8115700000000001e-01 , 9.7629600000000005e-01 , 1.1843800000000000e-01 -4.5616920929751767e+00 , 6.6207514430187633e+00 , 7.1200967999999998e+00 , -3.2761200000000001e-01 , -9.2205999999999999e-01 , -2.0609700000000000e-01 -4.5210212836550960e+00 , 6.5983831233901089e+00 , 7.2270399999999997e+00 , -8.3573500000000001e-01 , -8.3826100000000001e-02 , -5.4269699999999998e-01 -4.4748614802590003e+00 , 6.5683335962292064e+00 , 7.3262560000000008e+00 , -8.7280199999999997e-01 , -1.3103200000000001e-01 , -4.7015800000000002e-01 -4.4183372336120641e+00 , 6.5152359440577925e+00 , 7.4037879999999996e+00 , 2.2453600000000001e-01 , 9.3082299999999996e-01 , 2.8836099999999998e-01 -4.3931037179804839e+00 , 6.5283196208464771e+00 , 7.5529032000000003e+00 , 4.8226100000000000e-01 , 2.4366499999999999e-01 , 8.4145800000000004e-01 -4.3128035443759263e+00 , 6.4251548113950090e+00 , 7.5771455999999997e+00 , -1.1515200000000000e-01 , -8.2439799999999996e-01 , -5.5417400000000006e-01 -4.7023385693426505e+00 , 7.3542491028635197e+00 , 8.7880488000000003e+00 , -4.9205800000000000e-01 , -8.5788399999999998e-01 , 1.4803500000000000e-01 -3.9796953503937385e+00 , 5.8277652103023847e+00 , 7.1497472000000002e+00 , 3.7273099999999998e-01 , 4.4013300000000000e-01 , 8.1691800000000003e-01 -3.9101109282560698e+00 , 5.7372779999587857e+00 , 7.1653680000000008e+00 , -6.0952699999999999e-02 , 1.1418399999999999e-01 , 9.9158800000000002e-01 -3.8736836764897902e+00 , 5.7222959792847892e+00 , 7.2729872000000002e+00 , 6.5997799999999995e-02 , 2.7288099999999998e-01 , 9.5978100000000000e-01 -3.7569732672790224e+00 , 5.5153872003512330e+00 , 7.1328576000000004e+00 , 6.6327499999999995e-01 , 4.2557900000000003e-02 , -7.4716400000000005e-01 -3.7198835015677951e+00 , 5.4987003759017981e+00 , 7.2371176000000004e+00 , 5.2616300000000005e-01 , 1.2015500000000000e-01 , 8.4185200000000004e-01 -3.6659292387826765e+00 , 5.4393110868503669e+00 , 7.2839592000000000e+00 , -3.7618900000000000e-01 , -8.4809000000000001e-01 , -3.7312899999999999e-01 -3.6658803353183353e+00 , 5.5183888619053789e+00 , 7.5288895999999994e+00 , -7.5812500000000005e-01 , -5.8677199999999996e-01 , -2.8450999999999999e-01 -3.5976297968817468e+00 , 5.4255616082732931e+00 , 7.5331744000000000e+00 , 2.0487400000000000e-01 , -3.8463999999999998e-01 , 9.0004399999999996e-01 -3.4930692702861958e+00 , 5.2327884088622207e+00 , 7.3815008000000004e+00 , 3.9211800000000002e-01 , -7.1776199999999998e-02 , 9.1711100000000001e-01 -3.4399364666716608e+00 , 5.1759426192016029e+00 , 7.4305888000000007e+00 , 5.8355299999999999e-01 , -4.7680600000000001e-01 , 6.5736000000000006e-01 -3.4199693686092982e+00 , 5.2148187025733614e+00 , 7.6350840000000000e+00 , -9.7135400000000005e-01 , 1.0785599999999999e-01 , -2.1175099999999999e-01 -3.3648014903943215e+00 , 5.1546634368196678e+00 , 7.6831216000000007e+00 , -8.2676000000000005e-01 , -4.6724200000000000e-02 , -5.6061099999999997e-01 -3.3044010099626453e+00 , 5.0784427751666570e+00 , 7.7029648000000002e+00 , -7.7429899999999996e-01 , -3.6551800000000001e-01 , -5.1658300000000001e-01 -3.2755192616934838e+00 , 5.1014621117191474e+00 , 7.9007000000000005e+00 , -7.7104899999999998e-01 , -3.3726899999999999e-01 , -5.4012300000000002e-01 -3.1551457817278328e+00 , 4.8209096217894389e+00 , 7.5471104000000002e+00 , -6.4471599999999996e-01 , 7.6436099999999996e-01 , -9.6686099999999994e-03 -3.1009607056040647e+00 , 4.7561677825642406e+00 , 7.5778216000000000e+00 , -9.2859100000000006e-01 , -3.3128900000000000e-01 , 1.6722999999999999e-01 -3.1348020001465926e+00 , 5.0310430139320843e+00 , 8.2800712000000001e+00 , -8.1847499999999995e-01 , -5.5142300000000000e-01 , -1.6134499999999999e-01 -3.0948039137401304e+00 , 5.0471823327275338e+00 , 8.4991888000000007e+00 , -9.7875999999999996e-01 , -1.6347700000000001e-01 , 1.2371300000000000e-01 -3.0513966562445121e+00 , 5.0613465839279712e+00 , 8.7288935999999993e+00 , -5.0296500000000000e-01 , -8.5707299999999997e-01 , 1.1158999999999999e-01 -2.9933281420312352e+00 , 5.0185368056867512e+00 , 8.8465592000000015e+00 , -2.9517300000000002e-01 , -6.2324900000000005e-01 , 7.2417799999999999e-01 -2.7581059562404699e+00 , 4.0394496131076352e+00 , 6.8248927999999998e+00 , 1.2276700000000000e-01 , 2.7540700000000001e-01 , 9.5345599999999997e-01 -2.7123919964219265e+00 , 3.9729125397296410e+00 , 6.8116536000000005e+00 , -1.1116600000000000e-01 , 5.9685200000000005e-01 , 7.9461300000000001e-01 -2.6707017909678967e+00 , 3.9292418685875488e+00 , 6.8547720000000005e+00 , -1.8633600000000000e-02 , 3.6343599999999998e-01 , 9.3143299999999996e-01 -2.6981669327660098e+00 , 4.4673698828117558e+00 , 8.3984752000000000e+00 , 4.4159500000000002e-01 , 5.1015500000000003e-01 , -7.3806200000000000e-01 -2.5803990839233699e+00 , 3.7815396801338093e+00 , 6.7822736000000008e+00 , -5.0075599999999998e-01 , -6.7749999999999999e-01 , -5.3873700000000002e-01 -2.5382067903381311e+00 , 3.7340850318651873e+00 , 6.8117992000000003e+00 , 8.3708099999999996e-01 , 1.2726299999999999e-01 , 5.3207199999999999e-01 -2.4944477920054062e+00 , 3.6283950988984044e+00 , 6.6731464000000003e+00 , 2.0468800000000001e-01 , -1.5453100000000000e-01 , 9.6655199999999997e-01 -2.4543247419355496e+00 , 3.5946243120404979e+00 , 6.7394151999999998e+00 , 9.8645799999999995e-01 , -1.5334500000000001e-01 , -5.8197499999999999e-02 -2.4013481818278235e+00 , 3.9104656938957985e+00 , 7.9373807999999997e+00 , 9.9709999999999999e-01 , 3.9454200000000002e-02 , -6.5079899999999996e-02 -2.3380734217424881e+00 , 3.9777350480889053e+00 , 8.4158952000000014e+00 , -8.7492599999999998e-01 , 2.2068900000000000e-01 , -4.3104500000000001e-01 -2.3215057286013603e+00 , 3.5356219281174219e+00 , 7.1244232000000007e+00 , -6.2851199999999996e-01 , 3.1376199999999999e-01 , 7.1170699999999998e-01 -2.2783125182788400e+00 , 3.4715165218009925e+00 , 7.1079911999999998e+00 , -1.1743999999999999e-03 , 4.6472999999999998e-01 , 8.8545099999999999e-01 -2.2307968216916145e+00 , 3.4318964464702173e+00 , 7.1910664000000004e+00 , 5.5127199999999998e-01 , 7.7189200000000002e-01 , 3.1667299999999998e-01 -2.1255612487250568e+00 , 3.5930717407964838e+00 , 8.1319544000000015e+00 , 5.2081200000000005e-01 , -7.6036599999999999e-01 , 3.8807000000000003e-01 -2.0624874264755206e+00 , 3.5463822249089070e+00 , 8.2557040000000015e+00 , -5.6410400000000005e-01 , 7.3763400000000001e-01 , -3.7105700000000003e-01 -1.9948259285859382e+00 , 3.5026571704328049e+00 , 8.4089896000000000e+00 , 6.7004799999999998e-01 , -7.0042700000000002e-01 , 2.4584300000000001e-01 -1.9688616948051045e+00 , 3.3648029674587185e+00 , 8.0933911999999992e+00 , -7.3241999999999996e-01 , 4.2325800000000002e-01 , -5.3330400000000000e-01 -1.9128290095189739e+00 , 3.2964288614504831e+00 , 8.1215335999999994e+00 , 4.7853499999999999e-01 , -4.2677199999999998e-01 , 7.6737900000000003e-01 -1.8533537522700996e+00 , 3.2329916307947415e+00 , 8.1787232000000003e+00 , -6.5558899999999998e-01 , -7.5474600000000003e-01 , -2.3717100000000001e-02 -3.9078728510924527e+00 , 3.6183715049872180e+00 , 9.3794160000000004e-01 , -2.0331500000000000e-01 , 1.0035700000000000e-01 , 9.7395699999999996e-01 -3.9474374077669321e+00 , 3.6700156127877408e+00 , 9.3921040000000011e-01 , -1.7485100000000001e-01 , 1.2914400000000001e-01 , 9.7608899999999998e-01 -3.9919962179551147e+00 , 3.7266514273906362e+00 , 9.3468639999999992e-01 , -1.3340700000000000e-01 , 1.9537099999999999e-01 , 9.7161399999999998e-01 -4.0322416077983192e+00 , 3.7800146639810870e+00 , 9.3931439999999999e-01 , -1.1414400000000000e-01 , 2.1103800000000000e-01 , 9.7079099999999996e-01 -4.0888196076591976e+00 , 3.8477140579510660e+00 , 9.2376639999999988e-01 , -1.1687699999999999e-01 , 1.7117299999999999e-01 , 9.7828400000000004e-01 -4.1338208138197245e+00 , 3.9075593387095164e+00 , 9.2473359999999993e-01 , -1.2639800000000001e-01 , 1.6286600000000001e-01 , 9.7851800000000000e-01 -4.1857739610005478e+00 , 3.9725278810746310e+00 , 9.2096879999999981e-01 , -9.8084199999999996e-02 , 2.0678099999999999e-01 , 9.7345800000000005e-01 -4.2375295798674202e+00 , 4.0389419958264448e+00 , 9.1911760000000009e-01 , -6.3416299999999995e-02 , 1.7554800000000001e-01 , 9.8242600000000002e-01 -4.3002866328759062e+00 , 4.1164149996412585e+00 , 9.0591999999999984e-01 , -6.8386699999999995e-02 , 1.8587200000000001e-01 , 9.8019100000000003e-01 -4.3576674688038217e+00 , 4.1906758855032900e+00 , 9.0205120000000005e-01 , -3.5003500000000000e-02 , 1.8449800000000000e-01 , 9.8220900000000000e-01 -4.4280155529113117e+00 , 4.2761394740860625e+00 , 8.8799040000000007e-01 , -2.4968100000000000e-02 , 1.8596399999999999e-01 , 9.8223899999999997e-01 -4.4980329131395678e+00 , 4.3632869230774514e+00 , 8.7695600000000007e-01 , -3.9561399999999997e-02 , 1.9744000000000000e-01 , 9.7951600000000005e-01 -4.5737746716896357e+00 , 4.4570066422894890e+00 , 8.6289520000000008e-01 , -4.9527200000000000e-02 , 2.0158300000000001e-01 , 9.7821800000000003e-01 -4.6440877415180513e+00 , 4.5465167352896882e+00 , 8.5836079999999981e-01 , 4.7919499999999997e-02 , -2.1502299999999999e-01 , -9.7543299999999999e-01 -4.7333181997290632e+00 , 4.6556196858819288e+00 , 8.3918319999999991e-01 , -5.8508299999999999e-02 , 1.9597100000000001e-01 , 9.7886300000000004e-01 -4.8099279613024262e+00 , 4.7535901832287966e+00 , 8.3588639999999992e-01 , -7.6594999999999996e-02 , 1.7771500000000001e-01 , 9.8109700000000000e-01 -4.8992935154727864e+00 , 4.8664239409993506e+00 , 8.2472720000000010e-01 , -7.0125699999999999e-02 , 1.9815500000000000e-01 , 9.7765899999999994e-01 -4.9941826415365158e+00 , 4.9861924973696343e+00 , 8.1224720000000006e-01 , 6.7921599999999999e-02 , -1.9197200000000000e-01 , -9.7904700000000000e-01 -5.0966300163481897e+00 , 5.1140086623402539e+00 , 7.9920560000000007e-01 , -1.3687900000000000e-01 , 1.7736499999999999e-01 , 9.7458000000000000e-01 -5.2045161068069525e+00 , 5.2500158075763910e+00 , 7.8575839999999997e-01 , 5.5798199999999998e-01 , -1.3576400000000000e-01 , -8.1867199999999996e-01 -5.2509550846677993e+00 , 5.3224512953886487e+00 , 8.2843999999999984e-01 , 9.8585699999999998e-01 , -3.6277499999999997e-02 , -1.6361600000000001e-01 -5.2263928670495972e+00 , 5.3221201348895679e+00 , 9.2694880000000013e-01 , 9.8405299999999996e-01 , 1.2260900000000000e-01 , -1.2886500000000001e-01 -5.2326783770311227e+00 , 5.3536689487771323e+00 , 1.0005995200000000e+00 , 9.6912399999999999e-01 , 2.4655600000000000e-01 , -2.9640000000000001e-03 -5.2189819340823460e+00 , 5.3624484919629083e+00 , 1.0886781600000000e+00 , 9.7741900000000004e-01 , 2.0951900000000001e-01 , 2.7449500000000002e-02 -5.2102543927327876e+00 , 5.3773394244062356e+00 , 1.1712687200000000e+00 , 9.8824400000000001e-01 , 1.2582399999999999e-01 , 8.6848200000000000e-02 -5.2074294864748349e+00 , 5.3984991886845490e+00 , 1.2493082400000000e+00 , 9.9680100000000005e-01 , 6.4092800000000005e-02 , 4.7756000000000000e-02 -5.1966094323540819e+00 , 5.4102069515530040e+00 , 1.3314547200000000e+00 , 9.9295000000000000e-01 , -9.9923100000000001e-02 , 6.3756999999999994e-02 -5.3212814948636558e+00 , 5.5712961252858442e+00 , 1.3301973600000001e+00 , -4.3480900000000000e-01 , 9.0037100000000003e-01 , -1.6558300000000001e-02 -5.1661389279233596e+00 , 5.4237889321824024e+00 , 1.4978068800000002e+00 , 9.9759900000000001e-01 , 2.4192600000000002e-02 , -6.4897200000000002e-02 -5.1659933186412008e+00 , 5.4460223930451868e+00 , 1.5712360800000000e+00 , -9.2669500000000005e-01 , 4.5580700000000002e-02 , 3.7304100000000001e-01 -5.1911306523032019e+00 , 5.4972781121895444e+00 , 1.6307459200000001e+00 , -8.7499700000000002e-01 , 5.2491299999999998e-02 , 4.8127500000000001e-01 -5.2218509240775717e+00 , 5.5553851603461055e+00 , 1.6885366400000001e+00 , 7.8654100000000005e-01 , -6.3858399999999996e-02 , -6.1422800000000000e-01 -5.2717207952936178e+00 , 5.6355515650758603e+00 , 1.7386833600000000e+00 , 7.7790099999999995e-01 , -7.6649099999999998e-02 , -6.2369500000000000e-01 -6.0256900951821430e+00 , 6.7071769015527503e+00 , 2.0430232400000001e+00 , 4.3662000000000001e-01 , 6.5435500000000002e-01 , 6.1739999999999995e-01 -2.1030607841494987e+01 , 2.5234231877032418e+01 , -8.2531599999999994e-01 , 2.3748700000000000e-01 , 2.9072900000000002e-01 , -9.2686400000000002e-01 -2.2429623475984595e+01 , 2.7120378738552397e+01 , -5.8353680000000052e-01 , 1.9607300000000000e-01 , 7.7573499999999995e-01 , -5.9982500000000005e-01 -2.2305495486376945e+01 , 2.7134903849084242e+01 , -2.6283999999999974e-02 , 3.5625600000000002e-01 , 9.3379299999999998e-01 , -3.3337199999999997e-02 -2.2461008844601107e+01 , 2.7497931976817949e+01 , 4.9101200000000000e-01 , 3.5625699999999999e-01 , 9.3379299999999998e-01 , -3.3337100000000001e-02 -2.6603328228901685e+01 , 3.2899728078955803e+01 , 6.1202639999999997e-01 , 7.7395700000000001e-01 , 4.2861300000000002e-01 , 4.6613399999999999e-01 -2.6557699659448708e+01 , 3.3049439339352858e+01 , 1.2765770400000001e+00 , 7.7395700000000001e-01 , 4.2861399999999999e-01 , 4.6613500000000002e-01 -2.6465415076732270e+01 , 3.3140349371103227e+01 , 1.9453012000000001e+00 , 9.9481200000000003e-01 , 9.7473900000000002e-02 , 2.9131399999999998e-02 -2.6417205297723612e+01 , 3.3286566167703128e+01 , 2.6133556000000002e+00 , 9.9480199999999996e-01 , 9.4558199999999995e-02 , 3.7795099999999998e-02 -2.6349396766835810e+01 , 3.3408542089797763e+01 , 3.2836720000000001e+00 , 9.9619100000000005e-01 , 8.2497399999999999e-02 , 2.8247200000000000e-02 -2.6285629458894324e+01 , 3.3537279661772288e+01 , 3.9561880000000000e+00 , -9.2250500000000002e-01 , -3.0057299999999998e-01 , 2.4215600000000001e-01 -2.6239726763994440e+01 , 3.3690437157106111e+01 , 4.6325935999999999e+00 , 9.5578200000000002e-01 , 2.4825500000000000e-01 , 1.5764300000000001e-01 -2.6179430440675510e+01 , 3.3825608555449911e+01 , 5.3117760000000001e+00 , 9.9605800000000000e-01 , 8.5237800000000002e-02 , 2.4572600000000000e-02 -2.6104965004396117e+01 , 3.3942733253100407e+01 , 5.9932151999999999e+00 , 9.9592199999999997e-01 , 8.6309100000000000e-02 , 2.6272500000000001e-02 -2.6054317210668309e+01 , 3.4093124910204466e+01 , 6.6816120000000003e+00 , 9.9602700000000000e-01 , 8.1712400000000004e-02 , 3.5410799999999999e-02 -2.5975799502419257e+01 , 3.4207730327822119e+01 , 7.3705704000000001e+00 , 9.9519800000000003e-01 , 8.1173400000000007e-02 , 5.4697200000000001e-02 -2.5908231949908330e+01 , 3.4338987124521125e+01 , 8.0658415999999988e+00 , -9.4369999999999998e-01 , -2.8996499999999997e-01 , -1.5921900000000000e-01 -2.5839058371606029e+01 , 3.4468220519836947e+01 , 8.7662504000000006e+00 , 9.9713200000000002e-01 , 7.1729699999999993e-02 , 2.4136000000000001e-02 -2.5767113485870667e+01 , 3.4596467682365109e+01 , 9.4716720000000016e+00 , 9.9594099999999997e-01 , 8.9979900000000002e-02 , 2.4891599999999998e-03 -2.5716176374288850e+01 , 3.4756138832945616e+01 , 1.0189979200000000e+01 , 9.9398699999999995e-01 , 1.0484100000000000e-01 , 3.1605399999999999e-02 -2.5632290956643949e+01 , 3.4872096812518130e+01 , 1.0905624000000001e+01 , 9.9425300000000005e-01 , 1.0006400000000000e-01 , 3.8055800000000001e-02 -2.5575366342662573e+01 , 3.5028325816237263e+01 , 1.1637700800000001e+01 , 9.9243199999999998e-01 , 1.0124900000000001e-01 , 6.9484900000000002e-02 -2.5496954594104640e+01 , 3.5157066039850889e+01 , 1.2370484800000000e+01 , 9.9243199999999998e-01 , 1.0124900000000001e-01 , 6.9484900000000002e-02 -5.0920734255105007e+00 , 7.0162618227878575e+00 , 6.8774023999999994e+00 , 5.0151999999999997e-01 , -2.6152799999999998e-01 , 8.2467000000000001e-01 -5.0209770540416478e+00 , 6.9432318162965343e+00 , 6.9424751999999996e+00 , 6.5388800000000002e-01 , -1.0916900000000000e-01 , 7.4867399999999995e-01 -5.0530605551664998e+00 , 7.0566465681217343e+00 , 7.1696632000000005e+00 , 2.4287500000000001e-01 , 8.2387999999999995e-01 , 5.1208799999999999e-01 -4.9323086905561500e+00 , 6.8955349704972182e+00 , 7.1558831999999999e+00 , -2.5105800000000000e-01 , 6.8396000000000001e-01 , 6.8495899999999998e-01 -4.8853830319780744e+00 , 6.8690017841048174e+00 , 7.2618799999999997e+00 , -2.2983199999999999e-02 , 3.5035300000000003e-01 , 9.3633599999999995e-01 -4.7597332555853651e+00 , 6.6940998326801919e+00 , 7.2260000000000009e+00 , -1.6747699999999999e-01 , 3.4155200000000002e-01 , 9.2482100000000000e-01 -4.6717818117393577e+00 , 6.5896280990181015e+00 , 7.2526032000000002e+00 , -3.0422600000000001e-02 , -1.0530800000000000e-01 , -9.9397400000000002e-01 -4.5322398764589735e+00 , 6.3827495996547192e+00 , 7.1710256000000001e+00 , -8.3463699999999996e-01 , -1.8852099999999999e-01 , -5.1753400000000005e-01 -4.6494904866732760e+00 , 6.6696514353299445e+00 , 7.6028960000000003e+00 , 1.4818700000000001e-01 , 9.3984000000000001e-01 , -3.0780099999999999e-01 -4.5575746987703241e+00 , 6.5555260783378211e+00 , 7.6176640000000004e+00 , 1.4641199999999999e-01 , -9.2633699999999997e-01 , -3.4707700000000002e-01 -4.1919033445750884e+00 , 5.8910605226780088e+00 , 7.0085048000000008e+00 , 2.5318299999999999e-01 , 9.6584199999999998e-01 , -5.5206300000000000e-02 -3.9637628324336651e+00 , 5.4867388859304196e+00 , 6.6606040000000002e+00 , 6.1100100000000002e-01 , 7.9047900000000004e-01 , 4.2674299999999998e-02 -3.9013834449029905e+00 , 5.4114859665434754e+00 , 6.6795944000000000e+00 , -9.1461300000000001e-01 , -1.4273200000000000e-02 , -4.0407700000000002e-01 -4.0227137118193390e+00 , 5.7240669787521004e+00 , 7.1765584000000002e+00 , -3.7273000000000001e-01 , -4.4013300000000000e-01 , -8.1691800000000003e-01 -3.9829350199527491e+00 , 5.7045217697569797e+00 , 7.2766064000000004e+00 , 2.4166399999999999e-01 , -1.4946999999999999e-01 , 9.5877900000000005e-01 -3.8475674315993400e+00 , 5.4752183803030476e+00 , 7.1056511999999996e+00 , -4.0414699999999998e-01 , -7.7891999999999995e-01 , -4.7953000000000001e-01 -3.7846778514661836e+00 , 5.4008595230103538e+00 , 7.1289888000000001e+00 , 7.9885700000000004e-01 , 5.9191099999999996e-01 , 1.0709200000000001e-01 -3.7500136205453152e+00 , 5.3918377690198742e+00 , 7.2401856000000002e+00 , -7.1945899999999996e-01 , -3.2982099999999998e-01 , -6.1122600000000005e-01 -3.7108879460260584e+00 , 5.3729448978698029e+00 , 7.3435927999999997e+00 , -2.8660000000000002e-01 , -6.6739199999999999e-01 , -6.8734799999999996e-01 -3.6652618861498021e+00 , 5.3423562629135279e+00 , 7.4297360000000001e+00 , 7.2920899999999997e-02 , 3.1685900000000000e-01 , 9.4566499999999998e-01 -3.5920286790815092e+00 , 5.2424385691014077e+00 , 7.4136264000000001e+00 , -5.8605600000000002e-01 , 7.9662299999999997e-01 , -1.4808900000000000e-01 -3.5179712782409815e+00 , 5.1371117100906813e+00 , 7.3862432000000000e+00 , 3.2091199999999998e-01 , -4.8850700000000002e-01 , 8.1140400000000001e-01 -3.4980138425432079e+00 , 5.1730609715001901e+00 , 7.5814927999999995e+00 , 7.8885700000000003e-01 , 2.6457599999999998e-01 , 5.5471099999999995e-01 -3.4015161221696788e+00 , 5.0052675365969375e+00 , 7.4448575999999997e+00 , -9.0213600000000005e-01 , 4.2688399999999999e-01 , 6.2610600000000002e-02 -3.4119543497294864e+00 , 5.1323341650277321e+00 , 7.8089512000000010e+00 , -1.1910500000000000e-01 , 9.2022700000000002e-01 , 3.7282300000000002e-01 -3.5978528343419609e+00 , 5.7917892899615717e+00 , 9.1454136000000013e+00 , -9.1745800000000000e-01 , 3.1553300000000001e-01 , -2.4229999999999999e-01 -3.3796543250398381e+00 , 5.2727774561492673e+00 , 8.3884703999999992e+00 , -2.1874199999999999e-01 , -2.9199599999999998e-01 , 9.3106900000000004e-01 -3.2381670448594826e+00 , 4.9560891920181733e+00 , 7.9617063999999997e+00 , 2.3794400000000000e-02 , -2.4697100000000000e-01 , 9.6873100000000001e-01 -3.1561429364877149e+00 , 4.8123784708246014e+00 , 7.8475560000000000e+00 , 6.1173500000000003e-01 , -4.5656099999999999e-01 , 6.4601299999999995e-01 -3.0873465780373230e+00 , 4.7137634086648834e+00 , 7.8124560000000001e+00 , 2.9581800000000003e-01 , 9.4077800000000000e-01 , 1.6561699999999999e-01 -3.1228356468339520e+00 , 5.0083068571153078e+00 , 8.6073696000000020e+00 , -6.0365300000000000e-01 , -7.8481800000000002e-01 , -1.4022499999999999e-01 -3.0484516544362692e+00 , 4.9046434731283792e+00 , 8.5829191999999992e+00 , -1.8560299999999999e-01 , -9.8262499999999997e-01 , -6.2189700000000005e-05 -2.8112258881855583e+00 , 4.0464186308109564e+00 , 6.8286471999999998e+00 , 3.4537800000000000e-02 , 4.9955600000000000e-01 , 8.6559299999999995e-01 -2.7633185382656933e+00 , 3.9841060058020910e+00 , 6.8253919999999999e+00 , 1.2397500000000000e-01 , -4.8427900000000002e-01 , -8.6608499999999999e-01 -2.7196447907169468e+00 , 3.9345683159180402e+00 , 6.8494992000000003e+00 , -1.2522200000000000e-01 , 5.5855699999999997e-01 , 8.1996000000000002e-01 -2.7688647619183948e+00 , 4.5101717611277863e+00 , 8.4784615999999993e+00 , -6.1483699999999997e-01 , -5.4457599999999995e-01 , 5.7045000000000001e-01 -2.6213361272195455e+00 , 3.7670763106810488e+00 , 6.7192183999999999e+00 , 7.0350599999999996e-01 , 3.4054000000000001e-01 , -6.2378800000000001e-01 -2.5791964903370448e+00 , 3.7217228066800239e+00 , 6.7486296000000001e+00 , -7.2841900000000004e-01 , -4.7405200000000002e-02 , -6.8349000000000004e-01 -2.5394400317380157e+00 , 3.7096950635744328e+00 , 6.8754576000000007e+00 , -8.6629500000000004e-01 , 3.8087500000000002e-01 , 3.2321600000000000e-01 -2.4930462970520924e+00 , 3.5967857829958829e+00 , 6.7056984000000002e+00 , 1.5462600000000001e-01 , 2.3890600000000001e-01 , 9.5865299999999998e-01 -2.4513090337254173e+00 , 3.5813640611291708e+00 , 6.8310704000000007e+00 , -8.0462400000000001e-01 , 5.5216500000000002e-01 , 2.1839000000000000e-01 -2.3928166494882568e+00 , 3.9323256844962660e+00 , 8.1916296000000006e+00 , -9.6707900000000002e-01 , 2.1992300000000001e-01 , -1.2803500000000001e-01 -2.3523264270375459e+00 , 3.6385724110888935e+00 , 7.4206568000000006e+00 , -3.5788399999999998e-01 , 2.0533499999999999e-01 , 9.1091000000000000e-01 -2.3135318365027784e+00 , 3.4925569274722368e+00 , 7.1145328000000001e+00 , -4.3986799999999998e-01 , 2.4992400000000001e-01 , 8.6258599999999996e-01 -2.2668277656134848e+00 , 3.4396777989714624e+00 , 7.1372567999999994e+00 , 3.8097999999999999e-01 , 7.5575199999999998e-01 , 5.3262799999999999e-01 -2.1803424876867963e+00 , 3.5561699131726821e+00 , 7.8656312000000002e+00 , 4.8524499999999998e-01 , 7.4726700000000001e-01 , 4.5401500000000000e-01 -2.1115162465582240e+00 , 3.5426426043490760e+00 , 8.1105719999999994e+00 , 7.5579099999999999e-01 , -5.5452400000000002e-01 , 3.4825699999999998e-01 -2.0466525654298491e+00 , 3.4948156248535343e+00 , 8.2230167999999999e+00 , -5.0337500000000002e-01 , 7.9558799999999996e-01 , -3.3712599999999998e-01 -2.0061649020944419e+00 , 3.3852895381495669e+00 , 8.0396752000000014e+00 , -6.9887999999999995e-01 , 5.4023600000000005e-01 , -4.6873399999999998e-01 -1.9477816437626281e+00 , 3.3243233097184044e+00 , 8.0882536000000016e+00 , 5.3163899999999997e-01 , -8.3907699999999996e-01 , 1.1536700000000000e-01 -1.8946694825586916e+00 , 3.2505457121976997e+00 , 8.0743487999999992e+00 , -6.4949999999999997e-01 , 6.5871500000000005e-01 , -3.7979499999999999e-01 -3.9722977165621449e+00 , 3.6083616186056391e+00 , 9.4942320000000002e-01 , -1.8186600000000000e-01 , 1.3127200000000000e-01 , 9.7452200000000000e-01 -4.0137940729700716e+00 , 3.6591133271962497e+00 , 9.5195039999999986e-01 , -1.3322300000000001e-01 , 1.7591399999999999e-01 , 9.7534900000000002e-01 -4.0602990079061918e+00 , 3.7148384233654550e+00 , 9.4860159999999993e-01 , -8.3608600000000005e-02 , 1.6388100000000000e-01 , 9.8293100000000000e-01 -4.1128090573091818e+00 , 3.7766408944876968e+00 , 9.3978240000000013e-01 , -7.7281600000000006e-02 , 1.8009600000000001e-01 , 9.8060899999999995e-01 -4.1599109414881292e+00 , 3.8341848420970939e+00 , 9.4029199999999991e-01 , -8.0278400000000000e-02 , 1.9141800000000000e-01 , 9.7821999999999998e-01 -4.2129974166363358e+00 , 3.8978550619605361e+00 , 9.3564319999999990e-01 , -4.2576700000000002e-02 , 1.7036599999999999e-01 , 9.8446100000000003e-01 -4.2730296343217145e+00 , 3.9666791215078701e+00 , 9.2636640000000003e-01 , -6.0277799999999999e-02 , 1.4321000000000000e-01 , 9.8785500000000004e-01 -4.3266412955275051e+00 , 4.0323128185534864e+00 , 9.2629359999999994e-01 , -7.6978300000000000e-02 , 1.6248000000000001e-01 , 9.8370500000000005e-01 -4.3922626498083748e+00 , 4.1079576290357958e+00 , 9.1519679999999992e-01 , -5.1777700000000003e-02 , 1.8347400000000000e-01 , 9.8165999999999998e-01 -4.4576242091876654e+00 , 4.1862451035771775e+00 , 9.0662719999999997e-01 , -2.4116599999999998e-02 , 1.9014000000000000e-01 , 9.8146100000000003e-01 -4.5298078121364629e+00 , 4.2709771717547600e+00 , 8.9463599999999999e-01 , -4.7146399999999998e-02 , 1.5492700000000001e-01 , 9.8680000000000001e-01 -4.5965287120590910e+00 , 4.3504634008528527e+00 , 8.9228559999999990e-01 , -5.1641399999999997e-02 , 1.9167600000000001e-01 , 9.8009900000000005e-01 -4.6822736120616621e+00 , 4.4493306452762162e+00 , 8.7428320000000004e-01 , -5.2101099999999997e-02 , 2.0128299999999999e-01 , 9.7814699999999999e-01 -4.7554059419579504e+00 , 4.5370776953076586e+00 , 8.7215120000000002e-01 , -4.9921300000000002e-02 , 1.9816200000000000e-01 , 9.7889700000000002e-01 -4.8474126851933672e+00 , 4.6444725606024768e+00 , 8.5568800000000000e-01 , -4.5630700000000003e-02 , 1.8943599999999999e-01 , 9.8083200000000004e-01 -4.9389194285187124e+00 , 4.7527635541525832e+00 , 8.4346799999999988e-01 , -6.7876000000000006e-02 , 1.7746300000000001e-01 , 9.8178399999999999e-01 -5.0260050459610746e+00 , 4.8568475456338991e+00 , 8.4110719999999994e-01 , 5.7964399999999999e-02 , -1.7745900000000001e-01 , -9.8241999999999996e-01 -5.1306952550954090e+00 , 4.9810329188945595e+00 , 8.2629759999999997e-01 , -1.1860000000000000e-01 , 1.6883100000000001e-01 , 9.7848400000000002e-01 -5.2439307523187475e+00 , 5.1133174221996072e+00 , 8.1136319999999995e-01 , -6.0572700000000002e-01 , 2.2189800000000001e-01 , 7.6410500000000003e-01 -5.2655791909419563e+00 , 5.1587511527448431e+00 , 8.7283759999999999e-01 , -9.6345499999999995e-01 , 3.0025300000000001e-02 , 2.6618000000000003e-01 -5.2671190772985685e+00 , 5.1838199886254488e+00 , 9.5016159999999994e-01 , -9.7366799999999998e-01 , -2.4780300000000002e-02 , 2.2662099999999999e-01 -5.2934368462935018e+00 , 5.2337020422119771e+00 , 1.0083807999999999e+00 , 9.9751599999999996e-01 , 4.5660800000000001e-02 , -5.3636099999999999e-02 -5.2927646532333306e+00 , 5.2568580770851998e+00 , 1.0862612000000000e+00 , 9.9679200000000001e-01 , 7.6647400000000004e-02 , 2.3020700000000002e-02 -5.2514407878500595e+00 , 5.2393341811888714e+00 , 1.1907323200000000e+00 , 9.8663199999999995e-01 , 6.6982600000000003e-02 , 1.4856000000000000e-01 -5.2358949375072097e+00 , 5.2455634685187116e+00 , 1.2763399199999999e+00 , 9.9438400000000005e-01 , 5.9693299999999998e-02 , -8.7396199999999993e-02 -5.2263254134894570e+00 , 5.2579597988722337e+00 , 1.3568889600000000e+00 , 9.8889899999999997e-01 , 8.5508399999999998e-02 , 1.2151800000000000e-01 -5.4487926797683066e+00 , 5.5115513696233442e+00 , 1.2980249600000000e+00 , -2.3938200000000001e-01 , 8.0687999999999996e-02 , 9.6756699999999995e-01 -5.1893299728098157e+00 , 5.2645737786816307e+00 , 1.5241261600000000e+00 , 9.8828600000000000e-01 , 1.2234600000000000e-01 , 9.1222399999999995e-02 -5.2031164591355079e+00 , 5.3003172197950921e+00 , 1.5884969600000001e+00 , -9.2828200000000005e-01 , 8.2676599999999996e-03 , 3.7178600000000001e-01 -5.2226327080585460e+00 , 5.3437057824444132e+00 , 1.6499307999999999e+00 , -8.8117000000000001e-01 , 3.2810800000000001e-02 , 4.7165899999999999e-01 -5.2487955260371333e+00 , 5.3927817846538364e+00 , 1.7093699199999999e+00 , 7.8680200000000000e-01 , -6.6047099999999997e-02 , -6.1366200000000004e-01 -5.3135239340296376e+00 , 5.4854999239658184e+00 , 1.7511945600000001e+00 , 6.8563799999999997e-01 , -3.7585899999999998e-02 , -7.2697199999999995e-01 -6.2942654849162665e+00 , 6.7796381960730949e+00 , 2.0858005199999998e+00 , -5.0547200000000003e-01 , -5.7424799999999998e-01 , -6.4400100000000005e-01 -1.7831546288279412e+01 , 2.0037120238791623e+01 , -5.0410159999999982e-01 , 1.1142900000000000e-01 , -1.7929000000000000e-01 , -9.7746500000000003e-01 -2.1926462475437891e+01 , 2.4883874904201821e+01 , -9.5574240000000010e-01 , -2.3748700000000000e-01 , -2.9072900000000002e-01 , 9.2686400000000002e-01 -2.3644541036090516e+01 , 2.7033983443296954e+01 , -7.6330080000000011e-01 , -3.2431799999999997e-02 , -3.9712599999999998e-01 , 9.1719099999999998e-01 -2.3728673064078212e+01 , 2.7301045354820623e+01 , -2.2615120000000033e-01 , -3.2431799999999997e-02 , -3.9712599999999998e-01 , 9.1719099999999998e-01 -2.3699789569171536e+01 , 2.7435156381936132e+01 , 3.3295279999999994e-01 , 1.3736400000000001e-01 , 6.7141799999999996e-01 , -7.2823700000000002e-01 -2.8276070260715237e+01 , 3.3239234136581075e+01 , 1.0993496000000000e+00 , 7.7395700000000001e-01 , 4.2861300000000002e-01 , 4.6613399999999999e-01 -2.6948692068775230e+01 , 3.1851918858368489e+01 , 1.8512644000000000e+00 , 9.8911800000000005e-01 , 1.3617099999999999e-01 , 5.5710799999999998e-02 -2.6813778939770838e+01 , 3.1888239757121752e+01 , 2.5088127199999999e+00 , 9.9148000000000003e-01 , 1.2290500000000000e-01 , 4.3139700000000003e-02 -2.6850549476252077e+01 , 3.2132436614036173e+01 , 3.1648312000000001e+00 , 9.9134900000000004e-01 , 1.3122400000000001e-01 , 2.5963499999999999e-03 -2.8024496595751302e+01 , 3.3986118118634920e+01 , 4.5630800000000002e+00 , 9.8678100000000002e-01 , 1.4978200000000000e-01 , 6.1869100000000003e-02 -2.6511564830766858e+01 , 3.2524261165565619e+01 , 5.8120159999999998e+00 , 9.9109100000000006e-01 , 1.2393300000000000e-01 , 4.8778000000000002e-02 -2.6538794178476003e+01 , 3.2766842273484883e+01 , 6.4946200000000003e+00 , 9.9311099999999997e-01 , 1.1644200000000000e-01 , -1.3095000000000001e-02 -2.7712425406840577e+01 , 3.4686993999181432e+01 , 8.1119343999999991e+00 , -9.4369999999999998e-01 , -2.8996499999999997e-01 , -1.5922000000000000e-01 -2.6169062130111886e+01 , 3.3139169612900716e+01 , 9.2020624000000009e+00 , 9.9152799999999996e-01 , 1.2900300000000001e-01 , 1.5165600000000000e-02 -2.6233298850876647e+01 , 3.3441036723784613e+01 , 9.9341703999999993e+00 , 9.9188600000000005e-01 , 1.1905800000000000e-01 , -4.4583999999999999e-02 -2.6213231620091484e+01 , 3.3635828854243258e+01 , 1.0653995999999999e+01 , 9.8858199999999996e-01 , 1.4832699999999999e-01 , -2.6539600000000000e-02 -2.6015692874995967e+01 , 3.3824570225378693e+01 , 1.2065026400000001e+01 , 9.7977000000000003e-01 , 1.6285800000000000e-01 , 1.1631300000000000e-01 -2.5853474489974062e+01 , 3.3835406409618784e+01 , 1.2753600000000000e+01 , 9.7977000000000003e-01 , 1.6285800000000000e-01 , 1.1631300000000000e-01 -5.5113008701114587e+00 , 7.0511358167006799e+00 , 6.1069703999999998e+00 , 8.1334400000000001e-02 , 3.1845299999999999e-01 , 9.4444300000000003e-01 -5.4081532710318410e+00 , 6.9368771867115600e+00 , 6.1450240000000003e+00 , 5.0343899999999997e-02 , 3.8208900000000001e-01 , 9.2275300000000005e-01 -5.2961156665034430e+00 , 6.8082630305251657e+00 , 6.1678936000000002e+00 , -1.0168400000000000e-01 , 5.7915000000000005e-01 , 8.0885399999999996e-01 -5.2781559920383572e+00 , 6.9628720815005476e+00 , 6.7522592000000010e+00 , 2.1049399999999999e-01 , 1.2584999999999999e-01 , 9.6946100000000002e-01 -5.2398897575493040e+00 , 6.9515178251167633e+00 , 6.8669400000000005e+00 , 1.8021899999999999e-01 , 7.2580699999999998e-02 , 9.8094499999999996e-01 -5.1400578109225359e+00 , 6.8383345490656158e+00 , 6.8952176000000005e+00 , -2.9588199999999998e-01 , -5.0080699999999999e-02 , -9.5391099999999995e-01 -5.0325475462285976e+00 , 6.7115188865887774e+00 , 6.9069280000000006e+00 , -5.4961099999999999e-02 , 1.6997899999999999e-01 , 9.8391399999999996e-01 -5.1130725936892603e+00 , 6.9006295669055122e+00 , 7.2039416000000003e+00 , 7.3189800000000005e-01 , 4.1139900000000001e-01 , 5.4320900000000005e-01 -5.0047682879002666e+00 , 6.7701405298902744e+00 , 7.2129896000000002e+00 , -7.7941600000000000e-01 , 5.2043899999999998e-01 , -3.4878999999999999e-01 -4.9086248307872822e+00 , 6.6613234773591392e+00 , 7.2373880000000002e+00 , 3.5954900000000001e-01 , 2.7716299999999999e-01 , 8.9101399999999997e-01 -5.2136352135544657e+00 , 7.2532614351943643e+00 , 7.9637343999999999e+00 , -7.4986200000000003e-01 , 4.9058900000000000e-01 , 4.4388100000000003e-01 -4.8754884811555641e+00 , 6.7195701565994570e+00 , 7.5616079999999997e+00 , -1.0526800000000000e-01 , -9.5091899999999996e-01 , -2.9098299999999999e-01 -4.7972339724315987e+00 , 6.6414918172192507e+00 , 7.6158647999999998e+00 , -3.8157499999999997e-02 , -9.9783500000000003e-01 , -5.3567700000000003e-02 -4.5835656078852214e+00 , 6.3127184886702388e+00 , 7.3930448000000002e+00 , 8.8074600000000003e-01 , -3.8128400000000000e-02 , 4.7205200000000003e-01 -4.2175217698119747e+00 , 5.6925972662014974e+00 , 6.8194743999999998e+00 , -8.7014999999999998e-01 , 3.3675300000000002e-01 , -3.5977399999999998e-01 -3.9972843119554087e+00 , 5.3291721311939177e+00 , 6.5075680000000000e+00 , -5.9763599999999995e-01 , 8.7509699999999996e-02 , -7.9697799999999996e-01 -3.9659252701002341e+00 , 5.3205444725726352e+00 , 6.6003672000000000e+00 , -7.9203500000000004e-01 , -1.7040799999999998e-02 , -6.1023799999999995e-01 -3.9310971882632657e+00 , 5.3031700695510233e+00 , 6.6859071999999999e+00 , -9.1415700000000000e-01 , -1.2896900000000000e-01 , -3.8429600000000003e-01 -3.9121902795440850e+00 , 5.3210592390153835e+00 , 6.8181016000000003e+00 , 7.7522300000000000e-01 , 4.9711100000000003e-01 , 3.8975700000000002e-01 -3.8707894856520335e+00 , 5.2939163197297221e+00 , 6.8958936000000000e+00 , 8.0634600000000001e-01 , 8.6164099999999993e-02 , 5.8513400000000004e-01 -3.7680635052611615e+00 , 5.1407245823783434e+00 , 6.8040408000000001e+00 , -6.9537499999999997e-01 , -3.0277999999999999e-01 , -6.5175000000000005e-01 -3.7705277497165821e+00 , 5.2063576436939929e+00 , 7.0090664000000009e+00 , -2.6907399999999998e-01 , -9.0183500000000005e-01 , 3.3807199999999998e-01 -3.7527777916248928e+00 , 5.2326734351793975e+00 , 7.1675519999999997e+00 , -6.9544399999999995e-01 , -6.3056299999999998e-01 , 3.4459800000000002e-01 -3.7692348180377557e+00 , 5.3394187408450158e+00 , 7.4531776000000001e+00 , 2.0014299999999999e-01 , -4.6246300000000001e-01 , 8.6375400000000002e-01 -3.6950017105462551e+00 , 5.2467370354977607e+00 , 7.4463656000000000e+00 , -2.5180700000000000e-01 , 4.0102100000000002e-01 , 8.8078100000000004e-01 -3.6189484092025008e+00 , 5.1496858140468387e+00 , 7.4280407999999998e+00 , -1.9500000000000001e-01 , 3.1972800000000001e-01 , 9.2722700000000002e-01 -3.5474765545644455e+00 , 5.0579352457031126e+00 , 7.4159040000000003e+00 , 8.3924900000000002e-01 , -4.9698999999999999e-01 , -2.2059400000000001e-01 -3.4677162346275847e+00 , 4.9471865151169361e+00 , 7.3656616000000001e+00 , -9.0213600000000005e-01 , 4.2688399999999999e-01 , 6.2610700000000005e-02 -3.4586225183417443e+00 , 5.0102644313205689e+00 , 7.6135767999999997e+00 , -9.3608300000000000e-01 , -2.8543900000000000e-01 , -2.0560300000000001e-01 -3.5743119495992812e+00 , 5.4204528317591327e+00 , 8.4989287999999998e+00 , -8.1013799999999997e-02 , 2.0040100000000000e-01 , 9.7635899999999998e-01 -3.5038814123132140e+00 , 5.3470696664352255e+00 , 8.5412776000000008e+00 , 1.6964899999999999e-01 , 1.2963200000000000e-01 , 9.7694199999999998e-01 -3.3111446236401658e+00 , 4.9168698225083354e+00 , 7.8985576000000002e+00 , -3.4109000000000000e-01 , 3.9250599999999997e-02 , -9.3921100000000002e-01 -3.2684296462406071e+00 , 4.9111292370194501e+00 , 8.0506679999999999e+00 , 6.1753899999999995e-01 , -4.1853699999999999e-01 , 6.6593700000000000e-01 -3.1772876801311156e+00 , 4.7575373109016486e+00 , 7.9065968000000009e+00 , -5.5108500000000005e-01 , 5.9161200000000003e-01 , 5.8847300000000002e-01 -3.1305196739860195e+00 , 4.7393873516176104e+00 , 8.0384583999999997e+00 , -7.1506599999999998e-01 , 8.3595100000000006e-03 , 6.9900700000000004e-01 -3.1445792456450801e+00 , 4.9584683921788688e+00 , 8.6966640000000002e+00 , 6.1343899999999996e-01 , 7.7266500000000005e-01 , -1.6334499999999999e-01 -2.8642808576572216e+00 , 4.0462223128014845e+00 , 6.8231767999999997e+00 , 2.3390700000000000e-01 , 1.1914100000000000e-01 , 9.6493099999999998e-01 -2.8163450896872670e+00 , 3.9901222802252851e+00 , 6.8296560000000008e+00 , 1.3515600000000000e-01 , 3.0481799999999998e-01 , 9.4277200000000005e-01 -2.7745174567908140e+00 , 3.9608448122603201e+00 , 6.9020712000000009e+00 , -3.1623300000000000e-02 , 3.8707599999999998e-01 , 9.2150600000000005e-01 -2.8911627767897716e+00 , 4.8043681670568192e+00 , 9.2058584000000003e+00 , -9.1926699999999995e-01 , 1.0422900000000001e-02 , 3.9349600000000001e-01 -2.7636385302732500e+00 , 4.3914199389812971e+00 , 8.3569896000000004e+00 , -5.2407400000000004e-01 , -4.4857100000000000e-01 , 7.2396799999999994e-01 -2.6246800515031876e+00 , 3.7396760652206940e+00 , 6.7736936000000005e+00 , 3.5211300000000001e-01 , 2.9248499999999999e-01 , 8.8908299999999996e-01 -2.5786803426398799e+00 , 3.6841807217344975e+00 , 6.7729967999999996e+00 , 6.6296200000000005e-01 , 1.0370100000000000e-01 , 7.4143599999999998e-01 -2.5370620576204383e+00 , 3.6649735808531974e+00 , 6.8795967999999998e+00 , -8.4071499999999999e-01 , 3.7177700000000002e-01 , 3.9367400000000002e-01 -2.4900203409044335e+00 , 3.5835446777727507e+00 , 6.7974472000000006e+00 , 8.3426100000000003e-01 , 2.6513300000000001e-01 , -4.8343900000000001e-01 -2.4439290000490979e+00 , 3.8655196684570972e+00 , 7.9078552000000002e+00 , 9.9709999999999999e-01 , 3.9454200000000002e-02 , -6.5079899999999996e-02 -2.4044336740094412e+00 , 3.4184405414870018e+00 , 6.5973927999999997e+00 , -8.3107699999999995e-01 , 5.4153099999999998e-01 , 1.2671399999999999e-01 -2.3491095009745617e+00 , 3.5248014621868768e+00 , 7.1714936000000007e+00 , 7.9405899999999996e-01 , 4.8758299999999997e-02 , -6.0588299999999995e-01 -2.3021273520052219e+00 , 3.4576995799454586e+00 , 7.1340640000000004e+00 , -4.9628199999999997e-02 , 5.5710499999999996e-01 , 8.2895799999999997e-01 -2.2517386889901663e+00 , 3.4181444284513134e+00 , 7.2063128000000001e+00 , 5.5127199999999998e-01 , 7.7189200000000002e-01 , 3.1667299999999998e-01 -2.1610465251106299e+00 , 3.5264830361483268e+00 , 7.9249736000000004e+00 , 2.9389599999999999e-01 , 5.5367299999999997e-01 , 7.7914799999999995e-01 -2.1023545110348567e+00 , 3.4693380376087273e+00 , 7.9766720000000007e+00 , 1.7625299999999999e-01 , -5.5900399999999995e-01 , 8.1021500000000002e-01 -2.0341383013698482e+00 , 3.4306789611947774e+00 , 8.1180495999999991e+00 , 6.7627800000000005e-01 , -2.4895400000000001e-01 , 6.9330300000000000e-01 -1.9825025530915816e+00 , 3.3511308556698749e+00 , 8.0653216000000008e+00 , 4.7171400000000002e-01 , -7.0371300000000003e-01 , 5.3129499999999996e-01 -1.9200636721642881e+00 , 3.2901065415654651e+00 , 8.1127871999999996e+00 , 5.8363200000000004e-01 , -3.8824500000000001e-01 , 7.1318999999999999e-01 -1.8553854555831495e+00 , 3.2319178640872384e+00 , 8.1790768000000007e+00 , -6.5558899999999998e-01 , -7.5474600000000003e-01 , -2.3717100000000001e-02 -4.0366135064275870e+00 , 3.5963771010907690e+00 , 9.6161823999999996e-01 , -9.2842700000000000e-02 , 1.5767700000000001e-01 , 9.8311700000000002e-01 -4.0800314698765536e+00 , 3.6462343443104288e+00 , 9.6541631999999988e-01 , -1.0479600000000000e-01 , 1.5516800000000000e-01 , 9.8231400000000002e-01 -4.1284559456926715e+00 , 3.7010751678010920e+00 , 9.6332591999999995e-01 , -5.1560200000000000e-02 , 1.6434499999999999e-01 , 9.8505399999999999e-01 -4.1828494555101070e+00 , 3.7609673460695490e+00 , 9.5597519999999991e-01 , 8.2331399999999999e-02 , -1.6702100000000000e-01 , -9.8250999999999999e-01 -4.2318688144080117e+00 , 3.8176372136928145e+00 , 9.5785760000000009e-01 , -4.0165199999999998e-02 , 1.7202700000000001e-01 , 9.8427299999999995e-01 -4.3053801412906232e+00 , 3.8945630550817634e+00 , 9.3374000000000001e-01 , -4.3279199999999997e-02 , 1.5282100000000001e-01 , 9.8730600000000002e-01 -4.3539212557295208e+00 , 3.9531733903593400e+00 , 9.3986559999999986e-01 , -8.6006600000000002e-02 , 1.3210600000000000e-01 , 9.8749699999999996e-01 -4.4155287996087615e+00 , 4.0217119274680888e+00 , 9.3479040000000002e-01 , -8.0962300000000001e-02 , 1.7024400000000001e-01 , 9.8207100000000003e-01 -4.4779115295006235e+00 , 4.0917658776313672e+00 , 9.3216960000000015e-01 , -1.8675100000000000e-02 , 1.8882699999999999e-01 , 9.8183299999999996e-01 -4.5583839901213778e+00 , 4.1788997640731012e+00 , 9.1275279999999981e-01 , -2.2063099999999999e-02 , 1.7363200000000001e-01 , 9.8456299999999997e-01 -4.6273092793911426e+00 , 4.2569864398402206e+00 , 9.0923759999999998e-01 , -6.4314200000000002e-02 , 1.6445100000000001e-01 , 9.8428599999999999e-01 -4.7019596630775151e+00 , 4.3405949860586386e+00 , 9.0269599999999994e-01 , -4.5924399999999997e-02 , 1.9162699999999999e-01 , 9.8039299999999996e-01 -4.7905094981334706e+00 , 4.4377175067370231e+00 , 8.8718960000000013e-01 , -3.1777199999999999e-02 , 1.9057800000000000e-01 , 9.8115799999999997e-01 -4.8796385211904756e+00 , 4.5356471836948469e+00 , 8.7576000000000009e-01 , -4.1725900000000003e-02 , 1.8076100000000001e-01 , 9.8264200000000002e-01 -4.9683488041202661e+00 , 4.6353808290963698e+00 , 8.6797039999999992e-01 , -5.8652200000000002e-02 , 1.7337400000000000e-01 , 9.8310799999999998e-01 -5.0636597806935058e+00 , 4.7419704938141800e+00 , 8.5868319999999998e-01 , -5.1595099999999998e-02 , 1.7333399999999999e-01 , 9.8351100000000002e-01 -5.1665945707168124e+00 , 4.8564937194675721e+00 , 8.4824159999999993e-01 , -1.2017200000000000e-01 , 1.5856400000000001e-01 , 9.8000799999999999e-01 -5.2760113219455684e+00 , 4.9780399036123022e+00 , 8.3720720000000015e-01 , 6.0555999999999999e-01 , -1.6971100000000000e-01 , -7.7749299999999999e-01 -5.3048227207099279e+00 , 5.0282364335461640e+00 , 8.9223359999999996e-01 , -9.4294000000000000e-01 , -7.4580900000000006e-02 , 3.2450200000000001e-01 -5.3005153439846451e+00 , 5.0469203237659883e+00 , 9.7349815999999989e-01 , 9.7469099999999997e-01 , 1.1452200000000000e-01 , -1.9199400000000000e-01 -5.3011345899099043e+00 , 5.0707201611453510e+00 , 1.0495783200000000e+00 , 9.9708300000000005e-01 , 7.3687900000000001e-02 , 1.9891200000000001e-02 -5.2947585220255320e+00 , 5.0872550284969158e+00 , 1.1302906400000001e+00 , 9.8384300000000002e-01 , 6.9161200000000006e-02 , 1.6513300000000000e-01 -5.2873273861910706e+00 , 5.1016659486691260e+00 , 1.2107824800000000e+00 , 9.9330600000000002e-01 , 8.8445599999999999e-02 , 7.4299299999999999e-02 -5.2709268578648549e+00 , 5.1087088559254354e+00 , 1.2949455200000000e+00 , 9.9822000000000000e-01 , 4.8357299999999999e-02 , -3.4911100000000000e-02 -5.2614741382368546e+00 , 5.1208954101732296e+00 , 1.3744836800000000e+00 , 9.9776600000000004e-01 , 5.0627499999999999e-02 , 4.3591299999999999e-02 -5.3258678945108748e+00 , 5.2058417458086286e+00 , 1.4093195199999999e+00 , 9.8812500000000003e-01 , 1.0816700000000000e-01 , 1.0912600000000000e-01 -5.2316297965907790e+00 , 5.1344769819950891e+00 , 1.5356722400000000e+00 , 9.9042399999999997e-01 , 8.4822800000000004e-02 , 1.0893200000000000e-01 -5.2397513889264502e+00 , 5.1635116536772898e+00 , 1.6024704000000001e+00 , -9.2464700000000000e-01 , -5.4098000000000000e-02 , 3.7696400000000002e-01 -5.2535878829863201e+00 , 5.1980661296497477e+00 , 1.6662359200000001e+00 , -8.8456100000000004e-01 , -2.4104100000000000e-02 , 4.6580100000000002e-01 -5.2877892603329002e+00 , 5.2532390801127855e+00 , 1.7207672800000000e+00 , -8.1501500000000004e-01 , 1.4711900000000000e-02 , 5.7925300000000002e-01 -5.3353642013658451e+00 , 5.3217981792768771e+00 , 1.7707954400000001e+00 , 6.7791999999999997e-01 , -7.0443900000000004e-02 , -7.3175299999999999e-01 -6.3468221687209683e+00 , 6.5760665170559678e+00 , 2.0879685040000000e+00 , -6.6703299999999999e-01 , -4.4557600000000003e-01 , -5.9710099999999999e-01 -2.3444281382098566e+01 , 2.5346374163642732e+01 , -6.9220639999999989e-01 , -5.6184699999999997e-02 , -3.7855600000000000e-01 , 9.2387200000000003e-01 -2.5264930194333360e+01 , 2.7505071469492723e+01 , -4.4603839999999995e-01 , -3.7256600000000001e-02 , -3.3409899999999998e-01 , 9.4180100000000000e-01 -2.5231480649452799e+01 , 2.7638150797216014e+01 , 1.3366799999999990e-01 , 4.8694399999999999e-02 , -5.6105899999999997e-01 , 8.2634200000000002e-01 -2.5434024858108607e+01 , 2.8033527326883611e+01 , 6.8993280000000001e-01 , 2.0319700000000000e-02 , -6.2440799999999996e-01 , 7.8083400000000003e-01 -2.7486198770287672e+01 , 3.0510069301362481e+01 , 1.1139959200000000e+00 , 9.9588500000000002e-01 , 5.6175200000000002e-02 , 7.1121699999999996e-02 -2.7437628186623471e+01 , 3.0646025896209952e+01 , 1.7574044000000000e+00 , 9.9413799999999997e-01 , 6.3499299999999995e-02 , 8.7512999999999994e-02 -2.7210511741797585e+01 , 3.0577596798001299e+01 , 2.4075510400000000e+00 , 9.9296899999999999e-01 , 8.2728599999999999e-02 , 8.4669700000000001e-02 -2.7230578858803522e+01 , 3.0790074935114440e+01 , 3.0500880000000001e+00 , 9.9787000000000003e-01 , 6.3819200000000006e-02 , 1.3544799999999999e-02 -2.7173122788696816e+01 , 3.0915422787780106e+01 , 3.6966663999999998e+00 , 9.9895599999999996e-01 , 2.1722300000000000e-02 , -4.0196599999999999e-02 -2.7203633189076243e+01 , 3.1143388403460818e+01 , 4.3499528000000005e+00 , 9.9956699999999998e-01 , 1.9384400000000000e-02 , 2.2155500000000002e-02 -2.7164370936649664e+01 , 3.1292055644931132e+01 , 5.0053087999999999e+00 , 9.9483299999999997e-01 , 5.3776699999999997e-02 , 8.6116100000000001e-02 -2.6988136356707628e+01 , 3.1280949862623967e+01 , 5.6506807999999999e+00 , 9.9457899999999999e-01 , 5.9836399999999998e-02 , 8.5041800000000001e-02 -2.6873454202737360e+01 , 3.1341533678620809e+01 , 6.3011071999999997e+00 , 9.9725799999999998e-01 , 6.3843700000000003e-02 , 3.7420599999999998e-02 -2.6889938684992863e+01 , 3.1559121917909536e+01 , 6.9735920000000000e+00 , 9.9904000000000004e-01 , 3.7075100000000000e-02 , -2.3334700000000000e-02 -2.6903303374694289e+01 , 3.1776396089658466e+01 , 7.6542303999999994e+00 , 9.9980300000000000e-01 , 1.9666699999999999e-02 , 2.8005600000000001e-03 -2.6842595255603584e+01 , 3.1905223213714194e+01 , 8.3279320000000006e+00 , 9.9453000000000003e-01 , 5.8939199999999997e-02 , 8.6229899999999998e-02 -2.6733410194586519e+01 , 3.1977426754366284e+01 , 8.9954040000000006e+00 , 9.9318499999999998e-01 , 6.8704299999999996e-02 , 9.4145300000000001e-02 -2.6558471716279811e+01 , 3.1969873277303741e+01 , 9.6478999999999999e+00 , 9.9728099999999997e-01 , 6.6881999999999997e-02 , 3.0939200000000000e-02 -2.6574761901965807e+01 , 3.2199413152833706e+01 , 1.0358105600000000e+01 , 9.9767099999999997e-01 , 5.2621000000000001e-02 , -4.3389499999999998e-02 -2.6607230790716272e+01 , 3.2450696665574412e+01 , 1.1085367200000000e+01 , 9.9992199999999998e-01 , 1.1003000000000001e-02 , -5.9010099999999999e-03 -2.6559161444288314e+01 , 3.2605643378937401e+01 , 1.1796644000000001e+01 , 9.9514999999999998e-01 , 4.7540399999999997e-02 , 8.6117100000000002e-02 -2.6412872441878118e+01 , 3.2639976619708250e+01 , 1.2478936000000001e+01 , 9.8872800000000005e-01 , 6.6237099999999993e-02 , 1.3427200000000000e-01 -2.6202891984526431e+01 , 3.2593803555586646e+01 , 1.3137568000000000e+01 , -9.7559300000000004e-01 , -2.1855900000000000e-01 , -2.1211700000000000e-02 -1.3659526040492899e+01 , 1.7197716739469385e+01 , 9.6784968000000013e+00 , -6.5492600000000001e-01 , -6.6743300000000005e-01 , 3.5440899999999997e-01 -5.6056058435419605e+00 , 6.9362818908726416e+00 , 6.1842424000000005e+00 , 8.1334500000000004e-02 , 3.1845299999999999e-01 , 9.4444300000000003e-01 -5.4728260824640715e+00 , 6.7878110935141764e+00 , 6.1936960000000001e+00 , 5.0344000000000000e-02 , 3.8208900000000001e-01 , 9.2275300000000005e-01 -5.4329998467702083e+00 , 6.7716413230601189e+00 , 6.2946488000000009e+00 , 1.5971900000000001e-02 , 5.7079299999999999e-01 , 8.2093799999999995e-01 -6.2597124398422253e+00 , 8.1547849464365427e+00 , 7.7707519999999999e+00 , -1.0391599999999999e-01 , 2.2643199999999999e-01 , 9.6846800000000000e-01 -5.3531311459007762e+00 , 6.8340719170934046e+00 , 6.8141080000000001e+00 , -1.0817999999999999e-02 , 1.3824600000000001e-01 , 9.9033899999999997e-01 -5.2363741977356391e+00 , 6.7029836546606330e+00 , 6.8236760000000007e+00 , -1.2310400000000001e-02 , 3.2282400000000000e-01 , 9.4637899999999997e-01 -5.1350772324727112e+00 , 6.5931537688813915e+00 , 6.8472423999999998e+00 , 2.8144499999999999e-02 , 2.3090600000000000e-01 , 9.7256900000000002e-01 -5.0561868930686735e+00 , 6.5187879119248837e+00 , 6.8987432000000002e+00 , 3.5019200000000000e-02 , 3.4558200000000000e-01 , 9.3773499999999999e-01 -4.9866770624258736e+00 , 6.4568289869799713e+00 , 6.9610704000000005e+00 , 7.0062000000000002e-01 , -6.1043000000000003e-01 , 3.6946899999999999e-01 -4.8956994329973611e+00 , 6.3599571346972343e+00 , 6.9878815999999997e+00 , 6.8855500000000003e-01 , -3.3891800000000000e-01 , 6.4111399999999996e-01 -5.3116677184883851e+00 , 7.0948918393343590e+00 , 7.8573840000000006e+00 , -8.6902599999999997e-01 , 3.0688199999999999e-01 , 3.8809399999999999e-01 -4.9749558351397045e+00 , 6.5976236582184304e+00 , 7.4834936000000001e+00 , 5.6190099999999998e-01 , 8.2091999999999998e-01 , 1.0177400000000000e-01 -4.6968038749508487e+00 , 6.1886397454387998e+00 , 7.1755704000000007e+00 , -7.0505200000000001e-01 , -5.7905899999999999e-01 , -4.0938099999999999e-01 -4.2292678581912897e+00 , 5.4443659541838034e+00 , 6.4700759999999997e+00 , -1.3208500000000000e-02 , -7.5845799999999997e-01 , 6.5158799999999995e-01 -4.1555614006897157e+00 , 5.3609169167038608e+00 , 6.4775536000000002e+00 , -1.3208700000000000e-02 , -7.5845899999999999e-01 , 6.5158700000000003e-01 -4.1036906125051225e+00 , 5.3167954909210406e+00 , 6.5268392000000004e+00 , 3.3086800000000000e-01 , -3.8084499999999999e-01 , 8.6341400000000001e-01 -4.0790012320377844e+00 , 5.3206513282592880e+00 , 6.6355919999999999e+00 , 4.8141499999999997e-02 , -9.8092599999999996e-01 , -1.8832699999999999e-01 -4.0015882586167413e+00 , 5.2303599280369362e+00 , 6.6294040000000001e+00 , 6.4023799999999997e-01 , 5.6727899999999998e-01 , 5.1796699999999996e-01 -4.0957065455856903e+00 , 5.4550157035381037e+00 , 7.0267151999999999e+00 , 2.3838599999999999e-01 , -7.5742500000000001e-01 , 6.0784800000000005e-01 -3.9269314716481674e+00 , 5.1954145328151196e+00 , 6.7984248000000003e+00 , -6.9619200000000003e-01 , -3.6770799999999998e-01 , -6.1652899999999999e-01 -3.8846903247872406e+00 , 5.1690669142321513e+00 , 6.8746879999999999e+00 , -6.9537499999999997e-01 , -3.0277999999999999e-01 , -6.5175000000000005e-01 -3.9290913491698669e+00 , 5.3144785883192522e+00 , 7.1948520000000000e+00 , -4.5081500000000002e-01 , -7.8079500000000002e-01 , -4.3258000000000002e-01 -3.8845711604696080e+00 , 5.2892182675862660e+00 , 7.2813071999999996e+00 , -6.1181099999999999e-01 , -7.9058499999999998e-01 , -2.5752500000000001e-02 -3.8599316937122250e+00 , 5.3052344178999906e+00 , 7.4345824000000000e+00 , 5.4262999999999995e-01 , 7.4907800000000002e-01 , 3.8004599999999999e-01 -3.8034700671520905e+00 , 5.2594183533799574e+00 , 7.4955471999999999e+00 , 6.1907900000000005e-01 , 6.5727500000000005e-01 , 4.2980400000000002e-01 -4.0010784428982582e+00 , 5.7644194777516979e+00 , 8.4368200000000009e+00 , -3.7557699999999999e-01 , 6.4824000000000004e-01 , -6.6236499999999998e-01 -3.7029336531604407e+00 , 5.1950962924980209e+00 , 7.6660968000000000e+00 , 4.8392700000000000e-01 , 8.5995900000000003e-01 , 1.6212599999999999e-01 -3.6663704765999370e+00 , 5.1962799041089163e+00 , 7.8117384000000003e+00 , 3.5570100000000000e-02 , 9.8860099999999995e-01 , 1.4629500000000001e-01 -3.5400142004988240e+00 , 4.9872248037237323e+00 , 7.5956472000000002e+00 , -9.6756299999999995e-01 , -2.5017400000000001e-01 , -3.5137000000000002e-02 -3.5543720679758524e+00 , 5.1152663784091130e+00 , 7.9707024000000004e+00 , 2.2322300000000000e-01 , -3.2203700000000002e-01 , -9.2003500000000005e-01 -3.4642114507706512e+00 , 4.9874047082762027e+00 , 7.8913399999999996e+00 , 8.5881700000000005e-02 , 1.2228799999999999e-01 , 9.8877199999999998e-01 -3.3937283313848914e+00 , 4.9091508060467763e+00 , 7.8989735999999997e+00 , -1.1704300000000001e-02 , -9.9942900000000001e-01 , 3.1714100000000002e-02 -3.3076208037644301e+00 , 4.7850607415160020e+00 , 7.8127991999999997e+00 , -3.4826499999999999e-01 , 4.5087800000000000e-01 , 8.2184000000000001e-01 -3.3092676932427922e+00 , 4.9107909614996093e+00 , 8.2316175999999999e+00 , -4.4101800000000002e-01 , -8.0121200000000004e-01 , 4.0442800000000001e-01 -3.1859526350532672e+00 , 4.6719184957094431e+00 , 7.8998575999999998e+00 , -4.6708499999999997e-01 , 4.4427699999999998e-01 , 7.6449299999999998e-01 -3.2365857741266137e+00 , 4.9790185016281328e+00 , 8.7445248000000007e+00 , 6.1343899999999996e-01 , 7.7266500000000005e-01 , -1.6334499999999999e-01 -3.1621688002677519e+00 , 4.9036812010143631e+00 , 8.7763279999999995e+00 , 6.1343899999999996e-01 , 7.7266500000000005e-01 , -1.6334499999999999e-01 -2.8672835921936781e+00 , 3.9849764239035057e+00 , 6.8150127999999999e+00 , 3.1161699999999998e-01 , 2.3337400000000000e-01 , 9.2110300000000001e-01 -2.8214289453759500e+00 , 3.9458310098423230e+00 , 6.8586408000000008e+00 , 3.4521700000000000e-01 , 3.3445100000000000e-01 , 8.7690800000000002e-01 -2.9726747158401494e+00 , 4.8189495462264098e+00 , 9.2271055999999998e+00 , -9.1926699999999995e-01 , 1.0422900000000001e-02 , 3.9349600000000001e-01 -2.8688026685525281e+00 , 4.5983333197255520e+00 , 8.8846752000000002e+00 , -9.4750400000000001e-01 , 7.1760099999999993e-02 , 3.1158599999999997e-01 -2.6692813758587266e+00 , 3.7443558649057227e+00 , 6.7695336000000008e+00 , 4.4947900000000002e-01 , 7.3702699999999999e-01 , 5.0473699999999999e-01 -2.6178352144879455e+00 , 3.6566222594593425e+00 , 6.6709519999999998e+00 , -7.5175099999999995e-01 , 2.5732899999999997e-01 , -6.0716700000000001e-01 -2.5786592861439046e+00 , 3.6699463997043633e+00 , 6.8657335999999995e+00 , 6.0213000000000005e-01 , -6.2415399999999999e-01 , -4.9786599999999998e-01 -2.5318520619078990e+00 , 3.6151681212392464e+00 , 6.8631856000000004e+00 , 6.4825699999999997e-01 , -1.1740600000000000e-01 , -7.5231499999999996e-01 -2.4846795250717557e+00 , 3.5448123536984091e+00 , 6.8096256000000004e+00 , -9.2918800000000001e-01 , 1.2641600000000000e-01 , 3.4731800000000002e-01 -2.4388143296765259e+00 , 3.4505909918401607e+00 , 6.6641816000000000e+00 , -8.1817799999999996e-01 , 1.5011300000000000e-01 , 5.5502399999999996e-01 -2.3925396773401109e+00 , 3.4481930382055959e+00 , 6.8374248000000000e+00 , -7.9552699999999998e-01 , 5.8643199999999995e-01 , -1.5242900000000001e-01 -2.3393366870958312e+00 , 3.4766390623453853e+00 , 7.1411672000000008e+00 , 6.6744000000000003e-01 , -4.0210000000000001e-01 , -6.2677000000000005e-01 -2.2896115380635353e+00 , 3.4258746926517274e+00 , 7.1632151999999998e+00 , -2.6668799999999998e-01 , -7.8714200000000001e-01 , -5.5613400000000002e-01 -2.2004749612154320e+00 , 3.5516874677387262e+00 , 7.9320040000000001e+00 , -5.7728900000000005e-01 , -5.8442400000000005e-01 , -5.7025000000000003e-01 -2.1343971093457386e+00 , 3.5154462128950366e+00 , 8.0647912000000002e+00 , 7.7517700000000000e-01 , 4.3153100000000000e-01 , -4.6139100000000000e-01 -2.0781969932725941e+00 , 3.4385277247481350e+00 , 8.0241272000000006e+00 , 4.9067100000000002e-01 , -5.8204900000000004e-01 , 6.4842900000000003e-01 -2.0232957466214536e+00 , 3.3633156977301732e+00 , 7.9816640000000003e+00 , 5.8208199999999999e-01 , -4.2844100000000002e-01 , 6.9110000000000005e-01 -1.9571646553047530e+00 , 3.3138416918280047e+00 , 8.0698247999999992e+00 , -5.3027899999999994e-01 , 7.6073100000000005e-01 , -3.7429000000000001e-01 -1.9012690990488659e+00 , 3.2421527531943313e+00 , 8.0446880000000007e+00 , -5.8002900000000002e-01 , 6.9152800000000003e-01 , -4.3052900000000000e-01 -4.0593436916836705e+00 , 3.5326677463203415e+00 , 9.7178839999999989e-01 , -8.4178799999999998e-02 , 1.4950200000000000e-01 , 9.8517200000000005e-01 -4.1027857750936692e+00 , 3.5803120703847950e+00 , 9.7508728000000011e-01 , -9.6009399999999995e-02 , 1.3746300000000000e-01 , 9.8584300000000002e-01 -4.1585256981603802e+00 , 3.6385352712411301e+00 , 9.6503464000000005e-01 , 7.4982499999999994e-02 , -1.6634699999999999e-01 , -9.8321199999999997e-01 -4.2098690130510086e+00 , 3.6925352169659340e+00 , 9.6463944000000001e-01 , -8.8128700000000004e-02 , 1.6939000000000001e-01 , 9.8160099999999995e-01 -4.2661349563828903e+00 , 3.7516184656120051e+00 , 9.5896000000000003e-01 , -2.5241400000000001e-02 , 1.8193699999999999e-01 , 9.8298600000000003e-01 -4.3232190607708629e+00 , 3.8121621696412689e+00 , 9.5543440000000013e-01 , -2.0832099999999999e-02 , 1.7427300000000001e-01 , 9.8447700000000005e-01 -4.3862188933114785e+00 , 3.8778631495817111e+00 , 9.4714560000000003e-01 , -1.0695600000000000e-01 , 1.6664599999999999e-01 , 9.8019900000000004e-01 -4.4376468986814110e+00 , 3.9345862015333655e+00 , 9.5507040000000010e-01 , 1.0521000000000000e-01 , -1.4593800000000001e-01 , -9.8368299999999997e-01 -4.5073204200041737e+00 , 4.0080918117481428e+00 , 9.4478480000000009e-01 , -3.3313700000000002e-02 , 1.8765699999999999e-01 , 9.8167000000000004e-01 -4.5837942294453775e+00 , 4.0869976762000979e+00 , 9.3108799999999992e-01 , -9.8616499999999996e-03 , 1.8571900000000000e-01 , 9.8255400000000004e-01 -4.6609272547170360e+00 , 4.1665253004198739e+00 , 9.2065679999999994e-01 , -6.8551200000000007e-02 , 1.7088600000000001e-01 , 9.8290299999999997e-01 -4.7326819967470843e+00 , 4.2428509993792751e+00 , 9.1955439999999977e-01 , -5.9415200000000001e-02 , 1.6359699999999999e-01 , 9.8473699999999997e-01 -4.8162551020213824e+00 , 4.3306028060848405e+00 , 9.0914399999999995e-01 , -4.7421199999999997e-02 , 2.0310800000000001e-01 , 9.7800699999999996e-01 -4.9075872824720701e+00 , 4.4260396930116634e+00 , 8.9635200000000004e-01 , -3.1019399999999999e-02 , 1.9522700000000001e-01 , 9.8026800000000003e-01 -4.9994925905534799e+00 , 4.5222612846720649e+00 , 8.8762639999999982e-01 , -6.1730300000000002e-02 , 1.8432699999999999e-01 , 9.8092400000000002e-01 -5.0849350632066228e+00 , 4.6142970717327341e+00 , 8.8831280000000001e-01 , -6.1787700000000001e-02 , 1.7892500000000000e-01 , 9.8192100000000004e-01 -5.1971179344215575e+00 , 4.7302068461494482e+00 , 8.7096559999999990e-01 , -1.1132400000000001e-01 , 1.6928299999999999e-01 , 9.7926000000000002e-01 -5.3038364341951487e+00 , 4.8430776402715505e+00 , 8.6365439999999993e-01 , -5.8394599999999997e-01 , 1.8552099999999999e-01 , 7.9030900000000004e-01 -5.3408007328103473e+00 , 4.8969748689532402e+00 , 9.1247199999999995e-01 , -8.7899700000000003e-01 , 6.4663100000000001e-02 , 4.7242200000000001e-01 -5.3366203531672269e+00 , 4.9154510492283787e+00 , 9.9272151999999991e-01 , 9.8460099999999995e-01 , -4.7674500000000002e-02 , -1.6819000000000001e-01 -5.4082385406782958e+00 , 4.9995697603950946e+00 , 1.0197084800000000e+00 , 9.9908399999999997e-01 , 3.1419599999999999e-02 , -2.9068099999999999e-02 -5.3321354190163124e+00 , 4.9553219947509257e+00 , 1.1475151200000000e+00 , 9.9250700000000003e-01 , 3.7314300000000002e-02 , 1.1635400000000000e-01 -5.3248530357150763e+00 , 4.9705695443774687e+00 , 1.2268900000000000e+00 , 9.9032200000000004e-01 , 1.3581099999999999e-01 , 2.8594399999999999e-02 -5.3165155844637528e+00 , 4.9836931468246544e+00 , 1.3060444000000000e+00 , 9.8669799999999996e-01 , 1.5775900000000001e-01 , 3.9239099999999999e-02 -5.3002634109248978e+00 , 4.9893760174428312e+00 , 1.3887940799999998e+00 , 9.7344900000000001e-01 , 2.1653100000000000e-01 , 7.4238600000000002e-02 -5.3106339973504930e+00 , 5.0202460809152196e+00 , 1.4546229600000000e+00 , 9.7900200000000004e-01 , 2.0131199999999999e-01 , 3.2078200000000001e-02 -5.2775353198002879e+00 , 5.0099923978019394e+00 , 1.5442387200000001e+00 , 9.8751199999999995e-01 , 1.5554299999999999e-01 , 2.5026500000000000e-02 -5.2789332156196345e+00 , 5.0324114043508095e+00 , 1.6136420800000000e+00 , 9.8326300000000000e-01 , 3.3382599999999998e-02 , -1.7910799999999999e-01 -5.2939152965003355e+00 , 5.0656594312902250e+00 , 1.6764237600000000e+00 , 8.9698900000000004e-01 , -4.4101499999999998e-03 , -4.4203199999999998e-01 -5.3224669390789732e+00 , 5.1130018637057839e+00 , 1.7330808799999999e+00 , -7.5800800000000002e-01 , 5.7322900000000003e-02 , 6.4972099999999999e-01 -5.3644679027385056e+00 , 5.1736184633186832e+00 , 1.7846295200000000e+00 , 6.1069899999999999e-01 , -9.8941799999999996e-02 , -7.8565700000000005e-01 -5.4567694053770488e+00 , 5.2813914250221972e+00 , 1.8175060000000001e+00 , 5.2414200000000000e-01 , -2.6397199999999999e-02 , -8.5122200000000003e-01 -6.4225851103613287e+00 , 6.4000880366295263e+00 , 2.0844987520000000e+00 , 5.4233799999999999e-01 , 3.4602600000000000e-01 , 7.6559500000000003e-01 -2.1389235901138317e+01 , 2.1850119329605484e+01 , -2.9061040000000027e-01 , -9.5552899999999996e-02 , 2.0003299999999999e-01 , 9.7511899999999996e-01 -2.5372608128754191e+01 , 2.6100710043497667e+01 , -4.4175360000000019e-01 , -1.4157900000000001e-01 , -3.9180799999999999e-01 , 9.0908900000000004e-01 -2.7814393922827644e+01 , 2.8802563172176040e+01 , -1.9755120000000037e-01 , 8.6384799999999995e-01 , 4.6368199999999998e-01 , -1.9689100000000001e-01 -2.7781853378188060e+01 , 2.8946862748317344e+01 , 4.2762400000000000e-01 , -8.8462600000000002e-01 , -4.5848899999999998e-01 , 8.5005700000000003e-02 -2.7726446895586612e+01 , 2.9068381463344025e+01 , 1.0557975200000000e+00 , -8.6178200000000005e-01 , -4.9618400000000001e-01 , 1.0551600000000000e-01 -2.7678609136181933e+01 , 2.9197058542231986e+01 , 1.6842185599999999e+00 , -9.3078099999999997e-01 , -3.6454599999999998e-01 , -2.7434900000000002e-02 -2.7609048677718754e+01 , 2.9302549814564784e+01 , 2.3145438399999998e+00 , -9.0603900000000004e-01 , -4.2271199999999998e-01 , -2.0204400000000001e-02 -2.7552361230580701e+01 , 2.9422535482346269e+01 , 2.9453246399999999e+00 , -8.8824999999999998e-01 , -4.5875800000000000e-01 , 2.3536800000000000e-02 -2.7494329452946921e+01 , 2.9541824179885747e+01 , 3.5777008000000001e+00 , -8.9697199999999999e-01 , -4.4203700000000001e-01 , 6.6990900000000004e-03 -2.7443556474353880e+01 , 2.9669800145147942e+01 , 4.2122568000000005e+00 , -9.0801299999999996e-01 , -4.1847800000000002e-01 , 1.9713399999999999e-02 -2.7377571689693180e+01 , 2.9780685312998660e+01 , 4.8487368000000002e+00 , -9.2180499999999999e-01 , -3.8765300000000003e-01 , 8.7163900000000001e-04 -2.7330412945867590e+01 , 2.9914911912392345e+01 , 5.4891376000000003e+00 , -9.0312899999999996e-01 , -4.2936099999999999e-01 , -2.5805799999999999e-03 -2.7262717446235587e+01 , 3.0024813609711234e+01 , 6.1310672000000004e+00 , -8.7148999999999999e-01 , -4.8963899999999999e-01 , 2.7542299999999999e-02 -2.7213642752462590e+01 , 3.0158545711583169e+01 , 6.7787271999999996e+00 , -8.7112699999999998e-01 , -4.8908299999999999e-01 , 4.3998799999999998e-02 -2.7149356252621935e+01 , 3.0275187016043631e+01 , 7.4284256000000006e+00 , -8.9395100000000005e-01 , -4.4624900000000001e-01 , 4.1392600000000002e-02 -2.7089759717109221e+01 , 3.0400100974890837e+01 , 8.0832927999999988e+00 , -9.0324000000000004e-01 , -4.2830000000000001e-01 , 2.6772500000000001e-02 -2.7035755351142580e+01 , 3.0531454284618995e+01 , 8.7445559999999993e+00 , -8.9475099999999996e-01 , -4.4591300000000000e-01 , 2.4148900000000001e-02 -2.6972880635832166e+01 , 3.0654218110164770e+01 , 9.4092927999999993e+00 , -8.6136199999999996e-01 , -5.0627000000000000e-01 , 4.1791300000000003e-02 -2.6907213951478283e+01 , 3.0776097629846987e+01 , 1.0079250400000001e+01 , -8.4714800000000001e-01 , -5.2594300000000005e-01 , 7.5655299999999995e-02 -2.6853296320028644e+01 , 3.0913304859725233e+01 , 1.0758973600000001e+01 , -8.2578499999999999e-01 , -5.6376999999999999e-01 , -1.5569800000000000e-02 -2.6782983701515096e+01 , 3.1033499795249856e+01 , 1.1440714400000001e+01 , -8.5823600000000000e-01 , -5.1224400000000003e-01 , -3.2202099999999997e-02 -2.6715960256514226e+01 , 3.1159455010767971e+01 , 1.2131035199999999e+01 , -8.7673999999999996e-01 , -4.7876999999999997e-01 , 4.5895499999999999e-02 -2.6659300210701065e+01 , 3.1300244820088285e+01 , 1.2833368000000000e+01 , -8.8168899999999994e-01 , -4.6320699999999998e-01 , 8.9798000000000003e-02 -2.6554894610784775e+01 , 3.1385514342815458e+01 , 1.3523928000000002e+01 , -8.8168899999999994e-01 , -4.6320699999999998e-01 , 8.9798000000000003e-02 -1.4335388393960965e+01 , 1.7129069486264285e+01 , 9.7452128000000009e+00 , -6.5492600000000001e-01 , -6.6743300000000005e-01 , 3.5440899999999997e-01 -5.7426140105380270e+00 , 6.8379580817272565e+00 , 6.1628704000000001e+00 , 2.1116499999999999e-01 , 3.4687200000000001e-01 , 9.1383199999999998e-01 -5.6803653875344997e+00 , 6.7947254144442297e+00 , 6.2459144000000002e+00 , 2.0705499999999999e-01 , 3.1077500000000002e-01 , 9.2765699999999995e-01 -5.5286415050316080e+00 , 6.6283117381797814e+00 , 6.2361072000000002e+00 , 3.7014999999999998e-01 , 7.0755800000000002e-01 , 6.0195600000000005e-01 -5.4670567936934571e+00 , 6.5838978234795817e+00 , 6.3134936000000001e+00 , 4.6735900000000002e-01 , 7.5042200000000003e-01 , 4.6737800000000002e-01 -5.5008787319030308e+00 , 6.6735555914486087e+00 , 6.4969391999999999e+00 , -5.4215999999999998e-01 , -7.6725800000000000e-01 , -3.4260499999999999e-01 -6.4368113942659821e+00 , 8.0399692065834536e+00 , 7.7445751999999999e+00 , 1.8937200000000001e-01 , 3.6430699999999999e-01 , 9.1182200000000002e-01 -5.5274798350227297e+00 , 6.8010334854814758e+00 , 6.8402016000000003e+00 , -9.6126100000000003e-01 , -1.9899600000000001e-01 , -1.9073100000000001e-01 -5.4835324424192438e+00 , 6.7845164452673528e+00 , 6.9490688000000000e+00 , 3.1323600000000001e-01 , 1.4828100000000000e-01 , 9.3802799999999997e-01 -5.3479091963846734e+00 , 6.6353631297324753e+00 , 6.9387728000000006e+00 , -4.4678899999999999e-01 , 1.6735700000000001e-01 , -8.7884700000000004e-01 -5.2747224002708881e+00 , 6.5755770160829066e+00 , 7.0058840000000000e+00 , -2.0929400000000001e-01 , 3.7638899999999997e-01 , 9.0251199999999998e-01 -5.1961490894563509e+00 , 6.5079182380191387e+00 , 7.0643631999999998e+00 , 2.2831799999999999e-01 , 6.7602899999999999e-01 , 7.0061200000000001e-01 -4.9638207112943693e+00 , 6.2071756863617074e+00 , 6.8871055999999999e+00 , 5.5064900000000006e-01 , 2.5614900000000002e-01 , 7.9446399999999995e-01 -5.0659758176315091e+00 , 6.4111870169528480e+00 , 7.2152360000000000e+00 , -8.7391200000000002e-01 , 4.0567300000000001e-01 , -2.6778299999999999e-01 -5.1925896619207750e+00 , 6.6599602056594556e+00 , 7.6074511999999999e+00 , 6.6644700000000001e-01 , 6.7087900000000000e-01 , 3.2522299999999998e-01 -4.8018786182260937e+00 , 6.1025296045788435e+00 , 7.1342200000000000e+00 , -6.0848500000000005e-01 , -6.2233300000000003e-01 , -4.9238900000000002e-01 -4.7181203484190650e+00 , 6.0208737240289834e+00 , 7.1643071999999997e+00 , 2.4371100000000001e-01 , 5.6541100000000000e-01 , 7.8798199999999996e-01 -4.2458308518817223e+00 , 5.3099434117706696e+00 , 6.4599152000000002e+00 , 3.3441199999999999e-01 , -1.4229800000000001e-01 , 9.3162199999999995e-01 -4.2614780981883502e+00 , 5.3791189448266552e+00 , 6.6432048000000004e+00 , -7.4025799999999997e-01 , -5.7250699999999999e-01 , -3.5249799999999998e-01 -4.4811198880586991e+00 , 5.7934859853829099e+00 , 7.2605176000000000e+00 , -1.4584600000000000e-01 , 6.6212700000000002e-01 , 7.3506300000000002e-01 -4.1637294104594762e+00 , 5.3118283465466334e+00 , 6.7732256000000000e+00 , -1.5357899999999999e-01 , 6.9788300000000003e-01 , 6.9955199999999995e-01 -4.1111214171218817e+00 , 5.2711866230847573e+00 , 6.8290736000000001e+00 , 2.3862300000000000e-01 , 4.4617600000000002e-01 , 8.6254699999999995e-01 -4.0141542137600581e+00 , 5.1520898065622891e+00 , 6.7812024000000006e+00 , 1.3782300000000000e-01 , 7.5190000000000001e-01 , 6.4471000000000001e-01 -3.9453996644534737e+00 , 5.0820600536336329e+00 , 6.7931207999999996e+00 , 3.0273499999999998e-01 , 7.9247599999999996e-01 , 5.2946400000000005e-01 -4.1047106211388193e+00 , 5.4271392643725012e+00 , 7.3962479999999999e+00 , 6.3287400000000005e-01 , -2.3212700000000000e-01 , 7.3863900000000005e-01 -3.9960306221669564e+00 , 5.2881909666287861e+00 , 7.3210559999999996e+00 , -1.9147400000000001e-01 , -9.7633800000000004e-01 , 1.0050700000000000e-01 -3.9164239879498455e+00 , 5.2014448223678276e+00 , 7.3162304000000002e+00 , -1.4404000000000000e-01 , -9.8184199999999999e-01 , 1.2344300000000000e-01 -4.1460431854142321e+00 , 5.7154179581597777e+00 , 8.2456367999999998e+00 , -4.3357000000000001e-01 , 4.8238199999999998e-01 , -7.6113399999999998e-01 -4.0714181590150593e+00 , 5.6494827395569498e+00 , 8.2977096000000010e+00 , -4.3357099999999998e-01 , 4.8238199999999998e-01 , -7.6113399999999998e-01 -3.7838651893231985e+00 , 5.1466867385523756e+00 , 7.6222399999999997e+00 , -8.9802499999999996e-01 , -3.9202500000000001e-01 , -1.9966700000000001e-01 -3.9131187799197775e+00 , 5.4970804078305351e+00 , 8.3613056000000014e+00 , 3.8397500000000001e-01 , -6.5594699999999995e-01 , 6.4984399999999998e-01 -3.7075205916671647e+00 , 5.1442524854311262e+00 , 7.9048392000000005e+00 , 3.1397500000000000e-01 , -8.1934200000000001e-01 , -4.7968600000000000e-01 -3.6354811060977514e+00 , 5.0731005474245316e+00 , 7.9263256000000002e+00 , 7.4672600000000006e-02 , 4.8267400000000004e-03 , 9.9719599999999997e-01 -3.5230086578701130e+00 , 4.9054857855946699e+00 , 7.7660616000000005e+00 , -1.9031999999999999e-01 , -9.2967200000000005e-01 , -3.1541900000000000e-01 -3.4888548624341658e+00 , 4.9197536819119083e+00 , 7.9455239999999998e+00 , 2.2145400000000001e-01 , 9.7503399999999996e-01 , 1.6336199999999999e-02 -3.4048887557894547e+00 , 4.8168750688704733e+00 , 7.8965816000000002e+00 , -2.3129700000000000e-01 , 9.6633999999999998e-01 , -1.1264399999999999e-01 -3.3528087548538492e+00 , 4.7904324786224048e+00 , 8.0019544000000007e+00 , 1.1839600000000000e-01 , -6.9186700000000001e-01 , 7.1225099999999997e-01 -3.2672653554092967e+00 , 4.6737150509415750e+00 , 7.9208344000000004e+00 , -1.2869000000000000e-01 , 4.8968299999999998e-01 , 8.6235099999999998e-01 -3.1895073884028955e+00 , 4.5772733138125119e+00 , 7.8735352000000010e+00 , -9.2653799999999997e-01 , -3.4321900000000000e-01 , 1.5404200000000001e-01 -3.2457919140668503e+00 , 4.8923527339555353e+00 , 8.7590223999999992e+00 , -5.7972699999999999e-01 , -8.0195300000000003e-01 , 1.4417900000000000e-01 -2.9192046039732036e+00 , 3.9777058083181291e+00 , 6.8005151999999995e+00 , 3.8158100000000000e-01 , 2.3289899999999999e-01 , 8.9451300000000000e-01 -2.8703302021931068e+00 , 3.9327273898195019e+00 , 6.8251008000000004e+00 , -3.9848600000000001e-01 , -3.4691699999999998e-01 , -8.4903300000000004e-01 -3.0533045921747792e+00 , 4.8111846488219170e+00 , 9.2004815999999998e+00 , 8.6465999999999998e-01 , 4.9372400000000000e-01 , -9.2735399999999996e-02 -2.9449952873035947e+00 , 4.6082178896086878e+00 , 8.8972800000000003e+00 , 9.7115300000000004e-01 , -2.3668000000000000e-01 , -2.9049599999999998e-02 -2.7025777701192029e+00 , 3.6833932436050496e+00 , 6.5899983999999998e+00 , 8.9692200000000000e-01 , 4.4179299999999999e-01 , 1.8701900000000000e-02 -2.6675985074130422e+00 , 3.7048794301178534e+00 , 6.7945976000000003e+00 , -1.3424400000000000e-01 , 4.5702799999999999e-01 , 8.7926300000000002e-01 -2.6170710638297021e+00 , 3.6332493439678704e+00 , 6.7339551999999996e+00 , -6.2990599999999997e-01 , 7.8437799999999998e-03 , 7.7663199999999999e-01 -2.5757332212421522e+00 , 3.6445859599976638e+00 , 6.9289864000000003e+00 , 1.3695399999999999e-01 , -9.3601199999999996e-01 , -3.2423000000000002e-01 -2.5225405712061995e+00 , 3.5347553111217920e+00 , 6.7466744000000007e+00 , 6.2863799999999997e-02 , -2.8154299999999999e-01 , 9.5748699999999998e-01 -2.4764842031662355e+00 , 3.4743884042656594e+00 , 6.7112832000000004e+00 , 6.9094199999999995e-01 , -4.6182800000000002e-01 , -5.5615999999999999e-01 -2.4314681613375742e+00 , 3.3697276503696543e+00 , 6.5142135999999997e+00 , -3.5042800000000002e-01 , 5.8692000000000000e-01 , 7.2987999999999997e-01 -2.3792938729477440e+00 , 3.4554509787030616e+00 , 7.0076520000000002e+00 , -7.8489200000000003e-01 , -1.4599300000000001e-01 , -6.0218799999999995e-01 -2.3274306835423673e+00 , 3.4315142118930586e+00 , 7.1202215999999998e+00 , 4.9628199999999997e-02 , -5.5710499999999996e-01 , -8.2895799999999997e-01 -2.2712637278287224e+00 , 3.4064715749341623e+00 , 7.2421408000000005e+00 , -5.3408000000000000e-01 , -7.9239999999999999e-01 , -2.9471999999999998e-01 -2.1820293372420498e+00 , 3.5075821174000774e+00 , 7.9304959999999998e+00 , -6.1993799999999999e-01 , -4.9274200000000001e-01 , -6.1064099999999999e-01 -2.1287761689145261e+00 , 3.4245120758793530e+00 , 7.8388512000000006e+00 , 8.3261099999999999e-01 , -5.5223800000000001e-01 , 4.2331100000000003e-02 -2.0571472302862959e+00 , 3.3962078015269586e+00 , 8.0098687999999996e+00 , 4.7589700000000001e-01 , -5.0839100000000004e-01 , 7.1767700000000001e-01 -1.9875469994327424e+00 , 3.3521215809948508e+00 , 8.1187360000000002e+00 , 5.7047300000000001e-01 , -7.3855999999999999e-01 , 3.5929000000000000e-01 -1.9272550918368034e+00 , 3.2827673611170933e+00 , 8.1042488000000006e+00 , 7.2514000000000001e-01 , -6.8859300000000001e-01 , 3.5256100000000002e-03 -1.8573750647421241e+00 , 3.2298168581694791e+00 , 8.1796384000000000e+00 , -6.5558899999999998e-01 , -7.5474600000000003e-01 , -2.3717100000000001e-02 -4.1224728864489162e+00 , 3.5165907108631549e+00 , 9.8447639999999992e-01 , -8.6522600000000005e-02 , 1.3210700000000000e-01 , 9.8745200000000000e-01 -4.1740678697097549e+00 , 3.5679357336754363e+00 , 9.8155711999999995e-01 , -8.6766399999999994e-02 , 1.4105200000000001e-01 , 9.8619299999999999e-01 -4.2203132197579638e+00 , 3.6160421927797879e+00 , 9.8776280000000005e-01 , 1.1509999999999999e-01 , -1.7999899999999999e-01 , -9.7690999999999995e-01 -4.2776764105916740e+00 , 3.6728010987489426e+00 , 9.8130543999999986e-01 , 7.6629299999999997e-02 , -2.1037500000000001e-01 , -9.7461299999999995e-01 -4.3431006123392351e+00 , 3.7356508926013836e+00 , 9.6994135999999997e-01 , -5.6096699999999999e-02 , 1.8756400000000001e-01 , 9.8064899999999999e-01 -4.4071669761916592e+00 , 3.7990743610048767e+00 , 9.6108263999999988e-01 , -1.1296399999999999e-01 , 1.8673300000000001e-01 , 9.7589400000000004e-01 -4.4669076608456546e+00 , 3.8592333779272954e+00 , 9.6147263999999999e-01 , -9.8122000000000001e-02 , 1.7335999999999999e-01 , 9.7995800000000000e-01 -4.5253641988380018e+00 , 3.9198642805894623e+00 , 9.6396240000000000e-01 , -7.0635100000000006e-02 , 1.8354000000000001e-01 , 9.8047099999999998e-01 -4.6050363315453193e+00 , 3.9963411353079170e+00 , 9.4943360000000010e-01 , -3.5455100000000000e-03 , 1.9603200000000001e-01 , 9.8059099999999999e-01 -4.6843212745230289e+00 , 4.0734716979376646e+00 , 9.3814960000000003e-01 , -5.6469400000000003e-02 , 1.8440599999999999e-01 , 9.8122699999999996e-01 -4.7572060464059653e+00 , 4.1474160303877738e+00 , 9.3595519999999999e-01 , -7.5092699999999998e-02 , 1.8962100000000001e-01 , 9.7898200000000002e-01 -4.8368419328807528e+00 , 4.2268461528236276e+00 , 9.3085920000000000e-01 , -7.1577000000000002e-02 , 1.9338500000000000e-01 , 9.7850899999999996e-01 -4.9242520537540084e+00 , 4.3128396068645198e+00 , 9.2307999999999990e-01 , -4.4005799999999998e-02 , 2.2537800000000000e-01 , 9.7327699999999995e-01 -5.0254639750384591e+00 , 4.4114677070931574e+00 , 9.0715759999999990e-01 , -6.3539600000000002e-02 , 1.9387399999999999e-01 , 9.7896700000000003e-01 -5.1201578269977226e+00 , 4.5059730869247687e+00 , 9.0105279999999999e-01 , -6.3185599999999995e-02 , 1.7944099999999999e-01 , 9.8173699999999997e-01 -5.2214523726004369e+00 , 4.6073344860726664e+00 , 8.9344000000000001e-01 , -1.1410800000000000e-01 , 1.6635000000000000e-01 , 9.7944200000000003e-01 -5.3243172778673440e+00 , 4.7095341775592381e+00 , 8.9034079999999993e-01 , 5.5031399999999997e-01 , -2.1008900000000000e-01 , -8.0809500000000001e-01 -5.3775643500638495e+00 , 4.7741919892149074e+00 , 9.2752079999999992e-01 , 9.6092800000000000e-01 , 2.8866400000000000e-02 , -2.7528900000000001e-01 -5.3665139852780843e+00 , 4.7874023483024386e+00 , 1.0117888799999999e+00 , 9.8777300000000001e-01 , 4.2250500000000003e-02 , -1.5006700000000001e-01 -5.3683711047070277e+00 , 4.8097022136057674e+00 , 1.0859741600000001e+00 , 9.9556800000000001e-01 , 8.4894999999999998e-02 , -4.0457899999999998e-02 -5.3622245132800810e+00 , 4.8258379141306964e+00 , 1.1647645600000001e+00 , 9.9084700000000003e-01 , 1.0886600000000000e-01 , -7.9809599999999994e-02 -5.3630585129024091e+00 , 4.8470602378147323e+00 , 1.2386243200000000e+00 , 9.9832900000000002e-01 , 5.4041199999999998e-02 , -2.0457199999999998e-02 -5.3905640482699138e+00 , 4.8911875525119459e+00 , 1.2948612800000001e+00 , 9.9438499999999996e-01 , 9.8917000000000005e-02 , 3.7601599999999999e-02 -5.3456056621313062e+00 , 4.8728526221163353e+00 , 1.3945816799999999e+00 , 9.9607999999999997e-01 , 4.8213499999999999e-02 , -7.4159799999999998e-02 -5.3273987014544870e+00 , 4.8772903158453715e+00 , 1.4759700000000000e+00 , 9.9113300000000004e-01 , 1.2721499999999999e-01 , 3.8360900000000003e-02 -5.3753924213305044e+00 , 4.9385486849883904e+00 , 1.5214627199999999e+00 , -9.5389599999999997e-01 , -2.9608200000000001e-01 , -4.9179899999999999e-02 -5.2970754469087913e+00 , 4.8899364968213401e+00 , 1.6323797600000001e+00 , 9.9786699999999995e-01 , 3.6666100000000000e-02 , -5.4002399999999999e-02 -5.3279850597846643e+00 , 4.9356452202060899e+00 , 1.6866604800000000e+00 , -9.0694699999999995e-01 , 6.4622799999999994e-02 , 4.1625899999999999e-01 -5.3430368376895681e+00 , 4.9687588140959331e+00 , 1.7488348000000000e+00 , -8.0448200000000003e-01 , 7.5828999999999994e-02 , 5.8911700000000000e-01 -5.3794134184956448e+00 , 5.0204252132061766e+00 , 1.8022096800000000e+00 , 6.7817099999999997e-01 , -1.1483100000000000e-01 , -7.2587800000000002e-01 -5.4740286844345025e+00 , 5.1255261868501893e+00 , 1.8328137600000001e+00 , 5.1895899999999995e-01 , -1.4800700000000000e-01 , -8.4188799999999997e-01 -6.4735497010159975e+00 , 6.2110709809837399e+00 , 2.0847565680000000e+00 , -1.7114699999999999e-01 , -4.4563300000000000e-02 , 9.8423700000000003e-01 -1.4981728931244009e+01 , 1.4344700322280511e+01 , 2.7421359999999995e-01 , -7.3366799999999996e-02 , 1.8319500000000000e-01 , 9.8033499999999996e-01 -1.8561214804806767e+01 , 1.7861425962168006e+01 , -1.4789120000000011e-01 , 1.0869900000000000e-01 , -1.8576500000000001e-01 , -9.7656299999999996e-01 -2.8598748957665176e+01 , 2.8011297836068728e+01 , -3.0492080000000010e-01 , 7.5936199999999998e-01 , 6.1010699999999995e-01 , -2.2613900000000001e-01 -2.8777994881593681e+01 , 2.8361946124179507e+01 , 2.9814399999999996e-01 , 7.5936199999999998e-01 , 6.1010699999999995e-01 , -2.2613900000000001e-01 -2.8742527404533238e+01 , 2.8502362809309755e+01 , 9.2987120000000001e-01 , 6.8437300000000001e-01 , 7.0526000000000000e-01 , -1.8504399999999999e-01 -2.8684295916435023e+01 , 2.8620019294935776e+01 , 1.5642743200000000e+00 , 6.3514700000000002e-01 , 7.5971599999999995e-01 , -1.3935400000000001e-01 -2.8624901908950953e+01 , 2.8737652356695570e+01 , 2.1989613600000002e+00 , 6.2764200000000003e-01 , 7.6587200000000000e-01 , -1.3965900000000001e-01 -2.8601757866502275e+01 , 2.8892133686839806e+01 , 2.8343753600000001e+00 , 6.1842200000000003e-01 , 7.7345799999999998e-01 , -1.3898600000000000e-01 -2.8548406440609384e+01 , 2.9015554595843081e+01 , 3.4725359999999998e+00 , 6.0533499999999996e-01 , 7.8156000000000003e-01 , -1.5077499999999999e-01 -2.8493809848889018e+01 , 2.9139359788676501e+01 , 4.1123855999999996e+00 , 5.9442099999999998e-01 , 7.8964299999999998e-01 , -1.5207499999999999e-01 -2.8466449622715373e+01 , 2.9291606957949785e+01 , 4.7565407999999998e+00 , 5.8547199999999999e-01 , 7.9677799999999999e-01 , -1.4955800000000000e-01 -2.8410019727489214e+01 , 2.9414509945565076e+01 , 5.4021416000000002e+00 , 5.7481599999999999e-01 , 8.0529499999999998e-01 , -1.4521200000000001e-01 -2.8358548397526231e+01 , 2.9544360537553882e+01 , 6.0514967999999998e+00 , 5.6267699999999998e-01 , 8.1365200000000004e-01 , -1.4616899999999999e-01 -2.8306608756163580e+01 , 2.9673903967642470e+01 , 6.7044816000000003e+00 , 5.5555299999999996e-01 , 8.1808899999999996e-01 , -1.4863299999999999e-01 -2.8266787314436577e+01 , 2.9818001015755133e+01 , 7.3638104000000002e+00 , 5.4585499999999998e-01 , 8.2376000000000005e-01 , -1.5317500000000001e-01 -2.8217952273220902e+01 , 2.9953691771923204e+01 , 8.0267999999999997e+00 , 5.4280700000000004e-01 , 8.2685699999999995e-01 , -1.4720300000000000e-01 -2.8166447851496255e+01 , 3.0088416956914021e+01 , 8.6947191999999998e+00 , 5.3096299999999996e-01 , 8.3410300000000004e-01 , -1.4950200000000000e-01 -2.8092425976930741e+01 , 3.0199689115542348e+01 , 9.3628879999999999e+00 , 5.2011900000000000e-01 , 8.3959700000000004e-01 , -1.5669600000000000e-01 -2.8065403131546404e+01 , 3.0363359005953917e+01 , 1.0048736800000000e+01 , 5.1004899999999997e-01 , 8.4537099999999998e-01 , -1.5873699999999999e-01 -2.8027142193697845e+01 , 3.0519126714529698e+01 , 1.0739535999999999e+01 , 5.0024700000000000e-01 , 8.5119699999999998e-01 , -1.5879699999999999e-01 -2.7966366565264266e+01 , 3.0650380804281230e+01 , 1.1431198400000000e+01 , 4.8316799999999999e-01 , 8.6065300000000000e-01 , -1.6070100000000001e-01 -2.7902617156677344e+01 , 3.0780077041793419e+01 , 1.2129402400000000e+01 , 4.6544900000000000e-01 , 8.7144200000000005e-01 , -1.5474800000000000e-01 -2.7875873850634846e+01 , 3.0953884545422916e+01 , 1.2849591999999999e+01 , 7.4115500000000001e-01 , 6.6546600000000000e-01 , -8.8567000000000007e-02 -2.7811212568934376e+01 , 3.1089126160057063e+01 , 1.3565112000000001e+01 , 7.9665900000000001e-01 , 5.8719800000000000e-01 , -1.4329500000000001e-01 -5.8005959078049933e+00 , 6.6822192995641654e+00 , 6.2138408000000007e+00 , -4.2619800000000002e-01 , -5.3171500000000005e-01 , -7.3187000000000002e-01 -5.6982079210194190e+00 , 6.5903351818397349e+00 , 6.2577392000000005e+00 , -1.3301400000000000e-02 , 7.0954700000000004e-01 , 7.0453299999999996e-01 -5.6516397966365712e+00 , 6.5690528949225904e+00 , 6.3529615999999995e+00 , -2.4909999999999999e-01 , -8.9946899999999996e-01 , -3.5903200000000002e-01 -5.6873976669016741e+00 , 6.6577978782968872e+00 , 6.5375720000000008e+00 , 7.2221000000000002e-01 , 3.7143900000000002e-01 , 5.8347800000000005e-01 -5.5685345713566861e+00 , 6.5428578791222600e+00 , 6.5583200000000001e+00 , 7.4860700000000002e-01 , 2.0325699999999999e-01 , 6.3109000000000004e-01 -5.5076057390186399e+00 , 6.5034794417596338e+00 , 6.6397624000000004e+00 , 5.3753600000000001e-01 , 1.4612900000000001e-01 , 8.3048299999999997e-01 -5.4606585514375547e+00 , 6.4828631216072310e+00 , 6.7382192000000005e+00 , 8.0965399999999998e-01 , -1.5598500000000001e-01 , 5.6579999999999997e-01 -5.3578770715114787e+00 , 6.3870048095709473e+00 , 6.7675055999999998e+00 , -6.6935000000000000e-01 , 3.9388299999999998e-01 , -6.2994200000000000e-01 -5.3285522092099544e+00 , 6.3914278246281961e+00 , 6.8886343999999999e+00 , -8.2222700000000004e-01 , -7.9036099999999995e-04 , -5.6916000000000000e-01 -5.1465965085184955e+00 , 6.1821912054768626e+00 , 6.8021063999999996e+00 , -2.1837899999999999e-01 , 7.8914600000000001e-01 , 5.7407300000000006e-01 -5.0745981029712004e+00 , 6.1258082246694672e+00 , 6.8599928000000006e+00 , 2.5864599999999999e-01 , 6.0993200000000003e-01 , 7.4905600000000006e-01 -5.0254823745296431e+00 , 6.1014415240381705e+00 , 6.9498904000000001e+00 , -1.4544799999999999e-01 , -8.7289499999999998e-01 , -4.6572400000000003e-01 -4.9572677781295678e+00 , 6.0488498436537723e+00 , 7.0116144000000000e+00 , -1.6009000000000001e-01 , -9.6140499999999995e-01 , -2.2376599999999999e-01 -5.0010240058785760e+00 , 6.1606938989081170e+00 , 7.2546208000000005e+00 , -8.2884100000000005e-01 , -3.5709099999999999e-01 , 4.3070799999999998e-01 -4.9296717231006975e+00 , 6.1060442337923480e+00 , 7.3159704000000003e+00 , 6.0749200000000003e-01 , 7.4121300000000001e-01 , -2.8558200000000000e-01 -4.3552465490925432e+00 , 5.2877987359421610e+00 , 6.4787808000000000e+00 , -7.4025799999999997e-01 , -5.7250699999999999e-01 , -3.5249700000000000e-01 -4.2687741891059874e+00 , 5.1972838587935088e+00 , 6.4695352000000002e+00 , 3.3441199999999999e-01 , -1.4229800000000001e-01 , 9.3162199999999995e-01 -4.6466480747024193e+00 , 5.8321761875850404e+00 , 7.3614080000000000e+00 , 3.1629200000000002e-01 , 8.9305899999999994e-02 , 9.4444899999999998e-01 -4.9107970152041087e+00 , 6.3042191117083402e+00 , 8.0953048000000010e+00 , -1.8825700000000001e-01 , 6.5911900000000001e-01 , 7.2809400000000002e-01 -4.1815685788273651e+00 , 5.1940911366801590e+00 , 6.7723832000000002e+00 , 4.9203799999999998e-01 , -5.9500100000000000e-01 , -6.3551000000000002e-01 -4.1126946948540830e+00 , 5.1315077063041015e+00 , 6.7949304000000001e+00 , -9.3142900000000001e-02 , 4.1345199999999999e-01 , 9.0574900000000003e-01 -4.0627104607155946e+00 , 5.0960350811451312e+00 , 6.8559160000000006e+00 , -6.7548100000000000e-02 , 2.5148599999999999e-01 , 9.6550100000000005e-01 -4.1199864908416357e+00 , 5.2465609677646787e+00 , 7.1830584000000002e+00 , -9.7543199999999997e-01 , -6.2575399999999998e-03 , -2.2021199999999999e-01 -4.3856434853877850e+00 , 5.7652925609257544e+00 , 8.0752224000000012e+00 , 4.2116399999999998e-01 , -6.9331900000000002e-01 , 5.8474700000000002e-01 -4.4116679307833788e+00 , 5.8847267522323135e+00 , 8.4047879999999999e+00 , 1.4045800000000000e-01 , -8.5189199999999998e-01 , 5.0453099999999995e-01 -4.4470818897677376e+00 , 6.0287729535048715e+00 , 8.7900248000000012e+00 , -3.5246400000000000e-01 , 8.1823599999999996e-01 , -4.5415800000000001e-01 -4.1267373823025295e+00 , 5.5183959646029876e+00 , 8.1332127999999990e+00 , 4.7923399999999999e-01 , -4.2975900000000000e-01 , 7.6527299999999998e-01 -3.8789456518554664e+00 , 5.1272072168865304e+00 , 7.6302064000000005e+00 , -7.7348899999999998e-01 , -1.2661200000000000e-01 , -6.2103500000000000e-01 -3.8824107467730027e+00 , 5.2071670990621097e+00 , 7.9065760000000003e+00 , -3.6995899999999998e-01 , -8.8296900000000000e-01 , -2.8895500000000002e-01 -3.8273915490322512e+00 , 5.1776349959882664e+00 , 8.0012264000000002e+00 , -2.2548000000000001e-01 , 7.1917900000000007e-02 , 9.7158999999999995e-01 -3.7391871495542137e+00 , 5.0825774650777760e+00 , 7.9796776000000005e+00 , -4.9051600000000001e-02 , -8.4966700000000006e-02 , 9.9517599999999995e-01 -3.6203340482240143e+00 , 4.9175955447062600e+00 , 7.8205784000000005e+00 , -4.7988799999999998e-01 , -2.7781099999999997e-01 , 8.3218300000000001e-01 -3.5404249368799467e+00 , 4.8310852079678028e+00 , 7.8010159999999997e+00 , -3.1776199999999999e-01 , -8.2457400000000003e-01 , -4.6808600000000000e-01 -3.5084530073443987e+00 , 4.8541678828252346e+00 , 7.9983664000000001e+00 , 1.9168299999999999e-01 , 9.7317399999999998e-01 , 1.2724199999999999e-01 -3.5225492346760241e+00 , 4.9926087715550276e+00 , 8.4460760000000015e+00 , -9.3904399999999999e-01 , -3.4039999999999998e-01 , 4.8214600000000003e-02 -3.2942386789824654e+00 , 4.5400232887502678e+00 , 7.6530551999999998e+00 , 8.2827799999999996e-01 , 5.4624700000000004e-01 , -1.2477800000000000e-01 -3.2406701693325459e+00 , 4.5079413662822088e+00 , 7.7353608000000005e+00 , 8.8719099999999995e-01 , 4.6089999999999998e-01 , 2.1522500000000000e-02 -3.3190347790757655e+00 , 4.8530810253865679e+00 , 8.6851200000000013e+00 , -5.0322100000000003e-01 , -7.6414499999999996e-01 , -4.0354800000000002e-01 -2.9721378412413033e+00 , 3.9733463196142687e+00 , 6.7954607999999999e+00 , 2.6585999999999999e-01 , 2.2008600000000000e-01 , 9.3855200000000005e-01 -2.9211863510760003e+00 , 3.9255274269861968e+00 , 6.8107696000000004e+00 , -3.6709500000000000e-01 , -3.0143399999999998e-01 , -8.7998799999999999e-01 -2.8753768116746983e+00 , 3.8964721044390185e+00 , 6.8728472000000007e+00 , -4.7410700000000000e-01 , -3.4863400000000000e-01 , -8.0850299999999997e-01 -3.0693342280808196e+00 , 4.7985379539525130e+00 , 9.3940880000000000e+00 , 6.8274599999999996e-01 , 6.4935600000000004e-01 , -3.3495500000000000e-01 -2.7422087842515479e+00 , 3.6668399468082828e+00 , 6.5373744000000009e+00 , -8.2405300000000004e-01 , -5.6088199999999999e-01 , -7.9679700000000006e-02 -2.7112664298101414e+00 , 3.7014432114401634e+00 , 6.7710623999999999e+00 , -8.1351499999999999e-01 , -5.6953799999999999e-01 , 1.1755599999999999e-01 -2.6676712182196476e+00 , 3.6836180637333285e+00 , 6.8682711999999997e+00 , -2.8064800000000001e-01 , -9.1206200000000004e-01 , -2.9896400000000001e-01 -2.6209629208259257e+00 , 3.6636868604585322e+00 , 6.9649080000000003e+00 , -6.9648299999999996e-02 , 9.1302099999999997e-01 , 4.0192299999999997e-01 -2.5659540736910520e+00 , 3.5765362803048553e+00 , 6.8526296000000002e+00 , -7.9021500000000000e-01 , 1.0305300000000001e-01 , 6.0410399999999997e-01 -2.5143060803864272e+00 , 3.4950331721765453e+00 , 6.7480367999999995e+00 , -3.3919300000000002e-01 , 4.0603000000000000e-01 , -8.4858000000000000e-01 -2.4675808779869897e+00 , 3.4815927947677223e+00 , 6.8716512000000005e+00 , -9.0377200000000002e-01 , 3.9883700000000000e-01 , -1.5532399999999999e-01 -2.4180643585186887e+00 , 3.4568371155775290e+00 , 6.9647936000000001e+00 , -3.1988000000000000e-01 , 9.2425400000000002e-01 , -2.0840300000000000e-01 -2.3670250812872520e+00 , 3.4196225631415405e+00 , 7.0169183999999998e+00 , -6.7961400000000005e-01 , -7.0130800000000004e-01 , -2.1515799999999999e-01 -2.3105623744289239e+00 , 3.4059379742680336e+00 , 7.1688416000000004e+00 , 3.1570599999999999e-01 , 8.0105499999999996e-01 , 5.0856699999999999e-01 -2.2237563001198750e+00 , 3.5265672233221994e+00 , 7.9177040000000005e+00 , 4.7285100000000002e-01 , 6.4593400000000001e-01 , 5.9931800000000002e-01 -2.1561716921180918e+00 , 3.4862109967779986e+00 , 8.0191976000000000e+00 , -1.6109700000000001e-02 , -6.1453100000000005e-01 , 7.8872799999999998e-01 -2.0984218365415073e+00 , 3.4103260244277234e+00 , 7.9569744000000000e+00 , 3.5012599999999999e-01 , -6.6443100000000005e-02 , 9.3434300000000003e-01 -2.0353038488079478e+00 , 3.3527931897621879e+00 , 7.9847216000000003e+00 , 5.8208199999999999e-01 , -4.2844100000000002e-01 , 6.9110000000000005e-01 -1.9689336988347399e+00 , 3.2991746760121381e+00 , 8.0311576000000002e+00 , -6.5334400000000004e-01 , 5.1004600000000000e-01 , -5.5945900000000004e-01 -1.9040422737858487e+00 , 3.2400726340708772e+00 , 8.0560240000000007e+00 , -6.4949999999999997e-01 , 6.5871500000000005e-01 , -3.7979499999999999e-01 -4.1937236605130117e+00 , 3.5020655584705365e+00 , 9.9085160000000005e-01 , -1.1531300000000000e-01 , 1.0280499999999999e-01 , 9.8799499999999996e-01 -4.2461640317757059e+00 , 3.5515434761567155e+00 , 9.8937896000000003e-01 , 1.2344700000000000e-01 , -1.6077900000000001e-01 , -9.7924000000000000e-01 -4.2932825171438518e+00 , 3.5987976107259980e+00 , 9.9682535999999988e-01 , -8.7579799999999999e-02 , 1.8708900000000001e-01 , 9.7843100000000005e-01 -4.3597875752177107e+00 , 3.6593515738177116e+00 , 9.8478320000000008e-01 , -4.4019599999999999e-02 , 2.1387100000000001e-01 , 9.7587000000000002e-01 -4.4198196051708942e+00 , 3.7157176661486515e+00 , 9.8224767999999996e-01 , -9.4169100000000006e-02 , 1.8978200000000001e-01 , 9.7729999999999995e-01 -4.4745422146990830e+00 , 3.7698508295620847e+00 , 9.8852928000000007e-01 , -8.7628700000000004e-02 , 2.1119599999999999e-01 , 9.7350800000000004e-01 -4.5484248208441862e+00 , 3.8365693662397384e+00 , 9.7704560000000007e-01 , -8.4174100000000002e-02 , 1.7659800000000000e-01 , 9.8067700000000002e-01 -4.6159208848142130e+00 , 3.9011337532833252e+00 , 9.7465775999999993e-01 , -3.9409600000000003e-02 , 1.9613600000000000e-01 , 9.7978399999999999e-01 -4.6974088470728130e+00 , 3.9758245555051590e+00 , 9.6220895999999989e-01 , -5.4192499999999998e-02 , 2.0162600000000000e-01 , 9.7796200000000000e-01 -4.7724115223572872e+00 , 4.0463356134975879e+00 , 9.5927200000000012e-01 , -8.4829299999999996e-02 , 1.9871800000000001e-01 , 9.7637900000000000e-01 -4.8542443677426359e+00 , 4.1233035239796685e+00 , 9.5290719999999984e-01 , -8.4619600000000003e-02 , 1.9205200000000000e-01 , 9.7772999999999999e-01 -4.9367179716218699e+00 , 4.2009318988381654e+00 , 9.5001599999999997e-01 , -6.4192600000000002e-02 , 2.0237200000000000e-01 , 9.7720200000000002e-01 -5.0330466817609700e+00 , 4.2910889987510243e+00 , 9.3847199999999997e-01 , -4.2142499999999999e-02 , 2.1508900000000000e-01 , 9.7568500000000002e-01 -5.1298960478897078e+00 , 4.3810332951384083e+00 , 9.3121279999999995e-01 , -5.3522100000000003e-02 , 2.0943300000000001e-01 , 9.7635700000000003e-01 -5.2344491171851235e+00 , 4.4787787855728425e+00 , 9.2217519999999986e-01 , -9.0905600000000003e-02 , 1.6496700000000000e-01 , 9.8210100000000000e-01 -5.3395200802143403e+00 , 4.5773720649435630e+00 , 9.1750560000000014e-01 , 4.5270300000000002e-01 , -1.9729099999999999e-01 , -8.6956100000000003e-01 -5.4090371312800452e+00 , 4.6506549496352028e+00 , 9.4295440000000008e-01 , -9.4109399999999999e-01 , 2.7427500000000000e-02 , 3.3703100000000003e-01 -5.3910758724692061e+00 , 4.6586442525140548e+00 , 1.0314448800000000e+00 , 9.8265100000000005e-01 , -2.3304999999999999e-02 , -1.8399399999999999e-01 -5.4300842451396605e+00 , 4.7092630251724561e+00 , 1.0802146399999999e+00 , 9.9624000000000001e-01 , 6.0455399999999999e-02 , -6.2060900000000002e-02 -5.4030465843938567e+00 , 4.7078994913097096e+00 , 1.1730897599999999e+00 , 9.9758999999999998e-01 , 6.7347500000000005e-02 , -1.6702399999999999e-02 -5.3969971080666381e+00 , 4.7227708836374784e+00 , 1.2508713600000001e+00 , 9.9843199999999999e-01 , 7.8236099999999999e-03 , 5.5432700000000001e-02 -5.3888924313872320e+00 , 4.7365783632656475e+00 , 1.3282015999999999e+00 , 9.9376200000000003e-01 , -1.3318600000000000e-02 , 1.1072400000000000e-01 -5.3728381839081942e+00 , 4.7430123275895930e+00 , 1.4094308000000000e+00 , 9.9995400000000001e-01 , -5.7464100000000004e-03 , -7.6683599999999999e-03 -5.3627181219183706e+00 , 4.7545648632161175e+00 , 1.4857054399999998e+00 , 9.9954100000000001e-01 , 2.6763200000000001e-02 , 1.4228200000000000e-02 -5.4266172205926306e+00 , 4.8250429233129815e+00 , 1.5224039199999999e+00 , 9.9350300000000002e-01 , 7.1896299999999996e-02 , 8.8221400000000005e-02 -5.3394443212385667e+00 , 4.7732666636940584e+00 , 1.6367779200000001e+00 , 9.9522800000000000e-01 , 5.6964700000000000e-02 , 7.9218499999999997e-02 -5.3567816101606702e+00 , 4.8059415740644251e+00 , 1.6972820000000000e+00 , -8.7161599999999995e-01 , 1.0266000000000001e-02 , 4.9008099999999999e-01 -5.3651105257568368e+00 , 4.8313360734284991e+00 , 1.7618618399999999e+00 , -8.7221199999999999e-01 , 3.2057800000000002e-04 , 4.8912800000000001e-01 -5.4105598126375174e+00 , 4.8890755991802530e+00 , 1.8104537599999999e+00 , -7.3298600000000003e-01 , 3.3780100000000000e-02 , 6.7940500000000004e-01 -5.4781394068761475e+00 , 4.9646398459745011e+00 , 1.8520943200000000e+00 , 4.5893800000000001e-01 , -1.1435300000000000e-01 , -8.8107899999999995e-01 -5.5979472075051557e+00 , 5.0864884410342723e+00 , 1.8763284000000000e+00 , -3.1832100000000002e-01 , 1.2175999999999999e-01 , 9.4013100000000005e-01 -6.5565575806403817e+00 , 6.0561499954740174e+00 , 2.0766179440000001e+00 , -1.7114699999999999e-01 , -4.4563199999999997e-02 , 9.8423700000000003e-01 -1.4794385616325693e+01 , 1.3462354377060624e+01 , 3.4511040000000004e-01 , -6.9375400000000004e-02 , 1.8081300000000000e-01 , 9.8106800000000005e-01 -2.1928068317945637e+01 , 2.0218525557818648e+01 , 1.0583759999999987e-01 , -1.2751799999999999e-01 , 2.0488300000000001e-01 , 9.7044399999999997e-01 -2.9319882174780446e+01 , 2.7147155577277399e+01 , -4.0348160000000011e-01 , -9.2764200000000005e-02 , -7.5216499999999997e-01 , 6.5241400000000005e-01 -3.1077444797952015e+01 , 2.8945961729874803e+01 , 3.0375199999999936e-02 , 1.0014900000000000e-01 , -9.2331099999999999e-01 , 3.7076700000000001e-01 -3.1021428079625540e+01 , 2.9074678695547291e+01 , 6.9920959999999988e-01 , -6.1239500000000002e-02 , 9.7479099999999996e-01 , -2.1455299999999999e-01 -3.0979430373783401e+01 , 2.9216424518766168e+01 , 1.3674241600000001e+00 , -6.4996499999999999e-02 , 9.7599400000000003e-01 , -2.0787200000000000e-01 -3.0928723468096951e+01 , 2.9350356331102542e+01 , 2.0371835360000001e+00 , -6.7886100000000005e-02 , 9.7575000000000001e-01 , -2.0809700000000000e-01 -3.0876674994170610e+01 , 2.9482530580735133e+01 , 2.7084417599999999e+00 , -6.6220399999999999e-02 , 9.7583399999999998e-01 , -2.0823700000000001e-01 -3.0814976554216866e+01 , 2.9607867384377457e+01 , 3.3808183999999999e+00 , 6.4858499999999999e-02 , -9.7592800000000002e-01 , 2.0822299999999999e-01 -3.0767889407809541e+01 , 2.9745928645921797e+01 , 4.0557264000000002e+00 , 4.9810199999999999e-02 , -9.7572800000000004e-01 , 2.1324499999999999e-01 -3.0719437269296090e+01 , 2.9883394864148215e+01 , 4.7331407999999993e+00 , -6.4100299999999999e-02 , 9.7455400000000003e-01 , -2.1479100000000001e-01 -3.0683308565394398e+01 , 3.0034925727388629e+01 , 5.4145488000000004e+00 , -6.3434099999999993e-02 , 9.7446800000000000e-01 , -2.1537999999999999e-01 -3.0653035107462337e+01 , 3.0193692076420263e+01 , 6.1007512000000004e+00 , -6.5083100000000005e-02 , 9.7477100000000005e-01 , -2.1350800000000000e-01 -3.0599022454728193e+01 , 3.0328227163533704e+01 , 6.7890128000000001e+00 , 3.1637100000000001e-02 , -9.7710399999999997e-01 , 2.1039600000000000e-01 -3.0549804455501921e+01 , 3.0469994974182537e+01 , 7.4821312000000004e+00 , -3.8925500000000002e-02 , 9.7700799999999999e-01 , -2.0961800000000000e-01 -3.0483209379807835e+01 , 3.0595930909218168e+01 , 8.1772360000000006e+00 , -4.0276399999999997e-02 , 9.7561200000000003e-01 , -2.1577600000000000e-01 -3.0458884808002004e+01 , 3.0765135183036715e+01 , 8.8854655999999999e+00 , 6.9102300000000005e-02 , -9.7450099999999995e-01 , 2.1348000000000000e-01 -3.0394172590493675e+01 , 3.0896440208596111e+01 , 9.5918543999999990e+00 , 3.3025400000000003e-02 , -9.7814100000000004e-01 , 2.0530599999999999e-01 -3.0377484195919124e+01 , 3.1078228397119254e+01 , 1.0316370400000000e+01 , 4.4617600000000004e-03 , -9.7801700000000003e-01 , 2.0847700000000000e-01 -3.0308128806506957e+01 , 3.1206788246059293e+01 , 1.1034750400000000e+01 , 1.8375100000000001e-03 , -9.7732200000000002e-01 , 2.1175300000000000e-01 -3.0242164517531560e+01 , 3.1341129036603235e+01 , 1.1761003199999999e+01 , 1.7485100000000000e-02 , -9.7726199999999996e-01 , 2.1131300000000000e-01 -3.0186649036441324e+01 , 3.1488836120791230e+01 , 1.2498176000000001e+01 , 3.3831000000000000e-02 , -9.7799100000000005e-01 , 2.0588899999999999e-01 -3.0141397789870538e+01 , 3.1650296544709260e+01 , 1.3247703999999999e+01 , -3.3830899999999997e-02 , 9.7799100000000005e-01 , -2.0588899999999999e-01 -5.8334678502952571e+00 , 6.5383264698605386e+00 , 6.3868344000000006e+00 , -6.4960300000000004e-01 , -5.7961200000000002e-01 , -4.9200199999999999e-01 -5.7332084180305740e+00 , 6.4561483034635980e+00 , 6.4318663999999997e+00 , -5.5678399999999995e-01 , -6.1497599999999997e-01 , -5.5838699999999997e-01 -5.6997106564581568e+00 , 6.4534646308089121e+00 , 6.5431775999999999e+00 , 4.9650899999999998e-01 , 3.1059999999999999e-01 , 8.1055900000000003e-01 -5.5999929671935611e+00 , 6.3692421417853158e+00 , 6.5834464000000006e+00 , -5.8938800000000002e-01 , 5.6305599999999997e-02 , -8.0588599999999999e-01 -5.5486286424079463e+00 , 6.3452367154563012e+00 , 6.6747167999999997e+00 , 6.0679399999999994e-01 , -1.3491100000000000e-01 , 7.8332599999999997e-01 -5.4382375027484828e+00 , 6.2461910628072062e+00 , 6.6971287999999998e+00 , -6.8065900000000001e-01 , 4.1884500000000002e-01 , -6.0105900000000001e-01 -5.4612368458149341e+00 , 6.3172071199500230e+00 , 6.8805848000000003e+00 , -6.0036199999999995e-01 , 7.8767299999999996e-01 , 1.3833400000000001e-01 -5.5182519377374533e+00 , 6.4371401457413651e+00 , 7.1190880000000005e+00 , -7.2043299999999999e-01 , -2.1094299999999999e-01 , 6.6066599999999998e-01 -5.2905844813431582e+00 , 6.1808814926212179e+00 , 6.9791663999999995e+00 , 2.4500200000000000e-01 , -8.2247199999999998e-01 , -5.1333600000000001e-01 -5.2244010592003338e+00 , 6.1377956276998216e+00 , 7.0515712000000006e+00 , 2.0815600000000001e-01 , -8.9047600000000005e-01 , -4.0462900000000002e-01 -5.1156257513404597e+00 , 6.0370082731946590e+00 , 7.0604215999999997e+00 , -9.9244799999999994e-02 , 9.1438799999999998e-01 , 3.9248499999999997e-01 -5.0408454368601525e+00 , 5.9790108306539187e+00 , 7.1150007999999998e+00 , -4.1403400000000001e-01 , -9.0729899999999997e-01 , -7.3381799999999997e-02 -5.2773418079700649e+00 , 6.3576591635062405e+00 , 7.6745416000000004e+00 , 5.1264699999999996e-01 , 3.6141299999999998e-01 , -7.7882799999999996e-01 -5.0692472599284635e+00 , 6.1183354176458646e+00 , 7.5227328000000000e+00 , 6.9119600000000003e-01 , -7.1212600000000004e-01 , 1.2297800000000000e-01 -4.8596715342121879e+00 , 5.8689912662340129e+00 , 7.3471599999999997e+00 , -3.1135299999999999e-01 , 8.8844999999999996e-01 , 3.3721899999999999e-01 -4.7781547229726122e+00 , 5.8030279002758425e+00 , 7.3870960000000006e+00 , 1.2491500000000000e-01 , 5.1595199999999997e-01 , 8.4745999999999999e-01 -5.6406935254362320e+00 , 7.1351235315194810e+00 , 9.2498712000000012e+00 , 4.9945600000000001e-01 , -3.5831000000000002e-01 , 7.8876999999999997e-01 -4.9307484523195022e+00 , 6.1421400602118856e+00 , 8.0961783999999994e+00 , -4.6605799999999997e-01 , 8.4604999999999997e-01 , -2.5882300000000003e-01 -4.7518398307998417e+00 , 5.9313775867422116e+00 , 7.9500272000000010e+00 , -5.9356900000000001e-01 , 6.5634199999999998e-01 , -4.6571600000000002e-01 -4.1611119842229378e+00 , 5.0724217515011834e+00 , 6.8703615999999998e+00 , -4.1339999999999999e-01 , 3.6013400000000001e-01 , 8.3630400000000005e-01 -4.1014340079910045e+00 , 5.0265585574922520e+00 , 6.9145928000000003e+00 , -4.7409400000000002e-01 , 2.4289500000000000e-01 , 8.4630799999999995e-01 -4.4512339869470861e+00 , 5.6452546149243368e+00 , 7.9572343999999999e+00 , -4.6145599999999998e-01 , 4.9036500000000000e-01 , -7.3932399999999998e-01 -5.0121209050331066e+00 , 6.6394326133354689e+00 , 9.6384152000000007e+00 , -6.8337599999999998e-01 , 3.4822300000000000e-01 , -6.4166800000000002e-01 -4.2834766952460832e+00 , 5.4992014465839532e+00 , 8.0133736000000013e+00 , -4.4697100000000001e-01 , 4.1951800000000000e-01 , -7.9007799999999995e-01 -4.2386430134224193e+00 , 5.4932860550217235e+00 , 8.1483863999999997e+00 , -4.7923399999999999e-01 , 4.2975900000000000e-01 , -7.6527299999999998e-01 -4.1363818415176459e+00 , 5.3879510084823004e+00 , 8.1202439999999996e+00 , 1.7087800000000000e-01 , -7.2625499999999998e-01 , 6.6584900000000002e-01 -3.8736068864135644e+00 , 4.9890134941131850e+00 , 7.5755960000000009e+00 , -6.5480700000000003e-01 , 2.0756200000000000e-01 , -7.2673600000000005e-01 -3.8243938771053028e+00 , 4.9698903895716899e+00 , 7.6757271999999999e+00 , -9.0193400000000001e-01 , 4.8192600000000002e-02 , -4.2917600000000000e-01 -3.8416389008354019e+00 , 5.0779308632681168e+00 , 8.0153704000000001e+00 , -2.8143600000000002e-01 , -1.4497500000000000e-02 , 9.5947099999999996e-01 -3.7185707868944862e+00 , 4.9204457869186866e+00 , 7.8662032000000002e+00 , 4.8151600000000000e-01 , -6.2206999999999998e-02 , -8.7422699999999998e-01 -3.6641202861134454e+00 , 4.8949658398250619e+00 , 7.9653152000000000e+00 , -2.0082100000000000e-01 , -8.3406400000000003e-01 , -5.1381800000000000e-01 -3.6150440079946877e+00 , 4.8820781936004671e+00 , 8.0911135999999999e+00 , 5.4304600000000003e-01 , 7.8284900000000002e-01 , 3.0372600000000000e-01 -3.5953942588359773e+00 , 4.9408515451121851e+00 , 8.3734111999999996e+00 , 5.6005400000000005e-01 , 8.2668100000000000e-01 , -5.4196800000000003e-02 -3.5418446151720433e+00 , 4.9289353425448521e+00 , 8.5189072000000010e+00 , -4.1850799999999999e-01 , -7.8154100000000004e-01 , -4.6265000000000001e-01 -3.3051673561276083e+00 , 4.4772112222877052e+00 , 7.6914728000000006e+00 , 8.8719099999999995e-01 , 4.6089900000000000e-01 , 2.1523000000000000e-02 -3.2909172864734391e+00 , 4.5521156725136525e+00 , 8.0180120000000006e+00 , 6.0466600000000004e-01 , -6.4395199999999997e-01 , 4.6872799999999998e-01 -3.4809306854238482e+00 , 5.1986523967913936e+00 , 9.7234248000000001e+00 , 6.9057100000000005e-01 , -6.6592799999999996e-01 , 2.8222799999999998e-01 -2.9740023862084812e+00 , 3.9191810482955960e+00 , 6.8063392000000000e+00 , 3.3417400000000003e-01 , 2.5457999999999997e-01 , 9.0747800000000001e-01 -2.9241494417103748e+00 , 3.8802862915683889e+00 , 6.8398168000000004e+00 , -4.5140100000000000e-01 , -3.1992799999999999e-01 , -8.3299599999999996e-01 -3.1389620849538975e+00 , 4.7454812724514781e+00 , 9.2615607999999998e+00 , 2.6714100000000002e-01 , 2.0631500000000000e-01 , 9.4131299999999996e-01 -2.9874850326076610e+00 , 4.4224278679390743e+00 , 8.6060592000000007e+00 , -8.7661900000000004e-01 , -3.3558900000000003e-01 , 3.4484599999999999e-01 -2.8885699591253839e+00 , 4.2587073666158872e+00 , 8.3520912000000003e+00 , 8.1007799999999996e-01 , 4.2376100000000000e-01 , -4.0521699999999999e-01 -2.7168721979195563e+00 , 3.7054022222733218e+00 , 6.9236616000000000e+00 , -2.4851300000000001e-01 , -9.6406899999999995e-01 , -9.3868400000000005e-02 -2.6752901947035834e+00 , 3.7251255060634314e+00 , 7.1391704000000002e+00 , 9.3834799999999996e-01 , 2.7938800000000003e-01 , -2.0358200000000001e-01 -2.6023223712224119e+00 , 3.5409318270399046e+00 , 6.7206016000000002e+00 , -1.1547900000000000e-02 , -3.0362100000000000e-02 , 9.9947200000000003e-01 -2.5628166026363797e+00 , 3.5908413092101981e+00 , 7.0441872000000005e+00 , -8.5750099999999996e-01 , 2.9360799999999998e-01 , 4.2247600000000002e-01 -2.5043908698966866e+00 , 3.4471178067366521e+00 , 6.7189168000000006e+00 , 8.7961100000000003e-01 , 7.7601900000000001e-02 , -4.6932000000000001e-01 -2.4561215796514739e+00 , 3.4223602768508612e+00 , 6.8018255999999999e+00 , -4.9953999999999998e-01 , 6.9563600000000003e-01 , -5.1628499999999999e-01 -2.4068868896849427e+00 , 3.3759293262028081e+00 , 6.8032608000000003e+00 , -4.3363900000000000e-01 , 5.4555699999999996e-01 , -7.1716400000000002e-01 -2.3603155587626556e+00 , 3.3014508195391619e+00 , 6.6924695999999999e+00 , -3.1837199999999999e-01 , 9.3557299999999999e-01 , -1.5278300000000000e-01 -2.2923647420703235e+00 , 3.3844748288875728e+00 , 7.2376272000000004e+00 , -4.2482500000000001e-01 , -8.3598499999999998e-01 , -3.4735100000000002e-01 -2.2018217091752001e+00 , 3.4907638082302039e+00 , 7.9461376000000001e+00 , 3.8768000000000002e-01 , 6.5819799999999995e-01 , 6.4535299999999995e-01 -2.1433650718807917e+00 , 3.4129422165789425e+00 , 7.8635928000000002e+00 , -9.0237900000000004e-01 , 3.4568599999999999e-01 , 2.5731900000000002e-01 -2.0739982232638150e+00 , 3.3732221952311656e+00 , 7.9626111999999996e+00 , -1.7590100000000000e-01 , -2.0675199999999999e-01 , -9.6245099999999995e-01 -2.0065892279836559e+00 , 3.3218231361051673e+00 , 8.0093280000000000e+00 , -5.6642999999999999e-01 , 7.2633199999999998e-01 , -3.8935799999999998e-01 -1.9296424993901218e+00 , 3.2827525709595928e+00 , 8.1362807999999998e+00 , 4.8154200000000003e-01 , -4.7455599999999998e-01 , 7.3682599999999998e-01 -1.6734464074993967e+00 , 3.4861641537837675e+00 , 9.7816335999999993e+00 , -2.1129200000000001e-01 , -9.0743099999999999e-01 , 3.6321399999999998e-01 -4.2575849745936427e+00 , 3.4810158094694543e+00 , 1.0053991199999999e+00 , -1.3100800000000001e-01 , 1.3882600000000000e-01 , 9.8161299999999996e-01 -4.3057670986481389e+00 , 3.5260067022711619e+00 , 1.0123702399999999e+00 , 1.2675100000000000e-01 , -1.3543800000000000e-01 , -9.8264499999999999e-01 -4.3671584282955322e+00 , 3.5795932805354127e+00 , 1.0068291199999999e+00 , -6.9184899999999994e-02 , 1.9629800000000000e-01 , 9.7810100000000000e-01 -4.4283360450695470e+00 , 3.6346529238333103e+00 , 1.0033097600000001e+00 , -5.7467799999999999e-02 , 1.9045999999999999e-01 , 9.8001099999999997e-01 -4.4974833583949403e+00 , 3.6948405190419571e+00 , 9.9528927999999994e-01 , -8.0655900000000003e-02 , 1.7053499999999999e-01 , 9.8204499999999995e-01 -4.5591398880685752e+00 , 3.7508355531857465e+00 , 9.9654872000000005e-01 , -8.1130999999999995e-02 , 1.8231300000000000e-01 , 9.7988799999999998e-01 -4.6287312657814876e+00 , 3.8120257557650712e+00 , 9.9361175999999984e-01 , -3.0385300000000001e-02 , 1.8376200000000001e-01 , 9.8250099999999996e-01 -4.7123854707606290e+00 , 3.8843011771730982e+00 , 9.8020616000000005e-01 , -2.2081099999999999e-02 , 2.0931900000000001e-01 , 9.7759799999999997e-01 -4.7956245320759781e+00 , 3.9562165451706246e+00 , 9.7014208000000002e-01 , -7.4800000000000005e-02 , 1.8215300000000001e-01 , 9.8042099999999999e-01 -4.8663953451472599e+00 , 4.0211157994772009e+00 , 9.7534207999999989e-01 , -7.7019900000000002e-02 , 1.7921699999999999e-01 , 9.8079000000000005e-01 -4.9510536490836046e+00 , 4.0962900889132925e+00 , 9.7129127999999998e-01 , -5.7521099999999999e-02 , 1.8645200000000001e-01 , 9.8077899999999996e-01 -5.0424240867776202e+00 , 4.1770377702447359e+00 , 9.6463736000000000e-01 , -3.4931600000000000e-02 , 1.9765600000000000e-01 , 9.7964899999999999e-01 -5.1496019539625602e+00 , 4.2693728801196205e+00 , 9.5040079999999993e-01 , -4.3950299999999998e-02 , 2.0355400000000001e-01 , 9.7807699999999997e-01 -5.2563364252005940e+00 , 4.3635812411240309e+00 , 9.4009440000000000e-01 , -7.4037599999999995e-02 , 1.8850800000000001e-01 , 9.7927699999999995e-01 -5.3635969167037985e+00 , 4.4586496499181774e+00 , 9.3417680000000014e-01 , -3.6346299999999998e-01 , 1.7789099999999999e-01 , 9.1446700000000003e-01 -5.4422997823735031e+00 , 4.5345161750455123e+00 , 9.5333359999999989e-01 , -9.0606600000000004e-01 , -7.4203400000000003e-02 , 4.1657899999999998e-01 -5.4324331510351627e+00 , 4.5474359125828343e+00 , 1.0364129600000000e+00 , -9.3944600000000000e-01 , -6.3619499999999995e-02 , 3.3673900000000001e-01 -5.4285405202278074e+00 , 4.5642831901206939e+00 , 1.1139335199999998e+00 , 9.9679899999999999e-01 , 6.8364300000000003e-02 , -4.1453700000000003e-02 -5.4386233965334938e+00 , 4.5912853947529859e+00 , 1.1815948800000000e+00 , 9.9772700000000003e-01 , 4.5921900000000002e-02 , 4.9323300000000000e-02 -5.4316196632162743e+00 , 4.6060482418043263e+00 , 1.2586432799999998e+00 , 9.9840300000000004e-01 , 4.4000699999999997e-02 , 3.5422700000000001e-02 -5.4097021592256773e+00 , 4.6083224384761472e+00 , 1.3443174400000000e+00 , 9.8708200000000001e-01 , 1.4423100000000000e-01 , 6.9761600000000007e-02 -5.4006973656125297e+00 , 4.6208120223020650e+00 , 1.4202093599999999e+00 , 9.8566799999999999e-01 , 1.5889300000000001e-01 , 5.6668999999999997e-02 -5.3917077312214596e+00 , 4.6321798575117654e+00 , 1.4958007200000001e+00 , 9.6130700000000002e-01 , 2.3588200000000001e-01 , 1.4229700000000001e-01 -5.4192554461407045e+00 , 4.6718588823527067e+00 , 1.5510382400000000e+00 , 9.8894599999999999e-01 , -3.4591200000000003e-02 , 1.4418600000000001e-01 -5.3607789644398469e+00 , 4.6462950236789986e+00 , 1.6488408800000001e+00 , 9.9940600000000002e-01 , 3.3696299999999998e-02 , 7.2678600000000001e-03 -5.3792761651972718e+00 , 4.6776451657925442e+00 , 1.7082592000000001e+00 , 9.6412299999999995e-01 , 8.1470599999999994e-03 , -2.6533000000000001e-01 -5.4034834392620201e+00 , 4.7155858973505174e+00 , 1.7647436800000000e+00 , -8.5494300000000001e-01 , 2.0004399999999999e-02 , 5.1833600000000002e-01 -5.4432243212505540e+00 , 4.7645279748729665e+00 , 1.8158700800000001e+00 , 7.1258100000000002e-01 , -3.4998000000000001e-02 , -7.0071700000000003e-01 -5.4973573566641223e+00 , 4.8257574620081147e+00 , 1.8625213599999999e+00 , 5.6149400000000005e-01 , -9.9057999999999993e-02 , -8.2153100000000001e-01 -5.5902114414705544e+00 , 4.9179267706371803e+00 , 1.8970837839999999e+00 , -3.5209900000000000e-01 , 1.2643599999999999e-01 , 9.2738399999999999e-01 -6.6081533225745872e+00 , 5.8824459713524710e+00 , 2.0739996399999998e+00 , -9.8927500000000002e-01 , -1.4333099999999999e-01 , -2.8113200000000001e-02 -1.4177974811549758e+01 , 1.2283932065564594e+01 , 5.0450079999999997e-01 , -6.1517400000000000e-02 , 1.8116399999999999e-01 , 9.8152700000000004e-01 -1.5853719706208853e+01 , 1.3775991431598847e+01 , 4.3609999999999993e-01 , -7.3366799999999996e-02 , 1.8319500000000000e-01 , 9.8033499999999996e-01 -1.9037203994122713e+01 , 1.6575444402559025e+01 , 1.7940719999999999e-01 , -1.2960700000000000e-01 , 1.9570899999999999e-01 , 9.7206000000000004e-01 -2.2211104863777084e+01 , 1.9404375440990187e+01 , 6.7274399999999845e-02 , -1.2196500000000000e-01 , 2.0512600000000000e-01 , 9.7110700000000005e-01 -2.4888096125520946e+01 , 2.1841079351223645e+01 , 1.6307919999999987e-01 , -4.7350999999999999e-01 , 3.9034000000000002e-01 , 7.8957200000000005e-01 -3.3465425843300210e+01 , 2.9642896623558382e+01 , 4.4672879999999981e-01 , -4.4447499999999999e-03 , -9.6502100000000002e-01 , 2.6213500000000001e-01 -3.3456453620759461e+01 , 2.9822216578473277e+01 , 1.1503127200000001e+00 , -4.4447499999999999e-03 , -9.6502100000000002e-01 , 2.6213500000000001e-01 -3.3422452952112515e+01 , 2.9978954001610067e+01 , 1.8577508800000000e+00 , -7.6241900000000001e-02 , -9.8721599999999998e-01 , 1.3996800000000001e-01 -3.3363806740061591e+01 , 3.0114884355027094e+01 , 2.5675207200000001e+00 , -1.6598900000000000e-01 , -9.8123199999999999e-01 , 9.8142800000000002e-02 -3.3248430212180040e+01 , 3.0199309458675224e+01 , 3.2782640000000001e+00 , 1.0561000000000000e-01 , 9.9206600000000000e-01 , -6.8210999999999994e-02 -3.3123690218560881e+01 , 3.0276530731857502e+01 , 3.9877000000000002e+00 , -1.3692499999999999e-01 , -9.9013499999999999e-01 , 2.9741099999999999e-02 -3.3281827711922929e+01 , 3.0610909107152874e+01 , 4.7114360000000000e+00 , -1.2520600000000001e-01 , -9.7248900000000005e-01 , 1.9643900000000000e-01 -3.7046381674683822e+01 , 3.4488822610636568e+01 , 6.5430320000000002e+00 , -3.8294099999999998e-01 , 8.8682200000000000e-01 , -2.5865500000000002e-01 -3.2937027266366897e+01 , 3.0870714646878962e+01 , 6.8603256000000004e+00 , -1.4926700000000001e-01 , -9.6866399999999997e-01 , 1.9851700000000000e-01 -3.2788439245381966e+01 , 3.0926335477687040e+01 , 7.5737344000000002e+00 , -9.4359700000000005e-02 , -9.8168200000000005e-01 , 1.6551800000000000e-01 -3.7149600882556115e+01 , 3.5250642784728996e+01 , 9.0654480000000000e+00 , -4.7987000000000002e-01 , 8.5935300000000003e-01 , -1.7674100000000001e-01 -3.6703624516223002e+01 , 3.5052638046441459e+01 , 9.8324272000000015e+00 , -3.7365999999999999e-01 , 9.2496900000000004e-01 , 6.9356799999999996e-02 -3.2483774305930240e+01 , 3.1430489411239957e+01 , 1.0506544800000000e+01 , -1.7111399999999999e-01 , -9.7481399999999996e-01 , 1.4302799999999999e-01 -3.2439889432593503e+01 , 3.1592014582245032e+01 , 1.1261855200000001e+01 , -1.8670800000000001e-01 , -9.6451200000000004e-01 , 1.8669800000000000e-01 -7.0211016402398210e+00 , 7.6586715924301130e+00 , 7.3628432000000004e+00 , 3.9228300000000001e-02 , -4.8249399999999998e-01 , 8.7502100000000005e-01 -6.8271680230026925e+00 , 7.4843913283980550e+00 , 7.3629264000000001e+00 , 3.3137600000000000e-01 , -4.9228699999999997e-01 , 8.0488700000000002e-01 -5.8666129734081078e+00 , 6.4077958676908020e+00 , 6.5682208000000006e+00 , 3.3148300000000003e-01 , 5.2166199999999996e-01 , 7.8612199999999999e-01 -5.7636436550287300e+00 , 6.3261083095340922e+00 , 6.6098312000000004e+00 , 1.3245699999999999e-01 , 2.3752000000000001e-01 , 9.6230899999999997e-01 -5.5858533455817518e+00 , 6.1534875043513209e+00 , 6.5635928000000003e+00 , 2.6317000000000002e-01 , -2.9572999999999999e-01 , 9.1830599999999996e-01 -5.4157135715655720e+00 , 5.9887207847258956e+00 , 6.5158880000000003e+00 , -2.5181199999999998e-01 , 2.5055899999999998e-01 , -9.3477900000000003e-01 -5.3446747485679538e+00 , 5.9390159620875131e+00 , 6.5755112000000002e+00 , -2.5181199999999998e-01 , 2.5055899999999998e-01 , -9.3477800000000000e-01 -5.5749770955147504e+00 , 6.2627356157535781e+00 , 7.0139544000000003e+00 , -5.5480200000000002e-01 , -1.6635000000000000e-01 , 8.1518299999999999e-01 -5.6213943673858147e+00 , 6.3662160227309750e+00 , 7.2423280000000005e+00 , -6.3900599999999996e-01 , -7.6713200000000004e-01 , 5.6393300000000000e-02 -5.4319853444779458e+00 , 6.1728608281838246e+00 , 7.1592320000000003e+00 , 3.8325599999999999e-01 , -9.1428799999999999e-01 , -1.3112199999999999e-01 -5.5210107661904706e+00 , 6.3324967391440694e+00 , 7.4593759999999998e+00 , 2.1168699999999999e-01 , 9.6504800000000002e-01 , -1.5450400000000000e-01 -5.2439958235078974e+00 , 6.0241707742401536e+00 , 7.2349128000000000e+00 , -2.3119999999999999e-01 , 9.4101699999999999e-01 , -2.4704899999999999e-01 -5.1056485485455028e+00 , 5.8887696050395908e+00 , 7.1974000000000000e+00 , 1.4225699999999999e-01 , 9.1875499999999999e-01 , 3.6831100000000000e-01 -5.9236759421114531e+00 , 7.0246444323435222e+00 , 8.6986504000000018e+00 , 1.0293400000000000e-01 , -9.6147600000000000e-01 , 2.5488800000000000e-01 -5.6439196016324331e+00 , 6.7124625746348681e+00 , 8.4702768000000006e+00 , -8.2456499999999999e-01 , 2.0464399999999999e-01 , -5.2746000000000004e-01 -5.6020669259158478e+00 , 6.7186437434047974e+00 , 8.6343576000000013e+00 , -6.5136200000000000e-01 , 6.9971700000000003e-01 , -2.9346699999999998e-01 -5.6821634163375290e+00 , 6.8953157369876203e+00 , 9.0276336000000015e+00 , 4.9945600000000001e-01 , -3.5831000000000002e-01 , 7.8876999999999997e-01 -5.1445316179894123e+00 , 6.2075586347337453e+00 , 8.2609455999999994e+00 , 5.8099800000000000e-02 , 7.4923200000000001e-01 , 6.5975399999999995e-01 -4.8388412123983748e+00 , 5.8313000043032552e+00 , 7.8829263999999997e+00 , 6.5922099999999995e-01 , -5.9300299999999995e-01 , 4.6235900000000002e-01 -4.1680583468463155e+00 , 4.9113143590483705e+00 , 6.6940712000000007e+00 , 5.6037000000000003e-01 , 1.0284100000000000e-01 , 8.2183300000000004e-01 -4.1537299844642064e+00 , 4.9356178037047762e+00 , 6.8327448000000004e+00 , 9.8694099999999996e-01 , -1.2665100000000001e-01 , -9.9535499999999999e-02 -4.1009503118699477e+00 , 4.9029423682211757e+00 , 6.8912136000000004e+00 , -9.5862899999999995e-01 , 2.7771499999999999e-01 , 6.2480500000000001e-02 -5.2197435799778757e+00 , 6.6801190919795932e+00 , 9.7898184000000015e+00 , -6.8337599999999998e-01 , 3.4822300000000000e-01 , -6.4166800000000002e-01 -4.4476400553925250e+00 , 5.5528955793001966e+00 , 8.1621039999999994e+00 , 3.5618300000000003e-01 , -6.8296000000000001e-01 , 6.3773000000000002e-01 -3.9978267324056826e+00 , 4.8984966574706332e+00 , 7.2213095999999997e+00 , 4.6274300000000002e-01 , -7.3492299999999999e-01 , 4.9574000000000001e-01 -4.0157446176365656e+00 , 4.9862569547940403e+00 , 7.4921048000000008e+00 , -6.1841500000000005e-01 , 2.7803299999999997e-01 , -7.3502400000000001e-01 -3.9275984131051542e+00 , 4.9009632111276584e+00 , 7.4715439999999997e+00 , -7.3390200000000005e-01 , 2.3244400000000001e-01 , -6.3824599999999998e-01 -3.8516138969881775e+00 , 4.8354527708990283e+00 , 7.4832752000000005e+00 , -7.3135799999999995e-01 , -2.8377100000000000e-01 , -6.2015299999999995e-01 -3.8241015714961550e+00 , 4.8557996995228043e+00 , 7.6522128000000000e+00 , 9.7970599999999997e-01 , 4.6977900000000003e-02 , 1.9485800000000000e-01 -3.8262954857619631e+00 , 4.9336024378295900e+00 , 7.9387223999999996e+00 , 2.4316999999999998e-02 , -2.1719300000000000e-01 , 9.7582599999999997e-01 -3.7410040195352829e+00 , 4.8548510547472397e+00 , 7.9301839999999997e+00 , 1.2975800000000001e-01 , -6.2391900000000000e-01 , -7.7064100000000002e-01 -3.6612931324418385e+00 , 4.7854230075774105e+00 , 7.9374744000000002e+00 , -2.0438000000000001e-01 , -2.4239400000000000e-01 , -9.4840599999999997e-01 -3.6450078115167037e+00 , 4.8429895111860652e+00 , 8.2091951999999999e+00 , -2.1773200000000001e-01 , -8.5259399999999996e-01 , 4.7505300000000000e-01 -3.4450428230547505e+00 , 4.5184371617520016e+00 , 7.6676983999999999e+00 , -3.6569000000000002e-01 , -3.7034499999999998e-01 , 8.5388299999999995e-01 -3.5486847908656287e+00 , 4.8446232470804365e+00 , 8.5446056000000006e+00 , -4.1850799999999999e-01 , -7.8154100000000004e-01 , -4.6265000000000001e-01 -3.4785943632815526e+00 , 4.8058919820811958e+00 , 8.6325375999999991e+00 , 3.9004499999999998e-01 , 7.7850699999999995e-01 , 4.9172300000000002e-01 -3.6057433085139845e+00 , 5.2525193906239762e+00 , 9.8856544000000000e+00 , 6.9057100000000005e-01 , -6.6592799999999996e-01 , 2.8222799999999998e-01 -3.0257347033618940e+00 , 3.9107473608731969e+00 , 6.8018880000000008e+00 , 2.0962000000000000e-01 , 1.0360900000000001e-01 , 9.7227799999999998e-01 -2.9718114660192758e+00 , 3.8660719332368370e+00 , 6.8163023999999997e+00 , 4.1112900000000002e-01 , 2.0781900000000000e-01 , 8.8757200000000003e-01 -3.3061482535553948e+00 , 4.9972686201822807e+00 , 9.9408992000000005e+00 , -5.6985500000000000e-01 , 8.1734200000000001e-01 , -8.4955900000000001e-02 -3.1743723763645777e+00 , 4.8040084584556837e+00 , 9.6597559999999998e+00 , 9.1148300000000004e-01 , 1.9913100000000000e-01 , -3.5992400000000002e-01 -2.9531428644409958e+00 , 4.2529402644197241e+00 , 8.3372712000000000e+00 , -8.4577000000000002e-01 , -3.9863100000000001e-01 , 3.5463699999999998e-01 -2.7510514505140113e+00 , 3.6555166003519259e+00 , 6.7729448000000003e+00 , 8.1500399999999995e-01 , 8.9312799999999998e-02 , 5.7253100000000001e-01 -2.7091100072411578e+00 , 3.6589738364305875e+00 , 6.9287055999999998e+00 , 7.3303200000000002e-01 , -6.5769999999999995e-02 , 6.7700700000000003e-01 -2.6453202744768207e+00 , 3.5570760003265760e+00 , 6.7571783999999999e+00 , 2.2677300000000000e-01 , 8.5806599999999997e-02 , -9.7016100000000005e-01 -2.5937754784809770e+00 , 3.5064309000357436e+00 , 6.7425351999999998e+00 , -6.9049399999999997e-02 , 9.0347799999999999e-04 , 9.9761299999999997e-01 -2.5468749506471724e+00 , 3.5023567926547208e+00 , 6.8862319999999997e+00 , -2.5907999999999998e-01 , 3.3283299999999999e-01 , 9.0669699999999998e-01 -2.4948303866568975e+00 , 3.4666150792941588e+00 , 6.9296000000000006e+00 , -1.8108199999999999e-01 , -9.8217800000000000e-01 , -5.0364600000000002e-02 -2.4429260984090986e+00 , 3.3640916462097374e+00 , 6.7205912000000003e+00 , 2.6179799999999998e-01 , -8.5826899999999995e-01 , 4.4140299999999999e-01 -2.3942896477126308e+00 , 3.3123276413358438e+00 , 6.6904832000000001e+00 , -2.5243300000000002e-01 , 9.5150199999999996e-01 , -1.7584600000000000e-01 -2.3419237928044887e+00 , 3.2922683006791971e+00 , 6.7905416000000010e+00 , -1.5525400000000000e-01 , 9.8510399999999998e-01 , -7.3929700000000001e-02 -2.2447810763534046e+00 , 3.5025176104607079e+00 , 7.9134919999999997e+00 , 2.8434399999999999e-01 , 7.5550300000000004e-01 , 5.9022399999999997e-01 -2.1743677641658308e+00 , 3.4632433749325946e+00 , 8.0039616000000002e+00 , -7.4776700000000002e-02 , 8.3400399999999997e-01 , 5.4666800000000004e-01 -2.1123324503798337e+00 , 3.3956686654456094e+00 , 7.9609991999999998e+00 , -7.8434000000000004e-02 , 2.6801100000000000e-01 , 9.6021800000000002e-01 -2.0426910841641712e+00 , 3.3485816565983439e+00 , 8.0181056000000002e+00 , 3.0611899999999997e-01 , -4.1561399999999998e-01 , 8.5647899999999999e-01 -1.9784668882530771e+00 , 3.2866330304588418e+00 , 8.0025888000000016e+00 , 6.3329299999999999e-01 , -2.2070000000000001e-01 , 7.4177599999999999e-01 -1.9044417306335364e+00 , 3.2421485744922851e+00 , 8.0875048000000014e+00 , -6.4949999999999997e-01 , 6.5871500000000005e-01 , -3.7979499999999999e-01 -4.2792155909784526e+00 , 3.4167630930296680e+00 , 1.0073231199999999e+00 , -1.3234599999999999e-01 , 1.5825500000000001e-01 , 9.7848900000000005e-01 -4.3222866571294922e+00 , 3.4569720551347300e+00 , 1.0210937599999999e+00 , -1.2617800000000001e-01 , 1.6171900000000000e-01 , 9.7873699999999997e-01 -4.3847426585437566e+00 , 3.5082902952852013e+00 , 1.0150763199999999e+00 , -4.8260999999999998e-02 , 1.6178799999999999e-01 , 9.8564499999999999e-01 -4.4480162011657987e+00 , 3.5610720486265888e+00 , 1.0112064799999998e+00 , -5.9914299999999997e-02 , 1.9627600000000001e-01 , 9.7871600000000003e-01 -4.5120663838563591e+00 , 3.6142627278223438e+00 , 1.0095871999999999e+00 , -5.6862400000000000e-02 , 1.5191499999999999e-01 , 9.8675700000000000e-01 -4.5748521091752954e+00 , 3.6689798248492789e+00 , 1.0099636800000000e+00 , -5.6156699999999997e-02 , 1.4259200000000000e-01 , 9.8818700000000004e-01 -4.6465850737890584e+00 , 3.7278239293006235e+00 , 1.0063735999999999e+00 , -5.0854999999999997e-02 , 1.5769700000000000e-01 , 9.8617699999999997e-01 -4.7241416179854028e+00 , 3.7919658030830483e+00 , 9.9873895999999984e-01 , -3.7750400000000003e-02 , 1.8992899999999999e-01 , 9.8107200000000006e-01 -4.8034807729202473e+00 , 3.8576787436861339e+00 , 9.9398407999999994e-01 , -3.6755700000000002e-02 , 1.9006899999999999e-01 , 9.8108300000000004e-01 -4.8824634543155048e+00 , 3.9239985610605448e+00 , 9.9216303999999989e-01 , -6.0808300000000003e-02 , 1.7224700000000001e-01 , 9.8317500000000002e-01 -4.9682300326536737e+00 , 3.9957471445883237e+00 , 9.8713359999999994e-01 , -5.8727300000000003e-02 , 1.7381300000000000e-01 , 9.8302599999999996e-01 -5.0628151847893328e+00 , 4.0740373042700773e+00 , 9.7954680000000005e-01 , -3.5628699999999999e-02 , 1.7779000000000000e-01 , 9.8342300000000005e-01 -5.1650729261557817e+00 , 4.1579788230463794e+00 , 9.6998919999999988e-01 , -4.5497099999999999e-02 , 1.9165900000000000e-01 , 9.8040700000000003e-01 -5.2598234926949434e+00 , 4.2377562926740122e+00 , 9.6981344000000003e-01 , 4.4278100000000001e-02 , -1.9779099999999999e-01 , -9.7924400000000000e-01 -5.3773784709498376e+00 , 4.3341793020880068e+00 , 9.5701520000000007e-01 , -2.6881100000000002e-01 , 1.1297100000000000e-01 , 9.5654499999999998e-01 -5.4653080601059703e+00 , 4.4125847026721114e+00 , 9.6968343999999984e-01 , -8.5275299999999998e-01 , 7.2378300000000007e-02 , 5.1727500000000004e-01 -5.4705659589287912e+00 , 4.4353829326553562e+00 , 1.0418147200000001e+00 , -9.5125800000000005e-01 , -7.8909199999999999e-02 , 2.9813000000000001e-01 -5.4967984132505006e+00 , 4.4733840082835474e+00 , 1.0989554400000001e+00 , 9.9715799999999999e-01 , 4.7698699999999997e-02 , -5.8315499999999999e-02 -5.4619329139086279e+00 , 4.4688101298109650e+00 , 1.1953135200000000e+00 , 9.9689799999999995e-01 , 3.8358700000000003e-02 , 6.8727600000000000e-02 -5.4560596081901629e+00 , 4.4833882764454795e+00 , 1.2716786400000000e+00 , 9.9651500000000004e-01 , 1.1729300000000000e-02 , -8.2584900000000003e-02 -5.4491591884557948e+00 , 4.4968562372224330e+00 , 1.3476163200000000e+00 , 9.9841999999999997e-01 , 2.8372000000000001e-02 , 4.8510200000000003e-02 -5.5107977689973335e+00 , 4.5589598707137533e+00 , 1.3843896800000000e+00 , 9.9275000000000002e-01 , 6.7524200000000006e-02 , 9.9436600000000000e-02 -5.4323476596914162e+00 , 4.5215264641002797e+00 , 1.4981105600000000e+00 , 9.9199499999999996e-01 , 9.1196500000000000e-03 , 1.2594600000000000e-01 -5.4451270583560136e+00 , 4.5484704240084168e+00 , 1.5607591199999999e+00 , 9.8483200000000004e-01 , 4.2576599999999999e-02 , 1.6820800000000000e-01 -5.3788480899735749e+00 , 4.5185765382696950e+00 , 1.6617441600000000e+00 , 9.9672000000000005e-01 , 3.7899099999999998e-02 , 7.1510400000000002e-02 -5.4132633261285585e+00 , 4.5613349108981849e+00 , 1.7126646400000001e+00 , -9.3020199999999997e-01 , 4.8785700000000001e-02 , 3.6379200000000000e-01 -5.4228599972108427e+00 , 4.5862860364386977e+00 , 1.7753464800000001e+00 , -8.8353400000000004e-01 , 1.2120499999999999e-01 , 4.5241300000000001e-01 -5.4637649233567789e+00 , 4.6338829603195073e+00 , 1.8252862400000001e+00 , -7.2960300000000000e-01 , 1.4889400000000000e-01 , 6.6746600000000000e-01 -5.5044248160773463e+00 , 4.6808041335507022e+00 , 1.8771510400000000e+00 , 6.1389199999999999e-01 , -1.6394100000000000e-01 , -7.7217899999999995e-01 -5.5839655376240014e+00 , 4.7584003944987519e+00 , 1.9156116960000000e+00 , -3.8550899999999999e-01 , 1.4559400000000000e-01 , 9.1114499999999998e-01 -5.7419411980346977e+00 , 4.8957005757089895e+00 , 1.9298237119999999e+00 , -1.7157800000000001e-01 , 1.2017300000000000e-01 , 9.7781399999999996e-01 -6.6630346692122346e+00 , 5.7127399908090659e+00 , 2.0708362720000002e+00 , -9.7595799999999999e-01 , -1.2949099999999999e-01 , 1.7532600000000001e-01 -1.3706801066153124e+01 , 1.1309839290368664e+01 , 6.2866639999999996e-01 , -5.5363400000000000e-02 , 1.8474399999999999e-01 , 9.8122600000000004e-01 -1.5243010621760821e+01 , 1.2597186245054774e+01 , 5.7380640000000005e-01 , -7.3366799999999996e-02 , 1.8319500000000000e-01 , 9.8033499999999996e-01 -2.2474784132300314e+01 , 1.8700375292655647e+01 , 4.7135599999999989e-01 , -5.4991400000000001e-01 , 3.0847799999999997e-01 , 7.7616700000000005e-01 -3.5475515722834857e+01 , 2.9655188861124131e+01 , 2.3035679999999981e-01 , 6.0825499999999998e-02 , 9.8334299999999997e-01 , -1.7127999999999999e-01 -4.1079992474484222e+01 , 3.4501591904648855e+01 , 5.9995199999999982e-01 , -3.8291899999999997e-02 , -9.7647600000000001e-01 , 2.1219900000000000e-01 -3.4260651696448782e+01 , 2.9572235085363108e+01 , 3.8809544000000002e+00 , 1.3755100000000001e-01 , 9.8919299999999999e-01 , -5.0760399999999997e-02 -3.4176503202380324e+01 , 2.9687396930025347e+01 , 4.5980135999999998e+00 , -2.3959300000000000e-01 , -9.6327799999999997e-01 , 1.2120700000000000e-01 -4.0984542623121698e+01 , 3.5768678314880958e+01 , 5.8038311999999994e+00 , 8.5354799999999995e-02 , -9.8070700000000000e-01 , 1.7586499999999999e-01 -2.3423982493204473e+01 , 2.0688575530485039e+01 , 5.0451303999999997e+00 , 8.3908300000000002e-01 , -1.0678000000000000e-01 , 5.3342100000000003e-01 -4.0586055196059569e+01 , 3.5881348996681531e+01 , 7.5378232000000009e+00 , 4.4078699999999998e-02 , -9.9222800000000000e-01 , 1.1636800000000000e-01 -3.4023375423416567e+01 , 3.0311405768255728e+01 , 7.5099096000000003e+00 , -1.8395800000000001e-01 , -9.6531500000000003e-01 , 1.8527700000000000e-01 -4.0589936149696555e+01 , 3.6349042760376179e+01 , 9.3329775999999995e+00 , 1.4904700000000001e-01 , -9.6726000000000001e-01 , 2.0541000000000001e-01 -3.8877305836838488e+01 , 3.5278700049102973e+01 , 1.0801613600000000e+01 , -3.4397499999999998e-01 , 9.3570299999999995e-01 , 7.8364400000000001e-02 -3.3981447818504314e+01 , 3.1060569434674704e+01 , 1.0534156800000002e+01 , -2.1506300000000000e-01 , -9.6549099999999999e-01 , 1.4688599999999999e-01 -3.3805835461971625e+01 , 3.1100312867956660e+01 , 1.1268209600000000e+01 , -1.8694000000000000e-01 , -9.7364099999999998e-01 , 1.3067699999999999e-01 -6.9745169554392481e+00 , 7.3876649545548903e+00 , 7.5150888000000000e+00 , 3.3137600000000000e-01 , -4.9228699999999997e-01 , 8.0488700000000002e-01 -5.9519667684847377e+00 , 6.3005080353856586e+00 , 6.6599800000000000e+00 , 1.3922000000000001e-01 , 8.2672999999999996e-01 , 5.4510199999999998e-01 -5.6779384335363794e+00 , 6.0303204461849891e+00 , 6.5200376000000002e+00 , -2.8001799999999999e-01 , 8.9767899999999998e-02 , 9.5578799999999997e-01 -5.4754365850524227e+00 , 5.8395214627782090e+00 , 6.4416112000000005e+00 , -1.7868800000000001e-01 , 8.6048799999999995e-02 , -9.8013600000000001e-01 -5.4793540148487256e+00 , 5.8805014064515602e+00 , 6.5878664000000002e+00 , -1.8972900000000001e-01 , 1.8594100000000000e-01 , 9.6406899999999995e-01 -5.7731266437977267e+00 , 6.2600107377650236e+00 , 7.0901551999999999e+00 , 6.4994099999999999e-01 , 7.5204300000000002e-01 , -1.0958100000000000e-01 -5.7335193216190738e+00 , 6.2568950716859453e+00 , 7.2085280000000003e+00 , 7.2714800000000002e-01 , 6.8620099999999995e-01 , -1.9606900000000000e-02 -5.8613258107915645e+00 , 6.4526189480145169e+00 , 7.5484520000000002e+00 , -4.2173100000000002e-01 , -8.9950699999999995e-01 , 1.1415300000000000e-01 -5.6433532453234942e+00 , 6.2392011369776981e+00 , 7.4387632000000004e+00 , 7.5450200000000001e-01 , 6.4012800000000003e-01 , -1.4478400000000000e-01 -5.6802052803623102e+00 , 6.3330704426142992e+00 , 7.6753632000000005e+00 , 4.3265100000000001e-02 , 9.6707799999999999e-01 , 2.5077500000000003e-01 -5.6932386728749851e+00 , 6.3987555060824173e+00 , 7.8882512000000009e+00 , 2.9983199999999999e-01 , 7.5801499999999999e-01 , 5.7923599999999997e-01 -5.9856365365784114e+00 , 6.8158799108430976e+00 , 8.5453128000000014e+00 , 7.2491799999999995e-01 , 1.6920900000000000e-01 , -6.6773000000000005e-01 -6.0944639064812094e+00 , 7.0149299194460610e+00 , 8.9556448000000000e+00 , 6.0821899999999995e-01 , -5.7147000000000003e-01 , 5.5090099999999997e-01 -6.0064042097024952e+00 , 6.9676854137400985e+00 , 9.0607472000000016e+00 , 5.5331600000000003e-01 , -2.2392500000000001e-01 , 8.0230800000000002e-01 -5.7903431856341712e+00 , 6.7548885448560210e+00 , 8.9439968000000007e+00 , 2.8455100000000001e-02 , -1.9516600000000001e-01 , 9.8035700000000003e-01 -5.6942270688487522e+00 , 6.6950916637814046e+00 , 9.0272280000000009e+00 , 2.3743200000000000e-01 , 2.6684400000000000e-02 , 9.7103799999999996e-01 -5.5576191642593535e+00 , 6.5794303367358724e+00 , 9.0300984000000000e+00 , 1.7920000000000000e-01 , 3.6318400000000001e-02 , 9.8314199999999996e-01 -5.4127900937003606e+00 , 6.4526051828760078e+00 , 9.0127096000000009e+00 , 6.8040299999999998e-01 , -4.2078500000000002e-01 , -5.9999400000000003e-01 -4.6451832469609453e+00 , 5.4564223105797760e+00 , 7.6779736000000005e+00 , 7.5052900000000000e-01 , 1.7140600000000000e-01 , 6.3822100000000004e-01 -4.2363709535510345e+00 , 4.9333222719254763e+00 , 6.9971168000000006e+00 , -6.5695199999999998e-01 , 2.9592700000000000e-01 , 6.9342700000000002e-01 -4.1084501400138338e+00 , 4.7963736753149941e+00 , 6.8909120000000001e+00 , 4.7693300000000000e-01 , 3.6192900000000000e-01 , 8.0096400000000001e-01 -4.1811089814927413e+00 , 4.9539334645214499e+00 , 7.2562639999999998e+00 , -1.9571200000000000e-01 , -9.7880199999999995e-01 , -6.0366599999999999e-02 -4.0851310988612743e+00 , 4.8629879474221429e+00 , 7.2218296000000004e+00 , 7.4617199999999995e-01 , -4.6832000000000002e-03 , 6.6573700000000002e-01 -4.0413957860342835e+00 , 4.8519682212365609e+00 , 7.3211496000000000e+00 , 8.9979200000000004e-01 , -2.4166699999999999e-01 , 3.6327900000000002e-01 -4.0084523632220677e+00 , 4.8580665337093354e+00 , 7.4550808000000002e+00 , -8.5069399999999995e-01 , 4.2176999999999999e-02 , -5.2396600000000004e-01 -3.9658446825529738e+00 , 4.8526342094921517e+00 , 7.5718728000000004e+00 , 5.0741199999999997e-01 , 4.5946399999999998e-01 , 7.2899000000000003e-01 -3.8568955079132383e+00 , 4.7379423485943519e+00 , 7.4853344000000002e+00 , -4.6956100000000001e-01 , -6.9641200000000003e-01 , -5.4269999999999996e-01 -3.8560653029157068e+00 , 4.8037565138634033e+00 , 7.7432752000000002e+00 , 8.4754300000000005e-01 , 4.6610900000000000e-01 , 2.5379699999999999e-01 -3.8294333442281996e+00 , 4.8330045743910173e+00 , 7.9407296000000009e+00 , 2.7711700000000000e-01 , 3.0988599999999999e-01 , 9.0949300000000000e-01 -3.7676920741396058e+00 , 4.8009319606302512e+00 , 8.0213192000000006e+00 , -2.9543300000000000e-01 , 5.4016600000000004e-01 , 7.8799799999999998e-01 -3.6944534250478180e+00 , 4.7500914621070258e+00 , 8.0643440000000002e+00 , 7.0844099999999999e-01 , 1.2307500000000000e-01 , 6.9495600000000002e-01 -3.6276949085101666e+00 , 4.7116748170987464e+00 , 8.1334727999999998e+00 , -8.3329799999999998e-01 , 2.4224599999999999e-01 , -4.9692199999999997e-01 -3.6485895069736598e+00 , 4.8539026198272195e+00 , 8.6119768000000008e+00 , 8.6540099999999998e-01 , 4.8988999999999999e-01 , 1.0530700000000000e-01 -3.5814876817002106e+00 , 4.8243512858902964e+00 , 8.7197519999999997e+00 , -4.2310799999999998e-01 , -6.8022499999999997e-01 , -5.9855999999999998e-01 -3.6028958314036323e+00 , 4.9972868257884793e+00 , 9.3191872000000000e+00 , 2.6540200000000003e-01 , -7.4458299999999999e-01 , 6.1250099999999996e-01 -3.0774298738632746e+00 , 3.8962151286828846e+00 , 6.7882120000000006e+00 , 2.5269900000000001e-01 , 7.4124399999999993e-02 , 9.6470199999999995e-01 -3.0204458069088824e+00 , 3.8497307494806483e+00 , 6.7930168000000002e+00 , -4.0339599999999998e-01 , -1.5747800000000001e-01 , -9.0137299999999998e-01 -2.9726897062979201e+00 , 3.8248862408520665e+00 , 6.8545224000000005e+00 , 4.2959000000000003e-01 , 2.4254500000000001e-01 , 8.6984099999999998e-01 -3.2093474443457817e+00 , 4.6427782622401157e+00 , 9.2359144000000004e+00 , 6.1843999999999999e-01 , 2.0240300000000000e-01 , 7.5931899999999997e-01 -3.0431128428536987e+00 , 4.3232169955726292e+00 , 8.5471640000000004e+00 , -8.7820100000000001e-01 , -3.3869800000000000e-01 , 3.3770699999999998e-01 -2.7820274520285428e+00 , 3.6036870413639144e+00 , 6.6224568000000001e+00 , 9.8473200000000005e-01 , 1.7185900000000001e-01 , 2.7717200000000001e-02 -2.7461283250880819e+00 , 3.6232146376592267e+00 , 6.8170928000000002e+00 , -9.5982699999999999e-01 , -1.0356600000000001e-01 , -2.6078000000000001e-01 -2.6921798435874162e+00 , 3.5760934422615929e+00 , 6.8141496000000004e+00 , 6.3830900000000002e-01 , -7.4611300000000003e-01 , 1.8941000000000000e-01 -2.6348635668245981e+00 , 3.5115021300187346e+00 , 6.7500752000000004e+00 , -7.8595100000000001e-02 , 6.4208299999999996e-02 , 9.9483699999999997e-01 -2.5783847786757161e+00 , 3.4342936987177417e+00 , 6.6341880000000000e+00 , 2.7203399999999999e-02 , -7.3674099999999998e-01 , 6.7562699999999998e-01 -2.5322847003072564e+00 , 3.4392636960537057e+00 , 6.8070984000000001e+00 , 5.7437700000000003e-01 , 7.6258599999999999e-01 , -2.9758099999999998e-01 -2.4785302006560235e+00 , 3.3583841188238273e+00 , 6.6682376000000003e+00 , -6.3782200000000000e-01 , 2.4016299999999999e-01 , 7.3178200000000004e-01 -2.4285801687439954e+00 , 3.3129117596792894e+00 , 6.6584928000000003e+00 , -7.9776899999999998e-02 , 7.5465700000000002e-01 , 6.5125200000000005e-01 -2.3767449635342808e+00 , 3.3052481318192495e+00 , 6.7991320000000002e+00 , -1.5525400000000000e-01 , 9.8510399999999998e-01 , -7.3929700000000001e-02 -2.3085578947195948e+00 , 3.3728693752817982e+00 , 7.2836160000000003e+00 , -4.5200699999999999e-01 , -8.3302699999999996e-01 , -3.1899200000000000e-01 -2.2186318816371760e+00 , 3.4709215498305097e+00 , 7.9513584000000002e+00 , -2.4918599999999999e-01 , -7.7855700000000005e-01 , -5.7598300000000002e-01 -2.1528621613807721e+00 , 3.4138698886738981e+00 , 7.9492992000000005e+00 , -1.8389100000000000e-01 , -3.6448500000000000e-01 , 9.1287200000000002e-01 -2.0848856927980997e+00 , 3.3606897877485773e+00 , 7.9659496000000001e+00 , -6.0668300000000001e-02 , 4.0099000000000001e-01 , 9.1407099999999997e-01 -2.0158415189607015e+00 , 3.3082801239839852e+00 , 7.9915128000000006e+00 , 3.8206400000000001e-01 , -3.5483599999999998e-01 , 8.5329900000000003e-01 -1.7564060427742316e+00 , 3.5760518585732726e+00 , 9.8713024000000011e+00 , -4.6755300000000000e-01 , -1.6027400000000000e-01 , 8.6931400000000003e-01 -1.6804301327198916e+00 , 3.4757161411532969e+00 , 9.7312767999999998e+00 , 2.1129200000000001e-01 , 9.0743099999999999e-01 , -3.6321399999999998e-01 -4.3347024033922867e+00 , 3.3890750229298137e+00 , 1.0293118400000001e+00 , -1.1432100000000001e-01 , 1.3385600000000000e-01 , 9.8438499999999995e-01 -4.3920915616431877e+00 , 3.4355502590968579e+00 , 1.0297912800000000e+00 , -1.1384500000000000e-01 , 1.5027599999999999e-01 , 9.8206800000000005e-01 -4.4502849769110693e+00 , 3.4824028790169170e+00 , 1.0323184799999998e+00 , -5.6039300000000000e-02 , 1.8870600000000001e-01 , 9.8043300000000000e-01 -4.5215767929922812e+00 , 3.5369320493817860e+00 , 1.0230458400000000e+00 , -1.7271600000000002e-02 , 1.8107899999999999e-01 , 9.8331700000000000e-01 -4.5936431752378022e+00 , 3.5929796906089075e+00 , 1.0162234400000001e+00 , -6.9130399999999995e-02 , 1.6470499999999999e-01 , 9.8391700000000004e-01 -4.6593116591656951e+00 , 3.6458298896947410e+00 , 1.0185000000000000e+00 , 6.8700499999999998e-02 , -1.4807100000000001e-01 , -9.8658800000000002e-01 -4.7318447639606980e+00 , 3.7028730586529699e+00 , 1.0166602400000000e+00 , -5.0538500000000000e-02 , 1.6066200000000000e-01 , 9.8571500000000001e-01 -4.8122533505759773e+00 , 3.7651948656342586e+00 , 1.0111284800000000e+00 , -3.2294999999999997e-02 , 1.9621100000000000e-01 , 9.8002999999999996e-01 -4.9005303863208258e+00 , 3.8339293181082752e+00 , 1.0022073599999999e+00 , -6.0002000000000000e-02 , 1.7228800000000000e-01 , 9.8321700000000001e-01 -4.9813288972673657e+00 , 3.8984630829860647e+00 , 1.0024652800000000e+00 , -7.0909799999999995e-02 , 1.6208700000000001e-01 , 9.8422600000000005e-01 -5.0699126695123695e+00 , 3.9684588162374941e+00 , 9.9984031999999989e-01 , 5.3539000000000003e-02 , -1.7683199999999999e-01 , -9.8278399999999999e-01 -5.1672544173824084e+00 , 4.0439863585303941e+00 , 9.9496688000000000e-01 , -4.1257299999999997e-02 , 1.9201099999999999e-01 , 9.8052499999999998e-01 -5.2712993382711604e+00 , 4.1261784632576326e+00 , 9.8768999999999996e-01 , -4.9053399999999997e-02 , 1.9802900000000001e-01 , 9.7896799999999995e-01 -5.3839452176075602e+00 , 4.2131065183416467e+00 , 9.7938039999999993e-01 , 2.0358599999999999e-01 , -1.4459500000000000e-01 , -9.6832099999999999e-01 -5.4961858476236483e+00 , 4.3029236520380172e+00 , 9.7480856000000005e-01 , -7.6179300000000005e-01 , 8.5699899999999996e-02 , 6.4212700000000000e-01 -5.4945061304406604e+00 , 4.3205803011908204e+00 , 1.0515657599999999e+00 , 9.4518800000000003e-01 , 7.7837900000000002e-02 , -3.1711200000000000e-01 -5.4917931007586507e+00 , 4.3371573425632892e+00 , 1.1279974400000001e+00 , 9.9849500000000002e-01 , 4.5083900000000003e-02 , 3.1224499999999999e-02 -5.4950736227848545e+00 , 4.3587694856508126e+00 , 1.1990710400000000e+00 , 9.9629100000000004e-01 , 4.0237700000000001e-02 , 7.6060400000000000e-02 -5.4822996157337247e+00 , 4.3681286422376893e+00 , 1.2796564799999999e+00 , 9.9586399999999997e-01 , 6.2421999999999998e-02 , 6.6017999999999993e-02 -5.4755151661815198e+00 , 4.3824902563013524e+00 , 1.3547819200000000e+00 , 9.9622599999999994e-01 , 5.7176200000000003e-02 , 6.5301399999999996e-02 -5.4676735825181870e+00 , 4.3947381158780683e+00 , 1.4296868800000000e+00 , 9.9710600000000005e-01 , 5.7861999999999997e-02 , 4.9308299999999999e-02 -5.4588634168503649e+00 , 4.4068957494021346e+00 , 1.5039605599999999e+00 , 9.9167200000000000e-01 , 1.2596499999999999e-01 , -2.6836200000000001e-02 -5.4569105797258697e+00 , 4.4221306645527090e+00 , 1.5739171999999999e+00 , 9.8648700000000000e-01 , 1.5291399999999999e-01 , 5.8833900000000001e-02 -5.4381624395618022e+00 , 4.4268300591082275e+00 , 1.6512308000000000e+00 , -9.8052899999999998e-01 , -1.1949000000000000e-01 , -1.5583400000000000e-01 -5.4173763244286643e+00 , 4.4293335996555179e+00 , 1.7276926399999999e+00 , 9.9293299999999995e-01 , -2.1145100000000000e-02 , -1.1677999999999999e-01 -5.4281669216507833e+00 , 4.4539961698068629e+00 , 1.7891857600000001e+00 , 9.3948699999999996e-01 , -8.6986999999999995e-02 , -3.3135700000000001e-01 -5.4624321733190868e+00 , 4.4948246762809889e+00 , 1.8410214400000000e+00 , -8.8027999999999995e-01 , 1.4566999999999999e-01 , 4.5153900000000002e-01 -5.4954572256895933e+00 , 4.5349136518080018e+00 , 1.8942528000000001e+00 , 6.2317100000000003e-01 , -1.8416199999999999e-01 , -7.6009400000000005e-01 -5.6094869024370277e+00 , 4.6316619765790046e+00 , 1.9191422880000000e+00 , -4.1572199999999998e-01 , 1.2987000000000001e-01 , 9.0017199999999997e-01 -5.7151658913865973e+00 , 4.7239054792733226e+00 , 1.9515669920000001e+00 , -1.7057200000000000e-01 , 1.7995800000000001e-01 , 9.6877300000000000e-01 -6.7250790366721116e+00 , 5.5587373031859482e+00 , 2.0628157919999999e+00 , 9.9224400000000001e-01 , 1.2229000000000000e-01 , 2.2293000000000000e-02 -1.3183778491715168e+01 , 1.0381084687942311e+01 , 7.5595199999999996e-01 , -4.8232600000000000e-02 , 1.9129399999999999e-01 , 9.8034699999999997e-01 -1.4822793907633670e+01 , 1.1666435422601664e+01 , 6.6561759999999981e-01 , 7.3171000000000000e-02 , -1.8660700000000000e-01 , -9.7970599999999997e-01 -1.9536433294868313e+01 , 1.5380021075821146e+01 , 4.7681600000000013e-01 , -1.7334400000000000e-01 , 1.7615000000000000e-01 , 9.6898099999999998e-01 -2.2671626299056118e+01 , 1.7870662784501835e+01 , 4.3235599999999996e-01 , -1.3978099999999999e-01 , 2.6313300000000001e-01 , 9.5457999999999998e-01 -2.4998702931317947e+01 , 1.9774197502877353e+01 , 6.1122559999999981e-01 , -5.2396399999999999e-01 , 4.8670000000000002e-01 , 6.9898899999999997e-01 -4.4838394493725254e+01 , 3.5518134287122393e+01 , 2.6539439999999992e-01 , 1.5840499999999999e-01 , 9.2815999999999999e-01 , -3.3678799999999998e-01 -4.4765165549347259e+01 , 3.5693024094101773e+01 , 1.1862790400000001e+00 , 1.5840499999999999e-01 , 9.2815999999999999e-01 , -3.3678799999999998e-01 -4.4736696114692897e+01 , 3.5903091451895563e+01 , 2.1067705600000002e+00 , 1.5648899999999999e-01 , 9.5298000000000005e-01 , -2.5950200000000001e-01 -4.4630148225775748e+01 , 3.6051277509347997e+01 , 3.0306139999999999e+00 , 1.5648899999999999e-01 , 9.5298000000000005e-01 , -2.5950200000000001e-01 -4.4598904721432476e+01 , 3.6261419226815889e+01 , 3.9561152000000002e+00 , -2.3164899999999999e-01 , -9.7208600000000001e-01 , 3.7252399999999998e-02 -2.4683697131610884e+01 , 2.0387994587867919e+01 , 4.0332831999999996e+00 , -5.9054200000000001e-01 , 4.2127500000000001e-01 , -6.8832199999999999e-01 -2.4372173095332876e+01 , 2.0260115243089132e+01 , 4.5073463999999994e+00 , 9.3827400000000005e-01 , -1.9142000000000001e-01 , 2.8809899999999999e-01 -2.3840789535947728e+01 , 1.9947914395660469e+01 , 4.9519775999999993e+00 , -7.9206500000000002e-01 , 4.5235100000000000e-01 , -4.0989100000000001e-01 -2.3929085928499902e+01 , 2.0143131526359266e+01 , 5.4445840000000008e+00 , 8.0615000000000003e-01 , 1.9337199999999999e-01 , 5.5922300000000003e-01 -2.3372461837701223e+01 , 1.9803636084777867e+01 , 5.8597935999999997e+00 , -9.2771400000000004e-01 , 3.6921100000000001e-01 , -5.5051700000000002e-02 -2.3312207280070034e+01 , 1.9875783496960629e+01 , 6.3311528000000008e+00 , -8.2577500000000004e-01 , 5.6385600000000002e-01 , 1.2724500000000000e-02 -2.3025669096166226e+01 , 1.9755515800960801e+01 , 6.7641359999999997e+00 , -9.3795799999999996e-01 , 3.0623699999999998e-01 , 1.6264600000000001e-01 -4.2664804814258950e+01 , 3.6556878405098317e+01 , 1.1223760000000000e+01 , 1.1374700000000000e-01 , -9.7991099999999998e-01 , 1.6381899999999999e-01 -4.6016811628969592e+01 , 3.9665129435767078e+01 , 1.2936016000000000e+01 , 1.1269100000000000e-01 , -9.7803600000000002e-01 , 1.7534700000000000e-01 -6.3556488145320831e+00 , 6.4925815599791079e+00 , 6.9194392000000002e+00 , -8.5886599999999994e-02 , -8.3157700000000001e-01 , 5.4872900000000002e-01 -6.1079719921884230e+00 , 6.2726330448248850e+00 , 6.8289800000000005e+00 , -4.4925599999999999e-01 , -3.0475400000000002e-01 , 8.3981799999999995e-01 -5.6194372922243616e+00 , 5.7902502428795568e+00 , 6.4649072000000007e+00 , -4.2708900000000000e-01 , 4.3119999999999999e-02 , 9.0318100000000001e-01 -5.5735797116948618e+00 , 5.7765082225513646e+00 , 6.5555640000000004e+00 , -4.2708900000000000e-01 , 4.3119999999999999e-02 , 9.0318100000000001e-01 -5.4930191185204311e+00 , 5.7255629906015155e+00 , 6.6070440000000001e+00 , -1.6277100000000001e-03 , 1.6446200000000000e-01 , 9.8638199999999998e-01 -5.7921343315569711e+00 , 6.0922223863296301e+00 , 7.1151879999999998e+00 , 9.0028799999999998e-01 , -5.4468199999999998e-03 , -4.3525999999999998e-01 -5.8312344602662076e+00 , 6.1788752712711084e+00 , 7.3322672000000004e+00 , -9.6862400000000004e-01 , -1.8024100000000001e-01 , 1.7111399999999999e-01 -5.8812160310714230e+00 , 6.2795870060201597e+00 , 7.5740255999999997e+00 , -5.0538099999999997e-01 , -8.4961299999999995e-01 , 1.5082300000000001e-01 -5.8428072700283220e+00 , 6.2830175455599377e+00 , 7.7093607999999998e+00 , -7.7861400000000003e-01 , -4.4879999999999998e-01 , -4.3856499999999998e-01 -5.7321053884396171e+00 , 6.2038267329276620e+00 , 7.7459167999999998e+00 , 7.5579499999999999e-01 , 4.5120100000000002e-01 , 4.7454299999999999e-01 -5.6861905795949088e+00 , 6.1995279797184244e+00 , 7.8728800000000003e+00 , -7.8364999999999996e-01 , 3.3669999999999999e-02 , 6.2028899999999998e-01 -6.0172326635793532e+00 , 6.6434169145379762e+00 , 8.5866943999999990e+00 , 5.4924200000000001e-01 , -3.1229899999999999e-01 , -7.7511500000000000e-01 -6.5437257052712052e+00 , 7.3391668112063559e+00 , 9.6700520000000001e+00 , 5.8621000000000001e-01 , 1.1879800000000000e-01 , -8.0140199999999995e-01 -5.9827385974146541e+00 , 6.7241182553926695e+00 , 9.0115240000000014e+00 , 4.9810300000000002e-02 , 1.7775500000000000e-02 , 9.9860099999999996e-01 -5.7346721326542793e+00 , 6.4814882097171802e+00 , 8.8347344000000003e+00 , -9.2259500000000005e-01 , -3.8505600000000001e-01 , -2.3446800000000000e-02 -5.7160667119910418e+00 , 6.5222320473609763e+00 , 9.0540704000000005e+00 , -8.8658399999999998e-02 , -1.3429500000000000e-01 , -9.8696700000000004e-01 -4.7965422272524805e+00 , 5.4121020433063682e+00 , 7.5640832000000007e+00 , 2.4916300000000000e-01 , 3.3421400000000001e-01 , 9.0896600000000005e-01 -4.7460192829063619e+00 , 5.3978706024447067e+00 , 7.6671056000000002e+00 , -4.1950399999999999e-01 , -3.9766400000000002e-01 , 8.1601400000000002e-01 -4.6901253808274355e+00 , 5.3768414146450958e+00 , 7.7616103999999995e+00 , -3.0833100000000002e-01 , -6.2633700000000003e-01 , 7.1598499999999998e-01 -4.2819055892387059e+00 , 4.8807616953640363e+00 , 7.0884912000000000e+00 , -4.5213600000000000e-02 , 6.1611800000000005e-01 , -7.8635500000000003e-01 -4.1392511587844947e+00 , 4.7326343502268715e+00 , 6.9552775999999996e+00 , -2.2760100000000000e-01 , 3.8835199999999997e-01 , 8.9296200000000003e-01 -4.0588931434162348e+00 , 4.6673409563044057e+00 , 6.9513775999999998e+00 , 7.3295399999999999e-01 , -9.8427600000000004e-02 , -6.7312000000000005e-01 -4.1406516559910420e+00 , 4.8354998474514241e+00 , 7.3554904000000008e+00 , -1.1469400000000000e-01 , 9.2571000000000003e-01 , 3.6042500000000000e-01 -4.0420708966880881e+00 , 4.7470297624180464e+00 , 7.3169272000000003e+00 , 4.1960399999999998e-01 , 8.3093200000000000e-01 , 3.6535699999999999e-01 -4.0403351387385289e+00 , 4.8010831903457962e+00 , 7.5374280000000002e+00 , 2.9375699999999999e-01 , 6.9256200000000001e-01 , 6.5883599999999998e-01 -3.9720893454400183e+00 , 4.7581204498175564e+00 , 7.5836872000000000e+00 , 1.2397500000000000e-01 , 8.3706700000000001e-01 , 5.3286900000000004e-01 -3.9147043049728971e+00 , 4.7332447442905394e+00 , 7.6640480000000002e+00 , -5.7960800000000001e-01 , -8.0623400000000001e-01 , -1.1849899999999999e-01 -3.8966254680876720e+00 , 4.7730660079238980e+00 , 7.8789328000000003e+00 , -7.3585599999999995e-01 , -5.4275899999999999e-01 , -4.0488099999999999e-01 -3.8814645752301651e+00 , 4.8217875913768520e+00 , 8.1227920000000005e+00 , -2.0925800000000000e-01 , 6.8578700000000004e-01 , 6.9707100000000000e-01 -3.7586683048724860e+00 , 4.6914912872855847e+00 , 7.9927296000000005e+00 , -1.0620200000000000e-01 , 3.4368700000000002e-01 , 9.3306000000000000e-01 -3.6647236958443310e+00 , 4.6053298830334075e+00 , 7.9508072000000007e+00 , 7.2063500000000003e-01 , -3.1090800000000002e-01 , 6.1969500000000000e-01 -3.6128935565928448e+00 , 4.5980705200054608e+00 , 8.0829287999999995e+00 , 7.2063500000000003e-01 , -3.1090800000000002e-01 , 6.1969500000000000e-01 -3.6699088411459009e+00 , 4.8079893082579996e+00 , 8.7312024000000008e+00 , -7.9061300000000001e-01 , -4.7298699999999999e-01 , 3.8886300000000001e-01 -3.7089803741857796e+00 , 5.0042958854559974e+00 , 9.3871199999999995e+00 , 7.3285800000000001e-01 , -5.3620699999999999e-01 , 4.1881000000000002e-01 -3.1301577933508402e+00 , 3.8845451260730797e+00 , 6.7836880000000006e+00 , 2.9774899999999999e-01 , 2.6131800000000000e-02 , 9.5428599999999997e-01 -3.0721059631311869e+00 , 3.8392450217077632e+00 , 6.7888776000000002e+00 , 2.6353900000000002e-01 , 3.8460599999999998e-02 , 9.6388200000000002e-01 -3.0193063250213217e+00 , 3.8056211133789084e+00 , 6.8215544000000010e+00 , -4.1631000000000001e-01 , -1.1204200000000000e-01 , -9.0229300000000001e-01 -3.3453590735056791e+00 , 4.7782896064164264e+00 , 9.6371256000000010e+00 , 7.8523900000000002e-01 , 4.9424699999999999e-01 , -3.7298700000000001e-01 -3.3145341055974225e+00 , 4.8982120962872377e+00 , 1.0209926400000001e+01 , -5.6985500000000000e-01 , 8.1734200000000001e-01 , -8.4955900000000001e-02 -3.0075687212546400e+00 , 4.1790276822679626e+00 , 8.3351183999999989e+00 , -8.4577000000000002e-01 , -3.9863100000000001e-01 , 3.5463699999999998e-01 -2.7848310336081923e+00 , 3.5985463555802619e+00 , 6.7450728000000000e+00 , -8.7616400000000005e-01 , 1.2907200000000001e-02 , -4.8184100000000002e-01 -2.7298826600121986e+00 , 3.5535676188216927e+00 , 6.7420048000000001e+00 , 5.6063700000000001e-02 , -4.5527899999999999e-01 , 8.8858199999999998e-01 -2.6760758154547508e+00 , 3.5123645304668489e+00 , 6.7473816000000006e+00 , -9.3716800000000003e-02 , 2.8657300000000002e-01 , 9.5346399999999998e-01 -2.6224926825679109e+00 , 3.4678853837046448e+00 , 6.7418072000000002e+00 , -1.7425199999999999e-01 , -2.2527800000000001e-01 , 9.5858600000000005e-01 -2.5684219771884669e+00 , 3.4160066726018292e+00 , 6.7046688000000003e+00 , -8.3153000000000005e-02 , -5.9446900000000003e-01 , 7.9980799999999996e-01 -2.5175710050386590e+00 , 3.3883276054643363e+00 , 6.7566687999999999e+00 , -1.8570700000000001e-01 , 8.7908699999999995e-01 , -4.3899800000000000e-01 -2.4645652398610616e+00 , 3.3410473278344428e+00 , 6.7373040000000008e+00 , 2.6179799999999998e-01 , -8.5826899999999995e-01 , 4.4140299999999999e-01 -2.4126311492587131e+00 , 3.2965628897246875e+00 , 6.7267999999999999e+00 , -3.1837199999999999e-01 , 9.3557299999999999e-01 , -1.5278300000000000e-01 -2.3483094614552504e+00 , 3.3754200358368536e+00 , 7.2414960000000006e+00 , -3.0962899999999999e-01 , -8.3024900000000001e-01 , -4.6348400000000001e-01 -2.2584890681388683e+00 , 3.5084904266824957e+00 , 8.0514584000000013e+00 , 2.3403600000000000e-02 , 9.5884300000000000e-01 , 2.8297000000000000e-01 -2.1901890714324757e+00 , 3.4444422119405660e+00 , 8.0088495999999996e+00 , 5.4428699999999997e-01 , 2.5563000000000002e-01 , -7.9900199999999999e-01 -2.1227929759186948e+00 , 3.3841745336732121e+00 , 7.9852416000000002e+00 , 1.3954900000000001e-01 , -2.7019700000000002e-01 , -9.5263799999999998e-01 -2.0515576079575526e+00 , 3.3371039734431163e+00 , 8.0209864000000000e+00 , -1.2411999999999999e-01 , 1.9494600000000001e-01 , -9.7292900000000004e-01 -1.9855810506482798e+00 , 3.2772407765794647e+00 , 7.9943624000000009e+00 , 6.3329299999999999e-01 , -2.2070000000000001e-01 , 7.4177599999999999e-01 -1.7148374245448657e+00 , 3.5317054737986417e+00 , 9.8531128000000017e+00 , -2.7548499999999998e-01 , -2.9213499999999998e-01 , 9.1584100000000002e-01 -4.7969219096770797e+00 , 3.4363843395031353e+00 , 1.4004320000000003e-01 , 4.1663000000000000e-01 , -8.8790899999999995e-01 , 1.9503400000000001e-01 -4.3982959264886503e+00 , 3.3619128709644013e+00 , 1.0450907199999999e+00 , -1.2955500000000000e-01 , 1.6024800000000000e-01 , 9.7853800000000002e-01 -4.4637322148438079e+00 , 3.4100978664381287e+00 , 1.0399655999999999e+00 , -9.3049400000000004e-02 , 1.5400200000000000e-01 , 9.8367899999999997e-01 -4.5227606188050302e+00 , 3.4550823343402866e+00 , 1.0439394399999999e+00 , -2.0692100000000001e-02 , 1.8274699999999999e-01 , 9.8294199999999998e-01 -4.6030693866916135e+00 , 3.5114053744490423e+00 , 1.0296945600000000e+00 , -5.0409299999999997e-02 , 1.9478000000000001e-01 , 9.7955099999999995e-01 -4.6708640994253452e+00 , 3.5619328909768795e+00 , 1.0314188799999999e+00 , -8.7563500000000002e-02 , 1.7773500000000000e-01 , 9.8017500000000002e-01 -4.7445205461114250e+00 , 3.6176746520031542e+00 , 1.0286951200000001e+00 , -7.8257900000000005e-02 , 1.5559899999999999e-01 , 9.8471600000000004e-01 -4.8117589919576442e+00 , 3.6691664773351911e+00 , 1.0350734399999999e+00 , -4.1654299999999998e-02 , 1.8285199999999999e-01 , 9.8225799999999996e-01 -4.9092930696330770e+00 , 3.7381963080335403e+00 , 1.0190564000000000e+00 , -3.0856200000000000e-02 , 1.9388600000000000e-01 , 9.8053900000000005e-01 -4.9922414321246276e+00 , 3.8003432040137124e+00 , 1.0184584000000001e+00 , -6.5400700000000006e-02 , 1.7525399999999999e-01 , 9.8234900000000003e-01 -5.0748537064614094e+00 , 3.8631011090872898e+00 , 1.0207942399999999e+00 , -7.2347700000000001e-02 , 1.7863499999999999e-01 , 9.8125200000000001e-01 -5.1733242522308842e+00 , 3.9351540481708684e+00 , 1.0147393599999999e+00 , -5.4464199999999997e-02 , 1.8767400000000001e-01 , 9.8072000000000004e-01 -5.2724490473011461e+00 , 4.0089525617995232e+00 , 1.0121456000000000e+00 , -5.5820000000000002e-02 , 1.9830999999999999e-01 , 9.7854900000000000e-01 -5.3792607566166879e+00 , 4.0883841152989486e+00 , 1.0075810399999998e+00 , -1.2127700000000000e-01 , 1.8890999999999999e-01 , 9.7447700000000004e-01 -5.4946489066729782e+00 , 4.1725678722178881e+00 , 1.0020846400000001e+00 , 5.9786499999999998e-01 , -2.2721500000000000e-01 , -7.6871999999999996e-01 -5.5323292627496476e+00 , 4.2138764241481521e+00 , 1.0517664799999999e+00 , 9.1023900000000002e-01 , 8.4898200000000004e-03 , -4.1399599999999998e-01 -5.5456957163135918e+00 , 4.2393901034736219e+00 , 1.1179863999999999e+00 , 9.9023700000000003e-01 , 3.1287700000000002e-02 , -1.3583400000000001e-01 -5.5259960537611761e+00 , 4.2468466185605047e+00 , 1.2034931200000001e+00 , 9.9720100000000000e-01 , 7.1978299999999995e-02 , 2.0253500000000001e-02 -5.5132732863976770e+00 , 4.2561100467064072e+00 , 1.2836740000000000e+00 , 9.9425200000000002e-01 , 9.0820200000000004e-02 , 5.6693700000000000e-02 -5.5075742232397165e+00 , 4.2703521107169919e+00 , 1.3584198399999998e+00 , 9.7613899999999998e-01 , 1.7158899999999999e-01 , -1.3307600000000000e-01 -5.4998444774364694e+00 , 4.2835140089652377e+00 , 1.4326134399999999e+00 , -9.7738000000000003e-01 , -2.1143100000000001e-01 , 4.9769300000000001e-03 -5.4910876176173176e+00 , 4.2955657213559197e+00 , 1.5063806399999999e+00 , -9.7913600000000001e-01 , -1.9596900000000000e-01 , 5.3742499999999999e-02 -5.4813138364746710e+00 , 4.3065093140500785e+00 , 1.5797214400000001e+00 , 9.8678699999999997e-01 , 1.3537700000000000e-01 , 8.9018200000000006e-02 -5.5358148475054030e+00 , 4.3572337041202225e+00 , 1.6217447199999999e+00 , -9.7363299999999997e-01 , -1.5857900000000000e-01 , -1.6398499999999999e-01 -5.4340611165345756e+00 , 4.3092294698145235e+00 , 1.7359710399999999e+00 , 9.9275700000000000e-01 , 3.0158500000000001e-02 , 1.1629399999999999e-01 -5.4538358677246617e+00 , 4.3379416381730813e+00 , 1.7930920000000001e+00 , 8.8699300000000003e-01 , -6.6049899999999998e-03 , -4.6173500000000001e-01 -5.4813794890376819e+00 , 4.3721442868214675e+00 , 1.8475339200000001e+00 , -8.7836499999999995e-01 , 2.9988100000000000e-02 , 4.7704999999999997e-01 -5.5077136272429232e+00 , 4.4055605733827718e+00 , 1.9030666960000000e+00 , -6.7101800000000000e-01 , 6.7454899999999998e-02 , 7.3836599999999997e-01 -5.5994978606578325e+00 , 4.4824870944321313e+00 , 1.9355202080000000e+00 , -4.3561600000000000e-01 , 1.3124600000000000e-01 , 8.9051300000000000e-01 -5.7074545324421635e+00 , 4.5710325888917049e+00 , 1.9658776000000000e+00 , -3.0145200000000000e-01 , 1.3453799999999999e-01 , 9.4394199999999995e-01 -5.9651297841271411e+00 , 4.7611308679546234e+00 , 1.9524992480000001e+00 , -9.1904399999999997e-02 , 1.8454200000000001e-01 , 9.7851800000000000e-01 -6.7760614988690397e+00 , 5.3941834330720582e+00 , 2.0580226399999999e+00 , -9.9408300000000005e-01 , -1.0335500000000000e-01 , 3.3424599999999999e-02 -1.2796321940527410e+01 , 9.6101414165158801e+00 , 8.5219359999999988e-01 , -5.2806100000000002e-02 , 1.8919000000000000e-01 , 9.8051999999999995e-01 -1.4264398823692655e+01 , 1.0692839547362686e+01 , 7.8409439999999986e-01 , -5.8458999999999997e-02 , 1.9094700000000001e-01 , 9.7985800000000001e-01 -1.5880123103880251e+01 , 1.1896259486538751e+01 , 7.5134479999999981e-01 , -7.7971899999999997e-02 , 1.8998599999999999e-01 , 9.7868599999999994e-01 -2.3191478421681001e+01 , 1.7386996330198457e+01 , 7.8851439999999995e-01 , -2.7230100000000002e-01 , 3.5839599999999999e-01 , 8.9297499999999996e-01 -4.7622174087073141e+01 , 3.5740849390184231e+01 , 9.4768639999999982e-01 , 3.4888000000000002e-01 , 9.2182500000000001e-01 , -1.6888100000000000e-01 -4.7556924280535775e+01 , 3.5929772131543857e+01 , 1.9084057440000000e+00 , -3.4888000000000002e-01 , -9.2182500000000001e-01 , 1.6888100000000000e-01 -4.7493628984910785e+01 , 3.6120046109038796e+01 , 2.8705850399999999e+00 , 3.4888000000000002e-01 , 9.2182500000000001e-01 , -1.6888100000000000e-01 -2.4091745400590391e+01 , 1.8717762492135762e+01 , 3.4432391999999998e+00 , -4.4726300000000002e-01 , 6.3604400000000005e-02 , -8.9213799999999999e-01 -2.3887521024540085e+01 , 1.8677743659733231e+01 , 3.9017439999999999e+00 , 5.3921300000000005e-01 , 4.2216599999999999e-01 , 7.2871500000000000e-01 -2.3000306320718341e+01 , 1.8114926434912860e+01 , 4.3131991999999997e+00 , -7.3942699999999995e-01 , 4.4180599999999998e-01 , -5.0799099999999997e-01 -2.3190605101626193e+01 , 1.8372311532167899e+01 , 4.7774239999999999e+00 , -4.2455799999999999e-01 , 8.5549600000000003e-01 , -2.9644100000000001e-01 -2.2889302650827272e+01 , 1.8251067160659105e+01 , 5.2023576000000000e+00 , -9.6819299999999997e-01 , -1.7659900000000001e-01 , 1.7724000000000001e-01 -2.3495907836146714e+01 , 1.8837119026124586e+01 , 5.7319984000000002e+00 , -8.0113500000000004e-01 , -2.9918099999999997e-01 , 5.1833600000000002e-01 -2.3198696218282421e+01 , 1.8719250673262209e+01 , 6.1586375999999996e+00 , -8.9420500000000003e-01 , -1.2192699999999999e-01 , 4.3073299999999998e-01 -2.3170183527776910e+01 , 1.8812794729279339e+01 , 6.6222488000000004e+00 , -9.2434899999999998e-01 , -2.0893300000000001e-01 , 3.1925999999999999e-01 -2.3963865057098520e+01 , 1.9562197060611261e+01 , 7.2486200000000007e+00 , -9.5121199999999995e-01 , -3.0094599999999999e-01 , 6.8031099999999997e-02 -2.3749019674640245e+01 , 1.9512278831111836e+01 , 7.6980767999999999e+00 , 9.3985500000000000e-01 , 3.2942500000000002e-01 , -9.0288700000000000e-02 -4.6523083669152427e+01 , 3.8060149418959043e+01 , 1.3663600000000001e+01 , 1.1374700000000000e-01 , -9.7991099999999998e-01 , 1.6381899999999999e-01 -6.4284411197445452e+00 , 6.2793805324564058e+00 , 6.6936863999999998e+00 , 6.3341899999999995e-01 , -1.5330300000000000e-02 , 7.7365700000000004e-01 -6.4139303882705621e+00 , 6.3040078008832934e+00 , 6.8338784000000006e+00 , 4.8491600000000001e-01 , 1.2521599999999999e-01 , 8.6555099999999996e-01 -6.2886988540716473e+00 , 6.2175527915916051e+00 , 6.8681880000000000e+00 , 2.2567999999999999e-01 , -3.7423900000000003e-02 , 9.7348199999999996e-01 -6.4490145351731112e+00 , 6.4180626482926018e+00 , 7.1913888000000004e+00 , -5.9692500000000004e-01 , -6.2051900000000004e-01 , 5.0856400000000002e-01 -5.6372998515897175e+00 , 5.6369055001013351e+00 , 6.4929144000000001e+00 , -6.5629700000000002e-01 , 1.1755300000000000e-01 , 7.4528899999999998e-01 -5.7107025390135533e+00 , 5.7477131383214441e+00 , 6.7160048000000003e+00 , 8.1550100000000003e-01 , -4.7918599999999999e-02 , -5.7676799999999995e-01 -5.4410216164332148e+00 , 5.5045536083411912e+00 , 6.5530264000000003e+00 , 1.0364700000000000e-01 , 2.0319700000000000e-02 , 9.9440700000000004e-01 -5.4048260950175973e+00 , 5.5016201953645432e+00 , 6.6519824000000005e+00 , -1.0526199999999999e-01 , 2.8958000000000000e-01 , 9.5134799999999997e-01 -5.8795561544085402e+00 , 6.0421572519126672e+00 , 7.3965600000000000e+00 , 9.8478100000000002e-01 , -9.7771800000000006e-02 , -1.4369199999999999e-01 -5.7122782616882857e+00 , 5.9062503757727516e+00 , 7.3556360000000005e+00 , -8.6784499999999998e-01 , -6.2016500000000002e-02 , -4.9295000000000000e-01 -5.9776653640877857e+00 , 6.2380689331932739e+00 , 7.8944704000000003e+00 , 7.9325900000000005e-01 , 4.5814100000000002e-01 , 4.0105700000000000e-01 -5.8672919357344444e+00 , 6.1666805023148079e+00 , 7.9382127999999996e+00 , -7.8364800000000001e-01 , 3.3672199999999999e-02 , 6.2029100000000004e-01 -5.7185025096388351e+00 , 6.0505978827417675e+00 , 7.9205952000000002e+00 , -7.8364999999999996e-01 , 3.3670199999999997e-02 , 6.2028899999999998e-01 -6.0205146182503730e+00 , 6.4420706175379632e+00 , 8.5894295999999990e+00 , -9.6294400000000002e-01 , 7.6564499999999994e-02 , -2.5860499999999997e-01 -5.8696038635876144e+00 , 6.3268207547302513e+00 , 8.5806936000000000e+00 , 7.2509500000000005e-01 , -5.9158299999999997e-01 , 3.5251600000000000e-01 -5.9357143174553046e+00 , 6.4629230590474362e+00 , 8.9277936000000011e+00 , -4.9611499999999997e-01 , -1.6186600000000001e-01 , -8.5303499999999999e-01 -5.8412472787783170e+00 , 6.4136793602545916e+00 , 9.0163080000000004e+00 , 2.4854499999999999e-01 , 4.6956600000000001e-02 , 9.6748100000000004e-01 -5.7809235937990930e+00 , 6.4050802851341260e+00 , 9.1662968000000014e+00 , -5.2997499999999997e-01 , -8.1282699999999997e-01 , -2.4174000000000001e-01 -4.3991566942274591e+00 , 4.7845239462463613e+00 , 6.7992464000000004e+00 , 6.3689899999999999e-01 , 5.2040600000000004e-01 , 5.6880399999999998e-01 -4.3520100336916636e+00 , 4.7676661165117116e+00 , 6.8741368000000005e+00 , 7.4746000000000001e-01 , 3.9143200000000000e-01 , 5.3673499999999996e-01 -4.3983300744735523e+00 , 4.8693228546937135e+00 , 7.1461591999999996e+00 , 5.8939100000000000e-01 , 2.6638800000000001e-01 , -7.6266400000000001e-01 -4.2882977120244448e+00 , 4.7750508349120828e+00 , 7.0974976000000005e+00 , 5.9502699999999997e-01 , -1.7613699999999999e-01 , -7.8416699999999995e-01 -4.1765107204252043e+00 , 4.6762952513620322e+00 , 7.0367303999999997e+00 , 6.7955100000000002e-01 , 5.6692800000000002e-02 , -7.3143400000000003e-01 -4.2666032755201098e+00 , 4.8459525291324574e+00 , 7.4500679999999999e+00 , 2.6369700000000001e-01 , 8.5530200000000001e-01 , 4.4600800000000002e-01 -4.2087959261165331e+00 , 4.8211185556337846e+00 , 7.5252495999999995e+00 , 9.7410399999999994e-02 , 8.8001700000000005e-01 , 4.6484500000000001e-01 -4.1329049561319220e+00 , 4.7721598325173193e+00 , 7.5559191999999999e+00 , 1.1359900000000001e-01 , 7.9619700000000004e-01 , 5.9427799999999997e-01 -4.0507905823591503e+00 , 4.7132275018043250e+00 , 7.5673903999999999e+00 , -2.9657899999999998e-01 , -7.1235800000000005e-01 , -6.3607199999999997e-01 -4.0083171634418182e+00 , 4.7126294141578962e+00 , 7.6923880000000002e+00 , 4.4908199999999998e-01 , 8.6154799999999998e-01 , 2.3677100000000001e-01 -4.0432373654040425e+00 , 4.8316808906525512e+00 , 8.0693672000000003e+00 , 3.0767499999999998e-01 , 9.5089199999999996e-01 , 3.3766699999999997e-02 -3.9200682965431612e+00 , 4.7121752171265499e+00 , 7.9611967999999997e+00 , -1.2717300000000001e-01 , 8.0828999999999995e-01 , -5.7488600000000001e-01 -3.8658871147573741e+00 , 4.7007570753593679e+00 , 8.0774271999999989e+00 , -4.6619100000000002e-01 , -8.5329100000000002e-01 , 2.3358200000000001e-01 -3.7676391067788391e+00 , 4.6160896988023374e+00 , 8.0367215999999999e+00 , 1.8691199999999999e-01 , -4.7338300000000000e-01 , 8.6079700000000003e-01 -3.6593808860993633e+00 , 4.5133273043563449e+00 , 7.9463040000000005e+00 , -1.1502000000000000e-01 , -3.0748999999999999e-01 , 9.4457400000000002e-01 -3.7260242818318270e+00 , 4.7235954672458469e+00 , 8.5930800000000005e+00 , 7.8962399999999999e-01 , -1.6434099999999999e-01 , 5.9117299999999995e-01 -3.6756123299184082e+00 , 4.7325302594806535e+00 , 8.7847624000000000e+00 , -7.9061300000000001e-01 , -4.7298699999999999e-01 , 3.8886300000000001e-01 -3.6608920649048873e+00 , 4.8203809593691105e+00 , 9.1860672000000001e+00 , 7.8927700000000001e-01 , -5.9563600000000005e-01 , 1.4920000000000000e-01 -3.1226547513200056e+00 , 3.8216259063655569e+00 , 6.7754928000000003e+00 , 3.1000600000000000e-01 , -9.6478799999999993e-03 , 9.5068600000000003e-01 -3.0688058072814499e+00 , 3.7891475682650237e+00 , 6.8083463999999996e+00 , -4.3364399999999997e-01 , -7.7228800000000000e-02 , -8.9776900000000004e-01 -3.3706412004160056e+00 , 4.6102769218819244e+00 , 9.2143864000000004e+00 , 7.0261499999999999e-01 , 1.9134799999999999e-01 , 6.8535999999999997e-01 -3.3576855358534363e+00 , 4.7536015795809474e+00 , 9.8334256000000000e+00 , 8.5818399999999995e-01 , -5.0872600000000001e-01 , 6.8690000000000001e-02 -3.1912505935396629e+00 , 4.5023485278211517e+00 , 9.3202895999999988e+00 , 4.5476600000000000e-01 , 6.4553700000000002e-03 , 8.9058800000000005e-01 -3.0002822448215536e+00 , 4.1300640705279159e+00 , 8.3962184000000004e+00 , 9.7721599999999997e-01 , 2.1140900000000001e-01 , 1.8853600000000002e-02 -2.7627932068286287e+00 , 3.5138877801585480e+00 , 6.6205639999999999e+00 , 8.6176299999999995e-01 , -4.9174000000000001e-01 , -1.2472300000000000e-01 -2.7183580040330617e+00 , 3.5080743873422278e+00 , 6.7350783999999999e+00 , 1.5573200000000001e-01 , 1.5257799999999999e-01 , 9.7594400000000003e-01 -2.6723247195547581e+00 , 3.5144161995404226e+00 , 6.8990656000000001e+00 , -7.0089000000000001e-01 , -5.1321099999999997e-01 , -4.9534699999999998e-01 -2.6082704518072268e+00 , 3.4232460479117610e+00 , 6.7227335999999998e+00 , -3.4785800000000000e-01 , 8.1684400000000001e-01 , -4.6017400000000003e-01 -2.5555828918642165e+00 , 3.3916186024137431e+00 , 6.7547968000000003e+00 , -5.6678900000000001e-03 , -1.2008700000000000e-01 , 9.9274700000000005e-01 -2.5003604371945087e+00 , 3.3281414779809078e+00 , 6.6650864000000007e+00 , 3.6184300000000003e-01 , -8.8367099999999998e-01 , 2.9697800000000002e-01 -2.4480832477751555e+00 , 3.2940080068533897e+00 , 6.6847840000000005e+00 , -2.5243300000000002e-01 , 9.5150199999999996e-01 , -1.7584600000000000e-01 -2.3875970313779251e+00 , 3.3830550632873191e+00 , 7.2297960000000003e+00 , 2.4809700000000001e-01 , 7.1053500000000003e-01 , 6.5847400000000000e-01 -2.3245586734116546e+00 , 3.3622966894670521e+00 , 7.3399631999999997e+00 , 6.2496300000000005e-01 , 7.5542699999999996e-01 , 1.9685300000000000e-01 -2.2336015990529048e+00 , 3.4603626995515619e+00 , 8.0075807999999995e+00 , 6.4048800000000003e-02 , -7.9138100000000000e-01 , 6.0795900000000003e-01 -2.1651502394340838e+00 , 3.4023535937490657e+00 , 7.9843368000000003e+00 , -1.8587699999999999e-01 , -4.3491299999999999e-01 , 8.8107899999999995e-01 -2.0945517932598814e+00 , 3.3491937909004070e+00 , 7.9795112000000001e+00 , -3.3842299999999997e-01 , 3.7295200000000001e-01 , 8.6393100000000000e-01 -2.0251050771445147e+00 , 3.2947181727907124e+00 , 7.9736039999999999e+00 , -3.1063299999999999e-01 , 4.4160100000000002e-01 , -8.4172199999999997e-01 -1.7621363717447114e+00 , 3.5697747754471960e+00 , 9.8835432000000001e+00 , -4.6755300000000000e-01 , -1.6027400000000000e-01 , 8.6931400000000003e-01 -1.7126503036539080e+00 , 3.4315986891556221e+00 , 9.4770384000000014e+00 , -8.4288300000000005e-01 , -5.0956999999999997e-01 , 1.7288000000000001e-01 -4.4148012715202896e+00 , 3.2966127213674321e+00 , 1.0459840800000000e+00 , -7.4535799999999999e-02 , 1.8016299999999999e-01 , 9.8080900000000004e-01 -4.4678959109676768e+00 , 3.3353772271130531e+00 , 1.0547127999999999e+00 , -8.6813500000000002e-02 , 1.7696100000000001e-01 , 9.8038199999999998e-01 -4.5351903155659627e+00 , 3.3816722598726985e+00 , 1.0511601600000000e+00 , 3.3149699999999997e-02 , -1.7903800000000000e-01 , -9.8328400000000005e-01 -4.6094476803413711e+00 , 3.4330885433230840e+00 , 1.0428807199999999e+00 , -5.6987400000000001e-02 , 2.0094999999999999e-01 , 9.7794300000000001e-01 -4.6701294406681306e+00 , 3.4776642953212922e+00 , 1.0504477600000000e+00 , -6.4316899999999996e-02 , 2.0782800000000001e-01 , 9.7604900000000006e-01 -4.7459079915811397e+00 , 3.5300044068589149e+00 , 1.0470729599999999e+00 , -5.4060499999999997e-02 , 2.0167099999999999e-01 , 9.7796000000000005e-01 -4.8295417151760907e+00 , 3.5865716821358897e+00 , 1.0400113599999998e+00 , -6.9607100000000005e-02 , 1.7440400000000000e-01 , 9.8221099999999995e-01 -4.9057632896529277e+00 , 3.6410188497058700e+00 , 1.0419187200000000e+00 , -4.2585999999999999e-02 , 1.9604300000000000e-01 , 9.7967000000000004e-01 -4.9979877635167744e+00 , 3.7045187138095290e+00 , 1.0342227199999998e+00 , 6.5884899999999996e-02 , -1.8502299999999999e-01 , -9.8052300000000003e-01 -5.0827179412550940e+00 , 3.7638433444254265e+00 , 1.0358066400000001e+00 , -8.5203699999999993e-02 , 1.7388899999999999e-01 , 9.8107200000000006e-01 -5.1752333802918784e+00 , 3.8286299434149647e+00 , 1.0345087199999998e+00 , -6.0260399999999999e-02 , 1.8761400000000000e-01 , 9.8039299999999996e-01 -5.2754890394226139e+00 , 3.8989436611418880e+00 , 1.0307345600000000e+00 , -4.7356500000000003e-02 , 1.8986700000000001e-01 , 9.8066699999999996e-01 -5.3844616271831640e+00 , 3.9748869825122974e+00 , 1.0251144000000001e+00 , -8.1986199999999995e-02 , 1.8431800000000001e-01 , 9.7944100000000001e-01 -5.4939971498820270e+00 , 4.0516129424552467e+00 , 1.0234649600000001e+00 , 4.4492500000000001e-01 , -1.8020200000000000e-01 , -8.7725100000000000e-01 -5.5488386797385374e+00 , 4.0984588721853470e+00 , 1.0621581600000001e+00 , -9.3694699999999997e-01 , -9.2723700000000003e-03 , 3.4934900000000002e-01 -5.5473228743108542e+00 , 4.1158304021762655e+00 , 1.1374988799999999e+00 , 9.7423199999999999e-01 , 9.2260399999999996e-03 , -2.2535900000000000e-01 -5.5517346581433991e+00 , 4.1361544154545253e+00 , 1.2076884799999998e+00 , 9.9609099999999995e-01 , 8.4916000000000005e-02 , -2.4328400000000000e-02 -5.5550803471258607e+00 , 4.1554558447848278e+00 , 1.2778572800000001e+00 , 9.9654100000000001e-01 , 8.1941799999999995e-02 , -1.3837900000000000e-02 -5.5414640590576063e+00 , 4.1655674651437176e+00 , 1.3567963999999999e+00 , 9.9663900000000005e-01 , 3.6083400000000002e-02 , -7.3547500000000002e-02 -5.5427205333833651e+00 , 4.1827687689067670e+00 , 1.4266188799999999e+00 , 9.9676799999999999e-01 , -9.9841400000000007e-03 , 7.9707100000000003e-02 -5.5926997346221459e+00 , 4.2287882286899237e+00 , 1.4706826399999999e+00 , 9.9779399999999996e-01 , 5.8395900000000001e-02 , 3.1590600000000003e-02 -5.5173805054513760e+00 , 4.2015080199165071e+00 , 1.5774396799999999e+00 , 9.9024000000000001e-01 , -1.0131800000000001e-01 , 9.5700999999999994e-02 -5.5403122345634239e+00 , 4.2311360390053974e+00 , 1.6345294400000001e+00 , 9.6547700000000003e-01 , -1.8518700000000000e-03 , 2.6048100000000002e-01 -5.4623347954273136e+00 , 4.2009506145463309e+00 , 1.7368685600000000e+00 , 9.8877599999999999e-01 , 8.5431300000000002e-02 , 1.2257100000000000e-01 -5.4832256492016640e+00 , 4.2294964017118417e+00 , 1.7934060800000000e+00 , -9.1418800000000000e-01 , -3.2451199999999999e-02 , 4.0398899999999999e-01 -5.4940814133800391e+00 , 4.2518482581059649e+00 , 1.8539943999999999e+00 , -8.8073199999999996e-01 , 4.3462399999999998e-02 , 4.7161700000000001e-01 -5.5382641547628344e+00 , 4.2946871392722734e+00 , 1.9020960640000000e+00 , -7.7611300000000005e-01 , 1.0287600000000000e-01 , 6.2214499999999995e-01 -5.6077386120965489e+00 , 4.3529991409647710e+00 , 1.9428194480000001e+00 , 5.1929899999999996e-01 , -1.6350300000000001e-01 , -8.3880600000000005e-01 -5.7012760107292468e+00 , 4.4271400350974144e+00 , 1.9776574720000000e+00 , 3.4640799999999999e-01 , -1.6216000000000000e-01 , -9.2396199999999995e-01 -5.8285877490683777e+00 , 4.5238536053805394e+00 , 2.0052925496000000e+00 , 1.2955700000000001e-01 , -2.2251399999999999e-01 , -9.6628300000000000e-01 -6.8275345250595043e+00 , 5.2386214623041489e+00 , 2.0505730160000000e+00 , -9.9346699999999999e-01 , -9.6866800000000003e-02 , 6.0334100000000002e-02 -1.2438958094919986e+01 , 8.9205551666247480e+00 , 9.3710959999999988e-01 , -5.5918900000000001e-02 , 1.8642700000000001e-01 , 9.8087599999999997e-01 -1.3663681569985092e+01 , 9.7756919625822434e+00 , 9.0506719999999996e-01 , -4.8232700000000003e-02 , 1.9129399999999999e-01 , 9.8034699999999997e-01 -1.5237920896761649e+01 , 1.0873861717470374e+01 , 8.6264560000000001e-01 , -7.5518900000000000e-02 , 1.8579899999999999e-01 , 9.7968100000000002e-01 -1.9978593738308913e+01 , 1.4188681316873931e+01 , 7.6111039999999996e-01 , -1.4002500000000001e-01 , 1.6958100000000001e-01 , 9.7551800000000000e-01 -2.2180650155739102e+01 , 1.5767214357181759e+01 , 8.7585359999999990e-01 , -6.7384299999999997e-01 , 2.6272600000000002e-01 , 6.9058699999999995e-01 -2.4638954660026613e+01 , 1.7542676708515156e+01 , 1.0584827999999999e+00 , -4.3137700000000001e-01 , 4.9721700000000002e-01 , 7.5278800000000001e-01 -4.8847086846202572e+01 , 3.4753439530751002e+01 , 1.7365628000000000e+00 , -3.4888000000000002e-01 , -9.2182500000000001e-01 , 1.6888100000000000e-01 -4.8868077934623123e+01 , 3.5002714723898897e+01 , 2.7039718400000003e+00 , -3.4888000000000002e-01 , -9.2182500000000001e-01 , 1.6888100000000000e-01 -2.5662889825144962e+01 , 1.8824018754478701e+01 , 3.3782703999999999e+00 , 1.2893700000000000e-01 , 2.5713200000000003e-01 , 9.5773600000000003e-01 -2.4482184140384426e+01 , 1.8100898484610571e+01 , 3.8271552000000000e+00 , 7.9561000000000004e-01 , -4.2400100000000002e-01 , -4.3269700000000000e-01 -2.4001930219282869e+01 , 1.7868355379611565e+01 , 4.2675536000000003e+00 , 5.3921300000000005e-01 , 4.2216599999999999e-01 , 7.2871500000000000e-01 -2.3239790181340876e+01 , 1.7428730295916637e+01 , 4.6686504000000006e+00 , 5.5979000000000001e-01 , 5.1885499999999996e-01 , 6.4608500000000002e-01 -2.3087721894996530e+01 , 1.7426661758197852e+01 , 5.1000320000000006e+00 , -9.4361600000000001e-01 , -2.1301200000000001e-01 , 2.5340800000000002e-01 -2.4425529064418033e+01 , 1.8513874891645212e+01 , 5.7066432000000002e+00 , 8.0073300000000003e-01 , -6.7196300000000000e-02 , 5.9524100000000002e-01 -2.4305852712400547e+01 , 1.8542036222575899e+01 , 6.1689440000000006e+00 , -8.4403399999999995e-01 , -3.5941600000000001e-01 , -3.9802700000000002e-01 -2.3616617771203359e+01 , 1.8145840848396819e+01 , 6.5374784000000004e+00 , -9.4317300000000004e-01 , -2.9046699999999998e-01 , 1.6141200000000000e-01 -2.3973293720296319e+01 , 1.8526301299296303e+01 , 7.0740248000000001e+00 , -9.0956300000000001e-01 , -2.5907400000000003e-01 , 3.2492300000000002e-01 -2.3859260528941139e+01 , 1.8556986053643584e+01 , 7.5337048000000006e+00 , -9.3134799999999995e-01 , -2.1950600000000001e-01 , 2.9053099999999998e-01 -2.3950840681111050e+01 , 1.8744379616181185e+01 , 8.0407256000000000e+00 , -9.3134799999999995e-01 , -2.1950600000000001e-01 , 2.9053099999999998e-01 -2.3620852734473019e+01 , 1.8610741261920086e+01 , 8.4507040000000018e+00 , -9.3134799999999995e-01 , -2.1950600000000001e-01 , 2.9053099999999998e-01 -2.4983694813173379e+01 , 1.9780705578303998e+01 , 9.3202792000000017e+00 , 3.4551800000000001e-02 , 9.9926499999999996e-01 , 1.6621799999999999e-02 -6.6672688420466342e+00 , 6.2311966056675212e+00 , 6.6267104000000003e+00 , -5.7270399999999999e-01 , -2.5517000000000001e-01 , -7.7903699999999998e-01 -6.5721175284427975e+00 , 6.1799890153541268e+00 , 6.6947992000000003e+00 , -7.2986600000000001e-01 , -3.7557099999999999e-01 , -5.7117700000000005e-01 -6.4570699025849976e+00 , 6.1107198081659115e+00 , 6.7427952000000007e+00 , 6.6821900000000001e-01 , 4.0316700000000000e-01 , 6.2525100000000000e-01 -6.4369587369207828e+00 , 6.1289484964814882e+00 , 6.8763832000000003e+00 , 7.3629900000000004e-01 , 3.5287299999999999e-01 , 5.7735899999999996e-01 -5.6033458958830664e+00 , 5.3802274178712572e+00 , 6.2077568000000003e+00 , 6.3982899999999998e-01 , -4.9809300000000001e-01 , 5.8525499999999997e-01 -5.5680101460316003e+00 , 5.3768740438756133e+00 , 6.2995368000000003e+00 , -3.6899799999999999e-01 , -9.2403500000000005e-01 , 1.0000400000000000e-01 -5.6896175892029444e+00 , 5.5266455723342922e+00 , 6.5629064000000001e+00 , -5.7265299999999997e-01 , -1.1102600000000000e-01 , 8.1224499999999999e-01 -5.7346911163725913e+00 , 5.6049271189291741e+00 , 6.7554832000000005e+00 , -9.6959899999999999e-01 , -1.1275300000000001e-01 , -2.1717500000000001e-01 -5.4438971557261358e+00 , 5.3543149185806147e+00 , 6.5668584000000001e+00 , 5.6193899999999997e-01 , 2.8592699999999999e-01 , 7.7619000000000005e-01 -5.9376769264577653e+00 , 5.8816502122193199e+00 , 7.3079624000000001e+00 , -9.4967699999999999e-01 , 2.0857999999999999e-01 , 2.3368200000000000e-01 -5.8219311371203499e+00 , 5.8071353372494272e+00 , 7.3350440000000008e+00 , -8.6784499999999998e-01 , -6.2016500000000002e-02 , -4.9295000000000000e-01 -5.7508047231166755e+00 , 5.7753992921937201e+00 , 7.4153111999999997e+00 , 9.9309300000000000e-01 , -3.4976000000000000e-02 , -1.1199700000000000e-01 -5.9033851008763243e+00 , 5.9763254802652677e+00 , 7.8021912000000002e+00 , 9.9352099999999999e-01 , 9.6765199999999996e-02 , 5.9607700000000000e-02 -5.9272042568215300e+00 , 6.0489508889681307e+00 , 8.0307416000000007e+00 , 1.1304300000000000e-01 , 8.1823900000000005e-01 , 5.6365399999999999e-01 -6.0444699829599626e+00 , 6.2235434189103538e+00 , 8.4110903999999991e+00 , -9.0732500000000005e-01 , 4.0652899999999997e-01 , 1.0721899999999999e-01 -6.1764087940548666e+00 , 6.4184601721445063e+00 , 8.8375008000000008e+00 , -9.0577099999999999e-01 , 4.2105399999999998e-01 , -4.7886499999999999e-02 -6.0478166545338530e+00 , 6.3380091945406996e+00 , 8.8745560000000001e+00 , -8.2848099999999994e-02 , -9.7504900000000005e-01 , 2.0595200000000000e-01 -6.0180150613250696e+00 , 6.3641528647768810e+00 , 9.0717503999999991e+00 , -4.8129699999999997e-01 , -1.1540499999999999e-01 , -8.6892800000000003e-01 -5.0513010617369032e+00 , 5.3374140226209938e+00 , 7.6377568000000000e+00 , -2.7010200000000001e-01 , -1.4966399999999999e-01 , 9.5112900000000000e-01 -4.9952338507019931e+00 , 5.3210612200071630e+00 , 7.7343728000000000e+00 , -7.9928500000000000e-02 , -1.5333900000000000e-01 , 9.8493600000000003e-01 -4.8816434650754443e+00 , 5.2381120329465798e+00 , 7.7252832000000007e+00 , -3.1007699999999999e-01 , -3.5196400000000000e-01 , 8.8316099999999997e-01 -4.3662062120190983e+00 , 4.6782129541102870e+00 , 6.9075416000000001e+00 , -8.6375900000000005e-01 , -7.1737899999999993e-02 , -4.9877300000000002e-01 -4.3171101286208717e+00 , 4.6611827988017076e+00 , 6.9811736000000000e+00 , -7.4276200000000003e-01 , -3.6908000000000002e-01 , -5.5864499999999995e-01 -4.2735421527147963e+00 , 4.6524784711465941e+00 , 7.0709464000000004e+00 , 8.3552800000000005e-01 , 4.9224200000000001e-01 , 2.4410999999999999e-01 -4.2321632411668020e+00 , 4.6474756266693671e+00 , 7.1690808000000006e+00 , -6.5586800000000001e-01 , -9.0687799999999999e-02 , 7.4940799999999996e-01 -4.2959748645082021e+00 , 4.7781669647908176e+00 , 7.5256863999999997e+00 , -3.9331600000000000e-01 , -6.0007999999999995e-01 , -6.9656799999999996e-01 -4.2532520091486745e+00 , 4.7762343194718602e+00 , 7.6439864000000002e+00 , 4.9662400000000001e-01 , 7.0800300000000005e-01 , 5.0209199999999998e-01 -4.1571993302232588e+00 , 4.7053930898932386e+00 , 7.6302896000000002e+00 , -1.6798299999999999e-01 , -9.3853299999999995e-01 , -3.0155700000000002e-01 -4.1306190698084508e+00 , 4.7281043198793276e+00 , 7.8005687999999997e+00 , -9.5942200000000005e-02 , -9.9523799999999996e-01 , -1.7209700000000001e-02 -4.1134268590500653e+00 , 4.7681583691462777e+00 , 8.0167847999999999e+00 , -4.0843499999999999e-01 , -9.1187600000000002e-01 , 4.0772500000000003e-02 -4.0040952842236166e+00 , 4.6781244543076532e+00 , 7.9629544000000001e+00 , -4.2066500000000001e-01 , -9.0659800000000001e-01 , 3.3494299999999998e-02 -3.9856956233334717e+00 , 4.7220934587185752e+00 , 8.1983168000000006e+00 , 4.7378999999999999e-01 , 4.8021399999999997e-01 , 7.3818499999999998e-01 -3.9313599932049756e+00 , 4.7167244119671317e+00 , 8.3340264000000008e+00 , 6.5376500000000004e-01 , -5.7314799999999999e-01 , 4.9405700000000002e-01 -3.7475462227294152e+00 , 4.5027816416370312e+00 , 7.9865624000000004e+00 , -2.1581100000000000e-01 , 5.7902100000000001e-01 , -7.8623200000000004e-01 -3.7934563400050441e+00 , 4.6647242441747760e+00 , 8.5208207999999992e+00 , 7.7355399999999996e-01 , 1.3939800000000000e-02 , 6.3357799999999997e-01 -3.7162928578601901e+00 , 4.6266496702598809e+00 , 8.5893984000000003e+00 , 8.3694599999999997e-01 , -5.5523500000000003e-02 , 5.4446099999999997e-01 -3.6453925613602443e+00 , 4.6020691825629338e+00 , 8.6947296000000005e+00 , -9.0482700000000005e-01 , -3.2784200000000002e-01 , 2.7167700000000000e-01 -3.1731981752332907e+00 , 3.8029339397081405e+00 , 6.7620040000000001e+00 , 3.5439999999999999e-01 , -2.9736900000000000e-02 , 9.3462100000000004e-01 -3.1162822030998409e+00 , 3.7686772281189596e+00 , 6.7853520000000005e+00 , 3.5566399999999998e-01 , -2.7281699999999999e-02 , 9.3421600000000005e-01 -3.4335882087651108e+00 , 4.5490321438914894e+00 , 9.0924984000000002e+00 , -5.2252300000000002e-02 , -7.5408200000000003e-01 , 6.5469800000000000e-01 -3.3543889944827523e+00 , 4.5227799938001727e+00 , 9.2140848000000002e+00 , 6.7725400000000002e-01 , -2.4083199999999999e-01 , 6.9521699999999997e-01 -3.3391273341212289e+00 , 4.6610954707423051e+00 , 9.8340911999999996e+00 , 6.6317199999999998e-01 , 6.4388299999999998e-01 , -3.8159799999999999e-01 -3.1704328900836822e+00 , 4.4136077818548323e+00 , 9.2970456000000006e+00 , 5.3939300000000001e-01 , 2.5766399999999998e-02 , 8.4165999999999996e-01 -3.0080561698094166e+00 , 4.1414449713025938e+00 , 8.6440712000000008e+00 , 9.7721599999999997e-01 , 2.1140900000000001e-01 , 1.8853700000000001e-02 -2.7642683739105038e+00 , 3.5168184692789688e+00 , 6.7724664000000008e+00 , -3.1879299999999999e-01 , 3.7407499999999999e-01 , 8.7088399999999999e-01 -2.8473590545201612e+00 , 4.0631131619225496e+00 , 8.7902224000000011e+00 , 6.8846799999999997e-01 , -5.9799000000000002e-01 , -4.1038999999999998e-01 -2.6508981255512358e+00 , 3.4374475437394523e+00 , 6.7706880000000007e+00 , 3.4102800000000000e-01 , 3.1057499999999999e-01 , 8.8726700000000003e-01 -2.6002170811538674e+00 , 3.4314504315969629e+00 , 6.8934807999999999e+00 , 6.8697299999999994e-01 , 5.7343200000000005e-01 , -4.4636700000000001e-01 -2.5812149991611033e+00 , 3.7967840499267007e+00 , 8.4655760000000004e+00 , 5.6411800000000001e-01 , 5.2980600000000000e-01 , -6.3330600000000004e-01 -2.4913000799039136e+00 , 3.4735609710057993e+00 , 7.3901952000000000e+00 , -7.5300000000000000e-01 , -4.1426900000000000e-01 , 5.1124700000000001e-01 -2.4277169603200610e+00 , 3.3906147532124660e+00 , 7.2284752000000001e+00 , -6.1411699999999996e-03 , 7.0876799999999995e-01 , 7.0541500000000001e-01 -2.3657381038351826e+00 , 3.3565732924631551e+00 , 7.2676416000000001e+00 , -2.8943000000000002e-01 , -7.0355599999999996e-01 , -6.4902899999999997e-01 -2.2793124131395865e+00 , 3.4689814373349730e+00 , 7.9862815999999999e+00 , 4.2748500000000000e-01 , -7.8155799999999997e-01 , -4.5433800000000002e-01 -2.2045956164001650e+00 , 3.4277100207578801e+00 , 8.0343191999999988e+00 , -7.9464900000000005e-01 , -4.0002300000000002e-01 , 4.5663500000000001e-01 -2.1357968462063166e+00 , 3.3664364226251799e+00 , 7.9790016000000001e+00 , -6.2598500000000001e-02 , 2.5723000000000001e-01 , 9.6431999999999995e-01 -2.0641651068277680e+00 , 3.3172799358973708e+00 , 7.9832656000000002e+00 , -1.3365600000000000e-01 , 3.9486500000000002e-01 , -9.0896500000000002e-01 -1.9914738439709800e+00 , 3.2688849333345047e+00 , 7.9963487999999998e+00 , 4.0093899999999999e-01 , 2.7132200000000001e-01 , 8.7500400000000000e-01 -1.7187286280133556e+00 , 3.5254694309122598e+00 , 9.8546520000000015e+00 , -2.7548499999999998e-01 , -2.9213499999999998e-01 , 9.1584100000000002e-01 -4.4689345010665766e+00 , 3.2618344845793343e+00 , 1.0693840799999998e+00 , -7.0709300000000003e-02 , 1.7272899999999999e-01 , 9.8242799999999997e-01 -4.5373326267692260e+00 , 3.3058255876694407e+00 , 1.0651533600000000e+00 , -8.5357699999999995e-02 , 1.6175400000000001e-01 , 9.8313300000000003e-01 -4.5982980113528420e+00 , 3.3476934699997134e+00 , 1.0698936799999998e+00 , -5.7540800000000003e-02 , 2.1468799999999999e-01 , 9.7498600000000002e-01 -4.6754188586793894e+00 , 3.3961862848790840e+00 , 1.0635174400000000e+00 , -6.9701799999999994e-02 , 1.8905900000000000e-01 , 9.7948900000000005e-01 -4.7441369288265109e+00 , 3.4435721401461326e+00 , 1.0656795999999999e+00 , -7.3830599999999996e-02 , 1.9630700000000001e-01 , 9.7775900000000004e-01 -4.8288602628706121e+00 , 3.4967534333926320e+00 , 1.0578400800000001e+00 , -4.2681299999999998e-02 , 1.9797100000000001e-01 , 9.7927799999999998e-01 -4.9072323087407721e+00 , 3.5488106742572718e+00 , 1.0588925599999999e+00 , -4.7037299999999997e-02 , 1.7020800000000000e-01 , 9.8428499999999997e-01 -4.9924071298657946e+00 , 3.6051565858127237e+00 , 1.0563341600000000e+00 , -4.2053399999999998e-02 , 1.9444300000000000e-01 , 9.8001199999999999e-01 -5.0864125925119934e+00 , 3.6658382616290721e+00 , 1.0508200800000000e+00 , -5.3176899999999999e-02 , 1.7786399999999999e-01 , 9.8261699999999996e-01 -5.1729579799532841e+00 , 3.7233798975560712e+00 , 1.0544819200000000e+00 , -6.5497799999999995e-02 , 1.6935800000000001e-01 , 9.8337600000000003e-01 -5.2753745175290288e+00 , 3.7902053831539790e+00 , 1.0496511200000000e+00 , -5.4352499999999998e-02 , 1.8762499999999999e-01 , 9.8073600000000005e-01 -5.3783847062331063e+00 , 3.8577666761844589e+00 , 1.0485892799999998e+00 , -4.4855500000000000e-02 , 1.8101800000000001e-01 , 9.8245600000000000e-01 -5.4901220162594058e+00 , 3.9309596390194645e+00 , 1.0456824800000000e+00 , 3.1160700000000002e-01 , -1.7550800000000000e-01 , -9.3386199999999997e-01 -5.5863120617880426e+00 , 3.9960454336139759e+00 , 1.0572607999999999e+00 , -8.1672699999999998e-01 , -8.5576000000000003e-03 , 5.7696099999999995e-01 -5.5848249063893389e+00 , 4.0133803251573372e+00 , 1.1323987199999999e+00 , -9.1707399999999994e-01 , -1.3130500000000001e-01 , 3.7647500000000000e-01 -5.6143372421089488e+00 , 4.0466131653786164e+00 , 1.1877017599999999e+00 , 9.9177700000000002e-01 , 1.1163600000000000e-01 , -6.2579499999999996e-02 -5.5787527242558994e+00 , 4.0448010922106477e+00 , 1.2818019999999999e+00 , 9.9325200000000002e-01 , 8.6594000000000004e-02 , 7.7147599999999997e-02 -5.5731478758290418e+00 , 4.0588924701089200e+00 , 1.3558385600000000e+00 , 9.9115200000000003e-01 , 9.8941399999999999e-02 , -8.8476299999999994e-02 -5.5416079232834985e+00 , 4.0586430775971696e+00 , 1.4427180800000001e+00 , 9.7889099999999996e-01 , 1.5370200000000001e-01 , 1.3471300000000000e-01 -5.5340163395752029e+00 , 4.0704428730462405e+00 , 1.5154983200000001e+00 , 9.7916899999999996e-01 , 1.2699299999999999e-01 , 1.5843099999999999e-01 -5.5333528752750976e+00 , 4.0863317833953641e+00 , 1.5836557600000001e+00 , 9.9522699999999997e-01 , 4.3100500000000000e-02 , -8.7554300000000002e-02 -5.5406087020463275e+00 , 4.1063409447037724e+00 , 1.6476188800000000e+00 , 9.9745600000000001e-01 , 5.9666400000000001e-02 , 3.9005300000000000e-02 -5.5042209116645200e+00 , 4.1012674751286582e+00 , 1.7306441600000000e+00 , -9.6648999999999996e-01 , -1.7886099999999999e-01 , -1.8413700000000000e-01 -5.5083595755555574e+00 , 4.1191697544046892e+00 , 1.7940331999999999e+00 , -9.5123999999999997e-01 , 2.1580200000000001e-02 , 3.0769500000000000e-01 -5.5124982394465949e+00 , 4.1370720336807203e+00 , 1.8574232799999999e+00 , -9.1728100000000001e-01 , 2.5275100000000002e-02 , 3.9743699999999998e-01 -5.5489252037674941e+00 , 4.1733088786333923e+00 , 1.9080047200000001e+00 , -8.6991399999999997e-01 , 7.7310799999999999e-02 , 4.8710700000000001e-01 -5.5763483248304029e+00 , 4.2044415932874184e+00 , 1.9629609200000000e+00 , 6.0402000000000000e-01 , -1.5505400000000000e-01 , -7.8173999999999999e-01 -5.6810033378005480e+00 , 4.2802737286458452e+00 , 1.9927735496000001e+00 , 3.9680199999999999e-01 , -1.8377499999999999e-01 , -8.9931899999999998e-01 -5.8105587446699243e+00 , 4.3722530778265734e+00 , 2.0184453360000001e+00 , -2.7411500000000000e-01 , 1.6233000000000000e-01 , 9.4789800000000002e-01 -6.0615068527077449e+00 , 4.5366979189547720e+00 , 2.0133159520000001e+00 , -9.7633200000000003e-02 , 2.1149399999999999e-01 , 9.7249099999999999e-01 -6.8572255521843832e+00 , 5.0701123964463459e+00 , 2.0479359920000002e+00 , -9.9261100000000002e-01 , -9.3049300000000001e-02 , 7.7884400000000006e-02 -6.8800734967674657e+00 , 5.1052838701397860e+00 , 2.1325188800000001e+00 , -9.9261100000000002e-01 , -9.3049300000000001e-02 , 7.7884499999999995e-02 -1.3100306186188190e+01 , 8.9475892307525200e+00 , 1.0173944800000001e+00 , -5.5918900000000001e-02 , 1.8642700000000001e-01 , 9.8087599999999997e-01 -1.4742206019808517e+01 , 1.0015075833022253e+01 , 9.4781120000000008e-01 , -6.0528199999999997e-02 , 1.8180399999999999e-01 , 9.8146999999999995e-01 -1.6292886239643686e+01 , 1.1041012462517916e+01 , 9.5826319999999998e-01 , -8.1125799999999998e-02 , 1.8708800000000000e-01 , 9.7898799999999997e-01 -2.2684478824190432e+01 , 1.5318098036356963e+01 , 1.2049303999999998e+00 , 5.5476999999999999e-01 , -5.3189800000000002e-02 , -8.3030199999999998e-01 -2.3083719843786106e+01 , 1.5671797421711540e+01 , 1.5858012800000001e+00 , 5.4733799999999999e-01 , -8.0332500000000001e-02 , -8.3304800000000001e-01 -2.4352679722424572e+01 , 1.6910191054691332e+01 , 3.2809784000000004e+00 , -9.5169499999999996e-01 , 1.1163400000000000e-01 , 2.8603099999999998e-01 -2.4850967083652055e+01 , 1.7349016769517785e+01 , 3.7472415999999997e+00 , -9.6071899999999999e-01 , -2.5934900000000000e-02 , 2.7630900000000003e-01 -2.4589537008806754e+01 , 1.7283394556217871e+01 , 4.1981023999999998e+00 , 1.5782800000000000e-01 , -9.8158800000000002e-01 , 1.0759199999999999e-01 -2.4658236141224439e+01 , 1.7438135483102315e+01 , 4.6645944000000004e+00 , -5.1331199999999999e-01 , -8.1430899999999995e-01 , -2.7094600000000002e-01 -2.4966486139507261e+01 , 1.7758056423133816e+01 , 5.1591871999999999e+00 , -9.1707899999999998e-01 , 3.4930899999999998e-01 , -1.9222200000000000e-01 -2.3882852949675303e+01 , 1.7126135393834566e+01 , 5.5120696000000002e+00 , -3.5997200000000001e-01 , -9.1168600000000000e-01 , 1.9811100000000001e-01 -2.4186598882815442e+01 , 1.7444718853701566e+01 , 6.0094080000000005e+00 , 4.1715799999999997e-01 , -8.4876900000000000e-01 , 3.2491500000000001e-01 -2.3870786899469092e+01 , 1.7334328235518477e+01 , 6.4271656000000004e+00 , -8.4136100000000003e-01 , 4.7110200000000002e-01 , 2.6490399999999997e-01 -2.4197933210185738e+01 , 1.7674103048935379e+01 , 6.9499528000000002e+00 , -9.4907399999999997e-01 , 2.9722199999999999e-01 , -1.0449100000000000e-01 -2.4657725893468200e+01 , 1.8111757708720820e+01 , 7.5180632000000003e+00 , 9.8350300000000002e-01 , -1.6230400000000000e-01 , 7.9869899999999994e-02 -2.5913432721471452e+01 , 1.9122903744714634e+01 , 8.2880688000000013e+00 , 2.8107300000000002e-01 , 8.9387799999999995e-01 , -3.4925600000000001e-01 -2.5829073855073776e+01 , 1.9185708131536728e+01 , 8.7925104000000012e+00 , 5.2180199999999999e-01 , 5.9947899999999998e-01 , -6.0691600000000001e-01 -2.5966631115544800e+01 , 1.9410648369137085e+01 , 9.3587488000000008e+00 , -6.3745900000000000e-01 , -6.8120000000000003e-01 , 3.6001899999999998e-01 -2.6184634573399045e+01 , 1.9696782604732189e+01 , 9.9609920000000010e+00 , 3.0615399999999998e-01 , 9.5113899999999996e-01 , -4.0064400000000000e-02 -2.5528324514398697e+01 , 1.9345462920946950e+01 , 1.0306906400000001e+01 , 2.2583300000000001e-02 , 9.2196400000000001e-01 , 3.8661699999999999e-01 -2.2515999127352792e+01 , 1.8608557199325276e+01 , 1.5608712000000001e+01 , 5.5000000000000004e-01 , -8.3223100000000005e-01 , -6.9938500000000001e-02 -6.8822299195683625e+00 , 6.1450667156270846e+00 , 6.5349303999999995e+00 , 5.1453300000000002e-01 , 2.3784400000000000e-01 , 8.2382400000000000e-01 -6.7519385891188435e+00 , 6.0701713023068127e+00 , 6.5781216000000002e+00 , -5.2630500000000002e-01 , -2.4864700000000001e-01 , -8.1312799999999996e-01 -6.6693689691951290e+00 , 6.0333247737640390e+00 , 6.6569224000000000e+00 , 6.4721799999999996e-01 , 2.7239000000000002e-01 , 7.1197800000000000e-01 -6.6243747952509384e+00 , 6.0310802707099560e+00 , 6.7679631999999996e+00 , 6.9922899999999999e-01 , 3.1536700000000001e-01 , 6.4157799999999998e-01 -6.5849875523290304e+00 , 6.0319567038281363e+00 , 6.8851088000000003e+00 , -7.0428700000000000e-01 , -2.3934100000000000e-01 , -6.6835299999999997e-01 -5.8529604582333397e+00 , 5.4207989045006801e+00 , 6.3411576000000007e+00 , -6.7174900000000004e-01 , -6.7200300000000002e-01 , 3.1171300000000002e-01 -5.7155371049080319e+00 , 5.3292620562200685e+00 , 6.3371328000000000e+00 , 5.6359000000000004e-01 , 8.0371899999999996e-01 , 1.9079099999999999e-01 -5.7071057813631061e+00 , 5.3525855274111409e+00 , 6.4616312000000002e+00 , -7.9267699999999996e-01 , -6.0799800000000004e-01 , -4.4747900000000000e-02 -5.7209175477024097e+00 , 5.3974175575702636e+00 , 6.6132736000000003e+00 , 9.9861400000000000e-01 , -3.1621299999999998e-02 , -4.2064100000000000e-02 -5.5766983313988323e+00 , 5.2979982554597456e+00 , 6.5950008000000002e+00 , 1.8925600000000001e-01 , 8.0988199999999999e-01 , 5.5522400000000005e-01 -5.4362355338211330e+00 , 5.1995738706502586e+00 , 6.5719440000000002e+00 , 5.5024700000000004e-01 , 5.4953799999999997e-01 , 6.2867799999999996e-01 -5.5734886768785827e+00 , 5.3642957311144084e+00 , 6.8812192000000003e+00 , -3.4077099999999999e-01 , -9.3102200000000002e-01 , -1.3066200000000000e-01 -5.8416147245455470e+00 , 5.6570566811824339e+00 , 7.3743455999999998e+00 , -9.8456800000000000e-01 , 1.7459300000000000e-01 , 1.1952200000000000e-02 -5.4330024938342518e+00 , 5.3006936275627590e+00 , 7.0099192000000006e+00 , -7.7415999999999996e-01 , 4.0758299999999997e-01 , -4.8430600000000001e-01 -5.3928685823467504e+00 , 5.2992857871480297e+00 , 7.1155831999999997e+00 , 5.4296400000000000e-01 , 7.5860200000000000e-01 , 3.6015700000000000e-01 -5.2890362051922750e+00 , 5.2349429044195519e+00 , 7.1324520000000007e+00 , -7.8554500000000005e-01 , 4.6392200000000000e-01 , -4.0950700000000001e-01 -5.1954160273778864e+00 , 5.1800557576771471e+00 , 7.1615095999999996e+00 , -9.1432899999999995e-01 , 3.4758699999999998e-01 , 2.0781100000000000e-01 -5.8762238686883439e+00 , 5.9190353888655274e+00 , 8.3869104000000014e+00 , -9.4603899999999996e-01 , 3.1951499999999999e-01 , 5.4032999999999998e-02 -5.7498282460853325e+00 , 5.8402075464467647e+00 , 8.4061400000000006e+00 , -6.7005300000000001e-01 , 5.5484800000000001e-01 , 4.9312600000000001e-01 -5.1942694230412361e+00 , 5.3062702493050704e+00 , 7.6981392000000000e+00 , -3.7509300000000001e-01 , -2.5031500000000001e-01 , 8.9255099999999998e-01 -5.0859551781876959e+00 , 5.2375488786722935e+00 , 7.7081128000000003e+00 , -3.7509199999999998e-01 , -2.5031500000000001e-01 , 8.9255099999999998e-01 -4.8553088807699254e+00 , 5.0333619896558988e+00 , 7.4886727999999998e+00 , -5.3344499999999995e-01 , -2.0114000000000001e-01 , 8.2157100000000005e-01 -4.6342094015636874e+00 , 4.8333281450115226e+00 , 7.2602991999999995e+00 , -3.8418099999999999e-01 , 7.3053000000000001e-01 , 5.6456300000000004e-01 -4.3707978964545227e+00 , 4.5793423515238487e+00 , 6.9236928000000004e+00 , -7.6029700000000000e-01 , -7.2006399999999998e-02 , -6.4557200000000003e-01 -4.3607172294791301e+00 , 4.6102264580961823e+00 , 7.0801087999999996e+00 , 7.5507000000000002e-01 , -3.1600400000000001e-01 , 5.7446500000000000e-01 -4.2215030451759796e+00 , 4.4912990388085827e+00 , 6.9660728000000010e+00 , 7.3848200000000003e-02 , 2.4148900000000001e-01 , 9.6758999999999995e-01 -4.3948030392877495e+00 , 4.7442302166097798e+00 , 7.5522584000000004e+00 , 4.6703200000000000e-01 , 5.4732700000000001e-01 , 6.9448900000000002e-01 -4.3253377634520849e+00 , 4.7121517633959016e+00 , 7.6101240000000008e+00 , -3.9333000000000001e-01 , -4.0459499999999998e-01 , -8.2558799999999999e-01 -4.3359634596897632e+00 , 4.7797681901357443e+00 , 7.8689384000000002e+00 , -7.8630100000000003e-01 , -5.2665700000000004e-01 , -3.2305400000000001e-01 -4.2389362322556261e+00 , 4.7150432665668109e+00 , 7.8642479999999999e+00 , 8.1983399999999995e-01 , 2.2339400000000001e-01 , 5.2722500000000005e-01 -4.1538459513292754e+00 , 4.6632010444999015e+00 , 7.8839455999999997e+00 , 6.3581299999999996e-01 , 3.5888900000000001e-01 , 6.8333100000000002e-01 -4.1407989566023442e+00 , 4.7100272125647287e+00 , 8.1188296000000015e+00 , -4.4849499999999998e-01 , -8.6733099999999996e-01 , -2.1584700000000001e-01 -4.0580117766371568e+00 , 4.6635225416856478e+00 , 8.1549072000000002e+00 , 4.6028899999999998e-02 , 8.5665500000000006e-01 , 5.1383100000000004e-01 -3.9743933425548419e+00 , 4.6166689713471811e+00 , 8.1891543999999996e+00 , 5.8511100000000005e-01 , -5.9479199999999999e-01 , -5.5124200000000001e-01 -3.9149582394048892e+00 , 4.6044192605214338e+00 , 8.3053640000000009e+00 , -8.8051500000000005e-01 , 2.8398499999999999e-01 , -3.7953399999999998e-01 -3.8638667083995433e+00 , 4.6095871540506961e+00 , 8.4677080000000018e+00 , 8.0926799999999999e-01 , -7.4877799999999994e-02 , 5.8264899999999997e-01 -3.8529752828342043e+00 , 4.6831562455815465e+00 , 8.8094520000000003e+00 , -6.5196200000000004e-01 , -7.3041599999999995e-01 , 2.0356299999999999e-01 -3.6943711837804014e+00 , 4.5169714435458266e+00 , 8.5462904000000002e+00 , 4.7820099999999999e-01 , -5.3899100000000000e-01 , 6.9340599999999997e-01 -3.2215857536012757e+00 , 3.7771833705555551e+00 , 6.7393528000000007e+00 , 3.4761799999999998e-01 , 5.2641800000000002e-02 , 9.3615700000000002e-01 -3.1636708810191800e+00 , 3.7450799301461597e+00 , 6.7626695999999997e+00 , -5.5661700000000003e-01 , -5.3321399999999997e-01 , -6.3707100000000005e-01 -3.5195102083988665e+00 , 4.5352621264892896e+00 , 9.1162624000000001e+00 , -8.7487400000000004e-01 , -4.1063300000000003e-01 , 2.5685799999999998e-01 -3.4042827770692825e+00 , 4.4347904249765442e+00 , 9.0146128000000001e+00 , -6.3311300000000004e-01 , 7.3006899999999997e-01 , -2.5722899999999999e-01 -3.3134505409040513e+00 , 4.3854664497828963e+00 , 9.0560983999999998e+00 , 8.3604500000000004e-01 , -4.4615400000000000e-01 , 3.1933499999999998e-01 -3.2276809680149068e+00 , 4.3477590281811249e+00 , 9.1352320000000002e+00 , 8.3036600000000005e-01 , -2.4519900000000000e-01 , 5.0036899999999995e-01 -3.0744129952486947e+00 , 4.1273486494723723e+00 , 8.6304368000000000e+00 , 9.9146900000000004e-01 , -1.2672000000000000e-01 , -3.0532699999999999e-02 -2.8017405123123851e+00 , 3.4931953442141035e+00 , 6.7106696000000001e+00 , 5.3223299999999996e-01 , 7.2546800000000000e-01 , 4.3637799999999999e-01 -2.7504800396704452e+00 , 3.4774773469429956e+00 , 6.7850608000000001e+00 , -3.5442299999999999e-01 , -3.3252200000000003e-02 , 9.3449400000000005e-01 -2.6866018898305950e+00 , 3.4130521020579101e+00 , 6.6888504000000006e+00 , -5.0628200000000001e-01 , -5.5412600000000001e-01 , 6.6077399999999997e-01 -2.6455409788762325e+00 , 3.4527564009072527e+00 , 6.9720320000000005e+00 , -2.1882799999999999e-01 , -5.5054700000000001e-01 , 8.0561300000000002e-01 -2.6380101011108841e+00 , 3.8022696414348234e+00 , 8.4732720000000015e+00 , -4.5984100000000000e-01 , -6.2483599999999995e-01 , 6.3097300000000001e-01 -2.5519949704737606e+00 , 3.7014375442322036e+00 , 8.2865192000000008e+00 , 5.1260499999999998e-01 , 5.5175700000000005e-01 , -6.5787600000000002e-01 -2.4667528295097512e+00 , 3.3038092525305913e+00 , 6.8428535999999998e+00 , -3.6986999999999998e-01 , 8.9635900000000002e-01 , -2.4440999999999999e-01 -2.4059372816758762e+00 , 3.3611141510749496e+00 , 7.2565863999999998e+00 , 1.2373400000000000e-01 , 6.8010599999999999e-01 , 7.2259700000000004e-01 -2.3393472840769389e+00 , 3.3527516679070430e+00 , 7.4064296000000001e+00 , 7.9947699999999999e-01 , 5.9980999999999995e-01 , 3.2629699999999998e-02 -2.2489629672888536e+00 , 3.4415638060181761e+00 , 8.0334768000000008e+00 , 1.4153299999999999e-01 , -9.7662300000000002e-01 , -1.6179199999999999e-01 -2.1795520638045867e+00 , 3.3752954328142275e+00 , 7.9480096000000007e+00 , -1.5042399999999999e-02 , -6.5782300000000002e-02 , 9.9772099999999997e-01 -2.1041715653185831e+00 , 3.3366909195651888e+00 , 7.9932808000000000e+00 , 1.3881700000000000e-02 , 4.0815800000000002e-01 , 9.1280600000000001e-01 -2.0343829879653761e+00 , 3.2811272964490437e+00 , 7.9555807999999999e+00 , -1.5016699999999999e-01 , 3.2800200000000002e-01 , -9.3266499999999997e-01 -1.7692200129733784e+00 , 3.5593364052703018e+00 , 9.8754103999999998e+00 , -2.0866699999999999e-01 , -6.5643799999999997e-01 , 7.2494599999999998e-01 -1.7158311378484683e+00 , 3.4274152327538867e+00 , 9.4674808000000006e+00 , -8.4288300000000005e-01 , -5.0956999999999997e-01 , 1.7288000000000001e-01 -4.5363682815409181e+00 , 3.2322174599644176e+00 , 1.0790675200000002e+00 , -8.0707399999999999e-02 , 1.2437100000000000e-01 , 9.8894800000000005e-01 -4.6055866576902140e+00 , 3.2743607687988829e+00 , 1.0763853600000000e+00 , -7.1130799999999994e-02 , 1.5182100000000001e-01 , 9.8584499999999997e-01 -4.6766315841986872e+00 , 3.3179630800826221e+00 , 1.0760754399999999e+00 , -6.0905599999999997e-02 , 1.8412999999999999e-01 , 9.8101300000000002e-01 -4.7464052427472740e+00 , 3.3620260927670174e+00 , 1.0777644000000000e+00 , -4.4350300000000002e-02 , 1.5304300000000001e-01 , 9.8722399999999999e-01 -4.8251204934525651e+00 , 3.4101916227914817e+00 , 1.0753848800000001e+00 , -5.9645200000000002e-02 , 1.7081099999999999e-01 , 9.8349699999999995e-01 -4.9045674115251767e+00 , 3.4588832393879061e+00 , 1.0757623999999999e+00 , 5.7823899999999998e-02 , -1.8978100000000001e-01 , -9.8012200000000005e-01 -4.9908365952697427e+00 , 3.5118197257203407e+00 , 1.0723262400000000e+00 , -3.6265600000000002e-02 , 1.6842099999999999e-01 , 9.8504800000000003e-01 -5.0869545892987738e+00 , 3.5690946280792746e+00 , 1.0661611199999999e+00 , -3.5698800000000003e-02 , 1.6656599999999999e-01 , 9.8538400000000004e-01 -5.1746216734454809e+00 , 3.6242436579127721e+00 , 1.0687403199999999e+00 , -7.6098700000000005e-02 , 1.6649200000000000e-01 , 9.8310200000000003e-01 -5.2710806248952853e+00 , 3.6838150346475307e+00 , 1.0687684000000002e+00 , -6.3797199999999998e-02 , 1.6160400000000000e-01 , 9.8479099999999997e-01 -5.3752341431293917e+00 , 3.7478823859756689e+00 , 1.0664242399999999e+00 , -4.8594300000000000e-02 , 1.8016299999999999e-01 , 9.8243599999999998e-01 -5.4891385300838209e+00 , 3.8175565386044301e+00 , 1.0623609599999999e+00 , 2.2671400000000000e-01 , -1.5319600000000000e-01 , -9.6183799999999997e-01 -5.5944872704898589e+00 , 3.8831087829204045e+00 , 1.0676535199999999e+00 , -7.2810500000000000e-01 , 1.3322300000000001e-01 , 6.7239400000000005e-01 -5.6101678850999832e+00 , 3.9081471402788406e+00 , 1.1320003999999999e+00 , -8.5359099999999999e-01 , 5.0251999999999998e-02 , 5.1851499999999995e-01 -5.6327467371358662e+00 , 3.9362180142848575e+00 , 1.1918274400000000e+00 , 9.9730099999999999e-01 , -2.6379000000000000e-02 , -6.8526199999999995e-02 -5.6052261305652973e+00 , 3.9393832069153252e+00 , 1.2807193600000000e+00 , 9.9436199999999997e-01 , -2.6811700000000001e-02 , 1.0259400000000000e-01 -5.6006882111961112e+00 , 3.9533937393691181e+00 , 1.3545780800000000e+00 , 9.9766800000000000e-01 , 3.1846500000000000e-02 , -6.0367799999999999e-02 -5.5861450842133848e+00 , 3.9622669393039929e+00 , 1.4323836000000001e+00 , 9.9519899999999994e-01 , 3.8625199999999998e-02 , 8.9923100000000006e-02 -5.6631767628244223e+00 , 4.0180572634267815e+00 , 1.4622253600000001e+00 , 9.8710100000000001e-01 , 8.3991899999999994e-02 , 1.3629600000000000e-01 -5.5700232167747332e+00 , 3.9868329024019573e+00 , 1.5772077600000001e+00 , -9.6314900000000003e-01 , -6.0286800000000001e-02 , 2.6212600000000003e-01 -5.5604440635774113e+00 , 3.9974445447942655e+00 , 1.6489303200000001e+00 , 9.7812699999999997e-01 , 1.1820799999999999e-01 , -1.7115700000000000e-01 -5.6270111839141919e+00 , 4.0466992039589442e+00 , 1.6862642399999999e+00 , -9.7395399999999999e-01 , -1.8981200000000001e-01 , -1.2403500000000001e-01 -5.5204735720751241e+00 , 4.0069041972416652e+00 , 1.7980184800000001e+00 , 9.9536100000000005e-01 , 3.6184500000000001e-02 , -8.9151499999999995e-02 -5.5335799987585990e+00 , 4.0288845866410989e+00 , 1.8572381600000001e+00 , -8.7482000000000004e-01 , 1.6545100000000001e-03 , 4.8444599999999999e-01 -5.5544159169849596e+00 , 4.0542463921474976e+00 , 1.9137854560000001e+00 , -8.7262899999999999e-01 , 9.6827900000000001e-03 , 4.8828800000000000e-01 -5.5996311753750483e+00 , 4.0937715489092046e+00 , 1.9615156320000000e+00 , -7.0492500000000002e-01 , 3.1875800000000003e-02 , 7.0856500000000000e-01 -5.6799421331552882e+00 , 4.1520730210026313e+00 , 1.9992428779200000e+00 , 4.4780100000000000e-01 , -1.1331900000000000e-01 , -8.8692300000000002e-01 -5.7862990716555913e+00 , 4.2252152578853162e+00 , 2.0318448000000000e+00 , -2.5718099999999999e-01 , 1.6692599999999999e-01 , 9.5183700000000004e-01 -5.9361387485042094e+00 , 4.3233438447593828e+00 , 2.0554314800000002e+00 , 1.4784100000000000e-01 , -1.8761600000000000e-01 , -9.7105300000000006e-01 -6.9036830442714097e+00 , 4.9388740458641172e+00 , 2.1285148800000000e+00 , -8.1829399999999997e-01 , -1.1631900000000001e-02 , 5.7468300000000005e-01 -1.2726552457684942e+01 , 8.2985486272814555e+00 , 1.0891024800000000e+00 , -6.4161099999999999e-02 , 1.8188399999999999e-01 , 9.8122500000000001e-01 -1.4122797842716043e+01 , 9.1534896641602295e+00 , 1.0506079200000000e+00 , -4.1358399999999997e-02 , 1.8769800000000000e-01 , 9.8135600000000001e-01 -1.5633314623371072e+01 , 1.0087549225689051e+01 , 1.0497530399999999e+00 , -8.3460199999999998e-02 , 1.7863699999999999e-01 , 9.8036900000000005e-01 -2.0406806445894919e+01 , 1.3033691958457798e+01 , 1.0277996800000000e+00 , -1.3883200000000001e-01 , 1.7787600000000001e-01 , 9.7421000000000002e-01 -2.2668713680447528e+01 , 1.4465640795750371e+01 , 1.1708953599999998e+00 , -5.5323400000000000e-01 , 3.8913900000000001e-02 , 8.3211599999999997e-01 -2.3035446453096672e+01 , 1.4778167476537192e+01 , 1.5459609599999999e+00 , -5.9740899999999997e-01 , -4.4871599999999998e-02 , 8.0067999999999995e-01 -2.4230302798379430e+01 , 1.5596900946952035e+01 , 1.8909060799999999e+00 , -7.0338500000000004e-01 , -8.5054699999999994e-03 , 7.1075900000000003e-01 -2.3835710351939607e+01 , 1.5456883706926106e+01 , 2.3397139199999999e+00 , -7.0338500000000004e-01 , -8.5053999999999998e-03 , 7.1075900000000003e-01 -2.4436724838124903e+01 , 1.5925510590193797e+01 , 2.7595400799999998e+00 , 8.0131399999999997e-01 , -5.3092700000000000e-02 , -5.9588399999999997e-01 -2.4535912371639764e+01 , 1.6400458651306039e+01 , 4.5478439999999996e+00 , -1.8177199999999999e-01 , -9.7179499999999996e-01 , 1.5024599999999999e-01 -2.8809072557398881e+01 , 1.9232997110682579e+01 , 5.3734688000000004e+00 , -6.1702100000000004e-01 , 5.7581400000000005e-01 , -5.3639899999999996e-01 -2.8958588359750749e+01 , 1.9455480163698034e+01 , 5.9348296000000005e+00 , -6.1702100000000004e-01 , 5.7581400000000005e-01 , -5.3639899999999996e-01 -2.8404314719528728e+01 , 1.9223743689548989e+01 , 6.4160376000000001e+00 , -6.1702100000000004e-01 , 5.7581400000000005e-01 , -5.3639899999999996e-01 -2.8183511887634889e+01 , 1.9205831895343465e+01 , 6.9282064000000005e+00 , -4.4160300000000002e-01 , 8.6115500000000000e-01 , -2.5179299999999999e-01 -2.7379241280610042e+01 , 1.8802341038480655e+01 , 7.3363231999999998e+00 , 3.0097800000000002e-01 , -5.8459000000000005e-01 , 7.5343700000000002e-01 -2.8970236034070826e+01 , 1.9979609898632937e+01 , 8.1753535999999993e+00 , 1.0050600000000000e-01 , -9.5758799999999999e-01 , 2.7004400000000001e-01 -2.8491390858701845e+01 , 1.9793512489876548e+01 , 8.6460992000000001e+00 , -5.7743199999999995e-01 , 8.0837800000000004e-01 , 1.1444500000000001e-01 -2.9466051900868312e+01 , 2.0580343991362710e+01 , 9.4445800000000002e+00 , 8.0308099999999993e-02 , 8.4093700000000005e-01 , 5.3514099999999998e-01 -2.7268149270678105e+01 , 1.9356133440957684e+01 , 1.0030027200000001e+01 , 4.6187899999999998e-01 , 8.5014400000000001e-01 , -2.5282800000000000e-01 -2.7205694914448799e+01 , 1.9442797180710730e+01 , 1.0573375199999999e+01 , 1.5702300000000000e-01 , 7.9362900000000003e-01 , 5.8779000000000003e-01 -2.6862073343742662e+01 , 1.9336107421195358e+01 , 1.1029664800000001e+01 , 1.5702300000000000e-01 , 7.9362900000000003e-01 , 5.8779000000000003e-01 -2.6357619926665016e+01 , 1.9115106697688198e+01 , 1.1422056800000002e+01 , 1.5702300000000000e-01 , 7.9362900000000003e-01 , 5.8778900000000001e-01 -2.9136440166201407e+01 , 2.1202852983145057e+01 , 1.3022544000000000e+01 , -2.8619499999999998e-01 , 8.7088600000000005e-01 , -3.9956199999999997e-01 -2.8423976603483588e+01 , 2.0844819491181763e+01 , 1.3380616000000000e+01 , 4.2887199999999998e-01 , -8.6539100000000002e-01 , 2.5916800000000001e-01 -2.3944550991401783e+01 , 1.8426244526693463e+01 , 1.4898080000000000e+01 , 2.0465600000000000e-01 , 8.8251000000000002e-01 , 4.2342800000000003e-01 -1.9692290909498841e+01 , 1.5364966718968638e+01 , 1.3031384000000001e+01 , -9.3181899999999995e-01 , -6.6519700000000001e-02 , -3.5677599999999998e-01 -2.4644532231326426e+01 , 1.9230615191226651e+01 , 1.6510287999999999e+01 , 1.2538900000000000e-02 , -9.9679300000000004e-01 , 7.9030199999999995e-02 -2.2935093972141100e+01 , 1.8070191011174618e+01 , 1.6061736000000000e+01 , -4.3956800000000001e-01 , 8.4959899999999999e-01 , 2.9148000000000002e-01 -2.2274532041323386e+01 , 1.7699014802364879e+01 , 1.6223663999999999e+01 , 7.6652699999999996e-01 , 3.1169100000000000e-01 , 5.6150199999999995e-01 -2.4037741252694730e+01 , 1.9209270970201057e+01 , 1.8040336000000000e+01 , -3.6875999999999998e-01 , 9.2662800000000001e-01 , -7.3333400000000007e-02 -2.3141275893157726e+01 , 1.8658585756295523e+01 , 1.8056248000000000e+01 , 2.0376700000000000e-01 , -9.2442100000000005e-01 , 3.2237399999999999e-01 -2.3054317751924696e+01 , 1.8740494563400112e+01 , 1.8644784000000001e+01 , -1.2185600000000000e-02 , -3.5326700000000000e-01 , 9.3544300000000002e-01 -2.1780830502793222e+01 , 1.7876215667749204e+01 , 1.8310216000000000e+01 , -8.2551399999999997e-01 , 5.6077800000000000e-01 , 6.3676499999999997e-02 -6.8346965237803090e+00 , 5.9470023878349849e+00 , 6.6801247999999998e+00 , -5.1024000000000003e-01 , -2.5934600000000002e-01 , -8.1999699999999998e-01 -6.6884974721459249e+00 , 5.8630035354994536e+00 , 6.7063224000000003e+00 , 6.7387300000000006e-01 , 2.1765599999999999e-01 , 7.0606000000000002e-01 -6.6301820625128212e+00 , 5.8492086732803710e+00 , 6.8046024000000003e+00 , -6.9464999999999999e-01 , -3.6368699999999998e-01 , -6.2063900000000005e-01 -5.7663932545815477e+00 , 5.2241707847633725e+00 , 6.4113264000000010e+00 , -8.9783000000000002e-01 , -3.3252999999999999e-01 , -2.8866199999999997e-01 -5.7823942510459077e+00 , 5.2687250102077403e+00 , 6.5621160000000005e+00 , 6.6356000000000004e-01 , 3.9421499999999998e-01 , 6.3583299999999998e-01 -5.7639153083568093e+00 , 5.2851834847510579e+00 , 6.6820384000000006e+00 , -8.3602900000000002e-01 , -1.5967400000000001e-01 , -5.2493800000000002e-01 -5.7066938425802052e+00 , 5.2687664875013498e+00 , 6.7622847999999998e+00 , -8.8942600000000005e-01 , -9.5163700000000004e-02 , -4.4706200000000001e-01 -5.6262914211049022e+00 , 5.2307038740909739e+00 , 6.8144407999999999e+00 , -3.0941299999999999e-01 , -9.4981099999999996e-01 , -4.6078300000000003e-02 -5.4810918887403695e+00 , 5.1349166122363776e+00 , 6.7875984000000003e+00 , -2.9418299999999997e-01 , 9.2996699999999999e-01 , 2.2049600000000000e-01 -5.4961292365448884e+00 , 5.1829683067743009e+00 , 6.9555167999999998e+00 , -6.4158800000000005e-01 , 4.5111699999999999e-01 , -6.2036899999999995e-01 -5.3801758477213930e+00 , 5.1121996633687123e+00 , 6.9590320000000006e+00 , -5.5892799999999998e-01 , 4.5964100000000002e-01 , -6.9016699999999997e-01 -5.2722414615578224e+00 , 5.0472056581561286e+00 , 6.9664680000000008e+00 , -7.8489799999999998e-01 , 1.3558600000000001e-01 , -6.0460899999999995e-01 -5.3837680944263937e+00 , 5.1895430510147831e+00 , 7.2856648000000002e+00 , -1.1842400000000000e-01 , 8.5256399999999999e-01 , 5.0902899999999995e-01 -5.9451783014965436e+00 , 5.7705719351896168e+00 , 8.2972000000000001e+00 , -6.7005300000000001e-01 , 5.5484800000000001e-01 , 4.9312600000000001e-01 -5.8375311723986503e+00 , 5.7151016392637661e+00 , 8.3467456000000002e+00 , -6.7005300000000001e-01 , 5.5484800000000001e-01 , 4.9312600000000001e-01 -5.7585488994946825e+00 , 5.6885645081233580e+00 , 8.4406263999999993e+00 , -6.7005199999999998e-01 , 5.5484800000000001e-01 , 4.9312600000000001e-01 -5.0941685063362971e+00 , 5.0708195285570739e+00 , 7.5463928000000005e+00 , 3.3524599999999999e-01 , 3.2784400000000002e-01 , -8.8324899999999995e-01 -5.0927245522709939e+00 , 5.1146389297927968e+00 , 7.7371912000000007e+00 , 1.0034100000000000e-01 , -2.8082600000000002e-01 , 9.5449899999999999e-01 -4.7579849616185719e+00 , 4.8123752906040762e+00 , 7.3249664000000001e+00 , 7.4792499999999995e-01 , -1.5163299999999999e-01 , -6.4623200000000003e-01 -4.7224114098263179e+00 , 4.8180996223977255e+00 , 7.4459495999999996e+00 , -6.8143200000000004e-01 , 4.9880799999999997e-01 , 5.3557500000000002e-01 -4.5329431916810110e+00 , 4.6592198813409045e+00 , 7.2651872000000006e+00 , 5.8636800000000000e-01 , -3.9369500000000002e-01 , -7.0793799999999996e-01 -4.3313152076386814e+00 , 4.4813849254309197e+00 , 7.0351600000000003e+00 , -8.5512200000000005e-01 , -3.4805100000000000e-01 , -3.8422299999999998e-01 -4.4807433473998595e+00 , 4.6928885040805355e+00 , 7.5528928000000004e+00 , -6.2529199999999996e-01 , -3.4634199999999998e-01 , -6.9932700000000003e-01 -4.3921131581951389e+00 , 4.6422812274944985e+00 , 7.5674320000000002e+00 , -6.2529199999999996e-01 , -3.4634199999999998e-01 , -6.9932600000000000e-01 -4.3303040472297152e+00 , 4.6205941552148220e+00 , 7.6415944000000007e+00 , -7.7369200000000005e-01 , -2.7648200000000001e-01 , -5.7005200000000000e-01 -4.3079024868230569e+00 , 4.6481848287431511e+00 , 7.8211919999999999e+00 , -9.2149899999999996e-01 , 1.2093300000000000e-01 , -3.6907299999999998e-01 -4.2705430979205605e+00 , 4.6606250399323574e+00 , 7.9751016000000003e+00 , 8.0701100000000003e-01 , -1.4106500000000000e-01 , 5.7343999999999995e-01 -4.1951277702171357e+00 , 4.6271706671092891e+00 , 8.0300967999999990e+00 , 8.2897600000000005e-01 , -1.4785500000000000e-02 , 5.5908899999999995e-01 -4.1818700270640967e+00 , 4.6750364897998908e+00 , 8.2754224000000001e+00 , 1.2982299999999999e-01 , 9.8883600000000005e-01 , -7.3134299999999999e-02 -4.1044194589932541e+00 , 4.6422519287763873e+00 , 8.3385920000000002e+00 , -4.0835100000000002e-01 , 7.9082399999999997e-01 , 4.5590199999999997e-01 -3.9675455776116637e+00 , 4.5269080889054241e+00 , 8.2059192000000003e+00 , -3.9237300000000003e-01 , 7.7620400000000001e-01 , 4.9350899999999998e-01 -3.8988745803807814e+00 , 4.5038937125611440e+00 , 8.2931232000000001e+00 , 6.4192400000000005e-01 , -6.6211200000000003e-01 , 3.8670599999999999e-01 -3.8033855931695522e+00 , 4.4437252153173734e+00 , 8.2851048000000009e+00 , 8.4764200000000001e-01 , -1.8338499999999999e-01 , 4.9786799999999998e-01 -3.3300168033189412e+00 , 3.7869601799085686e+00 , 6.7108880000000006e+00 , -3.0002200000000001e-01 , -4.8852400000000001e-01 , -8.1934799999999997e-01 -3.2699235949298293e+00 , 3.7533009589517077e+00 , 6.7260407999999998e+00 , -4.5063700000000001e-01 , -3.8923099999999999e-01 , -8.0338399999999999e-01 -3.2140793139008883e+00 , 3.7273156366108040e+00 , 6.7590295999999999e+00 , 6.0992100000000005e-01 , 5.8518000000000003e-01 , 5.3437900000000005e-01 -3.4971866668664293e+00 , 4.3198859389631625e+00 , 8.5695239999999995e+00 , -8.2136299999999995e-01 , 3.3857300000000001e-01 , -4.5905499999999999e-01 -3.4659599029320272e+00 , 4.3826369816950965e+00 , 8.9217928000000004e+00 , 2.8440900000000002e-01 , -6.9741900000000001e-01 , -6.5781299999999998e-01 -3.4109965021266628e+00 , 4.4099939577924090e+00 , 9.1881368000000005e+00 , -9.4022200000000000e-01 , 3.2433800000000002e-01 , -1.0386700000000000e-01 -3.3278762502066561e+00 , 4.3856529126391184e+00 , 9.3077991999999998e+00 , 5.5050500000000002e-01 , 2.5257299999999999e-01 , 7.9570799999999997e-01 -3.2309874885891121e+00 , 4.3351118304799598e+00 , 9.3472255999999998e+00 , 8.3333100000000004e-01 , 3.5548099999999999e-01 , -4.2331200000000002e-01 -2.8458095323497887e+00 , 3.4896388130975620e+00 , 6.7182095999999998e+00 , 6.0480199999999998e-02 , 3.7895200000000001e-01 , 9.2343799999999998e-01 -2.7964160100970248e+00 , 3.4810906407580653e+00 , 6.8128184000000003e+00 , 7.8383099999999994e-03 , 9.9819599999999997e-01 , 5.9528900000000003e-02 -2.7330920360158188e+00 , 3.4290340430661264e+00 , 6.7569911999999999e+00 , -2.2570499999999999e-01 , -2.0677999999999998e-02 , 9.7397599999999995e-01 -2.6659358473513493e+00 , 3.3502660523947592e+00 , 6.5994312000000006e+00 , -8.0138900000000002e-01 , -5.9721599999999997e-01 , -3.3289300000000001e-02 -2.6916442808650700e+00 , 3.7801612113644696e+00 , 8.3908415999999999e+00 , -4.5984100000000000e-01 , -6.2483500000000003e-01 , 6.3097300000000001e-01 -2.6086612659214952e+00 , 3.7254459692996766e+00 , 8.3755743999999996e+00 , -4.5984100000000000e-01 , -6.2483599999999995e-01 , 6.3097300000000001e-01 -2.5117898035486874e+00 , 3.4207942289450428e+00 , 7.3171352000000001e+00 , 5.6894599999999995e-01 , 3.0396800000000002e-01 , -7.6413600000000004e-01 -2.4470253672540787e+00 , 3.3665780068848958e+00 , 7.2555984000000002e+00 , -2.2211800000000001e-01 , 5.6929399999999997e-01 , 7.9156099999999996e-01 -2.3822157404223705e+00 , 3.3336287298440821e+00 , 7.2837304000000005e+00 , 1.6980700000000001e-01 , 7.2698399999999996e-01 , 6.6532700000000000e-01 -2.2957921158878145e+00 , 3.4460266820234899e+00 , 8.0023704000000002e+00 , -4.1100799999999998e-01 , 8.7907700000000000e-01 , 2.4144399999999999e-01 -2.2209710388392501e+00 , 3.3985900543925305e+00 , 7.9986471999999997e+00 , -7.9232499999999995e-01 , 9.6966399999999994e-02 , 6.0234399999999999e-01 -2.1478888765970292e+00 , 3.3456165264307103e+00 , 7.9625903999999998e+00 , -3.5583199999999998e-01 , -2.6066899999999998e-01 , -8.9746099999999995e-01 -2.0743412921988407e+00 , 3.3006240224815309e+00 , 7.9660016000000002e+00 , -5.9291299999999998e-02 , -4.3071799999999999e-01 , 9.0053700000000003e-01 -1.9949332576334975e+00 , 3.2637074069118599e+00 , 8.0187816000000005e+00 , 7.4955300000000002e-01 , 3.6946000000000001e-01 , 5.4924499999999998e-01 -1.7226734986234604e+00 , 3.5202417501488745e+00 , 9.8558687999999997e+00 , -2.7548499999999998e-01 , -2.9213499999999998e-01 , 9.1584100000000002e-01 -4.5404254167720808e+00 , 3.1602734785524715e+00 , 1.0864951999999999e+00 , -6.9568099999999994e-02 , 1.4296400000000001e-01 , 9.8728000000000005e-01 -4.6107457848504243e+00 , 3.2011683538329541e+00 , 1.0831307999999999e+00 , -8.5020600000000002e-02 , 1.4513799999999999e-01 , 9.8575199999999996e-01 -4.6675089980735187e+00 , 3.2362833453681352e+00 , 1.0956118399999999e+00 , 5.9264400000000002e-02 , -1.2297900000000000e-01 , -9.9063800000000002e-01 -4.7547069311611905e+00 , 3.2832247634854386e+00 , 1.0836872000000000e+00 , -3.9757700000000000e-02 , 1.5854799999999999e-01 , 9.8655099999999996e-01 -4.8263044772891170e+00 , 3.3254619721728158e+00 , 1.0872523199999999e+00 , -5.5093600000000000e-02 , 1.6313500000000000e-01 , 9.8506400000000005e-01 -4.9068540148822617e+00 , 3.3718027450920598e+00 , 1.0867489600000000e+00 , 5.7369900000000001e-02 , -1.8036600000000000e-01 , -9.8192500000000005e-01 -4.9952645789115735e+00 , 3.4223941525657553e+00 , 1.0826596799999999e+00 , -1.9505600000000001e-02 , 1.7574200000000001e-01 , 9.8424299999999998e-01 -5.0843669345062947e+00 , 3.4735513152441353e+00 , 1.0815281600000000e+00 , -4.3708499999999997e-02 , 1.8118000000000001e-01 , 9.8247799999999996e-01 -5.1812039470465034e+00 , 3.5280644122984564e+00 , 1.0776219199999999e+00 , -8.1869200000000003e-02 , 1.8093500000000001e-01 , 9.8008200000000001e-01 -5.2706712960333775e+00 , 3.5814518244745566e+00 , 1.0823799200000002e+00 , -7.6030000000000000e-02 , 1.5722000000000000e-01 , 9.8463299999999998e-01 -5.3688825862365563e+00 , 3.6382416513695626e+00 , 1.0847927199999998e+00 , 4.5611600000000002e-02 , -1.7292299999999999e-01 , -9.8387899999999995e-01 -5.4838715640934961e+00 , 3.7034029217603091e+00 , 1.0796519999999998e+00 , 1.4077400000000001e-01 , -1.5123000000000000e-01 , -9.7842300000000004e-01 -5.5994938545214055e+00 , 3.7703607025356218e+00 , 1.0782760800000000e+00 , -5.8404400000000001e-01 , 1.2979099999999999e-01 , 8.0127800000000005e-01 -5.6322870892330910e+00 , 3.8010189156347356e+00 , 1.1320399200000000e+00 , -9.4607900000000000e-01 , -5.6745900000000002e-02 , 3.1892900000000002e-01 -5.6308991150951577e+00 , 3.8170793062885284e+00 , 1.2061690400000000e+00 , -9.4998700000000003e-01 , -1.2769200000000000e-01 , 2.8499099999999999e-01 -5.6364626842316561e+00 , 3.8360662924565174e+00 , 1.2752739200000001e+00 , 9.9441900000000005e-01 , 7.2190000000000004e-02 , 7.6931700000000006e-02 -5.6160361749856236e+00 , 3.8430252881327438e+00 , 1.3581244799999999e+00 , 9.9739599999999995e-01 , 2.3498300000000000e-02 , 6.8180000000000004e-02 -5.6105284416584933e+00 , 3.8558523578338582e+00 , 1.4311532800000000e+00 , 9.9354900000000002e-01 , 6.4777799999999996e-02 , 9.3081899999999995e-02 -5.6040419336344645e+00 , 3.8685871353212815e+00 , 1.5035508000000000e+00 , 9.9561699999999997e-01 , 7.5427700000000000e-02 , 5.5289999999999999e-02 -5.5786274964089664e+00 , 3.8720413198026398e+00 , 1.5837587200000001e+00 , 9.9485000000000001e-01 , 8.9432800000000007e-02 , -4.7691999999999998e-02 -5.5959958385858766e+00 , 3.8959255715938466e+00 , 1.6427672799999999e+00 , 9.8248800000000003e-01 , -4.8503900000000003e-02 , -1.7990200000000001e-01 -5.6200563655973603e+00 , 3.9220789874734154e+00 , 1.6986766400000000e+00 , 9.9055300000000002e-01 , -1.1202800000000000e-01 , 7.9086900000000002e-02 -5.5382632298516352e+00 , 3.8979963505629502e+00 , 1.7988764800000001e+00 , 9.9045600000000000e-01 , 9.3475500000000003e-02 , 1.0128500000000000e-01 -5.5613292870854831e+00 , 3.9230355863756667e+00 , 1.8542575200000000e+00 , -9.0616900000000000e-01 , -4.1937700000000001e-02 , 4.2083100000000001e-01 -5.5910879268997693e+00 , 3.9525406523692146e+00 , 1.9069388240000000e+00 , -8.6901700000000004e-01 , -3.9448000000000000e-04 , 4.9478299999999997e-01 -5.6207440873387933e+00 , 3.9822371752447099e+00 , 1.9605303359999999e+00 , -7.9754300000000000e-01 , 4.0358600000000001e-02 , 6.0191099999999997e-01 -5.6668271167732849e+00 , 4.0198371561561386e+00 , 2.0094036592000002e+00 , 5.3423299999999996e-01 , -1.1081299999999999e-01 , -8.3804299999999998e-01 -5.7754248234352072e+00 , 4.0893587940212752e+00 , 2.0403430560000002e+00 , -3.4437699999999999e-01 , 1.2006400000000000e-01 , 9.3112200000000001e-01 -5.9098747170794548e+00 , 4.1729497175850829e+00 , 2.0675764960000000e+00 , 2.2373999999999999e-01 , -1.5009700000000001e-01 , -9.6302200000000004e-01 -6.3669607695381423e+00 , 4.4422556873275569e+00 , 2.0893540960000001e+00 , -5.9724500000000000e-02 , 1.8319800000000000e-01 , 9.8126000000000002e-01 -6.9501230625620414e+00 , 4.7853691758424608e+00 , 2.1196218400000002e+00 , -8.0241300000000004e-01 , -1.1825499999999999e-02 , 5.9665100000000004e-01 -1.2462905451304909e+01 , 7.7465541132809230e+00 , 1.1391150400000001e+00 , -6.8617899999999996e-02 , 1.8749600000000000e-01 , 9.7986600000000001e-01 -1.3531507927960938e+01 , 8.3662492979294711e+00 , 1.1489555199999999e+00 , -4.9639799999999998e-02 , 1.8666099999999999e-01 , 9.8116899999999996e-01 -1.5197072189008583e+01 , 9.3175190975711111e+00 , 1.1084069599999999e+00 , -7.1335399999999993e-02 , 1.8659999999999999e-01 , 9.7984300000000002e-01 -1.6723491271738951e+01 , 1.0208726978165055e+01 , 1.1512039999999999e+00 , -6.1737800000000002e-02 , 1.9127200000000000e-01 , 9.7959399999999996e-01 -2.2807191020212446e+01 , 1.3715504819072148e+01 , 1.1242960800000001e+00 , 5.1073800000000003e-01 , -4.6210700000000000e-02 , -8.5849299999999995e-01 -2.3220166938952218e+01 , 1.4037044657829464e+01 , 1.4907650399999999e+00 , -5.1073900000000005e-01 , 4.6210700000000000e-02 , 8.5849299999999995e-01 -2.3735588089543405e+01 , 1.4419091330505841e+01 , 1.8684660000000000e+00 , -5.6951200000000002e-01 , -2.4772599999999999e-02 , 8.2160999999999995e-01 -2.4243189771110462e+01 , 1.4802545368103122e+01 , 2.2672997600000002e+00 , -8.8895599999999997e-01 , 1.1412200000000000e-01 , 4.4354600000000000e-01 -2.4282393660609699e+01 , 1.4922189291426841e+01 , 2.6955467999999998e+00 , -9.4349000000000005e-01 , 1.9310700000000000e-01 , 2.6932699999999998e-01 -2.4323300685469196e+01 , 1.5043377559590489e+01 , 3.1266736000000002e+00 , -9.7868900000000003e-01 , -3.9057599999999998e-02 , 2.0160100000000000e-01 -6.5709803518407483e+01 , 3.9241535274554849e+01 , 4.4692200000000000e+00 , -5.8055700000000002e-02 , -9.7349900000000000e-01 , 2.2119800000000001e-01 -3.0069328594786644e+01 , 1.9116105280054011e+01 , 6.4692648000000004e+00 , 4.2070500000000000e-01 , -7.7351899999999996e-01 , 4.7399900000000000e-01 -2.8320009118215278e+01 , 1.8177548501816229e+01 , 6.7867040000000003e+00 , 5.8522399999999997e-01 , -2.3340699999999999e-02 , 8.1053600000000003e-01 -2.7677605204787316e+01 , 1.8023556967982589e+01 , 7.7459167999999998e+00 , 7.1009400000000000e-01 , -3.4107999999999999e-01 , 6.1597999999999997e-01 -2.2572781679546100e+01 , 1.4959304047327402e+01 , 7.2266240000000002e+00 , 6.4989399999999997e-01 , -7.5597599999999998e-01 , -7.8348699999999993e-02 -2.3105747707325680e+01 , 1.5391428163842347e+01 , 7.7775639999999999e+00 , 8.5643000000000002e-01 , -5.1590100000000005e-01 , 1.9347400000000001e-02 -2.9917879377693520e+01 , 1.9808262017900198e+01 , 9.9198599999999999e+00 , -4.7842899999999999e-01 , -5.6367699999999998e-01 , -6.7332999999999998e-01 -2.6925431572347307e+01 , 1.8033121795529407e+01 , 9.7091560000000001e+00 , -7.4721099999999996e-01 , -5.6484000000000001e-01 , 3.5018700000000003e-01 -2.8308529322040457e+01 , 1.9045578629371597e+01 , 1.0655223200000000e+01 , 7.5669000000000000e-02 , -6.0774799999999995e-01 , 7.9051700000000003e-01 -2.7916509035923976e+01 , 1.8922711050144386e+01 , 1.1110847200000000e+01 , -1.4639600000000000e-01 , -6.9113300000000000e-01 , 7.0774599999999999e-01 -2.6373055649286691e+01 , 1.8043818869845865e+01 , 1.1167308799999999e+01 , 9.7564999999999999e-02 , 7.1037300000000003e-01 , 6.9703000000000004e-01 -2.1416188761771977e+01 , 1.4902456132873253e+01 , 9.9283567999999995e+00 , 6.7869999999999997e-01 , -3.3035500000000001e-01 , 6.5592099999999998e-01 -2.1344552950025054e+01 , 1.4954320528995442e+01 , 1.0344388000000000e+01 , 6.7763099999999998e-01 , 3.1938800000000001e-01 , 6.6242500000000004e-01 -2.4735197378362066e+01 , 1.7325973549407117e+01 , 1.2177595999999999e+01 , 5.9060000000000001e-01 , -8.0491900000000005e-01 , -5.7410500000000003e-02 -2.3247971943609741e+01 , 1.6444005220512977e+01 , 1.2073044800000000e+01 , 1.3416100000000000e-01 , -9.3206599999999995e-01 , -3.3653200000000000e-01 -2.6385980640953669e+01 , 1.8696182509113417e+01 , 1.4018239999999999e+01 , -4.4717299999999999e-01 , 8.6087400000000003e-01 , -2.4275900000000000e-01 -2.5862933819341919e+01 , 1.8472155522592043e+01 , 1.4365183999999999e+01 , -8.8849400000000001e-01 , 3.7930999999999998e-01 , -2.5826700000000002e-01 -2.5298522731827070e+01 , 1.8217141038167522e+01 , 1.4676040000000000e+01 , 3.3940999999999999e-01 , -6.9873700000000005e-01 , 6.2973599999999996e-01 -2.0405408081525152e+01 , 1.4935598451374034e+01 , 1.2659896000000000e+01 , -9.5920099999999997e-01 , 2.9401600000000000e-02 , -2.8119400000000000e-01 -1.9847784995937367e+01 , 1.4650762082538259e+01 , 1.2824216000000000e+01 , -9.5920099999999997e-01 , 2.9401600000000000e-02 , -2.8119400000000000e-01 -1.9873666699392533e+01 , 1.4776449360821541e+01 , 1.3311248000000001e+01 , 9.6838199999999997e-01 , -1.6875499999999999e-01 , 1.8373400000000001e-01 -2.0025474515124479e+01 , 1.4994430834724563e+01 , 1.3888032000000001e+01 , -9.4068900000000000e-01 , -1.6253999999999999e-01 , -2.9779899999999998e-01 -1.9633827154878571e+01 , 1.4823133575167466e+01 , 1.4134824000000002e+01 , 9.8376300000000005e-01 , 1.3871600000000001e-01 , 1.1388100000000000e-01 -2.3486469356522068e+01 , 1.7746675620958424e+01 , 1.7224768000000001e+01 , -8.0202899999999999e-01 , -1.7849699999999999e-01 , 5.6999000000000000e-01 -2.2573104623270513e+01 , 1.7216016202419262e+01 , 1.7210520000000002e+01 , -3.7706299999999998e-01 , -7.6304799999999995e-01 , -5.2495800000000004e-01 -2.1785791397332765e+01 , 1.6770227108493110e+01 , 1.7248688000000001e+01 , 7.9000599999999999e-01 , 1.8541500000000000e-01 , 5.8438999999999997e-01 -2.1900244282487414e+01 , 1.6993455084069151e+01 , 1.7943719999999999e+01 , 7.9000599999999999e-01 , 1.8541500000000000e-01 , 5.8438999999999997e-01 -6.9379431901868678e+00 , 5.8023811375211638e+00 , 6.6536464000000004e+00 , -4.1615600000000003e-01 , -4.8408200000000001e-01 , -7.6972700000000005e-01 -6.8312181654526700e+00 , 5.7554490307816959e+00 , 6.7141536000000004e+00 , 5.1090100000000005e-01 , 4.3009799999999998e-01 , 7.4430900000000000e-01 -6.7314879297311192e+00 , 5.7120677542928240e+00 , 6.7779576000000006e+00 , 5.1090100000000005e-01 , 4.3009799999999998e-01 , 7.4430900000000000e-01 -6.0370906805136606e+00 , 5.2344436342671843e+00 , 6.4357768000000002e+00 , 1.3935000000000000e-01 , 4.5786500000000002e-01 , 8.7803200000000003e-01 -5.9714613815865327e+00 , 5.2111863072510864e+00 , 6.5066008000000002e+00 , 7.3595999999999995e-01 , 7.5766700000000006e-02 , 6.7277200000000004e-01 -5.8528784990385923e+00 , 5.1476310515900376e+00 , 6.5242392000000002e+00 , 4.8630499999999999e-01 , 3.4827100000000000e-03 , 8.7378199999999995e-01 -5.7988758413098553e+00 , 5.1342329088831962e+00 , 6.6043504000000004e+00 , -8.7359500000000001e-01 , 1.3029700000000000e-01 , -4.6888700000000000e-01 -5.7118950064391480e+00 , 5.0940727553327552e+00 , 6.6499648000000002e+00 , -9.0971599999999997e-01 , 1.6292300000000001e-01 , -3.8193400000000000e-01 -5.6980433858678481e+00 , 5.1146633032270863e+00 , 6.7755656000000002e+00 , -8.4151600000000004e-01 , -4.8757499999999998e-01 , -2.3263800000000001e-01 -5.7569925925725052e+00 , 5.1983574126901280e+00 , 6.9927071999999999e+00 , 8.0823299999999998e-01 , 5.1669600000000004e-01 , -2.8246199999999999e-01 -5.7704389301640999e+00 , 5.2441022385056542e+00 , 7.1646504000000002e+00 , 1.4931900000000001e-01 , 8.9098400000000000e-01 , 4.2877799999999999e-01 -5.4906435472210742e+00 , 5.0385370595230139e+00 , 6.9700560000000005e+00 , -4.4685100000000000e-01 , -3.6159600000000001e-03 , -8.9460099999999998e-01 -5.4014462299167576e+00 , 4.9958052979422742e+00 , 7.0077040000000004e+00 , -7.8489799999999998e-01 , 1.3558600000000001e-01 , -6.0460899999999995e-01 -5.5126423433889258e+00 , 5.1303505017395281e+00 , 7.3198184000000008e+00 , 8.6592900000000000e-02 , 8.4692199999999995e-01 , 5.2461899999999995e-01 -5.3242492579481251e+00 , 4.9995651743862837e+00 , 7.2207167999999999e+00 , -8.1654499999999997e-01 , 5.6989500000000004e-01 , 9.2050099999999996e-02 -6.0908478533405255e+00 , 5.7414931682340953e+00 , 8.5423071999999998e+00 , -4.8204200000000003e-01 , -1.9440800000000000e-01 , -8.5430700000000004e-01 -5.8984603152541695e+00 , 5.6126146753840054e+00 , 8.4676767999999996e+00 , -4.8204200000000003e-01 , -1.9440800000000000e-01 , -8.5430700000000004e-01 -5.2218830367265410e+00 , 5.0246244631011239e+00 , 7.5920591999999996e+00 , 2.9578399999999999e-01 , -5.0917199999999996e-01 , 8.0824200000000002e-01 -5.1499357877462018e+00 , 4.9995027903860922e+00 , 7.6628416000000001e+00 , -8.8790899999999995e-01 , 3.2047700000000001e-01 , -3.3001799999999998e-01 -4.9992541448218990e+00 , 4.8965238464604877e+00 , 7.5938688000000010e+00 , -4.1367900000000002e-01 , -7.8046699999999997e-02 , 9.0707199999999999e-01 -4.8027432623027213e+00 , 4.7454272894794176e+00 , 7.4291640000000001e+00 , -6.6660500000000000e-01 , 4.7912400000000001e-02 , 7.4386900000000000e-01 -4.6134576065123225e+00 , 4.5978964402145985e+00 , 7.2573040000000004e+00 , -1.2510099999999999e-01 , -3.7679299999999999e-01 , -9.1781100000000004e-01 -4.5353610759082006e+00 , 4.5601845272607378e+00 , 7.2906256000000003e+00 , -6.8461700000000003e-01 , 1.3947999999999999e-01 , -7.1543400000000001e-01 -4.5098844217144816e+00 , 4.5773468002539524e+00 , 7.4336359999999999e+00 , -8.4589800000000004e-01 , 3.9449400000000001e-01 , -3.5893000000000003e-01 -4.5078649810393223e+00 , 4.6228535036564127e+00 , 7.6380064000000010e+00 , 6.8013000000000001e-01 , 1.8911900000000001e-01 , 7.0827799999999996e-01 -4.4023612840861004e+00 , 4.5572804596172443e+00 , 7.6167696000000005e+00 , 7.4987300000000001e-01 , -1.1369400000000000e-01 , 6.5173999999999999e-01 -4.3311243856960768e+00 , 4.5280263379286794e+00 , 7.6724616000000001e+00 , -9.2002600000000001e-01 , 9.6877300000000000e-02 , -3.7969300000000000e-01 -4.3013333111828160e+00 , 4.5469987501945299e+00 , 7.8340464000000001e+00 , -8.4580000000000000e-01 , 2.4743100000000001e-01 , -4.7265200000000002e-01 -4.2398128494726599e+00 , 4.5327345876628851e+00 , 7.9240272000000003e+00 , -6.0005900000000001e-01 , 4.1983199999999998e-01 , -6.8093300000000001e-01 -4.1541172882892816e+00 , 4.4885373047723496e+00 , 7.9498816000000003e+00 , 5.5641700000000002e-02 , -4.5391799999999999e-01 , 8.8930500000000001e-01 -4.2479159062494256e+00 , 4.6706927957318243e+00 , 8.5156519999999993e+00 , 2.1106400000000000e-01 , 9.6991000000000005e-01 , 1.2135200000000000e-01 -4.1735148093564103e+00 , 4.6487771252908789e+00 , 8.6070784000000007e+00 , 2.1106400000000000e-01 , 9.6991000000000005e-01 , 1.2135200000000000e-01 -3.9909785170963872e+00 , 4.4815611761559850e+00 , 8.3337144000000016e+00 , 6.4192400000000005e-01 , -6.6211200000000003e-01 , 3.8670599999999999e-01 -3.9140236508465600e+00 , 4.4518801601546532e+00 , 8.4018656000000007e+00 , 8.2311900000000005e-01 , -2.3089299999999999e-01 , 5.1881100000000002e-01 -3.8567663862026977e+00 , 4.4531240935542939e+00 , 8.5539240000000003e+00 , 4.6296900000000002e-01 , 8.4185800000000000e-01 , -2.7737099999999998e-01 -3.3192296205170084e+00 , 3.7273121073080424e+00 , 6.7129471999999994e+00 , 6.5495999999999999e-02 , 7.5948300000000002e-01 , 6.4722100000000005e-01 -3.2633722464270303e+00 , 3.7024383408909465e+00 , 6.7462480000000005e+00 , -4.8421199999999998e-01 , -5.6026600000000004e-01 , -6.7204299999999995e-01 -3.2197532628122132e+00 , 3.7000056956619174e+00 , 6.8460463999999996e+00 , -4.9685900000000000e-01 , -7.2423400000000004e-01 , -4.7813800000000001e-01 -3.6008923501860122e+00 , 4.4587172610193120e+00 , 9.2280416000000010e+00 , -9.6543999999999996e-01 , 6.8180500000000000e-03 , 2.6053599999999999e-01 -3.5246129416095808e+00 , 4.4508312875251992e+00 , 9.3887216000000002e+00 , -5.3740299999999996e-01 , 6.3188999999999995e-01 , 5.5849199999999999e-01 -3.3738742144880707e+00 , 4.2977225442675167e+00 , 9.0972720000000002e+00 , -2.4352499999999999e-01 , -8.7942299999999995e-01 , -4.0903699999999998e-01 -3.2939699751750746e+00 , 4.2821724560423160e+00 , 9.2349472000000006e+00 , 5.1222000000000001e-01 , 6.6380300000000003e-01 , 5.4497399999999996e-01 -2.8917880331567356e+00 , 3.4859281651722607e+00 , 6.7359416000000003e+00 , 2.1413499999999999e-01 , 6.9285799999999997e-01 , 6.8854499999999996e-01 -2.8404108030422801e+00 , 3.4754922619834470e+00 , 6.8207639999999996e+00 , 4.0536299999999997e-01 , 6.9614200000000004e-01 , 5.9250899999999995e-01 -2.7732100122106909e+00 , 3.4165906144335785e+00 , 6.7354215999999996e+00 , -1.6127900000000001e-01 , 3.7378400000000001e-01 , 9.1338699999999995e-01 -2.7047105923271180e+00 , 3.3492336252242056e+00 , 6.6078552000000004e+00 , -8.5558000000000001e-01 , -4.7926600000000003e-01 , 1.9566900000000001e-01 -2.6604160705571500e+00 , 3.3716329575740835e+00 , 6.8202440000000006e+00 , -7.9434800000000005e-01 , -1.3052400000000000e-01 , -5.9327500000000000e-01 -2.6642513430570669e+00 , 3.7268671415494619e+00 , 8.3839672000000007e+00 , -4.5984100000000000e-01 , -6.2483599999999995e-01 , 6.3097300000000001e-01 -2.5784119242538792e+00 , 3.6556768148237522e+00 , 8.2863632000000003e+00 , 5.1260600000000001e-01 , 5.5175600000000002e-01 , -6.5787600000000002e-01 -2.4886907652331578e+00 , 3.3770932483662586e+00 , 7.2850615999999997e+00 , 3.9967200000000003e-01 , -1.2025000000000000e-01 , -9.0873700000000002e-01 -2.4233738738534036e+00 , 3.3360825007203569e+00 , 7.2731119999999994e+00 , 1.9271500000000000e-01 , 6.8818999999999997e-01 , 6.9946799999999998e-01 -2.3521329753437552e+00 , 3.3545688145866626e+00 , 7.5341312000000000e+00 , -8.0836200000000002e-01 , -5.8816199999999996e-01 , -2.4816200000000000e-02 -2.2615988647563556e+00 , 3.4300225138632578e+00 , 8.1000991999999989e+00 , -5.1960600000000001e-01 , 8.2295499999999999e-01 , 2.2968200000000000e-01 -2.1922883690187245e+00 , 3.3565268234338093e+00 , 7.9524296000000003e+00 , -3.9975100000000002e-01 , 3.1711299999999998e-01 , 8.6002199999999995e-01 -2.1139197874249915e+00 , 3.3210730752434352e+00 , 7.9969000000000001e+00 , -4.8441800000000000e-02 , 2.3185400000000000e-01 , 9.7154399999999996e-01 -2.0386388928660129e+00 , 3.2759414424097617e+00 , 7.9886944000000000e+00 , 4.2917200000000000e-01 , -9.6989699999999998e-02 , 8.9800000000000002e-01 -1.7714885787299290e+00 , 3.5562414057795908e+00 , 9.9079624000000006e+00 , -4.6755300000000000e-01 , -1.6027400000000000e-01 , 8.6931400000000003e-01 -1.7301140324175972e+00 , 3.4074639076743143e+00 , 9.3557015999999997e+00 , -6.2735300000000005e-01 , -2.2582500000000000e-01 , 7.4527200000000005e-01 -4.6128147230010779e+00 , 3.1291386294874419e+00 , 1.0896994400000000e+00 , -1.0030799999999999e-01 , 1.7645500000000000e-01 , 9.7918400000000005e-01 -4.6777765203573480e+00 , 3.1645880546525582e+00 , 1.0950606400000000e+00 , -1.0810500000000001e-01 , 1.5254699999999999e-01 , 9.8236599999999996e-01 -4.7435859552631054e+00 , 3.2014572196763469e+00 , 1.1023655999999999e+00 , -4.9244999999999997e-02 , 2.0824500000000001e-01 , 9.7683600000000004e-01 -4.8244446756436963e+00 , 3.2439694212032375e+00 , 1.0987339199999999e+00 , -6.4183599999999993e-02 , 1.8156800000000001e-01 , 9.8128199999999999e-01 -4.8979586634100611e+00 , 3.2853376462506865e+00 , 1.1036666399999999e+00 , -8.3442000000000002e-02 , 1.6770599999999999e-01 , 9.8229900000000003e-01 -4.9792714342544766e+00 , 3.3288555405785361e+00 , 1.1051184800000000e+00 , -3.3613700000000003e-02 , 1.9255300000000000e-01 , 9.8071100000000000e-01 -5.0765973049214832e+00 , 3.3803288452856299e+00 , 1.0967662400000000e+00 , -4.6709000000000001e-02 , 1.9920800000000000e-01 , 9.7884400000000005e-01 -5.1756144719645141e+00 , 3.4324102808408479e+00 , 1.0918023200000000e+00 , -7.1047399999999997e-02 , 1.9688000000000000e-01 , 9.7785000000000000e-01 -5.2590806399336678e+00 , 3.4786015996328592e+00 , 1.1017228800000001e+00 , -6.6635000000000000e-02 , 1.9122000000000000e-01 , 9.7928300000000001e-01 -5.3665043440951266e+00 , 3.5357499165774620e+00 , 1.0973444799999998e+00 , -7.0409500000000000e-02 , 1.8759899999999999e-01 , 9.7971900000000001e-01 -5.4665057064460640e+00 , 3.5907760596540301e+00 , 1.1019360799999998e+00 , -4.5397199999999999e-02 , 1.8245100000000000e-01 , 9.8216599999999998e-01 -5.5912547513510713e+00 , 3.6560545322752693e+00 , 1.0941797599999998e+00 , 3.7329299999999999e-01 , -1.8459700000000001e-01 , -9.0916200000000003e-01 -5.6674015872127859e+00 , 3.7028611084405867e+00 , 1.1213892800000000e+00 , -8.5587000000000002e-01 , 2.2628400000000000e-02 , 5.1669600000000004e-01 -5.6580210362590648e+00 , 3.7160003507233914e+00 , 1.2004178400000001e+00 , -8.8566900000000004e-01 , -7.4377899999999997e-02 , 4.5832099999999998e-01 -5.7247388836363466e+00 , 3.7595383623802321e+00 , 1.2357424799999999e+00 , 9.9752300000000005e-01 , 6.9756899999999997e-02 , -9.0768499999999992e-03 -5.6442252318233059e+00 , 3.7418644678538859e+00 , 1.3521954400000000e+00 , 9.8577999999999999e-01 , 6.3972399999999999e-02 , 1.5538500000000000e-01 -5.6398180286261557e+00 , 3.7556489435166531e+00 , 1.4249423999999999e+00 , 9.9642799999999998e-01 , 7.7491599999999994e-02 , 3.3572499999999998e-02 -5.6423080375174148e+00 , 3.7713716798577304e+00 , 1.4929698400000000e+00 , 9.9315299999999995e-01 , 9.2865799999999998e-02 , 7.0869600000000005e-02 -5.6258798126777521e+00 , 3.7799646221693681e+00 , 1.5690063200000000e+00 , 9.9612400000000001e-01 , 8.4759600000000004e-02 , 2.3505900000000000e-02 -5.6174198535630850e+00 , 3.7914939466454909e+00 , 1.6402442399999999e+00 , -9.5344099999999998e-01 , -8.6008000000000001e-02 , 2.8905700000000001e-01 -5.6247416737549862e+00 , 3.8091883171197143e+00 , 1.7033025600000000e+00 , 9.8753999999999997e-01 , 9.9924299999999994e-02 , -1.2157600000000000e-01 -5.5875508428233100e+00 , 3.8070294051225630e+00 , 1.7847772000000000e+00 , -9.6042000000000005e-01 , -2.2477900000000001e-01 , -1.6452400000000000e-01 -5.5839370277669440e+00 , 3.8194126921925773e+00 , 1.8507444000000000e+00 , -9.3754999999999999e-01 , 6.1763199999999999e-03 , 3.4779500000000002e-01 -5.5970708725259453e+00 , 3.8402632064444235e+00 , 1.9095630560000001e+00 , -9.0847900000000004e-01 , 3.2882200000000000e-02 , 4.1663400000000000e-01 -5.6277914981157373e+00 , 3.8676924104753811e+00 , 1.9626787680000000e+00 , -8.5568000000000000e-01 , 6.8881499999999998e-02 , 5.1290000000000002e-01 -5.6661978059973563e+00 , 3.8996614176770787e+00 , 2.0136241039999998e+00 , 6.5961199999999998e-01 , -1.2945999999999999e-01 , -7.4037299999999995e-01 -5.7671102668291709e+00 , 3.9613431568865680e+00 , 2.0461353359999999e+00 , 4.1036899999999998e-01 , -1.5549499999999999e-01 , -8.9856499999999995e-01 -5.8774262901967811e+00 , 4.0281463843597747e+00 , 2.0797629039999999e+00 , -2.2735100000000000e-01 , 1.7098600000000000e-01 , 9.5868399999999998e-01 -6.0594615334271378e+00 , 4.1300953970215204e+00 , 2.0975900639999998e+00 , -1.8738500000000000e-01 , 1.6795499999999999e-01 , 9.6782100000000004e-01 -6.9980627379872677e+00 , 4.6387050001480397e+00 , 2.1081028000000002e+00 , -5.3179999999999998e-02 , 4.8095499999999999e-02 , 9.9742600000000003e-01 -1.2119227103443819e+01 , 7.1941370024241778e+00 , 1.2014755199999998e+00 , -6.8410299999999993e-02 , 1.9008800000000001e-01 , 9.7938099999999995e-01 -1.3140686030262598e+01 , 7.7464429106799448e+00 , 1.2094159200000001e+00 , -6.4215800000000003e-02 , 1.8015700000000001e-01 , 9.8153999999999997e-01 -1.4575801361812163e+01 , 8.5148525468819010e+00 , 1.1922985600000000e+00 , -4.4603600000000000e-02 , 1.8797000000000000e-01 , 9.8116099999999995e-01 -1.6118270217578235e+01 , 9.3504411424557894e+00 , 1.2154395999999998e+00 , -8.4918599999999997e-02 , 1.8012300000000001e-01 , 9.7997199999999995e-01 -1.8441361153296025e+01 , 1.0599391927280335e+01 , 1.2064279999999998e+00 , -5.0767899999999998e-02 , 1.8465200000000001e-01 , 9.8149200000000003e-01 -2.0814836108642023e+01 , 1.1893987937106676e+01 , 1.2817926399999999e+00 , -9.1153300000000007e-02 , 1.7885799999999999e-01 , 9.7964300000000004e-01 -2.3134567311644908e+01 , 1.3181499086098645e+01 , 1.4528820000000000e+00 , 4.9590299999999998e-01 , -6.4885100000000001e-02 , -8.6595000000000000e-01 -2.3956617177531655e+01 , 1.3700916958563173e+01 , 1.8030780799999999e+00 , -4.7028399999999998e-01 , -3.2526800000000002e-02 , 8.8191600000000003e-01 -2.4468502010935190e+01 , 1.4063241544795464e+01 , 2.1981189600000000e+00 , -8.4063299999999996e-01 , -4.3921300000000002e-01 , 3.1690499999999999e-01 -2.4632761727507994e+01 , 1.4340720416248374e+01 , 3.0517208000000000e+00 , -9.3399699999999997e-01 , -2.7351900000000001e-01 , -2.2986300000000001e-01 -2.4187596279210343e+01 , 1.4194727965386985e+01 , 3.4759159999999998e+00 , -9.3399699999999997e-01 , -2.7351900000000001e-01 , -2.2986300000000001e-01 -2.9167494219792758e+01 , 1.7481075509629992e+01 , 6.2091400000000005e+00 , 5.8522300000000005e-01 , -2.3340699999999999e-02 , 8.1053600000000003e-01 -2.3231111071612752e+01 , 1.4224381179309679e+01 , 5.9329055999999998e+00 , -1.9187199999999999e-01 , 6.9338699999999998e-01 , -6.9455000000000000e-01 -2.7606631767930832e+01 , 1.6825740950431722e+01 , 7.0450920000000004e+00 , 7.9866800000000004e-01 , 5.0158000000000003e-01 , 3.3248600000000000e-01 -2.1345534135541268e+01 , 1.3321448329583147e+01 , 6.4457399999999998e+00 , -8.2350000000000001e-01 , 5.5726399999999998e-01 , -1.0632400000000000e-01 -2.2734296548194294e+01 , 1.4216968408523417e+01 , 7.1129208000000004e+00 , 6.8276599999999998e-01 , -7.2001099999999996e-01 , -1.2415400000000000e-01 -2.2032281605313180e+01 , 1.3898999766437143e+01 , 7.3824472000000005e+00 , 6.8096100000000004e-01 , -5.4091999999999996e-01 , -4.9365700000000001e-01 -2.2977421948509569e+01 , 1.4549304157893989e+01 , 8.0238256000000003e+00 , -9.2282600000000004e-01 , 3.8519500000000001e-01 , 4.1285999999999996e-03 -2.8409963868509390e+01 , 1.7887168280317308e+01 , 9.8866215999999998e+00 , -5.2539300000000000e-01 , -8.3395500000000000e-01 , 1.6876700000000000e-01 -2.2829959587071340e+01 , 1.4655908090420429e+01 , 8.8641040000000011e+00 , -9.3976700000000002e-01 , 1.5459200000000001e-01 , -3.0486000000000002e-01 -2.8816690013556325e+01 , 1.8383497021702187e+01 , 1.1140404000000000e+01 , 9.6175400000000008e-03 , -4.5507999999999998e-01 , 8.9039800000000002e-01 -1.9843390815014978e+01 , 1.3030796842543689e+01 , 8.7829112000000009e+00 , -8.8761400000000001e-01 , -4.2928300000000003e-01 , 1.6690600000000000e-01 -1.9931912795217432e+01 , 1.3171505857303925e+01 , 9.2050264000000013e+00 , 9.7831699999999999e-01 , 1.8930200000000000e-01 , -8.4023299999999995e-02 -1.9909821644731693e+01 , 1.3245935051774753e+01 , 9.5960560000000008e+00 , -9.8205799999999999e-01 , -1.3735800000000001e-01 , 1.2920999999999999e-01 -2.0959575671988460e+01 , 1.3992638945816804e+01 , 1.0416824000000000e+01 , 5.7110499999999997e-01 , -5.5704500000000001e-01 , -6.0294199999999998e-01 -2.0873959386598827e+01 , 1.4035472229621817e+01 , 1.0816724799999999e+01 , -5.3996000000000000e-01 , -3.7600600000000001e-01 , -7.5303600000000004e-01 -2.3360649871596937e+01 , 1.5715921672328768e+01 , 1.2362320800000001e+01 , -2.0832200000000001e-01 , -1.3372800000000001e-01 , 9.6887500000000004e-01 -2.3946910962923688e+01 , 1.6204457563165590e+01 , 1.3146720000000000e+01 , -9.7314400000000001e-01 , 9.5459400000000000e-02 , -2.0947199999999999e-01 -2.0591705987706032e+01 , 1.4151097135816396e+01 , 1.2026005600000000e+01 , 7.4478699999999998e-01 , -4.7683100000000000e-01 , 4.6682299999999999e-01 -2.0574121554002080e+01 , 1.4241508251068183e+01 , 1.2476336000000000e+01 , 7.1552700000000002e-01 , 2.9971300000000001e-01 , 6.3102599999999998e-01 -1.9900616052657018e+01 , 1.3900158290970667e+01 , 1.2577840000000000e+01 , -8.4632499999999999e-01 , 3.9185599999999998e-01 , -3.6080899999999999e-01 -2.0060542289977509e+01 , 1.4108452342783648e+01 , 1.3129248000000000e+01 , 9.8644200000000004e-01 , 7.0345800000000000e-02 , 1.4826900000000001e-01 -2.0122508091168463e+01 , 1.4255578168227462e+01 , 1.3640927999999999e+01 , 9.9339000000000000e-01 , 1.0996800000000000e-01 , -3.2907899999999997e-02 -1.9729742197458279e+01 , 1.4097127568264566e+01 , 1.3882624000000000e+01 , 9.8437399999999997e-01 , 1.2426500000000000e-01 , 1.2476700000000000e-01 -2.3250935612610100e+01 , 1.6609986587304725e+01 , 1.6671176000000003e+01 , 5.5986000000000002e-01 , -2.1511600000000000e-01 , -8.0017600000000000e-01 -2.3794844492267973e+01 , 1.7117951683136987e+01 , 1.7643264000000002e+01 , 5.3853099999999998e-01 , -3.8334499999999999e-01 , -7.5035399999999997e-01 -2.4517987729304227e+01 , 1.7760947166524492e+01 , 1.8790904000000001e+01 , -8.4257400000000005e-01 , 4.4640999999999997e-01 , -3.0130899999999999e-01 -2.2276637348813715e+01 , 1.6335425664458107e+01 , 1.7798952000000000e+01 , -6.1190900000000004e-01 , -2.9191099999999998e-01 , -7.3508899999999999e-01 -6.9381891363584067e+00 , 5.6539121035508417e+00 , 6.8443720000000008e+00 , 5.1090100000000005e-01 , 4.3009799999999998e-01 , 7.4430900000000000e-01 -6.8353917067749865e+00 , 5.6127317414659634e+00 , 6.9078951999999996e+00 , -6.6043700000000005e-01 , -3.5853900000000000e-01 , -6.5975099999999998e-01 -5.9124932322547998e+00 , 5.0204286924186752e+00 , 6.4800392000000002e+00 , 4.8630499999999999e-01 , 3.4828099999999998e-03 , 8.7378199999999995e-01 -5.8198853406100639e+00 , 4.9793931660894462e+00 , 6.5201415999999996e+00 , 8.2693300000000003e-01 , 1.1636600000000000e-02 , 5.6218000000000001e-01 -5.7585147584588139e+00 , 4.9624003894117887e+00 , 6.5913608000000004e+00 , -9.3203800000000003e-01 , 2.5421599999999999e-02 , -3.6146800000000001e-01 -5.7898722365103374e+00 , 5.0170499105676800e+00 , 6.7638967999999995e+00 , -9.4657000000000002e-01 , -3.3635699999999998e-02 , -3.2074000000000003e-01 -5.7550782958708773e+00 , 5.0218074558231320e+00 , 6.8696647999999998e+00 , 8.5694999999999999e-01 , -2.8409600000000002e-01 , 4.3003000000000002e-01 -5.9147780071963538e+00 , 5.1831632640433503e+00 , 7.2092248000000003e+00 , 7.3319000000000001e-01 , 6.7904900000000001e-01 , 3.6403199999999997e-02 -5.7963770572785638e+00 , 5.1225842800967269e+00 , 7.2258440000000004e+00 , -1.0056100000000000e-01 , -9.9435200000000001e-01 , -3.3945200000000002e-02 -5.7582965119610989e+00 , 5.1284264990591168e+00 , 7.3415856000000002e+00 , 6.1675399999999998e-02 , 9.1031200000000001e-01 , 4.0930299999999997e-01 -5.6448876223448554e+00 , 5.0713319409225424e+00 , 7.3607424000000004e+00 , -5.7260999999999995e-01 , -4.0722100000000000e-01 , -7.1153900000000003e-01 -5.6201128883303122e+00 , 5.0883818236045038e+00 , 7.4980848000000000e+00 , 1.7462600000000002e-02 , 6.1162200000000000e-01 , 7.9095700000000002e-01 -5.5550610813348786e+00 , 5.0720647699222772e+00 , 7.5824080000000000e+00 , 4.0504099999999998e-01 , -4.8130499999999998e-01 , -7.7736000000000005e-01 -5.2806629582361797e+00 , 4.8741622030225233e+00 , 7.3531920000000008e+00 , 5.4016599999999998e-02 , 6.7733699999999997e-01 , 7.3368699999999998e-01 -5.2130580503245456e+00 , 4.8529556622801113e+00 , 7.4232567999999999e+00 , -1.1291000000000000e-01 , 3.6270100000000000e-01 , -9.2503999999999997e-01 -5.0991796394785247e+00 , 4.7913196989276603e+00 , 7.4197832000000004e+00 , -6.1288600000000004e-01 , 1.0388699999999999e-01 , -7.8331200000000001e-01 -5.0826756814218879e+00 , 4.8161477771904826e+00 , 7.5763760000000007e+00 , -6.1655400000000005e-01 , 4.2460599999999998e-01 , -6.6300099999999995e-01 -5.0392043233146158e+00 , 4.8181170050161342e+00 , 7.6928144000000005e+00 , -8.6161600000000005e-01 , 4.7765999999999997e-01 , -1.7163700000000001e-01 -5.0506095644931728e+00 , 4.8746114033400296e+00 , 7.9176728000000010e+00 , 9.7246500000000002e-01 , -1.7298400000000000e-01 , -1.5617000000000000e-01 -4.7691866490372359e+00 , 4.6502204208738878e+00 , 7.5871608000000004e+00 , 2.0345500000000000e-01 , 4.3406499999999998e-01 , 8.7760700000000003e-01 -4.5754672935689653e+00 , 4.5040935168951952e+00 , 7.4002624000000008e+00 , -2.4199699999999999e-01 , -3.1409999999999999e-01 , -9.1803000000000001e-01 -4.4785191823249306e+00 , 4.4512801493618301e+00 , 7.3967472000000010e+00 , 6.8732800000000005e-01 , -3.4654900000000000e-01 , 6.3834500000000005e-01 -4.4180024439494598e+00 , 4.4345771821501412e+00 , 7.4696096000000001e+00 , -8.1440800000000002e-01 , 4.8324299999999998e-01 , -3.2127299999999998e-01 -4.4127683275485143e+00 , 4.4770446456249164e+00 , 7.6740216000000006e+00 , -8.9004700000000003e-01 , 6.6142500000000007e-02 , -4.5104499999999997e-01 -4.3692422658721428e+00 , 4.4820058457765644e+00 , 7.7999968000000006e+00 , -8.2907200000000003e-01 , -2.4371100000000000e-02 , -5.5861000000000005e-01 -4.2665849099975368e+00 , 4.4222837110602420e+00 , 7.7820567999999994e+00 , -7.8131499999999998e-01 , 1.7722900000000000e-01 , -5.9844500000000000e-01 -4.1979130730282304e+00 , 4.4011580157623111e+00 , 7.8522984000000005e+00 , 5.3495700000000002e-01 , -2.4707999999999999e-01 , 8.0794299999999997e-01 -4.3609970945078409e+00 , 4.6523472706320970e+00 , 8.5910311999999998e+00 , 2.1106400000000000e-01 , 9.6991000000000005e-01 , 1.2135200000000000e-01 -4.2822968967535004e+00 , 4.6279259546088394e+00 , 8.6743455999999988e+00 , -1.7821500000000001e-01 , -9.7946100000000003e-01 , -9.4321100000000005e-02 -4.2099801529152909e+00 , 4.6138927048127796e+00 , 8.7842839999999995e+00 , -3.4724699999999997e-01 , -9.2584000000000000e-01 , -1.4913399999999999e-01 -4.0754587116303052e+00 , 4.5193998542131171e+00 , 8.6871375999999998e+00 , 8.3614099999999997e-02 , 9.9649600000000005e-01 , 1.8373800000000000e-03 -4.0447346934274249e+00 , 4.5629716694650559e+00 , 8.9548024000000002e+00 , 4.3482199999999999e-01 , 6.8852300000000000e-01 , 5.8040099999999994e-01 -3.3900941184659450e+00 , 3.7303970022049819e+00 , 6.7855600000000003e+00 , -2.9676500000000000e-01 , 8.1717099999999998e-01 , 4.9412800000000001e-01 -3.3106037801178640e+00 , 3.6765277105487177e+00 , 6.7331128000000007e+00 , 1.4566100000000001e-01 , 7.7396900000000002e-01 , 6.1624199999999996e-01 -3.2660086514800275e+00 , 3.6722099586134158e+00 , 6.8233535999999999e+00 , -3.6789699999999997e-01 , -8.7484499999999998e-01 , -3.1511600000000001e-01 -3.5513520219382726e+00 , 4.2120804004982890e+00 , 8.5730496000000009e+00 , 6.7402399999999996e-01 , -3.6476300000000000e-01 , 6.4237000000000000e-01 -3.5892981934641250e+00 , 4.3933133335654633e+00 , 9.2962032000000008e+00 , 9.8998200000000003e-01 , 1.1640800000000000e-01 , -7.9907699999999998e-02 -3.4712264483429851e+00 , 4.3120555533395137e+00 , 9.2208135999999996e+00 , 2.0853500000000000e-01 , 9.6517100000000000e-01 , 1.5798000000000001e-01 -3.3704481939545650e+00 , 4.2630605672398847e+00 , 9.2407503999999996e+00 , 4.5182300000000002e-02 , 8.5297699999999999e-01 , 5.1998999999999995e-01 -2.9347874282506701e+00 , 3.4740900521150322e+00 , 6.7338303999999995e+00 , 2.1413499999999999e-01 , 6.9285799999999997e-01 , 6.8854499999999996e-01 -2.8835287979922608e+00 , 3.4627549877203463e+00 , 6.8089184000000005e+00 , -6.3811099999999998e-01 , 6.1634799999999998e-03 , -7.6992000000000005e-01 -2.8189390157362393e+00 , 3.4201831770287656e+00 , 6.7735376000000009e+00 , 1.8567200000000000e-01 , 4.1208400000000001e-01 , -8.9202700000000001e-01 -2.7363836384969642e+00 , 3.3167840571721596e+00 , 6.5062575999999996e+00 , -8.7272700000000003e-01 , 2.2297700000000001e-01 , 4.3431500000000001e-01 -2.6978177522670372e+00 , 3.3543094070031785e+00 , 6.7685872000000007e+00 , 4.4074400000000002e-01 , 2.7170699999999998e-01 , 8.5552399999999995e-01 -2.6435053222905185e+00 , 3.3443396617448400e+00 , 6.8603464000000001e+00 , -7.5473500000000004e-01 , -1.2671700000000000e-01 , -6.4367500000000000e-01 -2.6334962062413356e+00 , 3.6633517601895482e+00 , 8.3256855999999999e+00 , 5.1260600000000001e-01 , 5.5175700000000005e-01 , -6.5787600000000002e-01 -2.5314783621172676e+00 , 3.3823604244500154e+00 , 7.3045200000000001e+00 , 4.3042100000000000e-01 , -7.6395699999999997e-02 , -8.9938899999999999e-01 -2.4642365904391221e+00 , 3.3415431180697834e+00 , 7.2825655999999999e+00 , -1.4521000000000001e-01 , 5.5311200000000005e-01 , 8.2035400000000003e-01 -2.3973228769526425e+00 , 3.3137702062138090e+00 , 7.3201824000000002e+00 , 2.8591800000000001e-01 , 7.5144599999999995e-01 , 5.9462599999999999e-01 -2.3077337362653001e+00 , 3.4406691212314859e+00 , 8.1100728000000011e+00 , -2.0205400000000001e-01 , 9.2226399999999997e-01 , 3.2955099999999998e-01 -2.2270583688168446e+00 , 3.4067745654801809e+00 , 8.1565295999999989e+00 , -9.3213400000000002e-01 , 2.7861300000000000e-01 , 2.3130300000000001e-01 -2.1572410835822469e+00 , 3.3320831567631055e+00 , 7.9870200000000002e+00 , -1.4552699999999999e-01 , -6.2397499999999995e-01 , -7.6777399999999996e-01 -2.0810694554314884e+00 , 3.2871211435829979e+00 , 7.9689344000000002e+00 , -3.4477399999999998e-02 , -4.2395100000000002e-01 , 9.0502899999999997e-01 -2.0021768893456482e+00 , 3.2512003866620516e+00 , 8.0004048000000001e+00 , -5.4639000000000004e-01 , -5.1272600000000002e-01 , -6.6224600000000000e-01 -1.7277558557786892e+00 , 3.5119232423153894e+00 , 9.8472888000000012e+00 , -1.3031300000000001e-01 , -6.8132400000000004e-01 , 7.2028899999999996e-01 -4.6644563127715575e+00 , 3.0852939347588908e+00 , 1.1149995200000000e+00 , -9.4572500000000004e-02 , 2.0453600000000000e-01 , 9.7428000000000003e-01 -4.7303307080174664e+00 , 3.1198534052946982e+00 , 1.1213986399999998e+00 , 8.5191199999999995e-02 , -2.1022199999999999e-01 , -9.7393500000000000e-01 -4.8194424199637371e+00 , 3.1626410333257815e+00 , 1.1103444800000000e+00 , -5.5647900000000000e-02 , 2.0406199999999999e-01 , 9.7737499999999999e-01 -4.8939918173628518e+00 , 3.2006812641992566e+00 , 1.1148039999999999e+00 , -6.3984700000000005e-02 , 1.8477700000000000e-01 , 9.8069499999999998e-01 -4.9764024555574080e+00 , 3.2418717580424672e+00 , 1.1154768800000001e+00 , -6.0482500000000002e-02 , 1.9753999999999999e-01 , 9.7842700000000005e-01 -5.0677267242313118e+00 , 3.2872503602194278e+00 , 1.1124868800000001e+00 , -4.9612700000000003e-02 , 2.0291799999999999e-01 , 9.7793799999999997e-01 -5.1515805183917962e+00 , 3.3294878756152393e+00 , 1.1186717599999998e+00 , -5.5712900000000003e-02 , 2.0955399999999999e-01 , 9.7620899999999999e-01 -5.2432554631865340e+00 , 3.3760156941982249e+00 , 1.1214724800000000e+00 , -6.4976300000000001e-02 , 1.9762700000000000e-01 , 9.7812100000000002e-01 -5.3528404590252094e+00 , 3.4296737404753301e+00 , 1.1160384799999998e+00 , -6.2809900000000002e-02 , 2.0855799999999999e-01 , 9.7599100000000005e-01 -5.4620017636933440e+00 , 3.4840608653424416e+00 , 1.1141467199999999e+00 , -5.0814300000000000e-02 , 1.9248199999999999e-01 , 9.7998399999999997e-01 -5.5728153839033219e+00 , 3.5391437229672826e+00 , 1.1160457600000000e+00 , 2.5350200000000001e-01 , -1.5779399999999999e-01 , -9.5437799999999995e-01 -5.6742033060001926e+00 , 3.5931404124067416e+00 , 1.1263594399999999e+00 , -8.2771200000000000e-01 , 1.7140400000000000e-01 , 5.3433399999999998e-01 -5.6829332270298156e+00 , 3.6119500402275930e+00 , 1.1952334400000000e+00 , 9.7061399999999998e-01 , -5.6534899999999999e-02 , -2.3390500000000000e-01 -5.7076244038324280e+00 , 3.6366151600454359e+00 , 1.2544104800000000e+00 , 9.7414699999999999e-01 , -2.0999799999999999e-01 , -8.3301399999999998e-02 -5.6792436710133050e+00 , 3.6416678155642668e+00 , 1.3419555999999999e+00 , 9.9780300000000000e-01 , -4.6318200000000000e-03 , 6.6094500000000000e-02 -5.6658691105127552e+00 , 3.6524714948806252e+00 , 1.4190716000000001e+00 , 9.8903700000000005e-01 , 9.1294100000000003e-02 , -1.1606700000000000e-01 -5.6604591043904957e+00 , 3.6651305508923318e+00 , 1.4912902400000001e+00 , 9.9061500000000002e-01 , 1.3666700000000001e-01 , 1.8193400000000000e-03 -5.6529982368542324e+00 , 3.6767042895503774e+00 , 1.5629576800000000e+00 , 9.8831500000000005e-01 , 1.0011100000000001e-01 , 1.1494100000000000e-01 -5.6456006612429483e+00 , 3.6881751925053212e+00 , 1.6341186400000001e+00 , 9.7436500000000004e-01 , -2.3954099999999999e-02 , -2.2369500000000000e-01 -5.6450894774361817e+00 , 3.7026847001007326e+00 , 1.7007608000000001e+00 , 9.8888600000000004e-01 , 9.5951400000000006e-02 , -1.1356800000000000e-01 -5.7058471675614513e+00 , 3.7422268807178929e+00 , 1.7413405600000000e+00 , 9.7627799999999998e-01 , 9.1565499999999994e-02 , 1.9620699999999999e-01 -5.6043669861987242e+00 , 3.7138648486388881e+00 , 1.8476940799999999e+00 , 9.8446999999999996e-01 , 4.5587000000000003e-02 , 1.6952900000000001e-01 -5.6185659082136343e+00 , 3.7335443385539469e+00 , 1.9062361999999999e+00 , -9.1795899999999997e-01 , 3.5339900000000000e-02 , 3.9509899999999998e-01 -5.6404892944816201e+00 , 3.7565776966839080e+00 , 1.9620037040000000e+00 , -8.8695000000000002e-01 , 6.4861100000000005e-02 , 4.5728799999999997e-01 -5.6799963545956649e+00 , 3.7873043859470688e+00 , 2.0122681519999999e+00 , -7.8182499999999999e-01 , 1.3637700000000000e-01 , 6.0840000000000005e-01 -5.7369563723837338e+00 , 3.8259504631344554e+00 , 2.0581424479999999e+00 , 4.8100599999999999e-01 , -1.8474699999999999e-01 , -8.5703099999999999e-01 -5.8582686756310913e+00 , 3.8924784272315254e+00 , 2.0874584880000002e+00 , -2.7454699999999999e-01 , 1.7416899999999999e-01 , 9.4566899999999998e-01 -6.0064365963773669e+00 , 3.9730986865551294e+00 , 2.1133964000000001e+00 , -2.0403299999999999e-01 , 1.7911700000000000e-01 , 9.6243800000000002e-01 -6.5802582181213936e+00 , 4.2603166816913962e+00 , 2.1172267200000001e+00 , -3.2251400000000000e-02 , 1.3884900000000000e-01 , 9.8978800000000000e-01 -7.0534647183330819e+00 , 4.4915054844194815e+00 , 2.0955409519999999e+00 , -4.7040800000000001e-02 , 4.5310900000000001e-02 , 9.9786500000000000e-01 -1.1791304492173667e+01 , 6.6786371607231692e+00 , 1.2607368000000001e+00 , -5.7069599999999998e-02 , 1.8816900000000000e-01 , 9.8047700000000004e-01 -1.2754796323656915e+01 , 7.1625057958845071e+00 , 1.2696735200000000e+00 , -6.8269099999999999e-02 , 1.9053300000000001e-01 , 9.7930399999999995e-01 -1.3921933585755614e+01 , 7.7489263430202620e+00 , 1.2829283199999999e+00 , -4.7016099999999998e-02 , 1.8795999999999999e-01 , 9.8105100000000001e-01 -1.5573855672068733e+01 , 8.5722359769338432e+00 , 1.2738366399999999e+00 , -7.2710600000000000e-02 , 1.8568999999999999e-01 , 9.7991499999999998e-01 -1.7092901710090359e+01 , 9.3459122525709795e+00 , 1.3429196800000001e+00 , -6.1830099999999999e-02 , 1.9193800000000000e-01 , 9.7945700000000002e-01 -2.0785117051894126e+01 , 1.1172661977116148e+01 , 1.2527069599999998e+00 , -9.1299900000000003e-02 , 1.6637900000000000e-01 , 9.8182599999999998e-01 -2.3770170168013525e+01 , 1.2774364698603540e+01 , 1.7654030400000000e+00 , 5.0534999999999997e-01 , -1.0635900000000000e-01 , -8.5633499999999996e-01 -2.5160986467209607e+01 , 1.3544586396279296e+01 , 2.1116117600000002e+00 , -7.6208500000000001e-01 , -1.8795400000000001e-01 , 6.1959600000000004e-01 -2.4958905075464326e+01 , 1.3538491938005526e+01 , 2.5493540000000001e+00 , -8.9736700000000003e-01 , -2.8429300000000002e-01 , 3.3750599999999997e-01 -2.4963854060534842e+01 , 1.3634478898156015e+01 , 2.9794158400000001e+00 , -9.3818999999999997e-01 , -3.0626900000000001e-01 , -1.6124200000000000e-01 -2.5193481884203386e+01 , 1.3842852503253321e+01 , 3.4144624000000001e+00 , 8.6512900000000004e-01 , 1.0755500000000000e-01 , 4.8988100000000001e-01 -2.4220009555444033e+01 , 1.3443816044971522e+01 , 3.8191264000000000e+00 , 7.8180400000000005e-01 , -2.3172300000000001e-01 , 5.7886700000000002e-01 -2.1135095332566927e+01 , 1.1957835931837746e+01 , 4.0756112000000000e+00 , 9.0674600000000005e-01 , -4.0317700000000001e-01 , 1.2353200000000000e-01 -2.1500297455982128e+01 , 1.2224518285234121e+01 , 4.4651952000000001e+00 , 6.7617099999999997e-01 , -7.3400799999999999e-01 , 6.3440200000000002e-02 -2.1590447604269333e+01 , 1.2352483948452166e+01 , 4.8455752000000007e+00 , 6.7617099999999997e-01 , -7.3400799999999999e-01 , 6.3440300000000005e-02 -2.1857383400165972e+01 , 1.2573641123726377e+01 , 5.2517991999999998e+00 , -6.3358099999999995e-01 , -7.3523600000000000e-01 , 2.4084000000000000e-01 -2.1322026645494788e+01 , 1.2374220622501205e+01 , 5.5654320000000004e+00 , -6.9503599999999999e-01 , 7.1557599999999999e-01 , -6.9825600000000002e-02 -2.1603188777136257e+01 , 1.2604766483003679e+01 , 5.9845520000000008e+00 , -8.7535900000000000e-01 , 4.3294400000000000e-01 , -2.1519099999999999e-01 -2.1195600598096735e+01 , 1.2469182152536606e+01 , 6.2997448000000000e+00 , -9.1896599999999995e-01 , 3.9093499999999998e-01 , -5.1681499999999998e-02 -2.1750152782109996e+01 , 1.2852401537607498e+01 , 6.7864751999999999e+00 , -8.4882299999999999e-01 , 5.1155600000000001e-01 , 1.3345699999999999e-01 -2.1090553659423080e+01 , 1.2577507849373941e+01 , 7.0416183999999999e+00 , -9.1550699999999996e-01 , 3.9920200000000000e-01 , 4.9851600000000003e-02 -3.0491108394122257e+01 , 1.7834235131711260e+01 , 9.6199240000000010e+00 , -6.7512099999999997e-01 , 7.0803199999999999e-01 , 2.0712800000000001e-01 -2.2559578204139967e+01 , 1.3560257128858547e+01 , 8.1904959999999996e+00 , 8.5519900000000004e-01 , -4.7753099999999998e-01 , -2.0149000000000000e-01 -2.2987815561059051e+01 , 1.3892361127178225e+01 , 8.7339376000000009e+00 , 7.7939400000000003e-01 , -5.7013899999999995e-01 , -2.5978299999999999e-01 -2.0307742772216372e+01 , 1.2475946060255806e+01 , 8.3785176000000003e+00 , -9.6334799999999998e-01 , -2.4016999999999999e-01 , 1.1949500000000000e-01 -2.0312359182791113e+01 , 1.2562580520729485e+01 , 8.7672799999999995e+00 , -9.2635699999999999e-01 , -3.6939499999999997e-01 , -7.3550199999999996e-02 -2.0206504994604426e+01 , 1.2586943375060960e+01 , 9.1239272000000007e+00 , -9.2635699999999999e-01 , -3.6939499999999997e-01 , -7.3550199999999996e-02 -2.0196953584853244e+01 , 1.2667564865073022e+01 , 9.5166415999999998e+00 , 9.5805399999999996e-01 , 2.8310099999999999e-01 , 4.4567000000000002e-02 -2.0436437217126716e+01 , 1.2893800569843744e+01 , 1.0010839199999999e+01 , -9.5144700000000004e-01 , -2.1520800000000001e-01 , 2.2007599999999999e-01 -2.1612112252492178e+01 , 1.3675240718731851e+01 , 1.0904375999999999e+01 , -6.8243100000000001e-01 , -2.5804400000000000e-01 , -6.8388700000000002e-01 -2.0554440827287941e+01 , 1.3144531799556116e+01 , 1.0895837600000000e+01 , -7.0483099999999999e-01 , 6.8808000000000002e-01 , -1.7250900000000000e-01 -2.0786832223915088e+01 , 1.3376439558058685e+01 , 1.1432383999999999e+01 , 5.1099099999999997e-01 , 2.6998800000000001e-01 , 8.1608499999999995e-01 -2.0208700910555212e+01 , 1.3123673708535954e+01 , 1.1598596799999999e+01 , 9.7838800000000004e-01 , 5.4174500000000000e-02 , 1.9955300000000001e-01 -2.0030805899601635e+01 , 1.3110289431309788e+01 , 1.1947485600000000e+01 , -8.9566999999999997e-01 , -1.2487200000000000e-01 , -4.2682799999999999e-01 -2.1286935220007699e+01 , 1.3978010860348139e+01 , 1.3054472000000001e+01 , -6.2520200000000004e-01 , -6.2034999999999996e-01 , -4.7359099999999998e-01 -2.0061294367859471e+01 , 1.3323182237067265e+01 , 1.2857808000000000e+01 , -8.8052799999999998e-01 , 4.6596199999999999e-01 , -8.6886599999999994e-02 -2.0481864256466483e+01 , 1.3685258800379671e+01 , 1.3564072000000001e+01 , 4.0358699999999997e-01 , 8.1039600000000001e-01 , 4.2470700000000000e-01 -2.0132437723750478e+01 , 1.3570038530685892e+01 , 1.3834680000000001e+01 , -8.8616300000000003e-01 , 4.1114600000000001e-01 , -2.1371299999999999e-01 -2.2540214218714006e+01 , 1.5209479953632526e+01 , 1.5850304000000001e+01 , 2.3452100000000001e-01 , -5.7878399999999997e-01 , 7.8103100000000003e-01 -2.4216140230760043e+01 , 1.6409589339941739e+01 , 1.7526783999999999e+01 , 4.6792200000000000e-01 , -7.4457099999999998e-01 , -4.7609200000000002e-01 -1.9200672035234877e+01 , 1.3286675265297427e+01 , 1.4680200000000001e+01 , 4.7651199999999999e-01 , 9.2298000000000005e-02 , 8.7431000000000003e-01 -2.0577472358372429e+01 , 1.4297218856139674e+01 , 1.6168751999999998e+01 , 5.7435000000000003e-01 , 9.3753399999999994e-03 , 8.1855599999999995e-01 -2.2383524678363255e+01 , 1.5612874787019011e+01 , 1.8077359999999999e+01 , 1.3033300000000000e-01 , 5.7475900000000002e-01 , 8.0787699999999996e-01 -2.2382787521880918e+01 , 1.5746335056527508e+01 , 1.8697512000000000e+01 , 1.3033200000000000e-01 , 5.7475900000000002e-01 , 8.0787699999999996e-01 -6.8374212793033511e+00 , 5.5758648724175597e+00 , 7.6002232000000003e+00 , 2.1272600000000000e-01 , -4.9414900000000000e-01 , 8.4294999999999998e-01 -6.6423586702712569e+00 , 5.4716995429310540e+00 , 7.5685968000000008e+00 , -8.0617399999999995e-01 , -9.4608600000000001e-02 , -5.8406499999999995e-01 -6.5687692376022806e+00 , 5.4545219718123494e+00 , 7.6626752000000007e+00 , -5.1767799999999997e-01 , -5.6543500000000002e-01 , -6.4210000000000000e-01 -6.5546747215094037e+00 , 5.4837965665884969e+00 , 7.8260072000000003e+00 , -4.8226300000000000e-01 , -8.3632600000000001e-01 , -2.6073200000000002e-01 -6.4298621094809407e+00 , 5.4283590694480939e+00 , 7.8615544000000011e+00 , 6.2426599999999999e-01 , 7.4972399999999995e-01 , 2.1955800000000000e-01 -5.8651156420746613e+00 , 5.0342868589670600e+00 , 7.3450800000000003e+00 , -6.9107900000000000e-01 , -6.1397699999999999e-01 , -3.8136799999999998e-01 -6.3985473569527400e+00 , 5.4873039619455577e+00 , 8.2054095999999994e+00 , -7.5582400000000005e-01 , -6.4514300000000002e-01 , -1.1189499999999999e-01 -5.8161815806249724e+00 , 5.0701667711625777e+00 , 7.6234152000000011e+00 , 3.9962300000000001e-01 , 5.9007100000000001e-01 , 7.0151100000000000e-01 -5.5728238075913614e+00 , 4.9147629145716891e+00 , 7.4642327999999996e+00 , -1.2209600000000000e-01 , 4.6868399999999999e-01 , 8.7488699999999997e-01 -5.4440602318542473e+00 , 4.8468836756234470e+00 , 7.4529176000000001e+00 , 2.3972499999999999e-01 , 5.5052700000000003e-02 , -9.6927900000000000e-01 -5.3731368981722554e+00 , 4.8272328767126442e+00 , 7.5247296000000006e+00 , -1.1257900000000000e-01 , 5.1682899999999998e-01 , 8.4865400000000002e-01 -5.1900447308444377e+00 , 4.7129088084400248e+00 , 7.4188888000000004e+00 , 1.4735100000000001e-01 , 4.0349800000000002e-01 , 9.0303800000000001e-01 -5.1552241731520176e+00 , 4.7224043093740882e+00 , 7.5429192000000000e+00 , 5.2705700000000000e-01 , -2.1674599999999999e-01 , 8.2172500000000004e-01 -5.0160825803946114e+00 , 4.6421706100553362e+00 , 7.4944552000000000e+00 , 1.4309600000000000e-01 , 2.3345500000000000e-01 , 9.6178100000000000e-01 -4.8065601154896918e+00 , 4.4968938593647767e+00 , 7.3084096000000001e+00 , -2.1355800000000000e-01 , -4.1324400000000000e-01 , 8.8522400000000001e-01 -4.7788366604182073e+00 , 4.5137280215601265e+00 , 7.4440568000000003e+00 , -4.0370000000000000e-01 , -3.5442000000000001e-01 , 8.4345300000000001e-01 -4.6217498632769534e+00 , 4.4110424171938742e+00 , 7.3330055999999999e+00 , -6.7981399999999997e-02 , -2.0715700000000001e-01 , 9.7594300000000000e-01 -4.4534779149593131e+00 , 4.2934405338425199e+00 , 7.1824552000000006e+00 , 2.5460800000000000e-01 , -1.4499899999999999e-01 , 9.5611199999999996e-01 -4.4240750246193858e+00 , 4.3074617725659081e+00 , 7.3143064000000004e+00 , 2.5603700000000001e-01 , -7.9988700000000001e-01 , 5.4279400000000000e-01 -4.4349061769085143e+00 , 4.3627574218639289e+00 , 7.5436264000000000e+00 , 9.7831999999999997e-01 , 2.0614399999999999e-01 , -1.9856200000000001e-02 -4.3862347667985899e+00 , 4.3620065376974555e+00 , 7.6507151999999996e+00 , -9.1626700000000005e-01 , -1.9385100000000000e-01 , -3.5053899999999999e-01 -4.3533652395445728e+00 , 4.3781052736135884e+00 , 7.8026904000000004e+00 , -4.1195700000000002e-01 , -3.6726500000000001e-01 , -8.3391099999999996e-01 -4.2636389960756205e+00 , 4.3364123379818720e+00 , 7.8190080000000002e+00 , 1.8376600000000001e-01 , 1.0192200000000000e-01 , 9.7767199999999999e-01 -4.3931896565419244e+00 , 4.5351532678561792e+00 , 8.4378391999999991e+00 , 7.7251199999999998e-01 , 5.8898899999999998e-01 , -2.3731400000000000e-01 -4.3794704633821100e+00 , 4.5863424607234613e+00 , 8.7047656000000000e+00 , -1.7821500000000001e-01 , -9.7946100000000003e-01 , -9.4321000000000002e-02 -3.8043421133786115e+00 , 3.9856180020715986e+00 , 7.2605903999999999e+00 , 4.1116399999999997e-01 , 6.5899600000000003e-01 , -6.2981600000000004e-01 -3.7370417653474846e+00 , 3.9618097061525450e+00 , 7.3019408000000006e+00 , 7.7100800000000003e-01 , -7.2102899999999998e-02 , -6.3273000000000001e-01 -3.6832708822161035e+00 , 3.9541781579117656e+00 , 7.3896439999999997e+00 , 7.7100800000000003e-01 , -7.2102700000000006e-02 , -6.3273000000000001e-01 -3.4721732905436911e+00 , 3.7417613466696524e+00 , 6.8963615999999996e+00 , -2.2838500000000000e-01 , 8.7304000000000004e-01 , 4.3086200000000002e-01 -3.3894362896104937e+00 , 3.6893031711030151e+00 , 6.8449544000000007e+00 , -2.0604000000000000e-01 , 9.2022300000000001e-01 , 3.3277200000000001e-01 -3.3273644061012737e+00 , 3.6627876463973301e+00 , 6.8687704000000007e+00 , -2.2145800000000000e-02 , 9.7735899999999998e-01 , 2.1042400000000000e-01 -3.6033473993971117e+00 , 4.1480638177738669e+00 , 8.4719304000000015e+00 , -9.3763799999999997e-01 , -1.6291100000000000e-03 , -3.4761100000000000e-01 -3.7130258335948447e+00 , 4.4291330301650031e+00 , 9.5162256000000003e+00 , 1.8290100000000001e-01 , 1.7565500000000001e-01 , 9.6731199999999995e-01 -3.5466736529215055e+00 , 4.2784515563247698e+00 , 9.2071480000000001e+00 , 3.4601500000000002e-01 , -8.7889300000000004e-02 , 9.3410400000000005e-01 -3.4685639240123267e+00 , 4.2763492424436986e+00 , 9.3750768000000004e+00 , 4.0246500000000002e-01 , -3.7273299999999998e-01 , 8.3611700000000000e-01 -3.3637179456140718e+00 , 4.2284185391353528e+00 , 9.3940984000000007e+00 , -5.3817400000000004e-01 , 2.7755200000000002e-01 , 7.9582200000000003e-01 -2.9236614887461077e+00 , 3.4419208264025469e+00 , 6.7773232000000005e+00 , -5.3545699999999996e-01 , -5.1378500000000005e-01 , -6.7030599999999996e-01 -2.8580080755469068e+00 , 3.4005129051630671e+00 , 6.7422231999999997e+00 , -2.9811100000000001e-01 , 9.3683699999999995e-02 , 9.4992299999999996e-01 -2.8130938022228751e+00 , 3.4161437936373087e+00 , 6.9156432000000008e+00 , 2.2313100000000000e-01 , -2.9051500000000002e-01 , 9.3049099999999996e-01 -2.7368421602911792e+00 , 3.3419944814194951e+00 , 6.7474023999999995e+00 , -4.3377500000000002e-01 , 4.7369600000000001e-03 , -9.0100899999999995e-01 -2.6808844695868710e+00 , 3.3270539893181161e+00 , 6.8088872000000000e+00 , -7.2776900000000000e-01 , 5.3083000000000004e-04 , -6.8582200000000004e-01 -2.6931059248088940e+00 , 3.6809956869264315e+00 , 8.4154480000000014e+00 , -4.5984100000000000e-01 , -6.2483599999999995e-01 , 6.3097300000000001e-01 -2.5800274236515914e+00 , 3.4273471738837813e+00 , 7.5065192000000005e+00 , -5.9763800000000000e-01 , -8.0064400000000002e-01 , -4.2399699999999999e-02 -2.5059439525203100e+00 , 3.3469096654379040e+00 , 7.3023047999999999e+00 , 2.8548499999999999e-01 , -1.1778700000000000e-01 , -9.5111699999999999e-01 -2.4385641512975438e+00 , 3.3121023362326047e+00 , 7.2996319999999999e+00 , 3.0902000000000002e-01 , 6.9499500000000003e-01 , 6.4922100000000005e-01 -2.3523922388422691e+00 , 3.4821294421321110e+00 , 8.2832639999999991e+00 , 5.9921999999999997e-01 , 2.9994799999999999e-01 , -7.4227100000000001e-01 -2.2693347066589964e+00 , 3.4391884978250018e+00 , 8.2790312000000004e+00 , 5.3536099999999998e-01 , -1.8688700000000000e-01 , 8.2368799999999998e-01 -2.2017268023480909e+00 , 3.3388618268324199e+00 , 7.9669168000000008e+00 , -3.0611200000000000e-01 , 6.0354099999999999e-01 , 7.3622900000000002e-01 -2.1214567283717667e+00 , 3.3075431362722787e+00 , 8.0104199999999999e+00 , 4.7735400000000000e-01 , 5.5462999999999998e-02 , -8.7695900000000004e-01 -2.0458083527311324e+00 , 3.2613713626526417e+00 , 7.9706296000000005e+00 , -2.9838199999999998e-01 , 1.6875899999999999e-01 , -9.3940900000000005e-01 -1.7786882539808122e+00 , 3.5427173803351559e+00 , 9.8897936000000009e+00 , -1.4835999999999999e-01 , -6.3337500000000002e-01 , 7.5949000000000000e-01 -1.7320712581028437e+00 , 3.4043270194746689e+00 , 9.3563568000000004e+00 , -6.2735300000000005e-01 , -2.2582500000000000e-01 , 7.4527200000000005e-01 -4.6542143302932395e+00 , 3.0118584667690405e+00 , 1.1277832000000001e+00 , -9.9539400000000000e-02 , 1.6606699999999999e-01 , 9.8107800000000001e-01 -4.7365137018837231e+00 , 3.0492529478250736e+00 , 1.1201402400000000e+00 , -6.0372599999999998e-02 , 1.7812500000000001e-01 , 9.8215399999999997e-01 -4.7950259634888681e+00 , 3.0794039931974080e+00 , 1.1347075200000001e+00 , -6.3447299999999998e-02 , 1.9524500000000000e-01 , 9.7870000000000001e-01 -4.8788133333768560e+00 , 3.1166820123960619e+00 , 1.1320752800000000e+00 , -5.3858499999999997e-02 , 2.0141999999999999e-01 , 9.7802299999999998e-01 -4.9623517286471559e+00 , 3.1555023516916307e+00 , 1.1317664000000001e+00 , -7.7308000000000002e-02 , 1.7137800000000000e-01 , 9.8216800000000004e-01 -5.0455828239044607e+00 , 3.1948440320099594e+00 , 1.1339868000000000e+00 , -5.8254700000000000e-02 , 1.9186900000000001e-01 , 9.7968999999999995e-01 -5.1387411728501142e+00 , 3.2383988963509416e+00 , 1.1328719199999999e+00 , -4.3580599999999997e-02 , 1.9108100000000000e-01 , 9.8060599999999998e-01 -5.2395907982087486e+00 , 3.2842673389622092e+00 , 1.1290863199999999e+00 , -5.8354999999999997e-02 , 2.0057000000000000e-01 , 9.7794000000000003e-01 -5.3341138597164450e+00 , 3.3289944568596379e+00 , 1.1340918400000000e+00 , -7.0186100000000001e-02 , 1.7478500000000000e-01 , 9.8210200000000003e-01 -5.4282765219785789e+00 , 3.3743478176439696e+00 , 1.1421320800000001e+00 , -6.7296300000000003e-02 , 2.0688000000000001e-01 , 9.7604900000000006e-01 -5.5472657311740452e+00 , 3.4287268851151698e+00 , 1.1370163199999999e+00 , 1.4677200000000001e-01 , -1.6960200000000000e-01 , -9.7452200000000000e-01 -5.6678487161567741e+00 , 3.4838810778546612e+00 , 1.1360980000000001e+00 , -5.5693700000000002e-01 , 1.3319900000000001e-01 , 8.1980399999999998e-01 -5.7027544822512919e+00 , 3.5111325174963595e+00 , 1.1892097600000000e+00 , -8.3053999999999994e-01 , -7.6106599999999996e-02 , 5.5173499999999998e-01 -5.6844323391408658e+00 , 3.5201692424390965e+00 , 1.2723068000000000e+00 , 9.8670700000000000e-01 , 9.5544699999999996e-02 , -1.3145599999999999e-01 -5.6911454208041725e+00 , 3.5378304134584648e+00 , 1.3403259199999999e+00 , 9.8748899999999995e-01 , 9.4532900000000003e-02 , 1.2620999999999999e-01 -5.6957690734515012e+00 , 3.5544918304952970e+00 , 1.4081973600000000e+00 , 9.9124400000000001e-01 , 1.7482399999999999e-02 , -1.3087900000000000e-01 -5.6914446525964184e+00 , 3.5681296695001588e+00 , 1.4802350399999999e+00 , 9.8005100000000001e-01 , 8.9650099999999996e-02 , -1.7737600000000001e-01 -5.7298327329870862e+00 , 3.5968383050947894e+00 , 1.5307852799999999e+00 , 9.8919400000000002e-01 , 1.4649899999999999e-01 , -5.7573199999999998e-03 -5.6597528591796387e+00 , 3.5850666949895453e+00 , 1.6313200000000001e+00 , 9.6858500000000003e-01 , 1.8075100000000000e-01 , 1.7079900000000001e-01 -5.6682044871219830e+00 , 3.6025794228546664e+00 , 1.6936950399999999e+00 , -9.3312899999999999e-01 , 9.9127199999999999e-02 , 3.4560600000000002e-01 -5.6855259517789598e+00 , 3.6232399414863630e+00 , 1.7525101599999999e+00 , 9.8726700000000001e-01 , -2.6363999999999999e-02 , -1.5687100000000001e-01 -5.6286055211621910e+00 , 3.6157552011380512e+00 , 1.8402424799999999e+00 , -9.5851100000000000e-01 , -1.3576500000000000e-01 , -2.5064799999999998e-01 -5.6349876314810299e+00 , 3.6311229832118768e+00 , 1.9020674639999999e+00 , -9.3236399999999997e-01 , 6.5472799999999998e-02 , 3.5554200000000002e-01 -5.6392989689933941e+00 , 3.6465506397408012e+00 , 1.9637427919999999e+00 , -9.1021900000000000e-01 , 7.2238499999999997e-02 , 4.0777700000000000e-01 -5.6798848192726972e+00 , 3.6749916909356442e+00 , 2.0134304560000000e+00 , 8.5976799999999998e-01 , -8.5761900000000002e-02 , -5.0343300000000002e-01 -5.7105228768796952e+00 , 3.7014671600397913e+00 , 2.0670548320000002e+00 , -6.1601300000000003e-01 , 1.6303599999999999e-01 , 7.7067900000000000e-01 -5.8329836828028547e+00 , 3.7633763483880207e+00 , 2.0947879920000001e+00 , 3.6004000000000003e-01 , -1.9388900000000001e-01 , -9.1256700000000002e-01 -5.9549714096696080e+00 , 3.8272005226595374e+00 , 2.1266668000000002e+00 , -2.1822600000000000e-01 , 1.6957800000000001e-01 , 9.6105200000000002e-01 -6.1330581166737606e+00 , 3.9142877969669740e+00 , 2.1489155200000001e+00 , -1.7731700000000000e-01 , 1.7767400000000000e-01 , 9.6798300000000004e-01 -7.0064062687314186e+00 , 4.3099959066901281e+00 , 2.1016143440000001e+00 , -7.5219200000000000e-02 , 1.0760300000000000e-01 , 9.9134400000000000e-01 -7.0900209405833357e+00 , 4.3629927867754361e+00 , 2.1717185600000000e+00 , -7.5219200000000000e-02 , 1.0760300000000000e-01 , 9.9134400000000000e-01 -1.2347726831632698e+01 , 6.6218043419743235e+00 , 1.3293040000000000e+00 , -6.8140800000000001e-02 , 1.8446799999999999e-01 , 9.8047399999999996e-01 -1.3333410668334094e+01 , 7.0857119565105107e+00 , 1.3598342400000001e+00 , -6.0761799999999998e-02 , 1.8966000000000000e-01 , 9.7996799999999995e-01 -1.4847599847573798e+01 , 7.7859800469175768e+00 , 1.3535048000000001e+00 , -4.5479100000000001e-02 , 1.8771599999999999e-01 , 9.8116999999999999e-01 -1.6322812977592790e+01 , 8.4811699663837707e+00 , 1.4085166400000000e+00 , -8.0961500000000006e-02 , 1.8570600000000001e-01 , 9.7926400000000002e-01 -1.8580961216527530e+01 , 9.5348624632138126e+00 , 1.4389075199999999e+00 , 3.9474900000000000e-02 , -1.9121500000000000e-01 , -9.8075400000000001e-01 -2.1194083696150816e+01 , 1.0764876139394456e+01 , 1.5242187199999999e+00 , -1.0958600000000000e-01 , 1.7120400000000000e-01 , 9.7912200000000005e-01 -2.3573893645838655e+01 , 1.1909913502668052e+01 , 1.7229398400000000e+00 , -9.7238800000000003e-01 , -1.3262699999999999e-01 , 1.9202300000000000e-01 -2.4421250017281086e+01 , 1.2378825037506498e+01 , 2.0808902640000002e+00 , 4.8031099999999999e-01 , -7.9074300000000000e-02 , -8.7352700000000005e-01 -2.5421679646316022e+01 , 1.2924416834020693e+01 , 2.4673406400000002e+00 , -8.7195699999999998e-01 , -1.9962800000000000e-01 , 4.4703399999999999e-01 -2.5242176377484935e+01 , 1.2932576897721075e+01 , 2.9017080800000001e+00 , -8.7195699999999998e-01 , -1.9962800000000000e-01 , 4.4703399999999999e-01 -2.4819619856468641e+01 , 1.2827384634680659e+01 , 3.3276224000000001e+00 , 5.9707900000000003e-01 , -1.6775100000000001e-01 , 7.8444599999999998e-01 -2.3658342479917387e+01 , 1.2371718653038316e+01 , 3.7168320000000001e+00 , 7.8605999999999998e-01 , -4.5862900000000001e-01 , 4.1444999999999999e-01 -2.3753556589804173e+01 , 1.2502971086701340e+01 , 4.1251256000000005e+00 , -7.7162600000000003e-01 , 1.0209100000000000e-01 , -6.2783000000000000e-01 -2.3859616254742548e+01 , 1.2639350803834501e+01 , 4.5400543999999998e+00 , 7.8386800000000001e-01 , -6.1156699999999997e-01 , -1.0740600000000000e-01 -2.3931557315510812e+01 , 1.2760823859942333e+01 , 4.9579887999999999e+00 , -1.2938900000000000e-01 , 9.4288799999999995e-01 , 3.0695299999999998e-01 -2.0792548401849977e+01 , 1.1323408859688206e+01 , 5.0381415999999994e+00 , 7.9478000000000004e-01 , -5.8280399999999999e-01 , 1.6930700000000001e-01 -2.0794403902166906e+01 , 1.1399583104065252e+01 , 5.3956104000000007e+00 , -7.4679499999999999e-01 , 6.5817000000000003e-01 , 9.5447400000000002e-02 -2.4239032524736260e+01 , 1.3179317361635166e+01 , 6.2575311999999998e+00 , 9.1797799999999996e-01 , 3.9191700000000002e-01 , -6.0962799999999998e-02 -2.1287649598951614e+01 , 1.1798368249211862e+01 , 6.1994368000000000e+00 , -8.1725199999999998e-01 , 5.4803700000000000e-01 , 1.7819499999999999e-01 -2.1232643046116007e+01 , 1.1850908235905651e+01 , 6.5644767999999996e+00 , -9.0412999999999999e-01 , 4.2720200000000003e-01 , 6.9007900000000004e-03 -2.1099146044135729e+01 , 1.1863491707510812e+01 , 6.9146239999999999e+00 , 9.5496800000000004e-01 , -2.3288800000000001e-01 , -1.8384500000000001e-01 -2.1368169988502590e+01 , 1.2081676483759605e+01 , 7.3541072000000005e+00 , -8.8232900000000003e-01 , 3.9719199999999999e-01 , 2.5245400000000001e-01 -2.1538054359572342e+01 , 1.2251315177774840e+01 , 7.7842200000000004e+00 , 7.7775399999999995e-01 , 6.2360700000000002e-01 , 7.8818299999999994e-02 -2.2730842666492862e+01 , 1.2955661668435287e+01 , 8.4991160000000008e+00 , 7.9591199999999995e-01 , -5.5984500000000004e-01 , -2.3042799999999999e-01 -2.7748625628455390e+01 , 1.5679255803241452e+01 , 1.0370835200000000e+01 , 5.6269400000000003e-01 , -2.1098800000000001e-01 , 7.9928699999999997e-01 -2.1850778799857871e+01 , 1.2671658004057319e+01 , 9.0835752000000003e+00 , 1.2194199999999999e-01 , 8.7683400000000000e-01 , 4.6507199999999999e-01 -2.0892930404788135e+01 , 1.2248941518240438e+01 , 9.1843199999999996e+00 , 9.5677799999999993e-02 , 7.9086100000000004e-01 , 6.0446999999999995e-01 -2.0360099802604367e+01 , 1.2047528773814664e+01 , 9.3990384000000002e+00 , 9.7599199999999997e-01 , 9.4577700000000001e-02 , -1.9620099999999999e-01 -2.0305909339132974e+01 , 1.2102324660237969e+01 , 9.7753623999999988e+00 , 9.6365500000000004e-01 , 2.8151400000000000e-02 , -2.6566200000000001e-01 -2.0365256927917962e+01 , 1.2219440934115035e+01 , 1.0200743200000000e+01 , -8.8253499999999996e-01 , -4.6203400000000000e-01 , -8.7498999999999993e-02 -2.1936580626506107e+01 , 1.3175472543441790e+01 , 1.1270560000000000e+01 , 1.4107000000000000e-01 , 5.6682600000000005e-01 , 8.1167000000000000e-01 -2.5895381487094433e+01 , 1.5478473144376082e+01 , 1.3479728000000000e+01 , -7.0405300000000004e-01 , 1.0290799999999999e-02 , 7.1007299999999995e-01 -2.0767315118190258e+01 , 1.2711576307881652e+01 , 1.1638283200000002e+01 , -9.4773099999999999e-01 , -2.7877099999999999e-01 , -1.5522100000000000e-01 -2.0772780621397494e+01 , 1.2808156101545398e+01 , 1.2081853599999999e+01 , -9.3593899999999997e-01 , -2.8182499999999999e-01 , -2.1116900000000000e-01 -2.0677594917076004e+01 , 1.2848465934279632e+01 , 1.2482992000000001e+01 , 7.7846000000000004e-01 , 2.9994700000000002e-01 , 5.5139099999999996e-01 -2.5174951533522663e+01 , 1.5545545999144759e+01 , 1.5371800000000000e+01 , -9.1085400000000005e-01 , -2.8172599999999998e-01 , -3.0162299999999997e-01 -1.9628313076750636e+01 , 1.2431844318703028e+01 , 1.2810488000000001e+01 , 7.2306199999999998e-01 , 5.4083000000000003e-01 , 4.2974899999999999e-01 -1.9816472442320826e+01 , 1.2637489016519977e+01 , 1.3370631999999999e+01 , -7.1046399999999998e-01 , 6.5630800000000000e-01 , -2.5396900000000000e-01 -2.0322364668366092e+01 , 1.3036704823740591e+01 , 1.4147824000000000e+01 , 6.4350299999999996e-03 , 2.1961400000000000e-01 , 9.7556600000000004e-01 -1.9402745996705224e+01 , 1.2587674894513890e+01 , 1.4041744000000000e+01 , -9.2564999999999997e-01 , -3.4118199999999999e-01 , 1.6360600000000000e-01 -1.9519885156692375e+01 , 1.2759960290569806e+01 , 1.4595128000000001e+01 , -9.3881199999999998e-01 , -2.1732699999999999e-01 , -2.6720899999999997e-01 -2.1029654030506897e+01 , 1.3789318902142991e+01 , 1.6147536000000002e+01 , -9.7997299999999998e-01 , 1.8897100000000000e-01 , -6.2785300000000002e-02 -2.1102109962803812e+01 , 1.3949607167382670e+01 , 1.6747720000000001e+01 , -9.1247599999999995e-01 , -1.5489300000000000e-01 , -3.7867600000000001e-01 -2.2773215345391691e+01 , 1.5114867379155497e+01 , 1.8587479999999999e+01 , 9.9907299999999999e-01 , 4.2212800000000002e-02 , 8.4147900000000001e-03 -2.1968673187127330e+01 , 1.4740460721000654e+01 , 1.8581240000000001e+01 , -9.2141799999999996e-01 , 2.1262200000000001e-01 , 3.2523999999999997e-01 -2.1950084422171031e+01 , 1.4860953537688619e+01 , 1.9191200000000002e+01 , 9.9907299999999999e-01 , 4.2212800000000002e-02 , 8.4147800000000002e-03 -7.0108939166186053e+00 , 5.4884133572132443e+00 , 7.6511415999999999e+00 , 5.7464000000000001e-02 , -3.0802400000000002e-01 , 9.4964099999999996e-01 -6.8059615881473459e+00 , 5.3858234201325157e+00 , 7.6147104000000008e+00 , -7.4592199999999997e-02 , 1.7307700000000001e-01 , -9.8207999999999995e-01 -6.7443239905134869e+00 , 5.3797276094918818e+00 , 7.7241599999999995e+00 , -3.5133599999999998e-01 , -6.2664299999999995e-01 , -6.9561600000000001e-01 -6.6862262624421405e+00 , 5.3778936149477490e+00 , 7.8396623999999999e+00 , -5.8553299999999997e-01 , -7.5716399999999995e-01 , -2.8957600000000000e-01 -6.5461974909486020e+00 , 5.3172175102124353e+00 , 7.8617728000000007e+00 , 5.9904199999999996e-01 , 7.4974900000000000e-01 , 2.8111399999999998e-01 -6.5703117931392514e+00 , 5.3744099229996056e+00 , 8.0769696000000000e+00 , 6.4150099999999999e-01 , 7.4206700000000003e-01 , 1.9445599999999999e-01 -6.4765846719354458e+00 , 5.3472714560339298e+00 , 8.1541584000000000e+00 , 6.4150099999999999e-01 , 7.4206700000000003e-01 , 1.9445599999999999e-01 -5.8981256576921162e+00 , 4.9603307381008648e+00 , 7.5964271999999999e+00 , -2.7681299999999998e-01 , 3.9321400000000001e-01 , 8.7678800000000001e-01 -5.6723265843458677e+00 , 4.8285525980072377e+00 , 7.4686424000000002e+00 , 4.3023100000000002e-02 , 4.1876000000000002e-01 , 9.0707700000000002e-01 -5.5957249542022138e+00 , 4.8081221547586219e+00 , 7.5353479999999999e+00 , 2.9480299999999998e-01 , 4.5239599999999998e-02 , -9.5448699999999997e-01 -5.4003234396092736e+00 , 4.6939026816417107e+00 , 7.4274063999999997e+00 , -1.7016000000000001e-01 , 1.2725500000000001e-01 , 9.7716499999999995e-01 -5.3350968210096568e+00 , 4.6804895840374989e+00 , 7.5050112000000002e+00 , 2.8291100000000002e-01 , -1.7014599999999999e-01 , 9.4393400000000005e-01 -5.2128921958259760e+00 , 4.6206145587769090e+00 , 7.4927080000000004e+00 , 2.2687900000000000e-01 , 1.2041499999999999e-01 , 9.6645000000000003e-01 -5.1072150903617128e+00 , 4.5738524296939120e+00 , 7.5015583999999995e+00 , 3.0430600000000002e-01 , 2.0227899999999999e-01 , 9.3084999999999996e-01 -5.0211038826827821e+00 , 4.5420182087247101e+00 , 7.5412863999999997e+00 , 3.7001800000000001e-02 , -1.3062599999999999e-01 , 9.9074099999999998e-01 -5.2465687785393786e+00 , 4.7746972584275440e+00 , 8.1434567999999992e+00 , -7.8827499999999995e-01 , -5.4004900000000000e-01 , 2.9490499999999997e-01 -4.6595996456657947e+00 , 4.3144673362738093e+00 , 7.2570336000000006e+00 , -2.3926700000000001e-01 , 1.1202700000000000e-01 , 9.6446900000000002e-01 -4.5969574408702574e+00 , 4.2994027628661762e+00 , 7.3217112000000002e+00 , 3.1653700000000001e-01 , 2.4702600000000000e-01 , 9.1585099999999997e-01 -4.4866266173105798e+00 , 4.2414147116790293e+00 , 7.2896792000000001e+00 , -6.0935599999999999e-02 , 2.3245199999999999e-01 , 9.7069700000000003e-01 -4.4391469345974937e+00 , 4.2396532427849749e+00 , 7.3867528000000000e+00 , 9.9202299999999999e-01 , 1.4306900000000001e-02 , 1.2523899999999999e-01 -4.4709860821155125e+00 , 4.3145410757035858e+00 , 7.6704023999999995e+00 , 5.7417799999999997e-01 , 5.3292099999999998e-01 , 6.2154299999999996e-01 -4.4423135740934221e+00 , 4.3355335801764472e+00 , 7.8316960000000000e+00 , -6.2258800000000003e-01 , -7.2497599999999995e-01 , -2.9460799999999998e-01 -4.3294487753947273e+00 , 4.2754931958207223e+00 , 7.7942352000000010e+00 , 2.1570800000000001e-01 , 4.5758599999999999e-01 , 8.6260400000000004e-01 -4.2556920223973460e+00 , 4.2536444712098165e+00 , 7.8545136000000007e+00 , 4.6276200000000001e-01 , 1.9172300000000000e-01 , 8.6550199999999999e-01 -4.3012011723235810e+00 , 4.3580974488701560e+00 , 8.2455952000000003e+00 , 9.8287599999999997e-01 , 1.0335200000000000e-01 , -1.5255299999999999e-01 -3.9243405374726024e+00 , 4.0107811972756799e+00 , 7.4321280000000005e+00 , -7.1597400000000000e-01 , -6.2664100000000000e-01 , 3.0773600000000001e-01 -3.7976637126434074e+00 , 3.9232373487699537e+00 , 7.2973752000000003e+00 , 7.7100800000000003e-01 , -7.2102899999999998e-02 , -6.3273000000000001e-01 -3.7604315859869839e+00 , 3.9369342940761181e+00 , 7.4417480000000005e+00 , 7.7100800000000003e-01 , -7.2102500000000000e-02 , -6.3273000000000001e-01 -3.5511848048017871e+00 , 3.7429746975680978e+00 , 6.9877464000000007e+00 , -2.0601300000000000e-01 , 7.7879799999999999e-01 , 5.9248000000000001e-01 -3.4632133010997008e+00 , 3.6900602926265904e+00 , 6.9276863999999998e+00 , -2.6656900000000000e-01 , 8.3597900000000003e-01 , 4.7966599999999998e-01 -3.3990386734110212e+00 , 3.6658562937623671e+00 , 6.9519496000000007e+00 , -1.1329100000000000e-01 , 9.2197399999999996e-01 , 3.7030999999999997e-01 -3.8568405145304085e+00 , 4.3714091623593703e+00 , 9.2814872000000008e+00 , 3.9420899999999998e-01 , 7.3471900000000001e-01 , -5.5207600000000001e-01 -3.6194105248106814e+00 , 4.1327391959949145e+00 , 8.6733575999999992e+00 , 8.3523400000000003e-01 , 5.0321600000000000e-01 , -2.2171399999999999e-01 -3.6170931476638124e+00 , 4.2378222694937389e+00 , 9.1733791999999994e+00 , -6.5672299999999995e-01 , 1.4400400000000001e-02 , -7.5399400000000005e-01 -3.5360460174157806e+00 , 4.2319410576867478e+00 , 9.3218600000000009e+00 , 6.6449100000000005e-01 , 5.3829800000000005e-01 , 5.1835100000000001e-01 -3.4420376165540785e+00 , 4.2070801077888573e+00 , 9.4103120000000011e+00 , -5.8193900000000000e-02 , 5.3361499999999995e-01 , 8.4372300000000000e-01 -3.3228122464160004e+00 , 4.1341307530046087e+00 , 9.3284744000000011e+00 , 7.8345500000000001e-01 , -4.6925600000000001e-01 , -4.0742699999999998e-01 -2.9018052131270919e+00 , 3.3948426250904151e+00 , 6.7603192000000005e+00 , -7.1997900000000004e-01 , 6.0090100000000002e-01 , -3.4720200000000001e-01 -2.8494658314701571e+00 , 3.3904618717568331e+00 , 6.8539295999999998e+00 , -5.4303800000000002e-01 , 6.6190000000000004e-01 , -5.1671900000000004e-01 -2.7812729628353372e+00 , 3.3467564413859439e+00 , 6.7963344000000001e+00 , -2.7007100000000001e-01 , -2.0441400000000001e-01 , 9.4089100000000003e-01 -2.7162723487684208e+00 , 3.3056930795614976e+00 , 6.7473400000000003e+00 , -6.8106500000000003e-01 , 2.0830399999999999e-01 , -7.0196899999999995e-01 -2.6627452090351702e+00 , 3.3058891876363639e+00 , 6.8686351999999999e+00 , 6.4032900000000004e-01 , -2.9087700000000000e-01 , 7.1089400000000003e-01 -2.6546130623522162e+00 , 3.5941581667529392e+00 , 8.2449815999999991e+00 , -3.9825700000000003e-01 , -6.0268900000000003e-01 , 6.9148900000000002e-01 -2.5487581416002398e+00 , 3.3470568659407114e+00 , 7.3121328000000005e+00 , -2.9538599999999998e-01 , 1.3441600000000001e-01 , 9.4587500000000002e-01 -2.4794554986175634e+00 , 3.3124433912332893e+00 , 7.2994656000000004e+00 , -3.2834900000000000e-02 , 3.6559999999999998e-01 , 9.3019300000000005e-01 -2.4103205156353735e+00 , 3.2929428784765982e+00 , 7.3565928000000005e+00 , 3.9168999999999998e-01 , 7.6869399999999999e-01 , 5.0565599999999999e-01 -2.3173206843651668e+00 , 3.4497752705127169e+00 , 8.2996128000000002e+00 , 4.6970600000000001e-01 , -8.2226399999999999e-01 , 3.2133899999999999e-01 -2.2387736010907289e+00 , 3.3818352978868749e+00 , 8.1511943999999996e+00 , -8.3705200000000002e-01 , 3.9545599999999997e-01 , 3.7809900000000002e-01 -2.1643367278965506e+00 , 3.3196204186505365e+00 , 8.0215376000000003e+00 , 4.2145600000000000e-01 , -5.1547399999999999e-01 , -7.4609800000000004e-01 -2.0890323211044461e+00 , 3.2725527222855462e+00 , 7.9615504000000001e+00 , -1.8689000000000000e-01 , -2.8304699999999999e-01 , 9.4072100000000003e-01 -2.0071969534221572e+00 , 3.2408000042188263e+00 , 7.9920328000000005e+00 , -7.0227200000000001e-01 , -1.7240500000000000e-01 , -6.9071700000000003e-01 -1.7306694612586149e+00 , 3.5067093557645821e+00 , 9.8483912000000000e+00 , -1.3031300000000001e-01 , -6.8132400000000004e-01 , 7.2028899999999996e-01 -4.7929608251790059e+00 , 3.0030599148075217e+00 , 1.1400770400000000e+00 , -7.7415200000000003e-02 , 1.7454500000000001e-01 , 9.8160099999999995e-01 -4.8686786974065335e+00 , 3.0364875407927183e+00 , 1.1429536800000000e+00 , 8.4070300000000001e-02 , -1.9274400000000000e-01 , -9.7764099999999998e-01 -4.9532522956934795e+00 , 3.0719809051835538e+00 , 1.1421716000000000e+00 , -5.4793599999999998e-02 , 1.7109199999999999e-01 , 9.8372999999999999e-01 -5.0304956929967943e+00 , 3.1063109546019279e+00 , 1.1498520000000001e+00 , -5.4461400000000000e-02 , 1.8226300000000001e-01 , 9.8173999999999995e-01 -5.1236901533806876e+00 , 3.1464944298562529e+00 , 1.1478354399999999e+00 , -4.9415800000000003e-02 , 1.7688799999999999e-01 , 9.8299000000000003e-01 -5.2175870112546088e+00 , 3.1872436879378201e+00 , 1.1487776800000000e+00 , -4.5896600000000003e-02 , 1.6798900000000000e-01 , 9.8472000000000004e-01 -5.3202182452439075e+00 , 3.2302908844540545e+00 , 1.1471739999999999e+00 , -6.7824899999999994e-02 , 1.6947599999999999e-01 , 9.8319800000000002e-01 -5.4154750635094793e+00 , 3.2722358392846100e+00 , 1.1543364800000000e+00 , -8.3778599999999995e-02 , 1.8561100000000000e-01 , 9.7904500000000005e-01 -5.5285645302387980e+00 , 3.3203318051514508e+00 , 1.1536719199999999e+00 , -4.3378600000000003e-02 , 1.9473900000000000e-01 , 9.7989499999999996e-01 -5.6412255536271800e+00 , 3.3691802928008396e+00 , 1.1566494399999998e+00 , 2.9647699999999999e-01 , -1.5173500000000001e-01 , -9.4290900000000000e-01 -5.7465268995385355e+00 , 3.4169061810022892e+00 , 1.1682912000000001e+00 , -9.0189600000000003e-01 , -1.6263600000000000e-02 , 4.3164599999999997e-01 -5.7372247919886972e+00 , 3.4299201912812478e+00 , 1.2467134400000000e+00 , -9.0189600000000003e-01 , -1.6263500000000000e-02 , 4.3164599999999997e-01 -5.7799154371221571e+00 , 3.4582382285731690e+00 , 1.2962476000000001e+00 , -9.4622200000000001e-01 , -3.1692100000000001e-01 , 6.4999600000000005e-02 -5.7066192600228778e+00 , 3.4496125059485174e+00 , 1.4064439200000001e+00 , 9.9100299999999997e-01 , 3.5369699999999997e-02 , 1.2908500000000001e-01 -5.7202403740584860e+00 , 3.4681115936840392e+00 , 1.4695448799999999e+00 , 9.8043499999999995e-01 , -9.7446199999999997e-02 , -1.7102899999999999e-01 -5.7059310547281967e+00 , 3.4776635744536915e+00 , 1.5455262400000001e+00 , 9.9812699999999999e-01 , -4.6777100000000002e-02 , 3.9415400000000003e-02 -5.7532006263249773e+00 , 3.5073162274603011e+00 , 1.5921171999999999e+00 , 9.9111199999999999e-01 , -3.9164299999999999e-02 , 1.2713800000000000e-01 -5.6901857788377068e+00 , 3.5004764497023304e+00 , 1.6870151199999999e+00 , 9.9011700000000002e-01 , 1.9187500000000000e-02 , -1.3892599999999999e-01 -5.6986085578781385e+00 , 3.5169274829687756e+00 , 1.7493922399999999e+00 , 9.7655499999999995e-01 , 1.1240700000000001e-01 , -1.8358700000000000e-01 -5.7524589504417563e+00 , 3.5490845855230582e+00 , 1.7939957600000001e+00 , 9.5450299999999999e-01 , 1.0013800000000000e-01 , 2.8088600000000002e-01 -5.6393202890105449e+00 , 3.5236363734143206e+00 , 1.9017953999999999e+00 , 9.8847300000000005e-01 , 3.8424600000000003e-02 , 1.4643900000000001e-01 -5.6623814184305807e+00 , 3.5443026624269209e+00 , 1.9565813519999999e+00 , -8.7592499999999995e-01 , 1.4093400000000001e-02 , 4.8224200000000000e-01 -5.6952518955653835e+00 , 3.5693449975602602e+00 , 2.0088411023999999e+00 , -8.4481300000000004e-01 , 6.2031999999999997e-02 , 5.3145299999999995e-01 -5.7259014010477580e+00 , 3.5936177125790518e+00 , 2.0620665759999999e+00 , -7.6250799999999996e-01 , 6.6401399999999999e-02 , 6.4356300000000000e-01 -5.7848426219414826e+00 , 3.6279867785922968e+00 , 2.1082036799999999e+00 , -4.4847799999999999e-01 , 1.5062200000000001e-01 , 8.8101099999999999e-01 -5.9276476231510573e+00 , 3.6948073145692950e+00 , 2.1330451199999998e+00 , -2.2601399999999999e-01 , 1.9688200000000000e-01 , 9.5402100000000001e-01 -6.0806882752211413e+00 , 3.7659948088769566e+00 , 2.1606488000000001e+00 , -1.9704400000000000e-01 , 1.6896700000000001e-01 , 9.6572499999999994e-01 -6.4504043535404172e+00 , 3.9205794557665343e+00 , 2.1424789600000000e+00 , -8.3900899999999994e-03 , 1.7435000000000000e-01 , 9.8464799999999997e-01 -6.8313890460656612e+00 , 4.0812929189825677e+00 , 2.1360236800000001e+00 , -6.2507699999999999e-02 , 1.8527800000000000e-01 , 9.8069600000000001e-01 -7.1263711214622010e+00 , 4.2125679715396718e+00 , 2.1601444000000001e+00 , -9.1421299999999997e-02 , 1.8408900000000000e-01 , 9.7864899999999999e-01 -1.2027418177868745e+01 , 6.1446486910580207e+00 , 1.3749163200000001e+00 , -5.7694400000000000e-02 , 1.8880400000000000e-01 , 9.8031800000000002e-01 -1.2977976792543812e+01 , 6.5572602962305027e+00 , 1.4016443199999999e+00 , -7.0240300000000006e-02 , 1.8466399999999999e-01 , 9.8028800000000005e-01 -1.4205794119769594e+01 , 7.0867092729331658e+00 , 1.4244088800000001e+00 , -4.7982900000000002e-02 , 1.8923499999999999e-01 , 9.8075900000000005e-01 -1.5854641295445758e+01 , 7.7953641548338686e+00 , 1.4409844000000001e+00 , -7.8516000000000002e-02 , 1.8695000000000001e-01 , 9.7922699999999996e-01 -1.7500440220677753e+01 , 8.5153921478845422e+00 , 1.5186724000000000e+00 , -6.1913400000000000e-02 , 1.8688900000000000e-01 , 9.8042799999999997e-01 -2.1206717756547768e+01 , 1.0091122320413927e+01 , 1.4819593599999998e+00 , -6.2222800000000002e-02 , 1.8987999999999999e-01 , 9.7983399999999998e-01 -2.4195735793037990e+01 , 1.1483764661151900e+01 , 2.0330703360000002e+00 , 3.6871500000000001e-01 , -1.2379400000000000e-01 , -9.2126200000000003e-01 -2.5731206849754805e+01 , 1.2215151511290184e+01 , 2.3911928800000002e+00 , -3.9866600000000002e-01 , 8.4006800000000006e-02 , 9.1324099999999997e-01 -2.5668039856015049e+01 , 1.2278633173691560e+01 , 2.8246451200000000e+00 , 5.5918500000000004e-01 , 1.5680600000000000e-01 , -8.1407900000000000e-01 -2.7065827049920177e+01 , 1.3159471135035526e+01 , 4.1903439999999996e+00 , 3.0324200000000001e-01 , 5.0372099999999997e-01 , -8.0889400000000000e-01 -2.7389471362265937e+01 , 1.3398214710461545e+01 , 4.6749944000000001e+00 , -1.1558900000000000e-01 , -4.0559800000000001e-01 , -9.0671299999999999e-01 -2.2962003582450937e+01 , 1.1689673169721662e+01 , 5.5639552000000005e+00 , 2.4783800000000000e-01 , 4.2347499999999999e-01 , 8.7134699999999998e-01 -2.0327896442022869e+01 , 1.0568938387345209e+01 , 5.5897888000000000e+00 , 9.5492299999999997e-01 , -2.9073900000000003e-01 , -5.9948300000000003e-02 -2.0099893392877231e+01 , 1.0536292020336681e+01 , 5.9007176000000001e+00 , 9.5492299999999997e-01 , -2.9073900000000003e-01 , -5.9948300000000003e-02 -2.0761861583713518e+01 , 1.0915711935155262e+01 , 6.3651815999999997e+00 , 7.9651499999999997e-01 , -4.6659600000000001e-01 , -3.8451600000000002e-01 -2.1031471036242959e+01 , 1.1117397753220231e+01 , 6.7807760000000004e+00 , -9.1562299999999996e-01 , 3.5407100000000002e-01 , 1.9044200000000000e-01 -2.1338435242362923e+01 , 1.1338965122537326e+01 , 7.2187928000000001e+00 , 7.5980099999999995e-01 , -6.4956700000000001e-01 , 2.7647800000000000e-02 -2.1386958004076771e+01 , 1.1441429166173233e+01 , 7.6111744000000003e+00 , 4.4694600000000001e-01 , -8.9369600000000005e-01 , -3.9318100000000002e-02 -2.2241031762935680e+01 , 1.1932691977300454e+01 , 8.2185448000000001e+00 , 8.3696599999999999e-01 , -5.1672200000000001e-01 , -1.8023700000000001e-01 -2.0656926702077801e+01 , 1.1248059006928520e+01 , 8.1820823999999988e+00 , -6.2356500000000004e-01 , 7.0042899999999997e-01 , -3.4722700000000001e-01 -2.0670423174138445e+01 , 1.1333288864737131e+01 , 8.5658840000000005e+00 , -8.7848199999999999e-01 , 4.6110099999999998e-01 , -1.2512000000000001e-01 -2.0624421293237578e+01 , 1.1390614803991037e+01 , 8.9354896000000004e+00 , -8.9841400000000005e-01 , 4.3694499999999997e-01 , -4.3951900000000002e-02 -2.0223873540954951e+01 , 1.1271600283411855e+01 , 9.1868368000000018e+00 , -9.6006300000000000e-01 , 2.6107500000000000e-01 , -1.0059200000000000e-01 -2.1120304604589140e+01 , 1.1802562333625147e+01 , 9.9001416000000013e+00 , 9.8254200000000003e-01 , -2.0614500000000001e-02 , -1.8489500000000000e-01 -2.5860721525034222e+01 , 1.4296252775204824e+01 , 1.2147435999999999e+01 , -5.8044799999999996e-01 , 3.1528000000000000e-02 , -8.1368700000000005e-01 -2.0711234346506696e+01 , 1.1765375355469356e+01 , 1.0561082400000000e+01 , -9.4941799999999998e-01 , -6.3651799999999994e-02 , 3.0749500000000002e-01 -2.0714494703590926e+01 , 1.1853464608701763e+01 , 1.0977924800000000e+01 , -9.3388199999999999e-01 , -3.4090199999999998e-01 , 1.0793500000000000e-01 -2.0941409083397211e+01 , 1.2058996082316122e+01 , 1.1503676000000000e+01 , 9.9987099999999995e-01 , 1.5983000000000001e-02 , -1.3562900000000000e-03 -2.0850555952852066e+01 , 1.2101489388684850e+01 , 1.1895433600000000e+01 , -9.7889099999999996e-01 , -1.3211500000000001e-01 , 1.5594500000000000e-01 -2.0810974694642709e+01 , 1.2172160932318226e+01 , 1.2316924800000001e+01 , 7.3581399999999997e-01 , 1.9071700000000000e-01 , 6.4977200000000002e-01 -2.1869039131330290e+01 , 1.2833895724870077e+01 , 1.3323727999999999e+01 , -8.0156799999999995e-01 , -5.7700099999999999e-01 , 1.5671199999999999e-01 -2.1743633480673235e+01 , 1.2866763842235121e+01 , 1.3739416000000000e+01 , -4.9482500000000001e-01 , -7.6737599999999995e-01 , -4.0777700000000000e-01 -2.1302540247737515e+01 , 1.2727380150867473e+01 , 1.3975912000000001e+01 , 3.3988800000000002e-01 , 7.5862600000000002e-01 , 5.5584400000000000e-01 -2.0064587749551738e+01 , 1.2144803408348324e+01 , 1.3718928000000000e+01 , -1.8430600000000000e-01 , 9.0798199999999996e-01 , 3.7629699999999999e-01 -2.0736904323364779e+01 , 1.2617654431207033e+01 , 1.4612392000000000e+01 , 1.4349899999999999e-01 , 9.0838300000000005e-01 , 3.9274399999999998e-01 -2.1494135383117939e+01 , 1.3147978594534013e+01 , 1.5608919999999999e+01 , -9.6534399999999998e-01 , 2.5797799999999999e-01 , -3.9472000000000000e-02 -2.2694467033034066e+01 , 1.3942842436679197e+01 , 1.6964351999999998e+01 , -6.5722100000000006e-01 , 7.5363899999999995e-01 , -9.4594399999999995e-03 -2.1016822292628564e+01 , 1.3097234009021474e+01 , 1.6346176000000000e+01 , -9.7997299999999998e-01 , 1.8897100000000000e-01 , -6.2785199999999999e-02 -2.1019264980110545e+01 , 1.3211866718296031e+01 , 1.6894568000000000e+01 , -8.7705699999999998e-01 , -2.8191400000000000e-01 , -3.8896599999999998e-01 -2.0651563087858879e+01 , 1.3112467053958639e+01 , 1.7171312000000000e+01 , 8.8766599999999996e-01 , 3.0499100000000001e-02 , 4.5947700000000002e-01 -2.2721454085236591e+01 , 1.4460923872248214e+01 , 1.9404608000000000e+01 , 9.9955600000000000e-01 , -2.8635799999999999e-02 , -8.2719500000000001e-03 -6.7770954706444950e+00 , 5.1647702619642786e+00 , 7.4652935999999999e+00 , -6.5553499999999998e-01 , -1.2913600000000000e-01 , 7.4404099999999995e-01 -6.8681149923374907e+00 , 5.2588703869447393e+00 , 7.7304624000000004e+00 , 7.6959000000000000e-01 , -1.5142300000000000e-01 , 6.2032399999999999e-01 -6.3416959315347352e+00 , 4.9521221217507119e+00 , 7.3340976000000007e+00 , -9.4950900000000005e-02 , 9.8490599999999995e-01 , 1.4471999999999999e-01 -6.1588532998879248e+00 , 4.8641546048295865e+00 , 7.2906256000000003e+00 , 3.0532999999999999e-01 , 5.2335699999999996e-01 , 7.9553200000000002e-01 -6.1020351828794439e+00 , 4.8604576954919656e+00 , 7.3866696000000003e+00 , -3.0532999999999999e-01 , -5.2335600000000004e-01 , -7.9553200000000002e-01 -5.9778248677768300e+00 , 4.8102676560686968e+00 , 7.4008968000000008e+00 , -6.4227699999999999e-01 , -4.3149300000000002e-01 , -6.3347799999999999e-01 -5.9604348471061943e+00 , 4.8330803268977540e+00 , 7.5473184000000009e+00 , 1.2215200000000001e-02 , -9.9746100000000004e-01 , 7.0159399999999997e-02 -5.7945090242544701e+00 , 4.7528502956270540e+00 , 7.5037111999999997e+00 , 1.3715700000000000e-01 , 4.4184499999999999e-01 , 8.8654400000000000e-01 -5.7557240561350653e+00 , 4.7621151930780110e+00 , 7.6257136000000001e+00 , -2.4018399999999999e-02 , 5.3700700000000001e-01 , 8.4323599999999999e-01 -5.6380489086896368e+00 , 4.7133984590584088e+00 , 7.6381519999999998e+00 , 2.8415499999999999e-01 , 6.8994400000000000e-01 , 6.6575799999999996e-01 -5.3753125899266214e+00 , 4.5588415625689303e+00 , 7.4316079999999998e+00 , 1.7503900000000000e-01 , 1.0718999999999999e-01 , 9.7870900000000005e-01 -5.2629578898061862e+00 , 4.5112563942354367e+00 , 7.4349255999999997e+00 , 9.2888299999999993e-02 , 7.8734700000000005e-02 , 9.9255899999999997e-01 -5.2475548751117369e+00 , 4.5370398399214302e+00 , 7.5912376000000004e+00 , 2.9324299999999998e-01 , 1.3968300000000000e-01 , 9.4577800000000001e-01 -4.8678490032938555e+00 , 4.2813397506427933e+00 , 7.1422904000000003e+00 , 1.2395000000000000e-01 , -2.2318499999999999e-01 , 9.6686399999999995e-01 -4.8744235602765125e+00 , 4.3225081403708572e+00 , 7.3269839999999995e+00 , 4.8012400000000000e-01 , 3.8947300000000001e-01 , -7.8599699999999995e-01 -4.7070283048682517e+00 , 4.2269649339322886e+00 , 7.2070408000000006e+00 , 4.4321300000000002e-01 , 3.4012500000000001e-01 , 8.2938400000000001e-01 -4.6359034707863653e+00 , 4.2055860565542744e+00 , 7.2543920000000002e+00 , -1.0383900000000000e-01 , 3.7483100000000003e-01 , 9.2125900000000005e-01 -4.7603233126326856e+00 , 4.3499640099673096e+00 , 7.6918471999999998e+00 , 3.6818699999999999e-01 , 9.1892200000000002e-01 , 1.4149600000000001e-01 -4.6593995595788389e+00 , 4.3074974516522522e+00 , 7.6967352000000009e+00 , 5.5208999999999997e-01 , -2.7012700000000001e-01 , 7.8881400000000002e-01 -4.5598328102125434e+00 , 4.2655606481785808e+00 , 7.6992208000000000e+00 , -8.5171500000000000e-01 , -3.6557400000000001e-01 , -3.7541700000000000e-01 -4.5353172467475371e+00 , 4.2903882567946612e+00 , 7.8699472000000004e+00 , 5.0270999999999999e-01 , 5.1163999999999998e-01 , 6.9678399999999996e-01 -4.4308483869067627e+00 , 4.2441045047526256e+00 , 7.8603480000000001e+00 , 1.7764800000000000e-01 , 1.5660700000000000e-01 , -9.7155300000000000e-01 -4.3130092780866249e+00 , 4.1831618930554253e+00 , 7.8120088000000001e+00 , 3.7341500000000000e-01 , -3.1494400000000000e-01 , 8.7256599999999995e-01 -4.2426228202719898e+00 , 4.1680343182495125e+00 , 7.8800560000000006e+00 , 7.8826700000000005e-01 , -8.9620599999999995e-02 , 6.0877199999999998e-01 -4.1878943211969109e+00 , 4.1678489489177029e+00 , 7.9939152000000000e+00 , 9.4481199999999999e-01 , 6.4613299999999999e-02 , 3.2117800000000002e-01 -3.9038628555414756e+00 , 3.9300998546472408e+00 , 7.4331264000000008e+00 , -1.0950400000000000e-01 , -3.1735400000000002e-01 , 9.4196299999999999e-01 -3.7920365182309590e+00 , 3.8636802204402190e+00 , 7.3431144000000002e+00 , -5.8113600000000001e-02 , -4.6337899999999999e-01 , 8.8425299999999996e-01 -3.6126756555405062e+00 , 3.7177049308056489e+00 , 7.0124984000000001e+00 , -1.6354800000000000e-01 , 7.4283500000000002e-01 , 6.4919000000000004e-01 -3.5328381025826001e+00 , 3.6796825412445813e+00 , 6.9911680000000000e+00 , -2.5503700000000001e-01 , 7.8674299999999997e-01 , 5.6213100000000005e-01 -3.7879315299984047e+00 , 4.0513405987178155e+00 , 8.2578568000000008e+00 , -7.3460599999999998e-01 , -3.6158099999999999e-01 , -5.7411999999999996e-01 -3.9210459364733192e+00 , 4.3062597600301640e+00 , 9.2089680000000005e+00 , 1.0664000000000000e-01 , 4.8061300000000001e-01 , -8.7042500000000000e-01 -3.6621749747182584e+00 , 4.0568341329747035e+00 , 8.5429208000000010e+00 , -8.3607600000000004e-01 , -4.9459599999999998e-01 , -2.3738300000000001e-01 -3.7003225695285398e+00 , 4.2116321442144820e+00 , 9.2086976000000007e+00 , 8.5639699999999996e-01 , 4.7156400000000001e-02 , 5.1415999999999995e-01 -3.6222969897091710e+00 , 4.2108945517447918e+00 , 9.3675888000000000e+00 , -6.0642700000000005e-01 , -6.0311499999999996e-01 , -5.1816799999999996e-01 -3.4986252301088858e+00 , 4.1418721126090343e+00 , 9.2884864000000000e+00 , 5.9401099999999996e-01 , -1.6429800000000000e-01 , 7.8750100000000001e-01 -3.3979464551720406e+00 , 4.1079338214826970e+00 , 9.3356816000000009e+00 , -5.9557800000000005e-01 , -5.3629099999999996e-01 , 5.9806300000000001e-01 -3.2761964628489322e+00 , 4.0348228807372584e+00 , 9.2314527999999996e+00 , -2.3790600000000001e-01 , -5.6883700000000004e-01 , 7.8729000000000005e-01 -3.1656156338033812e+00 , 3.9780681453316671e+00 , 9.1843928000000012e+00 , -7.8564800000000001e-01 , -6.5734500000000001e-02 , 6.1517100000000002e-01 -2.8174763568698364e+00 , 3.3231732517769625e+00 , 6.7449688000000005e+00 , 2.0803500000000000e-01 , -3.1034400000000001e-01 , 9.2758200000000002e-01 -2.7605777397779163e+00 , 3.3084877084616107e+00 , 6.7969896000000007e+00 , 5.0912000000000002e-01 , -9.4085299999999997e-02 , 8.5553800000000002e-01 -2.6999422303118368e+00 , 3.2896171373124745e+00 , 6.8274200000000000e+00 , 6.4032900000000004e-01 , -2.9087700000000000e-01 , 7.1089400000000003e-01 -2.6368147595547562e+00 , 3.2603939263412567e+00 , 6.8164999999999996e+00 , -7.9673799999999995e-01 , 2.8858400000000001e-01 , -5.3096900000000002e-01 -2.5945639962661060e+00 , 3.3634306703901098e+00 , 7.4031951999999999e+00 , -8.2522600000000002e-01 , -4.0168900000000002e-01 , 3.9704899999999999e-01 -2.5211925383248524e+00 , 3.3126799769441551e+00 , 7.3095744000000007e+00 , -1.0242800000000001e-01 , 3.4480400000000000e-01 , 9.3306999999999995e-01 -2.4516469970551826e+00 , 3.2871431749455056e+00 , 7.3261000000000003e+00 , 3.2593299999999997e-01 , 6.4011700000000005e-01 , 6.9571400000000005e-01 -2.3649912078095383e+00 , 3.4726286883291664e+00 , 8.4021672000000009e+00 , 4.0475100000000003e-01 , -8.6498699999999995e-01 , -2.9660399999999998e-01 -2.2804050011364301e+00 , 3.4163681379534028e+00 , 8.3051455999999995e+00 , 5.3536099999999998e-01 , -1.8688700000000000e-01 , 8.2368799999999998e-01 -2.2094255446740614e+00 , 3.3274233222781389e+00 , 8.0224527999999999e+00 , 3.9294800000000002e-01 , -7.2214699999999998e-01 , -5.6929399999999997e-01 -2.1306407311383366e+00 , 3.2857623503553004e+00 , 7.9832967999999997e+00 , -3.6318200000000000e-01 , -3.3401300000000000e-01 , 8.6978999999999995e-01 -2.0517400247256603e+00 , 3.2478768113707455e+00 , 7.9628920000000001e+00 , 3.5060500000000000e-01 , -3.7424299999999999e-01 , 8.5849799999999998e-01 -1.7849007224897078e+00 , 3.5302241749595353e+00 , 9.8713024000000011e+00 , 5.2113699999999996e-01 , 2.9994700000000002e-01 , -7.9903000000000002e-01 -1.7378406472085985e+00 , 3.3949168431297334e+00 , 9.3161191999999993e+00 , -9.2347599999999996e-01 , 3.8217299999999998e-01 , -3.3718100000000001e-02 -4.7878286996233772e+00 , 2.9289157315523879e+00 , 1.1451647199999999e+00 , -1.1530899999999999e-01 , 1.8123100000000000e-01 , 9.7665700000000000e-01 -4.8483028727900219e+00 , 2.9559318997516169e+00 , 1.1603965600000001e+00 , -7.1941599999999994e-02 , 1.6865900000000000e-01 , 9.8304599999999998e-01 -4.9340040215366088e+00 , 2.9890561288640511e+00 , 1.1586337599999998e+00 , -2.5939100000000000e-02 , 2.0395199999999999e-01 , 9.7863699999999998e-01 -5.0275084989155356e+00 , 3.0243076033335843e+00 , 1.1532892000000001e+00 , -4.9735099999999997e-02 , 1.9442999999999999e-01 , 9.7965500000000005e-01 -5.1136296760782631e+00 , 3.0585006646947996e+00 , 1.1569135999999998e+00 , -4.4864399999999999e-02 , 1.7036200000000001e-01 , 9.8436000000000001e-01 -5.2086059517089254e+00 , 3.0958618745848510e+00 , 1.1570789600000000e+00 , -4.7118300000000002e-02 , 1.7562100000000000e-01 , 9.8333000000000004e-01 -5.2951744913736647e+00 , 3.1321405873243631e+00 , 1.1658835999999999e+00 , -5.1456300000000003e-02 , 1.7106299999999999e-01 , 9.8391600000000001e-01 -5.3996105357574207e+00 , 3.1734037422599002e+00 , 1.1663588800000000e+00 , -9.2916700000000005e-02 , 1.8257599999999999e-01 , 9.7879099999999997e-01 -5.4967016409108460e+00 , 3.2135239399852358e+00 , 1.1753975200000000e+00 , -5.8281899999999998e-02 , 1.7482000000000000e-01 , 9.8287400000000003e-01 -5.6195370640330164e+00 , 3.2606550557216325e+00 , 1.1720185600000002e+00 , -1.5921700000000000e-01 , 1.5831200000000001e-01 , 9.7446800000000000e-01 -5.7430003592041352e+00 , 3.3095571724890127e+00 , 1.1723035200000000e+00 , -7.2412200000000004e-01 , 1.4137000000000000e-01 , 6.7502700000000004e-01 -5.7607875288164188e+00 , 3.3290196105670722e+00 , 1.2358028000000001e+00 , -8.8427800000000001e-01 , 1.8301300000000001e-01 , 4.2960199999999998e-01 -5.7425224029013648e+00 , 3.3390314198455622e+00 , 1.3184921599999999e+00 , 9.9943300000000002e-01 , -1.0591700000000001e-02 , 3.1977999999999999e-02 -5.8571312757883334e+00 , 3.3865418942688343e+00 , 1.3310626399999999e+00 , 9.9943300000000002e-01 , -1.0591700000000001e-02 , 3.1978100000000002e-02 -5.7459172642251861e+00 , 3.3681934946204204e+00 , 1.4586800000000000e+00 , 9.9059299999999995e-01 , 1.3650899999999999e-01 , 9.4830699999999997e-03 -5.7226785276019880e+00 , 3.3757815257957384e+00 , 1.5388255200000001e+00 , 9.9735200000000002e-01 , -7.2259799999999999e-02 , -8.1528499999999997e-03 -5.7342340419768973e+00 , 3.3932156539398601e+00 , 1.6014751199999999e+00 , 9.8630499999999999e-01 , 1.4954400000000001e-01 , -6.9571499999999994e-02 -5.7080003873852760e+00 , 3.3985125363306552e+00 , 1.6801355199999999e+00 , 9.9331899999999995e-01 , 7.5821799999999995e-02 , -8.7001499999999996e-02 -5.7085864433371647e+00 , 3.4117970535646256e+00 , 1.7461983999999999e+00 , 9.8921099999999995e-01 , 8.1670499999999993e-02 , 1.2161900000000000e-01 -5.7536064009957100e+00 , 3.4396173725887706e+00 , 1.7937576000000000e+00 , 9.9235099999999998e-01 , -9.3912499999999996e-02 , 8.0120800000000006e-02 -5.6671154570951341e+00 , 3.4257797229319147e+00 , 1.8910745600000001e+00 , 9.8672099999999996e-01 , 4.2648199999999997e-02 , 1.5672500000000000e-01 -5.6823829765828915e+00 , 3.4431715086176160e+00 , 1.9490402080000000e+00 , -9.3390499999999999e-01 , -2.3578700000000001e-02 , 3.5674200000000000e-01 -5.6877430001756348e+00 , 3.4574566527259414e+00 , 2.0105405040000002e+00 , -8.8728099999999999e-01 , 7.6770000000000005e-02 , 4.5479500000000000e-01 -5.7480148629914174e+00 , 3.4901821954355299e+00 , 2.0540741759999999e+00 , 7.8765099999999999e-01 , -5.8659900000000001e-02 , -6.1332299999999995e-01 -5.7697511512266511e+00 , 3.5102647635820894e+00 , 2.1109627999999998e+00 , -6.1108899999999999e-01 , 1.2918600000000000e-01 , 7.8094900000000000e-01 -5.8863689181228231e+00 , 3.5625225742921423e+00 , 2.1422449600000002e+00 , -3.3857700000000002e-01 , 1.8591400000000000e-01 , 9.2238900000000001e-01 -6.0405584938440882e+00 , 3.6279899019970072e+00 , 2.1680660800000000e+00 , -1.8272099999999999e-01 , 1.9384899999999999e-01 , 9.6386499999999997e-01 -6.2136539704086751e+00 , 3.7013283915627460e+00 , 2.1948107200000000e+00 , -7.2047200000000006e-02 , 1.8646799999999999e-01 , 9.7981600000000002e-01 -6.6752962698359974e+00 , 3.8772257546517301e+00 , 2.1650084800000000e+00 , 3.4863699999999997e-02 , -2.0862500000000000e-01 , -9.7737399999999997e-01 -7.0991884374664398e+00 , 4.0426778340702318e+00 , 2.1596389600000001e+00 , -1.0219300000000001e-01 , 2.1658500000000000e-01 , 9.7089999999999999e-01 -1.1619461876883827e+01 , 5.6687842795426544e+00 , 1.4346258399999998e+00 , -6.1347899999999997e-02 , 1.9097100000000000e-01 , 9.7967700000000002e-01 -1.2581477868104372e+01 , 6.0497403101138882e+00 , 1.4489268800000001e+00 , -5.8299200000000002e-02 , 1.8965599999999999e-01 , 9.8011800000000004e-01 -1.3601467435216241e+01 , 6.4590552013528804e+00 , 1.4899725600000000e+00 , -5.9339799999999998e-02 , 1.8703000000000000e-01 , 9.8055999999999999e-01 -1.5134451818529488e+01 , 7.0629392587561659e+00 , 1.5045856000000000e+00 , -4.9119299999999998e-02 , 1.8578600000000001e-01 , 9.8136199999999996e-01 -1.6627542788181824e+01 , 7.6647001973405988e+00 , 1.5792908800000001e+00 , -7.7036400000000005e-02 , 1.8499800000000000e-01 , 9.7971500000000000e-01 -1.9038824050097045e+01 , 8.6209817968292271e+00 , 1.6279712000000000e+00 , 3.9246999999999997e-02 , -1.8698100000000001e-01 , -9.8157899999999998e-01 -2.1553457577498694e+01 , 9.6348661415769481e+00 , 1.7578599200000000e+00 , 1.0777200000000001e-01 , -1.9264999999999999e-01 , -9.7533099999999995e-01 -2.4023037956952173e+01 , 1.0649571370604489e+01 , 1.9824312799999999e+00 , -3.3150000000000002e-01 , 1.1720200000000000e-01 , 9.3614699999999995e-01 -2.4717596853918774e+01 , 1.0998563529904015e+01 , 2.3554730400000001e+00 , -2.9648799999999997e-01 , 1.2955500000000000e-01 , 9.4620800000000005e-01 -2.8535347519121689e+01 , 1.2568801720444119e+01 , 2.7106070400000002e+00 , -1.4857600000000000e-02 , -3.1882300000000002e-01 , 9.4769800000000004e-01 -2.6684881848414360e+01 , 1.1938667002638551e+01 , 3.1829896000000000e+00 , 7.1082900000000004e-01 , -8.1815200000000005e-02 , -6.9859000000000004e-01 -2.8484587290677812e+01 , 1.2744351732324965e+01 , 3.6711967999999997e+00 , 4.5608700000000002e-01 , -4.5143299999999997e-01 , 7.6693800000000001e-01 -2.8447483878663757e+01 , 1.2826879890915079e+01 , 4.1519992000000006e+00 , 4.5608700000000002e-01 , -4.5143299999999997e-01 , 7.6693800000000001e-01 -2.8431373247506272e+01 , 1.2918396236556434e+01 , 4.6343719999999999e+00 , 4.5608599999999999e-01 , -4.5143299999999997e-01 , 7.6693800000000001e-01 -2.1694007121916545e+01 , 1.0265401758141101e+01 , 4.5906920000000007e+00 , -7.7101600000000003e-01 , -6.1535899999999999e-01 , -1.6391100000000000e-01 -2.0991069300354603e+01 , 1.0048830158415932e+01 , 4.8836288000000003e+00 , -6.8437000000000003e-01 , -4.7792400000000002e-01 , -5.5065900000000001e-01 -2.4790752812634988e+01 , 1.1701391134615378e+01 , 5.6751312000000009e+00 , 9.6758999999999995e-01 , 2.2125300000000001e-01 , 1.2172600000000000e-01 -2.5116164433011669e+01 , 1.1924087545030593e+01 , 6.1436200000000003e+00 , 8.5165900000000005e-01 , 3.5840800000000000e-01 , 3.8238800000000001e-01 -2.0795167982747973e+01 , 1.0181333418159021e+01 , 5.9106079999999999e+00 , -6.5496500000000002e-01 , -7.6801700000000001e-02 , -7.5174600000000003e-01 -2.1014571724161748e+01 , 1.0346440563060376e+01 , 6.3026048000000001e+00 , 7.2713499999999998e-01 , 2.3790600000000001e-01 , -6.4395400000000003e-01 -2.4357122926311117e+01 , 1.1863359560292078e+01 , 7.3087632000000005e+00 , -9.7872899999999996e-01 , -6.5708499999999996e-03 , 2.0505300000000001e-01 -2.4351772595580577e+01 , 1.2037375751875603e+01 , 8.1713288000000013e+00 , 6.7823800000000001e-01 , 6.8717200000000001e-01 , 2.6036100000000001e-01 -2.4754107156028834e+01 , 1.2305144027841127e+01 , 8.7114216000000013e+00 , -6.8646099999999999e-01 , -7.1238699999999999e-01 , 1.4586099999999999e-01 -2.0392847604932054e+01 , 1.0442212919159118e+01 , 7.9733856000000003e+00 , 7.5851800000000003e-01 , -5.9182000000000001e-01 , 2.7276299999999998e-01 -1.9910031102118573e+01 , 1.0299263414831199e+01 , 8.1991383999999989e+00 , -8.9538700000000004e-01 , 4.2439700000000002e-01 , -1.3479200000000000e-01 -2.0155620317697753e+01 , 1.0484386190376952e+01 , 8.6379768000000006e+00 , 8.7240300000000004e-01 , -4.7480899999999998e-01 , 1.1606100000000000e-01 -2.0272456061738836e+01 , 1.0614195819598077e+01 , 9.0490159999999999e+00 , -9.1411399999999998e-01 , 4.0243600000000002e-01 , 4.9409399999999999e-02 -2.0704155188913656e+01 , 1.0892055082282518e+01 , 9.5821512000000020e+00 , -8.3417100000000000e-01 , 5.1859000000000000e-01 , 1.8768000000000001e-01 -2.0463416765582739e+01 , 1.0859416338973599e+01 , 9.8852696000000009e+00 , -8.6637600000000003e-01 , 2.6851300000000000e-01 , 4.2106300000000002e-01 -2.1305299998107913e+01 , 1.1338052779618907e+01 , 1.0617065600000002e+01 , -9.3893400000000005e-01 , -1.9542200000000001e-01 , 2.8322100000000000e-01 -2.3345444776816549e+01 , 1.2399284966724018e+01 , 1.1897877599999999e+01 , 5.9367800000000004e-01 , -3.5462199999999999e-01 , -7.2235000000000005e-01 -2.2455923384734401e+01 , 1.2066662849958337e+01 , 1.1975565599999999e+01 , -6.1756700000000003e-03 , 9.1566099999999997e-02 , 9.9578000000000000e-01 -1.9780190692389489e+01 , 1.0855505516148192e+01 , 1.1185196800000000e+01 , 4.3193500000000001e-01 , -1.5881400000000001e-01 , 8.8781200000000005e-01 -2.0876423652242906e+01 , 1.1477618219830587e+01 , 1.2130078400000000e+01 , -9.7005799999999998e-01 , -1.8103000000000000e-01 , 1.6191100000000000e-01 -1.8898558576339919e+01 , 1.0583949615232537e+01 , 1.1551807200000001e+01 , -7.5412299999999999e-01 , 5.3131700000000004e-01 , -3.8600699999999999e-01 -1.9136467341162724e+01 , 1.0784451478616615e+01 , 1.2081281600000001e+01 , 7.9298000000000002e-01 , -5.8255299999999999e-01 , 1.7836800000000000e-01 -2.9591323761497048e+01 , 1.6173389177338763e+01 , 1.8397368000000000e+01 , -6.4674399999999999e-01 , -4.8595500000000003e-01 , -5.8785200000000004e-01 -2.5962756297204475e+01 , 1.4454058360459607e+01 , 1.6947296000000001e+01 , -7.5089899999999998e-01 , -3.1101400000000001e-01 , -5.8259899999999998e-01 -2.1606751327064547e+01 , 1.2322309518498697e+01 , 1.4876240000000001e+01 , -1.0191100000000000e-01 , 9.7801600000000000e-01 , 1.8193200000000001e-01 -2.1255406523821598e+01 , 1.2242726520055470e+01 , 1.5159952000000001e+01 , -6.8001999999999996e-01 , 7.1571600000000002e-01 , -1.5913099999999999e-01 -2.0275979828671041e+01 , 1.1829091308678995e+01 , 1.5016536000000000e+01 , -8.6269700000000005e-01 , 2.5534299999999999e-01 , 4.3652500000000000e-01 -2.0568394383163927e+01 , 1.2086314041864243e+01 , 1.5718016000000000e+01 , -8.1583499999999998e-01 , 5.7607100000000000e-01 , -5.0558600000000002e-02 -2.1395765574513700e+01 , 1.2638634560840513e+01 , 1.6838720000000002e+01 , -8.7208100000000000e-01 , -3.1647599999999998e-01 , -3.7325300000000000e-01 -2.0881819473275570e+01 , 1.2471791479263459e+01 , 1.7007615999999999e+01 , -8.5954200000000003e-01 , 3.7561000000000000e-01 , 3.4656199999999998e-01 -2.0901316971411450e+01 , 1.2595993607628001e+01 , 1.7580863999999998e+01 , 4.7667099999999997e-02 , 4.1281299999999999e-01 , 9.0956800000000004e-01 -2.2940353645434822e+01 , 1.3851669578341655e+01 , 1.9821335999999999e+01 , -9.6853900000000004e-01 , -1.9920399999999999e-01 , -1.4916299999999999e-01 -6.9626111690220780e+00 , 5.0823492079484645e+00 , 7.5384991999999995e+00 , -7.1326500000000004e-01 , 1.1439700000000000e-01 , -6.9149600000000000e-01 -6.8693381336003903e+00 , 5.0609799540610574e+00 , 7.6128384000000002e+00 , -7.1326500000000004e-01 , 1.1439700000000000e-01 , -6.9149600000000000e-01 -6.6757973955808945e+00 , 4.9778368179249384e+00 , 7.5804736000000004e+00 , -3.7679600000000002e-01 , 5.9414100000000003e-01 , 7.1064799999999995e-01 -6.3694347732250982e+00 , 4.8236578462300947e+00 , 7.4139280000000003e+00 , 1.8589600000000001e-01 , -7.7190599999999998e-01 , -6.0795100000000002e-01 -6.1838987460360579e+00 , 4.7415961575872974e+00 , 7.3675335999999998e+00 , 1.3283300000000000e-02 , 9.8604000000000003e-01 , 1.6597600000000001e-01 -6.0826374462678112e+00 , 4.7112644277512743e+00 , 7.4114632000000000e+00 , 2.0346100000000000e-01 , 7.8760500000000000e-01 , 5.8162000000000003e-01 -6.0662323987771982e+00 , 4.7341388127167932e+00 , 7.5584152000000007e+00 , -5.6403300000000003e-02 , -9.8123600000000000e-01 , 1.8437500000000001e-01 -6.0758409308089441e+00 , 4.7764634073581469e+00 , 7.7441903999999999e+00 , -8.6076399999999997e-03 , 9.8194000000000004e-01 , 1.8899900000000000e-01 -5.8129228118396066e+00 , 4.6392407229097437e+00 , 7.5761680000000000e+00 , -9.5757900000000007e-02 , -1.0839200000000000e-01 , -9.8948599999999998e-01 -5.9370652855910180e+00 , 4.7585510889881375e+00 , 7.9260864000000000e+00 , -2.8607800000000000e-01 , 7.5543700000000003e-01 , 5.8947000000000005e-01 -5.6643864842290341e+00 , 4.6107969279314975e+00 , 7.7247736000000007e+00 , -9.8918600000000001e-01 , 5.6749599999999997e-02 , 1.3524600000000001e-01 -5.4001367687949990e+00 , 4.4640722896474241e+00 , 7.5146208000000003e+00 , 5.1558099999999996e-01 , 4.9735799999999997e-02 , 8.5539600000000005e-01 -5.2591033458930907e+00 , 4.4007094353763971e+00 , 7.4756935999999996e+00 , -9.6343799999999993e-02 , 1.9031899999999999e-01 , 9.7698300000000005e-01 -4.9783122387793810e+00 , 4.2352343696918746e+00 , 7.2005407999999997e+00 , -6.8449300000000002e-01 , -2.2507600000000000e-01 , 6.9340500000000005e-01 -4.8864947751737677e+00 , 4.2023919947169759e+00 , 7.2182000000000004e+00 , 2.1668100000000001e-01 , 9.4383399999999995e-01 , -2.4945300000000001e-01 -4.9292262537330913e+00 , 4.2707120821101725e+00 , 7.4715648000000003e+00 , 1.0694800000000000e-01 , 9.8535399999999995e-01 , 1.3281100000000001e-01 -4.7461575488292453e+00 , 4.1693069945990011e+00 , 7.3244776000000007e+00 , 2.0209299999999999e-01 , -5.9576400000000002e-03 , 9.7934800000000000e-01 -4.6814822968784497e+00 , 4.1564195139832583e+00 , 7.3889991999999998e+00 , 2.5550400000000001e-01 , 1.6819000000000001e-01 , 9.5206599999999997e-01 -4.5460095871492294e+00 , 4.0872969930091045e+00 , 7.3121536000000003e+00 , 1.6557600000000000e-01 , -3.7513600000000002e-01 , 9.1206200000000004e-01 -4.6021513672394123e+00 , 4.1744756110866215e+00 , 7.6303415999999995e+00 , 5.4783400000000004e-01 , -7.9658300000000004e-01 , 2.5560400000000000e-01 -4.4797886089143368e+00 , 4.1157994674338623e+00 , 7.5765111999999997e+00 , -2.9462400000000000e-01 , 7.8915599999999997e-01 , 5.3891500000000003e-01 -4.4596860503317810e+00 , 4.1440365676113746e+00 , 7.7545280000000005e+00 , -1.9901300000000000e-01 , 8.8544500000000004e-01 , -4.1997699999999999e-01 -4.3608524731933400e+00 , 4.1040841791558647e+00 , 7.7512416000000002e+00 , 6.8833199999999997e-02 , -2.6471099999999997e-01 , 9.6186799999999995e-01 -4.2550162733289767e+00 , 4.0581068873884014e+00 , 7.7270928000000003e+00 , -3.4763899999999998e-01 , 2.9692900000000000e-01 , -8.8937100000000002e-01 -4.2306716211249622e+00 , 4.0862268792963947e+00 , 7.9141472000000004e+00 , 8.2275200000000004e-01 , -2.1853200000000000e-01 , 5.2471299999999998e-01 -4.1636072517560239e+00 , 4.0775347826824238e+00 , 7.9990112000000000e+00 , 9.8385000000000000e-01 , 1.6748199999999999e-01 , 6.3161499999999995e-02 -3.8069884584448994e+00 , 3.7761523830635380e+00 , 7.2069887999999995e+00 , -6.9265500000000002e-01 , -4.9106800000000000e-01 , 5.2828100000000000e-01 -3.6782500579517494e+00 , 3.6931249911359032e+00 , 7.0467976000000005e+00 , 4.9781799999999998e-01 , 4.9469000000000002e-01 , -7.1236100000000002e-01 -3.6095991588184289e+00 , 3.6717913096677006e+00 , 7.0737960000000006e+00 , -1.6354800000000000e-01 , 7.4283600000000005e-01 , 6.4918900000000002e-01 -3.8158925389136513e+00 , 3.9628737465357604e+00 , 8.1093447999999988e+00 , -3.1360300000000002e-01 , -4.4084200000000001e-01 , 8.4101800000000004e-01 -3.9922024486364291e+00 , 4.2496928036617927e+00 , 9.1752719999999997e+00 , -2.4869100000000000e-01 , -7.5540799999999997e-01 , 6.0622699999999996e-01 -3.9090187201405620e+00 , 4.2418928685898818e+00 , 9.2980336000000001e+00 , 1.3271400000000000e-01 , -5.6168399999999996e-01 , 8.1663799999999998e-01 -3.6237845005045384e+00 , 3.9670991988290440e+00 , 8.5003848000000009e+00 , -9.8284800000000005e-01 , -6.1549800000000002e-02 , -1.7384300000000000e-01 -3.6605789587854387e+00 , 4.1198826257809724e+00 , 9.1769984000000004e+00 , 7.4894200000000000e-01 , 8.7913099999999994e-02 , 6.5677799999999997e-01 -3.5984635804922283e+00 , 4.1476574524895460e+00 , 9.4333272000000008e+00 , 7.6103799999999999e-02 , 4.6405600000000002e-01 , 8.8253099999999995e-01 -3.4622339598855976e+00 , 4.0637375949819603e+00 , 9.2829016000000006e+00 , 3.5604300000000000e-01 , -2.8235700000000002e-01 , 8.9079100000000000e-01 -3.3801833382817716e+00 , 4.0664711418401236e+00 , 9.4581416000000011e+00 , -8.4211599999999998e-02 , 2.7141399999999999e-01 , 9.5877199999999996e-01 -3.2670260285423525e+00 , 4.0192856872535980e+00 , 9.4422504000000007e+00 , 8.0660200000000004e-01 , -5.8666399999999996e-01 , 7.2240799999999994e-02 -2.8581919093617461e+00 , 3.3095669634543325e+00 , 6.7441368000000006e+00 , -4.3330900000000000e-01 , 5.2449299999999999e-01 , -7.3290599999999995e-01 -2.7929811213483617e+00 , 3.2779370881824716e+00 , 6.7155056000000002e+00 , 1.2070900000000000e-01 , -4.5293800000000001e-01 , 8.8333300000000003e-01 -2.7317314124308236e+00 , 3.2540819346544971e+00 , 6.7157864000000007e+00 , 3.0453799999999998e-01 , -4.1379500000000002e-01 , 8.5792199999999996e-01 -2.6916936653400203e+00 , 3.3120756759614629e+00 , 7.0794328000000002e+00 , 9.8589499999999997e-01 , -1.3704700000000000e-02 , -1.6680100000000000e-01 -2.6755257550778029e+00 , 3.5454034286449070e+00 , 8.2551632000000001e+00 , -5.2008200000000004e-01 , -5.8492500000000003e-01 , 6.2239599999999995e-01 -2.5639768177997908e+00 , 3.3117811851191084e+00 , 7.3195063999999999e+00 , -2.2971000000000000e-01 , 2.0767800000000000e-01 , 9.5084400000000002e-01 -2.4936566788874819e+00 , 3.2833283681680934e+00 , 7.3161263999999999e+00 , 2.5395400000000001e-01 , 4.9118400000000001e-01 , 8.3321400000000001e-01 -2.4221672556065630e+00 , 3.2844675194697470e+00 , 7.4646072000000006e+00 , -7.9517300000000002e-01 , -6.0339200000000004e-01 , -6.0142200000000000e-02 -2.3300954042933517e+00 , 3.4135160451251432e+00 , 8.2752456000000016e+00 , -2.4001000000000000e-01 , 2.8542400000000001e-01 , -9.2786199999999996e-01 -2.2409716122974270e+00 , 3.3942400443504197e+00 , 8.3502919999999996e+00 , 6.0643000000000002e-01 , -7.1588600000000002e-02 , 7.9190799999999995e-01 -2.1719115282459125e+00 , 3.3009515650263390e+00 , 8.0253232000000008e+00 , -4.5490300000000000e-01 , 8.7548500000000001e-02 , 8.8622699999999999e-01 -2.0960946140872618e+00 , 3.2548835767695667e+00 , 7.9439016000000002e+00 , 2.9281900000000000e-01 , -4.8729499999999998e-01 , 8.2267900000000005e-01 -2.0083895840987931e+00 , 3.2367016491147940e+00 , 8.0246576000000012e+00 , 7.9219600000000001e-01 , 2.3358699999999999e-01 , 5.6379299999999999e-01 -1.7347323301250521e+00 , 3.4983858063796358e+00 , 9.8395720000000004e+00 , -1.4328600000000000e-01 , -5.0674399999999997e-01 , 8.5010500000000000e-01 -4.7025308505789436e+00 , 2.8274766774761861e+00 , 1.1505019999999999e+00 , -1.3432200000000000e-01 , 2.1746299999999999e-01 , 9.6678200000000003e-01 -4.7642732079502572e+00 , 2.8518487286824232e+00 , 1.1634364800000001e+00 , -1.3053999999999999e-01 , 1.6925999999999999e-01 , 9.7688799999999998e-01 -4.8329273090405742e+00 , 2.8781397020739510e+00 , 1.1715526400000000e+00 , -1.0049400000000000e-01 , 1.7823900000000001e-01 , 9.7884199999999999e-01 -4.9187036108197226e+00 , 2.9089563028594450e+00 , 1.1688839999999998e+00 , -8.5650299999999999e-02 , 1.7615600000000001e-01 , 9.8062899999999997e-01 -5.0051578001251720e+00 , 2.9392555872194439e+00 , 1.1690763999999998e+00 , -6.9029099999999996e-02 , 2.1009200000000000e-01 , 9.7524200000000005e-01 -5.0843004446564910e+00 , 2.9694511850446177e+00 , 1.1777281600000000e+00 , -3.9397200000000000e-02 , 1.9406000000000001e-01 , 9.8019800000000001e-01 -5.1793377626644999e+00 , 3.0034227142467920e+00 , 1.1768899199999998e+00 , -4.0395100000000003e-02 , 2.1723700000000001e-01 , 9.7528300000000001e-01 -5.2842099869178654e+00 , 3.0406495878452873e+00 , 1.1732260000000001e+00 , -6.1800099999999997e-02 , 1.8217100000000000e-01 , 9.8132299999999995e-01 -5.3816449244979054e+00 , 3.0757756646072494e+00 , 1.1786329599999998e+00 , -8.6716399999999999e-02 , 1.7262200000000000e-01 , 9.8116400000000004e-01 -5.4787779948437940e+00 , 3.1125479440610286e+00 , 1.1868707999999999e+00 , -8.1544900000000003e-02 , 1.7728600000000000e-01 , 9.8077499999999995e-01 -5.5936999198887136e+00 , 3.1544309169839191e+00 , 1.1873845599999999e+00 , -3.9416899999999998e-02 , 1.9865900000000000e-01 , 9.7927600000000004e-01 -5.7182683979632696e+00 , 3.1988232645661245e+00 , 1.1865931199999999e+00 , -3.7381300000000001e-01 , 1.8708600000000000e-01 , 9.0844000000000003e-01 -5.7902961056248348e+00 , 3.2310338278008794e+00 , 1.2195392800000000e+00 , 9.9144399999999999e-01 , 6.7115400000000006e-02 , -1.1196000000000000e-01 -5.7720119025248993e+00 , 3.2410873994956906e+00 , 1.3024304000000000e+00 , 9.6920399999999995e-01 , 6.7989999999999995e-02 , -2.3668900000000001e-01 -5.7617748295292177e+00 , 3.2528507304971845e+00 , 1.3797180000000000e+00 , 9.9332799999999999e-01 , 9.2433199999999993e-02 , -6.8960199999999999e-02 -5.8223027758998800e+00 , 3.2818526036785625e+00 , 1.4206295199999999e+00 , 9.8804899999999996e-01 , -1.2194700000000000e-01 , 9.4275600000000001e-02 -5.7541707559366237e+00 , 3.2779039098864118e+00 , 1.5235208800000000e+00 , 9.9063800000000002e-01 , 1.1493800000000000e-01 , 7.3662300000000000e-02 -5.7488966313890000e+00 , 3.2903114273760692e+00 , 1.5945258400000000e+00 , 9.9448999999999999e-01 , 9.3903600000000004e-02 , 4.6610699999999998e-02 -5.8527247614962423e+00 , 3.3318514064413520e+00 , 1.6173205600000000e+00 , 9.9448999999999999e-01 , 9.3903600000000004e-02 , 4.6610699999999998e-02 -5.7510628683415188e+00 , 3.3180486908031912e+00 , 1.7273806400000000e+00 , -9.6077699999999999e-01 , -1.0146700000000000e-01 , 2.5809199999999999e-01 -5.7506160172834200e+00 , 3.3313509140338198e+00 , 1.7933176799999999e+00 , -9.7358800000000001e-01 , -2.2443900000000000e-01 , -4.1874700000000001e-02 -5.7115985287733961e+00 , 3.3331777508109224e+00 , 1.8731127200000000e+00 , 9.0519000000000005e-01 , 1.4961099999999999e-01 , 3.9780399999999999e-01 -5.6903958667252006e+00 , 3.3389925407942354e+00 , 1.9448840560000000e+00 , 9.7671399999999997e-01 , -2.8064499999999999e-02 , -2.1270200000000000e-01 -5.7046597490802622e+00 , 3.3563623362213146e+00 , 2.0025212408000002e+00 , 9.7671399999999997e-01 , -2.8064499999999999e-02 , -2.1270200000000000e-01 -5.7374744642026583e+00 , 3.3782247667725045e+00 , 2.0547895920000001e+00 , 8.2105700000000004e-01 , -9.2559699999999995e-02 , -5.6329300000000004e-01 -5.7887611477131253e+00 , 3.4058064553056093e+00 , 2.1024956399999999e+00 , -7.2764300000000004e-01 , 1.1774600000000000e-01 , 6.7577399999999999e-01 -5.8398486577239801e+00 , 3.4337425180638652e+00 , 2.1519221599999998e+00 , 4.8372599999999999e-01 , -1.6670599999999999e-01 , -8.5919599999999996e-01 -5.9669381946260991e+00 , 3.4855380944003347e+00 , 2.1831440000000000e+00 , 2.4489300000000000e-01 , -2.1114300000000000e-01 , -9.4628000000000001e-01 -6.1608482750104994e+00 , 3.5596874915407373e+00 , 2.2025535199999999e+00 , -1.6730200000000001e-01 , 1.8899600000000000e-01 , 9.6762099999999995e-01 -6.5108473994195135e+00 , 3.6833379603610572e+00 , 2.1952901599999999e+00 , -1.8398700000000000e-02 , 2.4365899999999999e-01 , 9.6968699999999997e-01 -6.8323169092917837e+00 , 3.8002119513603656e+00 , 2.2062673600000000e+00 , -6.0059099999999997e-02 , 2.5346800000000003e-01 , 9.6547799999999995e-01 -7.1728971284772722e+00 , 3.9263547737183409e+00 , 2.2251724799999999e+00 , -1.0030699999999999e-01 , 2.2657800000000000e-01 , 9.6881399999999995e-01 -1.2223219859108273e+01 , 5.5891392763621273e+00 , 1.4896460000000000e+00 , -5.4992800000000001e-02 , 1.9094500000000000e-01 , 9.8005900000000001e-01 -1.3196602956574951e+01 , 5.9456903275678901e+00 , 1.5275363200000001e+00 , -6.8908100000000000e-02 , 1.8755600000000000e-01 , 9.7983399999999998e-01 -1.4443056249672429e+01 , 6.3999566515839863e+00 , 1.5658967200000000e+00 , -4.6895500000000000e-02 , 1.8318100000000001e-01 , 9.8196000000000006e-01 -1.6128654330536285e+01 , 7.0110708924490410e+00 , 1.6016040800000000e+00 , -7.9979099999999997e-02 , 1.8065200000000001e-01 , 9.8028999999999999e-01 -1.7871942906636445e+01 , 7.6542961478036942e+00 , 1.6930720799999999e+00 , -6.0289000000000002e-02 , 1.8199100000000001e-01 , 9.8145000000000004e-01 -2.1338680361765750e+01 , 8.9025133994799130e+00 , 1.7240921600000001e+00 , -6.3742199999999999e-02 , 2.0228900000000000e-01 , 9.7724900000000003e-01 -2.4693242479621350e+01 , 1.0216746371184701e+01 , 2.2907631999999998e+00 , -3.8032199999999999e-01 , 8.2270899999999994e-02 , 9.2118800000000001e-01 -2.5765447270521165e+01 , 1.0677330395259487e+01 , 2.6765148000000001e+00 , -5.0638099999999997e-01 , 1.2314400000000000e-01 , 8.5347200000000001e-01 -2.6191812730575080e+01 , 1.0914495651047540e+01 , 3.1013288000000001e+00 , 5.2251999999999998e-01 , -1.2614300000000001e-01 , -8.4324399999999999e-01 -2.6610880753191580e+01 , 1.1153110423654050e+01 , 3.5424136000000002e+00 , -8.0040100000000003e-01 , -2.0953600000000000e-01 , 5.6165200000000004e-01 -2.6091278086922014e+01 , 1.1224612184449988e+01 , 4.8352480000000000e+00 , -6.2209599999999998e-01 , -6.7765699999999995e-01 , -3.9214599999999999e-01 -2.4567676371606520e+01 , 1.0737245158597474e+01 , 5.1320535999999999e+00 , 2.8469699999999998e-01 , 1.9350500000000001e-01 , 9.3888400000000005e-01 -2.1729353350486193e+01 , 9.7392528208313855e+00 , 5.2279727999999999e+00 , 1.2017700000000001e-01 , 9.1203900000000004e-01 , 3.9210099999999998e-01 -2.1860487171492135e+01 , 9.8618692544297524e+00 , 5.6063767999999996e+00 , 1.2017700000000001e-01 , 9.1203900000000004e-01 , 3.9210099999999998e-01 -2.2436600983286770e+01 , 1.0158614140977798e+01 , 6.0584440000000006e+00 , -3.8586500000000001e-01 , 4.7528399999999998e-01 , -7.9070499999999999e-01 -2.0590770363640864e+01 , 9.5108488275595473e+00 , 6.1281552000000001e+00 , 2.5763900000000001e-01 , 1.9236100000000000e-01 , 9.4689999999999996e-01 -2.4536527920151542e+01 , 1.1141130126153483e+01 , 7.2143936000000002e+00 , 9.8564700000000005e-01 , -1.6298699999999999e-01 , 4.3994300000000000e-02 -2.9664682089446458e+01 , 1.3273656022130194e+01 , 8.7005015999999991e+00 , -9.2142700000000000e-01 , 2.2749200000000000e-01 , 3.1499100000000002e-01 -2.8986962601696309e+01 , 1.3106998286022236e+01 , 9.0779280000000000e+00 , 2.3619200000000001e-01 , -9.6801000000000004e-01 , 8.4676100000000004e-02 -2.4822774441126608e+01 , 1.1603624016887867e+01 , 9.0228391999999999e+00 , 5.1960799999999996e-01 , 2.4952500000000000e-01 , 8.1715599999999999e-01 -2.2185745726073627e+01 , 1.0598334016817551e+01 , 8.7198144000000006e+00 , -3.3514200000000000e-01 , -7.7753000000000005e-01 , -5.3209600000000001e-01 -2.0284222091932687e+01 , 9.8813826955782353e+00 , 8.5396239999999999e+00 , -9.5507399999999998e-01 , 1.7829200000000001e-01 , 2.3673900000000000e-01 -2.0316336773521591e+01 , 9.9679460007843304e+00 , 8.9180592000000001e+00 , 9.4216699999999998e-01 , -1.5587599999999999e-01 , -2.9668899999999998e-01 -3.0843217980373076e+01 , 1.4542479758072130e+01 , 1.2951720000000000e+01 , 6.4142299999999997e-01 , -1.9417699999999999e-01 , 7.4220699999999995e-01 -2.0276150405878639e+01 , 1.0100232729221561e+01 , 9.6556791999999998e+00 , -5.1650799999999997e-01 , 8.5391099999999998e-01 , 6.3687999999999995e-02 -1.9200385950566023e+01 , 9.7079869235571792e+00 , 9.6189672000000002e+00 , -1.4952299999999999e-01 , -5.9395799999999999e-01 , 7.9047900000000004e-01 -1.9468602247199602e+01 , 9.8987469763816804e+00 , 1.0095984000000000e+01 , -4.4466699999999998e-01 , -4.3292799999999998e-01 , 7.8412000000000004e-01 -1.8534174459911522e+01 , 9.5583695461956353e+00 , 1.0067675200000000e+01 , -9.8311899999999997e-01 , 1.3897300000000001e-01 , -1.1900800000000000e-01 -1.9682887013401601e+01 , 1.0146689939232404e+01 , 1.0956022400000002e+01 , 4.4958799999999999e-01 , 4.7638900000000001e-01 , 7.5559500000000002e-01 -2.1332720940182828e+01 , 1.0974542475479225e+01 , 1.2144316000000000e+01 , -6.6612499999999997e-01 , 4.1735399999999999e-02 , 7.4467200000000000e-01 -1.8835773441559024e+01 , 9.9173827763247608e+00 , 1.1328987200000000e+01 , 8.1643399999999999e-01 , -3.0907499999999999e-01 , 4.8775800000000002e-01 -1.8820869548004122e+01 , 9.9888120598285468e+00 , 1.1711967200000002e+01 , -9.4338200000000005e-01 , 1.9055100000000000e-01 , 2.7151599999999998e-01 -1.8780355865687536e+01 , 1.0049425874429764e+01 , 1.2088488800000000e+01 , -9.2434400000000005e-01 , 3.0965300000000001e-01 , 2.2294300000000000e-01 -1.9007707686156291e+01 , 1.0238141863944435e+01 , 1.2625680000000001e+01 , 7.9418699999999998e-01 , -4.2579400000000001e-01 , -4.3354999999999999e-01 -2.6849271066262784e+01 , 1.4070206984852158e+01 , 1.7766400000000001e+01 , 7.2861700000000001e-02 , 1.3077300000000000e-02 , -9.9725600000000003e-01 -2.5037805731452920e+01 , 1.3321488660591545e+01 , 1.7263248000000001e+01 , 3.0437700000000001e-01 , 1.9334699999999999e-01 , 9.3272299999999997e-01 -2.0138675793423442e+01 , 1.1048009984097691e+01 , 1.4657320000000000e+01 , -9.3784000000000001e-01 , 2.2681999999999999e-01 , 2.6269399999999998e-01 -2.0279869795990521e+01 , 1.1212607493746068e+01 , 1.5235664000000000e+01 , 8.0783400000000005e-01 , -4.5615299999999998e-01 , -3.7326799999999999e-01 -2.0256412172715674e+01 , 1.1301106470900246e+01 , 1.5717392000000000e+01 , 8.0783400000000005e-01 , -4.5615299999999998e-01 , -3.7326799999999999e-01 -2.1772566402263507e+01 , 1.2168617888378758e+01 , 1.7347904000000000e+01 , 6.8611500000000006e-02 , 2.5950200000000001e-01 , 9.6330199999999999e-01 -2.1378054171069039e+01 , 1.2080029742506962e+01 , 1.7614559999999997e+01 , 6.8611500000000006e-02 , 2.5950200000000001e-01 , 9.6330199999999999e-01 -2.0476587473968845e+01 , 1.1728336711400697e+01 , 1.7468544000000001e+01 , 1.4537200000000000e-01 , 2.0584800000000000e-01 , 9.6772599999999998e-01 -1.9877026325457866e+01 , 1.1526321851776064e+01 , 1.7534272000000001e+01 , 1.5086900000000000e-01 , 2.1115500000000001e-01 , 9.6573900000000001e-01 -1.9589880148186232e+01 , 1.1486005469427887e+01 , 1.7847312000000002e+01 , 1.5086900000000000e-01 , 2.1115500000000001e-01 , 9.6573900000000001e-01 -7.8380389847792031e+00 , 5.3694879234995181e+00 , 8.2756408000000015e+00 , -2.9769299999999999e-01 , 8.1537300000000001e-01 , -4.9653300000000000e-01 -6.9299328295365070e+00 , 4.9020886135853434e+00 , 7.5643952000000008e+00 , 4.0463300000000002e-01 , 1.6279400000000000e-03 , 9.1447800000000001e-01 -6.8894387761451163e+00 , 4.9136599432969765e+00 , 7.6922528000000003e+00 , 4.0463300000000002e-01 , 1.6278700000000000e-03 , 9.1447800000000001e-01 -6.7531183767184224e+00 , 4.8700773097355894e+00 , 7.7208839999999999e+00 , 1.7196900000000001e-01 , 1.7122299999999999e-01 , 9.7010799999999997e-01 -6.6117659693664574e+00 , 4.8234690596353751e+00 , 7.7387512000000003e+00 , -2.8999300000000000e-01 , 8.1729700000000005e-01 , 4.9792599999999998e-01 -7.1798755061598634e+00 , 5.1941454501039077e+00 , 8.5772095999999998e+00 , 7.2439299999999998e-02 , 7.8794699999999995e-01 , -6.1146800000000001e-01 -7.0315906813106510e+00 , 5.1474477583811016e+00 , 8.6089191999999990e+00 , -3.4661100000000000e-02 , -7.6026800000000005e-01 , 6.4868400000000004e-01 -5.8104737828633759e+00 , 4.4471638260907005e+00 , 7.2916448000000003e+00 , -8.7617299999999998e-01 , 3.2438400000000001e-01 , -3.5650599999999999e-01 -5.7362482432887436e+00 , 4.4338047966418710e+00 , 7.3570608000000002e+00 , 8.1218299999999999e-01 , -6.5323300000000001e-02 , 5.7973399999999997e-01 -5.7064045866757906e+00 , 4.4479064720022015e+00 , 7.4839304000000002e+00 , -8.7094199999999999e-01 , 3.9062300000000000e-01 , -2.9811799999999999e-01 -5.8648569723047856e+00 , 4.5838495114120974e+00 , 7.8815016000000000e+00 , 3.0312400000000000e-01 , -7.8807899999999997e-01 , -5.3576800000000002e-01 -5.7745428451016112e+00 , 4.5634832958262539e+00 , 7.9403760000000005e+00 , 5.1642900000000003e-01 , -6.7978700000000003e-01 , -5.2076000000000000e-01 -5.3447254157437190e+00 , 4.3188481389140625e+00 , 7.4829216000000001e+00 , 2.0893300000000001e-01 , 9.6563899999999994e-02 , 9.7315099999999999e-01 -5.3089735884658138e+00 , 4.3303726706707488e+00 , 7.6063176000000006e+00 , -4.1402899999999998e-01 , 3.0016100000000001e-01 , 8.5934999999999995e-01 -5.1131024033105055e+00 , 4.2328135869935490e+00 , 7.4702856000000004e+00 , -1.0100600000000000e-01 , -4.3818499999999999e-01 , -8.9319199999999999e-01 -4.8678792182333570e+00 , 4.0982334175878776e+00 , 7.2348504000000000e+00 , -3.6406400000000000e-01 , 7.6931700000000006e-02 , -9.2819099999999999e-01 -5.0103917134586702e+00 , 4.2358584168541995e+00 , 7.6689984000000004e+00 , -3.4357399999999999e-01 , -8.5319699999999998e-01 , -3.9244299999999999e-01 -4.6240040151074773e+00 , 3.9934902034802779e+00 , 7.1477712000000002e+00 , 9.2729300000000001e-02 , -1.6876600000000000e-01 , 9.8128499999999996e-01 -4.6158172719336870e+00 , 4.0231452757676021e+00 , 7.3142855999999998e+00 , 2.3976399999999998e-02 , -3.2673099999999999e-01 , 9.4481300000000001e-01 -4.8228231468444731e+00 , 4.2207785009162588e+00 , 7.9336056000000008e+00 , -2.7134599999999998e-01 , -9.5302799999999999e-01 , -1.3456899999999999e-01 -4.5969127825584710e+00 , 4.0886594553126612e+00 , 7.6775992000000004e+00 , -3.5554900000000000e-01 , 8.3080100000000001e-01 , 4.2819900000000000e-01 -4.5809097303622455e+00 , 4.1208579661515952e+00 , 7.8656519999999999e+00 , -9.7499700000000000e-01 , -8.0367900000000006e-02 , -2.0717500000000000e-01 -4.4672982905940160e+00 , 4.0741853117180842e+00 , 7.8363448000000000e+00 , -2.9508200000000001e-01 , 3.6969999999999997e-01 , 8.8105000000000000e-01 -4.3362986148760214e+00 , 4.0120499228719515e+00 , 7.7582616000000000e+00 , 4.2993500000000001e-01 , 4.3926300000000001e-01 , 7.8879900000000003e-01 -4.2765104191053993e+00 , 4.0092896197411658e+00 , 7.8530264000000001e+00 , -8.1735700000000000e-01 , -3.7828800000000001e-01 , -4.3454100000000001e-01 -3.9707938759048238e+00 , 3.7848129300705224e+00 , 7.2744328000000005e+00 , -8.3527600000000002e-01 , -2.9303200000000001e-01 , 4.6523799999999998e-01 -3.8301415825203184e+00 , 3.7011956546176652e+00 , 7.1086776000000000e+00 , 5.7190099999999999e-01 , -2.2776800000000000e-01 , -7.8806799999999999e-01 -3.7488951839585329e+00 , 3.6700186220337336e+00 , 7.0999832000000005e+00 , 4.5466899999999999e-01 , 7.8738900000000001e-01 , -4.1628700000000002e-01 -3.7490073528781949e+00 , 3.7217088700940151e+00 , 7.3565719999999999e+00 , -6.1987199999999998e-01 , 3.0351599999999999e-02 , -7.8411500000000001e-01 -3.9377845333100709e+00 , 3.9783292281310794e+00 , 8.3069552000000009e+00 , -6.6097700000000004e-01 , -6.6193900000000006e-01 , 3.5347699999999999e-01 -3.9950281568656947e+00 , 4.1146715495664354e+00 , 8.8904888000000000e+00 , 2.4397500000000000e-01 , -8.4021100000000004e-01 , 4.8427399999999998e-01 -3.9770586329363207e+00 , 4.1814364083889597e+00 , 9.2549360000000007e+00 , -6.4582300000000004e-01 , 1.6835500000000000e-01 , -7.4469399999999997e-01 -3.6854626814920874e+00 , 3.9215887834480885e+00 , 8.4773904000000009e+00 , -9.9037799999999998e-01 , -1.3784500000000000e-01 , 1.2230300000000000e-02 -3.7136097536201991e+00 , 4.0514386965671001e+00 , 9.0751927999999999e+00 , 3.9912399999999998e-01 , -1.1082100000000000e-01 , 9.1017499999999996e-01 -3.6338357044179626e+00 , 4.0516837238291341e+00 , 9.2227792000000015e+00 , -7.2303899999999999e-01 , -9.5643400000000003e-02 , -6.8415499999999996e-01 -3.5568568670653180e+00 , 4.0617486175014559e+00 , 9.4091784000000001e+00 , 4.7988999999999998e-01 , -5.6168300000000004e-01 , -6.7395600000000000e-01 -3.4541658004497164e+00 , 4.0361144758511092e+00 , 9.4655464000000009e+00 , -1.5894200000000000e-01 , 2.8540500000000002e-01 , 9.4513599999999998e-01 -3.3110895247005816e+00 , 3.9395372941618638e+00 , 9.2402823999999999e+00 , 6.1405600000000005e-01 , -3.1283699999999998e-01 , -7.2461600000000004e-01 -3.1929366356279067e+00 , 3.8800379124647382e+00 , 9.1516328000000016e+00 , 7.0899000000000001e-01 , 1.8328800000000001e-01 , -6.8098400000000003e-01 -3.0633334418906939e+00 , 3.7868285511477850e+00 , 8.9195671999999995e+00 , -7.4186099999999999e-01 , 1.8297500000000001e-02 , 6.7030400000000001e-01 -2.7730032068424180e+00 , 3.2528341008326045e+00 , 6.7553272000000000e+00 , 3.0453799999999998e-01 , -4.1379500000000002e-01 , 8.5792199999999996e-01 -2.7099165040579325e+00 , 3.2279274326774381e+00 , 6.7446984000000008e+00 , 4.1605199999999998e-01 , -6.2012800000000001e-01 , 6.6508800000000001e-01 -2.6511750122279278e+00 , 3.2179724631964253e+00 , 6.8039680000000002e+00 , -5.6760500000000003e-01 , 4.4246099999999999e-01 , -6.9430099999999995e-01 -2.6075284854928862e+00 , 3.3087352498817495e+00 , 7.3400151999999999e+00 , 6.4235100000000001e-01 , 1.8118400000000001e-01 , -7.4468599999999996e-01 -2.5345486008136406e+00 , 3.2764006457158481e+00 , 7.3062360000000002e+00 , -5.8864600000000003e-02 , 2.9876700000000000e-01 , 9.5250900000000005e-01 -2.4634600791761985e+00 , 3.2622237424981861e+00 , 7.3629992000000000e+00 , 5.0468199999999996e-01 , 6.9767999999999997e-01 , 5.0846700000000000e-01 -2.3770376087206344e+00 , 3.4415275873614712e+00 , 8.4189943999999990e+00 , 4.0475100000000003e-01 , -8.6498699999999995e-01 , -2.9660399999999998e-01 -2.2921169160011430e+00 , 3.3852629024512928e+00 , 8.2902944000000005e+00 , 6.0643000000000002e-01 , -7.1588600000000002e-02 , 7.9190799999999995e-01 -2.2165621338212329e+00 , 3.3098116834362230e+00 , 8.0472464000000006e+00 , -4.1673100000000002e-01 , 6.7332999999999998e-01 , 6.1070599999999997e-01 -2.1372617274886805e+00 , 3.2691604056979076e+00 , 7.9866456000000001e+00 , -2.9292299999999999e-01 , -6.2828499999999998e-01 , 7.2073200000000004e-01 -2.0576716967201887e+00 , 3.2343822600888492e+00 , 7.9551544000000005e+00 , 1.8132999999999999e-01 , -5.1750700000000005e-01 , 8.3624500000000002e-01 -1.7935091375206609e+00 , 3.5135369699100396e+00 , 9.8324688000000009e+00 , -5.0039800000000001e-01 , -8.1914900000000002e-01 , 2.8035199999999999e-01 -1.7447939531894816e+00 , 3.3834227348633563e+00 , 9.2658664000000002e+00 , -9.7253599999999996e-01 , 1.7168600000000001e-01 , -1.5715299999999999e-01 -4.6921712803079210e+00 , 2.7579192306308640e+00 , 1.1561648000000000e+00 , -1.3091700000000001e-01 , 2.1659800000000001e-01 , 9.6744300000000005e-01 -4.7539777638117995e+00 , 2.7810850167415597e+00 , 1.1683941600000001e+00 , -1.3390800000000000e-01 , 2.0981800000000000e-01 , 9.6852700000000003e-01 -4.8318553057603957e+00 , 2.8066331169512866e+00 , 1.1695183999999998e+00 , -1.1068500000000001e-01 , 1.7374200000000001e-01 , 9.7855099999999995e-01 -4.9013400566058705e+00 , 2.8310773429789724e+00 , 1.1791810400000000e+00 , -7.3173699999999994e-02 , 1.6714399999999999e-01 , 9.8321300000000000e-01 -4.9726619714783133e+00 , 2.8558812467630155e+00 , 1.1910172800000001e+00 , -6.5479300000000004e-02 , 1.7121900000000001e-01 , 9.8305500000000001e-01 -5.0599513560932081e+00 , 2.8843113598358716e+00 , 1.1926563200000000e+00 , -5.9310700000000001e-02 , 1.9049500000000000e-01 , 9.7989499999999996e-01 -5.1641971700966929e+00 , 2.9175613928877464e+00 , 1.1849291200000001e+00 , 5.0997500000000001e-02 , -2.2112699999999999e-01 , -9.7391099999999997e-01 -5.2529249585071218e+00 , 2.9470619707057453e+00 , 1.1921820800000000e+00 , -2.4568500000000000e-02 , 2.0953300000000000e-01 , 9.7749299999999995e-01 -5.3585309395183618e+00 , 2.9815066812373674e+00 , 1.1906751199999999e+00 , -6.7096199999999995e-02 , 1.6849400000000000e-01 , 9.8341599999999996e-01 -5.4476969993222255e+00 , 3.0131377582802656e+00 , 1.2033111200000000e+00 , -1.0001900000000000e-01 , 1.8232699999999999e-01 , 9.7813799999999995e-01 -5.5556817293367180e+00 , 3.0487777595187557e+00 , 1.2082521600000000e+00 , 6.9716600000000004e-02 , -1.7689800000000000e-01 , -9.8175699999999999e-01 -5.6723557865189065e+00 , 3.0878802018711342e+00 , 1.2111506400000001e+00 , 1.7493000000000000e-01 , -1.9177900000000001e-01 , -9.6572300000000000e-01 -5.8066075566528204e+00 , 3.1303081249028013e+00 , 1.2079505600000000e+00 , -7.8513299999999997e-01 , 9.5459799999999997e-02 , 6.1192599999999997e-01 -5.7983873230234577e+00 , 3.1432199127057778e+00 , 1.2860940800000000e+00 , -9.2421200000000003e-01 , 1.1273699999999999e-02 , 3.8171300000000002e-01 -5.8071774522228399e+00 , 3.1597432892311903e+00 , 1.3541641599999998e+00 , 9.8549100000000001e-01 , 8.7870599999999993e-02 , -1.4521200000000001e-01 -5.7858920564248777e+00 , 3.1685836321803347e+00 , 1.4356700000000000e+00 , 9.8265100000000005e-01 , 1.8531800000000001e-01 , -7.2984199999999999e-03 -5.8194628958613528e+00 , 3.1898045335714258e+00 , 1.4901920000000000e+00 , 9.8265100000000005e-01 , 1.8531800000000001e-01 , -7.2984199999999999e-03 -5.7962528015239627e+00 , 3.1984552786146603e+00 , 1.5703333600000000e+00 , 9.5398600000000000e-01 , 2.9475600000000002e-01 , -5.5035199999999999e-02 -5.7620925325645409e+00 , 3.2029136310621817e+00 , 1.6536852000000000e+00 , 9.7484899999999997e-01 , 2.2270899999999999e-01 , 8.3930700000000007e-03 -5.7726452440143401e+00 , 3.2192223395552428e+00 , 1.7158085600000001e+00 , -9.6545999999999998e-01 , -1.9586100000000001e-01 , 1.7183200000000001e-01 -5.7731935665718446e+00 , 3.2314889907678985e+00 , 1.7820752799999999e+00 , 9.9597899999999995e-01 , 8.4660500000000000e-02 , 2.9291800000000000e-02 -5.8290118780503200e+00 , 3.2582829527101378e+00 , 1.8268441600000001e+00 , 9.5262000000000002e-01 , 1.3102900000000001e-01 , 2.7449299999999999e-01 -5.7031557041787018e+00 , 3.2391407410852660e+00 , 1.9368653440000001e+00 , 9.5213499999999995e-01 , 1.0991099999999999e-01 , 2.8523300000000001e-01 -5.7282890682042833e+00 , 3.2575413161271300e+00 , 1.9914023824000000e+00 , -8.7999200000000000e-01 , 4.1522099999999999e-02 , 4.7317100000000001e-01 -5.7326543391568023e+00 , 3.2717606413994726e+00 , 2.0523723199999999e+00 , -8.7999200000000000e-01 , 4.1522099999999999e-02 , 4.7317100000000001e-01 -5.7948696639406858e+00 , 3.3002906592290784e+00 , 2.0965734640000000e+00 , -7.9830800000000002e-01 , 8.6494900000000000e-02 , 5.9600600000000004e-01 -5.8176164916297033e+00 , 3.3182148874722062e+00 , 2.1534925600000001e+00 , -6.0017399999999999e-01 , 1.3422600000000001e-01 , 7.8852699999999998e-01 -5.9360528128023660e+00 , 3.3631766336081306e+00 , 2.1858552800000002e+00 , 3.5530499999999998e-01 , -1.7095399999999999e-01 , -9.1898500000000005e-01 -6.0832949014038604e+00 , 3.4169551915132690e+00 , 2.2154089600000000e+00 , -1.6716200000000001e-01 , 1.9783800000000001e-01 , 9.6587599999999996e-01 -6.2797056089301009e+00 , 3.4855215372540256e+00 , 2.2392592800000002e+00 , -6.4318200000000006e-02 , 2.0782300000000001e-01 , 9.7604999999999997e-01 -6.7020709446281765e+00 , 3.6205008555831490e+00 , 2.2246108800000002e+00 , -4.1371999999999999e-02 , 2.5885300000000000e-01 , 9.6503000000000005e-01 -6.9771190297637968e+00 , 3.7150547778426715e+00 , 2.2519368800000001e+00 , -7.1394299999999994e-02 , 2.7266800000000002e-01 , 9.5945599999999998e-01 -1.1826051580821842e+01 , 5.1514559946762599e+00 , 1.5355786400000000e+00 , -7.0900299999999999e-02 , 2.0006099999999999e-01 , 9.7721499999999994e-01 -1.2739931812009697e+01 , 5.4559928299332574e+00 , 1.5715387199999999e+00 , -5.6713000000000000e-02 , 1.9463600000000000e-01 , 9.7923499999999997e-01 -1.3810609799184762e+01 , 5.8136539186127401e+00 , 1.6198113599999999e+00 , -5.5428100000000001e-02 , 1.8865100000000001e-01 , 9.8047899999999999e-01 -1.5365801844713538e+01 , 6.3257825579227003e+00 , 1.6528947999999999e+00 , -4.8312399999999998e-02 , 1.9132099999999999e-01 , 9.8033800000000004e-01 -1.6831097779417370e+01 , 6.8207176712420212e+00 , 1.7501327200000001e+00 , -7.5842000000000007e-02 , 1.8740799999999999e-01 , 9.7935000000000005e-01 -2.1860312873630289e+01 , 8.5011500361731347e+00 , 1.9830817999999999e+00 , -1.0183700000000000e-01 , 1.9853699999999999e-01 , 9.7478799999999999e-01 -2.4440767384554064e+01 , 9.3887292991538125e+00 , 2.2327675999999999e+00 , 5.5088899999999996e-01 , -1.5639600000000001e-01 , -8.1979400000000002e-01 -2.5805532092080639e+01 , 9.9042780410055826e+00 , 2.6004855999999998e+00 , -4.8780000000000001e-01 , 1.7116999999999999e-01 , 8.5600900000000002e-01 -2.6547430095694118e+01 , 1.0227561771988404e+01 , 3.0194828800000000e+00 , -1.2402000000000001e-01 , 5.4270800000000001e-02 , 9.9079499999999998e-01 -2.6461034801222262e+01 , 1.0283660720678744e+01 , 3.4534311999999998e+00 , 5.5281199999999997e-01 , 4.8665199999999997e-01 , -6.7643799999999998e-01 -2.8172601950573668e+01 , 1.0936797471431349e+01 , 3.9456424000000001e+00 , -2.0207200000000000e-01 , -8.4591899999999998e-02 , 9.7571099999999999e-01 -2.7189262983047644e+01 , 1.0786405143036925e+01 , 4.8129504000000001e+00 , -9.4158200000000003e-01 , 1.0155100000000000e-01 , -3.2110899999999998e-01 -2.6582010588384815e+01 , 1.0665781473641157e+01 , 5.2124872000000000e+00 , -9.7468800000000000e-01 , 2.2133400000000000e-01 , -3.1541000000000000e-02 -2.6712125758812881e+01 , 1.0798134414520895e+01 , 5.6705240000000003e+00 , 3.9108500000000002e-01 , -4.9212600000000002e-02 , 9.1903800000000002e-01 -2.4553018986474513e+01 , 1.0130594971418361e+01 , 5.8492480000000002e+00 , -9.7752700000000003e-01 , 5.1511700000000001e-02 , 2.0442199999999999e-01 -2.2118995721493569e+01 , 9.3514150764407837e+00 , 5.9106496000000002e+00 , 1.2017700000000001e-01 , 9.1203900000000004e-01 , 3.9210099999999998e-01 -2.0789495607444007e+01 , 8.9487692696432504e+00 , 6.0632799999999998e+00 , 4.3347599999999997e-01 , 3.0825100000000001e-02 , 9.0063800000000005e-01 -1.9983515068454796e+01 , 8.7264631332634792e+00 , 6.2635839999999998e+00 , -4.5194899999999999e-01 , -7.8950300000000001e-02 , -8.8854299999999997e-01 -1.9697624376754153e+01 , 8.6872820069309338e+00 , 6.5404008000000005e+00 , -8.5406599999999999e-01 , 5.0515399999999999e-01 , -1.2406100000000000e-01 -2.0001299685903270e+01 , 8.8638265135589993e+00 , 6.9386896000000000e+00 , -3.3030900000000002e-01 , -9.2061300000000001e-01 , 2.0824799999999999e-01 -2.0332945621294908e+01 , 9.0531506678974374e+00 , 7.3589016000000003e+00 , 6.8867299999999998e-01 , 7.2428099999999995e-01 , -3.3862400000000001e-02 -1.9605309684974735e+01 , 8.8484872816885254e+00 , 7.5211832000000003e+00 , 1.5156400000000000e-01 , 9.8844100000000001e-01 , 3.6643000000000001e-03 -1.9246823721130266e+01 , 8.7784820717490888e+00 , 7.7612776000000006e+00 , 1.7141500000000001e-01 , -9.4672299999999998e-01 , 2.7263999999999999e-01 -2.0000049379560210e+01 , 9.2029296010324799e+00 , 8.6794936000000007e+00 , -2.8112999999999999e-01 , 4.2692700000000000e-01 , 8.5947600000000002e-01 -1.9090456979134991e+01 , 8.9169725856365858e+00 , 8.7314936000000003e+00 , 7.3729999999999996e-01 , 6.4066800000000002e-01 , 2.1432200000000001e-01 -1.8984201955706492e+01 , 8.9433128222955141e+00 , 9.0399056000000009e+00 , -9.3608899999999995e-01 , 1.6941800000000001e-01 , 3.0827700000000002e-01 -1.8773064967280277e+01 , 8.9269253190790536e+00 , 9.3087352000000010e+00 , 8.0388000000000004e-01 , 2.7921000000000001e-01 , -5.2518500000000001e-01 -1.9487858397186688e+01 , 9.2839348736206535e+00 , 9.9472951999999992e+00 , 6.4618900000000001e-01 , 2.3256399999999999e-01 , -7.2687900000000005e-01 -2.0498492873031218e+01 , 9.7681914391693354e+00 , 1.0748282399999999e+01 , 7.8173300000000001e-01 , -9.5287100000000000e-02 , -6.1629100000000003e-01 -2.0640572739576548e+01 , 9.9043386306182288e+00 , 1.1211872800000002e+01 , -2.3339699999999999e-01 , 6.7173600000000003e-05 , 9.7238199999999997e-01 -2.1828581707865318e+01 , 1.0480452294194180e+01 , 1.2179842400000000e+01 , -7.7702000000000004e-01 , 4.6511200000000003e-01 , 4.2415900000000001e-01 -2.4496431587350308e+01 , 1.1690712063312748e+01 , 1.3939096000000001e+01 , 9.9866299999999997e-01 , -2.4701299999999999e-02 , 4.5408700000000003e-02 -1.8892151674859996e+01 , 9.4047398748339646e+00 , 1.1563382400000000e+01 , 9.5766899999999999e-01 , -2.1061099999999999e-01 , -1.9624900000000001e-01 -1.8891965874439173e+01 , 9.4815614794647161e+00 , 1.1955212800000000e+01 , -9.6533700000000000e-01 , 1.7875800000000000e-01 , 1.9018199999999999e-01 -1.9340309452932399e+01 , 9.7542630741810754e+00 , 1.2608624000000001e+01 , 7.7590000000000003e-01 , -4.3271599999999999e-01 , -4.5905899999999999e-01 -1.9670067403056240e+01 , 9.9816925124610965e+00 , 1.3222848000000001e+01 , -6.0449599999999999e-02 , 4.6333900000000000e-01 , 8.8411700000000004e-01 -2.2833303578262651e+01 , 1.1474433972227487e+01 , 1.5604343999999999e+01 , 9.8940700000000004e-01 , 1.0069900000000000e-01 , 1.0456500000000001e-01 -2.0467671214769986e+01 , 1.0513345593275737e+01 , 1.4619360000000000e+01 , 9.9423799999999996e-01 , -4.6164100000000000e-02 , 9.6747299999999994e-02 -2.4482141404460048e+01 , 1.2434930257687705e+01 , 1.7777424000000003e+01 , -3.2947799999999999e-01 , 5.6583899999999998e-01 , 7.5582400000000005e-01 -2.0979403405884405e+01 , 1.0938194171289833e+01 , 1.5946607999999999e+01 , 8.4693399999999996e-01 , -8.3604600000000001e-02 , -5.2508299999999997e-01 -1.9879988556447731e+01 , 1.0527560831164925e+01 , 1.5671216000000001e+01 , -9.4585300000000005e-01 , 1.5994800000000001e-01 , 2.8245100000000001e-01 -2.2874893427072308e+01 , 1.2038261205932415e+01 , 1.8422328000000000e+01 , 4.4419100000000000e-01 , 3.0614200000000003e-01 , -8.4200399999999997e-01 -2.0749559880531976e+01 , 1.1140771776852073e+01 , 1.7366832000000002e+01 , 2.7329300000000001e-01 , 1.7139299999999999e-01 , 9.4653900000000002e-01 -8.4933981212515501e+00 , 5.3255053615989194e+00 , 7.9810920000000003e+00 , 3.9767100000000000e-01 , 1.9069100000000000e-01 , 8.9749400000000001e-01 -2.0089880341908351e+01 , 1.1038500671251953e+01 , 1.7941223999999998e+01 , 1.6987400000000000e-01 , 9.4867000000000007e-03 , 9.8541999999999996e-01 -8.1349531604718628e+00 , 5.2225278468393945e+00 , 8.0522592000000017e+00 , -5.1720400000000000e-01 , -7.0095299999999999e-02 , -8.5298700000000005e-01 -6.3333337189069665e+00 , 4.3545156647722347e+00 , 6.6060455999999999e+00 , -6.2760099999999996e-01 , 1.0042200000000000e-01 , -7.7203100000000002e-01 -6.2621958579759589e+00 , 4.3444035851957796e+00 , 6.6724392000000003e+00 , -6.2760099999999996e-01 , 1.0042200000000000e-01 , -7.7203100000000002e-01 -7.8286566985673005e+00 , 5.1792102661042314e+00 , 8.3410983999999999e+00 , -4.6116099999999999e-01 , 7.3438000000000003e-01 , -4.9801299999999998e-01 -7.7812800696458675e+00 , 5.1934824769449097e+00 , 8.4914199999999997e+00 , -4.8346699999999998e-01 , 7.3680100000000004e-01 , -4.7263500000000003e-01 -7.6828423002222435e+00 , 5.1808925508568997e+00 , 8.5924144000000009e+00 , -3.0276100000000000e-01 , 9.2110999999999998e-01 , -2.4472700000000000e-01 -7.7160994530350946e+00 , 5.2391530584432804e+00 , 8.8359407999999995e+00 , -2.6752900000000000e-02 , 9.8725700000000005e-01 , 1.5687200000000001e-01 -7.2176759057990685e+00 , 5.0100258974329428e+00 , 8.4883103999999996e+00 , -2.4160299999999999e-02 , -6.5697700000000003e-01 , 7.5352300000000005e-01 -6.4101099212475834e+00 , 4.6015905903077758e+00 , 7.7433896000000004e+00 , -1.3036800000000001e-01 , 9.1140500000000002e-01 , 3.9031500000000002e-01 -5.8808937643193069e+00 , 4.3374323937155310e+00 , 7.2732160000000006e+00 , 6.2779600000000002e-01 , 3.8896999999999998e-01 , 6.7422099999999996e-01 -5.7754601894740869e+00 , 4.3091518478990611e+00 , 7.3000895999999997e+00 , 8.1218299999999999e-01 , -6.5323300000000001e-02 , 5.7973399999999997e-01 -5.7294935276513783e+00 , 4.3137987098161679e+00 , 7.4029663999999995e+00 , 8.1218299999999999e-01 , -6.5323400000000004e-02 , 5.7973399999999997e-01 -5.6986825209873864e+00 , 4.3289033958238772e+00 , 7.5293055999999998e+00 , -5.1326200000000000e-01 , -1.7009199999999999e-01 , -8.4120799999999996e-01 -5.8620489169143015e+00 , 4.4614918296009254e+00 , 7.9376616000000002e+00 , -5.2490199999999998e-01 , 2.6318700000000000e-01 , 8.0945100000000003e-01 -5.7591024805372939e+00 , 4.4360181524169242e+00 , 7.9790016000000001e+00 , -5.2490199999999998e-01 , 2.6318700000000000e-01 , 8.0945100000000003e-01 -5.5110524832772922e+00 , 4.3194139037432455e+00 , 7.7953168000000002e+00 , -5.1338399999999995e-01 , 5.2938099999999999e-01 , 6.7542100000000005e-01 -5.2510265531444862e+00 , 4.1907998071310590e+00 , 7.5704792000000003e+00 , -5.5929799999999996e-01 , -2.9729299999999997e-01 , -7.7382300000000004e-01 -5.1058286833480420e+00 , 4.1327474615948523e+00 , 7.5148912000000001e+00 , -4.3600899999999998e-01 , -7.9572299999999996e-01 , -4.2038300000000001e-01 -5.0864395027755451e+00 , 4.1572559643987184e+00 , 7.6692896000000008e+00 , 3.4379100000000001e-01 , 8.6541400000000002e-01 , 3.6450900000000003e-01 -5.0435978375463035e+00 , 4.1664837814095597e+00 , 7.7902936000000000e+00 , 3.5742900000000000e-01 , 9.3273499999999998e-01 , -4.7432400000000000e-02 -4.9098372458815263e+00 , 4.1142516898453829e+00 , 7.7449080000000006e+00 , -6.1440799999999995e-01 , 5.6927000000000005e-01 , -5.4629200000000000e-01 -4.9569132476600402e+00 , 4.1895646935113451e+00 , 8.0497216000000016e+00 , -2.9845600000000000e-01 , 9.4851900000000000e-01 , 1.0600400000000000e-01 -4.9729926697505444e+00 , 4.2462956231067199e+00 , 8.3136735999999996e+00 , 4.0508000000000000e-01 , -2.7528200000000003e-01 , -8.7185400000000002e-01 -4.7986938290753764e+00 , 4.1638695554683069e+00 , 8.1835800000000010e+00 , 3.4261399999999997e-01 , -8.0443799999999999e-01 , -4.8527799999999999e-01 -4.6574730594902523e+00 , 4.1035248430528402e+00 , 8.1121528000000005e+00 , 4.8765500000000001e-01 , -6.9634600000000002e-01 , -5.2658799999999995e-01 -4.5428625535064011e+00 , 4.0629847476917567e+00 , 8.0920495999999993e+00 , 3.0375799999999997e-01 , -9.3758699999999995e-01 , -1.6929600000000000e-01 -4.6024248629615636e+00 , 4.1626567560722822e+00 , 8.5045864000000009e+00 , 5.8293499999999998e-01 , -1.2522300000000000e-01 , 8.0281100000000005e-01 -4.3540236075792915e+00 , 4.0101992449666923e+00 , 8.1375600000000006e+00 , -3.8864500000000002e-01 , -5.4715300000000000e-01 , -7.4133599999999999e-01 -3.9039703090328586e+00 , 3.6734819289133060e+00 , 7.1608440000000000e+00 , 3.8671400000000000e-01 , 9.1913500000000004e-01 , -7.5123999999999996e-02 -3.8587562435641178e+00 , 3.6797032938783594e+00 , 7.2663728000000001e+00 , 7.1400200000000003e-01 , 6.0858199999999996e-01 , -3.4616300000000000e-01 -4.0877493741655737e+00 , 3.9453884196652291e+00 , 8.2492248000000004e+00 , 1.1979099999999999e-01 , -6.7387699999999995e-01 , 7.2906800000000005e-01 -4.0760868895369828e+00 , 3.9986287026859637e+00 , 8.5425983999999993e+00 , 5.0799399999999995e-01 , 8.5392599999999996e-01 , -1.1293100000000000e-01 -3.9732042777041698e+00 , 3.9658778463982465e+00 , 8.5478087999999985e+00 , -4.1209600000000002e-01 , -8.7873999999999997e-01 , -2.4081700000000000e-01 -4.0044258195835472e+00 , 4.0774200265962062e+00 , 9.0659472000000001e+00 , 1.3760800000000001e-01 , -7.6966400000000001e-01 , 6.2344299999999997e-01 -3.9205331326869590e+00 , 4.0716517409591262e+00 , 9.1775184000000003e+00 , 3.8788699999999998e-01 , -7.5512000000000001e-01 , 5.2852399999999999e-01 -3.7804958811628806e+00 , 4.0024846980466089e+00 , 9.0520320000000005e+00 , -1.6492499999999999e-01 , 8.3534799999999998e-01 , -5.2439700000000000e-01 -3.6998116493856106e+00 , 4.0029272370300841e+00 , 9.1898528000000006e+00 , -9.0634000000000003e-01 , 9.6637700000000007e-02 , -4.1134900000000002e-01 -3.6397295502265488e+00 , 4.0347009249318777e+00 , 9.4559576000000014e+00 , -5.7772199999999996e-01 , 2.5093700000000002e-01 , -7.7670300000000003e-01 -3.5251834819191386e+00 , 3.9976120255063878e+00 , 9.4530040000000000e+00 , 3.8594699999999998e-01 , 4.1622600000000003e-02 , 9.2158200000000001e-01 -3.3895679585067384e+00 , 3.9253726012851162e+00 , 9.3079447999999996e+00 , -7.1689899999999995e-01 , 5.4695800000000003e-02 , 6.9502799999999998e-01 -3.2663533065774804e+00 , 3.8633084784814251e+00 , 9.2001904000000003e+00 , -3.6026999999999998e-01 , -2.8842000000000001e-01 , 8.8714099999999996e-01 -3.2105797106950087e+00 , 3.9315678177370810e+00 , 9.6430432000000010e+00 , -3.7226799999999999e-01 , 7.6768999999999998e-01 , -5.2160200000000001e-01 -2.8052140078395480e+00 , 3.2233172676137354e+00 , 6.6841912000000008e+00 , -2.1601999999999999e-01 , 5.9247600000000000e-01 , -7.7608500000000002e-01 -2.7494102510156178e+00 , 3.2186576504741335e+00 , 6.7545784000000006e+00 , -4.5966299999999999e-01 , 5.8874300000000002e-01 , -6.6490000000000005e-01 -2.6768770920342280e+00 , 3.1673521215517608e+00 , 6.6109232000000002e+00 , -7.7282899999999999e-01 , 3.0499500000000002e-01 , 5.5651799999999996e-01 -2.6573988184389172e+00 , 3.3350800985447737e+00 , 7.5025151999999995e+00 , -7.9897300000000004e-01 , -4.6202799999999999e-01 , 3.8493100000000002e-01 -2.5770530287390865e+00 , 3.2744900880144021e+00 , 7.3269320000000002e+00 , -1.7210600000000001e-01 , 3.1725999999999999e-01 , 9.3259099999999995e-01 -2.5055426816073973e+00 , 3.2542958346268720e+00 , 7.3431975999999999e+00 , 4.9420399999999998e-01 , 6.1931400000000003e-01 , 6.1009199999999997e-01 -2.4324510748045132e+00 , 3.2554603875414800e+00 , 7.4704208000000003e+00 , -8.1966000000000006e-01 , -5.6406800000000001e-01 , -9.9919800000000003e-02 -2.3412189300796618e+00 , 3.3855280520682109e+00 , 8.2915320000000001e+00 , 2.4001000000000000e-01 , -2.8542400000000001e-01 , 9.2786199999999996e-01 -2.2505453985802966e+00 , 3.3672855670901138e+00 , 8.3450088000000004e+00 , 6.0643000000000002e-01 , -7.1588499999999999e-02 , 7.9190799999999995e-01 -2.1856385246677763e+00 , 3.2604709816618600e+00 , 7.9063784000000004e+00 , 5.3106200000000003e-01 , 7.7832400000000002e-01 , -3.3494200000000002e-01 -2.1045263878577520e+00 , 3.2341281856486823e+00 , 7.9058896000000010e+00 , -2.6694099999999998e-01 , 7.3009800000000002e-01 , -6.2904599999999999e-01 -2.0109484250711680e+00 , 3.2284233984736201e+00 , 8.0368256000000002e+00 , -9.9255000000000004e-01 , -1.2178400000000000e-01 , 3.5577000000000000e-03 -1.7661205127918975e+00 , 3.4470748731311289e+00 , 9.5652407999999998e+00 , -9.7399000000000002e-01 , -1.4842600000000000e-01 , -1.7121400000000001e-01 -4.7252249315081638e+00 , 2.7074616246336878e+00 , 1.1868385600000000e+00 , -5.5793799999999998e-02 , 2.3116200000000001e-01 , 9.7131400000000001e-01 -4.8031672271808086e+00 , 2.7307010496246749e+00 , 1.1870579999999999e+00 , -8.7323700000000004e-02 , 1.9481599999999999e-01 , 9.7694499999999995e-01 -4.8737500519925270e+00 , 2.7528168558984811e+00 , 1.1959416800000000e+00 , 6.7605999999999999e-02 , -2.1781200000000001e-01 , -9.7364600000000001e-01 -4.9695071741270009e+00 , 2.7800442340956790e+00 , 1.1881375199999999e+00 , -7.3428300000000002e-02 , 1.8232799999999999e-01 , 9.8049200000000003e-01 -5.0406118868818108e+00 , 2.8030404735440402e+00 , 1.2014973599999998e+00 , 8.8781899999999997e-02 , -1.9618700000000000e-01 , -9.7653900000000005e-01 -5.1297457510769684e+00 , 2.8296478956727174e+00 , 1.2050115200000000e+00 , -7.6881400000000003e-02 , 2.0104600000000000e-01 , 9.7655999999999998e-01 -5.2094580494810980e+00 , 2.8551487642311928e+00 , 1.2168383999999999e+00 , 2.7895600000000000e-02 , -2.0397100000000001e-01 , -9.7857899999999998e-01 -5.3252917360747949e+00 , 2.8877701817164381e+00 , 1.2084695200000000e+00 , -1.5799799999999999e-02 , 1.9880800000000001e-01 , 9.7991099999999998e-01 -5.4326795323328039e+00 , 2.9193926268837860e+00 , 1.2091444800000000e+00 , -8.2897799999999994e-02 , 1.9744800000000001e-01 , 9.7680199999999995e-01 -5.5316448543781922e+00 , 2.9499529326628560e+00 , 1.2185606400000000e+00 , -9.3635599999999999e-02 , 1.8168000000000001e-01 , 9.7889000000000004e-01 -5.6403486029038614e+00 , 2.9828311285967337e+00 , 1.2257605599999999e+00 , 6.0096400000000001e-02 , -1.8711900000000001e-01 , -9.8049699999999995e-01 -5.7576996062646550e+00 , 3.0181753042772446e+00 , 1.2312247200000002e+00 , 3.7636199999999997e-01 , -1.7285100000000000e-01 , -9.1020500000000004e-01 -5.8486664004763682e+00 , 3.0498222891167144e+00 , 1.2548680800000001e+00 , 9.7099700000000000e-01 , -6.1259800000000003e-02 , -2.3111200000000001e-01 -5.8213847359881523e+00 , 3.0580381901128360e+00 , 1.3425307200000001e+00 , 9.1664000000000001e-01 , 2.4732500000000001e-02 , -3.9894800000000002e-01 -5.8660387544821813e+00 , 3.0810155107160151e+00 , 1.3923300800000000e+00 , 9.6725499999999998e-01 , 1.4553900000000000e-01 , -2.0793300000000001e-01 -5.8078762671559510e+00 , 3.0822754430445327e+00 , 1.4915793599999998e+00 , 9.9360999999999999e-01 , 1.0207400000000000e-01 , -4.8173399999999998e-02 -5.8782036823842407e+00 , 3.1102055256928409e+00 , 1.5292710400000000e+00 , 9.7768400000000000e-01 , 1.9471400000000000e-01 , -7.8866500000000006e-02 -5.7983522471943223e+00 , 3.1071155813353091e+00 , 1.6339168799999999e+00 , 9.8828300000000002e-01 , 8.8573700000000005e-02 , 1.2430500000000000e-01 -5.8752758492276307e+00 , 3.1364273456458314e+00 , 1.6693216000000000e+00 , -9.3148200000000003e-01 , -2.0888300000000001e-01 , -2.9783999999999999e-01 -5.8015524319805190e+00 , 3.1337306901040929e+00 , 1.7666978400000000e+00 , 9.9839400000000000e-01 , 5.1429099999999998e-02 , 2.3772200000000000e-02 -5.8109712188441396e+00 , 3.1480427219601252e+00 , 1.8292070400000000e+00 , 9.8105100000000001e-01 , 9.4834600000000005e-02 , 1.6895299999999999e-01 -5.7610842486635967e+00 , 3.1488387791224426e+00 , 1.9121024240000000e+00 , 9.7294199999999997e-01 , 9.3604599999999996e-02 , 2.1123900000000001e-01 -5.7389638155799929e+00 , 3.1566683577815633e+00 , 1.9831353599999999e+00 , 9.7008200000000000e-01 , 1.9807900000000000e-02 , -2.4196799999999999e-01 -5.7541942292648471e+00 , 3.1719398673227515e+00 , 2.0411063120000001e+00 , 9.7008200000000000e-01 , 1.9807900000000000e-02 , -2.4196799999999999e-01 -5.7879754757170359e+00 , 3.1917040119880511e+00 , 2.0937083680000002e+00 , -8.3323000000000003e-01 , 6.5512600000000004e-02 , 5.4903199999999996e-01 -5.8304085225586375e+00 , 3.2139117124766825e+00 , 2.1444736799999999e+00 , -7.3649699999999996e-01 , 9.2586500000000002e-02 , 6.7007499999999998e-01 -5.8922456260950407e+00 , 3.2409049153631173e+00 , 2.1915139200000002e+00 , 4.7277700000000000e-01 , -1.5587300000000001e-01 , -8.6728600000000000e-01 -6.0211493783354681e+00 , 3.2854258317795182e+00 , 2.2239182400000002e+00 , -2.0844799999999999e-01 , 1.8674800000000000e-01 , 9.6003899999999998e-01 -6.2100340073596856e+00 , 3.3447912505798105e+00 , 2.2479266400000002e+00 , 1.3247999999999999e-01 , -2.0019100000000001e-01 , -9.7075900000000004e-01 -6.4575439403065280e+00 , 3.4206629866688711e+00 , 2.2662441599999998e+00 , -4.0807900000000001e-02 , 2.3220499999999999e-01 , 9.7181099999999998e-01 -6.8332953734733204e+00 , 3.5314972995905469e+00 , 2.2693662400000001e+00 , -5.3556399999999997e-02 , 2.3730499999999999e-01 , 9.6995799999999999e-01 -1.1532533992391690e+01 , 4.7696415431578298e+00 , 1.5647652000000001e+00 , -1.0083300000000001e-01 , 1.8855900000000000e-01 , 9.7687199999999996e-01 -1.2235662508449805e+01 , 4.9869999110121999e+00 , 1.6236011200000000e+00 , -6.0923600000000001e-02 , 1.9303500000000001e-01 , 9.7929900000000003e-01 -1.3326327246473733e+01 , 5.3120221093271649e+00 , 1.6566086400000000e+00 , -6.9360699999999997e-02 , 1.8674299999999999e-01 , 9.7995699999999997e-01 -1.4655856602825468e+01 , 5.7087653472766320e+00 , 1.7012454399999999e+00 , -4.2273499999999999e-02 , 1.8906000000000001e-01 , 9.8105500000000001e-01 -1.6295115213408614e+01 , 6.1998397518591304e+00 , 1.7636620800000000e+00 , -7.5540399999999994e-02 , 1.8011900000000000e-01 , 9.8073999999999995e-01 -1.8021026735954923e+01 , 6.7262008163615521e+00 , 1.8774256000000000e+00 , -6.2817200000000004e-02 , 1.8076200000000001e-01 , 9.8151900000000003e-01 -2.5102859297749873e+01 , 8.9226374508971897e+00 , 2.5428415200000001e+00 , 6.5612000000000004e-01 , -2.0830000000000001e-01 , -7.2533999999999998e-01 -2.7354111124909320e+01 , 9.6554296001151005e+00 , 2.9342788000000000e+00 , -3.1773099999999999e-01 , 3.2724700000000002e-02 , 9.4761600000000001e-01 -2.7918790139387959e+01 , 9.9070284276800891e+00 , 3.3865280000000002e+00 , -3.5383399999999998e-01 , -2.6983400000000002e-01 , 8.9553899999999997e-01 -2.5813426267643859e+01 , 9.3675026001141646e+00 , 3.7800016000000003e+00 , -8.3828599999999998e-01 , 5.2752299999999996e-01 , 1.3782800000000001e-01 -2.6404124401484037e+01 , 9.7907007912671595e+00 , 5.0948528000000000e+00 , 8.5611300000000001e-01 , -1.7579800000000001e-01 , -4.8596899999999998e-01 -2.5692008460286086e+01 , 9.6523857006894538e+00 , 5.4579896000000003e+00 , -4.5642500000000003e-01 , -4.3519200000000002e-01 , -7.7607000000000004e-01 -2.4611912546054263e+01 , 9.3930095131707994e+00 , 5.7530376000000008e+00 , -5.2643499999999999e-01 , -4.6176600000000001e-01 , -7.1389000000000002e-01 -2.4866811054446014e+01 , 9.5521004561823339e+00 , 6.1965351999999996e+00 , -5.2643499999999999e-01 , -4.6176600000000001e-01 , -7.1389000000000002e-01 -2.4965228432163364e+01 , 9.6633628102255642e+00 , 6.6275112000000007e+00 , -7.8149900000000005e-01 , 2.4505500000000000e-01 , -5.7376600000000000e-01 -2.0443876715603768e+01 , 8.2698196054094986e+00 , 6.2509687999999999e+00 , 4.7397899999999998e-01 , 2.5729200000000002e-01 , 8.4210700000000005e-01 -1.9437760622646206e+01 , 8.0030283314269095e+00 , 6.3932512000000008e+00 , 7.4795000000000000e-01 , -4.0590100000000001e-01 , -5.2518200000000004e-01 -1.9817499614354308e+01 , 8.1911927842599432e+00 , 6.7969271999999998e+00 , -6.8925599999999998e-01 , 5.2357799999999999e-01 , 5.0079200000000001e-01 -2.0149169758200365e+01 , 8.3657399929806040e+00 , 7.2069368000000003e+00 , -9.5226500000000003e-01 , -3.4247500000000000e-02 , 3.0334499999999998e-01 -2.0596521999737849e+01 , 8.5836549543563372e+00 , 7.6620512000000005e+00 , -7.8455600000000003e-01 , -6.1758800000000003e-01 , -5.5282600000000001e-02 -1.9618550421609768e+01 , 8.3795633513104715e+00 , 8.0899592000000009e+00 , 7.4692000000000003e-01 , 6.6107899999999997e-01 , 7.1309300000000006e-02 -2.0032358374314633e+01 , 8.5907316063257699e+00 , 8.5622752000000002e+00 , -1.4084400000000000e-01 , -9.8509199999999997e-01 , -9.8776500000000003e-02 -2.0798433632055765e+01 , 8.9313742385125039e+00 , 9.1727448000000003e+00 , 3.2418000000000002e-01 , 3.0339500000000003e-01 , 8.9602400000000004e-01 -2.2440226128019543e+01 , 9.5936910965235782e+00 , 1.0127766400000001e+01 , -6.0206999999999999e-01 , -4.2273800000000000e-01 , -6.7735100000000004e-01 -1.9697386856727910e+01 , 8.6758901400954613e+00 , 9.5195743999999998e+00 , 9.6150300000000000e-01 , 2.7478300000000000e-01 , -2.4684099999999999e-03 -1.9760732500310837e+01 , 8.7685720442365849e+00 , 9.9087736000000000e+00 , 6.9354400000000005e-01 , 1.3740700000000000e-01 , -7.0718899999999996e-01 -2.0352215301275606e+01 , 9.0596460372634873e+00 , 1.0525784800000000e+01 , -7.1224500000000002e-01 , 3.6462099999999997e-01 , 5.9979800000000005e-01 -2.1152424178607163e+01 , 9.4344901248610089e+00 , 1.1265776000000001e+01 , 7.1602500000000002e-01 , -5.3255100000000000e-01 , -4.5133000000000001e-01 -2.0563347338025292e+01 , 9.2901624792669342e+00 , 1.1409254400000000e+01 , -8.3141200000000004e-01 , 5.5162400000000000e-01 , 6.6823999999999995e-02 -2.2118697316478475e+01 , 9.9664091285825958e+00 , 1.2567856000000001e+01 , -7.8808000000000000e-01 , 4.5995200000000003e-01 , 4.0911399999999998e-01 -1.8848931415608401e+01 , 8.7809029296653858e+00 , 1.1367082399999999e+01 , 7.4037299999999995e-01 , 4.5169799999999999e-01 , 4.9781199999999998e-01 -1.8976568717717811e+01 , 8.9045402622040246e+00 , 1.1818182400000000e+01 , -8.5304599999999997e-01 , -3.4226600000000001e-01 , -3.9391300000000001e-01 -2.1947923333104466e+01 , 1.0161838756871486e+01 , 1.3854544000000001e+01 , -9.3351700000000004e-01 , -1.8282000000000001e-01 , -3.0841900000000000e-01 -1.8824816575345352e+01 , 8.9956625445543299e+00 , 1.2527920000000000e+01 , -9.5674199999999998e-01 , 2.6967200000000002e-01 , 1.0919100000000000e-01 -1.9016559581487627e+01 , 9.1511726478073427e+00 , 1.3050936000000000e+01 , -8.4799800000000003e-01 , 3.9167600000000002e-01 , 3.5705700000000001e-01 -1.8736598528615737e+01 , 9.1172895670314595e+00 , 1.3297312000000000e+01 , -6.3505400000000001e-01 , 2.8230300000000003e-01 , 7.1903499999999998e-01 -2.2761622758183510e+01 , 1.0876354623529490e+01 , 1.6352000000000004e+01 , 1.9955600000000001e-01 , -9.5857599999999998e-01 , -2.0324800000000001e-01 -2.1652126446121589e+01 , 1.0511790319516658e+01 , 1.6139840000000000e+01 , -4.8737900000000001e-01 , 8.3197399999999999e-01 , -2.6510499999999998e-01 -2.0686873095018008e+01 , 1.0199938202301672e+01 , 1.5982800000000001e+01 , 6.8604200000000004e-01 , -1.6257099999999999e-01 , -7.0916599999999996e-01 -2.1593906923584356e+01 , 1.0690635277993257e+01 , 1.7162576000000001e+01 , 6.4784100000000000e-01 , -5.5607399999999996e-01 , 5.2065700000000004e-01 -2.1559856446629592e+01 , 1.0781136083280909e+01 , 1.7688816000000003e+01 , 7.4168800000000001e-01 , 9.4317000000000001e-04 , 6.7074500000000004e-01 -8.6355456045975210e+00 , 5.1506318800575288e+00 , 7.9919599999999997e+00 , 3.9767100000000000e-01 , 1.9069100000000000e-01 , 8.9749400000000001e-01 -8.4011175520250276e+00 , 5.0812618333062973e+00 , 7.9876336000000006e+00 , 3.9767100000000000e-01 , 1.9069100000000000e-01 , 8.9749400000000001e-01 -8.2957965330999102e+00 , 5.0692821815010412e+00 , 8.0849152000000011e+00 , -3.9767100000000000e-01 , -1.9069100000000000e-01 , -8.9749400000000001e-01 -8.1677557708150204e+00 , 5.0465211027519166e+00 , 8.1606792000000006e+00 , -5.1720400000000000e-01 , -7.0095299999999999e-02 , -8.5298700000000005e-01 -6.3042574269200253e+00 , 4.2094620830204903e+00 , 6.6335432000000001e+00 , -6.2760199999999999e-01 , 1.0042200000000000e-01 , -7.7203100000000002e-01 -6.2323030346322463e+00 , 4.2011794508533384e+00 , 6.6982831999999997e+00 , -6.2760099999999996e-01 , 1.0042200000000000e-01 , -7.7203100000000002e-01 -6.1377129210233834e+00 , 4.1819626394689671e+00 , 6.7408087999999999e+00 , -5.6638200000000005e-01 , 3.4981200000000001e-01 , -7.4621999999999999e-01 -7.4570857891623339e+00 , 4.8534359247144181e+00 , 8.2365159999999999e+00 , -1.3570199999999999e-01 , 7.0851299999999995e-01 , -6.9252800000000003e-01 -7.4778046155535600e+00 , 4.9002623306052211e+00 , 8.4522744000000003e+00 , -1.3570199999999999e-01 , 7.0851299999999995e-01 , -6.9252700000000000e-01 -7.1624118419811671e+00 , 4.7800561385700631e+00 , 8.3048023999999998e+00 , -1.0989800000000000e-01 , -7.0748000000000000e-01 , 6.9813599999999998e-01 -7.4051615890944262e+00 , 4.9418097718373541e+00 , 8.7799887999999999e+00 , -7.2439299999999998e-02 , -7.8794699999999995e-01 , 6.1146800000000001e-01 -6.6944424239603464e+00 , 4.6133328007834944e+00 , 8.1469199999999997e+00 , 2.6126100000000002e-01 , -9.0564800000000001e-01 , -3.3398200000000000e-01 -6.7892677313269676e+00 , 4.7004367611542275e+00 , 8.4571728000000004e+00 , -1.7058000000000001e-01 , -8.9959400000000000e-01 , 4.0203699999999998e-01 -5.8021312234943725e+00 , 4.2077321221713273e+00 , 7.3927016000000005e+00 , -5.8783500000000000e-01 , -4.4441900000000001e-01 , -6.7597499999999999e-01 -5.7487601203218741e+00 , 4.2110584254272814e+00 , 7.4873936000000008e+00 , -5.1326200000000000e-01 , -1.7009199999999999e-01 , -8.4120799999999996e-01 -5.6353920896524059e+00 , 4.1805646289216547e+00 , 7.5015999999999998e+00 , -4.9702800000000003e-01 , -3.4083100000000000e-01 , -7.9799600000000004e-01 -5.5223456840104248e+00 , 4.1495311721694881e+00 , 7.5131752000000001e+00 , -2.5549900000000000e-02 , 2.6225700000000002e-01 , 9.6465999999999996e-01 -5.3497836227502269e+00 , 4.0831409996013139e+00 , 7.4313896000000002e+00 , -6.2453000000000003e-01 , 2.0192099999999999e-01 , -7.5444699999999998e-01 -5.3046342877760200e+00 , 4.0903517462940533e+00 , 7.5366168000000000e+00 , 5.9671399999999997e-01 , 8.0091199999999996e-01 , -4.9734599999999997e-02 -5.2616203135653592e+00 , 4.0991732312055937e+00 , 7.6502992000000001e+00 , 6.8148200000000003e-01 , 7.1945700000000001e-01 , 1.3402900000000001e-01 -5.2006055363549599e+00 , 4.0982759809810867e+00 , 7.7382208000000006e+00 , 3.2641399999999998e-01 , 7.9980700000000005e-01 , 5.0374900000000000e-01 -5.0401021152483816e+00 , 4.0348501804620209e+00 , 7.6526600000000000e+00 , 3.1830100000000000e-01 , -3.6690799999999999e-03 , 9.4798300000000002e-01 -4.8642582004534667e+00 , 3.9598891578766855e+00 , 7.5276832000000002e+00 , -5.2434999999999998e-01 , 2.3371900000000001e-01 , -8.1879900000000005e-01 -4.8725390527980901e+00 , 4.0037379660753887e+00 , 7.7418399999999998e+00 , 7.5361900000000004e-01 , -6.5513699999999997e-01 , 5.3424699999999999e-02 -5.0257210650481863e+00 , 4.1475157165359224e+00 , 8.2615072000000005e+00 , 5.6666600000000000e-01 , -3.3961300000000000e-01 , -7.5070199999999998e-01 -4.8620106914704877e+00 , 4.0796515205040631e+00 , 8.1585159999999988e+00 , 2.6864600000000000e-01 , -3.6181600000000003e-01 , -8.9270300000000002e-01 -4.7847043014601081e+00 , 4.0713875831832089e+00 , 8.2327823999999996e+00 , 4.3685499999999999e-01 , 7.5809000000000000e-04 , -8.9953099999999997e-01 -4.5560984312241413e+00 , 3.9514665717816344e+00 , 7.9576815999999999e+00 , -4.1845800000000000e-01 , 3.6680000000000001e-01 , 8.3087400000000000e-01 -4.4357333299946049e+00 , 3.9089004287709805e+00 , 7.9157280000000005e+00 , -2.1117000000000000e-01 , 4.9746400000000002e-01 , 8.4138999999999997e-01 -4.3479002974818242e+00 , 3.8889628753100158e+00 , 7.9456176000000003e+00 , 7.0118100000000005e-01 , 6.8998599999999999e-01 , 1.7962500000000001e-01 -4.0822116060482010e+00 , 3.7246285350025525e+00 , 7.4948816000000003e+00 , 7.8969500000000004e-01 , 2.1586900000000001e-01 , -5.7426699999999997e-01 -3.9220993801003163e+00 , 3.6394329057779640e+00 , 7.2908128000000003e+00 , 7.1400200000000003e-01 , 6.0858199999999996e-01 , -3.4616300000000000e-01 -4.1563516307326207e+00 , 3.8914234781065744e+00 , 8.2542480000000005e+00 , 7.8988499999999995e-01 , 2.4619400000000000e-01 , 5.6166799999999995e-01 -4.0341462430841037e+00 , 3.8420218724622641e+00 , 8.1832263999999988e+00 , 1.1979099999999999e-01 , -6.7387699999999995e-01 , 7.2906800000000005e-01 -3.9898762583473402e+00 , 3.8655722233056515e+00 , 8.3697400000000002e+00 , 1.5913099999999999e-01 , -9.5124500000000001e-01 , 2.6421699999999998e-01 -4.0671568754671501e+00 , 4.0129480156776047e+00 , 9.0228391999999999e+00 , -2.4397500000000000e-01 , 8.4021100000000004e-01 , -4.8427399999999998e-01 -3.9287614152585570e+00 , 3.9524332151470611e+00 , 8.9196088000000007e+00 , -1.2703700000000001e-01 , 9.5007100000000000e-01 , -2.8500399999999998e-01 -3.7628376255409757e+00 , 3.8573262393827354e+00 , 8.6756352000000003e+00 , 4.2274600000000001e-01 , 6.6058899999999998e-01 , -6.2040899999999999e-01 -3.7516351598555886e+00 , 3.9344189750675440e+00 , 9.0980728000000006e+00 , 6.6848500000000000e-01 , -1.8534999999999999e-01 , 7.2026000000000001e-01 -3.6729807433309993e+00 , 3.9417566191292606e+00 , 9.2546968000000014e+00 , 1.0023700000000001e-01 , 4.4895600000000002e-01 , 8.8791399999999998e-01 -3.5979538976754641e+00 , 3.9588387920759462e+00 , 9.4605023999999993e+00 , 6.1315799999999998e-01 , -4.6518700000000002e-01 , 6.3846599999999998e-01 -3.4768096162240196e+00 , 3.9147245917724947e+00 , 9.4160007999999991e+00 , -9.9453799999999995e-02 , 8.7775700000000001e-01 , -4.6866900000000000e-01 -3.3656872815299819e+00 , 3.8849831430494355e+00 , 9.4291359999999997e+00 , 2.7228700000000000e-01 , -3.5452099999999998e-01 , -8.9452500000000001e-01 -3.2311410406235517e+00 , 3.8109761181372761e+00 , 9.2491848000000001e+00 , 9.7662300000000002e-01 , 2.0675600000000000e-01 , 5.8816399999999998e-02 -3.1535093072857316e+00 , 3.8422696610278724e+00 , 9.5302135999999997e+00 , -5.2343300000000004e-01 , 5.9836500000000004e-01 , -6.0661100000000001e-01 -3.0528687560909447e+00 , 3.8375101976789754e+00 , 9.6590488000000008e+00 , -5.0033099999999997e-01 , 7.9352199999999995e-01 , -3.4639900000000001e-01 -2.8297934646823641e+00 , 3.4923770949808759e+00 , 8.1935432000000006e+00 , -5.0838099999999997e-01 , -7.3705500000000002e-01 , 4.4530700000000001e-01 -2.6557141219905809e+00 , 3.1522882948383484e+00 , 6.6792096000000001e+00 , 1.3489799999999999e-01 , -8.7772600000000001e-01 , 4.5978300000000000e-01 -2.6205305245851509e+00 , 3.2693810932697320e+00 , 7.3477528000000003e+00 , -3.0377100000000001e-01 , 1.7171600000000001e-01 , 9.3714299999999995e-01 -2.5463737650543328e+00 , 3.2452759209028148e+00 , 7.3335151999999999e+00 , 2.1856200000000001e-01 , 4.9025600000000003e-01 , 8.4372999999999998e-01 -2.4740950351975108e+00 , 3.2393575812486373e+00 , 7.4099240000000002e+00 , -7.2609199999999996e-01 , -6.4597199999999999e-01 , -2.3560900000000001e-01 -2.3878626405592280e+00 , 3.4114628970281942e+00 , 8.4460344000000003e+00 , 3.1311699999999998e-01 , -9.2072100000000001e-01 , -2.3287300000000000e-01 -2.3017759093589207e+00 , 3.3541765916410986e+00 , 8.2750792000000004e+00 , 6.7292699999999997e-02 , -6.0696600000000001e-01 , 7.9187399999999997e-01 -2.2226768627378011e+00 , 3.2922051337504250e+00 , 8.0718111999999991e+00 , -2.8811900000000001e-01 , 7.5067799999999996e-01 , 5.9453400000000001e-01 -2.1469835011693972e+00 , 3.2421616463003629e+00 , 7.9284783999999995e+00 , 5.0647499999999998e-03 , -7.9194600000000004e-01 , 6.1056999999999995e-01 -2.0625702412773457e+00 , 3.2209117370351610e+00 , 7.9472920000000000e+00 , -5.6957800000000003e-01 , 5.4389100000000001e-01 , -6.1624900000000005e-01 -1.8012770029253029e+00 , 3.4958410666209438e+00 , 9.7831624000000001e+00 , -5.3235699999999997e-01 , -8.4629299999999996e-01 , -1.9595399999999999e-02 -1.7469551258194795e+00 , 3.3792342017854224e+00 , 9.2560800000000008e+00 , -9.7253599999999996e-01 , 1.7168600000000001e-01 , -1.5715399999999999e-01 -4.7097808863719637e+00 , 2.6400581281717583e+00 , 1.1915643199999999e+00 , 8.6059099999999999e-02 , -1.9766300000000001e-01 , -9.7648500000000005e-01 -4.7806235060852638e+00 , 2.6595312703864922e+00 , 1.1979239200000000e+00 , -5.1625699999999997e-02 , 1.6859299999999999e-01 , 9.8433300000000001e-01 -4.8685408626991977e+00 , 2.6814085131050316e+00 , 1.1935070400000001e+00 , -7.6243599999999995e-02 , 1.8985099999999999e-01 , 9.7884800000000005e-01 -4.9308142856797375e+00 , 2.7011715003426184e+00 , 1.2100211999999999e+00 , -5.8743099999999999e-02 , 1.9122100000000000e-01 , 9.7978799999999999e-01 -5.0192242190362482e+00 , 2.7239690763448410e+00 , 1.2102822400000000e+00 , -9.7622299999999995e-02 , 1.7558099999999999e-01 , 9.7961299999999996e-01 -5.1003122083101182e+00 , 2.7466619189204393e+00 , 1.2190026399999998e+00 , -1.0658900000000000e-01 , 1.9949300000000000e-01 , 9.7408499999999998e-01 -5.1891805310686392e+00 , 2.7704437830695610e+00 , 1.2242463199999998e+00 , -3.6917499999999999e-02 , 1.8047400000000000e-01 , 9.8288699999999996e-01 -5.2969988600581370e+00 , 2.7980054568155261e+00 , 1.2206812000000000e+00 , -1.5882400000000001e-02 , 1.9487599999999999e-01 , 9.8069899999999999e-01 -5.4044476986934917e+00 , 2.8262382212949970e+00 , 1.2203535999999999e+00 , -8.3401799999999998e-02 , 1.9003400000000001e-01 , 9.7822900000000002e-01 -5.4954796112691593e+00 , 2.8526955760693200e+00 , 1.2340649600000000e+00 , -8.1346199999999994e-02 , 1.9086700000000001e-01 , 9.7824000000000000e-01 -5.6042636859731623e+00 , 2.8821413096297590e+00 , 1.2400584800000001e+00 , -7.1519399999999997e-02 , 1.8527399999999999e-01 , 9.8008099999999998e-01 -5.7226947346821806e+00 , 2.9129950269955565e+00 , 1.2445471200000000e+00 , 2.0415200000000000e-01 , -1.7808199999999999e-01 , -9.6260500000000004e-01 -5.8417831319335463e+00 , 2.9455790298678162e+00 , 1.2524968800000000e+00 , -7.7355099999999999e-01 , -3.2223299999999998e-03 , 6.3372499999999998e-01 -5.8515584486722254e+00 , 2.9610637489449743e+00 , 1.3208987200000002e+00 , 9.1774400000000000e-01 , 1.3532500000000000e-01 , -3.7340800000000002e-01 -5.8323571021283627e+00 , 2.9720296991923947e+00 , 1.4028527999999998e+00 , 9.9578599999999995e-01 , -1.7089300000000002e-02 , 9.0101299999999995e-02 -5.9137604880800803e+00 , 2.9984538185298004e+00 , 1.4354255999999999e+00 , 9.9578599999999995e-01 , -1.7089300000000002e-02 , 9.0101299999999995e-02 -5.8357829017446514e+00 , 2.9989452189270951e+00 , 1.5424395199999998e+00 , 9.9920900000000001e-01 , -3.2967799999999998e-02 , -2.2228100000000001e-02 -5.9059275578783730e+00 , 3.0239031069379427e+00 , 1.5811514400000000e+00 , 9.9286799999999997e-01 , -1.0630900000000000e-01 , 5.3961200000000001e-02 -5.8152638648294115e+00 , 3.0207564480321376e+00 , 1.6884908800000000e+00 , 9.6164400000000005e-01 , -6.3729099999999997e-02 , 2.6679599999999998e-01 -5.8168453010130081e+00 , 3.0330043739788932e+00 , 1.7548834400000000e+00 , 9.6591099999999996e-01 , -4.0468200000000003e-02 , -2.5569199999999997e-01 -5.8174506407658839e+00 , 3.0462461095273019e+00 , 1.8207435199999999e+00 , -9.7577999999999998e-01 , -1.2454400000000000e-01 , 1.7984100000000000e-01 -5.8929251745312339e+00 , 3.0730219181392373e+00 , 1.8590664800000001e+00 , 9.5179400000000003e-01 , 8.5367999999999999e-02 , 2.9462100000000002e-01 -5.7563602242836716e+00 , 3.0580238479998378e+00 , 1.9715662960000000e+00 , 9.9568999999999996e-01 , 6.6185599999999997e-02 , 6.4968600000000001e-02 -5.7716099217695129e+00 , 3.0732525758554639e+00 , 2.0293348640000000e+00 , -9.0388000000000002e-01 , 2.9660599999999999e-02 , 4.2675600000000002e-01 -5.7867831116428903e+00 , 3.0875500203301396e+00 , 2.0877133919999999e+00 , -9.0388000000000002e-01 , 2.9660599999999999e-02 , 4.2675600000000002e-01 -5.8401153232645111e+00 , 3.1107467656397945e+00 , 2.1351760799999999e+00 , -8.1197600000000003e-01 , 7.9063599999999998e-02 , 5.7831100000000002e-01 -5.8628335086677206e+00 , 3.1276082800150049e+00 , 2.1920983999999999e+00 , -6.0984799999999995e-01 , 1.3907800000000001e-01 , 7.8022000000000002e-01 -5.9841271448810884e+00 , 3.1652797263952426e+00 , 2.2257684000000002e+00 , 3.5183300000000001e-01 , -1.7008300000000001e-01 , -9.2048099999999999e-01 -6.1341452279802899e+00 , 3.2097087816869636e+00 , 2.2569392800000001e+00 , -1.7193300000000000e-01 , 1.8764200000000000e-01 , 9.6707299999999996e-01 -6.3332506094612429e+00 , 3.2668664219565722e+00 , 2.2827156799999999e+00 , -9.7313300000000005e-02 , 1.8723400000000001e-01 , 9.7748299999999999e-01 -6.6132531730489452e+00 , 3.3423710086876763e+00 , 2.3008772000000000e+00 , -2.7265399999999999e-02 , 2.1517900000000001e-01 , 9.7619400000000001e-01 -1.1952895092465324e+01 , 4.6100504040531645e+00 , 1.6423637600000001e+00 , -1.0268600000000000e-01 , 1.8487700000000001e-01 , 9.7738199999999997e-01 -1.2892146779593517e+01 , 4.8631846601731379e+00 , 1.6866875200000000e+00 , -5.5753400000000002e-02 , 1.9511800000000001e-01 , 9.7919400000000001e-01 -1.3921294506751936e+01 , 5.1435636634538042e+00 , 1.7537311199999999e+00 , -6.0219900000000000e-02 , 1.8643899999999999e-01 , 9.8061900000000002e-01 -1.5492553674748399e+01 , 5.5617731776628032e+00 , 1.8037280800000000e+00 , -4.9109500000000000e-02 , 1.8849099999999999e-01 , 9.8084600000000000e-01 -1.7102946288004922e+01 , 6.0005123740754751e+00 , 1.9059413599999999e+00 , 7.4669799999999995e-02 , -1.8234700000000001e-01 , -9.8039500000000002e-01 -1.9496773571572032e+01 , 6.6440031722765296e+00 , 2.0163130240000000e+00 , -6.3908999999999994e-02 , 1.9262299999999999e-01 , 9.7918899999999998e-01 -2.2188647150311031e+01 , 7.3792584485662500e+00 , 2.1976998399999998e+00 , -1.0751800000000000e-01 , 1.9365399999999999e-01 , 9.7516099999999994e-01 -2.4854215892405616e+01 , 8.1254489367583993e+00 , 2.4752945600000000e+00 , -5.2718900000000002e-01 , 1.4260600000000001e-01 , 8.3769600000000000e-01 -2.6302757549258004e+01 , 8.5737352180469362e+00 , 2.8590836800000003e+00 , 3.3973900000000001e-01 , -8.1095200000000006e-02 , -9.3701699999999999e-01 -2.7591473645744909e+01 , 8.9912149829167021e+00 , 3.2931568000000002e+00 , -1.7286699999999999e-01 , 5.0258800000000003e-01 , 8.4706700000000001e-01 -2.9372294036350919e+01 , 9.5471812892752883e+00 , 3.7868864000000002e+00 , -4.7538599999999998e-01 , 5.2208399999999999e-01 , 7.0812200000000003e-01 -2.6183796186934270e+01 , 8.7800179648803081e+00 , 4.1263112000000000e+00 , -7.2305200000000003e-01 , -6.1358900000000005e-01 , 3.1734000000000001e-01 -2.6674079849474406e+01 , 9.0740611795477957e+00 , 5.0157711999999997e+00 , 7.5765099999999996e-01 , 6.0363900000000004e-01 , -2.4816299999999999e-01 -2.6867331241669465e+01 , 9.2095665908792679e+00 , 5.4714159999999996e+00 , -7.7475499999999997e-01 , -6.2280700000000000e-01 , 1.0892900000000000e-01 -2.4932545220492109e+01 , 8.7472663203640355e+00 , 5.6890256000000008e+00 , -5.9470900000000004e-01 , -3.1663900000000000e-01 , -7.3895900000000003e-01 -2.5154057241816815e+01 , 8.8867919894679073e+00 , 6.1284672000000002e+00 , -5.1134999999999997e-01 , -3.5971500000000001e-01 , -7.8046499999999996e-01 -2.5474720670050154e+01 , 9.0570069447263748e+00 , 6.5936696000000001e+00 , -4.2859300000000000e-01 , -4.4946399999999997e-01 , -7.8376699999999999e-01 -2.4141556036482747e+01 , 8.7472968368079229e+00 , 6.7904895999999999e+00 , -8.3584000000000003e-01 , -5.4838199999999997e-02 , -5.4622800000000005e-01 -2.0652288585372723e+01 , 7.7897781837955229e+00 , 6.5321536000000009e+00 , -5.8301999999999998e-01 , -1.9186800000000001e-01 , -7.8947800000000001e-01 -1.9441422582180806e+01 , 7.4913189309752406e+00 , 6.6211359999999999e+00 , -5.1438600000000001e-01 , -1.9039199999999999e-02 , 8.5734699999999997e-01 -1.9938440217524729e+01 , 7.7018880552297260e+00 , 7.0554920000000001e+00 , -1.9033700000000001e-01 , 3.0827900000000003e-01 , 9.3206000000000000e-01 -2.0336622524352482e+01 , 7.8864904246222371e+00 , 7.4876328000000010e+00 , -9.5292200000000005e-01 , 2.3304399999999999e-02 , 3.0231799999999998e-01 -2.3305917787155263e+01 , 8.8717907344450655e+00 , 8.6214824000000014e+00 , -8.0895099999999998e-01 , 1.4439800000000000e-01 , -5.6986599999999998e-01 -2.3822401232915276e+01 , 9.1098739685961920e+00 , 9.1754904000000010e+00 , -9.5286099999999996e-01 , 8.2056299999999999e-02 , -2.9210199999999997e-01 -2.0974707275481794e+01 , 8.2853162588409326e+00 , 8.7284256000000013e+00 , 9.6110899999999999e-01 , -1.4553800000000000e-01 , -2.3470900000000000e-01 -2.1114846553010661e+01 , 8.3991042187674942e+00 , 9.1439160000000008e+00 , 9.9793299999999996e-01 , 4.1006700000000000e-02 , -4.9482699999999998e-02 -1.9790286154356426e+01 , 8.0396193266550462e+00 , 9.0639503999999995e+00 , -9.1441499999999998e-01 , -3.6974099999999999e-01 , -1.6472999999999999e-01 -1.9437013479061154e+01 , 7.9899626532316033e+00 , 9.2901920000000011e+00 , -8.2326999999999995e-01 , -5.3031799999999996e-01 , -2.0246000000000000e-01 -1.9277118055588250e+01 , 8.0024263812044030e+00 , 9.5814440000000012e+00 , -9.7773800000000000e-01 , -3.5266899999999997e-02 , 2.0684600000000000e-01 -1.9599479083608504e+01 , 8.1778773695341425e+00 , 1.0067789599999999e+01 , 5.4822599999999999e-01 , -5.2200800000000003e-01 , -6.5341899999999997e-01 -2.0912360158144601e+01 , 8.6933929639996332e+00 , 1.0998859999999999e+01 , -9.1916699999999996e-01 , 3.7572699999999998e-01 , 1.1815500000000000e-01 -2.0198456590217205e+01 , 8.5225413628143656e+00 , 1.1078908800000001e+01 , 6.6876199999999997e-01 , -6.0409800000000002e-01 , 4.3338599999999999e-01 -2.0366607772962691e+01 , 8.6551871298343919e+00 , 1.1551744800000000e+01 , 9.9506799999999995e-01 , 1.8662900000000000e-02 , -9.7421800000000003e-02 -2.0141205036868460e+01 , 8.6515916488549482e+00 , 1.1844276000000001e+01 , -5.7505899999999999e-01 , 8.0116699999999996e-01 , 1.6564799999999999e-01 -2.0536060713804652e+01 , 8.8683092861050490e+00 , 1.2456056000000000e+01 , 7.2497599999999995e-01 , -6.1605299999999996e-01 , -3.0803999999999998e-01 -2.0775652206795801e+01 , 9.0343358451732616e+00 , 1.3009752000000001e+01 , 7.4235200000000001e-01 , 2.3208999999999999e-01 , 6.2852900000000000e-01 -1.9096027330338693e+01 , 8.5010688590225190e+00 , 1.2497344000000000e+01 , -8.3527600000000002e-01 , -5.2883400000000003e-01 , 1.5049299999999999e-01 -1.9523162772365840e+01 , 8.7354826403111616e+00 , 1.3156392000000000e+01 , -7.2715799999999997e-01 , -5.6541300000000005e-01 , 3.8929300000000000e-01 -1.8895090646327471e+01 , 8.5793664412381450e+00 , 1.3196223999999999e+01 , -7.2715799999999997e-01 , -5.6541300000000005e-01 , 3.8929300000000000e-01 -2.0806542591967570e+01 , 9.3850158703069724e+00 , 1.4841192000000001e+01 , -4.2439199999999999e-01 , -2.6304899999999998e-01 , -8.6642699999999995e-01 -2.0446292038101326e+01 , 9.3362792461478605e+00 , 1.5081120000000000e+01 , -9.7433800000000004e-01 , 1.9333800000000001e-01 , 1.1526400000000001e-01 -2.0312735625497233e+01 , 9.3748064622965082e+00 , 1.5470392000000000e+01 , 9.7907500000000003e-01 , -5.0099499999999998e-02 , 1.9723800000000000e-01 -2.3648467414541599e+01 , 1.0785596742776036e+01 , 1.8367519999999999e+01 , -2.5013800000000003e-01 , 4.3747500000000000e-01 , 8.6373999999999995e-01 -2.0726121107922634e+01 , 9.7262583176516273e+00 , 1.6776112000000001e+01 , -7.5968100000000005e-01 , 4.4141999999999998e-01 , 4.7752699999999998e-01 -2.1231370758674995e+01 , 1.0030752743588222e+01 , 1.7699424000000000e+01 , -9.6170299999999997e-01 , 2.4744700000000000e-01 , -1.1788700000000001e-01 -8.7137236065794106e+00 , 4.9832077148290903e+00 , 8.1421256000000000e+00 , -3.9767100000000000e-01 , -1.9069100000000000e-01 , -8.9749400000000001e-01 -8.4008946733778309e+00 , 4.8880444709013915e+00 , 8.0720919999999996e+00 , -3.9767100000000000e-01 , -1.9069100000000000e-01 , -8.9749400000000001e-01 -6.4406611756789589e+00 , 4.0941752636648090e+00 , 6.5542327999999994e+00 , 6.3733099999999998e-01 , 2.8899000000000001e-02 , 7.7004799999999995e-01 -6.3040491160116350e+00 , 4.0599883755184507e+00 , 6.5609096000000005e+00 , -4.1575800000000002e-01 , 3.4308499999999997e-01 , -8.4228199999999998e-01 -6.2834246198665813e+00 , 4.0748340456819259e+00 , 6.6723560000000006e+00 , 4.2619699999999999e-01 , -3.5509600000000002e-01 , 8.3202399999999999e-01 -6.2258279744842957e+00 , 4.0748206925134411e+00 , 6.7495968000000000e+00 , 4.2619699999999999e-01 , -3.5509600000000002e-01 , 8.3202399999999999e-01 -7.6319849617386142e+00 , 4.7312024957452028e+00 , 8.3048232000000013e+00 , -2.1146899999999999e-01 , 8.1313500000000005e-01 , -5.4230299999999998e-01 -6.4614433948928740e+00 , 4.2341306429062815e+00 , 7.2743704000000005e+00 , 2.0449300000000001e-01 , -7.5778599999999996e-01 , 6.1963100000000004e-01 -6.3777196028737659e+00 , 4.2245976683683271e+00 , 7.3409823999999997e+00 , 2.0449300000000001e-01 , -7.5778599999999996e-01 , 6.1963100000000004e-01 -6.2877124386188008e+00 , 4.2124539391989178e+00 , 7.3985152000000003e+00 , 2.0449300000000001e-01 , -7.5778599999999996e-01 , 6.1963100000000004e-01 -6.0867652039920275e+00 , 4.1460081955109125e+00 , 7.3262248000000003e+00 , 1.3802000000000000e-01 , 6.5361899999999995e-01 , -7.4413200000000002e-01 -6.0103517656427261e+00 , 4.1394639394311543e+00 , 7.3933983999999997e+00 , 1.6776700000000000e-01 , 8.0064599999999997e-01 , -5.7516999999999996e-01 -6.0630714972853461e+00 , 4.1951542313349517e+00 , 7.6230824000000004e+00 , -1.1117100000000001e-01 , -9.8010900000000001e-01 , 1.6440099999999999e-01 -5.8419060104356806e+00 , 4.1167893518422156e+00 , 7.5084328000000005e+00 , 3.8231700000000002e-01 , 4.7749900000000001e-01 , 7.9109399999999996e-01 -6.0231394504423346e+00 , 4.2415391688527233e+00 , 7.9238296000000004e+00 , 6.4742200000000005e-01 , 4.5573399999999997e-01 , -6.1086099999999999e-01 -5.8036658234815359e+00 , 4.1619997984079387e+00 , 7.8037407999999999e+00 , 4.4493600000000000e-01 , 7.3563299999999998e-01 , -5.1075999999999999e-01 -5.4098646617280224e+00 , 3.9867747502789053e+00 , 7.4139072000000006e+00 , -5.8487699999999998e-01 , 2.6599000000000000e-01 , -7.6626899999999998e-01 -5.3763844181986915e+00 , 4.0000755838323618e+00 , 7.5360240000000003e+00 , -8.7073999999999996e-01 , 4.2971199999999998e-01 , -2.3908099999999999e-01 -5.3822704464121394e+00 , 4.0369977420860517e+00 , 7.7257927999999998e+00 , -9.7038400000000002e-01 , 1.3680300000000001e-01 , -1.9909800000000000e-01 -5.3306896551094614e+00 , 4.0436369631932028e+00 , 7.8320808000000008e+00 , 7.9561499999999996e-01 , -5.8677900000000005e-01 , 1.5062000000000000e-01 -5.2506116759095987e+00 , 4.0352781039847780e+00 , 7.8947095999999997e+00 , 6.6936799999999996e-01 , 4.4599600000000000e-01 , 5.9416700000000000e-01 -5.0047724708045598e+00 , 3.9273459361575607e+00 , 7.6596800000000007e+00 , -2.0413200000000001e-01 , -1.8367400000000000e-01 , 9.6155800000000002e-01 -4.8525672382005780e+00 , 3.8713537077256786e+00 , 7.5759080000000001e+00 , -3.4836499999999998e-01 , 1.3153699999999999e-01 , 9.2808400000000002e-01 -4.8828252700072792e+00 , 3.9276055422200731e+00 , 7.8352112000000007e+00 , -8.0868300000000004e-01 , 4.1430800000000001e-01 , 4.1758899999999999e-01 -4.9830320591749429e+00 , 4.0331290016291890e+00 , 8.2591359999999998e+00 , 5.6666499999999997e-01 , -3.3961300000000000e-01 , -7.5070199999999998e-01 -4.8197778375404017e+00 , 3.9710238259831909e+00 , 8.1532016000000009e+00 , 3.3031700000000003e-01 , -3.9183200000000001e-01 , -8.5869600000000001e-01 -4.6570794132256932e+00 , 3.9061768160790233e+00 , 8.0337783999999992e+00 , -5.6836299999999995e-01 , -2.4855300000000000e-01 , 7.8433699999999995e-01 -4.5189239590735966e+00 , 3.8560993491683671e+00 , 7.9559968000000003e+00 , 3.4509699999999999e-01 , 3.4882900000000000e-01 , -8.7133600000000000e-01 -4.4061000248525151e+00 , 3.8218744747896780e+00 , 7.9307352000000000e+00 , 4.0480200000000001e-02 , 2.4081600000000000e-01 , 9.6972599999999998e-01 -4.1662916233517429e+00 , 3.6905779102964482e+00 , 7.5651647999999998e+00 , 6.6417899999999996e-01 , 7.4257499999999999e-01 , -8.6309700000000003e-02 -4.0122825329207981e+00 , 3.6184619086591381e+00 , 7.3904344000000002e+00 , 4.8855799999999999e-01 , 8.5339500000000001e-01 , -1.8173500000000001e-01 -4.1817626821408602e+00 , 3.8015589674567751e+00 , 8.1351160000000000e+00 , -8.6227600000000004e-01 , -2.7283099999999999e-01 , 4.2666500000000002e-01 -4.0555581626043775e+00 , 3.7535114485388785e+00 , 8.0541624000000009e+00 , 1.0245200000000000e-01 , -4.9706800000000001e-01 , 8.6164200000000002e-01 -4.0094402952450849e+00 , 3.7731429660184501e+00 , 8.2208432000000009e+00 , 2.1813700000000000e-01 , -7.8363300000000002e-01 , 5.8166600000000002e-01 -3.9112962743464763e+00 , 3.7480060952073591e+00 , 8.2226944000000017e+00 , 4.9712400000000001e-01 , -6.2005500000000002e-01 , 6.0695900000000003e-01 -3.8265272037929883e+00 , 3.7349398252125310e+00 , 8.2715224000000003e+00 , -5.0551000000000001e-01 , 5.8486899999999997e-01 , -6.3434000000000001e-01 -3.7428388237988224e+00 , 3.7235570123496169e+00 , 8.3288991999999986e+00 , -3.0402099999999999e-01 , 6.6366800000000004e-01 , -6.8345900000000004e-01 -3.8712722766204033e+00 , 3.9424668221263528e+00 , 9.3216415999999995e+00 , 4.2343399999999998e-01 , -8.1744099999999997e-01 , 3.9050499999999999e-01 -3.4724505606647842e+00 , 3.5851808465279040e+00 , 7.9638488000000001e+00 , -8.1388799999999997e-02 , 7.7436899999999997e-01 , 6.2747799999999998e-01 -3.6499866262691665e+00 , 3.8914447046494209e+00 , 9.3584783999999992e+00 , 3.0792100000000000e-01 , -6.5390599999999999e-01 , 6.9107900000000000e-01 -3.5250253113268819e+00 , 3.8476815748941666e+00 , 9.2937800000000017e+00 , -3.5393200000000000e-02 , -8.4259700000000004e-01 , 5.3738100000000000e-01 -3.4576211023182015e+00 , 3.8833298172619770e+00 , 9.5775752000000001e+00 , -4.8335000000000003e-02 , 2.5832100000000002e-01 , 9.6484899999999996e-01 -3.2881483388136470e+00 , 3.7663122154924604e+00 , 9.1872007999999994e+00 , -3.9617100000000000e-01 , -3.9578000000000002e-01 , 8.2849700000000004e-01 -3.2098911664401593e+00 , 3.7926295091516904e+00 , 9.4381839999999997e+00 , -9.2557900000000004e-01 , -1.1389300000000000e-02 , -3.7838200000000000e-01 -3.1243248723503183e+00 , 3.8170513210527544e+00 , 9.6886992000000003e+00 , 5.0033099999999997e-01 , -7.9352199999999995e-01 , 3.4639900000000001e-01 -2.8935489214710675e+00 , 3.5013216443951150e+00 , 8.3253528000000010e+00 , 3.6608000000000002e-01 , 9.2896199999999995e-01 , 5.4920799999999999e-02 -2.6861706948861332e+00 , 3.1219712391236469e+00 , 6.5879287999999994e+00 , -7.7751899999999996e-01 , 5.7059300000000002e-01 , 2.6436500000000002e-01 -2.6638750679381205e+00 , 3.2652001848793311e+00 , 7.3784224000000007e+00 , -3.1649400000000000e-01 , 7.9971000000000000e-02 , 9.4521699999999997e-01 -2.5889180909208473e+00 , 3.2382268617805359e+00 , 7.3444767999999998e+00 , -1.6744999999999999e-01 , 2.8053499999999998e-01 , 9.4512499999999999e-01 -2.5151977415002151e+00 , 3.2262860684201984e+00 , 7.3801592000000005e+00 , 5.3124000000000005e-01 , 6.8642300000000001e-01 , 4.9659700000000001e-01 -2.4401494849640359e+00 , 3.3302935056711949e+00 , 8.0384792000000012e+00 , -5.2513100000000001e-01 , -2.3028699999999999e-01 , -8.1927099999999997e-01 -2.3500338525481084e+00 , 3.3472670337863923e+00 , 8.2563279999999999e+00 , 5.0385100000000005e-01 , 4.6951799999999999e-01 , -7.2504299999999999e-01 -2.2632656277817182e+00 , 3.3155330823877840e+00 , 8.2067928000000006e+00 , -6.4950699999999995e-01 , -3.3282200000000001e-01 , 6.8364499999999995e-01 -2.1923447280930279e+00 , 3.2397372034545788e+00 , 7.8997952000000007e+00 , 1.9556499999999999e-01 , 9.6790100000000001e-01 , -1.5786600000000001e-01 -2.1105112911611563e+00 , 3.2154660011814529e+00 , 7.8883240000000008e+00 , -1.0564800000000001e-01 , -6.8481899999999996e-01 , 7.2101400000000004e-01 -1.8443179028581003e+00 , 3.5350634089144006e+00 , 9.9606904000000007e+00 , -8.4157999999999999e-01 , -3.1075700000000001e-01 , 4.4178400000000001e-01 -1.7778236176628199e+00 , 3.4261655263067450e+00 , 9.4745112000000002e+00 , -8.6916899999999997e-01 , -4.8755999999999999e-01 , 8.2651400000000000e-02 -4.7559159338407166e+00 , 2.5885664457348949e+00 , 1.2093483200000001e+00 , -3.4730200000000003e-02 , 1.6213400000000000e-01 , 9.8615699999999995e-01 -4.8357721736648429e+00 , 2.6076512652242698e+00 , 1.2104371999999999e+00 , -5.8583999999999997e-02 , 1.7546600000000001e-01 , 9.8274099999999998e-01 -4.9072209461239815e+00 , 2.6256522625130922e+00 , 1.2201664000000001e+00 , -9.2556299999999994e-02 , 1.6324400000000000e-01 , 9.8223499999999997e-01 -4.9957058878817833e+00 , 2.6461429236768437e+00 , 1.2195226400000001e+00 , -8.1293599999999994e-02 , 1.8236900000000000e-01 , 9.7986399999999996e-01 -5.0687437666042312e+00 , 2.6649420817188028e+00 , 1.2335501600000001e+00 , -7.8843300000000005e-02 , 1.8193300000000001e-01 , 9.8014500000000004e-01 -5.1576815539339718e+00 , 2.6863920313104908e+00 , 1.2377871199999999e+00 , -5.0993600000000000e-02 , 1.6258800000000001e-01 , 9.8537500000000000e-01 -5.2564568728768037e+00 , 2.7089380940097341e+00 , 1.2390007999999999e+00 , -1.9200600000000002e-02 , 1.5731400000000001e-01 , 9.8736199999999996e-01 -5.3650089379625641e+00 , 2.7337177066157503e+00 , 1.2375936799999998e+00 , -5.2511400000000000e-02 , 1.8871499999999999e-01 , 9.8062700000000003e-01 -5.4561020168852412e+00 , 2.7567847691406513e+00 , 1.2503014399999999e+00 , 8.7456300000000001e-02 , -1.8377199999999999e-01 , -9.7907100000000002e-01 -5.5660097034244691e+00 , 2.7827814831497162e+00 , 1.2552164800000001e+00 , 8.6236300000000002e-02 , -1.9561999999999999e-01 , -9.7688100000000000e-01 -5.6845359198665708e+00 , 2.8101818707451933e+00 , 1.2583978400000000e+00 , -6.0109099999999999e-02 , 1.9000500000000001e-01 , 9.7994099999999995e-01 -5.8047525364922814e+00 , 2.8392941243620067e+00 , 1.2651661600000002e+00 , 3.1282300000000002e-01 , -1.0203300000000000e-01 , -9.4431500000000002e-01 -5.9065162691838813e+00 , 2.8655244777423583e+00 , 1.2853213600000000e+00 , 9.8572499999999996e-01 , 1.5132999999999999e-01 , -7.3799500000000004e-02 -5.8882505570005659e+00 , 2.8766384932901978e+00 , 1.3682104000000002e+00 , -9.6923899999999996e-01 , -5.7466799999999998e-02 , 2.3931700000000000e-01 -5.8501325780203182e+00 , 2.8848640065430740e+00 , 1.4588692800000000e+00 , 9.9850499999999998e-01 , 1.6753199999999999e-02 , 5.2034499999999997e-02 -5.8557723358378020e+00 , 2.8982403130184178e+00 , 1.5264703200000000e+00 , 9.9539599999999995e-01 , -9.0808299999999995e-02 , 3.0657299999999998e-02 -5.8892388595835916e+00 , 2.9163637877682018e+00 , 1.5814052000000001e+00 , 9.9184300000000003e-01 , -6.9419200000000000e-02 , 1.0690000000000000e-01 -5.8462001831732735e+00 , 2.9220615383960791e+00 , 1.6690137599999999e+00 , 9.9550000000000005e-01 , 8.2767499999999994e-02 , 4.6149400000000000e-02 -5.8388853899040560e+00 , 2.9333858046931169e+00 , 1.7394664799999999e+00 , 9.9084799999999995e-01 , 7.2539800000000002e-02 , -1.1383400000000000e-01 -5.8394382580158481e+00 , 2.9456300319824709e+00 , 1.8056333600000001e+00 , 9.9084799999999995e-01 , 7.2539699999999999e-02 , -1.1383400000000000e-01 -5.8686368666580133e+00 , 2.9629785554639443e+00 , 1.8610799199999999e+00 , 9.7576399999999996e-01 , 1.0584100000000000e-01 , -1.9152800000000000e-01 -5.7991380955467964e+00 , 2.9637306734005429e+00 , 1.9501179600000000e+00 , -9.7393399999999997e-01 , -1.2529299999999999e-01 , -1.8908800000000001e-01 -5.7967147018996688e+00 , 2.9747433803430097e+00 , 2.0147975360000001e+00 , 9.7848800000000002e-01 , 4.2297200000000000e-02 , -2.0191899999999999e-01 -5.8020421652437975e+00 , 2.9868858243835219e+00 , 2.0762023599999999e+00 , -9.3634499999999998e-01 , 4.9621400000000003e-04 , 3.5108000000000000e-01 -5.8269587481271241e+00 , 3.0023773442357475e+00 , 2.1320633600000001e+00 , -8.6918300000000004e-01 , 6.7090200000000003e-02 , 4.8991899999999999e-01 -5.8801370495560903e+00 , 3.0236635895066168e+00 , 2.1805439999999998e+00 , -7.5892400000000004e-01 , 1.1402500000000000e-01 , 6.4111799999999997e-01 -5.9320724579347353e+00 , 3.0453229066459802e+00 , 2.2306179199999998e+00 , 4.7881800000000002e-01 , -1.6910100000000000e-01 , -8.6147399999999996e-01 -6.0637855991290710e+00 , 3.0815335911243391e+00 , 2.2645354400000000e+00 , -2.5807400000000003e-01 , 1.7676600000000001e-01 , 9.4981700000000002e-01 -6.2446313020121149e+00 , 3.1282079863166485e+00 , 2.2923564800000000e+00 , 1.3332200000000000e-01 , -1.9195899999999999e-01 , -9.7230499999999997e-01 -6.4957794450957742e+00 , 3.1895345072650949e+00 , 2.3130379200000002e+00 , -6.6716899999999996e-02 , 1.7793800000000001e-01 , 9.8177700000000001e-01 -1.1596425970438105e+01 , 4.2377305941826968e+00 , 1.6736074400000001e+00 , -1.2963800000000000e-01 , 1.9035700000000000e-01 , 9.7311800000000004e-01 -1.2259226173985816e+01 , 4.4022394923891737e+00 , 1.7460860800000000e+00 , -6.1443699999999997e-02 , 1.8792700000000001e-01 , 9.8025899999999999e-01 -1.3447524494500241e+01 , 4.6806344078881628e+00 , 1.7792797600000001e+00 , -7.1076000000000000e-02 , 1.8392300000000000e-01 , 9.8036699999999999e-01 -1.4676531000911464e+01 , 4.9744079807057151e+00 , 1.8501245600000000e+00 , -4.6317999999999998e-02 , 1.8777400000000000e-01 , 9.8111999999999999e-01 -1.6390401175926996e+01 , 5.3795692725177418e+00 , 1.9236845920000001e+00 , -7.2662099999999993e-02 , 1.8087300000000001e-01 , 9.8081900000000000e-01 -1.8193609868902278e+01 , 5.8151444405410588e+00 , 2.0513104800000002e+00 , -6.3362100000000005e-02 , 1.8829899999999999e-01 , 9.8006599999999999e-01 -2.5404251059256065e+01 , 7.5986283990911012e+00 , 2.7921898399999998e+00 , -2.9197600000000001e-01 , 3.7194300000000002e-01 , 8.8114099999999995e-01 -2.7173569234067042e+01 , 8.0794192233136215e+00 , 3.2054743999999999e+00 , -6.3256299999999999e-01 , 4.8597200000000002e-01 , 6.0307100000000002e-01 -2.7524864080854112e+01 , 8.2409119991121464e+00 , 3.6497936000000002e+00 , 7.5250300000000003e-01 , -5.5487200000000003e-01 , -3.5476300000000000e-01 -2.7180209406713878e+01 , 8.2403509010405820e+00 , 4.0794280000000001e+00 , 6.8704699999999996e-01 , -6.0379099999999997e-01 , 4.0423199999999998e-01 -2.7475414616282972e+01 , 8.3916739078499525e+00 , 4.5351663999999996e+00 , -9.2153200000000002e-01 , 3.2573400000000002e-01 , -2.1136900000000000e-01 -2.7358319318957747e+01 , 8.4453167488872936e+00 , 4.9714463999999996e+00 , 6.3844699999999999e-01 , 7.3422500000000002e-01 , -2.3086799999999999e-01 -2.7284144206354004e+01 , 8.5081374606729980e+00 , 5.4097232000000002e+00 , 8.0195200000000000e-01 , 5.7114100000000001e-01 , -1.7513500000000001e-01 -2.7102036778962322e+01 , 8.5443252463491568e+00 , 5.8351144000000001e+00 , -8.5346400000000000e-01 , -5.0262700000000005e-01 , 1.3771400000000000e-01 -2.7753716782033845e+01 , 8.7907558823521992e+00 , 6.3645263999999999e+00 , -5.1087600000000000e-01 , -8.5517500000000002e-01 , 8.7646699999999994e-02 -2.7246096877951832e+01 , 8.7455617010142426e+00 , 6.7486816000000003e+00 , 6.2381399999999998e-01 , 7.5982799999999995e-01 , 1.8307899999999999e-01 -2.1704555460309859e+01 , 7.3923157532365158e+00 , 6.2806504000000007e+00 , 7.2019500000000003e-01 , -3.7688500000000000e-02 , -6.9274700000000000e-01 -2.1177346472244128e+01 , 7.3191686237771414e+00 , 6.5376344000000000e+00 , 4.5714600000000000e-01 , 5.3463099999999997e-01 , 7.1076499999999998e-01 -2.0657191810707854e+01 , 7.2447243154342829e+00 , 6.7792576000000002e+00 , 6.8426799999999999e-01 , 5.8650700000000000e-01 , 4.3334400000000001e-01 -1.9979027788607194e+01 , 7.1242321008133747e+00 , 6.9693176000000010e+00 , 3.0586300000000000e-01 , 7.3788200000000004e-01 , 6.0164600000000001e-01 -2.2144467930012045e+01 , 7.7751855749895027e+00 , 7.8215456000000003e+00 , 1.3291000000000000e-01 , -9.1348200000000002e-01 , 3.8455899999999998e-01 -2.3008683347498820e+01 , 8.0829298706058452e+00 , 8.4214072000000009e+00 , -4.0303899999999998e-01 , 5.0823799999999997e-01 , 7.6108699999999996e-01 -2.0915950668806424e+01 , 7.5700845066552818e+00 , 8.2331672000000005e+00 , -7.8766199999999997e-01 , 6.0435000000000005e-01 , -1.1979099999999999e-01 -2.0483426986931871e+01 , 7.5140617917985288e+00 , 8.4636728000000012e+00 , -7.6680700000000002e-01 , 6.0800600000000005e-01 , -2.0575700000000000e-01 -2.0910131640308265e+01 , 7.7008698434889560e+00 , 8.9549480000000017e+00 , -7.5748700000000002e-01 , 6.5218799999999999e-01 , 2.9418000000000000e-02 -2.0441242807488084e+01 , 7.6326473041784748e+00 , 9.1644456000000005e+00 , -6.9473799999999997e-01 , 6.4068300000000000e-01 , 3.2690000000000002e-01 -2.0933639976576263e+01 , 7.8435001388127423e+00 , 9.7047880000000006e+00 , -9.6434699999999995e-01 , 2.3688400000000001e-01 , -1.1798300000000000e-01 -2.0513018343077992e+01 , 7.7879163451433175e+00 , 9.9240928000000004e+00 , 5.8786100000000001e-02 , -9.8737900000000001e-01 , 1.4706300000000000e-01 -2.0583911429584209e+01 , 7.8779154166844290e+00 , 1.0327997600000000e+01 , -9.9849900000000005e-02 , -9.0728600000000004e-01 , 4.0848699999999999e-01 -2.0821208346049559e+01 , 8.0212350877860548e+00 , 1.0810630400000001e+01 , -7.9738699999999996e-01 , 4.9453000000000003e-01 , -3.4585399999999999e-01 -1.9656002157563460e+01 , 7.7325727253494652e+00 , 1.0689272799999999e+01 , -8.8395500000000005e-01 , 3.2500000000000001e-01 , 3.3615200000000001e-01 -2.0199147101239674e+01 , 7.9715718380432321e+00 , 1.1316798400000001e+01 , -8.3400799999999997e-01 , 1.3790200000000000e-01 , 5.3424099999999997e-01 -2.0904974818396546e+01 , 8.2681140595567193e+00 , 1.2053919200000001e+01 , -9.4881000000000004e-01 , -8.5142099999999998e-02 , 3.0415500000000001e-01 -2.0840387786544067e+01 , 8.3239434683345905e+00 , 1.2438376000000000e+01 , -7.1513499999999997e-01 , -1.3704700000000000e-01 , 6.8541900000000000e-01 -1.9692428683367023e+01 , 8.0266270682078602e+00 , 1.2251415200000000e+01 , 8.0391900000000005e-01 , -1.9615500000000000e-01 , 5.6145999999999996e-01 -1.9989852717598222e+01 , 8.1999836928336229e+00 , 1.2822136000000000e+01 , -1.4658599999999999e-01 , -9.7356900000000002e-01 , 1.7514800000000000e-01 -1.8985028571830568e+01 , 7.9399061160961075e+00 , 1.2660936000000000e+01 , -8.4718199999999999e-01 , -5.0119599999999997e-01 , 1.7631100000000000e-01 -1.9686341086328028e+01 , 8.2519172537547032e+00 , 1.3489504000000000e+01 , -9.7122500000000000e-02 , -5.8178099999999999e-01 , 8.0752599999999997e-01 -2.1790683145436940e+01 , 9.0545609173921093e+00 , 1.5245127999999999e+01 , 7.4240099999999998e-01 , 6.4714099999999997e-01 , -1.7334600000000000e-01 -2.0444327698902775e+01 , 8.6769584728822871e+00 , 1.4859704000000001e+01 , 9.5329299999999995e-01 , -7.2377099999999996e-03 , 3.0196200000000001e-01 -2.0728200158967745e+01 , 8.8637718545563562e+00 , 1.5526032000000001e+01 , -7.9861700000000002e-01 , 5.8433999999999997e-01 , -1.4407400000000001e-01 -2.0692722793569040e+01 , 8.9414193708357992e+00 , 1.5993408000000001e+01 , 8.7716700000000003e-01 , 2.5137399999999999e-01 , -4.0913300000000002e-01 -2.1088503944726163e+01 , 9.1771282315037404e+00 , 1.6789320000000000e+01 , 6.9228400000000001e-01 , 4.7283199999999997e-01 , -5.4513599999999995e-01 -2.0137567486479636e+01 , 8.9244724269012750e+00 , 1.6591927999999999e+01 , -9.4958200000000004e-01 , -1.3612400000000000e-01 , 2.8242499999999998e-01 -2.0271861583363904e+01 , 9.0686660169622719e+00 , 1.7215095999999999e+01 , -9.2362800000000000e-01 , 3.4408699999999998e-01 , 1.6886699999999999e-01 -2.1121610138676338e+01 , 9.4891327343721024e+00 , 1.8450407999999999e+01 , -7.7967500000000001e-01 , 5.8346799999999997e-02 , 6.2346000000000001e-01 -2.0626372582845232e+01 , 9.4048407937332179e+00 , 1.8606200000000001e+01 , 8.1607300000000005e-01 , 3.0624800000000002e-01 , -4.9014000000000002e-01 -6.3955665742201351e+00 , 3.9474737664961284e+00 , 6.5753760000000003e+00 , 1.8129999999999999e-01 , -2.3996999999999999e-01 , 9.5370100000000002e-01 -6.1994496359988993e+00 , 3.8927439123344474e+00 , 6.5253936000000010e+00 , -3.1497100000000000e-02 , -4.7633799999999998e-01 , 8.7869799999999998e-01 -6.0496735765249356e+00 , 3.8558630816622799e+00 , 6.5106568000000005e+00 , 1.5960099999999999e-01 , 2.1036500000000000e-01 , -9.6450700000000000e-01 -6.5691233189847438e+00 , 4.0921907944451510e+00 , 7.1515360000000001e+00 , 1.8833500000000000e-01 , 9.7904999999999998e-01 , -7.7406299999999997e-02 -5.7774829652437436e+00 , 3.7901383971884792e+00 , 6.4900023999999998e+00 , 5.3255399999999997e-01 , -2.7349800000000002e-01 , 8.0098999999999998e-01 -6.3658624920392191e+00 , 4.0628090227194527e+00 , 7.2416208000000006e+00 , -1.3103600000000001e-01 , 7.0830599999999999e-01 , -6.9363699999999995e-01 -6.2695260801363011e+00 , 4.0492231186747709e+00 , 7.2906880000000003e+00 , -1.3103600000000001e-01 , 7.0830599999999999e-01 , -6.9363699999999995e-01 -5.7464297809600700e+00 , 3.8488922471423690e+00 , 6.8487815999999997e+00 , 2.6234200000000002e-01 , -9.6236800000000000e-01 , 7.0878499999999997e-02 -5.9171957458894529e+00 , 3.9509975145166676e+00 , 7.1917216000000002e+00 , 4.5204000000000000e-01 , -8.2914500000000002e-01 , 3.2890500000000000e-01 -5.9562008480995967e+00 , 3.9966069848978960e+00 , 7.3948232000000003e+00 , -4.7597099999999998e-01 , 7.0109299999999997e-01 , -5.3096200000000005e-01 -5.7064505161347761e+00 , 3.9110575607945091e+00 , 7.2384176000000009e+00 , -4.5342199999999999e-01 , 7.5912999999999997e-01 , -4.6704400000000001e-01 -5.6973361330239438e+00 , 3.9358661321267925e+00 , 7.3859416000000007e+00 , 5.1556000000000002e-01 , -6.3228399999999996e-01 , -5.7828599999999997e-01 -5.7608311702427759e+00 , 3.9970302590426510e+00 , 7.6398160000000006e+00 , -6.4673400000000003e-01 , -5.9331599999999995e-01 , 4.7928300000000001e-01 -5.4218239172449101e+00 , 3.8634418406148505e+00 , 7.3313312000000002e+00 , -8.0869700000000000e-01 , 2.6388499999999998e-01 , -5.2571400000000001e-01 -5.3671664686677687e+00 , 3.8665180002721415e+00 , 7.4192840000000002e+00 , -8.6570899999999995e-01 , 1.6783600000000001e-01 , -4.7157100000000002e-01 -5.3338505346396072e+00 , 3.8817303807561818e+00 , 7.5403815999999999e+00 , -8.1066499999999997e-01 , 4.7433900000000001e-01 , -3.4325600000000001e-01 -5.3387032503540297e+00 , 3.9175729312295369e+00 , 7.7298280000000004e+00 , -8.7221499999999996e-01 , 3.6934200000000000e-01 , -3.2066600000000001e-01 -5.1994433281190755e+00 , 3.8780741089737480e+00 , 7.6885295999999999e+00 , -3.9351100000000000e-01 , -5.6759800000000005e-01 , 7.2317500000000001e-01 -5.2115939784137142e+00 , 3.9201075406753993e+00 , 7.9050263999999997e+00 , 7.3929999999999996e-01 , -6.2965899999999997e-01 , 2.3867500000000000e-01 -5.1307801917812785e+00 , 3.9123423325953066e+00 , 7.9652007999999999e+00 , -2.2047000000000000e-01 , 3.6016900000000002e-01 , -9.0646099999999996e-01 -4.8377595108133633e+00 , 3.7829080416347622e+00 , 7.6238624000000002e+00 , 7.4884700000000004e-01 , -6.3553099999999996e-01 , -1.8795799999999999e-01 -4.8563677427193443e+00 , 3.8319276552674015e+00 , 7.8658600000000005e+00 , 5.4684699999999997e-01 , -2.9399900000000001e-01 , 7.8391500000000003e-01 -4.9374287442951363e+00 , 3.9217594451959643e+00 , 8.2552775999999994e+00 , 8.1189899999999995e-02 , 7.0072700000000003e-03 , -9.9667399999999995e-01 -4.7829673136127120e+00 , 3.8698303719901137e+00 , 8.1648391999999994e+00 , 5.3505000000000003e-01 , -4.4100699999999998e-01 , -7.2057899999999997e-01 -4.5956968271138532e+00 , 3.7943358046788109e+00 , 7.9873216000000005e+00 , -3.4538300000000000e-01 , 2.1703400000000000e-01 , -9.1302099999999997e-01 -4.6334045236762122e+00 , 3.8650862663409162e+00 , 8.3254359999999998e+00 , 1.8492300000000000e-01 , 7.6885599999999998e-01 , 6.1209800000000003e-01 -4.2036829774645961e+00 , 3.6180935645315362e+00 , 7.5137784000000005e+00 , -5.4086000000000001e-01 , -8.1133100000000002e-01 , 2.2184000000000001e-01 -4.1002480100700724e+00 , 3.5883293052326093e+00 , 7.4810080000000001e+00 , 7.5774100000000000e-01 , 1.4000199999999999e-01 , -6.3736000000000004e-01 -4.2316465536332775e+00 , 3.7322542832966983e+00 , 8.1021895999999991e+00 , -8.3765999999999996e-01 , -5.4401400000000000e-01 , 4.8719999999999999e-02 -4.1659725723735228e+00 , 3.7363337960388674e+00 , 8.2032775999999998e+00 , -9.0522199999999997e-01 , -2.6826100000000003e-01 , 3.2956099999999999e-01 -4.1574121301189031e+00 , 3.7873059481308218e+00 , 8.4966200000000001e+00 , -6.6203500000000004e-01 , -6.8691199999999997e-01 , 2.9976799999999998e-01 -3.8443335292868612e+00 , 3.5867408839220944e+00 , 7.7927168000000000e+00 , -5.9193600000000002e-01 , -3.7150600000000000e-01 , -7.1525899999999998e-01 -3.7510581625402222e+00 , 3.5639173786654528e+00 , 7.7807672000000005e+00 , 1.3546700000000000e-01 , -9.8703700000000005e-01 , 8.6065199999999994e-02 -3.7899579287787963e+00 , 3.6632846999562285e+00 , 8.2769824000000014e+00 , 4.2253400000000002e-01 , -7.8400300000000001e-01 , 4.5475700000000002e-01 -3.7264484665160427e+00 , 3.6750082072085757e+00 , 8.4217607999999995e+00 , 4.4633400000000001e-01 , -6.2242399999999998e-01 , 6.4294200000000001e-01 -3.5284423904020548e+00 , 3.5482485181795242e+00 , 7.9716696000000002e+00 , -5.7411900000000005e-01 , -5.4381800000000002e-01 , -6.1208600000000002e-01 -3.6878999346951487e+00 , 3.8104177722121362e+00 , 9.2068256000000002e+00 , -3.8358599999999998e-01 , 8.5929299999999997e-01 , 3.3834500000000001e-01 -3.5915119571014857e+00 , 3.8041009207398018e+00 , 9.2919079999999994e+00 , -1.7328499999999999e-01 , 8.4147799999999995e-01 , -5.1174799999999998e-01 -3.4581959988679039e+00 , 3.7503035630922188e+00 , 9.1651216000000009e+00 , 1.6833500000000001e-01 , 2.2308200000000000e-01 , -9.6015499999999998e-01 -3.3457964010284620e+00 , 3.7215235255701504e+00 , 9.1458399999999997e+00 , 8.6795100000000003e-01 , 4.1803099999999999e-01 , 2.6816200000000001e-01 -3.2801692505924267e+00 , 3.7647902779516960e+00 , 9.4678240000000002e+00 , -6.2525399999999998e-01 , -6.3425200000000004e-01 , -4.5473300000000000e-01 -3.1741571892136640e+00 , 3.7534451861572027e+00 , 9.5364536000000015e+00 , 1.1801600000000000e-01 , -3.8231399999999999e-01 , 9.1646499999999997e-01 -2.9455502042786854e+00 , 3.4788928212507275e+00 , 8.3252072000000013e+00 , -4.0155500000000000e-01 , -8.8226000000000004e-01 , -2.4570700000000001e-01 -2.9493974272650689e+00 , 3.7097199204815006e+00 , 9.5771487999999998e+00 , -6.7544899999999997e-01 , 5.9301099999999995e-01 , -4.3830000000000002e-01 -2.7130264350107973e+00 , 3.2750999911000087e+00 , 7.5012568000000002e+00 , -7.7844199999999997e-01 , -4.1795300000000002e-01 , 4.6834100000000001e-01 -2.6294947023553354e+00 , 3.2270648938002839e+00 , 7.3451528000000001e+00 , -1.7682500000000001e-01 , 1.3345899999999999e-01 , 9.7515200000000002e-01 -2.5560771449714750e+00 , 3.2132011244388310e+00 , 7.3608463999999998e+00 , -4.7913499999999998e-01 , -5.7584100000000005e-01 , -6.6244800000000004e-01 -2.4827376762122215e+00 , 3.2124265819777076e+00 , 7.4467504000000000e+00 , -7.5641099999999994e-01 , -6.0061900000000001e-01 , -2.5903500000000002e-01 -2.3959468021005277e+00 , 3.3886951325302959e+00 , 8.5139151999999996e+00 , -8.8550300000000004e-01 , 8.9723299999999999e-04 , 4.6463300000000002e-01 -2.3104330882304578e+00 , 3.3087420415056363e+00 , 8.1884160000000001e+00 , -7.7823799999999999e-01 , -3.9911200000000002e-01 , 4.8482599999999998e-01 -2.2251286611451975e+00 , 3.2788222645171441e+00 , 8.1271392000000002e+00 , 9.4502600000000003e-01 , 4.9582300000000003e-02 , -3.2321499999999997e-01 -2.1561761167065883e+00 , 3.2100257588667320e+00 , 7.8394544000000002e+00 , 1.6203100000000001e-01 , -5.0991600000000004e-01 , 8.4482599999999997e-01 -2.0668017639133311e+00 , 3.2043347752276778e+00 , 7.9186088000000003e+00 , -7.0150199999999996e-01 , 3.3824100000000001e-01 , -6.2728600000000001e-01 -1.8029524866288229e+00 , 3.4855267338986407e+00 , 9.7850655999999994e+00 , -7.2012900000000002e-01 , -6.1271299999999995e-01 , -3.2557300000000000e-01 -1.7468343197885958e+00 , 3.3761642058062322e+00 , 9.2565896000000016e+00 , -9.7253599999999996e-01 , 1.7168600000000001e-01 , -1.5715299999999999e-01 -4.7374012107736601e+00 , 2.5222817370116561e+00 , 1.2136934400000001e+00 , -6.3678899999999997e-02 , 1.6880600000000001e-01 , 9.8358999999999996e-01 -4.8172550770804943e+00 , 2.5380803230778013e+00 , 1.2142852000000000e+00 , -7.7837699999999996e-02 , 1.6113400000000000e-01 , 9.8385800000000001e-01 -4.8887347258472680e+00 , 2.5538350711072382e+00 , 1.2234132799999999e+00 , -1.1297500000000001e-01 , 2.0156199999999999e-01 , 9.7293900000000000e-01 -4.9610287623386018e+00 , 2.5699695748315028e+00 , 1.2345891199999999e+00 , 5.5329000000000003e-02 , -1.3927000000000000e-01 , -9.8870800000000003e-01 -5.0502860491178598e+00 , 2.5875924076303329e+00 , 1.2356977599999999e+00 , 7.9370599999999999e-02 , -1.6571600000000000e-01 , -9.8297400000000001e-01 -5.1322548275938997e+00 , 2.6061495738240663e+00 , 1.2451627999999999e+00 , -7.0334499999999994e-02 , 1.2666300000000000e-01 , 9.8944900000000002e-01 -5.2401279694654761e+00 , 2.6259550414782558e+00 , 1.2399981600000001e+00 , -5.3181399999999997e-02 , 1.5667600000000001e-01 , 9.8621700000000001e-01 -5.3225506950972878e+00 , 2.6455184101075684e+00 , 1.2545467200000000e+00 , -4.0585700000000002e-02 , 2.0340700000000000e-01 , 9.7825300000000004e-01 -5.4408604123906024e+00 , 2.6671291953746961e+00 , 1.2500258399999999e+00 , -7.1884299999999998e-02 , 2.0416799999999999e-01 , 9.7629299999999997e-01 -5.5327250847735927e+00 , 2.6884314512194187e+00 , 1.2646867199999998e+00 , -8.9986200000000002e-02 , 1.9720699999999999e-01 , 9.7622299999999995e-01 -5.6433518518088288e+00 , 2.7116660541430990e+00 , 1.2718596000000000e+00 , -7.4476600000000004e-02 , 1.9307700000000000e-01 , 9.7835300000000003e-01 -5.7546173111769061e+00 , 2.7355713141356057e+00 , 1.2824977600000000e+00 , -5.4041699999999998e-02 , 1.9313400000000000e-01 , 9.7968299999999997e-01 -5.8844986256373035e+00 , 2.7616592089834717e+00 , 1.2868615999999999e+00 , -5.7152300000000000e-01 , 1.2120599999999999e-01 , 8.1158500000000000e-01 -5.9401235889261503e+00 , 2.7811359574653354e+00 , 1.3321556800000001e+00 , 9.2233699999999996e-01 , -4.4903100000000001e-02 , -3.8376800000000000e-01 -5.8939623360262381e+00 , 2.7887320023729285e+00 , 1.4285168800000001e+00 , 9.9524800000000002e-01 , 7.5443099999999999e-02 , 6.1567299999999998e-02 -5.9294618431911505e+00 , 2.8057780128682621e+00 , 1.4838074400000001e+00 , -9.7035199999999999e-01 , -2.1123500000000001e-01 , 1.1746300000000000e-01 -5.8784170955670216e+00 , 2.8129660932580958e+00 , 1.5771131199999999e+00 , 9.9349799999999999e-01 , 1.1368300000000001e-01 , -6.2222400000000004e-03 -6.1973764617101867e+00 , 2.8648522374978969e+00 , 1.5127028000000000e+00 , 5.2442200000000005e-01 , 6.8421500000000002e-01 , 5.0678599999999996e-01 -5.8667749009955559e+00 , 2.8357442733330385e+00 , 1.7193060800000000e+00 , 9.8490599999999995e-01 , 1.6899500000000001e-01 , 3.7436700000000003e-02 -5.8782600804042442e+00 , 2.8500180392418799e+00 , 1.7820659200000000e+00 , 9.5340300000000000e-01 , 2.2009400000000002e-03 , -3.0169200000000002e-01 -5.8699231177624904e+00 , 2.8602600752811145e+00 , 1.8521941600000000e+00 , -9.2402399999999996e-01 , -2.5116200000000002e-02 , 3.8150899999999999e-01 -5.9571330395225583e+00 , 2.8839520583766993e+00 , 1.8882613600000000e+00 , 9.4134200000000001e-01 , 1.2400600000000001e-01 , 3.1384499999999999e-01 -5.8177062286800023e+00 , 2.8762667119162875e+00 , 1.9995553209600001e+00 , 9.9533000000000005e-01 , 6.0122200000000001e-02 , 7.5522400000000003e-02 -5.8241046216910508e+00 , 2.8894078890045187e+00 , 2.0608805600000002e+00 , 9.6838400000000002e-01 , -2.6601400000000001e-02 , -2.4804100000000001e-01 -5.8294318784190757e+00 , 2.9015513523142720e+00 , 2.1222852799999998e+00 , -9.1903299999999999e-01 , 3.5277599999999999e-02 , 3.9259800000000000e-01 -5.8738137669906543e+00 , 2.9184376746071816e+00 , 2.1734179199999999e+00 , -8.2977400000000001e-01 , 4.9675999999999998e-02 , 5.5588400000000004e-01 -5.9062772811952318e+00 , 2.9354367489751461e+00 , 2.2278255200000001e+00 , -6.3986900000000002e-01 , 1.2296600000000001e-01 , 7.5858300000000001e-01 -6.0196311338123403e+00 , 2.9646394324352068e+00 , 2.2651948000000002e+00 , -3.5121900000000000e-01 , 1.6455300000000000e-01 , 9.2171999999999998e-01 -6.1811450558940315e+00 , 3.0020362620411976e+00 , 2.2955388800000001e+00 , 1.6286900000000001e-01 , -1.9223799999999999e-01 , -9.6773900000000002e-01 -6.3935967632910984e+00 , 3.0481107222419594e+00 , 2.3218633600000000e+00 , -1.0028100000000000e-01 , 1.8224199999999999e-01 , 9.7812699999999997e-01 -6.7179397322306205e+00 , 3.1145321287658776e+00 , 2.3360094399999998e+00 , -4.3826200000000003e-02 , 1.6983699999999999e-01 , 9.8449699999999996e-01 -1.1479678808963630e+01 , 3.9364621057778351e+00 , 1.6659467999999999e+00 , -1.2761700000000001e-01 , 1.9465700000000000e-01 , 9.7253400000000001e-01 -1.2055970313176477e+01 , 4.0647635276688021e+00 , 1.7458666400000000e+00 , -1.1297300000000000e-01 , 1.8023200000000000e-01 , 9.7711499999999996e-01 -1.3007633419243966e+01 , 4.2620622059389026e+00 , 1.8002992000000000e+00 , -4.7746400000000001e-02 , 1.7958099999999999e-01 , 9.8258400000000001e-01 -1.4071276609181202e+01 , 4.4863890238514390e+00 , 1.8759383999999999e+00 , -6.4317500000000000e-02 , 1.8406700000000001e-01 , 9.8080699999999998e-01 -1.5613046560022678e+01 , 4.8040364443555994e+00 , 1.9473893120000001e+00 , -4.6534499999999999e-02 , 1.8762499999999999e-01 , 9.8113799999999995e-01 -1.7366739398486089e+01 , 5.1703147266212017e+00 , 2.0578368960000000e+00 , -7.5642899999999999e-02 , 1.8540300000000001e-01 , 9.7974700000000003e-01 -1.9517328134966061e+01 , 5.6233683324995969e+00 , 2.2093343200000000e+00 , -6.4963499999999993e-02 , 1.9262799999999999e-01 , 9.7911899999999996e-01 -2.2520517156686612e+01 , 6.2519646657745094e+00 , 2.4074449599999999e+00 , -1.3469100000000001e-01 , 1.9581799999999999e-01 , 9.7134600000000004e-01 -2.5273177970746008e+01 , 6.8517207304387053e+00 , 2.7145288800000000e+00 , 3.8398800000000000e-01 , -4.3697000000000003e-01 , -8.1339399999999995e-01 -2.5997496794947544e+01 , 7.0669896324260550e+00 , 3.1153895999999999e+00 , -4.7408299999999998e-01 , 1.8676000000000001e-01 , 8.6044500000000002e-01 -2.6601147537881758e+01 , 7.2624404451194273e+00 , 3.5397927999999999e+00 , -4.8578500000000002e-01 , 3.3702399999999999e-01 , 8.0649099999999996e-01 -2.6819040595577196e+01 , 7.3826517354755872e+00 , 3.9720895999999999e+00 , -7.5190699999999999e-01 , 1.3106499999999999e-01 , 6.4610999999999996e-01 -2.9602699268328578e+01 , 8.2095391572081340e+00 , 5.5133799999999997e+00 , 4.6054600000000001e-01 , 8.8117599999999996e-01 , 1.0689700000000001e-01 -2.9500369476409865e+01 , 8.2740987393321177e+00 , 5.9858208000000008e+00 , -4.8473899999999998e-01 , -7.1321900000000005e-01 , 5.0630699999999995e-01 -2.8077877914346804e+01 , 8.0485603405188719e+00 , 6.2915703999999995e+00 , -4.0304299999999998e-01 , -9.0677099999999999e-01 , 1.2378699999999999e-01 -3.0023908655900900e+01 , 8.5653200756041432e+00 , 7.0318008000000001e+00 , 6.1825699999999995e-01 , 7.4750499999999998e-01 , -2.4288699999999999e-01 -2.9422971013126457e+01 , 8.5192883055595701e+00 , 7.4339896000000003e+00 , 3.3564899999999998e-01 , 8.2934699999999995e-01 , 4.4668099999999999e-01 -2.1519343138455145e+01 , 6.7894668229737567e+00 , 6.5059351999999997e+00 , 6.0589899999999997e-01 , 4.7439500000000001e-01 , 6.3861900000000005e-01 -2.1416034337806430e+01 , 6.8284939978358254e+00 , 6.8356880000000002e+00 , 7.9309600000000002e-01 , 3.3303199999999999e-01 , 5.0998800000000000e-01 -2.1217446819639328e+01 , 6.8449484214699945e+00 , 7.1437984000000005e+00 , 7.9309600000000002e-01 , 3.3303199999999999e-01 , 5.0998800000000000e-01 -2.1014263031424004e+01 , 6.8584262943671108e+00 , 7.4466359999999998e+00 , 7.3603900000000000e-01 , 4.1136200000000001e-01 , 5.3761300000000001e-01 -2.1169946204778512e+01 , 6.9599222071095870e+00 , 7.8360328000000008e+00 , 7.2476600000000002e-01 , -3.8933600000000002e-01 , 5.6844700000000004e-01 -2.0389343469307462e+01 , 6.8312392931889594e+00 , 7.9794695999999998e+00 , -5.6815800000000005e-01 , 4.0416000000000002e-01 , -7.1683399999999997e-01 -2.0155562693551747e+01 , 6.8344241071581671e+00 , 8.2563488000000014e+00 , -5.6815800000000005e-01 , 4.0416000000000002e-01 , -7.1683399999999997e-01 -2.0225533001722820e+01 , 6.9137943826666044e+00 , 8.6231048000000001e+00 , -4.9197999999999997e-01 , 6.2744999999999995e-01 , -6.0354099999999999e-01 -2.3060168126077627e+01 , 7.7059289995961722e+00 , 9.9131104000000008e+00 , 9.0307400000000004e-01 , -3.0209700000000000e-01 , 3.0527799999999999e-01 -2.1096144015673477e+01 , 7.2679871644355769e+00 , 9.6340368000000005e+00 , -9.3700399999999995e-01 , -2.3995900000000001e-01 , -2.5385799999999997e-01 -2.7439912761934902e+01 , 9.0128174955596627e+00 , 1.2369642400000000e+01 , -9.2180799999999996e-01 , 2.0958900000000000e-01 , -3.2610299999999998e-01 -2.5944774986784630e+01 , 8.7043580214069873e+00 , 1.2295688000000000e+01 , -8.6810399999999999e-01 , -3.4266000000000002e-01 , 3.5913600000000001e-01 -1.9687960811207631e+01 , 7.0912175257344225e+00 , 1.0200566400000000e+01 , 6.0095799999999999e-01 , 5.4956799999999995e-01 , 5.8036600000000005e-01 -1.9957733921864509e+01 , 7.2308484920940073e+00 , 1.0682450399999999e+01 , -9.2468200000000000e-01 , 3.6731599999999998e-01 , -1.0020999999999999e-01 -2.0133874098394500e+01 , 7.3471165636451570e+00 , 1.1138968800000001e+01 , 8.5286499999999998e-01 , -1.1184500000000000e-01 , -5.1001200000000002e-01 -2.0135181436311001e+01 , 7.4176192514331571e+00 , 1.1526077599999999e+01 , -9.0637400000000001e-01 , -2.1265800000000001e-01 , 3.6505100000000001e-01 -2.0830524624305298e+01 , 7.6878843250725097e+00 , 1.2267608000000001e+01 , 7.9641099999999998e-01 , 1.2442000000000000e-01 , -5.9181899999999998e-01 -2.1326590422319430e+01 , 7.9068133906819096e+00 , 1.2943504000000001e+01 , 7.9724099999999998e-01 , 2.7641399999999999e-01 , -5.3665900000000000e-01 -2.1837916962418074e+01 , 8.1373570156230244e+00 , 1.3659232000000001e+01 , 6.6059100000000004e-01 , 7.4869500000000000e-01 , 5.5458700000000000e-02 -2.1569189681639877e+01 , 8.1380950583007063e+00 , 1.3964055999999999e+01 , 8.1363500000000000e-01 , 5.4549999999999998e-01 , 2.0106399999999999e-01 -2.1824623988650831e+01 , 8.2982072041322823e+00 , 1.4576096000000000e+01 , 5.9270500000000004e-01 , -4.6576299999999998e-01 , 6.5708900000000003e-01 -2.1575881931421364e+01 , 8.3071455580642457e+00 , 1.4899432000000001e+01 , 1.0691600000000001e-02 , -6.5746499999999997e-01 , 7.5340900000000000e-01 -2.0501683945384553e+01 , 8.0574117128733889e+00 , 1.4690288000000001e+01 , 1.1866100000000000e-01 , -4.5633699999999999e-01 , 8.8185899999999995e-01 -2.0561540583311956e+01 , 8.1599766614936087e+00 , 1.5196248000000001e+01 , -9.2963899999999999e-01 , -3.5977900000000002e-01 , 7.9562900000000006e-02 -2.1690153126353923e+01 , 8.6103157595018622e+00 , 1.6460160000000002e+01 , -8.0153399999999997e-01 , -5.7461799999999996e-01 , -1.6539899999999999e-01 -2.0408863286716453e+01 , 8.2844544331226437e+00 , 1.6055703999999999e+01 , 7.9306900000000002e-01 , 4.6439399999999997e-01 , -3.9418399999999998e-01 -2.1430991805366329e+01 , 8.7135795541048271e+00 , 1.7323152000000000e+01 , -9.3380900000000000e-01 , -3.3519599999999999e-01 , 1.2508000000000000e-01 -2.1074477245967167e+01 , 8.6909087382267174e+00 , 1.7587935999999999e+01 , 8.1383200000000000e-01 , 5.7067900000000005e-01 , -1.0955900000000000e-01 -2.1909286850147669e+01 , 9.0756636864409739e+00 , 1.8811392000000001e+01 , 8.5691099999999998e-01 , 4.2330200000000001e-01 , -2.9414000000000001e-01 -6.5463504485815003e+00 , 3.8312372258757277e+00 , 6.5154928000000005e+00 , -7.2481000000000004e-02 , -3.0181500000000000e-01 , 9.5060699999999998e-01 -6.4992909489107946e+00 , 3.8379249355079725e+00 , 6.6018856000000010e+00 , 8.5353700000000005e-02 , -3.7154700000000002e-01 , 9.2448200000000003e-01 -6.3304357989454729e+00 , 3.8004661541609193e+00 , 6.5802016000000005e+00 , 7.6391799999999996e-02 , 2.7062500000000000e-01 , -9.5964899999999997e-01 -6.0393107738776655e+00 , 3.7172218361191582e+00 , 6.4369415999999999e+00 , 2.2770699999999999e-01 , -4.9277599999999999e-01 , 8.3983399999999997e-01 -6.0930171615747186e+00 , 3.7589361982120320e+00 , 6.6132840000000002e+00 , 3.6521500000000001e-01 , -8.3975000000000000e-01 , 4.0179399999999998e-01 -5.8162055714877088e+00 , 3.6782643998398710e+00 , 6.4647616000000010e+00 , -6.3437299999999996e-01 , -2.6152900000000001e-01 , -7.2744299999999995e-01 -6.0678651463960982e+00 , 3.7974255282526563e+00 , 6.8516624000000004e+00 , -5.3676199999999996e-01 , 7.0768799999999998e-01 , -4.5941599999999999e-01 -5.7335502762011599e+00 , 3.6905244320360708e+00 , 6.6291855999999996e+00 , -8.9373899999999995e-01 , -2.7524900000000002e-01 , -3.5421500000000000e-01 -5.7096448324717297e+00 , 3.7050658130137859e+00 , 6.7331544000000010e+00 , 9.9511799999999995e-01 , 5.1559800000000003e-02 , 8.4153500000000006e-02 -5.6372906335979884e+00 , 3.6993836681510102e+00 , 6.7843744000000008e+00 , 9.9511799999999995e-01 , 5.1559800000000003e-02 , 8.4153500000000006e-02 -5.7820907948111770e+00 , 3.7848392412935192e+00 , 7.0971232000000004e+00 , -8.9536400000000005e-01 , 4.3530900000000000e-01 , -9.3967700000000001e-02 -5.9101655842002181e+00 , 3.8654867141149452e+00 , 7.4087800000000001e+00 , 6.1510299999999996e-01 , -7.8840299999999996e-01 , 8.2598700000000008e-03 -5.6856884224354207e+00 , 3.7982240107465768e+00 , 7.2800072000000000e+00 , -8.8090199999999996e-01 , 3.0880200000000002e-01 , -3.5868200000000000e-01 -5.7534887258927387e+00 , 3.8567855842286436e+00 , 7.5324672000000001e+00 , 7.4598299999999995e-01 , -5.5159199999999997e-01 , -3.7317000000000000e-01 -5.5277664922456360e+00 , 3.7863470174362770e+00 , 7.3876368000000001e+00 , -2.2915199999999999e-01 , 2.0988299999999999e-01 , -9.5049399999999995e-01 -5.3932198145612347e+00 , 3.7547966114583815e+00 , 7.3604408000000001e+00 , -4.4805099999999998e-01 , 2.1566500000000000e-01 , -8.6760499999999996e-01 -5.3833267815563168e+00 , 3.7809860136211566e+00 , 7.5146416000000000e+00 , 7.5925699999999996e-01 , -4.9000600000000000e-01 , 4.2827799999999999e-01 -5.3521113597796006e+00 , 3.7978763488487859e+00 , 7.6445272000000006e+00 , 6.8371999999999999e-01 , -5.9435899999999997e-01 , 4.2339500000000002e-01 -5.1601018512575276e+00 , 3.7368609016165308e+00 , 7.5167944000000002e+00 , -2.3473299999999999e-03 , -4.3081300000000000e-01 , 9.0243799999999996e-01 -5.0352029740425586e+00 , 3.7067144023670298e+00 , 7.4880903999999999e+00 , 6.2987000000000001e-02 , -5.3709600000000002e-01 , 8.4116599999999997e-01 -5.0107755870616719e+00 , 3.7282278667092967e+00 , 7.6318184000000002e+00 , -8.5645600000000000e-01 , -4.7600500000000001e-01 , -1.9975599999999999e-01 -4.9347106227717070e+00 , 3.7225819486894967e+00 , 7.6877287999999995e+00 , 5.6772900000000004e-01 , 8.5124900000000003e-02 , 8.1880200000000003e-01 -4.7371732940447391e+00 , 3.6515641112497779e+00 , 7.5091400000000004e+00 , 1.6270899999999999e-01 , -5.6353699999999995e-01 , 8.0990899999999999e-01 -4.7203019681304745e+00 , 3.6788326515461467e+00 , 7.6777968000000003e+00 , -6.5490000000000004e-01 , 7.4704999999999999e-01 , -1.1411600000000000e-01 -4.6771865807310284e+00 , 3.6929181179323072e+00 , 7.8017231999999996e+00 , -5.8260500000000004e-01 , 4.2407299999999998e-01 , -6.9334899999999999e-01 -4.6225537547885587e+00 , 3.7006365048272345e+00 , 7.9074288000000008e+00 , 4.6563100000000002e-01 , -2.9639900000000002e-01 , 8.3386800000000005e-01 -4.5056401698087676e+00 , 3.6711961133873583e+00 , 7.8734311999999997e+00 , 6.5176299999999998e-01 , -1.0106800000000001e-01 , 7.5165800000000005e-01 -4.2752394298227276e+00 , 3.5692904234211689e+00 , 7.5555968000000000e+00 , 5.4086000000000001e-01 , 8.1133100000000002e-01 , -2.2184000000000001e-01 -4.2285291985969211e+00 , 3.5814268536290905e+00 , 7.6743648000000002e+00 , 3.4929600000000000e-01 , 7.3255899999999996e-01 , 5.8425099999999996e-01 -4.4502567852285644e+00 , 3.7791473714348740e+00 , 8.5344344000000003e+00 , 5.9605400000000003e-02 , 9.1868799999999995e-01 , 3.9045999999999997e-01 -4.3512387339632292e+00 , 3.7646040227443072e+00 , 8.5623271999999986e+00 , -6.8714299999999995e-01 , -5.8283499999999999e-01 , 4.3374900000000000e-01 -4.1624597677036137e+00 , 3.6833069020216702e+00 , 8.3188008000000018e+00 , -8.8252900000000001e-01 , -4.5764700000000003e-01 , -1.0817100000000000e-01 -3.8942433160484815e+00 , 3.5341121572313456e+00 , 7.7793216000000003e+00 , -5.9193600000000002e-01 , -3.7150600000000000e-01 , -7.1525899999999998e-01 -3.7756252920122217e+00 , 3.4926641940276695e+00 , 7.6800432000000001e+00 , 7.3129600000000003e-02 , 1.8886600000000001e-01 , 9.7927600000000004e-01 -3.7522662261204740e+00 , 3.5315742751114323e+00 , 7.9208968000000004e+00 , 6.1115900000000001e-01 , 6.1424400000000001e-01 , 4.9918800000000002e-01 -3.7585719830577777e+00 , 3.6023367743935220e+00 , 8.3103560000000005e+00 , 4.9214000000000002e-01 , -7.5329800000000002e-01 , 4.3628099999999997e-01 -3.5993222356215147e+00 , 3.5235131082272844e+00 , 8.0485255999999996e+00 , 2.4073900000000001e-01 , 8.1836699999999996e-01 , 5.2184299999999995e-01 -3.5055657240472398e+00 , 3.5037436927098016e+00 , 8.0410168000000013e+00 , 1.0690900000000000e-01 , 8.0217400000000005e-01 , 5.8744099999999999e-01 -3.4386371852901778e+00 , 3.5118135036520988e+00 , 8.1616672000000001e+00 , -8.1388900000000000e-02 , 7.7436899999999997e-01 , 6.2747799999999998e-01 -3.4143655445011198e+00 , 3.5776828750057632e+00 , 8.5519584000000002e+00 , -1.7390700000000001e-01 , 9.7133999999999998e-01 , -1.6203500000000001e-01 -3.3406597767728838e+00 , 3.5918599980337724e+00 , 8.7120248000000000e+00 , 5.1264600000000005e-01 , -6.8373499999999998e-01 , 5.1932699999999998e-01 -3.2217415075376823e+00 , 3.5466583617675465e+00 , 8.5887847999999991e+00 , -2.2071900000000000e-01 , 9.7290800000000000e-01 , 6.8795700000000001e-02 -3.0811708054699829e+00 , 3.4559903507178160e+00 , 8.2405200000000001e+00 , -3.3817399999999997e-01 , -7.8892700000000004e-01 , 5.1306200000000002e-01 -2.9985443271646193e+00 , 3.4542882753806956e+00 , 8.3251032000000009e+00 , -4.6897499999999998e-01 , -8.4540800000000005e-01 , -2.5563200000000003e-01 -3.0335482957983047e+00 , 3.7267781460299583e+00 , 9.8009775999999995e+00 , 5.6693099999999996e-01 , 3.9409600000000000e-01 , 7.2337899999999999e-01 -2.8021116431910342e+00 , 3.3867202638103260e+00 , 8.1638927999999993e+00 , -5.0176200000000004e-01 , -6.9216699999999998e-01 , 5.1878599999999997e-01 -2.6718357958970351e+00 , 3.2177780519808357e+00 , 7.3660671999999998e+00 , -2.4508700000000000e-01 , 1.5708500000000000e-01 , 9.5669099999999996e-01 -2.5967772675465608e+00 , 3.2000373923246839e+00 , 7.3515799999999993e+00 , 9.2877100000000004e-02 , 4.9623400000000001e-01 , 8.6320699999999995e-01 -2.5236037463156746e+00 , 3.1993707697608400e+00 , 7.4275416000000005e+00 , -6.4666699999999999e-01 , -6.4447399999999999e-01 , -4.0801399999999999e-01 -2.4472451653869021e+00 , 3.2931483700835278e+00 , 8.0348080000000000e+00 , -5.3574299999999997e-01 , -5.0589900000000000e-02 , -8.4286399999999995e-01 -2.3576358004047506e+00 , 3.3111265032271309e+00 , 8.2314407999999997e+00 , 6.4304200000000000e-01 , 4.6038499999999999e-01 , -6.1199899999999996e-01 -2.2726007394849788e+00 , 3.2690156307821634e+00 , 8.0885759999999998e+00 , -3.4812799999999999e-01 , 4.1755100000000001e-01 , 8.3931999999999995e-01 -2.1885111874055885e+00 , 3.2409444612713454e+00 , 8.0262072000000000e+00 , -8.4046500000000002e-01 , -2.9551300000000003e-01 , 4.5419199999999998e-01 -2.1132591886815719e+00 , 3.1999890148404466e+00 , 7.8806176000000008e+00 , 1.5596100000000000e-02 , -7.1856100000000001e-01 , 6.9528900000000005e-01 -2.0203780331038264e+00 , 3.2004422115802802e+00 , 7.9895263999999999e+00 , 8.7689099999999998e-01 , -9.3519300000000000e-02 , 4.7150500000000001e-01 -1.7898772246672461e+00 , 3.4021649956340481e+00 , 9.3631999999999991e+00 , -6.9189100000000003e-01 , -6.5535600000000005e-01 , 3.0297900000000000e-01 -4.7885449865376870e+00 , 2.4691668186259172e+00 , 1.2244927999999999e+00 , -6.9526000000000004e-02 , 1.8918699999999999e-01 , 9.7947700000000004e-01 -4.8600702498587953e+00 , 2.4826549596337077e+00 , 1.2329178400000000e+00 , -7.5398000000000007e-02 , 1.8896399999999999e-01 , 9.7908499999999998e-01 -4.9415441193981842e+00 , 2.4970053552666793e+00 , 1.2372068000000001e+00 , -5.9620500000000000e-02 , 1.6343299999999999e-01 , 9.8475100000000004e-01 -5.0307990326601510e+00 , 2.5113419546422802e+00 , 1.2378193600000000e+00 , -7.1536600000000006e-02 , 1.8422900000000000e-01 , 9.8027699999999995e-01 -5.1127755889880859e+00 , 2.5266151574276723e+00 , 1.2467862400000000e+00 , -7.8941700000000004e-02 , 1.7147799999999999e-01 , 9.8202000000000000e-01 -5.1955121462696843e+00 , 2.5423270211067099e+00 , 1.2581055999999999e+00 , -5.9822000000000000e-02 , 1.7399200000000001e-01 , 9.8292800000000002e-01 -5.2860245121432570e+00 , 2.5591502283556480e+00 , 1.2660480800000000e+00 , -9.1377899999999998e-02 , 1.8720600000000001e-01 , 9.7806099999999996e-01 -5.3873576613777967e+00 , 2.5770874066486815e+00 , 1.2712959200000000e+00 , -3.7640500000000000e-02 , 2.2102600000000000e-01 , 9.7454099999999999e-01 -5.4973919988876165e+00 , 2.5962822334317672e+00 , 1.2741018399999999e+00 , -8.7401699999999999e-02 , 1.9511200000000001e-01 , 9.7687900000000005e-01 -5.5900244294145569e+00 , 2.6147392886887184e+00 , 1.2906180800000000e+00 , -8.9475299999999994e-02 , 2.0719399999999999e-01 , 9.7419999999999995e-01 -5.7103749505793235e+00 , 2.6348675921597877e+00 , 1.2949808799999998e+00 , -5.9651999999999997e-02 , 1.9009599999999999e-01 , 9.7995200000000005e-01 -5.8313724209779227e+00 , 2.6567251342455207e+00 , 1.3028058400000000e+00 , -2.1965799999999999e-01 , 1.6124900000000000e-01 , 9.6215899999999999e-01 -5.9619533668404578e+00 , 2.6800945151089559e+00 , 1.3096313600000000e+00 , 9.8107200000000006e-01 , 1.4163600000000001e-01 , -1.3204700000000000e-01 -5.9257445346069630e+00 , 2.6896333114955171e+00 , 1.4019552800000001e+00 , -9.2552100000000004e-01 , 1.3692599999999999e-01 , 3.5307500000000003e-01 -5.9055248540069281e+00 , 2.7005974253927278e+00 , 1.4836815999999999e+00 , 9.9346599999999996e-01 , 3.7422499999999997e-02 , 1.0781800000000000e-01 -6.0065043968854868e+00 , 2.7227393682957026e+00 , 1.5097200800000001e+00 , -9.6219200000000005e-01 , -1.5090700000000001e-01 , 2.2674500000000000e-01 -5.8978875719126256e+00 , 2.7246104167642633e+00 , 1.6275895199999999e+00 , -9.9020100000000000e-01 , -5.7004300000000001e-02 , -1.2748200000000001e-01 -5.9499822741569179e+00 , 2.7416101390377641e+00 , 1.6756520799999999e+00 , -9.3835400000000002e-01 , -2.9716300000000001e-01 , -1.7659400000000000e-01 -5.8951415654707517e+00 , 2.7483124603427727e+00 , 1.7657233600000000e+00 , 9.9811099999999997e-01 , 5.6015400000000000e-02 , -2.5223099999999998e-02 -5.8868129836996497e+00 , 2.7596124663662995e+00 , 1.8358484799999999e+00 , 9.9559900000000001e-01 , 7.9013600000000003e-02 , 5.0402000000000002e-02 -5.9257243195713496e+00 , 2.7749560536265605e+00 , 1.8886846399999999e+00 , 9.8170700000000000e-01 , 7.8494800000000003e-02 , -1.7346500000000001e-01 -5.8464640547377318e+00 , 2.7777966355725319e+00 , 1.9807377440000000e+00 , -9.7692500000000004e-01 , -7.6796299999999998e-02 , -1.9930000000000000e-01 -5.8429779965893189e+00 , 2.7888691502423466e+00 , 2.0454940719999999e+00 , 9.8680999999999996e-01 , 1.1165500000000000e-02 , -1.6149700000000000e-01 -5.8493238125850695e+00 , 2.8010133388988367e+00 , 2.1071262399999999e+00 , -9.4944799999999996e-01 , 1.2278300000000001e-02 , 3.1368299999999999e-01 -5.8742128960896416e+00 , 2.8154888550369388e+00 , 2.1631916000000002e+00 , -8.9449400000000001e-01 , 3.4511699999999999e-02 , 4.4574599999999998e-01 -5.9282276893342409e+00 , 2.8327009049204221e+00 , 2.2127195199999998e+00 , -7.8248600000000001e-01 , 6.8492100000000000e-02 , 6.1889000000000005e-01 -5.9605079201608193e+00 , 2.8478296851395024e+00 , 2.2683470400000001e+00 , -5.1391200000000004e-01 , 1.3965200000000000e-01 , 8.4640000000000004e-01 -6.1037693099938997e+00 , 2.8780059579719581e+00 , 2.3011309600000001e+00 , 2.7376400000000001e-01 , -1.6574000000000000e-01 , -9.4740899999999995e-01 -6.2776004191774417e+00 , 2.9120139232331272e+00 , 2.3330922400000000e+00 , -1.2355200000000000e-01 , 1.9021399999999999e-01 , 9.7393700000000005e-01 -6.5517092399487842e+00 , 2.9615228536310432e+00 , 2.3527201600000001e+00 , 5.2181600000000002e-02 , -1.7057100000000000e-01 , -9.8396300000000003e-01 -1.1658420481236462e+01 , 3.7114634163315694e+00 , 1.7731500000000000e+00 , -1.1200300000000001e-01 , 1.9147300000000000e-01 , 9.7508600000000001e-01 -1.2482671147435957e+01 , 3.8590305832273106e+00 , 1.8329978400000000e+00 , -5.6865199999999998e-02 , 1.8469400000000000e-01 , 9.8114999999999997e-01 -1.3602822154603256e+01 , 4.0558673852823954e+00 , 1.8894251200000001e+00 , -6.3070299999999996e-02 , 1.8962399999999999e-01 , 9.7982899999999995e-01 -1.4835096073071586e+01 , 4.2769861537804017e+00 , 1.9744816240000000e+00 , -4.9255100000000003e-02 , 1.8253100000000000e-01 , 9.8196499999999998e-01 -1.6538158309018762e+01 , 4.5773728431892273e+00 , 2.0686285600000001e+00 , -6.8706699999999996e-02 , 1.8539100000000000e-01 , 9.8026000000000002e-01 -1.8362306663549614e+01 , 4.9075554860647141e+00 , 2.2151427200000002e+00 , -7.1127499999999996e-02 , 1.9064600000000001e-01 , 9.7907900000000003e-01 -2.5369543511888367e+01 , 6.2203366832522882e+00 , 3.0322551200000003e+00 , -8.7861699999999998e-01 , -1.2824199999999999e-01 , -4.5998499999999998e-01 -2.5386056426574832e+01 , 6.2927798940662143e+00 , 3.4323088000000004e+00 , -7.7111799999999997e-01 , -5.9298899999999999e-01 , -2.3182100000000000e-01 -2.5210952943383020e+01 , 6.3331538738233411e+00 , 3.8271864000000000e+00 , 9.3551300000000004e-01 , 2.1030399999999999e-01 , 2.8388099999999999e-01 -2.5152436603973538e+01 , 6.3930620059201102e+00 , 4.2226775999999999e+00 , -6.7383599999999999e-01 , 7.3868699999999998e-01 , -1.6954100000000000e-02 -2.5097062230226069e+01 , 6.4536983050940853e+00 , 4.6173368000000004e+00 , 8.5287000000000002e-01 , 5.2206799999999998e-01 , 7.6092000000000000e-03 -2.5056417683669153e+01 , 6.5160046590864562e+00 , 5.0127448000000001e+00 , -8.5614800000000002e-01 , -5.1649999999999996e-01 , 1.5474900000000000e-02 -2.5017792504819678e+01 , 6.5793423005994081e+00 , 5.4084856000000006e+00 , -8.6001099999999997e-01 , -5.0977899999999998e-01 , 2.2501600000000000e-02 -2.4972863205052821e+01 , 6.6407997234358254e+00 , 5.8041016000000001e+00 , -8.7903600000000004e-01 , -4.6907799999999999e-01 , -8.5217699999999993e-02 -2.4930041439284981e+01 , 6.7033769787346724e+00 , 6.2003623999999995e+00 , -9.4823900000000005e-01 , -3.1566300000000003e-01 , -3.4648199999999997e-02 -2.4901542195181836e+01 , 6.7691101071796460e+00 , 6.5995872000000002e+00 , -9.5233999999999996e-01 , -3.0445899999999998e-01 , -1.8785000000000000e-02 -2.4875841921208107e+01 , 6.8351695211339463e+00 , 7.0011104000000008e+00 , -9.5020499999999997e-01 , 1.9932800000000001e-01 , -2.3953900000000000e-01 -2.4842847048299280e+01 , 6.9005705174833167e+00 , 7.4029768000000002e+00 , -9.5020499999999997e-01 , 1.9932800000000001e-01 , -2.3953900000000000e-01 -2.4822919896517288e+01 , 6.9685122345016550e+00 , 7.8097000000000003e+00 , 9.9696499999999999e-01 , 6.0551800000000003e-02 , 4.8927499999999999e-02 -2.1039555444025968e+01 , 6.2567619721197145e+00 , 7.3538888000000000e+00 , -9.2215300000000000e-01 , 3.6567699999999997e-01 , -1.2614900000000001e-01 -2.0992393425947892e+01 , 6.3082944236606400e+00 , 7.6891744000000006e+00 , -8.4787400000000002e-01 , 2.6421499999999998e-01 , -4.5967400000000003e-01 -2.0604734769441322e+01 , 6.2864052516899704e+00 , 7.9352383999999994e+00 , -5.8759399999999995e-01 , -3.9271599999999997e-02 , -8.0820199999999998e-01 -2.0400257379922035e+01 , 6.3031237626890633e+00 , 8.2224032000000005e+00 , -6.5367299999999995e-01 , 2.6923000000000002e-01 , -7.0726699999999998e-01 -2.2332299875038409e+01 , 6.7899514133404439e+00 , 9.1589440000000018e+00 , 3.8942100000000002e-01 , -8.0518000000000001e-01 , 4.4725399999999998e-01 -2.2571332596702263e+01 , 6.9116210157400433e+00 , 9.6241255999999993e+00 , -4.0297699999999999e-02 , -1.9144100000000000e-01 , 9.8067599999999999e-01 -2.3078357517119620e+01 , 7.0963793839261964e+00 , 1.0196052800000000e+01 , -9.1631200000000002e-01 , -2.2241700000000000e-01 , 3.3302199999999998e-01 -2.0839341171295022e+01 , 6.6523908132490499e+00 , 9.7913056000000012e+00 , -6.5162100000000001e-01 , -1.8156500000000000e-01 , -7.3649500000000001e-01 -2.7925006058861324e+01 , 8.3786797202511636e+00 , 1.2893688000000001e+01 , 9.9182300000000001e-01 , -5.9486100000000000e-02 , -1.1291000000000000e-01 -2.0650938083658371e+01 , 6.7390049337371520e+00 , 1.0465620800000000e+01 , -8.4309299999999998e-01 , -5.2966400000000002e-01 , -9.3001200000000006e-02 -1.9902660449513210e+01 , 6.6251770986218492e+00 , 1.0526315200000001e+01 , 7.9450900000000002e-01 , 4.9392799999999998e-01 , -3.5325600000000001e-01 -1.9964710677679154e+01 , 6.7048806198637125e+00 , 1.0924562400000001e+01 , -8.4940499999999997e-01 , -3.5533900000000002e-01 , 3.9018599999999998e-01 -2.0505564591673583e+01 , 6.9064978258972101e+00 , 1.1555904800000000e+01 , 5.5725599999999997e-01 , 8.1789299999999998e-01 , 1.4323800000000000e-01 -2.1046117509065901e+01 , 7.1132642751766140e+00 , 1.2217781600000000e+01 , 3.0488000000000001e-02 , -4.1964699999999999e-01 , 9.0717499999999995e-01 -2.0405155289330416e+01 , 7.0212603875852428e+00 , 1.2304268000000000e+01 , 8.4700999999999999e-02 , 5.4766199999999998e-01 , 8.3240099999999995e-01 -1.9919763133867320e+01 , 6.9658750332365722e+00 , 1.2452832000000001e+01 , 3.2384200000000002e-01 , 2.0989500000000000e-01 , 9.2253499999999999e-01 -2.5199378695988141e+01 , 8.4375931013690639e+00 , 1.5814112000000000e+01 , -6.3741199999999998e-02 , -9.8299899999999996e-01 , 1.7219499999999999e-01 -2.1638230653491814e+01 , 7.5734545646480651e+00 , 1.4275328000000000e+01 , -5.7230899999999996e-01 , -7.9633900000000002e-01 , -1.9572100000000001e-01 -2.1749413701715248e+01 , 7.6856068043748955e+00 , 1.4808120000000001e+01 , 6.4756199999999997e-01 , 6.9547800000000004e-01 , 3.1140600000000002e-01 -2.2857972506834585e+01 , 8.0773057405896314e+00 , 1.5987584000000000e+01 , -2.9013500000000000e-03 , -4.7988999999999998e-01 , 8.7732399999999999e-01 -2.2518319864771083e+01 , 8.0724846771962255e+00 , 1.6281072000000002e+01 , -4.8346899999999998e-01 , -7.3516700000000001e-01 , -4.7517100000000001e-01 -2.1388835963543585e+01 , 7.8400251525560885e+00 , 1.6029911999999999e+01 , 6.0926199999999997e-01 , 7.6580800000000004e-01 , -2.0576400000000000e-01 -2.1620465510892213e+01 , 7.9955983458588937e+00 , 1.6698632000000000e+01 , -9.1652500000000003e-01 , -3.9835999999999999e-01 , 3.5936200000000001e-02 -2.1768081119849096e+01 , 8.1316579741140380e+00 , 1.7331783999999999e+01 , 7.5170000000000003e-01 , 6.5896299999999997e-01 , 2.6746700000000002e-02 -2.1715907671229321e+01 , 8.2115769690561606e+00 , 1.7833168000000001e+01 , -9.1680899999999999e-01 , -3.2178699999999999e-01 , 2.3646300000000001e-01 -2.1982905054527546e+01 , 8.3910751740162599e+00 , 1.8602039999999999e+01 , 7.8990099999999996e-01 , 4.5165200000000000e-01 , -4.1481000000000001e-01 -6.2162731142075298e+00 , 3.5991015646109394e+00 , 6.2995056000000007e+00 , 1.2328600000000001e-01 , -2.7673199999999998e-01 , 9.5300600000000002e-01 -6.1426598222376985e+00 , 3.5960186888945542e+00 , 6.3528264000000005e+00 , -4.3836300000000000e-01 , -2.0616799999999999e-01 , -8.7483299999999997e-01 -6.1202987178173620e+00 , 3.6096421861659165e+00 , 6.4525624000000006e+00 , -4.3836300000000000e-01 , -2.0616799999999999e-01 , -8.7483299999999997e-01 -5.9787056721555611e+00 , 3.5836946064791571e+00 , 6.4411224000000002e+00 , -4.1498200000000002e-01 , -2.1661100000000000e-01 , -8.8366900000000004e-01 -5.9176779311475780e+00 , 3.5851122852016273e+00 , 6.5036576000000004e+00 , 5.7276000000000005e-01 , 2.6421200000000000e-01 , 7.7597499999999997e-01 -5.8265566453735689e+00 , 3.5754284891407386e+00 , 6.5362824000000002e+00 , -7.4624199999999996e-01 , -3.8038699999999998e-01 , -5.4628699999999997e-01 -5.7852745438603090e+00 , 3.5831398351752024e+00 , 6.6184424000000002e+00 , 8.5760700000000001e-01 , 3.4695399999999998e-01 , 3.7964900000000001e-01 -5.7418971595768458e+00 , 3.5898279564120292e+00 , 6.7003632000000009e+00 , -8.9278999999999997e-01 , -3.1937800000000000e-01 , -3.1768400000000002e-01 -5.7298228672458329e+00 , 3.6090841261962732e+00 , 6.8197136000000000e+00 , -9.2583599999999999e-01 , -3.7690899999999999e-01 , -2.7697599999999999e-02 -5.7273739061397135e+00 , 3.6322630683717545e+00 , 6.9553191999999999e+00 , 9.8492199999999996e-01 , -8.7034799999999996e-02 , -1.4951300000000001e-01 -5.7344904890641093e+00 , 3.6605496433799560e+00 , 7.1077728000000002e+00 , -8.3144600000000002e-01 , 3.3008399999999999e-01 , -4.4692500000000002e-01 -5.7179456597347329e+00 , 3.6800827753751122e+00 , 7.2380848000000002e+00 , -8.2464499999999996e-01 , 3.7189299999999997e-01 , -4.2621100000000001e-01 -5.7771758071364143e+00 , 3.7314007724217699e+00 , 7.4738216000000000e+00 , 6.4317599999999997e-01 , -6.9478200000000001e-01 , -3.2187199999999999e-01 -5.6027844573596974e+00 , 3.6905244751758932e+00 , 7.4023735999999998e+00 , 1.3844000000000001e-01 , 9.4306699999999999e-01 , 3.0242200000000002e-01 -5.4437771807558182e+00 , 3.6535349582858370e+00 , 7.3429583999999997e+00 , 2.7413500000000002e-01 , 2.3138700000000002e-02 , 9.6141299999999996e-01 -5.3669587704179538e+00 , 3.6496166712414793e+00 , 7.3967056000000007e+00 , -6.7985899999999999e-01 , 1.4079200000000000e-01 , -7.1970100000000004e-01 -5.3062162734106391e+00 , 3.6530298360655507e+00 , 7.4744663999999998e+00 , -5.2831300000000003e-01 , 5.5147500000000002e-02 , -8.4725700000000004e-01 -5.2487578077429173e+00 , 3.6589307056677174e+00 , 7.5600167999999996e+00 , -9.3815700000000002e-02 , 4.5326699999999998e-01 , -8.8642399999999999e-01 -5.1217451517053210e+00 , 3.6332964478065515e+00 , 7.5321656000000008e+00 , -8.0268400000000004e-02 , -2.9769099999999998e-01 , 9.5128199999999996e-01 -4.9613602529440133e+00 , 3.5897541400987016e+00 , 7.4399384000000000e+00 , -5.6305599999999997e-02 , -2.6934500000000000e-01 , 9.6139600000000003e-01 -5.0651829985484618e+00 , 3.6722046972522087e+00 , 7.8133607999999999e+00 , -3.6876300000000001e-01 , 1.9744900000000001e-01 , -9.0830999999999995e-01 -4.8004497325323818e+00 , 3.5767587929498195e+00 , 7.5202888000000003e+00 , 3.3746300000000001e-01 , 9.4128199999999995e-01 , 1.0386100000000001e-02 -4.6894086763469822e+00 , 3.5550444596542121e+00 , 7.4994992000000007e+00 , 1.6164300000000001e-01 , 9.6882199999999996e-01 , -1.8776599999999999e-01 -4.6058193770314215e+00 , 3.5468895951405637e+00 , 7.5307824000000005e+00 , 5.3456799999999999e-02 , -6.2310600000000005e-01 , 7.8030800000000000e-01 -4.5182143790089437e+00 , 3.5357209392768580e+00 , 7.5515096000000002e+00 , -1.4986500000000000e-02 , -7.9999900000000002e-01 , 5.9981499999999999e-01 -4.4390893397498070e+00 , 3.5286811332527175e+00 , 7.5892824000000010e+00 , 3.6044199999999998e-01 , 7.7155600000000002e-01 , 5.2419700000000002e-01 -4.3508263655935000e+00 , 3.5168846020057476e+00 , 7.6067647999999997e+00 , 2.2467100000000001e-01 , 5.6664400000000004e-01 , 7.9274000000000000e-01 -4.4433996292480415e+00 , 3.6146794564643883e+00 , 8.0749935999999991e+00 , -5.3393500000000005e-01 , 5.3127300000000002e-02 , -8.4385500000000002e-01 -4.4877689104443999e+00 , 3.6908338903473776e+00 , 8.4624872000000018e+00 , -6.9865200000000005e-01 , -7.1497900000000003e-01 , -2.6252800000000000e-02 -4.4370143237666309e+00 , 3.7107246004998320e+00 , 8.6241863999999993e+00 , 5.9605400000000003e-02 , 9.1868799999999995e-01 , 3.9045999999999997e-01 -4.1438809377041483e+00 , 3.5666129484589812e+00 , 8.0835007999999995e+00 , -6.3902499999999995e-01 , 1.0161299999999999e-01 , 7.6244500000000004e-01 -3.9531865794791252e+00 , 3.4838239600683352e+00 , 7.7952648000000009e+00 , 7.1564399999999995e-01 , -4.1190500000000002e-01 , -5.6408100000000005e-01 -3.8436460346259795e+00 , 3.4552308548911066e+00 , 7.7353400000000008e+00 , 7.3129600000000003e-02 , 1.8886600000000001e-01 , 9.7927600000000004e-01 -3.7778826615211636e+00 , 3.4591755202453278e+00 , 7.8199959999999997e+00 , -7.9740200000000006e-01 , 7.7798199999999998e-02 , -5.9841299999999997e-01 -3.7121125264203867e+00 , 3.4649333854769511e+00 , 7.9135647999999996e+00 , 6.4437800000000001e-01 , 5.5948799999999999e-01 , 5.2129599999999998e-01 -3.6772313261506948e+00 , 3.4992793942544735e+00 , 8.1451312000000016e+00 , 2.7249299999999999e-01 , 1.0782600000000000e-02 , 9.6209699999999998e-01 -3.5634678687616415e+00 , 3.4655538181602239e+00 , 8.0588320000000007e+00 , -4.2612899999999998e-01 , -8.0997100000000000e-01 , -4.0294000000000002e-01 -3.4856617052892434e+00 , 3.4651472147336788e+00 , 8.1298120000000011e+00 , -1.1424400000000000e-01 , -4.4286600000000001e-03 , 9.9344299999999996e-01 -3.4450020107300485e+00 , 3.5074265523097692e+00 , 8.4100503999999994e+00 , 1.0522900000000000e-01 , -9.2674400000000001e-01 , 3.6065500000000000e-01 -3.4713996356240764e+00 , 3.6402007958299416e+00 , 9.1432296000000015e+00 , 3.0467100000000003e-01 , -7.5078599999999995e-01 , -5.8608499999999997e-01 -3.3994468837810401e+00 , 3.6727940865968218e+00 , 9.3950551999999998e+00 , 6.4391900000000002e-01 , 1.6477900000000001e-01 , 7.4713799999999997e-01 -3.1367828040133432e+00 , 3.4309826604043678e+00 , 8.2705240000000000e+00 , 2.4227499999999999e-01 , -6.2139000000000000e-01 , 7.4510200000000004e-01 -3.0532965486129902e+00 , 3.4304857977401531e+00 , 8.3451336000000005e+00 , 4.6897499999999998e-01 , 8.4540800000000005e-01 , 2.5563200000000003e-01 -2.9612873406800460e+00 , 3.4187957676686684e+00 , 8.3675975999999999e+00 , -4.6897499999999998e-01 , -8.4540800000000005e-01 , -2.5563200000000003e-01 -2.9782801369510605e+00 , 3.6675363664966274e+00 , 9.7639431999999999e+00 , -6.7544899999999997e-01 , 5.9301099999999995e-01 , -4.3830000000000002e-01 -2.7151266102926814e+00 , 3.2053294253770011e+00 , 7.3873144000000002e+00 , 3.3950100000000000e-01 , -1.0810300000000000e-01 , -9.3437300000000001e-01 -2.6381876705019591e+00 , 3.1887982548967351e+00 , 7.3626352000000006e+00 , -1.3013100000000000e-01 , 2.6524500000000001e-01 , 9.5535899999999996e-01 -2.5635464966312385e+00 , 3.1821590813857004e+00 , 7.3980680000000003e+00 , 5.1505900000000004e-01 , 6.2266500000000002e-01 , 5.8906800000000004e-01 -2.5059301093035353e+00 , 3.5444828244001245e+00 , 9.5108904000000010e+00 , 2.9042899999999999e-01 , 9.5423400000000003e-01 , 7.1326600000000004e-02 -2.4049378319842294e+00 , 3.3082677820910327e+00 , 8.2642216000000008e+00 , -3.7784800000000002e-01 , -6.6212499999999996e-01 , 6.4716399999999996e-01 -2.3172940742977874e+00 , 3.2736079666703786e+00 , 8.1525464000000003e+00 , 5.8023800000000003e-01 , 6.0674499999999998e-01 , -5.4330999999999996e-01 -2.2294012529313760e+00 , 3.2550908491470683e+00 , 8.1314759999999993e+00 , -1.6802400000000001e-01 , 2.6298199999999999e-01 , 9.5005700000000004e-01 -2.1586121869114798e+00 , 3.1925012070138816e+00 , 7.8426159999999996e+00 , 3.6605700000000002e-01 , -1.3160600000000000e-01 , 9.2123900000000003e-01 -2.0706270511131573e+00 , 3.1898508278379212e+00 , 7.9108296000000005e+00 , -7.1245599999999998e-01 , 5.0933099999999998e-01 , -4.8268800000000001e-01 -1.8008557329779455e+00 , 3.4825231005626831e+00 , 9.8276640000000004e+00 , 5.3235699999999997e-01 , 8.4629299999999996e-01 , 1.9595300000000000e-02 -1.7479087997665315e+00 , 3.3709913594951195e+00 , 9.2469904000000014e+00 , -9.6554899999999999e-01 , 1.9924900000000001e-01 , -1.6737900000000000e-01 -4.8293426097117447e+00 , 2.4136958162112352e+00 , 1.2424702399999998e+00 , -6.3409400000000005e-02 , 1.9508600000000001e-01 , 9.7873399999999999e-01 -4.9017177032809460e+00 , 2.4252949378042423e+00 , 1.2522400000000000e+00 , -5.5185100000000001e-02 , 1.8590100000000001e-01 , 9.8101799999999995e-01 -4.9921000017096695e+00 , 2.4372632173168349e+00 , 1.2518708000000001e+00 , -7.8978099999999996e-02 , 1.9347400000000001e-01 , 9.7792199999999996e-01 -5.0650164736390515e+00 , 2.4496989711295942e+00 , 1.2659160000000000e+00 , -7.2523099999999993e-02 , 2.2935300000000000e-01 , 9.7063800000000000e-01 -5.1649722614554054e+00 , 2.4631760039896085e+00 , 1.2645463200000000e+00 , -6.6197199999999998e-02 , 2.0157000000000000e-01 , 9.7723499999999996e-01 -5.2565825566639486e+00 , 2.4776715049731353e+00 , 1.2717098400000000e+00 , 8.5643300000000006e-02 , -2.2245400000000001e-01 , -9.7117399999999998e-01 -5.3398195511864621e+00 , 2.4910193308198187e+00 , 1.2872100000000000e+00 , -7.0386000000000004e-02 , 1.9153600000000001e-01 , 9.7895799999999999e-01 -5.4499342148746166e+00 , 2.5067816952294648e+00 , 1.2888116000000001e+00 , -4.2137800000000003e-02 , 2.1698200000000001e-01 , 9.7526599999999997e-01 -5.5426528253341143e+00 , 2.5218297589280776e+00 , 1.3042223200000000e+00 , -7.8970700000000005e-02 , 1.9999400000000001e-01 , 9.7660999999999998e-01 -5.6630880116153985e+00 , 2.5385041953716483e+00 , 1.3072788800000001e+00 , -5.1131200000000002e-02 , 1.9819500000000001e-01 , 9.7882800000000003e-01 -5.7841805464390301e+00 , 2.5569089173216812e+00 , 1.3137976000000000e+00 , -4.3929400000000000e-02 , 1.8417200000000000e-01 , 9.8191200000000001e-01 -5.9148335615789076e+00 , 2.5757872542658409e+00 , 1.3194198400000001e+00 , -3.1316899999999998e-01 , 4.3826999999999998e-02 , 9.4868500000000000e-01 -6.0191969038001867e+00 , 2.5940617223107445e+00 , 1.3428084000000000e+00 , -9.7557499999999997e-01 , -1.8140000000000001e-01 , -1.2388600000000000e-01 -5.9531114592506569e+00 , 2.6032595963734502e+00 , 1.4481416800000000e+00 , 9.9548499999999995e-01 , 8.6720500000000006e-02 , 3.8597699999999999e-02 -5.9418365204584918e+00 , 2.6150650958333852e+00 , 1.5254043200000000e+00 , 9.9547699999999995e-01 , -1.3653700000000000e-02 , 9.4015899999999999e-02 -5.9295485860488082e+00 , 2.6257431094812191e+00 , 1.6021396800000001e+00 , 9.9368199999999995e-01 , 9.7109500000000001e-02 , -5.6263800000000003e-02 -6.0786533400034077e+00 , 2.6477707371696102e+00 , 1.6115329599999999e+00 , 9.7563200000000005e-01 , -1.7171800000000001e-01 , 1.3658600000000001e-01 -5.9178282579976154e+00 , 2.6486449926561466e+00 , 1.7449410400000001e+00 , 9.9822400000000000e-01 , 5.2655300000000002e-02 , 2.7856599999999999e-02 -5.9203940475129198e+00 , 2.6609576905470864e+00 , 1.8118639999999999e+00 , -9.1748200000000002e-01 , -4.4084199999999997e-02 , 3.9532699999999998e-01 -5.9307262664737657e+00 , 2.6732763383813714e+00 , 1.8752124800000001e+00 , -9.1748200000000002e-01 , -4.4084100000000001e-02 , 3.9532699999999998e-01 -6.0088690814556474e+00 , 2.6908675726390152e+00 , 1.9159611360000000e+00 , 9.7889099999999996e-01 , 2.0247000000000001e-02 , 2.0337900000000000e-01 -5.8588101865794151e+00 , 2.6894084021528046e+00 , 2.0295254960000002e+00 , 9.8942500000000000e-01 , 8.9330699999999999e-02 , 1.1427600000000000e-01 -5.8760062644956896e+00 , 2.7026258361361766e+00 , 2.0882592880000002e+00 , 9.7039299999999995e-01 , -9.0195999999999991e-03 , -2.4136299999999999e-01 -5.8714537726467810e+00 , 2.7126774384595889e+00 , 2.1529943999999999e+00 , -9.5389199999999996e-01 , -1.2716300000000000e-02 , 2.9987999999999998e-01 -5.9157496091665802e+00 , 2.7275278991603855e+00 , 2.2045368000000001e+00 , -8.4995900000000002e-01 , 4.1655800000000000e-02 , 5.2519899999999997e-01 -5.9588615469460704e+00 , 2.7426697968267844e+00 , 2.2572689600000002e+00 , -7.0974499999999996e-01 , 1.1701900000000000e-01 , 6.9467199999999996e-01 -6.0427592964902210e+00 , 2.7620236633762674e+00 , 2.3027148799999999e+00 , 4.0101300000000001e-01 , -1.7904700000000001e-01 , -8.9840500000000001e-01 -6.1963010193583115e+00 , 2.7888083165057984e+00 , 2.3366625600000002e+00 , 1.6751300000000000e-01 , -1.8843199999999999e-01 , -9.6769499999999997e-01 -6.4104435982845089e+00 , 2.8234528963921828e+00 , 2.3645855199999999e+00 , -9.5591800000000005e-02 , 1.8973499999999999e-01 , 9.7717100000000001e-01 -6.7585948049505671e+00 , 2.8728809498929380e+00 , 2.3785267200000000e+00 , -2.5372300000000000e-02 , 1.6909199999999999e-01 , 9.8527399999999998e-01 -1.1524391690571205e+01 , 3.4177106686530596e+00 , 1.7622206400000000e+00 , -1.4032500000000001e-01 , 1.9671200000000000e-01 , 9.7036800000000001e-01 -1.2035278619077388e+01 , 3.5039524466192500e+00 , 1.8565860800000000e+00 , -1.0723800000000000e-01 , 1.9762800000000000e-01 , 9.7439399999999998e-01 -1.3047615989929737e+01 , 3.6523174570110459e+00 , 1.9129924560000000e+00 , -5.4434099999999999e-02 , 1.9043399999999999e-01 , 9.8019000000000001e-01 -1.4089633286655864e+01 , 3.8100553112678215e+00 , 2.0013313248000002e+00 , -6.2410399999999998e-02 , 1.9047700000000001e-01 , 9.7970599999999997e-01 -1.5677620074286848e+01 , 4.0410483045282426e+00 , 2.0846884480000001e+00 , -4.5886999999999997e-02 , 1.8307300000000001e-01 , 9.8202800000000001e-01 -1.7335103298227470e+01 , 4.2898843411998548e+00 , 2.2188482399999998e+00 , -7.3183499999999999e-02 , 1.8992800000000001e-01 , 9.7906700000000002e-01 -1.9187422888225885e+01 , 4.5753208408096615e+00 , 2.4023011200000002e+00 , -7.2405300000000006e-02 , 1.8699299999999999e-01 , 9.7968900000000003e-01 -2.2786937895027940e+01 , 5.1025670190502694e+00 , 2.6094400000000002e+00 , -2.4881100000000000e-01 , 1.5456600000000001e-01 , 9.5613899999999996e-01 -2.5731483735911453e+01 , 5.5618882140401773e+00 , 2.9455971200000000e+00 , 8.3934900000000001e-01 , 3.5526300000000000e-01 , -4.1143900000000000e-01 -2.6318244443152196e+01 , 5.7129303579018913e+00 , 3.3566488000000003e+00 , 6.1061100000000001e-01 , 3.0428200000000000e-01 , -7.3114100000000004e-01 -2.6618713623450486e+01 , 5.8267687577585123e+00 , 3.7803344000000001e+00 , 5.5678600000000000e-01 , -1.2845300000000001e-01 , -8.2066399999999995e-01 -2.7108056896695036e+01 , 5.9705001162289140e+00 , 4.2239672000000006e+00 , 5.6696999999999997e-01 , -9.0633800000000000e-02 , -8.1873700000000005e-01 -3.0199739571590481e+01 , 6.5844707807296645e+00 , 5.3379735999999998e+00 , 7.9234499999999999e-02 , -1.0284699999999999e-01 , 9.9153599999999997e-01 -2.5643521326239032e+01 , 5.9680758097973126e+00 , 5.3750288000000008e+00 , 9.7941299999999998e-01 , 1.9883999999999999e-01 , 3.4830699999999999e-02 -2.5457680782388362e+01 , 6.0095925643102799e+00 , 5.7628552000000006e+00 , -9.0933799999999998e-01 , -1.0800700000000001e-01 , -4.0179500000000001e-01 -2.5489627432146786e+01 , 6.0849446895621337e+00 , 6.1752359999999999e+00 , -8.8069699999999995e-01 , 3.0071400000000002e-02 , -4.7272500000000001e-01 -2.4844225745812992e+01 , 6.0504382163463761e+00 , 6.4881200000000003e+00 , -9.5865500000000003e-01 , 1.0686900000000001e-01 , -2.6374100000000000e-01 -3.1429580766764165e+01 , 7.2122966663798804e+00 , 8.0103992000000002e+00 , -9.4306599999999996e-01 , -2.9356199999999999e-01 , 1.5635800000000000e-01 -3.0944354146750481e+01 , 7.2194361324897676e+00 , 8.4429248000000001e+00 , 9.5189000000000001e-01 , 1.9861999999999999e-01 , -2.3335900000000001e-01 -2.7479967360267402e+01 , 6.7129145800669692e+00 , 8.2464896000000003e+00 , 6.1068200000000003e-02 , 7.4055599999999999e-01 , 6.6921399999999998e-01 -2.0853946389622191e+01 , 5.6307430051436889e+00 , 7.2165151999999999e+00 , 7.6577799999999996e-01 , -9.0315699999999999e-02 , -6.3673199999999996e-01 -2.0900359030053220e+01 , 5.6975501075336981e+00 , 7.5685448000000006e+00 , -6.5049299999999999e-01 , -3.0963600000000002e-01 , 6.9352999999999998e-01 -2.1465888285405217e+01 , 5.8596268503767144e+00 , 8.0614008000000013e+00 , -7.4340399999999995e-01 , 9.3550100000000004e-03 , 6.6877799999999998e-01 -2.1870800585128436e+01 , 5.9958481180285208e+00 , 8.5341535999999998e+00 , 7.2408700000000004e-01 , -3.9296499999999998e-02 , -6.8858799999999998e-01 -2.2960333577754021e+01 , 6.2646824079442247e+00 , 9.2313592000000000e+00 , 5.4395099999999996e-01 , 3.7950600000000001e-01 , -7.4839299999999997e-01 -2.2820925289037536e+01 , 6.3064271725331036e+00 , 9.5827024000000005e+00 , 5.9333800000000003e-01 , 2.0069100000000001e-01 , -7.7953399999999995e-01 -2.1484906739757601e+01 , 6.1139220066791626e+00 , 9.5279255999999997e+00 , -7.1090600000000004e-01 , -4.0503099999999997e-01 , -5.7494599999999996e-01 -2.1563931264666916e+01 , 6.1941694421680520e+00 , 9.9325584000000013e+00 , 6.9015099999999996e-01 , 3.8236599999999998e-01 , 6.1439999999999995e-01 -2.0763327032357122e+01 , 6.0992451286896774e+00 , 1.0012690400000000e+01 , 6.5302400000000005e-01 , 4.6703600000000001e-01 , 5.9618599999999999e-01 -2.0888607720171620e+01 , 6.1884415081868793e+00 , 1.0434712000000001e+01 , 6.5302400000000005e-01 , 4.6703600000000001e-01 , 5.9618599999999999e-01 -2.0551493127021409e+01 , 6.1841869292463478e+00 , 1.0673568800000000e+01 , 7.5718799999999997e-01 , 6.5295000000000003e-01 , 1.7965200000000001e-02 -2.1351153270697225e+01 , 6.4193506526285056e+00 , 1.1405354400000000e+01 , -8.2450800000000002e-01 , -3.6700700000000003e-01 , 4.3068899999999999e-01 -1.3921462179474752e+01 , 4.8830889831166093e+00 , 8.3769992000000002e+00 , -1.3514099999999999e-02 , 4.8098200000000002e-01 , 8.7662600000000002e-01 -2.1501294766661367e+01 , 6.5911101170707607e+00 , 1.2289926400000001e+01 , -8.7948499999999996e-01 , -4.7197400000000000e-01 , -6.1215499999999999e-02 -2.0682222558039520e+01 , 6.4810241596479656e+00 , 1.2296072799999999e+01 , -2.3154300000000000e-01 , -6.4002499999999996e-01 , -7.3263699999999998e-01 -2.0105611295652380e+01 , 6.4196831701819566e+00 , 1.2400936000000000e+01 , 2.5178400000000001e-01 , 6.2857799999999997e-01 , 7.3586300000000004e-01 -1.9717407042261556e+01 , 6.3994385463150198e+00 , 1.2591672000000001e+01 , 5.7916000000000001e-01 , 2.5763000000000003e-01 , 7.7343399999999995e-01 -2.4198152845526803e+01 , 7.5232093544405618e+00 , 1.5568152000000001e+01 , -3.5415300000000000e-01 , 7.5485700000000000e-01 , -5.5205599999999999e-01 -2.3879721500545696e+01 , 7.5361953475110175e+00 , 1.5896584000000001e+01 , -4.8496000000000000e-01 , -7.7083900000000005e-01 , 4.1306399999999999e-01 -2.1463484597595119e+01 , 7.0378045446867574e+00 , 1.4915448000000000e+01 , -9.4723999999999997e-01 , -2.4148800000000001e-01 , 2.1075800000000000e-01 -2.3348510313507649e+01 , 7.5869647851036133e+00 , 1.6609712000000002e+01 , -7.5498299999999996e-01 , -4.7416799999999998e-01 , -4.5295299999999999e-01 -2.1899753244156134e+01 , 7.3130140112244844e+00 , 1.6168856000000002e+01 , -7.8503900000000004e-01 , -2.7842000000000000e-01 , 5.5335000000000001e-01 -2.3736221658304569e+01 , 7.8724294257086500e+00 , 1.7961815999999999e+01 , 7.2969200000000001e-01 , -4.9650499999999997e-01 , 4.7014099999999998e-01 -2.3174612802687104e+01 , 7.8234539207793539e+00 , 1.8125927999999998e+01 , -1.6281699999999999e-01 , -6.7646899999999999e-01 , 7.1824800000000000e-01 -2.2614897180307281e+01 , 7.7735145296804884e+00 , 1.8275064000000000e+01 , -5.6351099999999998e-01 , -6.1300399999999999e-01 , 5.5378899999999998e-01 -6.4041993882115573e+00 , 3.5166194815234117e+00 , 6.4045456000000005e+00 , 4.0027199999999999e-02 , -4.8738100000000001e-01 , 8.7227200000000005e-01 -6.2825287293610179e+00 , 3.5027942285481739e+00 , 6.4206344000000000e+00 , -7.4711799999999995e-02 , 5.6839799999999996e-01 , -8.1935400000000003e-01 -6.1536559096450354e+00 , 3.4861794013325427e+00 , 6.4266248000000008e+00 , -2.8829900000000003e-01 , -5.5437499999999995e-01 , -7.8073899999999996e-01 -6.0403849928110054e+00 , 3.4741566086852167e+00 , 6.4429008000000003e+00 , 5.1213299999999995e-01 , -1.8021699999999999e-01 , 8.3978600000000003e-01 -5.9793078639171551e+00 , 3.4767601947409679e+00 , 6.5060392000000000e+00 , -8.9926600000000001e-01 , -1.0737200000000000e-01 , -4.2401800000000001e-01 -5.9107613643060510e+00 , 3.4759555073616477e+00 , 6.5612007999999999e+00 , -7.0675800000000000e-01 , -3.8357900000000000e-01 , -5.9443999999999997e-01 -5.8618759926722852e+00 , 3.4826466200677828e+00 , 6.6366840000000007e+00 , -7.9834400000000005e-01 , -4.1074800000000000e-01 , -4.4037799999999999e-01 -5.8313919289313478e+00 , 3.4950914801746746e+00 , 6.7341112000000001e+00 , -7.7098599999999995e-01 , -2.0531800000000000e-01 , -6.0284700000000002e-01 -5.7525961926015032e+00 , 3.4925519218809544e+00 , 6.7784776000000004e+00 , -9.0225500000000003e-01 , -1.0038100000000000e-01 , -4.1935699999999998e-01 -5.8252062227449093e+00 , 3.5401070034961850e+00 , 6.9983856000000007e+00 , 9.9830500000000000e-01 , -5.7058400000000002e-02 , 1.1491899999999999e-02 -5.7604658490325944e+00 , 3.5426694348002745e+00 , 7.0658088000000001e+00 , -7.8799100000000000e-01 , 4.0936099999999997e-01 , -4.5988600000000002e-01 -5.7012220147952073e+00 , 3.5474316287204113e+00 , 7.1400440000000005e+00 , 8.7217500000000003e-01 , -3.1825100000000001e-01 , 3.7152000000000002e-01 -5.6036855843032729e+00 , 3.5386662881117212e+00 , 7.1653159999999998e+00 , 7.5747299999999995e-01 , -4.9143700000000001e-01 , 4.2979600000000001e-01 -5.6330897691738162e+00 , 3.5755212024078151e+00 , 7.3597856000000004e+00 , -9.1776100000000005e-01 , -1.2105600000000000e-01 , -3.7823299999999999e-01 -5.7037800042559255e+00 , 3.6307147401944602e+00 , 7.6224791999999999e+00 , 9.2712700000000003e-01 , -3.7417400000000001e-01 , -2.0719600000000001e-02 -5.6923403746511116e+00 , 3.6556345333942897e+00 , 7.7806112000000001e+00 , 6.2457099999999999e-01 , 1.7764400000000000e-01 , 7.6049599999999995e-01 -5.3938860557352406e+00 , 3.5695472800183468e+00 , 7.5162640000000005e+00 , 7.5051699999999999e-01 , 4.0117199999999999e-02 , 6.5963300000000002e-01 -5.2877235922129220e+00 , 3.5569025619311012e+00 , 7.5257072000000003e+00 , -2.7328500000000000e-01 , -2.9215099999999999e-01 , -9.1649499999999995e-01 -5.1596993558978497e+00 , 3.5345310926350471e+00 , 7.4980328000000007e+00 , -1.2909000000000001e-01 , 1.8220300000000000e-01 , 9.7475000000000001e-01 -5.0857094646366852e+00 , 3.5343006570834619e+00 , 7.5548896000000001e+00 , -1.2557199999999999e-01 , 3.9909600000000001e-01 , 9.0827000000000002e-01 -4.9614459937288453e+00 , 3.5118033481189030e+00 , 7.5221088000000007e+00 , -1.7818100000000000e-02 , 3.8056499999999999e-01 , 9.2458200000000001e-01 -4.8522214045626564e+00 , 3.4955762300887767e+00 , 7.5131231999999999e+00 , 5.0239699999999998e-01 , 7.8130699999999997e-01 , 3.7034600000000001e-01 -4.8530828608182448e+00 , 3.5297501787725283e+00 , 7.7092776000000010e+00 , 5.2353099999999997e-01 , 7.6246199999999997e-01 , 3.8022000000000000e-01 -4.7024378038772614e+00 , 3.4929160355966991e+00 , 7.6155320000000000e+00 , 1.9828999999999999e-01 , 9.7759200000000002e-01 , 7.0670899999999995e-02 -4.6875504001839641e+00 , 3.5209719351576689e+00 , 7.7937776000000003e+00 , -7.8197799999999995e-01 , -8.8878799999999994e-02 , -6.1693600000000004e-01 -4.7462178268484827e+00 , 3.5899851837717489e+00 , 8.1488231999999989e+00 , -8.5537300000000005e-01 , 1.2179200000000000e-01 , 5.0349200000000005e-01 -4.5464939042282815e+00 , 3.5262991654318485e+00 , 7.9376824000000008e+00 , -5.7698000000000005e-01 , 1.5714600000000001e-01 , -8.0149800000000004e-01 -4.4838465106425058e+00 , 3.5341363924263431e+00 , 8.0317296000000002e+00 , -6.4340600000000003e-01 , 4.6015499999999998e-01 , -6.1178999999999994e-01 -4.6507307046332613e+00 , 3.6757021740552029e+00 , 8.7225704000000004e+00 , -6.8593400000000004e-01 , -7.2714000000000001e-01 , 2.7613200000000001e-02 -4.4478595371713343e+00 , 3.6079113927150024e+00 , 8.4850656000000004e+00 , -7.0621500000000004e-01 , -4.9902700000000000e-01 , 5.0222800000000001e-01 -4.2550263983898668e+00 , 3.5397041584839686e+00 , 8.2424232000000011e+00 , -5.6570399999999998e-01 , -1.8673100000000001e-01 , 8.0318800000000001e-01 -4.0834275735844097e+00 , 3.4794506358922770e+00 , 8.0332375999999996e+00 , -1.6703100000000001e-01 , 2.8925000000000001e-01 , 9.4256799999999996e-01 -3.9086155437015746e+00 , 3.4126956312110064e+00 , 7.7805488000000009e+00 , 6.1265199999999999e-02 , 5.9651099999999999e-02 , 9.9633799999999995e-01 -3.8761418463647823e+00 , 3.4432266920166583e+00 , 7.9831408000000001e+00 , -1.1620200000000000e-01 , -9.3910800000000005e-01 , -3.2337900000000003e-01 -3.7487822444369598e+00 , 3.4050652367329697e+00 , 7.8614088000000004e+00 , -9.3232499999999996e-01 , 6.0676599999999997e-02 , -3.5649599999999998e-01 -3.7050714037268211e+00 , 3.4298357136337341e+00 , 8.0435648000000004e+00 , -8.8123399999999996e-01 , -3.1492500000000001e-01 , -3.5249100000000000e-01 -3.6421116396977133e+00 , 3.4442916966594268e+00 , 8.1756552000000013e+00 , 1.0716600000000000e-01 , -9.4398800000000005e-02 , 9.8975000000000002e-01 -3.5354969278939294e+00 , 3.4192204678240468e+00 , 8.1180184000000004e+00 , 2.0634400000000000e-01 , 4.9988900000000003e-02 , 9.7720200000000002e-01 -3.4341534677652001e+00 , 3.3985073470389819e+00 , 8.0779576000000013e+00 , -1.0670000000000000e-01 , 5.1816600000000002e-01 , -8.4859799999999996e-01 -3.3419624487223856e+00 , 3.3861437705917155e+00 , 8.0759608000000007e+00 , 6.2802200000000002e-02 , -5.9702100000000002e-01 , 7.9976400000000003e-01 -3.4819579500443667e+00 , 3.6530268767762903e+00 , 9.5148007999999997e+00 , 9.2084500000000002e-01 , -3.0196400000000001e-01 , 2.4670400000000001e-01 -3.3739884276070655e+00 , 3.6485114358165260e+00 , 9.5747360000000015e+00 , 8.4270800000000000e-03 , -4.7562100000000003e-02 , 9.9883299999999997e-01 -3.1051445875352925e+00 , 3.3995473028564089e+00 , 8.3449151999999991e+00 , -6.1215799999999998e-01 , -7.8033799999999998e-01 , 1.2780500000000000e-01 -3.0297131775925665e+00 , 3.4200386579539233e+00 , 8.5201448000000006e+00 , -2.3892400000000001e-02 , 9.9684200000000001e-01 , 7.5729500000000005e-02 -2.9329098298870573e+00 , 3.4064005474320687e+00 , 8.5213824000000002e+00 , 4.9745099999999998e-01 , 8.5929599999999995e-01 , 1.1896400000000000e-01 -2.7591463275874779e+00 , 3.1947815784684517e+00 , 7.4286751999999998e+00 , 4.2507400000000001e-01 , -2.7868199999999999e-02 , -9.0473000000000003e-01 -2.6786425574760546e+00 , 3.1723737639066201e+00 , 7.3635295999999997e+00 , 1.4942700000000000e-02 , 3.2261299999999998e-01 , 9.4641299999999995e-01 -2.6041851608787878e+00 , 3.1669062158074643e+00 , 7.3890200000000004e+00 , -4.0192099999999997e-01 , -6.5395800000000004e-01 , -6.4093599999999995e-01 -2.5299259007499662e+00 , 3.1714281968494391e+00 , 7.4746848000000004e+00 , 6.4832400000000001e-01 , 6.4224700000000001e-01 , 4.0889599999999998e-01 -2.4533307303810550e+00 , 3.2898720774849428e+00 , 8.2254088000000003e+00 , -2.8896300000000003e-01 , -7.1926100000000004e-01 , 6.3179500000000000e-01 -2.3621912408038157e+00 , 3.2852982847399770e+00 , 8.2675704000000003e+00 , 3.4322599999999998e-01 , 5.7999699999999998e-01 , -7.3878299999999997e-01 -2.2766623149157215e+00 , 3.2452520518031718e+00 , 8.1032608000000010e+00 , -2.0726500000000000e-01 , -1.3542800000000001e-02 , 9.7819100000000003e-01 -2.1884597986067420e+00 , 3.2348324179533581e+00 , 8.1117992000000001e+00 , 7.2080900000000003e-01 , 6.4385000000000003e-01 , -2.5669399999999998e-01 -2.1159863776427228e+00 , 3.1834572897919049e+00 , 7.8729215999999997e+00 , 2.1897900000000001e-01 , -2.3444000000000001e-01 , 9.4714600000000004e-01 -2.0222688328857887e+00 , 3.1890573155692077e+00 , 7.9808736000000007e+00 , -7.7384100000000000e-01 , 5.4905500000000003e-02 , -6.3099600000000000e-01 -1.7870300024005570e+00 , 3.4001765024169437e+00 , 9.3949096000000019e+00 , 9.8411899999999997e-01 , 1.5352299999999999e-01 , -8.9107099999999995e-02 -5.1855871488860386e+00 , 2.2383040421325022e+00 , 3.6361199999999982e-01 , 4.1637999999999997e-01 , 8.2998100000000005e-02 , -9.0539400000000003e-01 -4.7965665023295951e+00 , 2.3469374869314081e+00 , 1.2519664800000001e+00 , -5.4209599999999997e-02 , 1.8790200000000001e-01 , 9.8069099999999998e-01 -4.8770798724652771e+00 , 2.3557135614955023e+00 , 1.2547276799999998e+00 , -5.8733399999999998e-02 , 1.8357000000000001e-01 , 9.8124999999999996e-01 -4.9593863985039377e+00 , 2.3649093678334943e+00 , 1.2599661600000001e+00 , -7.7010800000000004e-02 , 2.0699000000000001e-01 , 9.7530700000000004e-01 -5.0323630786030797e+00 , 2.3750588703508155e+00 , 1.2732063999999998e+00 , -1.1573200000000000e-01 , 2.0146700000000001e-01 , 9.7263400000000000e-01 -5.1152441708420184e+00 , 2.3861315988531757e+00 , 1.2826152799999999e+00 , 6.7715999999999998e-02 , -2.0094100000000001e-01 , -9.7726000000000002e-01 -5.2068677889572168e+00 , 2.3962164676972288e+00 , 1.2889811199999999e+00 , -5.3397600000000003e-02 , 2.0471600000000001e-01 , 9.7736400000000001e-01 -5.3072751710736608e+00 , 2.4074133676426683e+00 , 1.2921968000000001e+00 , 7.9977300000000001e-02 , -2.0271800000000001e-01 , -9.7596600000000000e-01 -5.3993710826299788e+00 , 2.4195655962637983e+00 , 1.3036430399999999e+00 , -6.3347899999999999e-02 , 1.9397700000000001e-01 , 9.7895900000000002e-01 -5.5102195030760068e+00 , 2.4325457976065712e+00 , 1.3074026400000001e+00 , -7.6307399999999997e-02 , 1.9123499999999999e-01 , 9.7857400000000005e-01 -5.6127187195675265e+00 , 2.4454634616037199e+00 , 1.3195956000000000e+00 , -6.4615900000000004e-02 , 1.8002599999999999e-01 , 9.8153699999999999e-01 -5.7338206593350076e+00 , 2.4583775652143820e+00 , 1.3252178400000001e+00 , -6.4511200000000005e-02 , 1.8347200000000000e-01 , 9.8090599999999994e-01 -5.8466339170739490e+00 , 2.4732862405535521e+00 , 1.3389655999999999e+00 , -5.8457500000000003e-02 , 1.9421200000000000e-01 , 9.7921599999999998e-01 -5.9789911382643002e+00 , 2.4883641147448445e+00 , 1.3471784800000002e+00 , -5.7767100000000005e-01 , 3.1150600000000001e-02 , 8.1567500000000004e-01 -6.0452620896259344e+00 , 2.5026977588826860e+00 , 1.3902999999999999e+00 , 9.8680400000000001e-01 , 4.7756800000000000e-03 , -1.6184699999999999e-01 -5.9693331680947868e+00 , 2.5130274774960020e+00 , 1.4991578400000001e+00 , 9.7147499999999998e-01 , 1.8855300000000000e-01 , 1.4381700000000000e-01 -5.9669552929630205e+00 , 2.5246532072132171e+00 , 1.5721616800000000e+00 , 9.9532100000000001e-01 , 8.8666599999999998e-02 , 3.8392000000000003e-02 -5.9526635890185435e+00 , 2.5363692650821852e+00 , 1.6483395999999999e+00 , 9.9911700000000003e-01 , 3.6817299999999997e-02 , 2.0266800000000001e-02 -5.9769943136376842e+00 , 2.5496207819397956e+00 , 1.7087615199999999e+00 , 9.9741599999999997e-01 , 6.3928899999999997e-02 , 3.2765000000000002e-02 -5.9507906559117743e+00 , 2.5592192899063981e+00 , 1.7877141599999999e+00 , 9.9451599999999996e-01 , 6.6339400000000007e-02 , -8.0856499999999998e-02 -5.9424087269687806e+00 , 2.5706254209171577e+00 , 1.8583457600000000e+00 , -9.3121600000000004e-01 , 3.0041900000000000e-02 , 3.6322900000000002e-01 -5.9822333296448225e+00 , 2.5839764395710638e+00 , 1.9120217200000000e+00 , 9.7161500000000001e-01 , 9.7613500000000006e-02 , -2.1548999999999999e-01 -5.9020288659128788e+00 , 2.5910561145854709e+00 , 2.0038362479999998e+00 , -9.7025700000000004e-01 , -6.5797300000000003e-02 , -2.3296400000000000e-01 -5.8886622993617408e+00 , 2.6011398307244562e+00 , 2.0721219199999998e+00 , 9.8306400000000005e-01 , 3.7953099999999997e-02 , -1.7928700000000000e-01 -5.9047007886294454e+00 , 2.6124249782642699e+00 , 2.1315454400000000e+00 , 9.5695900000000000e-01 , 2.5371999999999999e-02 , -2.8911399999999998e-01 -5.9207182649208461e+00 , 2.6248084036052006e+00 , 2.1911676000000000e+00 , -9.0101299999999995e-01 , 2.3618699999999999e-02 , 4.3314900000000001e-01 -5.9648408867853924e+00 , 2.6377912478796981e+00 , 2.2439309600000001e+00 , -8.2945700000000000e-01 , 2.1700700000000000e-02 , 5.5814900000000001e-01 -5.9883571616951450e+00 , 2.6506633148232535e+00 , 2.3023051199999998e+00 , -6.0222500000000001e-01 , 1.1973300000000001e-01 , 7.8929700000000003e-01 -6.1215414748140251e+00 , 2.6703508327898677e+00 , 2.3388465599999999e+00 , 2.9561599999999999e-01 , -1.6827900000000001e-01 , -9.4036900000000001e-01 -6.3164874855988007e+00 , 2.6965689225449294e+00 , 2.3682785599999998e+00 , -1.0758800000000000e-01 , 1.6613300000000000e-01 , 9.8021700000000000e-01 -6.5940999521001205e+00 , 2.7295790502971120e+00 , 2.3910857600000002e+00 , 4.3497899999999999e-02 , -1.6857400000000000e-01 , -9.8472899999999997e-01 -1.1689433512862960e+01 , 3.1836052141874287e+00 , 1.8687270400000000e+00 , 1.2483000000000000e-01 , -1.8516600000000000e-01 , -9.7474700000000003e-01 -1.2519198638198267e+01 , 3.2825582489711076e+00 , 1.9361650079999999e+00 , -5.4123600000000001e-02 , 1.9259100000000001e-01 , 9.7978500000000002e-01 -1.3586759220164838e+01 , 3.4085140454379079e+00 , 2.0090535327999999e+00 , -6.1279500000000001e-02 , 1.9156100000000001e-01 , 9.7956600000000005e-01 -1.4767458318891888e+01 , 3.5511242547588866e+00 , 2.1098052799999998e+00 , -4.8144199999999998e-02 , 1.8672000000000000e-01 , 9.8123300000000002e-01 -1.6555697254393635e+01 , 3.7584979140723940e+00 , 2.2136378400000001e+00 , -6.3284199999999999e-02 , 1.8913800000000000e-01 , 9.7990900000000003e-01 -1.8312342669576697e+01 , 3.9735816378158826e+00 , 2.3805661599999999e+00 , 7.9511399999999996e-02 , -1.8895300000000001e-01 , -9.7876200000000002e-01 -2.3168208083526334e+01 , 4.5743819768267686e+00 , 2.8835278400000002e+00 , -2.4190600000000001e-01 , 1.5165899999999999e-01 , 9.5837399999999995e-01 -2.6005030756477250e+01 , 4.9400796448452704e+00 , 3.2642759999999997e+00 , -5.8488399999999996e-01 , -4.2775000000000001e-02 , 8.0998899999999996e-01 -2.6684144328513192e+01 , 5.0836321769600987e+00 , 3.6895736000000001e+00 , -6.4218699999999995e-01 , -9.7517300000000001e-02 , 7.6032000000000000e-01 -2.6527936582153586e+01 , 5.1375810746790620e+00 , 4.1032232000000004e+00 , 6.1588200000000004e-01 , 1.0211300000000000e-01 , -7.8119300000000003e-01 -2.7766992214387233e+01 , 5.3514187444987336e+00 , 4.5962768000000001e+00 , 7.6888699999999999e-01 , 1.2389900000000000e-01 , -6.2726599999999999e-01 -3.1548804415793381e+01 , 5.8771378240952004e+00 , 5.3299864000000001e+00 , -5.0786399999999998e-01 , -5.2624999999999998e-02 , 8.5982800000000004e-01 -3.0326837833226826e+01 , 5.8962278708436422e+00 , 6.2127280000000003e+00 , -9.5465199999999995e-01 , -8.8771299999999997e-02 , 2.8418199999999999e-01 -2.5153319319728244e+01 , 5.3155674608272854e+00 , 6.0319551999999996e+00 , 5.2105999999999997e-01 , -1.9415399999999999e-01 , 8.3114399999999999e-01 -2.4835991933282166e+01 , 5.3414293574217409e+00 , 6.3877287999999997e+00 , 3.8526400000000000e-01 , -1.1937399999999999e-01 , 9.1505300000000001e-01 -2.2580817920913766e+01 , 5.1059258548208888e+00 , 6.4136144000000002e+00 , 3.8575900000000002e-01 , 6.0058199999999995e-01 , 7.0035099999999995e-01 -2.2218266353817317e+01 , 5.1172243962022694e+00 , 6.7084855999999995e+00 , -5.5270500000000000e-01 , -4.9629299999999998e-01 , -6.6948500000000000e-01 -3.0286264505619421e+01 , 6.3094399253227698e+00 , 8.6924832000000016e+00 , 8.5560300000000000e-01 , 5.1738799999999996e-01 , -1.5929599999999999e-02 -2.0507290030521247e+01 , 4.9930316485794224e+00 , 7.0498344000000008e+00 , 9.7847600000000000e-03 , -5.2520500000000003e-01 , 8.5091899999999998e-01 -2.1280579632051740e+01 , 5.1614557652454849e+00 , 7.5659864000000008e+00 , 9.7848099999999997e-03 , -5.2520500000000003e-01 , 8.5091899999999998e-01 -2.1143561281686974e+01 , 5.1997863204095385e+00 , 7.8798271999999994e+00 , 7.1834799999999999e-01 , 4.6491200000000003e-02 , -6.9412900000000000e-01 -2.2925169330018257e+01 , 5.5314806828651175e+00 , 8.7204696000000013e+00 , 7.5285299999999999e-01 , 6.1466200000000004e-01 , -2.3537700000000000e-01 -2.3339212497577833e+01 , 5.6608722179776123e+00 , 9.2296952000000001e+00 , -9.7143999999999997e-01 , -1.3097400000000001e-01 , -1.9786500000000001e-01 -2.3790366145555062e+01 , 5.7993102347379031e+00 , 9.7707240000000013e+00 , -8.8402899999999995e-01 , -6.1395199999999997e-02 , 4.6338200000000002e-01 -2.2132300835061780e+01 , 5.5994122175218308e+00 , 9.6316240000000004e+00 , 4.9600100000000003e-01 , 7.2758999999999996e-01 , 4.7391400000000000e-01 -2.3819578800852160e+01 , 5.9441622497829645e+00 , 1.0611855200000001e+01 , -9.4008400000000003e-01 , -2.1425100000000000e-01 , 2.6521400000000001e-01 -2.1925420089785522e+01 , 5.6960396333757384e+00 , 1.0330556000000000e+01 , 4.7354900000000000e-01 , 6.9647199999999998e-01 , 5.3914499999999999e-01 -2.3337507407066461e+01 , 6.0053597236660794e+00 , 1.1276467199999999e+01 , -3.0471199999999998e-01 , 9.4536699999999996e-01 , -1.1589400000000000e-01 -2.0460894060016397e+01 , 5.5710732596259547e+00 , 1.0515114400000000e+01 , 3.7495600000000001e-01 , 2.8311800000000002e-02 , 9.2661000000000004e-01 -2.0932883743473724e+01 , 5.7182257468297397e+00 , 1.1093250400000001e+01 , 4.6233800000000003e-01 , -4.8990299999999998e-01 , -7.3907999999999996e-01 -2.1886190781328253e+01 , 5.9576166663421359e+00 , 1.1915599200000001e+01 , -9.5397299999999996e-01 , -2.1212100000000000e-01 , 2.1199200000000001e-01 -1.3813166173333370e+01 , 4.5226976555744702e+00 , 8.4888095999999997e+00 , -1.3513600000000001e-02 , 4.8098299999999999e-01 , 8.7662600000000002e-01 -2.1432129568877805e+01 , 6.0125532716705914e+00 , 1.2528960000000001e+01 , -7.5698100000000001e-01 , -4.6312100000000000e-01 , -4.6097600000000000e-01 -2.1392968721778736e+01 , 6.0759160330558899e+00 , 1.2929776000000000e+01 , 1.8892400000000001e-01 , 3.0031600000000003e-01 , 9.3494299999999997e-01 -2.3894830150663910e+01 , 6.6424112777376543e+00 , 1.4715456000000000e+01 , 2.1068300000000001e-01 , -7.2011499999999995e-01 , 6.6109600000000002e-01 -2.3921421334314534e+01 , 6.7310956739062950e+00 , 1.5224536000000001e+01 , -5.0952399999999998e-01 , 7.1915300000000004e-01 , -4.7244500000000000e-01 -2.3785812885626495e+01 , 6.7886451113876012e+00 , 1.5650000000000000e+01 , 8.2222899999999999e-01 , -2.7994900000000000e-01 , 4.9554799999999999e-01 -2.2717150541655556e+01 , 6.6508495413967790e+00 , 1.5507416000000001e+01 , -1.6879400000000000e-01 , -3.3644599999999997e-02 , -9.8507699999999998e-01 -2.5578282633113563e+01 , 7.3462969052152038e+00 , 1.7830568000000000e+01 , -1.3444100000000000e-01 , 9.8687199999999997e-01 , 8.9495699999999997e-02 -2.3440252547521482e+01 , 6.9778647451066087e+00 , 1.6994928000000002e+01 , -6.7240100000000003e-01 , 7.0367199999999996e-01 , -2.2961400000000001e-01 -2.2874223054235436e+01 , 6.9433681696638718e+00 , 1.7145727999999998e+01 , -7.3962300000000003e-01 , 4.7561500000000001e-01 , -4.7617999999999999e-01 -2.3083251566405664e+01 , 7.0816589732626261e+00 , 1.7834520000000001e+01 , 4.7598400000000002e-01 , -6.0337799999999997e-01 , 6.3982399999999995e-01 -2.2682573011906435e+01 , 7.0826438244304226e+00 , 1.8096392000000002e+01 , 3.7999100000000002e-01 , -6.1932399999999999e-01 , 6.8705499999999997e-01 -2.2498133138377852e+01 , 7.1340023085295563e+00 , 1.8517592000000000e+01 , -3.9015300000000003e-01 , -4.5002599999999998e-01 , 8.0327899999999997e-01 -6.2841921327218282e+00 , 3.3470709172771835e+00 , 6.2541615999999998e+00 , -1.6984400000000000e-02 , -6.6234700000000002e-01 , 7.4900500000000003e-01 -6.1182721708931265e+00 , 3.3244997896801420e+00 , 6.2279327999999996e+00 , 9.4292500000000001e-02 , -8.1044099999999997e-01 , 5.7818199999999997e-01 -5.9539877942326784e+00 , 3.3019217039954376e+00 , 6.1967639999999999e+00 , -8.0602399999999996e-01 , 5.5405499999999996e-01 , -2.0820300000000000e-01 -6.1831852685570299e+00 , 3.3807623364493420e+00 , 6.5210360000000005e+00 , 2.9287099999999999e-01 , 5.8640700000000001e-01 , 7.5521799999999994e-01 -5.9284715734895279e+00 , 3.3338843381764121e+00 , 6.4026736000000000e+00 , -8.8043199999999999e-01 , 4.4135200000000002e-01 , -1.7334300000000000e-01 -5.9702097272327626e+00 , 3.3656448040228781e+00 , 6.5639464000000007e+00 , -7.7571299999999999e-01 , 4.8404599999999998e-01 , -4.0493000000000001e-01 -5.9493245533862407e+00 , 3.3813576513299393e+00 , 6.6690904000000000e+00 , -8.0927000000000004e-01 , 3.3253400000000000e-01 , -4.8425600000000002e-01 -6.1789477938124513e+00 , 3.4679917407175100e+00 , 7.0426896000000001e+00 , -6.7600199999999999e-01 , -6.2429499999999999e-02 , -7.3424999999999996e-01 -5.8119302073021970e+00 , 3.3857368203634466e+00 , 6.7827311999999997e+00 , -8.0957000000000001e-01 , 2.4050400000000000e-01 , -5.3549400000000003e-01 -5.6989820071239787e+00 , 3.3746347344542622e+00 , 6.7878480000000003e+00 , -9.6403799999999995e-01 , 1.8653400000000001e-01 , -1.8930100000000000e-01 -5.7308400476503714e+00 , 3.4071842941607953e+00 , 6.9614864000000010e+00 , -9.3241200000000002e-01 , 3.5124699999999998e-01 , -8.5055099999999995e-02 -5.7443663955308164e+00 , 3.4356782670325368e+00 , 7.1216048000000001e+00 , 8.7012500000000004e-01 , 2.0143100000000001e-02 , 4.9242000000000002e-01 -5.6340403325955588e+00 , 3.4253560243182872e+00 , 7.1311520000000002e+00 , -8.5039100000000001e-01 , -1.3127500000000000e-01 , -5.0951100000000005e-01 -5.6602478140228651e+00 , 3.4595541732550794e+00 , 7.3170311999999997e+00 , -9.6704500000000004e-01 , -1.9336999999999999e-01 , -1.6562499999999999e-01 -5.5300876865373656e+00 , 3.4424322084792718e+00 , 7.2991328000000006e+00 , -1.4475800000000000e-01 , -8.9398800000000000e-01 , -4.2406300000000002e-01 -5.4310333602791498e+00 , 3.4349254361064392e+00 , 7.3197871999999995e+00 , 2.8571600000000003e-01 , 1.8340300000000001e-01 , 9.4060100000000002e-01 -5.3142827455488444e+00 , 3.4215372369829837e+00 , 7.3127464000000000e+00 , 6.5057299999999996e-01 , -9.8810800000000004e-02 , 7.5298799999999999e-01 -5.5284840057395606e+00 , 3.5279235819262125e+00 , 7.8074432000000007e+00 , 3.4726800000000002e-01 , -4.7740899999999997e-01 , -8.0714699999999995e-01 -5.2914983949527787e+00 , 3.4704898381625449e+00 , 7.6193696000000006e+00 , 7.1158100000000002e-01 , 3.0001000000000000e-01 , 6.3533099999999998e-01 -5.2373419892426725e+00 , 3.4810404511036408e+00 , 7.7128968000000002e+00 , 1.1028499999999999e-01 , 6.0371300000000006e-01 , 7.8953600000000002e-01 -4.9910540799344165e+00 , 3.4148447705325449e+00 , 7.4793544000000001e+00 , 1.2487600000000000e-01 , 4.6942400000000001e-01 , 8.7409800000000004e-01 -4.9866666675574969e+00 , 3.4446025404418048e+00 , 7.6577352000000003e+00 , -8.4698099999999998e-01 , -4.5048700000000003e-01 , -2.8228599999999998e-01 -4.9475946621044038e+00 , 3.4620363670920806e+00 , 7.7833671999999998e+00 , 7.7301600000000004e-01 , -5.1048899999999997e-01 , 3.7662600000000002e-01 -4.8406875729480170e+00 , 3.4503952397259399e+00 , 7.7818280000000000e+00 , -5.1002499999999995e-01 , -8.1672400000000001e-01 , -2.6988099999999998e-01 -4.8412116228933950e+00 , 3.4865477557417353e+00 , 7.9982728000000005e+00 , 6.6196900000000003e-01 , 7.3144500000000001e-01 , -1.6366200000000000e-01 -4.7065582837341209e+00 , 3.4622764569158031e+00 , 7.9386600000000005e+00 , -2.2260900000000000e-01 , -9.1933500000000001e-01 , 3.2445200000000002e-01 -4.5702517462331151e+00 , 3.4355339384166546e+00 , 7.8664319999999996e+00 , -2.2382700000000000e-01 , -1.0329300000000000e-01 , -9.6914000000000000e-01 -4.4973724197705351e+00 , 3.4391429105649296e+00 , 7.9320351999999996e+00 , -2.7901799999999999e-01 , 5.7160299999999997e-01 , -7.7163400000000004e-01 -4.4152964120400968e+00 , 3.4380755692701777e+00 , 7.9777432000000008e+00 , 4.6355800000000003e-01 , -5.7776600000000000e-01 , 6.7178899999999997e-01 -4.3569430102485160e+00 , 3.4502234875704585e+00 , 8.0888360000000006e+00 , 3.7416199999999999e-01 , -8.0203400000000002e-01 , 4.6555900000000000e-01 -4.5062041440699971e+00 , 3.5830862261987302e+00 , 8.7853864000000002e+00 , -7.9787100000000000e-01 , -6.0056600000000004e-01 , 5.2173700000000003e-02 -4.1586047785592237e+00 , 3.4306365286894906e+00 , 8.0968648000000005e+00 , 9.2467499999999994e-02 , 2.6114599999999999e-01 , 9.6086000000000005e-01 -4.0658653108558305e+00 , 3.4239100387387320e+00 , 8.1174672000000001e+00 , 9.2467400000000005e-02 , 2.6114599999999999e-01 , 9.6086000000000005e-01 -3.9652854131418636e+00 , 3.4123078259632327e+00 , 8.1069320000000005e+00 , -4.2380500000000002e-02 , 5.3129499999999996e-01 , 8.4612600000000004e-01 -3.7793086317685751e+00 , 3.3383881511811122e+00 , 7.7899504000000004e+00 , 7.6675099999999996e-01 , 1.4501700000000001e-01 , 6.2534999999999996e-01 -3.7547476457875786e+00 , 3.3783067508314168e+00 , 8.0408192000000014e+00 , -6.2981100000000001e-01 , 3.9745200000000003e-01 , -6.6736099999999998e-01 -3.6649646864744376e+00 , 3.3710770374591381e+00 , 8.0542872000000010e+00 , 5.5278899999999999e-02 , -5.5150900000000003e-01 , 8.3233500000000005e-01 -3.7971761071731036e+00 , 3.5528705997558108e+00 , 9.0533320000000010e+00 , -4.0501999999999999e-01 , -1.9148399999999999e-01 , -8.9403200000000005e-01 -3.5360087448230164e+00 , 3.4028232984515268e+00 , 8.3266112000000003e+00 , -1.2240700000000000e-01 , -8.9563999999999999e-01 , 4.2760399999999998e-01 -3.3838250633453919e+00 , 3.3377731971640046e+00 , 8.0345480000000009e+00 , 5.5012499999999998e-01 , 5.6517800000000000e-02 , -8.3316699999999999e-01 -3.5296350787413515e+00 , 3.5868085011935937e+00 , 9.4229272000000002e+00 , -7.1509199999999995e-01 , 6.1707400000000001e-01 , -3.2842500000000002e-01 -3.3912878251116823e+00 , 3.5461576340007781e+00 , 9.2707024000000011e+00 , -6.4872500000000000e-01 , -7.2457800000000006e-01 , -2.3268500000000000e-01 -3.3123532060192229e+00 , 3.5788530781398080e+00 , 9.5109840000000005e+00 , -4.4229999999999998e-02 , -4.9269600000000002e-01 , 8.6907699999999999e-01 -3.1324477604830081e+00 , 3.4665544884730810e+00 , 8.9574128000000002e+00 , -7.5068699999999999e-01 , 6.4300199999999996e-01 , -1.5171699999999999e-01 -3.0027927964140946e+00 , 3.4096684909231678e+00 , 8.7053376000000000e+00 , 1.9438400000000000e-01 , -9.7158199999999995e-01 , -1.3507000000000000e-01 -2.8093207311408861e+00 , 3.1941223122128610e+00 , 7.5415255999999999e+00 , 7.4761500000000003e-01 , 4.1227399999999997e-01 , -5.2067399999999997e-01 -2.7208234142005043e+00 , 3.1578887505991968e+00 , 7.3849640000000001e+00 , -3.2258999999999999e-01 , 8.1291699999999995e-02 , 9.4304200000000005e-01 -2.6446039872667164e+00 , 3.1505444510329639e+00 , 7.3902160000000006e+00 , -2.4922300000000000e-01 , -6.3070300000000001e-01 , -7.3491600000000001e-01 -2.5698045067286421e+00 , 3.1521406255103428e+00 , 7.4454191999999999e+00 , 6.1702500000000005e-01 , 6.6252599999999995e-01 , 4.2466500000000001e-01 -2.5055396809563382e+00 , 3.3596039904156316e+00 , 8.7196999999999996e+00 , -8.4329200000000004e-01 , -4.7451100000000002e-01 , 2.5238400000000000e-01 -2.4105077106633290e+00 , 3.2567000242744815e+00 , 8.1675639999999987e+00 , -2.1341299999999999e-01 , -8.4265599999999996e-01 , 4.9435499999999999e-01 -2.3198945590264946e+00 , 3.2509064850136813e+00 , 8.1880103999999996e+00 , -3.3166000000000001e-01 , -4.7831600000000002e-01 , 8.1315199999999999e-01 -2.2328587110812110e+00 , 3.2303028299936836e+00 , 8.1251320000000007e+00 , 3.5192499999999999e-01 , 4.8153800000000002e-01 , 8.0266499999999996e-01 -2.1567754416791822e+00 , 3.1874385867201962e+00 , 7.9172047999999995e+00 , 6.3480800000000004e-01 , 5.0720500000000002e-02 , -7.7100400000000002e-01 -2.0762557405416731e+00 , 3.1701295635126372e+00 , 7.8615751999999999e+00 , 1.2051300000000000e-01 , -5.1993299999999998e-01 , 8.4566300000000005e-01 -1.8013055114330341e+00 , 3.4732655225363960e+00 , 9.8397800000000011e+00 , -7.2123099999999996e-01 , -6.8255900000000003e-01 , -1.1806100000000000e-01 -1.7488212230999434e+00 , 3.3678973559493315e+00 , 9.2476248000000005e+00 , -9.6554899999999999e-01 , 1.9924900000000001e-01 , -1.6737900000000000e-01 -4.8422908436796162e+00 , 2.2888867616140893e+00 , 1.2634678400000001e+00 , -7.2714100000000004e-02 , 1.8592200000000000e-01 , 9.7987000000000002e-01 -4.9246577845041379e+00 , 2.2957952973874023e+00 , 1.2679024000000001e+00 , -8.3360299999999998e-02 , 1.8046000000000001e-01 , 9.8004400000000003e-01 -4.9976801411424461e+00 , 2.3036778871023045e+00 , 1.2804406399999999e+00 , 7.6241600000000007e-02 , -1.9686300000000001e-01 , -9.7746200000000005e-01 -5.0795505945306658e+00 , 2.3114652235538102e+00 , 1.2891246400000000e+00 , -1.0096300000000000e-01 , 1.6980799999999999e-01 , 9.8029200000000005e-01 -5.1712433053080975e+00 , 2.3192200125250637e+00 , 1.2944837599999999e+00 , -9.7137100000000004e-02 , 2.1344099999999999e-01 , 9.7211499999999995e-01 -5.2546349448339189e+00 , 2.3279311770638067e+00 , 1.3080734400000000e+00 , -5.8245699999999997e-02 , 1.8779000000000001e-01 , 9.8048100000000005e-01 -5.3558101057559213e+00 , 2.3362827744945509e+00 , 1.3131444800000001e+00 , -5.1965699999999997e-02 , 1.8885099999999999e-01 , 9.8063000000000000e-01 -5.4576729259212549e+00 , 2.3452205125147976e+00 , 1.3212752000000001e+00 , -5.6875599999999998e-02 , 1.9580600000000001e-01 , 9.7899199999999997e-01 -5.5602754637387948e+00 , 2.3557439379220826e+00 , 1.3321588000000000e+00 , -7.4045100000000003e-02 , 1.8366099999999999e-01 , 9.8019699999999998e-01 -5.6725073601755387e+00 , 2.3655112700354106e+00 , 1.3413409600000001e+00 , 5.7395900000000000e-02 , -1.7335100000000001e-01 , -9.8318600000000000e-01 -5.7943532493933052e+00 , 2.3756452767402405e+00 , 1.3491211999999999e+00 , -6.9989800000000005e-02 , 1.9151799999999999e-01 , 9.7899000000000003e-01 -5.9168313495982048e+00 , 2.3875288798219945e+00 , 1.3604634400000000e+00 , -2.2607600000000000e-01 , 1.7519299999999999e-01 , 9.5822600000000002e-01 -6.0488172518621646e+00 , 2.3988896089080614e+00 , 1.3712170399999999e+00 , 9.7592199999999996e-01 , 1.6373599999999999e-01 , -1.4410899999999999e-01 -6.0404220950638434e+00 , 2.4109891744733702e+00 , 1.4505763200000001e+00 , 9.7592199999999996e-01 , 1.6373599999999999e-01 , -1.4410899999999999e-01 -6.0102080697215312e+00 , 2.4233582523285908e+00 , 1.5371428000000000e+00 , 9.8059200000000002e-01 , 1.0857200000000000e-01 , 1.6325000000000001e-01 -5.9879847848795844e+00 , 2.4353595950315432e+00 , 1.6183116799999999e+00 , 9.9615399999999998e-01 , 4.6970699999999997e-02 , 7.3969099999999996e-02 -5.9736932875512112e+00 , 2.4470746336312703e+00 , 1.6944896000000000e+00 , 9.9980999999999998e-01 , 1.5823500000000001e-02 , 1.1412600000000000e-02 -5.9672366847391283e+00 , 2.4575679524247409e+00 , 1.7662849599999999e+00 , 9.9733000000000005e-01 , 1.4732400000000000e-03 , -7.3006199999999993e-02 -5.9697159805656632e+00 , 2.4689462815044485e+00 , 1.8338184000000000e+00 , -9.4699699999999998e-01 , -1.0131200000000000e-01 , 3.0484800000000001e-01 -5.9908504713092459e+00 , 2.4813185584567257e+00 , 1.8944743200000000e+00 , -9.2019600000000001e-01 , -7.1879200000000004e-02 , 3.8480199999999998e-01 -6.0599548011371409e+00 , 2.4938718596712701e+00 , 1.9399011040000000e+00 , 9.8047799999999996e-01 , 8.5899199999999995e-02 , 1.7687600000000001e-01 -5.8993249226782920e+00 , 2.5006931202795175e+00 , 2.0554269039999999e+00 , 9.8480800000000002e-01 , 3.3001400000000000e-02 , -1.7048099999999999e-01 -5.9261554910363223e+00 , 2.5120298307762825e+00 , 2.1121577600000001e+00 , 9.7424699999999997e-01 , 1.1186300000000000e-02 , -2.2520599999999999e-01 -5.9313143059410969e+00 , 2.5222821325402700e+00 , 2.1746815200000000e+00 , -9.1477900000000001e-01 , -1.5397700000000000e-02 , 4.0366000000000002e-01 -5.9569904107289942e+00 , 2.5338697683319631e+00 , 2.2323994400000000e+00 , -8.9538399999999996e-01 , 1.1089699999999999e-02 , 4.4515800000000000e-01 -6.0106732455335425e+00 , 2.5461758842005069e+00 , 2.2838638400000000e+00 , -7.9915099999999994e-01 , 5.3875300000000001e-02 , 5.9871099999999999e-01 -6.0641816311614818e+00 , 2.5588191019622228e+00 , 2.3369475199999998e+00 , 4.6760000000000002e-01 , -1.2115700000000000e-01 , -8.7559799999999999e-01 -6.2087364081368372e+00 , 2.5760713592957671e+00 , 2.3743708799999999e+00 , 1.8843599999999999e-01 , -1.6986000000000001e-01 , -9.6728499999999995e-01 -6.4245175109207429e+00 , 2.5982879390471751e+00 , 2.4041991199999999e+00 , -9.6969399999999997e-02 , 1.6752300000000001e-01 , 9.8108799999999996e-01 -6.8049910042326438e+00 , 2.6290297018852651e+00 , 2.4166167199999999e+00 , -3.6371199999999999e-02 , 1.6922100000000001e-01 , 9.8490699999999998e-01 -1.1559443991653922e+01 , 2.9001834370661141e+00 , 1.8519705600000000e+00 , -1.6704400000000000e-01 , 1.9004199999999999e-01 , 9.6746100000000002e-01 -1.2052104379861952e+01 , 2.9546821321978003e+00 , 1.9535250000000000e+00 , -1.1888799999999999e-01 , 1.8585399999999999e-01 , 9.7535799999999995e-01 -1.3039789329641170e+01 , 3.0418087723053286e+00 , 2.0222395679999998e+00 , -5.0702100000000000e-02 , 1.8974099999999999e-01 , 9.8052399999999995e-01 -1.4098665584312858e+01 , 3.1388885412328404e+00 , 2.1186723199999999e+00 , -6.5964599999999998e-02 , 1.8973699999999999e-01 , 9.7961699999999996e-01 -1.5664948983787777e+01 , 3.2743598222773849e+00 , 2.2187796000000000e+00 , -4.2298799999999998e-02 , 1.8829099999999999e-01 , 9.8120200000000002e-01 -1.7292288665895260e+01 , 3.4237677185685502e+00 , 2.3696076800000001e+00 , -7.4635699999999999e-02 , 1.8884699999999999e-01 , 9.7916599999999998e-01 -1.9372276526112277e+01 , 3.6152487878082828e+00 , 2.5622115200000000e+00 , -6.7955500000000002e-02 , 1.8510199999999999e-01 , 9.8036699999999999e-01 -2.2724938115567252e+01 , 3.9128308510613046e+00 , 2.8098011999999999e+00 , -9.3811099999999994e-02 , 1.8302900000000000e-01 , 9.7862099999999996e-01 -2.7025408747647560e+01 , 4.3717062302929994e+00 , 3.6017976000000003e+00 , 5.1057699999999995e-01 , 3.7570300000000001e-02 , -8.5901099999999997e-01 -2.7773179920289831e+01 , 4.5042604887422879e+00 , 4.0556327999999997e+00 , -8.2334799999999997e-01 , -1.8108399999999999e-01 , 5.3787200000000002e-01 -2.7632730882948781e+01 , 4.5642265003066207e+00 , 4.4866919999999997e+00 , -7.7020500000000003e-01 , -2.8937299999999999e-01 , 5.6837300000000002e-01 -2.7722676824204878e+01 , 4.6445156375307519e+00 , 4.9307616000000003e+00 , -7.7020500000000003e-01 , -2.8937299999999999e-01 , 5.6837300000000002e-01 -2.8011378356149560e+01 , 4.7431180614230328e+00 , 5.3974720000000005e+00 , 8.5209900000000005e-01 , 8.1424399999999994e-02 , -5.1700900000000005e-01 -3.1162283062030355e+01 , 5.1136211859313434e+00 , 6.1854072000000002e+00 , -5.5750800000000000e-01 , 7.2277800000000003e-01 , -4.0838400000000002e-01 -2.5252529546255310e+01 , 4.6219897120736153e+00 , 5.9466960000000002e+00 , -2.6331900000000003e-01 , -2.8349000000000002e-01 , -9.2211500000000002e-01 -2.4067461063294985e+01 , 4.5700340963967641e+00 , 6.1791568000000003e+00 , -2.5050099999999997e-01 , -1.2691600000000000e-01 , -9.5976099999999998e-01 -2.4086569173432633e+01 , 4.6354331181601491e+00 , 6.5657871999999999e+00 , -3.3567700000000000e-01 , -9.2461600000000005e-02 , -9.3742800000000004e-01 -2.3079890221070983e+01 , 4.5918048231464104e+00 , 6.7721232000000002e+00 , 3.8575900000000002e-01 , 6.0058199999999995e-01 , 7.0035099999999995e-01 -2.2408327969071301e+01 , 4.5795619577500304e+00 , 7.0107303999999999e+00 , -1.8275100000000000e-01 , 5.0794399999999995e-01 , 8.4178100000000000e-01 -2.3110249140636984e+01 , 4.7173915832876965e+00 , 7.5231904000000007e+00 , -6.5522700000000000e-01 , 4.2383100000000001e-01 , 6.2533600000000000e-01 -2.3446489986677662e+01 , 4.8191364505481520e+00 , 7.9787103999999998e+00 , -7.2883299999999995e-01 , -5.7820400000000005e-01 , 3.6671900000000002e-01 -2.3463075402678530e+01 , 4.8844167232810261e+00 , 8.3694488000000007e+00 , -9.2463799999999996e-01 , -3.5950500000000002e-01 , 1.2570400000000001e-01 -2.6842220953482411e+01 , 5.3575868075611925e+00 , 9.6735360000000004e+00 , 2.7475400000000000e-01 , -9.2390300000000003e-01 , -2.6629399999999998e-01 -2.3472227953274306e+01 , 5.0141090666133596e+00 , 9.1574671999999993e+00 , -9.4915300000000002e-01 , 1.3104600000000000e-01 , -2.8624500000000003e-01 -2.6268035607117344e+01 , 5.4355649604879641e+00 , 1.0417572799999999e+01 , 9.2576900000000004e-02 , -9.6194500000000005e-01 , -2.5708399999999998e-01 -2.3177527205415704e+01 , 5.1084283727994135e+00 , 9.8630864000000003e+00 , -6.0877100000000003e-02 , 1.1868500000000000e-01 , -9.9106399999999994e-01 -2.7593229820226263e+01 , 5.7647020362592496e+00 , 1.1796415200000000e+01 , -8.6787099999999995e-01 , 4.7252899999999998e-01 , -1.5334700000000001e-01 -2.1938893733733256e+01 , 5.0720627587428471e+00 , 1.0219431999999999e+01 , -7.3240600000000000e-01 , -5.6615700000000002e-01 , -3.7821700000000003e-01 -1.9669426443187557e+01 , 4.8175546329546819e+00 , 9.7315471999999996e+00 , -2.8170000000000001e-02 , -5.9960700000000000e-01 , 7.9979800000000001e-01 -2.2096415033084295e+01 , 5.2231209975148873e+00 , 1.1066064800000001e+01 , 9.9468299999999998e-01 , -9.8031199999999999e-02 , 3.1553299999999999e-02 -2.0213323060991133e+01 , 5.0130609193773701e+00 , 1.0665113600000000e+01 , 8.6736599999999997e-01 , -4.5789900000000000e-01 , -1.9494900000000001e-01 -2.1371183231181718e+01 , 5.2484467496687781e+00 , 1.1553460800000000e+01 , 9.6785600000000005e-01 , -1.3247300000000001e-01 , -2.1378900000000001e-01 -2.2193782364847010e+01 , 5.4405955930796850e+00 , 1.2340116800000001e+01 , 9.9860800000000005e-01 , -5.1338399999999999e-02 , 1.2126400000000001e-02 -2.2392949763948881e+01 , 5.5416815969652387e+00 , 1.2863216000000000e+01 , 7.6126899999999997e-01 , -1.9929300000000000e-01 , -6.1705100000000002e-01 -2.3266834940338207e+01 , 5.7546100121394943e+00 , 1.3748152000000001e+01 , 1.9433100000000000e-01 , 9.8038300000000000e-01 , -3.2922500000000000e-02 -2.3061862887372069e+01 , 5.7968020227033179e+00 , 1.4103624000000000e+01 , 2.1279900000000001e-02 , -9.9620600000000004e-01 , -8.4383200000000005e-02 -2.2329538837181655e+01 , 5.7513713856597288e+00 , 1.4164568000000001e+01 , -8.6499800000000004e-01 , 4.6972300000000000e-01 , -1.7646300000000001e-01 -2.2127063662400975e+01 , 5.7922390506013617e+00 , 1.4508704000000000e+01 , 7.6587400000000005e-01 , 4.4241599999999998e-01 , 4.6658899999999998e-01 -2.1979381794463492e+01 , 5.8428662051724194e+00 , 1.4886536000000001e+01 , 9.7968200000000005e-01 , -1.8524499999999999e-01 , -7.6858899999999994e-02 -1.1276700579870482e+01 , 3.9943642405339190e+00 , 8.6296776000000008e+00 , 4.0562200000000000e-02 , 3.8409199999999999e-01 , 9.2240299999999997e-01 -2.2291536914702544e+01 , 6.0581948589736605e+00 , 1.6048216000000000e+01 , 9.9589200000000000e-01 , -8.6436700000000005e-02 , -2.6971700000000001e-02 -2.3441052538452432e+01 , 6.3577788773937023e+00 , 1.7332616000000002e+01 , -6.4911099999999999e-01 , 7.2016500000000006e-01 , -2.4498500000000001e-01 -2.2568840937650751e+01 , 6.2795052898870933e+00 , 1.7263871999999999e+01 , 4.9858300000000000e-01 , -8.0745100000000003e-01 , 3.1533800000000001e-01 -2.2427123180246383e+01 , 6.3399717819750379e+00 , 1.7697136000000000e+01 , -4.3878200000000001e-01 , 6.6720800000000002e-01 , -6.0191700000000004e-01 -6.2587614061679595e+00 , 3.1894250706384701e+00 , 6.0776216000000005e+00 , 2.6039100000000001e-03 , -6.9650199999999995e-01 , 7.1755000000000002e-01 -6.2276501487741918e+00 , 3.2015613352375407e+00 , 6.1628496000000004e+00 , 8.8138300000000003e-02 , -7.0025899999999996e-01 , 7.0842700000000003e-01 -5.9837990329770570e+00 , 3.1676835776037899e+00 , 6.0691560000000004e+00 , 7.4335399999999996e-01 , -1.5330400000000000e-01 , 6.5109399999999995e-01 -6.0072966427489058e+00 , 3.1905415496183047e+00 , 6.1981576000000000e+00 , -7.9768799999999995e-01 , 5.8182699999999998e-01 , -1.5865399999999999e-01 -5.8218728043114769e+00 , 3.1671323339440489e+00 , 6.1425384000000003e+00 , 9.6450599999999997e-01 , -9.1194100000000000e-02 , 2.4781500000000001e-01 -5.9762160450515616e+00 , 3.2204296808096355e+00 , 6.3978376000000008e+00 , -9.0707899999999997e-01 , 2.6796100000000000e-01 , -3.2466099999999998e-01 -5.9165238582931048e+00 , 3.2267754876595163e+00 , 6.4587712000000002e+00 , -7.6417400000000002e-01 , 5.0629599999999997e-01 , -3.9962799999999998e-01 -5.8838792884902391e+00 , 3.2387282727335416e+00 , 6.5480136000000009e+00 , -6.9448200000000004e-01 , 6.4202300000000001e-01 , -3.2480900000000001e-01 -5.8212006472804543e+00 , 3.2438404930754947e+00 , 6.6074600000000006e+00 , -6.1492899999999995e-01 , 6.5534800000000004e-01 , -4.3861299999999998e-01 -5.8273477245513430e+00 , 3.2662830864921593e+00 , 6.7412352000000002e+00 , 6.2068699999999999e-01 , -6.1574099999999998e-01 , 4.8539700000000002e-01 -5.7069705498300953e+00 , 3.2560753996155123e+00 , 6.7386663999999996e+00 , -9.4381599999999999e-01 , 2.5378800000000001e-01 , -2.1166900000000000e-01 -5.7548675559079374e+00 , 3.2909561994687948e+00 , 6.9272808000000001e+00 , -9.8503700000000005e-01 , -1.1143000000000000e-01 , 1.3147600000000001e-01 -5.7971711781058683e+00 , 3.3255807373109239e+00 , 7.1187136000000004e+00 , 9.2855699999999997e-01 , 3.2054700000000003e-01 , 1.8716900000000000e-01 -5.7113896974129261e+00 , 3.3260416148128571e+00 , 7.1606775999999996e+00 , -9.4640000000000002e-01 , -1.7218000000000000e-01 , -2.7327800000000002e-01 -5.7194494518795196e+00 , 3.3540726349979986e+00 , 7.3225952000000003e+00 , -9.0175799999999995e-01 , -3.0642599999999998e-01 , -3.0485299999999999e-01 -5.6986701019027208e+00 , 3.3738700864002196e+00 , 7.4533231999999998e+00 , 9.9045200000000000e-01 , 1.3631900000000000e-01 , -2.0530500000000000e-02 -5.5909098860034678e+00 , 3.3676939243762387e+00 , 7.4681847999999995e+00 , -4.3416600000000000e-01 , -7.0064899999999997e-01 , -5.6620800000000004e-01 -5.4422217717238563e+00 , 3.3487410811908047e+00 , 7.4214368000000004e+00 , 6.5859800000000002e-01 , 6.4995899999999995e-01 , 3.7921199999999999e-01 -5.4269842731212421e+00 , 3.3713523372530618e+00 , 7.5673072000000001e+00 , -4.7814899999999999e-01 , 1.4034000000000000e-02 , -8.7816700000000003e-01 -5.2967901743926937e+00 , 3.3568583275714374e+00 , 7.5413696000000003e+00 , 5.4695899999999997e-01 , -1.2685900000000000e-01 , 8.2749200000000001e-01 -5.2385145420335455e+00 , 3.3667904070215813e+00 , 7.6256719999999998e+00 , 6.6507399999999994e-02 , -6.1133800000000005e-01 , 7.8856999999999999e-01 -5.2201551769726482e+00 , 3.3901971405519280e+00 , 7.7800912000000002e+00 , -1.3948199999999999e-01 , -5.5561400000000005e-01 , 8.1965699999999997e-01 -5.0456968857114992e+00 , 3.3591261167408959e+00 , 7.6676983999999999e+00 , -7.7100299999999999e-01 , -5.9566500000000000e-01 , 2.2525000000000001e-01 -5.2563697771529858e+00 , 3.4710877373494045e+00 , 8.2525528000000001e+00 , -9.7808499999999998e-01 , 6.6606100000000001e-02 , 1.9726500000000000e-01 -5.0550332543985856e+00 , 3.4294386155824612e+00 , 8.0924656000000006e+00 , 5.7707200000000003e-01 , -6.7615000000000003e-01 , -4.5804800000000001e-01 -5.0478970170280855e+00 , 3.4635958139341745e+00 , 8.3026391999999998e+00 , 9.9414299999999997e-02 , -9.8841000000000001e-01 , 1.1472900000000000e-01 -4.7665142690062190e+00 , 3.3835403115624887e+00 , 7.9506616000000010e+00 , 4.3628000000000000e-01 , 7.6926200000000000e-01 , 4.6679300000000001e-01 -4.9293629260627583e+00 , 3.4932939100937523e+00 , 8.5406952000000000e+00 , 7.8282700000000005e-01 , 1.0502200000000000e-01 , 6.1331199999999997e-01 -4.8030082990968985e+00 , 3.4803273734629876e+00 , 8.5178984000000000e+00 , 7.8282700000000005e-01 , 1.0502200000000000e-01 , 6.1331199999999997e-01 -4.5894561986555420e+00 , 3.4236103971459269e+00 , 8.2751415999999995e+00 , -7.0630499999999996e-01 , 4.2127399999999998e-01 , 5.6891300000000000e-01 -4.3521669142647683e+00 , 3.3505044827573638e+00 , 7.9407088000000003e+00 , 4.7581400000000001e-01 , -6.7068000000000005e-01 , 5.6902500000000000e-01 -4.3717370114530762e+00 , 3.4047775896203261e+00 , 8.2617048000000004e+00 , -1.8002099999999999e-01 , 9.2743500000000001e-01 , 3.2780799999999999e-01 -4.2153950537517311e+00 , 3.3685119389846268e+00 , 8.1115808000000005e+00 , 1.9577600000000001e-01 , -1.2226200000000000e-01 , 9.7299700000000000e-01 -4.1074344722214366e+00 , 3.3559431025776121e+00 , 8.0841248000000014e+00 , -5.5021100000000001e-01 , -2.7892000000000000e-01 , -7.8706500000000001e-01 -4.0209993543328473e+00 , 3.3557547000422203e+00 , 8.1227295999999996e+00 , 6.1450300000000001e-03 , 5.4426099999999999e-01 , 8.3889300000000000e-01 -3.8197851010630863e+00 , 3.2810988116589068e+00 , 7.7672160000000003e+00 , 4.1976900000000000e-01 , 1.1591200000000000e-01 , 9.0019899999999997e-01 -3.7853227934135769e+00 , 3.3115461680694751e+00 , 7.9689551999999999e+00 , 5.4508400000000001e-01 , -3.6734400000000000e-01 , 7.5361900000000004e-01 -3.7235535015983432e+00 , 3.3271963866139824e+00 , 8.0914256000000009e+00 , 2.1964700000000001e-01 , -5.9561799999999998e-01 , 7.7265399999999995e-01 -3.6279320553704446e+00 , 3.3191397005578729e+00 , 8.0837400000000006e+00 , -3.3066099999999998e-01 , 6.0381300000000004e-01 , -7.2530899999999998e-01 -3.7779369558083515e+00 , 3.5142921703087198e+00 , 9.2055879999999988e+00 , 5.1964100000000002e-01 , 5.1936599999999999e-01 , 6.7840500000000004e-01 -3.4383227659115168e+00 , 3.3008828687732974e+00 , 8.0633455999999999e+00 , 5.5012499999999998e-01 , 5.6517800000000000e-02 , -8.3316699999999999e-01 -3.3385119596277155e+00 , 3.2858530468983753e+00 , 8.0201544000000009e+00 , 2.9638600000000001e-02 , -7.9312600000000000e-01 , 6.0833599999999999e-01 -3.2334171191245922e+00 , 3.2626020533965234e+00 , 7.9244744000000003e+00 , -1.1507500000000000e-01 , -5.0177799999999995e-01 , 8.5730799999999996e-01 -3.1724266748911494e+00 , 3.2879159553498933e+00 , 8.1108943999999994e+00 , -2.8247100000000003e-01 , 7.9025100000000004e-01 , -5.4379500000000003e-01 -3.0856456253089481e+00 , 3.2876542455314093e+00 , 8.1437999999999988e+00 , 4.6267000000000003e-01 , -6.2022100000000002e-01 , 6.3345300000000004e-01 -3.0922403679338082e+00 , 3.4354088740210509e+00 , 9.0419544000000016e+00 , 8.5890800000000000e-01 , -4.7410900000000000e-01 , -1.9364200000000001e-01 -2.8765708228348088e+00 , 3.2192150265944770e+00 , 7.8279832000000003e+00 , 1.4820200000000000e-01 , 9.8090500000000003e-01 , 1.2594100000000000e-01 -2.7619572057578061e+00 , 3.1412612504612549e+00 , 7.4060656000000007e+00 , -2.7926699999999999e-01 , 9.6445900000000001e-02 , 9.5535800000000004e-01 -2.6839380625950557e+00 , 3.1321004738728688e+00 , 7.3913912000000002e+00 , 9.8749199999999995e-02 , 5.1436899999999997e-01 , 8.5186499999999998e-01 -2.6093034965048290e+00 , 3.1338096645937323e+00 , 7.4366520000000005e+00 , -5.6921299999999997e-01 , -6.2638799999999994e-01 , -5.3257399999999999e-01 -2.5377365952187780e+00 , 3.1701007619728188e+00 , 7.6858256000000003e+00 , -6.2219400000000002e-01 , -6.6321300000000005e-01 , -4.1596100000000003e-01 -2.4567083543756438e+00 , 3.2260386899214994e+00 , 8.0674223999999999e+00 , 7.1340199999999998e-01 , -1.0454800000000000e-01 , 6.9291199999999997e-01 -2.3664977586857452e+00 , 3.2399262375957032e+00 , 8.1908600000000007e+00 , -3.0159900000000001e-01 , -7.5055600000000000e-01 , 5.8796599999999999e-01 -2.2784550411995417e+00 , 3.2225778368352018e+00 , 8.1281479999999995e+00 , 2.0492099999999999e-01 , 1.4796899999999999e-01 , 9.6752899999999997e-01 -2.1985818358782998e+00 , 3.1892385137847219e+00 , 7.9614256000000001e+00 , -9.2090899999999998e-01 , -1.0983400000000000e-01 , 3.7398399999999998e-01 -2.1187146134956731e+00 , 3.1669151654348502e+00 , 7.8652152000000006e+00 , 5.3438800000000002e-02 , 4.3719800000000003e-02 , 9.9761400000000000e-01 -2.0239981875847719e+00 , 3.1797513862931224e+00 , 7.9824647999999998e+00 , -7.8299900000000000e-01 , 9.7266400000000003e-02 , -6.1437200000000003e-01 -1.7890284786994439e+00 , 3.3918907754727829e+00 , 9.3858512000000012e+00 , -8.7704700000000002e-01 , -4.4099200000000000e-01 , -1.9056300000000001e-01 -5.0518263327490587e+00 , 2.0712732551127933e+00 , 2.4914959999999997e-01 , 4.1637999999999997e-01 , 8.2998100000000005e-02 , -9.0539400000000003e-01 -5.2733945324003964e+00 , 2.1059822501130374e+00 , 4.0546159999999998e-01 , 4.1637999999999997e-01 , 8.2998100000000005e-02 , -9.0539400000000003e-01 -4.8787795693075626e+00 , 2.2294403417328388e+00 , 1.2818643999999999e+00 , -7.2784000000000001e-02 , 2.0187500000000000e-01 , 9.7670299999999999e-01 -4.9518187535831224e+00 , 2.2339943240466460e+00 , 1.2937027200000000e+00 , -6.5473699999999996e-02 , 1.9493900000000000e-01 , 9.7862800000000005e-01 -5.0519277710627399e+00 , 2.2384444212215064e+00 , 1.2897257600000001e+00 , -9.6870499999999998e-02 , 1.6759900000000000e-01 , 9.8108399999999996e-01 -5.1255265766757763e+00 , 2.2448967027311837e+00 , 1.3058353600000001e+00 , -9.1776499999999997e-02 , 1.9080900000000001e-01 , 9.7732799999999997e-01 -5.2180076582596904e+00 , 2.2498093022405810e+00 , 1.3130498399999999e+00 , -7.3185500000000001e-02 , 1.9674100000000000e-01 , 9.7772000000000003e-01 -5.3101714537543039e+00 , 2.2552401573424574e+00 , 1.3227936000000000e+00 , -5.7827099999999999e-02 , 2.1785299999999999e-01 , 9.7426699999999999e-01 -5.4121432423837792e+00 , 2.2618081468571822e+00 , 1.3297158400000000e+00 , -4.6298600000000002e-02 , 2.0887400000000000e-01 , 9.7684599999999999e-01 -5.5227303531912497e+00 , 2.2675970059275281e+00 , 1.3346069599999999e+00 , -6.9318199999999996e-02 , 1.9253300000000001e-01 , 9.7883900000000001e-01 -5.6260289143722773e+00 , 2.2743204022466252e+00 , 1.3478544800000001e+00 , -4.5317999999999997e-02 , 1.7973900000000001e-01 , 9.8267000000000004e-01 -5.7479301988292697e+00 , 2.2810402381792363e+00 , 1.3545302399999999e+00 , -6.3149100000000000e-02 , 1.8965299999999999e-01 , 9.7981799999999997e-01 -5.8615152605557448e+00 , 2.2887388459800801e+00 , 1.3695363999999999e+00 , -8.1781599999999996e-02 , 1.7655399999999999e-01 , 9.8088799999999998e-01 -5.9836415322513448e+00 , 2.2968615030018054e+00 , 1.3832176000000000e+00 , -2.6563700000000001e-01 , 8.6745400000000000e-02 , 9.6016299999999999e-01 -6.1262766303129723e+00 , 2.3052619317746403e+00 , 1.3920960800000000e+00 , -9.3412899999999999e-01 , -7.9090599999999997e-02 , -3.4806199999999998e-01 -6.0315083923680737e+00 , 2.3192750793478498e+00 , 1.5099457599999999e+00 , 9.9496600000000002e-01 , 1.7577400000000000e-02 , 9.8661600000000002e-02 -6.0290327900314375e+00 , 2.3310688227544722e+00 , 1.5837587200000001e+00 , 9.8261299999999996e-01 , 8.6345099999999994e-02 , 1.6436700000000001e-01 -6.0068140507437793e+00 , 2.3430477415341233e+00 , 1.6648267200000000e+00 , 9.8940200000000000e-01 , 1.0945400000000000e-01 , 9.5411200000000002e-02 -5.9914939853436024e+00 , 2.3547590814764487e+00 , 1.7407768799999999e+00 , 9.9580500000000005e-01 , 9.1189099999999995e-02 , -7.5600299999999997e-03 -6.0136236497027866e+00 , 2.3660957864107521e+00 , 1.8017635200000000e+00 , 9.8906300000000003e-01 , 7.4667700000000004e-02 , -1.2720100000000001e-01 -6.0061441259570216e+00 , 2.3766098966311624e+00 , 1.8734340800000000e+00 , 9.4283300000000003e-01 , -3.5417200000000003e-02 , -3.3137699999999998e-01 -6.0359721756663776e+00 , 2.3880788304044556e+00 , 1.9314518320000000e+00 , 9.9315900000000001e-01 , 8.4398799999999996e-02 , -8.0692200000000006e-02 -5.9460055554958116e+00 , 2.3983495528272041e+00 , 2.0264806879999999e+00 , -9.6051399999999998e-01 , -1.2905400000000000e-01 , -2.4649299999999999e-01 -5.9434506192122329e+00 , 2.4095923936376602e+00 , 2.0922732719999999e+00 , 9.7291499999999997e-01 , 9.4619400000000006e-02 , -2.1091099999999999e-01 -5.9603960592314547e+00 , 2.4199630964638232e+00 , 2.1526345600000001e+00 , 9.6610600000000002e-01 , 4.3931300000000000e-02 , -2.5437900000000002e-01 -5.9752265117041077e+00 , 2.4304547470318685e+00 , 2.2131490400000002e+00 , -9.2892399999999997e-01 , -3.7891700000000000e-02 , 3.6832700000000002e-01 -5.9997489871294594e+00 , 2.4411898787260515e+00 , 2.2716552800000001e+00 , -8.9020299999999997e-01 , 2.2797499999999998e-02 , 4.5499299999999998e-01 -6.0338464137415100e+00 , 2.4512279242520192e+00 , 2.3287616799999999e+00 , -6.7613900000000005e-01 , 1.3189300000000001e-01 , 7.2487299999999999e-01 -6.1580617476008435e+00 , 2.4635453907642528e+00 , 2.3689764000000002e+00 , 3.4360600000000002e-01 , -1.7391999999999999e-01 , -9.2286900000000005e-01 -6.3235483029565085e+00 , 2.4777325730664148e+00 , 2.4061855200000002e+00 , 1.1651000000000000e-01 , -1.6516000000000000e-01 , -9.7936100000000004e-01 -6.6016137726190811e+00 , 2.4942168825412501e+00 , 2.4313899200000000e+00 , -4.4859599999999999e-02 , 1.6788200000000000e-01 , 9.8478600000000005e-01 -1.1728921490343156e+01 , 2.6578066596906207e+00 , 1.9552562880000000e+00 , 1.2834699999999999e-01 , -1.9736500000000001e-01 , -9.7189199999999998e-01 -1.2490910977917284e+01 , 2.7065045161917065e+00 , 2.0381267120000000e+00 , -5.9029900000000003e-02 , 1.8777700000000000e-01 , 9.8043599999999997e-01 -1.3542262782917282e+01 , 2.7684629187150156e+00 , 2.1220075999999999e+00 , -5.7569799999999997e-02 , 1.8771199999999999e-01 , 9.8053599999999996e-01 -1.4738523118210750e+01 , 2.8421593816925834e+00 , 2.2317619199999998e+00 , -5.1950499999999997e-02 , 1.8087800000000001e-01 , 9.8213300000000003e-01 -1.6503887534664251e+01 , 2.9446076943851676e+00 , 2.3527513600000001e+00 , 6.4063999999999996e-02 , -1.8540599999999999e-01 , -9.8057200000000000e-01 -1.8288291580066510e+01 , 3.0573036683784354e+00 , 2.5339484799999998e+00 , -7.0785100000000004e-02 , 1.8268000000000001e-01 , 9.8062099999999996e-01 -2.3426165636974144e+01 , 3.3850711975015253e+00 , 3.0805807999999999e+00 , 1.2177100000000000e-01 , -1.8790799999999999e-01 , -9.7460899999999995e-01 -2.6431963849050799e+01 , 3.5919558356297561e+00 , 3.4944904000000001e+00 , 4.2073899999999997e-01 , -3.0284900000000000e-02 , -9.0667600000000004e-01 -2.7839969629147340e+01 , 3.7319099664904227e+00 , 3.9572903999999998e+00 , 5.2888000000000002e-01 , 2.3213300000000001e-01 , -8.1633299999999998e-01 -2.7702685817779908e+01 , 3.7951068129771821e+00 , 4.3892128000000001e+00 , -6.4876100000000003e-01 , -3.2715600000000000e-01 , 6.8708000000000002e-01 -2.8273198445562389e+01 , 3.8985734184755940e+00 , 4.8663335999999999e+00 , -8.3798899999999998e-01 , -4.6668900000000002e-01 , 2.8279900000000002e-01 -3.1565093777395269e+01 , 4.1703184699283788e+00 , 5.5999911999999998e+00 , -1.0616100000000001e-01 , -6.5782099999999996e-02 , 9.9217100000000003e-01 -2.9127002224730017e+01 , 4.0980176499767609e+00 , 5.8540007999999997e+00 , -7.8583800000000004e-01 , -3.3664400000000000e-01 , -5.1877600000000001e-01 -2.6073082858126590e+01 , 3.9704302802078524e+00 , 5.9499823999999997e+00 , 7.5078999999999996e-01 , 5.7487400000000000e-01 , 3.2532299999999997e-01 -2.5985354215812315e+01 , 4.0310129086560611e+00 , 6.3531279999999999e+00 , 7.5078999999999996e-01 , 5.7487400000000000e-01 , 3.2532299999999997e-01 -2.4383228370159316e+01 , 3.9833658705250281e+00 , 6.5178951999999999e+00 , 1.3205700000000001e-01 , 2.1968299999999999e-01 , 9.6659200000000001e-01 -2.5358086144835269e+01 , 4.1190610821790852e+00 , 7.0779248000000008e+00 , -5.9740000000000004e-01 , -6.5754100000000004e-01 , -4.5907799999999999e-01 -2.2837403774935364e+01 , 3.9882937624147301e+00 , 7.0029928000000004e+00 , -6.2731599999999998e-01 , 5.7268500000000000e-02 , -7.7665600000000001e-01 -2.2377345459192185e+01 , 4.0105205404491180e+00 , 7.2734240000000003e+00 , -2.6498500000000001e-02 , 4.2355999999999999e-01 , 9.0548099999999998e-01 -2.2388596964715340e+01 , 4.0696578790576705e+00 , 7.6378608000000003e+00 , 7.2327399999999997e-01 , -1.1176700000000001e-01 , 6.8145599999999995e-01 -2.3851278722152099e+01 , 4.2550236593256434e+00 , 8.3641240000000003e+00 , -9.6084000000000003e-01 , -7.9227099999999995e-02 , -2.6553800000000000e-01 -2.4302934048647266e+01 , 4.3595778434817110e+00 , 8.8792776000000018e+00 , -8.5350899999999996e-01 , 3.1450800000000001e-02 , -5.2012800000000003e-01 -2.3297384446478095e+01 , 4.3318410884909770e+00 , 9.0013216000000007e+00 , -8.3652499999999996e-01 , 1.5809900000000002e-02 , -5.4770099999999999e-01 -2.3237156848495477e+01 , 4.3897214659020198e+00 , 9.3758776000000008e+00 , -8.5863800000000001e-01 , 1.1045400000000000e-01 , -5.0053999999999998e-01 -2.3011005874501169e+01 , 4.4306488255781868e+00 , 9.6994112000000001e+00 , -5.6371000000000004e-01 , 5.4572299999999997e-02 , -8.2416800000000001e-01 -2.5807954524890381e+01 , 4.7789467110064061e+00 , 1.1050028000000001e+01 , -2.0885500000000001e-01 , 2.8848800000000002e-01 , 9.3442700000000001e-01 -2.0724770777291404e+01 , 4.3195829048908294e+00 , 9.6722047999999994e+00 , -7.9925400000000002e-01 , -1.8550600000000000e-01 , 5.7164700000000002e-01 -2.0148938646059506e+01 , 4.3156458415837280e+00 , 9.8143416000000006e+00 , -3.9346999999999999e-01 , -8.0347299999999999e-01 , 4.4678099999999998e-01 -1.9689239941892389e+01 , 4.3219645613684623e+00 , 9.9848391999999997e+00 , -3.9346999999999999e-01 , -8.0347299999999999e-01 , 4.4678099999999998e-01 -1.9200096753627925e+01 , 4.3222509195923644e+00 , 1.0129586400000001e+01 , -8.6530899999999999e-01 , -2.0945000000000000e-01 , 4.5537899999999998e-01 -2.0101692195080286e+01 , 4.4843315032922098e+00 , 1.0873508800000002e+01 , 1.2854099999999999e-01 , -5.1197499999999996e-01 , 8.4932900000000000e-01 -2.1591991673712965e+01 , 4.7240025679065907e+00 , 1.1933029600000001e+01 , -8.5224999999999995e-01 , 4.8657400000000001e-01 , -1.9213200000000000e-01 -2.4564945714241560e+01 , 5.1604418868133290e+00 , 1.3779768000000001e+01 , -1.9999600000000001e-01 , -6.7932000000000003e-01 , 7.0606300000000000e-01 -2.1520369131223234e+01 , 4.8475186638032230e+00 , 1.2720632000000000e+01 , -8.4389700000000001e-01 , 1.0080300000000000e-01 , 5.2695000000000003e-01 -2.8014305655970475e+01 , 5.7704082348254637e+00 , 1.6568424000000000e+01 , -7.2340899999999997e-01 , -6.8013999999999997e-01 , 1.1869900000000000e-01 -2.4005695550930941e+01 , 5.3202168937857799e+00 , 1.4938328000000000e+01 , -5.6838500000000003e-01 , 7.1552000000000004e-01 , 4.0616500000000000e-01 -2.2696705593332091e+01 , 5.2179027029330616e+00 , 1.4683424000000000e+01 , 5.5041600000000002e-01 , 6.4927999999999997e-01 , 5.2485899999999996e-01 -2.2530391922264954e+01 , 5.2709278498383769e+00 , 1.5058759999999999e+01 , -8.8396699999999995e-01 , -3.5775800000000002e-01 , -3.0101699999999998e-01 -2.2654938415753684e+01 , 5.3663635382181401e+00 , 1.5617032000000000e+01 , 9.7653000000000001e-01 , -1.7426500000000000e-01 , 1.2656999999999999e-01 -2.2159099063852633e+01 , 5.3719385143467990e+00 , 1.5791856000000001e+01 , -9.5945800000000003e-01 , 2.6558799999999999e-01 , -9.4359100000000001e-02 -2.2306850934747590e+01 , 5.4732995520155194e+00 , 1.6384447999999999e+01 , 7.8168400000000005e-01 , -5.7721999999999996e-01 , 2.3619399999999999e-01 -2.2176320356122918e+01 , 5.5345906302488537e+00 , 1.6803152000000001e+01 , 7.8304600000000002e-01 , -5.8456699999999995e-01 , 2.1241399999999999e-01 -6.3717280660539100e+00 , 3.0437053078108480e+00 , 5.9107640000000004e+00 , 4.2616900000000002e-01 , -6.1712900000000004e-01 , 6.6146199999999999e-01 -6.2705602161814724e+00 , 3.0435886738650355e+00 , 5.9412984000000000e+00 , -3.8267400000000001e-01 , 6.8840299999999999e-01 , -6.1616700000000002e-01 -6.2034249442247695e+00 , 3.0497468273865151e+00 , 5.9944319999999998e+00 , 3.0508000000000002e-01 , -5.6385700000000005e-01 , 7.6745799999999997e-01 -6.0941670599202533e+00 , 3.0477133014976392e+00 , 6.0137239999999998e+00 , 6.6006900000000002e-01 , 2.1992600000000001e-02 , 7.5088299999999997e-01 -6.0177439094288330e+00 , 3.0511631322653265e+00 , 6.0567072000000000e+00 , -7.6770600000000000e-01 , -5.1942500000000003e-02 , -6.3869399999999998e-01 -6.0032797362667969e+00 , 3.0656668942737246e+00 , 6.1519608000000003e+00 , -9.3141600000000002e-01 , 1.0408100000000001e-01 , -3.4875600000000001e-01 -5.9866858373114962e+00 , 3.0803119617862649e+00 , 6.2474640000000008e+00 , -9.7300299999999995e-01 , -3.5094000000000000e-02 , -2.2811000000000001e-01 -5.9366566665800207e+00 , 3.0887194907407736e+00 , 6.3154072000000001e+00 , -9.3286000000000002e-01 , 5.9353400000000001e-02 , -3.5531499999999999e-01 -5.9007799094871611e+00 , 3.1002844894189554e+00 , 6.3967664000000006e+00 , 9.4330000000000003e-01 , 1.4881600000000000e-01 , 2.9671399999999998e-01 -5.8487867842626606e+00 , 3.1085390312925538e+00 , 6.4635552000000001e+00 , 8.0908899999999995e-01 , -3.0313899999999999e-01 , 5.0346900000000006e-01 -5.8452937920619554e+00 , 3.1270792100802414e+00 , 6.5811792000000002e+00 , 6.2007500000000004e-01 , 2.3202900000000001e-01 , 7.4944699999999997e-01 -5.7613367237453366e+00 , 3.1294284233623570e+00 , 6.6170799999999996e+00 , -8.2777500000000004e-01 , 3.5020099999999998e-01 , -4.3834699999999999e-01 -5.7674889741619975e+00 , 3.1507461827325227e+00 , 6.7505536000000008e+00 , -9.3804799999999999e-01 , 1.9020599999999999e-01 , -2.8963299999999997e-01 -5.8698389992090458e+00 , 3.1958088060088254e+00 , 7.0013183999999997e+00 , -9.4795099999999999e-01 , -3.0995000000000000e-01 , 7.2934200000000005e-02 -5.7999231828547408e+00 , 3.2021779565278128e+00 , 7.0601824000000004e+00 , -8.1332800000000005e-01 , -5.2060700000000004e-01 , -2.5974399999999997e-01 -5.7940599515478439e+00 , 3.2237734238547180e+00 , 7.1977432000000006e+00 , -8.4233100000000005e-01 , -4.4435500000000000e-01 , -3.0500300000000002e-01 -5.7328535781574743e+00 , 3.2327729050711573e+00 , 7.2715208000000002e+00 , -9.0252800000000000e-01 , -3.1373400000000001e-01 , -2.9498200000000002e-01 -5.6760239303110671e+00 , 3.2430575246275528e+00 , 7.3525992000000002e+00 , 8.7487099999999995e-01 , -5.4898700000000000e-03 , 4.8432500000000001e-01 -5.7570381883712978e+00 , 3.2910842296472897e+00 , 7.6240703999999999e+00 , -7.0202799999999999e-01 , -7.0509999999999995e-01 , 9.9950399999999995e-02 -5.5224599123799818e+00 , 3.2537071881906350e+00 , 7.4622880000000000e+00 , -7.0475900000000002e-01 , -4.3922099999999997e-01 , -5.5713500000000005e-01 -5.6686570714425351e+00 , 3.3228484621481202e+00 , 7.8471920000000006e+00 , -4.1282600000000003e-02 , -1.5742100000000001e-01 , -9.8666799999999999e-01 -5.4264256192848679e+00 , 3.2809806529345238e+00 , 7.6614792000000005e+00 , -6.8065299999999995e-01 , -6.5999200000000002e-01 , -3.1799800000000000e-01 -5.2522964729292081e+00 , 3.2572898124310785e+00 , 7.5647072000000000e+00 , -8.1418900000000002e-02 , -2.4185499999999999e-01 , 9.6689099999999994e-01 -5.1668969248304464e+00 , 3.2603685103453208e+00 , 7.6039256000000002e+00 , 2.4220200000000000e-01 , -5.4813800000000001e-01 , 8.0055100000000001e-01 -5.0459924846165656e+00 , 3.2500921429482945e+00 , 7.5798288000000005e+00 , -3.4300999999999998e-01 , -3.5160000000000002e-01 , 8.7104700000000002e-01 -4.8262396085243706e+00 , 3.2072131000509314e+00 , 7.3728168000000007e+00 , 7.6900900000000005e-01 , -2.0524600000000001e-01 , -6.0539200000000004e-01 -4.7834128516544094e+00 , 3.2216022009460810e+00 , 7.4772536000000001e+00 , 6.7992500000000000e-01 , -4.8565500000000000e-01 , -5.4940000000000000e-01 -4.8820865949993024e+00 , 3.2890930511116587e+00 , 7.8649240000000002e+00 , 7.3432299999999995e-01 , 5.5055200000000004e-01 , 3.9706700000000000e-01 -4.8772655594986736e+00 , 3.3216704788346583e+00 , 8.0730280000000008e+00 , 3.5201300000000002e-01 , -1.3995099999999999e-01 , -9.2547299999999999e-01 -4.9488906914442508e+00 , 3.3878518164072604e+00 , 8.4589512000000013e+00 , -6.4933900000000000e-01 , -4.7865600000000003e-01 , -5.9097200000000005e-01 -4.8938320318446547e+00 , 3.4071459474085710e+00 , 8.5956799999999998e+00 , -6.4933900000000000e-01 , -4.7865600000000003e-01 , -5.9097200000000005e-01 -4.7563764612609631e+00 , 3.3918824473973110e+00 , 8.5432848000000003e+00 , 6.4168099999999995e-01 , 6.3348599999999999e-01 , -4.3236599999999997e-01 -4.3955351372774407e+00 , 3.2755993836384816e+00 , 7.9260136000000001e+00 , -6.0100799999999999e-01 , 7.1814699999999998e-01 , -3.5079100000000002e-01 -4.2473483830977017e+00 , 3.2484149413893997e+00 , 7.7963567999999999e+00 , -1.8602500000000000e-01 , -5.1887600000000000e-01 , 8.3436299999999997e-01 -4.2118680183287411e+00 , 3.2727866934877099e+00 , 7.9624552000000000e+00 , -7.2174300000000002e-01 , -6.8252000000000002e-01 , 1.1512400000000000e-01 -4.1691586867239501e+00 , 3.2965950410009657e+00 , 8.1189543999999998e+00 , -5.5021100000000001e-01 , -2.7892099999999997e-01 , -7.8706500000000001e-01 -4.0826882916047094e+00 , 3.2986745981597920e+00 , 8.1582456000000008e+00 , -5.5021100000000001e-01 , -2.7892000000000000e-01 , -7.8706500000000001e-01 -3.9005396897720797e+00 , 3.2454975773229617e+00 , 7.8817928000000004e+00 , -6.6184900000000002e-01 , -6.7374199999999995e-01 , -3.2867499999999999e-01 -3.7926458507742229e+00 , 3.2318142652972082e+00 , 7.8277543999999999e+00 , -7.8198299999999998e-01 , -4.3979600000000002e-01 , 4.4168000000000002e-01 -3.7321266117511374e+00 , 3.2474748781882878e+00 , 7.9400016000000004e+00 , -2.5287999999999999e-01 , -7.5315500000000002e-01 , 6.0729699999999998e-01 -3.6336751868598038e+00 , 3.2376220794934776e+00 , 7.9122544000000001e+00 , -8.0180500000000002e-02 , -7.9495199999999999e-01 , 6.0135099999999997e-01 -3.8446857831178516e+00 , 3.4616705869254116e+00 , 9.2432464000000003e+00 , 5.6639600000000001e-01 , 4.4054300000000002e-01 , 6.9650400000000001e-01 -3.5054088855169310e+00 , 3.2722480329908441e+00 , 8.1621455999999988e+00 , 2.8259200000000001e-01 , 9.1069100000000003e-01 , -3.0130299999999999e-01 -3.3724340138885136e+00 , 3.2317396536045937e+00 , 7.9485192000000007e+00 , -4.9137100000000000e-01 , -9.7307899999999996e-04 , 8.7095000000000000e-01 -3.2914165710955903e+00 , 3.2349776365430518e+00 , 7.9947471999999999e+00 , -1.2463200000000001e-01 , -1.3315600000000000e-01 , 9.8322799999999999e-01 -3.1961498836121383e+00 , 3.2253279155310048e+00 , 7.9581391999999997e+00 , -5.8013300000000001e-01 , -6.6932800000000001e-02 , -8.1176700000000002e-01 -3.2176729232473207e+00 , 3.3569697149740385e+00 , 8.7742584000000008e+00 , -8.4097900000000003e-01 , 1.4617000000000000e-02 , -5.4086999999999996e-01 -3.1156279737121753e+00 , 3.3534324023939082e+00 , 8.7770767999999997e+00 , -9.0605599999999997e-01 , -4.0699999999999997e-01 , 1.1581900000000001e-01 -3.0778299447462749e+00 , 3.4551963979580220e+00 , 9.4216480000000011e+00 , -5.1427199999999995e-01 , 7.2069600000000000e-01 , -4.6488900000000000e-01 -2.8021230020529715e+00 , 3.1194628455240654e+00 , 7.4171208000000002e+00 , -2.1082400000000001e-01 , 1.0798600000000000e-01 , 9.7154099999999999e-01 -2.7242765617617337e+00 , 3.1114969171127180e+00 , 7.3925976000000002e+00 , 1.6497200000000001e-01 , 5.0998900000000003e-01 , 8.4421299999999999e-01 -2.6496460986959649e+00 , 3.1153897300420206e+00 , 7.4381599999999999e+00 , -5.4930299999999999e-01 , -6.3692700000000002e-01 , -5.4091599999999995e-01 -2.5773310284717041e+00 , 3.1394787194289977e+00 , 7.6055272000000000e+00 , -5.5896900000000005e-01 , -8.1107600000000002e-01 , -1.7236199999999999e-01 -2.5015232890314358e+00 , 3.2066524080587304e+00 , 8.0492327999999986e+00 , -4.2918800000000001e-01 , -1.4903700000000000e-01 , -8.9083500000000004e-01 -2.4135577982764436e+00 , 3.2113385742054863e+00 , 8.1011808000000016e+00 , -1.8618499999999999e-01 , 6.5803000000000000e-01 , -7.2961100000000001e-01 -2.3245231521614746e+00 , 3.2075628576930564e+00 , 8.1003384000000000e+00 , -5.3635699999999997e-01 , -3.5445900000000002e-01 , -7.6595100000000005e-01 -2.2404639957998276e+00 , 3.1858329295197323e+00 , 7.9956104000000003e+00 , -9.3459999999999999e-01 , 2.2493400000000000e-02 , 3.5499000000000003e-01 -2.1623709040935353e+00 , 3.1605053621582551e+00 , 7.8585384000000005e+00 , 3.4540199999999999e-01 , 3.0778800000000001e-01 , 8.8654599999999995e-01 -2.0782296812375036e+00 , 3.1546230266440860e+00 , 7.8429904000000006e+00 , -5.0808399999999998e-01 , -5.8650000000000001e-02 , 8.5930799999999996e-01 -1.7993266541115651e+00 , 3.4671659999172668e+00 , 9.8723424000000009e+00 , -3.7217200000000000e-01 , -5.0878699999999999e-01 , 7.7628900000000001e-01 -1.7487139542907153e+00 , 3.3647982695288610e+00 , 9.2480408000000001e+00 , -9.6554899999999999e-01 , 1.9924900000000001e-01 , -1.6737900000000000e-01 -5.0289719413486402e+00 , 2.0029447678861869e+00 , 2.3715839999999977e-01 , -4.1088200000000002e-01 , -7.6364100000000004e-02 , 9.0848499999999999e-01 -5.3451624427115636e+00 , 2.0336261889134812e+00 , 3.9893040000000002e-01 , 4.1637999999999997e-01 , 8.2998100000000005e-02 , -9.0539400000000003e-01 -4.8490651202139379e+00 , 2.1641727862803597e+00 , 1.2836105600000001e+00 , -7.2969900000000004e-02 , 1.9176499999999999e-01 , 9.7872499999999996e-01 -4.9302085590082942e+00 , 2.1659668610130760e+00 , 1.2887429600000000e+00 , -4.8399499999999998e-02 , 1.9686999999999999e-01 , 9.7923400000000005e-01 -5.0041161264333978e+00 , 2.1696919619843569e+00 , 1.3019249600000000e+00 , -2.8410500000000002e-02 , 1.9644000000000000e-01 , 9.8010399999999998e-01 -5.0868193189673292e+00 , 2.1723243014331870e+00 , 1.3115584800000000e+00 , -1.2873999999999999e-01 , 1.9317300000000001e-01 , 9.7268200000000005e-01 -5.1612680581365096e+00 , 2.1768870538934606e+00 , 1.3290128000000001e+00 , 1.1808700000000000e-01 , -1.9245499999999999e-01 , -9.7417500000000001e-01 -5.2615278512489301e+00 , 2.1784994198684093e+00 , 1.3320537600000000e+00 , -7.5225500000000001e-02 , 1.8874900000000000e-01 , 9.7914000000000001e-01 -5.3545175443283073e+00 , 2.1821069707989857e+00 , 1.3434459200000000e+00 , -6.1908800000000000e-02 , 1.9713900000000001e-01 , 9.7841900000000004e-01 -5.4562138054448415e+00 , 2.1858463169038740e+00 , 1.3520966400000001e+00 , 4.1768300000000001e-02 , -1.9709299999999999e-01 , -9.7949500000000000e-01 -5.5585697718705216e+00 , 2.1891580422764711e+00 , 1.3640129599999999e+00 , -4.7021399999999998e-02 , 1.9104199999999999e-01 , 9.8045499999999997e-01 -5.6895225583751152e+00 , 2.1910624664276628e+00 , 1.3645183999999999e+00 , 5.8969500000000001e-02 , -1.9961000000000001e-01 , -9.7809900000000005e-01 -5.7932471553256448e+00 , 2.1966264315566035e+00 , 1.3826518399999999e+00 , 6.4709000000000003e-02 , -1.8913800000000000e-01 , -9.7981600000000002e-01 -5.9254240206472542e+00 , 2.1999780909788322e+00 , 1.3905922400000001e+00 , -6.9815900000000000e-02 , 1.8301799999999999e-01 , 9.8062700000000003e-01 -6.0581762863767308e+00 , 2.2041032431729906e+00 , 1.4025033599999999e+00 , 3.1197799999999998e-01 , 8.3195300000000000e-02 , -9.4643999999999995e-01 -6.1627459066892065e+00 , 2.2106810580222360e+00 , 1.4311096000000001e+00 , 9.2819600000000002e-01 , 3.1618800000000002e-01 , 1.9615700000000000e-01 -6.0571867376177781e+00 , 2.2278825736156262e+00 , 1.5519472000000001e+00 , -9.6963699999999997e-01 , -1.8346399999999999e-01 , -1.6169700000000001e-01 -6.0546441320094635e+00 , 2.2386981472562137e+00 , 1.6261668000000000e+00 , 9.8941999999999997e-01 , 1.1722900000000000e-01 , 8.5471400000000003e-02 -6.0412734894717186e+00 , 2.2505818127724688e+00 , 1.7033805600000000e+00 , 9.8355700000000001e-01 , 1.5781400000000001e-01 , 8.7810600000000003e-02 -6.0259295947162661e+00 , 2.2623583583236568e+00 , 1.7796354400000001e+00 , 9.9360000000000004e-01 , 9.7148399999999996e-02 , -5.7638099999999998e-02 -6.0282966317073372e+00 , 2.2739240395857920e+00 , 1.8480799200000000e+00 , 9.5594400000000002e-01 , 5.9134100000000002e-02 , -2.8753000000000001e-01 -6.0393966294737433e+00 , 2.2833973849053812e+00 , 1.9132819919999999e+00 , 9.9076799999999998e-01 , -3.4393899999999998e-02 , -1.3113000000000000e-01 -6.0985050339264353e+00 , 2.2929661911161157e+00 , 1.9628510960000001e+00 , -9.6626000000000001e-01 , -6.5496700000000005e-02 , -2.4910399999999999e-01 -5.9782767894360429e+00 , 2.3072556847495749e+00 , 2.0660964719999999e+00 , -9.4843699999999997e-01 , -1.5448300000000001e-01 , -2.7677099999999999e-01 -5.9756249601551819e+00 , 2.3175631098569993e+00 , 2.1324991199999999e+00 , 9.7938899999999995e-01 , 2.9109199999999998e-02 , -1.9987300000000000e-01 -5.9914360546128433e+00 , 2.3270385269000911e+00 , 2.1934452000000002e+00 , 9.6261500000000000e-01 , 4.8596200000000003e-03 , -2.7083099999999999e-01 -6.0061800133967278e+00 , 2.3365958086569041e+00 , 2.2545701600000001e+00 , -9.1777299999999995e-01 , 7.9125100000000004e-02 , 3.8914300000000002e-01 -6.0403067098860701e+00 , 2.3465941579275915e+00 , 2.3114748000000001e+00 , -8.8856199999999996e-01 , 6.6169000000000006e-02 , 4.5395999999999997e-01 -6.0732208240260750e+00 , 2.3558214341498114e+00 , 2.3695723200000001e+00 , 5.2157600000000004e-01 , -1.5528900000000001e-01 , -8.3895399999999998e-01 -6.2292189683428374e+00 , 2.3650439575385711e+00 , 2.4064746399999999e+00 , -3.0223899999999998e-01 , 1.9648499999999999e-01 , 9.3276199999999998e-01 -6.4551232500568050e+00 , 2.3731799073323252e+00 , 2.4370901599999999e+00 , 1.1349800000000000e-01 , -1.7718600000000001e-01 , -9.7761100000000001e-01 -1.1604019924670721e+01 , 2.3835733407059023e+00 , 1.9324989040000000e+00 , -1.3940100000000000e-01 , 1.9303699999999999e-01 , 9.7123800000000005e-01 -1.2057266836585825e+01 , 2.4087682215776605e+00 , 2.0435820320000002e+00 , -1.2421900000000000e-01 , 1.9046399999999999e-01 , 9.7380400000000000e-01 -1.3005667293987516e+01 , 2.4385242451551199e+00 , 2.1248624000000000e+00 , -5.2729400000000003e-02 , 1.8962499999999999e-01 , 9.8043999999999998e-01 -1.4109750708962729e+01 , 2.4732993450979444e+00 , 2.2274167999999999e+00 , -6.4184199999999997e-02 , 1.8794700000000000e-01 , 9.8007999999999995e-01 -1.5544946206774254e+01 , 2.5178601230060087e+00 , 2.3490219200000002e+00 , -4.4818499999999997e-02 , 1.8767400000000001e-01 , 9.8120799999999997e-01 -1.7332298962646153e+01 , 2.5736075356196748e+00 , 2.5064040800000003e+00 , 7.0247599999999993e-02 , -1.8959500000000001e-01 , -9.7934600000000005e-01 -1.9460140371214681e+01 , 2.6436623974327986e+00 , 2.7178641600000000e+00 , -7.4331599999999998e-02 , 1.8313399999999999e-01 , 9.8027399999999998e-01 -2.7070956736036369e+01 , 2.9513759761036531e+00 , 3.8296511999999998e+00 , 6.8540199999999996e-01 , -2.7363799999999999e-01 , -6.7479400000000000e-01 -2.9015600447093732e+01 , 3.0666614753392905e+00 , 4.3477584000000000e+00 , 3.1646299999999999e-01 , -1.1849300000000000e-01 , -9.4117499999999998e-01 -2.9278681229746784e+01 , 3.1461267737134779e+00 , 4.8245984000000002e+00 , -8.5355400000000003e-01 , -1.0395500000000001e-01 , 5.1052900000000001e-01 -2.9532182229477755e+01 , 3.2278310944023940e+00 , 5.3106424000000008e+00 , 8.6810299999999996e-01 , 2.6304300000000003e-01 , 4.2095700000000003e-01 -2.8722729455106290e+01 , 3.2744493140605462e+00 , 5.7012872000000003e+00 , -4.8229600000000000e-01 , 8.7387199999999998e-01 , -6.1147199999999999e-02 -2.6296488583604187e+01 , 3.2599004552265316e+00 , 5.8754872000000002e+00 , 8.1443200000000004e-01 , 4.1133199999999998e-01 , 4.0927599999999997e-01 -2.6232044061555118e+01 , 3.3228790847672505e+00 , 6.2850495999999998e+00 , 9.4397299999999995e-01 , 3.2997399999999999e-01 , 5.6518899999999997e-03 -2.5687906783791330e+01 , 3.3662212536835572e+00 , 6.6212815999999997e+00 , 6.7580399999999996e-01 , 7.1446200000000004e-01 , 1.8119700000000000e-01 -2.3540913134571195e+01 , 3.3362051382716755e+00 , 6.6677176000000005e+00 , 4.0649400000000002e-01 , 1.1705300000000000e-01 , 9.0612400000000004e-01 -2.6434787926948246e+01 , 3.5319577256406145e+00 , 7.5873792000000009e+00 , -9.7170400000000001e-01 , -2.3406600000000000e-01 , 3.1705400000000002e-02 -2.2636933142587001e+01 , 3.4099385984000143e+00 , 7.2360776000000007e+00 , -7.7033600000000002e-01 , -1.7764300000000000e-01 , -6.1239299999999997e-01 -2.2599806505816829e+01 , 3.4653602168352027e+00 , 7.5927976000000008e+00 , 6.9373200000000002e-01 , 1.3650499999999999e-01 , 7.0717900000000000e-01 -2.4039921388472859e+01 , 3.6039600457412000e+00 , 8.3086295999999997e+00 , -8.0874999999999997e-01 , 5.2968700000000002e-01 , -2.5564500000000001e-01 -2.3642360088270394e+01 , 3.6429622557981514e+00 , 8.6018888000000011e+00 , -7.3631400000000002e-01 , 2.0869699999999999e-01 , -6.4365099999999997e-01 -2.3560578365476363e+01 , 3.6998584719552898e+00 , 8.9722848000000006e+00 , -7.3631400000000002e-01 , 2.0869699999999999e-01 , -6.4365099999999997e-01 -2.3521254073700831e+01 , 3.7587927021136025e+00 , 9.3564608000000007e+00 , -7.1500500000000000e-01 , 1.9713900000000001e-01 , -6.7074800000000001e-01 -2.4614040769385568e+01 , 3.8958862471555995e+00 , 1.0101464800000000e+01 , 7.2597500000000004e-01 , -4.8937200000000000e-02 , -6.8597799999999998e-01 -1.9655811474229115e+01 , 3.6137028707911418e+00 , 8.8603079999999999e+00 , -1.9301199999999999e-01 , -5.7252400000000003e-01 , 7.9684500000000003e-01 -1.9931567071610854e+01 , 3.6866540167758419e+00 , 9.2917728000000004e+00 , -8.3367100000000005e-01 , -1.9628499999999999e-01 , 5.1620299999999997e-01 -1.9866453235063140e+01 , 3.7356595422712200e+00 , 9.6107095999999999e+00 , -2.6796900000000001e-01 , -7.5606200000000001e-01 , 5.9712900000000002e-01 -2.0143461544698365e+01 , 3.8123770400411328e+00 , 1.0066458400000000e+01 , 5.9409400000000001e-01 , 7.0291000000000003e-01 , -3.9111400000000002e-01 -1.9959199840621501e+01 , 3.8534338942076358e+00 , 1.0346904799999999e+01 , 5.9409500000000004e-01 , 7.0291000000000003e-01 , -3.9111400000000002e-01 -2.7468967893612000e+01 , 4.5549378624667405e+00 , 1.3976536000000001e+01 , -3.3366600000000002e-01 , 9.4004200000000004e-01 , -7.0630299999999993e-02 -2.1538216403528292e+01 , 4.1072155958700503e+00 , 1.1790466400000000e+01 , 8.4326500000000004e-01 , -5.1525900000000002e-01 , 1.5301300000000001e-01 -2.1189680251899311e+01 , 4.2022309326883924e+00 , 1.2430160000000001e+01 , -7.9085799999999995e-01 , 5.5179199999999995e-01 , -2.6470600000000000e-01 -2.2370701036097742e+01 , 4.3846093678815095e+00 , 1.3455704000000001e+01 , -8.4688699999999995e-01 , 4.5726800000000001e-01 , 2.7145599999999998e-01 -2.2229539924600964e+01 , 4.4391889420186796e+00 , 1.3822928000000001e+01 , -8.4388900000000000e-01 , 4.4650499999999999e-01 , 2.9746299999999998e-01 -2.3666461405641357e+01 , 4.6636890260109176e+00 , 1.5085800000000001e+01 , -3.5498900000000000e-01 , 8.8605400000000001e-01 , 2.9814600000000002e-01 -2.2326572720002847e+01 , 4.5934019760561995e+00 , 1.4788256000000001e+01 , 9.6112799999999998e-01 , -2.7610200000000001e-01 , 1.0495000000000001e-03 -2.3952063861160116e+01 , 4.8519142475235935e+00 , 1.6254863999999998e+01 , 6.8741300000000005e-01 , 6.8646700000000005e-01 , 2.3712200000000000e-01 -2.2580015181400945e+01 , 4.7727628972175040e+00 , 1.5901368000000000e+01 , -7.8685700000000003e-01 , 5.3334999999999999e-01 , -3.1047400000000003e-01 -2.1788609461696332e+01 , 4.7549558980649156e+00 , 1.5875784000000001e+01 , -7.8685700000000003e-01 , 5.3334999999999999e-01 , -3.1047400000000003e-01 -2.1942139186015297e+01 , 4.8513706210276517e+00 , 1.6471496000000002e+01 , -8.3951299999999995e-01 , 4.2921300000000001e-01 , -3.3315800000000001e-01 -6.2236778941664204e+00 , 2.8942943515720141e+00 , 5.7700208000000002e+00 , 5.5219900000000000e-01 , -5.6152700000000000e-01 , 6.1624999999999996e-01 -6.2175366880321841e+00 , 2.9085189471272921e+00 , 5.8656696000000004e+00 , 5.8129699999999995e-01 , -6.4116200000000001e-01 , 5.0100500000000003e-01 -6.1669162887560605e+00 , 2.9183773459031341e+00 , 5.9301391999999993e+00 , -6.2928700000000004e-01 , 4.7377900000000001e-01 , -6.1606099999999997e-01 -6.1402679669818383e+00 , 2.9309546748571069e+00 , 6.0132352000000004e+00 , 7.1845099999999995e-01 , -4.5960600000000001e-01 , 5.2210199999999996e-01 -6.0475376751667360e+00 , 2.9336579595528249e+00 , 6.0437592000000002e+00 , -7.5726800000000005e-01 , 2.2795000000000001e-01 , -6.1203200000000002e-01 -6.0731031806059432e+00 , 2.9542716222506638e+00 , 6.1726152000000001e+00 , 9.4726800000000000e-01 , 8.9609300000000003e-02 , 3.0765799999999999e-01 -5.9407414667992109e+00 , 2.9512560178298082e+00 , 6.1662920000000003e+00 , 9.8314599999999996e-01 , 6.2771999999999994e-02 , 1.7170700000000000e-01 -6.0375813179998632e+00 , 2.9840829187360631e+00 , 6.3657016000000004e+00 , 9.6209900000000004e-01 , 2.6663300000000001e-01 , 5.7201200000000001e-02 -5.9563175147767904e+00 , 2.9892691119098025e+00 , 6.4057208000000001e+00 , -9.0783800000000003e-01 , -3.5167900000000002e-01 , -2.2836799999999999e-01 -5.9849982450924353e+00 , 3.0133602726863797e+00 , 6.5525064000000004e+00 , -8.2993099999999997e-01 , -4.0595900000000001e-01 , -3.8263700000000000e-01 -5.9382929815024639e+00 , 3.0242158377862611e+00 , 6.6280311999999997e+00 , -7.8502799999999995e-01 , -2.3279400000000000e-01 , -5.7405300000000004e-01 -5.8102827993490118e+00 , 3.0207251185833721e+00 , 6.6202832000000003e+00 , -8.1906500000000004e-01 , -2.0038800000000001e-01 , -5.3756599999999999e-01 -5.7543126523720094e+00 , 3.0299105847130372e+00 , 6.6855536000000004e+00 , -8.7743000000000004e-01 , -1.9354799999999998e-02 , -4.7931499999999999e-01 -5.9634976265824555e+00 , 3.0913674695824733e+00 , 7.0510408000000000e+00 , 9.9039999999999995e-01 , 8.0231700000000003e-02 , 1.1256700000000000e-01 -5.9457094346350772e+00 , 3.1094961479921541e+00 , 7.1741248000000004e+00 , -8.7118300000000004e-01 , -4.5826699999999998e-01 , -1.7615700000000001e-01 -5.9055947570919702e+00 , 3.1249019216393981e+00 , 7.2736424000000000e+00 , -8.7094199999999999e-01 , -4.4308199999999998e-01 , -2.1245900000000001e-01 -5.7538985499265172e+00 , 3.1163912100711268e+00 , 7.2359216000000002e+00 , -8.2546900000000001e-01 , -4.5944400000000002e-01 , -3.2789099999999999e-01 -5.7554440171302721e+00 , 3.1411184250206619e+00 , 7.3906008000000005e+00 , -5.5486500000000005e-01 , -5.7288899999999998e-01 , -6.0326000000000002e-01 -5.8680773406867077e+00 , 3.1919880987177245e+00 , 7.7040255999999996e+00 , -8.6643499999999996e-01 , -4.0128200000000003e-01 , 2.9709200000000002e-01 -5.8395989777682535e+00 , 3.2127557314041528e+00 , 7.8379152000000003e+00 , -4.5528400000000002e-01 , -8.8733399999999996e-01 , 7.3174199999999995e-02 -5.6854798068594539e+00 , 3.2031108024157957e+00 , 7.7940480000000001e+00 , 1.3628499999999999e-01 , 9.1205599999999998e-01 , 3.8675700000000002e-01 -5.4823537808428480e+00 , 3.1802357527378842e+00 , 7.6687903999999998e+00 , 6.8330800000000003e-01 , 7.2842399999999996e-01 , 4.9888200000000001e-02 -5.4553723007143713e+00 , 3.2008430949895725e+00 , 7.8074848000000010e+00 , -1.5700600000000001e-01 , 5.8389999999999997e-01 , 7.9649800000000004e-01 -5.1619255170534810e+00 , 3.1505151711024850e+00 , 7.5161392000000005e+00 , -1.6937099999999999e-01 , -1.7658799999999999e-01 , 9.6960299999999999e-01 -4.9479792481568206e+00 , 3.1172578365450772e+00 , 7.3317679999999994e+00 , 5.1750799999999997e-01 , 3.6938100000000001e-01 , -7.7184399999999997e-01 -4.7410584436136993e+00 , 3.0835262324748967e+00 , 7.1412712000000003e+00 , -7.1614999999999995e-01 , -5.5023900000000003e-01 , 4.2937900000000001e-01 -4.7173104611874876e+00 , 3.1042531551992649e+00 , 7.2707096000000000e+00 , -7.1614999999999995e-01 , -5.5023900000000003e-01 , 4.2937900000000001e-01 -4.7142352411392263e+00 , 3.1313067540979915e+00 , 7.4464904000000001e+00 , -6.4793100000000003e-01 , -6.3302599999999998e-01 , -4.2363200000000001e-01 -4.9330269541274578e+00 , 3.2354635180473617e+00 , 8.0839376000000005e+00 , 6.2915500000000002e-01 , -6.7076899999999995e-01 , -3.9272499999999999e-01 -4.9807762461253073e+00 , 3.2882956021708734e+00 , 8.4143247999999993e+00 , 6.9354800000000005e-01 , 3.2291500000000001e-01 , 6.4398599999999995e-01 -4.9412791904180402e+00 , 3.3136369278887319e+00 , 8.5791024000000000e+00 , 5.3651300000000002e-01 , 1.8671699999999999e-01 , 8.2297699999999996e-01 -4.8440033325416758e+00 , 3.3189241915607584e+00 , 8.6214927999999986e+00 , 4.1821000000000003e-01 , -3.1008700000000000e-01 , 8.5378399999999999e-01 -4.4019364438526249e+00 , 3.1860188401412461e+00 , 7.8253311999999999e+00 , -4.7478999999999999e-01 , -6.0678600000000005e-01 , 6.3748300000000002e-01 -4.2917040917896019e+00 , 3.1786369461149633e+00 , 7.7915207999999998e+00 , 8.2414000000000001e-02 , 7.6644599999999996e-01 , -6.3699899999999998e-01 -4.1858677490715284e+00 , 3.1724974087430731e+00 , 7.7648136000000001e+00 , -3.7544599999999997e-02 , 9.2159500000000005e-01 , 3.8633400000000001e-01 -4.0894963460399865e+00 , 3.1694490830317341e+00 , 7.7554744000000007e+00 , 3.9629499999999998e-02 , 5.8306100000000005e-01 , 8.1146200000000002e-01 -4.0034838729674096e+00 , 3.1704213022219259e+00 , 7.7735704000000005e+00 , -2.2843600000000000e-01 , -4.7045199999999998e-01 , -8.5234500000000002e-01 -3.9327976636200068e+00 , 3.1792298651172421e+00 , 7.8391007999999998e+00 , -6.2470800000000004e-01 , -6.1653000000000002e-01 , -4.7919800000000001e-01 -3.8681862690821776e+00 , 3.1935102189236764e+00 , 7.9330856000000001e+00 , 6.7492099999999999e-01 , 2.9897299999999999e-01 , 6.7460900000000001e-01 -3.7635262393304614e+00 , 3.1846039484017377e+00 , 7.8876271999999998e+00 , -2.9159000000000002e-01 , -2.5340200000000002e-01 , 9.2236799999999997e-01 -3.6482471245820225e+00 , 3.1667834196982798e+00 , 7.7903767999999998e+00 , 4.5482599999999998e-02 , -7.5849200000000006e-01 , 6.5009399999999995e-01 -3.5483322135692479e+00 , 3.1578160814520206e+00 , 7.7403632000000009e+00 , 4.9933600000000000e-01 , -4.9301099999999998e-01 , -7.1246299999999996e-01 -3.4585246437102137e+00 , 3.1540057180658412e+00 , 7.7286424000000000e+00 , 1.6980400000000001e-01 , 9.2241799999999996e-01 , -3.4685899999999997e-01 -3.3543895923728724e+00 , 3.1374318634637604e+00 , 7.6346992000000000e+00 , 1.5499599999999999e-01 , 9.8566200000000004e-01 , -6.6686700000000002e-02 -3.2594635529786529e+00 , 3.1251070551348392e+00 , 7.5690751999999994e+00 , 2.2998800000000000e-01 , 9.2123100000000002e-01 , -3.1374900000000000e-01 -3.1687917876005223e+00 , 3.1142526711672600e+00 , 7.5116672000000007e+00 , 2.2237699999999999e-01 , 9.2788499999999996e-01 , -2.9929499999999998e-01 -3.1087238754222204e+00 , 3.1362719386060238e+00 , 7.6555824000000001e+00 , -1.8643000000000001e-01 , -9.7156799999999999e-01 , -1.4594499999999999e-01 -3.0919912105627310e+00 , 3.2184503278001033e+00 , 8.1758424000000005e+00 , -9.5685699999999996e-01 , -1.1834900000000000e-01 , -2.6536300000000002e-01 -3.0791495265049571e+00 , 3.3322640969296016e+00 , 8.9013671999999993e+00 , -2.0168300000000000e-02 , -9.9809300000000001e-01 , -5.8340700000000002e-02 -2.8431453170874064e+00 , 3.0975536766880651e+00 , 7.4383472000000008e+00 , -1.0450700000000000e-01 , 2.4783200000000000e-01 , 9.6314999999999995e-01 -2.7634063716847375e+00 , 3.0908202536016582e+00 , 7.4037256000000005e+00 , -4.0675000000000003e-02 , 3.9958600000000000e-01 , 9.1579299999999997e-01 -2.6880775351731221e+00 , 3.0938552213558070e+00 , 7.4290703999999996e+00 , 4.6170899999999998e-01 , 5.8122499999999999e-01 , 6.7007700000000003e-01 -2.6178102685551412e+00 , 3.1190289082481315e+00 , 7.5969888000000001e+00 , -6.8150699999999997e-01 , -7.2828999999999999e-01 , -7.1708300000000003e-02 -2.5392792813305793e+00 , 3.1340286864813631e+00 , 7.7021223999999995e+00 , 8.1929399999999997e-01 , 4.2939699999999997e-01 , 3.7996900000000000e-01 -2.4587076912642791e+00 , 3.1992148050215494e+00 , 8.1244040000000002e+00 , -4.3403000000000003e-01 , 6.4737999999999996e-01 , -6.2651199999999996e-01 -2.3703286093344742e+00 , 3.1904147772905018e+00 , 8.0829808000000014e+00 , 7.6251899999999997e-02 , 5.6801800000000002e-01 , 8.1947599999999998e-01 -2.2809502263498649e+00 , 3.1937109375085337e+00 , 8.1118512000000003e+00 , -1.5280500000000000e-01 , -6.3755599999999997e-03 , -9.8823600000000000e-01 -2.2049659835033042e+00 , 3.1519809779302972e+00 , 7.8516431999999998e+00 , -3.8158799999999998e-01 , 2.7909099999999998e-01 , 8.8119199999999998e-01 -2.1204086750194531e+00 , 3.1504074686145165e+00 , 7.8573944000000004e+00 , 1.2388700000000000e-01 , 1.5181100000000000e-01 , 9.8061500000000001e-01 -2.0234164970558335e+00 , 3.1705075611561919e+00 , 7.9944559999999996e+00 , -8.4770999999999996e-01 , 8.9623700000000001e-02 , -5.2283400000000002e-01 -1.7936460004979844e+00 , 3.3794244386844561e+00 , 9.3459983999999992e+00 , 7.3572099999999996e-01 , 6.1576600000000004e-01 , -2.8204200000000001e-01 -5.0531965200459465e+00 , 1.9405008068889498e+00 , 2.6968959999999997e-01 , -4.1212100000000002e-01 , -5.3536399999999998e-02 , 9.0955500000000000e-01 -5.3589412377040189e+00 , 1.9489018060020815e+00 , 3.5028959999999998e-01 , 4.0297699999999997e-01 , 8.6251800000000003e-02 , -9.1113699999999997e-01 -4.8000937316495227e+00 , 2.1022408376081652e+00 , 1.2977919999999998e+00 , -4.7469499999999998e-02 , 1.8319099999999999e-01 , 9.8193100000000000e-01 -4.8732138696948990e+00 , 2.1022599474253356e+00 , 1.3082252800000000e+00 , -8.2681400000000002e-02 , 1.9971200000000000e-01 , 9.7636000000000001e-01 -4.9541888666660050e+00 , 2.1021628606122866e+00 , 1.3144767200000000e+00 , 4.7327800000000003e-02 , -2.2289300000000001e-01 , -9.7369300000000003e-01 -5.0540595696547523e+00 , 2.1004598392982960e+00 , 1.3115283199999999e+00 , -7.1571700000000002e-02 , 1.7774799999999999e-01 , 9.8146999999999995e-01 -5.1285539853630979e+00 , 2.1027556789561510e+00 , 1.3282816799999999e+00 , -1.0869400000000000e-01 , 2.0719599999999999e-01 , 9.7224200000000005e-01 -5.2117913479230840e+00 , 2.1029622681017419e+00 , 1.3417923199999999e+00 , -9.7535399999999994e-02 , 1.8352900000000000e-01 , 9.7816400000000003e-01 -5.2947992262824730e+00 , 2.1046673763894450e+00 , 1.3574256000000000e+00 , -7.5323899999999999e-02 , 1.3979300000000000e-01 , 9.8731199999999997e-01 -5.3965667224687639e+00 , 2.1050191079674958e+00 , 1.3650727199999999e+00 , -5.3445500000000000e-02 , 1.7322000000000001e-01 , 9.8343199999999997e-01 -5.5169631280530904e+00 , 2.1031441673114455e+00 , 1.3656488800000002e+00 , -5.8175400000000002e-02 , 1.6353500000000001e-01 , 9.8482099999999995e-01 -5.6200760530004370e+00 , 2.1047109341315045e+00 , 1.3796192000000000e+00 , -5.5468600000000000e-02 , 1.8875200000000000e-01 , 9.8045700000000002e-01 -5.7327747494183772e+00 , 2.1044802708211914e+00 , 1.3919900000000001e+00 , -4.7706600000000002e-02 , 2.0659900000000000e-01 , 9.7726199999999996e-01 -5.8640283037856253e+00 , 2.1043774776113593e+00 , 1.3983964000000000e+00 , 6.2206999999999998e-02 , -1.8679299999999999e-01 , -9.8042799999999997e-01 -5.9869159801602443e+00 , 2.1052890202029588e+00 , 1.4133370400000000e+00 , -3.5606599999999999e-01 , 1.5722600000000000e-01 , 9.2113900000000004e-01 -6.1103853316723349e+00 , 2.1058961355276322e+00 , 1.4321485599999999e+00 , -5.6152400000000002e-01 , -1.7208200000000001e-01 , 8.0936900000000001e-01 -6.1968998210384934e+00 , 2.1110848602749366e+00 , 1.4711007199999999e+00 , -9.5233999999999996e-01 , -1.6825399999999999e-01 , -2.5443900000000003e-01 -6.0805703128414592e+00 , 2.1314778569413471e+00 , 1.5949252000000000e+00 , -9.6483500000000000e-01 , -1.6597500000000001e-01 , -2.0382600000000001e-01 -6.0868758039830579e+00 , 2.1421981773185386e+00 , 1.6652916000000000e+00 , 9.9446100000000004e-01 , 1.0328400000000000e-01 , 1.9494500000000001e-02 -6.0625945487899173e+00 , 2.1552955520991257e+00 , 1.7462067200000000e+00 , 9.8709100000000005e-01 , 1.5173700000000001e-01 , 5.1254599999999997e-02 -6.0669118428510069e+00 , 2.1659301295427520e+00 , 1.8157140800000000e+00 , 9.9257899999999999e-01 , 1.1678100000000000e-01 , -3.3916000000000002e-02 -6.0691821934608994e+00 , 2.1765593758326145e+00 , 1.8847680000000000e+00 , 9.7872000000000003e-01 , 5.9140399999999997e-03 , -2.0511399999999999e-01 -6.0791810335058436e+00 , 2.1861777253137484e+00 , 1.9504524240000001e+00 , 9.9553800000000003e-01 , 4.1670800000000001e-02 , -8.4664500000000004e-02 -6.0294783371568474e+00 , 2.1997799834450262e+00 , 2.0337182560000002e+00 , -9.6024399999999999e-01 , -2.7017700000000003e-04 , -2.7916400000000002e-01 -5.9974633707905829e+00 , 2.2121341727729162e+00 , 2.1092780000000002e+00 , 9.9607199999999996e-01 , 5.9914799999999997e-02 , -6.5203999999999998e-02 -6.0142403689865542e+00 , 2.2206137140533144e+00 , 2.1707576000000000e+00 , 9.9569799999999997e-01 , 7.2668800000000006e-02 , -5.7484599999999997e-02 -6.0192381647614823e+00 , 2.2311368652098129e+00 , 2.2345969600000002e+00 , 9.5458600000000005e-01 , -3.8680600000000002e-02 , -2.9541499999999998e-01 -6.0241880344496144e+00 , 2.2406400841839558e+00 , 2.2986412000000001e+00 , -9.1747299999999998e-01 , 7.2327900000000001e-02 , 3.9116800000000002e-01 -6.0775298610287543e+00 , 2.2480849100303133e+00 , 2.3522448800000002e+00 , -7.7786100000000002e-01 , 6.0079199999999999e-02 , 6.2555799999999995e-01 -6.1617219887832144e+00 , 2.2544699391912655e+00 , 2.4019007200000000e+00 , 4.1573900000000003e-01 , -1.4530299999999999e-01 , -8.9780199999999999e-01 -6.3268327261172264e+00 , 2.2583662864186538e+00 , 2.4406563200000000e+00 , 2.1577099999999999e-01 , -1.9438100000000000e-01 , -9.5690100000000000e-01 -6.6053592492259394e+00 , 2.2593843784312195e+00 , 2.4682558399999999e+00 , 6.9468000000000002e-02 , -1.6689399999999999e-01 , -9.8352499999999998e-01 -1.1727746992598792e+01 , 2.1290722365432635e+00 , 2.0396298239999999e+00 , -1.2478200000000000e-01 , 2.0634000000000000e-01 , 9.7049099999999999e-01 -1.2407619089883950e+01 , 2.1364416691483274e+00 , 2.1369607199999998e+00 , -8.4698700000000002e-02 , 2.0174200000000000e-01 , 9.7577000000000003e-01 -1.3459986601320873e+01 , 2.1373244145323640e+00 , 2.2288748800000002e+00 , -5.0742400000000000e-02 , 1.9038099999999999e-01 , 9.8039799999999999e-01 -1.4676890426428995e+01 , 2.1395453540332037e+00 , 2.3467474400000001e+00 , -5.7209299999999998e-02 , 1.9112199999999999e-01 , 9.7989800000000005e-01 -1.6382737729337144e+01 , 2.1398477233966964e+00 , 2.4855531200000001e+00 , -5.5637800000000001e-02 , 1.8567800000000001e-01 , 9.8103399999999996e-01 -1.8189695259375160e+01 , 2.1470421767401424e+00 , 2.6802983199999999e+00 , -6.8919400000000006e-02 , 1.8740599999999999e-01 , 9.7986200000000001e-01 -2.3654834486175826e+01 , 2.1706376685293463e+00 , 3.2731680000000001e+00 , -1.3247200000000001e-01 , 1.8437200000000001e-01 , 9.7388799999999998e-01 -2.6860459213789277e+01 , 2.2000047748727338e+00 , 3.7234568000000001e+00 , 6.4224999999999999e-01 , -3.7719599999999998e-01 , -6.6726200000000002e-01 -2.7407757562290634e+01 , 2.2609461415027083e+00 , 4.1690968000000002e+00 , 8.4664399999999995e-01 , -4.6230399999999999e-01 , -2.6356900000000000e-01 -2.7457769540191510e+01 , 2.3272720908320759e+00 , 4.6037543999999997e+00 , -8.6441999999999997e-01 , 4.3798999999999999e-01 , 2.4686600000000000e-01 -2.7490708045619090e+01 , 2.3935433751500774e+00 , 5.0399408000000001e+00 , 9.1000400000000004e-01 , -1.6811300000000001e-01 , -3.7898700000000002e-01 -2.7546269532964011e+01 , 2.4607608122081785e+00 , 5.4803080000000000e+00 , 2.7033499999999999e-01 , -9.5782199999999995e-01 , -9.7444100000000006e-02 -2.8234134192210412e+01 , 2.5318278326584336e+00 , 5.9955864000000005e+00 , -4.6942499999999998e-01 , 8.7148899999999996e-01 , 1.4194000000000001e-01 -2.8324722068763599e+01 , 2.6021449257734397e+00 , 6.4587919999999999e+00 , 3.9243899999999998e-01 , -8.8307500000000005e-01 , 2.5723499999999999e-01 -2.7880368487433454e+01 , 2.6667754037357367e+00 , 6.8481264000000008e+00 , -5.4169100000000003e-01 , 5.8101899999999995e-01 , -6.0744399999999998e-01 -2.6918818411969688e+01 , 2.7240318098314069e+00 , 7.1379432000000005e+00 , -8.3417300000000005e-01 , -4.9996000000000002e-01 , -2.3280000000000001e-01 -2.2957967580656597e+01 , 2.7281870540321997e+00 , 6.8456928000000001e+00 , -7.5807199999999997e-01 , -2.7355099999999999e-01 , -5.9202800000000000e-01 -2.2950132576313496e+01 , 2.7841132800352448e+00 , 7.2112216000000000e+00 , -7.5807199999999997e-01 , -2.7355099999999999e-01 , -5.9202800000000000e-01 -2.3402503037885410e+01 , 2.8505897198455394e+00 , 7.6799184000000000e+00 , -6.3629300000000000e-01 , 5.4538399999999998e-01 , 5.4560699999999995e-01 -2.2438612234258159e+01 , 2.8864138769769827e+00 , 7.8311656000000003e+00 , 4.4874100000000000e-01 , 3.1496099999999999e-01 , 8.3631999999999995e-01 -2.1889030136230257e+01 , 2.9278246273131967e+00 , 8.0565128000000001e+00 , 8.2945800000000003e-01 , -3.3373000000000003e-01 , 4.4791100000000000e-01 -2.3683986419248093e+01 , 3.0361017239440069e+00 , 8.9084079999999997e+00 , -9.1415599999999997e-01 , 4.0533999999999998e-01 , 4.2238800000000002e-03 -2.3348926996188240e+01 , 3.0860970709458897e+00 , 9.2063367999999990e+00 , -8.5693500000000000e-01 , 6.2922900000000004e-02 , -5.1156900000000005e-01 -2.1789637009022016e+01 , 3.0909694968016566e+00 , 9.1137663999999994e+00 , 5.3879699999999997e-01 , -7.5223799999999996e-01 , 3.7925700000000001e-01 -2.1177949703586211e+01 , 3.1241416231737706e+00 , 9.2797191999999988e+00 , 6.4566000000000001e-01 , 4.9136500000000000e-01 , -5.8453800000000000e-01 -2.1654748165113137e+01 , 3.1994112354057860e+00 , 9.8077375999999994e+00 , -8.1740400000000002e-01 , -5.3232500000000005e-01 , 2.2018199999999999e-01 -2.0689976966710940e+01 , 3.2694170423523019e+00 , 1.0186464000000001e+01 , 6.5661999999999998e-01 , 5.9140199999999998e-01 , 4.6807500000000002e-01 -2.4523610696969818e+01 , 3.5190766606231949e+00 , 1.2122444800000000e+01 , -6.2845600000000001e-01 , 6.6400499999999996e-01 , -4.0514299999999998e-01 -2.1040282159100432e+01 , 3.4012420643121715e+00 , 1.1073594400000001e+01 , -8.4467000000000003e-01 , 3.5625099999999998e-01 , 3.9952100000000002e-01 -2.1616494518481492e+01 , 3.4933424643002011e+00 , 1.1716969600000001e+01 , -6.6297300000000003e-01 , -3.4311900000000001e-01 , 6.6538399999999998e-01 -2.1001774254563678e+01 , 3.5179199135122134e+00 , 1.1829071200000000e+01 , -7.7882899999999999e-01 , 5.3483800000000004e-01 , -3.2767900000000000e-01 -2.0602062865306472e+01 , 3.5539182901355839e+00 , 1.2027867199999999e+01 , -6.3367799999999996e-01 , 7.5899300000000003e-01 , -1.4960599999999999e-01 -2.0949964847716597e+01 , 3.6373981841320795e+00 , 1.2600720000000001e+01 , 6.2204899999999996e-01 , -7.8219200000000000e-01 , -3.5068000000000002e-02 -2.0889452815605225e+01 , 3.6956347533262894e+00 , 1.2977096000000000e+01 , -8.2564899999999997e-01 , 5.2803999999999995e-01 , 1.9869100000000001e-01 -2.1772556989619371e+01 , 3.8248701727737151e+00 , 1.3885952000000001e+01 , -6.3284600000000002e-01 , 6.2085100000000004e-01 , 4.6265400000000001e-01 -2.2466881263136884e+01 , 3.9467812158353692e+00 , 1.4734072000000001e+01 , -8.8915500000000003e-01 , 3.0593700000000001e-01 , 3.4030199999999999e-01 -2.2277120211897330e+01 , 4.0029270942719908e+00 , 1.5088191999999999e+01 , 9.4696400000000003e-01 , -1.0665100000000000e-01 , -3.0312600000000001e-01 -6.4717326885164494e+00 , 2.7434275152274283e+00 , 5.6117016000000000e+00 , 6.1456900000000003e-01 , -1.1407000000000000e-01 , 7.8057200000000004e-01 -6.3656226401416189e+00 , 2.7495790031314646e+00 , 5.6406863999999999e+00 , 6.1456999999999995e-01 , -1.1407000000000000e-01 , 7.8057200000000004e-01 -2.5459290705054034e+01 , 4.5196704398789347e+00 , 1.8706248000000002e+01 , 3.7825799999999998e-01 , -1.5955900000000001e-01 , -9.1184500000000002e-01 -2.3757132571794454e+01 , 4.4467266023291234e+00 , 1.8096807999999999e+01 , 4.4620599999999999e-01 , -7.5945100000000001e-02 , -8.9170199999999999e-01 -6.1832565207359416e+00 , 2.7775155675619039e+00 , 5.8089376000000001e+00 , -8.5145599999999999e-01 , 2.5252200000000002e-01 , -4.5962500000000001e-01 -6.1761494521866185e+00 , 2.7927358350260265e+00 , 5.9040559999999997e+00 , 7.5439900000000004e-01 , 2.4122900000000000e-01 , 6.1048500000000006e-01 -6.1093578551462802e+00 , 2.8015958434270778e+00 , 5.9548496000000002e+00 , -8.1566300000000003e-01 , 2.3442499999999999e-01 , -5.2890300000000001e-01 -6.0502767881768849e+00 , 2.8101617308395670e+00 , 6.0111135999999998e+00 , 8.1026299999999996e-01 , -3.1140499999999999e-01 , 4.9648799999999998e-01 -6.0293392668051160e+00 , 2.8245623678571570e+00 , 6.0992119999999996e+00 , 9.9570300000000000e-01 , 5.9200900000000001e-02 , 7.1207800000000002e-02 -6.0775050001701247e+00 , 2.8463391288419979e+00 , 6.2491903999999998e+00 , 9.9631800000000004e-01 , -8.2247200000000006e-02 , -2.4201100000000000e-02 -6.0058106723329034e+00 , 2.8548337189596564e+00 , 6.2971447999999999e+00 , -9.2086699999999999e-01 , 8.0062800000000003e-02 , -3.8156899999999999e-01 -6.0764931441804784e+00 , 2.8819021732674575e+00 , 6.4781984000000001e+00 , 7.3728199999999999e-01 , -3.4948800000000002e-01 , 5.7816400000000001e-01 -6.0017141104036265e+00 , 2.8904330910551730e+00 , 6.5256640000000008e+00 , 7.1198099999999998e-01 , -4.9843199999999999e-01 , 4.9462000000000000e-01 -5.8745250697534299e+00 , 2.8905867524624331e+00 , 6.5203704000000009e+00 , -6.5011600000000003e-01 , 3.0764999999999998e-01 , -6.9476700000000002e-01 -5.8066662750544831e+00 , 2.8995289313579780e+00 , 6.5713512000000005e+00 , -5.0729599999999997e-01 , 4.3273000000000000e-01 , -7.4524900000000005e-01 -5.8567255650409322e+00 , 2.9269360955741570e+00 , 6.7496800000000006e+00 , 9.7528000000000004e-01 , -1.7828300000000000e-01 , -1.3055600000000001e-01 -5.9502838322163853e+00 , 2.9618175200641073e+00 , 6.9849487999999997e+00 , -9.6140899999999996e-01 , 2.0855899999999999e-01 , 1.7943200000000001e-01 -5.9283131216949894e+00 , 2.9794305006859383e+00 , 7.0992968000000003e+00 , 9.7877700000000001e-01 , -1.9317799999999999e-01 , 6.8396399999999996e-02 -5.8829049961393718e+00 , 2.9933621236918797e+00 , 7.1903800000000002e+00 , -9.4342899999999996e-01 , 2.3785999999999999e-01 , -2.3100799999999999e-01 -5.9268812076991919e+00 , 3.0249703482981367e+00 , 7.3935336000000005e+00 , -6.5613900000000003e-01 , -5.9022600000000003e-01 , -4.7022799999999998e-01 -5.8125048979480569e+00 , 3.0277186259599116e+00 , 7.4038608000000004e+00 , 4.3164100000000000e-01 , 5.2880799999999994e-01 , 7.3078600000000005e-01 -5.7238281622039198e+00 , 3.0344529564654570e+00 , 7.4447224000000007e+00 , -4.3994100000000003e-01 , -3.5283999999999999e-01 , -8.2580600000000004e-01 -5.6460237830570792e+00 , 3.0447166021089282e+00 , 7.5001336000000007e+00 , -5.1899200000000001e-01 , -2.5499899999999998e-01 , -8.1585700000000005e-01 -5.8921545988624029e+00 , 3.1209528968192957e+00 , 8.0206432000000003e+00 , 4.0706700000000001e-01 , 1.0212000000000000e-01 , 9.0767200000000003e-01 -6.0751477742421880e+00 , 3.1901175976930620e+00 , 8.4820391999999991e+00 , -4.5844400000000002e-01 , 8.5670000000000002e-01 , 2.3642099999999999e-01 -5.5647495237156477e+00 , 3.1068569695724531e+00 , 7.9018960000000007e+00 , -3.5180899999999998e-01 , 4.2667400000000000e-01 , 8.3317399999999997e-01 -5.2009930008142975e+00 , 3.0514926645303726e+00 , 7.5073096000000001e+00 , 1.3572200000000001e-01 , 2.9472999999999999e-01 , -9.4589299999999998e-01 -5.0645239258907768e+00 , 3.0450255326715991e+00 , 7.4566407999999997e+00 , 2.0203900000000000e-01 , -4.0395599999999997e-02 , -9.7854399999999997e-01 -4.8689847114220024e+00 , 3.0229901675535755e+00 , 7.2950040000000005e+00 , -7.0005200000000001e-01 , -6.4395100000000005e-01 , 3.0863299999999999e-01 -4.7053155799986452e+00 , 3.0055433152699775e+00 , 7.1734800000000005e+00 , -7.1614999999999995e-01 , -5.5023800000000000e-01 , 4.2937900000000001e-01 -4.7190207601615155e+00 , 3.0371858992255412e+00 , 7.3756248000000006e+00 , -7.1615099999999998e-01 , -5.5023800000000000e-01 , 4.2937900000000001e-01 -5.1868299291814335e+00 , 3.2023964453352050e+00 , 8.4904527999999999e+00 , 5.6250800000000001e-01 , 1.2599299999999999e-01 , 8.1713499999999994e-01 -4.9122042255149418e+00 , 3.1561702543897532e+00 , 8.1655256000000005e+00 , -6.7239899999999997e-01 , 4.6955100000000000e-01 , 5.7219100000000001e-01 -4.6397001509768625e+00 , 3.1055501401555912e+00 , 7.8139640000000004e+00 , 4.7449000000000002e-01 , 8.0855800000000000e-01 , -3.4798499999999999e-01 -4.6473157691550604e+00 , 3.1427868244708939e+00 , 8.0583848000000007e+00 , -3.5291800000000001e-01 , 7.5443800000000005e-01 , 5.5341799999999997e-01 -4.3958818107356610e+00 , 3.0921359223988345e+00 , 7.7058976000000001e+00 , -2.9230200000000001e-02 , -3.8963500000000001e-01 , 9.2050500000000002e-01 -4.4710998850073649e+00 , 3.1564542512802256e+00 , 8.1307896000000000e+00 , -7.5189799999999996e-01 , -4.5151000000000002e-01 , -4.8040500000000003e-01 -4.3342308577209829e+00 , 3.1439508578020514e+00 , 8.0395192000000009e+00 , 5.8108599999999999e-01 , -3.4103699999999998e-01 , -7.3894099999999996e-01 -4.1591567311618869e+00 , 3.1133004303288567e+00 , 7.8289400000000002e+00 , -2.7250400000000002e-01 , 5.9448199999999995e-01 , 7.5652699999999995e-01 -4.0720691792707555e+00 , 3.1176392930565040e+00 , 7.8477119999999996e+00 , 1.6306999999999999e-01 , 6.8664099999999995e-01 , 7.0847199999999999e-01 -3.9528176855087049e+00 , 3.1064850973016638e+00 , 7.7669040000000003e+00 , -2.2720399999999999e-01 , 6.3278699999999999e-01 , 7.4024299999999998e-01 -3.8611756707380138e+00 , 3.1073794265978698e+00 , 7.7623280000000001e+00 , 4.0911500000000001e-01 , 6.6701900000000003e-01 , 6.2266400000000000e-01 -3.7637089659515692e+00 , 3.1041854752016107e+00 , 7.7362136000000010e+00 , -1.3298399999999999e-01 , 3.6384100000000003e-01 , -9.2191900000000004e-01 -3.6655476510084064e+00 , 3.0997067970699783e+00 , 7.6983056000000003e+00 , 5.5624399999999997e-02 , 9.5070299999999996e-01 , 3.0507499999999999e-01 -3.5697158552064332e+00 , 3.0947293814013284e+00 , 7.6584215999999996e+00 , 5.5926399999999998e-01 , -1.4166300000000001e-01 , -8.1679599999999997e-01 -3.4771154124868664e+00 , 3.0912431815209604e+00 , 7.6266392000000005e+00 , 2.3481800000000000e-01 , 9.4653699999999996e-01 , -2.2119700000000000e-01 -3.3868102602447010e+00 , 3.0873224028206385e+00 , 7.5931720000000000e+00 , 1.8588199999999999e-01 , 9.7904199999999997e-01 , -8.3218500000000001e-02 -3.2947691273187352e+00 , 3.0810770411050061e+00 , 7.5477967999999995e+00 , -2.8511799999999998e-01 , 5.0506700000000004e-01 , 8.1462599999999996e-01 -3.2060839391982388e+00 , 3.0753941751637948e+00 , 7.5006744000000003e+00 , 2.1231500000000000e-01 , -7.0773299999999995e-01 , -6.7382200000000003e-01 -3.1261979736770993e+00 , 3.0760866063774914e+00 , 7.5028791999999997e+00 , -2.2764400000000001e-01 , 9.5306500000000002e-02 , 9.6906899999999996e-01 -3.0493297124436314e+00 , 3.0804235300900924e+00 , 7.5238144000000000e+00 , -3.1794600000000001e-01 , 1.6464799999999999e-01 , 9.3370299999999995e-01 -2.9900390910757837e+00 , 3.1082403871759405e+00 , 7.6966624000000010e+00 , 6.1292800000000003e-01 , 7.6685400000000004e-01 , -1.9040899999999999e-01 -2.8832442985226741e+00 , 3.0714939346561021e+00 , 7.4493191999999997e+00 , -9.6661600000000000e-02 , 1.6096600000000000e-01 , 9.8221499999999995e-01 -2.8033164761502189e+00 , 3.0679746564145773e+00 , 7.4253368000000002e+00 , -1.2758100000000000e-01 , 2.8711599999999998e-01 , 9.4936200000000004e-01 -2.7263798841346452e+00 , 3.0681624178940261e+00 , 7.4203968000000007e+00 , 3.4093000000000001e-01 , 6.2202400000000002e-01 , 7.0487800000000000e-01 -2.6592830762267723e+00 , 3.1045818233522535e+00 , 7.6500807999999996e+00 , 7.9915999999999998e-01 , 5.4617899999999997e-01 , 2.5106200000000001e-01 -2.5798519163335185e+00 , 3.1105321381079891e+00 , 7.6837456000000000e+00 , 6.2219400000000002e-01 , 6.6321300000000005e-01 , 4.1596100000000003e-01 -2.4997302033229984e+00 , 3.1336880679265882e+00 , 7.8290128000000001e+00 , 6.8769499999999995e-01 , 5.2971299999999999e-01 , 4.9646699999999999e-01 -2.4115953264731687e+00 , 3.2216584007038218e+00 , 8.3943984000000000e+00 , -8.5996300000000003e-01 , 4.9937500000000001e-01 , -1.0529900000000000e-01 -2.3253679580828317e+00 , 3.1807808374034057e+00 , 8.1151583999999986e+00 , -4.5151900000000000e-01 , -2.1409600000000001e-01 , -8.6619500000000005e-01 -2.2422532803571515e+00 , 3.1589982994762060e+00 , 7.9682168000000004e+00 , -9.3459999999999999e-01 , 2.2493500000000000e-02 , 3.5499000000000003e-01 -2.1631170452548516e+00 , 3.1398898600162406e+00 , 7.8406504000000004e+00 , 2.6492300000000002e-01 , 8.9610499999999996e-02 , 9.6009699999999998e-01 -2.0774123737785541e+00 , 3.1453951087348306e+00 , 7.8655376000000006e+00 , -5.2107300000000001e-01 , 7.4734900000000007e-02 , 8.5023400000000005e-01 -1.6093683135014478e+00 , 3.7630498818376044e+00 , 1.1848488000000000e+01 , 2.8867700000000002e-01 , -9.4472999999999996e-01 , -1.5540699999999999e-01 -1.7497864700345349e+00 , 3.3596356365717686e+00 , 9.2384416000000016e+00 , -9.4550699999999999e-01 , 2.4715500000000001e-01 , -2.1196699999999999e-01 -5.0477983337084726e+00 , 1.8688208050854878e+00 , 2.3425680000000004e-01 , -4.1212100000000002e-01 , -5.3536599999999997e-02 , 9.0955500000000000e-01 -5.0978754127490049e+00 , 1.8737351444681885e+00 , 2.7987120000000010e-01 , -4.1212100000000002e-01 , -5.3536599999999997e-02 , 9.0955500000000000e-01 -4.8384251590901162e+00 , 2.0391483065903651e+00 , 1.3090343999999998e+00 , -6.2134799999999997e-02 , 1.9129800000000000e-01 , 9.7956299999999996e-01 -4.9204540152873726e+00 , 2.0367838733102186e+00 , 1.3148105600000000e+00 , -7.7140200000000006e-02 , 1.9340299999999999e-01 , 9.7808200000000001e-01 -4.9851274287894736e+00 , 2.0369074402019307e+00 , 1.3344884000000001e+00 , -5.1434700000000000e-02 , 1.7174800000000001e-01 , 9.8379700000000003e-01 -5.0757228468703408e+00 , 2.0338473736874891e+00 , 1.3386380000000000e+00 , -5.4475700000000002e-02 , 2.0183400000000001e-01 , 9.7790400000000000e-01 -5.1680977841913194e+00 , 2.0312743107168489e+00 , 1.3455685600000000e+00 , -8.7013699999999999e-02 , 2.1827900000000000e-01 , 9.7199899999999995e-01 -5.2601177020286105e+00 , 2.0282016373173724e+00 , 1.3552332800000000e+00 , 7.0769299999999993e-02 , -1.5878600000000001e-01 , -9.8477300000000001e-01 -5.3608791049184701e+00 , 2.0252455529212678e+00 , 1.3620556800000001e+00 , 7.3299600000000006e-02 , -1.6967599999999999e-01 , -9.8277000000000003e-01 -5.4543896915762753e+00 , 2.0242418717952293e+00 , 1.3770285600000001e+00 , -5.3928900000000002e-02 , 1.6638500000000001e-01 , 9.8458500000000004e-01 -5.5565120956814784e+00 , 2.0213770354864335e+00 , 1.3898725600000001e+00 , -5.7353599999999998e-02 , 1.6731799999999999e-01 , 9.8423300000000002e-01 -5.6693390443645466e+00 , 2.0187338419850369e+00 , 1.4008331199999999e+00 , -8.7811700000000006e-02 , 1.9503300000000001e-01 , 9.7685800000000000e-01 -5.7906610061052586e+00 , 2.0144392694066111e+00 , 1.4106767200000001e+00 , -5.2502899999999998e-02 , 1.8209500000000001e-01 , 9.8187800000000003e-01 -5.9136732233983071e+00 , 2.0118572763379898e+00 , 1.4241072799999999e+00 , -6.5276100000000004e-02 , 1.9429800000000000e-01 , 9.7876799999999997e-01 -6.0372421848897169e+00 , 2.0089891476036619e+00 , 1.4415116800000001e+00 , 2.0891100000000001e-01 , -2.0075499999999999e-01 , -9.5710700000000004e-01 -6.1792060260242803e+00 , 2.0054152897006459e+00 , 1.4540665600000000e+00 , -8.9571800000000001e-01 , 8.4383700000000006e-02 , 4.3654300000000001e-01 -6.1982261060081436e+00 , 2.0142412886252452e+00 , 1.5230092000000000e+00 , -9.6681499999999998e-01 , -2.5537399999999999e-01 , -7.2642999999999996e-03 -6.1008625974717505e+00 , 2.0361889168798433e+00 , 1.6375246400000001e+00 , -9.6374899999999997e-01 , -1.5536100000000000e-01 , -2.1691299999999999e-01 -6.1158965038343949e+00 , 2.0448393252377901e+00 , 1.7047502400000001e+00 , 9.9709800000000004e-01 , 7.6107499999999995e-02 , 1.9101599999999999e-03 -6.1113059139511918e+00 , 2.0567540163862938e+00 , 1.7787160799999999e+00 , 9.9409000000000003e-01 , 9.2122700000000002e-02 , 5.7426800000000000e-02 -6.0948461232275797e+00 , 2.0686959238612870e+00 , 1.8555533600000000e+00 , 9.9495800000000001e-01 , 4.7569199999999999e-02 , -8.8294300000000006e-02 -6.0862500759221723e+00 , 2.0804778061286999e+00 , 1.9280051679999999e+00 , -9.8159099999999999e-01 , -7.9853099999999996e-02 , 1.7350199999999999e-01 -6.1265484802974335e+00 , 2.0870942311511973e+00 , 1.9852674640000001e+00 , -9.7371700000000005e-01 , -2.1333700000000000e-01 , -7.9760999999999999e-02 -6.0259869645425335e+00 , 2.1057109979849629e+00 , 2.0825613359999999e+00 , 9.5508899999999997e-01 , 1.0474500000000000e-01 , 2.7718999999999999e-01 -6.0427104502737299e+00 , 2.1142974796679868e+00 , 2.1445475200000002e+00 , 9.9804599999999999e-01 , 3.1087100000000002e-03 , -6.2413400000000001e-02 -6.0389281933941144e+00 , 2.1247896051922361e+00 , 2.2116337599999998e+00 , 9.8180999999999996e-01 , 2.3728099999999998e-02 , -1.8837599999999999e-01 -6.0438394954802739e+00 , 2.1343783875375024e+00 , 2.2760825599999999e+00 , -9.5173799999999997e-01 , -1.4896899999999999e-02 , 3.0655100000000002e-01 -6.0788020148705471e+00 , 2.1414051553978490e+00 , 2.3342341600000003e+00 , -8.7606200000000001e-01 , -2.1923100000000001e-02 , 4.8170000000000002e-01 -6.1222587131108765e+00 , 2.1478839735736055e+00 , 2.3914684799999999e+00 , -6.8976300000000001e-01 , 6.5677399999999997e-02 , 7.2104999999999997e-01 -6.2158378598116970e+00 , 2.1517245559753801e+00 , 2.4410463199999999e+00 , -3.8214900000000002e-01 , 1.5090999999999999e-01 , 9.1169599999999995e-01 -6.4327327660918927e+00 , 2.1481877818471462e+00 , 2.4750418399999998e+00 , -1.1201600000000000e-01 , 1.6505200000000000e-01 , 9.7990299999999997e-01 -1.2009171298666592e+01 , 1.8626911280076595e+00 , 2.1319936799999999e+00 , -1.2476000000000000e-01 , 2.0079300000000000e-01 , 9.7165699999999999e-01 -1.2884742610139172e+01 , 1.8409999144033609e+00 , 2.2269675200000001e+00 , -5.4055899999999997e-02 , 1.9441800000000001e-01 , 9.7942799999999997e-01 -1.4059533589322857e+01 , 1.8075504905757347e+00 , 2.3327022400000001e+00 , -5.7639099999999999e-02 , 1.8700200000000000e-01 , 9.8066699999999996e-01 -1.5327372956045805e+01 , 1.7752204405833043e+00 , 2.4744074400000002e+00 , -4.7872499999999998e-02 , 1.9274500000000000e-01 , 9.8007999999999995e-01 -1.7217306438897456e+01 , 1.7211978048647136e+00 , 2.6412265599999998e+00 , -6.8740099999999998e-02 , 1.8596099999999999e-01 , 9.8014999999999997e-01 -1.9240157614049931e+01 , 1.6710600776475584e+00 , 2.8713275999999999e+00 , -8.6455500000000005e-02 , 2.0910100000000001e-01 , 9.7406499999999996e-01 -2.7281675598265263e+01 , 1.5134966967600771e+00 , 4.0582536000000005e+00 , 9.2790899999999998e-01 , -3.2616899999999999e-01 , -1.8054999999999999e-01 -2.8882502823383909e+01 , 1.5241009493361917e+00 , 4.5789504000000001e+00 , -2.9772900000000002e-01 , 4.5052799999999998e-01 , 8.4165400000000001e-01 -3.1011240692216049e+01 , 1.5279624501000697e+00 , 5.1946928000000003e+00 , -3.4683100000000000e-01 , 3.5646800000000001e-01 , 8.6754799999999999e-01 -3.0568616962537945e+01 , 1.6144213109026484e+00 , 5.6506080000000001e+00 , -8.4300200000000006e-02 , 4.0943900000000000e-01 , 9.0843399999999996e-01 -2.8362164956176308e+01 , 1.7447578200264278e+00 , 5.9004367999999996e+00 , 7.0795399999999997e-01 , 7.0503700000000002e-01 , -4.1517400000000003e-02 -2.7454941102420566e+01 , 1.8329233039299373e+00 , 6.2393311999999996e+00 , 4.9416100000000002e-01 , -6.6279399999999999e-01 , 5.6259099999999995e-01 -2.7182358685139135e+01 , 1.9050276233404135e+00 , 6.6391488000000001e+00 , 7.0603899999999997e-01 , -5.9602400000000000e-01 , 3.8244499999999998e-01 -2.6379424880354229e+01 , 1.9843986376055796e+00 , 6.9460839999999999e+00 , -5.3428200000000003e-01 , 6.3006200000000001e-01 , -5.6352899999999995e-01 -2.6565821513473132e+01 , 2.0453586741122676e+00 , 7.4043392000000008e+00 , 5.3428200000000003e-01 , -6.3006200000000001e-01 , 5.6352899999999995e-01 -2.6846255507051449e+01 , 2.1067471911749682e+00 , 7.8901648000000000e+00 , 4.7302200000000000e-01 , -3.3766600000000002e-01 , 8.1377600000000005e-01 -2.3120049061771581e+01 , 2.2076303978340373e+00 , 7.5272360000000003e+00 , -7.4625699999999995e-01 , -3.1226399999999999e-01 , -5.8787000000000000e-01 -2.3192834928777454e+01 , 2.2631649102028613e+00 , 7.9186088000000003e+00 , -7.8422499999999995e-01 , -4.1962200000000000e-01 , -4.5706500000000000e-01 -2.2038020764696594e+01 , 2.3252719590560837e+00 , 8.0067383999999997e+00 , -5.7156499999999999e-01 , -2.1706100000000000e-01 , -7.9132700000000000e-01 -2.1839252953237914e+01 , 2.3797830842406418e+00 , 8.3139128000000007e+00 , 7.8901600000000005e-01 , -1.8521899999999999e-01 , 5.8578799999999998e-01 -2.1645945132327089e+01 , 2.4335333760812530e+00 , 8.6185808000000002e+00 , 7.8901600000000005e-01 , -1.8521799999999999e-01 , 5.8578799999999998e-01 -2.0642907351467507e+01 , 2.4829209956663219e+00 , 8.6708096000000019e+00 , -6.9867800000000002e-01 , -6.5510699999999999e-01 , -2.8754900000000000e-01 -2.4953850196338351e+01 , 2.5655759212782936e+00 , 1.0422481599999999e+01 , -9.0213600000000005e-01 , 1.9822999999999999e-01 , 3.8321699999999997e-01 -2.4714393454971560e+01 , 2.6281701274529596e+00 , 1.0771734400000000e+01 , -4.3281599999999998e-01 , 7.3279499999999997e-01 , -5.2505500000000005e-01 -2.0973252533793715e+01 , 2.6446355769891770e+00 , 9.8389896000000014e+00 , -2.7968700000000002e-01 , -9.5798000000000005e-01 , -6.3633899999999993e-02 -2.2697046001870046e+01 , 2.7265386808664984e+00 , 1.0866374400000000e+01 , -9.1356499999999996e-01 , 8.0123799999999995e-02 , 3.9872299999999999e-01 -2.0033954680092826e+01 , 2.7371230936920368e+00 , 1.0192454400000001e+01 , 3.9319500000000002e-01 , 5.5879400000000001e-01 , 7.3016899999999996e-01 -1.9592024772032953e+01 , 2.7803745236110045e+00 , 1.0360300000000001e+01 , 6.0750099999999996e-01 , 3.5547699999999999e-01 , 7.1033700000000000e-01 -2.2416243942441813e+01 , 2.9035801663028322e+00 , 1.1969720800000001e+01 , 8.0242999999999998e-01 , 3.9351700000000001e-01 , 4.4861000000000001e-01 -2.2104266398431413e+01 , 3.0203106341046833e+00 , 1.2656464000000001e+01 , -7.9839199999999999e-01 , -2.1105099999999999e-01 , -5.6393899999999997e-01 -2.0507669013453491e+01 , 3.0286246264002257e+00 , 1.2267524800000000e+01 , -9.6454600000000001e-01 , 2.4723300000000001e-01 , 9.2343499999999995e-02 -2.1006156574230896e+01 , 3.1063064817258175e+00 , 1.2928008000000000e+01 , -9.4300700000000004e-01 , 4.2289599999999997e-02 , 3.3007300000000001e-01 -2.1114196726822552e+01 , 3.1737625773718916e+00 , 1.3401936000000001e+01 , 8.9352799999999999e-01 , -1.1433500000000001e-01 , -4.3420599999999998e-01 -2.0913092860753835e+01 , 3.2277577147475505e+00 , 1.3711232000000001e+01 , 7.2877700000000001e-01 , -4.0225300000000003e-01 , -5.5414399999999997e-01 -2.2178176332103043e+01 , 3.3529807245181376e+00 , 1.4897976000000000e+01 , -7.9367299999999996e-01 , 2.1478600000000000e-01 , 5.6916599999999995e-01 -2.2859515347627802e+01 , 3.4588571706749187e+00 , 1.5790192000000001e+01 , 7.7827000000000002e-01 , -3.7466400000000000e-01 , -5.0390699999999999e-01 -6.3762872469729084e+00 , 2.6217443513534198e+00 , 5.6198136000000005e+00 , 5.9475000000000000e-01 , -1.3193299999999999e-01 , 7.9301100000000002e-01 -2.3653011379937492e+01 , 3.6553296655860708e+00 , 1.7324712000000002e+01 , -9.2052100000000003e-01 , 3.7065799999999999e-01 , -1.2350600000000000e-01 -6.2676104475868808e+00 , 2.6445364896612391e+00 , 5.7413688000000000e+00 , 7.4503500000000000e-01 , -2.6146700000000000e-01 , 6.1364399999999997e-01 -6.2037458277276469e+00 , 2.6558134161078373e+00 , 5.7942631999999996e+00 , -8.6950099999999997e-01 , 2.8471400000000002e-01 , -4.0361500000000000e-01 -6.2389380290062197e+00 , 2.6723861790654269e+00 , 5.9209144000000000e+00 , -9.6052000000000004e-01 , 8.3019399999999993e-02 , -2.6553599999999999e-01 -6.2382114142124321e+00 , 2.6878537445022195e+00 , 6.0238952000000001e+00 , -7.4231800000000003e-01 , 1.3131999999999999e-01 , -6.5705300000000000e-01 -6.0967009959502105e+00 , 2.6935357053293920e+00 , 6.0166256000000002e+00 , -6.0096899999999998e-01 , 7.2127499999999997e-02 , -7.9601100000000002e-01 -6.0528777153094140e+00 , 2.7050932652114961e+00 , 6.0857128000000005e+00 , -9.7452600000000000e-01 , 1.8026000000000000e-01 , -1.3343800000000000e-01 -6.0783573546513354e+00 , 2.7236701489749056e+00 , 6.2149848000000008e+00 , 9.7380999999999995e-01 , -1.4184200000000000e-01 , 1.7769499999999999e-01 -6.0929257051540784e+00 , 2.7416842358179192e+00 , 6.3391191999999998e+00 , 9.9479899999999999e-01 , -4.5117200000000003e-02 , 9.1326299999999999e-02 -5.9136142846299089e+00 , 2.7413073798697631e+00 , 6.2884503999999994e+00 , 7.8432400000000002e-01 , -3.7476300000000001e-01 , 4.9435600000000002e-01 -5.9391284362488062e+00 , 2.7615985477123948e+00 , 6.4262400000000000e+00 , -8.5874700000000004e-01 , 3.1879800000000003e-01 , -4.0114899999999998e-01 -5.8947260717841310e+00 , 2.7741806275882803e+00 , 6.5002880000000003e+00 , -6.8628699999999998e-01 , 2.1184000000000000e-01 , -6.9579700000000000e-01 -5.8482914215346788e+00 , 2.7867374160631471e+00 , 6.5737848000000003e+00 , -6.8628699999999998e-01 , 2.1184000000000000e-01 , -6.9579700000000000e-01 -5.7934248243918809e+00 , 2.7990640197202659e+00 , 6.6390655999999995e+00 , 9.9434100000000003e-01 , -1.0063100000000000e-01 , 3.4067000000000000e-02 -5.9255226161500794e+00 , 2.8343194326374319e+00 , 6.9107656000000004e+00 , -9.3219500000000000e-01 , 3.1362699999999999e-01 , 1.8069600000000000e-01 -5.7895660912673765e+00 , 2.8374162673351488e+00 , 6.8918480000000004e+00 , -9.0444500000000005e-01 , 3.6270900000000000e-01 , 2.2454900000000000e-01 -5.8764028830693542e+00 , 2.8700683259189410e+00 , 7.1304135999999998e+00 , -9.3153600000000003e-01 , 3.4247200000000000e-01 , -1.2228000000000000e-01 -5.9947225767994361e+00 , 2.9086954388408186e+00 , 7.4211663999999997e+00 , -9.7313700000000003e-01 , -1.9581000000000001e-01 , -1.2108900000000000e-01 -5.8474202236924313e+00 , 2.9101798809354547e+00 , 7.3918488000000000e+00 , 5.3143499999999999e-01 , 4.6626600000000001e-01 , 7.0723000000000003e-01 -5.9154293742337485e+00 , 2.9443114931976195e+00 , 7.6390047999999995e+00 , 9.9061800000000000e-01 , -1.1158800000000001e-01 , 7.8890900000000000e-02 -5.6639886977488327e+00 , 2.9283483012210332e+00 , 7.4639623999999998e+00 , -5.2645900000000001e-01 , -9.4929100000000002e-02 , -8.4488399999999997e-01 -5.5736911658877730e+00 , 2.9376340476983422e+00 , 7.5013192000000002e+00 , -8.2024700000000006e-02 , -6.8102700000000005e-01 , -7.2765000000000002e-01 -5.4141231229848712e+00 , 2.9341916730922941e+00 , 7.4343744000000003e+00 , 2.5847300000000001e-01 , 7.2155400000000003e-01 , 6.4230200000000004e-01 -5.3432623086493907e+00 , 2.9459031727963851e+00 , 7.4931863999999999e+00 , 2.5418900000000000e-01 , 6.6685000000000005e-01 , 7.0049899999999998e-01 -5.2767636882272786e+00 , 2.9589191493334512e+00 , 7.5594136000000001e+00 , 1.9839899999999999e-01 , 5.4603999999999997e-01 , 8.1392699999999996e-01 -5.1329610699589399e+00 , 2.9564876717258812e+00 , 7.5008511999999996e+00 , -6.5314800000000006e-02 , 4.9251200000000001e-01 , 8.6785100000000004e-01 -5.0031216248889407e+00 , 2.9553204085126223e+00 , 7.4568176000000008e+00 , -1.6285400000000000e-01 , 7.3865300000000000e-01 , 6.5411799999999998e-01 -4.9101557610857753e+00 , 2.9614367828355221e+00 , 7.4725944000000002e+00 , 1.2912099999999999e-02 , -7.0193300000000003e-01 , -7.1212600000000004e-01 -4.8714357421657883e+00 , 2.9797516199686598e+00 , 7.5868696000000009e+00 , -5.1883699999999999e-01 , -3.6210799999999999e-01 , -7.7439400000000003e-01 -4.8586524571428642e+00 , 3.0059079994419795e+00 , 7.7561296000000004e+00 , -7.8545299999999996e-01 , -5.1285800000000004e-01 , -3.4646800000000000e-01 -5.1044123405478636e+00 , 3.1017725801720886e+00 , 8.4635688000000009e+00 , 7.2179899999999997e-01 , 5.5385899999999999e-01 , -4.1502499999999998e-01 -4.6312734015891541e+00 , 3.0074553588057400e+00 , 7.7047327999999995e+00 , -2.4543699999999999e-01 , -8.0478200000000000e-01 , 5.4045100000000001e-01 -4.5196412154658434e+00 , 3.0083924668639650e+00 , 7.6750303999999998e+00 , -4.2975099999999999e-01 , -6.5105700000000000e-01 , 6.2565099999999996e-01 -4.4626833639466081e+00 , 3.0239685329193691e+00 , 7.7665504000000007e+00 , 6.6608299999999998e-01 , 7.2715099999999999e-01 , -1.6608600000000001e-01 -4.4702764565447968e+00 , 3.0619445189050642e+00 , 8.0198944000000001e+00 , 1.9416300000000000e-01 , -4.8423300000000002e-01 , -8.5312299999999996e-01 -4.4917758564536907e+00 , 3.1080611322191820e+00 , 8.3324351999999990e+00 , 4.0672399999999997e-01 , 9.0997799999999995e-01 , 8.0717300000000006e-02 -4.2237349094945795e+00 , 3.0531174408664463e+00 , 7.8918496000000005e+00 , -6.4876100000000003e-01 , 3.9429300000000000e-01 , 6.5087799999999996e-01 -4.2643187707283055e+00 , 3.1097316850483061e+00 , 8.2816520000000011e+00 , 7.2766200000000003e-01 , 6.3944400000000001e-01 , 2.4823200000000001e-01 -4.2596906228569491e+00 , 3.1543922927551709e+00 , 8.5761175999999999e+00 , 1.9621000000000000e-01 , 8.7984700000000005e-01 , 4.3286400000000003e-01 -3.9435641696421460e+00 , 3.0651312640814923e+00 , 7.8969664000000002e+00 , 4.8480000000000001e-01 , 5.3379600000000005e-01 , 6.9284299999999999e-01 -3.8609841003161405e+00 , 3.0745074769814709e+00 , 7.9311512000000004e+00 , 4.5912799999999998e-01 , -3.2831800000000001e-02 , 8.8776299999999997e-01 -3.7974249451815858e+00 , 3.0916062594136098e+00 , 8.0340904000000002e+00 , 5.4238500000000001e-01 , 6.9743100000000002e-02 , 8.3723000000000003e-01 -3.6564309016496432e+00 , 3.0693519424440194e+00 , 7.8460999999999999e+00 , 7.5650300000000004e-01 , -4.0205700000000000e-01 , -5.1580300000000001e-01 -3.5438245638154329e+00 , 3.0591808112105046e+00 , 7.7452407999999995e+00 , -4.9933600000000000e-01 , 4.9301000000000000e-01 , 7.1246399999999999e-01 -3.4356818098538628e+00 , 3.0483482322817697e+00 , 7.6420519999999996e+00 , 1.5987699999999999e-01 , 9.8693600000000004e-01 , -1.9900500000000002e-02 -3.3718140509310448e+00 , 3.0652942596751394e+00 , 7.7388864000000002e+00 , 4.5509200000000000e-02 , 9.9860300000000002e-01 , -2.6865600000000000e-02 -3.2653547596322250e+00 , 3.0525957385331717e+00 , 7.6215223999999999e+00 , -4.2157600000000003e-02 , 9.6312299999999995e-01 , 2.6573999999999998e-01 -3.1738645723797014e+00 , 3.0479773846599647e+00 , 7.5632615999999997e+00 , 2.2237699999999999e-01 , 9.2788499999999996e-01 , -2.9929499999999998e-01 -3.0846362811483772e+00 , 3.0418851812914287e+00 , 7.5034407999999999e+00 , -1.8612799999999999e-01 , 4.9973099999999999e-02 , 9.8125399999999996e-01 -3.0042575417499702e+00 , 3.0442233179908920e+00 , 7.4926247999999998e+00 , -3.6426999999999998e-01 , -6.4234000000000001e-03 , 9.3127099999999996e-01 -2.9203422452837184e+00 , 3.0413410283013058e+00 , 7.4498704000000000e+00 , 2.0301900000000001e-01 , -1.5110999999999999e-01 , -9.6744500000000000e-01 -2.8423348095503562e+00 , 3.0420163242054596e+00 , 7.4365791999999997e+00 , -6.0935599999999999e-02 , 2.1380600000000000e-01 , 9.7497400000000001e-01 -2.7652540022279655e+00 , 3.0464385621330750e+00 , 7.4420808000000003e+00 , -3.7518400000000002e-01 , -4.8564700000000000e-01 , -7.8954700000000000e-01 -2.6907673908720238e+00 , 3.0566521078197075e+00 , 7.4874144000000005e+00 , -5.3460300000000005e-01 , -5.9838899999999995e-01 , -5.9676600000000002e-01 -2.6314365253485459e+00 , 3.1368063936887269e+00 , 8.0043568000000000e+00 , 5.0770000000000004e-01 , 4.8465900000000001e-01 , -7.1228199999999997e-01 -2.5394172188422894e+00 , 3.1000180623049141e+00 , 7.7388864000000002e+00 , -8.2762700000000000e-01 , -3.8416800000000001e-01 , -4.0920499999999999e-01 -2.4576890024923608e+00 , 3.1498398101888574e+00 , 8.0477768000000012e+00 , -4.9872499999999997e-01 , 6.0611499999999996e-01 , -6.1959500000000001e-01 -2.3688395953076049e+00 , 3.1626503151248810e+00 , 8.1082111999999995e+00 , 1.4433399999999999e-01 , 4.6472799999999997e-01 , 8.7361100000000003e-01 -2.2792949304952606e+00 , 3.1741897570578708e+00 , 8.1569456000000002e+00 , -2.9247400000000000e-02 , 2.5595199999999999e-02 , 9.9924500000000005e-01 -2.2024476317338961e+00 , 3.1376648900461044e+00 , 7.8959888000000005e+00 , 8.9678000000000002e-01 , -2.5070200000000000e-03 , -4.4246999999999997e-01 -2.1172915895393492e+00 , 3.1412227157723258e+00 , 7.8902375999999999e+00 , -5.2084699999999998e-02 , 3.0907600000000002e-01 , 9.4960999999999995e-01 -2.0216423001675845e+00 , 3.1633565382900470e+00 , 8.0165664000000003e+00 , -9.4416400000000000e-01 , -7.4615799999999996e-02 , -3.2091500000000001e-01 -1.7994702793659596e+00 , 3.3648363538153361e+00 , 9.2959224000000003e+00 , 5.6349400000000005e-01 , 8.2596099999999995e-01 , 1.6231499999999999e-02 -5.0904068745804363e+00 , 1.8010136262658691e+00 , 2.4409520000000007e-01 , -3.8777800000000001e-01 , -2.3689700000000001e-02 , 9.2144800000000004e-01 -4.7945036258947340e+00 , 1.9787928746790835e+00 , 1.3163237600000000e+00 , -4.4024000000000001e-02 , 1.6156999999999999e-01 , 9.8587899999999995e-01 -4.8755743148823560e+00 , 1.9741405576071374e+00 , 1.3210682399999998e+00 , -8.6253499999999997e-02 , 1.6524600000000000e-01 , 9.8247300000000004e-01 -4.9493417159968383e+00 , 1.9704431355462024e+00 , 1.3342700000000001e+00 , -8.6250099999999996e-02 , 1.5538900000000000e-01 , 9.8408099999999998e-01 -5.0399930033092808e+00 , 1.9651182223903827e+00 , 1.3377176000000000e+00 , -7.0305599999999996e-02 , 2.1026500000000001e-01 , 9.7511300000000001e-01 -5.1052725488956110e+00 , 1.9637697462831070e+00 , 1.3607640000000001e+00 , -7.0226600000000000e-02 , 1.7128299999999999e-01 , 9.8271600000000003e-01 -5.2053782716582990e+00 , 1.9568765175956628e+00 , 1.3637259200000000e+00 , -3.1158300000000000e-02 , 1.6051799999999999e-01 , 9.8654100000000000e-01 -5.3061905242330951e+00 , 1.9505286863506406e+00 , 1.3695457599999998e+00 , 8.8030800000000006e-02 , -1.7460300000000001e-01 , -9.8069600000000001e-01 -5.3897340344176108e+00 , 1.9476022048194679e+00 , 1.3886568000000001e+00 , 5.7487000000000003e-02 , -1.7320300000000000e-01 , -9.8320700000000005e-01 -5.5188199208478306e+00 , 1.9371488401609289e+00 , 1.3854015999999998e+00 , -3.5602500000000002e-02 , 1.9597500000000001e-01 , 9.7996300000000003e-01 -5.6127628180047395e+00 , 1.9339078078058778e+00 , 1.4051626399999999e+00 , -8.0234600000000003e-02 , 1.8617800000000001e-01 , 9.7923499999999997e-01 -5.7163064314950418e+00 , 1.9288479682889523e+00 , 1.4232232800000000e+00 , -5.6600400000000002e-02 , 1.8053700000000000e-01 , 9.8193799999999998e-01 -5.8472596346294097e+00 , 1.9204900720469764e+00 , 1.4307664000000000e+00 , -5.6954400000000002e-02 , 1.9375800000000001e-01 , 9.7939500000000002e-01 -5.9699052851664582e+00 , 1.9141674906805872e+00 , 1.4466367999999998e+00 , -7.3153499999999996e-02 , 1.8325200000000000e-01 , 9.8033999999999999e-01 -6.1020385589938488e+00 , 1.9073168837271901e+00 , 1.4619185600000000e+00 , 2.7105899999999999e-01 , -2.3257500000000000e-01 , -9.3404299999999996e-01 -6.2456199058740127e+00 , 1.8990092135293157e+00 , 1.4776735200000000e+00 , 8.2963799999999999e-01 , -1.7353299999999999e-01 , -5.3064800000000001e-01 -6.1875752702401057e+00 , 1.9175908808304107e+00 , 1.5785971999999999e+00 , 9.8224599999999995e-01 , -6.9728999999999999e-02 , 1.7415700000000001e-01 -6.1267377595333317e+00 , 1.9368108122988816e+00 , 1.6768137599999999e+00 , 9.9142900000000000e-01 , 8.3335300000000001e-02 , 1.0061700000000000e-01 -6.1417226989854887e+00 , 1.9455457371361529e+00 , 1.7444439199999999e+00 , 9.9830399999999997e-01 , 5.1701799999999999e-02 , 2.6747600000000000e-02 -6.1261883086067934e+00 , 1.9576338476043729e+00 , 1.8222161600000000e+00 , 9.9679899999999999e-01 , 4.6068499999999998e-02 , 6.5334799999999998e-02 -6.1097619123393825e+00 , 1.9706150257547410e+00 , 1.8989490240000000e+00 , 9.8495500000000002e-01 , 1.8194600000000000e-03 , -1.7280400000000001e-01 -6.1304431360220928e+00 , 1.9783133648672593e+00 , 1.9626543279999999e+00 , 9.7220700000000004e-01 , -1.4319300000000000e-02 , -2.3368500000000000e-01 -6.1803520361909507e+00 , 1.9831150874274044e+00 , 2.0182169520000000e+00 , 9.7020899999999999e-01 , 1.2062700000000000e-01 , 2.1010499999999999e-01 -6.0486009323884042e+00 , 2.0077633479866486e+00 , 2.1229893600000000e+00 , -9.2254999999999998e-01 , -1.6811200000000001e-01 , -3.4733399999999998e-01 -6.0652277317384211e+00 , 2.0154133946973998e+00 , 2.1855848800000000e+00 , 9.8777800000000004e-01 , 2.8317499999999999e-02 , -1.5327499999999999e-01 -6.0613967145644239e+00 , 2.0259890174317325e+00 , 2.2530756800000002e+00 , 9.5938599999999996e-01 , 1.7598800000000001e-02 , -2.8154699999999999e-01 -6.0866093595990387e+00 , 2.0329006492226265e+00 , 2.3138428800000002e+00 , -8.9507199999999998e-01 , 4.7760700000000003e-03 , 4.4589699999999999e-01 -6.1407484414771343e+00 , 2.0374594570297671e+00 , 2.3690991200000000e+00 , -7.8464500000000004e-01 , 7.3614700000000005e-02 , 6.1555899999999997e-01 -6.1636909335895602e+00 , 2.0447863567701541e+00 , 2.4314367200000002e+00 , 5.7202100000000000e-01 , -7.8384200000000001e-02 , -8.1648500000000002e-01 -6.3283963764085236e+00 , 2.0384325844472890e+00 , 2.4719416000000001e+00 , 2.8439700000000001e-01 , -1.6579300000000000e-01 , -9.4426200000000005e-01 -6.5850612250943135e+00 , 2.0255355766737764e+00 , 2.5048617599999998e+00 , -9.5616999999999994e-02 , 1.5768399999999999e-01 , 9.8285000000000000e-01 -1.1685094490380926e+01 , 1.6036237050703557e+00 , 2.1208958400000002e+00 , -1.2445600000000000e-01 , 2.0751200000000000e-01 , 9.7028300000000001e-01 -1.2352950215715715e+01 , 1.5714381875827912e+00 , 2.2248719200000000e+00 , -9.4418000000000002e-02 , 1.9271700000000000e-01 , 9.7670100000000004e-01 -1.3382019547511225e+01 , 1.5126729099857064e+00 , 2.3267867199999999e+00 , -4.7916399999999998e-02 , 1.9150400000000001e-01 , 9.8032200000000003e-01 -1.4534359235254030e+01 , 1.4491622804072022e+00 , 2.4576759199999998e+00 , -6.4345200000000005e-02 , 1.9292500000000001e-01 , 9.7910200000000003e-01 -1.6193669931624417e+01 , 1.3534305653458949e+00 , 2.6106256000000001e+00 , -4.0683100000000000e-02 , 1.9018399999999999e-01 , 9.8090500000000003e-01 -1.8027605149378449e+01 , 1.2526670868230019e+00 , 2.8180099200000002e+00 , -8.3532599999999999e-02 , 2.1105800000000000e-01 , 9.7389800000000004e-01 -2.3883430533818096e+01 , 9.2777172071224911e-01 , 3.4616784000000003e+00 , 9.4742099999999996e-02 , 6.1502400000000002e-01 , 7.8279600000000005e-01 -2.6859554842862078e+01 , 8.4707498342168353e-01 , 4.3602591999999998e+00 , -9.9011300000000002e-01 , 1.3805100000000001e-01 , 2.4878299999999999e-02 -2.6962201895585665e+01 , 9.0292182333049764e-01 , 4.7911000000000001e+00 , -9.7081399999999995e-01 , 2.3966499999999999e-01 , 8.9747700000000000e-03 -2.6932705270748681e+01 , 9.6624642462404098e-01 , 5.2150872000000001e+00 , 9.8857600000000001e-01 , -1.4551500000000001e-01 , 3.9281999999999997e-02 -2.9519364879673887e+01 , 8.8408663229893358e-01 , 5.9126256000000001e+00 , 1.6593800000000000e-01 , 4.3346099999999999e-01 , 8.8576299999999997e-01 -3.1387600821644114e+01 , 8.5282057718154558e-01 , 6.6145943999999997e+00 , -3.1240000000000001e-01 , 4.7895599999999999e-01 , 8.2037000000000004e-01 -2.6686724221750850e+01 , 1.1672930821290288e+00 , 6.4661656000000001e+00 , 3.4710000000000002e-01 , -8.0365500000000001e-01 , 4.8338500000000001e-01 -2.7028273930708895e+01 , 1.2135334632792203e+00 , 6.9476752000000008e+00 , 6.3101499999999999e-01 , 3.0557000000000001e-02 , 7.7516900000000000e-01 -2.5753486362282079e+01 , 1.3356292571571795e+00 , 7.1604488000000002e+00 , 4.2393599999999998e-01 , -8.6186200000000002e-01 , 2.7833900000000000e-01 -2.3416699022008093e+01 , 1.4980255948100467e+00 , 7.1253175999999998e+00 , -9.7419900000000004e-01 , -1.7189199999999999e-01 , 1.4624999999999999e-01 -2.5827266947162620e+01 , 1.4548329337902683e+00 , 8.0103056000000006e+00 , 5.5639499999999997e-01 , -8.2574199999999998e-01 , 9.2596999999999999e-02 -2.2955361055695569e+01 , 1.6255033578386882e+00 , 7.7755879999999999e+00 , 7.4468800000000002e-01 , 4.7773199999999999e-01 , 4.6605999999999997e-01 -2.3327006829820142e+01 , 1.6672329894400688e+00 , 8.2411543999999992e+00 , 9.7462300000000002e-01 , 2.1602299999999999e-01 , -5.8680799999999998e-02 -2.3378255101302919e+01 , 1.7217017990157117e+00 , 8.6383200000000002e+00 , 9.9372899999999997e-01 , -1.1102900000000000e-01 , 1.3257300000000000e-02 -2.1690614796838702e+01 , 1.8289345446938774e+00 , 8.5470080000000017e+00 , -7.2838099999999995e-01 , -2.0391799999999999e-01 , -6.5412499999999996e-01 -2.3485689581106268e+01 , 1.8329774395411380e+00 , 9.4508200000000002e+00 , -9.1616200000000003e-01 , 1.7714199999999999e-01 , 3.5953900000000000e-01 -2.1572920941745938e+01 , 1.9917971952309566e+00 , 9.5990719999999996e+00 , 9.9369099999999999e-01 , 9.5892300000000000e-02 , 5.8166000000000002e-02 -2.4364707496184174e+01 , 1.9938876312678706e+00 , 1.0974617600000000e+01 , -4.3281599999999998e-01 , 7.3279499999999997e-01 , -5.2505500000000005e-01 -2.4274827339440549e+01 , 2.0582787357446644e+00 , 1.1369880000000000e+01 , 4.8840800000000001e-01 , -7.9376599999999997e-01 , 3.6248100000000000e-01 -2.2053859259927119e+01 , 2.1502938701904415e+00 , 1.0915233600000001e+01 , -3.5258400000000001e-01 , -3.0241099999999999e-01 , 8.8556900000000005e-01 -2.3124574562051176e+01 , 2.1968220281503448e+00 , 1.1759297600000002e+01 , 3.4339700000000001e-01 , 4.8809200000000003e-01 , 8.0239899999999997e-01 -2.0935870635668643e+01 , 2.2741543822481658e+00 , 1.1217644800000000e+01 , 7.2169099999999997e-01 , -1.1559500000000000e-01 , 6.8249499999999996e-01 -2.4221284875428047e+01 , 2.3177006569222511e+00 , 1.3115104000000001e+01 , -3.3001100000000000e-01 , 9.2373000000000005e-01 , 1.9446300000000000e-01 -2.1029190960024742e+01 , 2.3870045588484339e+00 , 1.2034876800000001e+01 , 9.6998799999999996e-01 , -1.9102600000000000e-01 , -1.5043899999999999e-01 -2.0398120125579233e+01 , 2.4440814767856271e+00 , 1.2114925599999999e+01 , 9.9492000000000003e-01 , -7.9116400000000003e-02 , 6.2251399999999998e-02 -2.1528481925596623e+01 , 2.5078365560613500e+00 , 1.3099504000000000e+01 , 5.2513799999999999e-01 , -2.8131200000000001e-01 , 8.0317700000000003e-01 -2.0705058201676120e+01 , 2.5621281327878407e+00 , 1.3072048000000001e+01 , 8.3700799999999997e-01 , -2.8674100000000002e-01 , -4.6604499999999999e-01 -2.1352048750047288e+01 , 2.6301516536209615e+00 , 1.3853400000000001e+01 , -2.1994100000000000e-01 , -3.0173200000000000e-01 , 9.2767699999999997e-01 -2.2701620404981483e+01 , 2.7149655830265065e+00 , 1.5089440000000002e+01 , -9.4838900000000004e-01 , 4.3442000000000001e-02 , 3.1412000000000001e-01 -2.2473407987747045e+01 , 2.7807198830362645e+00 , 1.5425048000000000e+01 , -9.3175200000000002e-01 , 2.1439200000000000e-01 , 2.9304400000000003e-01 -6.4352510334274928e+00 , 2.4932512603214714e+00 , 5.6323456000000007e+00 , -6.6283700000000001e-01 , 2.9095199999999999e-01 , -6.8992299999999995e-01 -6.3294233076675237e+00 , 2.5054958126968176e+00 , 5.6599991999999997e+00 , -6.6283700000000001e-01 , 2.9095199999999999e-01 , -6.8992299999999995e-01 -2.3139965288969485e+01 , 3.0160529697725260e+00 , 1.7362463999999999e+01 , -8.7695400000000001e-01 , 4.4730100000000000e-01 , 1.7571000000000001e-01 -6.2374018494142174e+00 , 2.5317140299598009e+00 , 5.7915799999999997e+00 , -7.1594999999999998e-01 , 1.5493000000000001e-01 , -6.8074400000000002e-01 -6.1399523323221405e+00 , 2.5425169793638465e+00 , 5.8191191999999994e+00 , 7.8076800000000002e-01 , -2.5375300000000001e-01 , 5.7097299999999995e-01 -6.0749164056901170e+00 , 2.5693612739997573e+00 , 5.9701064000000006e+00 , -6.3305299999999998e-01 , 5.2535500000000002e-01 , -5.6854700000000002e-01 -6.0484475733007503e+00 , 2.5827282993411727e+00 , 6.0518919999999996e+00 , -9.3957500000000005e-01 , 1.3734299999999999e-01 , -3.1358500000000000e-01 -6.1149357046566708e+00 , 2.6020106144303377e+00 , 6.2144855999999997e+00 , 9.7059399999999996e-01 , -2.3103499999999999e-01 , 6.7608699999999994e-02 -5.9817801860793800e+00 , 2.6106585189954021e+00 , 6.2079128000000008e+00 , -9.4247499999999995e-01 , 2.6244000000000001e-01 , -2.0704200000000000e-01 -6.0114917318811854e+00 , 2.6285651932133800e+00 , 6.3452967999999998e+00 , 7.5056599999999996e-01 , -3.1125300000000000e-01 , 5.8289899999999994e-01 -6.0744102696369016e+00 , 2.6494382892387458e+00 , 6.5202976000000001e+00 , -5.6776300000000002e-01 , -5.9835000000000005e-01 , -5.6535100000000005e-01 -5.9107381470601341e+00 , 2.6557723170264702e+00 , 6.4799144000000002e+00 , -8.1665800000000000e-01 , -4.5852399999999999e-01 , -3.5046400000000000e-01 -5.8653551612720634e+00 , 2.6693705285003864e+00 , 6.5535360000000003e+00 , -7.4579700000000004e-01 , -4.0987899999999999e-01 , -5.2515400000000001e-01 -5.8189731045671955e+00 , 2.6829242238654549e+00 , 6.6267312000000000e+00 , -9.6960100000000005e-01 , -2.0526400000000000e-01 , -1.3319400000000001e-01 -5.8752410334681677e+00 , 2.7065055358931400e+00 , 6.8137544000000005e+00 , 9.8226400000000003e-01 , -3.2153899999999999e-02 , -1.8472500000000000e-01 -5.9408091922407342e+00 , 2.7323678015778250e+00 , 7.0193519999999996e+00 , 8.8564500000000002e-01 , -4.6394800000000003e-01 , 1.9625699999999999e-02 -5.9252474331294103e+00 , 2.7512915075287112e+00 , 7.1415727999999996e+00 , -9.1653200000000001e-01 , 3.9224199999999998e-01 , -7.8196799999999997e-02 -5.9531714574059045e+00 , 2.7755035842922964e+00 , 7.3204215999999995e+00 , -9.7419400000000000e-01 , 3.1648400000000000e-02 , 2.2348299999999999e-01 -5.9756384389063459e+00 , 2.8003572560023664e+00 , 7.5012672000000000e+00 , -8.9087200000000000e-01 , -8.5261399999999998e-03 , -4.5417600000000002e-01 -5.9047628047483220e+00 , 2.8149686719162652e+00 , 7.5692104000000002e+00 , 6.2650600000000001e-01 , -5.0462000000000000e-02 , 7.7778099999999994e-01 -5.7823721908190091e+00 , 2.8244303746665946e+00 , 7.5689712000000000e+00 , 2.6225799999999999e-01 , 4.7781299999999999e-01 , 8.3840099999999995e-01 -5.6486498520515287e+00 , 2.8304826170130069e+00 , 7.5493984000000003e+00 , 7.6698299999999997e-01 , -2.4968000000000001e-02 , 6.4118100000000000e-01 -5.5995361574944340e+00 , 2.8488220886120281e+00 , 7.6457544000000004e+00 , 6.2988000000000000e-01 , 9.0570899999999996e-02 , 7.7139300000000000e-01 -5.5252102232732376e+00 , 2.8623418603164592e+00 , 7.7075304000000004e+00 , 8.4017500000000001e-01 , 4.5598200000000000e-01 , 2.9357499999999997e-01 -5.3997127446765294e+00 , 2.8693841368992676e+00 , 7.6893615999999998e+00 , 4.6552300000000002e-01 , 8.7551599999999996e-01 , 1.2945599999999999e-01 -5.4377291083158763e+00 , 2.9019680921585440e+00 , 7.9329816000000006e+00 , 5.2890099999999995e-01 , 8.3746799999999999e-01 , 1.3751900000000000e-01 -5.2676661466602051e+00 , 2.9002014623965415e+00 , 7.8405048000000006e+00 , 2.1279100000000001e-01 , 9.6950400000000003e-01 , -1.2158099999999999e-01 -5.1585951017824723e+00 , 2.9085011113070669e+00 , 7.8426056000000006e+00 , -9.3342700000000001e-02 , 9.9173000000000000e-01 , -8.8079599999999994e-02 -5.2285572660397452e+00 , 2.9512154098052124e+00 , 8.1696752000000004e+00 , -3.7763799999999997e-01 , -8.9305299999999999e-01 , 2.4463399999999999e-01 -5.3125457837764980e+00 , 3.0011640395412211e+00 , 8.5461968000000006e+00 , -8.8937200000000005e-01 , -4.2641400000000002e-01 , -1.6489200000000001e-01 -4.7429578513157331e+00 , 2.9099395703139836e+00 , 7.6503824000000007e+00 , 7.1974000000000005e-01 , 6.5032900000000005e-01 , 2.4299599999999999e-01 -4.6404049144790429e+00 , 2.9168651780441617e+00 , 7.6417815999999998e+00 , 3.3128700000000000e-01 , -2.6190200000000002e-01 , 9.0645299999999995e-01 -4.6163052570636030e+00 , 2.9413685513168031e+00 , 7.8004336000000007e+00 , 5.9535700000000003e-01 , 7.8377200000000002e-01 , 1.7677999999999999e-01 -4.6033607926746924e+00 , 2.9709898164213637e+00 , 7.9973992000000003e+00 , -6.0675400000000002e-01 , -4.9821199999999999e-01 , -6.1938300000000002e-01 -4.7120363472278672e+00 , 3.0369341728131705e+00 , 8.5007280000000005e+00 , 9.6413499999999996e-01 , 1.1755100000000000e-01 , 2.3796200000000001e-01 -4.6400484983803914e+00 , 3.0559853502191210e+00 , 8.5957424000000007e+00 , -4.4065599999999999e-01 , 4.2455300000000001e-01 , 7.9093400000000003e-01 -4.2912532338023448e+00 , 2.9883764312983692e+00 , 7.9643895999999996e+00 , 2.5708399999999998e-01 , 8.2598199999999999e-01 , 5.0165899999999997e-01 -4.3510798663309460e+00 , 3.0487396335396788e+00 , 8.4032488000000001e+00 , -6.0183600000000004e-01 , -6.6805599999999998e-01 , -4.3760199999999999e-01 -4.2745822389116856e+00 , 3.0660627296813736e+00 , 8.4834432000000000e+00 , -7.3880000000000001e-01 , -6.1573599999999995e-01 , -2.7394000000000002e-01 -3.9886742248014473e+00 , 3.0026774503169253e+00 , 7.9128264000000001e+00 , -4.6477900000000000e-01 , 6.0684899999999997e-01 , -6.4475899999999997e-01 -3.8890337396387191e+00 , 3.0062809723351993e+00 , 7.8883656000000002e+00 , -8.8939800000000002e-01 , -1.7395200000000000e-02 , -4.5680199999999999e-01 -3.8235802474703555e+00 , 3.0246108275908306e+00 , 7.9812063999999996e+00 , 4.9898700000000001e-01 , -5.9785100000000002e-01 , 6.2736400000000003e-01 -3.7372305304569799e+00 , 3.0338426080751102e+00 , 8.0033272000000011e+00 , -3.3110200000000001e-01 , 6.7038600000000004e-01 , 6.6404300000000005e-01 -3.5997212573849198e+00 , 3.0163313127739846e+00 , 7.8132776000000002e+00 , 2.2723499999999999e-01 , 9.2805099999999996e-01 , 2.9510100000000000e-01 -3.9447348613851982e+00 , 3.2737746615490098e+00 , 9.7444328000000002e+00 , -9.4302200000000003e-01 , -1.3185800000000000e-01 , 3.0548700000000001e-01 -3.7762696720965345e+00 , 3.2529234389073243e+00 , 9.5154040000000002e+00 , -9.5907799999999999e-01 , -2.7020200000000000e-01 , 8.4619000000000000e-02 -3.3642920650081392e+00 , 3.0519376283956730e+00 , 7.9450352000000004e+00 , -8.7988100000000002e-01 , -2.3728399999999999e-01 , -4.1171099999999999e-01 -3.2989472716362762e+00 , 3.0768506232696051e+00 , 8.0810984000000001e+00 , 8.7059200000000003e-01 , 4.1531000000000001e-01 , 2.6379399999999997e-01 -3.1529374722937602e+00 , 3.0321739960741905e+00 , 7.7069896000000000e+00 , -5.7386700000000002e-01 , -4.1621999999999998e-01 , -7.0529200000000003e-01 -3.0412968493594947e+00 , 3.0087060721923700e+00 , 7.4928848000000006e+00 , -2.7609499999999998e-01 , 1.0932500000000000e-02 , 9.6106800000000003e-01 -2.9582721455751875e+00 , 3.0100154706441979e+00 , 7.4605927999999997e+00 , -2.0930799999999999e-01 , 1.4331700000000000e-01 , 9.6728999999999998e-01 -2.8792709256187718e+00 , 3.0139338171995149e+00 , 7.4473744000000002e+00 , -6.2225799999999998e-02 , 1.7099400000000001e-01 , 9.8330499999999998e-01 -2.8023201980434060e+00 , 3.0185309849330917e+00 , 7.4432352000000002e+00 , -3.1460199999999999e-01 , -3.8310300000000003e-01 , -8.6848000000000003e-01 -2.7278376897119232e+00 , 3.0309281528281637e+00 , 7.4888703999999997e+00 , 4.6631899999999998e-01 , 5.9767400000000004e-01 , 6.5217499999999995e-01 -2.7084399779714854e+00 , 3.2223860331722554e+00 , 8.7881008000000005e+00 , 8.2937600000000000e-01 , 5.3893999999999997e-01 , -1.4723600000000001e-01 -2.5803073895962854e+00 , 3.0816242332041242e+00 , 7.7617144000000007e+00 , -7.7959000000000001e-01 , -4.6063799999999999e-01 , -4.2432599999999998e-01 -2.4979019003537806e+00 , 3.0935889679103936e+00 , 7.8035224000000003e+00 , -6.7217899999999997e-01 , -5.8081300000000002e-01 , -4.5916499999999999e-01 -2.4037092201757257e+00 , 3.3246151536639799e+00 , 9.3359103999999995e+00 , -6.9942199999999999e-01 , -2.0162800000000000e-01 , 6.8567900000000004e-01 -2.3245013474388787e+00 , 3.1509353456602600e+00 , 8.1091471999999989e+00 , 1.3121900000000000e-01 , 4.5968799999999999e-01 , 8.7833300000000003e-01 -2.2377297110493450e+00 , 3.1498786185389429e+00 , 8.0642816000000010e+00 , 4.9726100000000001e-01 , -8.0230299999999999e-01 , -3.3021400000000001e-01 -2.1609238541687747e+00 , 3.1275922058793921e+00 , 7.8740448000000001e+00 , 9.3059000000000003e-02 , -3.6020000000000002e-01 , 9.2822199999999999e-01 -2.0705090040877767e+00 , 3.1435500424122136e+00 , 7.9391904000000002e+00 , 3.7514500000000001e-01 , -7.0968699999999996e-01 , 5.9633199999999997e-01 -1.6050579062466408e+00 , 3.7559577659733163e+00 , 1.1891450400000002e+01 , 2.8867700000000002e-01 , -9.4472999999999996e-01 , -1.5540699999999999e-01 -1.7484859813775280e+00 , 3.3586292077908104e+00 , 9.2489664000000005e+00 , -9.4550800000000002e-01 , 2.4715500000000001e-01 , -2.1196699999999999e-01 -5.1308145618085490e+00 , 1.7312906162537023e+00 , 2.5448479999999996e-01 , -3.8777800000000001e-01 , -2.3689600000000002e-02 , 9.2144800000000004e-01 -4.8216530985060420e+00 , 1.9163157391157568e+00 , 1.3334962400000001e+00 , -7.6245900000000005e-02 , 1.7749000000000001e-01 , 9.8116499999999995e-01 -4.9024924747208161e+00 , 1.9087737053471918e+00 , 1.3396665600000000e+00 , -6.0751399999999997e-02 , 1.6074400000000000e-01 , 9.8512500000000003e-01 -4.9841020859048850e+00 , 1.9016721947794646e+00 , 1.3481883200000000e+00 , -9.6124399999999999e-02 , 1.6429600000000000e-01 , 9.8171600000000003e-01 -5.0664817254421433e+00 , 1.8950122266818159e+00 , 1.3590615200000000e+00 , -1.1865000000000001e-01 , 1.8726400000000001e-01 , 9.7511800000000004e-01 -5.1486088856311181e+00 , 1.8888125539427034e+00 , 1.3721603199999999e+00 , -6.4512000000000000e-02 , 1.8217200000000000e-01 , 9.8114800000000002e-01 -5.2494674423365639e+00 , 1.8790953997720650e+00 , 1.3770784800000000e+00 , -6.6164700000000007e-02 , 1.9048699999999999e-01 , 9.7945800000000005e-01 -5.3320575374818366e+00 , 1.8738575912565503e+00 , 1.3950579999999999e+00 , -9.0917300000000006e-02 , 1.9185900000000000e-01 , 9.7720200000000002e-01 -5.4343544979828167e+00 , 1.8652109018310545e+00 , 1.4055890400000000e+00 , -4.8674700000000001e-02 , 1.9870499999999999e-01 , 9.7885000000000000e-01 -5.5362576647820312e+00 , 1.8561511846170871e+00 , 1.4192598400000001e+00 , -3.6931300000000000e-02 , 1.9088700000000000e-01 , 9.8091700000000004e-01 -5.6567366417467149e+00 , 1.8449696970331610e+00 , 1.4263640799999999e+00 , -8.6757399999999998e-02 , 1.9813500000000001e-01 , 9.7632799999999997e-01 -5.7689225977446750e+00 , 1.8358041858318026e+00 , 1.4416957600000000e+00 , -6.2092799999999997e-02 , 1.9411100000000001e-01 , 9.7901300000000002e-01 -5.8906494828816491e+00 , 1.8260047279100513e+00 , 1.4559312799999999e+00 , -4.9981999999999999e-02 , 1.8465899999999999e-01 , 9.8153100000000004e-01 -6.0228693576169787e+00 , 1.8146437385443586e+00 , 1.4699088800000000e+00 , -8.8276700000000000e-02 , 1.8778500000000001e-01 , 9.7823499999999997e-01 -6.1457531116831863e+00 , 1.8053143653968511e+00 , 1.4919870399999999e+00 , -2.5632199999999999e-01 , 8.4625400000000003e-02 , 9.6287999999999996e-01 -6.2978159963004350e+00 , 1.7920715013223378e+00 , 1.5061279200000000e+00 , -9.3427499999999997e-01 , -2.2995800000000000e-01 , -2.7248899999999998e-01 -6.1827655377866977e+00 , 1.8218592351962095e+00 , 1.6294448799999999e+00 , -9.7252700000000003e-01 , -1.5350100000000000e-01 , -1.7500900000000000e-01 -6.1603023694356409e+00 , 1.8353580501494746e+00 , 1.7127364000000000e+00 , 9.8784499999999997e-01 , 8.8192999999999994e-02 , 1.2800500000000001e-01 -6.1643426741847192e+00 , 1.8453698236989007e+00 , 1.7843716000000001e+00 , 9.9414800000000003e-01 , 1.0212400000000001e-01 , 3.5226700000000000e-02 -6.1488325871536471e+00 , 1.8585420526890979e+00 , 1.8622415999999999e+00 , 9.9428099999999997e-01 , 1.0012400000000000e-01 , 3.7162399999999998e-02 -6.1410901847510848e+00 , 1.8695154113762451e+00 , 1.9361377600000000e+00 , 9.8342300000000005e-01 , 3.7306999999999998e-04 , -1.8132899999999999e-01 -6.1616404933888269e+00 , 1.8763414742335545e+00 , 2.0007565272000001e+00 , 9.9589300000000003e-01 , -5.3676900000000000e-02 , -7.2905100000000000e-02 -6.1703587069890622e+00 , 1.8853150295618657e+00 , 2.0682401200000000e+00 , -9.6367800000000003e-01 , 1.4791600000000000e-02 , -2.6665800000000001e-01 -6.0884810284370197e+00 , 1.9059884581361177e+00 , 2.1586530399999999e+00 , 9.8551200000000005e-01 , 1.2124600000000001e-01 , 1.1859699999999999e-01 -6.0952938272988142e+00 , 1.9147296338729580e+00 , 2.2245703200000002e+00 , -9.8044399999999998e-01 , -5.6297000000000000e-02 , 1.8857199999999999e-01 -6.1000256606617258e+00 , 1.9235286179038578e+00 , 2.2903368000000000e+00 , 9.5756300000000005e-01 , 4.1278099999999998e-02 , -2.8525299999999998e-01 -6.1251364461693907e+00 , 1.9306286487689786e+00 , 2.3520150399999999e+00 , -9.0203800000000001e-01 , 1.1416200000000000e-02 , 4.3150500000000003e-01 -6.1683765698835717e+00 , 1.9341973924858553e+00 , 2.4105743199999998e+00 , -8.0166599999999999e-01 , 3.4938100000000000e-02 , 5.9675100000000003e-01 -6.2413376157411822e+00 , 1.9346872389569969e+00 , 2.4654686400000001e+00 , -4.2763200000000001e-01 , 1.0980200000000000e-01 , 8.9725900000000003e-01 -6.4363925875631773e+00 , 1.9204784090726557e+00 , 2.5050801599999999e+00 , -1.5829399999999999e-01 , 1.3789499999999999e-01 , 9.7771600000000003e-01 -1.1929402137458956e+01 , 1.3253997870101055e+00 , 2.2150720000000002e+00 , -1.0768300000000000e-01 , 1.9364700000000001e-01 , 9.7514400000000001e-01 -1.2676578666110411e+01 , 1.2657330864112091e+00 , 2.3260576799999999e+00 , -5.9574400000000000e-02 , 1.8896600000000000e-01 , 9.8017500000000002e-01 -1.3847164809415778e+01 , 1.1638252808297289e+00 , 2.4389143199999999e+00 , -4.9832899999999999e-02 , 1.8853700000000001e-01 , 9.8080100000000003e-01 -1.5099997307172625e+01 , 1.0584277411035301e+00 , 2.5890289600000003e+00 , -5.3034800000000000e-02 , 1.9382900000000000e-01 , 9.7960100000000006e-01 -1.7023157067834088e+01 , 8.8970212482791466e-01 , 2.7679432799999999e+00 , -5.4218900000000000e-02 , 1.8610699999999999e-01 , 9.8103200000000002e-01 -1.8943489657282687e+01 , 7.3125900161444912e-01 , 3.0132595200000001e+00 , -1.2278200000000000e-01 , 2.2642799999999999e-01 , 9.6625799999999995e-01 -2.4396718420152595e+01 , 2.8698684617850767e-01 , 3.7532112000000000e+00 , 1.8915699999999999e-01 , 8.6860000000000004e-01 , 4.5798899999999998e-01 -2.7210516518223255e+01 , 7.6841311660290401e-02 , 4.2697376000000000e+00 , 7.5587199999999999e-01 , 3.0627300000000002e-01 , 5.7866600000000001e-01 -2.7337250079913819e+01 , 1.2693798162171932e-01 , 4.7087736000000007e+00 , 7.5587199999999999e-01 , 3.0627300000000002e-01 , 5.7866600000000001e-01 -2.7527479419639075e+01 , 1.7213158032433440e-01 , 5.1582304000000008e+00 , -5.9944600000000003e-01 , -2.0586599999999999e-01 , 7.7348799999999995e-01 -2.8792823747968615e+01 , 1.2436534676032673e-01 , 5.7233768000000005e+00 , 5.2803800000000001e-01 , 5.3020900000000003e-02 , -8.4756399999999998e-01 -2.8749043509294065e+01 , 1.9481179482975830e-01 , 6.1796872000000000e+00 , 5.2803800000000001e-01 , 5.3020800000000000e-02 , -8.4756399999999998e-01 -2.8162763718219161e+01 , 3.0785001973535930e-01 , 6.5629375999999997e+00 , -2.0574600000000001e-01 , -1.9586300000000001e-01 , 9.5880500000000002e-01 -2.5255135648529009e+01 , 6.0239519015589593e-01 , 6.5717672000000000e+00 , -5.1220100000000002e-01 , 8.0608299999999999e-01 , -2.9644500000000001e-01 -2.5359740018667509e+01 , 6.5225066050698199e-01 , 6.9943400000000002e+00 , 6.3697599999999999e-01 , -7.6306600000000002e-01 , 1.0951000000000000e-01 -2.5282635178202050e+01 , 7.1696058366685689e-01 , 7.3885832000000002e+00 , -3.0896400000000002e-01 , 8.7904499999999997e-01 , -3.6307200000000001e-01 -2.6073131930850700e+01 , 7.1883582447797001e-01 , 7.9618936000000007e+00 , 5.7816800000000002e-02 , -4.6073400000000000e-02 , 9.9726400000000004e-01 -2.4126892389695225e+01 , 9.1399592596113455e-01 , 7.9514000000000005e+00 , 7.7642599999999995e-01 , 5.1236899999999996e-01 , 3.6693500000000001e-01 -2.3882081650656705e+01 , 9.8677426155225700e-01 , 8.2866752000000012e+00 , 9.3454499999999996e-01 , 2.2631000000000001e-01 , -2.7460800000000002e-01 -2.9587374403389603e+01 , 6.7945584703386008e-01 , 1.0171134400000000e+01 , -1.6671800000000001e-01 , -8.3024299999999995e-01 , 5.3188500000000005e-01 -2.7636705886045359e+01 , 8.7029062834860604e-01 , 1.0127652000000001e+01 , -2.3694200000000001e-01 , -9.2824399999999996e-01 , 2.8674300000000003e-01 -2.6629198611697110e+01 , 9.9669265738927404e-01 , 1.0297598400000000e+01 , -1.8469099999999999e-01 , -9.5231899999999994e-02 , 9.7817200000000004e-01 -2.4485504376720229e+01 , 1.1807325022181940e+00 , 1.0073800800000001e+01 , -8.5940200000000000e-01 , 2.2285900000000000e-01 , 4.6017700000000000e-01 -2.7899044164691169e+01 , 1.0602093282296690e+00 , 1.1642786400000000e+01 , -2.2013099999999999e-01 , 9.7108300000000003e-01 , -9.2407000000000003e-02 -2.9366345649623423e+01 , 1.0568411938717146e+00 , 1.2655944000000000e+01 , 2.6909100000000002e-01 , 9.2819499999999999e-01 , -2.5699200000000000e-01 -2.1769209142675937e+01 , 1.4914708239773282e+00 , 1.0330275200000001e+01 , -9.4940599999999997e-01 , 1.9675300000000001e-01 , 2.4477800000000000e-01 -2.2040461570119902e+01 , 1.5337650304873911e+00 , 1.0819501600000001e+01 , -9.4881599999999999e-01 , 1.7980099999999999e-01 , 2.5965500000000002e-01 -2.1906285165401968e+01 , 1.5957665973605808e+00 , 1.1156586400000002e+01 , -9.2279199999999995e-01 , -3.5249100000000000e-01 , 1.5558100000000000e-01 -2.0528075457319634e+01 , 1.7051003936788385e+00 , 1.0951862400000000e+01 , -6.9983200000000001e-01 , -7.0835999999999999e-01 , -9.1980500000000007e-02 -2.2386958087370687e+01 , 1.6917075975586955e+00 , 1.2172739200000001e+01 , 7.6926499999999998e-01 , -2.6677499999999998e-01 , 5.8057099999999995e-01 -2.2023298322750687e+01 , 1.7639622377300146e+00 , 1.2416848000000000e+01 , -6.4956199999999997e-01 , -6.3329899999999995e-01 , 4.2071599999999998e-01 -2.0884412800940041e+01 , 1.8568987561146360e+00 , 1.2266162399999999e+01 , 6.0323099999999996e-01 , 7.8482799999999997e-01 , 1.4197499999999999e-01 -2.1573553839662978e+01 , 1.8960185361921780e+00 , 1.3023792000000000e+01 , -4.1204900000000003e-02 , -5.2412000000000003e-01 , 8.5064700000000004e-01 -2.0934913420000804e+01 , 1.9705450396547517e+00 , 1.3099399999999999e+01 , -9.2285700000000004e-01 , 3.4487899999999999e-01 , 1.7144599999999999e-01 -2.0480011048344039e+01 , 2.0390539060562149e+00 , 1.3257896000000001e+01 , 8.0698800000000004e-01 , 2.9283900000000002e-02 , -5.8984099999999995e-01 -2.2158673219387897e+01 , 2.0703386073668169e+00 , 1.4656904000000001e+01 , 6.9659800000000005e-01 , 2.7016699999999999e-01 , -6.6465099999999999e-01 -2.4415732920149154e+01 , 2.1049449709359611e+00 , 1.6496144000000001e+01 , -3.3243299999999998e-01 , -5.0308900000000001e-01 , 7.9774100000000003e-01 -2.3981569876574135e+01 , 2.1842158290935063e+00 , 1.6744080000000000e+01 , 1.0495400000000001e-01 , -3.4905999999999998e-01 , 9.3120400000000003e-01 -2.2866406578600944e+01 , 2.2663939746250641e+00 , 1.6534624000000001e+01 , -8.6109300000000000e-01 , 3.9972400000000002e-01 , 3.1422800000000001e-01 -2.2898465573396823e+01 , 2.3390979527558247e+00 , 1.7065752000000000e+01 , 5.0336999999999998e-01 , -4.1610799999999998e-01 , 7.5727999999999995e-01 -2.2892408649566146e+01 , 2.4139972265965586e+00 , 1.7583672000000000e+01 , -8.0255200000000004e-01 , 4.5744699999999999e-01 , 3.8295200000000001e-01 -6.2496697878099825e+00 , 2.4657501675545768e+00 , 6.1888183999999997e+00 , 4.7073199999999998e-01 , 4.8297000000000001e-01 , 7.3834299999999997e-01 -6.1560149001490174e+00 , 2.4792440734194616e+00 , 6.2199976000000001e+00 , 5.6989400000000001e-01 , 4.9153000000000002e-01 , 6.5849800000000003e-01 -6.0303662790672634e+00 , 2.4923191367101531e+00 , 6.2211936000000003e+00 , -8.7839000000000000e-01 , -3.2321100000000003e-01 , -3.5208899999999999e-01 -5.9986630002444805e+00 , 2.5070094966691481e+00 , 6.3031456000000006e+00 , -8.3163399999999998e-01 , -2.9413700000000001e-02 , -5.5454400000000004e-01 -6.1249435359395861e+00 , 2.5279843875426522e+00 , 6.5343375999999997e+00 , 4.8799199999999998e-01 , 5.0050200000000000e-01 , 7.1509500000000004e-01 -6.0791847850677705e+00 , 2.5433316097889298e+00 , 6.6112976000000003e+00 , -4.4464500000000001e-01 , -3.9165000000000000e-01 , -8.0554400000000004e-01 -5.9297167135631152e+00 , 2.5549240449518216e+00 , 6.5842264000000004e+00 , -6.5258600000000000e-01 , -4.5782299999999998e-01 , -6.0376200000000002e-01 -5.9334584889354964e+00 , 2.5718003841548671e+00 , 6.7109608000000005e+00 , 6.8533999999999995e-01 , -1.9701800000000000e-01 , 7.0106599999999997e-01 -5.8700014087933354e+00 , 2.5874533455972815e+00 , 6.7698352000000002e+00 , -9.4119600000000003e-01 , -2.0192199999999999e-01 , -2.7088299999999998e-01 -5.8055900794043449e+00 , 2.6018984094477933e+00 , 6.8277840000000003e+00 , 1.9492300000000001e-01 , 8.7564399999999998e-01 , 4.4187399999999999e-01 -5.8423360182197941e+00 , 2.6227941032066910e+00 , 7.0025871999999998e+00 , -8.5333700000000001e-01 , 5.2117999999999998e-01 , -1.3686200000000001e-02 -6.0732051176450748e+00 , 2.6595190056754183e+00 , 7.4185976000000000e+00 , -8.6383900000000002e-01 , -6.6926299999999994e-02 , -4.9930200000000002e-01 -5.7891703243234698e+00 , 2.6595522663630291e+00 , 7.2211224000000005e+00 , 5.0390199999999996e-01 , -6.7167399999999999e-01 , 5.4308100000000004e-01 -5.9017327004925768e+00 , 2.6905654940696286e+00 , 7.5150160000000001e+00 , 7.2256500000000001e-01 , 6.3352800000000004e-03 , 6.9127400000000006e-01 -5.5248600342221597e+00 , 2.6795940186147886e+00 , 7.1746032000000000e+00 , 9.3796900000000002e-02 , 9.0910999999999997e-01 , -4.0585800000000000e-01 -5.6298786867948953e+00 , 2.7112824958364405e+00 , 7.4702440000000001e+00 , -5.2959800000000001e-01 , -2.7235300000000001e-01 , -8.0333699999999997e-01 -5.6071002213110450e+00 , 2.7320950324201432e+00 , 7.6003064000000000e+00 , 6.2988100000000002e-01 , 9.0570600000000001e-02 , 7.7139300000000000e-01 -5.6672214137477708e+00 , 2.7627370477148121e+00 , 7.8600880000000002e+00 , -9.4760999999999995e-01 , -2.3068900000000001e-01 , -2.2094800000000001e-01 -5.2051401062983551e+00 , 2.7342718875362744e+00 , 7.3303328000000008e+00 , -6.3909499999999997e-01 , 5.8554700000000004e-01 , -4.9869100000000000e-01 -5.4715711838139445e+00 , 2.7921842265102734e+00 , 7.9223424000000007e+00 , -6.5594399999999997e-01 , -7.0111699999999999e-01 , -2.7959400000000001e-01 -5.2002952515954011e+00 , 2.7820954752578397e+00 , 7.6615416000000005e+00 , -4.9896099999999999e-01 , 8.4515899999999999e-01 , -1.9168800000000000e-01 -5.0830852561797375e+00 , 2.7911275643509867e+00 , 7.6444647999999997e+00 , 4.7982600000000000e-02 , 5.4291100000000003e-01 , 8.3841800000000000e-01 -4.9080024448700819e+00 , 2.7908296407576221e+00 , 7.5160248000000003e+00 , -4.0590500000000002e-02 , 3.4123799999999999e-01 , 9.3910000000000005e-01 -4.8496411573753608e+00 , 2.8078848515433048e+00 , 7.5934944000000000e+00 , -8.1929600000000002e-01 , -8.5783300000000007e-02 , -5.6691700000000000e-01 -4.8699723566272137e+00 , 2.8392438494364107e+00 , 7.8272655999999996e+00 , -9.5240700000000000e-01 , -1.8014600000000000e-03 , 3.0482300000000001e-01 -5.0138183881387066e+00 , 2.8967409584002080e+00 , 8.3330696000000000e+00 , -1.8606200000000001e-01 , 7.4831400000000003e-01 , -6.3671500000000003e-01 -4.8262016091775610e+00 , 2.8919497533654654e+00 , 8.1691240000000001e+00 , -3.0710199999999999e-01 , 5.6233599999999995e-01 , -7.6776800000000001e-01 -5.0150898422502497e+00 , 2.9676300597207623e+00 , 8.8327688000000002e+00 , 6.7853499999999997e-02 , 3.2045299999999999e-01 , 9.4483099999999998e-01 -4.6588779778139422e+00 , 2.9235736520184110e+00 , 8.2745695999999995e+00 , 6.3619599999999998e-01 , 5.8822500000000000e-01 , -4.9924499999999999e-01 -4.4901753522515033e+00 , 2.9185512608511681e+00 , 8.1187776000000014e+00 , -6.0272599999999998e-01 , -1.9628399999999999e-01 , 7.7342999999999995e-01 -4.3801563858735149e+00 , 2.9268158071157311e+00 , 8.0941608000000009e+00 , 6.9219699999999995e-01 , 6.5111699999999995e-01 , -3.1130400000000003e-01 -4.4306989606456018e+00 , 2.9797928401872946e+00 , 8.5049191999999998e+00 , -1.0367600000000000e-01 , 5.9042700000000004e-01 , 8.0040400000000000e-01 -4.3055492898799521e+00 , 2.9845434956682944e+00 , 8.4490920000000003e+00 , 6.5693699999999999e-01 , 6.0401199999999999e-01 , 4.5122499999999999e-01 -3.9833506866105624e+00 , 2.9221487744552439e+00 , 7.7807776000000004e+00 , 9.8485800000000001e-01 , -1.5492200000000000e-01 , 7.7811500000000006e-02 -3.9009225961104619e+00 , 2.9338638014556748e+00 , 7.8055192000000000e+00 , -9.7137099999999998e-01 , 1.4229700000000001e-01 , -1.9023699999999999e-01 -3.8296210563510842e+00 , 2.9496340064201081e+00 , 7.8685848000000007e+00 , 3.6665500000000001e-01 , -6.6068300000000002e-01 , 6.5502899999999997e-01 -3.7861901406398779e+00 , 2.9786771854075349e+00 , 8.0403719999999996e+00 , 4.9898700000000001e-01 , -5.9785100000000002e-01 , 6.2736499999999995e-01 -3.6920902516683682e+00 , 2.9872993323322401e+00 , 8.0314487999999997e+00 , -4.8080800000000000e-02 , 9.6790699999999996e-01 , 2.4666500000000000e-01 -3.9117142811673302e+00 , 3.1560834565000473e+00 , 9.3693152000000008e+00 , -9.8715399999999998e-01 , -1.5827100000000000e-01 , -2.1850899999999999e-02 -3.6948521576335045e+00 , 3.1106175524842086e+00 , 8.8971136000000008e+00 , 1.4914300000000000e-01 , 5.0682700000000003e-01 , -8.4904800000000002e-01 -3.5757628330983722e+00 , 3.1119074685147643e+00 , 8.8253951999999991e+00 , 5.1410699999999997e-02 , 8.9213699999999996e-01 , 4.4883099999999998e-01 -3.3669093440467668e+00 , 3.0482394848135552e+00 , 8.2329280000000011e+00 , 9.9497999999999998e-01 , -4.4046000000000002e-02 , -8.9862800000000007e-02 -3.3447559292647955e+00 , 3.1137625394328534e+00 , 8.6746368000000000e+00 , 7.2839699999999996e-01 , 4.3214399999999997e-01 , -5.3168599999999999e-01 -3.1128567718407876e+00 , 3.0050100395239836e+00 , 7.7480696000000000e+00 , -6.0892299999999999e-01 , -5.6064999999999998e-01 , -5.6114600000000003e-01 -2.9962128661505498e+00 , 2.9775895690249321e+00 , 7.4711280000000002e+00 , 2.7362799999999998e-01 , -1.3710600000000001e-01 , -9.5201300000000000e-01 -2.9171854600720595e+00 , 2.9837310274278650e+00 , 7.4583984000000001e+00 , -2.6556799999999998e-02 , 1.7147499999999999e-01 , 9.8483100000000001e-01 -2.8391989311861856e+00 , 2.9905535725961148e+00 , 7.4545296000000008e+00 , -2.9468200000000000e-01 , -4.4668900000000000e-01 , -8.4476700000000005e-01 -2.7640170301396152e+00 , 3.0020926886999284e+00 , 7.4799576000000005e+00 , -5.1966100000000004e-01 , -5.1968499999999995e-01 , -6.7814500000000000e-01 -2.7914987033291045e+00 , 3.2797482804466398e+00 , 9.4489376000000007e+00 , 1.3524400000000000e-01 , -5.1512999999999998e-01 , 8.4637499999999999e-01 -2.6484474464751924e+00 , 3.1687094796865272e+00 , 8.5668824000000008e+00 , -6.0621000000000003e-01 , -6.4055099999999998e-01 , 4.7138400000000003e-01 -2.5382260259136675e+00 , 3.0701248140660962e+00 , 7.7957951999999997e+00 , -7.1178500000000000e-01 , -5.6321399999999999e-01 , -4.1970600000000002e-01 -2.4552727730278936e+00 , 3.0902045649798113e+00 , 7.8777680000000005e+00 , 8.0389699999999997e-01 , 3.4798400000000002e-01 , 4.8234600000000000e-01 -2.3661714082892327e+00 , 3.1369495234655447e+00 , 8.1434567999999992e+00 , 1.3136700000000001e-01 , 5.3285000000000005e-01 , 8.3595100000000000e-01 -2.2780288630036201e+00 , 3.1422683248933172e+00 , 8.1194535999999999e+00 , 3.4516300000000000e-01 , -3.2321499999999997e-01 , -8.8113200000000003e-01 -2.1972160956720499e+00 , 3.1305876710843936e+00 , 7.9809672000000003e+00 , 8.5018199999999999e-01 , -3.1761400000000001e-01 , -4.1989599999999999e-01 -2.1153329684914839e+00 , 3.1289195537163152e+00 , 7.9130760000000002e+00 , 4.4507999999999998e-01 , 8.5965999999999998e-01 , 2.5077800000000000e-01 -1.8623001583060830e+00 , 3.4285609735656957e+00 , 9.8311896000000001e+00 , -8.3236500000000002e-01 , -5.4900800000000005e-01 , -7.5889399999999996e-02 -1.8018213239593903e+00 , 3.3534492503304527e+00 , 9.2662720000000007e+00 , 5.4090400000000005e-01 , 6.6920900000000005e-01 , -5.0949199999999994e-01 -5.1689357359116261e+00 , 1.6576139768453166e+00 , 2.6586239999999983e-01 , -3.8777800000000001e-01 , -2.3689600000000002e-02 , 9.2144800000000004e-01 -4.7827874887931934e+00 , 1.8564599231957735e+00 , 1.3337947200000000e+00 , -1.1856400000000000e-01 , 1.6128200000000001e-01 , 9.7976099999999999e-01 -4.8626244830582390e+00 , 1.8466910789221904e+00 , 1.3392380799999999e+00 , -5.4659500000000000e-02 , 1.7368700000000001e-01 , 9.8328300000000002e-01 -4.9442752252271838e+00 , 1.8373450794753454e+00 , 1.3471587199999999e+00 , -8.4472800000000001e-02 , 1.8715999999999999e-01 , 9.7869099999999998e-01 -5.0086028175733421e+00 , 1.8314794368680916e+00 , 1.3686742399999998e+00 , -8.2066600000000003e-02 , 1.8849299999999999e-01 , 9.7863900000000004e-01 -5.0998237587585953e+00 , 1.8214597944455735e+00 , 1.3752969600000000e+00 , 8.4533999999999998e-02 , -1.5393100000000001e-01 , -9.8445899999999997e-01 -5.1907144047831633e+00 , 1.8109232692622395e+00 , 1.3845529600000002e+00 , -5.2004200000000000e-02 , 1.8508300000000000e-01 , 9.8134600000000005e-01 -5.2823080758892438e+00 , 1.7998501167829493e+00 , 1.3965691200000001e+00 , -7.8363900000000000e-02 , 2.2236900000000001e-01 , 9.7180800000000001e-01 -5.3736278414385286e+00 , 1.7903375760017946e+00 , 1.4110095199999999e+00 , -9.0144100000000005e-02 , 1.7730799999999999e-01 , 9.8001799999999994e-01 -5.4756403899340942e+00 , 1.7789060717438234e+00 , 1.4234708000000000e+00 , -5.3150400000000000e-02 , 2.1061299999999999e-01 , 9.7612399999999999e-01 -5.5862053896580548e+00 , 1.7656968818906200e+00 , 1.4342088000000000e+00 , -5.2862399999999997e-02 , 1.8886900000000001e-01 , 9.8057899999999998e-01 -5.6984716718343487e+00 , 1.7530989083158222e+00 , 1.4483351199999999e+00 , -6.1810900000000002e-02 , 1.8747200000000000e-01 , 9.8032300000000006e-01 -5.8192225677597733e+00 , 1.7388485087721963e+00 , 1.4613434399999998e+00 , -5.2211300000000002e-02 , 1.9370000000000001e-01 , 9.7967000000000004e-01 -5.9504863569328510e+00 , 1.7229907382913441e+00 , 1.4738920799999999e+00 , -7.1630600000000003e-02 , 1.8922300000000000e-01 , 9.7931800000000002e-01 -6.0734697209783786e+00 , 1.7101861210848357e+00 , 1.4945620800000001e+00 , -3.3490300000000001e-01 , 1.9529199999999999e-01 , 9.2179199999999994e-01 -6.2146948886819899e+00 , 1.6936618452784158e+00 , 1.5112020799999999e+00 , -3.2001499999999999e-01 , -6.9419099999999997e-02 , 9.4486599999999998e-01 -6.3289864715293600e+00 , 1.6835839914432604e+00 , 1.5435387999999999e+00 , 7.4517900000000004e-01 , 2.0465299999999999e-02 , 6.6654999999999998e-01 -6.2119826489608734e+00 , 1.7154174704897307e+00 , 1.6659925600000001e+00 , -9.6910499999999999e-01 , -1.5268200000000001e-01 , -1.9370899999999999e-01 -6.1983188170653465e+00 , 1.7289045293896828e+00 , 1.7458333600000000e+00 , 9.9636199999999997e-01 , 8.0326900000000007e-02 , 2.8462200000000000e-02 -6.1934964856907460e+00 , 1.7401302470109994e+00 , 1.8216243999999999e+00 , 9.9204099999999995e-01 , 1.1811400000000000e-01 , 4.3641600000000003e-02 -6.1866550344295117e+00 , 1.7513180721079591e+00 , 1.8967586800000000e+00 , 9.9571699999999996e-01 , 9.2427499999999996e-02 , -2.0248300000000000e-03 -6.1788306761492970e+00 , 1.7624339903760484e+00 , 1.9713628720000000e+00 , 9.9375199999999997e-01 , 7.2849399999999995e-02 , -8.4553199999999995e-02 -6.2079780639877384e+00 , 1.7674192558128607e+00 , 2.0339540239999998e+00 , 9.9693600000000004e-01 , 7.5023699999999999e-02 , 2.2144400000000002e-02 -6.1280528920533444e+00 , 1.7904484255533779e+00 , 2.1259283999999998e+00 , 9.5342300000000002e-01 , 7.0389400000000005e-02 , 2.9330899999999999e-01 -6.1153536601208600e+00 , 1.8022655126291074e+00 , 2.1976748800000001e+00 , 9.9405100000000002e-01 , 6.4117400000000005e-02 , -8.8047500000000001e-02 -6.1307191168271560e+00 , 1.8092279835014746e+00 , 2.2618678399999999e+00 , 9.7975900000000005e-01 , 5.7067000000000000e-02 , -1.9187699999999999e-01 -6.1364012814740923e+00 , 1.8181548789243807e+00 , 2.3284694400000001e+00 , 9.2403500000000005e-01 , -1.2171700000000001e-02 , -3.8211499999999998e-01 -6.1806116478647670e+00 , 1.8207063422245044e+00 , 2.3874592799999999e+00 , -8.3191599999999999e-01 , 9.2411899999999998e-03 , 5.5482399999999998e-01 -6.2129669240702476e+00 , 1.8243670742120546e+00 , 2.4494183199999999e+00 , 6.9609799999999999e-01 , -3.0364400000000000e-02 , -7.1730400000000005e-01 -6.3261251004914181e+00 , 1.8169489855017646e+00 , 2.4999956000000001e+00 , 3.8789400000000002e-01 , -1.0398900000000000e-01 , -9.1581900000000005e-01 -6.5821899273198996e+00 , 1.7886900765255640e+00 , 2.5355895999999998e+00 , -2.0834300000000000e-01 , 1.5204999999999999e-01 , 9.6616500000000005e-01 -1.1622201317421208e+01 , 1.0811288499642613e+00 , 2.1967056000000000e+00 , -1.0786100000000000e-01 , 2.0100399999999999e-01 , 9.7363400000000000e-01 -1.2254926472888522e+01 , 1.0137969785607279e+00 , 2.3085024800000000e+00 , 1.0632000000000000e-01 , -1.9636400000000001e-01 , -9.7475000000000001e-01 -1.3236734395174102e+01 , 9.0078743450077714e-01 , 2.4208557600000002e+00 , 5.0101800000000002e-02 , -1.9070500000000001e-01 , -9.8036800000000002e-01 -1.4454067596201273e+01 , 7.6007329250739342e-01 , 2.5566496000000001e+00 , -6.4761600000000002e-02 , 1.9064600000000001e-01 , 9.7951999999999995e-01 -1.5835174979390326e+01 , 6.0398887550517255e-01 , 2.7302141600000001e+00 , -4.4777800000000000e-02 , 1.8770700000000001e-01 , 9.8120399999999997e-01 -1.7915901423836161e+01 , 3.6152343990407054e-01 , 2.9457208800000001e+00 , -1.0473200000000001e-01 , 2.0934100000000000e-01 , 9.7221800000000003e-01 -1.8962575353328852e+01 , 2.6333950725838595e-01 , 3.2246104000000004e+00 , -1.3071700000000000e-01 , 2.2500000000000001e-01 , 9.6555100000000005e-01 -2.8499619715320915e+01 , -7.8436337543960688e-01 , 4.6709904000000000e+00 , -6.1530099999999999e-01 , -4.5404000000000000e-01 , 6.4440100000000000e-01 -2.7230110347664812e+01 , -5.6895165927362612e-01 , 5.0266288000000001e+00 , 8.7310500000000002e-01 , 3.1895099999999998e-01 , 3.6872600000000000e-01 -2.7168853768299130e+01 , -5.0128381111916331e-01 , 5.4547343999999995e+00 , -7.2052099999999997e-01 , -4.5983400000000002e-01 , 5.1903999999999995e-01 -2.9082745681047228e+01 , -6.6145698509478423e-01 , 6.1063983999999998e+00 , 8.2574199999999998e-01 , 3.5429200000000000e-01 , -4.3889299999999998e-01 -2.9341774479334120e+01 , -6.2534405275679328e-01 , 6.6096648000000000e+00 , -3.4228700000000001e-01 , 4.1067199999999998e-01 , 8.4509699999999999e-01 -3.0827961372269222e+01 , -7.2292379550737706e-01 , 7.3068079999999993e+00 , -3.0144900000000002e-01 , -2.1589300000000000e-01 , 9.2871899999999996e-01 -3.0585671095281342e+01 , -6.2645896857601358e-01 , 7.7708040000000000e+00 , -2.9214800000000002e-01 , 5.6310199999999999e-01 , 7.7302300000000002e-01 -2.4770395707812948e+01 , 5.5382801658202974e-02 , 7.2000520000000003e+00 , 6.6501600000000005e-01 , 1.7787900000000001e-01 , 7.2533700000000001e-01 -2.5036222683968674e+01 , 8.3609932432388012e-02 , 7.6550832000000000e+00 , 2.8904900000000000e-01 , -5.3761600000000000e-02 , 9.5580299999999996e-01 -2.4262695829470530e+01 , 2.1788237926422127e-01 , 7.8928896000000002e+00 , 6.3990400000000003e-01 , -1.3655000000000000e-01 , 7.5622500000000004e-01 -2.3839692297870151e+01 , 3.1486576141604350e-01 , 8.1891232000000009e+00 , 6.9058699999999995e-01 , -1.7144799999999999e-01 , 7.0263399999999998e-01 -2.4375568334515133e+01 , 3.1803588644592851e-01 , 8.7197624000000005e+00 , 6.9058699999999995e-01 , -1.7144799999999999e-01 , 7.0263399999999998e-01 -2.6906833318154998e+01 , 1.4061438920611224e-01 , 9.8234104000000002e+00 , -2.3013400000000001e-01 , -9.3501500000000004e-01 , 2.6978799999999997e-01 -2.7180629123469494e+01 , 1.7978441120694910e-01 , 1.0360819999999999e+01 , -5.4087200000000002e-01 , 3.4368300000000002e-01 , -7.6768499999999995e-01 -2.2983088921848225e+01 , 6.1083665470766380e-01 , 9.5122944000000000e+00 , -7.2860100000000005e-01 , 6.7264599999999997e-01 , 1.2917799999999999e-01 -3.1717282885589963e+01 , -7.4702415167648972e-02 , 1.2806328000000001e+01 , -7.9309600000000002e-01 , -6.0030399999999995e-01 , 1.0311900000000000e-01 -2.2151809056322261e+01 , 7.8868802659760928e-01 , 1.0006887200000000e+01 , 8.3774700000000002e-01 , -2.3267499999999999e-01 , 4.9400699999999997e-01 -2.5913557382583363e+01 , 5.4388019126590614e-01 , 1.1786899200000001e+01 , 6.1917699999999999e-02 , -9.4901300000000000e-01 , 3.0909599999999998e-01 -2.1900231496075108e+01 , 9.1526397283168048e-01 , 1.0681535200000001e+01 , 9.5701199999999997e-01 , -1.6822000000000001e-01 , -2.3628500000000000e-01 -2.2174124444143519e+01 , 9.4924342836580511e-01 , 1.1182721600000001e+01 , 9.6052499999999996e-01 , -1.5361000000000000e-01 , -2.3194000000000001e-01 -2.2301933083546469e+01 , 9.9613050512055934e-01 , 1.1637732000000000e+01 , -9.3983099999999997e-01 , 5.3571100000000003e-02 , 3.3741399999999999e-01 -2.2884925500998950e+01 , 1.0129051955401547e+00 , 1.2309104000000000e+01 , -9.4750400000000001e-01 , -3.1242300000000001e-01 , 6.8036500000000000e-02 -2.1994677114942704e+01 , 1.1309238603084153e+00 , 1.2314907200000000e+01 , -9.2491000000000001e-01 , -3.6548599999999998e-01 , 1.0469500000000000e-01 -2.1826656750609605e+01 , 1.1986501843753021e+00 , 1.2646792000000000e+01 , 6.1531400000000003e-01 , 6.6896900000000004e-01 , 4.1697600000000001e-01 -2.0803644220017617e+01 , 1.3172612948657556e+00 , 1.2537800000000001e+01 , 6.6676100000000005e-01 , 6.8457000000000001e-01 , 2.9460900000000001e-01 -2.3030411648535861e+01 , 1.2484618819844775e+00 , 1.4136592000000000e+01 , -9.3044099999999996e-01 , -2.3372200000000001e-01 , 2.8223100000000001e-01 -2.3211455090694567e+01 , 1.3028506150600567e+00 , 1.4698088000000000e+01 , 9.9678800000000001e-01 , 3.3557799999999999e-02 , -7.2710800000000006e-02 -2.2293669916905884e+01 , 1.4138016832510478e+00 , 1.4636624000000001e+01 , -9.1024000000000005e-01 , -1.5702600000000000e-01 , 3.8315300000000002e-01 -2.5081197362827595e+01 , 1.3479108660291081e+00 , 1.6785888000000000e+01 , 6.4220400000000000e-01 , 2.3709000000000000e-01 , -7.2894599999999998e-01 -2.5259106460811555e+01 , 1.4146209068743316e+00 , 1.7434328000000001e+01 , 6.1338499999999996e-01 , 4.8766700000000002e-01 , -6.2124000000000001e-01 -2.6125580603178499e+01 , 1.4573333500508669e+00 , 1.8553159999999998e+01 , -7.6306499999999999e-01 , -6.2174499999999999e-01 , 1.7653700000000000e-01 -2.2959714788066993e+01 , 1.6548035643205201e+00 , 1.6992120000000000e+01 , -8.5821599999999998e-01 , 4.9785699999999999e-01 , 1.2491400000000000e-01 -2.2575783155806704e+01 , 1.7396408207148111e+00 , 1.7241616000000000e+01 , -9.3486000000000002e-01 , 2.7044600000000002e-01 , 2.2999100000000000e-01 -2.3667163525893464e+01 , 1.7800223709715055e+00 , 1.8560336000000003e+01 , -8.9559699999999998e-01 , 2.1798600000000001e-01 , 3.8779999999999998e-01 -6.2004559969955571e+00 , 2.3522469490977085e+00 , 6.2315832000000002e+00 , 5.6989400000000001e-01 , 4.9153000000000002e-01 , 6.5849800000000003e-01 -6.1145671741402259e+00 , 2.3686277597523455e+00 , 6.2682120000000001e+00 , -5.4915000000000003e-01 , -1.7822800000000000e-01 , -8.1649799999999995e-01 -6.0601159680988026e+00 , 2.3846111385236846e+00 , 6.3306432000000008e+00 , -8.6427799999999999e-01 , -3.1733699999999998e-01 , -3.9028200000000002e-01 -6.2012962114563299e+00 , 2.4004503323298003e+00 , 6.5764160000000000e+00 , -9.1906600000000005e-01 , -1.7342099999999999e-01 , -3.5389599999999999e-01 -6.0739286460774053e+00 , 2.4173462161356198e+00 , 6.5751264000000003e+00 , -3.3052100000000001e-01 , -3.1119300000000000e-01 , -8.9101900000000001e-01 -5.9908238138024679e+00 , 2.4331325912002417e+00 , 6.6146671999999995e+00 , -4.7967700000000002e-01 , -2.5302300000000000e-01 , -8.4017200000000003e-01 -5.9004791944078070e+00 , 2.4494559056419667e+00 , 6.6447960000000004e+00 , 6.9903499999999996e-01 , 2.8276800000000002e-01 , 6.5680499999999997e-01 -5.9949354263120966e+00 , 2.4685479518405664e+00 , 6.8703824000000004e+00 , -7.1672999999999998e-01 , -3.3297100000000002e-01 , -6.1272300000000002e-01 -5.7897407154571567e+00 , 2.4817381007590584e+00 , 6.7761167999999996e+00 , -6.9433699999999998e-01 , 2.0424300000000001e-01 , -6.9005899999999998e-01 -5.7744157862427485e+00 , 2.4995458364405820e+00 , 6.8875840000000004e+00 , 1.3298199999999999e-01 , -4.3019299999999999e-01 , 8.9288900000000004e-01 -5.6540413315848541e+00 , 2.5138237313965739e+00 , 6.8800648000000004e+00 , -5.3261700000000001e-01 , 4.9389200000000000e-01 , -6.8730599999999997e-01 -6.0149985225614353e+00 , 2.5478718709122425e+00 , 7.4581071999999997e+00 , 5.4355399999999998e-01 , 3.2192799999999999e-01 , 7.7518500000000001e-01 -5.9324701878535269e+00 , 2.5651068540795645e+00 , 7.5102424000000001e+00 , 5.6601500000000005e-01 , 1.6041800000000001e-01 , 8.0863600000000002e-01 -5.5103186313191044e+00 , 2.5659113634741706e+00 , 7.1132016000000009e+00 , -8.5186799999999993e-02 , -8.0305499999999996e-01 , 5.8978399999999997e-01 -5.4530424595238802e+00 , 2.5821678317990409e+00 , 7.1816648000000010e+00 , -2.5179299999999999e-01 , 5.9557000000000004e-01 , 7.6282099999999997e-01 -5.2076752899645680e+00 , 2.5872303252426003e+00 , 6.9857807999999997e+00 , 1.8842800000000001e-01 , -4.2541000000000001e-01 , -8.8516700000000004e-01 -5.2454594586237953e+00 , 2.6101759862932106e+00 , 7.1867920000000005e+00 , -5.4360699999999998e-02 , -6.9897399999999998e-01 , 7.1307799999999999e-01 -5.4810250813124251e+00 , 2.6509009753095558e+00 , 7.7027048000000002e+00 , -4.5712999999999998e-01 , 8.3871700000000005e-01 , -2.9594799999999999e-01 -5.6172219523186646e+00 , 2.6881830192495442e+00 , 8.0960016000000010e+00 , 9.9140899999999998e-01 , 1.3066700000000001e-01 , 5.8844700000000002e-03 -5.1798471322412780e+00 , 2.6725290839371310e+00 , 7.5718624000000005e+00 , 4.4135600000000003e-01 , 8.7848999999999999e-01 , -1.8292300000000000e-01 -5.1012743561788083e+00 , 2.6893054617187051e+00 , 7.6172895999999994e+00 , -2.1854100000000001e-02 , -8.6855300000000002e-01 , -4.9511400000000000e-01 -4.9823153670968452e+00 , 2.7004220710321531e+00 , 7.5891055999999999e+00 , -1.8223699999999999e-02 , -1.1661500000000000e-01 , 9.9300999999999995e-01 -4.9238745049849353e+00 , 2.7198067225065330e+00 , 7.6675840000000006e+00 , -2.5247000000000003e-01 , -9.2711200000000005e-01 , -2.7698800000000001e-01 -5.0102664453223715e+00 , 2.7585794241087305e+00 , 8.0312927999999992e+00 , 3.7808399999999998e-01 , 9.0227299999999999e-01 , 2.0725900000000000e-01 -4.7957589427713447e+00 , 2.7567776057197979e+00 , 7.8132152000000001e+00 , -9.7577800000000003e-01 , 1.8274199999999999e-01 , 1.2026500000000000e-01 -4.7395387195137602e+00 , 2.7772476088010754e+00 , 7.9080840000000006e+00 , -8.7777099999999997e-01 , -4.4913399999999998e-01 , -1.6672500000000001e-01 -4.7110676190525709e+00 , 2.8033712886645095e+00 , 8.0685560000000009e+00 , -6.6657599999999995e-01 , -7.3156900000000002e-01 , 1.4311900000000000e-01 -4.6578327464501488e+00 , 2.8253420649076362e+00 , 8.1820616000000008e+00 , 5.9840400000000005e-01 , 7.6545500000000000e-01 , 2.3662400000000000e-01 -4.5208826603080539e+00 , 2.8322933253504008e+00 , 8.1030215999999999e+00 , 6.8320899999999996e-01 , 6.6168700000000003e-01 , 3.0886100000000000e-01 -4.5849379620212503e+00 , 2.8822655058456430e+00 , 8.5228175999999998e+00 , -4.9878099999999997e-01 , 1.9619500000000001e-01 , -8.4423099999999995e-01 -4.5264609042444013e+00 , 2.9091574769224064e+00 , 8.6543671999999994e+00 , -6.2994800000000004e-02 , 4.7280700000000002e-02 , 9.9689300000000003e-01 -4.3677276024905467e+00 , 2.9096588318066363e+00 , 8.5123031999999998e+00 , 6.5289399999999997e-01 , 2.0531500000000000e-01 , -7.2909199999999996e-01 -3.9546416813357248e+00 , 2.8350650591287434e+00 , 7.5901352000000006e+00 , 5.7233100000000003e-01 , 3.6704799999999999e-01 , -7.3328899999999997e-01 -3.9196934480068988e+00 , 2.8628841262090097e+00 , 7.7523752000000004e+00 , -7.1579300000000001e-01 , 4.7201700000000002e-01 , -5.1462600000000003e-01 -3.7655576892619704e+00 , 2.8518552754290427e+00 , 7.5277040000000000e+00 , 2.3168900000000001e-01 , 9.4521200000000005e-01 , 2.2999000000000000e-01 -3.6520049424521486e+00 , 2.8517971485426288e+00 , 7.4188679999999998e+00 , 7.2993799999999998e-01 , 5.9660500000000005e-01 , -3.3354699999999998e-01 -3.7210645057205767e+00 , 2.9232013763795601e+00 , 7.9988239999999999e+00 , -1.3846300000000000e-01 , -9.8302699999999998e-01 , -1.2035899999999999e-01 -3.7660083940454037e+00 , 2.9954218701879789e+00 , 8.5618696000000014e+00 , 4.9601600000000001e-01 , 7.9532499999999995e-01 , -3.4846300000000002e-01 -3.7545717032088253e+00 , 3.0528878031749418e+00 , 8.9658888000000001e+00 , -1.4914300000000000e-01 , -5.0682700000000003e-01 , 8.4904800000000002e-01 -3.6149780669683302e+00 , 3.0484858019306476e+00 , 8.8035656000000007e+00 , 3.1709100000000001e-01 , 1.9492100000000001e-01 , -9.2814799999999997e-01 -3.5137286422925333e+00 , 3.0628532794823160e+00 , 8.8111160000000002e+00 , 5.6058100000000000e-02 , 8.8156599999999996e-01 , 4.6872100000000000e-01 -3.4202689493291727e+00 , 3.0835505931151692e+00 , 8.8675567999999991e+00 , 3.9123599999999997e-01 , 8.9108399999999999e-01 , -2.3000899999999999e-01 -3.2966977604134780e+00 , 3.0799908702490804e+00 , 8.7286439999999992e+00 , 7.2839699999999996e-01 , 4.3214399999999997e-01 , -5.3168599999999999e-01 -3.0347790003987933e+00 , 2.9439629433826817e+00 , 7.5021824000000006e+00 , -2.0319100000000001e-01 , 1.8451500000000001e-01 , 9.6159600000000001e-01 -2.9510424378451363e+00 , 2.9484176133541879e+00 , 7.4590015999999997e+00 , -8.7115399999999996e-02 , 3.0549399999999999e-01 , 9.4820099999999996e-01 -2.8749889953065719e+00 , 2.9594139616736470e+00 , 7.4657200000000001e+00 , -3.0586799999999997e-01 , -3.5688900000000001e-01 , -8.8265199999999999e-01 -2.8006470472232392e+00 , 2.9741486901612690e+00 , 7.5019120000000008e+00 , -4.5090700000000000e-01 , -4.2826100000000000e-01 , -7.8311900000000001e-01 -2.8551932196027301e+00 , 3.2658869230819936e+00 , 9.6467039999999997e+00 , -5.2076999999999996e-01 , 7.6766000000000001e-01 , -3.7349100000000002e-01 -2.6919401332588522e+00 , 3.1345088878287353e+00 , 8.5487136000000010e+00 , 4.3765300000000001e-01 , 8.8213200000000003e-01 , -1.7407800000000001e-01 -2.5892557761595132e+00 , 3.1066901323232665e+00 , 8.2516895999999988e+00 , 8.3877000000000002e-01 , 3.9621899999999999e-01 , -3.7346499999999999e-01 -2.4948257797282438e+00 , 3.0627236251775036e+00 , 7.8499375999999996e+00 , -6.7792900000000000e-01 , -4.9198399999999998e-01 , -5.4622700000000002e-01 -2.4099417286163356e+00 , 3.0940400918996200e+00 , 7.9925320000000006e+00 , -9.1889900000000002e-01 , 2.6540200000000003e-01 , -2.9186800000000002e-01 -2.3208330280184080e+00 , 3.1262945884806808e+00 , 8.1441640000000000e+00 , 1.8693699999999999e-01 , 4.2442200000000002e-01 , 8.8595699999999999e-01 -2.2330955331327380e+00 , 3.1334994567672645e+00 , 8.1084920000000000e+00 , -5.2093000000000000e-01 , -1.0477200000000000e-01 , 8.4714500000000004e-01 -2.1580503077937192e+00 , 3.1122172447532490e+00 , 7.8867120000000002e+00 , -9.2793400000000005e-03 , -8.9789099999999999e-01 , 4.4012000000000001e-01 -2.0754706715951210e+00 , 3.1207223393331356e+00 , 7.8691256000000003e+00 , -3.6863699999999999e-02 , -4.3379499999999999e-01 , 9.0025699999999997e-01 -1.6034960138084351e+00 , 3.7415702738944301e+00 , 1.1893488800000000e+01 , 2.8867700000000002e-01 , -9.4472999999999996e-01 , -1.5540699999999999e-01 -1.7483672415076845e+00 , 3.3555490191192101e+00 , 9.2494863999999986e+00 , -9.2874299999999999e-01 , 2.5946200000000003e-01 , -2.6479300000000000e-01 -4.7419213999168726e+00 , 1.7998245478200185e+00 , 1.3338331999999999e+00 , -1.4145500000000000e-01 , 1.7732800000000001e-01 , 9.7393300000000005e-01 -4.8057231863571346e+00 , 1.7919984858383129e+00 , 1.3507747999999999e+00 , -1.3486699999999999e-01 , 1.6874700000000001e-01 , 9.7638899999999995e-01 -4.8853724549979445e+00 , 1.7803812617045269e+00 , 1.3575389599999999e+00 , -4.1628600000000002e-02 , 2.0340500000000000e-01 , 9.7820900000000000e-01 -4.9667962233322269e+00 , 1.7681241409070030e+00 , 1.3667835199999998e+00 , -8.6128700000000002e-02 , 2.1081100000000000e-01 , 9.7372499999999995e-01 -5.0479525674554226e+00 , 1.7563486924995171e+00 , 1.3783545600000000e+00 , -9.3439300000000003e-02 , 2.0688000000000001e-01 , 9.7389400000000004e-01 -5.1298938847946118e+00 , 1.7449934095306079e+00 , 1.3921761600000000e+00 , -7.7066399999999993e-02 , 2.0578399999999999e-01 , 9.7555800000000004e-01 -5.2205718742558362e+00 , 1.7326267960882911e+00 , 1.4028548800000000e+00 , -6.6782900000000006e-02 , 2.0154700000000000e-01 , 9.7719900000000004e-01 -5.3119333983814823e+00 , 1.7197673563048208e+00 , 1.4164944799999999e+00 , -6.7695699999999998e-02 , 1.8327499999999999e-01 , 9.8072800000000004e-01 -5.4129736690121977e+00 , 1.7049659158941128e+00 , 1.4278273600000000e+00 , -7.7398499999999995e-02 , 1.9079800000000000e-01 , 9.7857300000000003e-01 -5.5146911995777295e+00 , 1.6907495691811076e+00 , 1.4422209600000000e+00 , -6.6280800000000001e-02 , 1.7600900000000000e-01 , 9.8215500000000000e-01 -5.6249715806801728e+00 , 1.6747565837646694e+00 , 1.4548902399999999e+00 , -5.7399400000000003e-02 , 1.9537199999999999e-01 , 9.7904800000000003e-01 -5.7369009792099668e+00 , 1.6583762870983418e+00 , 1.4712525599999999e+00 , -6.1492100000000001e-02 , 1.9668600000000000e-01 , 9.7853599999999996e-01 -5.8573518984188615e+00 , 1.6413655075614648e+00 , 1.4862940800000000e+00 , -4.9661100000000000e-02 , 1.9044100000000000e-01 , 9.8044200000000004e-01 -5.9882544928546455e+00 , 1.6217406477825802e+00 , 1.5011806399999998e+00 , -7.2362999999999997e-02 , 1.9590600000000000e-01 , 9.7794899999999996e-01 -6.1197642292256633e+00 , 1.6039367056049281e+00 , 1.5199328800000000e+00 , -3.2723300000000000e-01 , 1.7862200000000000e-01 , 9.2790799999999996e-01 -6.2518068804397693e+00 , 1.5859118333704323e+00 , 1.5429626400000001e+00 , 5.5458900000000000e-01 , 1.1179000000000000e-01 , -8.2458100000000001e-01 -6.3460439017442125e+00 , 1.5754615290004108e+00 , 1.5849859200000000e+00 , 9.8117799999999999e-01 , 6.3528600000000005e-02 , 1.8235699999999999e-01 -6.2194521420680946e+00 , 1.6134480297777152e+00 , 1.7096330399999999e+00 , -9.7605100000000000e-01 , -1.1596500000000000e-01 , -1.8405700000000000e-01 -6.2341167801790442e+00 , 1.6205698049689765e+00 , 1.7796978400000001e+00 , 9.9811099999999997e-01 , 5.8177199999999998e-02 , 1.9732500000000000e-02 -6.2292002340733417e+00 , 1.6319462087026047e+00 , 1.8561960799999999e+00 , 9.9796300000000004e-01 , 6.2850199999999995e-02 , 1.0960500000000000e-02 -6.2114981624045491e+00 , 1.6453574825538428e+00 , 1.9348269440000001e+00 , 9.9648300000000001e-01 , 8.3591700000000005e-02 , 5.8527400000000004e-03 -6.2026006765835406e+00 , 1.6565848243436412e+00 , 2.0097101575999998e+00 , 9.9294499999999997e-01 , 6.1002500000000001e-02 , 1.0167800000000000e-01 -6.2326355247564083e+00 , 1.6606994460216065e+00 , 2.0734416800000002e+00 , 9.8475800000000002e-01 , 1.1967899999999999e-01 , 1.2620600000000001e-01 -6.1517770170754904e+00 , 1.6857678392771558e+00 , 2.1647786400000002e+00 , 9.5681700000000003e-01 , 1.4930399999999999e-01 , 2.4942100000000000e-01 -6.1583726060764805e+00 , 1.6938007029937892e+00 , 2.2324181599999999e+00 , 9.8942900000000000e-01 , 1.1945400000000000e-01 , -8.2221000000000002e-02 -6.1542756187472962e+00 , 1.7037515109179986e+00 , 2.3020368000000002e+00 , 9.7381300000000004e-01 , 6.1776600000000001e-02 , -2.1879699999999999e-01 -6.1684749728783208e+00 , 1.7109699758089405e+00 , 2.3672167200000001e+00 , -9.1803800000000002e-01 , -8.0025500000000006e-03 , 3.9641300000000002e-01 -6.2423623527644319e+00 , 1.7061571969728173e+00 , 2.4223533599999998e+00 , -7.6152799999999998e-01 , 2.3952299999999999e-02 , 6.4768999999999999e-01 -6.2745031051184617e+00 , 1.7090963664400283e+00 , 2.4859337600000000e+00 , 5.6657800000000003e-01 , -8.7889700000000001e-02 , -8.1930800000000004e-01 -6.4371898679100772e+00 , 1.6891443242532140e+00 , 2.5323229600000001e+00 , 2.6643200000000000e-01 , -1.6765800000000000e-01 , -9.4916000000000000e-01 -1.1807215437548171e+01 , 7.9346413927926118e-01 , 2.2946070399999998e+00 , -1.0363400000000000e-01 , 2.0072799999999999e-01 , 9.7414999999999996e-01 -1.2569807118385372e+01 , 6.8612487939968037e-01 , 2.4094521599999998e+00 , -7.2272799999999998e-02 , 1.9180100000000000e-01 , 9.7876900000000000e-01 -1.3680203131781177e+01 , 5.2433835317162591e-01 , 2.5337862400000000e+00 , -4.6741999999999999e-02 , 1.9186300000000001e-01 , 9.8030799999999996e-01 -1.4891951919860091e+01 , 3.5149593306404370e-01 , 2.6934075200000001e+00 , -6.4060000000000006e-02 , 1.9013600000000000e-01 , 9.7966600000000004e-01 -1.6758974021849902e+01 , 7.7563554909236165e-02 , 2.8863722400000000e+00 , -5.8585699999999998e-02 , 1.8640000000000001e-01 , 9.8072599999999999e-01 -1.8357145900553469e+01 , -1.4529340940391444e-01 , 3.1436776000000002e+00 , -1.3669300000000001e-01 , 2.1395500000000001e-01 , 9.6723199999999998e-01 -1.9910133678575153e+01 , -3.5307292358352127e-01 , 3.4557191999999999e+00 , -1.2975100000000001e-01 , 2.1981300000000001e-01 , 9.6687500000000004e-01 -2.8326876699443417e+01 , -1.5597037008261467e+00 , 4.5435175999999995e+00 , -7.1395600000000004e-01 , -4.5224100000000000e-01 , 5.3454999999999997e-01 -2.9425012820382740e+01 , -1.6636276933731113e+00 , 5.0789512000000006e+00 , 6.4410000000000001e-01 , 3.9025700000000002e-01 , -6.5790099999999996e-01 -3.0891626661637765e+01 , -1.8164605855558240e+00 , 5.6873824000000006e+00 , -6.7907600000000001e-01 , -3.5141800000000001e-01 , 6.4448499999999997e-01 -3.0637894327720758e+01 , -1.7122342306028373e+00 , 6.1610400000000007e+00 , -6.8158600000000003e-01 , -5.8857199999999998e-01 , 4.3476900000000002e-01 -3.0774056157544333e+01 , -1.6641526199487147e+00 , 6.6765368000000000e+00 , 6.3597199999999998e-01 , 5.8932300000000004e-01 , -4.9823499999999998e-01 -3.0207996933266639e+01 , -1.5158069911827372e+00 , 7.0969984000000004e+00 , -4.4768799999999997e-01 , -8.9155600000000002e-01 , 6.8579500000000002e-02 -3.0205603931623443e+01 , -1.4490362375987349e+00 , 7.5913415999999998e+00 , -4.4768799999999997e-01 , -8.9155600000000002e-01 , 6.8579600000000004e-02 -2.5051198246846237e+01 , -6.7864686913140249e-01 , 7.1582336000000000e+00 , 5.8042000000000005e-01 , 2.8429500000000002e-01 , 7.6307800000000003e-01 -2.5663356570629183e+01 , -7.0471990952596508e-01 , 7.6864704000000001e+00 , 4.2935000000000001e-01 , 4.0382200000000001e-01 , 8.0782799999999999e-01 -2.8380883126036746e+01 , -1.0058280428829778e+00 , 8.6955616000000013e+00 , 7.0699900000000004e-01 , -2.0099400000000001e-01 , 6.7805199999999999e-01 -2.3677303631157400e+01 , -3.3409346454335020e-01 , 8.0640320000000010e+00 , 1.3144800000000001e-01 , 1.6523699999999999e-01 , 9.7745499999999996e-01 -2.4136376995685776e+01 , -3.3994470160516510e-01 , 8.5703664000000011e+00 , -5.7670999999999994e-01 , -8.5640300000000003e-03 , -8.1690399999999996e-01 -2.2271423651066971e+01 , -5.3708058704346140e-02 , 8.4653367999999993e+00 , 6.0056399999999999e-01 , -5.4241799999999996e-01 , 5.8745700000000001e-01 -2.2400542280816151e+01 , -1.9565162168530659e-02 , 8.8732040000000012e+00 , -8.5114999999999996e-01 , 4.7314299999999998e-01 , -2.2733200000000001e-01 -2.2709189050760610e+01 , -4.6981647967632156e-03 , 9.3448024000000007e+00 , 6.2658599999999998e-01 , 6.2277099999999996e-01 , -4.6855700000000000e-01 -2.4716236946285491e+01 , -1.8626903125198213e-01 , 1.0389763200000001e+01 , 7.4403500000000000e-01 , -2.0556199999999999e-01 , -6.3573199999999996e-01 -2.3499406794237107e+01 , 9.5466126443886079e-03 , 1.0395836800000000e+01 , -1.4790900000000001e-01 , 9.4936699999999996e-01 , 2.7717199999999997e-01 -2.1793959959954307e+01 , 2.5487608735832801e-01 , 1.0179714400000000e+01 , -9.4457199999999997e-01 , 8.1994899999999996e-02 , -3.1790099999999999e-01 -2.1597886886291796e+01 , 3.2802611133573056e-01 , 1.0485068800000001e+01 , -9.2786299999999999e-01 , 1.4717000000000000e-01 , 3.4265499999999999e-01 -2.2163442374976334e+01 , 3.1984149437507692e-01 , 1.1097441600000002e+01 , -8.5966600000000004e-01 , -1.4964399999999999e-02 , 5.1063700000000001e-01 -2.2199876128789253e+01 , 3.6991714290547173e-01 , 1.1511840000000001e+01 , -9.1764100000000004e-01 , 6.6292000000000004e-02 , 3.9184200000000002e-01 -2.3003341223774392e+01 , 3.4498482931108887e-01 , 1.2276302400000001e+01 , -9.3319300000000005e-01 , 3.4976400000000002e-01 , 8.2562099999999999e-02 -2.5136272273599467e+01 , 1.9467257601118315e-01 , 1.3703536000000000e+01 , -7.5280000000000002e-01 , -2.1523100000000001e-01 , -6.2206700000000004e-01 -2.2639851016309152e+01 , 4.9544893763435982e-01 , 1.2961392000000000e+01 , 7.9155600000000004e-01 , 5.3006799999999998e-01 , 3.0408400000000002e-01 -2.2499579580324180e+01 , 5.6710240411404111e-01 , 1.3323936000000002e+01 , -9.4328199999999995e-01 , -3.3116600000000002e-01 , -2.3403600000000000e-02 -2.2508595577033475e+01 , 6.2627471275497637e-01 , 1.3767080000000002e+01 , -9.2061300000000001e-01 , -1.6874300000000000e-01 , 3.5213299999999997e-01 -2.2843936792854038e+01 , 6.5759953866904453e-01 , 1.4400024000000000e+01 , -9.1907099999999997e-01 , -1.2026600000000000e-01 , 3.7529400000000002e-01 -2.4385064209174221e+01 , 5.9313325754259849e-01 , 1.5752856000000001e+01 , 8.0180300000000004e-01 , -5.9745800000000004e-01 , 1.2515200000000001e-02 -2.3075760195095850e+01 , 7.6614991942006272e-01 , 1.5473200000000000e+01 , 5.8887699999999998e-01 , 8.0660699999999996e-01 , -5.1090000000000003e-02 -2.3700809915481489e+01 , 7.8431910309111363e-01 , 1.6350231999999998e+01 , 8.7097999999999998e-01 , 4.9098199999999997e-01 , 1.8190200000000000e-02 -2.2621938391687507e+01 , 9.3193082623818757e-01 , 1.6162303999999999e+01 , 9.8604999999999998e-01 , 1.2183600000000000e-01 , 1.1340900000000000e-01 -2.2664931874953076e+01 , 9.9675977560290274e-01 , 1.6688231999999999e+01 , 9.9795100000000003e-01 , 4.3706000000000002e-02 , 4.6727400000000002e-02 -2.2858976518914798e+01 , 1.0524469307352162e+00 , 1.7332824000000002e+01 , 9.6718000000000004e-01 , 1.9840200000000000e-01 , -1.5874099999999999e-01 -2.3187106258288431e+01 , 1.1031191165419263e+00 , 1.8097016000000000e+01 , -8.8944999999999996e-01 , -2.4730100000000001e-02 , 4.5636199999999999e-01 -7.3203892778821453e+00 , 2.1914673366572672e+00 , 7.2852591999999996e+00 , -4.5791399999999999e-01 , 8.4114900000000004e-01 , -2.8772100000000000e-01 -7.3187542416884304e+00 , 2.2113115889696027e+00 , 7.4308384000000007e+00 , 6.1210299999999995e-01 , -7.9031600000000002e-01 , -2.7015800000000000e-02 -6.4581932711228385e+00 , 2.2629181726578169e+00 , 6.7865896000000010e+00 , 3.2512300000000000e-01 , 9.1077300000000005e-01 , 2.5453500000000001e-01 -6.1385358782692157e+00 , 2.2900140866278353e+00 , 6.6104343999999999e+00 , 7.7037299999999997e-01 , 5.5743399999999999e-01 , 3.0950299999999997e-01 -6.1077680344599541e+00 , 2.3077326513182639e+00 , 6.7023495999999998e+00 , 5.4660900000000001e-01 , 6.2791900000000000e-01 , 5.5401900000000004e-01 -6.2340900083382058e+00 , 2.3219595848045747e+00 , 6.9580336000000003e+00 , -4.4564199999999998e-01 , -8.9041199999999998e-01 , -9.2577199999999998e-02 -6.0036868818762699e+00 , 2.3437646800255436e+00 , 6.8484384000000000e+00 , 4.4204599999999999e-01 , 8.1269700000000000e-01 , 3.7963000000000002e-01 -5.8613562683176461e+00 , 2.3630201802939288e+00 , 6.8240504000000000e+00 , 4.2566900000000002e-01 , 4.8938999999999999e-01 , 7.6112000000000002e-01 -5.7215877418560268e+00 , 2.3824618394755208e+00 , 6.7958559999999997e+00 , -7.1349200000000002e-01 , -2.1313699999999999e-01 , -6.6746000000000005e-01 -5.7391901525036788e+00 , 2.3993283866239397e+00 , 6.9465728000000002e+00 , -2.4048000000000000e-01 , -2.2447400000000001e-01 , 9.4434200000000001e-01 -5.8509860369710607e+00 , 2.4186277423824425e+00 , 7.2190631999999999e+00 , -9.5122600000000002e-01 , -1.6157000000000001e-02 , 3.0807299999999999e-01 -6.0638175193056281e+00 , 2.4412088696934835e+00 , 7.6348032000000003e+00 , 7.5543300000000002e-01 , 2.7441199999999999e-01 , 5.9499500000000005e-01 -5.8969005107261303e+00 , 2.4607236149563261e+00 , 7.5800888000000004e+00 , -5.8618300000000001e-01 , -3.6338300000000001e-01 , -7.2411400000000004e-01 -5.8189617647416334e+00 , 2.4810728054533460e+00 , 7.6381104000000004e+00 , 4.9854599999999999e-01 , 4.3578200000000000e-01 , 7.4936400000000003e-01 -5.2817159097069180e+00 , 2.4878534524604814e+00 , 7.0511656000000000e+00 , 1.8842800000000001e-01 , -4.2541000000000001e-01 , -8.8516700000000004e-01 -5.1776703703915663e+00 , 2.5032416135027926e+00 , 7.0473800000000004e+00 , -1.8842800000000001e-01 , 4.2541000000000001e-01 , 8.8516700000000004e-01 -5.1441256935314037e+00 , 2.5222521806598666e+00 , 7.1451192000000008e+00 , 1.3263800000000001e-01 , -5.5123800000000001e-01 , 8.2373799999999997e-01 -5.3478918702823588e+00 , 2.5538523297456539e+00 , 7.6195047999999996e+00 , 2.4442100000000001e-02 , 1.2219099999999999e-01 , 9.9220600000000003e-01 -5.5204447898665308e+00 , 2.5883551419270514e+00 , 8.0752848000000004e+00 , 3.2970899999999997e-01 , 5.8430800000000005e-01 , 7.4153599999999997e-01 -5.5661134497958145e+00 , 2.6173725686503460e+00 , 8.3502608000000009e+00 , 4.4239299999999998e-01 , -5.0227500000000003e-01 , 7.4297299999999999e-01 -5.1003147996244138e+00 , 2.6104912299053291e+00 , 7.7423912000000001e+00 , 1.2464900000000000e-01 , 1.6775100000000001e-01 , 9.7791700000000004e-01 -4.8954616027895774e+00 , 2.6183322568797629e+00 , 7.5584047999999999e+00 , 6.3887300000000002e-01 , -3.5642200000000002e-01 , 6.8176599999999998e-01 -4.9147559078147278e+00 , 2.6457501601886291e+00 , 7.7829303999999997e+00 , -9.8238099999999995e-02 , -8.1505600000000000e-01 , 5.7099400000000000e-01 -4.7769211837615684e+00 , 2.6586359251943636e+00 , 7.7120648000000003e+00 , 1.0774700000000000e-01 , -8.9669699999999997e-01 , 4.2932999999999999e-01 -4.6569911406694686e+00 , 2.6715590417285155e+00 , 7.6662944000000000e+00 , -1.1049399999999999e-01 , -6.7647299999999999e-01 , 7.2813099999999997e-01 -4.7766251811059881e+00 , 2.7154806443288702e+00 , 8.1364471999999992e+00 , 4.2627599999999999e-01 , -7.0269400000000004e-01 , 5.6965800000000000e-01 -4.6813937628728315e+00 , 2.7340297085250973e+00 , 8.1554895999999992e+00 , -9.1926500000000000e-01 , 3.2255299999999998e-01 , -2.2563500000000000e-01 -4.6659520137032660e+00 , 2.7640350558056381e+00 , 8.3643736000000004e+00 , -9.4078099999999998e-01 , -2.9231099999999999e-01 , -1.7171500000000001e-01 -4.6431703956546428e+00 , 2.7965891617298784e+00 , 8.5737880000000004e+00 , 8.6326899999999995e-01 , 1.8122800000000000e-01 , 4.7108699999999998e-01 -4.5186013005759040e+00 , 2.8104635061370837e+00 , 8.5317615999999994e+00 , -3.0415399999999998e-01 , -6.3113799999999998e-02 , 9.5052999999999999e-01 -4.0909491555232709e+00 , 2.7581533400424454e+00 , 7.6380167999999999e+00 , -5.9001000000000003e-01 , -4.0383100000000000e-01 , 6.9914900000000002e-01 -3.9954536665018869e+00 , 2.7704146040972240e+00 , 7.6152407999999996e+00 , 9.0349300000000000e-03 , 3.4261399999999997e-01 , 9.3943299999999996e-01 -3.8911661610029382e+00 , 2.7798770541816502e+00 , 7.5609112000000005e+00 , 4.2111500000000002e-01 , 8.5997900000000005e-01 , 2.8826900000000000e-01 -3.7662748366138055e+00 , 2.7823062811498289e+00 , 7.4250976000000009e+00 , 2.3168900000000001e-01 , 9.4521200000000005e-01 , 2.2999000000000000e-01 -3.6817174987374579e+00 , 2.7946837364621135e+00 , 7.4157896000000001e+00 , 2.3168900000000001e-01 , 9.4521200000000005e-01 , 2.2999000000000000e-01 -3.9550418263291229e+00 , 2.9310870832093401e+00 , 8.7466775999999999e+00 , 7.6690999999999998e-01 , 6.1045600000000000e-01 , -1.9796900000000001e-01 -3.7428602234635351e+00 , 2.9048812134969966e+00 , 8.3078184000000004e+00 , -8.3212200000000003e-01 , 5.4164000000000001e-01 , -1.1915500000000000e-01 -3.8995052056067765e+00 , 3.0294293172020237e+00 , 9.4073999999999991e+00 , -6.9103499999999995e-01 , -6.2421300000000002e-01 , 3.6445699999999998e-01 -3.6784329221357295e+00 , 2.9967234956392348e+00 , 8.9027712000000001e+00 , -1.4914300000000000e-01 , -5.0682700000000003e-01 , 8.4904800000000002e-01 -3.5769980699756267e+00 , 3.0154083546233994e+00 , 8.9211583999999995e+00 , 3.1709100000000001e-01 , 1.9492100000000001e-01 , -9.2814799999999997e-01 -3.5436025552461468e+00 , 3.0748811871380282e+00 , 9.3251671999999992e+00 , 3.9027299999999998e-01 , -9.1549800000000003e-01 , -9.7730999999999998e-02 -3.3548240990870912e+00 , 3.0384963839421166e+00 , 8.8302312000000001e+00 , -5.1822000000000001e-01 , -4.8044500000000001e-01 , 7.0754600000000001e-01 -3.1124218300089037e+00 , 2.9408303898707695e+00 , 7.8194240000000006e+00 , -2.8207599999999999e-01 , 2.8781400000000001e-01 , 9.1520299999999999e-01 -2.9877101104806614e+00 , 2.9149430936047733e+00 , 7.4798536000000002e+00 , -4.4982099999999997e-02 , 3.9085799999999998e-01 , 9.1935100000000003e-01 -2.9097475926615899e+00 , 2.9271908725099851e+00 , 7.4765775999999997e+00 , 1.6646500000000000e-01 , 3.8045000000000001e-01 , 9.0969599999999995e-01 -2.8338300576451561e+00 , 2.9401184780514189e+00 , 7.4823807999999996e+00 , 2.9972300000000002e-01 , 3.9241700000000002e-01 , 8.6958299999999999e-01 -2.8331640471386637e+00 , 3.0887071631784435e+00 , 8.5781352000000002e+00 , -7.3590999999999995e-01 , -6.6418999999999995e-01 , 1.3148199999999999e-01 -2.7470994706044358e+00 , 3.1263655927272604e+00 , 8.7572232000000003e+00 , -8.3832700000000004e-01 , -5.2352699999999996e-01 , 1.5207699999999999e-01 -2.6395531306275553e+00 , 3.1092562250865434e+00 , 8.5017783999999992e+00 , -1.7984500000000000e-01 , 9.2332800000000004e-01 , 3.3929599999999999e-01 -2.5343492739689468e+00 , 3.0423453628226049e+00 , 7.8837168000000002e+00 , -5.3120400000000001e-01 , -6.8051099999999998e-01 , -5.0470499999999996e-01 -2.4505370798866477e+00 , 3.0583756691756783e+00 , 7.9032376000000006e+00 , 7.9104200000000002e-01 , 3.9831499999999997e-01 , 4.6432600000000002e-01 -2.3629724240097816e+00 , 3.1061144549617419e+00 , 8.1478456000000001e+00 , 4.4290099999999999e-01 , 1.5413900000000000e-01 , 8.8322199999999995e-01 -2.2748194633446039e+00 , 3.1176250916389914e+00 , 8.1334727999999998e+00 , 3.4516300000000000e-01 , -3.2321499999999997e-01 , -8.8113200000000003e-01 -2.1961776953128243e+00 , 3.1048352386730587e+00 , 7.9425496000000004e+00 , -7.3601099999999997e-01 , 2.7775600000000000e-01 , 6.1736400000000002e-01 -2.1165523820513039e+00 , 3.1082726503511586e+00 , 7.8740864000000004e+00 , -4.0846700000000002e-01 , -4.4453799999999999e-01 , 7.9720800000000003e-01 -1.8621666673154125e+00 , 3.4120754398977970e+00 , 9.8125631999999996e+00 , -8.3236500000000002e-01 , -5.4900800000000005e-01 , -7.5889399999999996e-02 -1.8015954172072433e+00 , 3.3472699958999930e+00 , 9.2671975999999994e+00 , -1.5329899999999999e-01 , 7.9519899999999999e-01 , 5.8665000000000000e-01 -4.7070522073222882e+00 , 1.7427112042740891e+00 , 1.3275152000000001e+00 , -1.8560199999999999e-01 , 2.1027699999999999e-01 , 9.5986199999999999e-01 -4.7628394239069092e+00 , 1.7353180830535144e+00 , 1.3501570400000000e+00 , -1.7374999999999999e-01 , 1.9462599999999999e-01 , 9.6536599999999995e-01 -4.8344795024539540e+00 , 1.7230079463651196e+00 , 1.3623208800000000e+00 , -1.1873100000000000e-01 , 2.0873400000000000e-01 , 9.7073900000000002e-01 -4.9059007104681900e+00 , 1.7110970041259204e+00 , 1.3764076799999998e+00 , -8.9557700000000004e-02 , 1.7325800000000000e-01 , 9.8079600000000000e-01 -4.9871265604858266e+00 , 1.6969894373071526e+00 , 1.3869720000000001e+00 , 8.0561800000000003e-02 , -1.8992400000000001e-01 , -9.7848800000000002e-01 -5.0681142561696699e+00 , 1.6833238466231426e+00 , 1.3996620800000001e+00 , -7.8961400000000001e-02 , 1.8977200000000000e-01 , 9.7864799999999996e-01 -5.1588340042072538e+00 , 1.6676103341785105e+00 , 1.4095400000000000e+00 , -7.3494699999999996e-02 , 1.9360800000000000e-01 , 9.7832200000000002e-01 -5.2402369153767037e+00 , 1.6538856562665016e+00 , 1.4273167199999999e+00 , -6.0459300000000001e-02 , 1.7435500000000001e-01 , 9.8282499999999995e-01 -5.3493001199832184e+00 , 1.6342651054169717e+00 , 1.4322525599999998e+00 , -7.3429200000000000e-02 , 1.8486000000000000e-01 , 9.8001799999999994e-01 -5.4400944497973525e+00 , 1.6191259387610473e+00 , 1.4502518400000000e+00 , -7.4158199999999994e-02 , 1.7416400000000001e-01 , 9.8192000000000002e-01 -5.5504174236837418e+00 , 1.5986826249498551e+00 , 1.4619206400000000e+00 , -6.5006700000000001e-02 , 1.8340500000000001e-01 , 9.8088600000000004e-01 -5.6604138060129774e+00 , 1.5799027861624595e+00 , 1.4765201600000000e+00 , -7.0541499999999993e-02 , 1.8775000000000000e-01 , 9.7968100000000002e-01 -5.7809131032567338e+00 , 1.5584131386920814e+00 , 1.4904592800000001e+00 , -5.0095800000000003e-02 , 1.9129199999999999e-01 , 9.8025399999999996e-01 -5.9108905271932182e+00 , 1.5353429997043042e+00 , 1.5038128799999999e+00 , -6.5442200000000006e-02 , 1.9634699999999999e-01 , 9.7834800000000000e-01 -6.0315612992108054e+00 , 1.5153631137256660e+00 , 1.5252639200000000e+00 , -7.2256600000000004e-02 , 1.8399199999999999e-01 , 9.8026800000000003e-01 -6.1725143524783093e+00 , 1.4905491349780262e+00 , 1.5428367999999999e+00 , 2.0702100000000001e-01 , -2.0134600000000000e-01 , -9.5739399999999997e-01 -6.3129572131433314e+00 , 1.4666292183246359e+00 , 1.5647610400000000e+00 , 7.4170700000000001e-01 , -2.0620600000000000e-01 , -6.3824000000000003e-01 -6.3314928811577511e+00 , 1.4730288537188754e+00 , 1.6373540799999999e+00 , -9.6163500000000002e-01 , 1.4848900000000001e-01 , 2.3067299999999999e-01 -6.2618393134983021e+00 , 1.4999335282805664e+00 , 1.7402152800000001e+00 , 9.8807599999999995e-01 , 9.0239799999999995e-02 , 1.2475300000000000e-01 -6.2470552466964300e+00 , 1.5136073537583836e+00 , 1.8207404000000000e+00 , 9.9717900000000004e-01 , 7.4898400000000004e-02 , -4.8463800000000000e-03 -6.2605473163727439e+00 , 1.5198653576453673e+00 , 1.8915924799999999e+00 , 9.9563699999999999e-01 , 9.0892899999999999e-02 , 2.1127600000000000e-02 -6.2427755476797477e+00 , 1.5334110645461783e+00 , 1.9708301840000000e+00 , 9.9189099999999997e-01 , 1.1054600000000001e-01 , -6.2703900000000007e-02 -6.2435181722585247e+00 , 1.5427299587260153e+00 , 2.0436092800000001e+00 , 9.9403200000000003e-01 , 9.9792300000000000e-02 , 4.4072399999999998e-02 -6.2820633993272184e+00 , 1.5440704334414932e+00 , 2.1059229600000000e+00 , 9.8803700000000005e-01 , 1.1990300000000000e-01 , 9.6989000000000006e-02 -6.2012237467287363e+00 , 1.5712967881809123e+00 , 2.1974564800000000e+00 , 9.6308000000000005e-01 , 1.9197400000000001e-01 , 1.8874199999999999e-01 -6.1969935638342690e+00 , 1.5814858841270378e+00 , 2.2681879199999999e+00 , -9.8467700000000002e-01 , -1.3207199999999999e-01 , 1.1387899999999999e-01 -6.2120885048310885e+00 , 1.5878459641125824e+00 , 2.3346096000000003e+00 , -9.4329600000000002e-01 , -9.5019599999999996e-02 , 3.1806299999999998e-01 -6.2164744783222030e+00 , 1.5961525002218906e+00 , 2.4031112800000001e+00 , -8.8575400000000004e-01 , 9.2952599999999996e-03 , 4.6406100000000000e-01 -6.2794475342062182e+00 , 1.5914724251809624e+00 , 2.4618504799999998e+00 , -8.3467400000000003e-01 , 3.0667000000000000e-02 , 5.4988999999999999e-01 -6.3209914900660316e+00 , 1.5918396552420484e+00 , 2.5252520000000001e+00 , -6.2295100000000003e-01 , 9.2106800000000003e-02 , 7.7681900000000004e-01 -6.5542312026401888e+00 , 1.5528479956425203e+00 , 2.5659326400000002e+00 , -1.8133099999999999e-01 , 1.5296399999999999e-01 , 9.7145300000000001e-01 -1.1497863821141094e+01 , 5.6838853360168717e-01 , 2.2709532800000001e+00 , -1.0843600000000000e-01 , 2.0964200000000000e-01 , 9.7174700000000003e-01 -1.2113605559206194e+01 , 4.6564143127949076e-01 , 2.3877452799999999e+00 , -9.2152399999999995e-02 , 2.0514600000000000e-01 , 9.7438300000000000e-01 -1.2923313516239366e+01 , 3.2809173303988803e-01 , 2.5155592000000002e+00 , -5.7129100000000002e-02 , 1.8919400000000000e-01 , 9.8027699999999995e-01 -1.4170078584112936e+01 , 1.0741160457015297e-01 , 2.6559425600000002e+00 , -5.9058199999999998e-02 , 1.9401499999999999e-01 , 9.7921899999999995e-01 -1.5497423399066671e+01 , -1.2214718150171677e-01 , 2.8381308000000001e+00 , -4.8348299999999997e-02 , 1.8740999999999999e-01 , 9.8109100000000005e-01 -1.7660993441131779e+01 , -5.0579314608800230e-01 , 3.0662599999999998e+00 , -1.1188099999999999e-01 , 1.8589300000000000e-01 , 9.7618000000000005e-01 -1.8880748481563330e+01 , -7.0085671289655149e-01 , 3.3544648000000001e+00 , -1.4201100000000000e-01 , 2.0348900000000000e-01 , 9.6872300000000000e-01 -2.9236840488173648e+01 , -2.4727842233926323e+00 , 4.9437096000000000e+00 , 4.4411499999999998e-01 , -1.0553100000000000e-01 , -8.8973300000000000e-01 -3.0364548112732084e+01 , -2.6131810943884490e+00 , 5.5151687999999996e+00 , -5.0747399999999998e-01 , -2.3114600000000000e-03 , 8.6166399999999999e-01 -3.1481204173736320e+01 , -2.7461723529202278e+00 , 6.1264600000000007e+00 , 6.8912300000000004e-01 , 1.0746500000000000e-01 , -7.1663100000000002e-01 -3.2584779082381729e+01 , -2.8716918984271889e+00 , 6.7771151999999999e+00 , -6.2139599999999995e-01 , -7.2443199999999996e-01 , 2.9843700000000001e-01 -3.2265290546005275e+01 , -2.7451296534880605e+00 , 7.2687647999999996e+00 , -7.0145999999999997e-01 , 5.0353000000000002e-02 , 7.1092699999999998e-01 -3.3316098797369506e+01 , -2.8542861437983245e+00 , 7.9682896000000003e+00 , 4.1928799999999999e-01 , 9.0398699999999999e-01 , 8.3699300000000004e-02 -2.9116768977126970e+01 , -2.0751885068739480e+00 , 7.7821608000000007e+00 , 5.4097899999999999e-01 , 4.2920599999999998e-01 , 7.2327300000000005e-01 -2.7854406503965226e+01 , -1.8034240183604915e+00 , 8.0185111999999990e+00 , 3.2767800000000002e-01 , 7.6191100000000000e-01 , 5.5867599999999995e-01 -3.5681565545616209e+01 , -3.0199629536998627e+00 , 1.0143553600000001e+01 , -3.5969000000000001e-01 , -9.2998400000000003e-01 , -7.5851500000000002e-02 -2.8050181596118719e+01 , -1.7128243503868537e+00 , 8.9895695999999994e+00 , 8.1682200000000005e-01 , -1.4856700000000000e-01 , 5.5743200000000004e-01 -2.3716233191362907e+01 , -9.6429421242139490e-01 , 8.3806183999999995e+00 , 8.4177699999999994e-02 , 2.3127900000000001e-01 , 9.6923899999999996e-01 -2.2477682582613216e+01 , -7.1891131207435333e-01 , 8.4435903999999997e+00 , -5.7798400000000005e-01 , 1.9717199999999999e-01 , -7.9186999999999996e-01 -2.2686998653438199e+01 , -7.0191666692265597e-01 , 8.8783624000000003e+00 , 7.3116800000000004e-01 , -4.6120800000000003e-02 , 6.8063600000000002e-01 -2.6835842149450301e+01 , -1.2775004607465217e+00 , 1.0527417600000000e+01 , 7.0970999999999995e-01 , -1.3398599999999999e-01 , 6.9163600000000003e-01 -2.2550967167165680e+01 , -5.7998585287693993e-01 , 9.6020047999999996e+00 , -8.9932900000000005e-01 , 2.7644500000000000e-01 , -3.3879999999999999e-01 -2.5161049021790806e+01 , -9.1013238775215299e-01 , 1.0886748000000001e+01 , -2.2649600000000000e-01 , 1.6939499999999999e-01 , 9.5916900000000005e-01 -2.6001592414068984e+01 , -9.7192595170092044e-01 , 1.1634227200000002e+01 , 4.6236600000000003e-02 , 4.3931100000000001e-01 , 8.9714499999999997e-01 -2.1835148772837822e+01 , -3.2417543724137987e-01 , 1.0502894400000001e+01 , -9.6686600000000000e-01 , -1.4227799999999999e-01 , 2.1196200000000001e-01 -2.2438900915292905e+01 , -3.5693991122547919e-01 , 1.1133196800000000e+01 , -9.0232400000000001e-01 , -7.7159800000000001e-02 , 4.2409700000000000e-01 -2.2742195842220063e+01 , -3.4446300359223425e-01 , 1.1665593599999999e+01 , 9.8697199999999996e-01 , -4.0989999999999999e-02 , -1.5558500000000000e-01 -2.2590074674794597e+01 , -2.6984216545600548e-01 , 1.2014097600000001e+01 , -7.8002899999999997e-01 , 4.6586699999999998e-01 , -4.1776000000000002e-01 -2.2029368829525545e+01 , -1.4162378949188348e-01 , 1.2172406400000000e+01 , 7.7937199999999995e-01 , -2.4537200000000001e-01 , 5.7651699999999995e-01 -2.2295828084144613e+01 , -1.2122713251848394e-01 , 1.2715328000000001e+01 , 6.9341399999999997e-01 , -6.7422199999999999e-01 , 2.5416800000000001e-01 -2.3130505059751407e+01 , -1.6873827602540548e-01 , 1.3564072000000001e+01 , -8.7204800000000005e-01 , 2.8985199999999999e-02 , 4.8856200000000000e-01 -2.2397307479338615e+01 , -2.0358838702741355e-02 , 1.3627616000000002e+01 , -7.6179200000000002e-01 , 5.0069500000000000e-01 , 4.1106799999999999e-01 -2.3071039366355681e+01 , -4.2375849953706357e-02 , 1.4442144000000001e+01 , -8.9877899999999999e-01 , 2.7068100000000001e-02 , 4.3756600000000001e-01 -2.5843320435346335e+01 , -3.0160066283061715e-01 , 1.6498120000000000e+01 , -2.8134399999999998e-01 , 3.7172400000000000e-01 , 8.8468500000000005e-01 -2.6132504477128435e+01 , -2.6296165512067793e-01 , 1.7210104000000001e+01 , -4.0547600000000000e-01 , 7.2759400000000002e-02 , 9.1120599999999996e-01 -2.6853723935722105e+01 , -2.6901737923065916e-01 , 1.8214120000000001e+01 , -3.9939599999999999e-02 , -2.3322499999999999e-01 , 9.7160199999999997e-01 -2.3952214287189587e+01 , 1.1731619074438604e-01 , 1.6930032000000001e+01 , -8.9824800000000005e-01 , -3.4553200000000001e-01 , -2.7158599999999999e-01 -2.3322447299124928e+01 , 2.5171829862415174e-01 , 1.7035904000000002e+01 , -9.2291999999999996e-01 , -3.4605000000000002e-01 , 1.6872799999999999e-01 -2.3563039632623390e+01 , 2.9659434978736954e-01 , 1.7726360000000000e+01 , -8.8587700000000003e-01 , -4.5137500000000003e-01 , -1.0715800000000000e-01 -7.3763546943391329e+00 , 1.9641175287946047e+00 , 6.8855560000000002e+00 , 9.9875700000000001e-01 , 9.9478499999999994e-03 , 4.8844100000000001e-02 -7.2309570304832063e+00 , 1.9945247930523247e+00 , 6.9053263999999999e+00 , -6.9774000000000003e-01 , 5.2450399999999997e-01 , -4.8790800000000001e-01 -7.2219740928242251e+00 , 2.0133453979007685e+00 , 7.0336832000000005e+00 , 6.5349299999999999e-01 , -6.7524700000000004e-01 , 3.4203499999999998e-01 -7.3131158225308601e+00 , 2.0244987896146243e+00 , 7.2507936000000006e+00 , 7.9875399999999996e-01 , -5.9915099999999999e-01 , 5.4863099999999998e-02 -7.3039846019063317e+00 , 2.0442602904627027e+00 , 7.3890928000000002e+00 , -5.8154600000000001e-01 , 7.1514400000000000e-01 , -3.8778000000000001e-01 -7.2003545387367662e+00 , 2.0714711405241282e+00 , 7.4440568000000003e+00 , -2.8955199999999998e-01 , 8.5987199999999997e-01 , 4.2045100000000002e-01 -6.5687112936934495e+00 , 2.1335181285358686e+00 , 6.9953487999999995e+00 , -4.5847199999999999e-01 , -8.6138999999999999e-01 , -2.1865899999999999e-01 -6.5917057215092392e+00 , 2.1494880309282687e+00 , 7.1532936000000005e+00 , 4.7337000000000001e-01 , 8.1457199999999996e-01 , 3.3525100000000002e-01 -6.5292025745663009e+00 , 2.1721087611169199e+00 , 7.2311584000000000e+00 , 5.3036300000000003e-01 , 7.7310800000000002e-01 , 3.4787800000000002e-01 -6.1085158020815014e+00 , 2.2126436812277714e+00 , 6.9314928000000000e+00 , -3.7643900000000002e-01 , -9.2260100000000000e-01 , -8.4272299999999994e-02 -5.9372950807163507e+00 , 2.2390982246785307e+00 , 6.8786920000000000e+00 , -5.0721600000000000e-01 , -5.8121800000000001e-01 , -6.3633099999999998e-01 -6.1968988122929511e+00 , 2.2445256310858999e+00 , 7.3035944000000006e+00 , 6.3812000000000002e-01 , 4.6877400000000002e-01 , 6.1078100000000002e-01 -6.1182603315982638e+00 , 2.2675938452019704e+00 , 7.3591512000000003e+00 , -7.9666400000000004e-01 , -2.9228700000000002e-01 , -5.2905100000000005e-01 -6.0980251885284602e+00 , 2.2875334473775943e+00 , 7.4854176000000008e+00 , -8.5008600000000001e-01 , -4.2308299999999999e-01 , -3.1361499999999998e-01 -6.0482110696848599e+00 , 2.3096946584996356e+00 , 7.5795167999999995e+00 , -6.9979499999999994e-01 , -1.6929400000000000e-01 , -6.9399299999999997e-01 -5.9783773029952432e+00 , 2.3319393639082175e+00 , 7.6486872000000004e+00 , -7.9151600000000000e-01 , -3.2203800000000001e-03 , -6.1114000000000002e-01 -5.9372014992649911e+00 , 2.3546737690310207e+00 , 7.7580119999999999e+00 , -8.9190800000000003e-01 , -1.7891799999999999e-01 , -4.1531699999999999e-01 -5.9180898792605188e+00 , 2.3769231016134387e+00 , 7.9012512000000008e+00 , -8.8569299999999995e-01 , -2.4135899999999999e-01 , -3.9660299999999998e-01 -5.2662657543044764e+00 , 2.4011112311088074e+00 , 7.1390976000000004e+00 , -9.5948699999999998e-01 , 2.6033499999999998e-01 , 1.0775300000000000e-01 -5.1854214070563032e+00 , 2.4201944118400980e+00 , 7.1691431999999997e+00 , -9.5948699999999998e-01 , 2.6033600000000001e-01 , 1.0775300000000000e-01 -5.6848613745234289e+00 , 2.4477919289073338e+00 , 8.0978320000000004e+00 , 8.5945199999999999e-01 , 2.4285499999999999e-01 , 4.4984800000000003e-01 -5.5604937974641988e+00 , 2.4706706773515763e+00 , 8.0899904000000014e+00 , 6.1597100000000005e-01 , 3.7402999999999997e-01 , 6.9331200000000004e-01 -5.0638279015820578e+00 , 2.4818412233980296e+00 , 7.4544360000000003e+00 , -1.4463600000000000e-02 , -5.2535799999999999e-01 , 8.5075800000000001e-01 -4.9575222255638476e+00 , 2.5002126553933999e+00 , 7.4438800000000001e+00 , 4.3461800000000000e-01 , -4.0569000000000000e-01 , 8.0406599999999995e-01 -4.9136979672298189e+00 , 2.5215118205686560e+00 , 7.5402567999999999e+00 , -4.6765400000000001e-01 , 1.7589700000000000e-01 , -8.6623300000000003e-01 -5.1728670618019237e+00 , 2.5602829402461573e+00 , 8.2148944000000004e+00 , 2.0871400000000001e-01 , -3.3898600000000002e-03 , 9.7797100000000003e-01 -4.7786278218160092e+00 , 2.5626381240173752e+00 , 7.6575895999999997e+00 , -1.0492600000000001e-01 , -7.2810600000000003e-01 , 6.7738600000000004e-01 -4.6680305837204763e+00 , 2.5799848208889551e+00 , 7.6304872000000001e+00 , -2.7887800000000001e-02 , -6.0516300000000001e-01 , 7.9561300000000001e-01 -4.5772983860947107e+00 , 2.5993194328883384e+00 , 7.6385680000000002e+00 , -4.5090300000000000e-01 , 6.1031899999999994e-01 , -6.5130500000000002e-01 -4.5409856004399805e+00 , 2.6227722101734274e+00 , 7.7683080000000002e+00 , -2.9530400000000001e-01 , 5.8175200000000005e-01 , -7.5786600000000004e-01 -4.7537590753229315e+00 , 2.6774149100437734e+00 , 8.4907439999999994e+00 , -8.4864399999999995e-01 , -2.8397299999999998e-01 , -4.4627600000000001e-01 -4.6605371786904604e+00 , 2.6996089004035833e+00 , 8.5283087999999996e+00 , -5.1644500000000004e-01 , -2.6575300000000002e-01 , -8.1403899999999996e-01 -4.5746513301588436e+00 , 2.7239319785356479e+00 , 8.5832832000000003e+00 , 2.1979399999999999e-01 , -9.3369300000000002e-02 , 9.7106800000000004e-01 -4.1155014219097890e+00 , 2.6850889388206256e+00 , 7.6231863999999998e+00 , 4.2154000000000003e-01 , 6.6905099999999995e-01 , 6.1210699999999996e-01 -4.0371517452547332e+00 , 2.7033821472375692e+00 , 7.6498312000000004e+00 , 3.9405000000000001e-01 , 6.0655000000000003e-01 , 6.9052300000000000e-01 -3.9429059443855898e+00 , 2.7185347604853281e+00 , 7.6258592000000007e+00 , 9.0349400000000000e-03 , 3.4261399999999997e-01 , 9.3943299999999996e-01 -3.8608554983461199e+00 , 2.7354538281984890e+00 , 7.6396288000000006e+00 , -6.7643699999999995e-01 , -7.3580400000000001e-01 , -3.2027399999999998e-02 -3.8029362421838355e+00 , 2.7585994599861348e+00 , 7.7316064000000004e+00 , 9.7170000000000001e-01 , -1.0503700000000001e-01 , 2.1157899999999999e-01 -4.0959408203696448e+00 , 2.8862286499780887e+00 , 9.1232927999999998e+00 , 9.1730900000000004e-01 , -4.4124300000000002e-03 , 3.9815099999999998e-01 -3.7855327810365607e+00 , 2.8416266214669279e+00 , 8.3349936000000007e+00 , -8.3468200000000004e-01 , 5.2016100000000003e-02 , 5.4827000000000004e-01 -3.6806836697373528e+00 , 2.8571575022946947e+00 , 8.2948392000000002e+00 , 7.4189000000000005e-01 , -1.5169600000000000e-01 , -6.5313600000000005e-01 -3.6306725605717309e+00 , 2.8923829524735898e+00 , 8.4959024000000003e+00 , 5.0547500000000002e-02 , -9.4563299999999995e-01 , 3.2128200000000001e-01 -3.4662016117026200e+00 , 2.8802002971142424e+00 , 8.1579024000000011e+00 , -7.3511800000000005e-01 , -3.9213199999999998e-01 , 5.5302300000000004e-01 -3.4343680042609743e+00 , 2.9280942255207871e+00 , 8.4784199999999998e+00 , -8.4057000000000004e-01 , -5.2677300000000005e-01 , -1.2630500000000000e-01 -3.3664110552187259e+00 , 2.9626477948155339e+00 , 8.6459744000000001e+00 , -8.8946199999999997e-01 , -3.3962100000000001e-01 , 3.0580299999999999e-01 -3.1444260205751551e+00 , 2.8939271386867347e+00 , 7.7989984000000003e+00 , 7.8405300000000000e-01 , -4.2685400000000001e-01 , 4.5061899999999999e-01 -3.0232789214013831e+00 , 2.8783043091088278e+00 , 7.5005912000000006e+00 , -2.4854500000000002e-02 , 3.2167299999999999e-01 , 9.4652499999999995e-01 -2.9452898042280293e+00 , 2.8927772384001376e+00 , 7.4978248000000001e+00 , 2.0157300000000000e-01 , 5.6905200000000000e-01 , 7.9721299999999995e-01 -2.8685077261349345e+00 , 2.9069388027693277e+00 , 7.4937584000000008e+00 , -2.8743600000000002e-01 , -3.7597599999999998e-01 , -8.8092199999999998e-01 -2.8003401182345078e+00 , 2.9337266022414314e+00 , 7.6016272000000003e+00 , 7.5109599999999999e-01 , 5.5430999999999997e-01 , 3.5860100000000000e-01 -2.7894520652914805e+00 , 3.0858014930477689e+00 , 8.7388463999999999e+00 , -8.3832700000000004e-01 , -5.2352699999999996e-01 , 1.5207699999999999e-01 -2.6682015257525515e+00 , 3.0366730311275636e+00 , 8.1950719999999997e+00 , -8.4364600000000001e-01 , -1.4452200000000001e-01 , 5.1708299999999996e-01 -2.5766961450025754e+00 , 3.0360871599523525e+00 , 8.0514168000000002e+00 , 4.3322300000000002e-01 , 6.9045499999999996e-02 , 8.9863800000000005e-01 -2.4894816226089218e+00 , 3.0329488723409810e+00 , 7.9065552000000006e+00 , 6.7393400000000003e-01 , 5.3118100000000001e-01 , 5.1347799999999999e-01 -2.4043960218568614e+00 , 3.0714838264881577e+00 , 8.0691176000000002e+00 , -8.8799499999999998e-01 , 1.6538600000000001e-01 , -4.2908299999999999e-01 -2.3154834220650016e+00 , 3.0996300299439099e+00 , 8.1582352000000000e+00 , 1.8693699999999999e-01 , 4.2442200000000002e-01 , 8.8595699999999999e-01 -2.2305077103922222e+00 , 3.1067792710123774e+00 , 8.0912591999999997e+00 , -5.3670300000000004e-01 , 3.0036400000000002e-01 , 7.8849999999999998e-01 -2.1593547218123432e+00 , 3.0874395271074446e+00 , 7.8377800000000004e+00 , 1.1379100000000000e-01 , -7.0055199999999995e-01 , 7.0447099999999996e-01 -2.0767663231630125e+00 , 3.1021283027828801e+00 , 7.8298240000000003e+00 , 2.8509800000000002e-01 , -3.0098399999999997e-01 , 9.1001500000000002e-01 -1.6021687933353650e+00 , 3.7271772945579920e+00 , 1.1884981600000000e+01 , 2.8867700000000002e-01 , -9.4472999999999996e-01 , -1.5540699999999999e-01 -1.7482599726984567e+00 , 3.3524499326987405e+00 , 9.2499023999999999e+00 , -9.2874299999999999e-01 , 2.5946200000000003e-01 , -2.6479300000000000e-01 -4.7189451220029000e+00 , 1.6807960201721477e+00 , 1.3495101599999999e+00 , -1.6293400000000000e-01 , 2.4229899999999999e-01 , 9.5642199999999999e-01 -4.7896309513031152e+00 , 1.6672779858918498e+00 , 1.3607411200000001e+00 , -1.5235099999999999e-01 , 2.2206799999999999e-01 , 9.6305499999999999e-01 -4.8530761570636844e+00 , 1.6557144210426578e+00 , 1.3801225600000000e+00 , -9.7844299999999995e-02 , 1.8695400000000001e-01 , 9.7748400000000002e-01 -4.9332913682306021e+00 , 1.6383214621730358e+00 , 1.3899640799999999e+00 , -8.0935800000000002e-02 , 1.8095600000000001e-01 , 9.8015500000000000e-01 -5.0132814341351075e+00 , 1.6224056177914661e+00 , 1.4018252800000000e+00 , -9.5670699999999997e-02 , 1.6530600000000001e-01 , 9.8159099999999999e-01 -5.0940562666395035e+00 , 1.6069109581177141e+00 , 1.4159380800000001e+00 , -6.6646999999999998e-02 , 1.6029099999999999e-01 , 9.8481700000000005e-01 -5.1924493696912162e+00 , 1.5859042341590059e+00 , 1.4222539999999999e+00 , -7.6640000000000000e-02 , 1.8659800000000001e-01 , 9.7944200000000003e-01 -5.2835922763591858e+00 , 1.5668468556626409e+00 , 1.4367214399999999e+00 , -6.3719999999999999e-02 , 1.9225400000000001e-01 , 9.7927399999999998e-01 -5.3744720900110821e+00 , 1.5493490972177288e+00 , 1.4536131200000000e+00 , -6.7279099999999994e-02 , 1.7806500000000000e-01 , 9.8171600000000003e-01 -5.4828369786450146e+00 , 1.5265775625097771e+00 , 1.4638217600000001e+00 , -7.9883300000000004e-02 , 1.6611100000000001e-01 , 9.8286600000000002e-01 -5.5840004234464153e+00 , 1.5067712283695600e+00 , 1.4819760000000000e+00 , -8.6223700000000000e-02 , 1.9620099999999999e-01 , 9.7676499999999999e-01 -5.6936476632757032e+00 , 1.4842171930220036e+00 , 1.4988125600000000e+00 , -6.9965100000000002e-02 , 1.8292400000000000e-01 , 9.8063400000000001e-01 -5.8128099444708603e+00 , 1.4600052569398523e+00 , 1.5147599199999999e+00 , -5.2297400000000001e-02 , 1.8034300000000000e-01 , 9.8221199999999997e-01 -5.9424361597463555e+00 , 1.4331711140843235e+00 , 1.5304514400000000e+00 , -6.6978099999999999e-02 , 1.8938900000000000e-01 , 9.7961500000000001e-01 -6.0726232437991232e+00 , 1.4071298024937446e+00 , 1.5502145600000001e+00 , -7.9871999999999999e-02 , 1.8223600000000001e-01 , 9.8000600000000004e-01 -6.2121683520403748e+00 , 1.3786347314838747e+00 , 1.5703042400000000e+00 , 2.6135999999999998e-01 , -2.3048399999999999e-01 , -9.3731900000000001e-01 -6.3708018153917063e+00 , 1.3455941230941726e+00 , 1.5877065600000000e+00 , 9.8964500000000000e-01 , -8.9995300000000000e-02 , -1.1181700000000000e-01 -6.3030497290215504e+00 , 1.3738498956783876e+00 , 1.6924345599999999e+00 , 9.8629400000000000e-01 , -1.3266100000000000e-01 , -9.8105100000000001e-02 -6.2901700438775991e+00 , 1.3877611970938806e+00 , 1.7745259200000001e+00 , 9.8968999999999996e-01 , 6.5863500000000005e-02 , 1.2718299999999999e-01 -6.2948123483888256e+00 , 1.3963213130291381e+00 , 1.8496315999999999e+00 , 9.9563800000000002e-01 , 9.2628500000000003e-02 , -1.1161400000000000e-02 -6.2876418416635325e+00 , 1.4069861397498364e+00 , 1.9273995760000000e+00 , 9.9441199999999996e-01 , 1.0493600000000000e-01 , 1.1583599999999999e-02 -6.2892648938860258e+00 , 1.4165683976404930e+00 , 2.0016195296000001e+00 , 9.9434199999999995e-01 , 1.0129400000000000e-01 , -3.1996100000000000e-02 -6.2704848662595625e+00 , 1.4311618801676103e+00 , 2.0806277679999998e+00 , 9.9795999999999996e-01 , 4.5592700000000000e-02 , 4.4686900000000002e-02 -6.3088411280073950e+00 , 1.4306600906383307e+00 , 2.1442625600000000e+00 , 9.9105699999999997e-01 , 6.4246700000000004e-02 , 1.1695500000000000e-01 -6.2367184427545830e+00 , 1.4580192874438607e+00 , 2.2330546400000002e+00 , 9.7558199999999995e-01 , 1.3750799999999999e-01 , 1.7126400000000000e-01 -6.2430362159791457e+00 , 1.4654334243432579e+00 , 2.3028219999999999e+00 , 9.9168400000000001e-01 , 6.0977999999999997e-02 , -1.1333500000000001e-01 -6.2472734369370331e+00 , 1.4729033309982325e+00 , 2.3724395999999999e+00 , 9.6215399999999995e-01 , 1.7257800000000000e-02 , -2.7195900000000001e-01 -6.2611580606184889e+00 , 1.4795804782891340e+00 , 2.4401519199999999e+00 , -8.9632900000000004e-01 , 4.4877000000000000e-02 , 4.4111299999999998e-01 -6.3132454425293867e+00 , 1.4749964685958430e+00 , 2.5022919200000002e+00 , 7.5677700000000003e-01 , -3.7735900000000003e-02 , -6.5258300000000002e-01 -6.4150005827566892e+00 , 1.4598093632270737e+00 , 2.5593276000000000e+00 , 4.7107199999999999e-01 , -7.3247400000000004e-02 , -8.7904800000000005e-01 -6.7374648268603528e+00 , 1.3935825926320007e+00 , 2.5945575999999999e+00 , -1.8116199999999999e-01 , 1.4536800000000000e-01 , 9.7265000000000001e-01 -1.1645052555856456e+01 , 2.7708861681197972e-01 , 2.3691012000000002e+00 , -1.0410300000000000e-01 , 2.0522099999999999e-01 , 9.7316300000000000e-01 -1.2419935193308495e+01 , 1.2110392308900364e-01 , 2.4875332800000001e+00 , 8.1130099999999997e-02 , -1.9794300000000001e-01 , -9.7685000000000000e-01 -1.3456919696179927e+01 , -9.1717315269224109e-02 , 2.6221956000000000e+00 , -4.8204600000000000e-02 , 1.9665199999999999e-01 , 9.7928800000000005e-01 -1.4726045774765856e+01 , -3.5182818634319712e-01 , 2.7877927200000001e+00 , -6.1932800000000003e-02 , 1.9258300000000000e-01 , 9.7932399999999997e-01 -1.6420147750972422e+01 , -7.0033052466472556e-01 , 2.9953403199999999e+00 , -4.0881599999999997e-02 , 1.8555300000000000e-01 , 9.8178399999999999e-01 -1.8406185785640613e+01 , -1.1059567971110122e+00 , 3.2663144000000002e+00 , 1.4504200000000000e-01 , -1.8407899999999999e-01 , -9.7215099999999999e-01 -1.9790179574470194e+01 , -1.3710307074171224e+00 , 3.5898272000000002e+00 , -1.2402900000000000e-01 , 1.4462500000000000e-01 , 9.8168200000000005e-01 -3.0607938544231640e+01 , -3.5353708785180595e+00 , 5.4066863999999999e+00 , -3.5782900000000001e-01 , 3.2366400000000001e-01 , 8.7590000000000001e-01 -3.1448465750133369e+01 , -3.6457685034700136e+00 , 5.9919776000000002e+00 , -3.2525599999999999e-01 , 8.4020200000000000e-01 , 4.3390099999999998e-01 -3.4351634814375352e+01 , -4.1790112000766699e+00 , 6.8526192000000004e+00 , 3.6879200000000001e-01 , -7.1888799999999997e-01 , -5.8923099999999995e-01 -3.1348799282066402e+01 , -3.4927918252767123e+00 , 7.0145472000000000e+00 , -2.0815800000000001e-01 , 9.5676000000000005e-01 , 2.0317800000000000e-01 -3.1763683905364612e+01 , -3.5109856397943533e+00 , 7.5977584000000000e+00 , -1.8912100000000001e-01 , 9.5740999999999998e-01 , 2.1817300000000001e-01 -3.2118318501573945e+01 , -3.5135905465956228e+00 , 8.1875423999999999e+00 , -2.8530800000000001e-01 , 6.3871900000000004e-01 , 7.1458900000000003e-01 -3.3815195342328650e+01 , -3.7794608655076054e+00 , 9.0482776000000005e+00 , -4.4075300000000001e-01 , 6.2720900000000002e-01 , 6.4214199999999999e-01 -3.3703054234587704e+01 , -3.6842989619398701e+00 , 9.5966383999999998e+00 , -2.4225600000000000e-01 , 8.9009099999999997e-01 , 3.8607000000000002e-01 -2.7600609804592413e+01 , -2.4364675630031210e+00 , 8.7855424000000006e+00 , -7.7070700000000003e-01 , 3.1073200000000001e-01 , -5.5628800000000000e-01 -2.7838995080670259e+01 , -2.4220589058883304e+00 , 9.3085063999999988e+00 , -7.7070700000000003e-01 , 3.1073200000000001e-01 , -5.5628800000000000e-01 -2.2812344379897755e+01 , -1.4181578532637418e+00 , 8.4542920000000006e+00 , 5.7102699999999995e-01 , -4.1339099999999997e-02 , 8.1989000000000001e-01 -2.3534807491241516e+01 , -1.5031128339025210e+00 , 9.0405192000000003e+00 , -4.3027200000000002e-02 , 1.8722300000000000e-01 , 9.8137500000000000e-01 -2.7097769546497137e+01 , -2.1037290840054004e+00 , 1.0514188799999999e+01 , 6.6600599999999999e-01 , -1.9734499999999999e-01 , 7.1936800000000001e-01 -2.1853667061557953e+01 , -1.0965802932869124e+00 , 9.3030360000000005e+00 , -8.6373699999999998e-01 , 4.1142000000000001e-01 , -2.9101800000000000e-01 -2.2063721459030781e+01 , -1.0858453424025947e+00 , 9.7488944000000011e+00 , -9.4432099999999997e-01 , 2.9061199999999998e-01 , -1.5428200000000000e-01 -2.4428027788818934e+01 , -1.4520498960330297e+00 , 1.0981429600000000e+01 , -1.3005000000000000e-01 , 9.5541399999999999e-01 , -2.6508799999999999e-01 -2.2167955787232955e+01 , -1.0058963205694158e+00 , 1.0557962399999999e+01 , -9.2935100000000004e-01 , -1.4231400000000000e-01 , 3.4066600000000002e-01 -2.2561676756971330e+01 , -1.0222892052829029e+00 , 1.1108704800000000e+01 , 9.7165500000000005e-01 , 1.6428700000000001e-02 , -2.3583299999999999e-01 -2.2894315777063095e+01 , -1.0263179402396059e+00 , 1.1655131200000001e+01 , 9.9514499999999995e-01 , -8.0660399999999993e-02 , 5.6388300000000002e-02 -2.2443366788458949e+01 , -8.9774232194960302e-01 , 1.1875600800000001e+01 , -8.7450000000000006e-01 , 1.3673600000000000e-01 , -4.6535300000000002e-01 -2.2494429867912935e+01 , -8.5282958967337974e-01 , 1.2315011199999999e+01 , -8.0457199999999995e-01 , 1.5493999999999999e-01 , -5.7328699999999999e-01 -2.2017493601739822e+01 , -7.2326105418959630e-01 , 1.2508472000000001e+01 , -8.5307599999999995e-01 , 1.7430699999999999e-01 , -4.9181100000000000e-01 -2.1715542893901038e+01 , -6.2144464987921744e-01 , 1.2775440000000001e+01 , -8.5307599999999995e-01 , 1.7430699999999999e-01 , -4.9181100000000000e-01 -2.1856168968452820e+01 , -5.8962753782931587e-01 , 1.3269024000000000e+01 , 8.7631899999999996e-01 , -4.7005999999999998e-01 , 1.0539800000000001e-01 -2.3776728681543045e+01 , -8.2509611952172435e-01 , 1.4749984000000001e+01 , -9.3813000000000002e-01 , 2.0677499999999999e-01 , 2.7777000000000002e-01 -2.3779837026853535e+01 , -7.6400156305332123e-01 , 1.5233168000000001e+01 , -9.3813000000000002e-01 , 2.0677499999999999e-01 , 2.7777000000000002e-01 -2.3693179893284285e+01 , -6.8881250250246318e-01 , 1.5672256000000001e+01 , -7.9031399999999996e-01 , 6.1262000000000005e-01 , 1.0068100000000000e-02 -2.3387243660353874e+01 , -5.8146892430445662e-01 , 1.5981552000000001e+01 , -9.1969699999999999e-01 , 3.8932800000000001e-01 , -5.0815199999999998e-02 -2.4538400399395563e+01 , -6.7788162028935162e-01 , 1.7219048000000001e+01 , 2.5396099999999999e-01 , 9.2567400000000000e-01 , -2.8041300000000002e-01 -2.3795169740081342e+01 , -5.0827552816670085e-01 , 1.7264600000000002e+01 , -9.6970000000000001e-01 , -9.4641900000000008e-03 , 2.4411800000000000e-01 -2.3838800971013566e+01 , -4.4554572098718515e-01 , 1.7827656000000001e+01 , -9.3341700000000005e-01 , -3.3986499999999997e-01 , 1.1500100000000001e-01 -7.3846731204752043e+00 , 1.7969744106126746e+00 , 6.8693216000000001e+00 , 6.7786999999999997e-01 , 8.2658400000000007e-02 , 7.3051999999999995e-01 -7.2478762880158065e+00 , 1.8306001515424357e+00 , 6.8963824000000002e+00 , 6.7786999999999997e-01 , 8.2658300000000004e-02 , 7.3051999999999995e-01 -7.1837945653568127e+00 , 1.8553022764699783e+00 , 6.9789792000000004e+00 , -7.8637999999999997e-01 , 2.8859200000000002e-01 , -5.4618800000000001e-01 -7.1500306610671052e+00 , 1.8764936406071804e+00 , 7.0874616000000001e+00 , 8.9083599999999996e-01 , -3.7457000000000001e-01 , 2.5711400000000001e-01 -7.1765840666029774e+00 , 1.8922861874178611e+00 , 7.2505648000000003e+00 , -5.3675899999999999e-01 , 7.9590600000000000e-01 , -2.8004200000000001e-01 -7.0988927240055935e+00 , 1.9190577492186940e+00 , 7.3247064000000002e+00 , -3.5215999999999997e-01 , 7.2245400000000004e-01 , -5.9501499999999996e-01 -6.9667684361218205e+00 , 1.9505724206121309e+00 , 7.3475239999999999e+00 , 2.4992400000000001e-01 , -1.3032500000000000e-01 , 9.5945499999999995e-01 -6.8650206367315381e+00 , 1.9795432613970534e+00 , 7.3958216000000006e+00 , -4.4212200000000000e-02 , -3.4427500000000000e-01 , 9.3782699999999997e-01 -6.6535515163548453e+00 , 2.0180847770705541e+00 , 7.3311856000000004e+00 , -4.2760900000000002e-01 , -8.8139100000000004e-01 , -2.0074800000000001e-01 -6.5322751767929761e+00 , 2.0473861647795637e+00 , 7.3506023999999996e+00 , -6.4651200000000006e-02 , 9.7058999999999995e-01 , 2.3189699999999999e-01 -6.6646879545648581e+00 , 2.0556987816291250e+00 , 7.6414800000000005e+00 , 4.0421000000000001e-01 , 8.9668499999999995e-01 , 1.8047500000000000e-01 -6.5107770998588004e+00 , 2.0872189193339494e+00 , 7.6280431999999996e+00 , -5.1514200000000003e-02 , -8.3628599999999997e-01 , 5.4586800000000002e-01 -6.2852056873547824e+00 , 2.1248160777968907e+00 , 7.5240952000000005e+00 , -6.9365099999999999e-02 , 3.0217600000000001e-03 , 9.9758700000000000e-01 -6.2096286561201808e+00 , 2.1496901856711146e+00 , 7.5892616000000004e+00 , -6.3082600000000000e-01 , -3.3445799999999998e-01 , -7.0013999999999998e-01 -6.0750133062745553e+00 , 2.1781032538860958e+00 , 7.5803592000000002e+00 , 7.6531899999999997e-01 , 2.6403399999999999e-01 , 5.8700300000000005e-01 -5.9861907093583557e+00 , 2.2037219972233943e+00 , 7.6253184000000003e+00 , -8.5502599999999995e-01 , -7.0854500000000001e-02 , -5.1372099999999998e-01 -5.9281130482537625e+00 , 2.2275443685419170e+00 , 7.7100783999999996e+00 , -9.1855299999999995e-01 , -1.9735400000000000e-01 , -3.4250900000000001e-01 -5.8743598476681509e+00 , 2.2516533506720999e+00 , 7.8024512000000001e+00 , -9.4450100000000003e-01 , 4.0836200000000003e-02 , -3.2596100000000000e-01 -5.9014041940053072e+00 , 2.2718292883437505e+00 , 8.0137792000000001e+00 , 5.2887600000000000e-02 , 7.7992399999999995e-01 , 6.2363599999999997e-01 -5.1890892999080105e+00 , 2.3176623344754508e+00 , 7.1406159999999996e+00 , 4.0934999999999999e-01 , 5.4755600000000004e-01 , 7.2980500000000004e-01 -5.2505964409238466e+00 , 2.3360230284850045e+00 , 7.3871584000000006e+00 , -8.6557799999999996e-01 , 2.7726899999999999e-01 , -4.1700900000000002e-01 -5.3659445532831898e+00 , 2.3552306749005867e+00 , 7.7337384000000000e+00 , 3.3295500000000000e-01 , -6.7139199999999999e-01 , 6.6209700000000005e-01 -5.2225683948410460e+00 , 2.3794346168435747e+00 , 7.6757064000000002e+00 , -1.4898400000000001e-01 , 9.8874899999999999e-01 , -1.3375800000000000e-02 -5.0183786955306537e+00 , 2.4028478926368408e+00 , 7.5059056000000002e+00 , 9.6410099999999999e-01 , -2.1191299999999999e-01 , 1.6000400000000001e-01 -4.9132934584490027e+00 , 2.4241502681535483e+00 , 7.4943615999999995e+00 , 5.5873899999999999e-01 , -2.7836200000000000e-01 , 7.8123399999999998e-01 -5.2159264999707409e+00 , 2.4532411732820529e+00 , 8.2408944000000002e+00 , -1.3224600000000000e-01 , 9.3693899999999997e-01 , 3.2350699999999999e-01 -4.7721447832269392e+00 , 2.4681988339623255e+00 , 7.5932656000000005e+00 , 1.1083999999999999e-01 , -6.1576100000000000e-01 , 7.8009799999999996e-01 -4.6400379415645787e+00 , 2.4887389958540118e+00 , 7.5194672000000002e+00 , 9.1534699999999997e-02 , -4.2377900000000002e-01 , 9.0112899999999996e-01 -4.5996810917747837e+00 , 2.5118306308214171e+00 , 7.6307368000000002e+00 , -5.0892400000000004e-01 , 4.6826099999999998e-01 , -7.2230799999999995e-01 -4.6893396197470336e+00 , 2.5438590938483463e+00 , 8.0354631999999988e+00 , -8.6366399999999999e-01 , -1.1353100000000000e-02 , 5.0393900000000003e-01 -4.7781950590353643e+00 , 2.5793781831102116e+00 , 8.4731471999999997e+00 , 6.7511200000000005e-01 , 4.1644300000000001e-01 , 6.0893299999999995e-01 -4.6942130188118441e+00 , 2.6061401938378523e+00 , 8.5300976000000013e+00 , 4.0404000000000001e-01 , 3.2549400000000001e-01 , 8.5487199999999997e-01 -4.5971124027198087e+00 , 2.6305600099221063e+00 , 8.5567944000000011e+00 , 2.0838400000000001e-01 , 3.7848999999999999e-01 , 9.0184299999999995e-01 -4.4779578938457103e+00 , 2.6522732342498272e+00 , 8.5231816000000009e+00 , 3.7891999999999998e-01 , 1.4315800000000001e-01 , 9.1429000000000005e-01 -4.0707443751450185e+00 , 2.6326766500123839e+00 , 7.6644328000000002e+00 , -3.9405099999999998e-01 , -6.0655000000000003e-01 , -6.9052300000000000e-01 -3.9754577241211080e+00 , 2.6511317480805348e+00 , 7.6408351999999997e+00 , -3.5605399999999998e-01 , -7.8650699999999996e-01 , -5.0461199999999995e-01 -3.9414892985697021e+00 , 2.6790380110282861e+00 , 7.8037200000000002e+00 , -4.8577300000000001e-01 , -9.2356199999999999e-02 , -8.6919199999999996e-01 -4.1744250955257032e+00 , 2.7662915924000968e+00 , 8.8820544000000012e+00 , 4.1803699999999999e-01 , -7.1427799999999997e-01 , 5.6129499999999999e-01 -4.1307531416255232e+00 , 2.8043237455077366e+00 , 9.1089304000000002e+00 , -8.2031399999999999e-01 , 4.9994100000000002e-01 , -2.7774799999999999e-01 -3.8784294067168408e+00 , 2.7900470546436953e+00 , 8.5625976000000001e+00 , -8.7863300000000000e-01 , 1.3339400000000001e-01 , 4.5848699999999998e-01 -3.7261374456794307e+00 , 2.7957825201134101e+00 , 8.3424920000000000e+00 , 6.8603099999999995e-01 , -3.7560800000000000e-01 , 6.2312100000000004e-01 -3.6274159854707877e+00 , 2.8149017452649416e+00 , 8.3214527999999994e+00 , 6.3006400000000004e-02 , -6.3192499999999996e-01 , 7.7246499999999996e-01 -3.5018375774399439e+00 , 2.8230237870671795e+00 , 8.1663160000000001e+00 , 8.1195499999999998e-01 , 2.9569699999999999e-01 , -5.0328200000000001e-01 -3.4567001972022333e+00 , 2.8636261173312954e+00 , 8.4056408000000005e+00 , -3.0739899999999998e-01 , -9.5102900000000001e-01 , -3.2387699999999998e-02 -3.3681668738933448e+00 , 2.8862473804234359e+00 , 8.4305175999999999e+00 , 6.7961600000000000e-01 , 7.1940999999999999e-01 , 1.4342800000000000e-01 -3.1686481065261418e+00 , 2.8431691437521138e+00 , 7.7472376000000001e+00 , 7.5385500000000005e-01 , -4.6429900000000002e-01 , 4.6489700000000000e-01 -3.0558651472412812e+00 , 2.8386330079969264e+00 , 7.5109184000000004e+00 , 5.6998699999999999e-02 , 3.4241199999999999e-01 , 9.3781899999999996e-01 -2.9797767412282763e+00 , 2.8562406763801742e+00 , 7.5188432000000001e+00 , 1.8250700000000000e-01 , 5.8984800000000004e-01 , 7.8661999999999999e-01 -2.9010976124694614e+00 , 2.8716571699976061e+00 , 7.5047720000000000e+00 , 2.1408600000000000e-01 , 5.6420300000000001e-01 , 7.9739700000000002e-01 -2.8633223043695404e+00 , 2.9390890019908782e+00 , 7.9631727999999997e+00 , -5.7482699999999998e-01 , -6.6010199999999997e-01 , -4.8356900000000003e-01 -2.8207414924373966e+00 , 3.0261649012391785e+00 , 8.5760032000000006e+00 , -7.3590999999999995e-01 , -6.6418999999999995e-01 , 1.3148199999999999e-01 -2.7302499069999646e+00 , 3.0578812131524256e+00 , 8.6614184000000005e+00 , -7.9176000000000002e-01 , -5.6352199999999997e-01 , 2.3570900000000000e-01 -2.6106830385414530e+00 , 2.9890297787013624e+00 , 7.9199712000000009e+00 , 7.6367600000000002e-01 , 6.4376299999999997e-01 , 4.8665899999999998e-02 -2.5551136232678764e+00 , 3.2299630242519273e+00 , 9.7047984000000014e+00 , 5.7337999999999998e-03 , -7.2406800000000004e-01 , 6.8970500000000001e-01 -2.4442368459911630e+00 , 3.0306790372676109e+00 , 7.9594183999999997e+00 , 8.0824799999999997e-01 , 4.2410900000000001e-01 , 4.0849400000000002e-01 -2.3349171017406043e+00 , 3.2302455605928628e+00 , 9.3271952000000002e+00 , 1.6490299999999999e-01 , -8.8955700000000004e-01 , 4.2602400000000001e-01 -2.2593291644790328e+00 , 3.1334584574953617e+00 , 8.4353952000000003e+00 , -4.5828999999999998e-01 , -2.2638500000000000e-01 , -8.5948800000000003e-01 -2.1907775556114015e+00 , 3.0895073390381476e+00 , 7.9759648000000007e+00 , 6.8770100000000001e-01 , -5.6144899999999998e-01 , -4.6026400000000001e-01 -2.1167407343347930e+00 , 3.0876395825217999e+00 , 7.8349616000000006e+00 , -1.4946100000000001e-01 , -7.8132500000000005e-01 , 6.0596399999999995e-01 -2.0291000477771677e+00 , 3.1136676953336515e+00 , 7.8874607999999995e+00 , 3.7406200000000001e-01 , -8.2978799999999997e-01 , 4.1416100000000000e-01 -1.7979171521407422e+00 , 3.3442641200484386e+00 , 9.2883408000000003e+00 , 2.8934100000000001e-02 , 9.6128199999999997e-01 , 2.7404299999999998e-01 -4.7357074897247777e+00 , 1.6153272519549058e+00 , 1.3654356800000000e+00 , -1.4634500000000000e-01 , 2.4200300000000000e-01 , 9.5917600000000003e-01 -4.7981652583984200e+00 , 1.6015154995691943e+00 , 1.3839882399999999e+00 , -8.7510599999999994e-02 , 2.4470300000000000e-01 , 9.6564099999999997e-01 -4.8864226873421241e+00 , 1.5792606485751890e+00 , 1.3872309600000001e+00 , 8.2875000000000004e-02 , -1.8106300000000000e-01 , -9.7997299999999998e-01 -4.9574478521069647e+00 , 1.5636498335627436e+00 , 1.4039593600000000e+00 , -6.1882399999999997e-02 , 1.5609000000000001e-01 , 9.8580199999999996e-01 -5.0461939734104906e+00 , 1.5423344781141515e+00 , 1.4119808800000000e+00 , -1.2401100000000000e-01 , 1.7155599999999999e-01 , 9.7733800000000004e-01 -5.1266983056917521e+00 , 1.5240387229226271e+00 , 1.4279230400000000e+00 , 9.8563499999999998e-02 , -2.0791499999999999e-01 , -9.7316800000000003e-01 -5.2158544770782846e+00 , 1.5026897619770603e+00 , 1.4411320800000000e+00 , -7.0479500000000000e-02 , 1.9753299999999999e-01 , 9.7775900000000004e-01 -5.3057414893677208e+00 , 1.4818709646804187e+00 , 1.4570971200000000e+00 , -4.9293299999999998e-02 , 2.0311599999999999e-01 , 9.7791300000000003e-01 -5.4141723791654970e+00 , 1.4556852868228067e+00 , 1.4662023199999998e+00 , -5.9479400000000002e-02 , 1.8176100000000001e-01 , 9.8154200000000003e-01 -5.5133798048754805e+00 , 1.4335405390934208e+00 , 1.4828964000000000e+00 , -6.8049700000000005e-02 , 1.9359499999999999e-01 , 9.7871900000000001e-01 -5.6220547668399181e+00 , 1.4076165675931276e+00 , 1.4986045600000000e+00 , -7.9871100000000000e-02 , 1.9789899999999999e-01 , 9.7696300000000003e-01 -5.7324332840338315e+00 , 1.3822926004095897e+00 , 1.5177010399999999e+00 , 5.8483800000000002e-02 , -1.8312700000000001e-01 , -9.8134800000000000e-01 -5.8600920555720473e+00 , 1.3520247411038224e+00 , 1.5317327199999999e+00 , -5.6359100000000002e-02 , 1.8531900000000001e-01 , 9.8106099999999996e-01 -5.9893322136744525e+00 , 1.3214938109053291e+00 , 1.5500668799999999e+00 , -6.2138400000000003e-02 , 1.7717900000000000e-01 , 9.8221499999999995e-01 -6.1279100105805222e+00 , 1.2885049889654645e+00 , 1.5687275999999999e+00 , -2.8365600000000002e-01 , 2.1620300000000001e-01 , 9.3423599999999996e-01 -6.2571811555676948e+00 , 1.2586064200347387e+00 , 1.5954857599999999e+00 , 2.9789700000000002e-01 , -1.2198400000000000e-01 , -9.4677199999999995e-01 -6.4066198435760713e+00 , 1.2240733417483303e+00 , 1.6193787200000000e+00 , 9.9990999999999997e-01 , 7.8764799999999999e-03 , -1.0869100000000000e-02 -6.3281071135508560e+00 , 1.2576713943821902e+00 , 1.7271892799999999e+00 , 9.9961800000000001e-01 , -2.7250500000000000e-02 , 4.6589700000000001e-03 -6.3336040960454474e+00 , 1.2654178903909772e+00 , 1.8037384800000000e+00 , 9.9397899999999995e-01 , 1.0692400000000001e-01 , 2.3924600000000001e-02 -6.3283522959925644e+00 , 1.2763018738255723e+00 , 1.8829719199999999e+00 , 9.9674600000000002e-01 , 7.8789700000000004e-02 , -1.6996700000000000e-02 -6.3211317815330919e+00 , 1.2881556656872741e+00 , 1.9613442400000001e+00 , 9.9747100000000000e-01 , 7.1063200000000007e-02 , 1.2137700000000001e-03 -6.3226102135444409e+00 , 1.2968809087387783e+00 , 2.0365787759999998e+00 , 9.9554299999999996e-01 , 9.1456099999999999e-02 , 2.3002100000000001e-02 -6.2930588137118519e+00 , 1.3146709686851206e+00 , 2.1185745599999999e+00 , 9.9724599999999997e-01 , 3.8297900000000003e-02 , 6.3511999999999999e-02 -6.3408867440362195e+00 , 1.3103695700001141e+00 , 2.1812241600000002e+00 , 9.9048599999999998e-01 , 7.6258500000000007e-02 , 1.1454900000000000e-01 -6.2688156962169037e+00 , 1.3398297044571374e+00 , 2.2699091199999999e+00 , 9.8486300000000004e-01 , 8.2556599999999994e-02 , 1.5241499999999999e-01 -6.2846186288249033e+00 , 1.3445293423694680e+00 , 2.3387893599999998e+00 , 9.8601200000000000e-01 , 8.5802799999999992e-03 , -1.6645099999999999e-01 -6.2685214946376577e+00 , 1.3580324996268573e+00 , 2.4128883200000000e+00 , 9.6956399999999998e-01 , -1.9441500000000000e-02 , -2.4406700000000001e-01 -6.3215844912437555e+00 , 1.3524047085165480e+00 , 2.4753590399999998e+00 , -8.3700200000000002e-01 , 3.3092900000000001e-02 , 5.4619799999999996e-01 -6.3628276439226248e+00 , 1.3500156356613466e+00 , 2.5407937600000001e+00 , 6.2169600000000003e-01 , -6.8244399999999997e-02 , -7.8027999999999997e-01 -6.5128893070597620e+00 , 1.3182723332062452e+00 , 2.5944380000000002e+00 , -2.3941699999999999e-01 , 1.9334599999999999e-01 , 9.5147099999999996e-01 -1.1323986624282380e+01 , 7.1901379216484651e-02 , 2.3414579999999998e+00 , -1.1373800000000001e-01 , 2.1388399999999999e-01 , 9.7021500000000005e-01 -1.1921836265018433e+01 , -6.4291013195168389e-02 , 2.4624047999999998e+00 , -1.0309300000000000e-01 , 2.1038799999999999e-01 , 9.7216700000000000e-01 -1.2731132045442731e+01 , -2.5189393022640472e-01 , 2.5946304000000002e+00 , -6.6389900000000002e-02 , 1.9683700000000001e-01 , 9.7818600000000000e-01 -1.3901242155516876e+01 , -5.2891409764508523e-01 , 2.7447772800000001e+00 , -4.7669299999999998e-02 , 1.9324600000000000e-01 , 9.7999199999999997e-01 -1.5231400883487961e+01 , -8.4197757986136867e-01 , 2.9346022400000003e+00 , -5.2731699999999999e-02 , 1.8765599999999999e-01 , 9.8081799999999997e-01 -1.7276120552819314e+01 , -1.3282197621834322e+00 , 3.1763336000000000e+00 , -6.0066300000000003e-02 , 1.8127199999999999e-01 , 9.8159700000000005e-01 -1.8823378027961024e+01 , -1.6820506147871139e+00 , 3.4789528000000001e+00 , -1.2509700000000001e-01 , 1.7678400000000000e-01 , 9.7626800000000002e-01 -2.9588383193308001e+01 , -4.1881534483366565e+00 , 5.1955559999999998e+00 , 9.1284399999999999e-01 , -3.2100800000000002e-01 , -2.5233000000000000e-01 -2.9643738904445442e+01 , -4.1413836848086252e+00 , 5.6869455999999996e+00 , -8.7543199999999999e-01 , 4.6889399999999998e-01 , -1.1729299999999999e-01 -2.9870526587099739e+01 , -4.1346741843581825e+00 , 6.2008304000000001e+00 , -8.7543199999999999e-01 , 4.6889399999999998e-01 , -1.1729299999999999e-01 -2.9827059697746837e+01 , -4.0631561224578316e+00 , 6.6887256000000006e+00 , -9.3938200000000005e-01 , 3.2311400000000001e-01 , 1.1471099999999999e-01 -2.9886127482500441e+01 , -4.0163766910343757e+00 , 7.1921792000000000e+00 , -9.0402800000000005e-01 , 4.1815000000000002e-01 , -8.8789400000000004e-02 -3.0026599302130677e+01 , -3.9864160301309273e+00 , 7.7132088000000003e+00 , 3.2383899999999999e-01 , -9.4601000000000002e-01 , 1.3934900000000000e-02 -3.6613742255600506e+01 , -5.3581358173151372e+00 , 1.0068247200000000e+01 , -3.9063300000000001e-01 , 8.2767900000000005e-02 , 9.1681800000000002e-01 -2.4405628314173700e+01 , -2.4832660516375569e+00 , 8.3827712000000005e+00 , 2.5335000000000002e-01 , 8.7609999999999993e-02 , 9.6339900000000001e-01 -2.2748817393748347e+01 , -2.0669309858260982e+00 , 8.3616592000000001e+00 , -4.5752100000000001e-01 , -1.8361000000000000e-01 , -8.7003600000000003e-01 -3.4263581942803668e+01 , -4.5303805997232232e+00 , 1.1957188800000001e+01 , -5.0716099999999997e-01 , -5.5952100000000005e-01 , 6.5553399999999995e-01 -2.4002364562782283e+01 , -2.2423364395929646e+00 , 9.5030591999999992e+00 , 8.0058700000000005e-01 , 2.7843600000000002e-01 , 5.3059800000000001e-01 -3.2828033746164223e+01 , -4.0737987607269011e+00 , 1.2715640000000000e+01 , -6.9936399999999999e-01 , 7.1472599999999997e-01 , -7.5538000000000003e-03 -2.1782484694335864e+01 , -1.6714679243919988e+00 , 9.5860200000000013e+00 , -8.7739400000000001e-01 , 3.1540400000000002e-01 , 3.6152299999999998e-01 -2.3015163229162418e+01 , -1.8816011796798162e+00 , 1.0402981599999999e+01 , -9.1584600000000005e-01 , -1.1055200000000000e-01 , -3.8601000000000002e-01 -2.2630494374840378e+01 , -1.7517719425534910e+00 , 1.0664884799999999e+01 , -9.6218599999999999e-01 , -1.6910700000000001e-02 , 2.7186800000000000e-01 -2.2708118483846089e+01 , -1.7174878127306590e+00 , 1.1099375999999999e+01 , 9.7547399999999995e-01 , -7.9521900000000006e-02 , -2.0524899999999999e-01 -2.6610261699809040e+01 , -2.4502035637359736e+00 , 1.3133304000000001e+01 , -8.6804199999999998e-01 , 1.8654000000000001e-01 , -4.6011500000000000e-01 -2.3034197376264959e+01 , -1.6797317294401162e+00 , 1.2067844800000000e+01 , 9.8430899999999999e-01 , -1.7780999999999999e-03 , 1.7644499999999999e-01 -2.2199594272828019e+01 , -1.4624530620767691e+00 , 1.2114332800000000e+01 , -9.1285499999999997e-01 , -1.8234500000000001e-01 , -3.6530200000000002e-01 -2.2311510676271293e+01 , -1.4329644970848623e+00 , 1.2585016000000000e+01 , -8.6968400000000001e-01 , -4.3213800000000002e-01 , -2.3854900000000001e-01 -2.2936127111230512e+01 , -1.4990325299379785e+00 , 1.3323208000000001e+01 , 9.7926800000000003e-01 , 1.9209499999999999e-01 , 6.4296300000000001e-02 -2.7780875508180088e+01 , -2.3536384281948814e+00 , 1.6297400000000003e+01 , 9.4039399999999995e-01 , 2.0507800000000001e-01 , -2.7129900000000001e-01 -2.9097604365585578e+01 , -2.5276861540508442e+00 , 1.7574936000000001e+01 , -9.5630300000000001e-01 , -1.9591600000000001e-01 , 2.1702800000000000e-01 -2.2845113879672997e+01 , -1.3128385852419764e+00 , 1.4633712000000001e+01 , -8.9141000000000004e-01 , 2.5233800000000001e-01 , 3.7645000000000001e-01 -2.3099141530026394e+01 , -1.3002146435844582e+00 , 1.5251367999999999e+01 , -9.1556000000000004e-01 , 3.5098800000000002e-01 , 1.9636000000000001e-01 -2.3442264549111037e+01 , -1.3004733805149948e+00 , 1.5945152000000000e+01 , -9.3330700000000000e-01 , 3.3907599999999999e-01 , 1.1817700000000000e-01 -2.5843920870442883e+01 , -1.6551486175860641e+00 , 1.7975336000000002e+01 , -3.7387900000000002e-01 , -6.9444600000000001e-01 , 6.1478400000000000e-01 -3.0494193556656917e+01 , -2.3780022006311796e+00 , 2.1620016000000003e+01 , -8.8576699999999997e-01 , 3.0748900000000001e-01 , 3.4766100000000000e-01 -7.2844000321110158e+00 , 1.6589556367656808e+00 , 6.9059920000000004e+00 , 5.4026399999999997e-01 , 4.1861300000000001e-01 , 7.2998499999999999e-01 -7.3647592964996127e+00 , 1.6642517272524096e+00 , 7.1075440000000008e+00 , 6.9047899999999995e-01 , 5.6818599999999997e-01 , 4.4766400000000001e-01 -7.1239160009967852e+00 , 1.7173010045479344e+00 , 7.0454248000000002e+00 , -9.2484500000000003e-01 , -7.9108100000000001e-02 , -3.7202700000000000e-01 -7.1826621610391506e+00 , 1.7254635727685725e+00 , 7.2354952000000008e+00 , -9.1808599999999996e-01 , -1.1732400000000000e-01 , -3.7862099999999999e-01 -7.0448071889632251e+00 , 1.7628435281503778e+00 , 7.2546000000000008e+00 , 9.1442199999999996e-01 , 4.3363899999999997e-02 , 4.0243200000000001e-01 -6.9974143731909688e+00 , 1.7872464631619074e+00 , 7.3550431999999999e+00 , 5.7083099999999998e-01 , 1.1550299999999999e-01 , 8.1290300000000004e-01 -7.1266113294856019e+00 , 1.7889658084450872e+00 , 7.6283032000000004e+00 , 8.8834000000000002e-01 , -3.9674399999999999e-01 , 2.3118300000000000e-01 -7.0289184162525205e+00 , 1.8208618194012198e+00 , 7.6867407999999999e+00 , -9.3033600000000005e-01 , 1.4987100000000000e-01 , -3.3468300000000001e-01 -6.9165711348744869e+00 , 1.8542228598970607e+00 , 7.7281744000000003e+00 , 1.6504700000000000e-01 , 7.7220399999999995e-02 , 9.8325799999999997e-01 -6.7896434528105774e+00 , 1.8888410818751300e+00 , 7.7517096000000008e+00 , 1.6054599999999999e-01 , 2.6311699999999999e-01 , 9.5131200000000005e-01 -6.4272883628535693e+00 , 1.9501576068202253e+00 , 7.5096807999999999e+00 , -1.0415600000000000e-01 , 9.3958699999999995e-01 , -3.2607999999999998e-01 -6.3195935820767355e+00 , 1.9818205475576784e+00 , 7.5384472000000002e+00 , 6.9870199999999993e-02 , 1.7990000000000000e-01 , -9.8119999999999996e-01 -6.1910153158586310e+00 , 2.0143734400008979e+00 , 7.5408288000000008e+00 , 3.3166299999999999e-01 , -1.7544699999999999e-01 , 9.2693999999999999e-01 -6.0902429875199191e+00 , 2.0431387806458012e+00 , 7.5725072000000004e+00 , -7.6958100000000000e-03 , -3.1363700000000000e-01 , 9.4951200000000002e-01 -6.1047658084456273e+00 , 2.0621103480218888e+00 , 7.7488184000000002e+00 , 4.6599600000000002e-01 , -3.5066900000000001e-01 , 8.1233000000000000e-01 -6.0137972856903934e+00 , 2.0900965941412268e+00 , 7.7945368000000004e+00 , -8.4506599999999998e-01 , 1.4480500000000000e-02 , -5.3446600000000000e-01 -6.1059129561462155e+00 , 2.1031983148768529e+00 , 8.0900320000000008e+00 , -8.6316400000000004e-01 , -5.0472399999999995e-01 , 1.4212900000000001e-02 -6.0402702809001525e+00 , 2.1310465593271277e+00 , 8.1773503999999999e+00 , -3.4653600000000001e-01 , 5.1068700000000000e-01 , 7.8683700000000001e-01 -5.9307766970822220e+00 , 2.1622652782063412e+00 , 8.2035376000000007e+00 , 4.9915399999999999e-02 , 7.0206900000000005e-01 , 7.1035700000000002e-01 -5.2072199127348364e+00 , 2.2309433245588024e+00 , 7.2885144000000004e+00 , -2.7994400000000003e-01 , 8.8910699999999998e-01 , 3.6210500000000001e-01 -5.1860385629599168e+00 , 2.2518339822730757e+00 , 7.4140423999999996e+00 , -1.7114399999999999e-01 , 5.2162299999999995e-01 , -8.3583499999999999e-01 -5.0431039684948651e+00 , 2.2800367191024935e+00 , 7.3443312000000001e+00 , 1.0001500000000000e-02 , -6.5492700000000004e-01 , 7.5562600000000002e-01 -4.9400386545347494e+00 , 2.3046709670130183e+00 , 7.3339416000000002e+00 , -2.9072700000000001e-01 , 4.1609600000000002e-01 , -8.6159300000000005e-01 -4.9854204412381389e+00 , 2.3244245323649659e+00 , 7.5839680000000005e+00 , -9.9186600000000003e-01 , 1.2705300000000000e-01 , -7.6762100000000002e-03 -4.9497675697209917e+00 , 2.3471345689869594e+00 , 7.6996055999999999e+00 , -9.4517499999999999e-01 , -2.8707400000000000e-01 , -1.5567000000000000e-01 -5.1544243735241420e+00 , 2.3682687150975750e+00 , 8.2856248000000008e+00 , 6.7999699999999996e-02 , 8.6504599999999998e-01 , 4.9706200000000000e-01 -4.9411723607315921e+00 , 2.3963413439881611e+00 , 8.0790496000000012e+00 , -4.8966100000000001e-01 , 2.1171899999999999e-01 , 8.4581700000000004e-01 -4.6066120737448921e+00 , 2.4214169584712928e+00 , 7.5945344000000006e+00 , 1.8200200000000000e-01 , 7.9058399999999995e-01 , 5.8468200000000004e-01 -4.5293813427590717e+00 , 2.4446075445723885e+00 , 7.6299256000000000e+00 , -8.3353600000000005e-01 , -1.9516400000000000e-01 , -5.1684500000000000e-01 -4.4993020610620249e+00 , 2.4696607254374427e+00 , 7.7689319999999995e+00 , -9.2610899999999996e-01 , 2.4485199999999999e-01 , -2.8700199999999998e-01 -4.8437976368118427e+00 , 2.5136181896241814e+00 , 8.8195504000000007e+00 , -8.3018400000000006e-02 , -8.9574100000000001e-01 , 4.3675599999999998e-01 -4.6813937455662780e+00 , 2.5388753639502908e+00 , 8.6941680000000012e+00 , 6.4077599999999998e-02 , 6.1773599999999995e-01 , 7.8377100000000000e-01 -4.5428594502429345e+00 , 2.5636402972769714e+00 , 8.6135991999999995e+00 , 1.8348100000000001e-01 , 6.5588100000000005e-01 , 7.3222600000000004e-01 -4.5187457972135414e+00 , 2.5981065401357268e+00 , 8.8427840000000000e+00 , 5.3520400000000001e-01 , 8.1427700000000003e-01 , -2.2474400000000000e-01 -4.3918153998269149e+00 , 2.6232107682054586e+00 , 8.7874559999999988e+00 , 2.2873800000000000e-01 , 6.2913900000000000e-01 , -7.4287499999999995e-01 -4.3013200047203899e+00 , 2.6521609447094345e+00 , 8.8380520000000011e+00 , 1.8265200000000001e-01 , -3.9267000000000002e-01 , 9.0135900000000002e-01 -4.1760461641550988e+00 , 2.6761601407442335e+00 , 8.7775968000000013e+00 , -2.6414599999999999e-01 , 3.4554900000000000e-01 , -9.0045699999999995e-01 -4.2964446927886701e+00 , 2.7444214370938158e+00 , 9.5637328000000004e+00 , -9.6758800000000000e-01 , -2.5097000000000003e-01 , 2.8076400000000001e-02 -4.0631592177896092e+00 , 2.7489842809850735e+00 , 9.1307808000000001e+00 , -8.2031399999999999e-01 , 4.9994100000000002e-01 , -2.7774799999999999e-01 -4.0052757944695214e+00 , 2.7887569453184806e+00 , 9.3369192000000005e+00 , -9.6910399999999997e-01 , -1.0097600000000000e-01 , -2.2503500000000001e-01 -3.9597937387482700e+00 , 2.8367132285846655e+00 , 9.6232208000000004e+00 , -8.6146599999999995e-01 , -3.5731400000000002e-01 , 3.6083700000000002e-01 -3.5208786278920816e+00 , 2.7585634241924524e+00 , 8.1034167999999998e+00 , -4.8655999999999999e-01 , 7.4714800000000003e-01 , 4.5280199999999998e-01 -3.5664282129455835e+00 , 2.8324549201560081e+00 , 8.7908360000000005e+00 , -5.3397200000000000e-01 , -3.5570299999999999e-01 , 7.6703900000000003e-01 -3.4438099130078559e+00 , 2.8472276965525203e+00 , 8.6640703999999999e+00 , -6.9279500000000005e-01 , -6.7746899999999999e-01 , 2.4712500000000001e-01 -3.1804805279620725e+00 , 2.7849026728380442e+00 , 7.6239352000000000e+00 , -7.5790299999999999e-01 , -5.0059799999999999e-01 , 4.1831200000000002e-01 -3.0882417494684185e+00 , 2.7967502185720163e+00 , 7.5312920000000005e+00 , 2.5886900000000002e-01 , 6.6372299999999995e-01 , 7.0175399999999999e-01 -3.0112728362467092e+00 , 2.8156130161984185e+00 , 7.5294408000000006e+00 , -4.5856599999999997e-01 , -5.6578799999999996e-01 , -6.8527499999999997e-01 -2.9381436555269320e+00 , 2.8380959322604538e+00 , 7.5569072000000004e+00 , -4.9388199999999999e-01 , -7.3399000000000003e-01 , -4.6619699999999997e-01 -2.8683890128180267e+00 , 2.8652793628717248e+00 , 7.6347928000000005e+00 , -6.8746499999999999e-01 , -6.2439199999999995e-01 , -3.7084600000000001e-01 -2.8455138678681160e+00 , 2.9626413711458381e+00 , 8.3714040000000018e+00 , -8.7041199999999996e-01 , -2.9847200000000002e-01 , 3.9153100000000002e-01 -2.7737210267285288e+00 , 3.0213109407393404e+00 , 8.6947191999999998e+00 , -8.5474000000000006e-01 , -5.0317599999999996e-01 , 1.2740799999999999e-01 -2.6471423686472413e+00 , 2.9591952246539708e+00 , 7.9430488000000006e+00 , 7.8256099999999995e-01 , 5.4569599999999996e-01 , 2.9968899999999998e-01 -2.6005567640351521e+00 , 3.1649185435239398e+00 , 9.5023103999999989e+00 , 4.1955999999999999e-01 , -7.9193400000000003e-01 , 4.4363300000000000e-01 -2.4819483193225724e+00 , 3.0052208822870474e+00 , 7.9728656000000004e+00 , -3.4391699999999997e-01 , -9.0537699999999999e-01 , -2.4902800000000000e-01 -2.3979221095458585e+00 , 3.0324729993761181e+00 , 8.0216832000000000e+00 , -8.4066799999999997e-01 , -4.1157500000000002e-01 , -3.5197200000000001e-01 -2.2806939062649270e+00 , 3.2075494637545057e+00 , 9.1924008000000015e+00 , 1.0105500000000001e-01 , 8.8614000000000004e-01 , -4.5226499999999997e-01 -2.1523670764061662e+00 , 3.3036325225160117e+00 , 9.7104248000000002e+00 , 6.9887800000000000e-01 , 6.8081199999999997e-01 , -2.1923599999999999e-01 -2.1572414365297417e+00 , 3.0668587977683193e+00 , 7.8089719999999998e+00 , -1.3490800000000000e-01 , -3.8094600000000001e-01 , 9.1470200000000002e-01 -2.0742488663455205e+00 , 3.0898179743480387e+00 , 7.8314256000000002e+00 , 1.5447000000000000e-01 , -5.4352999999999996e-01 , 8.2505399999999995e-01 -1.6020369607980383e+00 , 3.7106814855512424e+00 , 1.1866344800000000e+01 , 2.8867700000000002e-01 , -9.4472999999999996e-01 , -1.5540699999999999e-01 -1.7471080034643180e+00 , 3.3493937515937375e+00 , 9.2502871999999989e+00 , -9.2874299999999999e-01 , 2.5946200000000003e-01 , -2.6479300000000000e-01 -4.6887756770683984e+00 , 1.5629643686837704e+00 , 1.3643041600000001e+00 , -1.6280700000000001e-01 , 2.5119100000000000e-01 , 9.5414699999999997e-01 -4.7432613614511778e+00 , 1.5505799798879631e+00 , 1.3882512000000000e+00 , -1.6280700000000001e-01 , 2.5119100000000000e-01 , 9.5414699999999997e-01 -4.8215687017159201e+00 , 1.5296688157113369e+00 , 1.3960283200000001e+00 , -4.2693799999999997e-02 , 1.8356700000000001e-01 , 9.8207999999999995e-01 -4.9005993839436819e+00 , 1.5081731462069881e+00 , 1.4063628000000001e+00 , -3.7365799999999998e-02 , 1.7646800000000001e-01 , 9.8359700000000005e-01 -4.9883601343213222e+00 , 1.4845994105294671e+00 , 1.4134545599999999e+00 , -1.0165800000000000e-01 , 1.9645599999999999e-01 , 9.7522900000000001e-01 -5.0589166584439376e+00 , 1.4665367778781966e+00 , 1.4337324800000000e+00 , 1.0597100000000000e-01 , -2.1260100000000001e-01 , -9.7137600000000002e-01 -5.1392238988729702e+00 , 1.4463864995884643e+00 , 1.4509964799999999e+00 , -9.6048599999999998e-02 , 2.2521200000000000e-01 , 9.6956399999999998e-01 -5.2281427656196371e+00 , 1.4221773807542668e+00 , 1.4657312000000000e+00 , -5.2213799999999998e-02 , 2.0575499999999999e-01 , 9.7721000000000002e-01 -5.3346217686480752e+00 , 1.3936329039226671e+00 , 1.4732753600000001e+00 , 3.0447100000000001e-02 , -1.8661000000000000e-01 , -9.8196200000000000e-01 -5.4416980192682711e+00 , 1.3636602126694402e+00 , 1.4843908799999999e+00 , -7.8596700000000005e-02 , 2.1264300000000000e-01 , 9.7396400000000005e-01 -5.5327296571198339e+00 , 1.3411209220474618e+00 , 1.5079011200000001e+00 , -6.8578500000000001e-02 , 2.1814000000000000e-01 , 9.7350499999999995e-01 -5.6500293384629439e+00 , 1.3100265540788945e+00 , 1.5208824000000001e+00 , -5.9200999999999997e-02 , 1.9363600000000000e-01 , 9.7928599999999999e-01 -5.7668688349377515e+00 , 1.2786372830635724e+00 , 1.5376097600000000e+00 , 6.5757200000000002e-02 , -1.8846099999999999e-01 , -9.7987700000000000e-01 -5.8853102414743610e+00 , 1.2469360438545163e+00 , 1.5583348799999999e+00 , 6.0712500000000003e-02 , -1.8176100000000001e-01 , -9.8146699999999998e-01 -6.0230039148763534e+00 , 1.2104041481037440e+00 , 1.5750580800000000e+00 , -6.2328300000000003e-02 , 1.8397400000000000e-01 , 9.8095299999999996e-01 -6.1601778990782510e+00 , 1.1737138485168299e+00 , 1.5961336799999999e+00 , -2.8855199999999998e-01 , 2.2058000000000000e-01 , 9.3170900000000001e-01 -6.3076560379272646e+00 , 1.1346660759336040e+00 , 1.6182680000000000e+00 , -3.1101200000000001e-01 , 7.8844100000000000e-02 , 9.4713000000000003e-01 -6.4468330215350109e+00 , 1.0987213731949699e+00 , 1.6487285599999999e+00 , 9.9335399999999996e-01 , -5.3237900000000001e-03 , -1.1497900000000000e-01 -6.3693556701698615e+00 , 1.1333888409167554e+00 , 1.7568646400000001e+00 , 9.8643899999999995e-01 , 1.3233600000000001e-01 , 9.7084000000000004e-02 -6.3931616894398333e+00 , 1.1350947718759992e+00 , 1.8283771200000001e+00 , -9.8247200000000001e-01 , -1.7719699999999999e-01 , 5.7875999999999997e-02 -6.3488956989123571e+00 , 1.1586777669576560e+00 , 1.9201647120000001e+00 , 9.9670800000000004e-01 , 6.4801600000000001e-02 , 4.8730900000000001e-02 -6.3706940229415592e+00 , 1.1614411082536122e+00 , 1.9912208920000001e+00 , 9.9190400000000001e-01 , 1.0511000000000000e-01 , 7.1263999999999994e-02 -6.3516353453310801e+00 , 1.1765192933559319e+00 , 2.0725562239999999e+00 , 9.9405299999999996e-01 , 1.0707600000000000e-01 , -1.9837700000000000e-02 -6.3316653857740706e+00 , 1.1914339755104866e+00 , 2.1528550399999999e+00 , 9.9031999999999998e-01 , 8.9183700000000005e-02 , 1.0636500000000000e-01 -6.3686121721932683e+00 , 1.1894049228807662e+00 , 2.2192039200000000e+00 , 9.8724500000000004e-01 , 8.8726100000000002e-02 , 1.3219500000000001e-01 -6.2965784367929594e+00 , 1.2209843142130616e+00 , 2.3078826399999999e+00 , 9.8744500000000002e-01 , 3.1873800000000001e-02 , 1.5471699999999999e-01 -6.3112065966924904e+00 , 1.2248834031366123e+00 , 2.3777529600000000e+00 , -9.6628099999999995e-01 , 2.8531500000000001e-02 , 2.5590400000000002e-01 -6.3056185759028835e+00 , 1.2356461736337905e+00 , 2.4510906399999999e+00 , -9.3725999999999998e-01 , 3.4949000000000001e-02 , 3.4687499999999999e-01 -6.3669538125573562e+00 , 1.2254875070648015e+00 , 2.5138702400000001e+00 , -7.2824299999999997e-01 , 4.9197400000000002e-02 , 6.8355100000000002e-01 -6.4280309227254229e+00 , 1.2157646457700071e+00 , 2.5787735199999999e+00 , 5.1053700000000002e-01 , -1.0119300000000001e-01 , -8.5387999999999997e-01 -6.6261897580667179e+00 , 1.1656187496617356e+00 , 2.6304490400000002e+00 , -3.0958999999999998e-01 , 1.9371900000000000e-01 , 9.3092799999999998e-01 -1.1463782690420274e+01 , -2.2993812412032000e-01 , 2.4384525600000000e+00 , -1.1726000000000000e-01 , 2.0949999999999999e-01 , 9.7075199999999995e-01 -1.2176383154522057e+01 , -4.1783979002375649e-01 , 2.5643663999999999e+00 , -7.9323199999999996e-02 , 2.0011200000000001e-01 , 9.7655700000000001e-01 -1.3078606474583419e+01 , -6.5581372164117635e-01 , 2.7088629599999998e+00 , -5.4717399999999999e-02 , 1.9187399999999999e-01 , 9.7989300000000001e-01 -1.4328962381961130e+01 , -9.9047652521119067e-01 , 2.8798399999999997e+00 , -5.5822400000000001e-02 , 1.8959599999999999e-01 , 9.8027399999999998e-01 -1.5867913205478466e+01 , -1.4017441664903467e+00 , 3.0958480000000002e+00 , -4.6536800000000003e-02 , 1.8330500000000000e-01 , 9.8195399999999999e-01 -1.8175068475568178e+01 , -2.0220601941933731e+00 , 3.3816712000000000e+00 , -1.0572200000000000e-01 , 1.7732300000000001e-01 , 9.7845800000000005e-01 -2.0478708564941964e+01 , -2.6318405688775144e+00 , 3.7505280000000001e+00 , 1.1028399999999999e-01 , -1.5453800000000001e-01 , -9.8181200000000002e-01 -2.4668706212899544e+01 , -3.7543724418352280e+00 , 4.3064391999999998e+00 , -4.2235000000000000e-01 , 2.9409900000000000e-01 , 8.5739500000000002e-01 -3.0025388286830047e+01 , -5.1190172397797369e+00 , 5.5962680000000002e+00 , -9.8530300000000004e-01 , -1.6908300000000001e-01 , -2.4281100000000000e-02 -2.9854763001471525e+01 , -5.0127897741207956e+00 , 6.0762175999999997e+00 , 9.9964100000000000e-01 , 2.3178500000000001e-02 , 1.3471300000000000e-02 -2.9646646396783691e+01 , -4.8975020824741664e+00 , 6.5464328000000007e+00 , 9.9935700000000005e-01 , -3.5840700000000003e-02 , -6.3075900000000005e-04 -2.9578668761479108e+01 , -4.8202349555287611e+00 , 7.0310936000000002e+00 , 9.8619199999999996e-01 , -5.1451200000000002e-02 , -1.5741200000000000e-01 -2.9861458632171932e+01 , -4.8348567434336180e+00 , 7.5724448000000004e+00 , 9.9532399999999999e-01 , 2.0975600000000000e-02 , 9.4287899999999994e-02 -3.2768941499335369e+01 , -5.5364787964957376e+00 , 8.6048736000000012e+00 , 7.2593300000000005e-01 , -8.2373399999999999e-02 , -6.8281499999999995e-01 -2.9199779090745530e+01 , -4.5419781015190202e+00 , 8.4472719999999999e+00 , -6.0092999999999996e-01 , -1.0247100000000001e-01 , -7.9270600000000002e-01 -3.7701442815004924e+01 , -6.6716499059123322e+00 , 1.0806324800000001e+01 , 5.7583099999999998e-01 , -1.2845000000000001e-01 , -8.0741499999999999e-01 -2.4388229962966754e+01 , -3.1941782840757957e+00 , 8.2972832000000007e+00 , 8.0164000000000002e-01 , 5.0346100000000005e-01 , 3.2233499999999998e-01 -2.4573462419820675e+01 , -3.1913401011323268e+00 , 8.7566096000000009e+00 , -9.1035200000000005e-01 , -2.7175899999999997e-01 , -3.1209999999999999e-01 -2.4301213007649650e+01 , -3.0732416024266787e+00 , 9.1002463999999996e+00 , -9.1035200000000005e-01 , -2.7175899999999997e-01 , -3.1209999999999999e-01 -2.2937052109015912e+01 , -2.6835261730800841e+00 , 9.1149728000000003e+00 , 3.8215399999999999e-01 , 8.6100200000000005e-01 , 3.3561000000000002e-01 -2.2002555923497976e+01 , -2.4063798298276620e+00 , 9.2159984000000001e+00 , -9.2073799999999995e-01 , -3.8240099999999999e-01 , -7.7535400000000004e-02 -2.2291978701299758e+01 , -2.4312130105192020e+00 , 9.6921415999999994e+00 , -8.9684399999999997e-01 , -4.1931299999999999e-01 , 1.4088000000000001e-01 -2.2905898554974087e+01 , -2.5329817635445488e+00 , 1.0298222400000000e+01 , 9.9943400000000004e-01 , 1.6559800000000000e-02 , -2.9267800000000000e-02 -2.5178441120010952e+01 , -3.0270440041602784e+00 , 1.1551058400000001e+01 , 1.1991900000000000e-02 , 6.1919099999999998e-02 , 9.9800900000000003e-01 -2.2625009805275553e+01 , -2.3680762114895817e+00 , 1.1004049600000000e+01 , 9.8760999999999999e-01 , 5.8912500000000000e-02 , 1.4544899999999999e-01 -2.2686863449082889e+01 , -2.3329459225879061e+00 , 1.1439383200000000e+01 , 9.8633800000000005e-01 , -6.3126399999999999e-02 , -1.5215899999999999e-01 -2.2768715486931708e+01 , -2.3017204015105053e+00 , 1.1891138399999999e+01 , 9.9021400000000004e-01 , 2.4645299999999998e-02 , -1.3736799999999999e-01 -2.2905822414370583e+01 , -2.2829048006742170e+00 , 1.2377411200000001e+01 , 9.9314300000000000e-01 , 3.3602699999999999e-02 , -1.1197300000000000e-01 -2.3346550579169850e+01 , -2.3306975032271060e+00 , 1.3019528000000001e+01 , 9.6194700000000000e-01 , -2.5524200000000002e-01 , 9.7520300000000004e-02 -2.3242029329543676e+01 , -2.2527097062641062e+00 , 1.3415976000000001e+01 , -8.8687000000000005e-01 , 4.0000500000000000e-01 , -2.3120900000000000e-01 -2.2767123127036520e+01 , -2.0928476049540272e+00 , 1.3623248000000000e+01 , -8.8687000000000005e-01 , 4.0000500000000000e-01 , -2.3120900000000000e-01 -2.2956761799122742e+01 , -2.0808604723021711e+00 , 1.4176424000000001e+01 , -9.7520899999999999e-01 , 1.1736000000000001e-01 , 1.8760099999999999e-01 -2.3570539606793314e+01 , -2.1578482763954652e+00 , 1.4984608000000001e+01 , -9.0643399999999996e-01 , 2.3930199999999999e-01 , 3.4801100000000001e-01 -2.3421188951151056e+01 , -2.0670562759318374e+00 , 1.5382304000000000e+01 , -8.8578500000000004e-01 , 1.2855600000000000e-01 , 4.4593400000000000e-01 -2.9286750921572303e+01 , -3.2430065171267186e+00 , 1.9451096000000003e+01 , -7.5006099999999998e-01 , 4.3969200000000003e-01 , 4.9404399999999998e-01 -2.8501480360904193e+01 , -3.0031636038659011e+00 , 1.9593888000000003e+01 , -5.4807099999999997e-01 , 7.5460499999999997e-01 , 3.6081900000000000e-01 -3.0014282877450263e+01 , -3.2357067203904055e+00 , 2.1223568000000004e+01 , -8.8576699999999997e-01 , 3.0748900000000001e-01 , 3.4766100000000000e-01 -7.6130040516022941e+00 , 1.4296327882647626e+00 , 7.1502048000000000e+00 , -6.8126500000000001e-01 , -5.5379699999999998e-01 , -4.7873599999999999e-01 -7.4424345420045546e+00 , 1.4784207693624312e+00 , 7.1557271999999994e+00 , -6.8126500000000001e-01 , -5.5379699999999998e-01 , -4.7873599999999999e-01 -7.3682646116331130e+00 , 1.5094928518683630e+00 , 7.2361296000000008e+00 , 6.6498999999999997e-01 , 4.0705599999999997e-01 , 6.2617400000000001e-01 -7.2534872984236705e+00 , 1.5478792929988137e+00 , 7.2809536000000001e+00 , -6.9535000000000002e-01 , -4.5195099999999999e-01 , -5.5877500000000002e-01 -7.1615967783657846e+00 , 1.5814608604329201e+00 , 7.3436760000000003e+00 , -6.5600800000000004e-01 , -4.9293199999999998e-01 , -5.7155199999999995e-01 -7.0603589903246666e+00 , 1.6157156316471846e+00 , 7.3972568000000001e+00 , -7.2903300000000004e-01 , -4.0572399999999997e-01 , -5.5127099999999996e-01 -6.9604495559421204e+00 , 1.6505367961503929e+00 , 7.4486224000000005e+00 , 9.0966400000000003e-01 , -3.8765200000000000e-01 , 1.4912400000000001e-01 -7.0189367608213313e+00 , 1.6594533473837545e+00 , 7.6581823999999994e+00 , 6.9387699999999997e-01 , -4.9109700000000001e-01 , 5.2664900000000003e-01 -6.9438700116306400e+00 , 1.6902905780950546e+00 , 7.7372432000000009e+00 , 3.2994200000000001e-01 , -4.4049500000000003e-01 , 8.3492699999999997e-01 -6.8945919399776452e+00 , 1.7172931910605131e+00 , 7.8449456000000000e+00 , 9.6478699999999995e-01 , -2.6292900000000002e-01 , 7.3302300000000001e-03 -6.9409397420631826e+00 , 1.7299779281031116e+00 , 8.0600904000000000e+00 , 8.5362199999999999e-01 , 1.9668800000000000e-01 , 4.8233199999999998e-01 -6.3212396616055351e+00 , 1.8412066570349253e+00 , 7.5207568000000000e+00 , 4.7715199999999999e-02 , 3.0295099999999998e-02 , 9.9840099999999998e-01 -6.2211910574893663e+00 , 1.8737828630755238e+00 , 7.5556799999999997e+00 , 2.3824500000000001e-01 , -1.4482000000000000e-02 , 9.7109699999999999e-01 -6.0749564315389870e+00 , 1.9124545059825340e+00 , 7.5319472000000003e+00 , 1.5701399999999999e-01 , 1.4705499999999999e-01 , 9.7658699999999998e-01 -5.9301740040708122e+00 , 1.9492494062876180e+00 , 7.5045016000000002e+00 , 1.4135700000000001e-01 , 4.5403399999999997e-02 , 9.8891700000000005e-01 -5.9132488641034024e+00 , 1.9705539729784374e+00 , 7.6382560000000002e+00 , -4.2811299999999997e-02 , -3.9655600000000002e-01 , 9.1701200000000005e-01 -6.1452382385732998e+00 , 1.9622817735117866e+00 , 8.1157615999999990e+00 , -9.3894100000000003e-01 , -3.0743199999999998e-01 , -1.5451899999999999e-01 -6.0490864858427660e+00 , 1.9947936827541546e+00 , 8.1617400000000018e+00 , -5.4717099999999996e-01 , 4.9760500000000002e-01 , 6.7304699999999995e-01 -5.7543026885820971e+00 , 2.0489527587486775e+00 , 7.9144072000000003e+00 , 2.4731900000000001e-01 , -1.9978900000000000e-03 , 9.6893200000000002e-01 -5.6851278923909740e+00 , 2.0773170047716940e+00 , 7.9877272000000001e+00 , -5.2053700000000003e-01 , 7.2258800000000001e-01 , 4.5487100000000003e-01 -5.1240598893088958e+00 , 2.1527226934953569e+00 , 7.2883480000000000e+00 , -5.9283400000000000e-02 , -9.9425399999999997e-01 , -8.9127600000000001e-02 -5.0707152228840835e+00 , 2.1769102449901867e+00 , 7.3601184000000002e+00 , 1.0001500000000000e-02 , -6.5492700000000004e-01 , 7.5562600000000002e-01 -4.9624257059875951e+00 , 2.2054347093256932e+00 , 7.3415751999999994e+00 , -1.2614300000000001e-01 , -8.1626299999999996e-01 , 5.6373899999999999e-01 -4.9373204336927428e+00 , 2.2271513894318908e+00 , 7.4650856000000001e+00 , -5.2717599999999998e-01 , -7.7683599999999997e-01 , 3.4439999999999998e-01 -4.9938073958120412e+00 , 2.2448361338714613e+00 , 7.7441072000000002e+00 , -2.5648100000000001e-01 , 9.0582600000000002e-01 , 3.3718999999999999e-01 -4.9395013689908724e+00 , 2.2703112378672472e+00 , 7.8326008000000007e+00 , 3.0612699999999998e-01 , 8.9668300000000001e-01 , 3.1975799999999999e-01 -5.2155175826821427e+00 , 2.2826661091957874e+00 , 8.5799968000000000e+00 , 6.4611499999999999e-01 , 2.2443399999999999e-01 , -7.2949600000000003e-01 -4.9613628685602951e+00 , 2.3188294207792417e+00 , 8.2888903999999997e+00 , 5.2676400000000001e-01 , -8.2778799999999997e-01 , -1.9309999999999999e-01 -4.6386589699241583e+00 , 2.3540442451527261e+00 , 7.8203600000000000e+00 , 9.9312199999999995e-01 , 1.1568600000000000e-01 , -1.8072499999999998e-02 -4.8615491966727227e+00 , 2.3782006573028527e+00 , 8.5412047999999992e+00 , -8.6354299999999995e-01 , -1.4808900000000000e-01 , -4.8204100000000000e-01 -4.8192090946037691e+00 , 2.4090343995601682e+00 , 8.6957488000000005e+00 , -8.2741900000000002e-01 , -3.0546899999999999e-01 , 4.7123900000000002e-01 -4.7868726455893551e+00 , 2.4408252799130588e+00 , 8.8888040000000004e+00 , -5.8166300000000004e-01 , -5.6301599999999996e-01 , 5.8709500000000003e-01 -4.6825031119957696e+00 , 2.4724169281802291e+00 , 8.9073887999999997e+00 , 1.5404899999999999e-01 , 6.1642300000000005e-01 , -7.7219899999999997e-01 -4.5057459350102862e+00 , 2.5012658780111146e+00 , 8.7282696000000008e+00 , 2.5031999999999999e-01 , 5.7650399999999997e-02 , 9.6644500000000000e-01 -4.3940738822186898e+00 , 2.5314529561875272e+00 , 8.7119624000000009e+00 , -1.7262100000000000e-01 , 7.2088799999999997e-01 , 6.7120999999999997e-01 -4.2706442073983899e+00 , 2.5590752317709158e+00 , 8.6540759999999999e+00 , 2.6426899999999998e-01 , -2.3128699999999999e-01 , 9.3630599999999997e-01 -4.2044837888571411e+00 , 2.5920949986469277e+00 , 8.7722303999999998e+00 , -5.2392700000000003e-01 , -2.0134900000000000e-01 , -8.2762300000000000e-01 -4.2226882664268999e+00 , 2.6370863414528247e+00 , 9.1891560000000005e+00 , -9.3862500000000004e-01 , -4.3322600000000003e-02 , 3.4221000000000001e-01 -4.0759137902854503e+00 , 2.6632924927775190e+00 , 9.0560152000000009e+00 , -8.5682000000000003e-01 , 4.7978199999999999e-01 , -1.8885800000000000e-01 -3.9887735521567724e+00 , 2.6971016114178452e+00 , 9.1314464000000015e+00 , -8.2031399999999999e-01 , 4.9994100000000002e-01 , -2.7774799999999999e-01 -3.7002753197913858e+00 , 2.6870118573305559e+00 , 8.3662872000000004e+00 , -2.5903099999999998e-02 , 1.3598399999999999e-01 , 9.9037200000000003e-01 -3.5668283663944162e+00 , 2.7023846324181124e+00 , 8.1822176000000013e+00 , -7.2268299999999996e-01 , 2.3008500000000001e-01 , 6.5176000000000001e-01 -3.4602052846233882e+00 , 2.7216413483636894e+00 , 8.0969376000000004e+00 , -7.5358999999999998e-01 , 1.9120599999999999e-01 , 6.2892199999999998e-01 -3.4697660981324843e+00 , 2.7823662029473430e+00 , 8.6217319999999997e+00 , -4.1160000000000002e-01 , 8.0850000000000000e-01 , 4.2060999999999998e-01 -3.1994798219711229e+00 , 2.7332642391664068e+00 , 7.5719560000000001e+00 , -5.3450299999999995e-01 , -4.1081099999999998e-01 , -7.3860700000000001e-01 -3.1195711274142486e+00 , 2.7538041020520687e+00 , 7.5514472000000001e+00 , 4.8579000000000000e-01 , 6.2675300000000000e-01 , 6.0925300000000004e-01 -3.0434650595564037e+00 , 2.7758438072288505e+00 , 7.5602663999999997e+00 , 4.9147500000000000e-01 , 6.5682399999999996e-01 , 5.7186999999999999e-01 -2.9730384394425196e+00 , 2.8014319367282310e+00 , 7.6090008000000005e+00 , 5.9441600000000006e-01 , 7.3323300000000002e-01 , 3.3021000000000000e-01 -2.8962195670429614e+00 , 2.8240041645014471e+00 , 7.6150640000000003e+00 , 6.0021800000000003e-01 , 6.8413500000000005e-01 , 4.1436400000000001e-01 -2.9136677019093038e+00 , 2.9593107368055573e+00 , 8.7752359999999996e+00 , 8.4341699999999997e-01 , 3.7235600000000002e-01 , 3.8729599999999997e-01 -2.7618752551593984e+00 , 2.8981622136638405e+00 , 7.9123064000000003e+00 , 2.9353500000000002e-03 , 5.5559000000000003e-01 , 8.3145100000000005e-01 -2.6917092644863914e+00 , 2.9473352909608685e+00 , 8.1519328000000009e+00 , 5.4908000000000001e-01 , 6.0823000000000005e-01 , -5.7320800000000005e-01 -2.6014306545834534e+00 , 2.9551509324271321e+00 , 8.0080904000000004e+00 , -7.0907100000000001e-01 , -5.9031599999999995e-01 , -3.8567699999999999e-01 -2.5429039713467070e+00 , 3.1910055858087976e+00 , 9.8250431999999996e+00 , -1.6389899999999999e-01 , -9.1107400000000005e-01 , 3.7826199999999999e-01 -2.4346901787714712e+00 , 3.0050886227438314e+00 , 8.0253648000000002e+00 , 8.2335700000000001e-01 , 4.0239200000000003e-01 , 4.0020499999999998e-01 -2.3282342040275998e+00 , 3.1727240736949121e+00 , 9.1667127999999991e+00 , 1.4960499999999999e-01 , 6.0208200000000001e-01 , -7.8429300000000002e-01 -2.2244032514254886e+00 , 3.2033758424725951e+00 , 9.1807423999999997e+00 , 2.1101300000000001e-01 , -7.5640399999999997e-01 , 6.1913399999999996e-01 -1.9684684565082680e+00 , 3.6140728447652561e+00 , 1.1992039200000001e+01 , -9.3798099999999995e-01 , 3.3340900000000001e-01 , -9.5028600000000005e-02 -2.1147032600167757e+00 , 3.0691190614983670e+00 , 7.8058415999999999e+00 , -2.6062100000000001e-02 , -5.0401700000000005e-01 , 8.6330099999999999e-01 -2.0282782793224805e+00 , 3.1002791557327356e+00 , 7.8577376000000001e+00 , 5.1954899999999998e-02 , -6.4570899999999998e-01 , 7.6181399999999999e-01 -1.7907677189607369e+00 , 3.3444490328887104e+00 , 9.3298991999999998e+00 , -1.0236099999999999e-01 , 9.8651100000000003e-01 , -1.2774300000000000e-01 -4.7556848928349478e+00 , 1.4822781044364786e+00 , 1.4049983200000000e+00 , -1.2641900000000000e-01 , 1.9517499999999999e-01 , 9.7258699999999998e-01 -4.8416994112885714e+00 , 1.4549122562517203e+00 , 1.4087111200000000e+00 , -3.5152400000000000e-02 , 1.9203700000000001e-01 , 9.8075800000000002e-01 -4.9205178501851963e+00 , 1.4315844599499066e+00 , 1.4204672800000000e+00 , -4.1506200000000000e-02 , 1.6493800000000000e-01 , 9.8543000000000003e-01 -5.0070071492163599e+00 , 1.4051743879958585e+00 , 1.4290618400000001e+00 , -1.3791000000000000e-01 , 1.9436600000000001e-01 , 9.7118599999999999e-01 -5.0694436552361317e+00 , 1.3887977647186691e+00 , 1.4559479199999998e+00 , -1.2310900000000000e-01 , 2.0661900000000000e-01 , 9.7064499999999998e-01 -5.1663825633331442e+00 , 1.3597838052150231e+00 , 1.4643875199999998e+00 , -7.6746200000000001e-02 , 1.8086600000000000e-01 , 9.8050899999999996e-01 -5.2539849375288243e+00 , 1.3328035004680441e+00 , 1.4809287200000001e+00 , -6.0665700000000003e-02 , 1.6786999999999999e-01 , 9.8394099999999995e-01 -5.3512662648456795e+00 , 1.3038801758245864e+00 , 1.4951621600000000e+00 , -4.3642899999999998e-02 , 1.9226799999999999e-01 , 9.8037200000000002e-01 -5.4492231991685198e+00 , 1.2755500990327593e+00 , 1.5124563200000001e+00 , 8.5894499999999999e-02 , -1.9904400000000000e-01 , -9.7621899999999995e-01 -5.5566865124672038e+00 , 1.2434062261835073e+00 , 1.5286636800000000e+00 , -7.3405999999999999e-02 , 1.9784199999999999e-01 , 9.7748100000000004e-01 -5.6726070369258341e+00 , 1.2085410978820639e+00 , 1.5437571999999999e+00 , -4.7663600000000000e-02 , 1.7596200000000001e-01 , 9.8324199999999995e-01 -5.7989390238237171e+00 , 1.1700562545481890e+00 , 1.5589006400000001e+00 , -5.5328799999999997e-02 , 1.8478900000000001e-01 , 9.8121999999999998e-01 -5.9258605295278537e+00 , 1.1323276040317058e+00 , 1.5779139199999999e+00 , -6.2724600000000005e-02 , 1.7691200000000001e-01 , 9.8222600000000004e-01 -6.0621298667280641e+00 , 1.0921431279348919e+00 , 1.5972537600000001e+00 , -6.5416100000000005e-02 , 1.9110300000000000e-01 , 9.7938800000000004e-01 -6.1978693220357703e+00 , 1.0517981818408959e+00 , 1.6209470399999999e+00 , -2.6799400000000001e-01 , 2.0838200000000001e-01 , 9.4061499999999998e-01 -6.3536427270535301e+00 , 1.0048603483206662e+00 , 1.6425894400000001e+00 , 4.1690100000000002e-01 , -6.5403199999999995e-02 , -9.0659599999999996e-01 -6.4641375293710492e+00 , 9.7482721360028823e-01 , 1.6857640000000000e+00 , 9.9957799999999997e-01 , -1.1213600000000001e-02 , -2.6779600000000001e-02 -6.4138816442798605e+00 , 1.0021515786443516e+00 , 1.7843040000000001e+00 , 9.9324199999999996e-01 , 6.6101999999999994e-02 , -9.5396400000000006e-02 -6.3996686389476709e+00 , 1.0166203015481585e+00 , 1.8689007200000001e+00 , 9.9317000000000000e-01 , 1.0650200000000000e-01 , 4.7642100000000000e-02 -6.4783808473003086e+00 , 9.9805676856731296e-01 , 1.9253088640000000e+00 , 9.8830700000000005e-01 , 1.5191099999999999e-01 , 1.3151899999999999e-02 -6.3760562198361521e+00 , 1.0431696575663747e+00 , 2.0325289120000001e+00 , 9.8727600000000004e-01 , 1.2631800000000001e-01 , 9.6588900000000005e-02 -6.4052579190286636e+00 , 1.0421810329308125e+00 , 2.1023483760000001e+00 , 9.8359099999999999e-01 , 1.5714000000000000e-01 , 8.8631199999999993e-02 -6.3658702505485829e+00 , 1.0643653199507570e+00 , 2.1882639199999998e+00 , 9.9275100000000005e-01 , 8.5444300000000001e-02 , 8.4530499999999995e-02 -6.4015611425892480e+00 , 1.0605748485207596e+00 , 2.2561114400000002e+00 , 9.7362899999999997e-01 , 1.3031499999999999e-01 , 1.8725800000000001e-01 -6.3199341058057747e+00 , 1.0972344102686797e+00 , 2.3468857600000002e+00 , 9.9198399999999998e-01 , 4.9335600000000000e-02 , 1.1633400000000001e-01 -6.3344209436086540e+00 , 1.1013595283606969e+00 , 2.4178688799999999e+00 , -9.2714799999999997e-01 , 1.6984400000000000e-02 , 3.7431100000000000e-01 -6.3669491951028938e+00 , 1.0988274207469755e+00 , 2.4860450400000000e+00 , -8.6629199999999995e-01 , -1.2580400000000000e-02 , 4.9937999999999999e-01 -6.4269077387797910e+00 , 1.0870844672451687e+00 , 2.5512332799999999e+00 , -8.0005599999999999e-01 , -1.0452100000000001e-02 , 5.9983399999999998e-01 -6.4676226779813311e+00 , 1.0823280656079084e+00 , 2.6206220800000000e+00 , 5.7429500000000000e-01 , -3.3769899999999999e-02 , -8.1795200000000001e-01 -1.1170875715153988e+01 , -4.2809081818435279e-01 , 2.4043353600000001e+00 , -1.2114300000000000e-01 , 2.1569800000000000e-01 , 9.6891600000000000e-01 -1.1709849248777479e+01 , -5.8363544362658981e-01 , 2.5326016800000000e+00 , 1.1354000000000000e-01 , -2.0737500000000000e-01 , -9.7165000000000001e-01 -1.2485190801061011e+01 , -8.1323475632417930e-01 , 2.6704630400000000e+00 , -7.9839700000000000e-02 , 1.8908500000000000e-01 , 9.7870999999999997e-01 -1.3546630402439447e+01 , -1.1294741952788812e+00 , 2.8293698400000000e+00 , 5.2568200000000002e-02 , -1.9222100000000000e-01 , -9.7994300000000001e-01 -1.4953702138687769e+01 , -1.5518442761877682e+00 , 3.0253880000000000e+00 , -5.7631300000000003e-02 , 1.8313599999999999e-01 , 9.8139699999999996e-01 -1.6696825365022121e+01 , -2.0730762890741179e+00 , 3.2768600000000001e+00 , -4.5666900000000003e-02 , 1.8565100000000001e-01 , 9.8155400000000004e-01 -1.9022067709303286e+01 , -2.7684846163599435e+00 , 3.6100344000000000e+00 , -9.6556199999999995e-02 , 1.6366500000000000e-01 , 9.8177899999999996e-01 -2.4875383758154381e+01 , -4.5012101842323800e+00 , 4.6122823999999998e+00 , -7.7532599999999996e-01 , -1.6241000000000000e-01 , 6.1032100000000000e-01 -3.0093568898955180e+01 , -6.0495158651125411e+00 , 5.4718423999999999e+00 , -9.7001300000000001e-01 , -2.4167200000000000e-01 , 2.5867899999999999e-02 -3.0808213757268238e+01 , -6.2079275360673698e+00 , 6.0506023999999998e+00 , -9.6114999999999995e-01 , -2.7110499999999998e-01 , 5.1897800000000001e-02 -3.0751577577788250e+01 , -6.1311203784457646e+00 , 6.5618248000000001e+00 , -9.6114999999999995e-01 , -2.7110499999999998e-01 , 5.1897800000000001e-02 -3.0193087252903485e+01 , -5.9028531301202465e+00 , 7.0013912000000005e+00 , -9.3145500000000003e-01 , -3.5742000000000002e-01 , 6.8136199999999994e-02 -3.0317589637212386e+01 , -5.8810109350520392e+00 , 7.5315312000000008e+00 , -9.5601199999999997e-01 , -2.7489300000000000e-01 , 1.0235000000000000e-01 -3.3283518840037203e+01 , -6.6966380038273101e+00 , 8.5746199999999995e+00 , -8.8026800000000005e-01 , 4.7419000000000000e-01 , -1.6483899999999999e-02 -3.5265240886316356e+01 , -7.2102731166098692e+00 , 9.5364743999999995e+00 , 3.4176000000000001e-01 , -4.6864299999999998e-01 , -8.1459999999999999e-01 -2.7769075827627653e+01 , -4.9589098376771830e+00 , 8.5338416000000006e+00 , -5.0926600000000000e-01 , 3.0346400000000001e-01 , -8.0533100000000002e-01 -2.7299550195282244e+01 , -4.7685312847815302e+00 , 8.8991520000000008e+00 , -4.1863000000000000e-01 , 2.3052800000000001e-01 , -8.7841100000000005e-01 -2.4512756859929613e+01 , -3.9147557843002749e+00 , 8.6631552000000003e+00 , -9.8781399999999997e-01 , 1.5368200000000001e-01 , 2.4614100000000000e-02 -2.4971033250441788e+01 , -3.9967683107908902e+00 , 9.2077823999999993e+00 , -9.6244799999999997e-01 , 1.9870699999999999e-01 , 1.8495900000000001e-01 -2.5061303270044970e+01 , -3.9719966422794535e+00 , 9.6660480000000000e+00 , 9.8446699999999998e-01 , -1.2794700000000001e-01 , -1.2022800000000000e-01 -2.4260692436289499e+01 , -3.6967859703426154e+00 , 9.8546520000000015e+00 , -8.3585200000000004e-01 , -4.4610800000000000e-01 , -3.1990600000000002e-01 -2.3765913709639214e+01 , -3.5100833058279228e+00 , 1.0117064800000000e+01 , -8.0963399999999996e-01 , -3.1290200000000001e-01 , -4.9657400000000002e-01 -2.6384498548596728e+01 , -4.1816086055314177e+00 , 1.1453433600000000e+01 , 9.9519599999999997e-01 , -6.7507899999999996e-02 , -7.0903800000000003e-02 -2.3731584190327286e+01 , -3.4025014539867682e+00 , 1.0949418399999999e+01 , -7.9905300000000001e-01 , -5.2252299999999996e-01 , -2.9746400000000001e-01 -2.3187057401305619e+01 , -3.2049042380388020e+00 , 1.1165759200000002e+01 , -9.1075399999999995e-01 , -3.7528099999999998e-01 , -1.7231500000000000e-01 -2.2789547621598459e+01 , -3.0494194969748420e+00 , 1.1425655200000000e+01 , -9.5345599999999997e-01 , -2.9953600000000002e-01 , -3.4647100000000000e-02 -2.2937281201635383e+01 , -3.0401012203512181e+00 , 1.1909255200000000e+01 , 9.9539400000000000e-01 , 8.8605100000000006e-02 , 3.6611999999999999e-02 -2.2992724454001355e+01 , -3.0042329695206673e+00 , 1.2362716000000001e+01 , -9.0603800000000001e-01 , 4.0998200000000001e-01 , 1.0492899999999999e-01 -2.3066000156037198e+01 , -2.9731011715624058e+00 , 1.2833264000000002e+01 , -8.5145199999999999e-01 , 5.1870200000000000e-01 , -7.7324000000000004e-02 -2.2766228982615733e+01 , -2.8443459783563876e+00 , 1.3129040000000002e+01 , 6.2470700000000001e-01 , -6.4537900000000004e-01 , 4.3957600000000002e-01 -2.2724382659613191e+01 , -2.7818693870744751e+00 , 1.3551384000000001e+01 , -5.8969600000000000e-01 , 6.4221799999999996e-01 , -4.8970900000000001e-01 -2.2513567803470199e+01 , -2.6752570854504727e+00 , 1.3887928000000000e+01 , -5.8969600000000000e-01 , 6.4221799999999996e-01 , -4.8970799999999998e-01 -2.3386898707076160e+01 , -2.8422603661648065e+00 , 1.4831728000000002e+01 , -8.9012999999999998e-01 , 1.8141000000000001e-02 , 4.5534599999999997e-01 -2.3462949119587336e+01 , -2.8044008111108916e+00 , 1.5357448000000000e+01 , -9.6342099999999997e-01 , 7.3154700000000001e-03 , 2.6789099999999999e-01 -2.8041874585791120e+01 , -3.8704728163110085e+00 , 1.8632616000000002e+01 , -9.0517599999999998e-01 , 2.2233400000000000e-01 , 3.6224899999999999e-01 -2.8542200489453624e+01 , -3.9206904123934549e+00 , 1.9559567999999999e+01 , -8.8846400000000003e-01 , -1.1559300000000000e-01 , 4.4414999999999999e-01 -2.8039132557004923e+01 , -3.7260752353958981e+00 , 1.9865016000000001e+01 , 6.9650100000000004e-01 , -5.6735100000000005e-01 , -4.3931700000000001e-01 -2.9558572411647209e+01 , -4.0112537194030811e+00 , 2.1535464000000001e+01 , -8.6931400000000003e-01 , 3.9605600000000002e-01 , 2.9568899999999998e-01 -2.9119662146984229e+01 , -3.8289946816203875e+00 , 2.1914439999999999e+01 , -7.6146800000000003e-01 , 2.1332499999999999e-01 , 6.1209400000000003e-01 -7.5224847567417985e+00 , 1.2828629554939970e+00 , 7.2087568000000006e+00 , -6.6484100000000002e-01 , -5.7373499999999999e-01 , -4.7834500000000002e-01 -7.4632121617796354e+00 , 1.3131559518022433e+00 , 7.3043431999999999e+00 , 7.1898399999999996e-01 , 4.6362799999999998e-01 , 5.1779500000000001e-01 -7.3567442352705994e+00 , 1.3531100622419272e+00 , 7.3586832000000006e+00 , -7.6709499999999997e-01 , -4.5398699999999997e-01 , -4.5327699999999999e-01 -7.3021747585366201e+00 , 1.3819263888200983e+00 , 7.4584400000000004e+00 , 6.8658200000000003e-01 , 4.9105500000000002e-01 , 5.3616200000000003e-01 -7.2231247051206546e+00 , 1.4158718161417974e+00 , 7.5362839999999993e+00 , 6.3631800000000005e-01 , 5.1922400000000002e-01 , 5.7053100000000001e-01 -7.0843745052089417e+00 , 1.4618035840988424e+00 , 7.5554512000000003e+00 , -6.7310199999999998e-01 , -4.5047799999999999e-01 , -5.8651799999999998e-01 -6.9022957387497899e+00 , 1.5159624897442996e+00 , 7.5271840000000010e+00 , 7.2981700000000005e-01 , 1.9563800000000001e-01 , 6.5505100000000005e-01 -6.9084093155305375e+00 , 1.5328643825159953e+00 , 7.6861584000000001e+00 , 8.9666000000000001e-01 , -1.2768900000000000e-01 , 4.2390499999999998e-01 -6.7697469992848509e+00 , 1.5779438204071352e+00 , 7.6958824000000003e+00 , -3.5455199999999998e-01 , 3.8840300000000000e-01 , -8.5055000000000003e-01 -6.9161161232324257e+00 , 1.5692324284575374e+00 , 8.0158592000000013e+00 , -8.5940300000000003e-01 , 9.3727000000000005e-02 , -5.0263500000000005e-01 -6.6039146220616836e+00 , 1.6458696063670590e+00 , 7.8289608000000008e+00 , -9.1255900000000001e-01 , 1.9821900000000001e-01 , -3.5769499999999999e-01 -6.6800436373438972e+00 , 1.6511995509221633e+00 , 8.0824920000000002e+00 , -3.8452999999999998e-01 , -8.7391700000000005e-01 , -2.9732999999999998e-01 -6.7093617485530102e+00 , 1.6665974941591726e+00 , 8.2916464000000012e+00 , -7.8262299999999996e-01 , -1.9090399999999999e-01 , -5.9250000000000003e-01 -6.0594063426826956e+00 , 1.7968902287103119e+00 , 7.6507360000000002e+00 , 1.3952400000000001e-01 , 1.7457300000000001e-01 , 9.7470900000000005e-01 -5.8843291162495426e+00 , 1.8445681371744440e+00 , 7.5812223999999997e+00 , 3.4299900000000000e-01 , -1.6683999999999999e-01 , 9.2440000000000000e-01 -5.8169305997318430e+00 , 1.8738018060645283e+00 , 7.6486976000000002e+00 , 4.7869299999999998e-01 , -2.8562100000000001e-01 , 8.3022499999999999e-01 -6.4196601099629182e+00 , 1.8000679871732332e+00 , 8.6604200000000002e+00 , -4.2986200000000002e-01 , -4.5932200000000001e-01 , -7.7732999999999997e-01 -5.6951322471509114e+00 , 1.9297585788397029e+00 , 7.8055816000000009e+00 , -3.4536000000000000e-01 , 6.4664400000000000e-01 , -6.8013100000000004e-01 -5.6051908814730451e+00 , 1.9625191787784404e+00 , 7.8435936000000002e+00 , -6.6548300000000005e-01 , 5.2815999999999996e-01 , -5.2742699999999998e-01 -5.5321372625143059e+00 , 1.9931097601605210e+00 , 7.9060559999999995e+00 , -7.5893999999999995e-01 , 3.8203900000000002e-01 , 5.2731099999999997e-01 -5.6651707913091691e+00 , 1.9973131502486263e+00 , 8.3031487999999989e+00 , 9.1345599999999999e-02 , -9.1721500000000000e-01 , 3.8778000000000001e-01 -5.6584222895615017e+00 , 2.0217576933190484e+00 , 8.4915447999999998e+00 , 5.5251000000000001e-02 , 9.9216899999999997e-01 , -1.1201700000000001e-01 -5.5748215409481485e+00 , 2.0551191566708940e+00 , 8.5549743999999990e+00 , -2.2627300000000000e-01 , -9.2069500000000004e-01 , 3.1799500000000003e-01 -5.0098911946092457e+00 , 2.1397369040995402e+00 , 7.7423704000000004e+00 , -6.5877500000000000e-01 , 7.4900999999999995e-01 , -7.0708599999999996e-02 -5.4360311192413384e+00 , 2.1208799542084504e+00 , 8.7410719999999991e+00 , -3.7591100000000000e-01 , -5.4779299999999997e-01 , 7.4740499999999999e-01 -5.2345738789536576e+00 , 2.1656775484544797e+00 , 8.5778648000000004e+00 , -6.0647300000000004e-01 , -3.5712400000000000e-01 , 7.1038900000000005e-01 -5.1210448474057522e+00 , 2.2013086617544406e+00 , 8.5776463999999990e+00 , 1.2558100000000000e-01 , 7.0801499999999995e-01 , -6.9494199999999995e-01 -4.9515539026313835e+00 , 2.2406927488139896e+00 , 8.4523575999999991e+00 , 6.8186599999999997e-01 , -6.9833000000000006e-02 , 7.2813600000000001e-01 -4.6764276514229284e+00 , 2.2828917307233203e+00 , 8.0760855999999990e+00 , 6.8345999999999996e-01 , 2.7128700000000000e-01 , 6.7770600000000003e-01 -4.8260401915147426e+00 , 2.3034613365790721e+00 , 8.6580696000000010e+00 , -3.8985900000000001e-01 , -8.0972900000000003e-01 , 4.3857600000000002e-01 -4.6983820055336523e+00 , 2.3385946983313621e+00 , 8.6102191999999995e+00 , 6.0992100000000000e-02 , -6.2849699999999997e-01 , 7.7541700000000002e-01 -4.6368985376663119e+00 , 2.3716802879402432e+00 , 8.7244111999999987e+00 , -3.7918499999999999e-01 , 1.2237300000000000e-01 , -9.1719300000000004e-01 -4.5430722303026938e+00 , 2.4051793083612996e+00 , 8.7599896000000008e+00 , 2.0672099999999999e-01 , 2.5547199999999998e-01 , 9.4445800000000002e-01 -4.4283255415109855e+00 , 2.4379704522013337e+00 , 8.7348840000000010e+00 , 7.4067499999999994e-02 , 3.3896300000000001e-01 , 9.3788000000000005e-01 -4.3279340173853331e+00 , 2.4712437182240250e+00 , 8.7468544000000001e+00 , 2.1010300000000001e-01 , 1.8819600000000000e-01 , 9.5939500000000000e-01 -4.2587099560655428e+00 , 2.5057663536731463e+00 , 8.8560024000000013e+00 , 2.2527400000000000e-01 , -1.1158400000000000e-01 , 9.6788500000000000e-01 -4.1447220677602825e+00 , 2.5383215527106753e+00 , 8.8246152000000002e+00 , -3.4561300000000000e-01 , -1.1440300000000000e-01 , -9.3137700000000001e-01 -4.0380239479979547e+00 , 2.5709308189302442e+00 , 8.8108560000000011e+00 , 3.5653400000000002e-01 , 7.9000699999999993e-02 , 9.3093599999999999e-01 -4.0368357669707597e+00 , 2.6160011701381798e+00 , 9.1976943999999996e+00 , -9.3862400000000001e-01 , -4.3322600000000003e-02 , 3.4221000000000001e-01 -3.7833572644540530e+00 , 2.6255859838094739e+00 , 8.5956176000000006e+00 , 7.5065999999999999e-01 , -1.6772999999999999e-01 , -6.3904399999999995e-01 -3.6214605209730824e+00 , 2.6433158837036328e+00 , 8.3012455999999997e+00 , 6.7284400000000000e-01 , -1.6669900000000001e-01 , -7.2075800000000001e-01 -3.5069627263254928e+00 , 2.6654565017498570e+00 , 8.1864296000000003e+00 , -8.5499099999999995e-01 , 1.8836300000000000e-01 , 4.8322900000000002e-01 -3.3270201928424736e+00 , 2.6658373506633901e+00 , 7.7019352000000003e+00 , -7.9938399999999998e-01 , 1.4553900000000000e-01 , 5.8292699999999997e-01 -3.2248697949020011e+00 , 2.6831313684208884e+00 , 7.5709783999999996e+00 , 4.9929200000000001e-01 , 2.6683000000000001e-01 , 8.2432300000000003e-01 -3.1468616048893709e+00 , 2.7068069896677294e+00 , 7.5611711999999995e+00 , -5.3969900000000004e-01 , -6.1584499999999998e-01 , -5.7398600000000000e-01 -3.0820000357011299e+00 , 2.7365602290030453e+00 , 7.6423016000000006e+00 , -6.4975600000000000e-01 , -6.6391800000000001e-01 , -3.7017699999999998e-01 -3.0124069910738180e+00 , 2.7653649623080865e+00 , 7.7019144000000006e+00 , 5.8105499999999999e-01 , 7.6822800000000002e-01 , 2.6870300000000003e-01 -2.9319593743204968e+00 , 2.7883540186895290e+00 , 7.6776304000000000e+00 , 5.8032799999999995e-01 , 7.5181299999999995e-01 , 3.1304399999999999e-01 -2.9504825969337962e+00 , 2.9092484139475880e+00 , 8.7665000000000006e+00 , -7.8697200000000000e-01 , -9.4341600000000005e-03 , 6.1691600000000002e-01 -2.8043832786160370e+00 , 2.8727085965418313e+00 , 8.0585512000000001e+00 , -1.0125500000000000e-01 , 9.8335600000000001e-01 , 1.5085599999999999e-01 -2.7246207725773397e+00 , 2.9061116704175509e+00 , 8.1335456000000015e+00 , 4.1343700000000000e-01 , 6.6648700000000005e-01 , -6.2037500000000001e-01 -2.6345783900344903e+00 , 2.9172011008325320e+00 , 7.9796360000000002e+00 , -7.9716699999999996e-01 , -4.8194500000000001e-01 , -3.6366799999999999e-01 -2.5642937412102782e+00 , 3.0029280481160443e+00 , 8.5271647999999995e+00 , -4.8669000000000001e-01 , 7.6495899999999994e-01 , 4.2186499999999999e-01 -2.4706615086932104e+00 , 2.9796873280568166e+00 , 8.0703448000000009e+00 , -2.3517099999999999e-01 , -8.9292600000000000e-01 , -3.8389899999999999e-01 -2.3875443230033291e+00 , 3.0069518067622121e+00 , 8.0772608000000012e+00 , -9.1885200000000000e-01 , -2.0043300000000000e-01 , -3.3990700000000001e-01 -2.2706709404280279e+00 , 3.1696825914883950e+00 , 9.1656832000000001e+00 , -1.2027800000000000e-01 , -6.2033499999999997e-01 , 7.7505999999999997e-01 -2.1428466765169731e+00 , 3.2760227538669366e+00 , 9.7241944000000000e+00 , -1.0556800000000000e-01 , -4.9159599999999998e-01 , 8.6440099999999997e-01 -2.1516243792325245e+00 , 3.0484392970706837e+00 , 7.8006728000000001e+00 , -1.4939700000000000e-01 , -5.0641199999999997e-01 , 8.4925099999999998e-01 -2.0696848439433095e+00 , 3.0786102344610446e+00 , 7.8327776000000000e+00 , 2.0236899999999999e-01 , 1.1196000000000000e-01 , 9.7288799999999998e-01 -1.5901341428870095e+00 , 3.7068573322195220e+00 , 1.1929129600000001e+01 , -9.8330099999999998e-01 , 5.3380900000000002e-02 , -1.7398200000000000e-01 -1.7449229067928083e+00 , 3.3463615987169435e+00 , 9.2505471999999997e+00 , -9.2049099999999995e-01 , 3.0606400000000000e-01 , -2.4294199999999999e-01 -4.6524878378398213e+00 , 1.4473093679947240e+00 , 1.3780352800000000e+00 , -2.1968199999999999e-01 , 2.1311900000000000e-01 , 9.5200899999999999e-01 -4.7058375392185514e+00 , 1.4318391429388226e+00 , 1.4022703999999999e+00 , -2.0115400000000000e-01 , 1.9512599999999999e-01 , 9.5992900000000003e-01 -4.7829109781446135e+00 , 1.4058124708298005e+00 , 1.4107453599999999e+00 , -1.1898700000000000e-01 , 1.9609099999999999e-01 , 9.7333999999999998e-01 -4.8517766423529256e+00 , 1.3838416118454986e+00 , 1.4270369599999999e+00 , -5.9048200000000002e-02 , 1.6525899999999999e-01 , 9.8448100000000005e-01 -4.9372793385047498e+00 , 1.3540799229624922e+00 , 1.4346040000000000e+00 , 9.5201200000000000e-02 , -1.5688500000000000e-01 , -9.8301799999999995e-01 -5.0156465532720294e+00 , 1.3293660530749354e+00 , 1.4499076000000000e+00 , 1.2508800000000000e-01 , -1.8328000000000000e-01 , -9.7506999999999999e-01 -5.0947188592818611e+00 , 1.3041053631990125e+00 , 1.4678684000000000e+00 , -1.3128999999999999e-01 , 1.7902000000000001e-01 , 9.7504599999999997e-01 -5.1813829699172063e+00 , 1.2747913351669489e+00 , 1.4831761600000000e+00 , -7.9558900000000002e-02 , 1.5978300000000001e-01 , 9.8394099999999995e-01 -5.2777239675126859e+00 , 1.2435444799308162e+00 , 1.4961782399999999e+00 , -6.8695400000000004e-02 , 1.5754199999999999e-01 , 9.8512000000000000e-01 -5.3825155800391249e+00 , 1.2074102812272525e+00 , 1.5078678399999998e+00 , -8.3549799999999994e-02 , 1.8974700000000000e-01 , 9.7827200000000003e-01 -5.4713129852769757e+00 , 1.1797171841064009e+00 , 1.5316474400000000e+00 , 9.1365699999999994e-02 , -1.6741800000000001e-01 , -9.8164300000000004e-01 -5.5862898818997362e+00 , 1.1414454812046628e+00 , 1.5454097600000001e+00 , -6.5121399999999996e-02 , 1.7915000000000000e-01 , 9.8166399999999998e-01 -5.7018529992142568e+00 , 1.1028469271126966e+00 , 1.5629420800000000e+00 , -5.2662199999999999e-02 , 1.6867799999999999e-01 , 9.8426300000000000e-01 -5.8268336450490530e+00 , 1.0616581143908272e+00 , 1.5801946400000000e+00 , -6.2819100000000003e-02 , 1.6405600000000001e-01 , 9.8444900000000002e-01 -5.9523411453566082e+00 , 1.0202259200662545e+00 , 1.6016227999999999e+00 , -7.2779999999999997e-02 , 1.7912400000000001e-01 , 9.8113099999999998e-01 -6.0881904110792142e+00 , 9.7530844375882308e-01 , 1.6237092799999999e+00 , 6.5665899999999999e-02 , -1.7996200000000001e-01 , -9.8147899999999999e-01 -6.2420279227573028e+00 , 9.2378663325594923e-01 , 1.6432903999999999e+00 , -9.1660599999999995e-02 , 1.8219800000000000e-01 , 9.7897999999999996e-01 -6.3963319503687694e+00 , 8.7326136975342350e-01 , 1.6678541600000001e+00 , 5.2012899999999995e-01 , -7.8153500000000001e-02 , -8.5050400000000004e-01 -6.4588152764668356e+00 , 8.5848596597407623e-01 , 1.7290508800000000e+00 , 6.7608400000000002e-01 , -1.4337100000000000e-01 , -7.2274200000000000e-01 -6.4551346702857328e+00 , 8.6910481235490433e-01 , 1.8125857599999999e+00 , 9.9045600000000000e-01 , 2.3619200000000000e-02 , -1.3578699999999999e-01 -6.6555507645192362e+00 , 8.0117527554250345e-01 , 1.8344195200000000e+00 , 9.9909099999999995e-01 , -3.4738900000000003e-02 , 2.4701500000000001e-02 -6.4244662617604158e+00 , 8.9837295438756959e-01 , 1.9829445200000000e+00 , 9.9589399999999995e-01 , 8.2104200000000002e-02 , 3.8129700000000002e-02 -6.4824229109337974e+00 , 8.8546016705277886e-01 , 2.0471764800000001e+00 , 9.8636800000000002e-01 , -1.3383100000000001e-03 , 1.6454900000000000e-01 -6.4255947722144704e+00 , 9.1615317545692321e-01 , 2.1399683999999999e+00 , 9.9222800000000000e-01 , 1.2103500000000000e-01 , 2.8887099999999999e-02 -6.4139938694566343e+00 , 9.2851973981745739e-01 , 2.2199631200000001e+00 , 9.8990699999999998e-01 , 1.1534999999999999e-01 , 8.2327800000000007e-02 -6.4398595197498052e+00 , 9.2802213222966379e-01 , 2.2915307199999999e+00 , 9.8489000000000004e-01 , 8.1200400000000006e-02 , 1.5296799999999999e-01 -6.3592813524332996e+00 , 9.6683621923416863e-01 , 2.3826274399999998e+00 , 9.9320500000000000e-01 , 9.3560400000000002e-02 , 6.9213700000000003e-02 -6.3725381836307884e+00 , 9.7022387254011200e-01 , 2.4550052000000000e+00 , 9.7325099999999998e-01 , 7.6841099999999996e-02 , -2.1651500000000001e-01 -6.4238752066465716e+00 , 9.5929062755991246e-01 , 2.5223254399999999e+00 , -8.5429800000000000e-01 , -1.7430500000000002e-02 , 5.1949199999999995e-01 -6.4930685120060048e+00 , 9.4308457310621630e-01 , 2.5884538400000001e+00 , 7.3752200000000001e-01 , 1.6442300000000000e-02 , -6.7512200000000000e-01 -6.6009663765020834e+00 , 9.1324659665898267e-01 , 2.6530898399999998e+00 , 5.6624399999999997e-01 , -9.6906900000000004e-02 , -8.1852100000000005e-01 -1.1263591508446002e+01 , -7.2685686328049925e-01 , 2.5012384000000001e+00 , -1.1973300000000001e-01 , 2.0921999999999999e-01 , 9.7051100000000001e-01 -1.1963406613067914e+01 , -9.5585947040832409e-01 , 2.6312477599999999e+00 , -8.2252000000000006e-02 , 1.8989600000000001e-01 , 9.7835300000000003e-01 -1.2857646414711416e+01 , -1.2508226734939050e+00 , 2.7810171200000000e+00 , 7.3486200000000002e-02 , -1.8223500000000001e-01 , -9.8050499999999996e-01 -1.4075324302127086e+01 , -1.6546645735564303e+00 , 2.9600811999999999e+00 , -5.1816000000000001e-02 , 1.8740899999999999e-01 , 9.8091399999999995e-01 -1.5517648722390422e+01 , -2.1310640174241522e+00 , 3.1853088000000001e+00 , -5.8709100000000000e-02 , 1.8080199999999999e-01 , 9.8176600000000003e-01 -1.7635610031731193e+01 , -2.8346607521912262e+00 , 3.4811056000000002e+00 , -6.4832899999999999e-02 , 1.7581700000000000e-01 , 9.8228599999999999e-01 -1.9964925840552741e+01 , -3.6030358851437265e+00 , 3.8641480000000001e+00 , -8.6268300000000006e-02 , 1.6912199999999999e-01 , 9.8181200000000002e-01 -2.3350650005450419e+01 , -4.7207277549307127e+00 , 4.3991863999999996e+00 , -6.0855100000000002e-02 , 1.9240800000000000e-01 , 9.7942600000000002e-01 -3.0601886433824145e+01 , -7.0772387956656804e+00 , 5.8920751999999998e+00 , -9.8592000000000002e-01 , -1.4929100000000001e-01 , 7.5323399999999999e-02 -3.0941441701629216e+01 , -7.1321379049647060e+00 , 6.4511167999999994e+00 , 8.4487800000000002e-01 , 3.1065300000000001e-01 , -4.3551699999999999e-01 -3.2602094709743476e+01 , -7.6250097048164314e+00 , 7.2048256000000004e+00 , -7.5961800000000002e-01 , 6.2204800000000005e-01 , 1.8983300000000000e-01 -3.2558246243507895e+01 , -7.5479448846662027e+00 , 7.7571592000000003e+00 , -6.4921099999999998e-01 , 7.3231500000000005e-01 , 2.0552200000000001e-01 -3.2524685546274746e+01 , -7.4739942772500072e+00 , 8.3118744000000007e+00 , -7.5119999999999998e-01 , 6.5993500000000005e-01 , 1.3583700000000001e-02 -3.2617075314365167e+01 , -7.4408342714569091e+00 , 8.8919864000000004e+00 , 7.6632500000000003e-01 , -6.4181299999999997e-01 , -2.8652400000000001e-02 -3.5397091078150993e+01 , -8.2789733807593500e+00 , 1.0046958399999999e+01 , -3.8342500000000002e-01 , 4.0910900000000000e-01 , 8.2801899999999995e-01 -3.5828732046252320e+01 , -8.3484198645620058e+00 , 1.0769300800000000e+01 , 4.0983700000000001e-01 , -4.1212199999999999e-01 , -8.1374999999999997e-01 -3.6816153629477988e+01 , -8.5924579944763781e+00 , 1.1650409600000000e+01 , -4.1347800000000001e-01 , 5.9128600000000003e-02 , 9.0859199999999996e-01 -2.9700871531471197e+01 , -6.2569884264674140e+00 , 1.0398010400000000e+01 , -6.2850200000000001e-01 , -5.5996699999999999e-01 , -5.3983599999999998e-01 -2.9784410175391958e+01 , -6.2241370190108061e+00 , 1.0948066400000002e+01 , 6.5545200000000003e-01 , 5.4519799999999996e-01 , 5.2263000000000004e-01 -2.4315394694570148e+01 , -4.4492919282326229e+00 , 9.7993032000000007e+00 , 9.9712900000000004e-01 , 2.7117400000000000e-02 , -7.0697499999999996e-02 -2.4962719443503062e+01 , -4.6027798939724214e+00 , 1.0440546400000001e+01 , 9.9159299999999995e-01 , -1.2874600000000000e-01 , 1.2975900000000000e-02 -2.4879835672286383e+01 , -4.5268365465290721e+00 , 1.0858064799999999e+01 , -9.3690499999999999e-01 , -3.4194799999999997e-01 , -7.2669600000000001e-02 -2.4546287904790876e+01 , -4.3743670188234898e+00 , 1.1185144800000000e+01 , -8.4833800000000004e-01 , -5.2708699999999997e-01 , -5.0009400000000002e-02 -2.3713063648195320e+01 , -4.0701869750589115e+00 , 1.1310163200000002e+01 , -7.7444400000000002e-01 , -5.6672100000000003e-01 , -2.8118199999999999e-01 -2.3429417568267997e+01 , -3.9351281677177239e+00 , 1.1630036000000000e+01 , 8.4559899999999999e-01 , 5.0837900000000003e-01 , 1.6283000000000000e-01 -2.4689957466949373e+01 , -4.2643839439929252e+00 , 1.2604880000000000e+01 , 6.5249900000000005e-01 , 7.5215699999999996e-01 , 9.2224700000000007e-02 -2.5311221793842044e+01 , -4.3966258088414003e+00 , 1.3351392000000001e+01 , 9.0048700000000004e-01 , 2.7334100000000000e-01 , 3.3824199999999999e-01 -2.2824918876395735e+01 , -3.6086713160577197e+00 , 1.2668215999999999e+01 , -9.0195599999999998e-01 , 2.1209200000000000e-01 , -3.7615399999999999e-01 -2.2648649071370333e+01 , -3.5075779842001378e+00 , 1.3021608000000001e+01 , 7.0417799999999997e-01 , -6.3237600000000005e-01 , 3.2285300000000000e-01 -2.2323320260197875e+01 , -3.3626744174354943e+00 , 1.3297312000000000e+01 , 6.6952199999999995e-01 , -5.7717900000000000e-01 , 4.6755099999999999e-01 -2.3522718831793838e+01 , -3.6583338093338851e+00 , 1.4383592000000000e+01 , -8.7303299999999995e-01 , 9.5655400000000008e-03 , 4.8756800000000000e-01 -2.3529983530652512e+01 , -3.6072735303772152e+00 , 1.4865216000000000e+01 , -8.9012999999999998e-01 , 1.8141100000000000e-02 , 4.5534599999999997e-01 -2.3572501962803923e+01 , -3.5636578113756228e+00 , 1.5375336000000001e+01 , 8.4507900000000002e-01 , 2.7525500000000003e-01 , -4.5834100000000000e-01 -3.2003198827151685e+01 , -5.8693394323134784e+00 , 2.0977191999999999e+01 , 2.0332900000000001e-01 , -3.6189500000000002e-01 , 9.0977399999999997e-01 -3.0058467303851284e+01 , -5.2507921791001877e+00 , 2.0459688000000000e+01 , 7.9068899999999998e-01 , 6.0483500000000001e-01 , 9.4787899999999994e-02 -2.9342708706515182e+01 , -4.9780018151584704e+00 , 2.0664671999999999e+01 , -9.5017300000000005e-01 , -2.7697599999999999e-02 , 3.1048900000000001e-01 -2.9726723283091637e+01 , -5.0077590599369284e+00 , 2.1595160000000000e+01 , -7.1953999999999996e-01 , -6.2966699999999998e-01 , 2.9288599999999998e-01 -2.9051179138965875e+01 , -4.7480398707317590e+00 , 2.1812624000000000e+01 , -7.6146800000000003e-01 , 2.1332499999999999e-01 , 6.1209400000000003e-01 -7.7637275852133518e+00 , 1.0411687134250469e+00 , 7.3940120000000009e+00 , -4.1984500000000002e-01 , -6.7079299999999997e-01 , -6.1136500000000005e-01 -7.7491341023699869e+00 , 1.0615452092479400e+00 , 7.5342248000000005e+00 , 4.6775200000000000e-01 , 5.0522800000000001e-01 , 7.2522600000000004e-01 -7.6238276494080930e+00 , 1.1103613324863635e+00 , 7.5810975999999997e+00 , 4.6775200000000000e-01 , 5.0522800000000001e-01 , 7.2522600000000004e-01 -7.5440219335025551e+00 , 1.1478251667376052e+00 , 7.6657223999999999e+00 , 4.0920299999999998e-01 , 2.5126700000000002e-01 , 8.7716499999999997e-01 -7.3358574483970349e+00 , 1.2164973391904548e+00 , 7.6301024000000002e+00 , 3.0956800000000001e-01 , 3.1112499999999998e-01 , 8.9853700000000003e-01 -7.1668935004747611e+00 , 1.2745350754257621e+00 , 7.6238519999999994e+00 , 6.0894800000000004e-01 , 2.9106700000000002e-01 , 7.3787599999999998e-01 -7.0721436069583028e+00 , 1.3143177829924899e+00 , 7.6851704000000005e+00 , -5.8550800000000003e-01 , -2.8098800000000002e-01 , -7.6041199999999998e-01 -7.0117868575553501e+00 , 1.3458235660538440e+00 , 7.7812248000000004e+00 , -8.3627700000000005e-01 , -4.2416199999999998e-01 , -3.4745799999999999e-01 -6.7888231078681498e+00 , 1.4152098124534251e+00 , 7.7038384000000004e+00 , -7.3591799999999996e-01 , -5.7378700000000005e-01 , -3.5943300000000000e-01 -6.9149084811026285e+00 , 1.4048485742416008e+00 , 8.0008104000000007e+00 , -9.4913400000000003e-01 , -3.1612500000000002e-02 , -3.1328000000000000e-01 -7.0659238652129854e+00 , 1.3906484423182257e+00 , 8.3420343999999993e+00 , 5.8126800000000001e-01 , 7.7170099999999997e-01 , 2.5807799999999997e-01 -6.7073201951361465e+00 , 1.4880055515213084e+00 , 8.1004943999999988e+00 , -7.1988500000000000e-01 , -5.3498000000000001e-01 , -4.4222299999999998e-01 -6.6784228622448580e+00 , 1.5138762288671010e+00 , 8.2385128000000005e+00 , 7.8560500000000000e-01 , 4.0780900000000002e-02 , 6.1738300000000002e-01 -6.6273755048932905e+00 , 1.5443721730731990e+00 , 8.3526631999999985e+00 , 8.8653599999999999e-01 , -1.2620200000000001e-01 , 4.4511400000000001e-01 -6.5164423283087753e+00 , 1.5868804893314159e+00 , 8.3923807999999998e+00 , -5.9579700000000002e-01 , -1.7871900000000000e-02 , -8.0293599999999998e-01 -5.7976716669496344e+00 , 1.7494697636883139e+00 , 7.6072224000000004e+00 , -4.7869299999999998e-01 , 2.8562199999999999e-01 , -8.3022499999999999e-01 -6.2346827199393831e+00 , 1.6836320869310788e+00 , 8.3803376000000007e+00 , 7.3701700000000003e-01 , 1.6435200000000000e-01 , -6.5558700000000003e-01 -6.0724775436517131e+00 , 1.7356012156892724e+00 , 8.3348791999999996e+00 , -2.9343600000000001e-02 , -3.1540400000000002e-01 , 9.4850400000000001e-01 -5.7634784162918447e+00 , 1.8116215920960126e+00 , 8.0612551999999997e+00 , 7.6429199999999997e-01 , 3.3534700000000001e-01 , 5.5081800000000003e-01 -5.5035768696847533e+00 , 1.8778624119859897e+00 , 7.8391527999999999e+00 , -7.5893999999999995e-01 , 3.8203900000000002e-01 , 5.2731099999999997e-01 -5.5180643073458704e+00 , 1.8946005090867015e+00 , 8.0412664000000014e+00 , -2.8616599999999998e-01 , 8.3876200000000001e-01 , 4.6323500000000001e-01 -5.7720800592982426e+00 , 1.8756124311652926e+00 , 8.6547416000000013e+00 , -1.0888100000000001e-01 , 1.3081400000000001e-01 , 9.8541000000000001e-01 -5.5981552092570013e+00 , 1.9260335633117662e+00 , 8.5674960000000002e+00 , -3.7157200000000001e-01 , -2.6309900000000003e-01 , 8.9034500000000005e-01 -5.4134480562671348e+00 , 1.9768783881931573e+00 , 8.4484159999999999e+00 , 1.8374499999999999e-01 , 4.4866299999999998e-01 , -8.7460800000000005e-01 -5.4376535847221810e+00 , 1.9986521091037399e+00 , 8.7092063999999993e+00 , 2.7876600000000001e-01 , 7.0733299999999999e-01 , -6.4959199999999995e-01 -5.2331279461942994e+00 , 2.0504202536465197e+00 , 8.5377936000000005e+00 , 5.5715300000000001e-01 , 4.2242099999999999e-01 , -7.1494100000000005e-01 -4.8744308206908151e+00 , 2.1183475186133034e+00 , 8.0342048000000013e+00 , -7.1443500000000004e-01 , -1.2950200000000000e-02 , -6.9958200000000004e-01 -4.8202399784365246e+00 , 2.1486986215961643e+00 , 8.1311224000000006e+00 , -3.8062200000000002e-01 , 3.3910499999999999e-01 , 8.6031100000000005e-01 -4.7160024318422673e+00 , 2.1834605828186788e+00 , 8.1233016000000013e+00 , -6.8285099999999999e-01 , -2.1946299999999999e-01 , -6.9681400000000004e-01 -4.9041856979584546e+00 , 2.1931524178030473e+00 , 8.7913040000000002e+00 , -8.9764100000000002e-01 , -2.6895999999999998e-01 , -3.4914400000000001e-01 -4.7195070381589925e+00 , 2.2368943586209253e+00 , 8.6106248000000001e+00 , -3.7852100000000000e-01 , 1.8170400000000000e-01 , 9.0758200000000000e-01 -4.5801256272347084e+00 , 2.2759938129159663e+00 , 8.5219752000000000e+00 , 1.1894500000000000e-01 , -8.4554900000000000e-01 , 5.2047900000000002e-01 -4.7447753563963797e+00 , 2.2987064449058954e+00 , 9.2390240000000006e+00 , -3.9921200000000001e-01 , -8.9966999999999997e-01 , -1.7670100000000000e-01 -4.4736301675296808e+00 , 2.3432001637669178e+00 , 8.7959320000000005e+00 , 1.5822000000000000e-01 , 1.9324299999999999e-02 , 9.8721499999999995e-01 -4.3792154467756976e+00 , 2.3803347946516564e+00 , 8.8283383999999998e+00 , 1.4020199999999999e-01 , 6.5063200000000002e-02 , 9.8798299999999994e-01 -4.2540608917711120e+00 , 2.4165708679085469e+00 , 8.7601352000000006e+00 , 5.5094900000000002e-01 , 3.6798599999999998e-01 , 7.4902800000000003e-01 -4.1928346170898116e+00 , 2.4523661538362287e+00 , 8.8983927999999999e+00 , -3.9898699999999998e-01 , -8.5494399999999998e-02 , -9.1296299999999997e-01 -4.0830951834679352e+00 , 2.4886191131390283e+00 , 8.8757207999999999e+00 , 4.4718500000000000e-01 , 6.7204200000000006e-02 , 8.9191299999999996e-01 -4.0061220552381034e+00 , 2.5260863474633122e+00 , 8.9714735999999995e+00 , -9.9349900000000002e-01 , -8.0940799999999993e-02 , -8.0046999999999993e-02 -3.7529740588437912e+00 , 2.5453479541653921e+00 , 8.3595375999999995e+00 , -4.7759900000000000e-01 , 2.3996500000000001e-01 , 8.4517200000000003e-01 -3.6614005608174653e+00 , 2.5767897716145924e+00 , 8.3590280000000003e+00 , -1.2907199999999999e-01 , 9.3927499999999997e-02 , 9.8717699999999997e-01 -3.5757981895015107e+00 , 2.6095035432104066e+00 , 8.3871912000000002e+00 , -5.2509600000000001e-01 , 1.7097499999999999e-01 , 8.3369099999999996e-01 -3.3494778027859820e+00 , 2.6103826265761958e+00 , 7.6897360000000008e+00 , -8.8006700000000004e-01 , -7.9440800000000006e-02 , 4.6815699999999999e-01 -3.2511255367948850e+00 , 2.6317637261944764e+00 , 7.5798703999999999e+00 , 6.8204600000000004e-01 , 1.6494800000000001e-01 , -7.1246399999999999e-01 -3.1750180579426037e+00 , 2.6585740865332559e+00 , 7.5807544000000000e+00 , 4.9929200000000001e-01 , 2.6683000000000001e-01 , 8.2432399999999995e-01 -3.1103238334184491e+00 , 2.6895433720835658e+00 , 7.6521504000000000e+00 , -6.5690099999999996e-01 , -2.0138500000000001e-01 , -7.2658500000000004e-01 -3.0498561753352647e+00 , 2.7251036203583667e+00 , 7.7841263999999999e+00 , -5.8663399999999999e-01 , -7.1987400000000001e-01 , -3.7100200000000000e-01 -2.9693585431045935e+00 , 2.7503809941962887e+00 , 7.7606536000000004e+00 , -5.4838799999999999e-01 , -7.7509399999999995e-01 , -3.1384800000000002e-01 -2.8899078213673937e+00 , 2.7762939871046131e+00 , 7.7458232000000002e+00 , 4.5944499999999999e-01 , 7.9434700000000003e-01 , 3.9739500000000000e-01 -2.8630642591867854e+00 , 2.8595362170816037e+00 , 8.4009712000000007e+00 , -9.4646300000000005e-01 , -2.8078599999999999e-02 , 3.2158900000000001e-01 -2.7517865428930381e+00 , 2.8568767758891260e+00 , 8.0320000000000000e+00 , 6.8100700000000000e-02 , -9.9747200000000003e-01 , -2.0307499999999999e-02 -2.6679860673018001e+00 , 2.8811726514269185e+00 , 7.9924072000000006e+00 , 6.7812499999999998e-01 , 4.7546899999999997e-01 , 5.6042499999999995e-01 -2.5900935937798701e+00 , 2.9202488889778229e+00 , 8.0959496000000009e+00 , -7.0899999999999996e-01 , -6.4797300000000002e-01 , 2.7829799999999999e-01 -2.5213050281922187e+00 , 3.0939111947399924e+00 , 9.4280960000000000e+00 , 1.1983000000000001e-01 , -7.2614800000000002e-01 , 6.7701599999999995e-01 -2.4229924374715508e+00 , 2.9774990864335247e+00 , 8.0914776000000010e+00 , -7.6178199999999996e-01 , -4.6614299999999997e-01 , -4.4988800000000001e-01 -2.3167757673324809e+00 , 3.1358714345306091e+00 , 9.1605664000000004e+00 , 1.4960499999999999e-01 , 6.0208200000000001e-01 , -7.8429300000000002e-01 -2.2138075280179246e+00 , 3.1747628421798613e+00 , 9.1945952000000002e+00 , 4.2619800000000002e-01 , -6.4833099999999999e-01 , 6.3088999999999995e-01 -1.9570532627859476e+00 , 3.5782370661643066e+00 , 1.1985684800000001e+01 , -9.6718999999999999e-01 , 2.5352599999999997e-01 , -1.6381000000000000e-02 -2.1102363317445518e+00 , 3.0537574911816709e+00 , 7.7971576000000002e+00 , -3.9621299999999998e-02 , -5.4245399999999999e-01 , 8.3914999999999995e-01 -2.0272651561798227e+00 , 3.0879235905389537e+00 , 7.8383624000000003e+00 , 2.6205000000000001e-01 , -5.4771400000000003e-01 , 7.9456899999999997e-01 -1.7846515151450273e+00 , 3.3446099381623853e+00 , 9.3715823999999994e+00 , -8.5536900000000005e-01 , 4.5995000000000003e-01 , 2.3830399999999999e-01 -4.6699259938209998e+00 , 1.3762558551055213e+00 , 1.3874971999999999e+00 , -2.2269900000000001e-01 , 1.8083399999999999e-01 , 9.5796899999999996e-01 -4.7220731066698693e+00 , 1.3589182901159589e+00 , 1.4127244800000001e+00 , -1.6551399999999999e-01 , 2.2429199999999999e-01 , 9.6036400000000000e-01 -4.7909854804978664e+00 , 1.3346754219830335e+00 , 1.4283140799999998e+00 , -7.4106199999999997e-02 , 1.6133500000000001e-01 , 9.8411400000000004e-01 -4.8755048718848437e+00 , 1.3026451601786886e+00 , 1.4349513599999999e+00 , -2.5510600000000001e-02 , 1.6748199999999999e-01 , 9.8554500000000000e-01 -4.9607735615112976e+00 , 1.2711063574146708e+00 , 1.4441428800000000e+00 , -1.0261000000000001e-01 , 2.1572800000000000e-01 , 9.7104699999999999e-01 -5.0299320736669966e+00 , 1.2471150029466544e+00 , 1.4663354399999999e+00 , -1.2430500000000000e-01 , 1.5648699999999999e-01 , 9.7982700000000000e-01 -5.1156373972443951e+00 , 1.2155161489305137e+00 , 1.4806135999999999e+00 , -8.2643099999999997e-02 , 1.7516000000000001e-01 , 9.8106499999999996e-01 -5.2109774669460451e+00 , 1.1809359959892012e+00 , 1.4926880000000000e+00 , -8.2968500000000001e-02 , 1.5840399999999999e-01 , 9.8388200000000003e-01 -5.2981159604130639e+00 , 1.1503810780953803e+00 , 1.5124781600000001e+00 , -6.2640000000000001e-02 , 1.6905300000000001e-01 , 9.8361500000000002e-01 -5.4026210947730489e+00 , 1.1114722572517506e+00 , 1.5261000800000000e+00 , -9.7762399999999999e-02 , 1.7679200000000000e-01 , 9.7938099999999995e-01 -5.4989729922174071e+00 , 1.0776065650994857e+00 , 1.5472307999999999e+00 , -8.3912799999999996e-02 , 1.8683400000000000e-01 , 9.7880100000000003e-01 -5.6125502084580763e+00 , 1.0356129991658793e+00 , 1.5633071199999999e+00 , -6.7216700000000004e-02 , 1.7496400000000001e-01 , 9.8227799999999998e-01 -5.7277838725626715e+00 , 9.9429478060518406e-01 , 1.5830743999999999e+00 , -5.5736000000000001e-02 , 1.6426800000000000e-01 , 9.8484000000000005e-01 -5.8601239849127857e+00 , 9.4506865706128473e-01 , 1.5989000799999999e+00 , -6.8102800000000005e-02 , 1.7158000000000001e-01 , 9.8281300000000005e-01 -5.9842112813406372e+00 , 8.9996349700585121e-01 , 1.6228440000000000e+00 , -7.9472699999999993e-02 , 1.8775700000000001e-01 , 9.7899499999999995e-01 -6.1186280843300915e+00 , 8.5138118149892805e-01 , 1.6475481599999999e+00 , -6.4314700000000002e-02 , 1.7484400000000000e-01 , 9.8249299999999995e-01 -6.2797225831482351e+00 , 7.9201351705597345e-01 , 1.6666124000000000e+00 , -1.1477999999999999e-01 , 1.9814499999999999e-01 , 9.7342899999999999e-01 -6.4335430407410170e+00 , 7.3685910831517476e-01 , 1.6944282399999999e+00 , 5.3995800000000005e-01 , -8.5627800000000004e-02 , -8.3732499999999999e-01 -6.4947131724025891e+00 , 7.2039556263066551e-01 , 1.7575281600000001e+00 , -7.8894500000000001e-01 , 1.6434099999999999e-01 , 5.9207900000000002e-01 -6.5092387258757389e+00 , 7.2296863475143214e-01 , 1.8366388800000000e+00 , -9.5137700000000003e-01 , 1.8937200000000001e-01 , 2.4294099999999999e-01 -6.4850583224918159e+00 , 7.4205968005834833e-01 , 1.9262686800000000e+00 , 9.9684099999999998e-01 , 7.9293900000000000e-02 , 4.5481999999999996e-03 -6.4879202150075370e+00 , 7.4977075851135710e-01 , 2.0073249176000001e+00 , 9.9618200000000001e-01 , 7.2628300000000007e-02 , 4.8431900000000000e-02 -6.4983977337608749e+00 , 7.5446264551483710e-01 , 2.0855227360000002e+00 , 9.9626499999999996e-01 , 4.7042599999999997e-02 , 7.2402999999999995e-02 -6.4501230870936368e+00 , 7.8227351966206982e-01 , 2.1763912799999998e+00 , 9.9623899999999999e-01 , 6.2120200000000000e-02 , 6.0402999999999998e-02 -6.4672107354069608e+00 , 7.8393339838056741e-01 , 2.2515042400000000e+00 , 9.9642299999999995e-01 , 8.3237000000000005e-02 , -1.4600200000000001e-02 -6.4832654689671267e+00 , 7.8671033541119861e-01 , 2.3266900000000001e+00 , 9.9099599999999999e-01 , 9.7919699999999998e-02 , 9.1316300000000003e-02 -6.4016535526898748e+00 , 8.2774491012027518e-01 , 2.4180602400000000e+00 , 9.9162499999999998e-01 , 1.2638500000000000e-01 , 2.6575900000000000e-02 -6.4432850387165432e+00 , 8.1878113079170278e-01 , 2.4878900000000002e+00 , -9.4048799999999999e-01 , -6.1595400000000002e-02 , 3.3419800000000000e-01 -6.4742399031268443e+00 , 8.1500687923942450e-01 , 2.5600940799999998e+00 , -7.9271899999999995e-01 , 7.3241299999999995e-02 , 6.0517200000000004e-01 -6.5430585759590496e+00 , 7.9619934030383299e-01 , 2.6289628800000000e+00 , -7.8053700000000004e-01 , 7.7246099999999998e-02 , 6.2031899999999995e-01 -1.0980022757461439e+01 , -9.1281281577704210e-01 , 2.4611089599999998e+00 , -1.2783900000000001e-01 , 2.2860200000000000e-01 , 9.6509000000000000e-01 -1.1488687897728633e+01 , -1.0927424664470657e+00 , 2.5936184799999999e+00 , -1.1451900000000000e-01 , 2.1537600000000001e-01 , 9.6979300000000002e-01 -1.2315942783258086e+01 , -1.3932300375502424e+00 , 2.7333175199999999e+00 , -7.5183200000000006e-02 , 1.8603200000000000e-01 , 9.7966299999999995e-01 -1.3259475942985906e+01 , -1.7343783902574450e+00 , 2.9015364799999999e+00 , 6.7898200000000006e-02 , -1.8774800000000000e-01 , -9.7986799999999996e-01 -1.4579669589060817e+01 , -2.2152138992617560e+00 , 3.1050520000000001e+00 , -5.3104400000000003e-02 , 1.8000099999999999e-01 , 9.8223199999999999e-01 -1.6258270178237431e+01 , -2.8275093880007809e+00 , 3.3650520000000004e+00 , -5.3976499999999997e-02 , 1.8147500000000000e-01 , 9.8191300000000004e-01 -1.8691958782817117e+01 , -3.7171125366817881e+00 , 3.7166968000000002e+00 , -7.1617100000000003e-02 , 1.7440900000000001e-01 , 9.8206599999999999e-01 -2.0936069351408257e+01 , -4.5252985038561322e+00 , 4.1475271999999999e+00 , -8.3789600000000006e-02 , 1.9009499999999999e-01 , 9.7818400000000005e-01 -2.5204897551262064e+01 , -6.0806862629343623e+00 , 4.8166840000000004e+00 , -7.1264300000000003e-02 , 1.9927400000000001e-01 , 9.7734900000000002e-01 -3.1004877657393347e+01 , -8.1282225008401241e+00 , 6.3217096000000002e+00 , 5.8791300000000002e-01 , -1.9703000000000001e-01 , -7.8456199999999998e-01 -3.1256962829556009e+01 , -8.1630756509376656e+00 , 6.8879896000000000e+00 , -6.9970200000000005e-01 , 2.8310700000000000e-01 , 6.5594799999999998e-01 -3.2351144055155963e+01 , -8.5034726766952140e+00 , 7.5924024000000001e+00 , 7.7468899999999996e-01 , -6.0123599999999999e-01 , -1.9588900000000001e-01 -3.2070457800301043e+01 , -8.3411365118042067e+00 , 8.1066615999999989e+00 , -8.0854400000000004e-01 , 5.8658800000000000e-01 , -4.6599000000000002e-02 -3.2022731967566088e+01 , -8.2632659441566361e+00 , 8.6566760000000009e+00 , -7.9620700000000000e-01 , 6.0405399999999998e-01 , 3.4251700000000003e-02 -3.2436001394952797e+01 , -8.3504437352932541e+00 , 9.3031088000000004e+00 , 8.1322499999999998e-01 , -5.7908499999999996e-01 , -5.7668400000000002e-02 -4.3222512543960590e+01 , -1.2136287607845134e+01 , 1.2319243999999999e+01 , -5.7669000000000004e-01 , -2.4719099999999999e-01 , 7.7866899999999994e-01 -4.4505168143703372e+01 , -1.2505543818128009e+01 , 1.3416496000000000e+01 , -5.7669000000000004e-01 , -2.4719099999999999e-01 , 7.7866899999999994e-01 -3.6535355844599380e+01 , -9.6089786375994102e+00 , 1.2115892800000001e+01 , 4.6222999999999997e-01 , -3.8888299999999998e-01 , -7.9693999999999998e-01 -2.4423694019612348e+01 , -5.2934511560583966e+00 , 9.3325095999999998e+00 , -8.8488100000000003e-01 , 3.3195799999999998e-01 , 3.2678800000000002e-01 -2.4568068231969587e+01 , -5.2973991244254490e+00 , 9.8074463999999999e+00 , -9.2921299999999996e-01 , 2.8397899999999998e-01 , 2.3647199999999999e-01 -2.4704352982177859e+01 , -5.2965138783196579e+00 , 1.0288987200000001e+01 , 9.6835400000000005e-01 , 1.6844899999999999e-02 , -2.4901100000000001e-01 -2.4906495176736552e+01 , -5.3184639641280782e+00 , 1.0802892800000000e+01 , 9.8858199999999996e-01 , -6.5178500000000000e-02 , -1.3585700000000001e-01 -2.5907137317747377e+01 , -5.6109696999235901e+00 , 1.1620104000000000e+01 , -9.1381400000000002e-01 , 4.0207100000000001e-01 , 5.7296800000000002e-02 -2.5223883741302306e+01 , -5.3278762086472566e+00 , 1.1835581600000001e+01 , 9.9156400000000000e-01 , 1.2200700000000000e-01 , -4.3771900000000002e-02 -3.2756116127453524e+01 , -7.8168422519782368e+00 , 1.5355784000000000e+01 , -9.6122500000000000e-01 , -2.5494899999999998e-01 , 1.0511000000000000e-01 -2.5072551261125533e+01 , -5.1739123036969445e+00 , 1.2715328000000001e+01 , 9.8324500000000004e-01 , 1.5090100000000001e-01 , -1.0226800000000000e-01 -2.9967614020030986e+01 , -6.7510022610883951e+00 , 1.5381680000000001e+01 , -5.9443999999999997e-01 , -7.5183100000000003e-01 , 2.8529100000000002e-01 -3.0068821875837770e+01 , -6.7205115804959004e+00 , 1.6018160000000002e+01 , -6.3790300000000000e-01 , -7.1341399999999999e-01 , 2.9003400000000001e-01 -2.8168678823632646e+01 , -6.0324401099954965e+00 , 1.5686504000000001e+01 , -6.6921699999999995e-01 , -3.5707400000000000e-01 , 6.5164999999999995e-01 -2.4898916616556761e+01 , -4.9067874702623229e+00 , 1.4578488000000000e+01 , 8.8480000000000003e-01 , 4.6166699999999999e-01 , 6.3191100000000000e-02 -2.7112618819146828e+01 , -5.5670581900916272e+00 , 1.6263911999999998e+01 , -6.6921699999999995e-01 , -3.5707400000000000e-01 , 6.5164999999999995e-01 -3.1754770548284295e+01 , -6.9958129851051059e+00 , 1.9412303999999999e+01 , -5.7917700000000005e-01 , -7.4101200000000000e-01 , 3.3978700000000001e-01 -2.8206359852099521e+01 , -5.7932583339721591e+00 , 1.8030560000000001e+01 , 7.1420099999999997e-01 , 5.5915499999999996e-01 , -4.2102600000000001e-01 -7.6986856238907375e+00 , 8.9812022457812679e-01 , 7.6398472000000002e+00 , -3.8135599999999997e-01 , -5.2866700000000000e-01 , -7.5833899999999999e-01 -7.4683115436231073e+00 , 9.8097718294882230e-01 , 7.5908736000000001e+00 , 2.6138099999999997e-01 , 2.0427600000000001e-01 , 9.4337199999999999e-01 -7.3448350739291755e+00 , 1.0327534740133972e+00 , 7.6317976000000005e+00 , 1.8764700000000001e-01 , 2.1529000000000001e-01 , 9.5835199999999998e-01 -7.2281779574497911e+00 , 1.0818266796750946e+00 , 7.6765384000000001e+00 , 2.9846800000000001e-01 , 1.2831000000000001e-01 , 9.4575600000000004e-01 -7.0606518365362021e+00 , 1.1446021064251037e+00 , 7.6677711999999998e+00 , 5.9133199999999997e-01 , 2.7336700000000003e-01 , 7.5868100000000005e-01 -7.0524343109604759e+00 , 1.1641487679746443e+00 , 7.8157424000000004e+00 , 8.0043799999999998e-01 , 5.8424500000000001e-01 , 1.3400500000000001e-01 -7.1867893332853052e+00 , 1.1455527072193483e+00 , 8.1210552000000007e+00 , -8.8035799999999997e-01 , -4.7422100000000000e-01 , 9.2173900000000007e-03 -7.2026979825438575e+00 , 1.1597817004503663e+00 , 8.3110216000000001e+00 , 3.2800400000000002e-01 , -1.2876400000000000e-02 , 9.4458900000000001e-01 -7.0923491924689497e+00 , 1.2081493121958740e+00 , 8.3641344000000011e+00 , 4.5620500000000003e-01 , -3.9704899999999999e-01 , 7.9638500000000001e-01 -6.9484342474936307e+00 , 1.2644309112601368e+00 , 8.3756368000000005e+00 , 4.3103599999999999e-02 , -5.0547000000000002e-02 , 9.9779099999999998e-01 -6.7331119731013347e+00 , 1.3373186818017659e+00 , 8.2961808000000019e+00 , 7.4774300000000005e-01 , 4.1050900000000001e-01 , 5.2188500000000004e-01 -6.8358600030263590e+00 , 1.3324668505468340e+00 , 8.6049775999999998e+00 , 2.1607299999999999e-01 , -4.3388399999999999e-01 , 8.7467499999999998e-01 -6.6592435031316528e+00 , 1.3951716907566871e+00 , 8.5675792000000008e+00 , 4.0249499999999999e-01 , 3.8992800000000000e-01 , 8.2822300000000004e-01 -6.1418407231629635e+00 , 1.5374844061431610e+00 , 8.0619936000000010e+00 , -7.0664899999999997e-01 , 5.1743300000000003e-01 , 4.8260799999999998e-01 -5.9963401488427639e+00 , 1.5901762328385041e+00 , 8.0342775999999994e+00 , 3.4640300000000002e-01 , 2.0971200000000001e-01 , 9.1434499999999996e-01 -5.8931243707146592e+00 , 1.6320948038424152e+00 , 8.0621912000000009e+00 , -3.1984800000000002e-01 , -1.2863700000000000e-01 , -9.3869599999999997e-01 -5.5845470560964898e+00 , 1.7198542615679531e+00 , 7.7783959999999999e+00 , 7.8632400000000002e-01 , 5.6288300000000002e-01 , 2.5467200000000001e-01 -5.6375758007302217e+00 , 1.7273778169834713e+00 , 8.0325927999999998e+00 , -8.5950499999999996e-01 , -5.0933799999999996e-01 , -4.2722599999999999e-02 -5.6881508477319098e+00 , 1.7363267914113849e+00 , 8.2986143999999999e+00 , -7.5871100000000002e-01 , 4.1558499999999998e-01 , -5.0164399999999998e-01 -5.5567809139796474e+00 , 1.7838554228615557e+00 , 8.2745904000000010e+00 , -9.0830000000000000e-01 , 3.0972000000000000e-01 , -2.8118500000000002e-01 -5.5252092196695486e+00 , 1.8119259981075191e+00 , 8.4177256000000007e+00 , -2.2646900000000000e-01 , -7.5138899999999997e-01 , 6.1978000000000000e-01 -5.4088560609210354e+00 , 1.8558877011077830e+00 , 8.4161032000000002e+00 , -2.0102600000000001e-01 , -4.1448099999999999e-01 , 8.8757699999999995e-01 -5.3567251689769897e+00 , 1.8875933742592659e+00 , 8.5307215999999997e+00 , 5.2857699999999996e-01 , 5.2551199999999998e-01 , -6.6666599999999998e-01 -5.1884364579690194e+00 , 1.9401014339841827e+00 , 8.4233936000000007e+00 , -2.5413799999999998e-01 , -1.5081700000000001e-01 , 9.5533699999999999e-01 -5.0699789198108913e+00 , 1.9838700116873222e+00 , 8.4045591999999996e+00 , 3.0667899999999998e-01 , 3.1323800000000002e-01 , -8.9879399999999998e-01 -4.9579913547785726e+00 , 2.0255597359585638e+00 , 8.3925783999999997e+00 , 1.4237600000000000e-01 , 3.6476799999999998e-01 , -9.2014799999999997e-01 -4.8973032616480729e+00 , 2.0587524372362571e+00 , 8.4916696000000016e+00 , -3.0131100000000000e-01 , 6.9567000000000001e-01 , -6.5211600000000003e-01 -4.6860610940098022e+00 , 2.1129781614076362e+00 , 8.2466872000000002e+00 , -6.8877900000000003e-01 , -2.4708900000000000e-01 , -6.8156499999999998e-01 -4.8562288519855121e+00 , 2.1180492399570929e+00 , 8.8984448000000000e+00 , -8.3638400000000002e-01 , -7.4173699999999995e-02 , 5.4310199999999997e-01 -4.5404503456618990e+00 , 2.1827555536943790e+00 , 8.3774879999999996e+00 , 4.2190800000000001e-01 , -8.7577799999999995e-01 , 2.3453399999999999e-01 -4.5167029818987707e+00 , 2.2134255998041459e+00 , 8.5773448000000005e+00 , -4.7580200000000000e-01 , 8.4031999999999996e-01 , -2.5975900000000002e-01 -4.4947230066795889e+00 , 2.2459511993430343e+00 , 8.7973360000000014e+00 , 1.5923899999999999e-01 , -1.8346799999999999e-01 , 9.7004299999999999e-01 -4.3852649684956582e+00 , 2.2856843824596682e+00 , 8.7814656000000006e+00 , 1.4171700000000001e-01 , -4.7993099999999997e-02 , 9.8874300000000004e-01 -4.2830974090925871e+00 , 2.3243688149274475e+00 , 8.7830256000000002e+00 , 4.0312599999999998e-01 , 1.5117500000000000e-01 , 9.0257200000000004e-01 -4.1812067563550865e+00 , 2.3636764589971229e+00 , 8.7824536000000002e+00 , 1.9213400000000000e-01 , -2.6104300000000003e-01 , 9.4601299999999999e-01 -4.2002408273305072e+00 , 2.4013296949887808e+00 , 9.2000343999999998e+00 , -9.0546300000000002e-01 , -3.4884999999999999e-01 , 2.4174399999999999e-01 -4.0086414190239772e+00 , 2.4397421484099913e+00 , 8.8860168000000002e+00 , -1.4047899999999999e-01 , -1.0410999999999999e-01 , -9.8459500000000000e-01 -3.8055256159610478e+00 , 2.4731957770438795e+00 , 8.4764128000000003e+00 , 7.3396600000000001e-01 , 2.2047299999999998e-03 , -6.7918299999999998e-01 -3.6816873682640932e+00 , 2.5062362448399953e+00 , 8.3452064000000004e+00 , -1.2907199999999999e-01 , 9.3927600000000000e-02 , 9.8717699999999997e-01 -3.5826706358650564e+00 , 2.5391139418917046e+00 , 8.3027952000000003e+00 , -4.1013200000000000e-01 , 2.8189700000000001e-01 , 8.6736700000000000e-01 -3.3842291256740200e+00 , 2.5549527821494529e+00 , 7.7487975999999996e+00 , 9.8643000000000003e-01 , -6.9922100000000001e-02 , -1.4854999999999999e-01 -3.2772093884693936e+00 , 2.5792024616763709e+00 , 7.5986112000000006e+00 , 7.0025800000000005e-01 , 1.4033599999999999e-01 , -6.9996000000000003e-01 -3.2059296504619823e+00 , 2.6089991538716544e+00 , 7.6206176000000001e+00 , -6.3119300000000000e-01 , -3.7564999999999998e-01 , 6.7858900000000000e-01 -3.3785730528870452e+00 , 2.7234102273243943e+00 , 9.2846592000000001e+00 , 4.1414099999999998e-01 , -8.1110000000000004e-01 , 4.1304299999999999e-01 -3.0864147669147663e+00 , 2.6806505902672337e+00 , 7.8558760000000003e+00 , -3.7964999999999999e-01 , -6.8385799999999997e-01 , -6.2305999999999995e-01 -3.0020948595441719e+00 , 2.7073518583460046e+00 , 7.8123104000000003e+00 , -6.0558900000000004e-01 , -6.5826600000000002e-01 , -4.4715500000000002e-01 -2.9341137220375773e+00 , 2.7440663364421107e+00 , 7.9115264000000005e+00 , -4.8507099999999997e-01 , -7.3071100000000000e-01 , -4.8038399999999998e-01 -2.9535601362972916e+00 , 2.8657983583320226e+00 , 9.1048743999999999e+00 , 2.1747300000000000e-01 , -9.2889500000000003e-01 , 2.9976599999999998e-01 -2.7882238883184782e+00 , 2.8213871288031163e+00 , 8.1060480000000013e+00 , -9.5691899999999996e-01 , 2.8370200000000001e-01 , -6.1804400000000002e-02 -2.7011972675874389e+00 , 2.8439933476038943e+00 , 8.0152248000000004e+00 , 1.9914599999999999e-01 , 8.9072399999999996e-01 , 4.0859899999999999e-01 -2.6540155463602737e+00 , 2.9687954394040834e+00 , 8.9987944000000013e+00 , -9.1134999999999999e-01 , 5.4739599999999999e-02 , -4.0797600000000001e-01 -2.5635276741181920e+00 , 3.0463086580916636e+00 , 9.4011080000000007e+00 , 3.3744600000000002e-01 , -6.9589900000000005e-01 , 6.3392099999999996e-01 -2.4584832471545330e+00 , 2.9838094897764442e+00 , 8.4465856000000006e+00 , 4.6354800000000002e-01 , -8.8178900000000004e-01 , -8.7014099999999997e-02 -2.3747405612896957e+00 , 2.9834887938493977e+00 , 8.1530768000000009e+00 , -8.8207500000000005e-01 , -2.5827299999999997e-01 , -3.9400400000000002e-01 -2.2605687256925706e+00 , 3.1348345505356363e+00 , 9.1487103999999988e+00 , -1.2027800000000000e-01 , -6.2033499999999997e-01 , 7.7505999999999997e-01 -2.1310686946876247e+00 , 3.2494834101567927e+00 , 9.7480624000000002e+00 , 6.0803599999999999e-02 , -4.7365099999999999e-01 , 8.7861100000000003e-01 -2.1456971729114023e+00 , 3.0341410499616277e+00 , 7.8127576000000003e+00 , -1.4939700000000000e-01 , -5.0641199999999997e-01 , 8.4925099999999998e-01 -2.0651468546171219e+00 , 3.0673525918150819e+00 , 7.8339319999999999e+00 , 2.0236899999999999e-01 , 1.1196000000000000e-01 , 9.7288799999999998e-01 -1.5792643504864279e+00 , 3.7030091299979828e+00 , 1.1992028800000002e+01 , -9.8330099999999998e-01 , 5.3381100000000001e-02 , -1.7398200000000000e-01 -1.7425471965443544e+00 , 3.3443519589539372e+00 , 9.2611656000000000e+00 , -8.8685499999999995e-01 , 3.2577699999999998e-01 , -3.2765400000000000e-01 -4.6692220577326857e+00 , 1.3105763880499528e+00 , 1.4092092800000000e+00 , -1.8047099999999999e-01 , 2.3270299999999999e-01 , 9.5565699999999998e-01 -4.7281768284554921e+00 , 1.2887612423887085e+00 , 1.4294320800000000e+00 , 1.5912799999999999e-01 , -2.2192899999999999e-01 , -9.6199100000000004e-01 -4.8117374327845237e+00 , 1.2544461546002865e+00 , 1.4350387199999999e+00 , 5.9798700000000003e-02 , -1.6217699999999999e-01 , -9.8494800000000005e-01 -4.8880998913955160e+00 , 1.2241793113872188e+00 , 1.4486887200000000e+00 , -5.4531299999999998e-02 , 2.1453700000000001e-01 , 9.7519199999999995e-01 -4.9642102838904325e+00 , 1.1943707249942057e+00 , 1.4645653599999999e+00 , -8.4527800000000000e-02 , 1.9797300000000001e-01 , 9.7655599999999998e-01 -5.0489466277174753e+00 , 1.1604849788329477e+00 , 1.4778118400000000e+00 , -1.0332600000000000e-01 , 2.0739199999999999e-01 , 9.7278600000000004e-01 -5.1265196743385806e+00 , 1.1305802607222575e+00 , 1.4987979999999999e+00 , -4.9303399999999997e-02 , 1.8115200000000001e-01 , 9.8221899999999995e-01 -5.2294192027764055e+00 , 1.0887036979722746e+00 , 1.5079250399999999e+00 , -5.4820300000000002e-02 , 1.9440399999999999e-01 , 9.7938800000000004e-01 -5.3152534625458880e+00 , 1.0553694676343031e+00 , 1.5294187200000000e+00 , -6.8721199999999996e-02 , 1.9068299999999999e-01 , 9.7924299999999997e-01 -5.4184740524983592e+00 , 1.0147358664379542e+00 , 1.5447420800000000e+00 , -8.0989500000000006e-02 , 1.9433800000000001e-01 , 9.7758599999999996e-01 -5.5134611180727262e+00 , 9.7708109472903493e-01 , 1.5678841600000000e+00 , -5.8923900000000001e-02 , 1.9504900000000000e-01 , 9.7902199999999995e-01 -5.6355315265419605e+00 , 9.2794856156419359e-01 , 1.5819470400000000e+00 , 4.2743600000000000e-02 , -1.7335000000000000e-01 , -9.8393200000000003e-01 -5.7581873214953667e+00 , 8.7959260660156291e-01 , 1.5999806400000001e+00 , -6.5186200000000000e-02 , 1.6392499999999999e-01 , 9.8431700000000000e-01 -5.8803337580538795e+00 , 8.3102728434074313e-01 , 1.6221648799999999e+00 , -6.3622300000000007e-02 , 1.8509600000000001e-01 , 9.8065899999999995e-01 -6.0127798191915609e+00 , 7.7792820837596177e-01 , 1.6451114400000000e+00 , -8.2428699999999994e-02 , 1.8534600000000001e-01 , 9.7921000000000002e-01 -6.1447300127412507e+00 , 7.2570487528165128e-01 , 1.6723064000000001e+00 , -5.5687899999999999e-02 , 1.9127800000000000e-01 , 9.7995500000000002e-01 -6.3053552665551988e+00 , 6.6168974637664468e-01 , 1.6945218399999999e+00 , -1.2271500000000000e-01 , 2.2650200000000001e-01 , 9.6624900000000002e-01 -6.4480012074984394e+00 , 6.0711403939764463e-01 , 1.7281668800000001e+00 , -4.9900800000000001e-01 , 2.4780900000000000e-01 , 8.3041100000000001e-01 -6.5349340571818120e+00 , 5.7642193172925138e-01 , 1.7840939199999999e+00 , -9.3899999999999995e-01 , 3.0184400000000000e-02 , 3.4259000000000001e-01 -6.5125871064781542e+00 , 5.9479164932338668e-01 , 1.8757990400000000e+00 , 9.8019599999999996e-01 , -7.2573100000000001e-02 , -1.8425400000000000e-01 -6.5345652086412054e+00 , 5.9352721976407019e-01 , 1.9532684320000000e+00 , 9.9855700000000003e-01 , 5.3709100000000003e-02 , 8.7660900000000006e-05 -6.5179716433531265e+00 , 6.0968874169210308e-01 , 2.0404442480000000e+00 , 9.9844500000000003e-01 , 5.4836500000000003e-02 , -1.0059500000000001e-02 -6.5272674948200811e+00 , 6.1466105755338218e-01 , 2.1198319200000002e+00 , 9.9793600000000005e-01 , 4.9586199999999997e-02 , 4.0798599999999997e-02 -6.5077305727505932e+00 , 6.3167971031001313e-01 , 2.2054135200000000e+00 , 9.9685800000000002e-01 , 6.7912600000000004e-02 , 4.0781999999999999e-02 -6.5054107048332570e+00 , 6.4061126005494096e-01 , 2.2861424800000001e+00 , 9.9527299999999996e-01 , 6.8584900000000004e-02 , 6.8761900000000001e-02 -6.5116586539824981e+00 , 6.4664235631917699e-01 , 2.3648465600000002e+00 , 9.9361400000000000e-01 , 6.5687999999999996e-02 , 9.1741000000000003e-02 -6.4586390078842655e+00 , 6.7713112419093835e-01 , 2.4521441600000000e+00 , 9.9783400000000000e-01 , 6.5777699999999995e-02 , 6.0796099999999996e-04 -6.4809912067158875e+00 , 6.7632454264413688e-01 , 2.5266767999999997e+00 , -9.4671000000000005e-01 , -9.8899499999999998e-03 , 3.2193600000000000e-01 -6.5106430693821045e+00 , 6.7086421534773777e-01 , 2.6007840799999999e+00 , -8.7241500000000005e-01 , 7.3184000000000001e-03 , 4.8871199999999998e-01 -6.5875710428277605e+00 , 6.4665446109982283e-01 , 2.6709757600000001e+00 , -8.0994999999999995e-01 , -5.8640400000000002e-02 , 5.8355999999999997e-01 -1.1025686629587616e+01 , -1.2052949752182696e+00 , 2.5581149600000002e+00 , -1.0994000000000000e-01 , 2.2299500000000000e-01 , 9.6860000000000002e-01 -1.1709640518477768e+01 , -1.4753535044893167e+00 , 2.6917414399999999e+00 , 7.2633000000000003e-02 , -1.9533700000000001e-01 , -9.7804300000000000e-01 -1.2603301408820178e+01 , -1.8299647082745487e+00 , 2.8457446399999999e+00 , -6.9706099999999993e-02 , 1.8629100000000001e-01 , 9.8001899999999997e-01 -1.3583541857431420e+01 , -2.2166660759417827e+00 , 3.0328292000000001e+00 , 5.6135800000000000e-02 , -1.9039200000000001e-01 , -9.8010200000000003e-01 -1.5175990827189473e+01 , -2.8531106226243281e+00 , 3.2653160000000003e+00 , -5.7437700000000001e-02 , 1.8307000000000001e-01 , 9.8142099999999999e-01 -1.7044236608514581e+01 , -3.5968854613389327e+00 , 3.5665832000000002e+00 , -4.7909700000000000e-02 , 1.8150300000000000e-01 , 9.8222299999999996e-01 -1.9505670661759037e+01 , -4.5752007773837828e+00 , 3.9687928000000001e+00 , -7.7697299999999997e-02 , 1.8822300000000000e-01 , 9.7904800000000003e-01 -2.2316043337420684e+01 , -5.6871606848851970e+00 , 4.4884912000000003e+00 , -7.4995699999999998e-02 , 1.8581800000000001e-01 , 9.7971799999999998e-01 -3.1172341613649753e+01 , -9.1820632002681482e+00 , 6.1971488000000008e+00 , 8.2882500000000003e-01 , -1.0005300000000000e-01 , -5.5048900000000001e-01 -3.1194919504268807e+01 , -9.1348281088297494e+00 , 6.7420880000000007e+00 , -8.7721099999999996e-01 , 1.3818800000000001e-01 , 4.5978799999999997e-01 -3.1926630797466117e+01 , -9.3695789025483442e+00 , 7.3929511999999997e+00 , 8.6196899999999999e-01 , -4.1942900000000000e-01 , -2.8476099999999999e-01 -3.1691090049143096e+01 , -9.2184654164809885e+00 , 7.9136895999999997e+00 , -8.6074399999999995e-01 , 4.4871899999999998e-01 , 2.4035599999999999e-01 -3.1723932284898332e+01 , -9.1731820183907651e+00 , 8.4771408000000008e+00 , 9.9524699999999999e-01 , -6.8644200000000002e-02 , -6.9082199999999996e-02 -3.1860901575197364e+01 , -9.1688684367027804e+00 , 9.0655935999999997e+00 , 9.9524699999999999e-01 , -6.8644200000000002e-02 , -6.9082299999999999e-02 -3.2017282502987470e+01 , -9.1702764081182195e+00 , 9.6663911999999996e+00 , -8.5340499999999997e-01 , 1.0831000000000000e-02 , 5.2113600000000004e-01 -4.5207584656647498e+01 , -1.4249461445845391e+01 , 1.3432824000000000e+01 , 5.5013900000000004e-01 , 2.2653000000000001e-01 , -8.0376000000000003e-01 -4.5458483719632966e+01 , -1.4259617950806003e+01 , 1.4331696000000001e+01 , 5.5013900000000004e-01 , 2.2653000000000001e-01 , -8.0376000000000003e-01 -3.0243607669987558e+01 , -8.3067338417100824e+00 , 1.0896565600000001e+01 , 7.9526200000000002e-01 , 1.8718599999999999e-01 , 5.7664499999999996e-01 -3.0356239738677282e+01 , -8.2928158712159803e+00 , 1.1480151200000000e+01 , 7.9526200000000002e-01 , 1.8718599999999999e-01 , 5.7664499999999996e-01 -2.5106924674710204e+01 , -6.2334026285411799e+00 , 1.0351865600000000e+01 , -9.1800599999999999e-01 , -8.8910699999999995e-02 , 3.8647100000000001e-01 -2.6029211141905304e+01 , -6.5361677380448668e+00 , 1.1122609600000001e+01 , -9.4962199999999997e-01 , -2.6972900000000000e-01 , 1.5957499999999999e-01 -2.4998430616956551e+01 , -6.0976021011484374e+00 , 1.1229303200000000e+01 , -9.1333500000000001e-01 , -2.0772699999999999e-01 , 3.5024000000000000e-01 -2.4842386406255351e+01 , -5.9905412101254321e+00 , 1.1632542400000000e+01 , -9.3280099999999999e-01 , -2.9397400000000001e-01 , 2.0847399999999999e-01 -3.2276483495844062e+01 , -8.6481738292104389e+00 , 1.5717703999999999e+01 , -6.4949699999999999e-01 , -6.9093800000000005e-01 , 3.1742399999999998e-01 -3.1872199271070546e+01 , -8.4320485899641362e+00 , 1.6171664000000000e+01 , 6.1567799999999995e-01 , 7.4076100000000000e-01 , -2.6872600000000002e-01 -8.0236342462623931e+00 , 5.8124351265646657e-01 , 7.7544032000000005e+00 , -4.8804599999999998e-01 , -6.2883000000000000e-01 , -6.0529599999999995e-01 -7.8362654390995417e+00 , 6.5861985237016696e-01 , 7.7558904000000002e+00 , 4.5455000000000001e-01 , 6.4679500000000001e-01 , 6.1240499999999998e-01 -7.7708767479832339e+00 , 6.9725526077044409e-01 , 7.8599320000000006e+00 , 5.3395499999999996e-01 , 6.8489199999999995e-01 , 4.9579699999999999e-01 -7.4516856449304827e+00 , 8.1612077439440034e-01 , 7.7282679999999999e+00 , 3.4135900000000002e-01 , 5.9246200000000004e-01 , 7.2970100000000004e-01 -7.2833386945710661e+00 , 8.8472532183117347e-01 , 7.7271760000000000e+00 , -6.2961800000000001e-01 , -4.7721500000000000e-01 , -6.1306400000000005e-01 -7.3622508232436861e+00 , 8.7711096136452560e-01 , 7.9644624000000004e+00 , 9.8151999999999995e-01 , -1.8209700000000001e-01 , -5.8810300000000003e-02 -7.4909619998730888e+00 , 8.5547137365416193e-01 , 8.2639719999999990e+00 , 9.9575499999999995e-01 , 6.1608200000000002e-02 , 6.8379300000000004e-02 -7.3467182314125985e+00 , 9.1740592832727219e-01 , 8.2876216000000014e+00 , -9.1186999999999996e-01 , -4.0128900000000001e-01 , -8.6368899999999998e-02 -7.0871542079741436e+00 , 1.0139665001339955e+00 , 8.1792535999999991e+00 , 6.1652499999999999e-01 , 7.7715699999999999e-01 , -1.2619200000000000e-01 -7.1613761512434770e+00 , 1.0099112897123459e+00 , 8.4384528000000003e+00 , -6.1809499999999995e-01 , -5.7563900000000001e-01 , -5.3534899999999996e-01 -6.9251583103331518e+00 , 1.0975685586845438e+00 , 8.3435424000000005e+00 , -3.9573600000000000e-02 , -4.6743800000000002e-01 , 8.8314000000000004e-01 -6.8027870433746056e+00 , 1.1517973054722046e+00 , 8.3757407999999991e+00 , 6.3606899999999994e-02 , 5.5111800000000000e-01 , -8.3199900000000004e-01 -6.6554721089663031e+00 , 1.2127591236953974e+00 , 8.3728391999999996e+00 , 7.3633599999999994e-02 , -4.3182500000000001e-01 , 8.9894700000000005e-01 -6.5654028434163134e+00 , 1.2565679834797534e+00 , 8.4393263999999988e+00 , 9.0156899999999998e-02 , -2.6637499999999997e-01 , 9.5964400000000005e-01 -6.4262036677376555e+00 , 1.3143467040289503e+00 , 8.4381407999999993e+00 , -5.7299200000000002e-02 , -6.5407599999999996e-03 , 9.9833600000000000e-01 -5.9761705573599002e+00 , 1.4554173478521168e+00 , 7.9987928000000004e+00 , 1.8712500000000001e-01 , 1.7431400000000000e-02 , 9.8218099999999997e-01 -5.9273781218866315e+00 , 1.4870389133634392e+00 , 8.1031464000000000e+00 , -3.1704199999999999e-01 , -2.2673900000000000e-01 , -9.2090899999999998e-01 -5.8368376666916877e+00 , 1.5285132267167967e+00 , 8.1473984000000002e+00 , -3.9238299999999998e-01 , -2.2555400000000000e-01 , -8.9171800000000001e-01 -5.7174056518466525e+00 , 1.5779789697911251e+00 , 8.1460879999999989e+00 , -3.7444400000000000e-01 , -5.7151599999999997e-02 , -9.2548699999999995e-01 -5.9258401186990763e+00 , 1.5466079745435104e+00 , 8.6672736000000015e+00 , 3.5150100000000001e-01 , -2.1752400000000000e-01 , 9.1056599999999999e-01 -5.7731770647880172e+00 , 1.6045331548587152e+00 , 8.6218152000000003e+00 , 6.8646799999999997e-01 , -2.4791700000000000e-02 , -7.2673699999999997e-01 -5.5143738074544881e+00 , 1.6867663948039926e+00 , 8.3844664000000009e+00 , 3.3496799999999999e-01 , -5.0653000000000004e-01 , 7.9449599999999998e-01 -5.4951773090803897e+00 , 1.7134129156678433e+00 , 8.5547976000000006e+00 , 6.6224499999999997e-01 , -9.2644000000000004e-02 , -7.4353800000000003e-01 -5.2862034026614575e+00 , 1.7815761357679196e+00 , 8.3794640000000005e+00 , -2.1929400000000002e-02 , -2.1214300000000000e-01 , 9.7699300000000000e-01 -5.1684465935781834e+00 , 1.8281173550831782e+00 , 8.3639888000000013e+00 , 1.9622000000000001e-01 , 9.9100599999999997e-02 , 9.7553900000000004e-01 -5.0295287959272539e+00 , 1.8794302099873192e+00 , 8.2991759999999992e+00 , -3.1995099999999999e-01 , 2.9227799999999998e-01 , 9.0122400000000003e-01 -4.8266032697034813e+00 , 1.9416790029604130e+00 , 8.0905000000000005e+00 , 2.4281000000000000e-01 , 5.1712000000000002e-01 , 8.2074999999999998e-01 -4.8101838087840552e+00 , 1.9673466027499413e+00 , 8.2723648000000001e+00 , -7.4167200000000000e-01 , -3.5487900000000000e-01 , 5.6919500000000001e-01 -4.6491221376698322e+00 , 2.0202181797984520e+00 , 8.1314968000000007e+00 , -6.7873399999999995e-01 , -2.1320500000000001e-01 , -7.0275399999999999e-01 -4.7676506165781447e+00 , 2.0246265064188611e+00 , 8.6477424000000003e+00 , 7.6865700000000003e-01 , -1.7269300000000001e-01 , -6.1590900000000004e-01 -4.5442212990213253e+00 , 2.0855257232174345e+00 , 8.3489503999999997e+00 , -3.5584300000000002e-01 , 8.5092299999999998e-01 , -3.8640099999999999e-01 -4.4529572411241229e+00 , 2.1254918965137408e+00 , 8.3644672000000000e+00 , 3.7909300000000001e-01 , -7.7800599999999998e-01 , 5.0099499999999997e-01 -4.3578747752451665e+00 , 2.1653971346044316e+00 , 8.3683152000000014e+00 , 3.8429300000000000e-01 , -8.2286499999999996e-01 , 4.1858299999999998e-01 -4.3871966706498986e+00 , 2.1910890232036362e+00 , 8.7339896000000010e+00 , 4.7726000000000002e-01 , -4.5357700000000001e-01 , 7.5265599999999999e-01 -4.5984450483856953e+00 , 2.2036290833527987e+00 , 9.6951056000000015e+00 , 7.2410600000000003e-01 , 6.2951299999999999e-01 , 2.8175099999999997e-01 -4.2300366194470289e+00 , 2.2708844978866600e+00 , 8.8751592000000006e+00 , 9.6162200000000003e-02 , -8.7734999999999994e-02 , 9.9149100000000001e-01 -4.1283138635877359e+00 , 2.3131853059176022e+00 , 8.8736719999999991e+00 , -1.2873499999999999e-01 , -2.6747799999999999e-01 , 9.5492500000000002e-01 -4.3025390211678953e+00 , 2.3456681557401491e+00 , 9.8836991999999988e+00 , -8.9463700000000002e-01 , -4.3159199999999998e-01 , -1.1555400000000000e-01 -4.2135928782509460e+00 , 2.3938826529776440e+00 , 9.9933568000000008e+00 , -8.9463700000000002e-01 , -4.3159199999999998e-01 , -1.1555400000000000e-01 -3.7077285006172289e+00 , 2.4340457189492963e+00 , 8.3613679999999988e+00 , -4.0582900000000000e-01 , 1.7577799999999999e-01 , 8.9688599999999996e-01 -3.6184550194412788e+00 , 2.4716255263519264e+00 , 8.3601823999999993e+00 , -4.0582900000000000e-01 , 1.7577799999999999e-01 , 8.9688599999999996e-01 -3.4025047938303583e+00 , 2.4953151345048501e+00 , 7.7360056000000004e+00 , 6.1821999999999999e-01 , -5.7408800000000004e-01 , 5.3686800000000001e-01 -3.2965390760089579e+00 , 2.5238925621882791e+00 , 7.5864431999999997e+00 , -5.4624499999999998e-01 , 1.6776200000000002e-02 , 8.3745700000000001e-01 -3.2762685174375852e+00 , 2.5657314154058875e+00 , 7.9057335999999996e+00 , 6.3160300000000003e-01 , 5.7055900000000004e-01 , 5.2491900000000002e-01 -3.3352435203406845e+00 , 2.6341172637510315e+00 , 8.8005911999999995e+00 , -1.8107200000000001e-01 , 9.9707500000000004e-02 , 9.7840199999999999e-01 -3.1420246729071941e+00 , 2.6398440388602880e+00 , 8.0815663999999998e+00 , -8.3092200000000005e-01 , -4.7402300000000003e-01 , -2.9132500000000000e-01 -3.0337949786024407e+00 , 2.6621580321692848e+00 , 7.8635408000000000e+00 , -6.0540499999999997e-01 , -5.4557000000000000e-01 , -5.7951500000000000e-01 -2.9560134463768666e+00 , 2.6945046459211373e+00 , 7.8704672000000002e+00 , -5.8592599999999995e-01 , -6.2567700000000004e-01 , -5.1499399999999995e-01 -2.9604271841731786e+00 , 2.7894153350900175e+00 , 8.7957344000000006e+00 , 6.9882000000000000e-01 , -3.7723299999999998e-01 , 6.0773800000000000e-01 -2.8741006879810871e+00 , 2.8341346365768336e+00 , 8.8833336000000003e+00 , 7.8321600000000002e-01 , -5.6255800000000000e-01 , 2.6476499999999997e-01 -2.7308240106659332e+00 , 2.8027564809534886e+00 , 8.0066032000000007e+00 , 1.9914599999999999e-01 , 8.9072300000000004e-01 , 4.0859899999999999e-01 -2.6541084754420727e+00 , 2.8441511544101146e+00 , 8.1008272000000012e+00 , 5.1183699999999999e-01 , 6.8443299999999996e-01 , -5.1920599999999995e-01 -2.6025635032644843e+00 , 2.9925665357324949e+00 , 9.3218911999999996e+00 , 3.4661599999999998e-01 , -7.0504199999999995e-01 , 6.1868699999999999e-01 -2.5020828459908877e+00 , 3.0397330202415658e+00 , 9.3711768000000006e+00 , 3.3744499999999999e-01 , -6.9589900000000005e-01 , 6.3392099999999996e-01 -2.4103183378796902e+00 , 2.9509255908433469e+00 , 8.1571536000000009e+00 , -9.1694100000000001e-01 , -1.9337399999999999e-01 , -3.4903600000000001e-01 -2.3041920303733097e+00 , 3.0928492934292833e+00 , 9.1024408000000001e+00 , 7.8704099999999999e-02 , -5.3846799999999995e-01 , 8.3896199999999999e-01 -2.1988420702283937e+00 , 3.1554935619992381e+00 , 9.2801976000000010e+00 , 2.4926400000000001e-01 , -8.3831599999999995e-01 , 4.8486499999999999e-01 -1.9402136920999959e+00 , 3.5518071206639608e+00 , 1.2051163200000001e+01 , -9.3798099999999995e-01 , 3.3340900000000001e-01 , -9.5028799999999997e-02 -2.1057704227415690e+00 , 3.0383961274810787e+00 , 7.7884632000000007e+00 , 1.0586099999999999e-02 , -5.7570699999999997e-01 , 8.1758699999999995e-01 -2.0225972843044797e+00 , 3.0797827528019033e+00 , 7.8496464000000010e+00 , 2.6205000000000001e-01 , -5.4771400000000003e-01 , 7.9456899999999997e-01 -1.7774694946374459e+00 , 3.3437589273975505e+00 , 9.4132448000000011e+00 , -8.7704700000000002e-01 , -4.4099200000000000e-01 , -1.9056300000000001e-01 -4.6292747364687727e+00 , 1.2571037885679957e+00 , 1.3935229599999999e+00 , -9.3838500000000005e-02 , 2.5972600000000001e-01 , 9.6111199999999997e-01 -4.6653386921765501e+00 , 1.2439871306343795e+00 , 1.4309525599999999e+00 , -1.1369500000000000e-01 , 2.2457900000000000e-01 , 9.6780100000000002e-01 -4.7400065562970237e+00 , 1.2120291125655678e+00 , 1.4411164800000000e+00 , -1.2291600000000000e-01 , 1.9705800000000001e-01 , 9.7265599999999997e-01 -4.8064851030363167e+00 , 1.1840882030128781e+00 , 1.4588942399999998e+00 , 7.9987600000000006e-02 , -1.7299100000000001e-01 , -9.8167000000000004e-01 -4.8895338850635488e+00 , 1.1473772745262081e+00 , 1.4683540799999999e+00 , 8.6120600000000005e-02 , -1.9272200000000000e-01 , -9.7746699999999997e-01 -4.9654111052406815e+00 , 1.1146881448597448e+00 , 1.4856555199999999e+00 , 6.6886600000000004e-02 , -2.2004099999999999e-01 , -9.7319500000000003e-01 -5.0489182766699230e+00 , 1.0789615045199736e+00 , 1.5000979999999999e+00 , -8.6639900000000006e-02 , 2.0367600000000000e-01 , 9.7519699999999998e-01 -5.1419675097946964e+00 , 1.0382504222055529e+00 , 1.5128484000000000e+00 , -5.1957600000000000e-02 , 2.1566399999999999e-01 , 9.7508399999999995e-01 -5.2268840295014538e+00 , 1.0025335712814893e+00 , 1.5329079200000000e+00 , -5.1333100000000000e-02 , 1.8374699999999999e-01 , 9.8163199999999995e-01 -5.3280826379145205e+00 , 9.5747893806825712e-01 , 1.5469791200000000e+00 , -7.5509800000000002e-02 , 2.1081600000000000e-01 , 9.7460500000000005e-01 -5.4221335060895921e+00 , 9.1748025038184378e-01 , 1.5687868800000000e+00 , -8.0547099999999996e-02 , 1.9954000000000000e-01 , 9.7657400000000005e-01 -5.5334547342654865e+00 , 8.6928853855034260e-01 , 1.5852365600000000e+00 , -4.8559800000000000e-02 , 1.8125400000000000e-01 , 9.8223700000000003e-01 -5.6541738016716341e+00 , 8.1745203599750638e-01 , 1.6014085599999999e+00 , -5.1820900000000003e-02 , 1.7751800000000001e-01 , 9.8275199999999996e-01 -5.7743453640562921e+00 , 7.6439033866364725e-01 , 1.6219360800000000e+00 , -5.8533599999999998e-02 , 2.0396500000000001e-01 , 9.7722699999999996e-01 -5.8961242007782850e+00 , 7.1208952445126439e-01 , 1.6465601599999999e+00 , -7.0744799999999997e-02 , 1.9218099999999999e-01 , 9.7880599999999995e-01 -6.0359145692092069e+00 , 6.5207488628067112e-01 , 1.6683793600000001e+00 , -7.8050099999999997e-02 , 1.9486300000000001e-01 , 9.7772000000000003e-01 -6.1664302338647046e+00 , 5.9619690667927805e-01 , 1.6981930400000000e+00 , -5.7283300000000002e-02 , 2.0424700000000001e-01 , 9.7724200000000006e-01 -6.3245220815833143e+00 , 5.2756157115160796e-01 , 1.7233080000000001e+00 , -1.2393999999999999e-01 , 2.2876099999999999e-01 , 9.6556100000000000e-01 -6.4742934825165008e+00 , 4.6317143946956718e-01 , 1.7571496000000000e+00 , 6.3367300000000004e-01 , -1.6967300000000001e-02 , -7.7341499999999996e-01 -6.5792321018874027e+00 , 4.2149599043528574e-01 , 1.8098765600000000e+00 , -9.3407399999999996e-01 , -5.4646300000000002e-02 , 3.5287299999999999e-01 -6.5654139874161412e+00 , 4.3705285645833536e-01 , 1.8999611519999999e+00 , 9.6927799999999997e-01 , -1.7048000000000001e-02 , -2.4537600000000001e-01 -6.5774786934709262e+00 , 4.3925442839939244e-01 , 1.9819600559999999e+00 , 9.9281100000000000e-01 , 1.1962100000000001e-01 , -4.2626000000000001e-03 -6.5607110237351343e+00 , 4.5569900332826885e-01 , 2.0705523520000000e+00 , 9.9644200000000005e-01 , 8.4001500000000007e-02 , 6.8656100000000003e-03 -6.5697720344691302e+00 , 4.5999763470097554e-01 , 2.1517640800000000e+00 , 9.9394000000000005e-01 , 9.0554200000000001e-02 , 6.2315599999999999e-02 -6.5500855256588295e+00 , 4.7728308739571146e-01 , 2.2386612800000001e+00 , 9.9736000000000002e-01 , 7.0035000000000000e-02 , 1.9207800000000001e-02 -6.5380391607930459e+00 , 4.9153309557817981e-01 , 2.3225986399999998e+00 , 9.9498600000000004e-01 , 7.6319300000000007e-02 , 6.4636299999999994e-02 -6.5621498891179897e+00 , 4.8901373842987250e-01 , 2.3996137599999998e+00 , 9.9656400000000001e-01 , 4.5518400000000001e-02 , 6.9203600000000004e-02 -6.5090024117300072e+00 , 5.2081364563876020e-01 , 2.4881229600000001e+00 , 9.9481500000000000e-01 , 7.3981400000000003e-02 , -6.9779700000000000e-02 -6.5395212112330405e+00 , 5.1453157188452048e-01 , 2.5635728799999997e+00 , -9.4886899999999996e-01 , -5.0226800000000002e-02 , 3.1164999999999998e-01 -6.5878671071920865e+00 , 5.0086969063496212e-01 , 2.6378371999999999e+00 , 7.8495400000000004e-01 , 2.8126800000000000e-02 , -6.1891499999999999e-01 -6.7200237732021755e+00 , 4.4846536957669514e-01 , 2.7063576000000000e+00 , 7.8324199999999999e-01 , -2.5649900000000000e-02 , -6.2118799999999996e-01 -1.0751185618147993e+01 , -1.3840539862960424e+00 , 2.5135031200000002e+00 , -1.2157100000000000e-01 , 2.3735100000000001e-01 , 9.6378699999999995e-01 -1.1199385060775350e+01 , -1.5720915348026248e+00 , 2.6508236800000002e+00 , -1.0500400000000000e-01 , 2.2796300000000000e-01 , 9.6799100000000005e-01 -1.1959518956538318e+01 , -1.8994708321569558e+00 , 2.7955407200000000e+00 , -6.6407499999999994e-02 , 1.9217799999999999e-01 , 9.7911099999999995e-01 -1.2908765742422688e+01 , -2.3082236509413576e+00 , 2.9667455199999999e+00 , -7.1882199999999993e-02 , 1.8964000000000000e-01 , 9.7921899999999995e-01 -1.4129882893872360e+01 , -2.8367647566283969e+00 , 3.1759279999999999e+00 , -4.6696599999999998e-02 , 1.8528400000000000e-01 , 9.8157499999999998e-01 -1.5748525514737212e+01 , -3.5385617255970008e+00 , 3.4425216000000001e+00 , -5.9415500000000003e-02 , 1.7948000000000000e-01 , 9.8196600000000001e-01 -1.7981025099759840e+01 , -4.5067143214474878e+00 , 3.7988672000000001e+00 , 5.0285099999999999e-02 , -1.8421599999999999e-01 , -9.8159900000000000e-01 -2.0456107671604936e+01 , -5.5732992100899663e+00 , 4.2559888000000008e+00 , -9.1302200000000000e-02 , 1.8372500000000000e-01 , 9.7872800000000004e-01 -2.3890393693304240e+01 , -7.0546196908964625e+00 , 4.8884232000000001e+00 , -6.1346499999999998e-02 , 1.8791400000000000e-01 , 9.8026800000000003e-01 -3.2798088886095059e+01 , -1.0870076968664792e+01 , 6.7982687999999998e+00 , 8.9461199999999996e-01 , 3.7372000000000000e-01 , -2.4495400000000001e-01 -3.3625387580875575e+01 , -1.1171722926831745e+01 , 7.4964520000000006e+00 , -9.1142500000000004e-01 , -3.8881800000000000e-01 , 1.3462700000000000e-01 -3.2901921760392341e+01 , -1.0798093687889555e+01 , 7.9788247999999999e+00 , -8.5552300000000003e-01 , -4.9808200000000002e-01 , 1.4140300000000000e-01 -3.2718671071183323e+01 , -1.0660468641533821e+01 , 8.5329991999999990e+00 , -8.5552300000000003e-01 , -4.9808200000000002e-01 , 1.4140300000000000e-01 -3.3249454729601752e+01 , -1.0830577050038350e+01 , 9.2251815999999991e+00 , -8.4484899999999996e-01 , -5.0755700000000004e-01 , 1.6916500000000001e-01 -3.3881037652777962e+01 , -1.1040419777013078e+01 , 9.9626663999999998e+00 , 4.0343099999999998e-01 , 3.7880200000000003e-01 , -8.3291800000000005e-01 -3.0078898408133274e+01 , -9.1955170106525514e+00 , 1.1314500000000001e+01 , 8.3449600000000002e-01 , 1.6744300000000001e-01 , 5.2495599999999998e-01 -3.0486774161235534e+01 , -9.3105291941431112e+00 , 1.2000702400000000e+01 , 8.3449600000000002e-01 , 1.6744300000000001e-01 , 5.2495599999999998e-01 -7.7333741768871214e+00 , 5.0467302710372985e-01 , 7.8288983999999999e+00 , 2.6829300000000000e-01 , 7.5448199999999999e-01 , 5.9897999999999996e-01 -7.7999173213808701e+00 , 4.9656753897258077e-01 , 8.0558472000000005e+00 , 6.0706899999999997e-01 , 7.4014899999999995e-01 , 2.8921799999999998e-01 -7.7592323578697373e+00 , 5.2818778419518853e-01 , 8.1883015999999991e+00 , 7.3660199999999998e-01 , 5.5868799999999996e-01 , 3.8116400000000000e-01 -7.3373258522214702e+00 , 6.9341341327587624e-01 , 7.9433400000000010e+00 , -7.8620900000000005e-01 , 5.9987100000000004e-01 , -1.4842700000000000e-01 -7.3679007583867424e+00 , 7.0004632607379569e-01 , 8.1408880000000003e+00 , -6.4323399999999997e-01 , 7.6541599999999999e-01 , 1.9720000000000001e-02 -7.3940022934760030e+00 , 7.0843593418288786e-01 , 8.3409528000000002e+00 , -9.4569800000000004e-01 , -3.2286500000000001e-01 , 3.7590800000000001e-02 -7.3806567165925925e+00 , 7.3050856032952005e-01 , 8.5056471999999985e+00 , -7.9020400000000002e-01 , -1.3922699999999999e-01 , 5.9681899999999999e-01 -6.5520379604518517e+00 , 1.0276210961683372e+00 , 7.7480696000000000e+00 , 7.1810300000000005e-01 , -1.2170499999999999e-01 , 6.8521200000000004e-01 -6.5189855778667090e+00 , 1.0544110162250546e+00 , 7.8687408000000003e+00 , -7.5019100000000005e-01 , 6.2187999999999999e-01 , 2.2467200000000001e-01 -6.6908514321403425e+00 , 1.0137807910492849e+00 , 8.2412896000000000e+00 , 9.6691600000000003e-02 , -4.9959799999999999e-01 , 8.6084400000000005e-01 -6.7113093535130677e+00 , 1.0253028261884189e+00 , 8.4451815999999997e+00 , 8.9659199999999994e-02 , 3.3827499999999999e-01 , 9.3676599999999999e-01 -6.4916359207986156e+00 , 1.1141066157440949e+00 , 8.3436464000000008e+00 , 8.6067400000000002e-02 , -4.6608800000000000e-01 , 8.8054200000000005e-01 -6.4281226906165010e+00 , 1.1523369461218711e+00 , 8.4408239999999992e+00 , 9.5690800000000006e-02 , -3.3885399999999999e-01 , 9.3596000000000001e-01 -6.3081878804205394e+00 , 1.2084709198367136e+00 , 8.4619152000000000e+00 , 9.5690800000000006e-02 , -3.3885399999999999e-01 , 9.3596000000000001e-01 -5.9741267053287324e+00 , 1.3293944290955877e+00 , 8.1686872000000008e+00 , 2.7537299999999998e-01 , -1.2787399999999999e-01 , 9.5279499999999995e-01 -5.8312779711929430e+00 , 1.3897865891003636e+00 , 8.1375600000000006e+00 , -3.3366099999999999e-01 , 5.9739300000000002e-02 , -9.4079800000000002e-01 -5.7243380759816080e+00 , 1.4402353276870588e+00 , 8.1542935999999990e+00 , -2.7441300000000002e-01 , 1.3145100000000001e-01 , -9.5258500000000002e-01 -5.6290672115340721e+00 , 1.4858336596028119e+00 , 8.1863464000000015e+00 , -5.0932900000000003e-01 , 3.0662599999999999e-03 , -8.6056699999999997e-01 -5.5330605396539632e+00 , 1.5320256426468974e+00 , 8.2159447999999990e+00 , 5.9858199999999995e-01 , -2.4881700000000001e-01 , 7.6143899999999998e-01 -5.4983595429181698e+00 , 1.5606142883920615e+00 , 8.3504792000000005e+00 , 5.3612599999999999e-01 , -1.6761200000000001e-01 , 8.2733000000000001e-01 -5.5566021508337347e+00 , 1.5655549934909034e+00 , 8.6561871999999997e+00 , 4.5206200000000002e-01 , -5.6926100000000002e-01 , -6.8671800000000005e-01 -5.2743597005402449e+00 , 1.6618617173525994e+00 , 8.3466728000000003e+00 , 2.8211700000000001e-01 , 1.4418800000000001e-01 , 9.4848299999999997e-01 -5.2193527887536915e+00 , 1.6969191455142074e+00 , 8.4509639999999990e+00 , 1.5612000000000001e-01 , 2.4703800000000001e-01 , 9.5634699999999995e-01 -5.1121048532669331e+00 , 1.7454325072619596e+00 , 8.4527840000000012e+00 , -3.0120599999999997e-01 , 1.3202400000000000e-01 , -9.4437499999999996e-01 -5.0143171517553426e+00 , 1.7904644099699556e+00 , 8.4709736000000007e+00 , -7.1591799999999997e-02 , 2.1974600000000000e-01 , 9.7292699999999999e-01 -4.8097245760886356e+00 , 1.8611987574867903e+00 , 8.2513672000000007e+00 , -3.8738099999999998e-01 , 2.5654199999999999e-01 , 8.8550700000000004e-01 -4.6985084492187141e+00 , 1.9085055502592341e+00 , 8.2252840000000003e+00 , 3.6793599999999999e-01 , -6.0440099999999997e-02 , 9.2788499999999996e-01 -4.7337024492820809e+00 , 1.9239177771243334e+00 , 8.5411736000000005e+00 , -6.8689699999999998e-01 , -2.1878399999999999e-02 , -7.2642600000000002e-01 -4.6551176941471528e+00 , 1.9655139913085231e+00 , 8.5991119999999999e+00 , -4.1489199999999997e-02 , 1.0107800000000000e-02 , 9.9908799999999998e-01 -4.5534507003002656e+00 , 2.0109947039216141e+00 , 8.5976144000000012e+00 , 5.9784199999999998e-01 , 7.9740200000000006e-01 , -8.2067799999999996e-02 -4.4128347128015601e+00 , 2.0626233554934279e+00 , 8.4865631999999991e+00 , -2.0958099999999999e-01 , 9.3558500000000000e-01 , 2.8417599999999998e-01 -4.4020084666765662e+00 , 2.0929976561790973e+00 , 8.7351544000000008e+00 , 4.4744000000000000e-01 , -5.5800000000000005e-01 , 6.9887999999999995e-01 -4.3099541043937943e+00 , 2.1365484336604919e+00 , 8.7577432000000002e+00 , -6.4847100000000005e-02 , -4.6447600000000000e-01 , 8.8320900000000002e-01 -4.2438734714314439e+00 , 2.1763986701177771e+00 , 8.8676504000000005e+00 , 7.3148199999999997e-02 , -2.6234099999999999e-01 , 9.6219900000000003e-01 -4.1085734089329566e+00 , 2.2258832543525755e+00 , 8.7470832000000005e+00 , -4.6205200000000002e-01 , -2.3919599999999999e-01 , 8.5398600000000002e-01 -4.2811100402151592e+00 , 2.2458088976874233e+00 , 9.7260559999999998e+00 , -8.0348699999999995e-01 , -5.4412099999999997e-01 , -2.4153900000000000e-01 -4.2698906565821098e+00 , 2.2901627135857656e+00 , 1.0117730400000001e+01 , -8.9463700000000002e-01 , -4.3159199999999998e-01 , -1.1555400000000000e-01 -3.8377679051975795e+00 , 2.3545524515769509e+00 , 8.8220048000000002e+00 , -2.2662399999999999e-02 , -2.0946600000000001e-01 , 9.7755300000000001e-01 -3.6423287339299844e+00 , 2.3985582360902065e+00 , 8.3768120000000010e+00 , -4.0582900000000000e-01 , 1.7577799999999999e-01 , 8.9688599999999996e-01 -3.4051478948255260e+00 , 2.4335400487474885e+00 , 7.6618431999999999e+00 , -7.9503100000000004e-01 , 1.5573399999999999e-02 , 6.0636800000000002e-01 -3.3184502836209777e+00 , 2.4671025069969224e+00 , 7.6043935999999999e+00 , 6.8710999999999998e-03 , 1.1906100000000000e-01 , 9.9286300000000005e-01 -3.2775413161742275e+00 , 2.5043820996694066e+00 , 7.7912400000000002e+00 , -3.7414100000000000e-01 , 8.0188000000000004e-01 , -4.6583999999999998e-01 -3.3538781260225785e+00 , 2.5662700818728226e+00 , 8.7576807999999993e+00 , -1.8107200000000001e-01 , 9.9707500000000004e-02 , 9.7840199999999999e-01 -3.2353702365866059e+00 , 2.6013354924161742e+00 , 8.5744120000000006e+00 , 2.6324700000000001e-01 , -1.1561700000000000e-01 , -9.5777500000000004e-01 -3.0624606685302851e+00 , 2.6118317709943564e+00 , 7.9044752000000003e+00 , 5.5943900000000002e-01 , 6.3373999999999997e-01 , 5.3422999999999998e-01 -2.9829859593665691e+00 , 2.6465633836061135e+00 , 7.8912464000000000e+00 , -6.0540499999999997e-01 , -5.4557000000000000e-01 , -5.7951600000000003e-01 -2.9803403887755349e+00 , 2.7265155093420050e+00 , 8.6828007999999990e+00 , 8.4126900000000004e-01 , -4.4058000000000003e-01 , 3.1329899999999999e-01 -2.9022491040708789e+00 , 2.7770840501404934e+00 , 8.8328000000000007e+00 , -6.6767200000000004e-01 , 5.8479099999999995e-01 , -4.6068900000000002e-01 -2.7751588794963657e+00 , 2.7779437775837486e+00 , 8.2671024000000006e+00 , -8.8288400000000000e-01 , 3.3461200000000002e-01 , 3.2947100000000001e-01 -2.6791416212709418e+00 , 2.7939777858020394e+00 , 7.9994376000000003e+00 , 1.9914599999999999e-01 , 8.9072399999999996e-01 , 4.0859800000000002e-01 -2.6373121921172222e+00 , 2.9317264024315919e+00 , 9.1907056000000011e+00 , 2.1564900000000001e-01 , -8.1153399999999998e-01 , 5.4305400000000004e-01 -2.5408465982000736e+00 , 2.9860662669018598e+00 , 9.3028072000000002e+00 , 4.7842800000000002e-01 , -6.7793999999999999e-01 , 5.5812600000000001e-01 -2.4427865939516322e+00 , 2.9439414599191176e+00 , 8.4403560000000013e+00 , 4.6354800000000002e-01 , -8.8178900000000004e-01 , -8.7014400000000006e-02 -2.3592073815313768e+00 , 2.9703652298808811e+00 , 8.3217856000000001e+00 , -8.4354300000000004e-01 , 5.3686400000000001e-01 , 1.4572399999999999e-02 -2.2491693248677316e+00 , 3.0959108363759698e+00 , 9.0900856000000001e+00 , 3.6798100000000000e-01 , -4.5007000000000003e-01 , 8.1365100000000001e-01 -2.1212772879984509e+00 , 3.2166827280997747e+00 , 9.7202216000000004e+00 , 6.0803599999999999e-02 , -4.7365099999999999e-01 , 8.7861100000000003e-01 -1.8535710275683603e+00 , 3.5791517525748144e+00 , 1.2147332000000000e+01 , -6.2367899999999998e-01 , -7.5682600000000000e-01 , -1.9555000000000000e-01 -2.0591664169871233e+00 , 3.0582219778913582e+00 , 7.8558448000000007e+00 , -1.2772000000000000e-01 , 4.6777000000000002e-01 , -8.7457399999999996e-01 -1.5608839952521572e+00 , 3.7086320001686710e+00 , 1.2126708800000001e+01 , -9.5609900000000003e-01 , -2.8882400000000003e-01 , 4.9560000000000000e-02 -1.7402040736234770e+00 , 3.3433782427960375e+00 , 9.2716696000000010e+00 , 6.8606400000000001e-01 , -7.2347799999999995e-01 , 7.6783699999999996e-02 -4.5446381268280405e+00 , 1.2307681301732980e+00 , 1.4133609599999999e+00 , -9.5953499999999997e-02 , 2.3413000000000000e-01 , 9.6745899999999996e-01 -4.6095799304617886e+00 , 1.2008284750571208e+00 , 1.4262361600000000e+00 , -8.2943100000000006e-02 , 2.3928400000000000e-01 , 9.6740000000000004e-01 -4.6832099520152912e+00 , 1.1656145685003256e+00 , 1.4357771200000000e+00 , -1.0400400000000000e-01 , 2.3410300000000001e-01 , 9.6663299999999996e-01 -4.7565899736137585e+00 , 1.1308487260711750e+00 , 1.4475436799999999e+00 , -9.4642599999999993e-02 , 1.8906400000000001e-01 , 9.7739299999999996e-01 -4.8228571034863315e+00 , 1.1010716126440565e+00 , 1.4667441600000000e+00 , -9.4935400000000003e-02 , 1.9941200000000001e-01 , 9.7530600000000001e-01 -4.9056718789881923e+00 , 1.0625835702763751e+00 , 1.4778284799999999e+00 , -8.8711200000000004e-02 , 2.0234099999999999e-01 , 9.7528899999999996e-01 -4.9802850782554229e+00 , 1.0281207629561853e+00 , 1.4966285600000000e+00 , -8.0092600000000000e-02 , 1.9295300000000001e-01 , 9.7793399999999997e-01 -5.0546121971020632e+00 , 9.9307999958839699e-01 , 1.5177582400000000e+00 , -8.2978899999999994e-02 , 1.9153100000000001e-01 , 9.7797299999999998e-01 -5.1385883870874460e+00 , 9.5503961807165827e-01 , 1.5365843200000000e+00 , -6.7090999999999998e-02 , 1.6985300000000000e-01 , 9.8318300000000003e-01 -5.2466905365207257e+00 , 9.0314985928955593e-01 , 1.5445444799999999e+00 , -6.5894099999999997e-02 , 1.8270300000000000e-01 , 9.8095800000000000e-01 -5.3309948207114619e+00 , 8.6521843185678460e-01 , 1.5692652800000000e+00 , -7.6898999999999995e-02 , 1.9584799999999999e-01 , 9.7761399999999998e-01 -5.4315320200819155e+00 , 8.1803475788340951e-01 , 1.5884043999999999e+00 , -7.2014099999999998e-02 , 1.7832000000000001e-01 , 9.8133400000000004e-01 -5.5414678928902088e+00 , 7.6610286379626102e-01 , 1.6070671999999999e+00 , -3.2028899999999999e-02 , 1.6205200000000000e-01 , 9.8626199999999997e-01 -5.6772701950490170e+00 , 7.0084418754330846e-01 , 1.6178447199999999e+00 , -6.2129700000000003e-02 , 1.8914800000000001e-01 , 9.7998099999999999e-01 -5.7796259585724057e+00 , 6.5474012688110483e-01 , 1.6479870400000001e+00 , -5.5797600000000003e-02 , 2.0269699999999999e-01 , 9.7765100000000005e-01 -5.9174906263560647e+00 , 5.9014357788890726e-01 , 1.6677460000000000e+00 , -6.2989500000000004e-02 , 1.9120400000000001e-01 , 9.7952700000000004e-01 -6.0460519403353192e+00 , 5.2972032591346840e-01 , 1.6957001599999999e+00 , -7.9331399999999996e-02 , 1.9840700000000000e-01 , 9.7690399999999999e-01 -6.1848628711595648e+00 , 4.6595228537507216e-01 , 1.7250208800000000e+00 , -6.3255800000000001e-02 , 2.0469699999999999e-01 , 9.7677899999999995e-01 -6.3404192466217957e+00 , 3.9270693591714823e-01 , 1.7530353599999999e+00 , -1.2134399999999999e-01 , 2.1148200000000000e-01 , 9.6982000000000002e-01 -6.4974046596515667e+00 , 3.2052590796636293e-01 , 1.7866637599999999e+00 , -5.5924099999999999e-01 , 9.9023700000000006e-03 , 8.2894599999999996e-01 -6.6267915706543228e+00 , 2.6184051834300726e-01 , 1.8339213599999999e+00 , -8.6456400000000000e-01 , -8.6037100000000005e-02 , 4.9510300000000002e-01 -6.6224028458109210e+00 , 2.7260233311231596e-01 , 1.9233273520000000e+00 , -9.3584000000000001e-01 , -2.1531700000000001e-02 , 3.5176800000000003e-01 -6.6524450692701214e+00 , 2.6605386822750998e-01 , 2.0026252512000000e+00 , 9.9267899999999998e-01 , 1.2014100000000000e-01 , 1.2413799999999999e-02 -6.6172716454050855e+00 , 2.9199998249555659e-01 , 2.0975609440000000e+00 , 9.9350200000000000e-01 , 1.0580199999999999e-01 , 4.1959000000000003e-02 -6.6164582408649952e+00 , 2.9967701345903208e-01 , 2.1828975200000000e+00 , 9.9075700000000000e-01 , 8.4707099999999994e-02 , 1.0595000000000000e-01 -6.5966090522528429e+00 , 3.1834082201568115e-01 , 2.2713100000000002e+00 , 9.9401600000000001e-01 , 8.9733499999999994e-02 , -6.2295799999999998e-02 -6.5928616494161663e+00 , 3.2798047936123309e-01 , 2.3552515199999999e+00 , 9.9287899999999996e-01 , 1.1867800000000001e-01 , 1.0377300000000001e-02 -6.6991987614623998e+00 , 2.8265164342750593e-01 , 2.4217272799999998e+00 , 9.9694300000000002e-01 , 7.7422699999999997e-02 , 1.0470100000000000e-02 -6.5454859428794592e+00 , 3.6774175779625962e-01 , 2.5267121599999998e+00 , 9.8693299999999995e-01 , 1.5609700000000001e-01 , -3.9964500000000000e-02 -6.6030915546896622e+00 , 3.4630042704716568e-01 , 2.6012156800000001e+00 , -9.1987500000000000e-01 , -9.1601900000000000e-02 , 3.8136500000000001e-01 -6.6500259091590337e+00 , 3.3112147538957615e-01 , 2.6781933599999999e+00 , -9.3690899999999999e-01 , -6.6714999999999997e-02 , 3.4314800000000001e-01 -1.0741685467523194e+01 , -1.6582926907308937e+00 , 2.6101825600000002e+00 , -9.8140099999999994e-02 , 2.3414499999999999e-01 , 9.6723599999999998e-01 -1.1398406758627862e+01 , -1.9637217578425545e+00 , 2.7469404800000001e+00 , -7.7339300000000000e-02 , 1.9556999999999999e-01 , 9.7763500000000003e-01 -1.2241549013933005e+01 , -2.3577128407994081e+00 , 2.9054749600000003e+00 , -6.6106799999999993e-02 , 1.8992000000000001e-01 , 9.7957200000000000e-01 -1.3241844726345304e+01 , -2.8241904562537501e+00 , 3.0962224000000003e+00 , -6.6014699999999996e-02 , 1.9028500000000001e-01 , 9.7950700000000002e-01 -1.4727641771593753e+01 , -3.5215382801420176e+00 , 3.3355472000000002e+00 , -5.1933300000000002e-02 , 1.7958199999999999e-01 , 9.8237099999999999e-01 -1.6359578724439800e+01 , -4.2836834186117247e+00 , 3.6376672000000001e+00 , -5.5899600000000001e-02 , 1.7960599999999999e-01 , 9.8214900000000005e-01 -1.8953496920659731e+01 , -5.5004415805383786e+00 , 4.0600632000000001e+00 , -7.0236800000000002e-02 , 1.8774700000000000e-01 , 9.7970299999999999e-01 -2.1344267518876944e+01 , -6.6107204429851514e+00 , 4.5666264000000005e+00 , 8.2822400000000004e-02 , -1.7890400000000001e-01 , -9.8037399999999997e-01 -3.8708434099056468e+01 , -1.4695910597266039e+01 , 8.0381672000000002e+00 , -2.0018200000000000e-01 , 2.0492900000000000e-01 , 9.5808700000000002e-01 -3.8781121641290639e+01 , -1.4662924281740402e+01 , 8.7547688000000008e+00 , 3.4014500000000003e-02 , -1.0433099999999999e-01 , 9.9396099999999998e-01 -3.8666094703116173e+01 , -1.4540439056875485e+01 , 9.4435712000000009e+00 , -2.4128800000000000e-01 , -1.0800700000000001e-01 , 9.6442399999999995e-01 -3.8688096775591426e+01 , -1.4483558087485065e+01 , 1.0157812000000000e+01 , -1.3142100000000001e-01 , -3.1329099999999999e-01 , 9.4052000000000002e-01 -4.7637550898694705e+01 , -1.7589447021160197e+01 , 2.3034832000000002e+01 , -7.6962600000000003e-01 , 5.9375500000000003e-01 , 2.3479900000000001e-01 -4.8280574993866196e+01 , -1.7681411011530844e+01 , 2.5339991999999999e+01 , 6.5351599999999999e-01 , -7.4449500000000002e-01 , -1.3654400000000000e-01 -7.2657682745770256e+00 , 5.3042091901513011e-01 , 7.8780280000000005e+00 , -7.8620900000000005e-01 , 5.9987100000000004e-01 , -1.4842700000000000e-01 -7.1502518390698828e+00 , 5.9025198395270428e-01 , 7.9236735999999999e+00 , 6.0262199999999999e-01 , -6.4915299999999998e-01 , 4.6416299999999999e-01 -7.5725568263535408e+00 , 4.4431398951564915e-01 , 8.5385320000000000e+00 , -6.0213200000000000e-01 , -3.4833100000000000e-01 , -7.1840300000000001e-01 -7.1306398278883529e+00 , 6.2983673843792909e-01 , 8.2372024000000010e+00 , -2.2904099999999999e-01 , -8.3227099999999998e-01 , 5.0484300000000004e-01 -6.6659485591648151e+00 , 8.2159850326655359e-01 , 7.8829472000000003e+00 , -9.0316099999999999e-01 , -9.7442600000000004e-02 , -4.1809600000000002e-01 -6.5595478822074602e+00 , 8.7645421401955259e-01 , 7.9217183999999996e+00 , -7.8339800000000004e-01 , 5.8402600000000005e-01 , 2.1260699999999999e-01 -6.5749861815594839e+00 , 8.8645997977322244e-01 , 8.1064016000000017e+00 , -9.3874800000000003e-01 , 3.2346999999999998e-01 , -1.1882700000000000e-01 -6.8200686815349396e+00 , 8.1349266779956619e-01 , 8.5870584000000001e+00 , -2.2295699999999999e-01 , 6.6673199999999999e-01 , 7.1116699999999999e-01 -6.4875610825586421e+00 , 9.5187932529160069e-01 , 8.3439584000000018e+00 , 1.5756000000000001e-01 , -1.7399899999999999e-01 , 9.7205900000000001e-01 -6.3283816109869369e+00 , 1.0254089431113109e+00 , 8.3112919999999999e+00 , -1.3300000000000001e-01 , -7.2955400000000004e-02 , 9.8842699999999994e-01 -6.2420888511987114e+00 , 1.0734639183805965e+00 , 8.3732864000000014e+00 , -2.7229599999999998e-01 , -1.3338900000000001e-01 , 9.5292299999999996e-01 -5.9112461470899849e+00 , 1.2061501096215306e+00 , 8.0811087999999991e+00 , -2.3676000000000000e-01 , 1.9570299999999999e-01 , 9.5165400000000000e-01 -5.7830692661153389e+00 , 1.2661949944935271e+00 , 8.0671728000000016e+00 , 5.7583700000000002e-02 , -2.7651799999999999e-01 , 9.5928199999999997e-01 -5.7448969532230434e+00 , 1.2963083896546963e+00 , 8.1874072000000009e+00 , 4.4986599999999999e-01 , 9.1361600000000001e-02 , 8.8841099999999995e-01 -5.7317165200483897e+00 , 1.3191891333394736e+00 , 8.3508847999999993e+00 , 5.8418400000000004e-01 , 5.6991199999999997e-01 , 5.7786599999999999e-01 -5.5389608445274892e+00 , 1.3997923910399002e+00 , 8.2249303999999999e+00 , 6.1333400000000005e-01 , 3.4070499999999998e-01 , 7.1255999999999997e-01 -5.5063088496607620e+00 , 1.4294755275618929e+00 , 8.3600160000000017e+00 , -6.4940500000000001e-01 , -4.2297200000000001e-01 , -6.3195500000000004e-01 -5.3888928830359220e+00 , 1.4848573247919787e+00 , 8.3516232000000006e+00 , 6.5643399999999996e-01 , 2.8064499999999998e-01 , 7.0023800000000003e-01 -5.3316119511690090e+00 , 1.5218148503495437e+00 , 8.4490504000000008e+00 , 3.7111600000000000e-01 , 2.5790900000000000e-01 , 8.9205199999999996e-01 -5.2579606657764071e+00 , 1.5644100672079821e+00 , 8.5182728000000001e+00 , 2.7262399999999998e-01 , 9.0589500000000003e-02 , 9.5784599999999998e-01 -5.0962571598681929e+00 , 1.6325403699891226e+00 , 8.4108408000000008e+00 , 7.3970900000000006e-02 , -5.0085699999999997e-02 , 9.9600200000000005e-01 -5.0139050065935251e+00 , 1.6772789967423880e+00 , 8.4572040000000008e+00 , -5.7050699999999999e-01 , 2.2437199999999999e-01 , -7.9005000000000003e-01 -5.8578054663579504e+00 , 1.4664309736865186e+00 , 1.0531608799999999e+01 , -8.7164100000000000e-01 , -4.6449699999999999e-01 , 1.5647600000000000e-01 -5.0988694651867128e+00 , 1.6994322592053290e+00 , 9.1228663999999995e+00 , 9.9808999999999995e-02 , -4.4421200000000000e-01 , 8.9034500000000005e-01 -4.7525558076112500e+00 , 1.8137410010165822e+00 , 8.5675479999999986e+00 , -1.3425100000000001e-01 , 3.8211699999999998e-01 , -9.1430999999999996e-01 -4.6719250547974891e+00 , 1.8579446329702529e+00 , 8.6168960000000006e+00 , -9.5617599999999997e-02 , -4.8297299999999999e-01 , 8.7039900000000003e-01 -4.3706455189480664e+00 , 1.9544608068396894e+00 , 8.0935471999999997e+00 , 2.9848500000000000e-01 , 8.6703699999999995e-01 , -3.9894000000000002e-01 -4.3884741476816123e+00 , 1.9739804621080337e+00 , 8.3892296000000002e+00 , -3.6851600000000001e-01 , -3.1950799999999999e-03 , -9.2961600000000000e-01 -4.3256208957157263e+00 , 2.0121482634996894e+00 , 8.4809368000000003e+00 , 4.6950999999999998e-01 , -1.7614400000000000e-01 , 8.6517800000000000e-01 -4.2389687940981382e+00 , 2.0573692780324668e+00 , 8.5024335999999998e+00 , 5.4871499999999995e-01 , -1.8114500000000000e-01 , 8.1614900000000001e-01 -4.1663172278754264e+00 , 2.0989064989496309e+00 , 8.5718847999999994e+00 , 7.3335399999999995e-01 , -2.5040000000000001e-01 , 6.3205299999999998e-01 -4.0927827468725768e+00 , 2.1412919397023416e+00 , 8.6400879999999987e+00 , -6.4330600000000004e-01 , 4.5005600000000001e-01 , -6.1936000000000002e-01 -4.0389383931086735e+00 , 2.1806651610151526e+00 , 8.7871336000000007e+00 , 2.0386499999999999e-01 , -7.9247500000000004e-01 , 5.7482400000000000e-01 -3.9888673961665067e+00 , 2.2215779208743642e+00 , 8.9637048000000004e+00 , -2.1663900000000000e-01 , -3.4210800000000002e-01 , 9.1434599999999999e-01 -3.6646663802329180e+00 , 2.2902477058084010e+00 , 8.0389991999999992e+00 , -8.7104499999999996e-01 , -3.8213100000000000e-01 , 3.0863600000000002e-01 -3.7629857818188466e+00 , 2.3187072598304188e+00 , 8.8283904000000000e+00 , 1.0191699999999999e-01 , 3.5976000000000002e-01 , -9.2746200000000001e-01 -3.4076712182528546e+00 , 2.3726699340306734e+00 , 7.5974256000000002e+00 , 7.9179900000000003e-01 , -5.1593100000000003e-02 , 6.0859900000000000e-01 -3.3354945551946704e+00 , 2.4085140934433826e+00 , 7.6018248000000002e+00 , -2.8410299999999999e-02 , 2.4028099999999999e-01 , 9.7028800000000004e-01 -3.2937204463773986e+00 , 2.4459260474735629e+00 , 7.7786040000000005e+00 , 9.6385299999999993e-02 , -8.0378600000000000e-01 , 5.8705799999999997e-01 -3.2111334402809941e+00 , 2.4819294125145195e+00 , 7.7394064000000000e+00 , 9.6001999999999998e-01 , -2.6032800000000000e-01 , 1.0291000000000000e-01 -3.2669371381143693e+00 , 2.5399426991523346e+00 , 8.6242695999999999e+00 , 2.6324700000000001e-01 , -1.1561700000000000e-01 , -9.5777599999999996e-01 -3.0882545704136986e+00 , 2.5604914805366814e+00 , 7.9344688000000003e+00 , -9.3732300000000002e-01 , -2.4944900000000000e-01 , -2.4331000000000000e-01 -3.0142302457687276e+00 , 2.5991686457591929e+00 , 7.9630792000000010e+00 , -6.7892399999999997e-01 , -5.9353800000000001e-01 , -4.3217499999999998e-01 -2.9927732532022779e+00 , 2.6629312870519888e+00 , 8.5279552000000010e+00 , 5.6181099999999995e-01 , 6.4851599999999998e-01 , 5.1361000000000001e-01 -2.9128923488510110e+00 , 2.7096861863876667e+00 , 8.6059447999999996e+00 , 5.1897199999999997e-02 , -7.1336200000000005e-01 , 6.9887200000000005e-01 -2.8442144580531536e+00 , 2.7677880854649732e+00 , 8.8691376000000002e+00 , 5.0024199999999996e-01 , -8.3331200000000005e-01 , -2.3526500000000000e-01 -2.7189849003837478e+00 , 2.7664050034901466e+00 , 8.2189295999999992e+00 , -9.5121800000000001e-01 , -2.9914900000000000e-01 , -7.5455800000000003e-02 -2.6707669432017282e+00 , 2.8769187309890638e+00 , 9.1313528000000002e+00 , -8.9590499999999995e-01 , 3.1384200000000001e-01 , -3.1441700000000000e-01 -2.5764434157244276e+00 , 2.9273187436358135e+00 , 9.1821984000000008e+00 , 2.4205199999999999e-01 , -7.5977600000000001e-01 , 6.0345000000000004e-01 -2.4807433951221531e+00 , 2.9927383614449399e+00 , 9.3757944000000002e+00 , 1.6461400000000001e-01 , -6.2639999999999996e-01 , 7.6192199999999999e-01 -2.3947386900569350e+00 , 2.9233789742997689e+00 , 8.2120967999999994e+00 , -7.3252200000000001e-01 , -6.1298399999999997e-01 , -2.9607800000000001e-01 -2.2897239755467811e+00 , 3.0580967576930731e+00 , 9.0955143999999990e+00 , -2.5495600000000002e-01 , 3.3389299999999997e-02 , 9.6637600000000001e-01 -2.1742722287840861e+00 , 3.1580896366946147e+00 , 9.5513879999999993e+00 , -8.6179099999999997e-01 , 3.6530899999999999e-01 , -3.5194700000000001e-01 -1.9289234790763272e+00 , 3.5087065599255367e+00 , 1.1982408800000002e+01 , -9.6718999999999999e-01 , 2.5352599999999997e-01 , -1.6381000000000000e-02 -2.0976946470962528e+00 , 3.0282635006089533e+00 , 7.8102407999999999e+00 , 9.5371999999999998e-02 , -6.5029599999999999e-01 , 7.5367099999999998e-01 -2.0193585549876985e+00 , 3.0695334121824964e+00 , 7.8402656000000004e+00 , 2.6205000000000001e-01 , -5.4771400000000003e-01 , 7.9456899999999997e-01 -1.7703200614574406e+00 , 3.3439438402378228e+00 , 9.4548032000000006e+00 , -9.2142700000000000e-01 , -3.2197499999999997e-02 , -3.8721600000000000e-01 -4.5458256451035837e+00 , 1.1624584070865716e+00 , 1.4277150399999998e+00 , -6.4072000000000004e-02 , 2.4134300000000000e-01 , 9.6832300000000004e-01 -4.6095484690319406e+00 , 1.1306799239529215e+00 , 1.4416843199999998e+00 , -1.0546100000000000e-01 , 1.7033899999999999e-01 , 9.7972599999999999e-01 -4.6819636432021312e+00 , 1.0936068039938347e+00 , 1.4523193600000002e+00 , -5.3555699999999998e-02 , 1.7998800000000001e-01 , 9.8221000000000003e-01 -4.7551588318018183e+00 , 1.0569783119351075e+00 , 1.4653058400000001e+00 , -9.0399999999999994e-02 , 1.8940199999999999e-01 , 9.7772899999999996e-01 -4.8280475545960968e+00 , 1.0197677315067015e+00 , 1.4806229600000000e+00 , -1.0005799999999999e-01 , 2.1680700000000000e-01 , 9.7107299999999996e-01 -4.8938839838369352e+00 , 9.8855564719283229e-01 , 1.5031670400000001e+00 , -9.1217500000000007e-02 , 1.8037100000000000e-01 , 9.7936000000000001e-01 -4.9829564482843391e+00 , 9.4217835597238841e-01 , 1.5133060000000000e+00 , -9.9854799999999994e-02 , 1.8899700000000000e-01 , 9.7688799999999998e-01 -5.0649098225227291e+00 , 9.0082037183120467e-01 , 1.5310796000000000e+00 , 1.0465700000000000e-01 , -1.7580599999999999e-01 , -9.7884599999999999e-01 -5.1553928672011038e+00 , 8.5554610672649711e-01 , 1.5470342399999999e+00 , -5.6457500000000001e-02 , 1.7674000000000001e-01 , 9.8263699999999998e-01 -5.2465338957564800e+00 , 8.0980036468957994e-01 , 1.5660516799999999e+00 , -7.6703999999999994e-02 , 2.0233799999999999e-01 , 9.7630700000000004e-01 -5.3451192083575956e+00 , 7.6025789174221692e-01 , 1.5836297600000000e+00 , -7.5447100000000003e-02 , 1.8324799999999999e-01 , 9.8016700000000001e-01 -5.4541114533300199e+00 , 7.0491942305477373e-01 , 1.6009603200000000e+00 , -6.0031500000000002e-02 , 1.7519199999999999e-01 , 9.8270199999999996e-01 -5.5626816600607345e+00 , 6.5030187880340939e-01 , 1.6218331200000000e+00 , -5.5773000000000003e-02 , 1.9341900000000001e-01 , 9.7953000000000001e-01 -5.6630986298758241e+00 , 6.0072746324340964e-01 , 1.6502147199999999e+00 , -7.0990499999999998e-02 , 1.9835900000000001e-01 , 9.7755499999999995e-01 -5.7979870591300777e+00 , 5.3160133695790046e-01 , 1.6678874399999999e+00 , -5.2732599999999998e-02 , 1.9581999999999999e-01 , 9.7922100000000001e-01 -5.9246301028986448e+00 , 4.6765883278365772e-01 , 1.6937782399999999e+00 , -6.4949599999999996e-02 , 1.9119500000000000e-01 , 9.7940099999999997e-01 -6.0604975775445444e+00 , 3.9930419111957316e-01 , 1.7208120000000000e+00 , -7.9512399999999997e-02 , 1.9631199999999999e-01 , 9.7731199999999996e-01 -6.2054748829518598e+00 , 3.2668396575587666e-01 , 1.7496948800000001e+00 , -6.7881399999999995e-02 , 1.9209000000000001e-01 , 9.7902699999999998e-01 -6.3595114755277535e+00 , 2.4884348536419298e-01 , 1.7809364800000000e+00 , -1.1029200000000000e-01 , 2.0532200000000000e-01 , 9.7245999999999999e-01 -6.5225512871677180e+00 , 1.6694926353966677e-01 , 1.8150412000000000e+00 , 4.6262799999999998e-01 , -3.5802399999999998e-02 , -8.8583000000000001e-01 -6.6859532073175520e+00 , 8.6200208666759925e-02 , 1.8549366400000000e+00 , 7.8535500000000003e-01 , 6.4474400000000001e-02 , -6.1567899999999998e-01 -6.6899084857077664e+00 , 9.2286522235406121e-02 , 1.9439427519999999e+00 , -9.5487299999999997e-01 , -8.3870299999999995e-02 , 2.8492600000000001e-01 -6.6918037353289197e+00 , 9.8379708258623078e-02 , 2.0325960959999998e+00 , 9.9711700000000003e-01 , 6.7219200000000007e-02 , 3.5214200000000001e-02 -6.6564962816910134e+00 , 1.2566753994102497e-01 , 2.1288445600000001e+00 , 9.9287499999999995e-01 , 5.6816400000000003e-02 , 1.0474600000000001e-01 -6.6746269103987883e+00 , 1.2469495282369647e-01 , 2.2122130400000000e+00 , 9.9229199999999995e-01 , 8.8352000000000000e-02 , 8.6897600000000005e-02 -6.6354566915015738e+00 , 1.5266415353348139e-01 , 2.3058307199999999e+00 , 9.9485100000000004e-01 , 5.4554900000000003e-02 , -8.5415599999999994e-02 -6.6325426089430639e+00 , 1.6264251764600957e-01 , 2.3916182400000001e+00 , 9.9743300000000001e-01 , 7.0992500000000000e-02 , 9.3075999999999992e-03 -6.9000592806946761e+00 , 2.7635524408843093e-02 , 2.4373584799999999e+00 , 9.8926400000000003e-01 , 1.3524000000000000e-01 , 5.5375599999999997e-02 -6.6027325742614718e+00 , 1.9437674985229236e-01 , 2.5638172799999999e+00 , 9.8923099999999997e-01 , 9.9569800000000000e-02 , -1.0727900000000000e-01 -6.6589287107430399e+00 , 1.7140815600275761e-01 , 2.6410341600000002e+00 , 9.9604999999999999e-01 , 3.6388900000000002e-02 , -8.0991800000000003e-02 -6.7317157385921131e+00 , 1.4035286794905821e-01 , 2.7184600799999998e+00 , 9.8839699999999997e-01 , -6.5533499999999995e-02 , -1.3702700000000001e-01 -1.0422943839435803e+01 , -1.7981511340731524e+00 , 2.5647231200000000e+00 , -9.8604200000000003e-02 , 2.2455100000000000e-01 , 9.6946100000000002e-01 -1.0914368187375665e+01 , -2.0415413884207796e+00 , 2.7000770400000000e+00 , -9.0784199999999995e-02 , 2.1254200000000001e-01 , 9.7292599999999996e-01 -1.1643998205664198e+01 , -2.4083075864176431e+00 , 2.8483695999999998e+00 , -7.5601699999999994e-02 , 1.8554499999999999e-01 , 9.7972300000000001e-01 -1.2546835028119421e+01 , -2.8630460937212510e+00 , 3.0238155200000003e+00 , 7.2368399999999999e-02 , -1.9050000000000000e-01 , -9.7901600000000000e-01 -1.3605056359048017e+01 , -3.3955216297208990e+00 , 3.2366223999999999e+00 , -5.6549000000000002e-02 , 1.8051600000000001e-01 , 9.8194499999999996e-01 -1.5150472236333485e+01 , -4.1762241647925284e+00 , 3.5071471999999999e+00 , -5.4446399999999999e-02 , 1.8250800000000000e-01 , 9.8169600000000001e-01 -1.7182747522018090e+01 , -5.2025581422426184e+00 , 3.8639815999999998e+00 , -4.8895000000000001e-02 , 1.8774299999999999e-01 , 9.8099999999999998e-01 -1.9836264308850104e+01 , -6.5426699524010647e+00 , 4.3458136000000005e+00 , -8.9197499999999999e-02 , 1.8181100000000000e-01 , 9.7928000000000004e-01 -2.2980696621085738e+01 , -8.1242377477359540e+00 , 4.9771976000000002e+00 , -6.4339499999999994e-02 , 1.9809499999999999e-01 , 9.7806899999999997e-01 -2.6861258442078238e+01 , -1.0070713041400722e+01 , 5.8149904000000001e+00 , 1.8509900000000001e-01 , 7.6767200000000002e-01 , 6.1353000000000002e-01 -4.4349659252842102e+01 , -1.8782903934653358e+01 , 1.0253814400000000e+01 , -5.5480300000000005e-01 , 1.4515900000000000e-02 , 8.3185500000000001e-01 -4.4199166993052252e+01 , -1.8630467552436563e+01 , 1.1057224800000000e+01 , -5.1027000000000000e-01 , 4.1776199999999999e-03 , 8.6000399999999999e-01 -2.7448659163838034e+01 , -1.0145831909204185e+01 , 8.3555647999999998e+00 , -3.5476899999999999e-02 , 9.9376600000000004e-01 , -1.0569400000000000e-01 -2.7372585160744904e+01 , -1.0061080086631533e+01 , 8.8391024000000016e+00 , 1.9957500000000000e-01 , 8.9556800000000003e-01 , -3.9765200000000001e-01 -2.7324616968505151e+01 , -9.9919600973574418e+00 , 9.3298471999999997e+00 , 5.8578100000000000e-01 , 5.7717700000000005e-01 , -5.6896999999999998e-01 -2.1250954882376750e+01 , -6.4461626011015714e+00 , 1.3495640000000000e+01 , 6.9551399999999997e-01 , -7.1437399999999995e-01 , -7.7011899999999994e-02 -2.0724374203214889e+01 , -6.1591121341006669e+00 , 1.3638328000000000e+01 , 6.5057900000000002e-01 , -5.6516900000000003e-01 , -5.0727800000000001e-01 -7.2445374999397512e+00 , 3.4263336666859923e-01 , 7.8689903999999995e+00 , -1.2786900000000000e-02 , -7.9015100000000005e-01 , 6.1277899999999996e-01 -7.0820005609243033e+00 , 4.2644409642254089e-01 , 7.8655480000000004e+00 , 1.2668299999999999e-01 , 5.5969400000000002e-01 , -8.1895899999999999e-01 -6.7720099674235970e+00 , 5.7357611734511282e-01 , 7.6969535999999996e+00 , 5.3069900000000003e-02 , -3.0308499999999999e-01 , 9.5148500000000003e-01 -6.7765894363035164e+00 , 5.8590119840682742e-01 , 7.8592560000000002e+00 , -9.6798399999999996e-01 , 2.4878700000000001e-01 , -3.3348799999999998e-02 -6.8426275260222633e+00 , 5.7280141804611784e-01 , 8.0981959999999997e+00 , -3.0921199999999999e-01 , -7.2680699999999998e-01 , 6.1330200000000001e-01 -6.5727652091969038e+00 , 7.0001097393579625e-01 , 7.9499856000000007e+00 , 3.2591799999999999e-01 , -2.2632900000000000e-01 , 9.1790700000000003e-01 -6.5246631034899751e+00 , 7.3440413416743811e-01 , 8.0576880000000006e+00 , 4.4732699999999997e-01 , -6.6325699999999999e-01 , 5.9999100000000005e-01 -6.5315019027958563e+00 , 7.4772839190338192e-01 , 8.2359752000000004e+00 , 5.0298399999999999e-01 , -7.8211600000000003e-01 , 3.6783500000000002e-01 -6.4908724383455549e+00 , 7.8074999698492920e-01 , 8.3596000000000004e+00 , 9.5099500000000003e-02 , -8.4161300000000006e-01 , 5.3164199999999995e-01 -6.4523991565053400e+00 , 8.1208637712245291e-01 , 8.4910872000000008e+00 , -1.8392600000000001e-01 , -1.4327300000000001e-01 , 9.7244200000000003e-01 -6.2525378207431253e+00 , 9.0743182026381675e-01 , 8.3999416000000000e+00 , -3.4129999999999999e-01 , -1.6059300000000001e-01 , 9.2613400000000001e-01 -5.9874907804783106e+00 , 1.0276906726174881e+00 , 8.2024352000000000e+00 , 4.7009899999999999e-01 , -1.2617300000000001e-01 , -8.7354799999999999e-01 -5.7296910594581263e+00 , 1.1438157446472399e+00 , 7.9964735999999998e+00 , 4.0650100000000000e-01 , 8.3487699999999998e-02 , -9.0982799999999997e-01 -5.7436168405934112e+00 , 1.1542683259825919e+00 , 8.1936160000000005e+00 , 5.3317199999999998e-01 , 3.0396400000000001e-01 , -7.8951400000000005e-01 -5.8114214039773637e+00 , 1.1458030717281988e+00 , 8.4876032000000006e+00 , -6.1142399999999997e-01 , -6.7490099999999997e-01 , -4.1312199999999999e-01 -5.7449960580008455e+00 , 1.1885578415718068e+00 , 8.5749528000000002e+00 , -4.4555499999999998e-01 , -5.4239999999999999e-01 , -7.1223800000000004e-01 -5.4872331411951949e+00 , 1.3007322757378978e+00 , 8.3335791999999991e+00 , -6.0215700000000005e-01 , -4.7829100000000002e-01 , -6.3925299999999996e-01 -5.4617759718086658e+00 , 1.3284251302925587e+00 , 8.4866984000000016e+00 , -6.7898800000000004e-01 , -5.1475700000000002e-01 , -5.2345100000000000e-01 -5.4526614727083897e+00 , 1.3501457246322874e+00 , 8.6768727999999999e+00 , 1.9104099999999999e-02 , 4.6452399999999999e-01 , 8.8535500000000000e-01 -5.2255720910357368e+00 , 1.4483124274744026e+00 , 8.4568712000000001e+00 , 6.9898799999999997e-02 , -4.2607199999999998e-02 , 9.9664399999999997e-01 -5.1029072523808239e+00 , 1.5095383277846821e+00 , 8.4236639999999987e+00 , 1.7835500000000001e-01 , 1.2672100000000000e-01 , -9.7577199999999997e-01 -5.0072089411693526e+00 , 1.5610667460525887e+00 , 8.4429040000000004e+00 , -4.5317200000000002e-01 , 1.1900600000000000e-01 , -8.8344299999999998e-01 -4.9810862790104311e+00 , 1.5895298615398514e+00 , 8.6102191999999995e+00 , 5.9349499999999999e-01 , -5.1232500000000000e-02 , 8.0320499999999995e-01 -5.7887543569673596e+00 , 1.3583412376538657e+00 , 1.0686579200000001e+01 , -8.7164100000000000e-01 , -4.6449699999999999e-01 , 1.5647600000000000e-01 -4.7712753229517038e+00 , 1.6979426981456847e+00 , 8.6028663999999999e+00 , -2.7317100000000000e-01 , -4.5835399999999998e-01 , 8.4574800000000006e-01 -4.4904250010043878e+00 , 1.8043950319401438e+00 , 8.1542624000000004e+00 , 4.2064400000000002e-01 , -6.3529400000000003e-01 , -6.4765799999999996e-01 -4.3500489521650341e+00 , 1.8662519564472164e+00 , 8.0255311999999996e+00 , -5.0379700000000005e-01 , -7.7039999999999997e-02 , 8.6038000000000003e-01 -4.2704842400782201e+00 , 1.9093845076948304e+00 , 8.0487128000000006e+00 , 5.0379700000000005e-01 , 7.7039499999999997e-02 , -8.6038000000000003e-01 -4.1560495249714799e+00 , 1.9615759535481205e+00 , 7.9723872000000000e+00 , 3.0741800000000002e-01 , -2.3504400000000000e-01 , -9.2208900000000005e-01 -4.2315999709947878e+00 , 1.9662527343468443e+00 , 8.4544271999999996e+00 , -5.1369200000000004e-01 , 3.0744600000000000e-01 , -8.0099699999999996e-01 -4.1550767417462859e+00 , 2.0103997568381384e+00 , 8.5043888000000010e+00 , 7.0256099999999999e-01 , -2.4978900000000001e-01 , 6.6634300000000002e-01 -4.1163384752662093e+00 , 2.0478593900429649e+00 , 8.6820416000000016e+00 , -8.3468699999999996e-01 , 8.9887700000000001e-02 , -5.4334000000000005e-01 -4.0240568805428065e+00 , 2.0958814309896816e+00 , 8.6898936000000013e+00 , -7.5469900000000001e-01 , 2.1499399999999999e-01 , -6.1984399999999995e-01 -3.7948599242986694e+00 , 2.1683771529019755e+00 , 8.1733776000000002e+00 , -9.0400599999999998e-01 , -2.7905099999999999e-01 , 3.2388899999999998e-01 -3.6287459395973283e+00 , 2.2245003827593188e+00 , 7.8420231999999999e+00 , 7.1956900000000001e-01 , 3.7473499999999998e-01 , -5.8463200000000004e-01 -3.5248818741689361e+00 , 2.2688841793412822e+00 , 7.7292144000000009e+00 , 3.1047999999999998e-01 , 9.2259400000000003e-01 , 2.2895799999999999e-01 -3.4032689870375679e+00 , 2.3122000050794318e+00 , 7.5124367999999997e+00 , 7.6283100000000004e-01 , 4.1764400000000002e-01 , -4.9362200000000001e-01 -3.3446251867857280e+00 , 2.3491801901690192e+00 , 7.5780608000000003e+00 , 2.1278500000000000e-01 , -1.3153200000000001e-01 , 9.6820600000000001e-01 -3.2869145513381701e+00 , 2.3859018369321903e+00 , 7.6531488000000003e+00 , -1.6843900000000001e-01 , 7.2227900000000000e-01 , -6.7077699999999996e-01 -3.2262536917113778e+00 , 2.4246138065782339e+00 , 7.7269472000000006e+00 , 2.1704000000000001e-01 , -8.0193499999999995e-01 , 5.5659099999999995e-01 -3.2925675117662943e+00 , 2.4735475865245009e+00 , 8.6532960000000010e+00 , -1.7982000000000001e-01 , 4.3713900000000000e-01 , 8.8123399999999996e-01 -3.1138000137061335e+00 , 2.5058749217370409e+00 , 7.9745296000000003e+00 , 9.9768699999999999e-01 , -5.4894400000000003e-02 , 4.0088899999999997e-02 -3.0460775782875622e+00 , 2.5484325499825138e+00 , 8.0553480000000004e+00 , 8.2913099999999995e-01 , 3.8505899999999998e-01 , 4.0530400000000000e-01 -2.9719850515234176e+00 , 2.5901159296778369e+00 , 8.0935991999999999e+00 , -4.6685900000000002e-02 , 9.7768600000000006e-01 , 2.0481800000000000e-01 -2.9468204391622694e+00 , 2.6570925257444835e+00 , 8.6894463999999996e+00 , -8.0738500000000002e-01 , 4.7148299999999999e-01 , -3.5472999999999999e-01 -2.8783134193135460e+00 , 2.7163878404973798e+00 , 8.9427799999999991e+00 , -5.0511799999999996e-01 , 6.7849499999999996e-01 , -5.3338600000000003e-01 -2.7725834692084343e+00 , 2.7489637310434540e+00 , 8.6971735999999993e+00 , 5.3973599999999999e-01 , 8.4138400000000002e-01 , 2.7533400000000000e-02 -2.6805063189946008e+00 , 2.7855232617892374e+00 , 8.5638560000000012e+00 , -2.5293000000000000e-03 , 2.7038400000000001e-01 , 9.6274899999999997e-01 -2.6116167104999470e+00 , 2.8786331684474518e+00 , 9.1957599999999999e+00 , 3.2034499999999999e-01 , -6.3501700000000005e-01 , 7.0294599999999996e-01 -2.5177832376739167e+00 , 2.9360278883769664e+00 , 9.2866871999999994e+00 , -1.3784600000000000e-01 , 7.4637699999999996e-01 , -6.5109099999999998e-01 -2.4250311180014390e+00 , 2.9010329172998990e+00 , 8.3817103999999993e+00 , -9.4012499999999999e-01 , 3.3440300000000001e-01 , 6.5884799999999993e-02 -2.3407051290535872e+00 , 2.9541896041872850e+00 , 8.4799799999999994e+00 , 9.1394699999999995e-01 , -4.0072300000000000e-01 , -6.4194500000000002e-02 -2.2346273439843412e+00 , 3.0652658921552485e+00 , 9.0929871999999996e+00 , 8.1810300000000002e-01 , -5.6751499999999999e-01 , -9.2918799999999996e-02 -1.9810958583014648e+00 , 3.4789267990467980e+00 , 1.2177720800000001e+01 , -9.7101999999999999e-01 , 2.2640399999999999e-01 , -7.6554200000000003e-02 -1.8288154002260717e+00 , 3.5704619511775832e+00 , 1.2315011199999999e+01 , -7.9298599999999997e-01 , -5.6979800000000003e-01 , -2.1564800000000001e-01 -1.6929765792706069e+00 , 3.6300466708947035e+00 , 1.2191760800000001e+01 , -1.1360200000000001e-02 , 9.2895300000000003e-01 , 3.7002299999999999e-01 -1.5413097066816386e+00 , 3.7163473833475988e+00 , 1.2271508000000001e+01 , -9.6778200000000003e-01 , -1.9153400000000001e-01 , -1.6343900000000000e-01 -1.7366351027564746e+00 , 3.3434612524078995e+00 , 9.2923968000000006e+00 , 5.6626600000000005e-01 , -8.1316600000000006e-01 , 1.3455000000000000e-01 -4.4959928429497324e+00 , 1.1189623320041564e+00 , 1.4172495199999999e+00 , -9.9660499999999999e-02 , 2.0339900000000000e-01 , 9.7401099999999996e-01 -4.5518037675274723e+00 , 1.0896230181113968e+00 , 1.4364073600000000e+00 , -1.2157200000000000e-01 , 2.0130700000000001e-01 , 9.7195500000000001e-01 -4.6153056779914952e+00 , 1.0549558651729274e+00 , 1.4518014400000001e+00 , -4.5467000000000000e-02 , 1.8233099999999999e-01 , 9.8218499999999997e-01 -4.6864854812807639e+00 , 1.0160724291125560e+00 , 1.4637333600000000e+00 , -6.0997999999999997e-02 , 2.0953400000000000e-01 , 9.7589700000000001e-01 -4.7584351063071182e+00 , 9.7763155479150421e-01 , 1.4780167199999998e+00 , 9.4329600000000000e-02 , -2.1877900000000000e-01 , -9.7120399999999996e-01 -4.8300884582204748e+00 , 9.3861065826181411e-01 , 1.4946307200000000e+00 , -7.0749900000000004e-02 , 2.0914700000000000e-01 , 9.7532200000000002e-01 -4.9103698276269965e+00 , 8.9550240927146940e-01 , 1.5086145599999998e+00 , -6.1485999999999999e-02 , 1.9174200000000000e-01 , 9.7951800000000000e-01 -4.9835103513734396e+00 , 8.5636912796136433e-01 , 1.5302372000000000e+00 , -9.7001400000000002e-02 , 2.0496400000000001e-01 , 9.7395100000000001e-01 -5.0719767787879437e+00 , 8.0774668215498369e-01 , 1.5449375999999999e+00 , -7.8548000000000007e-02 , 1.8429200000000001e-01 , 9.7972800000000004e-01 -5.1611576559298209e+00 , 7.5968291191371629e-01 , 1.5625967999999999e+00 , -5.3232799999999997e-02 , 1.9711400000000001e-01 , 9.7893399999999997e-01 -5.2509801257731699e+00 , 7.1117617665642707e-01 , 1.5834196800000000e+00 , -7.2049100000000005e-02 , 1.9068499999999999e-01 , 9.7900399999999999e-01 -5.3492768940467901e+00 , 6.5886927426140751e-01 , 1.6030299200000000e+00 , -5.1332700000000002e-02 , 1.9140699999999999e-01 , 9.8016800000000004e-01 -5.4558939820547163e+00 , 6.0079969433602609e-01 , 1.6221409600000001e+00 , -2.9421800000000001e-02 , 1.8906999999999999e-01 , 9.8152300000000003e-01 -5.5795596823915430e+00 , 5.3275184985317603e-01 , 1.6375184000000000e+00 , -5.8745699999999998e-02 , 2.0535900000000001e-01 , 9.7692199999999996e-01 -5.6786089199680134e+00 , 4.8050197682136941e-01 , 1.6681110399999999e+00 , -7.2922899999999999e-02 , 1.9049099999999999e-01 , 9.7897699999999999e-01 -5.8110328059435439e+00 , 4.0772464025606370e-01 , 1.6882756000000001e+00 , -6.1400099999999999e-02 , 1.9512399999999999e-01 , 9.7885500000000003e-01 -5.9362413208179170e+00 , 3.4012748957473882e-01 , 1.7167840800000000e+00 , -7.2233300000000000e-02 , 1.9893300000000000e-01 , 9.7734699999999997e-01 -6.0696114698340340e+00 , 2.6817866146323355e-01 , 1.7465114399999999e+00 , -6.8021399999999996e-02 , 1.9347400000000001e-01 , 9.7874499999999998e-01 -6.2217551441137262e+00 , 1.8569924641756907e-01 , 1.7753891200000000e+00 , -7.5974700000000006e-02 , 1.8883300000000000e-01 , 9.7906599999999999e-01 -6.3732616287087742e+00 , 1.0432160341084207e-01 , 1.8096290399999999e+00 , -8.0217899999999995e-02 , 1.8698100000000001e-01 , 9.7908300000000004e-01 -6.5423333874130725e+00 , 1.2720248082902508e-02 , 1.8443109600000001e+00 , -3.2632499999999998e-01 , 1.0583300000000000e-01 , 9.3931399999999998e-01 -6.7299122802503817e+00 , -8.8935118135363034e-02 , 1.8804696800000000e+00 , -6.4517800000000003e-01 , 8.8284000000000001e-02 , 7.5891500000000001e-01 -6.7593061877280052e+00 , -9.8724179704119397e-02 , 1.9646357360000000e+00 , -9.0981900000000004e-01 , -1.1896600000000000e-02 , 4.1483399999999998e-01 -6.7257248789782258e+00 , -7.0895433698379140e-02 , 2.0639682160000001e+00 , 9.9678999999999995e-01 , 8.0052399999999996e-02 , 1.4735600000000001e-03 -6.7083445372646908e+00 , -5.3365339793304045e-02 , 2.1578220799999999e+00 , 9.8879300000000003e-01 , 1.2456100000000001e-01 , 8.2293199999999997e-02 -6.7166183738273633e+00 , -4.9894802536023075e-02 , 2.2453120800000002e+00 , -9.7772199999999998e-01 , -1.6465199999999999e-01 , 1.3019200000000000e-01 -6.6963552735048717e+00 , -3.0497810689845917e-02 , 2.3372657600000002e+00 , -9.0890899999999997e-01 , -2.2119400000000000e-01 , 3.5349399999999997e-01 -6.8262768120125834e+00 , -9.7893002386208128e-02 , 2.4046639999999999e+00 , 9.9292000000000002e-01 , -8.2971199999999995e-02 , 8.5001300000000002e-02 -6.7227388175318445e+00 , -3.0147629341353621e-02 , 2.5080285600000001e+00 , -9.6452000000000004e-01 , -1.4918000000000001e-01 , -2.1782299999999999e-01 -6.6975410563627040e+00 , -8.8646082460539510e-03 , 2.5977296000000001e+00 , -8.8632400000000000e-01 , -2.6489800000000000e-03 , -4.6305800000000003e-01 -6.7259840049648201e+00 , -1.7679171083619050e-02 , 2.6812603199999998e+00 , -9.4603400000000004e-01 , -2.7322700000000000e-01 , 1.7425800000000000e-01 -6.9510637856299242e+00 , -1.3755056886002182e-01 , 2.7509382400000000e+00 , -8.5601400000000005e-01 , -9.2499799999999993e-02 , 5.0861000000000001e-01 -1.0461800197489795e+01 , -2.1065722558443767e+00 , 2.6549202400000000e+00 , -8.0372499999999999e-02 , 2.2410900000000000e-01 , 9.7124400000000000e-01 -1.1107980195390709e+01 , -2.4556398191903526e+00 , 2.7942095199999999e+00 , -8.0674399999999993e-02 , 1.8985900000000000e-01 , 9.7849100000000000e-01 -1.1915281066280285e+01 , -2.8929967150598612e+00 , 2.9565129600000000e+00 , -6.8993799999999994e-02 , 1.9198899999999999e-01 , 9.7896899999999998e-01 -1.2840044094148238e+01 , -3.3925068087391921e+00 , 3.1515919999999999e+00 , -7.1277099999999996e-02 , 1.9199300000000000e-01 , 9.7880500000000004e-01 -1.4107842347351315e+01 , -4.0801916912678289e+00 , 3.3924143999999998e+00 , -5.1045699999999999e-02 , 1.8267400000000000e-01 , 9.8184700000000003e-01 -1.5963836017312964e+01 , -5.0886078560204071e+00 , 3.7109768000000001e+00 , -5.6137699999999999e-02 , 1.8414200000000000e-01 , 9.8129500000000003e-01 -1.8151662784463507e+01 , -6.2755846865507117e+00 , 4.1256456000000004e+00 , -4.9990500000000000e-02 , 1.7777200000000001e-01 , 9.8280100000000004e-01 -2.0706000685630279e+01 , -7.6561964012478327e+00 , 4.6592072000000000e+00 , -8.7608199999999997e-02 , 1.8808000000000000e-01 , 9.7823899999999997e-01 -4.5796235626314648e+01 , -2.1108804737187928e+01 , 1.1171136000000001e+01 , -9.5770500000000003e-01 , 2.7759099999999998e-01 , -7.5792999999999999e-02 -4.7078075527797864e+01 , -2.0655833188671366e+01 , 2.4687183999999998e+01 , 4.5946799999999999e-01 , -8.7902800000000003e-01 , 1.2727300000000000e-01 -6.7092820954044088e+00 , 4.2068231630731878e-01 , 7.6467424000000008e+00 , -3.0295899999999998e-01 , 6.3883299999999998e-01 , -7.0718300000000001e-01 -6.7617022950097665e+00 , 4.1047799524344919e-01 , 7.8602752000000002e+00 , 6.2230899999999999e-02 , 9.5275600000000005e-01 , -2.9729200000000000e-01 -6.6716647675895810e+00 , 4.6559456171179381e-01 , 7.9196280000000003e+00 , 2.4792100000000001e-02 , -7.1950999999999998e-01 , 6.9403899999999996e-01 -6.5554854755418681e+00 , 5.3324990196703270e-01 , 7.9460439999999997e+00 , 5.8704300000000001e-02 , -4.5577000000000001e-01 , 8.8815999999999995e-01 -6.4576404506637406e+00 , 5.9144226937890743e-01 , 7.9926256000000002e+00 , -3.1572000000000003e-02 , -4.6998600000000001e-01 , 8.8210900000000003e-01 -6.3231930196614030e+00 , 6.6666391301258399e-01 , 7.9894536000000000e+00 , 6.8212300000000003e-02 , -7.4114700000000000e-01 , 6.6786900000000005e-01 -6.2618224370357813e+00 , 7.0840592150896131e-01 , 8.0781448000000005e+00 , 1.5965000000000000e-03 , -8.4817100000000001e-01 , 5.2971999999999997e-01 -6.2531170433523151e+00 , 7.2732311109768877e-01 , 8.2387000000000015e+00 , 1.5459800000000001e-01 , 8.6626899999999996e-01 , -4.7505500000000001e-01 -6.1772048640463471e+00 , 7.7578449036715136e-01 , 8.3101792000000003e+00 , -3.8687500000000002e-01 , 8.8261699999999998e-01 , -2.6705000000000001e-01 -5.9729194135391364e+00 , 8.8060057998714170e-01 , 8.1965591999999994e+00 , -5.6111699999999998e-01 , -2.1903300000000001e-01 , 7.9823100000000002e-01 -5.7567562721264061e+00 , 9.8815553159579661e-01 , 8.0518016000000010e+00 , 4.4296799999999997e-01 , -1.0223100000000000e-01 , -8.9068999999999998e-01 -5.6497547345213626e+00 , 1.0489592335863533e+00 , 8.0620143999999989e+00 , 1.2445500000000000e-01 , -3.8404199999999999e-01 , 9.1488999999999998e-01 -5.9712379614128110e+00 , 9.2946536949642833e-01 , 8.7602183999999994e+00 , 9.5352599999999998e-01 , 3.0094100000000001e-01 , 1.4919300000000000e-02 -5.8598013319403037e+00 , 9.9377381631181327e-01 , 8.7815904000000007e+00 , -9.0017899999999995e-01 , -4.3530300000000000e-01 , 1.3759800000000001e-02 -5.8407591061864341e+00 , 1.0197639830296059e+00 , 8.9592327999999988e+00 , 7.8675099999999998e-01 , 6.0494300000000001e-01 , 1.2275000000000000e-01 -5.5346727614019811e+00 , 1.1628167448378726e+00 , 8.6289183999999999e+00 , -4.6272900000000000e-01 , -4.6421200000000001e-01 , -7.5524100000000005e-01 -5.4079281718626744e+00 , 1.2312910084559121e+00 , 8.6044368000000002e+00 , 4.4058399999999998e-01 , 6.6835199999999995e-01 , 5.9932600000000003e-01 -5.1850290418951506e+00 , 1.3369499313860693e+00 , 8.3856104000000009e+00 , 8.4919999999999995e-02 , -2.5949600000000000e-01 , 9.6200300000000005e-01 -5.0870274252396843e+00 , 1.3926168479361634e+00 , 8.3985896000000011e+00 , 1.9065699999999999e-01 , 3.8546100000000000e-02 , 9.8089999999999999e-01 -5.0025879289420310e+00 , 1.4433077529227434e+00 , 8.4371736000000013e+00 , 6.2752200000000002e-01 , -9.4084799999999996e-02 , 7.7289300000000005e-01 -4.8112933970768861e+00 , 1.5329309329755434e+00 , 8.2403535999999988e+00 , -5.3334700000000002e-01 , -5.1732500000000003e-01 , 6.6926500000000000e-01 -4.7041431953529393e+00 , 1.5901231099115347e+00 , 8.2167664000000009e+00 , 5.6191199999999997e-01 , -5.3610199999999997e-01 , 6.2995999999999996e-01 -4.6673271800978950e+00 , 1.6232301126604800e+00 , 8.3521536000000012e+00 , -7.7599099999999999e-01 , 6.3059799999999999e-01 , 1.3545200000000000e-02 -4.5647161848468301e+00 , 1.6792307390282801e+00 , 8.3341512000000009e+00 , -3.0158900000000000e-01 , 8.1102599999999997e-02 , 9.4998199999999999e-01 -4.3556028643103577e+00 , 1.7700679929062579e+00 , 8.0341839999999998e+00 , -5.0379700000000005e-01 , -7.7039700000000003e-02 , 8.6038000000000003e-01 -4.2519012708824828e+00 , 1.8230206340886710e+00 , 7.9902752000000001e+00 , 3.0741800000000002e-01 , -2.3504400000000000e-01 , -9.2208900000000005e-01 -4.1406403148759292e+00 , 1.8793954371640484e+00 , 7.9143136000000007e+00 , 2.5605800000000001e-01 , -3.2351200000000002e-01 , -9.1091999999999995e-01 -4.0576655709443568e+00 , 1.9254255581478603e+00 , 7.9142720000000004e+00 , 3.5975800000000002e-01 , -3.3792600000000000e-01 , -8.6970099999999995e-01 -4.1656716811036425e+00 , 1.9176157026279050e+00 , 8.5151736000000007e+00 , 7.7644400000000002e-01 , -2.2426900000000000e-02 , 6.2978699999999999e-01 -4.1130162891622408e+00 , 1.9575100826672414e+00 , 8.6439775999999995e+00 , -8.7766500000000003e-01 , -1.0105800000000000e-01 , -4.6849900000000000e-01 -4.0346915398906038e+00 , 2.0056235430623284e+00 , 8.6921503999999992e+00 , -7.7685199999999999e-01 , 1.0391300000000001e-01 , -6.2105100000000002e-01 -3.9574120283042182e+00 , 2.0532920302908884e+00 , 8.7488823999999994e+00 , 7.2455899999999995e-01 , -2.2244500000000000e-01 , 6.5232900000000005e-01 -3.6307188032348972e+00 , 2.1546197541879111e+00 , 7.8065487999999998e+00 , -8.3222499999999999e-01 , -1.8054500000000001e-01 , 5.2421799999999996e-01 -3.5046989646382967e+00 , 2.2072692089961441e+00 , 7.5929952000000007e+00 , 6.9403400000000004e-01 , 6.1281699999999995e-01 , -3.7785299999999999e-01 -3.4227786957120854e+00 , 2.2486732726703273e+00 , 7.5491383999999995e+00 , -8.8516300000000003e-01 , -2.0534800000000000e-01 , 4.1751500000000002e-01 -3.3756393521831196e+00 , 2.2849652109642826e+00 , 7.6665023999999997e+00 , -6.4154900000000004e-01 , -2.5256800000000001e-01 , -7.2430899999999998e-01 -3.2998224297830792e+00 , 2.3263084401692748e+00 , 7.6499872000000009e+00 , -9.3421900000000002e-02 , 6.1765000000000003e-01 , 7.8088500000000005e-01 -3.2214082950268770e+00 , 2.3665394746873183e+00 , 7.6115903999999999e+00 , 1.0750800000000000e-02 , -5.2030100000000001e-01 , 8.5391499999999998e-01 -3.1638051735134702e+00 , 2.4059763326223775e+00 , 7.6948943999999999e+00 , 5.8746199999999998e-02 , -7.6323200000000002e-01 , 6.4344800000000002e-01 -3.1353544826146558e+00 , 2.4482272992553638e+00 , 8.0039407999999987e+00 , -9.5448200000000005e-01 , -2.3627400000000001e-01 , 1.8203900000000001e-01 -3.0759953507441367e+00 , 2.4935000205152207e+00 , 8.1369360000000004e+00 , -7.6973000000000003e-01 , -4.5831600000000000e-01 , -4.4436700000000001e-01 -2.9957846396205223e+00 , 2.5368878807482869e+00 , 8.1138064000000014e+00 , -2.4655400000000000e-01 , -9.6745899999999996e-01 , -5.6864999999999999e-02 -2.9588679711920061e+00 , 2.5944669386041550e+00 , 8.5550992000000008e+00 , 8.3612399999999998e-01 , -4.4625700000000001e-01 , 3.1898399999999999e-01 -2.8877352751417886e+00 , 2.6489376409881134e+00 , 8.7259607999999993e+00 , -8.4533300000000000e-01 , 1.0062400000000001e-01 , -5.2467699999999995e-01 -2.8069081695688061e+00 , 2.7017318227259337e+00 , 8.8126448000000011e+00 , -9.3464800000000003e-01 , 3.5227700000000001e-01 , 4.8310899999999997e-02 -2.7291138014973719e+00 , 2.7632055290207962e+00 , 9.0221112000000012e+00 , -7.5486600000000004e-01 , -6.0744200000000004e-01 , -2.4736900000000001e-01 -2.6399599711224853e+00 , 2.8178783332905124e+00 , 9.0741736000000000e+00 , -6.8153200000000003e-01 , -1.0985300000000001e-01 , -7.2349600000000003e-01 -2.5522491446945792e+00 , 2.8854034487330331e+00 , 9.2799376000000002e+00 , 2.3246800000000001e-01 , -7.7335299999999996e-01 , 5.8981700000000004e-01 -2.4576015552258617e+00 , 2.9498871768467794e+00 , 9.4216896000000006e+00 , 1.6461400000000001e-01 , -6.2640099999999999e-01 , 7.6192199999999999e-01 -2.3762825417623188e+00 , 2.8989770906201691e+00 , 8.3084008000000011e+00 , -9.4739600000000002e-01 , 3.1917099999999998e-01 , 2.3875100000000000e-02 -2.2718173200549368e+00 , 3.0264821878629391e+00 , 9.1087015999999998e+00 , -6.2488500000000002e-01 , -2.5393200000000001e-02 , -7.8030400000000000e-01 -2.1527318793962813e+00 , 3.1451596918475215e+00 , 9.7091975999999995e+00 , -2.0913300000000001e-01 , 6.9437499999999996e-01 , -6.8855400000000000e-01 -1.9150868358736168e+00 , 3.4718599645390524e+00 , 1.1944136799999999e+01 , -9.3408999999999998e-01 , 2.0228199999999999e-01 , -2.9420499999999999e-01 -2.0936372463065731e+00 , 3.0107979105289844e+00 , 7.7806632000000002e+00 , 1.6043300000000000e-02 , -5.5659700000000001e-01 , 8.3062800000000003e-01 -1.6172105249463646e+00 , 3.6577603071970941e+00 , 1.2181381600000000e+01 , -3.9623700000000001e-01 , 1.0831900000000000e-01 , 9.1173599999999999e-01 -1.7830322454068972e+00 , 3.3177953320637492e+00 , 9.3119280000000018e+00 , -3.6602499999999999e-01 , -3.4216900000000000e-01 , -8.6541699999999999e-01 -4.4302604459842589e+00 , 1.0859533384846098e+00 , 1.4185630400000000e+00 , -1.0999100000000001e-01 , 2.0974799999999999e-01 , 9.7154900000000000e-01 -4.4851056889261356e+00 , 1.0554101764543522e+00 , 1.4367890400000001e+00 , -1.0380000000000000e-01 , 2.1781600000000001e-01 , 9.7045499999999996e-01 -4.5476058372887405e+00 , 1.0185131552031423e+00 , 1.4514571999999999e+00 , -1.0589999999999999e-01 , 2.1055599999999999e-01 , 9.7182900000000005e-01 -4.6178506751321677e+00 , 9.7837903986530605e-01 , 1.4622544799999999e+00 , -7.7243699999999998e-02 , 2.0560300000000001e-01 , 9.7558199999999995e-01 -4.6809218849644552e+00 , 9.4227691604008545e-01 , 1.4809931999999999e+00 , -7.2714600000000004e-02 , 2.0166100000000001e-01 , 9.7675199999999995e-01 -4.7516164498198643e+00 , 9.0097119352631805e-01 , 1.4965765599999998e+00 , -6.8741200000000002e-02 , 2.2103200000000001e-01 , 9.7284099999999996e-01 -4.8220528881888685e+00 , 8.6010127628674615e-01 , 1.5142836000000000e+00 , 5.3132699999999998e-02 , -2.0930099999999999e-01 , -9.7640700000000002e-01 -4.9089230681660343e+00 , 8.0961658412749093e-01 , 1.5246877599999999e+00 , -5.9067599999999998e-02 , 1.9724900000000001e-01 , 9.7857200000000000e-01 -4.9875609557185498e+00 , 7.6320395815569397e-01 , 1.5430104800000000e+00 , -9.0378500000000001e-02 , 2.1383199999999999e-01 , 9.7268100000000002e-01 -5.0602072802921780e+00 , 7.2273956093118130e-01 , 1.5684842400000001e+00 , -6.3875799999999996e-02 , 1.9953199999999999e-01 , 9.7780699999999998e-01 -5.1548309834380026e+00 , 6.6640913046157801e-01 , 1.5831482399999999e+00 , -5.7424000000000003e-02 , 1.9628000000000001e-01 , 9.7886499999999999e-01 -5.2511418506377723e+00 , 6.1070721622491786e-01 , 1.6013014400000001e+00 , -5.7723999999999998e-02 , 2.1474699999999999e-01 , 9.7496300000000002e-01 -5.3480717208803634e+00 , 5.5462142696565331e-01 , 1.6229230399999999e+00 , -3.8738300000000003e-02 , 2.1787300000000001e-01 , 9.7520799999999996e-01 -5.4533517928396904e+00 , 4.9382955842849752e-01 , 1.6440423200000001e+00 , -1.1942800000000000e-02 , 1.9284799999999999e-01 , 9.8115600000000003e-01 -5.5746238788754487e+00 , 4.2308930731630712e-01 , 1.6614030399999999e+00 , -6.2412799999999997e-02 , 1.9876800000000000e-01 , 9.7805699999999995e-01 -5.6799746146485202e+00 , 3.6179179836796305e-01 , 1.6905459199999999e+00 , -6.9436399999999995e-02 , 2.0188300000000001e-01 , 9.7694499999999995e-01 -5.8109681040519394e+00 , 2.8533942991075523e-01 , 1.7132272799999999e+00 , -5.3764800000000001e-02 , 1.9324300000000000e-01 , 9.7967700000000002e-01 -5.9424125524207927e+00 , 2.0880869097764632e-01 , 1.7408933600000001e+00 , -6.6793800000000000e-02 , 2.0585800000000001e-01 , 9.7629999999999995e-01 -6.0829934154189997e+00 , 1.2798592258977792e-01 , 1.7703087200000001e+00 , -6.2063599999999997e-02 , 1.9219700000000001e-01 , 9.7939200000000004e-01 -6.2315244956922315e+00 , 4.0975272897300075e-02 , 1.8022637600000000e+00 , -6.3513399999999998e-02 , 1.9266100000000000e-01 , 9.7920799999999997e-01 -6.3977162967592678e+00 , -5.5316538528671799e-02 , 1.8341522399999999e+00 , -6.7445099999999994e-02 , 1.8746699999999999e-01 , 9.7995299999999996e-01 -6.5737606305982057e+00 , -1.5754856262916661e-01 , 1.8702475199999999e+00 , 2.9768600000000001e-01 , -1.7150699999999999e-01 , -9.3913199999999997e-01 -6.7576429073903608e+00 , -2.6358241122089421e-01 , 1.9101919439999999e+00 , 4.5575100000000002e-01 , -1.5915599999999998e-02 , -8.8996500000000001e-01 -6.9683472737742962e+00 , -3.8650579954851949e-01 , 1.9511186480000000e+00 , -9.7521199999999997e-01 , -2.1021999999999999e-01 , -6.9065900000000000e-02 -7.1003010639455342e+00 , -4.6047141622170784e-01 , 2.0179761919999999e+00 , -8.6060400000000004e-01 , -4.9775000000000003e-01 , 1.0773500000000000e-01 -6.8056050111312283e+00 , -2.7006380859725398e-01 , 2.1781280800000000e+00 , 9.9427500000000002e-01 , 1.0279800000000000e-01 , -2.9150700000000002e-02 -6.7774366076871067e+00 , -2.4606155949494779e-01 , 2.2754658399999999e+00 , -9.8781099999999999e-01 , -8.8994500000000004e-02 , 1.2770699999999999e-01 -6.8361806852921729e+00 , -2.7468956706952374e-01 , 2.3567200000000001e+00 , 9.9830600000000003e-01 , 2.1097400000000001e-03 , 5.8137599999999998e-02 -6.7702770614917700e+00 , -2.2707507615872036e-01 , 2.4577747200000002e+00 , 9.9123899999999998e-01 , 9.8987000000000006e-02 , 8.7444999999999995e-02 -6.7374202625798194e+00 , -1.9941781045764850e-01 , 2.5511355199999999e+00 , 9.7487299999999999e-01 , 3.7394100000000000e-02 , 2.1959999999999999e-01 -6.7655534472620333e+00 , -2.0989750567251209e-01 , 2.6368980799999999e+00 , -9.5251900000000000e-01 , -5.4046200000000003e-02 , 2.9964299999999999e-01 -1.0056169390541051e+01 , -2.1776874255095713e+00 , 2.6106734400000002e+00 , -6.6172499999999995e-02 , 2.1199100000000001e-01 , 9.7502900000000003e-01 -1.0637536499035077e+01 , -2.5149879651702367e+00 , 2.7418174400000002e+00 , -7.3212600000000003e-02 , 2.0868200000000001e-01 , 9.7523899999999997e-01 -1.1325260801238514e+01 , -2.9131591526514979e+00 , 2.8939028800000002e+00 , -7.2502100000000000e-02 , 1.9665199999999999e-01 , 9.7778900000000002e-01 -1.2181772615907807e+01 , -3.4096957981858163e+00 , 3.0733736000000000e+00 , -6.6704500000000000e-02 , 1.9849300000000000e-01 , 9.7782999999999998e-01 -1.3242006763944639e+01 , -4.0250743907829678e+00 , 3.2914719999999997e+00 , 6.1803600000000000e-02 , -1.9009799999999999e-01 , -9.7981799999999997e-01 -1.4790258315545604e+01 , -4.9281790577032556e+00 , 3.5716792000000002e+00 , -4.7051500000000003e-02 , 1.8507399999999999e-01 , 9.8159799999999997e-01 -1.6586323937419408e+01 , -5.9718020808362828e+00 , 3.9294600000000002e+00 , -5.8647499999999998e-02 , 1.8229600000000001e-01 , 9.8149299999999995e-01 -1.9573877842435135e+01 , -7.7133579134369121e+00 , 4.4556687999999998e+00 , -9.2367500000000005e-02 , 1.8799600000000000e-01 , 9.7781700000000005e-01 -2.2160111469010150e+01 , -9.2099610313184161e+00 , 5.0630183999999998e+00 , -8.2863000000000006e-02 , 1.8986700000000001e-01 , 9.7830700000000004e-01 -3.5800222299775335e+01 , -1.7081859210190039e+01 , 8.4717327999999998e+00 , -1.6860200000000000e-01 , 4.9812699999999999e-01 , 8.5055400000000003e-01 -3.6023118031915182e+01 , -1.7154888385632745e+01 , 9.1950111999999997e+00 , -9.5598699999999995e-02 , 1.5906000000000001e-01 , 9.8263000000000000e-01 -7.5112774196648671e+00 , -1.5822542165281916e-01 , 8.7180776000000009e+00 , -1.1329100000000000e-01 , -1.9175200000000000e-02 , 9.9337699999999995e-01 -6.5613575894458558e+00 , 3.3587740153300949e-01 , 7.8161480000000010e+00 , -2.0054000000000001e-03 , -6.8013100000000004e-01 , 7.3308799999999996e-01 -6.4547529756777609e+00 , 4.0247056387386260e-01 , 7.8498960000000002e+00 , 1.7497499999999999e-01 , 5.7963299999999995e-01 , -7.9586999999999997e-01 -6.3664601775333924e+00 , 4.5960681374168133e-01 , 7.9038095999999998e+00 , -1.9670000000000001e-01 , -5.2081900000000003e-01 , 8.3069700000000002e-01 -6.2658067481895756e+00 , 5.2322540043746768e-01 , 7.9398455999999999e+00 , -3.3101699999999998e-02 , -6.2693699999999997e-01 , 7.7836700000000003e-01 -6.1528345688491202e+00 , 5.9212509996676888e-01 , 7.9572968000000008e+00 , 8.0739599999999995e-02 , -7.8207300000000002e-01 , 6.1793399999999998e-01 -6.1106041555957242e+00 , 6.2587271753434504e-01 , 8.0683895999999997e+00 , 1.6524600000000000e-02 , -7.9056899999999997e-01 , 6.1214999999999997e-01 -6.0495617942265740e+00 , 6.6924115379942251e-01 , 8.1546471999999994e+00 , -1.9503699999999999e-01 , -6.9114799999999998e-01 , 6.9589800000000002e-01 -5.9520964954564608e+00 , 7.3042866460066813e-01 , 8.1898511999999997e+00 , 4.1748099999999999e-01 , 1.6294800000000001e-01 , -8.9395599999999997e-01 -6.0720025560683828e+00 , 6.8846585910377556e-01 , 8.5500240000000005e+00 , -2.4158399999999999e-01 , 8.8061999999999996e-01 , -4.0761100000000000e-01 -5.9319292559987753e+00 , 7.7018737988997787e-01 , 8.5251887999999987e+00 , -5.4077799999999998e-01 , 7.7057600000000004e-01 , -3.3730199999999999e-01 -5.9638125834920306e+00 , 7.7172670320812209e-01 , 8.7715128000000000e+00 , 8.4643199999999996e-01 , 4.7965099999999999e-01 , 2.3127300000000001e-01 -5.7558148714783375e+00 , 8.8365341944097064e-01 , 8.6291575999999992e+00 , -8.0214799999999997e-01 , -5.2478999999999998e-01 , 2.8487499999999999e-01 -5.9066115135294224e+00 , 8.3205638187138620e-01 , 9.0956703999999995e+00 , -2.7507299999999998e-03 , -9.8009299999999999e-01 , 1.9851800000000000e-01 -5.4681344849897116e+00 , 1.0468851158894077e+00 , 8.5294632000000004e+00 , -4.6272900000000000e-01 , -4.6421200000000001e-01 , -7.5524100000000005e-01 -5.7667880862056080e+00 , 9.3139062656988858e-01 , 9.2953504000000002e+00 , -2.3404100000000000e-01 , 9.2042500000000005e-01 , -3.1311800000000001e-01 -5.6375135819484896e+00 , 1.0080004431353689e+00 , 9.2843783999999996e+00 , -1.5427299999999999e-01 , 9.8281799999999997e-01 , -1.0133399999999999e-01 -5.2155820224184186e+00 , 1.2102552122587715e+00 , 8.6750424000000006e+00 , 1.0139400000000000e-01 , 6.9424100000000000e-01 , 7.1256399999999998e-01 -5.0193685269206298e+00 , 1.3122613396146310e+00 , 8.4859912000000008e+00 , 2.3224900000000001e-01 , 5.8286099999999996e-01 , 7.7867399999999998e-01 -4.9646138414072292e+00 , 1.3534556055797931e+00 , 8.5891592000000010e+00 , 6.4523699999999995e-01 , 4.1856299999999999e-02 , 7.6283500000000004e-01 -4.7391024486292137e+00 , 1.4644107232919537e+00 , 8.3065080000000009e+00 , 2.2878699999999999e-01 , -5.6874800000000003e-01 , 7.9005199999999998e-01 -4.6150103666878239e+00 , 1.5338290981880713e+00 , 8.2345608000000006e+00 , 2.2878699999999999e-01 , -5.6874800000000003e-01 , 7.9005199999999998e-01 -4.2851598981373211e+00 , 1.6817221816048118e+00 , 7.6438928000000006e+00 , -5.7325200000000000e-02 , 5.3134599999999998e-01 , 8.4521299999999999e-01 -4.1696506798136443e+00 , 1.7435592264191200e+00 , 7.5519672000000000e+00 , 4.2170699999999998e-02 , 4.4809700000000002e-01 , 8.9298999999999995e-01 -4.0776613418706056e+00 , 1.7952696519518487e+00 , 7.5149432000000003e+00 , -3.7598999999999999e-01 , -2.3099000000000000e-01 , -8.9737100000000003e-01 -3.9990544412028575e+00 , 1.8423146391914129e+00 , 7.5050527999999996e+00 , 1.6421100000000000e-01 , 4.1040500000000002e-01 , 8.9699600000000002e-01 -4.0701393234735361e+00 , 1.8354131345767601e+00 , 7.9444840000000001e+00 , -5.1474799999999998e-01 , -7.9753299999999999e-02 , 8.5362400000000005e-01 -4.2127978169573002e+00 , 1.8075778291147182e+00 , 8.6536703999999993e+00 , 8.8329899999999995e-01 , 1.7875800000000000e-01 , 4.3339100000000003e-01 -4.1125705924684599e+00 , 1.8655865457353611e+00 , 8.6250704000000002e+00 , 8.8329899999999995e-01 , 1.7875800000000000e-01 , 4.3339100000000003e-01 -4.0667930713728442e+00 , 1.9058394544769011e+00 , 8.7834624000000012e+00 , 7.4170499999999995e-01 , 9.3468500000000003e-03 , 6.7066099999999995e-01 -3.7249301553136562e+00 , 2.0338935337408945e+00 , 7.8493240000000002e+00 , 5.9857000000000005e-01 , 1.6637700000000000e-01 , -7.8360200000000002e-01 -3.5574419279515306e+00 , 2.1042819211358275e+00 , 7.4883607999999997e+00 , 8.7073599999999995e-01 , 3.3858500000000002e-01 , -3.5662100000000002e-01 -3.4774256326262991e+00 , 2.1481241019901942e+00 , 7.4464592000000005e+00 , 5.7570299999999996e-01 , 5.7084400000000002e-01 , -5.8540800000000004e-01 -3.4488523565905513e+00 , 2.1801960520821879e+00 , 7.6258904000000003e+00 , 7.8347100000000003e-01 , 5.6855699999999998e-01 , -2.5083299999999997e-01 -3.3719932306726115e+00 , 2.2241679146706606e+00 , 7.6011280000000001e+00 , 5.2271999999999996e-01 , 5.4990399999999995e-01 , 6.5143600000000002e-01 -3.3238918538464377e+00 , 2.2625359493591306e+00 , 7.7180552000000002e+00 , 5.1896400000000002e-02 , 3.4436800000000001e-01 , 9.3739899999999998e-01 -3.2267268028471996e+00 , 2.3086317356686927e+00 , 7.5677335999999995e+00 , -1.5395400000000001e-01 , 5.8156399999999997e-01 , 7.9879999999999995e-01 -3.1608470049255870e+00 , 2.3488522773392653e+00 , 7.5899272000000000e+00 , 2.6842899999999997e-01 , 3.1215900000000001e-02 , -9.6279400000000004e-01 -3.1687028236876071e+00 , 2.3884636987814796e+00 , 8.1255064000000008e+00 , -9.8946100000000003e-01 , -3.2472899999999999e-02 , -1.4111399999999999e-01 -3.0639101868509244e+00 , 2.4331357220473295e+00 , 7.9085207999999998e+00 , -8.6401799999999995e-01 , -1.9513400000000000e-01 , 4.6410699999999999e-01 -3.0189706154983562e+00 , 2.4813473502177810e+00 , 8.1645792000000004e+00 , 8.1533900000000004e-01 , 3.5540800000000000e-01 , 4.5706400000000003e-01 -2.9825831549908957e+00 , 2.5369962712245391e+00 , 8.5753272000000003e+00 , -1.1665399999999999e-01 , -8.5303099999999998e-01 , 5.0865499999999997e-01 -2.9067220523710038e+00 , 2.5889485841187132e+00 , 8.6641536000000006e+00 , 8.4116899999999994e-01 , -3.0621799999999999e-01 , 4.4571800000000000e-01 -2.8327827655731510e+00 , 2.6455647902285340e+00 , 8.8239808000000011e+00 , -9.3464800000000003e-01 , 3.5227700000000001e-01 , 4.8311000000000000e-02 -2.7487674559612127e+00 , 2.6994869378230995e+00 , 8.8681495999999989e+00 , -9.0829300000000002e-01 , 3.5058800000000001e-01 , -2.2823599999999999e-01 -2.6722153715371286e+00 , 2.7669299566046330e+00 , 9.1285863999999997e+00 , -5.7279400000000003e-01 , -3.4592099999999998e-01 , -7.4313200000000001e-01 -2.5806856488814445e+00 , 2.8196238576311239e+00 , 9.0965439999999997e+00 , 3.1303500000000001e-01 , -2.9312100000000002e-01 , 9.0337699999999999e-01 -2.4901242683975027e+00 , 2.8810361662479043e+00 , 9.1870344000000017e+00 , -4.8271599999999998e-01 , 6.3128099999999998e-01 , -6.0701700000000003e-01 -2.4057426638308308e+00 , 2.8632944767506721e+00 , 8.3536615999999988e+00 , -9.2388300000000001e-01 , 3.6703700000000000e-01 , 1.0827700000000000e-01 -2.3012506437222968e+00 , 3.0134624792304523e+00 , 9.4245495999999989e+00 , -5.5309100000000000e-02 , -3.7431599999999998e-01 , 9.2564999999999997e-01 -2.2162392734915732e+00 , 3.0398633468360838e+00 , 9.1369064000000009e+00 , 5.1376800000000000e-01 , 1.2499499999999999e-01 , 8.4877499999999995e-01 -1.9534778274735622e+00 , 3.4568486502845799e+00 , 1.2315219200000001e+01 , -9.8017100000000001e-01 , -1.6244600000000001e-02 , -1.9748700000000000e-01 -1.7995456282727138e+00 , 3.5639132062743188e+00 , 1.2502856000000001e+01 , -2.1728800000000001e-01 , 9.7348000000000001e-01 , 7.1578799999999998e-02 -1.6821001160467786e+00 , 3.6086138211832450e+00 , 1.2183149600000000e+01 , 5.0537299999999996e-01 , 2.6149600000000001e-01 , -8.2232499999999997e-01 -1.5209206921824727e+00 , 3.7230062453896600e+00 , 1.2405616000000000e+01 , -9.6632099999999999e-01 , -1.8406300000000000e-01 , -1.7984900000000001e-01 -1.7318287924973468e+00 , 3.3446198814060715e+00 , 9.3234512000000009e+00 , 6.3003100000000001e-01 , 3.0185899999999999e-01 , -7.1550100000000005e-01 -4.4194803014038708e+00 , 1.0243860067605051e+00 , 1.4374899999999999e+00 , -8.8212499999999999e-02 , 2.2182900000000000e-01 , 9.7108700000000003e-01 -4.4879473569256740e+00 , 9.8161003944783731e-01 , 1.4453108000000001e+00 , -1.2300200000000000e-01 , 2.1925100000000000e-01 , 9.6788399999999997e-01 -4.5413531044436901e+00 , 9.4853604568775585e-01 , 1.4664540000000001e+00 , -8.4191799999999997e-02 , 2.1762799999999999e-01 , 9.7239399999999998e-01 -4.6103183644092702e+00 , 9.0555333521994275e-01 , 1.4786521600000000e+00 , -5.7760499999999999e-02 , 2.0243800000000001e-01 , 9.7758999999999996e-01 -4.6800779638188370e+00 , 8.6299693342871020e-01 , 1.4931008800000001e+00 , -7.4449399999999999e-02 , 2.1877700000000000e-01 , 9.7293099999999999e-01 -4.7495290312619547e+00 , 8.1986863596020898e-01 , 1.5099800800000001e+00 , -7.9477999999999993e-02 , 2.0798200000000000e-01 , 9.7489800000000004e-01 -4.8187300987500361e+00 , 7.7718840261935207e-01 , 1.5289839999999999e+00 , -4.5917199999999998e-02 , 2.0202000000000001e-01 , 9.7830399999999995e-01 -4.8964440477567059e+00 , 7.2842373413869188e-01 , 1.5459724000000001e+00 , -5.0053500000000001e-02 , 1.9524300000000000e-01 , 9.7947700000000004e-01 -4.9817128867157487e+00 , 6.7568313671908675e-01 , 1.5606104000000001e+00 , -7.4359700000000001e-02 , 2.0848500000000000e-01 , 9.7519500000000003e-01 -5.0675729128962184e+00 , 6.2149187333199585e-01 , 1.5787188800000000e+00 , -5.9297599999999999e-02 , 2.0848900000000001e-01 , 9.7622600000000004e-01 -5.1541610177237569e+00 , 5.6889136605558988e-01 , 1.5996821600000000e+00 , -8.6248000000000005e-02 , 2.1376300000000001e-01 , 9.7307100000000002e-01 -5.2413627613185820e+00 , 5.1483413244136966e-01 , 1.6240150400000000e+00 , -6.1526499999999998e-02 , 2.2130800000000000e-01 , 9.7326100000000004e-01 -5.3359563173180629e+00 , 4.5598265965764906e-01 , 1.6472143200000000e+00 , -3.3793499999999997e-02 , 2.0682900000000001e-01 , 9.7779300000000002e-01 -5.4553203258355412e+00 , 3.8172522250769503e-01 , 1.6625106400000000e+00 , -1.3589100000000000e-02 , 1.9582600000000000e-01 , 9.8054500000000000e-01 -5.5664655327352719e+00 , 3.1262496171385923e-01 , 1.6858232799999999e+00 , -5.6231700000000003e-02 , 1.8398600000000001e-01 , 9.8131900000000005e-01 -5.6868401370420045e+00 , 2.3798874865292352e-01 , 1.7099772799999999e+00 , -6.1081799999999999e-02 , 2.0628199999999999e-01 , 9.7658400000000001e-01 -5.8077046811483557e+00 , 1.6318656320648040e-01 , 1.7387124800000000e+00 , -6.1523200000000000e-02 , 1.9797799999999999e-01 , 9.7827399999999998e-01 -5.9366804539164049e+00 , 8.3024999378393138e-02 , 1.7688704000000000e+00 , -5.7433699999999997e-02 , 1.9487499999999999e-01 , 9.7914500000000004e-01 -6.0909768194286569e+00 , -1.3895400181398454e-02 , 1.7951023200000000e+00 , -6.0666400000000002e-02 , 1.9796700000000000e-01 , 9.7833000000000003e-01 -6.2369921167355322e+00 , -1.0446153171269845e-01 , 1.8299547999999999e+00 , -6.1058899999999999e-02 , 1.9856599999999999e-01 , 9.7818400000000005e-01 -6.4005992720195977e+00 , -2.0527782132035854e-01 , 1.8651463200000000e+00 , -5.9348600000000001e-02 , 1.9637199999999999e-01 , 9.7873200000000005e-01 -6.5815704772386034e+00 , -3.1815196096261822e-01 , 1.9022023520000000e+00 , -1.1170500000000000e-01 , 1.5694800000000000e-01 , 9.8126899999999995e-01 -6.7713121269497618e+00 , -4.3576371921870471e-01 , 1.9439441040000001e+00 , -2.0148900000000000e-01 , 7.5943800000000004e-03 , 9.7946100000000003e-01 -6.9687388347588302e+00 , -5.5799354603553697e-01 , 1.9907522992000000e+00 , -2.1909600000000001e-02 , 1.2830700000000000e-01 , 9.9149200000000004e-01 -7.2108664047650475e+00 , -7.0788854400946777e-01 , 2.0362519040000002e+00 , -8.3330100000000004e-02 , 1.8280700000000000e-01 , 9.7961100000000001e-01 -6.8400641135850027e+00 , -4.5167721854310683e-01 , 2.3065036000000001e+00 , -9.7765100000000005e-01 , -1.7524000000000001e-01 , -1.1614900000000000e-01 -6.8540899765586847e+00 , -4.5302558733669063e-01 , 2.3976959999999998e+00 , 9.8748199999999997e-01 , 1.5483900000000000e-01 , 3.0059599999999999e-02 -6.8407105621994093e+00 , -4.3753896525817249e-01 , 2.4927665600000002e+00 , 9.8803799999999997e-01 , 1.5371499999999999e-01 , 1.2319600000000000e-02 -6.8338068498813831e+00 , -4.2593930014275072e-01 , 2.5857654399999999e+00 , -9.7591300000000003e-01 , -2.7814499999999999e-02 , 2.1637999999999999e-01 -6.8698697283410084e+00 , -4.4255797936121644e-01 , 2.6743724000000002e+00 , -9.7591300000000003e-01 , -2.7814400000000000e-02 , 2.1637999999999999e-01 -9.6642656927954462e+00 , -2.2309834428906381e+00 , 2.5682123199999998e+00 , -7.6177400000000006e-02 , 1.9790199999999999e-01 , 9.7725700000000004e-01 -1.0130779100802620e+01 , -2.5185799182700386e+00 , 2.6949019999999999e+00 , 7.3094400000000004e-02 , -2.1626400000000001e-01 , -9.7359499999999999e-01 -1.0745734932048613e+01 , -2.8998690520765900e+00 , 2.8362047200000000e+00 , -7.1287400000000001e-02 , 1.9916700000000001e-01 , 9.7736900000000004e-01 -1.1481104348435519e+01 , -3.3558820008536827e+00 , 3.0012568800000001e+00 , -6.2709100000000004e-02 , 1.9798199999999999e-01 , 9.7819800000000001e-01 -1.2400055006454744e+01 , -3.9268610551238989e+00 , 3.1987664000000002e+00 , -5.6649900000000003e-02 , 1.9801500000000000e-01 , 9.7856100000000001e-01 -1.3597283068532155e+01 , -4.6703316708681744e+00 , 3.4427816000000000e+00 , -3.3186700000000000e-02 , 2.0112500000000000e-01 , 9.7900299999999996e-01 -1.5161161493223473e+01 , -5.6428832724351263e+00 , 3.7558528000000004e+00 , -5.0500000000000003e-02 , 1.7845600000000000e-01 , 9.8265100000000005e-01 -1.7062407868315535e+01 , -6.8242836804913658e+00 , 4.1582495999999995e+00 , -6.1374600000000001e-02 , 1.8483100000000000e-01 , 9.8085199999999995e-01 -2.0238751653031422e+01 , -8.8019839201881638e+00 , 4.7596400000000001e+00 , -8.4997500000000004e-02 , 2.0432600000000001e-01 , 9.7520600000000002e-01 -3.6640101883112713e+01 , -1.8917079108405250e+01 , 9.1443632000000008e+00 , -1.6860200000000000e-01 , 4.9812699999999999e-01 , 8.5055400000000003e-01 -3.6221262050795175e+01 , -1.8601927691362235e+01 , 9.7760487999999999e+00 , -1.6860200000000000e-01 , 4.9812699999999999e-01 , 8.5055400000000003e-01 -7.2556594013080966e+00 , -3.4255847078508284e-01 , 7.1741456000000001e+00 , -9.4212399999999996e-01 , 1.1167600000000000e-01 , -3.1611800000000001e-01 -7.1771412791950402e+00 , -2.8652874947220175e-01 , 7.2510224000000001e+00 , -9.4212399999999996e-01 , 1.1167600000000000e-01 , -3.1611800000000001e-01 -7.1033333080008756e+00 , -2.3310970535906250e-01 , 7.3317784000000001e+00 , -8.1701100000000004e-01 , 3.9990799999999999e-01 , -4.1541099999999997e-01 -6.9823585609483478e+00 , -1.1756038399620605e-01 , 7.8267664000000003e+00 , -7.7709099999999998e-01 , -5.9076799999999996e-01 , 2.1707799999999999e-01 -6.6110880857359975e+00 , 1.0070472980532674e-01 , 7.5870775999999998e+00 , 6.0471799999999998e-01 , -3.6380099999999999e-01 , 7.0849499999999999e-01 -7.2684871001014670e+00 , -2.5036507048166401e-01 , 8.4776920000000011e+00 , 6.3520200000000004e-01 , 4.8468499999999998e-01 , -6.0133099999999995e-01 -7.2419129939230888e+00 , -2.2140240534151756e-01 , 8.6316015999999998e+00 , 5.4621600000000003e-01 , 2.8578300000000001e-01 , -7.8738500000000000e-01 -6.9303835908395497e+00 , -3.7102413840667481e-02 , 8.4469183999999995e+00 , 7.1945800000000004e-01 , -8.6481299999999997e-02 , -6.8913100000000005e-01 -6.2659690759153737e+00 , 3.3716400972969773e-01 , 7.8069232000000008e+00 , -6.8161799999999995e-02 , -4.1182099999999999e-01 , 9.0871199999999996e-01 -6.1379100874821795e+00 , 4.1850889819767234e-01 , 7.8038967999999995e+00 , -1.9307500000000000e-01 , 5.2029999999999998e-01 , -8.3187100000000003e-01 -6.0460992635616240e+00 , 4.7944190663011943e-01 , 7.8443008000000001e+00 , -5.0354100000000002e-01 , 4.6530300000000002e-01 , -7.2797000000000001e-01 -6.0365193700228135e+00 , 4.9738596202306318e-01 , 7.9945808000000005e+00 , -6.2694099999999997e-01 , 4.6691899999999997e-01 , -6.2364399999999998e-01 -5.9315191246925876e+00 , 5.6663888122415229e-01 , 8.0154744000000004e+00 , -3.5170299999999999e-01 , 6.2675199999999998e-01 , -6.9533199999999995e-01 -5.8205518672753946e+00 , 6.3711226618632244e-01 , 8.0253544000000012e+00 , -3.5704700000000000e-01 , -1.7271200000000000e-01 , 9.1798000000000002e-01 -5.6890807963227434e+00 , 7.1916621245195422e-01 , 7.9987928000000004e+00 , 1.1529900000000000e-01 , 1.1120300000000000e-01 , -9.8708700000000005e-01 -5.5913748505515795e+00 , 7.8269253458823451e-01 , 8.0191560000000006e+00 , 7.6231599999999997e-02 , -7.5314199999999998e-02 , 9.9424199999999996e-01 -5.4888123326532483e+00 , 8.4944715583915920e-01 , 8.0282352000000010e+00 , -5.4494399999999998e-02 , 4.3086100000000002e-02 , 9.9758400000000003e-01 -5.3968944937586478e+00 , 9.0918059209981750e-01 , 8.0520928000000005e+00 , -5.7027899999999999e-02 , 6.5417500000000003e-02 , 9.9622699999999997e-01 -5.2597800963767192e+00 , 9.9269040284149335e-01 , 7.9946328000000006e+00 , 2.0663599999999999e-01 , 4.4701299999999999e-01 , 8.7033400000000005e-01 -5.1014540596151283e+00 , 1.0854619290672036e+00 , 7.8890312000000007e+00 , 5.7587200000000005e-01 , 5.3032699999999999e-01 , -6.2219300000000000e-01 -5.1177108349646820e+00 , 1.0913253293805156e+00 , 8.1007648000000003e+00 , 5.7587200000000005e-01 , 5.3032699999999999e-01 , -6.2219300000000000e-01 -4.9796724935060706e+00 , 1.1732683492672391e+00 , 8.0248032000000009e+00 , 6.5673899999999996e-01 , 5.7405899999999999e-01 , 4.8903000000000002e-01 -4.8995258940557846e+00 , 1.2272807295672705e+00 , 8.0544432000000015e+00 , 6.6977200000000003e-01 , 6.3678400000000002e-01 , 3.8198399999999999e-01 -4.7184175820247560e+00 , 1.3285817381845186e+00 , 7.8703111999999997e+00 , 5.4302099999999998e-01 , 5.8986899999999998e-01 , -5.9764799999999996e-01 -4.6949440155721476e+00 , 1.3535038432881206e+00 , 8.0153704000000001e+00 , -4.9140400000000001e-01 , -6.4280499999999996e-01 , 5.8764300000000003e-01 -4.6358620984345897e+00 , 1.3967284935496402e+00 , 8.0855391999999995e+00 , -5.7374199999999997e-01 , 7.4461299999999997e-01 , -3.4113199999999999e-01 -4.5667284849810201e+00 , 1.4448342777337966e+00 , 8.1356463999999988e+00 , 5.4715899999999995e-01 , -7.5208200000000003e-01 , 3.6741000000000001e-01 -4.2644066975425901e+00 , 1.5969557929202789e+00 , 7.6034680000000003e+00 , -2.3684100000000000e-01 , 4.2123699999999997e-01 , 8.7548099999999995e-01 -4.1801656001909357e+00 , 1.6497041660742497e+00 , 7.5890535999999997e+00 , 2.4967099999999999e-02 , 5.0522000000000000e-01 , 8.6262899999999998e-01 -4.0761282820629710e+00 , 1.7103330426967824e+00 , 7.5146728000000005e+00 , -3.7598999999999999e-01 , -2.3099000000000000e-01 , -8.9737100000000003e-01 -4.0244578821064350e+00 , 1.7476192812492832e+00 , 7.5833024000000009e+00 , 4.7925699999999999e-01 , 4.5526400000000000e-01 , 7.5036499999999995e-01 -3.9659365730069078e+00 , 1.7895441173909785e+00 , 7.6313504000000005e+00 , 7.7903699999999998e-01 , 3.1201400000000001e-01 , 5.4382699999999995e-01 -4.2141991079973824e+00 , 1.7097360614074320e+00 , 8.6532024000000014e+00 , 8.8329899999999995e-01 , 1.7875800000000000e-01 , 4.3339100000000003e-01 -3.8826256490296167e+00 , 1.8590095557854522e+00 , 7.8529432000000003e+00 , -5.7580699999999996e-01 , -5.3107300000000002e-01 , 6.2161699999999998e-01 -3.7966247924435210e+00 , 1.9120633671793361e+00 , 7.8185920000000007e+00 , 4.1652499999999998e-01 , -4.4028200000000001e-01 , -7.9539800000000005e-01 -3.6628528834304079e+00 , 1.9803928724101887e+00 , 7.6021680000000007e+00 , -9.3813700000000000e-01 , -3.4571400000000002e-01 , -1.9494399999999999e-02 -3.5707742906489326e+00 , 2.0320724712626634e+00 , 7.5228055999999999e+00 , 8.5336000000000001e-01 , 5.1654800000000001e-01 , 7.0389400000000005e-02 -3.4724359825828959e+00 , 2.0859976997521543e+00 , 7.4005536000000003e+00 , -5.7097600000000004e-01 , -2.9727399999999998e-01 , 7.6525399999999999e-01 -3.4208477373769446e+00 , 2.1242397117699472e+00 , 7.4686735999999998e+00 , 2.2321099999999999e-01 , 8.1660200000000005e-01 , -5.3229499999999996e-01 -3.3500387907154674e+00 , 2.1679418876433494e+00 , 7.4543944000000000e+00 , 1.7851200000000000e-01 , -6.1455700000000002e-01 , 7.6841000000000004e-01 -3.3326121991524040e+00 , 2.1987348637517705e+00 , 7.7141967999999999e+00 , -1.3688600000000001e-01 , 5.8304400000000001e-01 , 8.0082600000000004e-01 -3.2505640562067875e+00 , 2.2459522306065280e+00 , 7.6464512000000004e+00 , -4.9156300000000003e-01 , 4.1764099999999998e-01 , 7.6416099999999998e-01 -3.1689615726697120e+00 , 2.2928032807725427e+00 , 7.5664335999999999e+00 , -6.9189000000000001e-01 , 2.3177400000000001e-01 , 6.8379000000000001e-01 -3.1456263155901527e+00 , 2.3306536400550550e+00 , 7.8758232000000001e+00 , 3.3600400000000002e-01 , -8.9015000000000000e-01 , 3.0778899999999998e-01 -3.0706210372187122e+00 , 2.3764733267530365e+00 , 7.8447895999999995e+00 , 7.6702400000000004e-01 , 2.0788400000000001e-01 , -6.0700799999999999e-01 -2.9859550676267603e+00 , 2.4216332265810063e+00 , 7.7293807999999995e+00 , -6.3362600000000002e-01 , -6.4975600000000000e-01 , 4.1992299999999999e-01 -2.9771369795150884e+00 , 2.4732482060933032e+00 , 8.3262680000000007e+00 , -9.1382900000000000e-01 , -4.0510600000000002e-01 , -2.8389600000000001e-02 -2.8674483688049266e+00 , 2.5145062165474887e+00 , 7.9595224000000009e+00 , 1.6747100000000001e-01 , -9.0591500000000003e-01 , 3.8893800000000001e-01 -2.8551257676891924e+00 , 2.5874403199021097e+00 , 8.8037632000000006e+00 , 4.4621200000000000e-01 , -6.9862100000000005e-01 , 5.5930599999999997e-01 -2.7746266861273758e+00 , 2.6444426732111586e+00 , 8.8797871999999991e+00 , 5.1664900000000002e-01 , -6.2981100000000001e-01 , 5.8001000000000003e-01 -2.7015820220605078e+00 , 2.7138838591575176e+00 , 9.1719752000000003e+00 , 2.9876700000000000e-01 , 5.3922899999999996e-01 , 7.8738200000000003e-01 -2.6104015971631580e+00 , 2.7678646469939578e+00 , 9.1200375999999999e+00 , 1.9186800000000000e-02 , 4.5967500000000000e-01 , 8.8788000000000000e-01 -2.5212255008097118e+00 , 2.8294421009945578e+00 , 9.1905599999999996e+00 , -6.6108000000000000e-01 , 4.2207400000000000e-01 , -6.2034400000000001e-01 -2.4327147970576171e+00 , 2.8438482628172284e+00 , 8.6370824000000006e+00 , -9.6004599999999995e-01 , -1.1649500000000000e-01 , 2.5444200000000000e-01 -2.3539727220507647e+00 , 2.8787347546393303e+00 , 8.4456080000000000e+00 , -9.1996100000000003e-01 , 3.3957500000000002e-01 , -1.9585700000000000e-01 -2.2525266107109867e+00 , 2.9979891110176555e+00 , 9.1423455999999987e+00 , 5.7828999999999997e-01 , 3.0161600000000000e-01 , 7.5802899999999995e-01 -1.9930111161077260e+00 , 3.4343543131636443e+00 , 1.2675808000000000e+01 , 5.5439799999999995e-01 , 8.3209299999999997e-01 , 1.6260600000000000e-02 -1.8907007752268270e+00 , 3.4497047734118809e+00 , 1.2029219200000000e+01 , -9.7802199999999995e-01 , 1.8316800000000000e-01 , -9.9615300000000004e-02 -1.7219768885710278e+00 , 3.5909112398682530e+00 , 1.2472800000000001e+01 , -3.5532599999999998e-02 , 8.0656700000000003e-01 , -5.9007299999999996e-01 -1.6097871106869390e+00 , 3.6393301258690860e+00 , 1.2162079199999999e+01 , -5.0537299999999996e-01 , -2.6149600000000001e-01 , 8.2232499999999997e-01 -1.3461772657347715e+00 , 3.8974268860601451e+00 , 1.3334232000000002e+01 , -9.5477199999999995e-01 , -2.5045299999999998e-01 , 1.6026299999999999e-01 -4.3667109983306709e+00 , 9.8616284623748296e-01 , 1.4262299199999999e+00 , -8.7536500000000003e-02 , 2.2571800000000000e-01 , 9.7025200000000000e-01 -4.4193477583191880e+00 , 9.5154286134564359e-01 , 1.4448219999999998e+00 , -9.7782200000000000e-02 , 2.2741100000000000e-01 , 9.6887699999999999e-01 -4.4796653115015790e+00 , 9.1159297124705296e-01 , 1.4596524000000000e+00 , -1.0874700000000000e-01 , 2.4316699999999999e-01 , 9.6386899999999998e-01 -4.5328882921818554e+00 , 8.7664613516498546e-01 , 1.4820165599999999e+00 , -6.6465600000000000e-02 , 2.2380300000000000e-01 , 9.7236599999999995e-01 -4.6075200538715535e+00 , 8.2722484181189548e-01 , 1.4897978400000000e+00 , -6.7257300000000006e-02 , 1.7627000000000001e-01 , 9.8204100000000005e-01 -4.6681574366151377e+00 , 7.8742467656691040e-01 , 1.5107247200000000e+00 , -7.3688799999999999e-02 , 1.9261600000000001e-01 , 9.7850300000000001e-01 -4.7431816252588570e+00 , 7.3690505293300457e-01 , 1.5236966400000000e+00 , -8.9825600000000005e-02 , 1.8873699999999999e-01 , 9.7791099999999997e-01 -4.8189047066620088e+00 , 6.8586918738796143e-01 , 1.5395285599999999e+00 , -6.3111700000000007e-02 , 2.2284200000000001e-01 , 9.7280900000000003e-01 -4.8954152329312297e+00 , 6.3634060836607897e-01 , 1.5577098400000000e+00 , -7.8043000000000001e-02 , 2.0657500000000001e-01 , 9.7531299999999999e-01 -4.9725517949339784e+00 , 5.8529414685192460e-01 , 1.5790568800000000e+00 , -7.1647799999999998e-02 , 1.9929100000000000e-01 , 9.7731800000000002e-01 -5.0561402373658728e+00 , 5.2932658166806257e-01 , 1.5984372800000000e+00 , -6.3224199999999994e-02 , 2.0080700000000001e-01 , 9.7758900000000004e-01 -5.1414282408179552e+00 , 4.7392637656268755e-01 , 1.6210042400000000e+00 , -9.0696499999999999e-02 , 2.1616700000000000e-01 , 9.7213499999999997e-01 -5.2340317634215054e+00 , 4.1170027732214587e-01 , 1.6428473600000000e+00 , -8.7539099999999995e-02 , 2.1340600000000001e-01 , 9.7303399999999995e-01 -5.3349896200638742e+00 , 3.4474771341889410e-01 , 1.6640893600000000e+00 , -4.4335699999999999e-02 , 1.7819299999999999e-01 , 9.8299599999999998e-01 -5.4442144905918752e+00 , 2.7213839311866361e-01 , 1.6854395200000001e+00 , -2.9156999999999999e-02 , 1.6635300000000000e-01 , 9.8563500000000004e-01 -5.5703699371055722e+00 , 1.8866734766666449e-01 , 1.7038672799999999e+00 , -5.3721199999999997e-02 , 1.9322300000000001e-01 , 9.7968299999999997e-01 -5.6795855817307057e+00 , 1.1568475384377885e-01 , 1.7338473599999999e+00 , -5.8576999999999997e-02 , 2.0384400000000000e-01 , 9.7724999999999995e-01 -5.8066594754635972e+00 , 3.1975425900699683e-02 , 1.7618410400000000e+00 , -6.8312999999999999e-02 , 1.9625300000000001e-01 , 9.7817100000000001e-01 -5.9407940599760440e+00 , -5.7040946895731803e-02 , 1.7913344000000000e+00 , -6.7666599999999993e-02 , 1.8636900000000001e-01 , 9.8014699999999999e-01 -6.0763421250880887e+00 , -1.4606791566127475e-01 , 1.8263439200000000e+00 , -6.4834900000000001e-02 , 1.9188200000000000e-01 , 9.7927399999999998e-01 -6.2360073602068864e+00 , -2.5261763069974430e-01 , 1.8586203200000000e+00 , -6.6979200000000003e-02 , 1.9599700000000000e-01 , 9.7831400000000002e-01 -6.3969937892424280e+00 , -3.5898441866433606e-01 , 1.8973217360000001e+00 , -6.3808299999999998e-02 , 1.9801700000000000e-01 , 9.7811999999999999e-01 -6.5743318769573627e+00 , -4.7634089565240201e-01 , 1.9376573040000000e+00 , -5.8885100000000003e-02 , 1.9740700000000000e-01 , 9.7855199999999998e-01 -6.7764061377218683e+00 , -6.1160399393599940e-01 , 1.9787263840000000e+00 , -6.3439099999999998e-02 , 1.9858200000000001e-01 , 9.7802900000000004e-01 -6.9796266537478200e+00 , -7.4529768275243580e-01 , 2.0278373680000001e+00 , -8.0419099999999993e-02 , 1.7654700000000001e-01 , 9.8100100000000001e-01 -7.2242976735254425e+00 , -9.0852513673643287e-01 , 2.0762805680000000e+00 , -7.1392999999999998e-02 , 1.8991900000000000e-01 , 9.7920099999999999e-01 -7.4698637166560218e+00 , -1.0708283538256533e+00 , 2.1346914400000001e+00 , -7.6170199999999993e-02 , 1.9574400000000000e-01 , 9.7769200000000001e-01 -7.7321709450513865e+00 , -1.2441059681343161e+00 , 2.2002259999999998e+00 , -7.3928199999999999e-02 , 1.8129600000000001e-01 , 9.8064600000000002e-01 -8.0626790036049645e+00 , -1.4636622616044548e+00 , 2.2666819999999999e+00 , -7.2035000000000002e-02 , 1.7934400000000000e-01 , 9.8114599999999996e-01 -8.4094508371719066e+00 , -1.6933559140321632e+00 , 2.3443107200000002e+00 , -7.1381899999999998e-02 , 1.8163000000000001e-01 , 9.8077300000000001e-01 -8.8162559389669433e+00 , -1.9642667977062027e+00 , 2.4303696800000001e+00 , -8.1875900000000001e-02 , 1.8232400000000001e-01 , 9.7982400000000003e-01 -9.2064345716025606e+00 , -2.2212618609584771e+00 , 2.5345766400000000e+00 , -7.7762300000000006e-02 , 1.9470799999999999e-01 , 9.7777400000000003e-01 -9.6979108725498548e+00 , -2.5464670453768754e+00 , 2.6485647999999999e+00 , -7.8795199999999996e-02 , 2.0150799999999999e-01 , 9.7631199999999996e-01 -1.0257591445413482e+01 , -2.9177061462261280e+00 , 2.7805283200000002e+00 , -8.1298599999999999e-02 , 1.9681399999999999e-01 , 9.7706400000000004e-01 -1.0902682886489275e+01 , -3.3445327767406230e+00 , 2.9341488000000000e+00 , -7.4733300000000003e-02 , 2.0081599999999999e-01 , 9.7677400000000003e-01 -1.1658335551231890e+01 , -3.8449075490976901e+00 , 3.1152439999999997e+00 , -6.1788299999999997e-02 , 2.0254800000000001e-01 , 9.7732100000000000e-01 -1.2635201574393923e+01 , -4.4928270836059152e+00 , 3.3332176000000002e+00 , -3.0011400000000001e-02 , 2.2091900000000000e-01 , 9.7482999999999997e-01 -1.3955109717785243e+01 , -5.3691589082593811e+00 , 3.6080272000000004e+00 , -9.4915499999999996e-03 , 2.1348000000000000e-01 , 9.7690100000000002e-01 -1.5718235751926851e+01 , -6.5405047705153834e+00 , 3.9676799999999997e+00 , -5.9659400000000001e-02 , 1.8412999999999999e-01 , 9.8109000000000002e-01 -1.8605195794667249e+01 , -8.4621554245199953e+00 , 4.5007424000000000e+00 , -6.1274400000000000e-02 , 1.9001100000000001e-01 , 9.7986799999999996e-01 -2.0734155019279562e+01 , -9.8675549419591224e+00 , 5.0730959999999996e+00 , -8.9714400000000000e-02 , 2.1029400000000001e-01 , 9.7351299999999996e-01 -3.4049797156039944e+01 , -1.8660939475656914e+01 , 8.5297440000000009e+00 , -1.6860200000000000e-01 , 4.9812699999999999e-01 , 8.5055400000000003e-01 -3.3688400299977445e+01 , -1.8372133046732372e+01 , 9.1323927999999999e+00 , -2.9523800000000000e-01 , 9.1672500000000001e-01 , 2.6916400000000001e-01 -3.3916677718717423e+01 , -1.8475375296056065e+01 , 9.8491920000000004e+00 , -2.4842200000000000e-01 , 9.6720099999999998e-01 , 5.3006499999999998e-02 -4.3696396219630799e+01 , -2.4838467366592582e+01 , 1.3730160000000000e+01 , -2.8291300000000003e-01 , 8.6746900000000005e-01 , 4.0921600000000002e-01 -4.3995953926617005e+01 , -2.4971404325942348e+01 , 1.4710255999999999e+01 , -2.8291300000000003e-01 , 8.6746900000000005e-01 , 4.0921600000000002e-01 -4.3875647284074887e+01 , -2.4826537882125145e+01 , 1.5582712000000001e+01 , 4.3639800000000001e-01 , -7.7333300000000005e-01 , 4.5990399999999998e-01 -4.3793057968065327e+01 , -2.4707027597308013e+01 , 1.6468896000000001e+01 , -3.4837200000000001e-01 , 9.2342299999999999e-01 , -1.6101900000000000e-01 -4.1118171777535423e+01 , -2.2509252263188429e+01 , 2.1794840000000001e+01 , 4.5641200000000000e-02 , -7.6391500000000001e-01 , 6.4370099999999997e-01 -7.1621897667530137e+00 , -4.9440443014277902e-01 , 7.2648336000000002e+00 , -8.1086999999999998e-01 , 7.0287300000000002e-04 , -5.8522600000000002e-01 -7.0902525606581204e+00 , -4.3958745686714940e-01 , 7.3476592000000007e+00 , -8.1086999999999998e-01 , 7.0286800000000005e-04 , -5.8522600000000002e-01 -7.1002596963199123e+00 , -4.3440728741755308e-01 , 7.5072576000000000e+00 , 8.5231299999999999e-01 , -4.6411800000000003e-02 , 5.2096900000000002e-01 -7.1134046896573162e+00 , -4.3193367278313932e-01 , 7.6751760000000004e+00 , 7.1228199999999997e-01 , -3.5525600000000002e-01 , 6.0534900000000003e-01 -7.3909139457662985e+00 , -5.8828164471062871e-01 , 8.1178519999999992e+00 , -9.2873499999999998e-01 , 2.1676599999999999e-01 , 3.0077199999999998e-01 -6.6534919255160645e+00 , -1.3041391320225593e-01 , 7.5135704000000008e+00 , 6.9583399999999995e-01 , 2.8154800000000002e-01 , 6.6071599999999997e-01 -6.6182849900201521e+00 , -9.8648865409017628e-02 , 7.6268576000000001e+00 , -3.5930200000000001e-01 , -4.5756900000000000e-01 , -8.1334700000000004e-01 -6.5991985738618695e+00 , -7.6052732681649804e-02 , 7.7612671999999998e+00 , -5.5829700000000004e-01 , -3.8926400000000000e-01 , -7.3265100000000005e-01 -6.7924449020278166e+00 , -1.7980637922334486e-01 , 8.1465975999999998e+00 , 6.5894500000000000e-01 , 6.0504500000000005e-01 , -4.4689099999999998e-01 -6.8767624063307089e+00 , -2.1733188889519051e-01 , 8.4210536000000005e+00 , 5.0222599999999995e-01 , 8.0979400000000001e-01 , -3.0332100000000001e-01 -6.5145114528645749e+00 , 9.4149980198823258e-03 , 8.1516103999999991e+00 , -3.9010000000000000e-01 , -9.1894100000000001e-01 , 5.8041299999999997e-02 -6.1082652974875220e+00 , 2.6071236264960440e-01 , 7.7996432000000002e+00 , -6.2188699999999997e-01 , -2.3093800000000000e-01 , -7.4828099999999997e-01 -6.0595193616202705e+00 , 3.0032322013623003e-01 , 7.8962487999999995e+00 , -7.3404300000000000e-01 , -1.5131100000000000e-01 , -6.6203199999999995e-01 -6.0203762292646328e+00 , 3.3512112148371109e-01 , 8.0079136000000002e+00 , 8.3710399999999996e-01 , -1.7278499999999999e-01 , 5.1903999999999995e-01 -5.9445933396499218e+00 , 3.9032580375509629e-01 , 8.0707503999999997e+00 , -8.4937300000000004e-01 , 1.2969500000000000e-01 , -5.1161000000000001e-01 -5.8637715088161686e+00 , 4.4908260891160712e-01 , 8.1238008000000015e+00 , 5.5489599999999994e-01 , -4.5151100000000000e-02 , 8.3069400000000004e-01 -5.6777937193291326e+00 , 5.6718143978370206e-01 , 8.0167743999999992e+00 , 1.0619900000000000e-01 , 1.8639300000000000e-01 , 9.7671900000000000e-01 -5.7945829541256497e+00 , 5.1436792481523907e-01 , 8.3750856000000002e+00 , -8.2571300000000003e-01 , 5.6408999999999998e-01 , 8.1668699999999997e-04 -5.4960310969999906e+00 , 6.9495290377356844e-01 , 8.0745672000000006e+00 , 4.0295999999999998e-01 , 4.5435399999999998e-01 , 7.9447299999999998e-01 -5.3947133084674039e+00 , 7.6462333667925653e-01 , 8.0825543999999994e+00 , 3.0981500000000001e-01 , 4.8848700000000000e-01 , 8.1571700000000003e-01 -5.2305812046354809e+00 , 8.6886685143594078e-01 , 7.9746439999999996e+00 , -2.0413100000000001e-01 , 4.4114599999999997e-02 , 9.7794899999999996e-01 -5.1847323523916753e+00 , 9.0659249175768486e-01 , 8.0730488000000005e+00 , -2.8911700000000001e-01 , -1.8446000000000001e-02 , 9.5711599999999997e-01 -5.0246652379679340e+00 , 1.0069060579152940e+00 , 7.9570368000000000e+00 , -4.5269799999999999e-01 , -2.9069200000000001e-01 , -8.4294899999999995e-01 -4.9463464285734497e+00 , 1.0623713250491533e+00 , 7.9890480000000004e+00 , -5.6171700000000002e-01 , -4.0190999999999999e-01 , -7.2314699999999998e-01 -5.4417842721316232e+00 , 8.1211190317395898e-01 , 9.1926191999999993e+00 , -2.3978300000000000e-01 , -2.0330000000000001e-01 , 9.4930199999999998e-01 -6.0549455149095888e+00 , 5.0668156507674134e-01 , 1.0737788799999999e+01 , 9.1197700000000004e-01 , -3.7827400000000000e-01 , -1.5876399999999999e-01 -4.9907694083078802e+00 , 1.0826669703711020e+00 , 8.6947815999999989e+00 , -3.1834000000000001e-01 , 4.2730400000000002e-01 , 8.4621000000000002e-01 -4.6463866371669624e+00 , 1.2768612318867878e+00 , 8.1358024000000011e+00 , -6.7901599999999995e-01 , 1.2613800000000000e-01 , -7.2320600000000002e-01 -4.7594886529608811e+00 , 1.2348562302456458e+00 , 8.6207960000000003e+00 , 2.7587800000000001e-01 , -4.2231999999999997e-01 , -8.6344500000000002e-01 -4.5474869198031413e+00 , 1.3578455865520951e+00 , 8.3322272000000002e+00 , -5.3771400000000003e-01 , 7.1192100000000003e-01 , 4.5169900000000002e-01 -4.2127076947276620e+00 , 1.5395803782664363e+00 , 7.6923984000000001e+00 , 9.0347600000000000e-02 , -9.3826800000000002e-02 , 9.9148099999999995e-01 -4.0804460940475575e+00 , 1.6181006727473544e+00 , 7.5426696000000000e+00 , -1.5603500000000001e-01 , 3.8559599999999999e-01 , 9.0937800000000002e-01 -4.0467937546317909e+00 , 1.6496301146722550e+00 , 7.6603664000000000e+00 , -7.8858700000000004e-01 , -2.6673900000000000e-01 , -5.5405899999999997e-01 -3.9881548069349240e+00 , 1.6928681563121171e+00 , 7.7096312000000005e+00 , 1.2808500000000000e-01 , -6.9382600000000005e-01 , 7.0866099999999999e-01 -4.0060395657183472e+00 , 1.7024264794615176e+00 , 8.0033063999999996e+00 , 4.6136199999999999e-01 , 3.5592099999999999e-01 , -8.1269000000000002e-01 -3.8671807970635057e+00 , 1.7819779539420053e+00 , 7.8046039999999994e+00 , -2.5809300000000002e-01 , 4.9944200000000000e-01 , -8.2701000000000002e-01 -3.7290963415769021e+00 , 1.8598559015844969e+00 , 7.5819504000000002e+00 , -7.5949699999999998e-01 , -1.7894699999999999e-01 , -6.2541400000000003e-01 -3.6534969591414197e+00 , 1.9096010131772323e+00 , 7.5650088000000002e+00 , -6.2681299999999995e-01 , -3.8269300000000001e-01 , 6.7871300000000001e-01 -3.5869414913993305e+00 , 1.9561909396121315e+00 , 7.5765111999999997e+00 , 6.9672000000000001e-01 , 7.0720799999999995e-01 , -1.2015800000000000e-01 -3.4556454984000022e+00 , 2.0268591926682720e+00 , 7.3142544000000003e+00 , 6.3464500000000001e-01 , 2.0678299999999999e-01 , -7.4462600000000001e-01 -3.4687011406624118e+00 , 2.0429653594004771e+00 , 7.6657744000000010e+00 , 7.2293700000000005e-01 , 4.8393600000000002e-02 , 6.8921699999999997e-01 -3.3479504465331114e+00 , 2.1067885953096859e+00 , 7.4192112000000003e+00 , 6.1342600000000003e-01 , -3.7413999999999997e-01 , 6.9550599999999996e-01 -3.2899226526794454e+00 , 2.1493673934965356e+00 , 7.4547791999999999e+00 , 1.6698499999999999e-01 , -8.5450000000000004e-01 , 4.9187900000000001e-01 -3.2553331440575572e+00 , 2.1845254187252472e+00 , 7.6324423999999995e+00 , 1.0981100000000001e-02 , 7.2014000000000000e-01 , 6.9374199999999997e-01 -3.1952736972135138e+00 , 2.2288556457423447e+00 , 7.6762784000000002e+00 , -3.4197600000000002e-02 , 7.1619699999999997e-01 , 6.9706000000000001e-01 -3.1195006629104585e+00 , 2.2772064323665338e+00 , 7.6260463999999999e+00 , 2.7930300000000002e-01 , 3.0573200000000000e-01 , 9.1022999999999998e-01 -3.0641548466296245e+00 , 2.3206363101723202e+00 , 7.7085704000000002e+00 , 4.6231299999999997e-01 , -2.5276199999999999e-02 , 8.8635699999999995e-01 -3.0050129279384112e+00 , 2.3661461924600369e+00 , 7.7795399999999999e+00 , -6.1712500000000003e-01 , 2.5817400000000001e-02 , 7.8644199999999997e-01 -2.9263856855320158e+00 , 2.4128570378290304e+00 , 7.6836519999999995e+00 , -1.6086200000000000e-01 , -2.3491300000000001e-01 , 9.5861300000000005e-01 -2.8688591224040825e+00 , 2.4597056471363370e+00 , 7.7932368000000007e+00 , 8.7805599999999998e-02 , -6.2756599999999996e-01 , 7.7359599999999995e-01 -2.8058429242872061e+00 , 2.5077335415213815e+00 , 7.8706024000000001e+00 , -1.9405200000000000e-01 , -8.0503100000000005e-01 , 5.6059700000000001e-01 -2.7434064859488512e+00 , 2.5575237452497621e+00 , 7.9779200000000001e+00 , 5.9208600000000000e-01 , 4.2520000000000002e-01 , -6.8457299999999999e-01 -2.7277611945062445e+00 , 2.6566749688666791e+00 , 9.2150935999999994e+00 , 2.0504300000000000e-01 , 4.5934900000000001e-01 , 8.6426599999999998e-01 -2.6378249177947466e+00 , 2.7139513431056344e+00 , 9.1534320000000005e+00 , 2.0060700000000001e-01 , 6.3050300000000004e-01 , 7.4981500000000001e-01 -2.5491714789760640e+00 , 2.7727462882042988e+00 , 9.1417424000000018e+00 , 4.5853600000000000e-01 , 3.7547000000000003e-01 , 8.0546099999999998e-01 -2.4612470646875009e+00 , 2.8220399551296174e+00 , 8.9934487999999995e+00 , -5.9196899999999997e-01 , 8.0425000000000002e-01 , 5.2481199999999999e-02 -2.3826375887852578e+00 , 2.8338148980664233e+00 , 8.4184952000000006e+00 , -8.3478300000000005e-01 , 5.1446800000000004e-01 , -1.9611500000000001e-01 -2.2859854051185411e+00 , 2.9499301273008660e+00 , 9.1270367999999991e+00 , -5.2561000000000002e-01 , -3.5238900000000001e-01 , -7.7431099999999997e-01 -2.0438126778537131e+00 , 3.3784151668197913e+00 , 1.2809552000000002e+01 , -2.8240100000000001e-01 , -9.4837099999999996e-01 , -1.4436900000000000e-01 -1.9397944670301481e+00 , 3.4034367033354003e+00 , 1.2152636000000001e+01 , -6.2172499999999997e-01 , 7.8316699999999995e-01 , 1.0432200000000001e-02 -1.7809495409736185e+00 , 3.5354081303429945e+00 , 1.2504935999999999e+01 , -4.6435799999999999e-01 , 7.8225199999999995e-01 , -4.1527599999999998e-01 -1.6699906088359844e+00 , 3.5882362385318531e+00 , 1.2184855199999999e+01 , -5.0537299999999996e-01 , -2.6149600000000001e-01 , 8.2232499999999997e-01 -1.5021078850652416e+00 , 3.7255171688873920e+00 , 1.2508991999999999e+01 , -7.7565300000000004e-01 , -6.2221400000000004e-01 , -1.0588800000000000e-01 -1.7308809944471926e+00 , 3.3405121008783230e+00 , 9.3133839999999992e+00 , 5.3674999999999995e-01 , -8.3103000000000005e-01 , 1.4590600000000001e-01 -4.3001375135856694e+00 , 9.6049631476735353e-01 , 1.4268913599999999e+00 , -1.3801700000000000e-01 , 2.3506099999999999e-01 , 9.6213199999999999e-01 -4.3517581864582802e+00 , 9.2366478078655168e-01 , 1.4448594400000001e+00 , -1.0858100000000000e-01 , 2.2565399999999999e-01 , 9.6813800000000005e-01 -4.4101147540195855e+00 , 8.8250029187605050e-01 , 1.4585302400000000e+00 , -1.0174999999999999e-01 , 2.4120200000000000e-01 , 9.6512600000000004e-01 -4.4613542975329175e+00 , 8.4634491735240092e-01 , 1.4797348000000001e+00 , -1.0594700000000000e-01 , 2.1724700000000000e-01 , 9.7035000000000005e-01 -4.5281635461862226e+00 , 8.0028289228205951e-01 , 1.4919932800000000e+00 , -6.2867099999999995e-02 , 1.8012900000000001e-01 , 9.8163199999999995e-01 -4.5946547662754664e+00 , 7.5259650560405822e-01 , 1.5066864000000000e+00 , -6.6092700000000004e-02 , 1.6834900000000000e-01 , 9.8350899999999997e-01 -4.6677343604736308e+00 , 7.0083377124205248e-01 , 1.5182969600000000e+00 , -1.0616500000000000e-01 , 2.0554100000000000e-01 , 9.7287299999999999e-01 -4.7278640532374965e+00 , 6.5861737991400116e-01 , 1.5429771999999999e+00 , -8.0225699999999997e-02 , 2.1037100000000000e-01 , 9.7432399999999997e-01 -4.8023702210962957e+00 , 6.0573249365907578e-01 , 1.5599031999999999e+00 , 7.4494599999999994e-02 , -1.7943200000000001e-01 , -9.8094599999999998e-01 -4.8843542895594840e+00 , 5.4789042326888970e-01 , 1.5748875199999999e+00 , -9.0830800000000003e-02 , 2.0630999999999999e-01 , 9.7426199999999996e-01 -4.9592172016526179e+00 , 4.9507785265037407e-01 , 1.5975064800000001e+00 , -7.5892100000000004e-02 , 1.9970900000000000e-01 , 9.7691200000000000e-01 -5.0570084511934557e+00 , 4.2542475005557545e-01 , 1.6099521600000000e+00 , -8.2900100000000004e-02 , 1.9838700000000001e-01 , 9.7661200000000004e-01 -5.1332172130230260e+00 , 3.7272582382511188e-01 , 1.6386935999999999e+00 , -9.3262300000000006e-02 , 2.1670500000000001e-01 , 9.7177199999999997e-01 -5.2235082429955710e+00 , 3.0876818776672565e-01 , 1.6620124800000000e+00 , -7.4663999999999994e-02 , 1.7603500000000000e-01 , 9.8154799999999998e-01 -5.3307901874931929e+00 , 2.3270889795351923e-01 , 1.6816019200000001e+00 , -4.4081900000000000e-02 , 1.6705700000000001e-01 , 9.8496099999999998e-01 -5.4452680844966928e+00 , 1.5109408257263413e-01 , 1.7014784000000001e+00 , -6.0333400000000002e-02 , 1.9313000000000000e-01 , 9.7931599999999996e-01 -5.5526096659080615e+00 , 7.5630515579637514e-02 , 1.7292911200000001e+00 , -4.4673600000000001e-02 , 2.0041400000000001e-01 , 9.7869200000000001e-01 -5.6767237122870773e+00 , -1.2636901572941728e-02 , 1.7550976800000000e+00 , -5.4781900000000001e-02 , 2.0368200000000000e-01 , 9.7750300000000001e-01 -5.8002968498735923e+00 , -9.9963425491305102e-02 , 1.7854573600000001e+00 , -8.0520400000000006e-02 , 1.7151900000000000e-01 , 9.8188500000000001e-01 -5.9405412050059443e+00 , -1.9880910598727120e-01 , 1.8149215999999999e+00 , -7.5549599999999995e-02 , 1.8786300000000000e-01 , 9.7928499999999996e-01 -6.0811082900681166e+00 , -2.9861868371448042e-01 , 1.8501828000000000e+00 , -7.7994300000000003e-02 , 1.8643399999999999e-01 , 9.7936699999999999e-01 -6.2382085686939686e+00 , -4.0863834484320760e-01 , 1.8857601600000000e+00 , -8.6976999999999999e-02 , 1.8493200000000001e-01 , 9.7889499999999996e-01 -6.4030733973884750e+00 , -5.2560510751368117e-01 , 1.9253974720000000e+00 , -7.7548699999999998e-02 , 1.8841900000000000e-01 , 9.7902199999999995e-01 -6.5852367113158001e+00 , -6.5451567255400178e-01 , 1.9674044239999999e+00 , -7.2191000000000005e-02 , 1.8691500000000000e-01 , 9.7972000000000004e-01 -6.7835454932185391e+00 , -7.9512624955392708e-01 , 2.0127680799999998e+00 , -7.6951599999999995e-02 , 1.8889000000000000e-01 , 9.7897900000000004e-01 -6.9989191515745919e+00 , -9.4726107671224291e-01 , 2.0625246960000001e+00 , -7.6830099999999998e-02 , 1.8433800000000000e-01 , 9.7985500000000003e-01 -7.2227505901342672e+00 , -1.1046850327768336e+00 , 2.1195001599999999e+00 , 8.3781900000000006e-02 , -1.9397800000000001e-01 , -9.7742200000000001e-01 -7.4877034769815545e+00 , -1.2921657523852454e+00 , 2.1783391999999999e+00 , -8.1934800000000002e-02 , 1.8714900000000001e-01 , 9.7890900000000003e-01 -7.7776816502495896e+00 , -1.4973565372956164e+00 , 2.2442128000000001e+00 , -7.6256400000000002e-02 , 1.8562999999999999e-01 , 9.7965599999999997e-01 -8.0850855765273515e+00 , -1.7140196421127873e+00 , 2.3200714400000000e+00 , -7.5590699999999997e-02 , 1.8140400000000001e-01 , 9.8049900000000001e-01 -8.4413103342051254e+00 , -1.9653758982583036e+00 , 2.4028606400000001e+00 , -7.3857099999999995e-02 , 1.8350400000000000e-01 , 9.8024100000000003e-01 -8.8562941465086826e+00 , -2.2597251294649210e+00 , 2.4955797600000000e+00 , -8.2305900000000001e-02 , 1.8620999999999999e-01 , 9.7905699999999996e-01 -9.2963477229246543e+00 , -2.5700669545370687e+00 , 2.6038562399999998e+00 , -8.1361799999999998e-02 , 1.9055800000000001e-01 , 9.7829900000000003e-01 -9.8121588315100148e+00 , -2.9337085277715138e+00 , 2.7272626400000002e+00 , -8.8846800000000004e-02 , 1.9056100000000001e-01 , 9.7764700000000004e-01 -1.0384492093717709e+01 , -3.3382073064959741e+00 , 2.8707930400000001e+00 , -8.9672699999999994e-02 , 1.9686999999999999e-01 , 9.7631999999999997e-01 -1.1040837775708928e+01 , -3.8009222412175179e+00 , 3.0383921599999999e+00 , -7.7233800000000005e-02 , 1.9806799999999999e-01 , 9.7714100000000004e-01 -1.1864149925671779e+01 , -4.3824912274662919e+00 , 3.2367471999999999e+00 , -4.6223399999999998e-02 , 2.3890700000000001e-01 , 9.6994199999999997e-01 -1.2938586285226563e+01 , -5.1421090578234923e+00 , 3.4797848000000000e+00 , -1.3919300000000001e-02 , 2.4134200000000000e-01 , 9.7033999999999998e-01 -1.4415185210086271e+01 , -6.1873738417750967e+00 , 3.7928872000000000e+00 , -5.1691799999999998e-03 , 1.9408300000000001e-01 , 9.8097199999999996e-01 -1.6520422200590076e+01 , -7.6783357916767336e+00 , 4.2202960000000003e+00 , -4.8012899999999997e-02 , 1.8154899999999999e-01 , 9.8220900000000000e-01 -2.1433624763074189e+01 , -1.1145693430109715e+01 , 5.4350263999999999e+00 , -8.4673200000000004e-01 , 2.8651500000000002e-01 , 4.4828000000000001e-01 -3.2944969905710622e+01 , -1.9276252051457007e+01 , 8.1806784000000015e+00 , -7.9426099999999999e-01 , 5.4148900000000000e-01 , -2.7557100000000001e-01 -3.3290741004488638e+01 , -1.9478028024302731e+01 , 8.9079295999999992e+00 , -7.9426099999999999e-01 , 5.4148900000000000e-01 , -2.7557100000000001e-01 -3.3324829953124357e+01 , -1.9457216755890855e+01 , 9.5872264000000005e+00 , -7.6215599999999994e-01 , 4.4621899999999998e-01 , -4.6904899999999999e-01 -4.2861106517848270e+01 , -2.5603519928352924e+01 , 2.0727384000000001e+01 , 5.6340500000000004e-01 , -6.9379299999999999e-01 , 4.4858199999999998e-01 -4.0578238077156215e+01 , -2.3900574340441146e+01 , 2.1551688000000002e+01 , 1.4958900000000000e-01 , -6.4316399999999996e-01 , 7.5097499999999995e-01 -7.4440468298169087e+00 , -9.1441635097364671e-01 , 7.3905799999999999e+00 , 4.9318500000000001e-02 , 3.9219599999999999e-01 , 9.1855799999999999e-01 -7.2048520038723565e+00 , -7.4485794774150049e-01 , 7.3326000000000002e+00 , -3.8189299999999998e-01 , -2.5784699999999999e-01 , 8.8751000000000002e-01 -7.1670854374431752e+00 , -7.0999323314593488e-01 , 7.4501927999999999e+00 , 5.8731699999999998e-01 , 2.0106199999999999e-01 , 7.8398500000000004e-01 -7.0196818897727828e+00 , -6.0326065171466592e-01 , 7.4635776000000007e+00 , -7.3370299999999999e-01 , 5.1968500000000001e-02 , -6.7747999999999997e-01 -6.9727360607218953e+00 , -5.6253147630827183e-01 , 7.5713944000000000e+00 , -5.8840899999999996e-01 , 3.4160900000000000e-01 , -7.3285599999999995e-01 -6.8520236168826694e+00 , -4.7329862056039262e-01 , 7.6038320000000006e+00 , -6.4439000000000002e-01 , 8.0855099999999999e-02 , -7.6041099999999995e-01 -6.8226430674718692e+00 , -4.4357840912912039e-01 , 7.7292456000000005e+00 , 5.1855700000000005e-01 , -1.2735099999999999e-02 , 8.5494800000000004e-01 -6.7463826018387625e+00 , -3.8355740070322231e-01 , 7.8053527999999996e+00 , 4.9297999999999997e-01 , 1.1701800000000000e-01 , 8.6213600000000001e-01 -6.6374163438782938e+00 , -3.0217298432261153e-01 , 7.8434792000000009e+00 , 2.7645199999999998e-01 , 2.2715500000000000e-01 , 9.3379599999999996e-01 -6.5160866924625420e+00 , -2.1324563865227208e-01 , 7.8637176000000002e+00 , 3.0068200000000000e-01 , 2.6096300000000000e-01 , 9.1732700000000000e-01 -6.3040466356914351e+00 , -6.6144056903515658e-02 , 7.7685784000000000e+00 , 1.6455199999999999e-03 , -3.8607300000000000e-01 , 9.2246700000000004e-01 -6.2695246656863306e+00 , -3.2680265705167244e-02 , 7.8851208000000002e+00 , 2.3497799999999999e-01 , -4.8436699999999999e-01 , 8.4271799999999997e-01 -6.2033470434901403e+00 , 1.9897933827131675e-02 , 7.9633184000000004e+00 , -9.3811199999999995e-01 , -5.0740599999999997e-02 , -3.4259400000000001e-01 -6.1531924277859824e+00 , 6.2374860398252352e-02 , 8.0633352000000009e+00 , -8.7168199999999996e-01 , 7.0602700000000004e-02 , -4.8496000000000000e-01 -5.9139858071038853e+00 , 2.2471503640730761e-01 , 7.9010120000000006e+00 , 4.5482899999999998e-01 , 6.3339000000000001e-01 , 6.2605699999999997e-01 -5.9861657040793963e+00 , 1.9026832744455402e-01 , 8.1723376000000005e+00 , -8.9769800000000000e-01 , -2.9881300000000000e-01 , -3.2380300000000001e-01 -5.8287033114128413e+00 , 2.9992807327557269e-01 , 8.1138167999999986e+00 , -5.8978799999999998e-01 , 7.2181200000000001e-01 , -3.6212899999999998e-01 -5.8765329875840973e+00 , 2.8242629265093955e-01 , 8.3639159999999997e+00 , -9.3621900000000002e-01 , -3.3192100000000002e-01 , -1.1542300000000000e-01 -5.8927028792421874e+00 , 2.8405930574507754e-01 , 8.5757536000000005e+00 , -7.1865199999999996e-01 , 2.2281599999999999e-01 , -6.5870499999999998e-01 -5.7549202057357878e+00 , 3.8217305702831417e-01 , 8.5432015999999997e+00 , -1.2084200000000000e-01 , -9.9175800000000003e-01 , 4.2588899999999999e-02 -5.3438716844997423e+00 , 6.4564461212460866e-01 , 8.0345376000000002e+00 , -4.3349500000000002e-01 , -4.4913300000000000e-01 , -7.8125699999999998e-01 -5.3772923960430958e+00 , 6.3640653605131803e-01 , 8.2751312000000006e+00 , 8.7075800000000003e-01 , -3.3242100000000002e-01 , 3.6232100000000000e-01 -5.3382285898912292e+00 , 6.7285469231043993e-01 , 8.3950224000000002e+00 , -6.4894700000000005e-01 , 6.9019399999999997e-01 , -3.2015600000000000e-01 -5.3114997978604137e+00 , 7.0247575013512575e-01 , 8.5416103999999997e+00 , 2.8148099999999998e-01 , 9.0869800000000001e-01 , 3.0827900000000003e-01 -5.2395522554294836e+00 , 7.5812893852671448e-01 , 8.6074839999999995e+00 , -9.6950499999999995e-01 , -8.9008900000000002e-02 , 2.2833700000000001e-01 -5.3080368234635369e+00 , 7.3212272907610032e-01 , 8.9620408000000005e+00 , 9.9103900000000000e-01 , -1.1392300000000000e-01 , -6.9732000000000002e-02 -5.1747860862295827e+00 , 8.2478823492961495e-01 , 8.9086992000000009e+00 , -8.2024699999999995e-01 , 1.6592000000000001e-01 , 5.4741700000000004e-01 -4.7863936443615041e+00 , 1.0639678363854062e+00 , 8.2790207999999996e+00 , 3.6737199999999998e-01 , 7.2729900000000003e-01 , -5.7971899999999998e-01 -4.8020727454198795e+00 , 1.0692260062192216e+00 , 8.5298167999999990e+00 , -6.1450899999999997e-01 , -5.3021200000000002e-01 , 5.8416900000000005e-01 -4.6797151789656555e+00 , 1.1534350855009721e+00 , 8.4631527999999996e+00 , -8.7973400000000002e-01 , -2.5641500000000000e-01 , 4.0039799999999998e-01 -4.6233993209750714e+00 , 1.1996610942274932e+00 , 8.5540799999999990e+00 , 6.7014899999999999e-01 , 7.6782199999999995e-02 , -7.3824400000000001e-01 -4.4524842040272299e+00 , 1.3098834102778540e+00 , 8.3479312000000014e+00 , -8.5091499999999998e-01 , 4.9939899999999998e-01 , 1.6292200000000001e-01 -4.1168488247100763e+00 , 1.5064684465968090e+00 , 7.6657016000000002e+00 , -1.0887200000000000e-01 , 8.2219799999999996e-02 , 9.9065000000000003e-01 -4.0060880198422693e+00 , 1.5795877495491017e+00 , 7.5622840000000000e+00 , -1.5921700000000000e-01 , 5.3594399999999998e-01 , 8.2910499999999998e-01 -3.9844282653722036e+00 , 1.6056129111564170e+00 , 7.7184400000000002e+00 , -5.1527999999999996e-01 , -5.6639799999999997e-02 , 8.5514800000000002e-01 -3.8703327883083034e+00 , 1.6793211362487264e+00 , 7.5908840000000000e+00 , -2.1425600000000000e-01 , 1.4962300000000000e-02 , 9.7666299999999995e-01 -3.7834645451496622e+00 , 1.7383813935547421e+00 , 7.5387280000000008e+00 , -1.7418300000000000e-01 , 5.1889800000000000e-02 , 9.8334500000000002e-01 -3.7156378602523219e+00 , 1.7879968370366592e+00 , 7.5438967999999997e+00 , -8.3671400000000007e-02 , -4.8423300000000002e-02 , 9.9531599999999998e-01 -3.6529149111472003e+00 , 1.8357297510381108e+00 , 7.5671616000000004e+00 , 5.2155300000000004e-01 , 1.2855000000000000e-01 , -8.4348000000000001e-01 -3.5512631481860808e+00 , 1.8992478361211633e+00 , 7.4391167999999999e+00 , 6.7199500000000001e-01 , 3.6521799999999999e-01 , -6.4423500000000000e-01 -3.5500120610491197e+00 , 1.9189778501762553e+00 , 7.7106920000000008e+00 , -5.9692999999999996e-01 , -6.9138500000000003e-01 , 4.0701500000000002e-01 -3.4470916465279866e+00 , 1.9830484261367671e+00 , 7.5587584000000003e+00 , -8.5150999999999994e-03 , -4.8858600000000002e-01 , 8.7247399999999997e-01 -3.3314277047421843e+00 , 2.0508835748822078e+00 , 7.3226576000000003e+00 , 2.3788300000000001e-01 , -5.0630100000000000e-01 , 8.2889800000000002e-01 -3.3048740336470912e+00 , 2.0825722383215775e+00 , 7.5111784000000004e+00 , -9.8862399999999995e-01 , -9.2127299999999995e-02 , -1.1888899999999999e-01 -3.2845153219001766e+00 , 2.1146380480042350e+00 , 7.7608512000000003e+00 , -1.8156300000000000e-01 , 6.3817199999999996e-01 , 7.4817800000000001e-01 -3.2000613338334127e+00 , 2.1684889923187054e+00 , 7.6622696000000001e+00 , 8.4226700000000002e-03 , 4.2306300000000002e-01 , 9.0606100000000001e-01 -3.1013893767255816e+00 , 2.2252118256139686e+00 , 7.4484248000000006e+00 , -6.6936099999999998e-01 , 2.3229000000000000e-01 , -7.0568900000000001e-01 -3.0864662328551162e+00 , 2.2602493148726412e+00 , 7.8088784000000002e+00 , 6.0559399999999997e-01 , 5.1478400000000002e-01 , -6.0683900000000002e-01 -3.0103154010058479e+00 , 2.3104638353039157e+00 , 7.7361823999999997e+00 , 4.9631599999999998e-01 , -8.6729700000000007e-02 , -8.6379899999999998e-01 -2.9381334490257038e+00 , 2.3589814329648435e+00 , 7.6822688000000001e+00 , -2.1283099999999999e-01 , -5.5115400000000002e-02 , 9.7553299999999998e-01 -3.0614962138711763e+00 , 2.4070917134324592e+00 , 9.7498408000000012e+00 , -5.5143600000000004e-01 , 6.2569100000000000e-01 , 5.5175099999999999e-01 -2.8158330267389089e+00 , 2.4554722011294201e+00 , 7.7978024000000001e+00 , 1.8464300000000000e-01 , -5.2078700000000000e-01 , 8.3348000000000000e-01 -2.7483144534173469e+00 , 2.5027667536322360e+00 , 7.7915103999999999e+00 , -2.8920699999999999e-01 , 6.5236000000000005e-01 , -7.0056099999999999e-01 -2.7514433269343899e+00 , 2.5963887312430640e+00 , 9.2265960000000007e+00 , -1.2338500000000001e-02 , 4.4278200000000001e-01 , 8.9654400000000001e-01 -2.6623162455622724e+00 , 2.6569234578927210e+00 , 9.1760103999999991e+00 , 2.3799999999999999e-01 , 4.7396899999999997e-01 , 8.4776799999999997e-01 -2.5763548912414027e+00 , 2.7199484366639504e+00 , 9.1858903999999999e+00 , 2.3026900000000000e-01 , 5.4562500000000003e-01 , 8.0577299999999996e-01 -2.4874440155522310e+00 , 2.7594928275274730e+00 , 8.8203512000000011e+00 , -6.9346799999999997e-01 , 4.9814999999999998e-01 , 5.2052699999999996e-01 -2.4082683743418491e+00 , 2.7949843636454390e+00 , 8.4947480000000013e+00 , -4.1021200000000002e-01 , 6.2251800000000002e-01 , 6.6648099999999999e-01 -2.3276110777664432e+00 , 2.8667651492126636e+00 , 8.6862431999999998e+00 , -9.4413499999999995e-01 , 6.9616699999999997e-03 , 3.2948600000000000e-01 -2.2301269185882671e+00 , 2.9695736008128506e+00 , 9.1757191999999996e+00 , 5.3602899999999998e-01 , 3.5697000000000001e-01 , 7.6501399999999997e-01 -1.9804309504073163e+00 , 3.3634129152290910e+00 , 1.2389548000000001e+01 , -7.1753700000000004e-02 , 9.5834399999999997e-01 , 2.7645700000000001e-01 -1.8612462228176376e+00 , 3.4338334881668890e+00 , 1.2165532000000001e+01 , -9.4200600000000001e-01 , 3.1154500000000002e-01 , -1.2475600000000001e-01 -1.7001502488438394e+00 , 3.5759176830626807e+00 , 1.2546536000000001e+01 , -3.5532599999999998e-02 , 8.0656700000000003e-01 , -5.9007299999999996e-01 -1.6000837839276725e+00 , 3.6220082889474119e+00 , 1.2153072800000000e+01 , 5.9016299999999999e-01 , 4.8158100000000002e-02 , -8.0584699999999998e-01 -1.3382516795171748e+00 , 3.8914165077417833e+00 , 1.3355344000000001e+01 , -9.5477199999999995e-01 , -2.5045299999999998e-01 , 1.6026299999999999e-01 -4.2901527084238307e+00 , 8.9427257443474995e-01 , 1.4386433599999999e+00 , -8.3470900000000001e-02 , 2.3787500000000000e-01 , 9.6770199999999995e-01 -4.3406089393931726e+00 , 8.5658952800312060e-01 , 1.4573987200000000e+00 , -1.5097700000000000e-01 , 2.1025400000000000e-01 , 9.6591899999999997e-01 -4.3977485934101264e+00 , 8.1357601838273741e-01 , 1.4721636000000000e+00 , -1.2192100000000000e-01 , 1.9523499999999999e-01 , 9.7314900000000004e-01 -4.4556609695327944e+00 , 7.6989144841682511e-01 , 1.4890812800000000e+00 , -9.5218399999999995e-02 , 1.7914900000000000e-01 , 9.7920300000000005e-01 -4.5270017622435175e+00 , 7.1539926017038247e-01 , 1.4973087199999999e+00 , -7.1249000000000007e-02 , 1.8236300000000000e-01 , 9.8064600000000002e-01 -4.5854586159679265e+00 , 6.7253603338560830e-01 , 1.5183988799999999e+00 , -7.7613199999999993e-02 , 1.7513400000000001e-01 , 9.8148100000000005e-01 -4.6572422411127157e+00 , 6.1795321580981444e-01 , 1.5316120799999999e+00 , -1.1197200000000000e-01 , 2.1417800000000001e-01 , 9.7035600000000000e-01 -4.7161971611681119e+00 , 5.7493627549298298e-01 , 1.5572824000000001e+00 , -7.8511499999999998e-02 , 1.8801499999999999e-01 , 9.7902299999999998e-01 -4.8029484486292624e+00 , 5.0823429702282952e-01 , 1.5662128799999999e+00 , -8.1217200000000003e-02 , 1.8114100000000000e-01 , 9.8009800000000002e-01 -4.8690571803546554e+00 , 4.5861335941721748e-01 , 1.5922731999999999e+00 , -1.0841500000000000e-01 , 2.1788299999999999e-01 , 9.6993499999999999e-01 -4.9504412721552713e+00 , 3.9854858598695420e-01 , 1.6119198400000001e+00 , -7.3829800000000001e-02 , 1.7727399999999999e-01 , 9.8138800000000004e-01 -5.0391451535422283e+00 , 3.3158450341361712e-01 , 1.6305410400000000e+00 , -9.5713599999999996e-02 , 1.9344500000000001e-01 , 9.7643100000000005e-01 -5.1197400050104811e+00 , 2.7070182856033753e-01 , 1.6564661599999999e+00 , -8.6797899999999997e-02 , 2.0479400000000000e-01 , 9.7494899999999995e-01 -5.2240326179176604e+00 , 1.9122451737762725e-01 , 1.6742720000000000e+00 , -5.1162300000000001e-02 , 1.6995800000000000e-01 , 9.8412200000000005e-01 -5.3289085511479710e+00 , 1.1253397708953661e-01 , 1.6960475200000000e+00 , -6.4782000000000006e-02 , 1.9289600000000001e-01 , 9.7907800000000000e-01 -5.4266728246058396e+00 , 3.9925402503508289e-02 , 1.7254545600000000e+00 , -5.0951700000000003e-02 , 2.0928800000000000e-01 , 9.7652600000000001e-01 -5.5392170270126639e+00 , -4.5551360521607798e-02 , 1.7521004000000000e+00 , -5.4640700000000000e-02 , 1.9290199999999999e-01 , 9.7969499999999998e-01 -5.6674905869415664e+00 , -1.4271698155521317e-01 , 1.7768139199999999e+00 , -4.4351500000000002e-02 , 1.6991400000000001e-01 , 9.8446000000000000e-01 -5.8047792270421255e+00 , -2.4614113664549864e-01 , 1.8039901599999999e+00 , -7.0823700000000003e-02 , 1.8438299999999999e-01 , 9.8029900000000003e-01 -5.9338339063028576e+00 , -3.4328636676344892e-01 , 1.8394822399999999e+00 , 9.0120900000000004e-02 , -1.8327199999999999e-01 , -9.7892299999999999e-01 -6.0880058879724421e+00 , -4.5901437763408159e-01 , 1.8724710400000000e+00 , -7.3475200000000004e-02 , 1.7626100000000000e-01 , 9.8159700000000005e-01 -6.2414205774531366e+00 , -5.7451388436766893e-01 , 1.9116348400000001e+00 , -8.4790500000000005e-02 , 1.7992600000000000e-01 , 9.8001899999999997e-01 -6.4111631040011199e+00 , -7.0203722683134240e-01 , 1.9526374639999999e+00 , -8.9325500000000002e-02 , 1.7913799999999999e-01 , 9.7975999999999996e-01 -6.5970785166000434e+00 , -8.4239045640220800e-01 , 1.9965948424000000e+00 , -7.5379699999999994e-02 , 1.7927899999999999e-01 , 9.8090599999999994e-01 -6.7990820971164192e+00 , -9.9437042103756301e-01 , 2.0443136719999999e+00 , -7.4398199999999998e-02 , 1.7924300000000001e-01 , 9.8098799999999997e-01 -7.0180345839039449e+00 , -1.1587682891180182e+00 , 2.0972378159999998e+00 , -8.4734100000000007e-02 , 1.8285199999999999e-01 , 9.7948199999999996e-01 -7.2527912243493731e+00 , -1.3353810410029716e+00 , 2.1561518400000002e+00 , -7.8295600000000007e-02 , 1.9145300000000001e-01 , 9.7837399999999997e-01 -7.5126559413007854e+00 , -1.5309498471632637e+00 , 2.2211924000000001e+00 , -8.2091899999999995e-02 , 1.8245000000000000e-01 , 9.7978200000000004e-01 -7.8122419896959983e+00 , -1.7569971844143386e+00 , 2.2910107200000001e+00 , 7.3030999999999999e-02 , -1.7855099999999999e-01 , -9.8121700000000001e-01 -8.1533164233055668e+00 , -2.0130269034117863e+00 , 2.3683856799999998e+00 , -7.5587399999999999e-02 , 1.8264000000000000e-01 , 9.8026999999999997e-01 -8.5187314485398211e+00 , -2.2877862387085655e+00 , 2.4581626399999998e+00 , -7.2154700000000002e-02 , 1.8471000000000001e-01 , 9.8014100000000004e-01 -8.9490455787480645e+00 , -2.6121145924210420e+00 , 2.5582366400000001e+00 , 8.5019399999999995e-02 , -1.8815200000000001e-01 , -9.7845300000000002e-01 -9.3958076540586752e+00 , -2.9483787656156233e+00 , 2.6762943200000002e+00 , -8.6835899999999994e-02 , 1.8063599999999999e-01 , 9.7970900000000005e-01 -9.9565404999059091e+00 , -3.3704566020743298e+00 , 2.8091532799999999e+00 , -8.7395700000000007e-02 , 1.9314799999999999e-01 , 9.7726999999999997e-01 -1.0524732231038955e+01 , -3.7964555479134381e+00 , 2.9662588000000003e+00 , 9.3283699999999997e-02 , -1.9548699999999999e-01 , -9.7626000000000002e-01 -1.1232382977315185e+01 , -4.3283144150414552e+00 , 3.1494808000000001e+00 , -8.1639900000000001e-02 , 2.1644900000000000e-01 , 9.7287500000000005e-01 -1.2085707148756896e+01 , -4.9698351771240823e+00 , 3.3676104000000002e+00 , -2.6012700000000000e-02 , 2.6583299999999999e-01 , 9.6366799999999997e-01 -1.2870939935736331e+01 , -5.5569797045499216e+00 , 3.6197168000000000e+00 , 2.1799200000000001e-02 , 2.6751500000000000e-01 , 9.6330700000000002e-01 -1.5221253223940998e+01 , -7.3354540156655332e+00 , 4.0216560000000001e+00 , -4.1217999999999998e-02 , 1.8070200000000000e-01 , 9.8267400000000005e-01 -1.7251779326135829e+01 , -8.8656487718405383e+00 , 4.4965824000000003e+00 , -4.3813800000000000e-02 , 1.7951900000000001e-01 , 9.8277800000000004e-01 -2.1007277370671805e+01 , -1.1699131495847597e+01 , 5.2638943999999999e+00 , -8.4673200000000004e-01 , 2.8651500000000002e-01 , 4.4828000000000001e-01 -2.2073263734274960e+01 , -1.2483075382801323e+01 , 5.8218335999999997e+00 , -8.4673200000000004e-01 , 2.8651500000000002e-01 , 4.4828000000000001e-01 -2.2044993790432812e+01 , -1.2435748364184450e+01 , 6.2508648000000004e+00 , -8.4673200000000004e-01 , 2.8651500000000002e-01 , 4.4828000000000001e-01 -2.1969228330367802e+01 , -1.2351995149242354e+01 , 6.6711704000000003e+00 , -8.4673100000000001e-01 , 2.8651500000000002e-01 , 4.4828000000000001e-01 -2.1962168965249674e+01 , -1.2319787622356094e+01 , 7.1038936000000001e+00 , -8.4673100000000001e-01 , 2.8651500000000002e-01 , 4.4828000000000001e-01 -2.1899666490776706e+01 , -1.2245973580678676e+01 , 7.5256447999999994e+00 , -8.4673100000000001e-01 , 2.8651500000000002e-01 , 4.4828000000000001e-01 -3.1977123712131185e+01 , -1.9797793513177751e+01 , 1.0492432000000001e+01 , 7.7197600000000000e-01 , -5.0507100000000005e-01 , 3.8594899999999999e-01 -3.1897316863194760e+01 , -1.9697244398498217e+01 , 1.1137554400000001e+01 , 7.7197600000000000e-01 , -5.0507100000000005e-01 , 3.8594899999999999e-01 -4.3563169139682671e+01 , -2.8339262325211052e+01 , 1.6205359999999999e+01 , -3.5733799999999999e-01 , 9.3388599999999999e-01 , -1.2912500000000000e-02 -4.0968767432540368e+01 , -2.6235956289034398e+01 , 1.8064984000000003e+01 , -3.7314000000000003e-01 , 9.2582399999999998e-01 , 6.0137299999999998e-02 -3.9828314251529896e+01 , -2.5334357408199299e+01 , 1.8506776000000002e+01 , 6.8638600000000005e-01 , -7.0334799999999997e-01 , 1.8486600000000000e-01 -3.7335769694659675e+01 , -2.3277574852314356e+01 , 2.0874127999999999e+01 , -2.5097399999999997e-01 , -8.5799700000000001e-01 , 4.4816699999999998e-01 -3.7339106984834778e+01 , -2.3063182256998452e+01 , 2.4452559999999998e+01 , -1.9835100000000000e-01 , -9.7948500000000005e-01 , -3.5578699999999998e-02 -4.0562933084467616e+01 , -2.5354166029888631e+01 , 2.7440895999999999e+01 , -3.2700899999999999e-01 , -8.6235099999999998e-01 , -3.8654500000000003e-01 -4.1109932572060437e+01 , -2.5689073867045657e+01 , 2.8836160000000000e+01 , -3.4109600000000001e-01 , -8.6851000000000000e-01 , -3.5964400000000002e-01 -6.9692823642191559e+00 , -8.1367415287533174e-01 , 7.1568816000000002e+00 , -7.4106399999999994e-01 , 6.6640800000000000e-01 , -8.2005999999999996e-02 -6.8950032695919550e+00 , -7.5243441331544103e-01 , 7.2341432000000001e+00 , -7.4106399999999994e-01 , 6.6640800000000000e-01 , -8.2005999999999996e-02 -6.9190341469161432e+00 , -7.6031816515259099e-01 , 7.4056911999999997e+00 , -5.7984000000000002e-01 , -7.7779900000000002e-01 , 2.4251800000000001e-01 -6.9933786735053882e+00 , -8.0282591268337944e-01 , 7.6322240000000008e+00 , -7.6661599999999996e-01 , -9.6099900000000005e-03 , -6.4203399999999999e-01 -6.9194604554346011e+00 , -7.4153424287189829e-01 , 7.7150808000000000e+00 , -8.3506100000000005e-01 , 7.0747800000000000e-02 , -5.4559000000000002e-01 -6.8565763103709845e+00 , -6.8798068827747372e-01 , 7.8093880000000002e+00 , 6.5790000000000004e-01 , 2.4655800000000002e-03 , 7.5310100000000002e-01 -6.6989187979890161e+00 , -5.6683638012059179e-01 , 7.7973136000000007e+00 , -9.9038699999999993e-02 , -1.7762400000000000e-01 , 9.7910200000000003e-01 -6.6174067036008379e+00 , -5.0069592780665007e-01 , 7.8657664000000000e+00 , -1.5497700000000000e-01 , -3.8699299999999998e-01 , 9.0896600000000005e-01 -6.4183335470409721e+00 , -3.5165557431481576e-01 , 7.7935487999999999e+00 , -2.2115200000000002e-02 , 1.7568300000000001e-01 , 9.8419800000000002e-01 -6.2942560893319834e+00 , -2.5629224224806002e-01 , 7.8029504000000003e+00 , 1.0531900000000000e-01 , -1.0691199999999999e-01 , 9.8867499999999997e-01 -6.1483923011252086e+00 , -1.4558656034559769e-01 , 7.7785000000000002e+00 , 7.2513499999999997e-01 , -3.8197399999999998e-01 , 5.7295300000000005e-01 -6.1192596855084043e+00 , -1.1630422034956078e-01 , 7.9017920000000004e+00 , 6.5940900000000002e-01 , -5.4706800000000000e-01 , 5.1565200000000000e-01 -6.0943762017346019e+00 , -8.8824031207582088e-02 , 8.0328944000000000e+00 , 6.0485400000000000e-01 , -5.1440200000000003e-01 , 6.0789899999999997e-01 -6.0779514649539657e+00 , -6.7004178333495368e-02 , 8.1798567999999996e+00 , 6.5543200000000001e-01 , -4.0451700000000002e-01 , 6.3778900000000005e-01 -6.0310232590320609e+00 , -2.5210278143259934e-02 , 8.2876632000000008e+00 , -6.2921400000000005e-01 , 3.4193600000000002e-01 , -6.9797600000000004e-01 -5.9225175781549240e+00 , 5.9450959030484141e-02 , 8.3052808000000002e+00 , 3.5077399999999997e-01 , -9.8733500000000002e-02 , 9.3124099999999999e-01 -5.6671399441617680e+00 , 2.4251637561651562e-01 , 8.0895223999999999e+00 , -2.4137600000000001e-01 , 6.8130299999999999e-01 , -6.9106000000000001e-01 -5.6357448049322798e+00 , 2.7437497523107979e-01 , 8.2145720000000004e+00 , 6.8514000000000005e-02 , -9.9005399999999999e-01 , 1.2287700000000000e-01 -5.6615343277392371e+00 , 2.6786642478497780e-01 , 8.4407823999999998e+00 , -1.7056199999999999e-01 , 9.8532699999999995e-01 , -6.3255500000000001e-03 -5.6777339743286426e+00 , 2.6903856244685453e-01 , 8.6608464000000005e+00 , -1.5755200000000000e-01 , 2.3032200000000000e-01 , -9.6027600000000002e-01 -5.6067905308549166e+00 , 3.2759061886650787e-01 , 8.7360591999999997e+00 , 4.2581500000000000e-01 , -1.1728600000000000e-01 , 8.9717700000000000e-01 -5.4638249477664314e+00 , 4.3363109165765334e-01 , 8.6784952000000004e+00 , 8.4810800000000006e-02 , 1.4499000000000001e-01 , 9.8579200000000000e-01 -5.2730627856410681e+00 , 5.7109176214218227e-01 , 8.5190008000000006e+00 , 2.1504599999999999e-01 , 5.1188400000000001e-01 , 8.3170299999999997e-01 -5.3283648600283868e+00 , 5.4761297569016620e-01 , 8.8358887999999993e+00 , 9.9727299999999997e-01 , -2.8480900000000000e-02 , 6.8077399999999996e-02 -5.2930883379668821e+00 , 5.8338568517944234e-01 , 8.9848064000000001e+00 , 9.8661100000000002e-01 , -1.1518600000000000e-01 , -1.1545900000000001e-01 -4.8157362857623074e+00 , 9.0157466772975159e-01 , 8.1854936000000009e+00 , 5.7873100000000000e-01 , -7.5234000000000001e-01 , 3.1473099999999998e-01 -4.7948519394073079e+00 , 9.2691551849140597e-01 , 8.3437087999999999e+00 , 4.1906100000000002e-01 , -7.9540100000000002e-01 , 4.3786399999999998e-01 -4.7555762799270003e+00 , 9.6482756636100597e-01 , 8.4655136000000013e+00 , -1.5435900000000000e-01 , -5.5226299999999995e-01 , 8.1925499999999996e-01 -4.6009035249789587e+00 , 1.0739173666863497e+00 , 8.3151712000000000e+00 , -2.4865599999999999e-01 , 4.8811899999999998e-02 , 9.6736100000000003e-01 -4.4771763810422947e+00 , 1.1632076384816341e+00 , 8.2260223999999997e+00 , -3.0336299999999999e-01 , 5.3329899999999997e-01 , 7.8966000000000003e-01 -4.4173332658418190e+00 , 1.2136423839040384e+00 , 8.2949224000000008e+00 , -3.0336299999999999e-01 , 5.3330000000000000e-01 , 7.8966000000000003e-01 -4.0829188902776776e+00 , 1.4278130989801165e+00 , 7.6053608000000006e+00 , 2.6351700000000000e-01 , -3.6506899999999998e-01 , -8.9290800000000004e-01 -4.0112570183536320e+00 , 1.4835751309654390e+00 , 7.6085951999999999e+00 , 8.8480299999999998e-02 , 2.6164900000000002e-01 , 9.6109900000000004e-01 -3.9268269467527155e+00 , 1.5455267733832483e+00 , 7.5713008000000004e+00 , 1.1994600000000000e-01 , 1.1749900000000001e-01 , 9.8580299999999998e-01 -3.8625844334661394e+00 , 1.5967251144054346e+00 , 7.5903535999999994e+00 , 3.5588100000000000e-01 , 2.6826699999999998e-01 , 8.9519899999999997e-01 -3.7826315315960937e+00 , 1.6553832217117601e+00 , 7.5587688000000002e+00 , 7.3362000000000005e-01 , 3.2829599999999998e-01 , 5.9499800000000003e-01 -3.7325296670771069e+00 , 1.6982804463034127e+00 , 7.6239664000000005e+00 , -8.0612799999999996e-01 , -2.8570299999999998e-01 , -5.1819999999999999e-01 -3.7068682151238370e+00 , 1.7281327208067001e+00 , 7.7877352000000002e+00 , 6.0592500000000005e-01 , -6.3968300000000000e-01 , 4.7292899999999999e-01 -3.5388818880085173e+00 , 1.8327537242441716e+00 , 7.4015727999999994e+00 , 4.3147200000000002e-01 , 8.5363500000000003e-01 , -2.9178500000000002e-01 -3.4583737611808183e+00 , 1.8911146413622353e+00 , 7.3314975999999996e+00 , -9.7394499999999995e-01 , -2.1251600000000001e-01 , 7.9173999999999994e-02 -3.4175935840701896e+00 , 1.9278112396514517e+00 , 7.4311400000000001e+00 , -8.7874099999999999e-01 , -4.7443900000000000e-01 , -5.2174699999999997e-02 -3.3748855174457466e+00 , 1.9675795756659513e+00 , 7.5298151999999998e+00 , 4.3252800000000002e-01 , -5.9898700000000005e-01 , -6.7389399999999999e-01 -3.3784418819263324e+00 , 1.9864175413397607e+00 , 7.8823232000000001e+00 , 5.0351100000000004e-01 , 5.2452200000000004e-01 , 6.8655100000000002e-01 -3.2916493210219060e+00 , 2.0462561087729090e+00 , 7.7866119999999999e+00 , -5.1823699999999995e-01 , 3.6832900000000002e-01 , 7.7185800000000004e-01 -3.2165931499435256e+00 , 2.1005978871009989e+00 , 7.7399264000000008e+00 , -3.7681399999999998e-01 , 4.5478299999999999e-01 , 8.0695899999999998e-01 -3.1474329771156819e+00 , 2.1530749043868114e+00 , 7.7221112000000005e+00 , -2.3669899999999999e-01 , 2.3306399999999999e-01 , 9.4321500000000003e-01 -3.0740172175286213e+00 , 2.2056584220153201e+00 , 7.6617600000000001e+00 , 4.6110300000000003e-03 , -8.3292900000000003e-02 , 9.9651400000000001e-01 -3.0206400945186744e+00 , 2.2520970657981723e+00 , 7.7543720000000000e+00 , 1.2853500000000001e-01 , 7.2181499999999998e-01 , -6.8004500000000001e-01 -2.9591105651582428e+00 , 2.3020147618852977e+00 , 7.7940063999999998e+00 , -2.7343300000000001e-02 , 5.1023799999999997e-01 , 8.5959900000000000e-01 -2.8872556746189706e+00 , 2.3525571210496303e+00 , 7.7291312000000003e+00 , -2.6446899999999999e-03 , 1.1339500000000000e-01 , 9.9354699999999996e-01 -2.8285614581650997e+00 , 2.4027631584843028e+00 , 7.7971472000000004e+00 , 2.7804800000000002e-01 , -3.4960000000000002e-01 , 8.9468899999999996e-01 -2.7637620156185072e+00 , 2.4531439991636530e+00 , 7.8120296000000007e+00 , -1.8464300000000000e-01 , 5.2078700000000000e-01 , -8.3348000000000000e-01 -2.7749248379067559e+00 , 2.5347417520529931e+00 , 9.2998224000000000e+00 , -5.4072399999999998e-01 , -1.6620599999999999e-01 , -8.2461700000000004e-01 -2.6863980414542095e+00 , 2.5987121414212728e+00 , 9.2189832000000003e+00 , 9.0956700000000001e-02 , 4.9116599999999999e-01 , 8.6630399999999996e-01 -2.6012008075775435e+00 , 2.6639771795384015e+00 , 9.2401472000000009e+00 , 2.0613200000000001e-01 , 4.1258400000000001e-01 , 8.8729000000000002e-01 -2.5154003884284908e+00 , 2.7249623508492875e+00 , 9.1450600000000009e+00 , 3.9224599999999998e-01 , 4.1902299999999998e-01 , 8.1887900000000002e-01 -2.4326198190404882e+00 , 2.7509431569011968e+00 , 8.5290576000000016e+00 , -7.2216899999999995e-01 , 4.1629200000000000e-01 , 5.5242400000000003e-01 -2.3573212325800514e+00 , 2.8064232247327707e+00 , 8.4932192000000004e+00 , -4.1021200000000002e-01 , 6.2251800000000002e-01 , 6.6648099999999999e-01 -2.2610726458420869e+00 , 2.9215368305158602e+00 , 9.1810647999999997e+00 , 5.5317499999999997e-01 , 4.7108899999999998e-01 , 6.8707600000000002e-01 -2.1747755060767986e+00 , 2.9891288558854194e+00 , 9.2029984000000002e+00 , 1.7022200000000001e-01 , 4.4933200000000001e-01 , 8.7699800000000006e-01 -1.9180208460857484e+00 , 3.3626042215358911e+00 , 1.2092867200000001e+01 , -6.8679199999999996e-01 , 7.2016999999999998e-01 , 9.8344500000000001e-02 -1.7654041870532249e+00 , 3.5016639074421558e+00 , 1.2455328000000002e+01 , -8.2580899999999999e-02 , -7.8955900000000001e-01 , 6.0809199999999997e-01 -1.6570960304842239e+00 , 3.5678480754174231e+00 , 1.2175786400000000e+01 , 5.0537299999999996e-01 , 2.6149600000000001e-01 , -8.2232499999999997e-01 -1.4820695765534275e+00 , 3.7290848884043601e+00 , 1.2622456000000001e+01 , -9.2951799999999996e-01 , -3.3267400000000003e-01 , -1.5913400000000000e-01 -1.7335990900241820e+00 , 3.3321706290278188e+00 , 9.2725639999999991e+00 , -5.7630199999999998e-01 , 8.0989500000000003e-01 , -1.0929899999999999e-01 -4.2354926138965467e+00 , 8.6234078009699888e-01 , 1.4266084800000001e+00 , -7.2184100000000001e-02 , 2.8486099999999998e-01 , 9.5584700000000000e-01 -4.2780525024832157e+00 , 8.2817182038251014e-01 , 1.4505492800000002e+00 , -6.8502199999999999e-02 , 2.6630199999999998e-01 , 9.6145199999999997e-01 -4.3342142160108565e+00 , 7.8396258915599826e-01 , 1.4644832000000001e+00 , -8.2945800000000000e-02 , 2.1035899999999999e-01 , 9.7409900000000005e-01 -4.3901369564834578e+00 , 7.3910005882573282e-01 , 1.4803421600000000e+00 , -1.0713399999999999e-01 , 1.9445100000000001e-01 , 9.7504400000000002e-01 -4.4468118955641636e+00 , 6.9361536545094604e-01 , 1.4985556799999999e+00 , -5.8159799999999998e-02 , 1.9304700000000000e-01 , 9.7946400000000000e-01 -4.5100884399276193e+00 , 6.4288973884525902e-01 , 1.5132851999999999e+00 , -6.9831000000000004e-02 , 1.8490000000000001e-01 , 9.8027299999999995e-01 -4.5730604465339155e+00 , 5.9162486080057186e-01 , 1.5305471200000000e+00 , -8.5644399999999996e-02 , 1.9350500000000001e-01 , 9.7735399999999995e-01 -4.6378384877449497e+00 , 5.4076853019069082e-01 , 1.5501844000000000e+00 , -8.0466200000000002e-02 , 2.0374400000000001e-01 , 9.7571200000000002e-01 -4.7158634106597521e+00 , 4.7832497567832277e-01 , 1.5625531200000000e+00 , -6.6489300000000001e-02 , 1.6997899999999999e-01 , 9.8320200000000002e-01 -4.7867549183510505e+00 , 4.2091904746899367e-01 , 1.5826573600000000e+00 , -9.8966999999999999e-02 , 2.2045500000000001e-01 , 9.7036299999999998e-01 -4.8583793331062939e+00 , 3.6403309021618036e-01 , 1.6054177599999999e+00 , -8.6542900000000006e-02 , 1.8993299999999999e-01 , 9.7797500000000004e-01 -4.9451251292407932e+00 , 2.9474078674608406e-01 , 1.6225787999999999e+00 , -1.0281100000000000e-01 , 1.9726199999999999e-01 , 9.7494499999999995e-01 -5.0170797043624296e+00 , 2.3795359088482781e-01 , 1.6512349600000000e+00 , 1.0486400000000000e-01 , -2.0031800000000000e-01 , -9.7410300000000005e-01 -5.1117879766254024e+00 , 1.6246527957875312e-01 , 1.6709356799999999e+00 , -6.0057699999999999e-02 , 1.9303799999999999e-01 , 9.7935099999999997e-01 -5.2060217390055801e+00 , 8.6700384449702739e-02 , 1.6944843999999999e+00 , -5.0609000000000001e-02 , 1.8270600000000001e-01 , 9.8186399999999996e-01 -5.3161249490510372e+00 , -2.0726345563328863e-03 , 1.7147893599999999e+00 , -5.2630999999999997e-02 , 2.1347600000000000e-01 , 9.7553000000000001e-01 -5.4114996024171269e+00 , -7.7340971533433223e-02 , 1.7462816000000001e+00 , -6.8163399999999999e-02 , 2.0512400000000000e-01 , 9.7635899999999998e-01 -5.5216194743328604e+00 , -1.6546331004792281e-01 , 1.7751124800000000e+00 , -4.3621300000000002e-02 , 1.6856399999999999e-01 , 9.8472499999999996e-01 -5.6701604326733097e+00 , -2.8602559620516566e-01 , 1.7933665599999999e+00 , -3.2912999999999998e-02 , 1.7676200000000000e-01 , 9.8370299999999999e-01 -5.7887327205171335e+00 , -3.8050991494114150e-01 , 1.8293172799999999e+00 , -6.6662100000000002e-02 , 1.9186600000000001e-01 , 9.7915500000000000e-01 -5.9228752825446094e+00 , -4.8746875767789133e-01 , 1.8646544000000000e+00 , -5.8019200000000000e-02 , 1.8876000000000001e-01 , 9.8030799999999996e-01 -6.0884523402582724e+00 , -6.2103612923070051e-01 , 1.8958336000000000e+00 , -6.2717099999999998e-02 , 1.8701400000000001e-01 , 9.8035300000000003e-01 -6.2392618604583863e+00 , -7.4101121684496896e-01 , 1.9386045359999999e+00 , -7.6317499999999996e-02 , 1.8887799999999999e-01 , 9.7903099999999998e-01 -6.4127934003511085e+00 , -8.8005463305638321e-01 , 1.9811529120000000e+00 , -7.7736700000000006e-02 , 1.8697300000000000e-01 , 9.7928499999999996e-01 -6.5939535324913674e+00 , -1.0247462703258678e+00 , 2.0289728400000002e+00 , -6.2045400000000001e-02 , 1.8210499999999999e-01 , 9.8131999999999997e-01 -6.8155180611721669e+00 , -1.2021867904812575e+00 , 2.0757043039999998e+00 , -6.3029799999999997e-02 , 1.9232600000000000e-01 , 9.7930499999999998e-01 -7.0295004144070221e+00 , -1.3737892845192921e+00 , 2.1339155999999999e+00 , -7.6342800000000002e-02 , 2.0262500000000000e-01 , 9.7627600000000003e-01 -7.2666959590875546e+00 , -1.5635328428399520e+00 , 2.1966847999999999e+00 , -7.0236900000000005e-02 , 1.8443599999999999e-01 , 9.8033199999999998e-01 -7.5363328606673150e+00 , -1.7780466544103639e+00 , 2.2646519199999999e+00 , -7.2218000000000004e-02 , 1.8385099999999999e-01 , 9.8029800000000000e-01 -7.8454394640365201e+00 , -2.0258808357364115e+00 , 2.3390233600000001e+00 , -6.6259899999999997e-02 , 1.8308800000000000e-01 , 9.8086099999999998e-01 -8.1937547423401398e+00 , -2.3054859594590518e+00 , 2.4222254400000001e+00 , -6.6649100000000003e-02 , 1.9281999999999999e-01 , 9.7896799999999995e-01 -8.5746816203633678e+00 , -2.6094448116397340e+00 , 2.5179376800000002e+00 , -6.3688400000000006e-02 , 1.9892399999999999e-01 , 9.7794300000000001e-01 -9.0108188552928592e+00 , -2.9588350624082063e+00 , 2.6265500799999999e+00 , -6.7535899999999996e-02 , 1.9911699999999999e-01 , 9.7764600000000002e-01 -9.5038023714949347e+00 , -3.3529324670905485e+00 , 2.7520583200000002e+00 , -7.1158899999999997e-02 , 1.9693700000000000e-01 , 9.7782999999999998e-01 -1.0051131506509460e+01 , -3.7909174945644253e+00 , 2.8979547200000000e+00 , 8.9017499999999999e-02 , -1.9718300000000000e-01 , -9.7631699999999999e-01 -1.0653414236479255e+01 , -4.2720726566210434e+00 , 3.0679031999999999e+00 , -8.8221499999999994e-02 , 1.9015599999999999e-01 , 9.7778200000000004e-01 -1.1432746653638242e+01 , -4.8937652681150610e+00 , 3.2685088000000002e+00 , -7.7096499999999998e-02 , 2.6893299999999998e-01 , 9.6006800000000003e-01 -1.1845334017800266e+01 , -5.2186945654377759e+00 , 3.4882711999999998e+00 , -4.2049799999999998e-02 , 4.0615000000000001e-01 , 9.1283899999999996e-01 -1.2982030409993174e+01 , -6.1274112879359279e+00 , 3.7740423999999999e+00 , 1.2635800000000001e-02 , 2.3900600000000000e-01 , 9.7093600000000002e-01 -1.5735942434422943e+01 , -8.3427846004516173e+00 , 4.2541583999999997e+00 , -4.4132800000000000e-02 , 1.8384600000000001e-01 , 9.8196399999999995e-01 -2.1421740539790278e+01 , -1.2894653214517847e+01 , 5.6107968000000001e+00 , -8.4673200000000004e-01 , 2.8651500000000002e-01 , 4.4828000000000001e-01 -3.2322013611801630e+01 , -2.1611214146650671e+01 , 8.4165399999999995e+00 , 7.7756700000000001e-01 , -4.5264599999999999e-01 , 4.3646299999999999e-01 -3.2663493007286135e+01 , -2.1848878119981801e+01 , 9.1648303999999996e+00 , -7.5815299999999997e-01 , 4.9786000000000002e-01 , -4.2111799999999999e-01 -3.2507239031066504e+01 , -2.1684769751482339e+01 , 9.8196456000000012e+00 , 7.7197600000000000e-01 , -5.0507100000000005e-01 , 3.8594899999999999e-01 -3.9871438417319361e+01 , -2.7396560728399557e+01 , 1.4936976000000000e+01 , -2.7345999999999998e-01 , 9.2573499999999997e-01 , -2.6121699999999998e-01 -3.9884924205391883e+01 , -2.7358915109902007e+01 , 1.5822744000000000e+01 , -1.6830400000000001e-01 , -9.8099999999999998e-01 , 9.6500699999999995e-02 -4.0132051199449933e+01 , -2.7455683480146799e+01 , 1.7703479999999999e+01 , -5.4179200000000005e-01 , 8.3740099999999995e-01 , -7.2258100000000006e-02 -4.0074020968869171e+01 , -2.7360482628455532e+01 , 1.8590496000000002e+01 , -5.4179200000000005e-01 , 8.3740099999999995e-01 , -7.2258100000000006e-02 -3.9845458540002802e+01 , -2.7077326706718573e+01 , 2.0331455999999999e+01 , 4.0693400000000002e-01 , -8.7119899999999995e-01 , 2.7462199999999998e-01 -3.3966603546019215e+01 , -2.2311189468580103e+01 , 2.0007808000000001e+01 , 1.1351899999999999e-01 , -9.8008300000000004e-01 , -1.6294400000000001e-01 -3.5020526346711407e+01 , -2.3044521140862930e+01 , 2.2274383999999998e+01 , 8.0265000000000006e-03 , 9.8944399999999999e-01 , 1.4469199999999999e-01 -3.5822631359392112e+01 , -2.3571569349201113e+01 , 2.4541271999999999e+01 , -3.0363500000000002e-02 , -9.9909400000000004e-01 , 2.9813400000000000e-02 -3.4835083150121186e+01 , -2.2754216246618274e+01 , 2.4798255999999999e+01 , -6.3809400000000002e-02 , 9.9682599999999999e-01 , -4.7615999999999999e-02 -3.9131529207080504e+01 , -2.6034617812957173e+01 , 2.8706680000000002e+01 , 2.5781700000000002e-01 , 8.7033799999999995e-01 , 4.1957499999999998e-01 -3.9777240308736175e+01 , -2.6476960218410923e+01 , 3.0222168000000003e+01 , 1.9542999999999999e-01 , 8.7489200000000000e-01 , 4.4313900000000001e-01 -6.7572081453921911e+00 , -8.4218960658542175e-01 , 7.7500976000000010e+00 , -4.8288599999999998e-01 , 1.1836199999999999e-01 , -8.6764699999999995e-01 -6.4797455652435003e+00 , -6.2466734870905771e-01 , 7.6005144000000007e+00 , 4.2793300000000001e-01 , 3.1172200000000000e-01 , -8.4835300000000002e-01 -6.2312115589731016e+00 , -4.2934845954125178e-01 , 7.4681224000000004e+00 , 4.9611300000000003e-01 , 6.1655000000000004e-01 , -6.1134100000000002e-01 -6.1612594142136370e+00 , -3.6924779337763125e-01 , 7.5354416000000004e+00 , 6.2813600000000003e-01 , -7.7481800000000001e-01 , 7.1431300000000003e-02 -6.1786083987925986e+00 , -3.7395491118781665e-01 , 7.7107855999999995e+00 , -5.0378999999999996e-01 , 8.2812600000000003e-01 , -2.4576999999999999e-01 -6.2053274123112567e+00 , -3.8415886231812824e-01 , 7.9030088000000003e+00 , 3.5140900000000003e-01 , -5.6814299999999995e-01 , 7.4412699999999998e-01 -6.1018759312721738e+00 , -2.9872776469144213e-01 , 7.9307872000000001e+00 , 7.5598799999999999e-01 , -2.9287500000000000e-01 , 5.8541200000000004e-01 -6.0599786670890623e+00 , -2.5898077255504992e-01 , 8.0400392000000007e+00 , 7.2290500000000002e-01 , -2.9440300000000003e-01 , 6.2508799999999998e-01 -5.9614237002700339e+00 , -1.7645153166031857e-01 , 8.0702824000000000e+00 , 3.6944800000000000e-01 , -6.4917199999999997e-01 , 6.6489399999999999e-01 -5.9061805333585227e+00 , -1.2703685097060013e-01 , 8.1614280000000008e+00 , 4.3562699999999999e-01 , -5.8223700000000000e-01 , 6.8646099999999999e-01 -5.7956792447962533e+00 , -3.6561790444961328e-02 , 8.1705488000000006e+00 , 1.2524800000000000e-01 , -3.7207699999999999e-01 , 9.1971300000000000e-01 -5.5936108950694861e+00 , 1.1992555404008320e-01 , 8.0293063999999994e+00 , 2.0705200000000001e-01 , 1.1288700000000000e-01 , 9.7179499999999996e-01 -5.5278686306240949e+00 , 1.7763247885151534e-01 , 8.0961263999999993e+00 , 3.3637099999999998e-01 , -1.6908599999999999e-02 , 9.4157800000000003e-01 -5.4861763251915079e+00 , 2.1699655722400868e-01 , 8.2035583999999986e+00 , 7.7023399999999997e-01 , -6.3270300000000002e-01 , 8.0166899999999999e-02 -5.3834222287328206e+00 , 3.0092423548570513e-01 , 8.2082072000000004e+00 , 7.3665700000000001e-01 , -1.5193400000000001e-01 , 6.5897799999999995e-01 -5.4961519932601153e+00 , 2.3112647412202958e-01 , 8.5973439999999997e+00 , 4.7514200000000001e-01 , -1.5176999999999999e-01 , 8.6672099999999996e-01 -5.3852998882518843e+00 , 3.2081944852629540e-01 , 8.5919463999999994e+00 , 1.2814100000000000e-01 , -2.6873799999999998e-01 , -9.5465199999999995e-01 -5.2490866904245621e+00 , 4.2794218642583970e-01 , 8.5306695999999995e+00 , -1.2395600000000000e-01 , 4.4107600000000002e-01 , 8.8886799999999999e-01 -5.1144690715939625e+00 , 5.3405131217805524e-01 , 8.4646608000000008e+00 , -3.7266400000000000e-01 , 3.2949099999999998e-01 , -8.6750000000000005e-01 -5.0294652590719551e+00 , 6.0406813654765412e-01 , 8.4936351999999999e+00 , -2.7518199999999998e-01 , 2.9908899999999999e-01 , -9.1368499999999997e-01 -4.7906658211311299e+00 , 7.8235508094579709e-01 , 8.1839648000000000e+00 , 3.9162500000000000e-01 , -2.1105699999999999e-01 , 8.9559200000000005e-01 -4.7025339403492143e+00 , 8.5366911185306105e-01 , 8.1870639999999995e+00 , -3.3203700000000003e-01 , 6.8108199999999997e-01 , -6.5259400000000001e-01 -4.6736058525520496e+00 , 8.8508338191619540e-01 , 8.3262888000000004e+00 , 5.6320799999999997e-02 , -7.5134000000000001e-01 , 6.5750799999999998e-01 -4.6182878895047121e+00 , 9.3502408840192142e-01 , 8.4095200000000006e+00 , -3.3706300000000000e-01 , -7.2547200000000006e-02 , 9.3868300000000005e-01 -4.4772893579384796e+00 , 1.0415163598969266e+00 , 8.2755472000000001e+00 , -6.0715699999999995e-01 , -1.3190399999999999e-01 , 7.8355699999999995e-01 -4.4113458637879415e+00 , 1.0981743986488812e+00 , 8.3266215999999993e+00 , -5.6751099999999999e-01 , 3.8046299999999998e-02 , 8.2248600000000005e-01 -4.1361889205663207e+00 , 1.2934341478876159e+00 , 7.7930080000000004e+00 , -5.5004800000000000e-02 , 3.4153499999999998e-01 , 9.3825800000000004e-01 -4.0043883321669771e+00 , 1.3916664797322209e+00 , 7.6252664000000001e+00 , 2.2488600000000000e-01 , -3.9135300000000001e-01 , 8.9233899999999999e-01 -3.9269223621490390e+00 , 1.4531324749402570e+00 , 7.6081480000000008e+00 , 3.5942400000000002e-01 , 3.6718600000000001e-01 , 8.5789800000000005e-01 -3.9062369749343775e+00 , 1.4792193230614750e+00 , 7.7648344000000007e+00 , -1.9824000000000000e-01 , 2.9362500000000002e-01 , -9.3513900000000005e-01 -3.7876444233050783e+00 , 1.5662131039516742e+00 , 7.6073888000000007e+00 , 6.5797600000000001e-01 , 2.4941400000000000e-01 , 7.1053500000000003e-01 -3.7571337015039279e+00 , 1.5989959128384557e+00 , 7.7425160000000002e+00 , -7.6873300000000000e-01 , 2.0704199999999999e-02 , -6.3923500000000000e-01 -3.6922696902949412e+00 , 1.6527890647450880e+00 , 7.7585008000000002e+00 , 8.0603999999999998e-01 , -1.6180200000000000e-01 , 5.6931600000000004e-01 -3.6469950418238404e+00 , 1.6949584814160434e+00 , 7.8527456000000004e+00 , -6.0530899999999999e-01 , 3.1577699999999997e-01 , -7.3067499999999996e-01 -3.4904637872669810e+00 , 1.8016999240628344e+00 , 7.4848040000000005e+00 , -5.3623299999999996e-01 , -7.4242300000000006e-01 , 4.0157500000000002e-01 -3.3842234939466946e+00 , 1.8780648095866739e+00 , 7.2930592000000001e+00 , -9.7394499999999995e-01 , -2.1251600000000001e-01 , 7.9173199999999999e-02 -3.3693849489176104e+00 , 1.9018488633602892e+00 , 7.5133416000000004e+00 , 7.5933399999999995e-01 , 6.0365999999999997e-01 , -2.4291199999999999e-01 -3.3806102720325018e+00 , 1.9137925085124150e+00 , 7.8965088000000003e+00 , -4.6362399999999998e-01 , -4.9722799999999999e-03 , 8.8601799999999997e-01 -3.3005295963143446e+00 , 1.9753842688175354e+00 , 7.8320183999999999e+00 , 3.9476400000000000e-01 , -2.8708499999999998e-01 , -8.7277899999999997e-01 -3.2413286240541739e+00 , 2.0254780313931300e+00 , 7.8782984000000003e+00 , -2.9680800000000002e-01 , 4.2396099999999998e-01 , 8.5566500000000001e-01 -3.1426183836923132e+00 , 2.0943251323251033e+00 , 7.6666479999999995e+00 , 2.7317399999999997e-01 , -1.8745899999999999e-01 , -9.4352300000000000e-01 -3.0767269517432454e+00 , 2.1475330944049995e+00 , 7.6478864000000000e+00 , -1.4834900000000001e-01 , -4.7929899999999998e-02 , 9.8777300000000001e-01 -3.0155810728575654e+00 , 2.1979766743399480e+00 , 7.6585880000000000e+00 , 2.1711700000000000e-01 , 3.6858999999999997e-01 , -9.0388199999999996e-01 -2.9535901469063601e+00 , 2.2492073027085864e+00 , 7.6677504000000010e+00 , 4.9912400000000001e-01 , 3.9718199999999998e-01 , -7.7014400000000005e-01 -2.8967614286267893e+00 , 2.2986281539696756e+00 , 7.7375344000000004e+00 , 1.7565400000000000e-01 , -9.6714400000000006e-02 , -9.7968999999999995e-01 -2.8307176649372821e+00 , 2.3507135232892358e+00 , 7.7026424000000002e+00 , -5.2783100000000005e-01 , 2.8997899999999999e-01 , -7.9831500000000000e-01 -2.7721386060124398e+00 , 2.4018119881252740e+00 , 7.7698472000000001e+00 , 2.7804800000000002e-01 , -3.4960000000000002e-01 , 8.9468899999999996e-01 -2.7913231320455365e+00 , 2.4694305136897183e+00 , 9.2584824000000001e+00 , 1.0758600000000000e-01 , 1.0968000000000000e-01 , 9.8812699999999998e-01 -2.7065282432173450e+00 , 2.5373854237820099e+00 , 9.2509112000000009e+00 , -3.1032300000000002e-01 , -4.6019700000000002e-01 , -8.3181600000000000e-01 -2.6223408217427937e+00 , 2.6039821048544893e+00 , 9.2209280000000007e+00 , 1.4311499999999999e-01 , 3.0345800000000001e-01 , 9.4203599999999998e-01 -2.5388388900345746e+00 , 2.6721545419297348e+00 , 9.2199920000000013e+00 , 5.7522300000000004e-01 , 4.6199699999999999e-01 , 6.7503800000000003e-01 -2.4551579363523981e+00 , 2.6937092826068434e+00 , 8.3868168000000001e+00 , 9.8654399999999998e-01 , -1.4868899999999999e-01 , -6.7995799999999995e-02 -2.3833755779420827e+00 , 2.7522695561529011e+00 , 8.3828336000000014e+00 , -8.1740100000000004e-01 , 1.9585400000000000e-01 , -5.4175300000000004e-01 -2.2897894765504607e+00 , 2.8734238884701511e+00 , 9.1960927999999988e+00 , 5.1298100000000002e-01 , 3.9966099999999999e-01 , 7.5968500000000005e-01 -2.2073708059745552e+00 , 2.9401000300192321e+00 , 9.1774144000000000e+00 , -4.3354399999999998e-01 , -4.3590000000000001e-01 , -7.8868899999999997e-01 -2.1237061823282692e+00 , 3.0074627242500585e+00 , 9.1776952000000005e+00 , 1.7022200000000001e-01 , 4.4933200000000001e-01 , 8.7699800000000006e-01 -1.8299620517329573e+00 , 3.4179945587667415e+00 , 1.2291049599999999e+01 , 6.9883300000000004e-01 , -2.0724699999999999e-01 , 6.8460299999999996e-01 -1.6894418894321881e+00 , 3.5420609805197634e+00 , 1.2465728000000000e+01 , 3.5532700000000000e-02 , -8.0656700000000003e-01 , 5.9007399999999999e-01 -1.5932634171644704e+00 , 3.6004320020106606e+00 , 1.2102528800000000e+01 , 5.9016299999999999e-01 , 4.8157999999999999e-02 , -8.0584699999999998e-01 -1.5074500857083772e+00 , 3.6497726529007641e+00 , 1.1738851200000001e+01 , -4.9305199999999999e-01 , -6.5200300000000000e-01 , 5.7601400000000003e-01 -4.1601358235772459e+00 , 8.4869937714961163e-01 , 1.4324085599999998e+00 , -7.5449299999999997e-02 , 3.5209900000000000e-01 , 9.3291700000000000e-01 -4.2017279643670111e+00 , 8.1333676199003468e-01 , 1.4555183999999999e+00 , -9.2782100000000006e-02 , 3.3758700000000003e-01 , 9.3671000000000004e-01 -4.2558967441300934e+00 , 7.6686652639154951e-01 , 1.4682968800000000e+00 , 1.7919299999999999e-02 , -2.3731500000000000e-01 , -9.7126800000000002e-01 -4.3177401186039290e+00 , 7.1509696366354314e-01 , 1.4775133600000001e+00 , -6.2530100000000005e-02 , 2.1311700000000000e-01 , 9.7502400000000000e-01 -4.3724336866787290e+00 , 6.6839353915476485e-01 , 1.4945683200000000e+00 , -7.7622999999999998e-02 , 2.1319299999999999e-01 , 9.7392199999999995e-01 -4.4336988399410568e+00 , 6.1544561278570287e-01 , 1.5083441600000000e+00 , -4.4788200000000000e-02 , 2.0442299999999999e-01 , 9.7785800000000000e-01 -4.4957379472625494e+00 , 5.6291986277114114e-01 , 1.5243695200000000e+00 , -4.9838300000000002e-02 , 2.0159700000000000e-01 , 9.7819999999999996e-01 -4.5653028967615708e+00 , 5.0425815617272440e-01 , 1.5379498400000000e+00 , -9.1106400000000004e-02 , 2.1031600000000000e-01 , 9.7337899999999999e-01 -4.6210070606256259e+00 , 4.5717595575296421e-01 , 1.5638624800000001e+00 , 8.5688100000000003e-02 , -1.8180700000000000e-01 , -9.7959399999999996e-01 -4.6967099943118091e+00 , 3.9194839849236085e-01 , 1.5777079999999999e+00 , -6.0660899999999997e-02 , 2.1134500000000001e-01 , 9.7552700000000003e-01 -4.7663497399466550e+00 , 3.3276066609793631e-01 , 1.5992100000000000e+00 , -7.4209100000000000e-02 , 2.0370400000000000e-01 , 9.7621599999999997e-01 -4.8511293242973270e+00 , 2.6112788287763089e-01 , 1.6149119199999999e+00 , -6.2708600000000003e-02 , 1.8073300000000000e-01 , 9.8153100000000004e-01 -4.9277957464072148e+00 , 1.9559689276220116e-01 , 1.6380196800000000e+00 , -1.0694900000000000e-01 , 2.3978700000000000e-01 , 9.6491700000000002e-01 -5.0061399740862260e+00 , 1.2958892332623750e-01 , 1.6644169600000001e+00 , 1.0470500000000001e-01 , -2.2148200000000001e-01 , -9.6952700000000003e-01 -5.0907750708077071e+00 , 5.7831347297601532e-02 , 1.6899624799999999e+00 , -5.5333100000000003e-02 , 2.0179000000000000e-01 , 9.7786499999999998e-01 -5.1902967081754863e+00 , -2.7006259436890279e-02 , 1.7117348800000001e+00 , -4.8798099999999997e-02 , 1.9811799999999999e-01 , 9.7896300000000003e-01 -5.2827148123021939e+00 , -1.0574964161587097e-01 , 1.7411387999999999e+00 , -4.7400600000000001e-02 , 1.9225900000000001e-01 , 9.8019900000000004e-01 -5.4051551634689456e+00 , -2.0999771994177019e-01 , 1.7610683199999999e+00 , -6.6785700000000003e-02 , 1.8759700000000001e-01 , 9.7997299999999998e-01 -5.5127899686083452e+00 , -3.0172237143504965e-01 , 1.7925938399999999e+00 , -3.9682000000000002e-02 , 1.8720300000000001e-01 , 9.8151999999999995e-01 -5.6360790699700871e+00 , -4.0607429920245552e-01 , 1.8226956000000001e+00 , -2.2264900000000001e-02 , 1.8698300000000001e-01 , 9.8211099999999996e-01 -5.7813621123773693e+00 , -5.3108531167769302e-01 , 1.8498208800000000e+00 , -5.6132500000000002e-02 , 2.0778400000000000e-01 , 9.7656299999999996e-01 -5.9129438502339786e+00 , -6.4153448588952022e-01 , 1.8883591200000001e+00 , -4.4966899999999997e-02 , 2.0023099999999999e-01 , 9.7871600000000003e-01 -6.0588461663788271e+00 , -7.6625018097962760e-01 , 1.9276806879999999e+00 , -5.0660900000000002e-02 , 1.9566100000000000e-01 , 9.7936199999999995e-01 -6.2284890919549527e+00 , -9.1113294375523557e-01 , 1.9668067359999999e+00 , -6.8963099999999999e-02 , 1.9541400000000000e-01 , 9.7829299999999997e-01 -6.3973041941103990e+00 , -1.0545493399517865e+00 , 2.0130151839999999e+00 , -6.8311499999999997e-02 , 2.0070199999999999e-01 , 9.7726800000000003e-01 -6.5832001661488242e+00 , -1.2117151643153843e+00 , 2.0631164559999999e+00 , -5.0478400000000000e-02 , 1.9162100000000001e-01 , 9.8016999999999999e-01 -6.7988116542579720e+00 , -1.3964322172572241e+00 , 2.1146048799999999e+00 , -5.8540099999999998e-02 , 2.0062099999999999e-01 , 9.7791899999999998e-01 -7.0143856641811393e+00 , -1.5792892391816951e+00 , 2.1753252800000000e+00 , -5.4806899999999999e-02 , 1.9716700000000001e-01 , 9.7883699999999996e-01 -7.2845503595271426e+00 , -1.8100696431715511e+00 , 2.2364533600000001e+00 , -6.0437200000000003e-02 , 1.9250900000000001e-01 , 9.7943199999999997e-01 -7.5553806017686753e+00 , -2.0395266434399941e+00 , 2.3095705600000001e+00 , -6.2012400000000002e-02 , 1.9364300000000001e-01 , 9.7911000000000004e-01 -7.8645480520398614e+00 , -2.3021091203548387e+00 , 2.3897774400000000e+00 , -5.4037599999999998e-02 , 1.9660800000000000e-01 , 9.7899199999999997e-01 -8.2127516031001271e+00 , -2.5983333158272206e+00 , 2.4800328000000000e+00 , 5.8077700000000003e-02 , -1.9768900000000000e-01 , -9.7854300000000005e-01 -8.6069668298496786e+00 , -2.9344997887602586e+00 , 2.5821462400000001e+00 , -5.5785599999999998e-02 , 2.0212500000000000e-01 , 9.7777000000000003e-01 -9.0478930227938150e+00 , -3.3089281149726224e+00 , 2.6992741599999999e+00 , -5.2980899999999997e-02 , 2.0453299999999999e-01 , 9.7742499999999999e-01 -9.5661495495132129e+00 , -3.7500686787175876e+00 , 2.8338428800000002e+00 , -6.4290000000000000e-02 , 2.0189399999999999e-01 , 9.7729500000000002e-01 -1.0123947944484000e+01 , -4.2232628235216128e+00 , 2.9916670400000003e+00 , -8.5245399999999999e-02 , 2.0055400000000001e-01 , 9.7596700000000003e-01 -1.0844520865340893e+01 , -4.8370336362650734e+00 , 3.1768744000000000e+00 , -9.3712299999999998e-02 , 2.2296500000000000e-01 , 9.7031199999999995e-01 -1.1224304742128599e+01 , -5.1547751023986876e+00 , 3.3831584000000001e+00 , -1.1006600000000000e-01 , 3.3516200000000002e-01 , 9.3571000000000004e-01 -1.2082468995757514e+01 , -5.8832524305327700e+00 , 3.6344640000000004e+00 , 5.2074700000000002e-02 , 2.6806900000000000e-01 , 9.6199100000000004e-01 -1.3873767711997063e+01 , -7.4122896578724262e+00 , 4.0006687999999997e+00 , -3.4364400000000003e-02 , 1.6808600000000001e-01 , 9.8517299999999997e-01 -1.6068933781198837e+01 , -9.2840153829637373e+00 , 4.4916736000000004e+00 , 4.2377199999999997e-02 , -1.9237899999999999e-01 , -9.8040499999999997e-01 -1.1536973887049021e+01 , -5.3318722855315990e+00 , 5.2903623999999994e+00 , -9.3532499999999996e-01 , -3.4391100000000002e-01 , 8.3024100000000003e-02 -1.1511227156767927e+01 , -5.2995053881777823e+00 , 5.4981856000000002e+00 , -9.3532499999999996e-01 , -3.4391100000000002e-01 , 8.3024200000000006e-02 -1.1483512944033693e+01 , -5.2650754456968309e+00 , 5.7053431999999997e+00 , -9.3532499999999996e-01 , -3.4391100000000002e-01 , 8.3024200000000006e-02 -3.8199229443992529e+01 , -2.7737125997358667e+01 , 1.7812159999999999e+01 , -5.4179200000000005e-01 , 8.3740099999999995e-01 , -7.2258199999999995e-02 -3.8252301771429259e+01 , -2.7737722034645941e+01 , 1.8727360000000001e+01 , -5.4179200000000005e-01 , 8.3740099999999995e-01 , -7.2258100000000006e-02 -3.8975713840121678e+01 , -2.8302157370908805e+01 , 1.9964544000000000e+01 , -3.7314000000000003e-01 , 9.2582399999999998e-01 , 6.0137599999999999e-02 -3.2686584132313214e+01 , -2.2899301147273651e+01 , 1.9398056000000000e+01 , -4.7953200000000001e-01 , 8.5403899999999999e-01 , 2.0165800000000000e-01 -3.2761723832395901e+01 , -2.2922907753795620e+01 , 2.0240768000000003e+01 , 3.4278999999999998e-01 , -9.2723000000000000e-01 , -1.5079500000000001e-01 -3.4439906288259607e+01 , -2.4108448247484162e+01 , 2.5618504000000001e+01 , -6.3809400000000002e-02 , 9.9682599999999999e-01 , -4.7616100000000001e-02 -3.3862003660602127e+01 , -2.3584446630339158e+01 , 2.6124776000000001e+01 , 1.5100500000000000e-01 , -9.5585299999999995e-01 , -2.5207800000000002e-01 -3.3086365505565624e+01 , -2.2897953996051239e+01 , 2.6462879999999998e+01 , -2.7956199999999998e-01 , 9.5209900000000003e-01 , 1.2390800000000000e-01 -3.8393870751803789e+01 , -2.7228428660218476e+01 , 3.1599232000000001e+01 , 2.2516500000000000e-01 , 8.7421700000000002e-01 , 4.3016900000000002e-01 -3.8105872385421755e+01 , -2.6936840758190154e+01 , 3.2468568000000005e+01 , 2.2516500000000000e-01 , 8.7421700000000002e-01 , 4.3016900000000002e-01 -6.1007783045144830e+00 , -5.3589498376486455e-01 , 7.3699880000000002e+00 , -6.5844100000000005e-01 , -1.8365300000000001e-01 , 7.2988100000000000e-01 -6.5873549427760674e+00 , -9.1963967356387011e-01 , 8.1094176000000004e+00 , -6.8555200000000005e-01 , 5.3207199999999999e-01 , -4.9690800000000002e-01 -6.0822556021937322e+00 , -5.0576712531828871e-01 , 7.6473352000000006e+00 , 8.1298199999999998e-01 , -5.7055800000000001e-01 , 1.1629000000000000e-01 -6.0920014845524371e+00 , -5.0599873414866980e-01 , 7.8168968000000003e+00 , -7.2101599999999999e-01 , 6.4200000000000002e-01 , -2.6071400000000000e-01 -6.3606562469507644e+00 , -7.1226486209346440e-01 , 8.3419616000000012e+00 , 6.3976800000000000e-01 , 5.2725900000000003e-01 , -5.5919099999999999e-01 -6.2820363690532997e+00 , -6.4144208021285909e-01 , 8.4132120000000015e+00 , -4.9639699999999998e-01 , -7.5804199999999999e-01 , 4.2303900000000000e-01 -6.2826766579004412e+00 , -6.3277001042807202e-01 , 8.5986751999999989e+00 , -4.9639699999999998e-01 , -7.5804199999999999e-01 , 4.2303900000000000e-01 -5.8560073625021039e+00 , -2.8574756899195020e-01 , 8.1535448000000006e+00 , -2.0401200000000000e-01 , -4.5050300000000001e-02 , -9.7793099999999999e-01 -5.8532062171751766e+00 , -2.7449415153868584e-01 , 8.3247080000000011e+00 , 6.1529599999999995e-01 , 1.9944000000000001e-01 , 7.6265000000000005e-01 -5.7082267733896970e+00 , -1.5249893853238516e-01 , 8.2773983999999992e+00 , -5.2153600000000000e-01 , -7.3812999999999995e-01 , -4.2797700000000000e-01 -5.5857187913597830e+00 , -4.8126619849323315e-02 , 8.2580752000000004e+00 , 5.2011300000000005e-01 , 5.2547600000000005e-01 , 6.7331900000000000e-01 -5.4896679121665031e+00 , 3.6183607615426050e-02 , 8.2765872000000016e+00 , 7.1160800000000002e-01 , -4.7954400000000003e-01 , 5.1347100000000001e-01 -5.5609422506591493e+00 , -9.2385870347175825e-03 , 8.5881399999999992e+00 , 6.6041700000000003e-01 , -6.9386499999999995e-01 , 2.8705599999999998e-01 -5.4609867250037514e+00 , 7.6954233451868470e-02 , 8.6046240000000012e+00 , 2.8175800000000001e-02 , -4.2643799999999998e-01 , 9.0407800000000005e-01 -5.4532497918044935e+00 , 9.3658923754601719e-02 , 8.7912935999999995e+00 , 5.8119299999999996e-01 , -7.5094099999999997e-01 , 3.1353300000000001e-01 -5.3033703865099993e+00 , 2.1909648241614743e-01 , 8.7073032000000001e+00 , -1.3252900000000001e-01 , 2.0855100000000001e-02 , -9.9095999999999995e-01 -5.3685448985037505e+00 , 1.7968546260320184e-01 , 9.0526039999999988e+00 , -3.0413699999999999e-01 , -4.5639700000000000e-01 , 8.3618300000000001e-01 -5.2356482922646359e+00 , 2.9143860534865551e-01 , 8.9992000000000019e+00 , 8.9803699999999997e-01 , -1.5047700000000000e-01 , -4.1338300000000000e-01 -4.9491713003849025e+00 , 5.1809525578190274e-01 , 8.5979160000000014e+00 , -4.2510199999999998e-01 , -2.4018200000000001e-01 , -8.7269799999999997e-01 -4.8971373178725255e+00 , 5.6795885139936364e-01 , 8.6972567999999999e+00 , -5.9335199999999999e-01 , 1.5879699999999999e-01 , -7.8912400000000005e-01 -4.6159393562308804e+00 , 7.8972193775871280e-01 , 8.2517415999999990e+00 , 6.0101700000000002e-01 , -2.0565100000000000e-01 , 7.7232500000000004e-01 -4.5597033437102148e+00 , 8.4209759282798680e-01 , 8.3258000000000010e+00 , 1.4398800000000000e-01 , -1.7747099999999999e-01 , 9.7353599999999996e-01 -4.3029415861447866e+00 , 1.0420943255830788e+00 , 7.8828535999999998e+00 , 3.5038100000000003e-02 , 6.1346599999999996e-01 , 7.8894299999999995e-01 -4.1420193349944867e+00 , 1.1692408754923860e+00 , 7.6573919999999998e+00 , -2.8610700000000000e-01 , 3.4056399999999998e-01 , 8.9563300000000001e-01 -4.0790763595705268e+00 , 1.2250215361437151e+00 , 7.6836728000000001e+00 , -2.8610700000000000e-01 , 3.4056399999999998e-01 , 8.9563300000000001e-01 -3.9923646992608228e+00 , 1.2976527778201081e+00 , 7.6409184000000003e+00 , 9.7903000000000004e-02 , -4.5745300000000003e-02 , 9.9414400000000003e-01 -3.9387858404745280e+00 , 1.3464476710053241e+00 , 7.6925127999999994e+00 , -2.7902300000000002e-01 , 5.4018999999999995e-01 , -7.9394100000000001e-01 -3.8694592419698992e+00 , 1.4060798351767818e+00 , 7.6943640000000002e+00 , 1.0727200000000001e-01 , -2.6043100000000002e-01 , 9.5951500000000001e-01 -3.7944416384144302e+00 , 1.4701251809960874e+00 , 7.6747496000000002e+00 , 7.1456699999999995e-01 , 1.2347400000000000e-01 , 6.8858500000000000e-01 -3.7432859654739290e+00 , 1.5178545677011988e+00 , 7.7320848000000000e+00 , 7.6008100000000001e-01 , 2.5852300000000000e-01 , 5.9619000000000000e-01 -3.6764819406919678e+00 , 1.5751457052337414e+00 , 7.7386784000000004e+00 , 7.2528599999999999e-01 , -6.1990499999999997e-02 , 6.8565100000000001e-01 -3.6128092922399131e+00 , 1.6308092272591992e+00 , 7.7536752000000000e+00 , -6.6119499999999998e-01 , 2.5259300000000001e-01 , -7.0641200000000004e-01 -3.7019411063138081e+00 , 1.5867042214129623e+00 , 8.4181103999999998e+00 , -9.2954199999999998e-01 , -2.9486899999999999e-01 , -2.2136600000000001e-01 -3.5119011735059571e+00 , 1.7251039758699478e+00 , 7.8997536000000004e+00 , 3.1435600000000002e-01 , -7.4358300000000002e-02 , 9.4638800000000001e-01 -3.4504464107387767e+00 , 1.7796678030791819e+00 , 7.9308392000000003e+00 , 2.8763000000000000e-01 , 3.3415699999999998e-01 , 8.9755700000000005e-01 -3.5348568668466318e+00 , 1.7452957798568949e+00 , 8.7216344000000010e+00 , -7.0551200000000003e-01 , 3.4738000000000002e-01 , 6.1772199999999999e-01 -3.2941159603288908e+00 , 1.9087659856872139e+00 , 7.8056751999999996e+00 , 4.6727800000000003e-01 , -1.4318200000000000e-01 , -8.7243899999999996e-01 -3.2332357151696893e+00 , 1.9623278187528910e+00 , 7.8319144000000005e+00 , -4.9095100000000003e-01 , 2.8048499999999998e-01 , 8.2479999999999998e-01 -3.1495571836127070e+00 , 2.0291571175112768e+00 , 7.7030479999999999e+00 , -1.6474100000000000e-01 , -1.6225800000000001e-01 , 9.7289899999999996e-01 -3.0809240539380029e+00 , 2.0858917754562833e+00 , 7.6643184000000000e+00 , -9.1441300000000003e-02 , 1.1418100000000000e-01 , 9.8924299999999998e-01 -3.0199345114118623e+00 , 2.1386526731033926e+00 , 7.6654727999999999e+00 , 1.2927700000000000e-02 , 1.0780900000000000e-01 , 9.9408799999999997e-01 -2.9581243494890908e+00 , 2.1921586361472252e+00 , 7.6648904000000000e+00 , -4.7052600000000000e-02 , -6.4760899999999999e-01 , 7.6051899999999995e-01 -2.9041756126649378e+00 , 2.2425949759587369e+00 , 7.7456047999999997e+00 , -2.6821699999999998e-01 , -4.4874399999999998e-01 , 8.5246000000000000e-01 -2.8391437901792118e+00 , 2.2968861726482306e+00 , 7.7113264000000008e+00 , 1.6544400000000001e-01 , -4.6002500000000002e-01 , 8.7235600000000002e-01 -2.7850853831428291e+00 , 2.3489052635986960e+00 , 7.8104176000000001e+00 , 2.6127099999999998e-01 , -5.1238600000000001e-01 , 8.1804500000000002e-01 -2.7226586844584646e+00 , 2.4023955577622873e+00 , 7.8148792000000009e+00 , -1.8464300000000000e-01 , 5.2078700000000000e-01 , -8.3348000000000000e-01 -2.7251532942594645e+00 , 2.4728152659945368e+00 , 9.3033272000000000e+00 , 3.5241400000000001e-01 , 3.1585500000000002e-02 , 9.3531100000000000e-01 -2.6438609371487436e+00 , 2.5445670667435785e+00 , 9.3364408000000001e+00 , 6.8283099999999997e-01 , 4.3679000000000001e-01 , 5.8562499999999995e-01 -2.5594699982586424e+00 , 2.6122462531837889e+00 , 9.2221760000000010e+00 , -6.1628099999999998e-02 , 2.6006600000000002e-01 , 9.6362199999999998e-01 -2.4782456752719724e+00 , 2.6872430541866925e+00 , 9.3241168000000005e+00 , 7.3580699999999999e-01 , 4.4953799999999999e-01 , 5.0646199999999997e-01 -2.4041396926875076e+00 , 2.7052738027415080e+00 , 8.3859016000000004e+00 , -8.3653800000000000e-01 , 4.4633000000000000e-01 , -3.1779499999999999e-01 -2.3317220239694350e+00 , 2.7718888998115951e+00 , 8.4744576000000009e+00 , -8.6148100000000005e-01 , 5.0285800000000003e-01 , 7.0602100000000001e-02 -2.2333436754719544e+00 , 2.8942057730217137e+00 , 9.2239544000000002e+00 , 6.7349800000000004e-01 , 4.9508200000000002e-01 , 5.4890300000000003e-01 -2.1533520479286938e+00 , 2.9617028577937328e+00 , 9.1940647999999996e+00 , 3.0559700000000001e-01 , 6.6754100000000005e-01 , 6.7896999999999996e-01 -1.8845200378937814e+00 , 3.3426868163453292e+00 , 1.2218748800000000e+01 , -4.1146500000000003e-01 , 9.0031600000000001e-01 , -1.4187100000000000e-01 -1.7521127694926415e+00 , 3.4626888032036085e+00 , 1.2343403199999999e+01 , 7.5783900000000004e-01 , -3.0308800000000002e-01 , 5.7776899999999998e-01 -1.6314348229749589e+00 , 3.5653416182248208e+00 , 1.2300170400000001e+01 , -3.1187399999999998e-01 , -8.7633300000000003e-01 , -3.6711800000000000e-01 -1.4571315965536502e+00 , 3.7379414175405570e+00 , 1.2777104000000001e+01 , -9.5387000000000000e-01 , -1.6777600000000001e-01 , -2.4896599999999999e-01 -1.4434452582782704e+00 , 3.7005522681759100e+00 , 1.1755886400000001e+01 , -4.9305300000000002e-01 , -6.5200199999999997e-01 , 5.7601400000000003e-01 -4.1055298303903651e+00 , 8.2105499386341174e-01 , 1.4205650400000001e+00 , -1.0420300000000000e-01 , 3.4967399999999998e-01 , 9.3105800000000005e-01 -4.1403012202451563e+00 , 7.9128151529932489e-01 , 1.4488790400000000e+00 , -9.7534599999999999e-02 , 3.3793400000000001e-01 , 9.3610199999999999e-01 -4.1866138704131988e+00 , 7.4933100120840423e-01 , 1.4666370399999999e+00 , -1.0499699999999999e-01 , 2.3869000000000001e-01 , 9.6540300000000001e-01 -4.2464499861079847e+00 , 6.9531875333220339e-01 , 1.4747989600000000e+00 , -4.0437500000000001e-02 , 1.5840099999999999e-01 , 9.8654600000000003e-01 -4.2991601170158402e+00 , 6.4740679038184279e-01 , 1.4906943200000000e+00 , -6.6439600000000001e-02 , 1.8646799999999999e-01 , 9.8021199999999997e-01 -4.3526469642386987e+00 , 5.9885641132422252e-01 , 1.5088433600000000e+00 , -6.9138500000000006e-02 , 2.0519999999999999e-01 , 9.7627500000000000e-01 -4.4127333505832675e+00 , 5.4507529172811164e-01 , 1.5235083999999999e+00 , 5.3659499999999999e-02 , -2.0630899999999999e-01 , -9.7701400000000005e-01 -4.4803217574932592e+00 , 4.8412406884153336e-01 , 1.5358313600000000e+00 , -5.0226100000000003e-02 , 1.9406899999999999e-01 , 9.7970100000000004e-01 -4.5340711342193503e+00 , 4.3579669153263345e-01 , 1.5603815999999999e+00 , -8.8069200000000000e-02 , 2.0190800000000000e-01 , 9.7543700000000000e-01 -4.6077792060927267e+00 , 3.6826529296937882e-01 , 1.5729697599999999e+00 , -7.6571100000000003e-02 , 2.0223400000000000e-01 , 9.7633899999999996e-01 -4.6764806881672367e+00 , 3.0674383728986943e-01 , 1.5932404000000000e+00 , 9.0666600000000000e-02 , -2.2414300000000001e-01 , -9.7033000000000003e-01 -4.7438345250390173e+00 , 2.4579812232245279e-01 , 1.6160153600000000e+00 , -5.1630700000000002e-02 , 1.8466600000000000e-01 , 9.8144399999999998e-01 -4.8329682508848997e+00 , 1.6493518491926995e-01 , 1.6290049600000001e+00 , -6.0096299999999998e-02 , 2.2650699999999999e-01 , 9.7215399999999996e-01 -4.9016801963465664e+00 , 1.0409498780853577e-01 , 1.6579013599999999e+00 , -9.9578600000000003e-02 , 2.5087300000000001e-01 , 9.6288499999999999e-01 -4.9766539630758562e+00 , 3.5345156460219629e-02 , 1.6857515199999999e+00 , -7.5563000000000005e-02 , 2.1041799999999999e-01 , 9.7468699999999997e-01 -5.0742728872008893e+00 , -5.1936784996825747e-02 , 1.7055572800000001e+00 , -6.6970000000000002e-02 , 1.8428500000000000e-01 , 9.8058900000000004e-01 -5.1637541313782389e+00 , -1.3310068028625555e-01 , 1.7328707999999999e+00 , -6.1128500000000002e-02 , 1.9684800000000000e-01 , 9.7852700000000004e-01 -5.2680215029876631e+00 , -2.2716334209200184e-01 , 1.7573201599999999e+00 , -5.5718600000000000e-02 , 1.7257100000000000e-01 , 9.8341999999999996e-01 -5.3803525981473701e+00 , -3.2870670531570489e-01 , 1.7831984800000000e+00 , -8.3849000000000007e-02 , 2.0111899999999999e-01 , 9.7597199999999995e-01 -5.4855351188614954e+00 , -4.2409069362015028e-01 , 1.8171149600000001e+00 , -3.5534999999999997e-02 , 2.0916699999999999e-01 , 9.7723400000000005e-01 -5.6204353488585035e+00 , -5.4551862951051433e-01 , 1.8439875200000000e+00 , -3.9095800000000000e-02 , 1.9668500000000000e-01 , 9.7968699999999997e-01 -5.7405845706302845e+00 , -6.5343582300161396e-01 , 1.8821492799999999e+00 , -5.4306800000000002e-02 , 1.9557200000000000e-01 , 9.7918499999999997e-01 -5.8901457319743349e+00 , -7.8902945221766085e-01 , 1.9156004639999999e+00 , -4.1783099999999997e-02 , 2.0415100000000000e-01 , 9.7804700000000000e-01 -6.0474203418122023e+00 , -9.3152748415756736e-01 , 1.9534157999999999e+00 , -4.5123999999999997e-02 , 1.9263800000000000e-01 , 9.8023199999999999e-01 -6.2123611546655422e+00 , -1.0808015461420912e+00 , 1.9961007488000000e+00 , -7.7638600000000002e-02 , 1.9829500000000000e-01 , 9.7706300000000001e-01 -6.3774435603102821e+00 , -1.2296224448873470e+00 , 2.0463002800000001e+00 , -7.0730100000000004e-02 , 2.0015200000000000e-01 , 9.7720899999999999e-01 -6.5723869364444782e+00 , -1.4062409867641303e+00 , 2.0966730960000000e+00 , -5.6769800000000002e-02 , 1.9529400000000000e-01 , 9.7909999999999997e-01 -6.7757274946098454e+00 , -1.5891584246596935e+00 , 2.1544691199999999e+00 , -6.7097500000000004e-02 , 2.0971400000000001e-01 , 9.7545800000000005e-01 -7.0011851292755800e+00 , -1.7922430794152229e+00 , 2.2170063999999998e+00 , -5.4914400000000002e-02 , 1.9386200000000001e-01 , 9.7949100000000000e-01 -7.2642684226122176e+00 , -2.0301255084671137e+00 , 2.2835747199999998e+00 , 6.4592300000000005e-02 , -1.9562800000000000e-01 , -9.7854900000000000e-01 -7.5426451411456226e+00 , -2.2814723956986338e+00 , 2.3602872000000001e+00 , -6.1726700000000002e-02 , 1.9764699999999999e-01 , 9.7832799999999998e-01 -7.8591980563220014e+00 , -2.5667732624995176e+00 , 2.4453051200000000e+00 , -5.8205699999999999e-02 , 1.9616500000000001e-01 , 9.7884199999999999e-01 -8.2208849817997827e+00 , -2.8933403629336389e+00 , 2.5406408799999998e+00 , -6.4309500000000006e-02 , 2.0152000000000000e-01 , 9.7737099999999999e-01 -8.6044340283549019e+00 , -3.2400733046306440e+00 , 2.6512698400000003e+00 , -5.9126699999999997e-02 , 2.0701000000000000e-01 , 9.7655000000000003e-01 -9.0718804638048649e+00 , -3.6619392664281838e+00 , 2.7757630400000002e+00 , -5.6802999999999999e-02 , 2.0053699999999999e-01 , 9.7803799999999996e-01 -9.6069778434471971e+00 , -4.1452743503769414e+00 , 2.9206028000000002e+00 , -6.9800500000000001e-02 , 2.0041800000000001e-01 , 9.7722100000000001e-01 -1.0218401999297079e+01 , -4.6968621550708978e+00 , 3.0907831999999997e+00 , -8.1944299999999998e-02 , 1.9625999999999999e-01 , 9.7712200000000005e-01 -1.0889120533372497e+01 , -5.3012031366683079e+00 , 3.2910456000000003e+00 , -1.7735000000000001e-01 , 2.8858800000000001e-01 , 9.4088499999999997e-01 -1.1273314304976605e+01 , -5.6433167114810745e+00 , 3.5090816000000000e+00 , -3.0303200000000002e-01 , 3.2200800000000002e-01 , 8.9693000000000001e-01 -1.1462252986355020e+01 , -5.8073787071093923e+00 , 3.7311528000000003e+00 , -1.9922999999999999e-01 , 2.5202200000000002e-01 , 9.4699100000000003e-01 -1.1464759786459071e+01 , -5.7995910481159365e+00 , 3.9442800000000000e+00 , -1.9922999999999999e-01 , 2.5202200000000002e-01 , 9.4699100000000003e-01 -3.3502508023521798e+01 , -2.5701523984627425e+01 , 9.7535120000000006e+00 , -5.3898800000000002e-01 , 2.4757299999999999e-01 , 8.0510800000000005e-01 -1.1176943976742988e+01 , -5.4762907409170181e+00 , 5.3768488000000003e+00 , -9.3532499999999996e-01 , -3.4391100000000002e-01 , 8.3024100000000003e-02 -1.1188418351907281e+01 , -5.4768829390165559e+00 , 5.5924408000000003e+00 , -9.3532499999999996e-01 , -3.4391100000000002e-01 , 8.3024100000000003e-02 -1.1949816536590300e+01 , -6.1534328256997224e+00 , 6.0439672000000000e+00 , -9.3532499999999996e-01 , -3.4391100000000002e-01 , 8.3024200000000006e-02 -1.1922027803945824e+01 , -6.1185829166689381e+00 , 6.2689919999999999e+00 , -9.3532499999999996e-01 , -3.4391100000000002e-01 , 8.3024200000000006e-02 -1.1892238806497154e+01 , -6.0816129386786404e+00 , 6.4935592000000000e+00 , -9.3532499999999996e-01 , -3.4391100000000002e-01 , 8.3024100000000003e-02 -1.1858417331296614e+01 , -6.0414492283293804e+00 , 6.7173151999999998e+00 , -9.3532499999999996e-01 , -3.4391100000000002e-01 , 8.3024100000000003e-02 -3.3378997338041373e+01 , -2.5328840921019545e+01 , 1.5819312000000002e+01 , 1.9409100000000001e-01 , -6.8400099999999997e-01 , 7.0318599999999998e-01 -3.1441562722792284e+01 , -2.3463233825676422e+01 , 1.8030872000000002e+01 , 2.4008800000000000e-01 , -8.6860000000000004e-01 , 4.3346600000000002e-01 -3.1855441338207537e+01 , -2.3799977287709389e+01 , 1.9030311999999999e+01 , 7.8999500000000000e-01 , -5.3377100000000000e-01 , -3.0165700000000001e-01 -3.3095812904068467e+01 , -2.4833809308902261e+01 , 2.1373120000000000e+01 , -2.9784100000000002e-01 , 9.3357800000000002e-01 , 1.9930600000000001e-01 -3.2462911059038973e+01 , -2.4125386197976113e+01 , 2.4416784000000000e+01 , 3.4633999999999998e-01 , -9.3773799999999996e-01 , 2.6362699999999999e-02 -3.2566252806462373e+01 , -2.4138925241645399e+01 , 2.6295336000000002e+01 , -4.0837699999999999e-01 , 8.2833000000000001e-01 , 3.8353300000000001e-01 -3.4092352336658301e+01 , -2.5399226179904112e+01 , 2.9441231999999999e+01 , 1.2904400000000000e-02 , 8.1517799999999996e-01 , 5.7906700000000000e-01 -6.4679105104226879e+00 , -1.0627543849662238e+00 , 7.8637487999999998e+00 , -2.4014600000000000e-01 , 9.5752499999999996e-01 , 1.5961100000000000e-01 -6.4820565146164721e+00 , -1.0687262474352912e+00 , 8.0479432000000006e+00 , 1.1776600000000000e-01 , 9.6701599999999999e-01 , 2.2585900000000000e-01 -6.4876131727406676e+00 , -1.0658807901836687e+00 , 8.2266463999999999e+00 , -9.3786800000000003e-01 , 4.4149800000000003e-02 , -3.4417199999999998e-01 -6.3785594452944245e+00 , -9.6422487088173936e-01 , 8.2599264000000012e+00 , -9.3786800000000003e-01 , 4.4149599999999997e-02 , -3.4417100000000000e-01 -6.1483496569867073e+00 , -7.5963104027065809e-01 , 8.1247888000000010e+00 , -5.8003300000000002e-01 , -7.0301899999999995e-01 , 4.1149300000000000e-01 -5.9391813260774740e+00 , -5.7335321812833806e-01 , 8.0033896000000002e+00 , -9.1510899999999995e-01 , 2.5547199999999998e-01 , -3.1194600000000000e-01 -5.9561230394217750e+00 , -5.8144307786504124e-01 , 8.1987328000000002e+00 , 9.7709500000000005e-01 , 4.0412799999999999e-02 , 2.0893200000000001e-01 -5.9330342981888045e+00 , -5.5391742211850303e-01 , 8.3409528000000002e+00 , -9.8025099999999998e-01 , -1.4911900000000000e-01 , 1.2989300000000001e-01 -5.8555032318511948e+00 , -4.8061367259862386e-01 , 8.4036855999999993e+00 , 8.3199800000000002e-01 , -1.2939300000000001e-01 , -5.3947800000000001e-01 -5.5587638834064821e+00 , -2.2144373663017980e-01 , 8.1088559999999994e+00 , 5.4200199999999997e-02 , -5.6061799999999995e-01 , 8.2629900000000001e-01 -5.4853695696622964e+00 , -1.5221456145135814e-01 , 8.1627696000000007e+00 , 3.4316600000000000e-03 , -4.8535200000000001e-01 , 8.7431199999999998e-01 -5.5640711768312343e+00 , -2.1056284682724646e-01 , 8.4802087999999998e+00 , 7.0520400000000005e-01 , 6.4214099999999996e-01 , -3.0057099999999998e-01 -5.3642515669340298e+00 , -3.5696796196802882e-02 , 8.3147136000000010e+00 , -1.4027700000000001e-01 , 5.9821299999999999e-01 , -7.8896400000000000e-01 -5.3349876561460068e+00 , -2.2070729786176635e-03 , 8.4483327999999993e+00 , -9.1078999999999997e-04 , -9.5222499999999999e-01 , 3.0539600000000000e-01 -5.3160228506710059e+00 , 2.2249505104494638e-02 , 8.6078168000000002e+00 , -2.6538299999999998e-01 , -7.2221700000000000e-01 , 6.3872899999999999e-01 -5.2537699232569661e+00 , 8.1693071376229831e-02 , 8.6893215999999995e+00 , 7.8439900000000003e-03 , -4.8968899999999999e-01 , 8.7186200000000003e-01 -5.1362658571053457e+00 , 1.8813027489941470e-01 , 8.6549808000000006e+00 , 3.1355100000000002e-01 , 3.5901899999999998e-01 , -8.7908500000000001e-01 -5.0693841656063876e+00 , 2.5260983224403533e-01 , 8.7235791999999996e+00 , 1.6083600000000001e-01 , 3.8429400000000002e-01 , 9.0909300000000004e-01 -4.9291908731748943e+00 , 3.7648783722416779e-01 , 8.6286583999999991e+00 , -1.4954000000000001e-01 , -1.4095500000000000e-01 , 9.7865700000000000e-01 -4.8343310142219842e+00 , 4.6240838303850729e-01 , 8.6290224000000002e+00 , 5.9555199999999997e-01 , -1.6409499999999999e-01 , 7.8637800000000002e-01 -4.6506237032649409e+00 , 6.2186427614143369e-01 , 8.4062751999999996e+00 , 1.1482100000000001e-01 , 8.0527700000000002e-01 , 5.8167400000000002e-01 -4.5011223667249585e+00 , 7.5093333366940640e-01 , 8.2508160000000004e+00 , -4.1777599999999998e-01 , -1.5814200000000000e-01 , -8.9468099999999995e-01 -4.4812977896858062e+00 , 7.7580987277151392e-01 , 8.4174863999999996e+00 , -4.1777599999999998e-01 , -1.5814200000000000e-01 , -8.9468099999999995e-01 -4.1661565929858746e+00 , 1.0374997570552891e+00 , 7.7834400000000006e+00 , 1.5154000000000001e-01 , -6.8907099999999999e-01 , -7.0867300000000000e-01 -4.0260094743154093e+00 , 1.1569621164174182e+00 , 7.5928079999999998e+00 , -1.5085200000000001e-01 , 6.9936799999999999e-01 , 6.9866200000000001e-01 -3.9145351509542916e+00 , 1.2537554087526879e+00 , 7.4644199999999996e+00 , -2.7933700000000000e-01 , -3.1354900000000002e-01 , 9.0755600000000003e-01 -3.8771174507994757e+00 , 1.2925003791545899e+00 , 7.5538808000000008e+00 , -1.2648100000000001e-01 , -6.7667800000000000e-01 , 7.2533400000000003e-01 -3.8495595260418769e+00 , 1.3236989591507138e+00 , 7.6817696000000000e+00 , 1.5506000000000000e-01 , -5.6193700000000002e-01 , 8.1251700000000004e-01 -3.7765485691603158e+00 , 1.3888906956104616e+00 , 7.6630184000000003e+00 , -1.1085399999999999e-01 , 5.7845800000000003e-01 , -8.0814500000000000e-01 -3.7744070495775492e+00 , 1.4012349852854094e+00 , 7.8977463999999999e+00 , -5.6302099999999999e-01 , 2.3200000000000001e-01 , -7.9321100000000000e-01 -3.6947833986469316e+00 , 1.4717747058689161e+00 , 7.8566872000000005e+00 , -6.4425100000000002e-01 , -3.3261600000000002e-01 , -6.8869999999999998e-01 -3.6183654428711942e+00 , 1.5394826120108362e+00 , 7.8233240000000004e+00 , -7.1193899999999999e-01 , 1.3666400000000000e-02 , -7.0210899999999998e-01 -3.5809308576374868e+00 , 1.5799336761521652e+00 , 7.9476040000000001e+00 , -8.8991900000000002e-01 , -8.9945899999999995e-02 , -4.4716299999999998e-01 -3.8655333804981691e+00 , 1.3888552622211705e+00 , 9.5580543999999996e+00 , -2.3217099999999999e-01 , 9.4344799999999995e-01 , 2.3664700000000000e-01 -3.6435807925618819e+00 , 1.5632893994029802e+00 , 8.9113304000000007e+00 , -8.1679000000000002e-01 , 9.8292000000000004e-02 , 5.6850000000000001e-01 -3.5071388430532173e+00 , 1.6754667266218144e+00 , 8.6115607999999995e+00 , 6.5466899999999995e-01 , 5.9569799999999995e-01 , 4.6535199999999999e-01 -3.4290606263785222e+00 , 1.7460777794913027e+00 , 8.5922687999999994e+00 , -6.5466800000000003e-01 , -5.9569799999999995e-01 , -4.6535300000000002e-01 -3.3280632429296846e+00 , 1.8319660235364974e+00 , 8.4278240000000011e+00 , -8.9157799999999998e-01 , -2.0127400000000001e-01 , 4.0568199999999999e-01 -3.1515284917430906e+00 , 1.9630532394710232e+00 , 7.7284864000000004e+00 , 4.2874400000000001e-01 , -5.8334200000000003e-01 , -6.8984800000000002e-01 -3.0830510522409926e+00 , 2.0232077169856204e+00 , 7.6804072000000003e+00 , 1.2664700000000001e-01 , 1.9769700000000001e-01 , 9.7204800000000002e-01 -3.0355977088063679e+00 , 2.0717905348190100e+00 , 7.7849376000000001e+00 , 4.1018100000000002e-01 , 2.5473699999999999e-01 , 8.7570599999999998e-01 -2.9579174152242098e+00 , 2.1363658743816258e+00 , 7.6408975999999997e+00 , 1.4590400000000000e-02 , 2.6895100000000000e-01 , 9.6304299999999998e-01 -2.8939669250166067e+00 , 2.1931435261907595e+00 , 7.5981119999999995e+00 , 9.6610099999999994e-03 , -2.3801600000000001e-01 , 9.7121299999999999e-01 -2.8446537473437337e+00 , 2.2421066814266539e+00 , 7.7093920000000002e+00 , -4.0283900000000000e-01 , -6.6007499999999997e-02 , 9.1288800000000003e-01 -2.9263957821862965e+00 , 2.2514697956961061e+00 , 9.6653511999999999e+00 , -5.0132299999999996e-01 , 4.8355799999999999e-01 , 7.1752899999999997e-01 -2.8272229090648646e+00 , 2.3321841078178238e+00 , 9.4334519999999991e+00 , -1.6876900000000000e-01 , -8.0914799999999998e-01 , -5.6284699999999999e-01 -2.7368035212356476e+00 , 2.4076791021395825e+00 , 9.2407608000000003e+00 , 2.2793099999999999e-01 , -9.0217500000000006e-02 , 9.6948900000000005e-01 -2.6591871843291957e+00 , 2.4804402960220484e+00 , 9.2954752000000003e+00 , -3.3624900000000002e-01 , -1.7485600000000001e-01 , -9.2539800000000005e-01 -2.5820405609042636e+00 , 2.5578257039788488e+00 , 9.4417615999999995e+00 , -7.8099099999999999e-01 , -5.6821100000000002e-01 , -2.5920900000000002e-01 -2.4976188030770796e+00 , 2.6244947929420226e+00 , 9.2328879999999991e+00 , -7.7980799999999995e-01 , 5.0008799999999998e-01 , -3.7657800000000002e-01 -2.4226667898237046e+00 , 2.6652356717639076e+00 , 8.5547767999999991e+00 , 5.2097599999999999e-01 , -5.0373100000000004e-01 , -6.8908599999999998e-01 -2.3543076386337769e+00 , 2.7198335270414971e+00 , 8.3842791999999999e+00 , 7.2020300000000004e-01 , -6.8951600000000002e-02 , 6.9032899999999997e-01 -2.2584596086048316e+00 , 2.8451368674396811e+00 , 9.2598240000000001e+00 , 7.1118300000000001e-01 , 2.2424500000000000e-01 , 6.6628299999999996e-01 -2.1772709395933121e+00 , 2.9210885049532274e+00 , 9.2927192000000005e+00 , 5.6718599999999997e-01 , 5.7811400000000002e-01 , 5.8658699999999997e-01 -2.1034223986515279e+00 , 2.9831148214967462e+00 , 9.1684704000000004e+00 , 1.2101600000000001e-02 , 6.0612999999999995e-01 , 7.9527300000000001e-01 -1.8082232143291406e+00 , 3.3843637412034289e+00 , 1.2240692800000000e+01 , -4.3222300000000002e-01 , -8.8755899999999999e-01 , -1.5944400000000000e-01 -1.6700733776341790e+00 , 3.5207849470860588e+00 , 1.2466664000000000e+01 , 7.2297700000000006e-02 , -7.5949599999999995e-01 , 6.4648200000000000e-01 -1.5813798676692854e+00 , 3.5862336841205344e+00 , 1.2103308800000001e+01 , 5.9016199999999996e-01 , 4.8157899999999997e-02 , -8.0584699999999998e-01 -1.5071240964431696e+00 , 3.6363254398571421e+00 , 1.1687828800000000e+01 , -4.9305199999999999e-01 , -6.5200300000000000e-01 , 5.7601400000000003e-01 -4.0767406180079551e+00 , 7.6938795949757632e-01 , 1.4425943200000000e+00 , -1.2176200000000000e-01 , 2.9637100000000000e-01 , 9.4727899999999998e-01 -4.1220936469104625e+00 , 7.2625604881501715e-01 , 1.4595213600000001e+00 , -1.0656700000000000e-01 , 2.6454899999999998e-01 , 9.5846600000000004e-01 -4.1740777653322905e+00 , 6.7674313706156197e-01 , 1.4725629599999999e+00 , 8.1916500000000003e-02 , -1.6796100000000000e-01 , -9.8238400000000003e-01 -4.2258344734577324e+00 , 6.2761919944233413e-01 , 1.4875264800000001e+00 , -5.7532199999999999e-02 , 1.6953599999999999e-01 , 9.8384300000000002e-01 -4.2841430774806772e+00 , 5.7119622787139179e-01 , 1.4992140000000000e+00 , 9.7217999999999999e-02 , -1.8124499999999999e-01 , -9.7862099999999996e-01 -4.3354190772402070e+00 , 5.2182628450641699e-01 , 1.5181253600000000e+00 , -9.9569599999999994e-02 , 2.0762900000000001e-01 , 9.7312699999999996e-01 -4.3884772899923696e+00 , 4.7183074186963636e-01 , 1.5395181600000001e+00 , -8.1654400000000002e-02 , 1.7305000000000001e-01 , 9.8152200000000001e-01 -4.4595242515317768e+00 , 4.0250774970557823e-01 , 1.5478880799999999e+00 , -7.1998999999999994e-02 , 1.7737000000000000e-01 , 9.8150700000000002e-01 -4.5255318409212553e+00 , 3.3925172425764250e-01 , 1.5642420800000001e+00 , -8.7599399999999994e-02 , 1.9395299999999999e-01 , 9.7709199999999996e-01 -4.5845068260473187e+00 , 2.8304872701567430e-01 , 1.5877211199999999e+00 , -7.2835800000000006e-02 , 1.9711300000000001e-01 , 9.7767199999999999e-01 -4.6509142728273947e+00 , 2.1975702990972312e-01 , 1.6092626399999999e+00 , -9.2094099999999998e-02 , 2.0547399999999999e-01 , 9.7431999999999996e-01 -4.7236707229154877e+00 , 1.4953901992354668e-01 , 1.6293502399999999e+00 , -8.6554199999999998e-02 , 1.8441099999999999e-01 , 9.7903099999999998e-01 -4.7961014156540127e+00 , 7.9881055568728154e-02 , 1.6521688800000001e+00 , -7.4297299999999997e-02 , 2.3246500000000000e-01 , 9.6976300000000004e-01 -4.8701914566250935e+00 , 9.7848165019724931e-03 , 1.6784798400000001e+00 , 9.6815200000000004e-02 , -2.1150300000000000e-01 , -9.7257000000000005e-01 -4.9571939595603469e+00 , -7.3494496158743150e-02 , 1.7000567200000001e+00 , -8.4066900000000000e-02 , 1.6906800000000000e-01 , 9.8201300000000002e-01 -5.0513305848755738e+00 , -1.6443233819966974e-01 , 1.7220267199999999e+00 , -8.7122900000000003e-02 , 1.9114400000000001e-01 , 9.7768800000000000e-01 -5.1384120162687328e+00 , -2.4825806204121159e-01 , 1.7514243999999999e+00 , -9.2374600000000001e-02 , 1.6514699999999999e-01 , 9.8193299999999994e-01 -5.2478193445401198e+00 , -3.5333349429917149e-01 , 1.7750116000000000e+00 , 6.6572500000000007e-02 , -1.7198400000000000e-01 , -9.8284800000000005e-01 -5.3501461269749511e+00 , -4.5017712590256931e-01 , 1.8063280800000001e+00 , -8.8720900000000005e-02 , 2.0116200000000001e-01 , 9.7553199999999995e-01 -5.4583994767302260e+00 , -5.5542281204258259e-01 , 1.8393314400000000e+00 , -7.4685000000000001e-02 , 1.7355999999999999e-01 , 9.8198700000000005e-01 -5.5897136965887135e+00 , -6.8140842833490778e-01 , 1.8691804800000000e+00 , -5.7400300000000001e-02 , 1.7781900000000000e-01 , 9.8238800000000004e-01 -5.7203239301069821e+00 , -8.0727146162357144e-01 , 1.9047997520000000e+00 , -6.7937399999999995e-02 , 1.9033800000000001e-01 , 9.7936500000000004e-01 -5.8587881000081321e+00 , -9.3916149741212296e-01 , 1.9437681360000001e+00 , -5.7833799999999998e-02 , 1.8293100000000001e-01 , 9.8142300000000005e-01 -6.0263401205471601e+00 , -1.1003747820791423e+00 , 1.9804600640000001e+00 , -6.0221299999999998e-02 , 1.7749599999999999e-01 , 9.8227699999999996e-01 -6.1801014502212901e+00 , -1.2479463275246081e+00 , 2.0291736640000000e+00 , -9.0955900000000006e-02 , 1.9959099999999999e-01 , 9.7564899999999999e-01 -6.3553506606605588e+00 , -1.4153032809684767e+00 , 2.0791603279999999e+00 , -7.5633900000000004e-02 , 1.8979799999999999e-01 , 9.7890600000000005e-01 -6.5518435526471848e+00 , -1.6042248224527977e+00 , 2.1320446400000002e+00 , -7.6584899999999997e-02 , 1.9099099999999999e-01 , 9.7860000000000003e-01 -6.7566687580576543e+00 , -1.8003816120604954e+00 , 2.1929626400000002e+00 , -7.5244800000000001e-02 , 1.9334899999999999e-01 , 9.7824000000000000e-01 -7.0055555478543665e+00 , -2.0395288632029818e+00 , 2.2554479199999999e+00 , -6.9960300000000003e-02 , 1.8510199999999999e-01 , 9.8022600000000004e-01 -7.2530866984989357e+00 , -2.2773804104560025e+00 , 2.3293700799999999e+00 , -7.7685400000000002e-02 , 1.9825799999999999e-01 , 9.7706700000000002e-01 -7.5389075520617395e+00 , -2.5504787573917351e+00 , 2.4103850400000000e+00 , -7.5657299999999997e-02 , 1.8839800000000001e-01 , 9.7917399999999999e-01 -7.8752343129522382e+00 , -2.8740688018394982e+00 , 2.4993341600000001e+00 , -7.3823200000000005e-02 , 1.8932800000000000e-01 , 9.7913499999999998e-01 -8.2345802063867701e+00 , -3.2180358337221184e+00 , 2.6026893600000003e+00 , -8.4127599999999997e-02 , 1.9817699999999999e-01 , 9.7654900000000000e-01 -8.6219168466009783e+00 , -3.5898400530832868e+00 , 2.7214043200000000e+00 , -8.0155599999999994e-02 , 1.9067500000000001e-01 , 9.7837499999999999e-01 -9.1280042822816760e+00 , -4.0753310988830380e+00 , 2.8546106400000002e+00 , -7.5448799999999996e-02 , 1.8761800000000001e-01 , 9.7933999999999999e-01 -9.6930052707083938e+00 , -4.6169314796448226e+00 , 3.0117005600000000e+00 , -7.9862299999999997e-02 , 1.9066100000000000e-01 , 9.7840199999999999e-01 -1.0345170480613513e+01 , -5.2436035732215300e+00 , 3.1973832000000000e+00 , -1.3166900000000001e-01 , 1.8694400000000000e-01 , 9.7350700000000001e-01 -1.0891175975029395e+01 , -5.7646268030297874e+00 , 3.4104064000000003e+00 , 4.0329700000000002e-01 , -2.3382100000000000e-01 , -8.8469200000000003e-01 -1.1539257854179207e+01 , -6.3842422664062664e+00 , 3.6565848000000001e+00 , -2.2843600000000000e-01 , 8.3532899999999993e-02 , 9.6996899999999997e-01 -1.3161674512794717e+01 , -7.9438526058680186e+00 , 4.0197631999999999e+00 , -9.2119699999999999e-02 , 1.6550400000000001e-01 , 9.8189700000000002e-01 -3.0827477323404523e+01 , -2.4889218515844860e+01 , 9.0405608000000015e+00 , 6.3690300000000000e-01 , -2.1566299999999999e-01 , -7.4016499999999996e-01 -3.1279110777039584e+01 , -2.5297046201268092e+01 , 9.8480792000000008e+00 , -5.3898800000000002e-01 , 2.4757299999999999e-01 , 8.0510800000000005e-01 -3.3318537671863240e+01 , -2.7229735741372746e+01 , 1.1094009600000000e+01 , 9.9984700000000004e-01 , -1.6864600000000000e-02 , 4.5998400000000000e-03 -3.8144907508700484e+01 , -3.1798874650496394e+01 , 1.4136800000000001e+01 , 6.3113699999999995e-01 , -7.4516400000000005e-01 , 2.1539900000000001e-01 -3.1856085122392354e+01 , -2.5636913818891109e+01 , 1.5973544000000000e+01 , 1.9409100000000001e-01 , -6.8400099999999997e-01 , 7.0318599999999998e-01 -3.1051110298148231e+01 , -2.4814598061388459e+01 , 1.7142608000000003e+01 , 1.9409100000000001e-01 , -6.8400099999999997e-01 , 7.0318599999999998e-01 -3.1099143014660317e+01 , -2.4657891740493387e+01 , 2.2816223999999998e+01 , 8.1607300000000005e-01 , -5.3561899999999996e-01 , 2.1710900000000000e-01 -3.1181745588865404e+01 , -2.4704179822228252e+01 , 2.3731840000000002e+01 , -6.0928199999999999e-01 , 7.9227800000000004e-01 , 3.2722399999999999e-02 -3.1256476310740531e+01 , -2.4743043812039168e+01 , 2.4661704000000000e+01 , 7.3140499999999997e-01 , -6.3689700000000005e-01 , -2.4374000000000001e-01 -3.2896393854459511e+01 , -2.6186348492570175e+01 , 2.8773656000000003e+01 , 5.7975399999999999e-01 , -7.1738000000000002e-01 , -3.8633000000000001e-01 -6.4325861815837406e+00 , -1.2991663451430266e+00 , 7.4206256000000002e+00 , 3.5965000000000003e-01 , -2.3446500000000001e-01 , 9.0314899999999998e-01 -6.2493543692642541e+00 , -1.1233678204697046e+00 , 7.3686984000000004e+00 , -3.1598199999999999e-01 , 6.5296200000000004e-01 , -6.8832800000000005e-01 -6.1975005183848992e+00 , -1.0690533163837648e+00 , 7.4585856000000001e+00 , 2.5719900000000001e-01 , -7.3969799999999997e-01 , 6.2184799999999996e-01 -6.1886143190969607e+00 , -1.0566776421098090e+00 , 7.6024072000000009e+00 , 4.1699000000000003e-01 , -6.9786899999999996e-01 , 5.8232200000000001e-01 -6.1839915766665161e+00 , -1.0461224379136906e+00 , 7.7539352000000008e+00 , -1.3223799999999999e-01 , 9.8480800000000002e-01 , -1.1254599999999999e-01 -6.3420709782738518e+00 , -1.1859423993004197e+00 , 8.1213984000000004e+00 , 2.5979100000000001e-02 , 9.9634900000000004e-01 , 8.1324900000000006e-02 -6.3232083814793665e+00 , -1.1623564705069915e+00 , 8.2713456000000001e+00 , -1.2673899999999999e-01 , 4.7729800000000000e-01 , -8.6955400000000005e-01 -5.9169705504788075e+00 , -7.8268981276717708e-01 , 7.8871903999999997e+00 , -5.1606200000000002e-01 , 8.2296599999999998e-01 , -2.3750199999999999e-01 -5.8832754039198178e+00 , -7.4560967086280661e-01 , 8.0060831999999991e+00 , -3.0535000000000001e-01 , -6.5105000000000002e-01 , 6.9490700000000005e-01 -5.8853958650943605e+00 , -7.4062748831223058e-01 , 8.1788063999999991e+00 , -2.6389699999999999e-02 , -9.2088800000000004e-01 , 3.8893299999999997e-01 -5.8779756235779423e+00 , -7.2805015340224299e-01 , 8.3450920000000011e+00 , -1.5863800000000000e-01 , -9.6141399999999999e-01 , 2.2475999999999999e-01 -5.8579120679529124e+00 , -7.0304166174997862e-01 , 8.4965264000000005e+00 , -4.8255799999999999e-01 , -2.6801599999999998e-02 , 8.7545399999999995e-01 -5.4928814365330361e+00 , -3.6442914680523097e-01 , 8.0860488000000004e+00 , -4.9969700000000000e-01 , 7.0841299999999996e-01 , -4.9845200000000001e-01 -5.4163459282828867e+00 , -2.8807969924147159e-01 , 8.1324535999999998e+00 , -4.4336500000000001e-01 , 5.7367199999999996e-01 , -6.8871400000000005e-01 -5.4284146838553253e+00 , -2.9369799960125276e-01 , 8.3337664000000000e+00 , -9.7350000000000006e-02 , 8.1383799999999995e-01 , -5.7287999999999994e-01 -5.2722853348351775e+00 , -1.4533309256301585e-01 , 8.2357568000000008e+00 , 7.9555600000000004e-02 , -5.4970100000000000e-01 , 8.3156500000000000e-01 -5.2306626877109350e+00 , -1.0060668566272035e-01 , 8.3434799999999996e+00 , -2.6056200000000002e-02 , -6.4271400000000001e-01 , 7.6566299999999998e-01 -5.1746142427907031e+00 , -4.3502715156075844e-02 , 8.4252344000000008e+00 , -1.1790200000000001e-01 , -8.8665300000000002e-01 , 4.4715300000000002e-01 -5.0313156705518232e+00 , 9.2500870276877700e-02 , 8.3318320000000003e+00 , 9.6156800000000001e-02 , -4.5760499999999998e-01 , 8.8394099999999998e-01 -4.9788681685441363e+00 , 1.4607956693024549e-01 , 8.4179543999999993e+00 , 1.8058399999999999e-01 , 7.6472399999999996e-01 , -6.1853599999999997e-01 -4.9643989315887698e+00 , 1.6573844196238952e-01 , 8.5914576000000000e+00 , 5.8797299999999997e-02 , 7.6632699999999998e-01 , -6.3975499999999996e-01 -4.8804561754863016e+00 , 2.4810993655804259e-01 , 8.6135160000000006e+00 , -2.2169200000000000e-01 , 3.3092500000000002e-01 , -9.1724700000000003e-01 -4.8313598871308709e+00 , 2.9929061589351358e-01 , 8.7147392000000004e+00 , -5.7957700000000001e-01 , -5.0637700000000004e-03 , -8.1490099999999999e-01 -4.7316682002057462e+00 , 3.9538441339877917e-01 , 8.6960815999999994e+00 , -3.5826700000000000e-01 , 9.8612000000000005e-02 , -9.2839700000000003e-01 -4.6798522307890753e+00 , 4.4925030090590745e-01 , 8.7942992000000011e+00 , -1.2878600000000001e-01 , -1.5520000000000000e-01 , -9.7945199999999999e-01 -4.5495757596314608e+00 , 5.7226282207801882e-01 , 8.6866175999999999e+00 , 2.0277500000000001e-01 , 7.4720100000000000e-01 , 6.3290900000000005e-01 -4.2030890390630669e+00 , 8.8121868481365340e-01 , 7.9642856000000002e+00 , 1.7367800000000000e-01 , 6.9337099999999996e-01 , 6.9933699999999999e-01 -4.1257941835246612e+00 , 9.5623632589904695e-01 , 7.9564648000000000e+00 , 1.7367800000000000e-01 , 6.9337099999999996e-01 , 6.9933699999999999e-01 -4.0029358655990785e+00 , 1.0698227114692225e+00 , 7.8036056000000009e+00 , 9.6489900000000003e-02 , 7.7467600000000003e-01 , 6.2495299999999998e-01 -3.8539594057060773e+00 , 1.2056728153490095e+00 , 7.5501680000000002e+00 , 3.8866299999999998e-01 , 7.4932799999999999e-01 , 5.3614300000000004e-01 -3.7977378341893475e+00 , 1.2611181281870594e+00 , 7.5814719999999998e+00 , 6.2227600000000005e-01 , -1.6979500000000000e-01 , 7.6416099999999998e-01 -3.7248964792626742e+00 , 1.3297134035311009e+00 , 7.5532672000000005e+00 , 2.6432499999999998e-01 , -5.0279499999999999e-01 , 8.2299999999999995e-01 -3.7248529594321460e+00 , 1.3386702582416534e+00 , 7.7874544000000006e+00 , -4.5360600000000001e-01 , 6.9180799999999998e-01 , -5.6182100000000001e-01 -3.7604374929296616e+00 , 1.3187053650539953e+00 , 8.1808240000000012e+00 , -5.7445299999999999e-01 , 8.0735599999999996e-01 , -1.3483500000000001e-01 -3.6391657457757143e+00 , 1.4293333423771242e+00 , 7.9714616000000005e+00 , 7.0907699999999996e-01 , 1.1778400000000000e-01 , 6.9522399999999995e-01 -3.5388663191903884e+00 , 1.5204682734732373e+00 , 7.8279312000000010e+00 , 9.2442500000000005e-01 , -8.4443299999999999e-02 , 3.7189800000000001e-01 -3.6977598034967469e+00 , 1.4038010792332130e+00 , 8.8638544000000010e+00 , 6.7084999999999995e-01 , 3.8967099999999999e-01 , -6.3096500000000000e-01 -3.6379374846219026e+00 , 1.4643411499631189e+00 , 8.9513080000000009e+00 , -7.6330500000000001e-01 , -2.2373999999999999e-01 , 6.0605799999999999e-01 -3.5186246160788714e+00 , 1.5722156501671685e+00 , 8.7339792000000003e+00 , 8.1625800000000004e-01 , -2.2536400000000001e-01 , -5.3191500000000003e-01 -3.4226900981766177e+00 , 1.6605584989957891e+00 , 8.6144207999999995e+00 , -6.5466800000000003e-01 , -5.9569799999999995e-01 , -4.6535199999999999e-01 -3.2161460172094749e+00 , 1.8312207268854446e+00 , 7.7888792000000002e+00 , 3.7861000000000000e-01 , -3.9962199999999998e-01 , 8.3483900000000000e-01 -3.1595220326624167e+00 , 1.8877612845740288e+00 , 7.8149936000000002e+00 , -3.2259800000000000e-01 , 4.2551899999999998e-01 , 8.4549600000000003e-01 -3.0774886071279228e+00 , 1.9619701147602744e+00 , 7.6651400000000010e+00 , -2.3691499999999999e-01 , 5.2293900000000004e-01 , 8.1878300000000004e-01 -3.0185462872256830e+00 , 2.0191008138530289e+00 , 7.6673448000000004e+00 , -3.2939600000000002e-01 , -1.5545500000000001e-01 , 9.3130700000000000e-01 -2.9632967903078256e+00 , 2.0735302787757748e+00 , 7.6990856000000001e+00 , -1.3533999999999999e-02 , 9.6658100000000002e-01 , 2.5600600000000001e-01 -2.8995116734965425e+00 , 2.1337061554578698e+00 , 7.6468568000000001e+00 , -1.5730800000000000e-02 , 1.3973500000000000e-01 , 9.9006400000000006e-01 -2.8470595090443744e+00 , 2.1863027654790774e+00 , 7.7069896000000000e+00 , 2.9176700000000000e-01 , -2.8967900000000002e-01 , 9.1156899999999996e-01 -2.7830238690059872e+00 , 2.2459294353072230e+00 , 7.6308927999999998e+00 , 7.9514700000000005e-01 , -2.4873999999999999e-01 , 5.5305499999999996e-01 -2.8414890849381647e+00 , 2.2576189894488095e+00 , 9.5460008000000016e+00 , 4.2158299999999999e-01 , -6.8174699999999999e-01 , -5.9790399999999999e-01 -2.7570125758423512e+00 , 2.3369856592533909e+00 , 9.4686559999999993e+00 , 3.7372800000000000e-01 , 7.1732099999999999e-01 , 5.8803000000000005e-01 -2.6719880182259312e+00 , 2.4150460581762001e+00 , 9.3267376000000013e+00 , 7.2558900000000004e-01 , -1.6472000000000001e-02 , 6.8793099999999996e-01 -2.5923014714411385e+00 , 2.4900786822239183e+00 , 9.2868847999999993e+00 , -2.9171100000000000e-01 , -5.2312700000000001e-01 , -8.0077600000000004e-01 -2.4363230681189374e+00 , 2.6466609782262163e+00 , 9.4299679999999988e+00 , -9.6636900000000003e-01 , -1.8359100000000000e-01 , -1.8007000000000001e-01 -2.3698349313741405e+00 , 2.6789888701097335e+00 , 8.5432535999999999e+00 , -3.0812800000000001e-01 , 2.2681000000000001e-01 , 9.2391299999999998e-01 -2.3023451615225685e+00 , 2.7435733116356325e+00 , 8.4962976000000001e+00 , 7.4989300000000003e-01 , -6.6093999999999997e-01 , 2.8624600000000000e-02 -2.2035142491858495e+00 , 2.8669763247764295e+00 , 9.2668959999999991e+00 , 1.9704600000000000e-01 , 4.9150400000000000e-01 , 8.4828999999999999e-01 -2.1284676475065649e+00 , 2.9374569874453718e+00 , 9.2054320000000001e+00 , 2.3799500000000001e-01 , -7.8678899999999996e-01 , -5.6949200000000000e-01 -1.8432391889720061e+00 , 3.3270498800632069e+00 , 1.2374790400000000e+01 , -5.3456899999999996e-01 , -8.0435100000000004e-01 , -2.5933600000000001e-01 -1.7258317257238815e+00 , 3.4415820357187918e+00 , 1.2375352000000001e+01 , 8.1430999999999998e-01 , 2.3569199999999998e-02 , 5.7995200000000002e-01 -1.6093483786830389e+00 , 3.5524070897001971e+00 , 1.2341936800000001e+01 , -6.9348699999999996e-01 , -7.0297900000000002e-01 , -1.5778500000000001e-01 -1.4054437015937919e+00 , 3.7794390070081043e+00 , 1.3156495999999999e+01 , -9.5918899999999996e-01 , -2.3301300000000000e-01 , 1.6019300000000000e-01 -1.4403888869600654e+00 , 3.6954652594387789e+00 , 1.1745777600000000e+01 , -4.9305199999999999e-01 , -6.5200300000000000e-01 , 5.7601400000000003e-01 -4.0153945590944415e+00 , 7.5159367810326971e-01 , 1.4360444000000001e+00 , -1.1767100000000000e-01 , 3.1270599999999998e-01 , 9.4253299999999995e-01 -4.0587211757865349e+00 , 7.0730818665046513e-01 , 1.4521155200000000e+00 , -1.2145700000000000e-01 , 2.2785500000000000e-01 , 9.6609000000000000e-01 -4.1028470984522816e+00 , 6.6232518909698390e-01 , 1.4701376800000001e+00 , -1.0092400000000000e-01 , 1.7580999999999999e-01 , 9.7923700000000002e-01 -4.1594664722602417e+00 , 6.0528389398550719e-01 , 1.4784368799999998e+00 , -9.0627299999999994e-02 , 1.9873499999999999e-01 , 9.7585400000000000e-01 -4.2089823128271284e+00 , 5.5433682342954160e-01 , 1.4943686400000000e+00 , 6.3740400000000003e-02 , -1.8914400000000001e-01 , -9.7987899999999994e-01 -4.2660474194377827e+00 , 4.9609127690386501e-01 , 1.5073530399999999e+00 , -9.0690900000000005e-02 , 1.9935400000000000e-01 , 9.7572199999999998e-01 -4.3160859821553483e+00 , 4.4492121013001551e-01 , 1.5275612800000000e+00 , -1.3284599999999999e-01 , 1.9747300000000001e-01 , 9.7126500000000004e-01 -4.3736532874190690e+00 , 3.8650156468746255e-01 , 1.5450249600000001e+00 , -9.3097500000000000e-02 , 1.5339800000000001e-01 , 9.8376900000000000e-01 -4.4309664604056742e+00 , 3.2855036875737365e-01 , 1.5647131999999999e+00 , -1.0155699999999999e-01 , 1.7276600000000000e-01 , 9.7971299999999995e-01 -4.4946943395152079e+00 , 2.6350578265921731e-01 , 1.5822392800000000e+00 , -8.1454600000000002e-02 , 2.1320700000000001e-01 , 9.7360599999999997e-01 -4.5648647405690674e+00 , 1.9243459733787449e-01 , 1.5975990400000000e+00 , -8.8903700000000002e-02 , 2.0691399999999999e-01 , 9.7431100000000004e-01 -4.6289296746229134e+00 , 1.2640779478469621e-01 , 1.6208212000000000e+00 , -8.7236499999999995e-02 , 1.8622500000000000e-01 , 9.7862700000000002e-01 -4.6993777644020822e+00 , 5.4437862595857256e-02 , 1.6422816000000000e+00 , -8.4316600000000005e-02 , 1.9584099999999999e-01 , 9.7700399999999998e-01 -4.7704776395751320e+00 , -1.7972968447963478e-02 , 1.6670065599999999e+00 , -1.2139400000000000e-01 , 1.8454300000000001e-01 , 9.7529900000000003e-01 -4.8555261895800079e+00 , -1.0360088739025741e-01 , 1.6870224000000000e+00 , -9.0791399999999994e-02 , 1.6549800000000001e-01 , 9.8202199999999995e-01 -4.9400764080899879e+00 , -1.9053953686213898e-01 , 1.7109902400000001e+00 , -8.6262199999999997e-02 , 1.8107799999999999e-01 , 9.7967800000000005e-01 -5.0252346027427910e+00 , -2.7676069812522686e-01 , 1.7386240799999999e+00 , -9.1057700000000005e-02 , 1.7621700000000001e-01 , 9.8013099999999997e-01 -5.1241169622996638e+00 , -3.7692359523740704e-01 , 1.7632720799999999e+00 , -8.6839000000000000e-02 , 1.6063900000000000e-01 , 9.8318600000000000e-01 -5.2300370252315762e+00 , -4.8453111330199139e-01 , 1.7893240800000001e+00 , -9.0316900000000006e-02 , 1.9805800000000001e-01 , 9.7602100000000003e-01 -5.3212388622893219e+00 , -5.7868491279968737e-01 , 1.8263626399999999e+00 , -9.9509299999999995e-02 , 1.7315000000000000e-01 , 9.7985599999999995e-01 -5.4486320832260180e+00 , -7.0825618573136184e-01 , 1.8533911999999999e+00 , -8.0751699999999996e-02 , 1.7046000000000000e-01 , 9.8204999999999998e-01 -5.5688308543050322e+00 , -8.3049950398759398e-01 , 1.8889591999999999e+00 , -9.3476400000000001e-02 , 1.8187500000000001e-01 , 9.7886899999999999e-01 -5.6958563096382342e+00 , -9.5982698097818941e-01 , 1.9276533360000001e+00 , -8.1235500000000002e-02 , 1.7831700000000000e-01 , 9.8061399999999999e-01 -5.8381246521061998e+00 , -1.1043588391306995e+00 , 1.9679679999999999e+00 , -5.9668899999999997e-02 , 1.6555900000000001e-01 , 9.8439299999999996e-01 -6.0148080987796906e+00 , -1.2851775935842560e+00 , 2.0041219776000001e+00 , -6.5908999999999995e-02 , 1.8454100000000001e-01 , 9.8061200000000004e-01 -6.1702647964708497e+00 , -1.4431018870980776e+00 , 2.0545319840000000e+00 , -8.6351499999999998e-02 , 1.9569800000000001e-01 , 9.7685500000000003e-01 -6.3470355688283631e+00 , -1.6237756014712770e+00 , 2.1072354400000002e+00 , -7.8569600000000003e-02 , 1.8241199999999999e-01 , 9.8007800000000000e-01 -6.5460063458842761e+00 , -1.8259155513009087e+00 , 2.1635691200000000e+00 , -8.8202299999999997e-02 , 1.9047100000000000e-01 , 9.7772199999999998e-01 -6.7511940355852555e+00 , -2.0351677629735550e+00 , 2.2280907200000000e+00 , 8.3105499999999999e-02 , -1.7685899999999999e-01 , -9.8072099999999995e-01 -7.0003190748461535e+00 , -2.2882633186980614e+00 , 2.2951936000000002e+00 , 8.1412899999999996e-02 , -1.8091599999999999e-01 , -9.8012299999999997e-01 -7.2626291712157478e+00 , -2.5558343537915000e+00 , 2.3722929600000002e+00 , -8.1887100000000004e-02 , 1.8252199999999999e-01 , 9.7978600000000005e-01 -7.5609770760450257e+00 , -2.8593739582729905e+00 , 2.4577570400000002e+00 , 8.1198400000000004e-02 , -1.8024399999999999e-01 , -9.8026500000000005e-01 -7.9022743298344515e+00 , -3.2072224725426874e+00 , 2.5538010399999997e+00 , -8.3000099999999993e-02 , 1.8448100000000001e-01 , 9.7932500000000000e-01 -8.2644138830090945e+00 , -3.5752313256869437e+00 , 2.6649115200000000e+00 , -9.3046299999999998e-02 , 1.8466199999999999e-01 , 9.7838800000000004e-01 -8.7060835685571085e+00 , -4.0244687439340856e+00 , 2.7904135200000000e+00 , -8.0557699999999996e-02 , 1.8348600000000001e-01 , 9.7971600000000003e-01 -9.2038814616908518e+00 , -4.5324599732611359e+00 , 2.9365948799999999e+00 , -7.9847299999999996e-02 , 1.8753100000000000e-01 , 9.7900799999999999e-01 -9.7943806170380405e+00 , -5.1339402617437582e+00 , 3.1076623999999997e+00 , -8.1780300000000000e-02 , 1.8464900000000001e-01 , 9.7939600000000004e-01 -1.0521778449754917e+01 , -5.8747164250851478e+00 , 3.3122096000000001e+00 , -1.7373900000000000e-01 , 1.8748300000000001e-01 , 9.6678100000000000e-01 -1.1057885331820213e+01 , -6.4183113364420379e+00 , 3.5428400000000000e+00 , -3.1434699999999999e-01 , 1.3436799999999999e-01 , 9.3975100000000000e-01 -1.2228593763104438e+01 , -7.6118654947495514e+00 , 3.8502952000000001e+00 , -1.0466000000000000e-01 , 1.5693199999999999e-01 , 9.8204800000000003e-01 -1.3685960213422579e+01 , -9.0961013777813218e+00 , 4.2464519999999997e+00 , -6.6565899999999997e-02 , 1.7488699999999999e-01 , 9.8233599999999999e-01 -3.2891586017039401e+01 , -2.8624047342688318e+01 , 1.0860030399999999e+01 , -9.7418899999999997e-01 , -2.1192700000000000e-01 , 7.7733300000000005e-02 -3.3239448911477353e+01 , -2.8955496571646933e+01 , 1.1739922399999999e+01 , -9.7418899999999997e-01 , -2.1192700000000000e-01 , 7.7733300000000005e-02 -3.5992635535449985e+01 , -3.1709148534563482e+01 , 1.4254424000000000e+01 , -6.3676699999999997e-01 , 2.0862000000000000e-01 , 7.4229699999999998e-01 -3.6591517652583498e+01 , -3.2292672657816041e+01 , 1.5349128000000000e+01 , 6.3336300000000001e-01 , -7.1896499999999997e-01 , 2.8625400000000001e-01 -3.0024610602882220e+01 , -2.5534155307257596e+01 , 1.5945048000000000e+01 , 1.9409100000000001e-01 , -6.8400099999999997e-01 , 7.0318599999999998e-01 -3.0846647110234802e+01 , -2.6344841616901199e+01 , 1.7108808000000000e+01 , -9.5815600000000001e-01 , 2.8539300000000001e-01 , -2.2078700000000000e-02 -3.0181306372529246e+01 , -2.5648618302774601e+01 , 1.7550392000000002e+01 , 1.9409100000000001e-01 , -6.8400099999999997e-01 , 7.0318599999999998e-01 -3.0296278561781040e+01 , -2.5624781710009486e+01 , 2.2473024000000002e+01 , 8.1908499999999995e-01 , -5.7028000000000001e-01 , 6.2293000000000001e-02 -3.0985533399758971e+01 , -2.6293448734687715e+01 , 2.3828456000000003e+01 , -8.0122400000000005e-01 , 5.8803499999999997e-01 , -1.1070700000000000e-01 -3.1127536168078951e+01 , -2.6357938644328382e+01 , 2.6664432000000001e+01 , 7.5812999999999997e-01 , -5.8416699999999999e-01 , -2.8980699999999998e-01 -6.2100797448410203e+00 , -1.3301891405047872e+00 , 7.3931072000000002e+00 , 5.0123200000000000e-02 , -1.5746599999999999e-01 , 9.8625200000000002e-01 -6.1354921346817548e+00 , -1.2522987898592199e+00 , 7.4581280000000003e+00 , -2.1340300000000001e-01 , 4.5271200000000000e-01 , -8.6574300000000004e-01 -6.0459767489906486e+00 , -1.1541103193974971e+00 , 7.6575584000000001e+00 , 4.2689800000000000e-01 , -7.9293700000000000e-01 , 4.3475200000000003e-01 -6.0019819336057978e+00 , -1.1062144105578802e+00 , 7.7594264000000006e+00 , -3.8782800000000001e-01 , 6.7896100000000004e-01 , -6.2337900000000002e-01 -5.9029612683103458e+00 , -1.0038511293695258e+00 , 7.7878704000000010e+00 , -4.3816500000000003e-01 , 2.7838299999999999e-01 , -8.5470100000000004e-01 -5.8308443005159907e+00 , -9.2778387847567645e-01 , 7.8496048000000007e+00 , 1.6740400000000000e-01 , -3.0425500000000000e-01 , 9.3776599999999999e-01 -5.7727488811718750e+00 , -8.6628782986089625e-01 , 7.9316088000000002e+00 , 2.3548200000000000e-01 , -5.6569199999999997e-01 , 7.9027899999999995e-01 -5.6537239270734592e+00 , -7.4444325856208904e-01 , 7.9207407999999999e+00 , 2.6061600000000001e-01 , 7.8469699999999998e-01 , -5.6243299999999996e-01 -5.6203537036564502e+00 , -7.0681973289663791e-01 , 8.0370960000000000e+00 , -5.1294300000000004e-01 , -6.8465500000000001e-01 , 5.1781900000000003e-01 -5.6090618631928830e+00 , -6.9095238473554366e-01 , 8.1925239999999988e+00 , 6.9140500000000005e-01 , 4.5238400000000001e-01 , -5.6330100000000005e-01 -5.3948884339131862e+00 , -4.7574342556921545e-01 , 8.0133527999999998e+00 , -6.7667400000000000e-01 , 7.1416000000000002e-01 , -1.7913000000000001e-01 -5.3308237650232506e+00 , -4.0825217895439181e-01 , 8.0764288000000004e+00 , 5.6633999999999995e-01 , -7.5884600000000002e-01 , 3.2157700000000000e-01 -5.3345844541839984e+00 , -4.0733067666126921e-01 , 8.2609768000000017e+00 , -5.6391100000000005e-01 , 7.1036699999999997e-01 , -4.2116799999999999e-01 -5.2324370796332111e+00 , -3.0105947855048765e-01 , 8.2554128000000002e+00 , 3.2847100000000001e-01 , -1.8975400000000001e-01 , 9.2525700000000000e-01 -5.1213327536454791e+00 , -1.8892120101666876e-01 , 8.2296312000000000e+00 , -3.1431199999999998e-01 , 7.2151399999999999e-01 , -6.1694800000000005e-01 -5.0767508833612816e+00 , -1.3959501159438537e-01 , 8.3279320000000006e+00 , 6.6268199999999999e-01 , 5.3500400000000004e-03 , 7.4888200000000005e-01 -5.0713526676309595e+00 , -1.2887865789879882e-01 , 8.5117311999999998e+00 , 2.8244700000000000e-01 , 1.6760200000000000e-01 , 9.4452800000000003e-01 -4.9037121777897186e+00 , 3.8110585249941042e-02 , 8.3561368000000016e+00 , 5.4239800000000005e-01 , -4.4346200000000002e-01 , 7.1354399999999996e-01 -4.8954017192138739e+00 , 5.1833904726626079e-02 , 8.5384384000000004e+00 , -4.2000199999999999e-01 , 5.7587999999999995e-01 , -7.0139899999999999e-01 -4.8064066194207236e+00 , 1.4368664730085312e-01 , 8.5431808000000000e+00 , -4.2023300000000002e-01 , 6.9142999999999999e-01 , -5.8764600000000000e-01 -4.8000505557678137e+00 , 1.5567322592029909e-01 , 8.7435992000000002e+00 , 2.2706699999999999e-01 , -6.1154299999999995e-01 , 7.5792899999999996e-01 -4.7134800958763563e+00 , 2.4535397481425947e-01 , 8.7538952000000005e+00 , 2.5890299999999999e-01 , -3.9340999999999998e-01 , 8.8215500000000002e-01 -4.6342744723065863e+00 , 3.2728501254748954e-01 , 8.7800200000000004e+00 , -6.3235000000000000e-02 , -4.3823099999999997e-02 , 9.9703600000000003e-01 -4.5281819567496271e+00 , 4.3532447978977129e-01 , 8.7296943999999996e+00 , -4.0722899999999999e-02 , 2.3506500000000000e-01 , 9.7112600000000004e-01 -4.3442862106414184e+00 , 6.1544525849590892e-01 , 8.4513487999999999e+00 , -1.1779299999999999e-01 , 8.3313899999999996e-01 , 5.4037400000000002e-01 -4.1035016998291214e+00 , 8.4875379848791788e-01 , 7.9768904000000003e+00 , 1.7367800000000000e-01 , 6.9337099999999996e-01 , 6.9933699999999999e-01 -4.0264832568158795e+00 , 9.2806146923707011e-01 , 7.9588048000000002e+00 , -2.2473799999999999e-01 , -7.3339699999999997e-01 , -6.4157699999999995e-01 -3.8932337678116395e+00 , 1.0586209802782385e+00 , 7.7562128000000001e+00 , -1.1072899999999999e-01 , -7.6027599999999995e-01 , -6.4009300000000002e-01 -3.8051830361958467e+00 , 1.1465478844521244e+00 , 7.6837352000000001e+00 , -5.3974900000000003e-01 , -3.8540000000000002e-01 , -7.4842399999999998e-01 -3.7333363266902273e+00 , 1.2206537298556768e+00 , 7.6567472000000008e+00 , 5.7993600000000001e-01 , 4.7446600000000000e-01 , 6.6223600000000005e-01 -3.6988878766208018e+00 , 1.2587802717892727e+00 , 7.7648656000000003e+00 , -3.1554700000000002e-01 , -5.0080599999999997e-01 , 8.0599299999999996e-01 -3.6516694667265037e+00 , 1.3085493295328112e+00 , 7.8331520000000001e+00 , -1.2991500000000000e-02 , -7.2288100000000000e-01 , 6.9084999999999996e-01 -3.6055029747360985e+00 , 1.3578928078479593e+00 , 7.9100912000000001e+00 , 1.0441000000000000e-01 , -8.1316699999999997e-01 , 5.7258900000000001e-01 -3.7469449741501153e+00 , 1.2393190137225907e+00 , 8.8221711999999997e+00 , 4.4302599999999998e-01 , 6.1409700000000000e-01 , -6.5315599999999996e-01 -3.6641796060498226e+00 , 1.3227398971146083e+00 , 8.7916576000000006e+00 , -5.3858600000000001e-01 , -4.7387099999999999e-01 , 6.9668600000000003e-01 -3.6217616869041773e+00 , 1.3723317733080322e+00 , 8.9496959999999994e+00 , 5.4242999999999997e-01 , 3.2972099999999999e-01 , -7.7269299999999996e-01 -3.5157772647546426e+00 , 1.4751266528138305e+00 , 8.7943200000000008e+00 , 7.2699800000000003e-01 , -4.7137499999999999e-02 , -6.8501999999999996e-01 -3.2882803601148485e+00 , 1.6838740857156846e+00 , 7.9056400000000000e+00 , -4.1774200000000000e-01 , -8.8485199999999997e-01 , 2.0622299999999999e-01 -3.3203136678282386e+00 , 1.6683932147866423e+00 , 8.4838903999999999e+00 , 5.2137699999999998e-01 , 8.5212299999999996e-01 , 4.5295299999999997e-02 -3.1901124889221442e+00 , 1.7888880276779435e+00 , 8.0738808000000013e+00 , 2.1943599999999999e-01 , 8.1827799999999995e-01 , 5.3128900000000001e-01 -3.0898893334666604e+00 , 1.8851956203553659e+00 , 7.7926752000000006e+00 , -1.2404000000000000e-01 , 4.2709200000000003e-01 , 8.9566000000000001e-01 -3.0192339121939904e+00 , 1.9541522976533270e+00 , 7.7035056000000006e+00 , 3.3946900000000002e-01 , 5.3626899999999998e-02 , 9.3908700000000001e-01 -2.9510860451939527e+00 , 2.0216010918093295e+00 , 7.6021160000000005e+00 , -2.6991199999999999e-01 , 2.7119100000000002e-01 , 9.2390700000000003e-01 -2.9100788582349733e+00 , 2.0683220091881576e+00 , 7.7567432000000007e+00 , 9.8868600000000001e-02 , 4.3555600000000000e-01 , 8.9471599999999996e-01 -2.8458166937815452e+00 , 2.1316312253122955e+00 , 7.6830695999999996e+00 , -4.7911399999999998e-01 , 7.8657299999999997e-01 , -3.8955499999999998e-01 -2.9397288595546209e+00 , 2.0944159445375066e+00 , 9.7213864000000001e+00 , -5.0210999999999995e-01 , 5.2892600000000001e-01 , 6.8419600000000003e-01 -2.8617495307141598e+00 , 2.1758830431292018e+00 , 9.7718056000000004e+00 , -5.0210999999999995e-01 , 5.2892499999999998e-01 , 6.8419600000000003e-01 -2.7716945316859301e+00 , 2.2633742258172025e+00 , 9.6123735999999997e+00 , -4.7437200000000002e-01 , 7.3649699999999996e-01 , 4.8222799999999999e-01 -2.6780502510237731e+00 , 2.3490721521897817e+00 , 9.2324720000000013e+00 , -7.5431300000000001e-01 , 5.0824800000000003e-01 , -4.1556799999999999e-01 -2.6091834129670670e+00 , 2.4262343706340395e+00 , 9.4742719999999991e+00 , -7.8330500000000003e-01 , -4.6644500000000000e-01 , -4.1092800000000002e-01 -2.5325969378889299e+00 , 2.5089181169023473e+00 , 9.5995400000000011e+00 , 7.7315100000000003e-01 , 2.6860699999999998e-01 , 5.7453299999999996e-01 -2.4535784825935387e+00 , 2.5838272486143130e+00 , 9.3905624000000003e+00 , -8.0839700000000003e-01 , -4.2532999999999999e-01 , -4.0692600000000001e-01 -2.3855683541057786e+00 , 2.6318296949273750e+00 , 8.6392975999999990e+00 , -2.9151700000000003e-01 , 7.7387899999999998e-01 , 5.6225300000000000e-01 -2.3206965798042885e+00 , 2.6946336404997395e+00 , 8.5102751999999988e+00 , 1.6293199999999999e-01 , -3.6489400000000000e-01 , -9.1668200000000000e-01 -2.2250540781226293e+00 , 2.8169076685145495e+00 , 9.3233888000000000e+00 , 1.3528899999999999e-01 , -1.1512400000000000e-03 , 9.9080599999999996e-01 -2.1422178909343939e+00 , 2.9052793282404350e+00 , 9.4492080000000005e+00 , 6.1813200000000001e-01 , 7.7767799999999998e-01 , 1.1458100000000000e-01 -2.0808703718648967e+00 , 2.9598585279090419e+00 , 9.1694376000000002e+00 , 3.9345000000000002e-01 , -6.7041700000000004e-01 , -6.2907700000000000e-01 -1.7746556890181224e+00 , 3.3654727411340586e+00 , 1.2324235999999999e+01 , -9.1369500000000003e-01 , -8.8407899999999998e-02 , -3.9666800000000002e-01 -1.6475979001609036e+00 , 3.4995794611131643e+00 , 1.2467392000000000e+01 , 7.3406199999999999e-01 , -1.8740999999999999e-01 , 6.5271000000000001e-01 -1.5599071120627366e+00 , 3.5815732068734274e+00 , 1.2175713600000000e+01 , 5.9016299999999999e-01 , 4.8158100000000002e-02 , -8.0584699999999998e-01 -1.4984360609145253e+00 , 3.6313489960984509e+00 , 1.1698197600000000e+01 , -4.9305199999999999e-01 , -6.5200300000000000e-01 , 5.7601400000000003e-01 -3.9530271481864232e+00 , 7.3595872825907804e-01 , 1.4294632800000000e+00 , -9.6219600000000002e-02 , 2.7688800000000002e-01 , 9.5607299999999995e-01 -3.9953416719718984e+00 , 6.8949433195558063e-01 , 1.4450102400000000e+00 , 1.3953099999999999e-01 , -2.4960599999999999e-01 , -9.5824200000000004e-01 -4.0375161056141735e+00 , 6.4434920152057895e-01 , 1.4618707199999998e+00 , 1.0039700000000000e-01 , -1.8225900000000000e-01 , -9.7811199999999998e-01 -4.0862957410026235e+00 , 5.9179911600047852e-01 , 1.4749476800000001e+00 , 9.8451100000000000e-02 , -1.6091900000000001e-01 , -9.8204499999999995e-01 -4.1348098194680940e+00 , 5.3862217713177230e-01 , 1.4901524799999999e+00 , -1.1015300000000000e-01 , 1.9186600000000001e-01 , 9.7521999999999998e-01 -4.1773254403767615e+00 , 4.9247444485692959e-01 , 1.5126081600000001e+00 , -8.8706300000000002e-02 , 1.9728100000000001e-01 , 9.7632600000000003e-01 -4.2379711321693243e+00 , 4.2677323388634325e-01 , 1.5209271200000001e+00 , -9.4661599999999999e-02 , 1.7335900000000001e-01 , 9.8029900000000003e-01 -4.2935651929585097e+00 , 3.6714711616324847e-01 , 1.5372311999999999e+00 , -6.0364000000000001e-02 , 1.7677499999999999e-01 , 9.8239799999999999e-01 -4.3613572659844948e+00 , 2.9377924928108112e-01 , 1.5459432799999999e+00 , -9.5286399999999993e-02 , 2.0568600000000001e-01 , 9.7396799999999994e-01 -4.4106381387673057e+00 , 2.4064102055180947e-01 , 1.5720285599999999e+00 , -8.2173999999999997e-02 , 2.1057400000000001e-01 , 9.7411800000000004e-01 -4.4720821752748163e+00 , 1.7382825918825162e-01 , 1.5908265600000000e+00 , -7.8787300000000005e-02 , 2.0194899999999999e-01 , 9.7622200000000003e-01 -4.5342107795272693e+00 , 1.0651757513733595e-01 , 1.6125864800000000e+00 , -5.3966100000000003e-02 , 1.8904099999999999e-01 , 9.8048500000000005e-01 -4.6093912397922985e+00 , 2.5754951393315517e-02 , 1.6282956799999999e+00 , -7.2910299999999997e-02 , 2.0009600000000000e-01 , 9.7706000000000004e-01 -4.6718663955866759e+00 , -4.1485483182231331e-02 , 1.6557485599999999e+00 , -8.4223300000000001e-02 , 1.9885900000000001e-01 , 9.7640199999999999e-01 -4.7472691725673046e+00 , -1.2303073996795488e-01 , 1.6781668000000001e+00 , -7.6765500000000000e-02 , 1.8824900000000000e-01 , 9.7911700000000002e-01 -4.8288620076303150e+00 , -2.1234100524927735e-01 , 1.7002449600000000e+00 , -7.9917500000000002e-02 , 1.9193800000000000e-01 , 9.7814800000000002e-01 -4.9110546923047789e+00 , -3.0094604117525714e-01 , 1.7259911999999999e+00 , -7.1792999999999996e-02 , 1.8309100000000000e-01 , 9.8047099999999998e-01 -5.0069722379781103e+00 , -4.0454321271967997e-01 , 1.7487526400000000e+00 , -7.0357500000000003e-02 , 1.7407100000000000e-01 , 9.8221599999999998e-01 -5.0957814219934932e+00 , -5.0097537455442209e-01 , 1.7792454400000000e+00 , -6.7391300000000001e-02 , 1.8111200000000000e-01 , 9.8115100000000000e-01 -5.1981864037645380e+00 , -6.1218176937051050e-01 , 1.8077653599999999e+00 , -8.1762100000000004e-02 , 1.8142700000000000e-01 , 9.7999999999999998e-01 -5.3075894119816471e+00 , -7.2969478346004601e-01 , 1.8380928000000001e+00 , -7.4249899999999994e-02 , 1.8367500000000000e-01 , 9.8017900000000002e-01 -5.4173663898162072e+00 , -8.4826742322179882e-01 , 1.8738126399999999e+00 , 7.1552800000000000e-02 , -1.8852400000000000e-01 , -9.7945899999999997e-01 -5.5404388980841421e+00 , -9.8222696241180518e-01 , 1.9097899840000001e+00 , -7.8021699999999999e-02 , 1.8127299999999999e-01 , 9.8033300000000001e-01 -5.6777971361282162e+00 , -1.1303858059553069e+00 , 1.9468545440000000e+00 , -7.7271800000000002e-02 , 1.8363499999999999e-01 , 9.7995299999999996e-01 -5.8217882646887382e+00 , -1.2864002873237599e+00 , 1.9884636959999999e+00 , -5.2211800000000003e-02 , 1.8093799999999999e-01 , 9.8210799999999998e-01 -5.9798098969076197e+00 , -1.4572918898563594e+00 , 2.0330858319999998e+00 , -7.0605100000000004e-02 , 1.9887700000000000e-01 , 9.7747799999999996e-01 -6.1369184517136786e+00 , -1.6276576102365810e+00 , 2.0852992399999999e+00 , -7.2753499999999999e-02 , 1.9793800000000000e-01 , 9.7751100000000002e-01 -6.3226813942700435e+00 , -1.8277209579202611e+00 , 2.1385779199999999e+00 , -6.8722599999999995e-02 , 1.9510100000000000e-01 , 9.7837300000000005e-01 -6.5146764086935551e+00 , -2.0360183160631697e+00 , 2.1997423999999999e+00 , -7.3812000000000003e-02 , 1.8155299999999999e-01 , 9.8060700000000001e-01 -6.7485925531589777e+00 , -2.2893105328671446e+00 , 2.2626343200000001e+00 , -6.4045099999999994e-02 , 1.8796800000000000e-01 , 9.8008499999999998e-01 -6.9894873054751852e+00 , -2.5492847086282628e+00 , 2.3359636799999999e+00 , -6.7651299999999998e-02 , 1.9515700000000000e-01 , 9.7843599999999997e-01 -7.2717405235897372e+00 , -2.8543571892152526e+00 , 2.4156765600000001e+00 , -6.3102300000000000e-02 , 1.9376499999999999e-01 , 9.7901600000000000e-01 -7.5678674988800090e+00 , -3.1744234572433507e+00 , 2.5082469600000001e+00 , 6.1851299999999998e-02 , -1.9634299999999999e-01 , -9.7858299999999998e-01 -7.9182754675740918e+00 , -3.5542865112149737e+00 , 2.6106952799999998e+00 , -6.6754499999999994e-02 , 1.9633700000000001e-01 , 9.7826199999999996e-01 -8.3047846162178196e+00 , -3.9717394632317236e+00 , 2.7293301599999999e+00 , 7.2275300000000001e-02 , -1.8927600000000000e-01 , -9.7926100000000005e-01 -8.7662995848202101e+00 , -4.4718156224610324e+00 , 2.8648951999999999e+00 , -6.9651500000000005e-02 , 1.9112799999999999e-01 , 9.7909100000000004e-01 -9.2908536054139930e+00 , -5.0379355334010514e+00 , 3.0234556800000001e+00 , -7.6009099999999996e-02 , 1.9027100000000000e-01 , 9.7878500000000002e-01 -9.9464550350246093e+00 , -5.7481984057910687e+00 , 3.2113088000000003e+00 , -9.8504400000000006e-02 , 1.9545599999999999e-01 , 9.7575299999999998e-01 -1.0677783474193873e+01 , -6.5391980030902879e+00 , 3.4361984000000003e+00 , -1.7074000000000000e-01 , 1.7916000000000001e-01 , 9.6889099999999995e-01 -1.1504522708192109e+01 , -7.4326559471090601e+00 , 3.7054647999999997e+00 , 1.1049200000000001e-01 , -1.5699600000000000e-01 , -9.8139900000000002e-01 -1.2581096741032656e+01 , -8.5972112774808185e+00 , 4.0416032000000000e+00 , -8.7707499999999994e-02 , 1.8627700000000000e-01 , 9.7857499999999997e-01 -1.4284061200798604e+01 , -1.0440842344250264e+01 , 4.5092704000000001e+00 , 6.3054899999999997e-02 , -2.1741800000000000e-01 , -9.7404000000000002e-01 -3.2715208090566918e+01 , -3.0381308454900520e+01 , 9.8896791999999998e+00 , -7.3883699999999997e-01 , 1.1611100000000001e-01 , 6.6380600000000001e-01 -3.6308399697650664e+01 , -3.4196044221359713e+01 , 1.4295088000000002e+01 , -6.3676699999999997e-01 , 2.0862000000000000e-01 , 7.4229699999999998e-01 -3.1127726393966736e+01 , -2.8529760698130698e+01 , 1.5716144000000000e+01 , -9.6849399999999997e-01 , 2.6811999999999999e-02 , -2.4758900000000000e-01 -3.1522474402977423e+01 , -2.8866880323151403e+01 , 2.0050552000000003e+01 , -9.5335999999999999e-01 , 3.0175299999999999e-01 , -7.1076500000000001e-03 -3.0969406531667424e+01 , -2.8198939602670436e+01 , 2.3190104000000002e+01 , -8.8131099999999996e-01 , 4.0815099999999999e-01 , -2.3812700000000001e-01 -3.0197644471037879e+01 , -2.7332644835480398e+01 , 2.4410544000000002e+01 , -8.3101700000000001e-01 , 5.0679399999999997e-01 , 2.2928299999999999e-01 -6.2219623823666010e+00 , -1.6050064748005610e+00 , 7.4862184000000003e+00 , 4.1068300000000002e-01 , -3.6543999999999999e-01 , 8.3533999999999997e-01 -6.0610225795138222e+00 , -1.4303981360018994e+00 , 7.4489343999999997e+00 , 2.3181900000000000e-01 , -2.8073599999999999e-01 , 9.3136900000000000e-01 -5.9662321522630783e+00 , -1.3264982055740990e+00 , 7.4858856000000005e+00 , 5.6094400000000000e-01 , -6.4137299999999997e-01 , 5.2343399999999995e-01 -5.8665084231702584e+00 , -1.2181015355124147e+00 , 7.5124680000000001e+00 , 7.2690900000000003e-01 , -4.8379899999999998e-01 , 4.8738399999999998e-01 -5.9622387326189816e+00 , -1.3148073365548116e+00 , 7.7960136000000002e+00 , -8.8319800000000004e-01 , 4.4243600000000000e-01 , -1.5559999999999999e-01 -5.8959039439128151e+00 , -1.2418232010516213e+00 , 7.8700720000000004e+00 , -8.9469900000000002e-01 , 3.2526800000000000e-01 , -3.0612899999999998e-01 -5.8580175952935392e+00 , -1.1946415651107296e+00 , 8.1541168000000006e+00 , 6.5892200000000001e-01 , 6.4516900000000002e-02 , 7.4943899999999997e-01 -5.5918336016787427e+00 , -9.1036801633420783e-01 , 7.9219472000000009e+00 , 1.9580700000000001e-01 , -1.1227700000000000e-01 , -9.7419400000000000e-01 -5.4100324841221745e+00 , -7.1456326390612590e-01 , 7.8009639999999996e+00 , 3.8537199999999999e-01 , 1.3711200000000001e-01 , -9.1251800000000005e-01 -5.3214115859253663e+00 , -6.1759419301900698e-01 , 7.8206199999999999e+00 , -6.5645800000000004e-02 , -4.0989300000000001e-01 , 9.0976800000000002e-01 -5.2519819090562176e+00 , -5.4117320871805941e-01 , 7.8689175999999996e+00 , -3.8898700000000003e-01 , -4.7113200000000000e-01 , 7.9165900000000000e-01 -5.2683875807407503e+00 , -5.5488972195208985e-01 , 8.0678175999999997e+00 , 4.6989300000000001e-01 , -8.5595900000000003e-01 , 2.1572000000000000e-01 -5.2679590401361533e+00 , -5.5010590192305386e-01 , 8.2443367999999992e+00 , -4.5620899999999998e-01 , 8.3901800000000004e-01 , -2.9651699999999998e-01 -5.2030126729331911e+00 , -4.7847449414170429e-01 , 8.3066639999999996e+00 , -2.5342199999999998e-01 , -9.5771099999999998e-01 , 1.3626099999999999e-01 -5.2138872372018854e+00 , -4.8526868317396099e-01 , 8.5176903999999993e+00 , -3.2658599999999999e-01 , 6.6125699999999998e-01 , -6.7533799999999999e-01 -5.1037916672904213e+00 , -3.6653778321969543e-01 , 8.4932295999999994e+00 , -4.0818300000000002e-01 , -6.7579699999999998e-01 , 6.1374600000000001e-01 -5.0198567006545360e+00 , -2.7541020233139912e-01 , 8.5165775999999997e+00 , 5.4920200000000002e-03 , 2.1511400000000000e-01 , 9.7657400000000005e-01 -4.8891177076147070e+00 , -1.3378332219668954e-01 , 8.4326808000000000e+00 , 1.2358400000000000e-01 , -5.8477599999999998e-02 , 9.9060999999999999e-01 -4.7988013751889564e+00 , -3.6616745118966065e-02 , 8.4319008000000011e+00 , -6.4046700000000001e-01 , 1.7130799999999999e-01 , -7.4863599999999997e-01 -4.7771803871937966e+00 , -9.5788138365402453e-03 , 8.5878592000000005e+00 , -5.5390200000000001e-01 , 2.8423100000000001e-01 , -7.8256300000000001e-01 -4.6833370682529010e+00 , 9.2475692344800908e-02 , 8.5736735999999993e+00 , 1.4672600000000000e-01 , -7.8767600000000004e-01 , 5.9836199999999995e-01 -4.6577155506493471e+00 , 1.2375376154625251e-01 , 8.7287168000000008e+00 , -4.6527699999999998e-02 , -5.0520699999999996e-01 , 8.6174300000000004e-01 -4.5704664120854659e+00 , 2.1871942421998214e-01 , 8.7282071999999999e+00 , -1.8200700000000000e-02 , -1.5185999999999999e-01 , 9.8823499999999997e-01 -4.4744985879832102e+00 , 3.2282636849767443e-01 , 8.6974231999999994e+00 , -8.0698900000000004e-02 , 7.6727199999999995e-02 , 9.9378100000000003e-01 -4.3688525951898383e+00 , 4.3484016816460280e-01 , 8.6353247999999994e+00 , -1.2715299999999999e-01 , 5.3445100000000001e-01 , 8.3557999999999999e-01 -4.3166768098723942e+00 , 4.9451190166672210e-01 , 8.7201160000000009e+00 , -1.2715299999999999e-01 , 5.3445100000000001e-01 , 8.3557999999999999e-01 -4.0219393113682544e+00 , 8.0029020814879148e-01 , 8.0456968000000018e+00 , 5.2163599999999999e-01 , 2.7441199999999999e-01 , 8.0783300000000002e-01 -3.9263323748840868e+00 , 9.0287857937025295e-01 , 7.9600112000000003e+00 , -3.8115199999999999e-01 , -7.4573199999999995e-01 , -5.4644800000000004e-01 -3.7799655313770621e+00 , 1.0571593196470297e+00 , 7.6878951999999998e+00 , 4.8250199999999999e-01 , 5.8803899999999998e-01 , 6.4915500000000004e-01 -3.7384913605604631e+00 , 1.1028284152478354e+00 , 7.7687136000000008e+00 , -9.7733600000000004e-02 , -3.2240600000000001e-02 , 9.9468999999999996e-01 -3.6453597567452896e+00 , 1.2025759311864970e+00 , 7.6536375999999997e+00 , -1.9901200000000001e-02 , -2.4767800000000001e-01 , 9.6863800000000000e-01 -3.6080491986156371e+00 , 1.2440379474449212e+00 , 7.7513248000000008e+00 , -8.6787199999999995e-02 , -7.1793099999999999e-01 , 6.9068300000000005e-01 -3.5418248091999978e+00 , 1.3168439041888536e+00 , 7.7296512000000011e+00 , -1.2421800000000000e-01 , -6.3696600000000003e-01 , 7.6081799999999999e-01 -3.5420629226056008e+00 , 1.3222127902930352e+00 , 8.0040551999999998e+00 , 3.6359900000000001e-01 , -8.6467200000000000e-01 , 3.4660999999999997e-01 -3.6218813506560070e+00 , 1.2497175864767684e+00 , 8.6889783999999999e+00 , -5.3858600000000001e-01 , -4.7387099999999999e-01 , 6.9668600000000003e-01 -3.5616075435150121e+00 , 1.3170392200908427e+00 , 8.7467503999999998e+00 , -5.3858600000000001e-01 , -4.7387099999999999e-01 , 6.9668600000000003e-01 -3.4910206496692329e+00 , 1.3935153195022221e+00 , 8.7528863999999995e+00 , -7.1431800000000001e-01 , -1.2442000000000000e-01 , 6.8867299999999998e-01 -3.3013632534222213e+00 , 1.5856741955064391e+00 , 8.0587383999999993e+00 , 3.0309399999999997e-01 , -1.7276600000000000e-01 , 9.3716900000000003e-01 -3.1842834042652317e+00 , 1.7047285407483752e+00 , 7.7128968000000002e+00 , 4.6715800000000002e-01 , 3.7691500000000000e-01 , -7.9981199999999997e-01 -3.1417486917915074e+00 , 1.7529596897397062e+00 , 7.8114575999999998e+00 , -6.7316500000000001e-01 , -4.5069599999999999e-01 , 5.8627799999999997e-01 -3.0981211011421159e+00 , 1.8030905450023200e+00 , 7.9192120000000008e+00 , 7.0883300000000003e-03 , 9.9032100000000001e-01 , 1.3861200000000001e-01 -3.0151716380773221e+00 , 1.8893774234604961e+00 , 7.7184296000000003e+00 , -1.8016099999999999e-01 , -5.3172100000000000e-01 , -8.2753500000000002e-01 -2.9664518655450274e+00 , 1.9436894840878138e+00 , 7.7826080000000006e+00 , -1.8124399999999999e-01 , 4.0069500000000001e-02 , 9.8262200000000000e-01 -2.8986914440202733e+00 , 2.0152417683782851e+00 , 7.6700488000000000e+00 , 2.8791499999999998e-01 , -5.4583099999999996e-01 , -7.8687600000000002e-01 -2.8400220610600746e+00 , 2.0782867352674095e+00 , 7.6278768000000001e+00 , 3.1796099999999999e-01 , -2.7441700000000002e-01 , 9.0752200000000005e-01 -2.7930534377333691e+00 , 2.1315034944290168e+00 , 7.7291520000000000e+00 , 1.5520700000000001e-01 , -8.1587400000000004e-02 , 9.8450700000000002e-01 -2.8599361908833782e+00 , 2.1001185243816667e+00 , 9.7063167999999997e+00 , -5.0210999999999995e-01 , 5.2892600000000001e-01 , 6.8419600000000003e-01 -2.7789014575141984e+00 , 2.1870786694139710e+00 , 9.6621272000000005e+00 , -5.0210999999999995e-01 , 5.2892600000000001e-01 , 6.8419500000000000e-01 -2.6795752402096293e+00 , 2.2833012006275317e+00 , 9.1066216000000004e+00 , 7.2117299999999995e-01 , 2.0683600000000000e-03 , -6.9275200000000003e-01 -2.6170368852343944e+00 , 2.3589883310176285e+00 , 9.4425831999999996e+00 , 3.9294400000000002e-01 , 7.2782599999999997e-01 , 5.6201800000000002e-01 -2.5430880811850831e+00 , 2.4409514163861417e+00 , 9.4857848000000011e+00 , 9.9788699999999997e-01 , 3.8097000000000001e-04 , -6.4975800000000000e-02 -2.4661892307965494e+00 , 2.5172558619668934e+00 , 9.1735040000000012e+00 , -7.4005799999999999e-01 , 6.7249099999999995e-01 , 8.3728799999999992e-03 -2.3998642144869953e+00 , 2.5756023199399478e+00 , 8.5477255999999997e+00 , -9.4746300000000006e-01 , 2.7082099999999998e-01 , 1.7020399999999999e-01 -2.3366196004576483e+00 , 2.6435919406054857e+00 , 8.4922312000000009e+00 , -1.6119200000000000e-01 , 2.5690299999999999e-01 , 9.5289999999999997e-01 -2.2459549921342852e+00 , 2.7606152995595541e+00 , 9.3066968000000010e+00 , 3.4516500000000000e-01 , 1.5955200000000000e-01 , 9.2488099999999995e-01 -2.1716878440738245e+00 , 2.8407618907919452e+00 , 9.3091824000000010e+00 , -8.6086999999999997e-02 , -3.6258000000000001e-01 , 9.2796800000000002e-01 -2.0993325412770658e+00 , 2.9194549328338169e+00 , 9.2785231999999986e+00 , -6.4570000000000005e-01 , 7.6261500000000004e-01 , -3.8599500000000002e-02 -1.8031933482713129e+00 , 3.3103474633669974e+00 , 1.2520536000000000e+01 , -8.2573900000000000e-01 , -1.9519800000000001e-01 , -5.2920000000000000e-01 -1.6851233148738367e+00 , 3.4393679894587015e+00 , 1.2571808000000001e+01 , -6.1032100000000000e-01 , -3.5502800000000001e-01 , -7.0814100000000002e-01 -1.5767754215873035e+00 , 3.5562459640142885e+00 , 1.2506808000000001e+01 , -4.3397900000000000e-01 , -7.2218700000000002e-01 , -5.3861800000000004e-01 -1.3884250956595232e+00 , 3.7767213599499905e+00 , 1.3218375999999999e+01 , -9.5477199999999995e-01 , -2.5045299999999998e-01 , 1.6026299999999999e-01 -1.4383666623484723e+00 , 3.6903544290895431e+00 , 1.1735804000000000e+01 , -4.9305199999999999e-01 , -6.5200300000000000e-01 , 5.7601400000000003e-01 -3.9024595218239275e+00 , 7.0990760370632566e-01 , 1.4106008000000001e+00 , -9.7807000000000005e-02 , 2.8140300000000001e-01 , 9.5459200000000000e-01 -3.9272208369324435e+00 , 6.8156433935486516e-01 , 1.4438558399999999e+00 , -8.8454300000000000e-02 , 2.7895700000000001e-01 , 9.5622099999999999e-01 -3.9732279218727040e+00 , 6.2850528765489977e-01 , 1.4538242399999999e+00 , -1.0971700000000000e-01 , 2.3613200000000001e-01 , 9.6550700000000000e-01 -4.0200158554500476e+00 , 5.7478743446285518e-01 , 1.4659454400000000e+00 , -8.5020200000000004e-02 , 1.7571999999999999e-01 , 9.8076200000000002e-01 -4.0675519934262070e+00 , 5.2041477398802050e-01 , 1.4803192800000000e+00 , -1.0816099999999999e-01 , 1.9924400000000000e-01 , 9.7396300000000002e-01 -4.1196364643811769e+00 , 4.5978010451336404e-01 , 1.4908596800000000e+00 , -1.1401600000000001e-01 , 1.8345500000000001e-01 , 9.7639399999999998e-01 -4.1619971342734967e+00 , 4.1282632086141668e-01 , 1.5145311200000000e+00 , 7.7866000000000005e-02 , -1.6259299999999999e-01 , -9.8361600000000005e-01 -4.2203085779839915e+00 , 3.4434923367396464e-01 , 1.5244287999999999e+00 , -6.9569800000000001e-02 , 1.8946900000000000e-01 , 9.7941900000000004e-01 -4.2678703385693826e+00 , 2.8953608315168755e-01 , 1.5471299199999999e+00 , -3.5402200000000002e-02 , 1.8860700000000000e-01 , 9.8141400000000001e-01 -4.3277050345785195e+00 , 2.2197263135906287e-01 , 1.5618313600000000e+00 , -7.6880799999999999e-02 , 2.2556100000000001e-01 , 9.7119100000000003e-01 -4.3757791865093889e+00 , 1.6698744808094945e-01 , 1.5890117600000000e+00 , -8.0345100000000003e-02 , 2.3423099999999999e-01 , 9.6885500000000002e-01 -4.4416306703607802e+00 , 9.0838611401130587e-02 , 1.6045920000000000e+00 , -5.8242500000000003e-02 , 2.1739300000000000e-01 , 9.7434500000000002e-01 -4.5014754320112083e+00 , 2.1759752084813178e-02 , 1.6276227999999999e+00 , -3.6936400000000001e-02 , 2.0152300000000001e-01 , 9.7878699999999996e-01 -4.5743535923376433e+00 , -6.0732342316010435e-02 , 1.6448077600000000e+00 , -4.5336300000000003e-02 , 2.2091300000000000e-01 , 9.7423899999999997e-01 -4.6467703358423229e+00 , -1.4461257646361814e-01 , 1.6655391200000000e+00 , -6.7204700000000006e-02 , 2.2634199999999999e-01 , 9.7172700000000001e-01 -4.7131865556291572e+00 , -2.2145341132495266e-01 , 1.6936211999999999e+00 , -3.9537000000000003e-02 , 2.0248800000000000e-01 , 9.7848599999999997e-01 -4.7924361818711434e+00 , -3.1244838228415217e-01 , 1.7173768800000000e+00 , -6.1390399999999998e-02 , 1.9462199999999999e-01 , 9.7895500000000002e-01 -4.8722842876583377e+00 , -4.0377833096494919e-01 , 1.7449025599999999e+00 , -6.8384100000000003e-02 , 1.7956300000000000e-01 , 9.8136699999999999e-01 -4.9713178416901203e+00 , -5.1735538033177342e-01 , 1.7662464800000000e+00 , -5.4720100000000001e-02 , 1.9104299999999999e-01 , 9.8005500000000001e-01 -5.0577210144381919e+00 , -6.1641879264139865e-01 , 1.7989243200000000e+00 , -6.2958500000000001e-02 , 1.9638800000000001e-01 , 9.7850300000000001e-01 -5.1631988914114277e+00 , -7.3749707798546371e-01 , 1.8265321600000000e+00 , -6.2084500000000001e-02 , 1.8929000000000001e-01 , 9.7995699999999997e-01 -5.2690507380021163e+00 , -8.5963498900174651e-01 , 1.8595324000000000e+00 , -4.8912100000000000e-02 , 1.9462699999999999e-01 , 9.7965700000000000e-01 -5.3882607793596726e+00 , -9.9616022502618851e-01 , 1.8924827200000001e+00 , -5.7147900000000001e-02 , 1.9228999999999999e-01 , 9.7967300000000002e-01 -5.5077607682959897e+00 , -1.1335923344494971e+00 , 1.9315345120000000e+00 , -6.2525600000000001e-02 , 1.8660700000000000e-01 , 9.8044299999999995e-01 -5.6404394832759301e+00 , -1.2862015671953309e+00 , 1.9718545839999999e+00 , -6.8648100000000004e-02 , 1.9167699999999999e-01 , 9.7905399999999998e-01 -5.7797809707547501e+00 , -1.4456098395136441e+00 , 2.0167162319999998e+00 , -5.2968700000000001e-02 , 1.9428999999999999e-01 , 9.7951299999999997e-01 -5.9320806685587248e+00 , -1.6208872388668354e+00 , 2.0646706319999999e+00 , -5.9938400000000003e-02 , 2.0202400000000001e-01 , 9.7754500000000000e-01 -6.1046009281034426e+00 , -1.8188067678797739e+00 , 2.1151976800000001e+00 , -5.4502599999999998e-02 , 1.9208300000000000e-01 , 9.7986399999999996e-01 -6.2907722303624167e+00 , -2.0331341173845852e+00 , 2.1715760799999999e+00 , -5.8474499999999999e-02 , 1.9262599999999999e-01 , 9.7952799999999995e-01 -6.4968628547194660e+00 , -2.2695598039805240e+00 , 2.2331576000000002e+00 , -5.9847200000000003e-02 , 1.9367999999999999e-01 , 9.7923800000000005e-01 -6.7089909229983382e+00 , -2.5138875507338438e+00 , 2.3042447199999998e+00 , -6.0940500000000002e-02 , 1.9377700000000000e-01 , 9.7915099999999999e-01 -6.9480475048341370e+00 , -2.7877746467062261e+00 , 2.3819400000000002e+00 , -5.7001099999999999e-02 , 1.9705500000000001e-01 , 9.7873399999999999e-01 -7.2282538978573951e+00 , -3.1096568438406660e+00 , 2.4673437599999999e+00 , -4.9708299999999997e-02 , 1.9631100000000001e-01 , 9.7928099999999996e-01 -7.5410161982763970e+00 , -3.4689668448545730e+00 , 2.5636727200000000e+00 , -5.1300699999999998e-02 , 1.9441500000000000e-01 , 9.7957700000000003e-01 -7.9004742837026827e+00 , -3.8818542056406224e+00 , 2.6728311200000001e+00 , -5.3886600000000000e-02 , 1.9662299999999999e-01 , 9.7899700000000001e-01 -8.3071836586379870e+00 , -4.3485989462490764e+00 , 2.7987928000000002e+00 , -5.9543100000000002e-02 , 1.9317000000000001e-01 , 9.7935700000000003e-01 -8.7596458591853192e+00 , -4.8694517627297644e+00 , 2.9452778400000001e+00 , -6.7582799999999998e-02 , 1.8988800000000000e-01 , 9.7947700000000004e-01 -9.3344169724008061e+00 , -5.5286635164865618e+00 , 3.1162631999999997e+00 , -6.5720399999999998e-02 , 1.8327700000000000e-01 , 9.8086200000000001e-01 -9.9954671616508293e+00 , -6.2878445946931460e+00 , 3.3207376000000002e+00 , -1.0417100000000000e-01 , 1.8948999999999999e-01 , 9.7634100000000001e-01 -1.0734871257695085e+01 , -7.1378944809843521e+00 , 3.5649920000000002e+00 , -1.1740200000000001e-01 , 1.8247800000000000e-01 , 9.7617500000000001e-01 -1.1717486178715594e+01 , -8.2655735348359798e+00 , 3.8696912000000001e+00 , -8.8859599999999997e-02 , 1.8436100000000000e-01 , 9.7883399999999998e-01 -1.2905494903025595e+01 , -9.6299574777187296e+00 , 4.2500608000000000e+00 , -7.5164999999999996e-02 , 1.7695000000000000e-01 , 9.8134600000000005e-01 -1.4257601198229356e+01 , -1.1182433586555645e+01 , 4.7173847999999996e+00 , -7.6518600000000006e-02 , 2.0069799999999999e-01 , 9.7665999999999997e-01 -3.4799728802353641e+01 , -3.4764396055564255e+01 , 1.1943024000000001e+01 , -6.3676699999999997e-01 , 2.0862000000000000e-01 , 7.4229699999999998e-01 -3.4578797247440356e+01 , -3.4497945100355615e+01 , 1.2765144000000001e+01 , -6.3676699999999997e-01 , 2.0862000000000000e-01 , 7.4229699999999998e-01 -5.9278235863805051e+00 , -1.5463340911679762e+00 , 7.3720784000000004e+00 , -5.6215099999999996e-01 , -4.2043799999999999e-02 , -8.2596599999999998e-01 -5.9155385025619189e+00 , -1.5297024347197943e+00 , 7.5100136000000006e+00 , 8.2250500000000004e-01 , -9.8588800000000004e-02 , 5.6014799999999998e-01 -5.8753778024073977e+00 , -1.4824512564600032e+00 , 7.6147207999999997e+00 , -9.1215100000000005e-01 , 3.3295000000000002e-01 , -2.3900800000000000e-01 -5.8695402125936393e+00 , -1.4737552656661763e+00 , 7.7673408000000004e+00 , -8.3591300000000002e-01 , 4.6769100000000002e-01 , -2.8725400000000001e-01 -5.8105032922557749e+00 , -1.4047354908124396e+00 , 7.8496151999999997e+00 , 8.3372100000000005e-01 , -4.0470200000000001e-01 , 3.7566699999999997e-01 -5.5830008924964538e+00 , -1.1393724467441477e+00 , 8.0113976000000005e+00 , 1.3458500000000001e-01 , 1.3787199999999999e-01 , 9.8126400000000003e-01 -5.3671247861253129e+00 , -8.9299241106894200e-01 , 7.8337240000000001e+00 , -4.4432300000000002e-01 , -5.9242300000000003e-01 , 6.7202200000000001e-01 -5.2898413993213378e+00 , -8.0358321862908655e-01 , 7.8710288000000004e+00 , 9.7976499999999994e-02 , -1.2645300000000001e-01 , 9.8712200000000005e-01 -5.2264717173168060e+00 , -7.2962662290156066e-01 , 7.9294247999999996e+00 , 1.7129100000000000e-01 , -2.3971700000000001e-01 , 9.5561200000000002e-01 -5.0955193074611316e+00 , -5.7967051207111941e-01 , 7.8657975999999996e+00 , -2.6850400000000001e-03 , -1.1388400000000000e-01 , 9.9349100000000001e-01 -5.0057503142898945e+00 , -4.7729945231973225e-01 , 7.8698848000000003e+00 , -4.4495000000000001e-01 , -8.4532700000000005e-01 , 2.9570500000000000e-01 -4.9641427821410362e+00 , -4.2741278080436862e-01 , 7.9610408000000001e+00 , -2.6362799999999997e-01 , -9.2917600000000000e-01 , 2.5909799999999999e-01 -5.0240559756771930e+00 , -4.9300779994682387e-01 , 8.2595936000000005e+00 , 9.2108999999999996e-02 , -2.9136499999999999e-01 , 9.5216699999999999e-01 -4.9369443969795661e+00 , -3.9212485669472086e-01 , 8.2674039999999991e+00 , -5.4426799999999997e-01 , 3.7198799999999999e-01 , -7.5192899999999996e-01 -4.8810571898940625e+00 , -3.2723117762609233e-01 , 8.3404120000000006e+00 , 4.0809200000000001e-01 , -5.0961800000000002e-01 , 7.5746300000000000e-01 -4.8479171113750912e+00 , -2.8713096028707552e-01 , 8.4638808000000001e+00 , -4.7023999999999999e-01 , 4.5071499999999998e-01 , -7.5876900000000003e-01 -4.7789882299077453e+00 , -2.0721277205648159e-01 , 8.5085176000000011e+00 , -7.7921300000000004e-01 , 2.6860099999999998e-01 , -5.6628699999999998e-01 -4.7388543843159088e+00 , -1.5930884714410398e-01 , 8.6217527999999994e+00 , 6.6571199999999997e-01 , -1.3848800000000000e-01 , 7.3324500000000004e-01 -4.6297211481482865e+00 , -3.3389878174763687e-02 , 8.5646984000000010e+00 , -6.1340099999999997e-01 , 1.9479099999999999e-01 , -7.6537299999999997e-01 -4.5878554950438595e+00 , 1.6147346960884157e-02 , 8.6751463999999991e+00 , 5.6727300000000003e-01 , -5.6558400000000002e-02 , 8.2158500000000001e-01 -4.5137382126677768e+00 , 1.0140193169944234e-01 , 8.7029975999999998e+00 , 4.5440300000000000e-01 , 3.5736799999999999e-02 , 8.9007899999999995e-01 -4.4399234018878149e+00 , 1.8720596056941030e-01 , 8.7284152000000006e+00 , 1.6323500000000001e-02 , -2.2394100000000000e-01 , 9.7446600000000005e-01 -4.3843744817000747e+00 , 2.5221065988304581e-01 , 8.8073200000000007e+00 , 1.5884999999999999e-01 , 3.8913999999999997e-02 , 9.8653500000000005e-01 -4.2741135691278602e+00 , 3.7882424011527216e-01 , 8.7165384000000010e+00 , 1.1385700000000000e-01 , 2.0798700000000001e-01 , 9.7148199999999996e-01 -4.0570982401859830e+00 , 6.2250085885365003e-01 , 8.2722504000000008e+00 , -9.4555000000000000e-01 , -2.3833000000000000e-02 , -3.2460299999999997e-01 -4.0007989113255977e+00 , 6.8822358776557335e-01 , 8.3229191999999994e+00 , -1.5368899999999999e-01 , -7.4910600000000005e-01 , 6.4437500000000003e-01 -3.8678645669511784e+00 , 8.3874358926219639e-01 , 8.1035104000000011e+00 , 4.3642900000000001e-01 , 4.5515699999999998e-01 , 7.7612000000000003e-01 -3.8258931308261599e+00 , 8.8817447892608459e-01 , 8.1976095999999998e+00 , 7.8315800000000002e-01 , 1.9264999999999999e-01 , 5.9122699999999995e-01 -4.0627530685347129e+00 , 6.3072503580860451e-01 , 9.3893976000000006e+00 , -8.8928900000000000e-01 , -2.1283099999999999e-02 , -4.5684999999999998e-01 -3.5731694355728516e+00 , 1.1721098348290662e+00 , 7.7084040000000007e+00 , -4.5685900000000002e-02 , 3.0963200000000002e-01 , -9.4975799999999999e-01 -3.5022455232072218e+00 , 1.2541746206419961e+00 , 7.6578600000000003e+00 , 1.8096499999999999e-01 , -1.0313300000000000e-01 , 9.7806700000000002e-01 -3.5380442127559029e+00 , 1.2187051340887527e+00 , 8.0902712000000001e+00 , 4.7959099999999998e-02 , -9.9845499999999998e-01 , 2.8053000000000002e-02 -3.4833266936474212e+00 , 1.2827493005924282e+00 , 8.1276800000000016e+00 , 4.2937199999999998e-01 , -8.6574799999999996e-01 , 2.5713999999999998e-01 -3.5326405995650276e+00 , 1.2330601463925928e+00 , 8.7137512000000008e+00 , -5.3858600000000001e-01 , -4.7387099999999999e-01 , 6.9668600000000003e-01 -3.4772754947818907e+00 , 1.2977338870510597e+00 , 8.7910439999999994e+00 , -5.3858600000000001e-01 , -4.7387099999999999e-01 , 6.9668600000000003e-01 -3.2294527179506947e+00 , 1.5694800120518804e+00 , 7.7258448000000008e+00 , 8.1808700000000001e-01 , -2.5802000000000003e-01 , -5.1396500000000001e-01 -3.1602011286768752e+00 , 1.6472210908980744e+00 , 7.6436847999999999e+00 , 7.4152899999999999e-01 , 3.9387499999999998e-01 , -5.4313699999999998e-01 -3.1124609302206094e+00 , 1.7035112735938127e+00 , 7.6915351999999997e+00 , -4.0720699999999999e-01 , -7.5381600000000004e-01 , 5.1569799999999999e-01 -3.1213360953710261e+00 , 1.6991312682187425e+00 , 8.1776416000000012e+00 , 2.9065800000000003e-01 , -2.0279300000000000e-01 , -9.3508999999999998e-01 -3.0045216550054672e+00 , 1.8281102540992828e+00 , 7.7019352000000003e+00 , 3.3775900000000002e-03 , 5.6462699999999998e-02 , 9.9839900000000004e-01 -2.9516545178553981e+00 , 1.8893184644368690e+00 , 7.7151224000000003e+00 , -1.5719800000000000e-01 , -3.4926800000000002e-01 , -9.2374299999999998e-01 -2.8962625087952940e+00 , 1.9525754186380742e+00 , 7.7063239999999995e+00 , 1.2792300000000001e-01 , -1.6768100000000000e-01 , -9.7750599999999999e-01 -2.8327980679205620e+00 , 2.0237591153169290e+00 , 7.5928496000000001e+00 , -7.9601900000000003e-02 , -3.8360100000000003e-01 , -9.2006200000000005e-01 -2.7806674496498687e+00 , 2.0840770144176619e+00 , 7.5912480000000002e+00 , 5.2679200000000004e-01 , -3.8140900000000000e-01 , 7.5961699999999999e-01 -2.8899407056162154e+00 , 1.9932264238797281e+00 , 1.0209874400000000e+01 , 3.9988400000000002e-01 , 2.5946900000000001e-01 , 8.7907299999999999e-01 -2.7810314628993380e+00 , 2.1120412842829199e+00 , 9.6590592000000015e+00 , -5.0210999999999995e-01 , 5.2892600000000001e-01 , 6.8419500000000000e-01 -2.7006853137657192e+00 , 2.2031950388742079e+00 , 9.5409672000000008e+00 , 1.3399700000000000e-01 , 6.6194500000000001e-01 , 7.3747799999999997e-01 -2.6121305489828592e+00 , 2.2975293037417233e+00 , 9.0258240000000001e+00 , -3.9053700000000002e-01 , -6.5537800000000002e-01 , 6.4649900000000005e-01 -2.5521096244036006e+00 , 2.3736333611256901e+00 , 9.4961535999999995e+00 , 4.7491899999999998e-01 , 3.2109300000000002e-01 , 8.1935999999999998e-01 -2.4776029806402016e+00 , 2.4569297175054334e+00 , 9.3719256000000009e+00 , -3.8141700000000001e-01 , 3.6189900000000003e-01 , 8.5061699999999996e-01 -2.4127350447523432e+00 , 2.5203743160592009e+00 , 8.4766207999999992e+00 , 8.2676000000000005e-01 , -4.8082999999999998e-01 , -2.9201100000000002e-01 -2.3494364558173788e+00 , 2.5935038292131827e+00 , 8.5256775999999999e+00 , -3.9669199999999999e-01 , -1.5383200000000000e-01 , 9.0497000000000005e-01 -2.2882275743679337e+00 , 2.6632972840970250e+00 , 8.4795744000000006e+00 , 7.9212199999999999e-01 , 1.3051199999999999e-01 , 5.9624699999999997e-01 -2.1940012951092367e+00 , 2.7834899024554973e+00 , 9.2721167999999992e+00 , -8.7939799999999999e-02 , 2.0302899999999999e-01 , 9.7521599999999997e-01 -2.1182923041814767e+00 , 2.8717177712475084e+00 , 9.3565752000000000e+00 , 8.5867499999999997e-01 , -4.1730299999999998e-01 , -2.9754900000000001e-01 -2.0484076868110912e+00 , 2.9522518814994978e+00 , 9.3144863999999998e+00 , 2.0219799999999999e-01 , -5.7506800000000002e-01 , 7.9272500000000001e-01 -1.7400989927310007e+00 , 3.3476227744875224e+00 , 1.2407487999999999e+01 , -9.0550200000000003e-01 , -3.5301100000000002e-01 , -2.3547699999999999e-01 -1.6183131930300327e+00 , 3.4908947723780708e+00 , 1.2560264000000000e+01 , 4.9604199999999998e-01 , 5.9560100000000005e-01 , 6.3182400000000005e-01 -1.5309804442674708e+00 , 3.5873821574036286e+00 , 1.2319587200000001e+01 , -9.5175100000000001e-01 , -2.2691100000000000e-01 , -2.0659500000000000e-01 -1.4933986417964857e+00 , 3.6221782102678466e+00 , 1.1677907200000002e+01 , -4.9305199999999999e-01 , -6.5200300000000000e-01 , 5.7601400000000003e-01 -3.8639819204038073e+00 , 6.7007161683823924e-01 , 1.4365311200000002e+00 , -1.1627899999999999e-01 , 2.9265099999999999e-01 , 9.4912300000000005e-01 -3.9031464989580291e+00 , 6.2155736233474101e-01 , 1.4518076799999999e+00 , -7.4992100000000006e-02 , 2.6700400000000002e-01 , 9.6077299999999999e-01 -3.9489708170605509e+00 , 5.6662546831278959e-01 , 1.4629970400000001e+00 , -4.2520200000000001e-02 , 1.9149400000000000e-01 , 9.8057200000000000e-01 -3.9934995638555613e+00 , 5.1107015716951687e-01 , 1.4760864800000000e+00 , -4.7933700000000003e-02 , 2.0356299999999999e-01 , 9.7788799999999998e-01 -4.0388473059142491e+00 , 4.5587187201699875e-01 , 1.4911227999999999e+00 , -5.3959899999999998e-02 , 1.7607200000000001e-01 , 9.8289700000000002e-01 -4.0850099109145344e+00 , 4.0105099824005430e-01 , 1.5082068799999999e+00 , -9.0772300000000000e-02 , 2.0342099999999999e-01 , 9.7487500000000005e-01 -4.1355832613731938e+00 , 3.3797709315446811e-01 , 1.5221719999999999e+00 , -7.6675499999999994e-02 , 2.2792499999999999e-01 , 9.7065500000000005e-01 -4.1812004275130317e+00 , 2.8192083190409112e-01 , 1.5435107200000000e+00 , -5.8471900000000000e-02 , 2.0916000000000001e-01 , 9.7613200000000000e-01 -4.2390340632262395e+00 , 2.1208411688604367e-01 , 1.5570567200000001e+00 , -6.3821799999999998e-02 , 2.1499599999999999e-01 , 9.7452700000000003e-01 -4.2908609767384824e+00 , 1.4931737923149879e-01 , 1.5780543200000001e+00 , -7.8350299999999998e-02 , 2.1571000000000001e-01 , 9.7330899999999998e-01 -4.3480344353625302e+00 , 7.8444860153337626e-02 , 1.5968668799999999e+00 , -8.7038000000000004e-02 , 2.2432800000000000e-01 , 9.7061900000000001e-01 -4.4003062474698798e+00 , 1.5577300477030986e-02 , 1.6227483199999999e+00 , -7.7429999999999999e-02 , 2.1257599999999999e-01 , 9.7407200000000005e-01 -4.4645420652886578e+00 , -6.2809122239359194e-02 , 1.6426632800000001e+00 , 7.5018100000000004e-02 , -1.9933500000000001e-01 , -9.7705600000000004e-01 -4.5284438611137094e+00 , -1.4059472855475308e-01 , 1.6655120800000001e+00 , -6.3146400000000005e-02 , 1.9875100000000001e-01 , 9.7801400000000005e-01 -4.5919551690946596e+00 , -2.1880967096647508e-01 , 1.6913987200000000e+00 , -5.4078099999999997e-02 , 2.1232899999999999e-01 , 9.7570100000000004e-01 -4.6748874621479519e+00 , -3.1964842934500215e-01 , 1.7092804799999999e+00 , -5.4543300000000003e-02 , 1.7790100000000000e-01 , 9.8253599999999996e-01 -4.7573369806742898e+00 , -4.2072300077686586e-01 , 1.7311121599999999e+00 , -7.9524100000000000e-02 , 1.7774799999999999e-01 , 9.8085800000000001e-01 -4.8347750809848842e+00 , -5.1471684417081498e-01 , 1.7607230400000000e+00 , -8.4784799999999994e-02 , 1.7511499999999999e-01 , 9.8089099999999996e-01 -4.9238124488231598e+00 , -6.2358190306388517e-01 , 1.7875030400000000e+00 , -7.3027300000000003e-02 , 1.9050400000000001e-01 , 9.7896600000000000e-01 -5.0198289880250631e+00 , -7.4091154271427095e-01 , 1.8158940000000001e+00 , -7.4969700000000000e-02 , 2.0036999999999999e-01 , 9.7684800000000005e-01 -5.1087813725659412e+00 , -8.5003789362628357e-01 , 1.8519123200000001e+00 , 6.5625000000000003e-02 , -2.0517400000000000e-01 , -9.7652300000000003e-01 -5.2176753981687991e+00 , -9.8200086403057618e-01 , 1.8842022400000000e+00 , -6.3273300000000005e-02 , 1.8049299999999999e-01 , 9.8153900000000005e-01 -5.3387864623887040e+00 , -1.1303121616566236e+00 , 1.9170310880000001e+00 , -5.3402400000000003e-02 , 1.8647100000000000e-01 , 9.8100799999999999e-01 -5.4665857891347702e+00 , -1.2865952109334153e+00 , 1.9538986720000000e+00 , -6.8283399999999994e-02 , 1.9185400000000000e-01 , 9.7904500000000005e-01 -5.5882239785221817e+00 , -1.4344706977544308e+00 , 1.9995304431200001e+00 , -6.9385199999999994e-02 , 1.8701499999999999e-01 , 9.7990400000000000e-01 -5.7420523979862290e+00 , -1.6226813918218861e+00 , 2.0415711920000001e+00 , -6.2657599999999994e-02 , 1.9425000000000001e-01 , 9.7894899999999996e-01 -5.8885666628342159e+00 , -1.8022407330233228e+00 , 2.0933636080000002e+00 , -6.9835599999999998e-02 , 2.0158300000000001e-01 , 9.7697900000000004e-01 -6.0552265662360005e+00 , -2.0054336517732327e+00 , 2.1481365600000002e+00 , -6.0889899999999997e-02 , 1.9556399999999999e-01 , 9.7879899999999997e-01 -6.2345556991737237e+00 , -2.2239600315207690e+00 , 2.2085303999999999e+00 , -6.5065600000000001e-02 , 1.9703999999999999e-01 , 9.7823400000000005e-01 -6.4336645005280433e+00 , -2.4665655779758451e+00 , 2.2748428800000000e+00 , -5.3453399999999998e-02 , 1.9368199999999999e-01 , 9.7960700000000001e-01 -6.6712563401113902e+00 , -2.7567836046471763e+00 , 2.3449409600000002e+00 , -5.9168199999999997e-02 , 2.0304000000000000e-01 , 9.7738100000000006e-01 -6.9020752045659259e+00 , -3.0386119792789694e+00 , 2.4288647999999999e+00 , -5.6935399999999997e-02 , 2.0489900000000000e-01 , 9.7712600000000005e-01 -7.1844512877568087e+00 , -3.3830283078751844e+00 , 2.5188570399999999e+00 , -5.2532900000000000e-02 , 2.0133400000000001e-01 , 9.7811300000000001e-01 -7.4991173236745903e+00 , -3.7676959597919391e+00 , 2.6215029599999999e+00 , -5.5615100000000001e-02 , 2.0090000000000000e-01 , 9.7803200000000001e-01 -7.8520330597366401e+00 , -4.1988773473057570e+00 , 2.7385872000000000e+00 , -5.7461800000000000e-02 , 1.9693300000000000e-01 , 9.7873200000000005e-01 -8.2767530330926000e+00 , -4.7168327378836263e+00 , 2.8724372800000002e+00 , -6.1764100000000002e-02 , 1.9486300000000001e-01 , 9.7888399999999998e-01 -8.7663995904954000e+00 , -5.3137030519424702e+00 , 3.0290633600000003e+00 , -6.3481700000000002e-02 , 1.8932199999999999e-01 , 9.7986099999999998e-01 -9.3325266931043043e+00 , -6.0057587986793131e+00 , 3.2143664000000003e+00 , -6.2570200000000006e-02 , 1.8787499999999999e-01 , 9.8019800000000001e-01 -1.0028501726582476e+01 , -6.8551997700085874e+00 , 3.4367912000000000e+00 , -9.0026999999999996e-02 , 1.9303699999999999e-01 , 9.7705299999999995e-01 -1.0832665838064580e+01 , -7.8368951730307881e+00 , 3.7058080000000002e+00 , -8.0621300000000007e-02 , 1.8329400000000001e-01 , 9.7974700000000003e-01 -1.1797595664702383e+01 , -9.0148498785372162e+00 , 4.0361327999999999e+00 , -8.9087700000000006e-02 , 1.8267000000000000e-01 , 9.7912999999999994e-01 -1.3243600055107638e+01 , -1.0780472046005695e+01 , 4.4830623999999997e+00 , -8.8312299999999996e-02 , 2.1212000000000000e-01 , 9.7324500000000003e-01 -1.4439760586218441e+01 , -1.2240192865087126e+01 , 4.9714359999999997e+00 , -8.8432899999999995e-02 , 2.0533000000000001e-01 , 9.7468900000000003e-01 -3.4097304581025568e+01 , -3.6228343691801179e+01 , 1.3428248000000000e+01 , -6.3676699999999997e-01 , 2.0862000000000000e-01 , 7.4229699999999998e-01 -5.3933835727427155e+00 , -1.1713049161602185e+00 , 7.5067791999999995e+00 , 6.6125699999999998e-01 , 3.3045000000000002e-01 , -6.7345600000000005e-01 -5.3068215320425960e+00 , -1.0644954608960382e+00 , 7.5282864000000007e+00 , 5.5369199999999996e-01 , 4.0848899999999999e-01 , -7.2564600000000001e-01 -5.2385788480195101e+00 , -9.8178529256030478e-01 , 7.5763864000000005e+00 , 5.5369199999999996e-01 , 4.0848899999999999e-01 , -7.2564600000000001e-01 -5.1611764193669298e+00 , -8.8739159177575999e-01 , 7.6067752000000004e+00 , -5.3687200000000002e-01 , -6.5863799999999995e-01 , 5.2722300000000000e-01 -5.1334703331640670e+00 , -8.5294939044135676e-01 , 7.7191160000000005e+00 , -3.7550400000000000e-01 , -8.5681099999999999e-01 , 3.5337200000000002e-01 -5.1435752359318130e+00 , -8.6338017745166429e-01 , 7.9014176000000003e+00 , 3.4277299999999999e-01 , -3.6561900000000003e-01 , 8.6534900000000003e-01 -5.0427764898076823e+00 , -7.4083342065164537e-01 , 7.8873151999999997e+00 , -5.9166499999999997e-02 , 1.4136499999999999e-01 , -9.8818799999999996e-01 -5.9027185504115547e+00 , -1.7830620910213892e+00 , 9.7123175999999987e+00 , -6.7146600000000001e-01 , 5.0174200000000002e-01 , 5.4533399999999999e-01 -4.8986984331508800e+00 , -5.6318905154640397e-01 , 7.9530431999999998e+00 , 7.4128600000000000e-01 , -4.9143300000000001e-01 , 4.5715299999999998e-01 -4.9844352579808540e+00 , -6.6718394810846782e-01 , 8.3089623999999986e+00 , 2.7177800000000002e-01 , -2.2475600000000001e-01 , 9.3574700000000000e-01 -4.8795826708688210e+00 , -5.3950588060212779e-01 , 8.2772943999999988e+00 , 3.7909999999999999e-01 , -6.0614999999999997e-01 , 6.9918899999999995e-01 -4.8411010082368744e+00 , -4.9163844496284304e-01 , 8.3854752000000001e+00 , 5.9044099999999999e-01 , -3.6027999999999999e-01 , 7.2220300000000004e-01 -4.7975376889754902e+00 , -4.3791423305153954e-01 , 8.4847016000000011e+00 , -5.2472900000000000e-01 , 3.1431999999999999e-01 , -7.9111500000000001e-01 -4.7080782884263419e+00 , -3.2911350137630135e-01 , 8.4786175999999998e+00 , -4.1014099999999998e-01 , 6.0944399999999999e-01 , -6.7849999999999999e-01 -4.6872750637414065e+00 , -3.0281178080315074e-01 , 8.6363231999999996e+00 , -4.4074700000000000e-01 , 7.6151700000000000e-01 , -4.7521900000000000e-01 -4.6735004601722734e+00 , -2.8516623598205770e-01 , 8.8211207999999992e+00 , -8.7481100000000001e-01 , 2.0348400000000000e-01 , -4.3965900000000002e-01 -4.6363163134885959e+00 , -2.3898830125250559e-01 , 8.9528056000000014e+00 , 1.7194599999999999e-01 , -6.1906799999999995e-01 , 7.6628300000000005e-01 -4.4943001031904970e+00 , -6.5181196317620760e-02 , 8.7943303999999998e+00 , 5.5571499999999996e-01 , -4.9118400000000000e-02 , 8.2992100000000002e-01 -4.4494549741232508e+00 , -1.0316098951243191e-02 , 8.9042792000000013e+00 , 5.6113299999999999e-01 , 1.2239300000000000e-01 , 8.1862699999999999e-01 -4.3175890116771747e+00 , 1.4896275109385892e-01 , 8.7549248000000013e+00 , 2.1715499999999999e-01 , 7.9665700000000006e-02 , 9.7288100000000000e-01 -4.2373418218677683e+00 , 2.4786271023324957e-01 , 8.7490904000000000e+00 , 1.9762500000000000e-01 , 2.1929799999999999e-01 , 9.5543299999999998e-01 -3.9758309592547021e+00 , 5.6410103417620516e-01 , 8.1389744000000004e+00 , -5.5564599999999997e-01 , 7.4650700000000003e-01 , 3.6603900000000000e-01 -3.9306095181833811e+00 , 6.2014200915338624e-01 , 8.2177439999999997e+00 , -5.6904399999999999e-01 , -2.6219999999999999e-01 , 7.7938399999999997e-01 -3.8736466698726488e+00 , 6.9002790322886098e-01 , 8.2573159999999994e+00 , 6.1395200000000005e-01 , 6.5871400000000002e-01 , -4.3492500000000001e-01 -3.8569354383330472e+00 , 7.1142888892461431e-01 , 8.4495392000000002e+00 , -3.2609500000000002e-01 , -7.7051800000000004e-01 , 5.4769000000000001e-01 -3.7708546750425187e+00 , 8.1591647648045784e-01 , 8.3806080000000005e+00 , 4.8947200000000003e-02 , -2.8714099999999998e-01 , 9.5663699999999996e-01 -3.5420141928899982e+00 , 1.0930629690689835e+00 , 7.6941144000000001e+00 , 2.6665499999999998e-01 , 5.8404500000000004e-01 , 7.6667200000000002e-01 -3.4885053248940414e+00 , 1.1586828263906150e+00 , 7.7132712000000003e+00 , -5.0325799999999998e-01 , -2.0893800000000001e-01 , -8.3849700000000005e-01 -3.4370715178381075e+00 , 1.2216565889567259e+00 , 7.7408104000000000e+00 , -7.3882400000000004e-01 , 3.5539599999999999e-01 , -5.7256799999999997e-01 -3.4151809764983456e+00 , 1.2483491233138415e+00 , 7.9160504000000005e+00 , -3.7701899999999999e-01 , -7.8882099999999999e-01 , 4.8540499999999998e-01 -3.3948700395304887e+00 , 1.2735833679089890e+00 , 8.1212839999999993e+00 , -1.1049399999999999e-02 , -9.2568499999999998e-01 , 3.7813300000000000e-01 -3.3321417181694759e+00 , 1.3507101754977229e+00 , 8.1059751999999996e+00 , 4.2312300000000003e-01 , 8.9980099999999996e-01 , -1.0641900000000000e-01 -3.5311386893278209e+00 , 1.1158803689179817e+00 , 9.6812736000000008e+00 , -6.3220799999999999e-01 , -5.4444800000000004e-01 , -5.5126200000000003e-01 -3.1468567486029144e+00 , 1.5756419546992961e+00 , 7.6650255999999999e+00 , -5.5868399999999996e-01 , -1.4097399999999999e-01 , 8.1731200000000004e-01 -3.0937858990043230e+00 , 1.6402003135455785e+00 , 7.6631743999999999e+00 , -2.6600900000000000e-01 , -1.3524000000000000e-02 , 9.6387599999999996e-01 -3.0337013035432534e+00 , 1.7134985110893517e+00 , 7.6083559999999997e+00 , -1.9655800000000001e-01 , -6.7088599999999998e-01 , 7.1503600000000000e-01 -3.0040500985876850e+00 , 1.7507362414429339e+00 , 7.7973864000000006e+00 , -2.1458800000000000e-01 , -3.0302800000000002e-01 , -9.2850800000000000e-01 -2.9494754638780289e+00 , 1.8176352208860105e+00 , 7.7910320000000004e+00 , 4.4292500000000001e-01 , -1.4444500000000001e-02 , 8.9644299999999999e-01 -2.8934117370143952e+00 , 1.8854622220358168e+00 , 7.7626192000000005e+00 , 2.3016500000000001e-01 , -2.6612500000000000e-01 , -9.3605700000000003e-01 -2.8361363238436934e+00 , 1.9563246854281928e+00 , 7.7015712000000001e+00 , -9.6729999999999997e-02 , 4.9548799999999997e-02 , -9.9407699999999999e-01 -2.7903094528668588e+00 , 2.0119235268157087e+00 , 7.7938296000000005e+00 , -1.2137400000000000e-01 , -7.3807800000000007e-02 , 9.8985900000000004e-01 -2.7321477102273724e+00 , 2.0834573665537834e+00 , 7.6884879999999995e+00 , 5.1856000000000002e-01 , -6.7622000000000004e-01 , 5.2327900000000005e-01 -2.7393456211536646e+00 , 2.0794992723376784e+00 , 8.8772808000000012e+00 , -9.4163799999999998e-01 , 2.0568500000000001e-01 , 2.6648100000000002e-01 -2.7000996690947487e+00 , 2.1305402955692077e+00 , 9.5175255999999990e+00 , 4.9991400000000003e-01 , -4.4713000000000003e-01 , -7.4172800000000005e-01 -2.6110870282579963e+00 , 2.2360744220777189e+00 , 8.8786848000000003e+00 , -2.7483299999999999e-01 , 4.0615499999999999e-01 , -8.7149600000000005e-01 -2.5582118407597920e+00 , 2.3040543362900987e+00 , 9.5473736000000002e+00 , 1.9770900000000001e-02 , -3.2421800000000001e-01 , 9.4577599999999995e-01 -2.4838050052323131e+00 , 2.3928836115123380e+00 , 9.0184712000000005e+00 , -9.3330199999999996e-01 , -3.5759400000000002e-01 , 3.2776899999999998e-02 -2.4194294978132431e+00 , 2.4704776880178012e+00 , 8.8101279999999988e+00 , -4.5138299999999998e-01 , -7.8018699999999996e-01 , -4.3308400000000002e-01 -2.3584804819335874e+00 , 2.5432398670522574e+00 , 8.6417831999999990e+00 , 6.6535299999999997e-01 , -6.9754099999999997e-01 , 2.6597300000000001e-01 -2.2993563369836987e+00 , 2.6153649321112824e+00 , 8.5444496000000001e+00 , 9.7859099999999999e-01 , 5.5474900000000001e-02 , 1.9819600000000001e-01 -2.2100774630796449e+00 , 2.7272902118294873e+00 , 9.2864687999999997e+00 , 8.6185300000000006e-02 , 5.0237299999999996e-01 , 8.6034500000000003e-01 -2.1444729942561098e+00 , 2.8082876520814715e+00 , 9.2265231999999990e+00 , 3.5682000000000003e-01 , -2.7995999999999999e-01 , -8.9123600000000003e-01 -2.0695933177666590e+00 , 2.9004284380478698e+00 , 9.3305752000000002e+00 , -4.9656400000000001e-01 , 5.3517499999999996e-01 , -6.8338299999999996e-01 -1.7251122575423330e+00 , 3.3388333668641041e+00 , 1.3140584000000000e+01 , -7.8617199999999998e-01 , -6.1790199999999995e-01 , 1.1441099999999999e-02 -1.6342179529473326e+00 , 3.4487439502555910e+00 , 1.2870912000000001e+01 , -9.5192100000000002e-01 , -3.0068200000000000e-01 , -5.8622300000000002e-02 -1.5523157690407088e+00 , 3.5474675983425783e+00 , 1.2568688000000000e+01 , -5.7196899999999995e-01 , -6.4979200000000004e-01 , -5.0062300000000004e-01 -1.3780901420812124e+00 , 3.7634948724803801e+00 , 1.3197992000000001e+01 , -9.5477199999999995e-01 , -2.5045299999999998e-01 , 1.6026299999999999e-01 -1.7215352016522929e+00 , 3.3262445779197174e+00 , 9.2933120000000002e+00 , 5.3807700000000003e-01 , -8.3100099999999999e-01 , 1.4110700000000001e-01 -3.8399805775680882e+00 , 6.1101325077616209e-01 , 1.4439744000000001e+00 , -1.2877200000000000e-01 , 1.8945300000000001e-01 , 9.7340899999999997e-01 -3.8779663892045528e+00 , 5.6166580304561520e-01 , 1.4601412000000000e+00 , -1.0172900000000000e-01 , 1.9724800000000001e-01 , 9.7506099999999996e-01 -3.9215560382316403e+00 , 5.0488019800969708e-01 , 1.4721968799999998e+00 , -1.0423300000000001e-01 , 1.7816000000000001e-01 , 9.7846500000000003e-01 -3.9601567205888446e+00 , 4.5516926064136509e-01 , 1.4919319199999999e+00 , -5.6286400000000000e-02 , 1.7632900000000001e-01 , 9.8272099999999996e-01 -4.0148446704439991e+00 , 3.8477977572323185e-01 , 1.4967762400000000e+00 , -5.6281299999999999e-02 , 1.7487500000000000e-01 , 9.8298099999999999e-01 -4.0587418901788297e+00 , 3.2815202207228800e-01 , 1.5149304799999999e+00 , 8.3325200000000002e-02 , -1.9709099999999999e-01 , -9.7683799999999998e-01 -4.1023735529906817e+00 , 2.7089741507273835e-01 , 1.5352125599999999e+00 , -8.9830900000000005e-02 , 2.0524700000000001e-01 , 9.7457899999999997e-01 -4.1514820561109946e+00 , 2.0641236071250479e-01 , 1.5523964800000001e+00 , -1.0997300000000000e-01 , 1.8913700000000000e-01 , 9.7577300000000000e-01 -4.2013460559539029e+00 , 1.4238818731537028e-01 , 1.5720327199999999e+00 , -9.9794200000000000e-02 , 1.8064300000000000e-01 , 9.7847300000000004e-01 -4.2565811186155162e+00 , 7.0241979431880708e-02 , 1.5893830400000000e+00 , 1.0568500000000000e-01 , -1.9718500000000000e-01 , -9.7465299999999999e-01 -4.3125130078755216e+00 , -2.4102776703354145e-03 , 1.6095933600000001e+00 , -1.1066700000000000e-01 , 2.1569900000000000e-01 , 9.7016899999999995e-01 -4.3681396632835696e+00 , -7.4551386442201384e-02 , 1.6323329600000001e+00 , -1.0542500000000000e-01 , 2.0030000000000001e-01 , 9.7404599999999997e-01 -4.4300731811637535e+00 , -1.5466727981539519e-01 , 1.6537226400000000e+00 , -8.7935200000000005e-02 , 1.6959099999999999e-01 , 9.8158400000000001e-01 -4.4972397378804825e+00 , -2.4159613449885686e-01 , 1.6740369600000000e+00 , -1.0253900000000001e-01 , 2.0125399999999999e-01 , 9.7415700000000005e-01 -4.5594140298128352e+00 , -3.2253336552235190e-01 , 1.7019308000000000e+00 , 9.6457000000000001e-02 , -1.6034799999999999e-01 , -9.8233599999999999e-01 -4.6389287545508555e+00 , -4.2603864275707526e-01 , 1.7216710399999999e+00 , -7.8465300000000002e-02 , 1.4107400000000000e-01 , 9.8688500000000001e-01 -4.7245187991425457e+00 , -5.3710934507407959e-01 , 1.7419822400000000e+00 , 1.1167100000000001e-01 , -1.5123500000000001e-01 , -9.8216999999999999e-01 -4.7985569542668518e+00 , -6.3270498254038410e-01 , 1.7734484799999999e+00 , -9.8363699999999998e-02 , 1.8152399999999999e-01 , 9.7845499999999996e-01 -4.8906352691638446e+00 , -7.5248833752149213e-01 , 1.7994204000000000e+00 , -1.0255499999999999e-01 , 1.8990299999999999e-01 , 9.7643199999999997e-01 -4.9766875703157147e+00 , -8.6405958113806225e-01 , 1.8331444800000001e+00 , -9.2618300000000001e-02 , 1.8516600000000000e-01 , 9.7833300000000001e-01 -5.0751188937916867e+00 , -9.9230710806894873e-01 , 1.8658899199999999e+00 , -8.9976600000000004e-02 , 1.7275900000000000e-01 , 9.8084600000000000e-01 -5.1804302073705166e+00 , -1.1277447148675828e+00 , 1.9012544960000000e+00 , 8.1409800000000004e-02 , -1.8235399999999999e-01 , -9.7985699999999998e-01 -5.2904380816643997e+00 , -1.2723218409889059e+00 , 1.9397014239999999e+00 , 8.2465100000000000e-02 , -1.7383699999999999e-01 , -9.8131599999999997e-01 -5.4200782308462276e+00 , -1.4392040528873391e+00 , 1.9770512560000000e+00 , -8.3345500000000003e-02 , 1.7947500000000000e-01 , 9.8022600000000004e-01 -5.5551855966877826e+00 , -1.6158866517615809e+00 , 2.0196352000000002e+00 , -8.6756399999999997e-02 , 1.8500100000000000e-01 , 9.7890100000000002e-01 -5.6915354986829234e+00 , -1.7911607199733832e+00 , 2.0694517200000000e+00 , -8.7387199999999998e-02 , 1.9334799999999999e-01 , 9.7723099999999996e-01 -5.8386408900712592e+00 , -1.9831112206739672e+00 , 2.1231245599999999e+00 , -7.9851099999999994e-02 , 1.9069200000000000e-01 , 9.7839699999999996e-01 -6.0121299196689133e+00 , -2.2076390798672163e+00 , 2.1788332000000001e+00 , -7.3547899999999999e-02 , 1.8934000000000001e-01 , 9.7915300000000005e-01 -6.1970807618557657e+00 , -2.4482969548375868e+00 , 2.2412560799999999e+00 , -7.0777099999999996e-02 , 1.9755500000000001e-01 , 9.7773399999999999e-01 -6.4007012302452813e+00 , -2.7128451637765876e+00 , 2.3102798400000002e+00 , -6.3975299999999999e-02 , 1.9618800000000000e-01 , 9.7847700000000004e-01 -6.6228172203897477e+00 , -3.0010006536833815e+00 , 2.3873209599999998e+00 , -7.8585500000000003e-02 , 1.9889200000000001e-01 , 9.7686499999999998e-01 -6.8641993882338364e+00 , -3.3134242922110824e+00 , 2.4745311999999999e+00 , -7.4788300000000002e-02 , 1.9193700000000000e-01 , 9.7855400000000003e-01 -7.1547512208835320e+00 , -3.6911058397866876e+00 , 2.5697920800000000e+00 , -7.4862200000000004e-02 , 1.9029799999999999e-01 , 9.7886799999999996e-01 -7.4702225128448134e+00 , -4.0999000366294025e+00 , 2.6793352800000001e+00 , 7.8115699999999996e-02 , -1.8746199999999999e-01 , -9.7916099999999995e-01 -7.8545722090506427e+00 , -4.5989901128780168e+00 , 2.8033542400000000e+00 , 7.5987600000000002e-02 , -1.8685499999999999e-01 , -9.7944399999999998e-01 -8.2815075602541270e+00 , -5.1531061818902373e+00 , 2.9479277599999998e+00 , -8.4055900000000003e-02 , 1.8673500000000001e-01 , 9.7880800000000001e-01 -8.7832051786738816e+00 , -5.8051860347659003e+00 , 3.1176984000000001e+00 , -7.3863499999999999e-02 , 1.8553700000000001e-01 , 9.7985699999999998e-01 -9.3977485158430838e+00 , -6.6021272876555077e+00 , 3.3197912000000001e+00 , -7.0325200000000004e-02 , 1.8684300000000001e-01 , 9.7986899999999999e-01 -1.0059859320468837e+01 , -7.4623379188452894e+00 , 3.5604472000000000e+00 , -8.4791599999999995e-02 , 1.9082800000000000e-01 , 9.7795500000000002e-01 -1.1118395383115509e+01 , -8.8353521397521497e+00 , 3.8754944000000000e+00 , -8.2948900000000006e-02 , 1.7587000000000000e-01 , 9.8091300000000003e-01 -1.2020415221479496e+01 , -1.0006215781359002e+01 , 4.2330672000000007e+00 , -9.8399100000000003e-02 , 1.8203100000000000e-01 , 9.7835700000000003e-01 -1.3213923526354193e+01 , -1.1555717150048867e+01 , 4.6866319999999995e+00 , -8.4115400000000007e-02 , 2.1781100000000000e-01 , 9.7236000000000000e-01 -1.4092818106874180e+01 , -1.2735937584048868e+01 , 1.3757408000000000e+01 , 2.7388299999999999e-01 , -9.6161399999999997e-01 , -1.6959399999999999e-02 -5.2956748718277957e+00 , -1.3032858704628709e+00 , 7.6266496000000004e+00 , 1.3092200000000001e-01 , -3.4493200000000002e-01 , 9.2945199999999994e-01 -5.1487748590591984e+00 , -1.1126626240493604e+00 , 7.5453736000000005e+00 , -2.5395099999999998e-01 , -1.3130500000000001e-01 , 9.5826299999999998e-01 -5.0480577317479316e+00 , -9.8151459939109076e-01 , 7.5318536000000007e+00 , -2.6973300000000000e-01 , -5.8258299999999996e-01 , 7.6670799999999995e-01 -4.9824984770227205e+00 , -8.9775111985570577e-01 , 7.5752423999999996e+00 , -2.6973300000000000e-01 , -5.8258299999999996e-01 , 7.6670799999999995e-01 -4.9088688582715463e+00 , -8.0239101368631793e-01 , 7.6006391999999998e+00 , 1.7180799999999999e-01 , -9.1838900000000001e-01 , 3.5643100000000000e-01 -4.9673141053068566e+00 , -8.7917102392714508e-01 , 7.8750224000000006e+00 , -7.2460400000000003e-01 , 6.0636299999999999e-01 , 3.2752599999999998e-01 -5.4462765667262740e+00 , -1.5047889790505686e+00 , 8.9934072000000000e+00 , -8.0377799999999999e-01 , 5.8755500000000005e-01 , 9.3382000000000007e-02 -5.3548883385550567e+00 , -1.3868394800264285e+00 , 9.0217679999999998e+00 , -8.0377799999999999e-01 , 5.8755500000000005e-01 , 9.3382000000000007e-02 -5.0122694646582158e+00 , -9.3955299203013309e-01 , 8.5125007999999998e+00 , -3.0923200000000001e-01 , 6.7862199999999995e-01 , -6.6621900000000001e-01 -4.8213501850097833e+00 , -6.9086234183651651e-01 , 8.2936639999999997e+00 , 5.2627599999999997e-01 , -8.1454300000000002e-01 , 2.4403400000000000e-01 -4.8722622698896014e+00 , -7.5869582546982350e-01 , 8.6055184000000011e+00 , 3.7200299999999997e-01 , 8.8387700000000002e-01 , 2.8350399999999998e-01 -4.7411411197036246e+00 , -5.8780554859865042e-01 , 8.5034528000000016e+00 , -7.1224399999999999e-01 , -2.4352699999999999e-01 , -6.5833399999999997e-01 -4.6362590041083305e+00 , -4.5270540002102955e-01 , 8.4559144000000011e+00 , 2.0307700000000001e-01 , -3.1629099999999999e-01 , 9.2667100000000002e-01 -4.5828089222260235e+00 , -3.8303063552501726e-01 , 8.5268423999999996e+00 , -1.4160000000000000e-01 , 1.3310200000000000e-01 , -9.8093500000000000e-01 -4.5406754747397660e+00 , -3.2934553149901324e-01 , 8.6314768000000015e+00 , 3.1759199999999999e-01 , -8.1540999999999997e-01 , 4.8398600000000003e-01 -4.1700252986799899e+00 , 1.5430158827851237e-01 , 7.8329024000000000e+00 , -2.8499900000000000e-01 , -9.4553699999999996e-01 , 1.5727400000000000e-01 -4.4516070757700303e+00 , -2.1483082064242609e-01 , 8.8382807999999997e+00 , -5.9257499999999996e-01 , -1.2813600000000000e-01 , -7.9525900000000005e-01 -4.3504742523438047e+00 , -8.3830730902303863e-02 , 8.7765255999999994e+00 , -4.4344899999999998e-01 , -2.5311099999999997e-01 , -8.5981799999999997e-01 -4.3278412763697993e+00 , -5.4313224170194907e-02 , 8.9498104000000005e+00 , 3.2069900000000001e-01 , 1.6616000000000000e-01 , 9.3249300000000002e-01 -4.2025150116488552e+00 , 1.0861521198622226e-01 , 8.7988752000000012e+00 , 8.2862000000000005e-02 , 3.5765400000000003e-01 , 9.3017099999999997e-01 -4.1215215123038629e+00 , 2.1292432526254479e-01 , 8.7828488000000000e+00 , 2.1936900000000001e-01 , 1.4722700000000000e-01 , 9.6446900000000002e-01 -3.8988749331104238e+00 , 5.0354024824932742e-01 , 8.2541232000000004e+00 , -4.7401599999999999e-01 , -2.5211600000000001e-01 , 8.4365000000000001e-01 -3.8213593627434297e+00 , 6.0613494516315236e-01 , 8.2092472000000001e+00 , 5.2678700000000001e-01 , 5.5631600000000003e-01 , -6.4265700000000003e-01 -3.7313671412172926e+00 , 7.2138559050343121e-01 , 8.1137960000000007e+00 , -6.0674499999999998e-01 , 5.5872500000000003e-01 , 5.6540800000000002e-01 -3.7430149027692794e+00 , 7.0512348406336400e-01 , 8.4203152000000010e+00 , 7.9244200000000001e-02 , -7.7111499999999999e-01 , 6.3174500000000000e-01 -3.6594398568038153e+00 , 8.1468196098172330e-01 , 8.3401519999999998e+00 , -3.7624500000000000e-01 , 9.1947400000000001e-01 , -1.1404900000000000e-01 -3.4899005204036264e+00 , 1.0364768251354801e+00 , 7.8554184000000005e+00 , -6.9935400000000003e-01 , -3.4147000000000000e-01 , -6.2793500000000002e-01 -3.4250435891342939e+00 , 1.1215393287981701e+00 , 7.8157736000000000e+00 , -7.7672600000000003e-01 , -8.3049799999999993e-02 , -6.2433899999999998e-01 -3.3898523983385225e+00 , 1.1668372612840525e+00 , 7.9224152000000005e+00 , -3.5541400000000001e-01 , -2.9817199999999999e-01 , -8.8587499999999997e-01 -3.3685984964445721e+00 , 1.1923260414330188e+00 , 8.1181847999999999e+00 , 1.7251400000000000e-01 , 6.4703299999999997e-01 , -7.4268900000000004e-01 -3.2687406545372690e+00 , 1.3236323345800574e+00 , 7.8737328000000009e+00 , 4.6527499999999999e-01 , 2.1376500000000001e-01 , 8.5896700000000004e-01 -3.5393470950353221e+00 , 9.6357108207341313e-01 , 9.9178840000000008e+00 , -6.2901600000000002e-01 , -7.8393300000000003e-03 , -7.7735299999999996e-01 -3.1624918911257827e+00 , 1.4604960459931058e+00 , 7.8979336000000009e+00 , -8.7591200000000002e-01 , -1.3015499999999999e-01 , -4.6458400000000000e-01 -3.0531908455302093e+00 , 1.6042508047021098e+00 , 7.4918968000000001e+00 , -3.3110199999999999e-02 , 9.3340800000000002e-01 , -3.5728700000000002e-01 -3.0159336158465964e+00 , 1.6521764989084551e+00 , 7.5900624000000008e+00 , -3.3110199999999999e-02 , 9.3340800000000002e-01 , -3.5728700000000002e-01 -2.9812631616958032e+00 , 1.6975439107565748e+00 , 7.7182424000000003e+00 , -5.8334200000000003e-01 , 3.7154900000000002e-01 , -7.2226299999999999e-01 -2.9400521379709765e+00 , 1.7496205294773459e+00 , 7.8150871999999998e+00 , -9.4638400000000000e-01 , 1.3484499999999999e-01 , -2.9355500000000001e-01 -2.9010757192745649e+00 , 1.7989549951901724e+00 , 7.9620496000000003e+00 , 5.4914799999999997e-01 , -4.8701299999999997e-01 , -6.7915700000000001e-01 -2.8287224924520404e+00 , 1.8938448271148056e+00 , 7.7271760000000000e+00 , -1.3671800000000001e-01 , 6.9138199999999997e-02 , 9.8819400000000002e-01 -2.7771418183236865e+00 , 1.9620712348923730e+00 , 7.6964232000000008e+00 , 2.9483900000000002e-01 , 4.1756100000000002e-01 , -8.5948400000000003e-01 -2.7286022773902450e+00 , 2.0242415846045985e+00 , 7.7258551999999998e+00 , -3.6230000000000001e-01 , -7.4999499999999997e-02 , 9.2903899999999995e-01 -2.6787593154834894e+00 , 2.0885127081561095e+00 , 7.7232760000000003e+00 , 5.0454399999999999e-01 , -6.6992099999999999e-02 , -8.6078299999999996e-01 -2.6839975632977220e+00 , 2.0764653951682357e+00 , 9.1508216000000004e+00 , -2.9279800000000000e-01 , -4.9225300000000000e-01 , 8.1972999999999996e-01 -2.6133721734425746e+00 , 2.1673073186388261e+00 , 8.9700175999999985e+00 , -9.5577000000000001e-01 , 9.8026500000000003e-02 , -2.7729900000000002e-01 -2.5516831581937525e+00 , 2.2481696339293573e+00 , 9.0156320000000001e+00 , -7.1737200000000001e-01 , -4.8231900000000001e-02 , -6.9501900000000005e-01 -2.4913763780459561e+00 , 2.3230612117110474e+00 , 9.5484031999999992e+00 , -4.7824699999999998e-01 , 8.4076899999999999e-01 , 2.5374700000000000e-01 -2.4258013585830929e+00 , 2.4117813218876081e+00 , 8.8521856000000003e+00 , -7.4093699999999996e-01 , -6.4340799999999998e-01 , -1.9245499999999999e-01 -2.3638886824130250e+00 , 2.4916478246613010e+00 , 8.8822727999999991e+00 , 3.9862399999999998e-01 , 7.5619700000000001e-01 , 5.1890800000000004e-01 -2.3075194642134460e+00 , 2.5652534824542093e+00 , 8.6505816000000006e+00 , 4.5636399999999999e-01 , 8.1719699999999995e-01 , 3.5202499999999998e-01 -2.2518681756305114e+00 , 2.6381599944758038e+00 , 8.5420471999999990e+00 , -9.8399199999999998e-01 , 1.5937299999999999e-01 , -7.9747100000000001e-02 -2.1588920121680641e+00 , 2.7552846168436709e+00 , 9.2721999999999998e+00 , -1.6875399999999999e-02 , 7.0801000000000003e-01 , 7.0600099999999999e-01 -2.0936448250809589e+00 , 2.8402202598777393e+00 , 9.2529496000000009e+00 , -7.6024300000000000e-01 , -2.4731600000000001e-01 , 6.0072099999999995e-01 -2.0169189375919698e+00 , 2.9394689859103722e+00 , 9.4077015999999993e+00 , 1.9538300000000000e-01 , 7.9275099999999998e-01 , -5.7738299999999998e-01 -1.6951663047780152e+00 , 3.3423664509244944e+00 , 1.2603632000000001e+01 , -8.5040899999999997e-01 , -3.3717000000000003e-01 , -4.0388299999999999e-01 -1.5881764652122352e+00 , 3.4812202831522479e+00 , 1.2642840000000000e+01 , -8.3022799999999997e-01 , -4.3936999999999998e-01 , -3.4303899999999998e-01 -1.4957774064442053e+00 , 3.6015965346190870e+00 , 1.2524904000000001e+01 , -8.9026499999999997e-01 , -3.2776499999999997e-01 , -3.1622499999999998e-01 -1.4857982162622201e+00 , 3.6181862656968282e+00 , 1.1688099200000002e+01 , -4.9305199999999999e-01 , -6.5200300000000000e-01 , 5.7601400000000003e-01 -3.7816666927065326e+00 , 5.9584981104920010e-01 , 1.4300758400000000e+00 , -1.2630200000000000e-01 , 2.3990000000000000e-01 , 9.6254600000000001e-01 -3.8128398799393919e+00 , 5.5210375876759299e-01 , 1.4514457599999999e+00 , 1.1365300000000000e-01 , -2.1203500000000000e-01 , -9.7063100000000002e-01 -3.8544133094484732e+00 , 4.9416663912246905e-01 , 1.4626465600000000e+00 , -1.3577700000000001e-01 , 1.7959100000000000e-01 , 9.7432600000000003e-01 -3.8910019046097526e+00 , 4.4328380176011239e-01 , 1.4814248000000001e+00 , 1.0715300000000000e-01 , -1.4501400000000000e-01 , -9.8360999999999998e-01 -3.9389591859389532e+00 , 3.7835315270997683e-01 , 1.4908669600000000e+00 , -1.1132900000000000e-01 , 1.6787199999999999e-01 , 9.7950199999999998e-01 -3.9750855300708894e+00 , 3.2718560499327531e-01 , 1.5133923199999999e+00 , -1.2455400000000000e-01 , 1.4152300000000001e-01 , 9.8206800000000005e-01 -4.0282418359321222e+00 , 2.5440578176521944e-01 , 1.5218631199999999e+00 , -1.2497500000000000e-01 , 1.8853100000000000e-01 , 9.7408300000000003e-01 -4.0706905995041360e+00 , 1.9633836692344042e-01 , 1.5431352800000000e+00 , 1.4052300000000001e-01 , -1.8456600000000001e-01 , -9.7272199999999998e-01 -4.1232010532906980e+00 , 1.2250442041149157e-01 , 1.5567728000000001e+00 , -1.1228800000000000e-01 , 1.8467400000000000e-01 , 9.7636400000000001e-01 -4.1707955355460724e+00 , 5.6693752525176722e-02 , 1.5775800799999999e+00 , -9.9578600000000003e-02 , 2.0953500000000000e-01 , 9.7271799999999997e-01 -4.2247624449757026e+00 , -1.7205747627219825e-02 , 1.5965309599999999e+00 , -9.6064300000000005e-02 , 2.2255800000000001e-01 , 9.7017500000000001e-01 -4.2727956273430632e+00 , -8.3086659458067480e-02 , 1.6223229600000000e+00 , 1.0665700000000000e-01 , -1.9061400000000001e-01 , -9.7585400000000000e-01 -4.3373326241234302e+00 , -1.7295736827473851e-01 , 1.6380165600000001e+00 , 8.5263699999999998e-02 , -1.7200399999999999e-01 , -9.8139900000000002e-01 -4.3959010453294267e+00 , -2.5474227224507429e-01 , 1.6609568800000001e+00 , -1.1255200000000000e-01 , 1.9307900000000000e-01 , 9.7470599999999996e-01 -4.4551233180903438e+00 , -3.3697826776280149e-01 , 1.6870608800000000e+00 , -1.2488600000000000e-01 , 1.6251900000000000e-01 , 9.7877000000000003e-01 -4.5316601358837838e+00 , -4.4280626350595842e-01 , 1.7051142399999999e+00 , 1.2294900000000000e-01 , -1.3931600000000000e-01 , -9.8258599999999996e-01 -4.6032236820880748e+00 , -5.4053770372836718e-01 , 1.7307419200000000e+00 , -9.9060400000000007e-02 , 1.3103100000000001e-01 , 9.8641699999999999e-01 -4.6908512432218901e+00 , -6.6254971166127330e-01 , 1.7499174399999999e+00 , -1.3201399999999999e-01 , 1.8327199999999999e-01 , 9.7415799999999997e-01 -4.7569811948559382e+00 , -7.5242646978660011e-01 , 1.7869674400000000e+00 , -1.0625300000000000e-01 , 1.9831799999999999e-01 , 9.7436100000000003e-01 -4.8445586212044560e+00 , -8.7476698626323524e-01 , 1.8150765600000001e+00 , -9.6917000000000003e-02 , 1.8200400000000000e-01 , 9.7850999999999999e-01 -4.9336232193860621e+00 , -9.9721988752028601e-01 , 1.8481943199999999e+00 , -1.0222100000000001e-01 , 1.6655600000000001e-01 , 9.8071900000000001e-01 -5.0404296380663158e+00 , -1.1444303358083694e+00 , 1.8781483999999999e+00 , 1.0379700000000000e-01 , -1.7513400000000001e-01 , -9.7905799999999998e-01 -5.1346881671991671e+00 , -1.2751260701508160e+00 , 1.9189262800000000e+00 , 8.8422600000000004e-02 , -1.7747700000000000e-01 , -9.8014500000000004e-01 -5.2583459186238937e+00 , -1.4466272733109697e+00 , 1.9531054640000001e+00 , -7.5918500000000000e-02 , 1.7781500000000000e-01 , 9.8113099999999998e-01 -5.3767976238875548e+00 , -1.6107157981313569e+00 , 1.9966834816000001e+00 , -8.8606400000000002e-02 , 1.8517800000000001e-01 , 9.7870199999999996e-01 -5.5008296156244807e+00 , -1.7825974345559938e+00 , 2.0448827600000001e+00 , -8.5930800000000002e-02 , 1.8989000000000000e-01 , 9.7803799999999996e-01 -5.6494494036583980e+00 , -1.9874629107470634e+00 , 2.0927428319999999e+00 , -8.7724899999999995e-02 , 1.8996700000000000e-01 , 9.7786300000000004e-01 -5.7970680980315104e+00 , -2.1916823967506707e+00 , 2.1489020000000001e+00 , -8.2526100000000005e-02 , 1.8576999999999999e-01 , 9.7912200000000005e-01 -5.9688922273888814e+00 , -2.4293027997635894e+00 , 2.2077608000000000e+00 , -8.3648799999999995e-02 , 1.9218700000000000e-01 , 9.7778699999999996e-01 -6.1405350925567115e+00 , -2.6670236159907290e+00 , 2.2766660000000001e+00 , -8.4881399999999996e-02 , 1.9101199999999999e-01 , 9.7791099999999997e-01 -6.3476106297289521e+00 , -2.9534846054312256e+00 , 2.3483771199999999e+00 , -7.0132600000000003e-02 , 1.8445400000000001e-01 , 9.8033599999999999e-01 -6.5792504122808255e+00 , -3.2732843889370322e+00 , 2.4284810399999999e+00 , 8.4373699999999996e-02 , -1.9023899999999999e-01 , -9.7810600000000003e-01 -6.8351336493924331e+00 , -3.6269867356540493e+00 , 2.5194071999999998e+00 , -8.3203700000000005e-02 , 1.8070800000000001e-01 , 9.8001099999999997e-01 -7.1316638748445156e+00 , -4.0376679563477369e+00 , 2.6207988799999997e+00 , -8.5740899999999995e-02 , 1.7926100000000000e-01 , 9.8005799999999998e-01 -7.4704246794750926e+00 , -4.5056543442263193e+00 , 2.7366538399999998e+00 , 8.8075600000000004e-02 , -1.7852899999999999e-01 , -9.7998499999999999e-01 -7.8570246020405481e+00 , -5.0409723154340718e+00 , 2.8710925600000001e+00 , -8.2134499999999999e-02 , 1.8318200000000001e-01 , 9.7964200000000001e-01 -8.3033758450518356e+00 , -5.6572623827699315e+00 , 3.0274815200000003e+00 , 8.6758299999999997e-02 , -1.8272500000000000e-01 , -9.7932900000000001e-01 -8.8331658227082990e+00 , -6.3902907258642241e+00 , 3.2124736000000000e+00 , -8.0325599999999997e-02 , 1.8571599999999999e-01 , 9.7931500000000005e-01 -9.4770539276460504e+00 , -7.2799600613962046e+00 , 3.4348255999999999e+00 , -7.4030899999999997e-02 , 1.8920600000000001e-01 , 9.7914299999999999e-01 -1.0153869760631531e+01 , -8.2159061207034725e+00 , 3.6982992000000001e+00 , -7.3566099999999995e-02 , 1.8983800000000001e-01 , 9.7905600000000004e-01 -1.1277705985518093e+01 , -9.7697681171332995e+00 , 4.0519824000000000e+00 , -8.8119699999999995e-02 , 1.8098200000000000e-01 , 9.7953100000000004e-01 -1.2347391694398858e+01 , -1.1249714774686366e+01 , 4.4659024000000000e+00 , -9.1842999999999994e-02 , 2.0609700000000000e-01 , 9.7421199999999997e-01 -1.3914308932201724e+01 , -1.3416454921699566e+01 , 5.0293951999999997e+00 , -9.5952599999999999e-02 , 1.8688500000000000e-01 , 9.7768500000000003e-01 -5.6828222022315433e+00 , -2.1169180429893828e+00 , 7.8607536000000007e+00 , 6.2176900000000002e-01 , -5.7020099999999996e-01 , 5.3691199999999994e-01 -5.6153686977016175e+00 , -2.0247522050376174e+00 , 7.9296536000000009e+00 , -6.5815800000000002e-01 , 6.5083299999999999e-01 , -3.7847700000000001e-01 -5.0932592314826088e+00 , -1.2961624562499856e+00 , 7.2762320000000003e+00 , 2.4549299999999999e-01 , 8.4276099999999998e-01 , -4.7904799999999997e-01 -5.0098523289914656e+00 , -1.1814657519240432e+00 , 7.2901680000000004e+00 , -7.2242300000000004e-01 , -3.7845499999999999e-01 , 5.7868500000000000e-01 -4.9321273581412619e+00 , -1.0736501866918604e+00 , 7.3080248000000001e+00 , 4.7686400000000001e-01 , 5.5480200000000002e-01 , -6.8175900000000000e-01 -4.9044583136626585e+00 , -1.0377679208899204e+00 , 7.4117336000000007e+00 , -5.3529599999999999e-01 , -6.0161900000000001e-01 , 5.9288500000000000e-01 -4.8757945010574897e+00 , -9.9975276929301371e-01 , 7.5152031999999993e+00 , -8.9619099999999996e-01 , 2.8712700000000002e-01 , -3.3823100000000000e-01 -4.8902910290372645e+00 , -1.0220589931574784e+00 , 7.7027152000000010e+00 , -8.8440200000000002e-01 , 4.6665800000000002e-01 , 7.9314499999999996e-03 -4.9296266128767012e+00 , -1.0806301424855445e+00 , 7.9474688000000002e+00 , -6.4093999999999995e-01 , 7.3218600000000000e-01 , -2.3043300000000000e-01 -5.4087552680732163e+00 , -1.7567464856904551e+00 , 9.0998200000000011e+00 , -8.0377799999999999e-01 , 5.8755500000000005e-01 , 9.3382000000000007e-02 -5.2578060050657403e+00 , -1.5478751543313138e+00 , 9.0028608000000006e+00 , -8.0377799999999999e-01 , 5.8755500000000005e-01 , 9.3382000000000007e-02 -5.3200521210225382e+00 , -1.6375947792898082e+00 , 9.3560552000000001e+00 , 4.8588900000000002e-01 , -8.3027300000000004e-01 , -2.7305299999999999e-01 -4.7549198851465135e+00 , -8.4433687777025446e-01 , 8.3082343999999999e+00 , -5.4173400000000005e-01 , 8.3711400000000002e-01 , -7.5921699999999995e-02 -4.6184179599997126e+00 , -6.5533047956528057e-01 , 8.1842664000000003e+00 , 5.5628999999999995e-01 , -6.0861799999999999e-01 , 5.6579599999999997e-01 -4.6868048334611832e+00 , -7.5424705095554279e-01 , 8.5458536000000009e+00 , 5.4260700000000002e-02 , -8.2189999999999996e-01 , 5.6704200000000005e-01 -4.6502544070498448e+00 , -7.0548939272599576e-01 , 8.6641431999999998e+00 , 1.7101700000000000e-01 , -1.6056400000000001e-01 , 9.7209699999999999e-01 -4.5465566490958960e+00 , -5.6152199396709568e-01 , 8.6081807999999995e+00 , -5.4673799999999995e-01 , -3.4347799999999998e-02 , -8.3659899999999998e-01 -4.4149913460290122e+00 , -3.7907029800402947e-01 , 8.4684984000000014e+00 , -1.9693900000000000e-01 , -5.6888000000000001e-02 , -9.7876399999999997e-01 -4.1346113065106112e+00 , 1.4966896929418105e-02 , 7.8874399999999998e+00 , -1.1606000000000000e-01 , -9.8702599999999996e-01 , -1.1095200000000000e-01 -4.1149290072959799e+00 , 4.0816702809264083e-02 , 8.0273096000000006e+00 , -5.6526799999999999e-01 , 7.5044000000000000e-01 , -3.4250799999999998e-01 -4.3156462379837466e+00 , -2.4767598584359218e-01 , 8.8570424000000010e+00 , 3.7536700000000001e-01 , 5.3811299999999995e-01 , -7.5467499999999998e-01 -4.0402598388468043e+00 , 1.4062454085291987e-01 , 8.2169328000000004e+00 , -7.8998500000000005e-01 , -6.1037900000000000e-01 , -5.7969199999999999e-02 -3.9985377949172873e+00 , 1.9767200142062213e-01 , 8.3014639999999993e+00 , -2.7166299999999999e-01 , -5.1824599999999998e-02 , 9.6099599999999996e-01 -4.2932272312767523e+00 , -2.2669982829956670e-01 , 9.5782720000000019e+00 , 8.2602900000000001e-01 , 4.6125500000000003e-01 , 3.2391300000000001e-01 -3.8059690833450031e+00 , 4.6648731345806982e-01 , 8.0820240000000005e+00 , 4.2485499999999998e-01 , 1.4194800000000000e-02 , -9.0515000000000001e-01 -3.7394523452580497e+00 , 5.5842919393324641e-01 , 8.0656648000000004e+00 , -3.3539900000000000e-01 , -3.6328600000000000e-01 , 8.6921300000000001e-01 -3.6849140926023178e+00 , 6.3242510755974002e-01 , 8.0945248000000003e+00 , 1.4668500000000001e-01 , -7.1489899999999995e-01 , 6.8366899999999997e-01 -3.6644776777930081e+00 , 6.5728373624560743e-01 , 8.2662496000000001e+00 , -2.1320699999999998e-03 , -9.0048799999999996e-01 , 4.3487599999999998e-01 -3.8779709431352130e+00 , 3.4534019816616124e-01 , 9.5040680000000002e+00 , 8.0961499999999997e-01 , 3.2848100000000002e-01 , 4.8643999999999998e-01 -3.4774998431322648e+00 , 9.2050466893231397e-01 , 7.9570160000000003e+00 , -5.5578899999999998e-01 , -4.6939500000000001e-01 , -6.8612499999999998e-01 -3.4249546900080663e+00 , 9.9278229903813964e-01 , 7.9777952000000010e+00 , -5.5578899999999998e-01 , -4.6939500000000001e-01 , -6.8612499999999998e-01 -3.3555312169947511e+00 , 1.0879657153326261e+00 , 7.9083648000000002e+00 , -6.3715699999999997e-01 , -4.3079899999999997e-02 , -7.6952900000000002e-01 -3.2987764321278794e+00 , 1.1664572858140168e+00 , 7.8958328000000000e+00 , 1.3681299999999999e-01 , 2.4523300000000001e-01 , 9.5976200000000000e-01 -3.2358043710821978e+00 , 1.2547850226540451e+00 , 7.8412015999999998e+00 , -3.6080399999999999e-03 , -2.8527500000000000e-01 , 9.5843900000000004e-01 -3.2081160472272772e+00 , 1.2900818688184184e+00 , 8.0052096000000006e+00 , -6.9898499999999997e-01 , 6.7495300000000003e-01 , 2.3634500000000000e-01 -3.1510924001170331e+00 , 1.3698421952661350e+00 , 7.9778472000000002e+00 , -8.6114400000000002e-01 , -9.4848299999999997e-02 , -4.9943399999999999e-01 -3.1103291046244816e+00 , 1.4229242863604818e+00 , 8.0797775999999999e+00 , 3.1720100000000001e-01 , 4.6448800000000001e-01 , 8.2682199999999995e-01 -3.0394483942085850e+00 , 1.5235637520105112e+00 , 7.9369959999999997e+00 , -7.7960700000000005e-01 , 4.1543299999999998e-02 , 6.2488900000000003e-01 -2.9919799080020804e+00 , 1.5885329990505970e+00 , 7.9752783999999997e+00 , 9.4254499999999997e-01 , 2.0297100000000001e-01 , -2.6535199999999998e-01 -2.9317196395965173e+00 , 1.6736019675139227e+00 , 7.8892496000000003e+00 , 9.8791600000000002e-01 , 1.5483200000000000e-01 , 6.9485700000000003e-03 -2.8675707822055192e+00 , 1.7629242150123403e+00 , 7.7497128000000002e+00 , -5.7594699999999999e-01 , -1.2839100000000001e-01 , 8.0734200000000000e-01 -2.8143278693840528e+00 , 1.8371625451270577e+00 , 7.6904744000000003e+00 , 6.9021100000000002e-01 , 1.5712599999999999e-01 , -7.0634300000000005e-01 -2.7686909812906313e+00 , 1.9007129113890118e+00 , 7.7221007999999998e+00 , -2.9102600000000001e-01 , -1.1114900000000000e-01 , 9.5023700000000000e-01 -2.7199060527688790e+00 , 1.9675121395005366e+00 , 7.7112120000000006e+00 , -2.8847699999999998e-01 , -4.8306399999999999e-01 , 8.2669899999999996e-01 -2.6733341598895892e+00 , 2.0305082528297000e+00 , 7.7504303999999999e+00 , -4.3053300000000000e-01 , -1.5017500000000000e-01 , 8.8999399999999995e-01 -2.6698718571651399e+00 , 2.0185716705303172e+00 , 8.9395144000000002e+00 , -5.0663400000000003e-01 , -1.8096200000000000e-02 , -8.6197100000000004e-01 -2.6079992199407096e+00 , 2.1045695634017849e+00 , 8.8840928000000012e+00 , 2.4702700000000000e-01 , 7.5433200000000006e-02 , 9.6606800000000004e-01 -2.5565164847454178e+00 , 2.1689677674404044e+00 , 9.3772088000000000e+00 , -4.9697100000000000e-01 , 2.8272999999999998e-01 , 8.2041699999999995e-01 -2.4891438004472635e+00 , 2.2648023689054422e+00 , 9.0584904000000002e+00 , -9.2938100000000001e-01 , -7.0167300000000002e-02 , -3.6239100000000002e-01 -2.4281819924944195e+00 , 2.3506990215546750e+00 , 8.9869488000000004e+00 , 5.1027500000000003e-01 , 5.4743799999999998e-01 , 6.6327300000000000e-01 -2.3677146461603211e+00 , 2.4339103814895120e+00 , 8.9970576000000015e+00 , -9.4897800000000004e-02 , -9.2860799999999999e-01 , -3.5872199999999999e-01 -2.3192122236558319e+00 , 2.5081418855770625e+00 , 8.4855543999999998e+00 , 8.3916800000000003e-01 , 2.0233999999999999e-01 , -5.0483199999999995e-01 -2.2545923136423176e+00 , 2.5932757811797078e+00 , 8.7625583999999996e+00 , 3.0827100000000002e-01 , 8.5287599999999997e-01 , 4.2139100000000002e-01 -2.1695571051117541e+00 , 2.7011906049462486e+00 , 9.3485568000000008e+00 , 2.4094499999999999e-01 , 1.1595600000000000e-01 , 9.6358699999999997e-01 -2.1078241412427676e+00 , 2.7883316577186728e+00 , 9.3093800000000009e+00 , 1.7526000000000000e-01 , 4.9446600000000002e-01 , 8.5134399999999999e-01 -2.0507598493236490e+00 , 2.8678004173652765e+00 , 9.1962280000000014e+00 , 2.6135999999999998e-01 , -2.6417800000000002e-01 , -9.2838600000000004e-01 -1.9740251811796039e+00 , 2.9699506764339603e+00 , 9.3601111999999986e+00 , -3.7056800000000001e-01 , 7.3370599999999997e-01 , -5.6952100000000005e-01 -1.6106432055237734e+00 , 3.4213201201791668e+00 , 1.2819432000000001e+01 , -9.7018899999999997e-01 , -2.2828599999999999e-01 , -8.1357299999999994e-02 -1.4679937813973587e+00 , 3.6113830593529563e+00 , 1.3236888000000000e+01 , -9.6207200000000004e-01 , -2.1449599999999999e-01 , 1.6854900000000000e-01 -1.3702143454459952e+00 , 3.7481564459011283e+00 , 1.3157016000000000e+01 , -9.5131500000000002e-01 , -2.2001299999999999e-01 , 2.1585799999999999e-01 -1.7207915645934306e+00 , 3.3210851959030627e+00 , 9.2728032000000002e+00 , 3.4873100000000001e-01 , -9.2891199999999996e-01 , 1.2453200000000000e-01 -3.7545825990410000e+00 , 5.3791744191486623e-01 , 1.4371395200000001e+00 , -6.7993300000000007e-02 , 2.0097200000000001e-01 , 9.7723499999999996e-01 -3.7846077355461225e+00 , 4.9329136526624318e-01 , 1.4591968799999999e+00 , -9.8194199999999995e-02 , 1.8442300000000000e-01 , 9.7792999999999997e-01 -3.8287788432181333e+00 , 4.2782667434733890e-01 , 1.4652018400000000e+00 , -9.0038099999999996e-02 , 1.3992299999999999e-01 , 9.8606000000000005e-01 -3.8689058827254383e+00 , 3.6843970081897037e-01 , 1.4794196799999999e+00 , 1.3842800000000000e-01 , -1.7701500000000001e-01 , -9.7442499999999999e-01 -3.9098137708698264e+00 , 3.0839392579852287e-01 , 1.4957892799999999e+00 , -1.0133900000000000e-01 , 1.8998699999999999e-01 , 9.7654300000000005e-01 -3.9552434081250878e+00 , 2.4211258753340181e-01 , 1.5085272000000001e+00 , -1.2294099999999999e-01 , 1.9434699999999999e-01 , 9.7319800000000001e-01 -3.9956562628890726e+00 , 1.8183912599098617e-01 , 1.5289465600000001e+00 , -1.1013900000000000e-01 , 2.2325100000000000e-01 , 9.6851900000000002e-01 -4.0415779061049903e+00 , 1.1538162264794805e-01 , 1.5461637600000000e+00 , -8.7958400000000006e-02 , 2.0597199999999999e-01 , 9.7459700000000005e-01 -4.0871528707278664e+00 , 4.7336396144808113e-02 , 1.5660173600000000e+00 , -1.0375100000000000e-01 , 2.2847799999999999e-01 , 9.6800500000000000e-01 -4.1324737030736260e+00 , -2.0240380845868433e-02 , 1.5880965599999999e+00 , -7.0061499999999999e-02 , 2.2917199999999999e-01 , 9.7086099999999997e-01 -4.1841445110477817e+00 , -9.5899929732297107e-02 , 1.6083193599999999e+00 , -9.8759299999999994e-02 , 2.1625000000000000e-01 , 9.7133000000000003e-01 -4.2355346028768812e+00 , -1.7106458335111396e-01 , 1.6309705600000000e+00 , -6.5468899999999997e-02 , 1.9594100000000000e-01 , 9.7842799999999996e-01 -4.2977692997186532e+00 , -2.6266476282458839e-01 , 1.6481378400000000e+00 , -7.5927599999999998e-02 , 1.7603199999999999e-01 , 9.8145199999999999e-01 -4.3596228672011472e+00 , -3.5358878284091100e-01 , 1.6685436800000000e+00 , -7.8486100000000003e-02 , 1.8408300000000000e-01 , 9.7977199999999998e-01 -4.4220491645684969e+00 , -4.4592476421612126e-01 , 1.6926228000000001e+00 , -1.3172800000000001e-01 , 1.4252100000000001e-01 , 9.8098700000000005e-01 -4.4896313733116164e+00 , -5.4600193247482709e-01 , 1.7162359999999999e+00 , -1.0306200000000000e-01 , 1.3972599999999999e-01 , 9.8481200000000002e-01 -4.5688198822731252e+00 , -6.6208432370232151e-01 , 1.7367188000000000e+00 , -8.6757200000000007e-02 , 1.7745300000000000e-01 , 9.8029800000000000e-01 -4.6364503032841302e+00 , -7.6266107200188715e-01 , 1.7684564800000000e+00 , -1.0741500000000000e-01 , 2.1997300000000000e-01 , 9.6957400000000005e-01 -4.7166637330493852e+00 , -8.7914055836414162e-01 , 1.7976950400000000e+00 , -8.3389800000000000e-02 , 1.9563500000000000e-01 , 9.7712500000000002e-01 -4.8007219459149555e+00 , -1.0050595662074628e+00 , 1.8283729600000000e+00 , 8.3082900000000001e-02 , -1.8113699999999999e-01 , -9.7994199999999998e-01 -4.8917134547320549e+00 , -1.1382745750519159e+00 , 1.8611641600000000e+00 , -7.0717799999999997e-02 , 1.7684600000000000e-01 , 9.8169499999999998e-01 -4.9874990371098029e+00 , -1.2796967453237498e+00 , 1.8964271280000000e+00 , -6.4646999999999996e-02 , 2.1164200000000000e-01 , 9.7520700000000005e-01 -5.0954389937711069e+00 , -1.4384668172374329e+00 , 1.9325353040000000e+00 , -4.1296800000000002e-02 , 1.8022900000000000e-01 , 9.8275699999999999e-01 -5.2090411927833271e+00 , -1.6051725603363076e+00 , 1.9725566880000001e+00 , -5.2255099999999999e-02 , 1.8597200000000000e-01 , 9.8116499999999995e-01 -5.3335546664126756e+00 , -1.7888521139392961e+00 , 2.0150174960000000e+00 , -6.2219999999999998e-02 , 2.0061599999999999e-01 , 9.7769200000000001e-01 -5.4581941758654811e+00 , -1.9731534217792679e+00 , 2.0649956320000000e+00 , -6.1899500000000003e-02 , 2.0095299999999999e-01 , 9.7764300000000004e-01 -5.5946110625646419e+00 , -2.1741468571887559e+00 , 2.1189551999999998e+00 , -7.0125099999999996e-02 , 1.9874900000000001e-01 , 9.7753800000000002e-01 -5.7479960863980306e+00 , -2.3996408235760445e+00 , 2.1761281600000002e+00 , -6.7147999999999999e-02 , 1.9925000000000001e-01 , 9.7764499999999999e-01 -5.9128518835595738e+00 , -2.6423559762794371e+00 , 2.2398156800000000e+00 , -7.2067999999999993e-02 , 1.9374900000000000e-01 , 9.7840000000000005e-01 -6.0943037873478154e+00 , -2.9100397006655552e+00 , 2.3096527199999999e+00 , -7.0682099999999998e-02 , 1.8932599999999999e-01 , 9.7936699999999999e-01 -6.3098996864108718e+00 , -3.2281679932329288e+00 , 2.3840979999999998e+00 , -6.7965200000000003e-02 , 1.8564200000000000e-01 , 9.8026400000000002e-01 -6.5373682823537207e+00 , -3.5635633364668333e+00 , 2.4702443199999999e+00 , -7.7355800000000002e-02 , 1.8509700000000001e-01 , 9.7967099999999996e-01 -6.8056240948930355e+00 , -3.9573098491689933e+00 , 2.5653408799999999e+00 , -6.7683099999999996e-02 , 1.8734400000000001e-01 , 9.7996000000000005e-01 -7.1131407061976342e+00 , -4.4106719887110337e+00 , 2.6733157599999999e+00 , -7.0901400000000003e-02 , 1.8495600000000001e-01 , 9.8018600000000000e-01 -7.4492215676932778e+00 , -4.9053272000146109e+00 , 2.7985317599999999e+00 , -6.9092399999999998e-02 , 1.8449199999999999e-01 , 9.8040200000000000e-01 -7.8656689095764571e+00 , -5.5196249415035679e+00 , 2.9426445600000002e+00 , -6.5756499999999996e-02 , 1.8714000000000000e-01 , 9.8012999999999995e-01 -8.3280442257406300e+00 , -6.1996785423819709e+00 , 3.1127064000000000e+00 , -7.6496200000000000e-02 , 1.9398099999999999e-01 , 9.7801800000000005e-01 -8.8753250023171670e+00 , -7.0075274296529617e+00 , 3.3147887999999996e+00 , -6.9482299999999997e-02 , 1.9977800000000001e-01 , 9.7737499999999999e-01 -9.6139631456799997e+00 , -8.0944438478260938e+00 , 3.5638272000000000e+00 , -6.3977800000000001e-02 , 1.9881099999999999e-01 , 9.7794700000000001e-01 -1.0283622686970441e+01 , -9.0823514134569443e+00 , 3.8522607999999998e+00 , -5.8294300000000000e-02 , 1.8640599999999999e-01 , 9.8074200000000000e-01 -1.1534070605919325e+01 , -1.0923057330316173e+01 , 4.2586303999999995e+00 , -8.4412799999999996e-02 , 2.1536500000000000e-01 , 9.7287900000000005e-01 -5.4110035905635554e+00 , -2.0506756266167327e+00 , 7.9259928000000004e+00 , -5.4191800000000001e-01 , 6.6043700000000005e-01 , -5.1975700000000002e-01 -4.8918094439129742e+00 , -1.2730214717214765e+00 , 7.2216215999999998e+00 , 9.9509099999999995e-01 , -7.0396500000000001e-02 , 6.9556499999999993e-02 -4.8575388880177179e+00 , -1.2256692890804390e+00 , 7.3123512000000002e+00 , -9.3903800000000004e-01 , 2.8667500000000001e-01 , -1.8980200000000000e-01 -4.9122228106366883e+00 , -1.3109581700380559e+00 , 7.5647488000000003e+00 , -7.3663199999999995e-01 , 6.3362799999999997e-01 , -2.3640900000000001e-01 -4.8747215468701244e+00 , -1.2589232877386731e+00 , 7.6569032000000004e+00 , 7.2609699999999999e-01 , -6.7858900000000000e-01 , 1.1090000000000000e-01 -4.8205923498536709e+00 , -1.1806635139779851e+00 , 7.7175352000000004e+00 , 7.9599200000000003e-01 , -6.0436999999999996e-01 , 3.3665700000000000e-02 -5.2976019695665038e+00 , -1.9077308726449931e+00 , 8.8537560000000006e+00 , -8.7157899999999999e-01 , -1.6473900000000000e-01 , 4.6174799999999999e-01 -5.2014589634521347e+00 , -1.7676863732019501e+00 , 8.8642703999999988e+00 , 7.4008399999999996e-01 , -6.5310699999999999e-01 , -1.6039600000000001e-01 -5.2608220888210866e+00 , -1.8617150542044505e+00 , 9.2060455999999995e+00 , 4.0339300000000000e-01 , -9.1439599999999999e-01 , 3.3987799999999999e-02 -5.2272803353218791e+00 , -1.8177487734916329e+00 , 9.3591335999999998e+00 , 4.0339300000000000e-01 , -9.1439599999999999e-01 , 3.3987799999999999e-02 -4.6917543517057592e+00 , -1.0077399137259699e+00 , 8.3375312000000008e+00 , -5.2488599999999996e-01 , 6.6631300000000004e-01 , -5.2964199999999995e-01 -4.6004135346217367e+00 , -8.7431981354903643e-01 , 8.3162008000000007e+00 , -8.6235499999999998e-01 , 4.9742399999999998e-01 , -9.4406599999999993e-02 -4.5813513433522592e+00 , -8.4927811967649891e-01 , 8.4680719999999994e+00 , -6.1999300000000002e-01 , 6.0311099999999995e-01 , -5.0186299999999995e-01 -4.5335523111538976e+00 , -7.8245837524163875e-01 , 8.5523223999999995e+00 , 7.4601399999999995e-01 , -3.7898300000000001e-01 , 5.4757199999999995e-01 -4.5073205799486695e+00 , -7.4712306201001999e-01 , 8.6957696000000002e+00 , 6.7651399999999995e-01 , -2.7387000000000000e-01 , 6.8361099999999997e-01 -4.4080942263066278e+00 , -5.9945843391559661e-01 , 8.6380704000000001e+00 , 1.8964900000000001e-01 , -2.1978900000000001e-01 , -9.5693600000000001e-01 -4.3134160785922804e+00 , -4.5957328850572754e-01 , 8.5848639999999996e+00 , 1.1881000000000000e-01 , -7.0381000000000005e-01 , 7.0038199999999995e-01 -4.0090521084047293e+00 , 4.2011366214802504e-03 , 7.8757191999999998e+00 , -1.1606000000000000e-01 , -9.8702599999999996e-01 , -1.1095200000000000e-01 -3.9773399570201269e+00 , 4.6575164106249956e-02 , 7.9791160000000003e+00 , -8.1664700000000001e-01 , 1.0639600000000000e-01 , -5.6724600000000003e-01 -3.9606650932333363e+00 , 6.7325607423248890e-02 , 8.1365303999999998e+00 , -7.8998599999999997e-01 , -6.1037900000000000e-01 , -5.7969100000000003e-02 -3.9607231170402755e+00 , 6.2275672489229272e-02 , 8.3591736000000001e+00 , -5.8573600000000003e-01 , 1.9705600000000001e-01 , -7.8618200000000005e-01 -3.8369850945874564e+00 , 2.4893508320839430e-01 , 8.1471903999999995e+00 , -1.3918700000000001e-01 , 2.3657400000000001e-01 , 9.6159200000000000e-01 -3.7612585598901367e+00 , 3.6003147450467199e-01 , 8.0974576000000003e+00 , -9.7572599999999998e-01 , 2.1422300000000000e-01 , -4.5463400000000001e-02 -3.6879740175287470e+00 , 4.6934140449678963e-01 , 8.0446464000000013e+00 , 3.8956700000000000e-01 , -1.0419100000000001e-01 , 9.1508599999999996e-01 -3.6452153187390195e+00 , 5.3050822650782226e-01 , 8.1124960000000002e+00 , -7.9360699999999995e-01 , 9.9196300000000001e-02 , -6.0028999999999999e-01 -3.5928264811665760e+00 , 6.0541736672160451e-01 , 8.1410856000000003e+00 , 7.9093700000000000e-01 , -4.1104600000000002e-01 , 4.5327699999999999e-01 -3.5733371636054403e+00 , 6.3000107446883447e-01 , 8.3221807999999999e+00 , -7.9237899999999994e-01 , 5.4318500000000003e-01 , -2.7764299999999997e-01 -3.6003928125154454e+00 , 5.8060272395731904e-01 , 8.7468232000000015e+00 , -7.0611699999999999e-01 , -2.9996699999999998e-01 , -6.4141899999999996e-01 -3.4121913849606900e+00 , 8.7116558445224235e-01 , 8.0986848000000009e+00 , -6.8890300000000004e-01 , -4.6773599999999999e-01 , -5.5374699999999999e-01 -3.3268593341153263e+00 , 1.0006465211889071e+00 , 7.9326384000000001e+00 , 6.2029299999999998e-01 , 3.0336500000000000e-01 , 7.2333000000000003e-01 -3.2804956816112552e+00 , 1.0676617277766787e+00 , 7.9707440000000007e+00 , 6.6684900000000003e-01 , 3.6356899999999998e-01 , 6.5048399999999995e-01 -3.2416563962906944e+00 , 1.1228422904032787e+00 , 8.0571783999999997e+00 , 7.9707700000000006e-02 , 4.4103799999999999e-01 , 8.9394200000000001e-01 -3.1605536112487229e+00 , 1.2452272045325770e+00 , 7.8725680000000002e+00 , 6.8897699999999995e-01 , -1.3712600000000000e-01 , 7.1169300000000002e-01 -3.1283549104332815e+00 , 1.2894413289974409e+00 , 8.0060935999999998e+00 , -8.0883300000000002e-01 , 3.5532599999999998e-01 , -4.6854299999999999e-01 -3.3213302159031883e+00 , 9.5981739067898553e-01 , 9.9265264000000002e+00 , -1.1210500000000000e-01 , 9.8514599999999997e-01 , -1.3007900000000000e-01 -3.2350329778625930e+00 , 1.0882961984619910e+00 , 9.8026935999999996e+00 , 2.9831800000000003e-01 , 9.2554499999999995e-01 , 2.3318100000000000e-01 -2.9370263156860799e+00 , 1.5785277263151434e+00 , 7.6503824000000007e+00 , -2.3648300000000001e-03 , -9.9984600000000001e-01 , 1.7398299999999998e-02 -2.9031880001273649e+00 , 1.6238261228694939e+00 , 7.7889416000000002e+00 , 9.3839200000000000e-01 , -1.0968799999999999e-01 , -3.2770300000000002e-01 -2.8458444228421382e+00 , 1.7118548260473758e+00 , 7.6707872000000004e+00 , -7.8593500000000005e-01 , 4.4428500000000003e-02 , 6.1670999999999998e-01 -2.7930340077463267e+00 , 1.7905188187974626e+00 , 7.5914456000000001e+00 , -8.0873899999999999e-01 , -1.8421699999999999e-01 , 5.5857500000000004e-01 -2.9000045563814707e+00 , 1.5768434650789951e+00 , 9.9003599999999992e+00 , -8.8551700000000000e-01 , -1.7172299999999999e-01 , -4.3170799999999998e-01 -2.7075889423641666e+00 , 1.9140556159683977e+00 , 7.6751551999999998e+00 , -1.9960700000000001e-01 , -1.1973200000000001e-01 , 9.7253400000000001e-01 -2.6616425891896069e+00 , 1.9804465635157151e+00 , 7.6839224000000002e+00 , -3.9494600000000002e-01 , -1.3496800000000000e-01 , 9.0873599999999999e-01 -2.6647947196846369e+00 , 1.9421094043946130e+00 , 9.0385223999999997e+00 , -1.9914000000000001e-01 , -9.4803700000000002e-01 , 2.4813099999999999e-01 -2.6021508869353678e+00 , 2.0359530123175058e+00 , 8.9217408000000002e+00 , -4.0976899999999999e-01 , -2.7426699999999998e-01 , -8.6998100000000000e-01 -2.5471933460073992e+00 , 2.1123314296762334e+00 , 9.0835648000000013e+00 , -4.9847000000000002e-01 , -1.2920899999999999e-01 , 8.5722399999999999e-01 -2.4869200736503778e+00 , 2.2054162540939277e+00 , 8.9213664000000001e+00 , 7.6981999999999995e-01 , 3.8574799999999999e-02 , 6.3709499999999997e-01 -2.4283092033673128e+00 , 2.2829819004921474e+00 , 9.2253375999999996e+00 , 8.5787100000000005e-01 , 4.8847900000000000e-01 , 1.5951799999999999e-01 -2.3689192969483641e+00 , 2.3717874663624539e+00 , 9.1843824000000005e+00 , -6.0464099999999998e-01 , 7.9620299999999999e-01 , -2.1651000000000000e-02 -2.3052517291031722e+00 , 2.4609759448588671e+00 , 9.3077991999999998e+00 , 8.9816599999999996e-02 , -2.6203900000000002e-01 , 9.6086899999999997e-01 -2.2613372506737046e+00 , 2.5391097591216445e+00 , 8.7850120000000000e+00 , 3.3909099999999998e-01 , 7.9940400000000000e-01 , 4.9595400000000001e-01 -2.1819285630901386e+00 , 2.6418406668526582e+00 , 9.3412144000000001e+00 , 3.0630000000000002e-01 , 1.1944500000000000e-01 , 9.4441200000000003e-01 -2.1193064616222124e+00 , 2.7333156248150638e+00 , 9.3444384000000014e+00 , 1.1661899999999999e-02 , 5.7247000000000003e-01 , 8.1984299999999999e-01 -2.0628905536190856e+00 , 2.8181133428373242e+00 , 9.2526064000000012e+00 , 5.7419699999999996e-01 , 7.0360100000000003e-01 , 4.1861999999999999e-01 -1.9930548267703916e+00 , 2.9172307141238276e+00 , 9.3765536000000012e+00 , -8.7751499999999996e-02 , -2.3097100000000001e-01 , 9.6899500000000005e-01 -1.6471800532813756e+00 , 3.3381889832250868e+00 , 1.2799360000000000e+01 , -9.3555800000000000e-01 , -3.3020300000000002e-01 , -1.2528600000000001e-01 -1.5456298743275596e+00 , 3.4852233757482338e+00 , 1.2838152000000001e+01 , 8.1635199999999997e-01 , 5.5887799999999999e-01 , 1.4568400000000001e-01 -1.4245312621292632e+00 , 3.6569462194402025e+00 , 1.3058528000000001e+01 , -9.4062900000000005e-01 , -2.3558000000000001e-01 , 2.4437300000000001e-01 -1.4795724231069509e+00 , 3.6110878967521902e+00 , 1.1677917600000001e+01 , -4.9305199999999999e-01 , -6.5200300000000000e-01 , 5.7601400000000003e-01 -3.6857758868714385e+00 , 5.4038565845622943e-01 , 1.4347173600000001e+00 , -6.1355400000000001e-03 , 2.1662400000000001e-01 , 9.7623599999999999e-01 -3.7185872691144839e+00 , 4.8787760868611518e-01 , 1.4498587199999999e+00 , 6.1949999999999998e-02 , -1.7457800000000001e-01 , -9.8269300000000004e-01 -3.7570045549091926e+00 , 4.2792120891821983e-01 , 1.4608910399999999e+00 , -3.7323599999999998e-02 , 1.5479799999999999e-01 , 9.8724100000000004e-01 -3.7998796935278270e+00 , 3.5963643478552698e-01 , 1.4683988000000001e+00 , -3.5921700000000001e-02 , 2.0515700000000001e-01 , 9.7806999999999999e-01 -3.8341168152239198e+00 , 3.0710966251493210e-01 , 1.4890563200000000e+00 , -6.3220799999999994e-02 , 2.1450100000000000e-01 , 9.7467599999999999e-01 -3.8775412598611720e+00 , 2.3857544640920736e-01 , 1.5007386400000000e+00 , -4.0878999999999999e-02 , 2.0408200000000001e-01 , 9.7809999999999997e-01 -3.9160046917627254e+00 , 1.7812965929286184e-01 , 1.5198954400000000e+00 , -6.2468500000000003e-02 , 2.2068099999999999e-01 , 9.7334399999999999e-01 -3.9542148255947498e+00 , 1.1704889229654158e-01 , 1.5410781600000001e+00 , -7.9708399999999999e-02 , 2.1274499999999999e-01 , 9.7385100000000002e-01 -4.0025268624289581e+00 , 4.1207228420475195e-02 , 1.5544213600000001e+00 , -6.4661499999999997e-02 , 2.2758700000000001e-01 , 9.7160800000000003e-01 -4.0412269360605997e+00 , -2.0039510961351592e-02 , 1.5801842399999999e+00 , -5.6630800000000002e-02 , 2.4612400000000001e-01 , 9.6758299999999997e-01 -4.0899415925412388e+00 , -9.6977438957193574e-02 , 1.5987180800000000e+00 , -6.3883300000000004e-02 , 2.1182400000000001e-01 , 9.7521800000000003e-01 -4.1393530756202708e+00 , -1.7442141617176166e-01 , 1.6201108799999999e+00 , -8.7983099999999995e-02 , 2.2790500000000000e-01 , 9.6970000000000001e-01 -4.1884449998328552e+00 , -2.5133592583220121e-01 , 1.6441359200000001e+00 , -8.0252500000000004e-02 , 1.9291400000000000e-01 , 9.7792800000000002e-01 -4.2473473823515002e+00 , -3.4466213973519455e-01 , 1.6625512000000000e+00 , -4.4435299999999997e-02 , 1.6873900000000000e-01 , 9.8465899999999995e-01 -4.3124541479670180e+00 , -4.4577168135756606e-01 , 1.6805265599999999e+00 , -6.2727099999999994e-02 , 1.2770599999999999e-01 , 9.8982599999999998e-01 -4.3871447957997978e+00 , -5.6400738248070192e-01 , 1.6946175200000000e+00 , -7.1871500000000005e-02 , 1.8024299999999999e-01 , 9.8099300000000000e-01 -4.4522800843931769e+00 , -6.6667103623536450e-01 , 1.7207204800000000e+00 , -5.5968999999999998e-02 , 1.8829299999999999e-01 , 9.8051699999999997e-01 -4.5224975931288354e+00 , -7.7697408806221846e-01 , 1.7468640000000000e+00 , -7.5213799999999997e-02 , 2.1378200000000000e-01 , 9.7398200000000001e-01 -4.5822403341471931e+00 , -8.7188085432181417e-01 , 1.7839847200000001e+00 , -8.2800700000000005e-02 , 2.1131400000000000e-01 , 9.7390500000000002e-01 -4.6634428087334694e+00 , -9.9925950546408782e-01 , 1.8120616000000001e+00 , -6.6378599999999996e-02 , 1.9310099999999999e-01 , 9.7893100000000000e-01 -4.7450839834317335e+00 , -1.1267084005508936e+00 , 1.8451242400000001e+00 , -6.7637699999999995e-02 , 1.9147700000000001e-01 , 9.7916400000000003e-01 -4.8369587595800994e+00 , -1.2717141613010359e+00 , 1.8775670400000000e+00 , -6.2991400000000003e-02 , 2.2397400000000001e-01 , 9.7255700000000000e-01 -4.9227904347130167e+00 , -1.4074288990011010e+00 , 1.9179608479999999e+00 , -5.2495699999999999e-02 , 2.0292299999999999e-01 , 9.7778699999999996e-01 -5.0315337689889752e+00 , -1.5778573559319411e+00 , 1.9543273600000000e+00 , -2.3447800000000001e-02 , 2.0038600000000001e-01 , 9.7943599999999997e-01 -5.1341016408917888e+00 , -1.7398599311832252e+00 , 1.9995593676000001e+00 , -3.9685800000000000e-02 , 1.9440600000000000e-01 , 9.8011800000000004e-01 -5.2582847664225465e+00 , -1.9360962133941673e+00 , 2.0428640159999998e+00 , 5.1376499999999999e-02 , -2.0214399999999999e-01 , -9.7800699999999996e-01 -5.3889532618899780e+00 , -2.1399315261843643e+00 , 2.0920286639999999e+00 , -4.5550300000000002e-02 , 2.1054100000000001e-01 , 9.7652300000000003e-01 -5.5238745243796927e+00 , -2.3532297732601934e+00 , 2.1478193600000002e+00 , -5.3952500000000000e-02 , 1.9774300000000000e-01 , 9.7876799999999997e-01 -5.6756684773190802e+00 , -2.5919711019015388e+00 , 2.2074332000000001e+00 , -5.8568700000000001e-02 , 1.9384000000000001e-01 , 9.7928300000000001e-01 -5.8493163917775401e+00 , -2.8657572824604340e+00 , 2.2716261599999998e+00 , -6.0833100000000001e-02 , 1.9889699999999999e-01 , 9.7813000000000005e-01 -6.0227187092977914e+00 , -3.1384365918687669e+00 , 2.3465706399999999e+00 , -6.5945199999999995e-02 , 1.8796199999999999e-01 , 9.7996000000000005e-01 -6.2405343062626502e+00 , -3.4802879810389182e+00 , 2.4250001600000002e+00 , -6.1463600000000000e-02 , 1.8667700000000001e-01 , 9.8049699999999995e-01 -6.4732434214142724e+00 , -3.8480791535701639e+00 , 2.5148218399999998e+00 , -6.0288899999999999e-02 , 1.8881200000000001e-01 , 9.8016099999999995e-01 -6.7402943308494079e+00 , -4.2670812742616313e+00 , 2.6160606399999997e+00 , -5.9434500000000001e-02 , 1.8756100000000001e-01 , 9.8045300000000002e-01 -7.0443316930454190e+00 , -4.7464147311279898e+00 , 2.7314476000000001e+00 , -5.7387700000000000e-02 , 1.8565100000000001e-01 , 9.8093900000000001e-01 -7.4043927727573449e+00 , -5.3117311277636823e+00 , 2.8641443199999999e+00 , -6.0420399999999999e-02 , 1.8683000000000000e-01 , 9.8053299999999999e-01 -7.8126210039284203e+00 , -5.9552106471762372e+00 , 3.0197314400000002e+00 , -5.9648600000000003e-02 , 1.9223399999999999e-01 , 9.7953500000000004e-01 -8.2756865894941036e+00 , -6.6825896703153376e+00 , 3.2027495999999998e+00 , -6.6078999999999999e-02 , 1.8496000000000001e-01 , 9.8052200000000000e-01 -8.8808626888986240e+00 , -7.6356470344135570e+00 , 3.4235831999999999e+00 , -6.0096700000000003e-02 , 1.8640399999999999e-01 , 9.8063299999999998e-01 -9.5963226113225346e+00 , -8.7609216646642416e+00 , 3.6938271999999999e+00 , -6.9280300000000003e-02 , 1.9265199999999999e-01 , 9.7881799999999997e-01 -1.0513153538873670e+01 , -1.0203303075409782e+01 , 4.0347287999999999e+00 , 6.2729300000000002e-02 , -1.7520700000000000e-01 , -9.8253100000000004e-01 -1.1413903518930256e+01 , -1.1622733791344098e+01 , 4.4339639999999996e+00 , -8.9033299999999996e-02 , 2.1526300000000001e-01 , 9.7248900000000005e-01 -5.1875071641754920e+00 , -2.0539907947278220e+00 , 8.2465831999999999e+00 , 6.1278100000000002e-01 , -6.7334499999999997e-01 , 4.1365099999999999e-01 -5.3418585273399302e+00 , -2.3129910746189433e+00 , 8.7384927999999995e+00 , -9.5396000000000003e-01 , -1.8845999999999999e-01 , 2.3333100000000001e-01 -5.1194132657125273e+00 , -1.9555772451365412e+00 , 8.4939160000000005e+00 , -9.5396000000000003e-01 , -1.8845999999999999e-01 , 2.3333100000000001e-01 -5.1426630184902988e+00 , -2.0018526596847925e+00 , 8.7435368000000011e+00 , -8.9226700000000003e-01 , -3.3614100000000002e-01 , 3.0144599999999999e-01 -5.0516735205258723e+00 , -1.8607953269936424e+00 , 8.7548832000000001e+00 , 1.9464500000000001e-01 , -9.5108499999999996e-01 , 2.3989800000000000e-01 -5.0455555350393375e+00 , -1.8579925134096644e+00 , 8.9519839999999995e+00 , 2.0451200000000000e-01 , -9.7001400000000004e-01 , 1.3133100000000000e-01 -4.6326582881217275e+00 , -1.1854076144125947e+00 , 8.2019984000000008e+00 , 5.2434499999999995e-01 , -4.2087400000000003e-01 , 7.4022100000000002e-01 -4.5491503204101331e+00 , -1.0561829976343686e+00 , 8.1931480000000008e+00 , 5.2367600000000003e-01 , -6.3911399999999996e-01 , 5.6329099999999999e-01 -4.4960106266416489e+00 , -9.7568522902957078e-01 , 8.2546016000000009e+00 , -5.2488599999999996e-01 , 6.6631300000000004e-01 , -5.2964199999999995e-01 -4.5220464649212051e+00 , -1.0266485804605825e+00 , 8.5236912000000000e+00 , 6.1915200000000004e-01 , -6.6274000000000000e-01 , 4.2121999999999998e-01 -4.4762107441380437e+00 , -9.5637473419066366e-01 , 8.6097095999999986e+00 , -7.1296199999999998e-01 , 6.2272700000000003e-01 , -3.2232899999999998e-01 -4.4528263982326859e+00 , -9.2655324215256218e-01 , 8.7632864000000001e+00 , 6.8039899999999998e-01 , -5.9710900000000000e-01 , 4.2487399999999997e-01 -3.9217970600681031e+00 , -7.8683540703662569e-02 , 8.2098816000000010e+00 , -7.8998900000000005e-01 , -6.1037399999999997e-01 , -5.7972400000000000e-02 -3.8522670194460140e+00 , 3.0007966350985127e-02 , 8.1863983999999999e+00 , -8.4914999999999996e-01 , -4.0432800000000002e-01 , 3.3979900000000002e-01 -3.8009297859421904e+00 , 1.0993729762914617e-01 , 8.2243480000000009e+00 , 7.2682500000000005e-01 , 5.6740199999999996e-01 , 3.8701400000000002e-01 -3.7045704294583297e+00 , 2.6413615977623262e-01 , 8.0837503999999996e+00 , -8.2283099999999998e-01 , -1.6265399999999999e-01 , -5.4451099999999997e-01 -3.6841118172053982e+00 , 2.9203579620189579e-01 , 8.2389183999999993e+00 , -5.9444900000000001e-01 , -4.9279899999999999e-01 , -6.3543600000000000e-01 -3.6274982935959752e+00 , 3.7893910570783618e-01 , 8.2523552000000002e+00 , -6.0510799999999998e-01 , 1.8086199999999999e-01 , -7.7532800000000002e-01 -3.8719296132524850e+00 , -5.3275401832594049e-02 , 9.6482223999999999e+00 , 5.1080000000000003e-01 , -1.6010800000000000e-01 , 8.4465900000000005e-01 -3.8301790408142704e+00 , 6.1114225213090290e-03 , 9.8022880000000008e+00 , -5.6416599999999995e-01 , -1.0876700000000000e-01 , -8.1846600000000003e-01 -3.4935383871570092e+00 , 5.8178887074349861e-01 , 8.4453479999999992e+00 , 2.3084600000000000e-01 , 1.0859300000000000e-01 , 9.6691199999999999e-01 -3.4905611984305711e+00 , 5.7527474585007132e-01 , 8.7443792000000009e+00 , 5.9377199999999997e-01 , -2.3918200000000001e-01 , 7.6826200000000000e-01 -3.4222861130516558e+00 , 6.8217262079705887e-01 , 8.7017392000000005e+00 , 7.6382399999999995e-01 , 5.6437800000000005e-01 , -3.1313000000000002e-01 -3.2616758786392506e+00 , 9.5656425733546069e-01 , 8.0741095999999999e+00 , -5.9687599999999996e-01 , -4.7070200000000001e-01 , -6.4975200000000000e-01 -3.2227458065186179e+00 , 1.0141033979397691e+00 , 8.1616464000000004e+00 , -4.7866300000000001e-01 , 2.2042100000000001e-01 , -8.4987999999999997e-01 -3.1519459000026773e+00 , 1.1295304847416725e+00 , 8.0290776000000008e+00 , -5.8999299999999999e-01 , -4.8489300000000002e-01 , -6.4559000000000000e-01 -3.1014859595669071e+00 , 1.2069327746644241e+00 , 8.0335496000000006e+00 , 8.4064399999999995e-01 , -1.1421400000000000e-01 , 5.2940900000000002e-01 -3.0709681276591478e+00 , 1.2498852880031541e+00 , 8.1875216000000002e+00 , -8.6873000000000000e-01 , 1.3430200000000000e-01 , -4.7673100000000002e-01 -3.0285211131102123e+00 , 1.3119016054651707e+00 , 8.2701911999999993e+00 , -7.4593100000000001e-01 , 1.9420699999999999e-01 , -6.3707899999999995e-01 -2.9327456348366123e+00 , 1.4776368253954222e+00 , 7.8338488000000002e+00 , 8.4521999999999997e-01 , 4.6633500000000000e-01 , -2.6102500000000001e-01 -2.8726876583878385e+00 , 1.5772081853585043e+00 , 7.6880720000000000e+00 , 9.8129800000000000e-01 , -5.8530499999999999e-02 , -1.8337999999999999e-01 -2.8274590458492463e+00 , 1.6482195058011064e+00 , 7.6830488000000008e+00 , -7.7788999999999997e-01 , -1.3035700000000000e-01 , 6.1473100000000003e-01 -2.7760744961198087e+00 , 1.7324549524111634e+00 , 7.5842279999999995e+00 , -8.4267899999999996e-01 , 1.4874300000000000e-02 , 5.3821099999999999e-01 -2.8657585124574196e+00 , 1.5135256048113206e+00 , 9.7158015999999989e+00 , -3.9127800000000001e-01 , 6.2132100000000001e-01 , 6.7886800000000003e-01 -2.7988943995719402e+00 , 1.6186349451030200e+00 , 9.6698544000000002e+00 , -7.4161600000000005e-01 , -3.9386199999999999e-01 , 5.4302700000000004e-01 -2.6505160797565743e+00 , 1.9235926951735467e+00 , 7.6892264000000008e+00 , 5.0886699999999996e-01 , 2.2192500000000001e-01 , -8.3174700000000001e-01 -2.6041545955600842e+00 , 1.9976066413687079e+00 , 7.6250688000000002e+00 , -3.9494600000000002e-01 , -1.3496800000000000e-01 , 9.0873599999999999e-01 -2.5930539504809325e+00 , 1.9685686980567807e+00 , 8.9173728000000008e+00 , -4.0976899999999999e-01 , -2.7426699999999998e-01 , -8.6998100000000000e-01 -2.5378157920147135e+00 , 2.0529535040414220e+00 , 8.9449640000000006e+00 , -4.3476199999999998e-01 , 5.7419699999999996e-01 , -6.9374400000000003e-01 -2.4836826879469811e+00 , 2.1334730587586401e+00 , 9.0748184000000016e+00 , 7.2371099999999999e-01 , -2.9779600000000001e-01 , 6.2254299999999996e-01 -2.4269027040061815e+00 , 2.2226737646744459e+00 , 9.0469152000000008e+00 , -3.2482100000000003e-01 , -1.9789200000000001e-01 , -9.2484100000000002e-01 -2.3661869067926498e+00 , 2.3054251562967778e+00 , 9.3603711999999994e+00 , 8.8302400000000003e-01 , -4.6139900000000000e-01 , 8.5902000000000006e-02 -2.2993638349291592e+00 , 2.3975956955984890e+00 , 9.6823759999999996e+00 , 1.0259600000000001e-01 , 4.4234899999999999e-01 , 8.9095500000000005e-01 -2.2753325570458971e+00 , 2.4779942765585123e+00 , 8.5057407999999999e+00 , -9.4710000000000005e-01 , -3.1273000000000001e-01 , -7.2128100000000001e-02 -2.2004696827202253e+00 , 2.5743342650767405e+00 , 9.0838871999999995e+00 , -9.9295800000000001e-01 , -9.5218700000000003e-02 , -7.0484800000000000e-02 -2.1289136768738448e+00 , 2.6751222915613377e+00 , 9.3686080000000018e+00 , 1.3862900000000000e-01 , -5.9559700000000000e-02 , -9.8855199999999999e-01 -2.0776513245384192e+00 , 2.7600531571254772e+00 , 9.2258264000000008e+00 , 8.9574100000000007e-03 , 5.2323399999999998e-01 , 8.5214199999999996e-01 -2.0238422851721083e+00 , 2.8466378403265766e+00 , 9.1645080000000014e+00 , -3.1362000000000001e-01 , 5.4894200000000004e-01 , 7.7479399999999998e-01 -1.9398425099145806e+00 , 2.9654685233595379e+00 , 9.4939488000000019e+00 , -4.8530699999999999e-01 , 6.8359300000000001e-01 , -5.4513999999999996e-01 -1.5730241804800094e+00 , 3.4107337510842619e+00 , 1.2911680000000000e+01 , 7.8759699999999999e-01 , 5.3534499999999996e-01 , 3.0511800000000000e-01 -1.4582330549477669e+00 , 3.5836396819063898e+00 , 1.3123528000000000e+01 , -9.5406899999999994e-01 , -1.8791300000000000e-01 , 2.3332800000000001e-01 -1.7715561660702563e+00 , 3.2333676545234940e+00 , 9.3331440000000008e+00 , -1.1441800000000001e-01 , 3.0424699999999999e-01 , 9.4569700000000001e-01 -1.7162219924604787e+00 , 3.3222281449512732e+00 , 9.2933120000000002e+00 , -4.8738700000000001e-01 , 8.5841800000000001e-01 , -1.5991600000000000e-01 -3.5644040282497635e+00 , 6.3768755225239415e-01 , 1.3963569599999999e+00 , -2.0444299999999999e-02 , 2.5457099999999999e-01 , 9.6683799999999998e-01 -3.5869553964725776e+00 , 5.9799827435421271e-01 , 1.4202551200000000e+00 , -2.0444299999999999e-02 , 2.5457099999999999e-01 , 9.6683799999999998e-01 -3.6190174804761472e+00 , 5.4499876554377158e-01 , 1.4328432799999999e+00 , -2.7439399999999999e-02 , 2.4898400000000001e-01 , 9.6811899999999995e-01 -3.6498412932301671e+00 , 4.9130256271689454e-01 , 1.4469279999999998e+00 , -2.3552099999999999e-02 , 1.7680799999999999e-01 , 9.8396399999999995e-01 -3.6863193488548540e+00 , 4.3117590353610957e-01 , 1.4566967200000001e+00 , -7.1822300000000006e-02 , 1.7474799999999999e-01 , 9.8199000000000003e-01 -3.7235197211052107e+00 , 3.6937048305833242e-01 , 1.4688231200000001e+00 , -2.6395499999999999e-02 , 1.7468900000000001e-01 , 9.8426999999999998e-01 -3.7594564701915303e+00 , 3.0798805101929605e-01 , 1.4827466400000000e+00 , -5.2991700000000003e-02 , 1.8427800000000000e-01 , 9.8144500000000001e-01 -3.7962286057170580e+00 , 2.4693413305482559e-01 , 1.4985151200000000e+00 , -6.9708199999999998e-02 , 2.2073699999999999e-01 , 9.7283900000000001e-01 -3.8327351843196062e+00 , 1.8525336174175000e-01 , 1.5164114399999999e+00 , -6.3398800000000005e-02 , 2.1495300000000001e-01 , 9.7456500000000001e-01 -3.8746825227650614e+00 , 1.1531612289274773e-01 , 1.5313136000000001e+00 , -6.5175300000000005e-02 , 2.2181999999999999e-01 , 9.7290699999999997e-01 -3.9153117002443549e+00 , 4.4814556915841131e-02 , 1.5484195199999999e+00 , -7.9350100000000007e-02 , 2.2389100000000001e-01 , 9.7137899999999999e-01 -3.9577203284604474e+00 , -2.5252015871110700e-02 , 1.5681046400000000e+00 , 7.6512499999999997e-02 , -2.3409300000000000e-01 , -9.6919900000000003e-01 -3.9988570688683418e+00 , -9.4854829449682931e-02 , 1.5897876000000000e+00 , -6.4986799999999997e-02 , 2.2344700000000001e-01 , 9.7254700000000005e-01 -4.0499088131185985e+00 , -1.8107099684516825e-01 , 1.6049528799999999e+00 , -6.4570699999999995e-02 , 2.2514400000000001e-01 , 9.7218400000000005e-01 -4.0924414109971075e+00 , -2.5174913117669373e-01 , 1.6321551200000000e+00 , -9.3756400000000004e-02 , 1.9291100000000000e-01 , 9.7672700000000001e-01 -4.1483999008756864e+00 , -3.4636185072046821e-01 , 1.6487805600000001e+00 , -7.8417399999999998e-02 , 1.8340699999999999e-01 , 9.7990400000000000e-01 -4.2003954442596250e+00 , -4.3393598306221026e-01 , 1.6732101600000000e+00 , -5.2781200000000000e-02 , 1.4458299999999999e-01 , 9.8808399999999996e-01 -4.2767004654904870e+00 , -5.6196782838046611e-01 , 1.6811765599999999e+00 , -4.1415199999999999e-02 , 1.7102200000000001e-01 , 9.8439600000000005e-01 -4.3289052325289861e+00 , -6.4921303784010354e-01 , 1.7125128000000001e+00 , -5.2128700000000000e-02 , 2.0229200000000000e-01 , 9.7793699999999995e-01 -4.3851875572397203e+00 , -7.4521389159982521e-01 , 1.7434652800000001e+00 , -3.8762999999999999e-02 , 1.9587900000000000e-01 , 9.7986200000000001e-01 -4.4575204060730744e+00 , -8.6658042323870488e-01 , 1.7678657600000001e+00 , -8.0611500000000003e-02 , 2.1413099999999999e-01 , 9.7347300000000003e-01 -4.5293451284649890e+00 , -9.8706308547574384e-01 , 1.7965156799999999e+00 , -6.7799799999999993e-02 , 2.1741800000000000e-01 , 9.7372099999999995e-01 -4.6016114513375159e+00 , -1.1087296137421645e+00 , 1.8299506400000001e+00 , -7.0388999999999993e-02 , 1.9744300000000001e-01 , 9.7778399999999999e-01 -4.6787845198383646e+00 , -1.2387926941568743e+00 , 1.8649476800000000e+00 , -7.8000700000000006e-02 , 1.8944300000000000e-01 , 9.7878900000000002e-01 -4.7661440824237662e+00 , -1.3863372971787649e+00 , 1.8996276240000001e+00 , -8.2468700000000006e-02 , 2.1287600000000001e-01 , 9.7359300000000004e-01 -4.8431031043840136e+00 , -1.5164437669753204e+00 , 1.9448736560000000e+00 , -7.6374999999999998e-02 , 2.1239800000000000e-01 , 9.7419400000000000e-01 -4.9516361930656263e+00 , -1.6985556846122210e+00 , 1.9811705920000000e+00 , -4.7102699999999997e-02 , 1.7375399999999999e-01 , 9.8366200000000004e-01 -5.0753322184843164e+00 , -1.9066801100541646e+00 , 2.0181052560000001e+00 , -5.0276099999999997e-02 , 1.9326099999999999e-01 , 9.7985800000000001e-01 -5.1788512592763052e+00 , -2.0799184851605661e+00 , 2.0710089119999999e+00 , -6.3116199999999997e-02 , 2.1003300000000000e-01 , 9.7565500000000005e-01 -5.3070072092107967e+00 , -2.2971667293136271e+00 , 2.1215780799999999e+00 , -4.8514500000000002e-02 , 1.9853799999999999e-01 , 9.7889199999999998e-01 -5.4520379157560015e+00 , -2.5398682477246153e+00 , 2.1758702400000001e+00 , -6.2466399999999998e-02 , 1.9599400000000000e-01 , 9.7861299999999996e-01 -5.5968921865285424e+00 , -2.7837409645039939e+00 , 2.2401100000000000e+00 , -6.1122700000000002e-02 , 2.0037900000000000e-01 , 9.7780999999999996e-01 -5.7667967146410852e+00 , -3.0705741118193890e+00 , 2.3073012799999999e+00 , -5.5529000000000002e-02 , 1.9554400000000000e-01 , 9.7912200000000005e-01 -5.9530297262963057e+00 , -3.3829924914737006e+00 , 2.3827709600000002e+00 , -6.5633200000000003e-02 , 1.8936300000000000e-01 , 9.7971100000000000e-01 -6.1657055546476478e+00 , -3.7405296664246004e+00 , 2.4665107200000000e+00 , -6.0583100000000001e-02 , 1.9531499999999999e-01 , 9.7886799999999996e-01 -6.3983640159059503e+00 , -4.1327270006553665e+00 , 2.5616873600000001e+00 , -6.2014800000000002e-02 , 1.9311200000000001e-01 , 9.7921499999999995e-01 -6.6569420081968564e+00 , -4.5680375121646613e+00 , 2.6697860000000002e+00 , -5.6228599999999997e-02 , 1.9066900000000001e-01 , 9.8004300000000000e-01 -6.9841295664454739e+00 , -5.1172878171224889e+00 , 2.7909054400000000e+00 , -5.8186099999999998e-02 , 1.9027200000000000e-01 , 9.8000600000000004e-01 -7.3259543173915800e+00 , -5.6935167369212731e+00 , 2.9340749600000002e+00 , -5.7056900000000001e-02 , 1.9446099999999999e-01 , 9.7924900000000004e-01 -7.7463704403241724e+00 , -6.4001048666041367e+00 , 3.1004968000000002e+00 , -5.8367099999999998e-02 , 1.9305400000000000e-01 , 9.7945099999999996e-01 -8.2716597405526979e+00 , -7.2829995043906308e+00 , 3.2996672000000000e+00 , 5.8938600000000001e-02 , -1.9884199999999999e-01 , -9.7825799999999996e-01 -8.7452915412544829e+00 , -8.0828144402676649e+00 , 3.5312752000000001e+00 , -5.0126200000000003e-02 , 1.9536600000000001e-01 , 9.7944900000000001e-01 -9.4359333075713607e+00 , -9.2448484165463558e+00 , 3.8188247999999998e+00 , -6.4960100000000007e-02 , 1.9749200000000000e-01 , 9.7814999999999996e-01 -1.0521014349137756e+01 , -1.1067928313372535e+01 , 4.2091992000000005e+00 , -6.4779900000000001e-02 , 1.8668100000000001e-01 , 9.8028199999999999e-01 -2.9521664794469139e+01 , -4.3069461883100743e+01 , 1.2516376000000001e+01 , 5.2966599999999997e-01 , -3.4341600000000000e-01 , -7.7557699999999996e-01 -5.4423748089456438e+00 , -2.7930442753266993e+00 , 7.6157608000000003e+00 , 1.2831600000000001e-01 , -4.4890300000000000e-01 , 8.8431999999999999e-01 -5.3504848956985454e+00 , -2.6500577725759831e+00 , 7.8157008000000001e+00 , 7.3114800000000002e-01 , -2.2533200000000000e-01 , 6.4393199999999995e-01 -5.2059277322465922e+00 , -2.4067084629804034e+00 , 7.7489328000000004e+00 , 3.8693300000000003e-01 , -6.5788599999999997e-01 , 6.4611799999999997e-01 -5.1501856644802571e+00 , -2.3168801159168320e+00 , 7.8245095999999998e+00 , -5.2800899999999995e-01 , 5.5240599999999995e-01 , -6.4502199999999998e-01 -5.1738841996038154e+00 , -2.3670969368950407e+00 , 8.0441056000000000e+00 , -8.0097099999999999e-01 , 5.7840700000000000e-01 , -1.5456900000000001e-01 -5.1941102915451900e+00 , -2.4122237648568969e+00 , 8.2671440000000000e+00 , -9.3404900000000002e-01 , 2.7884999999999999e-01 , 2.2314999999999999e-01 -5.1111276203497900e+00 , -2.2771624422500327e+00 , 8.2978863999999994e+00 , 9.8093500000000000e-01 , -9.1225700000000007e-02 , -1.7159400000000000e-01 -4.6743157308215686e+00 , -1.5160226471687435e+00 , 7.6028960000000003e+00 , 2.2786600000000001e-01 , -9.5937099999999997e-01 , -1.6638800000000001e-01 -4.6567584947503011e+00 , -1.4932226495315115e+00 , 7.7333743999999998e+00 , 2.3470500000000000e-01 , -9.5182400000000000e-01 , -1.9734499999999999e-01 -4.6371387272872084e+00 , -1.4671054912623940e+00 , 7.8641024000000002e+00 , -6.9983099999999998e-01 , -6.8589299999999997e-01 , 1.9946900000000001e-01 -4.6426441680052442e+00 , -1.4868835739101178e+00 , 8.0569807999999998e+00 , 2.8838100000000000e-01 , 9.1626200000000002e-01 , -2.7803099999999997e-01 -4.5593943874611345e+00 , -1.3471542688744247e+00 , 8.0476000000000010e+00 , -5.3552200000000005e-01 , -7.2156399999999998e-01 , 4.3881900000000001e-01 -4.5752302574417456e+00 , -1.3840769628286478e+00 , 8.2735711999999992e+00 , 1.4563599999999999e-01 , -5.7726100000000002e-01 , 8.0346799999999996e-01 -4.8482794482375340e+00 , -1.8828715458122289e+00 , 9.1658496000000014e+00 , -2.1239700000000000e-01 , -9.6367400000000003e-01 , -1.6192400000000001e-01 -4.4484470947689259e+00 , -1.1778411024436082e+00 , 8.3478376000000001e+00 , -7.9199399999999998e-01 , 3.5814200000000002e-01 , -4.9444900000000003e-01 -4.3901309218803659e+00 , -1.0832712364230219e+00 , 8.3936911999999992e+00 , -1.3522100000000001e-01 , 9.7669300000000003e-01 , 1.6669000000000000e-01 -4.3913560559803102e+00 , -1.0947592349761712e+00 , 8.6057264000000000e+00 , 6.1924699999999999e-01 , -7.0913599999999999e-01 , 3.3713399999999999e-01 -4.3536650976130709e+00 , -1.0388047072287314e+00 , 8.7172663999999997e+00 , 5.7983899999999999e-01 , -7.1268900000000002e-01 , 3.9479300000000001e-01 -4.3150768839648599e+00 , -9.7978493579101622e-01 , 8.8280576000000011e+00 , -6.0858900000000005e-01 , 6.1644800000000000e-01 , -4.9961100000000003e-01 -4.1454719932917259e+00 , -6.8113348038161448e-01 , 8.5192192000000002e+00 , -3.7891900000000001e-01 , -2.3193100000000000e-01 , 8.9589500000000000e-01 -4.0654308889422772e+00 , -5.4702515515711303e-01 , 8.4826112000000009e+00 , -5.4307899999999998e-01 , -5.1857299999999995e-01 , 6.6041399999999995e-01 -4.0587754640755431e+00 , -5.4696294387785160e-01 , 8.6923063999999997e+00 , -3.3843200000000001e-01 , -4.3174400000000002e-01 , 8.3609900000000004e-01 -3.9674271776809658e+00 , -3.8953047902166604e-01 , 8.6057264000000000e+00 , 5.4238600000000003e-01 , 4.6096100000000001e-01 , -7.0237700000000003e-01 -3.7005317546464607e+00 , 9.1156114690321255e-02 , 7.8409519999999997e+00 , 5.9830799999999995e-01 , 7.3448100000000005e-01 , -3.2025900000000002e-01 -3.5994717436831971e+00 , 2.6859638169221944e-01 , 7.6565184000000004e+00 , 8.0683299999999999e-02 , 8.9945500000000000e-01 , -4.2950100000000002e-01 -3.6215106709411287e+00 , 2.1656813971039224e-01 , 7.9669376000000005e+00 , -1.8826499999999999e-02 , -9.2923100000000003e-01 , 3.6902099999999999e-01 -3.6701669779279644e+00 , 1.1269694733058566e-01 , 8.4209807999999988e+00 , 5.8728400000000000e-02 , 2.2410300000000000e-01 , 9.7279400000000005e-01 -3.5718467737776858e+00 , 2.8520644276735174e-01 , 8.2390640000000008e+00 , -1.8357000000000001e-01 , -7.7109399999999995e-01 , 6.0968500000000003e-01 -3.5300103451186295e+00 , 3.5093216607212541e-01 , 8.3086504000000012e+00 , -2.2850799999999999e-01 , -9.3050400000000000e-01 , 2.8626299999999999e-01 -3.4911710210822120e+00 , 4.1160949027609939e-01 , 8.3959791999999993e+00 , 2.3758599999999999e-01 , -7.8671500000000005e-01 , 5.6976599999999999e-01 -3.4712963147885985e+00 , 4.3537226918056682e-01 , 8.5887431999999997e+00 , 6.9941399999999998e-01 , -7.0303499999999997e-01 , 1.2869000000000000e-01 -3.4426345572827972e+00 , 4.7494773139288493e-01 , 8.7527200000000001e+00 , 8.7708699999999995e-01 , -4.6082200000000001e-01 , -1.3550499999999999e-01 -3.3877098274266384e+00 , 5.6576945992426642e-01 , 8.7701400000000014e+00 , 5.4102300000000003e-01 , 3.0282599999999998e-01 , -7.8459500000000004e-01 -3.3153952204485990e+00 , 6.9031253504251366e-01 , 8.6771951999999999e+00 , 7.6382399999999995e-01 , 5.6437800000000005e-01 , -3.1313000000000002e-01 -3.2710288881650289e+00 , 7.5868765564197038e-01 , 8.7593968000000011e+00 , 5.3827899999999995e-01 , 3.9858800000000000e-01 , 7.4255199999999999e-01 -3.1382393731299274e+00 , 1.0094416365120178e+00 , 8.1837568000000012e+00 , 4.4715300000000002e-01 , 2.5425500000000001e-01 , 8.5755999999999999e-01 -3.0645401675601618e+00 , 1.1401346231369280e+00 , 7.9998016000000005e+00 , 8.4206199999999998e-01 , -1.2579000000000001e-01 , 5.2450799999999997e-01 -3.0526680204609931e+00 , 1.1458352241032563e+00 , 8.3048855999999986e+00 , 2.9860100000000001e-01 , -3.0452499999999999e-01 , 9.0449000000000002e-01 -3.0024519256489564e+00 , 1.2282849717791136e+00 , 8.3081200000000006e+00 , -5.3597099999999998e-01 , 2.5718400000000002e-01 , -8.0410899999999996e-01 -2.9483353773937733e+00 , 1.3215795944511823e+00 , 8.2589591999999996e+00 , -5.3597099999999998e-01 , 2.5718400000000002e-01 , -8.0410899999999996e-01 -3.0788597413866219e+00 , 1.0025195438147616e+00 , 1.0323889600000001e+01 , -1.0511400000000000e-01 , -6.2719999999999998e-01 , 7.7173300000000000e-01 -2.7990505633419360e+00 , 1.6037043522441634e+00 , 7.5825224000000002e+00 , -1.4141300000000001e-02 , 4.4230300000000000e-01 , 8.9675400000000005e-01 -2.7538064650408818e+00 , 1.6811314444272780e+00 , 7.5355455999999998e+00 , -7.8614899999999999e-01 , -9.3183900000000000e-02 , 6.1097199999999996e-01 -2.7128353390472157e+00 , 1.7492471983222468e+00 , 7.5381352000000001e+00 , 7.8948499999999999e-01 , 2.9703099999999999e-01 , -5.3710899999999995e-01 -2.7787091700704822e+00 , 1.5314645140643663e+00 , 9.7019383999999995e+00 , 8.7790800000000002e-02 , -8.9397199999999999e-01 , -4.3944000000000000e-01 -2.7183885265429550e+00 , 1.6327452029088927e+00 , 9.6963640000000009e+00 , -8.9259800000000000e-01 , -3.3825800000000000e-01 , -2.9807699999999998e-01 -2.6622124611523725e+00 , 1.7179406585748431e+00 , 9.8437216000000003e+00 , 3.2573299999999999e-01 , -4.0357300000000002e-01 , 8.5500100000000001e-01 -2.5913142985258055e+00 , 1.8597386880337075e+00 , 9.3887320000000010e+00 , -4.2856899999999998e-01 , -2.1381100000000000e-01 , 8.7784600000000002e-01 -2.5410099512203530e+00 , 1.9171825293579885e+00 , 9.9055496000000005e+00 , 7.6783900000000005e-01 , 5.9052499999999997e-01 , -2.4840100000000001e-01 -2.4749557439988656e+00 , 2.0684356729777083e+00 , 9.0505551999999998e+00 , 7.1179000000000003e-01 , -2.0183200000000001e-01 , 6.7276999999999998e-01 -2.4183577048561995e+00 , 2.1315069406209428e+00 , 9.6888240000000003e+00 , -4.5237400000000000e-01 , 7.8915900000000005e-01 , 4.1543500000000000e-01 -2.3597972129124769e+00 , 2.2325116646801551e+00 , 9.6084631999999992e+00 , 9.0155500000000000e-01 , -2.3631500000000000e-02 , -4.3201899999999999e-01 -2.3083518162652488e+00 , 2.3334532330514763e+00 , 9.2974096000000017e+00 , 6.6508400000000001e-01 , 3.0295899999999998e-01 , 6.8255399999999999e-01 -2.2641233470006794e+00 , 2.4253279297761150e+00 , 8.9428944000000001e+00 , 7.4906000000000000e-02 , 7.4109599999999998e-01 , 6.6720800000000002e-01 -2.2139433237890453e+00 , 2.5120179264459397e+00 , 8.8776031999999994e+00 , -9.3607499999999999e-01 , -2.9026500000000000e-01 , -1.9877300000000001e-01 -2.1406943785774999e+00 , 2.6127503494317690e+00 , 9.2881640000000019e+00 , -1.1292900000000000e-01 , 2.6252500000000001e-01 , 9.5829399999999998e-01 -2.0829043568926284e+00 , 2.7071902345966192e+00 , 9.3124064000000004e+00 , -2.9251199999999999e-01 , 3.5325600000000001e-01 , 8.8862099999999999e-01 -2.0253493549342609e+00 , 2.8023133909054190e+00 , 9.3348288000000004e+00 , -4.8422500000000002e-01 , 1.7366000000000001e-01 , -8.5753599999999996e-01 -1.9880062699778493e+00 , 2.8759991954565303e+00 , 9.0759624000000017e+00 , 6.7086500000000004e-01 , -6.0571399999999997e-01 , -4.2784499999999998e-01 -1.6188836706485752e+00 , 3.3097974187837513e+00 , 1.2726144000000000e+01 , -9.6479099999999995e-01 , -3.6636900000000000e-02 , -2.6045200000000002e-01 -1.5216479746280087e+00 , 3.4660788927215478e+00 , 1.2817040000000000e+01 , 8.9939800000000003e-01 , 4.0597499999999997e-01 , 1.6207400000000000e-01 -1.4163412157212663e+00 , 3.6354000188896540e+00 , 1.2976160000000000e+01 , 9.8996099999999998e-01 , 3.2264300000000003e-02 , 1.3761200000000001e-01 -1.7399951280220654e+00 , 3.2774064888921117e+00 , 9.3236488000000008e+00 , 4.8459200000000002e-01 , 8.5150499999999996e-01 , 2.0027400000000001e-01 -3.5270652461236764e+00 , 5.9914356788257783e-01 , 1.4131716800000000e+00 , -1.2988100000000000e-01 , 2.4683300000000000e-01 , 9.6031500000000003e-01 -3.5571233694626914e+00 , 5.4498441793156194e-01 , 1.4248030400000000e+00 , -9.6413600000000002e-02 , 2.3099100000000000e-01 , 9.6816700000000000e-01 -3.5821904599707817e+00 , 4.9791012834054205e-01 , 1.4442146400000000e+00 , -4.1051100000000000e-02 , 1.6425799999999999e-01 , 9.8556299999999997e-01 -3.6214248793509585e+00 , 4.2884489778579482e-01 , 1.4470715200000002e+00 , -9.1411599999999996e-02 , 1.2992699999999999e-01 , 9.8730099999999998e-01 -3.6508494094687531e+00 , 3.7362349801951766e-01 , 1.4638685599999999e+00 , -9.6776000000000001e-02 , 1.4788899999999999e-01 , 9.8425799999999997e-01 -3.6858872735747834e+00 , 3.1201640687825871e-01 , 1.4765534400000000e+00 , -9.3213099999999993e-02 , 1.4558800000000000e-01 , 9.8494400000000004e-01 -3.7254033758895595e+00 , 2.4208507369428389e-01 , 1.4857127200000000e+00 , -8.2970900000000000e-02 , 1.9625200000000001e-01 , 9.7703700000000004e-01 -3.7598958011351424e+00 , 1.7924259507959306e-01 , 1.5026532800000001e+00 , -9.4126500000000002e-02 , 2.1652199999999999e-01 , 9.7172999999999998e-01 -3.7941349283111969e+00 , 1.1576513658492726e-01 , 1.5216187200000000e+00 , -8.6573499999999998e-02 , 2.0168900000000001e-01 , 9.7561600000000004e-01 -3.8338631546491619e+00 , 4.5049104198208623e-02 , 1.5374870400000000e+00 , -8.2225300000000001e-02 , 2.0263700000000001e-01 , 9.7579600000000000e-01 -3.8732807828596370e+00 , -2.6228631173369710e-02 , 1.5557858400000000e+00 , -6.7233899999999999e-02 , 2.4047099999999999e-01 , 9.6832499999999999e-01 -3.9078110895679035e+00 , -8.9519726366872110e-02 , 1.5810526400000000e+00 , -8.0247399999999997e-02 , 2.4779999999999999e-01 , 9.6548199999999995e-01 -3.9522871163085540e+00 , -1.6947100651725489e-01 , 1.5994960000000000e+00 , 5.8636199999999999e-02 , -2.0610899999999999e-01 , -9.7677099999999994e-01 -3.9964824269041488e+00 , -2.4892739140002540e-01 , 1.6203688000000001e+00 , -6.7728099999999999e-02 , 1.7708800000000000e-01 , 9.8186200000000001e-01 -4.0504603799844103e+00 , -3.4586227147023063e-01 , 1.6356359999999999e+00 , -1.0780700000000000e-01 , 1.9028500000000001e-01 , 9.7579199999999999e-01 -4.0939660292542772e+00 , -4.2521439257311844e-01 , 1.6621767999999999e+00 , -9.4604599999999997e-02 , 1.9337399999999999e-01 , 9.7655300000000000e-01 -4.1527503147486371e+00 , -5.3036456060207327e-01 , 1.6798152000000000e+00 , 6.9142599999999999e-02 , -1.4869599999999999e-01 , -9.8646299999999998e-01 -4.2065231820272562e+00 , -6.2843400059311305e-01 , 1.7052328000000001e+00 , -3.1360699999999998e-02 , 2.0214599999999999e-01 , 9.7885299999999997e-01 -4.2654376356671531e+00 , -7.3422630824386914e-01 , 1.7302874400000001e+00 , -4.1331699999999999e-02 , 1.9089900000000001e-01 , 9.8073900000000003e-01 -4.3438242533859448e+00 , -8.7367865383406729e-01 , 1.7452405600000001e+00 , -5.9247200000000000e-02 , 1.7860000000000001e-01 , 9.8213600000000001e-01 -4.3972785285876599e+00 , -9.7158983363259388e-01 , 1.7819192799999999e+00 , -9.6171599999999996e-02 , 1.9637900000000000e-01 , 9.7580000000000000e-01 -4.4656672253277314e+00 , -1.0947003101172319e+00 , 1.8126294400000000e+00 , -7.2476399999999996e-02 , 1.8931200000000001e-01 , 9.7923899999999997e-01 -4.5433230076744548e+00 , -1.2354680710102648e+00 , 1.8419855199999999e+00 , -8.6706500000000006e-02 , 1.7646800000000001e-01 , 9.8048000000000002e-01 -4.6267628032915171e+00 , -1.3855050939714757e+00 , 1.8740445600000000e+00 , 1.1005600000000000e-01 , -2.0937600000000001e-01 , -9.7162199999999999e-01 -4.7051636245045172e+00 , -1.5272784841240963e+00 , 1.9143860560000001e+00 , -1.1363200000000000e-01 , 2.1402900000000000e-01 , 9.7019599999999995e-01 -4.7872834636891248e+00 , -1.6771904491130658e+00 , 1.9572764880000000e+00 , -9.6940999999999999e-02 , 1.8315899999999999e-01 , 9.7829200000000005e-01 -4.8900999822313640e+00 , -1.8626153122553464e+00 , 1.9970039680000000e+00 , -8.6090899999999998e-02 , 1.7693100000000000e-01 , 9.8045099999999996e-01 -4.9984197978988849e+00 , -2.0568145421981923e+00 , 2.0417603679999998e+00 , 1.0115300000000001e-01 , -1.8694200000000000e-01 , -9.7714900000000005e-01 -5.1111554581364045e+00 , -2.2596583961961159e+00 , 2.0920272080000002e+00 , -8.8077900000000001e-02 , 2.0163400000000001e-01 , 9.7549300000000005e-01 -5.2324971926838284e+00 , -2.4800919092701088e+00 , 2.1464070400000002e+00 , -8.1212000000000006e-02 , 1.8467400000000000e-01 , 9.7943899999999995e-01 -5.3748317526507652e+00 , -2.7369757719735066e+00 , 2.2035228000000000e+00 , -9.1211700000000007e-02 , 1.9572000000000001e-01 , 9.7640899999999997e-01 -5.5170271892640450e+00 , -2.9929115761700258e+00 , 2.2705820000000001e+00 , -6.9601899999999994e-02 , 1.9541100000000000e-01 , 9.7824800000000001e-01 -5.6934760725370328e+00 , -3.3115579064310783e+00 , 2.3393457600000001e+00 , -7.9950400000000005e-02 , 1.8410899999999999e-01 , 9.7964899999999999e-01 -5.8757009751309441e+00 , -3.6387535355829348e+00 , 2.4196410400000001e+00 , -8.5190000000000002e-02 , 1.9693700000000000e-01 , 9.7670800000000002e-01 -6.0760049631814814e+00 , -4.0019502293447733e+00 , 2.5096083199999999e+00 , -8.2353599999999999e-02 , 1.8672400000000000e-01 , 9.7895500000000002e-01 -6.3219418568574079e+00 , -4.4460415714597890e+00 , 2.6083022400000000e+00 , -6.8447499999999994e-02 , 1.9081400000000001e-01 , 9.7923700000000002e-01 -6.5873233750164193e+00 , -4.9249658017053024e+00 , 2.7226856000000002e+00 , -7.5975500000000001e-02 , 1.8394900000000000e-01 , 9.7999499999999995e-01 -6.9076276066480800e+00 , -5.5017688326749843e+00 , 2.8531733600000000e+00 , 7.4847700000000003e-02 , -1.9021399999999999e-01 , -9.7888500000000001e-01 -7.2516209651409467e+00 , -6.1228269152911601e+00 , 3.0061781600000002e+00 , -6.6129900000000005e-02 , 1.9047400000000000e-01 , 9.7946299999999997e-01 -7.6746555000639951e+00 , -6.8864093381220943e+00 , 3.1854336000000001e+00 , -6.3879400000000003e-02 , 1.8568499999999999e-01 , 9.8053100000000004e-01 -8.1767075223870762e+00 , -7.7928180258435784e+00 , 3.3997672000000003e+00 , -6.1583100000000002e-02 , 1.9667799999999999e-01 , 9.7853199999999996e-01 -8.7366884727188676e+00 , -8.8048686168599275e+00 , 3.6559816000000001e+00 , -5.6192600000000002e-02 , 1.9636100000000001e-01 , 9.7892000000000001e-01 -9.4808173193443608e+00 , -1.0146324850283881e+01 , 3.9761975999999999e+00 , -6.1763100000000001e-02 , 1.8148400000000001e-01 , 9.8145199999999999e-01 -1.0442456070972066e+01 , -1.1881415007621115e+01 , 4.3868831999999998e+00 , -5.8941300000000002e-02 , 1.8575800000000001e-01 , 9.8082599999999998e-01 -5.3018067702112175e+00 , -2.9489513959665112e+00 , 7.5761263999999997e+00 , 9.5282400000000003e-02 , -4.5777099999999998e-01 , 8.8395000000000001e-01 -5.2250748601984238e+00 , -2.8159868344423655e+00 , 7.6241744000000002e+00 , 5.3750900000000003e-04 , -6.0833099999999996e-01 , 7.9368300000000003e-01 -5.1758962566190831e+00 , -2.7332004997464390e+00 , 7.7136248000000007e+00 , 5.3754100000000000e-04 , -6.0833099999999996e-01 , 7.9368300000000003e-01 -5.1140884539319549e+00 , -2.6277400264080875e+00 , 7.7811935999999999e+00 , 2.0674999999999999e-01 , -7.4439900000000003e-01 , 6.3492000000000004e-01 -5.0816839728318879e+00 , -2.5779721590734788e+00 , 7.9000760000000003e+00 , 6.3247500000000001e-01 , -6.8105000000000004e-01 , 3.6897999999999997e-01 -5.0740777050790911e+00 , -2.5738474720704696e+00 , 8.0664864000000005e+00 , 2.8774400000000000e-01 , -8.3768399999999998e-01 , 4.6420800000000001e-01 -4.5399274737239441e+00 , -1.5700267590331456e+00 , 7.2007592000000002e+00 , -6.9366899999999998e-01 , 7.0294100000000004e-01 , -1.5715100000000001e-01 -4.4874010761271226e+00 , -1.4814566376730580e+00 , 7.2497119999999997e+00 , -6.9367100000000004e-01 , 7.0294000000000001e-01 , -1.5715000000000001e-01 -4.4637837622286884e+00 , -1.4444134766537440e+00 , 7.3547312000000007e+00 , -9.2960000000000001e-02 , -9.8159799999999997e-01 , 1.6680400000000001e-01 -4.4856052011878980e+00 , -1.4967298707480383e+00 , 7.5635216000000005e+00 , 3.4849700000000000e-01 , 8.2664899999999997e-01 , -4.4181700000000002e-01 -4.4703992121337626e+00 , -1.4792471438415875e+00 , 7.6997616000000004e+00 , 3.9894499999999999e-01 , 7.9758899999999999e-01 , -4.5243200000000000e-01 -4.3838848916151916e+00 , -1.3226281331448972e+00 , 7.6681143999999994e+00 , 3.6590699999999998e-01 , -7.7808800000000000e-01 , 5.1057900000000001e-01 -4.3636890961527488e+00 , -1.2961820575245113e+00 , 7.7950672000000010e+00 , 1.6685300000000000e-01 , -9.5037099999999997e-01 , 2.6259399999999999e-01 -4.3435133877261958e+00 , -1.2664847837202258e+00 , 7.9223216000000001e+00 , -1.4281500000000000e-01 , -9.6199000000000001e-01 , 2.3276400000000000e-01 -4.3957286846800159e+00 , -1.3820500161826943e+00 , 8.2505975999999990e+00 , -3.9361299999999999e-01 , -7.2682700000000000e-01 , 5.6284199999999995e-01 -4.7916046278343885e+00 , -2.1671293247644172e+00 , 9.5453144000000005e+00 , -4.0719000000000000e-01 , 9.0371100000000004e-01 , -1.3229800000000000e-01 -4.7015787617791709e+00 , -2.0076354444804130e+00 , 9.5430160000000015e+00 , -4.0719000000000000e-01 , 9.0371100000000004e-01 , -1.3229800000000000e-01 -4.2912544698860131e+00 , -1.2156162438762999e+00 , 8.5747447999999995e+00 , -1.7938499999999999e-01 , 9.7969200000000001e-01 , -8.9579300000000001e-02 -4.1487537330507376e+00 , -9.4974627150250290e-01 , 8.3566880000000001e+00 , 4.8773699999999998e-01 , 4.8294900000000002e-01 , -7.2723599999999999e-01 -4.0964244273061450e+00 , -8.5932162704420856e-01 , 8.4043200000000002e+00 , -7.4865899999999999e-02 , -4.5061000000000001e-01 , 8.8957600000000003e-01 -4.0151229149446026e+00 , -7.1192849456468643e-01 , 8.3543480000000017e+00 , -2.4084400000000000e-01 , -4.2658200000000000e-02 , 9.6962599999999999e-01 -3.9784534024379665e+00 , -6.5190431475916411e-01 , 8.4494456000000007e+00 , -1.8325000000000000e-01 , -1.5147300000000000e-01 , 9.7132700000000005e-01 -3.9089397749566297e+00 , -5.2680406451166872e-01 , 8.4283543999999999e+00 , 1.4137700000000000e-01 , 4.6023700000000001e-01 , -8.7646700000000000e-01 -3.8586541455214265e+00 , -4.4185454216913067e-01 , 8.4756432000000004e+00 , -2.9460599999999998e-01 , -3.7731399999999998e-01 , 8.7797599999999998e-01 -3.8204785673834101e+00 , -3.7837917748968852e-01 , 8.5664352000000008e+00 , -4.9163499999999999e-01 , -4.4106800000000002e-01 , 7.5083599999999995e-01 -3.5624362626206030e+00 , 1.3239235509189373e-01 , 7.7420792000000000e+00 , -3.2335199999999997e-01 , 7.1899900000000005e-01 , -6.1521000000000003e-01 -3.5568778145609503e+00 , 1.2945103128650515e-01 , 7.9423623999999995e+00 , -1.7558900000000000e-01 , -9.6615899999999999e-01 , 1.8895799999999999e-01 -3.4792299929786208e+00 , 2.7421033892562963e-01 , 7.8274112000000002e+00 , -4.9287199999999998e-01 , -8.6538000000000004e-01 , -9.0528399999999995e-02 -3.5053619631339781e+00 , 2.0513137989612851e-01 , 8.1963512000000005e+00 , 6.1274200000000001e-01 , -1.2134000000000000e-01 , -7.8091200000000005e-01 -3.4320572616776985e+00 , 3.4097664492986346e-01 , 8.0960432000000004e+00 , -7.0137700000000003e-01 , -1.2442700000000000e-01 , 7.0184599999999997e-01 -3.4040206835744908e+00 , 3.8327866065799099e-01 , 8.2209472000000012e+00 , 5.0955799999999996e-01 , 7.8044199999999997e-01 , -3.6230099999999998e-01 -3.3852440589902928e+00 , 4.0361366749310368e-01 , 8.4127232000000003e+00 , 4.3414599999999998e-01 , -8.2179899999999995e-01 , 3.6900200000000000e-01 -3.3419454153373129e+00 , 4.7748975823849915e-01 , 8.4697567999999990e+00 , 3.4324700000000002e-01 , -6.0865300000000000e-01 , -7.1534799999999998e-01 -3.2737362121460034e+00 , 6.0568770528477689e-01 , 8.3694904000000001e+00 , -7.1131200000000006e-02 , 3.8733899999999999e-01 , 9.1918900000000003e-01 -3.4720790717224488e+00 , 1.4422338536463553e-01 , 1.0079396000000001e+01 , 1.9839300000000001e-01 , -4.0317700000000001e-01 , 8.9335799999999999e-01 -3.4039619260005205e+00 , 2.6565922955585930e-01 , 1.0072053600000000e+01 , -1.1537799999999999e-01 , -7.1064400000000005e-01 , 6.9402699999999995e-01 -3.0949891418036986e+00 , 9.3707951732770112e-01 , 8.1578920000000004e+00 , 5.0930699999999995e-01 , 2.1903800000000001e-01 , 8.3224299999999996e-01 -3.0501368362439925e+00 , 1.0134951651654229e+00 , 8.1850360000000002e+00 , 2.0621899999999999e-02 , -3.9168199999999997e-01 , 9.1986900000000005e-01 -3.0038475074003363e+00 , 1.0962198818823841e+00 , 8.1905064000000003e+00 , 2.3279400000000000e-01 , -3.0686000000000002e-01 , 9.2284600000000006e-01 -2.9602674642126168e+00 , 1.1717930150332154e+00 , 8.2242752000000010e+00 , 1.7467500000000000e-01 , -2.1423600000000001e-01 , 9.6103700000000003e-01 -2.9176467926128637e+00 , 1.2448843960830904e+00 , 8.2670087999999993e+00 , -5.3597200000000000e-01 , 2.5718400000000002e-01 , -8.0410899999999996e-01 -2.8972446374716530e+00 , 1.2613658044450591e+00 , 8.5921647999999990e+00 , -7.0213499999999995e-01 , 6.7789800000000000e-01 , -2.1785399999999999e-01 -2.9617572043121898e+00 , 1.0436711535491279e+00 , 1.0181638400000001e+01 , -9.2935299999999998e-02 , 2.6698499999999997e-01 , 9.5920899999999998e-01 -2.9094136973647857e+00 , 1.1263136110459420e+00 , 1.0348787200000000e+01 , -9.2935400000000001e-02 , 2.6698499999999997e-01 , 9.5920899999999998e-01 -2.8222780240369345e+00 , 1.3079474899235204e+00 , 9.9299479999999996e+00 , -2.3975700000000000e-01 , 4.1330400000000000e-01 , 8.7846199999999997e-01 -2.7536109589585802e+00 , 1.4443561412905486e+00 , 9.7227488000000015e+00 , -5.5170200000000003e-01 , -2.3380400000000001e-01 , -8.0059999999999998e-01 -2.6932998114123339e+00 , 1.5545991259207284e+00 , 9.6667863999999994e+00 , -4.2863099999999998e-01 , -6.5451000000000004e-01 , -6.2280999999999997e-01 -2.6483573081811813e+00 , 1.6064424844308505e+00 , 1.0104252000000001e+01 , -8.4529799999999999e-01 , 4.9082399999999998e-01 , -2.1109900000000001e-01 -2.5815098894974793e+00 , 1.7447682177329122e+00 , 9.7962768000000011e+00 , -4.5270699999999997e-02 , -4.6399899999999999e-01 , 8.8467799999999996e-01 -2.5251837831898709e+00 , 1.8380012002868560e+00 , 9.9202551999999997e+00 , -8.6258900000000005e-01 , -4.1684399999999999e-01 , -2.8667199999999998e-01 -2.4634446312274085e+00 , 2.0068099401585697e+00 , 8.9635800000000003e+00 , 8.2537300000000002e-01 , 1.6320200000000001e-01 , 5.4048600000000002e-01 -2.4098499456316622e+00 , 2.0713298137143075e+00 , 9.4568416000000006e+00 , -9.1686299999999998e-02 , -7.7256700000000000e-01 , 6.2827800000000000e-01 -2.3567456115742398e+00 , 2.1701163897281033e+00 , 9.4087936000000010e+00 , 5.9182199999999997e-02 , 4.6448699999999998e-01 , 8.8360000000000005e-01 -2.3021600130475384e+00 , 2.2663164457256508e+00 , 9.3897615999999999e+00 , -5.8091400000000004e-01 , -9.6764400000000000e-02 , -8.0819300000000005e-01 -2.2607124052236598e+00 , 2.3657680071749412e+00 , 9.0049303999999992e+00 , 1.1932100000000000e-01 , 6.2349500000000002e-01 , 7.7266800000000002e-01 -2.2169922071661397e+00 , 2.4538056767174909e+00 , 8.8264871999999990e+00 , -3.5921700000000001e-01 , -6.7088499999999995e-01 , -6.4875000000000005e-01 -2.1407928730513732e+00 , 2.5544928866637271e+00 , 9.3732152000000006e+00 , 1.3363400000000000e-01 , 3.2313900000000001e-01 , 9.3686899999999995e-01 -2.0891782534535270e+00 , 2.6490661331766479e+00 , 9.3467471999999994e+00 , -1.3862900000000000e-01 , 5.9559800000000003e-02 , 9.8855199999999999e-01 -2.0384427649142203e+00 , 2.7422078201887747e+00 , 9.2869992000000003e+00 , 6.6240500000000002e-01 , -2.2816600000000001e-01 , 7.1355400000000002e-01 -1.9829107958275380e+00 , 2.8391555817103478e+00 , 9.3189063999999995e+00 , 3.1069300000000000e-01 , -2.3133300000000001e-01 , 9.2193000000000003e-01 -1.9443168094595900e+00 , 2.9198917279524284e+00 , 9.1316647999999994e+00 , 3.5339999999999999e-01 , -8.4163600000000005e-01 , 4.0835900000000003e-01 -1.5305716414197534e+00 , 3.4064258625988164e+00 , 1.3044592000000000e+01 , -7.7435799999999999e-01 , -6.3207000000000002e-01 , -2.9275300000000001e-02 -1.4462354551172845e+00 , 3.5580214681062907e+00 , 1.3020152000000000e+01 , -9.6266799999999997e-01 , -2.2185800000000000e-01 , 1.5507799999999999e-01 -1.7643081049766864e+00 , 3.2262742920885317e+00 , 9.3227440000000001e+00 , -1.1441700000000000e-01 , 3.0424699999999999e-01 , 9.4569700000000001e-01 -1.7167156030595101e+00 , 3.3159931249528594e+00 , 9.2624759999999995e+00 , 9.7889100000000007e-02 , -9.6734399999999998e-01 , 2.3380000000000001e-01 -3.4914592714847434e+00 , 5.5388356600441102e-01 , 1.4233480800000000e+00 , -1.4098300000000000e-01 , 2.5876399999999999e-01 , 9.5559700000000003e-01 -3.5241540538208680e+00 , 4.9210924287000957e-01 , 1.4293790399999999e+00 , -1.2341199999999999e-01 , 1.4173800000000000e-01 , 9.8218099999999997e-01 -3.5528436107136763e+00 , 4.3637806483962627e-01 , 1.4435220000000000e+00 , 1.6897499999999999e-01 , -1.3114300000000001e-01 , -9.7685699999999998e-01 -3.5850687115838840e+00 , 3.7325637272807910e-01 , 1.4533032000000001e+00 , -1.2469000000000000e-01 , 1.9033300000000000e-01 , 9.7376900000000000e-01 -3.6181026150253590e+00 , 3.1048964044624605e-01 , 1.4650302399999999e+00 , -1.2949300000000000e-01 , 1.7637500000000000e-01 , 9.7576799999999997e-01 -3.6508852865583457e+00 , 2.4707773559202839e-01 , 1.4787852800000001e+00 , -9.9548999999999999e-02 , 1.7130300000000001e-01 , 9.8017600000000005e-01 -3.6834146600218025e+00 , 1.8303085085783621e-01 , 1.4945651999999998e+00 , -9.3063900000000005e-02 , 2.2570999999999999e-01 , 9.6973900000000002e-01 -3.7167385110420379e+00 , 1.1935724517713675e-01 , 1.5123939200000001e+00 , -9.6440399999999996e-02 , 2.3252900000000001e-01 , 9.6779599999999999e-01 -3.7498111301537844e+00 , 5.5038466924053564e-02 , 1.5322496000000001e+00 , -6.5950400000000006e-02 , 1.9032399999999999e-01 , 9.7950400000000004e-01 -3.7909099284179160e+00 , -2.5056223607368366e-02 , 1.5440161600000000e+00 , -1.1848000000000000e-01 , 2.1235499999999999e-01 , 9.6998399999999996e-01 -3.8234424729447474e+00 , -8.9537538018674478e-02 , 1.5682252800000001e+00 , -1.3145599999999999e-01 , 2.5033000000000000e-01 , 9.5919399999999999e-01 -3.8613911214947949e+00 , -1.6220603728008021e-01 , 1.5898437599999999e+00 , 1.1020099999999999e-01 , -2.4121999999999999e-01 , -9.6419299999999997e-01 -3.9026036967289337e+00 , -2.4291435551711560e-01 , 1.6091284799999999e+00 , -8.0817899999999998e-02 , 1.7677100000000001e-01 , 9.8092900000000005e-01 -3.9536717714736422e+00 , -3.4009952836044999e-01 , 1.6225008000000001e+00 , 9.0527300000000005e-02 , -1.5713700000000000e-01 , -9.8341900000000004e-01 -3.9997427530170988e+00 , -4.3022229238964815e-01 , 1.6435514400000000e+00 , -9.1817599999999999e-02 , 1.8185499999999999e-01 , 9.7902900000000004e-01 -4.0465138592734391e+00 , -5.1976806162995404e-01 , 1.6675619200000000e+00 , -9.4407099999999994e-02 , 1.6820399999999999e-01 , 9.8122100000000001e-01 -4.1018581249066681e+00 , -6.2757868814477646e-01 , 1.6871586400000000e+00 , 6.3298900000000005e-02 , -1.7894399999999999e-01 , -9.8182100000000005e-01 -4.1568109303754177e+00 , -7.3466219174039882e-01 , 1.7101956800000000e+00 , 7.8459200000000007e-02 , -2.0042599999999999e-01 , -9.7656200000000004e-01 -4.2123254388290272e+00 , -8.4205629346351119e-01 , 1.7371046400000001e+00 , -8.0311300000000002e-02 , 1.4815400000000001e-01 , 9.8569799999999996e-01 -4.2772750769666734e+00 , -9.6741318414172239e-01 , 1.7612440800000000e+00 , 8.4839800000000007e-02 , -2.0269699999999999e-01 , -9.7555899999999995e-01 -4.3372369803878890e+00 , -1.0846021704523170e+00 , 1.7931606400000000e+00 , -1.0018400000000000e-01 , 2.1343200000000001e-01 , 9.7180800000000001e-01 -4.4065941984513710e+00 , -1.2185629144159664e+00 , 1.8229119199999999e+00 , 8.5934499999999997e-02 , -1.7675700000000000e-01 , -9.8049600000000003e-01 -4.4851087304224642e+00 , -1.3711051741519507e+00 , 1.8520204800000000e+00 , -9.2866900000000002e-02 , 1.8004800000000001e-01 , 9.7926400000000002e-01 -4.5586081096015967e+00 , -1.5143496543727326e+00 , 1.8893086400000001e+00 , 9.6022800000000005e-02 , -1.9659299999999999e-01 , -9.7577199999999997e-01 -4.6378709785534573e+00 , -1.6668144993606844e+00 , 1.9295009999999999e+00 , -1.1390800000000000e-01 , 1.9630600000000001e-01 , 9.7390399999999999e-01 -4.7304096279675916e+00 , -1.8466612693999815e+00 , 1.9683625760000001e+00 , 1.0943799999999999e-01 , -1.7042499999999999e-01 , -9.7927500000000001e-01 -4.8275415245139293e+00 , -2.0343526724875804e+00 , 2.0114163920000001e+00 , -1.0151100000000000e-01 , 1.6760800000000001e-01 , 9.8061399999999999e-01 -4.9386420339116430e+00 , -2.2499646940835216e+00 , 2.0558987520000001e+00 , -1.1213200000000000e-01 , 1.9556100000000001e-01 , 9.7426000000000001e-01 -5.0349795965448330e+00 , -2.4388676575016115e+00 , 2.1138612800000001e+00 , -1.1513300000000000e-01 , 1.8529699999999999e-01 , 9.7591499999999998e-01 -5.1694798487378328e+00 , -2.6996104791453508e+00 , 2.1659340800000000e+00 , 1.0862400000000000e-01 , -1.7205699999999999e-01 , -9.7907999999999995e-01 -5.2996303624524508e+00 , -2.9504643395832986e+00 , 2.2293460000000000e+00 , 1.1235900000000000e-01 , -2.0699100000000001e-01 , -9.7186899999999998e-01 -5.4327727822811482e+00 , -3.2114187383298969e+00 , 2.3011840000000001e+00 , -9.7410099999999999e-02 , 1.7434400000000000e-01 , 9.7985500000000003e-01 -5.6198504729647318e+00 , -3.5717148736832725e+00 , 2.3710366399999998e+00 , -9.5084900000000000e-02 , 1.8176300000000001e-01 , 9.7873500000000002e-01 -5.8000785969173849e+00 , -3.9224059461009606e+00 , 2.4555220800000002e+00 , -9.3636999999999998e-02 , 1.8114400000000000e-01 , 9.7898900000000000e-01 -6.0137257478800814e+00 , -4.3365072660193622e+00 , 2.5485989600000001e+00 , -8.9410100000000006e-02 , 1.8922300000000000e-01 , 9.7785500000000003e-01 -6.2459481225821412e+00 , -4.7868062010104797e+00 , 2.6557252000000000e+00 , -8.0359200000000006e-02 , 1.8101300000000001e-01 , 9.8019199999999995e-01 -6.5251421592742398e+00 , -5.3276926260287194e+00 , 2.7765128799999998e+00 , -8.2454600000000003e-02 , 1.8058600000000000e-01 , 9.8009700000000000e-01 -6.8414085491947469e+00 , -5.9415312994040050e+00 , 2.9172758400000003e+00 , -8.5106299999999996e-02 , 1.8787100000000001e-01 , 9.7850000000000004e-01 -7.2044767615616161e+00 , -6.6449625731595603e+00 , 3.0818496000000000e+00 , -7.7694500000000000e-02 , 1.8884400000000001e-01 , 9.7892900000000005e-01 -7.6377852603712411e+00 , -7.4854545449683538e+00 , 3.2770159999999997e+00 , -7.5923800000000000e-02 , 1.9409599999999999e-01 , 9.7804000000000002e-01 -8.1685132664501765e+00 , -8.5152137929789351e+00 , 3.5125032000000003e+00 , -7.5016799999999995e-02 , 1.9431399999999999e-01 , 9.7806700000000002e-01 -8.8113121649284452e+00 , -9.7619694732868645e+00 , 3.8015400000000001e+00 , -7.0099200000000000e-02 , 1.9627600000000001e-01 , 9.7804000000000002e-01 -9.6799834237645204e+00 , -1.1445444555112783e+01 , 4.1745568000000004e+00 , -6.5863099999999994e-02 , 1.8859200000000001e-01 , 9.7984400000000005e-01 -1.0819926538756281e+01 , -1.3654804932414521e+01 , 4.6666223999999996e+00 , -2.9715300000000000e-02 , 1.8736200000000000e-01 , 9.8184099999999996e-01 -1.1289902951189895e+01 , -1.4954102479584446e+01 , 9.7863448000000002e+00 , -8.9954699999999999e-01 , 3.7593799999999999e-01 , -2.2245400000000001e-01 -1.0687372508497930e+01 , -1.3799887341814516e+01 , 9.6947831999999998e+00 , 7.7922800000000003e-01 , 7.5318800000000005e-02 , 6.2219899999999995e-01 -1.1177325988713481e+01 , -1.4891287961067277e+01 , 1.1702586400000000e+01 , 9.0742599999999995e-01 , -1.4822700000000000e-01 , -3.9320100000000002e-01 -1.1181626200640473e+01 , -1.4968304851022292e+01 , 1.2559640000000000e+01 , 8.8434599999999997e-01 , 4.0214100000000003e-01 , -2.3709900000000000e-01 -1.1171261420324845e+01 , -1.4982609148593607e+01 , 1.2987080000000001e+01 , 8.8434500000000005e-01 , 4.0214100000000003e-01 , -2.3709900000000000e-01 -5.0472228027974690e+00 , -2.9045981096229392e+00 , 7.6945200000000007e+00 , 2.0987700000000001e-01 , -3.9255699999999999e-01 , 8.9546099999999995e-01 -4.9634213847516655e+00 , -2.7464953522587718e+00 , 7.7182632000000000e+00 , -1.6110700000000000e-01 , 6.4833499999999999e-01 , -7.4411400000000005e-01 -4.9190220932567623e+00 , -2.6685977642815386e+00 , 7.8107920000000002e+00 , -1.6110700000000000e-01 , 6.4833499999999999e-01 , -7.4411400000000005e-01 -4.9007004052547796e+00 , -2.6459527287223281e+00 , 7.9561840000000004e+00 , 1.6476700000000000e-01 , -8.3226500000000003e-01 , 5.2932800000000002e-01 -4.5011054495015106e+00 , -1.8339418352334880e+00 , 7.3161056000000002e+00 , -9.5425800000000005e-01 , 2.0973600000000001e-01 , -2.1307899999999999e-01 -4.3841096027086852e+00 , -1.6046899471558773e+00 , 7.2273832000000002e+00 , 8.0618500000000004e-01 , -2.9514299999999999e-01 , 5.1279300000000005e-01 -4.3996617844328600e+00 , -1.6493741139814793e+00 , 7.4199703999999995e+00 , 8.5943800000000004e-01 , -3.1684200000000001e-01 , 4.0122099999999999e-01 -4.3515401657901824e+00 , -1.5628504918676960e+00 , 7.4755272000000001e+00 , -5.0427500000000003e-01 , 8.2779499999999995e-01 , -2.4589000000000000e-01 -4.3289351160961775e+00 , -1.5283929655442408e+00 , 7.5890016000000005e+00 , -4.3469099999999999e-01 , 6.5477600000000002e-01 , -6.1831400000000003e-01 -4.2833319543404293e+00 , -1.4463886893155031e+00 , 7.6489992000000004e+00 , -3.4214000000000000e-01 , 7.4881100000000000e-01 , -5.6764599999999998e-01 -4.2703535133357580e+00 , -1.4329324791875271e+00 , 7.7921136000000004e+00 , 4.5719300000000002e-01 , -7.0251500000000000e-01 , 5.4538699999999996e-01 -4.2531694126743549e+00 , -1.4100886778300743e+00 , 7.9281872000000000e+00 , 4.1917199999999999e-01 , -7.6690899999999995e-01 , 4.8594799999999999e-01 -4.2452746005940645e+00 , -1.4087284202747226e+00 , 8.0966255999999994e+00 , 3.3806100000000000e-01 , 7.9790399999999995e-01 , -4.9906299999999998e-01 -4.1743755126592301e+00 , -1.2724485708585718e+00 , 8.0885552000000001e+00 , 4.9929800000000002e-01 , -4.9186900000000000e-01 , 7.1327799999999997e-01 -4.1172676460752378e+00 , -1.1664598342653618e+00 , 8.1175503999999989e+00 , -3.7620500000000001e-01 , 5.6674100000000005e-01 , -7.3299000000000003e-01 -4.0706992004294928e+00 , -1.0834627400816541e+00 , 8.1770175999999992e+00 , 4.7134100000000001e-01 , -6.2417100000000003e-01 , 6.2309599999999998e-01 -4.3914188364648892e+00 , -1.7947038539980267e+00 , 9.4374664000000017e+00 , 1.2820200000000001e-01 , 7.0913899999999996e-01 , 6.9331600000000004e-01 -4.1178536848818847e+00 , -1.2191864277752509e+00 , 8.7677687999999989e+00 , 1.1322200000000000e-01 , -9.8980699999999999e-01 , -8.6386099999999993e-02 -3.9604810911285631e+00 , -8.9340479280017782e-01 , 8.4485720000000004e+00 , 6.9479199999999998e-03 , -1.4822500000000000e-01 , 9.8892899999999995e-01 -3.8885172618173778e+00 , -7.5475156529331233e-01 , 8.4151880000000006e+00 , 2.3646400000000001e-01 , -4.1054399999999998e-02 , 9.7077300000000000e-01 -3.8220286486461719e+00 , -6.2740393959353824e-01 , 8.3953760000000006e+00 , 1.8267600000000001e-01 , -2.2476699999999999e-01 , 9.5713599999999999e-01 -3.7876452162004122e+00 , -5.7038631676157614e-01 , 8.4971296000000009e+00 , 4.0299200000000002e-01 , -5.5942499999999999e-02 , 9.1349199999999997e-01 -3.6765382651208895e+00 , -3.3977090604101612e-01 , 8.2741328000000003e+00 , 5.6416999999999995e-01 , 6.6147900000000004e-01 , 4.9412400000000001e-01 -3.6564204423884834e+00 , -3.1507053754766190e-01 , 8.4345943999999999e+00 , 6.9725899999999996e-01 , 2.7792400000000000e-01 , -6.6074900000000003e-01 -3.5933807159512670e+00 , -1.9238260750920677e-01 , 8.4028951999999997e+00 , 6.5220000000000000e-01 , -2.0830899999999999e-01 , -7.2886399999999996e-01 -3.5046424160343483e+00 , -1.0396581894010382e-02 , 8.2384295999999999e+00 , 5.0988699999999998e-01 , -3.9348000000000000e-01 , -7.6497599999999999e-01 -3.4272541931037721e+00 , 1.4784953836506309e-01 , 8.1061832000000003e+00 , 8.0035900000000004e-01 , 4.6902600000000003e-02 , -5.9768299999999996e-01 -3.3619112219668894e+00 , 2.7778515552749528e-01 , 8.0256767999999994e+00 , 9.0134899999999996e-01 , 2.1200600000000000e-01 , -3.7765500000000002e-01 -3.3188717046800029e+00 , 3.5788968074842264e-01 , 8.0556912000000001e+00 , 9.0134899999999996e-01 , 2.1200600000000000e-01 , -3.7765500000000002e-01 -3.3322194419068012e+00 , 3.0287932206822177e-01 , 8.4284584000000002e+00 , 4.1009800000000002e-01 , -8.8670700000000002e-01 , 2.1347400000000000e-01 -3.3159447338911612e+00 , 3.1643137552045086e-01 , 8.6503632000000010e+00 , 5.4388499999999995e-01 , -8.3116699999999999e-01 , 1.1554399999999999e-01 -3.2128244976560092e+00 , 5.4133321041542559e-01 , 8.3005592000000004e+00 , 2.5369100000000000e-01 , 5.4278499999999996e-01 , 8.0064100000000005e-01 -3.1646588874344141e+00 , 6.3143461010242130e-01 , 8.3053536000000001e+00 , -3.1299199999999999e-01 , -6.8522899999999998e-01 , -6.5764500000000004e-01 -3.3471646511136299e+00 , 1.4236405826359255e-01 , 1.0106748000000000e+01 , -5.4820700000000000e-02 , -3.5180400000000001e-01 , 9.3446700000000005e-01 -3.2760531297766282e+00 , 2.8033052370719069e-01 , 1.0049028000000000e+01 , -2.7507100000000001e-01 , -3.5331899999999999e-01 , 8.9414899999999997e-01 -3.0096452723440210e+00 , 9.3757498424593266e-01 , 8.1790559999999992e+00 , 2.0621899999999999e-02 , -3.9168199999999997e-01 , 9.1986900000000005e-01 -2.9678544455420228e+00 , 1.0135925182485492e+00 , 8.2154039999999995e+00 , -1.0045000000000000e-01 , -4.2387399999999997e-01 , 9.0013399999999999e-01 -2.9262533630233554e+00 , 1.0903700989527199e+00 , 8.2503376000000017e+00 , 4.0741400000000000e-01 , -3.7706899999999999e-01 , 8.3176499999999998e-01 -2.9037716809211944e+00 , 1.1119171853844716e+00 , 8.5158392000000003e+00 , -5.3942699999999999e-01 , 7.8715000000000002e-01 , -2.9902000000000001e-01 -2.8601912653503958e+00 , 1.1914706256971854e+00 , 8.5588328000000011e+00 , -8.4292999999999996e-01 , 5.0578900000000004e-01 , -1.8342800000000001e-01 -2.9285807372453050e+00 , 9.2310552139524460e-01 , 1.0298201600000001e+01 , -1.0511400000000000e-01 , -6.2719999999999998e-01 , 7.7173300000000000e-01 -2.8660206722822021e+00 , 1.0460498564879603e+00 , 1.0262654400000001e+01 , -9.2935299999999998e-02 , 2.6698499999999997e-01 , 9.5920899999999998e-01 -2.7900577942666231e+00 , 1.2153142203690133e+00 , 9.9481688000000013e+00 , 1.5525300000000000e-01 , 7.8093900000000005e-01 , 6.0500500000000001e-01 -2.7318410637888459e+00 , 1.3282441412716235e+00 , 9.9270671999999998e+00 , -6.6639400000000001e-02 , 1.9014200000000001e-01 , 9.7949200000000003e-01 -2.6712843446355525e+00 , 1.4496866226516496e+00 , 9.8317824000000016e+00 , 6.2239100000000003e-01 , 1.8783800000000000e-01 , 7.5983299999999998e-01 -2.6098185034996182e+00 , 1.5850156966895699e+00 , 9.5996752000000001e+00 , 2.7436800000000000e-01 , -5.8109899999999999e-02 , 9.5986700000000003e-01 -2.5603328535671213e+00 , 1.6577320617358398e+00 , 9.8709799999999994e+00 , -5.2037199999999999e-02 , -1.5577199999999999e-01 , 9.8642099999999999e-01 -2.5044987265298424e+00 , 1.7721785227028484e+00 , 9.7788567999999998e+00 , -6.0535000000000005e-01 , 3.0049099999999999e-02 , 7.9539199999999999e-01 -2.4494038804300500e+00 , 1.9228359853012875e+00 , 9.1867535999999994e+00 , -3.9236699999999999e-02 , 7.0164499999999996e-01 , 7.1144600000000002e-01 -2.3926908036037142e+00 , 1.9621327962020485e+00 , 1.0054841600000001e+01 , -4.6611300000000000e-01 , -6.3686799999999999e-01 , -6.1411499999999997e-01 -2.3447485370782939e+00 , 2.0953353040154954e+00 , 9.5304736000000005e+00 , 2.3652699999999999e-01 , 9.7143800000000002e-01 , 1.9041900000000000e-02 -2.2957296510973517e+00 , 2.2003250965992751e+00 , 9.3981440000000003e+00 , 3.4342099999999998e-01 , -4.6084300000000000e-01 , -8.1834300000000004e-01 -2.2554025842086696e+00 , 2.3030747779832783e+00 , 9.0562752000000017e+00 , 4.5824300000000001e-01 , -6.9475200000000004e-01 , -5.5437700000000001e-01 -2.2110093413586509e+00 , 2.3963486291868565e+00 , 8.9616560000000014e+00 , -1.1940400000000000e-01 , 7.7642299999999997e-01 , 6.1879799999999996e-01 -2.1409573808411180e+00 , 2.4930515532798889e+00 , 9.4056008000000002e+00 , 3.3523999999999998e-02 , -2.9146100000000003e-01 , -9.5599500000000004e-01 -2.0918107578948746e+00 , 2.5898717443300154e+00 , 9.3591751999999993e+00 , 1.4186799999999999e-01 , 2.7435399999999999e-01 , 9.5110600000000001e-01 -2.0451163663885605e+00 , 2.6841849048615760e+00 , 9.3008416000000000e+00 , -1.5325000000000000e-01 , 1.6853099999999999e-01 , 9.7370999999999996e-01 -1.9914256869981097e+00 , 2.7843720869118473e+00 , 9.3439392000000012e+00 , -3.8351299999999999e-01 , -5.6499799999999998e-03 , -9.2351799999999995e-01 -1.9507273156422729e+00 , 2.8715738380281177e+00 , 9.2094255999999994e+00 , 7.2002100000000002e-01 , 5.9439699999999995e-01 , 3.5813800000000001e-01 -1.5838719656745579e+00 , 3.2908789571032981e+00 , 1.2735504000000001e+01 , -9.7356900000000002e-01 , -1.7255300000000001e-01 , -1.4962800000000001e-01 -1.4887824362421922e+00 , 3.4595016104602463e+00 , 1.2888072000000001e+01 , 8.0247700000000000e-01 , 5.1605699999999999e-01 , 2.9952499999999999e-01 -1.3971920747065347e+00 , 3.6264778219405875e+00 , 1.2985832000000000e+01 , -9.2198300000000000e-01 , -2.8543200000000002e-01 , 2.6167800000000002e-01 -1.7385403393049927e+00 , 3.2681236278022983e+00 , 9.2825272000000005e+00 , 6.6550799999999999e-01 , -2.6183200000000001e-01 , -6.9895900000000000e-01 -3.4661815439579002e+00 , 4.8840116851960103e-01 , 1.4144373600000000e+00 , -1.2999900000000000e-01 , 1.3380000000000000e-01 , 9.8244500000000001e-01 -3.4976552804275922e+00 , 4.2479821006013641e-01 , 1.4216643200000001e+00 , -8.3234900000000001e-02 , 1.6773399999999999e-01 , 9.8231199999999996e-01 -3.5241134663594602e+00 , 3.6829636502340612e-01 , 1.4367724000000002e+00 , 9.9444699999999997e-02 , -1.8858800000000001e-01 , -9.7700799999999999e-01 -3.5503511365728606e+00 , 3.1110251627432417e-01 , 1.4536037600000000e+00 , -8.9934500000000001e-02 , 1.7527200000000001e-01 , 9.8040400000000005e-01 -3.5822123334669067e+00 , 2.4752504231130179e-01 , 1.4663208800000000e+00 , -9.1133500000000006e-02 , 1.7547099999999999e-01 , 9.8025799999999996e-01 -3.6127296197344396e+00 , 1.8230625758308472e-01 , 1.4811450399999999e+00 , 8.8292700000000002e-02 , -2.2250600000000001e-01 , -9.7092500000000004e-01 -3.6393609488553151e+00 , 1.2510731525321606e-01 , 1.5033656799999999e+00 , -8.7450500000000000e-02 , 2.1353200000000000e-01 , 9.7301400000000005e-01 -3.6741528846473122e+00 , 5.2987409323122847e-02 , 1.5164842400000000e+00 , -8.1532499999999994e-02 , 2.0601500000000000e-01 , 9.7514599999999996e-01 -3.7096281562307967e+00 , -2.0723655994358214e-02 , 1.5323640000000001e+00 , 8.3129900000000007e-02 , -1.7499200000000001e-01 , -9.8105399999999998e-01 -3.7484287868784136e+00 , -1.0256820256740262e-01 , 1.5455044000000000e+00 , -1.1114200000000000e-01 , 2.3960300000000001e-01 , 9.6448900000000004e-01 -3.7751566675861783e+00 , -1.5924883129425726e-01 , 1.5755427200000001e+00 , -1.3736400000000001e-01 , 2.3833900000000000e-01 , 9.6141799999999999e-01 -3.8144123895213111e+00 , -2.4119213372802228e-01 , 1.5935669600000000e+00 , -1.0289400000000000e-01 , 2.1561100000000000e-01 , 9.7104299999999999e-01 -3.8543670042158760e+00 , -3.2365167807292394e-01 , 1.6144512000000000e+00 , 7.5122900000000006e-02 , -1.7354600000000001e-01 , -9.8195600000000005e-01 -3.9020401003039646e+00 , -4.2356245976587248e-01 , 1.6293783200000000e+00 , -5.5253700000000003e-02 , 1.6880200000000001e-01 , 9.8409999999999997e-01 -3.9448086495067267e+00 , -5.1435465997211738e-01 , 1.6516738399999999e+00 , -7.5887700000000002e-02 , 1.7982300000000001e-01 , 9.8076799999999997e-01 -3.9972274798364609e+00 , -6.2349049673631907e-01 , 1.6692779199999999e+00 , -7.6949500000000004e-02 , 1.7808800000000000e-01 , 9.8100100000000001e-01 -4.0412545586224731e+00 , -7.1509934428878186e-01 , 1.6983063999999999e+00 , 6.7188899999999996e-02 , -2.0100499999999999e-01 , -9.7728300000000001e-01 -4.0928422674170353e+00 , -8.2385185848154618e-01 , 1.7228940800000001e+00 , 8.1901199999999993e-02 , -1.7039399999999999e-01 , -9.8196600000000001e-01 -4.1538835632322044e+00 , -9.5060586623800702e-01 , 1.7445104800000000e+00 , -5.1729400000000002e-02 , 1.7102899999999999e-01 , 9.8390699999999998e-01 -4.2153643933669480e+00 , -1.0785335473314390e+00 , 1.7709129600000000e+00 , 7.9828899999999994e-02 , -1.9985400000000000e-01 , -9.7656799999999999e-01 -4.2719242854408339e+00 , -1.1973141350219803e+00 , 1.8047847200000000e+00 , -8.5786399999999999e-02 , 1.9858899999999999e-01 , 9.7632099999999999e-01 -4.3411791015607681e+00 , -1.3420769452584294e+00 , 1.8336540800000001e+00 , -7.0153499999999994e-02 , 1.8385599999999999e-01 , 9.8044699999999996e-01 -4.4151435714567935e+00 , -1.4970908307413753e+00 , 1.8653054400000000e+00 , -6.7733699999999994e-02 , 1.9716900000000001e-01 , 9.7802699999999998e-01 -4.4894811767626832e+00 , -1.6520609125041008e+00 , 1.9025477360000000e+00 , -8.2252900000000004e-02 , 2.0459600000000000e-01 , 9.7538400000000003e-01 -4.5674606725794051e+00 , -1.8160977946764034e+00 , 1.9429494480000000e+00 , -8.0859799999999996e-02 , 1.7914300000000000e-01 , 9.8049500000000001e-01 -4.6630078237659820e+00 , -2.0155496644105559e+00 , 1.9800135919999999e+00 , -7.3985800000000004e-02 , 1.7252300000000001e-01 , 9.8222299999999996e-01 -4.7596545593101736e+00 , -2.2166568771062991e+00 , 2.0249258879999998e+00 , -8.0691200000000005e-02 , 1.9803899999999999e-01 , 9.7686700000000004e-01 -4.8543868530859902e+00 , -2.4172714098699375e+00 , 2.0771015440000000e+00 , -9.1494599999999995e-02 , 1.8981600000000001e-01 , 9.7754700000000005e-01 -4.9725166909140981e+00 , -2.6637387720197863e+00 , 2.1280375199999999e+00 , -9.2031600000000005e-02 , 1.7817800000000000e-01 , 9.7968500000000003e-01 -5.0948144395182080e+00 , -2.9184128867894774e+00 , 2.1866082400000000e+00 , -9.4887600000000002e-02 , 2.0908499999999999e-01 , 9.7328300000000001e-01 -5.2116868581962361e+00 , -3.1652730902317252e+00 , 2.2563984800000001e+00 , -1.0112000000000000e-01 , 1.9338300000000000e-01 , 9.7589899999999996e-01 -5.3785370318800823e+00 , -3.5127866116104336e+00 , 2.3221878399999998e+00 , -8.2931699999999997e-02 , 1.8340100000000001e-01 , 9.7953400000000002e-01 -5.5262028841868966e+00 , -3.8220400141787838e+00 , 2.4050737600000001e+00 , -8.2210500000000006e-02 , 1.8423800000000001e-01 , 9.7943800000000003e-01 -5.7322706331792812e+00 , -4.2525126654740912e+00 , 2.4890911999999998e+00 , -7.4607400000000004e-02 , 1.9695499999999999e-01 , 9.7757000000000005e-01 -5.9055226410003616e+00 , -4.6178398255288080e+00 , 2.5942726399999998e+00 , -7.1777900000000006e-02 , 1.8351300000000001e-01 , 9.8039299999999996e-01 -6.1783271469716166e+00 , -5.1863592750830509e+00 , 2.7030181600000001e+00 , -6.5155900000000003e-02 , 1.8213900000000000e-01 , 9.8111199999999998e-01 -6.4495578349280471e+00 , -5.7536060247448555e+00 , 2.8335516800000002e+00 , -6.2951300000000002e-02 , 1.9314400000000001e-01 , 9.7914900000000005e-01 -6.7698008724800154e+00 , -6.4228159997267955e+00 , 2.9849361600000002e+00 , -1.5676800000000001e-02 , 1.9333300000000000e-01 , 9.8100799999999999e-01 -7.1514776328011758e+00 , -7.2198783127460118e+00 , 3.1631255999999999e+00 , -5.4033999999999999e-02 , 2.0112700000000000e-01 , 9.7807400000000000e-01 -7.5344856969270637e+00 , -8.0245551194463260e+00 , 3.3723424000000000e+00 , -6.0071500000000000e-02 , 2.0861499999999999e-01 , 9.7615099999999999e-01 -8.0824484695711405e+00 , -9.1717920807707340e+00 , 3.6292119999999999e+00 , -6.5354499999999996e-02 , 1.8953200000000001e-01 , 9.7969700000000004e-01 -8.7761974625499022e+00 , -1.0622360219678793e+01 , 3.9509256000000001e+00 , -5.7428500000000000e-02 , 1.8672300000000000e-01 , 9.8073299999999997e-01 -9.7856139795360200e+00 , -1.2729355747090189e+01 , 4.3860200000000003e+00 , -3.0068700000000000e-02 , 1.9342899999999999e-01 , 9.8065300000000000e-01 -1.1093341273821881e+01 , -1.5461597366307569e+01 , 4.9699280000000003e+00 , 1.6783899999999999e-01 , 5.1942100000000002e-01 , 8.3787299999999998e-01 -1.0649781923687341e+01 , -1.4990055563750829e+01 , 9.4871888000000020e+00 , -8.9954699999999999e-01 , 3.7593799999999999e-01 , -2.2245400000000001e-01 -1.0569258879018525e+01 , -1.4857286480972103e+01 , 9.8074360000000009e+00 , -8.9954699999999999e-01 , 3.7593799999999999e-01 , -2.2245400000000001e-01 -1.0590402446174963e+01 , -1.4940651655858868e+01 , 1.0215188800000000e+01 , -8.9954699999999999e-01 , 3.7593799999999999e-01 , -2.2245400000000001e-01 -1.0547058808424460e+01 , -1.4885132010842774e+01 , 1.0571160000000001e+01 , -6.8850299999999998e-01 , 7.2409900000000005e-01 , -4.0549099999999998e-02 -1.0475292529708698e+01 , -1.4770643624062927e+01 , 1.0902722400000000e+01 , -9.0711500000000000e-01 , 4.2081099999999999e-01 , -7.7967599999999998e-03 -1.0707671585313978e+01 , -1.5309294181553554e+01 , 1.1546264000000001e+01 , 9.0895700000000001e-01 , -3.3607700000000001e-01 , -2.4667700000000001e-01 -1.0408677787322310e+01 , -1.4707638012908401e+01 , 1.1649192800000000e+01 , -8.4579300000000002e-01 , -2.9736499999999999e-01 , 4.4295299999999999e-01 -1.0243049295076737e+01 , -1.4389865011230320e+01 , 1.1878845600000000e+01 , 7.5336300000000000e-01 , 4.5740799999999998e-01 , -4.7246500000000002e-01 -1.0059599004122520e+01 , -1.4034638069170104e+01 , 1.2079752800000000e+01 , 7.5432900000000003e-01 , 5.5967400000000000e-01 , -3.4315099999999998e-01 -1.0581523701660686e+01 , -1.5204449993723248e+01 , 1.3141208000000001e+01 , 8.7490000000000001e-01 , 2.4554799999999999e-01 , -4.1744100000000001e-01 -9.4644256408381828e+00 , -1.2823327191878294e+01 , 1.2151533600000000e+01 , 5.5866700000000002e-01 , 7.4102699999999999e-01 , -3.7251800000000002e-01 -9.4015152927437313e+00 , -1.2726038247025167e+01 , 1.2468016000000000e+01 , 6.7479000000000000e-01 , 7.2092999999999996e-01 , -1.5785399999999999e-01 -1.0518880271075032e+01 , -1.5299706102383535e+01 , 1.5432640000000001e+01 , -7.6698599999999995e-01 , -5.8984999999999999e-01 , -2.5260500000000002e-01 -1.0366806927493890e+01 , -1.5013991134716989e+01 , 1.5700960000000000e+01 , -7.6214300000000001e-01 , -6.0918700000000003e-01 , -2.1915499999999999e-01 -1.0061900373302830e+01 , -1.4389657612119354e+01 , 1.5709384000000000e+01 , 6.9170900000000002e-01 , 6.0919299999999998e-01 , 3.8784400000000002e-01 -4.9148351098017171e+00 , -3.0814389266567401e+00 , 7.6792008000000003e+00 , -3.0809599999999998e-01 , 3.2065700000000003e-01 , -8.9568800000000004e-01 -4.8251283604622639e+00 , -2.8988109050633710e+00 , 7.6863871999999995e+00 , 3.7303999999999998e-01 , -3.9539500000000000e-01 , 8.3934799999999998e-01 -4.7956489169198262e+00 , -2.8499144935718492e+00 , 7.8068607999999999e+00 , 3.6531000000000002e-01 , -5.1029800000000003e-01 , 7.7855300000000005e-01 -4.7318518927628830e+00 , -2.7262128077424386e+00 , 7.8591000000000006e+00 , 5.3425100000000003e-01 , -8.1570200000000004e-01 , 2.2182299999999999e-01 -4.4384228735796931e+00 , -2.0817571478889523e+00 , 7.4060863999999995e+00 , -9.0208999999999995e-01 , 1.5968299999999999e-01 , -4.0091700000000002e-01 -4.4085001556106302e+00 , -2.0286847599292619e+00 , 7.5050216000000001e+00 , -8.6868699999999999e-01 , 1.0967399999999999e-01 , -4.8306900000000003e-01 -4.7357456785663512e+00 , -2.7897081105995527e+00 , 8.4459824000000001e+00 , 2.9889900000000000e-02 , -9.0642599999999995e-01 , 4.2130499999999999e-01 -4.6939310771011122e+00 , -2.7135680576719166e+00 , 8.5514696000000008e+00 , 4.9630999999999997e-01 , 7.8080899999999998e-01 , -3.7948999999999999e-01 -4.2530914701284921e+00 , -1.7255214165674464e+00 , 7.6484687999999998e+00 , 3.5103099999999998e-01 , -7.6276400000000000e-01 , 5.4310999999999998e-01 -4.1777787915168965e+00 , -1.5681491685722344e+00 , 7.6282512000000002e+00 , 3.6271999999999999e-01 , -7.9031300000000004e-01 , 4.9380099999999999e-01 -4.1678337013673934e+00 , -1.5626946252624561e+00 , 7.7796752000000007e+00 , -4.5797700000000002e-01 , 7.0910799999999996e-01 , -5.3611799999999998e-01 -4.1370091980494141e+00 , -1.5087332743201380e+00 , 7.8775704000000006e+00 , -4.5585399999999998e-02 , -8.6150599999999999e-01 , 5.0569799999999998e-01 -4.0886488327997519e+00 , -1.4159017456710892e+00 , 7.9274176000000001e+00 , -7.5688699999999998e-02 , -8.4937900000000000e-01 , 5.2232800000000001e-01 -4.0540174223133043e+00 , -1.3521642381726062e+00 , 8.0150375999999994e+00 , -1.9250500000000000e-02 , -7.4275700000000000e-01 , 6.6928399999999999e-01 -4.0359108857542552e+00 , -1.3299000502162537e+00 , 8.1586096000000001e+00 , 4.5866899999999999e-01 , -2.5748100000000002e-01 , 8.5048599999999996e-01 -4.0065525059747689e+00 , -1.2797163265305449e+00 , 8.2696400000000008e+00 , -5.7647199999999998e-01 , 4.4092799999999999e-01 , -6.8794100000000002e-01 -4.4388356492582943e+00 , -2.3318719866911302e+00 , 9.9910063999999998e+00 , -6.8670600000000004e-01 , 7.1630099999999997e-01 , -1.2388700000000000e-01 -3.7123517589714665e+00 , -6.1930881023802220e-01 , 7.6532112000000003e+00 , -8.3141200000000004e-01 , -1.5141099999999999e-01 , -5.3462900000000002e-01 -3.6914662579366033e+00 , -5.8647645760646849e-01 , 7.7695768000000003e+00 , -5.9494700000000000e-01 , 1.0160700000000000e-01 , -7.9731700000000005e-01 -3.7975683764420687e+00 , -8.6500933414008729e-01 , 8.3966656000000004e+00 , -4.6869899999999998e-01 , -9.7485999999999996e-03 , -8.8330399999999998e-01 -3.7669393408078378e+00 , -8.1326861454597088e-01 , 8.5099008000000005e+00 , 5.5130699999999999e-01 , -1.0817900000000000e-01 , 8.2725899999999997e-01 -3.7353319282225721e+00 , -7.5942352107307620e-01 , 8.6228031999999999e+00 , 4.1175899999999999e-01 , 3.3525699999999999e-02 , 9.1067600000000004e-01 -3.5200514817768211e+00 , -2.4994795169778339e-01 , 7.9118279999999999e+00 , 7.6821499999999998e-01 , 6.2412299999999998e-01 , -1.4253500000000000e-01 -3.5931302375015566e+00 , -4.5644809881086523e-01 , 8.4940719999999992e+00 , 6.9725899999999996e-01 , 2.7792400000000000e-01 , -6.6074800000000000e-01 -3.5097676795508796e+00 , -2.7028440287047584e-01 , 8.3462671999999998e+00 , -4.0817000000000002e-04 , 6.5134199999999998e-01 , 7.5878400000000001e-01 -3.4328136321003049e+00 , -1.0332310188268812e-01 , 8.2204063999999999e+00 , -5.9693399999999996e-01 , 4.2015599999999997e-01 , 6.8347599999999997e-01 -3.3413854666080409e+00 , 1.0749035938330809e-01 , 7.9876648000000001e+00 , 7.6956599999999997e-01 , 6.1953000000000003e-01 , -1.5476300000000001e-01 -3.2887535178430176e+00 , 2.1779270863648703e-01 , 7.9547176000000004e+00 , 7.6956599999999997e-01 , 6.1953000000000003e-01 , -1.5476300000000001e-01 -3.2346824796330047e+00 , 3.3441431946131495e-01 , 7.9001072000000008e+00 , 7.6441999999999999e-01 , 5.4379400000000000e-01 , -3.4633799999999998e-01 -3.2600784575155095e+00 , 2.3741580913705462e-01 , 8.3569272000000012e+00 , -1.4620800000000000e-01 , 7.5608100000000000e-01 , 6.3793800000000001e-01 -3.2254818955411624e+00 , 3.0108610011075077e-01 , 8.4442456000000004e+00 , -4.2361399999999999e-01 , 8.5214000000000001e-01 , 3.0725999999999998e-01 -3.1580075769865767e+00 , 4.5410480891851179e-01 , 8.2986456000000004e+00 , 2.9878600000000002e-02 , 1.7754400000000001e-01 , 9.8365899999999995e-01 -3.1209035822598787e+00 , 5.2158570837281037e-01 , 8.3726935999999998e+00 , -4.8434300000000002e-01 , -2.0422399999999999e-01 , -8.5070800000000002e-01 -3.0732128906653657e+00 , 6.2042115935730013e-01 , 8.3576760000000014e+00 , 5.6589000000000000e-01 , 5.2789999999999997e-02 , 8.2278899999999999e-01 -3.2039835882880521e+00 , 1.9761654344188884e-01 , 9.9656823999999986e+00 , -2.7507100000000001e-01 , -3.5331899999999999e-01 , 8.9414899999999997e-01 -3.0469079713114073e+00 , 6.1180992730890327e-01 , 8.9944367999999990e+00 , -5.5628000000000000e-01 , 4.2011900000000002e-01 , -7.1697500000000003e-01 -2.9982493689184340e+00 , 7.1303838491399052e-01 , 8.9963400000000000e+00 , 5.7573200000000002e-01 , 6.0688100000000000e-01 , 5.4793099999999995e-01 -2.9504466930864139e+00 , 8.0827505198596872e-01 , 9.0161416000000010e+00 , -6.4693199999999995e-01 , -5.2633900000000000e-01 , -5.5176700000000001e-01 -2.8573502653185034e+00 , 1.0530998428940066e+00 , 8.4406263999999993e+00 , -4.4416299999999997e-01 , 7.7488699999999999e-01 , -4.4974399999999998e-01 -2.8104790949066309e+00 , 1.1538915831432019e+00 , 8.3933271999999999e+00 , -6.7557000000000000e-01 , 7.0264000000000004e-01 , -2.2338900000000000e-01 -2.8798884590989737e+00 , 8.3051827848151105e-01 , 1.0270963999999999e+01 , -1.0511400000000000e-01 , -6.2719999999999998e-01 , 7.7173300000000000e-01 -2.8189335249120768e+00 , 9.6131156019792607e-01 , 1.0206182399999999e+01 , -6.0096700000000003e-01 , -3.6204700000000001e-01 , 7.1257300000000001e-01 -2.7635722576099897e+00 , 1.0736923071424149e+00 , 1.0230435200000001e+01 , -7.8509800000000005e-02 , 2.8059699999999999e-01 , 9.5660900000000004e-01 -2.6919780541739042e+00 , 1.2589233430934792e+00 , 9.8222039999999993e+00 , -1.8450999999999999e-02 , 2.6527600000000001e-01 , 9.6399599999999996e-01 -2.6409993674184840e+00 , 1.3548352133100314e+00 , 9.9026376000000003e+00 , 8.7324799999999994e-02 , -1.0494800000000000e-03 , 9.9617900000000004e-01 -2.5867693591256953e+00 , 1.4702361086171478e+00 , 9.8577615999999999e+00 , -3.6989000000000000e-01 , -1.6928499999999999e-01 , -9.1352299999999997e-01 -2.5341761901095858e+00 , 1.5796666235760519e+00 , 9.8415792000000000e+00 , 1.5220100000000000e-01 , -3.1828899999999999e-01 , -9.3569599999999997e-01 -2.4827585227342386e+00 , 1.6587625627542308e+00 , 1.0112509600000001e+01 , 5.1225900000000002e-01 , -8.2977999999999996e-01 , -2.2148599999999999e-01 -2.4313930868822515e+00 , 1.8511704537045082e+00 , 9.2119424000000016e+00 , 4.6371299999999999e-01 , 8.4774300000000002e-01 , 2.5749400000000000e-01 -2.3787720250874096e+00 , 1.9117929156992457e+00 , 9.6966135999999992e+00 , -7.0447700000000002e-01 , 2.5905200000000000e-01 , 6.6076000000000001e-01 -2.3231397215219003e+00 , 2.0006766971173726e+00 , 9.9519856000000004e+00 , 4.6427400000000002e-01 , 8.7729299999999999e-01 , -1.2168000000000000e-01 -2.2849414948373181e+00 , 2.1322171075157965e+00 , 9.4161776000000010e+00 , 7.6031300000000002e-01 , -3.0589300000000003e-01 , -5.7302200000000003e-01 -2.2462704847510664e+00 , 2.2403187678523433e+00 , 9.0959512000000000e+00 , 9.4948299999999999e-02 , 5.7914800000000000e-01 , 8.0967400000000000e-01 -2.2029459387866432e+00 , 2.3347908206083821e+00 , 9.0443984000000004e+00 , -1.5894599999999998e-02 , 7.0558399999999999e-01 , 7.0844799999999997e-01 -2.1401818389908431e+00 , 2.4305887800719304e+00 , 9.3852687999999986e+00 , 1.8651999999999998e-02 , -2.5006099999999998e-01 , -9.6804999999999997e-01 -2.0906788828143266e+00 , 2.5296065437811976e+00 , 9.4023871999999997e+00 , 1.4190000000000000e-01 , -1.4805800000000000e-01 , -9.7874600000000000e-01 -2.0460490976469674e+00 , 2.6271672530320767e+00 , 9.3447920000000000e+00 , 1.4270200000000000e-01 , -5.3907099999999997e-01 , -8.3008300000000002e-01 -1.9984807504085964e+00 , 2.7253886907013034e+00 , 9.3372832000000017e+00 , 1.4181600000000000e-01 , -3.3064300000000002e-01 , 9.3303999999999998e-01 -1.9486657116607142e+00 , 2.8253544703774454e+00 , 9.3485048000000006e+00 , 5.8893099999999998e-01 , 1.0909700000000000e-01 , -8.0078600000000000e-01 -1.9390185073198953e+00 , 2.8879381741342547e+00 , 8.9034160000000000e+00 , -7.5524199999999997e-01 , 6.1036999999999997e-01 , 2.3886900000000000e-01 -1.4977446254095494e+00 , 3.3905394711487160e+00 , 1.3053640000000001e+01 , -7.7435799999999999e-01 , -6.3207000000000002e-01 , -2.9275300000000001e-02 -1.4294028866708146e+00 , 3.5386920515777218e+00 , 1.2957440000000000e+01 , 8.8024599999999997e-01 , 4.6570600000000001e-01 , -9.1024400000000005e-02 -1.7571346132451520e+00 , 3.2212440697411613e+00 , 9.3120423999999993e+00 , -9.4102800000000000e-02 , 5.5106299999999997e-01 , 8.2914100000000002e-01 -1.7123501817251576e+00 , 3.3160844704460022e+00 , 9.2725223999999997e+00 , 1.5228500000000000e-01 , -9.6791799999999995e-01 , 1.9986000000000001e-01 -3.4064971478512565e+00 , 4.9355688046900292e-01 , 1.4062286399999999e+00 , -1.1184300000000000e-01 , 1.6203999999999999e-01 , 9.8042600000000002e-01 -3.4274272537870329e+00 , 4.4438121123393159e-01 , 1.4248404799999999e+00 , 7.1046700000000004e-02 , -1.9557099999999999e-01 , -9.7811300000000001e-01 -3.4567146605002947e+00 , 3.7994243540437389e-01 , 1.4327299199999999e+00 , -7.2678499999999993e-02 , 1.8398999999999999e-01 , 9.8023800000000005e-01 -3.4809885828367730e+00 , 3.2259458030514088e-01 , 1.4483985600000000e+00 , -4.8584000000000002e-02 , 2.2905200000000001e-01 , 9.7220099999999998e-01 -3.5108684087249151e+00 , 2.5779837520812654e-01 , 1.4599581599999998e+00 , -5.3537599999999998e-02 , 1.9591800000000001e-01 , 9.7915799999999997e-01 -3.5394464648224258e+00 , 1.9240933106702029e-01 , 1.4735187199999999e+00 , -7.0080299999999998e-02 , 2.0858199999999999e-01 , 9.7549100000000000e-01 -3.5677630963190379e+00 , 1.2637304819248985e-01 , 1.4891062399999999e+00 , -6.2421600000000001e-02 , 2.2979400000000000e-01 , 9.7123599999999999e-01 -3.5968925245962069e+00 , 6.0724369385941612e-02 , 1.5067415199999998e+00 , -5.8760699999999999e-02 , 2.3188200000000000e-01 , 9.7096700000000002e-01 -3.6257986748990714e+00 , -4.5557206711972498e-03 , 1.5261988799999999e+00 , -5.8256099999999998e-02 , 1.8234200000000000e-01 , 9.8150800000000005e-01 -3.6626609095842544e+00 , -8.7673956049570290e-02 , 1.5378760000000000e+00 , -3.9509700000000002e-02 , 2.2180900000000001e-01 , 9.7428899999999996e-01 -3.6956446175593536e+00 , -1.6170969040679362e-01 , 1.5569475200000000e+00 , -7.9067999999999999e-02 , 2.4886700000000000e-01 , 9.6530499999999997e-01 -3.7282918396338194e+00 , -2.3733108176307915e-01 , 1.5785545599999999e+00 , -6.0091199999999997e-02 , 2.4723400000000001e-01 , 9.6709100000000003e-01 -3.7617047511232906e+00 , -3.1248952599522628e-01 , 1.6026139200000000e+00 , -6.7128400000000005e-02 , 2.0214299999999999e-01 , 9.7705299999999995e-01 -3.8019036424673489e+00 , -4.0416341345282536e-01 , 1.6199798400000001e+00 , -3.9850499999999997e-02 , 1.6231300000000001e-01 , 9.8593399999999998e-01 -3.8473084529213555e+00 , -5.0476745293492398e-01 , 1.6362776800000001e+00 , -4.3322300000000001e-02 , 1.8132400000000001e-01 , 9.8246900000000004e-01 -3.8877645094931133e+00 , -5.9729118995901276e-01 , 1.6600479200000000e+00 , -6.2180600000000003e-02 , 1.7120500000000000e-01 , 9.8327100000000001e-01 -3.9368222373579487e+00 , -7.0806339308208832e-01 , 1.6793045600000001e+00 , -3.1378200000000002e-02 , 1.9806000000000001e-01 , 9.7968699999999997e-01 -3.9819933119813307e+00 , -8.0976535403746430e-01 , 1.7059545599999999e+00 , -5.0980999999999999e-02 , 1.8438199999999999e-01 , 9.8153199999999996e-01 -4.0390976154450442e+00 , -9.3787984042461758e-01 , 1.7252496800000001e+00 , -4.5147699999999999e-02 , 1.8261700000000000e-01 , 9.8214699999999999e-01 -4.0877904780750116e+00 , -1.0495218696914628e+00 , 1.7559723199999999e+00 , -4.4548699999999997e-02 , 1.7622399999999999e-01 , 9.8334200000000005e-01 -4.1492888706576592e+00 , -1.1873253195327145e+00 , 1.7807815199999999e+00 , -6.0431100000000001e-02 , 1.9672799999999999e-01 , 9.7859399999999996e-01 -4.2014003458241547e+00 , -1.3076655604597285e+00 , 1.8164836799999999e+00 , -5.8831599999999998e-02 , 2.0513000000000001e-01 , 9.7696499999999997e-01 -4.2671678966046152e+00 , -1.4549604565028016e+00 , 1.8478178400000000e+00 , -4.8662799999999999e-02 , 1.7942000000000000e-01 , 9.8256800000000000e-01 -4.3365986956011042e+00 , -1.6124744796488981e+00 , 1.8819090400000000e+00 , -6.0871000000000001e-02 , 1.9743400000000000e-01 , 9.7842499999999999e-01 -4.4054209549419312e+00 , -1.7689233692036153e+00 , 1.9211602000000001e+00 , -6.7933300000000002e-02 , 2.0207800000000001e-01 , 9.7701099999999996e-01 -4.4874685892649868e+00 , -1.9537618847611422e+00 , 1.9593870640000000e+00 , -5.3451699999999998e-02 , 1.7745700000000000e-01 , 9.8267599999999999e-01 -4.5816225956173788e+00 , -2.1657100230435846e+00 , 1.9973717639999999e+00 , -4.9148999999999998e-02 , 1.8708200000000000e-01 , 9.8111400000000004e-01 -4.6672906356949486e+00 , -2.3599804860019775e+00 , 2.0474890000000001e+00 , -5.3023500000000001e-02 , 1.9950200000000001e-01 , 9.7846200000000005e-01 -4.7733500605971155e+00 , -2.6001931923149906e+00 , 2.0952812640000000e+00 , -5.8564400000000003e-02 , 1.7777000000000001e-01 , 9.8232799999999998e-01 -4.8888075734590597e+00 , -2.8598087520506379e+00 , 2.1489373600000001e+00 , -5.5304699999999998e-02 , 1.9681799999999999e-01 , 9.7887900000000005e-01 -5.0021170357731233e+00 , -3.1185120796427235e+00 , 2.2118802400000002e+00 , -6.5564800000000006e-02 , 2.1766900000000000e-01 , 9.7381799999999996e-01 -5.1246606742916594e+00 , -3.3963331414955613e+00 , 2.2821031199999999e+00 , -6.6983899999999999e-02 , 1.7535899999999999e-01 , 9.8222299999999996e-01 -5.2812904889190291e+00 , -3.7486031477903285e+00 , 2.3536582400000001e+00 , -7.4226799999999996e-02 , 1.9503999999999999e-01 , 9.7798200000000002e-01 -5.4322167213821650e+00 , -4.0903778740899845e+00 , 2.4392606400000001e+00 , -7.0308300000000004e-02 , 1.8522000000000000e-01 , 9.8017900000000002e-01 -5.6206288874082242e+00 , -4.5174577179756081e+00 , 2.5310791200000002e+00 , -6.5650200000000006e-02 , 1.9757700000000000e-01 , 9.7808700000000004e-01 -5.8163476948093447e+00 , -4.9620510602660675e+00 , 2.6376416800000002e+00 , -3.8728100000000001e-02 , 2.0033999999999999e-01 , 9.7896099999999997e-01 -6.0588963836769079e+00 , -5.5101430230393111e+00 , 2.7569900000000001e+00 , 1.5174500000000000e-02 , 2.1232200000000001e-01 , 9.7708200000000001e-01 -6.3384661254041692e+00 , -6.1420319992602863e+00 , 2.8952299200000002e+00 , 3.5299700000000003e-02 , 2.0603600000000000e-01 , 9.7790800000000000e-01 -6.6585143752490481e+00 , -6.8664507728756785e+00 , 3.0571391999999999e+00 , 1.1788099999999999e-02 , 1.9166200000000000e-01 , 9.8138999999999998e-01 -7.0534850258750899e+00 , -7.7589324317065387e+00 , 3.2493416000000002e+00 , -3.2305599999999997e-02 , 2.0821200000000001e-01 , 9.7755000000000003e-01 -7.4453815991230181e+00 , -8.6497027015946468e+00 , 3.4757807999999999e+00 , -5.0886099999999997e-02 , 1.9568700000000000e-01 , 9.7934500000000002e-01 -7.9999894004073333e+00 , -9.9049974612374072e+00 , 3.7562895999999997e+00 , -4.9693899999999999e-02 , 1.9296600000000000e-01 , 9.7994599999999998e-01 -8.7118580185822125e+00 , -1.1515203924444464e+01 , 4.1114183999999998e+00 , -2.5972100000000001e-02 , 1.9075100000000000e-01 , 9.8129500000000003e-01 -9.7564114001568889e+00 , -1.3874528618279099e+01 , 4.5984816000000004e+00 , -8.8180599999999995e-04 , 1.9106500000000001e-01 , 9.8157700000000003e-01 -1.2158746266974831e+01 , -1.9632539213940657e+01 , 8.5753063999999988e+00 , -6.9135999999999997e-01 , -6.6682300000000005e-01 , -2.7815000000000001e-01 -1.2115784786212352e+01 , -1.9586704703936352e+01 , 9.0040984000000002e+00 , -6.9135999999999997e-01 , -6.6682300000000005e-01 , -2.7815000000000001e-01 -1.2069828808377766e+01 , -1.9534473602708182e+01 , 9.4327135999999996e+00 , -6.9135999999999997e-01 , -6.6682300000000005e-01 , -2.7815099999999998e-01 -1.2016232040123274e+01 , -1.9465645660358909e+01 , 9.8577408000000002e+00 , -6.9135999999999997e-01 , -6.6682300000000005e-01 , -2.7815099999999998e-01 -1.0355060311636507e+01 , -1.5805551330576627e+01 , 9.8564927999999998e+00 , 7.8718100000000002e-01 , -5.7463600000000004e-01 , 2.2391700000000000e-01 -1.0270843534540532e+01 , -1.5656340335569801e+01 , 1.0183697600000000e+01 , 7.8718100000000002e-01 , -5.7463600000000004e-01 , 2.2391700000000000e-01 -1.0286075395724048e+01 , -1.5787912923848385e+01 , 1.1020190400000001e+01 , 8.2298499999999997e-01 , -5.6452899999999995e-01 , -6.3268099999999994e-02 -1.0136936635917557e+01 , -1.5489505949255062e+01 , 1.1283497600000000e+01 , -8.9810400000000001e-01 , 4.3933299999999997e-01 , 1.9898699999999998e-02 -9.3616077057762972e+00 , -1.3727472675855829e+01 , 1.0835642400000001e+01 , 8.2774499999999995e-01 , 5.0565599999999999e-01 , -2.4321000000000001e-01 -9.3096458563827191e+00 , -1.3652052519893651e+01 , 1.1162316800000001e+01 , -8.2965900000000004e-01 , -4.1626700000000000e-01 , 3.7200499999999997e-01 -9.2074146690162859e+00 , -1.3457998562010056e+01 , 1.1429066400000000e+01 , 5.5866700000000002e-01 , 7.4102699999999999e-01 , -3.7251800000000002e-01 -9.2128896645552949e+00 , -1.3516207144559433e+01 , 1.1831504799999999e+01 , 5.5866700000000002e-01 , 7.4102800000000002e-01 , -3.7251800000000002e-01 -9.1713939702665215e+00 , -1.3465406434372539e+01 , 1.2180227199999999e+01 , 5.5866700000000002e-01 , 7.4102699999999999e-01 , -3.7251800000000002e-01 -7.9996721354184919e+00 , -1.0738596983243921e+01 , 1.0934234399999999e+01 , 8.5949499999999998e-02 , -9.0158799999999995e-01 , 4.2397000000000001e-01 -8.9114159488345681e+00 , -1.2945190408249385e+01 , 1.2630360000000001e+01 , -5.9258299999999997e-01 , -8.0510300000000001e-01 , -2.5583399999999999e-02 -7.9924597425920494e+00 , -1.0804258727773572e+01 , 1.1629391199999999e+01 , 4.2655399999999999e-01 , -8.0409600000000003e-01 , 4.1410400000000003e-01 -7.8983563574223297e+00 , -1.0621927703042179e+01 , 1.1844692000000000e+01 , -7.0841699999999996e-01 , 6.4044599999999996e-01 , -2.9660500000000001e-01 -7.7568467035986846e+00 , -1.0323884306421901e+01 , 1.1976605600000001e+01 , -7.0841699999999996e-01 , 6.4044599999999996e-01 , -2.9660500000000001e-01 -8.8047838673715404e+00 , -1.2889978367600428e+01 , 1.4178088000000001e+01 , -7.3703600000000002e-01 , -6.7194100000000001e-01 , -7.2612300000000005e-02 -9.8111675504002864e+00 , -1.5375252819602164e+01 , 1.6466296000000000e+01 , -7.4714700000000001e-01 , -5.2561899999999995e-01 , -4.0681099999999998e-01 -9.5610390948434425e+00 , -1.4830862102497079e+01 , 1.6537848000000000e+01 , 7.7606900000000001e-01 , 3.4314000000000000e-01 , 5.2912300000000001e-01 -1.0232776901483941e+01 , -1.6530593872918534e+01 , 1.8406312000000000e+01 , -7.0823300000000000e-01 , -5.5892799999999998e-01 , -4.3128400000000000e-01 -4.7103942950466546e+00 , -3.1143176316173395e+00 , 7.7095687999999996e+00 , -5.5496000000000001e-01 , 4.6291900000000002e-01 , -6.9117700000000004e-01 -4.6326635174539863e+00 , -2.9447547853875147e+00 , 7.7282368000000004e+00 , -6.3311700000000004e-01 , 4.9869100000000000e-01 , -5.9200500000000000e-01 -4.6488177310982248e+00 , -3.0052342002823051e+00 , 7.9479888000000001e+00 , 8.3188799999999996e-01 , -3.3701199999999998e-01 , 4.4089200000000001e-01 -4.6204767146347923e+00 , -2.9580277040388916e+00 , 8.0761168000000012e+00 , 7.7712899999999996e-01 , -3.8195000000000001e-01 , 5.0018499999999999e-01 -4.5793583707242655e+00 , -2.8798258268758996e+00 , 8.1761336000000000e+00 , -4.1456399999999999e-01 , -8.5726899999999995e-01 , 3.0533100000000002e-01 -4.5491670739433143e+00 , -2.8285693955186115e+00 , 8.3028784000000009e+00 , 4.9762899999999999e-01 , 7.2353900000000004e-01 , -4.7838900000000001e-01 -4.4680353014122662e+00 , -2.6484583611908645e+00 , 8.2994048000000014e+00 , -4.5018999999999998e-01 , -8.5481799999999997e-01 , 2.5809799999999999e-01 -4.4478901876554513e+00 , -2.6211106438651921e+00 , 8.4519415999999996e+00 , -4.9630999999999997e-01 , -7.8081000000000000e-01 , 3.7948999999999999e-01 -4.4182203810717251e+00 , -2.5711704454258140e+00 , 8.5827735999999994e+00 , 9.0956099999999995e-01 , 3.9609100000000003e-01 , 1.2574500000000000e-01 -4.0425211338336755e+00 , -1.6430962691035327e+00 , 7.7122416000000005e+00 , -4.3603900000000001e-01 , 5.9680500000000003e-01 , -6.7356700000000003e-01 -4.3853807688270363e+00 , -2.5391483594559965e+00 , 8.9350008000000010e+00 , -6.1248499999999995e-01 , -6.1970999999999998e-01 , -4.9073600000000001e-01 -3.9358565615726855e+00 , -1.4336629250326802e+00 , 7.9489872000000004e+00 , 2.5431500000000001e-01 , -7.7758300000000002e-01 , 5.7505499999999998e-01 -3.9486181002310712e+00 , -1.4914874391382957e+00 , 8.1969752000000007e+00 , -6.0715999999999999e-02 , -9.5573900000000001e-01 , 2.8788399999999997e-01 -3.8781913011545632e+00 , -1.3329337668972618e+00 , 8.1625511999999993e+00 , 5.0362300000000004e-01 , -6.9849899999999998e-01 , 5.0839299999999998e-01 -3.8560483809696202e+00 , -1.3004942555581054e+00 , 8.2977720000000001e+00 , -4.9731500000000001e-01 , 2.5349200000000000e-01 , -8.2971099999999998e-01 -3.8197691462934165e+00 , -1.2297794385323297e+00 , 8.3828023999999992e+00 , -4.9731399999999998e-01 , 2.5349200000000000e-01 , -8.2971099999999998e-01 -3.5876889184292216e+00 , -6.3475294785863179e-01 , 7.6764448000000005e+00 , 4.2846800000000002e-01 , 3.1239200000000000e-01 , 8.4783699999999995e-01 -3.6028263654552672e+00 , -6.9874926703476614e-01 , 7.9470528000000007e+00 , 5.9565199999999996e-01 , 2.7501399999999998e-01 , 7.5469600000000003e-01 -3.5191701887961120e+00 , -4.9891377851351804e-01 , 7.8037616000000005e+00 , -5.9494700000000000e-01 , 1.0160700000000000e-01 , -7.9731600000000002e-01 -3.4727704610726997e+00 , -3.9846897265047820e-01 , 7.8128200000000003e+00 , -1.0440800000000000e-01 , 4.5240799999999998e-01 , 8.8567799999999997e-01 -3.4070846976058737e+00 , -2.4302907012381514e-01 , 7.7217680000000000e+00 , -1.2682700000000000e-01 , 2.6254800000000000e-01 , 9.5654799999999995e-01 -3.3662839402352267e+00 , -1.5520183186941017e-01 , 7.7431815999999998e+00 , 3.1071800000000000e-02 , -5.0026499999999996e-01 , -8.6531400000000003e-01 -3.3151086459387660e+00 , -3.7993224693042116e-02 , 7.7079152000000004e+00 , 5.8758600000000005e-01 , -4.9810599999999999e-01 , 6.3767799999999997e-01 -3.3467062585842737e+00 , -1.5542455644450426e-01 , 8.1278983999999994e+00 , 6.9220899999999996e-01 , -4.4503500000000001e-01 , -5.6814600000000004e-01 -3.4884649964578114e+00 , -5.9765990678875491e-01 , 9.2465848000000008e+00 , -2.2575400000000001e-01 , -9.7398700000000005e-01 , -1.9631099999999999e-02 -3.5207110689182723e+00 , -7.3618283720287936e-01 , 9.8044200000000004e+00 , 9.9142600000000003e-01 , 1.1365100000000000e-01 , -6.4487600000000006e-02 -3.4697143015075307e+00 , -6.2917816148299677e-01 , 9.8608608000000011e+00 , 9.9142600000000003e-01 , 1.1365100000000000e-01 , -6.4487500000000003e-02 -3.4206819753663371e+00 , -5.3050855804523112e-01 , 9.9343368000000005e+00 , 9.6226299999999998e-01 , 1.4976300000000001e-01 , -2.2720399999999999e-01 -3.1645256731928946e+00 , 2.0800779914199530e-01 , 8.4488111999999997e+00 , 3.9337699999999998e-01 , -1.6106999999999999e-01 , 9.0515800000000002e-01 -3.1452720803498346e+00 , 2.2509449710016338e-01 , 8.6612936000000005e+00 , 1.9811799999999999e-01 , -2.0125199999999999e-01 , -9.5929500000000001e-01 -3.2531322707123005e+00 , -1.6617962328248170e-01 , 9.9887808000000007e+00 , 7.4398200000000003e-01 , 4.2264900000000001e-02 , -6.6686199999999995e-01 -3.0309825255942009e+00 , 5.0261500110401647e-01 , 8.4543128000000003e+00 , -6.5993500000000005e-01 , 3.4675299999999999e-02 , -7.5052200000000002e-01 -2.9785555713720164e+00 , 6.2700856256755610e-01 , 8.3701664000000005e+00 , -6.5694100000000000e-01 , -1.0384400000000001e-01 , -7.4675700000000000e-01 -2.9962887633614037e+00 , 5.0923925870164544e-01 , 9.0331767999999997e+00 , -8.4663999999999995e-01 , 4.5231300000000002e-01 , -2.8038099999999999e-01 -2.9437790798299335e+00 , 6.3407234563541959e-01 , 8.9669911999999989e+00 , -9.3931399999999998e-01 , 2.6116600000000001e-01 , 2.2244400000000000e-01 -2.9128792418153036e+00 , 6.7897740704144893e-01 , 9.1674512000000004e+00 , -8.8782899999999998e-01 , -5.7160000000000002e-02 , -4.5661000000000002e-01 -2.8339023394275080e+00 , 9.0685265215620170e-01 , 8.7058159999999987e+00 , -9.3389599999999995e-01 , 2.4233600000000000e-01 , 2.6289200000000001e-01 -2.7733646120154019e+00 , 1.0736292915220838e+00 , 8.4192128000000004e+00 , 8.3012399999999997e-01 , -4.7264000000000000e-01 , 2.9581400000000002e-01 -2.8180788428209933e+00 , 7.8670607625620348e-01 , 1.0040323200000001e+01 , -8.7020600000000004e-01 , -2.3901900000000001e-01 , 4.3082700000000002e-01 -2.7455600774508744e+00 , 9.9746884491302268e-01 , 9.6005175999999999e+00 , 9.0099399999999996e-01 , 4.0284799999999998e-01 , -1.6100800000000001e-01 -2.7255284014979830e+00 , 9.5111068855558356e-01 , 1.0378052800000001e+01 , -4.0164200000000000e-01 , -8.2278300000000004e-01 , -4.0213399999999999e-01 -2.6648464511623873e+00 , 1.1075585473053651e+00 , 1.0177166400000001e+01 , -3.4131700000000001e-02 , 8.7390900000000005e-01 , 4.8488900000000001e-01 -2.6038241282677479e+00 , 1.2842743948434463e+00 , 9.8185432000000006e+00 , 2.3849400000000001e-01 , 2.9844400000000000e-02 , 9.7068500000000002e-01 -2.5564329554842784e+00 , 1.3765701933766024e+00 , 9.9292303999999998e+00 , -2.4144800000000000e-01 , 1.0515200000000001e-02 , -9.7035700000000003e-01 -2.5071773653539968e+00 , 1.4540669947043221e+00 , 1.0182148000000000e+01 , -5.2340399999999998e-01 , 6.4687899999999998e-01 , -5.5461300000000002e-01 -2.4549698001088722e+00 , 1.6159223232471223e+00 , 9.7832767999999994e+00 , -5.0192599999999998e-01 , 2.2366899999999999e-02 , 8.6462099999999997e-01 -2.4094279949761637e+00 , 1.7750784495530161e+00 , 9.2775560000000006e+00 , -2.0420300000000000e-01 , -8.7762499999999999e-01 , -4.3367699999999998e-01 -2.3661056272273906e+00 , 1.8810092674568084e+00 , 9.1932744000000000e+00 , 7.1442700000000003e-01 , 3.6582799999999999e-01 , 5.9645999999999999e-01 -2.3074320828766997e+00 , 1.9315792259974234e+00 , 9.8639183999999993e+00 , 3.9292500000000002e-01 , 9.1292300000000004e-01 , -1.1037200000000000e-01 -2.2728986342442745e+00 , 2.0674353176962454e+00 , 9.3503144000000002e+00 , -8.0789100000000003e-01 , 3.0222700000000002e-01 , 5.0593500000000002e-01 -2.2348340772043627e+00 , 2.1754296420808235e+00 , 9.1456423999999998e+00 , -5.7249300000000003e-01 , -4.5035999999999998e-01 , -6.8514799999999998e-01 -2.1937865864357793e+00 , 2.2731795752427191e+00 , 9.0844799999999992e+00 , 6.0868500000000003e-01 , 4.2062800000000000e-01 , 6.7273700000000003e-01 -2.1341959861387161e+00 , 2.3669955438678634e+00 , 9.4161880000000018e+00 , 1.6273199999999999e-01 , 5.0978599999999996e-01 , 8.4477000000000002e-01 -2.0913365727357940e+00 , 2.4672241928616305e+00 , 9.3616816000000007e+00 , -1.8651999999999998e-02 , 2.5006200000000001e-01 , 9.6804999999999997e-01 -2.0451249667548574e+00 , 2.5680339678285788e+00 , 9.3778535999999999e+00 , -5.0116599999999997e-02 , 3.2942700000000003e-01 , 9.4284999999999997e-01 -2.0051920930363067e+00 , 2.6653264629074771e+00 , 9.2988552000000002e+00 , -3.7633800000000002e-02 , 2.5880199999999998e-01 , 9.6519699999999997e-01 -1.9693427881674983e+00 , 2.7569588526070197e+00 , 9.1768111999999995e+00 , -6.0878200000000005e-01 , 4.0824100000000002e-01 , 6.8023800000000001e-01 -1.9130477860250996e+00 , 2.8650712523081214e+00 , 9.3114080000000001e+00 , -8.8461999999999996e-01 , 1.7240900000000000e-02 , 4.6599400000000002e-01 -1.7889683944344814e+00 , 3.1012395652987181e+00 , 9.6349832000000006e+00 , -1.1323500000000000e-01 , 1.8150200000000000e-01 , 9.7684899999999997e-01 -1.3782897902060229e+00 , 3.6175313846163726e+00 , 1.2984792000000001e+01 , -9.2198300000000000e-01 , -2.8543200000000002e-01 , 2.6167800000000002e-01 -1.7320779482682063e+00 , 3.2672168741972816e+00 , 9.2924280000000010e+00 , 6.0416299999999999e-02 , -9.7341500000000003e-01 , 2.2093900000000000e-01 -3.3458478103553633e+00 , 5.0192328831507838e-01 , 1.3978868000000000e+00 , -5.8074500000000001e-02 , 2.6490500000000000e-01 , 9.6252400000000005e-01 -3.3695598722678870e+00 , 4.4377178941017448e-01 , 1.4094848799999999e+00 , -7.1448499999999998e-02 , 2.8620299999999999e-01 , 9.5550100000000004e-01 -3.3893388420456452e+00 , 3.9372608188439240e-01 , 1.4287820800000000e+00 , 1.4508099999999999e-02 , -2.1611100000000000e-01 , -9.7626100000000005e-01 -3.4164154012955774e+00 , 3.2846774174748039e-01 , 1.4374348800000001e+00 , -1.1932200000000000e-02 , 1.8041399999999999e-01 , 9.8351800000000000e-01 -3.4395371405822384e+00 , 2.7026024766605050e-01 , 1.4538918399999998e+00 , -4.6856099999999998e-02 , 1.9161400000000001e-01 , 9.8035099999999997e-01 -3.4661800988318077e+00 , 2.0468055872723556e-01 , 1.4660889600000000e+00 , -5.7477100000000003e-02 , 1.8532000000000001e-01 , 9.8099599999999998e-01 -3.4935895807039703e+00 , 1.3846038752012069e-01 , 1.4805387200000000e+00 , -6.2715699999999999e-02 , 2.1068799999999999e-01 , 9.7553999999999996e-01 -3.5207376379752349e+00 , 7.1592977579581607e-02 , 1.4970154400000000e+00 , -5.9436200000000002e-02 , 2.2142899999999999e-01 , 9.7336299999999998e-01 -3.5476562187890739e+00 , 5.1247344656792926e-03 , 1.5154151200000001e+00 , -6.7194900000000002e-02 , 2.1086700000000000e-01 , 9.7520300000000004e-01 -3.5779153178891225e+00 , -7.0598738520003312e-02 , 1.5307727999999998e+00 , -8.3802799999999997e-02 , 2.1289600000000000e-01 , 9.7347399999999995e-01 -3.6089544314186668e+00 , -1.4587758360532677e-01 , 1.5484840000000000e+00 , 4.1976899999999998e-02 , -2.2573299999999999e-01 , -9.7328400000000004e-01 -3.6350673807246130e+00 , -2.1313521622605691e-01 , 1.5733639200000000e+00 , -3.2736300000000003e-02 , 2.3168600000000000e-01 , 9.7223999999999999e-01 -3.6701471372532506e+00 , -2.9709229639426837e-01 , 1.5909919200000000e+00 , -4.9548099999999998e-02 , 2.3195099999999999e-01 , 9.7146500000000002e-01 -3.7038412400653566e+00 , -3.8154249295630827e-01 , 1.6112292799999999e+00 , 6.0978100000000000e-02 , -2.0674899999999999e-01 , -9.7649200000000003e-01 -3.7417500903242695e+00 , -4.7495397760208036e-01 , 1.6299690400000000e+00 , -4.6513100000000002e-02 , 1.7614199999999999e-01 , 9.8326499999999994e-01 -3.7803148582991435e+00 , -5.6882674648765308e-01 , 1.6518724800000000e+00 , -6.2529199999999993e-02 , 1.6711200000000001e-01 , 9.8395299999999997e-01 -3.8254758066001560e+00 , -6.7995379345099716e-01 , 1.6686029599999999e+00 , -3.7540299999999999e-02 , 2.0677499999999999e-01 , 9.7766799999999998e-01 -3.8632328769060971e+00 , -7.7460575915098762e-01 , 1.6969866400000000e+00 , -4.5454799999999997e-02 , 1.9837099999999999e-01 , 9.7907299999999997e-01 -3.9130268873810827e+00 , -8.9476847046467700e-01 , 1.7173061600000001e+00 , -4.2561300000000003e-02 , 1.8471199999999999e-01 , 9.8187100000000005e-01 -3.9622856516880312e+00 , -1.0161645030907582e+00 , 1.7418792800000000e+00 , -4.6540499999999999e-02 , 1.8772600000000000e-01 , 9.8111800000000005e-01 -4.0120590116142880e+00 , -1.1377957907881728e+00 , 1.7707299200000000e+00 , -4.2135199999999998e-02 , 1.9501700000000000e-01 , 9.7989400000000004e-01 -4.0690913641605615e+00 , -1.2782236186497387e+00 , 1.7973716000000000e+00 , -5.6465399999999999e-02 , 1.9774300000000000e-01 , 9.7862600000000000e-01 -4.1255786755922523e+00 , -1.4176901678922698e+00 , 1.8286683200000000e+00 , -6.5709100000000006e-02 , 1.9377800000000001e-01 , 9.7884199999999999e-01 -4.1901530737593857e+00 , -1.5767404314702733e+00 , 1.8594024000000000e+00 , -5.6978800000000003e-02 , 1.8284500000000001e-01 , 9.8148899999999994e-01 -4.2550842161608537e+00 , -1.7357183794118680e+00 , 1.8958294400000000e+00 , -5.8778999999999998e-02 , 1.9732300000000000e-01 , 9.7857499999999997e-01 -4.3226394935420700e+00 , -1.9037678180671236e+00 , 1.9351887600000000e+00 , -7.6372499999999996e-02 , 1.9231699999999999e-01 , 9.7835700000000003e-01 -4.3990701367323872e+00 , -2.0909971139271324e+00 , 1.9761350160000000e+00 , -5.2337099999999998e-02 , 1.8143799999999999e-01 , 9.8200900000000002e-01 -4.4832312550057667e+00 , -2.2971502177282010e+00 , 2.0196554799999999e+00 , -4.7226799999999999e-02 , 1.9694999999999999e-01 , 9.7927500000000001e-01 -4.5697338640655918e+00 , -2.5119227539059974e+00 , 2.0683339279999999e+00 , -5.3298699999999997e-02 , 1.9283000000000000e-01 , 9.7978399999999999e-01 -4.6732131125716556e+00 , -2.7654241512247122e+00 , 2.1181377600000002e+00 , -4.5718399999999999e-02 , 1.8512999999999999e-01 , 9.8165000000000002e-01 -4.7755970526858125e+00 , -3.0181288722436506e+00 , 2.1769497599999998e+00 , -4.5745099999999997e-02 , 2.0277600000000001e-01 , 9.7815600000000003e-01 -4.8862669723847736e+00 , -3.2900374212539134e+00 , 2.2423096000000000e+00 , -5.1766399999999997e-02 , 1.9976500000000000e-01 , 9.7847499999999998e-01 -5.0238513350446556e+00 , -3.6276085763393473e+00 , 2.3090099999999998e+00 , -6.0465100000000001e-02 , 1.8022299999999999e-01 , 9.8176600000000003e-01 -5.1526341667725575e+00 , -3.9469399443083324e+00 , 2.3905740799999999e+00 , -8.7834800000000005e-02 , 2.0007100000000000e-01 , 9.7583600000000004e-01 -5.3129972859864161e+00 , -4.3410266065352099e+00 , 2.4767630399999998e+00 , 1.3241700000000000e-02 , -2.2474400000000000e-01 , -9.7432799999999997e-01 -5.4756926700838520e+00 , -4.7441059746614727e+00 , 2.5768422400000000e+00 , 7.6123900000000001e-03 , 2.1282899999999999e-01 , 9.7706000000000004e-01 -5.6946435080530744e+00 , -5.2806397116876695e+00 , 2.6852497600000000e+00 , 4.7486899999999999e-02 , 2.5883499999999998e-01 , 9.6475400000000000e-01 -5.9274396025016269e+00 , -5.8533323923630043e+00 , 2.8121630400000002e+00 , 7.5926400000000005e-02 , 2.5138400000000000e-01 , 9.6490500000000001e-01 -6.1908523744921489e+00 , -6.5027796597800513e+00 , 2.9599304000000002e+00 , -4.3434100000000003e-02 , -2.0910599999999999e-01 , -9.7692800000000002e-01 -6.5275576225867686e+00 , -7.3319320990722829e+00 , 3.1326016000000001e+00 , 5.5195200000000000e-03 , 1.9343299999999999e-01 , 9.8109800000000003e-01 -6.9263883432188198e+00 , -8.3117706012144073e+00 , 3.3403000000000000e+00 , -2.8316100000000000e-02 , 2.0401600000000000e-01 , 9.7855800000000004e-01 -7.3931686962343592e+00 , -9.4607140353619261e+00 , 3.5922399999999999e+00 , -3.5209699999999997e-02 , 1.9506899999999999e-01 , 9.8015699999999994e-01 -7.8883580172068939e+00 , -1.0682954540312156e+01 , 3.8924776000000003e+00 , 3.2876799999999998e-02 , -2.0494699999999999e-01 , -9.7822100000000001e-01 -8.5879496349547360e+00 , -1.2407282907059047e+01 , 4.2797631999999997e+00 , -8.9157000000000004e-03 , 2.2187399999999999e-01 , 9.7503499999999999e-01 -9.2456882337578712e+00 , -1.4037587979044190e+01 , 4.7235519999999998e+00 , -3.9370400000000002e-03 , 3.1789499999999998e-01 , 9.4811800000000002e-01 -1.0309413491863300e+01 , -1.6662983511345665e+01 , 5.3483320000000001e+00 , 4.9638000000000002e-02 , 9.6522399999999997e-01 , 2.5666899999999998e-01 -1.0035622106787121e+01 , -1.6097709619474202e+01 , 5.9877864000000001e+00 , 2.9609000000000002e-01 , 9.5251399999999997e-01 , -7.1052900000000002e-02 -1.0032533196506293e+01 , -1.6141206329495965e+01 , 6.3509960000000003e+00 , -2.0374999999999999e-01 , -9.6257099999999995e-01 , -1.7872499999999999e-01 -1.0157169939595544e+01 , -1.6499866148742374e+01 , 6.7791848000000003e+00 , -3.2955800000000002e-01 , -8.5237499999999999e-01 , -4.0601500000000001e-01 -1.0433908036615358e+01 , -1.7288127522945377e+01 , 7.7004792000000002e+00 , -1.2926399999999999e-01 , 6.9264000000000003e-01 , 7.0960599999999996e-01 -1.0656528459870895e+01 , -1.7893698779948945e+01 , 8.2418720000000008e+00 , 1.9142500000000001e-01 , 5.5375600000000003e-01 , 8.1037700000000001e-01 -1.0774824188070708e+01 , -1.8245366997838584e+01 , 8.7404375999999999e+00 , 2.1451500000000001e-01 , 5.7376700000000003e-01 , 7.9042699999999999e-01 -1.1349145487049334e+01 , -1.9731923120464135e+01 , 9.5902528000000018e+00 , -5.9743900000000005e-01 , -7.4234299999999998e-01 , -3.0330400000000002e-01 -8.9648238413719721e+00 , -1.3849926382088555e+01 , 8.1879480000000004e+00 , 5.3264999999999996e-01 , 2.0877200000000001e-01 , -8.2018199999999997e-01 -8.7932032332219716e+00 , -1.3467258247996801e+01 , 8.3905607999999994e+00 , -2.3928600000000000e-01 , -6.0573399999999999e-01 , 7.5883400000000001e-01 -1.1205245081684261e+01 , -1.9569236823053419e+01 , 1.0883534400000000e+01 , -4.9963299999999999e-01 , -6.8787399999999999e-01 , -5.2649400000000002e-01 -8.1122201027473437e+00 , -1.1847501414045233e+01 , 8.4375272000000017e+00 , -2.1584600000000001e-01 , -4.2609999999999998e-01 , 8.7854900000000002e-01 -7.8498562999369730e+00 , -1.1229612412866670e+01 , 8.4915136000000011e+00 , 6.3545900000000002e-02 , -9.9785100000000004e-01 , -1.6007899999999999e-02 -7.7780697461368753e+00 , -1.1091676668037763e+01 , 8.7236104000000019e+00 , 8.2154900000000003e-02 , -9.7828300000000001e-01 , 1.9029900000000000e-01 -8.2938748796898345e+00 , -1.2445247302206727e+01 , 9.6094095999999993e+00 , 7.7747500000000003e-01 , 6.2012000000000000e-01 , 1.0480600000000000e-01 -7.9144462617097551e+00 , -1.1525420842695082e+01 , 9.5088520000000010e+00 , -7.6056199999999996e-01 , 6.4160099999999998e-01 , -9.9465600000000001e-02 -7.7778268627838436e+00 , -1.1221610956536514e+01 , 9.6703016000000002e+00 , -9.0435900000000002e-01 , 3.5324200000000000e-01 , -2.3949000000000001e-01 -7.7170216232206990e+00 , -1.1110312534354396e+01 , 9.9199015999999993e+00 , -1.2128400000000000e-01 , 9.7570800000000002e-01 , -1.8243699999999999e-01 -8.1361936223368545e+00 , -1.2238239355287815e+01 , 1.0824566400000000e+01 , 8.1738999999999995e-01 , 5.7606400000000002e-01 , -4.8951999999999997e-03 -7.7866719665640236e+00 , -1.1383447665120684e+01 , 1.0692424000000001e+01 , -4.4038300000000002e-01 , 8.5356500000000002e-01 , -2.7836899999999998e-01 -7.6657666888226474e+00 , -1.1118367888648994e+01 , 1.0865116000000000e+01 , 5.5154599999999998e-01 , -8.0107799999999996e-01 , 2.3253099999999999e-01 -8.4461366399356539e+00 , -1.3198786168528432e+01 , 1.2437232000000000e+01 , -3.5948900000000000e-01 , -8.1739499999999998e-01 , 4.5014799999999999e-01 -7.5228010270374561e+00 , -1.0844707798905675e+01 , 1.1349548000000000e+01 , 4.2655300000000002e-01 , -8.0409600000000003e-01 , 4.1410400000000003e-01 -7.4567274636639436e+00 , -1.0723229103403598e+01 , 1.1600926400000001e+01 , 4.2655399999999999e-01 , -8.0409600000000003e-01 , 4.1410400000000003e-01 -7.3517338354210571e+00 , -1.0498325009005487e+01 , 1.1783248799999999e+01 , -6.4858300000000002e-01 , 7.3991899999999999e-01 , -1.7849400000000001e-01 -8.4011788568163652e+00 , -1.3322291790924984e+01 , 1.4096864000000002e+01 , -5.8006599999999997e-01 , -8.1371300000000002e-01 , -3.7338600000000000e-02 -8.1895943304790961e+00 , -1.2826965601131556e+01 , 1.4153960000000001e+01 , -5.8036100000000002e-01 , -7.3110900000000001e-01 , -3.5869299999999998e-01 -8.1153678836891299e+00 , -1.2691965097614363e+01 , 1.4465959999999999e+01 , -7.1575299999999997e-01 , -6.9660299999999997e-01 , 4.9417799999999998e-02 -8.9840948075146514e+00 , -1.5082050277908490e+01 , 1.6754688000000002e+01 , -6.8202700000000005e-01 , -5.1684799999999997e-01 , -5.1740399999999998e-01 -8.7786676619946000e+00 , -1.4609351854202586e+01 , 1.6869920000000000e+01 , -6.8202700000000005e-01 , -5.1684799999999997e-01 , -5.1740399999999998e-01 -8.5134431376246340e+00 , -1.3969864664859310e+01 , 1.6830192000000000e+01 , -6.2935099999999999e-01 , -5.8023300000000000e-01 , -5.1695999999999998e-01 -8.7498013776179029e+00 , -1.4689377892405439e+01 , 1.7947360000000000e+01 , -6.3927100000000003e-01 , -6.2307699999999999e-01 , -4.5067400000000002e-01 -4.3274039573997927e+00 , -2.7925889112958515e+00 , 8.2707943999999998e+00 , 4.9762899999999999e-01 , 7.2353900000000004e-01 , -4.7838900000000001e-01 -4.3497051774418516e+00 , -2.9476761624835470e+00 , 9.0025592000000003e+00 , -6.1248499999999995e-01 , -6.1970899999999995e-01 , -4.9073600000000001e-01 -4.3258760378691594e+00 , -2.9130953681233080e+00 , 9.1690944000000005e+00 , -6.1248599999999997e-01 , -6.1970899999999995e-01 , -4.9073600000000001e-01 -3.7229033286243185e+00 , -1.3697922399845432e+00 , 8.3997647999999998e+00 , 5.9757300000000002e-01 , -9.1710899999999998e-02 , 7.9655200000000004e-01 -3.6666074381873877e+00 , -1.2329503803062019e+00 , 8.3923392000000003e+00 , 3.9753300000000003e-01 , 4.0804600000000002e-01 , -8.2186700000000001e-01 -3.6236901446844048e+00 , -1.1363413823452855e+00 , 8.4410840000000000e+00 , 5.3698400000000002e-01 , 8.7763200000000000e-02 , -8.3901499999999996e-01 -3.4413630014723822e+00 , -6.1600490725032531e-01 , 7.8226272000000003e+00 , 2.8942499999999999e-01 , 1.5719800000000000e-01 , 9.4420400000000004e-01 -3.4254128436783722e+00 , -5.9980846388220987e-01 , 7.9733648000000006e+00 , -2.0672199999999999e-01 , -3.8674100000000000e-01 , -8.9871999999999996e-01 -3.3205850160171826e+00 , -3.0699945261895945e-01 , 7.6651400000000010e+00 , -3.5977200000000001e-02 , 5.3741899999999998e-01 , 8.4254799999999996e-01 -3.2886250549345353e+00 , -2.3878354011765124e-01 , 7.7228599999999998e+00 , -3.4247100000000003e-01 , 6.1562899999999998e-01 , 7.0972800000000003e-01 -3.2452379666467337e+00 , -1.3525555691858315e-01 , 7.7162455999999997e+00 , -3.4247100000000003e-01 , 6.1562899999999998e-01 , 7.0972900000000005e-01 -3.2593576278802203e+00 , -2.1451594402697216e-01 , 8.0531640000000007e+00 , 3.2529300000000000e-01 , -8.9820199999999994e-01 , 2.9566500000000001e-01 -3.2330784881318433e+00 , -1.6763429136055175e-01 , 8.1642776000000019e+00 , -2.3619999999999999e-01 , 8.7299099999999996e-01 , -4.2672700000000002e-01 -3.3544080595577834e+00 , -6.1285418264618219e-01 , 9.2953919999999997e+00 , -9.6206499999999995e-01 , -2.0980900000000000e-01 , 1.7438600000000001e-01 -3.3818867419122198e+00 , -7.6124657950340069e-01 , 9.8822744000000000e+00 , 9.9142600000000003e-01 , 1.1365100000000000e-01 , -6.4487600000000006e-02 -3.1576201205785805e+00 , -4.3208523384757225e-02 , 8.5707512000000001e+00 , 8.3631299999999997e-01 , -1.5846600000000000e-01 , -5.2485199999999999e-01 -3.2754468643243921e+00 , -5.1082842802402872e-01 , 9.9166775999999999e+00 , 9.6226299999999998e-01 , 1.4976300000000001e-01 , -2.2720399999999999e-01 -3.0552003816604145e+00 , 2.1932582359366082e-01 , 8.4448071999999996e+00 , -3.9885100000000001e-01 , 4.2082700000000001e-03 , -9.1700599999999999e-01 -3.1367847388117496e+00 , -1.4082408697555371e-01 , 9.6312704000000018e+00 , -8.1844499999999998e-01 , -2.5428600000000001e-01 , 5.1525399999999999e-01 -2.9763210311819437e+00 , 3.9956448923205534e-01 , 8.5003744000000001e+00 , -6.0119699999999998e-01 , 1.1261400000000001e-01 , -7.9112600000000000e-01 -2.9355208676172388e+00 , 4.9695283096952081e-01 , 8.5060216000000004e+00 , 6.3427100000000003e-01 , 2.7485800000000001e-02 , 7.7262200000000003e-01 -2.8980951345125283e+00 , 5.7715539723059095e-01 , 8.5588016000000007e+00 , 6.0814999999999997e-01 , 1.9120899999999999e-01 , 7.7044900000000005e-01 -2.9023638597097845e+00 , 4.8442706909813782e-01 , 9.1640607999999997e+00 , 6.3484399999999996e-01 , -7.2046600000000005e-01 , 2.7910699999999999e-01 -2.8710878616309623e+00 , 5.2849184935710558e-01 , 9.3760855999999997e+00 , -8.5331100000000004e-01 , -7.5393699999999994e-02 , -5.1592199999999999e-01 -2.8263278121447577e+00 , 6.3252677231795995e-01 , 9.3980607999999997e+00 , -8.0636600000000003e-01 , -1.7033200000000001e-01 , -5.6635800000000003e-01 -2.8044642383865002e+00 , 6.2035900551827106e-01 , 9.8600184000000013e+00 , 9.8903600000000003e-01 , -2.3065300000000002e-03 , -1.4765600000000001e-01 -2.7358468405638097e+00 , 8.4498601808162443e-01 , 9.4161047999999994e+00 , -1.2276100000000000e-01 , -6.5776199999999996e-01 , 7.4315500000000001e-01 -2.7036394735658176e+00 , 8.7780479251905708e-01 , 9.7460032000000005e+00 , 8.3888900000000000e-01 , -1.6302100000000000e-01 , 5.1931600000000000e-01 -2.6541093129144038e+00 , 1.0023823251986679e+00 , 9.6897392000000000e+00 , 4.2775299999999999e-01 , 2.9654000000000003e-01 , -8.5386899999999999e-01 -2.6292152201033949e+00 , 9.3643650659737010e-01 , 1.0590368800000000e+01 , -5.4168799999999995e-01 , -8.2216599999999995e-01 , -1.7497900000000000e-01 -2.5655320708273766e+00 , 1.1805585660164475e+00 , 9.9280240000000006e+00 , 4.1762300000000002e-01 , -1.6984200000000001e-02 , 9.0846199999999999e-01 -2.5186997568374863e+00 , 1.2950152142240912e+00 , 9.9169376000000007e+00 , -3.2601799999999997e-01 , 9.2945100000000003e-02 , -9.4078399999999995e-01 -2.4712530439701208e+00 , 1.4034674721720535e+00 , 9.9444248000000002e+00 , 5.2909200000000001e-01 , -2.0695400000000000e-01 , 8.2294100000000003e-01 -2.4240600447117013e+00 , 1.5004916137651376e+00 , 1.0062808000000000e+01 , 2.2105300000000000e-01 , -8.0654899999999996e-01 , 5.4828299999999996e-01 -2.3797758399982030e+00 , 1.6519047626673706e+00 , 9.7350208000000009e+00 , 5.1883000000000001e-01 , -3.2137600000000000e-01 , -7.9217000000000004e-01 -2.3407912868213376e+00 , 1.7962234529552865e+00 , 9.3625968000000004e+00 , 7.9573700000000003e-01 , 3.5731499999999999e-01 , 4.8900800000000000e-01 -2.3030309082714613e+00 , 1.9127419155218430e+00 , 9.1739408000000005e+00 , -6.8659899999999996e-01 , -3.2733600000000002e-01 , -6.4917899999999995e-01 -2.2571701604864307e+00 , 2.0025395006222739e+00 , 9.3147152000000002e+00 , -9.6430199999999999e-01 , 1.8899500000000001e-03 , 2.6479900000000001e-01 -2.2193215519693505e+00 , 2.1094318736946649e+00 , 9.1942103999999993e+00 , -9.0645900000000001e-01 , -2.3621800000000001e-01 , -3.5004700000000000e-01 -2.1776648882252685e+00 , 2.2072292730325032e+00 , 9.2069504000000002e+00 , 8.7710299999999997e-01 , -4.7974099999999997e-01 , -2.3208900000000001e-02 -2.0798724349691660e+00 , 2.4047594848893574e+00 , 9.4550112000000013e+00 , 1.6273199999999999e-01 , 5.0978599999999996e-01 , 8.4477000000000002e-01 -2.0430298877724442e+00 , 2.5067882634075449e+00 , 9.3685559999999999e+00 , -8.3753999999999995e-02 , 1.3553499999999999e-01 , 9.8722600000000005e-01 -2.0017280553294090e+00 , 2.6073581173505680e+00 , 9.3529663999999997e+00 , -1.1468600000000000e-01 , 5.5209699999999995e-01 , 8.2585399999999998e-01 -1.9596639829568492e+00 , 2.7085682607570671e+00 , 9.3351199999999999e+00 , 1.3755200000000001e-01 , -1.2885600000000000e-01 , 9.8207699999999998e-01 -1.9293514173879243e+00 , 2.8009441716703414e+00 , 9.2021455999999997e+00 , 5.3840200000000005e-01 , -5.7815000000000005e-01 , 6.1307900000000004e-01 -1.8845832902739803e+00 , 2.9034992719235468e+00 , 9.2325552000000002e+00 , 9.7231900000000004e-01 , -2.3268900000000001e-01 , 2.1266000000000000e-02 -1.7939337508587707e+00 , 3.0521703111793128e+00 , 9.7244856000000013e+00 , -1.7175599999999999e-01 , 8.6365199999999998e-01 , 4.7392499999999999e-01 -1.7559497171508571e+00 , 3.1518167430140407e+00 , 9.6470471999999994e+00 , 4.2082799999999998e-01 , -3.2232400000000000e-01 , -8.4794499999999995e-01 -1.7475020970755248e+00 , 3.2183258133635260e+00 , 9.3218703999999999e+00 , -1.7905099999999999e-03 , 2.5991799999999998e-01 , 9.6562899999999996e-01 -1.7102112096028796e+00 , 3.3140591507330353e+00 , 9.2725848000000006e+00 , 9.7889199999999996e-02 , -9.6734399999999998e-01 , 2.3380000000000001e-01 -3.2910865648164132e+00 , 5.0452211175509709e-01 , 1.3833039199999999e+00 , 2.2914600000000000e-02 , 2.1246799999999999e-01 , 9.7689899999999996e-01 -3.3062526009373610e+00 , 4.6087387935922930e-01 , 1.4070429600000001e+00 , -1.9487299999999999e-02 , 2.6165300000000002e-01 , 9.6496499999999996e-01 -3.3278267000350175e+00 , 4.0289385080348827e-01 , 1.4189967200000000e+00 , -2.8846600000000000e-02 , 2.5941599999999998e-01 , 9.6533500000000005e-01 -3.3464607045153190e+00 , 3.5195813283438460e-01 , 1.4389813600000001e+00 , -5.0904300000000000e-02 , 2.1537899999999999e-01 , 9.7520300000000004e-01 -3.3713601350545486e+00 , 2.8585522894769833e-01 , 1.4481947200000000e+00 , -7.2606599999999993e-02 , 1.5691600000000000e-01 , 9.8493900000000001e-01 -3.3960165707068919e+00 , 2.1907698764360672e-01 , 1.4593341600000000e+00 , -9.1556499999999999e-02 , 1.6921500000000000e-01 , 9.8131699999999999e-01 -3.4214766297166230e+00 , 1.5268449086256219e-01 , 1.4725213600000000e+00 , -8.4514900000000004e-02 , 1.8302299999999999e-01 , 9.7946900000000003e-01 -3.4466783219331791e+00 , 8.5645375196405027e-02 , 1.4877344799999999e+00 , -6.2975799999999998e-02 , 2.2314400000000001e-01 , 9.7274899999999997e-01 -3.4716206004647603e+00 , 1.7970039953649097e-02 , 1.5049745600000000e+00 , -7.5567099999999998e-02 , 2.1273500000000001e-01 , 9.7418300000000002e-01 -3.4999547944092768e+00 , -5.7942011668702165e-02 , 1.5189688000000001e+00 , -9.4798999999999994e-02 , 2.0862500000000000e-01 , 9.7338999999999998e-01 -3.5243907723536871e+00 , -1.2582609436133518e-01 , 1.5403595200000000e+00 , -1.2051600000000000e-01 , 2.1111900000000000e-01 , 9.7000200000000003e-01 -3.5532026472443712e+00 , -2.0189599183782470e-01 , 1.5589349600000000e+00 , -9.1560400000000000e-02 , 2.4360999999999999e-01 , 9.6554200000000001e-01 -3.5842511966904507e+00 , -2.8706286452441798e-01 , 1.5750518400000000e+00 , -7.6490600000000006e-02 , 2.1424099999999999e-01 , 9.7378100000000001e-01 -3.6124458695354451e+00 , -3.6422352373235700e-01 , 1.5985901600000001e+00 , -9.9753200000000000e-02 , 1.9035400000000000e-01 , 9.7663400000000000e-01 -3.6473740505939416e+00 , -4.5889713442480273e-01 , 1.6157418400000001e+00 , -8.6991100000000002e-02 , 1.7359700000000000e-01 , 9.8096700000000003e-01 -3.6830208137018943e+00 , -5.5303245493695474e-01 , 1.6357504000000000e+00 , -7.8497600000000001e-02 , 1.5119299999999999e-01 , 9.8538300000000001e-01 -3.7252276766704311e+00 , -6.6544807370212133e-01 , 1.6506900000000000e+00 , -9.3857800000000005e-02 , 2.0315600000000000e-01 , 9.7463800000000000e-01 -3.7531066578071499e+00 , -7.4356409480239494e-01 , 1.6852897600000001e+00 , -1.1803000000000000e-01 , 1.8520500000000001e-01 , 9.7558599999999995e-01 -3.8023942766259093e+00 , -8.7447281534604970e-01 , 1.6995388000000000e+00 , -7.8760600000000000e-02 , 1.7381900000000000e-01 , 9.8162300000000002e-01 -3.8408957560733703e+00 , -9.7850303038320519e-01 , 1.7289853600000000e+00 , -6.6513600000000006e-02 , 1.6259399999999999e-01 , 9.8444900000000002e-01 -3.8912070637424225e+00 , -1.1109020827616489e+00 , 1.7518924000000000e+00 , -7.9596700000000006e-02 , 1.7539199999999999e-01 , 9.8127600000000004e-01 -3.9399700378930924e+00 , -1.2424158956720084e+00 , 1.7789230400000000e+00 , -7.7827900000000005e-02 , 1.8164400000000000e-01 , 9.8028000000000004e-01 -3.9891806728947055e+00 , -1.3750911230658893e+00 , 1.8107387200000000e+00 , -9.6037499999999998e-02 , 1.7454800000000001e-01 , 9.7995399999999999e-01 -4.0455519534631517e+00 , -1.5263918191267916e+00 , 1.8412575200000001e+00 , -8.8651800000000003e-02 , 1.8118400000000001e-01 , 9.7944500000000001e-01 -4.1056287611963036e+00 , -1.6869162001927029e+00 , 1.8742265599999999e+00 , -7.8038600000000000e-02 , 1.9869400000000001e-01 , 9.7694999999999999e-01 -4.1682977557657317e+00 , -1.8575584775323382e+00 , 1.9102316720000001e+00 , -8.5105000000000000e-02 , 1.8662300000000001e-01 , 9.7873800000000000e-01 -4.2355956801870525e+00 , -2.0372160338374998e+00 , 1.9499260800000000e+00 , -9.4239600000000007e-02 , 1.9368299999999999e-01 , 9.7652700000000003e-01 -4.3063908749080593e+00 , -2.2267974053913910e+00 , 1.9937940496000000e+00 , -8.4462200000000001e-02 , 1.8950100000000000e-01 , 9.7824100000000003e-01 -4.3871123103850937e+00 , -2.4443547951175209e+00 , 2.0379810080000000e+00 , -7.3952900000000002e-02 , 1.9701199999999999e-01 , 9.7760800000000003e-01 -4.4711158647188807e+00 , -2.6714551524895214e+00 , 2.0881626720000002e+00 , -6.0972600000000002e-02 , 1.9154700000000000e-01 , 9.7958800000000001e-01 -4.5635775750369341e+00 , -2.9180852277843661e+00 , 2.1433743999999999e+00 , -5.1498900000000000e-02 , 1.9855300000000001e-01 , 9.7873600000000005e-01 -4.6655032750816714e+00 , -3.1929760316057916e+00 , 2.2026512800000000e+00 , -5.5840300000000002e-02 , 2.1270100000000000e-01 , 9.7552000000000005e-01 -4.7672394462927095e+00 , -3.4679264778718029e+00 , 2.2720754400000001e+00 , -7.5234200000000001e-02 , 1.8004999999999999e-01 , 9.8077599999999998e-01 -4.9092690938287120e+00 , -3.8481568350703821e+00 , 2.3388101600000000e+00 , -2.6724100000000001e-02 , 1.9027400000000000e-01 , 9.8136699999999999e-01 -5.0547900838760285e+00 , -4.2376012370327274e+00 , 2.4185479999999999e+00 , -1.4089100000000000e-02 , 2.5014700000000001e-01 , 9.6810499999999999e-01 -5.1985637149736466e+00 , -4.6272725079019645e+00 , 2.5125608800000001e+00 , -3.4640499999999998e-02 , -2.7641700000000002e-01 , -9.6041299999999996e-01 -5.3753084638170892e+00 , -5.1025910725364509e+00 , 2.6154272800000000e+00 , -5.1424200000000003e-02 , -2.4939300000000000e-01 , -9.6703600000000001e-01 -5.4982861347412477e+00 , -5.4413404145924167e+00 , 2.7416884800000001e+00 , 6.4513799999999996e-02 , 2.4875500000000000e-01 , 9.6641500000000002e-01 -5.6349264223581130e+00 , -5.8166040689347733e+00 , 2.8793470399999999e+00 , 7.6881300000000000e-02 , 2.5062000000000001e-01 , 9.6502800000000000e-01 -5.8850585527588386e+00 , -6.4916219013968757e+00 , 3.0291174400000003e+00 , 4.9781199999999998e-02 , 1.9854500000000000e-01 , 9.7882700000000000e-01 -6.3135419383446694e+00 , -7.6299387441017981e+00 , 3.2099776000000002e+00 , 1.1640000000000001e-03 , 1.7825500000000000e-01 , 9.8398399999999997e-01 -6.6884228981080076e+00 , -8.6393038963907181e+00 , 3.4289808000000002e+00 , -2.4425100000000002e-02 , 1.9259499999999999e-01 , 9.8097400000000001e-01 -7.1494130567532208e+00 , -9.8791945539779533e+00 , 3.6977168000000002e+00 , -3.1568699999999998e-02 , 2.0048099999999999e-01 , 9.7918899999999998e-01 -7.6979781400729337e+00 , -1.1355585010212575e+01 , 4.0289359999999999e+00 , -2.1747300000000001e-02 , 2.0324000000000000e-01 , 9.7888699999999995e-01 -8.3138910672128858e+00 , -1.3019836223155471e+01 , 4.4323624000000006e+00 , 8.2095599999999994e-03 , 2.1954899999999999e-01 , 9.7556699999999996e-01 -9.1837994590565479e+00 , -1.5362354511041932e+01 , 4.9707287999999998e+00 , -1.3176399999999999e-01 , 5.5816200000000005e-01 , 8.1920300000000001e-01 -9.4137409986667233e+00 , -1.6084972427228422e+01 , 5.7441352000000006e+00 , -3.2176500000000002e-01 , -8.6591799999999997e-01 , -3.8295400000000002e-01 -9.3948776673778340e+00 , -1.6093995860537628e+01 , 6.0956967999999998e+00 , -7.8444200000000006e-02 , 8.9181800000000000e-01 , 4.4554100000000002e-01 -9.4599096158410507e+00 , -1.6328486201821093e+01 , 6.4902312000000002e+00 , -7.8444299999999995e-02 , 8.9181800000000000e-01 , 4.4554100000000002e-01 -9.9733736084733948e+00 , -1.7899112613331805e+01 , 7.9479056000000003e+00 , 1.1067700000000000e-01 , 7.2024999999999995e-01 , 6.8482900000000002e-01 -1.0082108922726999e+01 , -1.8260677466062504e+01 , 8.4374648000000008e+00 , 1.3448499999999999e-01 , 6.4684299999999995e-01 , 7.5067099999999998e-01 -8.9973623255465043e+00 , -1.5383487096335692e+01 , 8.0409335999999989e+00 , -5.7844200000000001e-01 , 3.8622899999999999e-01 , -7.1849300000000005e-01 -8.4129846230390228e+00 , -1.3849519805845338e+01 , 7.9351968000000008e+00 , -3.7935099999999999e-01 , -5.7076400000000005e-01 , 7.2823199999999999e-01 -8.4539307415631768e+00 , -1.4018219836815003e+01 , 8.3137360000000005e+00 , -3.7935099999999999e-01 , -5.7076400000000005e-01 , 7.2823199999999999e-01 -8.2543477376810515e+00 , -1.3526191040931725e+01 , 8.4785032000000005e+00 , -3.5306999999999999e-01 , -8.5793200000000003e-01 , 3.7322200000000000e-01 -8.2631198346283661e+00 , -1.3609092810267409e+01 , 8.8329664000000001e+00 , 2.6564700000000002e-01 , 7.3429199999999994e-01 , -6.2469699999999995e-01 -7.5939923508978175e+00 , -1.1815238259627423e+01 , 8.4817064000000002e+00 , -9.5153900000000003e-03 , -3.9156500000000000e-01 , 9.2010099999999995e-01 -7.3724077707344993e+00 , -1.1254980464739743e+01 , 8.5534663999999996e+00 , -1.6213200000000000e-01 , 7.6614099999999996e-01 , -6.2188500000000002e-01 -7.4901395034984821e+00 , -1.1632867359173185e+01 , 9.0012487999999991e+00 , 3.4973799999999999e-01 , -9.2593300000000001e-01 , -1.4258999999999999e-01 -7.6483632685301268e+00 , -1.2126488712480525e+01 , 9.5203856000000009e+00 , 1.5852500000000000e-01 , -2.0569299999999999e-01 , -9.6569199999999999e-01 -7.4062831998403427e+00 , -1.1504594110078003e+01 , 9.5461880000000008e+00 , -4.0100100000000000e-01 , 8.6454799999999998e-01 , -3.0291099999999999e-01 -7.4582054396237281e+00 , -1.1705768854556222e+01 , 9.9499576000000012e+00 , -3.5236000000000001e-01 , 6.9951500000000000e-01 , -6.2170800000000004e-01 -7.3533615526688312e+00 , -1.1463962082956359e+01 , 1.0142087200000001e+01 , 3.7076500000000001e-01 , -8.8785300000000000e-01 , 2.7248800000000001e-01 -7.2718374140229640e+00 , -1.1291390486540816e+01 , 1.0364616000000000e+01 , -8.8501899999999994e-02 , 9.8304300000000000e-01 , -1.6060600000000000e-01 -7.3153912874130107e+00 , -1.1470703999615774e+01 , 1.0780304000000001e+01 , 2.1223800000000001e-01 , -9.7628800000000004e-01 , -4.2630899999999999e-02 -7.2011465059958084e+00 , -1.1202151768900229e+01 , 1.0950500000000000e+01 , 4.5845200000000003e-01 , -8.8840100000000000e-01 , -2.3782200000000000e-02 -7.2939459735163013e+00 , -1.1529912758972069e+01 , 1.1472767200000000e+01 , -6.3592599999999999e-01 , 7.6629300000000000e-01 , 9.1612200000000005e-02 -7.5332713645651497e+00 , -1.2284479235819983e+01 , 1.2284861600000001e+01 , 7.3850199999999999e-01 , -5.9633100000000006e-01 , -3.1465100000000001e-01 -7.2838379723766788e+00 , -1.1627147122408878e+01 , 1.2221359200000000e+01 , -2.1679399999999999e-01 , 9.7478399999999998e-01 , -5.2875499999999999e-02 -7.1659463339189760e+00 , -1.1348404276506498e+01 , 1.2388591200000000e+01 , 8.4953100000000004e-01 , -1.7348400000000000e-01 , 4.9819700000000000e-01 -7.4794032340683332e+00 , -1.2330735221343783e+01 , 1.3435112000000000e+01 , 5.1828399999999997e-01 , 8.4578500000000001e-01 , 1.2660800000000000e-01 -7.7121309423009672e+00 , -1.3089398110946370e+01 , 1.4378184000000001e+01 , -5.8036100000000002e-01 , -7.3110900000000001e-01 , -3.5869400000000001e-01 -7.4427466938930742e+00 , -1.2372016631424104e+01 , 1.4255360000000001e+01 , -6.9515099999999996e-01 , -6.8291400000000002e-01 , 2.2448699999999999e-01 -7.2722733847514007e+00 , -1.1940409033207521e+01 , 1.4326808000000002e+01 , -1.2020699999999999e-01 , 9.6163399999999999e-01 , -2.4659900000000001e-01 -7.2644700090282370e+00 , -1.1994517899515024e+01 , 1.4778896000000000e+01 , 1.4555599999999999e-01 , 9.6292800000000001e-01 , -2.2711799999999999e-01 -7.3320970339509328e+00 , -1.2277825779298599e+01 , 1.5437320000000001e+01 , -3.5787799999999997e-01 , -9.3347800000000003e-01 , 2.3264199999999999e-02 -8.2915355552660479e+00 , -1.5266901274030818e+01 , 1.8482648000000001e+01 , 4.8966199999999999e-01 , 6.7100499999999996e-01 , 5.5676199999999998e-01 -7.0080995690905308e+00 , -1.1931457840474881e+01 , 1.8436368000000002e+01 , 8.3763900000000002e-01 , -5.1404000000000005e-01 , 1.8472700000000000e-01 -6.8553600259751351e+00 , -1.1554406581368296e+01 , 1.8552016000000002e+01 , 8.3763900000000002e-01 , -5.1404000000000005e-01 , 1.8472700000000000e-01 -4.1071167879442374e+00 , -2.8839764828787500e+00 , 9.1457464000000002e+00 , -6.1248499999999995e-01 , -6.1970899999999995e-01 , -4.9073600000000001e-01 -4.0565259741183599e+00 , -2.7664265536417005e+00 , 9.2176936000000005e+00 , -6.1248499999999995e-01 , -6.1970899999999995e-01 , -4.9073600000000001e-01 -4.0124525613351807e+00 , -2.6672080242325036e+00 , 9.3107736000000010e+00 , 3.3836699999999997e-01 , -9.1905300000000001e-01 , 2.0211299999999999e-01 -3.7619243210932933e+00 , -1.8906120874111880e+00 , 8.5425047999999997e+00 , 6.4550900000000000e-01 , 2.8342500000000000e-02 , 7.6322699999999999e-01 -3.6861116007108534e+00 , -1.6794664956171288e+00 , 8.4570375999999996e+00 , -2.2837099999999999e-01 , 4.6229700000000001e-01 , 8.5681300000000005e-01 -3.5353433567651127e+00 , -1.2166671469553010e+00 , 8.0182719999999996e+00 , 4.5605199999999999e-02 , -9.4605700000000004e-01 , 3.2077400000000000e-01 -3.4965738731435270e+00 , -1.1256373183184132e+00 , 8.0665176000000010e+00 , -7.7834999999999999e-01 , 4.1472599999999998e-01 , -4.7135400000000000e-01 -3.4362204041873117e+00 , -9.5756055655989547e-01 , 8.0024535999999991e+00 , 2.6108500000000000e-02 , -5.4169199999999995e-01 , 8.4017200000000003e-01 -3.3971134263942746e+00 , -8.6185579015612346e-01 , 8.0369816000000007e+00 , 9.0079500000000001e-01 , -3.5512700000000003e-01 , 2.4990799999999999e-01 -3.3856925117839571e+00 , -8.6377829777478921e-01 , 8.2252423999999991e+00 , 7.0000899999999999e-01 , -5.7146500000000003e-02 , 7.1184400000000003e-01 -3.2846689227117500e+00 , -5.4996195292813299e-01 , 7.9061808000000005e+00 , -4.3755599999999999e-02 , -3.7684299999999998e-01 , 9.2524300000000004e-01 -3.2389344406113958e+00 , -4.2497578993022822e-01 , 7.8790367999999997e+00 , -8.2732399999999998e-02 , -9.9403600000000003e-01 , 7.1048899999999998e-02 -3.1983004565539486e+00 , -3.2130357431037426e-01 , 7.8842575999999998e+00 , 6.1580699999999999e-01 , -7.8757600000000005e-01 , 2.2473099999999999e-02 -3.1910670039601143e+00 , -3.3815657752423345e-01 , 8.1047480000000007e+00 , -5.6851499999999999e-01 , 8.1741399999999997e-01 , -9.2873300000000006e-02 -3.2021367879736538e+00 , -4.2930464382678135e-01 , 8.4821431999999994e+00 , -1.3589300000000001e-01 , 8.2836699999999996e-01 , -5.4345399999999999e-01 -3.2455930439065828e+00 , -6.5336551854678149e-01 , 9.1501456000000001e+00 , 3.8689800000000002e-01 , -9.0322800000000003e-01 , -1.8571499999999999e-01 -3.2152452574790225e+00 , -5.9566777957900641e-01 , 9.2877272000000008e+00 , 6.5671800000000002e-01 , -7.5333600000000001e-01 , -3.4733699999999999e-02 -3.0881025201433756e+00 , -1.5582843886035613e-01 , 8.6082744000000009e+00 , -4.7558800000000001e-01 , -1.3745800000000000e-01 , 8.6886200000000002e-01 -3.0294265390178001e+00 , 2.1682442573067506e-02 , 8.4543648000000005e+00 , -6.8048699999999995e-01 , 1.8410099999999999e-01 , 7.0925700000000003e-01 -3.0014127383054410e+00 , 7.6383335524172313e-02 , 8.5723216000000004e+00 , 5.3543799999999997e-01 , -1.1127300000000000e-01 , -8.3721199999999996e-01 -2.9558829138728884e+00 , 2.0071062410201623e-01 , 8.5262080000000005e+00 , -4.5648499999999997e-01 , -2.4609499999999999e-02 , 8.8939100000000004e-01 -2.9142794665912515e+00 , 3.1207068211990019e-01 , 8.5061047999999992e+00 , -1.5859200000000001e-01 , 4.5377299999999998e-01 , -8.7689099999999998e-01 -2.8995064931859162e+00 , 2.9955751513964879e-01 , 8.8150368000000014e+00 , -8.9060799999999996e-01 , -3.5156799999999999e-01 , 2.8847400000000001e-01 -2.8460457785934379e+00 , 4.7081424340987343e-01 , 8.6259440000000005e+00 , -7.2890800000000000e-01 , -3.4515699999999999e-01 , -5.9123599999999998e-01 -2.8057898080770118e+00 , 5.7422351740045441e-01 , 8.6194024000000002e+00 , 6.3427100000000003e-01 , 2.7485599999999999e-02 , 7.7262200000000003e-01 -2.8163676585367678e+00 , 4.1039290715601484e-01 , 9.4634040000000006e+00 , 8.9952299999999996e-01 , -3.8467099999999999e-01 , -2.0709200000000000e-01 -2.7755928773061518e+00 , 5.0234268234179447e-01 , 9.5368800000000000e+00 , -8.4268399999999999e-01 , 6.9468699999999994e-02 , -5.3390800000000005e-01 -2.7231840983162443e+00 , 6.7066102589111498e-01 , 9.3386871999999990e+00 , -7.9334600000000000e-01 , -5.4761000000000004e-01 , 2.6594099999999998e-01 -2.6892351618543882e+00 , 7.2609010462939505e-01 , 9.5485800000000012e+00 , -8.8428300000000004e-01 , -1.8460499999999999e-01 , -4.2891200000000002e-01 -2.6443075515432595e+00 , 8.4786536400835488e-01 , 9.5057320000000018e+00 , 1.7160800000000001e-01 , -6.6907000000000005e-01 , 7.2311499999999995e-01 -2.6061721723341602e+00 , 9.1822514495793306e-01 , 9.6834056000000004e+00 , 3.1151699999999999e-01 , 3.1757400000000002e-01 , -8.9560200000000001e-01 -2.5617662345164920e+00 , 1.0401804332544780e+00 , 9.6363039999999991e+00 , -1.2531500000000001e-01 , 6.0069999999999998e-02 , 9.9029699999999998e-01 -2.5249721334949591e+00 , 1.0459215744178056e+00 , 1.0189230400000000e+01 , 1.2847900000000001e-01 , 8.6330499999999999e-01 , 4.8805399999999999e-01 -2.4779745648633309e+00 , 1.2144316616148734e+00 , 9.9035527999999999e+00 , 4.4262000000000001e-01 , -2.9706500000000000e-02 , 8.9621700000000004e-01 -2.4343726786633919e+00 , 1.3229035193956178e+00 , 9.9425008000000012e+00 , -3.3467700000000000e-01 , 1.6371900000000000e-01 , -9.2800199999999999e-01 -2.3871999711292546e+00 , 1.3882510694605033e+00 , 1.0288394400000001e+01 , 9.6792599999999995e-01 , 1.2514800000000001e-01 , 2.1784500000000001e-01 -2.3423493948235747e+00 , 1.5222674811913133e+00 , 1.0169262400000001e+01 , 6.4923399999999998e-01 , 7.4112299999999998e-01 , -1.7097499999999999e-01 -2.3081248232813829e+00 , 1.6918302344085592e+00 , 9.6754600000000011e+00 , 6.0867599999999999e-01 , -4.1350900000000002e-01 , -6.7714399999999997e-01 -2.2767931369393284e+00 , 1.8356681307607177e+00 , 9.2917415999999999e+00 , 7.9573700000000003e-01 , 3.5731499999999999e-01 , 4.8900800000000000e-01 -2.2359832613115671e+00 , 1.9332614284832901e+00 , 9.3405383999999998e+00 , -9.5784400000000003e-01 , 5.3810799999999999e-02 , -2.8220499999999998e-01 -2.1990061829818566e+00 , 2.0401993163401873e+00 , 9.2731463999999999e+00 , 9.8437900000000000e-01 , 1.7602100000000001e-01 , -3.7719199999999998e-03 -2.1436105103751504e+00 , 2.1260469265909192e+00 , 9.6294503999999996e+00 , -1.7781300000000000e-01 , -8.2318999999999998e-01 , -5.3920400000000002e-01 -2.0678531468321175e+00 , 2.3411858202633677e+00 , 9.5269063999999997e+00 , -8.8467300000000004e-01 , 2.2613900000000001e-01 , -4.0769499999999997e-01 -2.0364171810028151e+00 , 2.4454969354643152e+00 , 9.3791536000000004e+00 , -2.5747300000000001e-02 , 2.3652000000000001e-01 , 9.7128499999999995e-01 -1.9864068960731105e+00 , 2.5514356262712612e+00 , 9.5306504000000007e+00 , -1.7299000000000000e-01 , -9.6962400000000004e-01 , -1.7292900000000000e-01 -1.9632467692539697e+00 , 2.6475237852115896e+00 , 9.2964112000000014e+00 , -4.3190399999999997e-03 , 1.8593399999999999e-01 , 9.8255300000000001e-01 -1.9403689032624436e+00 , 2.7389215654223484e+00 , 9.1021912000000000e+00 , 7.3397500000000004e-01 , -6.5685600000000000e-01 , 1.7268600000000001e-01 -1.8890424121792964e+00 , 2.8479700349659804e+00 , 9.2477599999999995e+00 , -9.3715400000000004e-01 , 3.4878999999999999e-01 , 9.4042499999999994e-03 -1.7698939043233244e+00 , 3.0943805249665317e+00 , 9.6443016000000004e+00 , -1.1323500000000000e-01 , 1.8150200000000000e-01 , 9.7684899999999997e-01 -1.7598000815291179e+00 , 3.1673578803803362e+00 , 9.3508448000000008e+00 , -1.0635100000000000e-01 , 3.9565400000000001e-01 , 9.1222099999999995e-01 -1.7257777056101755e+00 , 3.2642312964223894e+00 , 9.2920847999999996e+00 , -2.8948499999999999e-02 , 9.6782500000000005e-01 , -2.4995400000000001e-01 -3.2108269947913990e+00 , 5.8154921036253460e-01 , 1.3742902400000001e+00 , -5.2206099999999998e-02 , 2.4301900000000001e-01 , 9.6861600000000003e-01 -3.2280117061358782e+00 , 5.3066988642198942e-01 , 1.3889615200000001e+00 , 1.0825700000000001e-02 , 2.4767900000000001e-01 , 9.6878200000000003e-01 -3.2477828560590769e+00 , 4.7227132435513708e-01 , 1.3984380000000001e+00 , -9.9621099999999997e-03 , 2.0542900000000000e-01 , 9.7862099999999996e-01 -3.2673335455089241e+00 , 4.1315954672669797e-01 , 1.4096367200000000e+00 , -2.6697400000000000e-02 , 2.8178399999999998e-01 , 9.5910700000000004e-01 -3.2839976036291834e+00 , 3.6210040048467196e-01 , 1.4285605600000000e+00 , -8.8749499999999995e-02 , 1.8449299999999999e-01 , 9.7881899999999999e-01 -3.3069404211761784e+00 , 2.9584493656056265e-01 , 1.4366122400000001e+00 , -5.6063500000000002e-02 , 1.4458599999999999e-01 , 9.8790299999999998e-01 -3.3306157756638108e+00 , 2.2790217157588333e-01 , 1.4470216000000000e+00 , 8.7755899999999998e-02 , -1.4948300000000000e-01 , -9.8486200000000002e-01 -3.3530418320018964e+00 , 1.6036407580616707e-01 , 1.4591272000000000e+00 , 8.7020000000000000e-02 , -2.1640799999999999e-01 , -9.7241699999999998e-01 -3.3762879304954585e+00 , 9.3172606718691542e-02 , 1.4731786400000000e+00 , -8.1923499999999996e-02 , 2.3295600000000000e-01 , 9.6903099999999998e-01 -3.3955946085545969e+00 , 3.2992659229787780e-02 , 1.4948324799999999e+00 , -7.2394100000000003e-02 , 2.0860100000000001e-01 , 9.7531800000000002e-01 -3.4219906468434496e+00 , -4.3110657038583966e-02 , 1.5074622400000000e+00 , -6.4125500000000002e-02 , 1.5285699999999999e-01 , 9.8616599999999999e-01 -3.4516943934448925e+00 , -1.2840157342174185e-01 , 1.5173557600000001e+00 , -1.1430400000000000e-01 , 2.3099700000000001e-01 , 9.6621699999999999e-01 -3.4702558531069378e+00 , -1.8946477931351202e-01 , 1.5449843999999999e+00 , -1.2931400000000001e-01 , 2.4593799999999999e-01 , 9.6062099999999995e-01 -3.4968475966208907e+00 , -2.6631367694382080e-01 , 1.5645249600000000e+00 , -1.2175800000000001e-01 , 2.1321799999999999e-01 , 9.6938800000000003e-01 -3.5256524610074629e+00 , -3.5222187825615636e-01 , 1.5817088799999999e+00 , -9.9142300000000003e-02 , 1.9456100000000001e-01 , 9.7586700000000004e-01 -3.5551459978384994e+00 , -4.3863778171605228e-01 , 1.6017538400000000e+00 , -1.1326200000000000e-01 , 1.8632499999999999e-01 , 9.7593799999999997e-01 -3.5877892617806135e+00 , -5.3505856244076799e-01 , 1.6202783199999999e+00 , 1.0198599999999999e-01 , -1.6945399999999999e-01 , -9.8024699999999998e-01 -3.6235888490627932e+00 , -6.3931813241506630e-01 , 1.6374799200000001e+00 , 1.0484700000000000e-01 , -1.9194000000000000e-01 , -9.7579000000000005e-01 -3.6554758953303761e+00 , -7.3553141423586821e-01 , 1.6621788799999999e+00 , 1.0198900000000000e-01 , -2.0124400000000001e-01 , -9.7421700000000000e-01 -3.6904615864605015e+00 , -8.4053960294735619e-01 , 1.6859626400000001e+00 , -1.1316700000000000e-01 , 1.9232600000000000e-01 , 9.7478399999999998e-01 -3.7294642370904088e+00 , -9.5531320307143286e-01 , 1.7096684000000000e+00 , 1.0176200000000001e-01 , -1.9339100000000001e-01 , -9.7582999999999998e-01 -3.7748044057013921e+00 , -1.0890489124684652e+00 , 1.7301283199999999e+00 , 9.7946400000000003e-02 , -1.7997400000000000e-01 , -9.7878299999999996e-01 -3.8172891674089069e+00 , -1.2126245792250550e+00 , 1.7583081599999999e+00 , 1.1046300000000001e-01 , -1.8063599999999999e-01 , -9.7732699999999995e-01 -3.8625935262490838e+00 , -1.3467071163895965e+00 , 1.7876007999999999e+00 , -1.0762400000000000e-01 , 1.6792199999999999e-01 , 9.7990800000000000e-01 -3.9173833595722618e+00 , -1.5086852350894326e+00 , 1.8122280000000000e+00 , 1.1678300000000000e-01 , -1.8192800000000001e-01 , -9.7635200000000000e-01 -3.9658776886991278e+00 , -1.6521702464799439e+00 , 1.8482234399999999e+00 , 1.0376199999999999e-01 , -2.0893999999999999e-01 , -9.7240800000000005e-01 -4.0170584193933720e+00 , -1.8059238402564906e+00 , 1.8865474400000000e+00 , 9.2689199999999999e-02 , -1.8462600000000001e-01 , -9.7842799999999996e-01 -4.0860608770535087e+00 , -2.0065013646390115e+00 , 1.9176170239999999e+00 , -1.0359500000000001e-01 , 1.7432100000000000e-01 , 9.7922399999999998e-01 -4.1477090279910307e+00 , -2.1884926774142768e+00 , 1.9603341919999999e+00 , -1.0965500000000000e-01 , 1.8461500000000000e-01 , 9.7667499999999996e-01 -4.2150583414325720e+00 , -2.3894477568160015e+00 , 2.0049698272000001e+00 , -1.0553800000000001e-01 , 1.9076099999999999e-01 , 9.7594700000000001e-01 -4.2900521798702371e+00 , -2.6092167288161123e+00 , 2.0527867600000000e+00 , -9.5093200000000003e-02 , 2.0521400000000001e-01 , 9.7408700000000004e-01 -4.3704229537647379e+00 , -2.8495432509731122e+00 , 2.1050566399999999e+00 , -7.7532400000000001e-02 , 2.0275000000000001e-01 , 9.7615600000000002e-01 -4.4581965173444864e+00 , -3.1082763723704927e+00 , 2.1624313599999998e+00 , -7.6257099999999994e-02 , 2.0055100000000001e-01 , 9.7671100000000000e-01 -4.5511536203892007e+00 , -3.3861418569228823e+00 , 2.2260772800000002e+00 , -5.4118399999999997e-02 , 1.9111600000000001e-01 , 9.8007400000000000e-01 -4.6761888839878232e+00 , -3.7505890648277083e+00 , 2.2885084800000000e+00 , 5.6250199999999997e-03 , 2.0937600000000001e-01 , 9.7781899999999999e-01 -4.8130012764195271e+00 , -4.1551268610501051e+00 , 2.3599689599999998e+00 , 3.3512599999999997e-02 , 2.5050099999999997e-01 , 9.6753599999999995e-01 -4.9008988594392218e+00 , -4.4215388088772549e+00 , 2.4582832799999998e+00 , 6.2753799999999998e-02 , 2.6407999999999998e-01 , 9.6245700000000001e-01 -4.9733276309253309e+00 , -4.6486509556140883e+00 , 2.5692096800000002e+00 , 4.1380199999999999e-02 , 2.7609000000000000e-01 , 9.6024100000000001e-01 -5.1218875077174086e+00 , -5.0889452360753298e+00 , 2.6764877600000001e+00 , 5.0542600000000000e-02 , 2.4080599999999999e-01 , 9.6925600000000001e-01 -5.2886135417060203e+00 , -5.5877087501603402e+00 , 2.7978744799999999e+00 , 2.4329699999999999e-02 , 2.6459800000000000e-01 , 9.6405200000000002e-01 -5.4822655262639675e+00 , -6.1628183422681122e+00 , 2.9360665600000000e+00 , 3.4344899999999998e-02 , 2.0795900000000000e-01 , 9.7753400000000001e-01 -5.7768925173131791e+00 , -7.0299580571291536e+00 , 3.0957024000000004e+00 , 9.5851400000000007e-03 , 1.6676400000000000e-01 , 9.8594999999999999e-01 -6.1587259604350546e+00 , -8.1503111333440099e+00 , 3.2923768000000000e+00 , -7.7044499999999998e-03 , 1.9649600000000000e-01 , 9.8047399999999996e-01 -6.5474659776858495e+00 , -9.2974589969064425e+00 , 3.5316288000000000e+00 , -1.8505700000000000e-02 , 2.0173400000000000e-01 , 9.7926599999999997e-01 -6.9956045882714024e+00 , -1.0626650943234155e+01 , 3.8235880000000000e+00 , -1.9412599999999999e-02 , 2.1307000000000001e-01 , 9.7684400000000005e-01 -7.5272303843866109e+00 , -1.2204737875102710e+01 , 4.1836672000000004e+00 , -6.9985100000000003e-03 , 2.2549200000000000e-01 , 9.7421999999999997e-01 -8.1175748742723712e+00 , -1.3962247715964626e+01 , 4.6195832000000001e+00 , 4.2086800000000001e-02 , 2.4605700000000000e-01 , 9.6834100000000001e-01 -8.8817523959017812e+00 , -1.6305824586250797e+01 , 5.5357920000000007e+00 , -6.6014899999999999e-01 , 7.1994700000000000e-01 , 2.1419600000000000e-01 -8.8551794113763727e+00 , -1.6299220174781766e+01 , 5.8842856000000001e+00 , 5.8950899999999995e-01 , -8.0684299999999998e-01 , -3.8509399999999999e-02 -8.8501718718548439e+00 , -1.6353929564672175e+01 , 6.2444376000000004e+00 , 2.4690300000000001e-01 , -8.8037299999999996e-01 , -4.0494799999999997e-01 -8.9810802981608013e+00 , -1.6810429684833224e+01 , 6.6836296000000006e+00 , 2.2556300000000001e-01 , -7.8063899999999997e-01 , -5.8285799999999999e-01 -9.1974437080234885e+00 , -1.7601803703384526e+01 , 7.5926728000000008e+00 , 9.3873700000000004e-02 , 7.4211199999999999e-01 , 6.6366999999999998e-01 -9.4419955475269823e+00 , -1.8405291004661215e+01 , 8.1734711999999998e+00 , 1.1067700000000000e-01 , 7.2024999999999995e-01 , 6.8482900000000002e-01 -8.5748460040459413e+00 , -1.5896461465842194e+01 , 7.9133152000000004e+00 , 8.1702799999999998e-01 , -2.3738799999999999e-01 , 5.2546499999999996e-01 -8.2292290601565234e+00 , -1.4935505818195761e+01 , 7.9973783999999997e+00 , -2.9967500000000001e-02 , 5.7224200000000003e-02 , 9.9791200000000002e-01 -7.3965164815760929e+00 , -1.2496416879427743e+01 , 7.5986528000000009e+00 , -1.9297500000000001e-01 , -3.4234599999999998e-01 , 9.1954300000000000e-01 -7.3406326827474428e+00 , -1.2387410404255673e+01 , 7.8591312000000002e+00 , 7.3723000000000005e-01 , -6.0207200000000005e-01 , 3.0659599999999998e-01 -7.3512913394298245e+00 , -1.2482026886346096e+01 , 8.1878960000000003e+00 , -8.9521300000000004e-01 , 3.7719300000000000e-01 , -2.3731700000000000e-01 -7.0497376543470311e+00 , -1.1625788595847272e+01 , 8.1781928000000015e+00 , -5.1130799999999998e-01 , 6.3459500000000002e-01 , -5.7952899999999996e-01 -7.0706390832321429e+00 , -1.1749314415263944e+01 , 8.5129687999999994e+00 , -5.1130799999999998e-01 , 6.3459500000000002e-01 , -5.7952899999999996e-01 -7.0401596455585223e+00 , -1.1718989260640434e+01 , 8.7937791999999995e+00 , -4.7013600000000000e-01 , 8.8012599999999996e-01 , 6.5954899999999997e-02 -6.9905838804743814e+00 , -1.1627804826901324e+01 , 9.0514288000000001e+00 , 3.2492399999999999e-01 , -9.4012600000000002e-01 , -1.0289500000000000e-01 -7.0657409296742149e+00 , -1.1924336313538772e+01 , 9.4823216000000006e+00 , 5.4282600000000003e-01 , -8.3447800000000005e-01 , 9.4798700000000000e-02 -7.0525156490324576e+00 , -1.1948452489101797e+01 , 9.8026935999999996e+00 , 5.2495999999999998e-01 , -7.4653499999999995e-01 , 4.0878199999999998e-01 -6.9057670886324747e+00 , -1.1553632820255915e+01 , 9.9233128000000015e+00 , -1.0664899999999999e-01 , 8.8687000000000005e-01 , -4.4954200000000000e-01 -6.9005763292189775e+00 , -1.1604559202021669e+01 , 1.0259492800000000e+01 , 1.8556099999999999e-02 , -9.7967000000000004e-01 , 1.9975399999999999e-01 -6.8399137043870173e+00 , -1.1481453078776328e+01 , 1.0509768800000000e+01 , 4.7001300000000001e-01 , -8.7690599999999996e-01 , -1.0061800000000000e-01 -6.8901788722706820e+00 , -1.1712039304083623e+01 , 1.0957343200000000e+01 , 5.1327500000000004e-01 , -8.5743800000000003e-01 , -3.6716899999999997e-02 -6.8964017465216427e+00 , -1.1802885893233777e+01 , 1.1340000800000000e+01 , -1.7209300000000000e-01 , 9.8174799999999995e-01 , 8.0957000000000001e-02 -6.9361701535690923e+00 , -1.2004932612979355e+01 , 1.1800648000000001e+01 , 5.8481000000000005e-01 , 7.6633899999999999e-01 , -2.6593499999999998e-01 -6.8819376538733383e+00 , -1.1907370194527422e+01 , 1.2088915200000001e+01 , 4.3579400000000001e-01 , 9.0004200000000001e-01 , 2.7773400000000001e-03 -6.7606105529603866e+00 , -1.1593881261223455e+01 , 1.2237999199999999e+01 , -2.7809200000000001e-01 , 9.6053800000000000e-01 , -5.5748400000000002e-03 -6.7497908859981983e+00 , -1.1637141114128745e+01 , 1.2621624000000001e+01 , 5.5507899999999999e-01 , -6.4947999999999995e-01 , 5.1967600000000003e-01 -6.9799673832795239e+00 , -1.2473466939182176e+01 , 1.3573848000000000e+01 , 9.7649500000000000e-02 , 9.7913899999999998e-01 , 1.7818899999999999e-01 -6.9483866929912388e+00 , -1.2458857844536873e+01 , 1.3956256000000000e+01 , 3.4749500000000001e-03 , -9.8643999999999998e-01 , 1.6408800000000001e-01 -6.9235876237874061e+00 , -1.2467705013371223e+01 , 1.4365183999999999e+01 , 1.5662400000000001e-01 , -9.4929200000000002e-01 , 2.7260699999999999e-01 -6.8074330520319322e+00 , -1.2174602834952601e+01 , 1.4546248000000002e+01 , 9.8040199999999994e-02 , -8.8635900000000001e-01 , 4.5250099999999999e-01 -6.8129073298271727e+00 , -1.2287354796291021e+01 , 1.5052519999999999e+01 , -1.4640600000000001e-01 , 9.8532100000000000e-01 , -8.7797299999999995e-02 -6.6551845264386769e+00 , -1.1852950312120710e+01 , 1.5114296000000000e+01 , 7.4468900000000005e-02 , 9.8643400000000003e-01 , 1.4629500000000001e-01 -7.3484566532471405e+00 , -1.4318607385980783e+01 , 1.7696823999999999e+01 , 4.2988999999999999e-01 , 6.9558900000000001e-01 , 5.7562999999999998e-01 -3.4851518771140908e+00 , -1.2986496464002499e+00 , 7.0577800000000002e+00 , -5.3490000000000004e-01 , 6.1270100000000005e-01 , -5.8179000000000003e-01 -6.3028540295838260e+00 , -1.1654307954169909e+01 , 1.9245280000000001e+01 , 6.4360600000000001e-01 , -9.2402899999999996e-02 , -7.5975800000000004e-01 -3.7972242776434775e+00 , -2.5587525954748696e+00 , 8.9862415999999996e+00 , -6.9154899999999997e-01 , -4.9962000000000001e-01 , -5.2166999999999997e-01 -3.4189082920904146e+00 , -1.2011662371564373e+00 , 7.5222128000000001e+00 , -4.6073100000000000e-01 , 8.8678500000000005e-01 , -3.6603600000000000e-02 -3.4025816841479122e+00 , -1.1798252342094955e+00 , 7.6510064000000000e+00 , 4.7193400000000002e-01 , -8.7998399999999999e-01 , 5.3901900000000003e-02 -3.3973174597908526e+00 , -1.2041103598002461e+00 , 7.8455800000000000e+00 , 3.1361499999999998e-01 , -9.4603000000000004e-01 , 8.1691200000000005e-02 -3.3657661095895088e+00 , -1.1271526141989709e+00 , 7.9098832000000003e+00 , -5.9110500000000003e-02 , 9.7867800000000005e-01 , -1.9671200000000000e-01 -3.3651946451909982e+00 , -1.1724311018578102e+00 , 8.1487815999999995e+00 , 2.3961600000000000e-02 , -9.3653200000000003e-01 , 3.4976400000000002e-01 -3.3376621024986770e+00 , -1.1133880434814190e+00 , 8.2462295999999995e+00 , 5.2538600000000002e-01 , -6.2856000000000001e-01 , 5.7348200000000005e-01 -3.2204936579191807e+00 , -6.9491461239220031e-01 , 7.8001632000000001e+00 , -1.6764599999999999e-01 , 4.5284099999999999e-01 , 8.7568800000000002e-01 -3.1640020812355800e+00 , -5.1308772400138158e-01 , 7.6892472000000005e+00 , -5.5448399999999998e-01 , 3.9956000000000003e-01 , 7.2999899999999995e-01 -3.1225217969364558e+00 , -3.8949944702544226e-01 , 7.6613959999999999e+00 , -4.1727700000000001e-01 , 8.7982300000000002e-01 , 2.2757500000000000e-01 -3.1012816067350006e+00 , -3.5126344706995072e-01 , 7.7728527999999999e+00 , -2.9022599999999998e-01 , 9.5617799999999997e-01 , -3.8632300000000001e-02 -3.0968666215776031e+00 , -3.8641240829926593e-01 , 8.0190520000000003e+00 , 4.1197499999999998e-01 , -9.0323100000000001e-01 , 1.2020699999999999e-01 -3.1013064954823282e+00 , -4.6262634611873699e-01 , 8.3584768000000000e+00 , -2.7494600000000002e-01 , -8.9062799999999998e-01 , -3.6219600000000002e-01 -3.1468903672435369e+00 , -7.3535545324828444e-01 , 9.0963256000000001e+00 , -4.3983499999999998e-01 , 8.4169799999999995e-01 , -3.1319399999999997e-01 -3.0211431250138299e+00 , -2.3341049291663296e-01 , 8.3459447999999998e+00 , -6.4895999999999998e-01 , -1.7619899999999999e-01 , 7.4013899999999999e-01 -3.1199939405121229e+00 , -7.7528447030109104e-01 , 9.6987664000000002e+00 , 4.8797400000000002e-01 , -8.6344100000000001e-01 , -1.2787000000000001e-01 -2.9536373995471408e+00 , -6.0501543128786306e-02 , 8.4361128000000001e+00 , -7.1272700000000000e-01 , -1.3069500000000001e-01 , 6.8915800000000005e-01 -2.8855080131595705e+00 , 2.0307318356773796e-01 , 8.0802040000000002e+00 , -9.7538000000000002e-01 , -8.4861599999999995e-02 , 2.0354900000000001e-01 -2.8540811767439296e+00 , 2.8430077895788952e-01 , 8.1182991999999992e+00 , -8.9361400000000002e-01 , -4.2010799999999998e-01 , 1.5799800000000000e-01 -2.8366371156353463e+00 , 2.8635696585250670e-01 , 8.3566672000000004e+00 , -4.4751600000000002e-01 , -8.6116300000000001e-01 , 2.4109800000000001e-01 -2.8674247033490077e+00 , 5.7578139480733981e-03 , 9.3526647999999994e+00 , 7.6125699999999996e-01 , 1.9247500000000001e-01 , -6.1922600000000005e-01 -2.7820619397888433e+00 , 3.8901773259161176e-01 , 8.6226783999999999e+00 , 9.7861500000000001e-01 , -1.6707500000000000e-01 , -1.1999500000000000e-01 -2.7420660401782064e+00 , 5.1708784969149368e-01 , 8.5488591999999990e+00 , 2.7138099999999998e-01 , -4.6381099999999997e-01 , 8.4334500000000001e-01 -2.7420792697567373e+00 , 3.7143675320893421e-01 , 9.3015904000000003e+00 , 3.3731800000000001e-01 , -9.0153300000000003e-01 , -2.7102500000000002e-01 -2.7319250425345123e+00 , 2.5866835968773039e-01 , 1.0030942400000001e+01 , 7.8739599999999998e-01 , 4.8368699999999998e-01 , -3.8217000000000001e-01 -2.6711651964733063e+00 , 5.2717509993740896e-01 , 9.5377223999999998e+00 , -5.7597900000000002e-01 , -5.5699100000000001e-02 , -8.1556499999999998e-01 -2.6274176594466838e+00 , 6.7160111067513806e-01 , 9.4283351999999994e+00 , -3.7546000000000002e-01 , -2.3567700000000000e-01 , -8.9637400000000000e-01 -2.5875910856444135e+00 , 7.9339169504315032e-01 , 9.3866207999999993e+00 , 1.2619300000000000e-01 , -8.6679799999999996e-01 , 4.8242800000000002e-01 -2.5529990787216517e+00 , 8.4395767724709070e-01 , 9.6354928000000015e+00 , -4.1966499999999997e-02 , 4.5763999999999999e-01 , 8.8814599999999999e-01 -2.5118848584574520e+00 , 9.7030487464535664e-01 , 9.5792184000000002e+00 , -1.5083800000000000e-01 , 1.3106599999999999e-01 , 9.7983100000000001e-01 -2.4731114749825105e+00 , 1.0752838221766534e+00 , 9.6124048000000002e+00 , -1.5083800000000000e-01 , 1.3106499999999999e-01 , 9.7983200000000004e-01 -2.4325248501966805e+00 , 1.1118265257279321e+00 , 1.0011744000000000e+01 , -6.6796500000000003e-01 , 5.2854299999999999e-01 , 5.2389300000000005e-01 -2.3915667062520081e+00 , 1.2434814110890016e+00 , 9.9291575999999999e+00 , 3.5623400000000000e-01 , -4.0257399999999999e-01 , -8.4322699999999995e-01 -2.3370750568506633e+00 , 1.2149274534771368e+00 , 1.0872031999999999e+01 , -1.5089700000000000e-01 , 9.8379200000000000e-01 , -9.6870899999999996e-02 -2.2945397441072259e+00 , 1.3698944948149192e+00 , 1.0694004800000000e+01 , -8.4615300000000004e-01 , 5.0493600000000005e-01 , 1.7048400000000000e-01 -2.2597979456125938e+00 , 1.5417208930922550e+00 , 1.0316724000000001e+01 , -6.9042700000000001e-01 , -6.7780099999999999e-01 , -2.5277699999999997e-01 -2.2448125541796924e+00 , 1.7477365933287241e+00 , 9.4809176000000015e+00 , -9.3033999999999994e-01 , -3.1655999999999997e-02 , -3.6532999999999999e-01 -2.2069367740014938e+00 , 1.8530407496300059e+00 , 9.4895496000000001e+00 , -9.7263999999999995e-01 , -5.0567800000000003e-03 , -2.3226100000000000e-01 -2.1607916901888613e+00 , 1.9449110665198932e+00 , 9.6932647999999997e+00 , 4.7309899999999999e-01 , 8.8007700000000000e-01 , 4.0534199999999999e-02 -2.1177148936283166e+00 , 2.0504575467216473e+00 , 9.7705055999999999e+00 , -8.9515400000000001e-01 , 4.3832800000000000e-01 , -8.1039399999999998e-02 -2.1040166479672533e+00 , 2.1773123191548622e+00 , 9.3167952000000014e+00 , -8.6621999999999999e-01 , -4.9919000000000002e-01 , 2.1736300000000000e-02 -2.0508610379952548e+00 , 2.2744934828556489e+00 , 9.5875383999999997e+00 , -9.2877600000000005e-01 , 1.3126599999999999e-01 , -3.4661900000000001e-01 -2.0038934305716047e+00 , 2.3819668517527983e+00 , 9.7314848000000005e+00 , -9.1179299999999996e-01 , -2.2147300000000000e-01 , -3.4580899999999998e-01 -1.9713109252007743e+00 , 2.4902604492103610e+00 , 9.6454143999999999e+00 , 7.8629700000000002e-01 , 6.0160100000000005e-01 , 1.4076200000000000e-01 -1.9569099662108347e+00 , 2.5896214654069931e+00 , 9.3396855999999993e+00 , -1.1928100000000000e-01 , 5.5749000000000004e-01 , 8.2157000000000002e-01 -1.9221470843137967e+00 , 2.6927573174015111e+00 , 9.3224112000000012e+00 , 1.2580300000000000e-01 , -1.9294500000000001e-01 , -9.7311099999999995e-01 -1.9049661602462535e+00 , 2.7828268282989224e+00 , 9.1070168000000002e+00 , 8.5042600000000002e-01 , -5.2516399999999996e-01 , -3.1281000000000003e-02 -1.7784665399436879e+00 , 3.0359191086570845e+00 , 9.6510824000000000e+00 , -4.7337299999999999e-01 , 5.2044599999999996e-01 , 7.1067100000000005e-01 -1.7414774170783056e+00 , 3.1448506834372338e+00 , 9.6357631999999995e+00 , -5.3116600000000003e-01 , 3.9752400000000000e-02 , 8.4633499999999995e-01 -1.7368227837418697e+00 , 3.2154606487952848e+00 , 9.3316879999999998e+00 , -1.1901000000000000e-01 , 9.3830499999999994e-01 , -3.2468399999999997e-01 -1.7083068075188133e+00 , 3.3120283231009058e+00 , 9.2620912000000004e+00 , 9.7889100000000007e-02 , -9.6734399999999998e-01 , 2.3380000000000001e-01 -3.1601898258253791e+00 , 5.8846460537895573e-01 , 1.3609064800000001e+00 , -1.0705600000000000e-01 , 3.2225300000000001e-01 , 9.4058100000000000e-01 -3.1725700057528892e+00 , 5.4432593264310580e-01 , 1.3816378400000000e+00 , -6.2271199999999999e-02 , 2.0683099999999999e-01 , 9.7639299999999996e-01 -3.1876188204435407e+00 , 4.9360788635931385e-01 , 1.3966647999999999e+00 , -5.1851599999999998e-02 , 1.9112999999999999e-01 , 9.8019400000000001e-01 -3.2062562446534923e+00 , 4.3431098070166696e-01 , 1.4067267999999999e+00 , -5.6939900000000002e-02 , 1.9237899999999999e-01 , 9.7966699999999995e-01 -3.2236689712884714e+00 , 3.7537067342239050e-01 , 1.4182822399999999e+00 , -7.6438400000000004e-02 , 1.8745000000000001e-01 , 9.7929600000000006e-01 -3.2446006656636648e+00 , 3.0796472796959673e-01 , 1.4254780000000000e+00 , -1.0171800000000000e-01 , 1.6545599999999999e-01 , 9.8095800000000000e-01 -3.2663183878898221e+00 , 2.3986919633139059e-01 , 1.4347256799999999e+00 , -3.8861199999999999e-02 , 1.4370700000000000e-01 , 9.8885699999999999e-01 -3.2867878312356726e+00 , 1.7217854052425130e-01 , 1.4456685600000001e+00 , -5.0866399999999999e-02 , 1.6196700000000000e-01 , 9.8548400000000003e-01 -3.3053717949232757e+00 , 1.1148068823987267e-01 , 1.4645664000000000e+00 , 8.7574100000000002e-02 , -2.2115899999999999e-01 , -9.7129799999999999e-01 -3.3227208407209385e+00 , 5.1147974097442539e-02 , 1.4850575200000000e+00 , -6.3768699999999998e-02 , 2.2133100000000000e-01 , 9.7311199999999998e-01 -3.3471405767275337e+00 , -2.6162434299783044e-02 , 1.4965287199999999e+00 , -8.0043799999999998e-02 , 2.0908700000000000e-01 , 9.7461600000000004e-01 -3.3702782598560788e+00 , -1.0302175557428761e-01 , 1.5099998399999999e+00 , -5.8205100000000003e-02 , 1.7668400000000001e-01 , 9.8254500000000000e-01 -3.3976981638554964e+00 , -1.9008084722284702e-01 , 1.5211652800000000e+00 , -9.8550399999999996e-02 , 2.4222199999999999e-01 , 9.6520300000000003e-01 -3.4151209865197436e+00 , -2.5093979377738895e-01 , 1.5495791200000000e+00 , 9.3986799999999995e-02 , -2.4307300000000001e-01 , -9.6544399999999997e-01 -3.4419618627226245e+00 , -3.3808442559918284e-01 , 1.5655025600000001e+00 , -8.2870500000000000e-02 , 2.0473100000000000e-01 , 9.7530399999999995e-01 -3.4685138133814046e+00 , -4.2471460323296206e-01 , 1.5838554400000000e+00 , -1.0705600000000000e-01 , 1.7124700000000001e-01 , 9.7939399999999999e-01 -3.4982001468675321e+00 , -5.2133154552388783e-01 , 1.6007887199999999e+00 , -9.3118699999999999e-02 , 1.8784000000000001e-01 , 9.7777599999999998e-01 -3.5275205378390178e+00 , -6.1840468289849637e-01 , 1.6206589600000001e+00 , -7.4909000000000003e-02 , 1.8142700000000000e-01 , 9.8054699999999995e-01 -3.5599550008244512e+00 , -7.2432265754531855e-01 , 1.6394122400000000e+00 , -6.8330500000000002e-02 , 1.8740299999999999e-01 , 9.7990400000000000e-01 -3.5954482466817970e+00 , -8.3900117341241387e-01 , 1.6575529599999999e+00 , -1.1509800000000001e-01 , 1.8913600000000000e-01 , 9.7518199999999999e-01 -3.6280527950485149e+00 , -9.4561686520068600e-01 , 1.6834188000000001e+00 , -7.9332100000000003e-02 , 1.9080100000000000e-01 , 9.7841800000000001e-01 -3.6636349769945222e+00 , -1.0619433620961112e+00 , 1.7091806400000000e+00 , -8.4828600000000004e-02 , 1.7457500000000001e-01 , 9.8098300000000005e-01 -3.7021466382624690e+00 , -1.1878949217340184e+00 , 1.7352440800000000e+00 , -8.4237000000000006e-02 , 1.7479100000000000e-01 , 9.8099599999999998e-01 -3.7469387025151848e+00 , -1.3316316777412238e+00 , 1.7586679999999999e+00 , -9.4500200000000006e-02 , 1.7080300000000001e-01 , 9.8076300000000005e-01 -3.7910880553686290e+00 , -1.4764537549578627e+00 , 1.7871556799999999e+00 , -9.4821500000000003e-02 , 1.7671200000000001e-01 , 9.7968500000000003e-01 -3.8346664793343463e+00 , -1.6213385075696682e+00 , 1.8204013600000000e+00 , -9.0068999999999996e-02 , 2.0694299999999999e-01 , 9.7419800000000001e-01 -3.8819635235258056e+00 , -1.7765585011102920e+00 , 1.8558986399999999e+00 , -9.0074899999999999e-02 , 2.0191799999999999e-01 , 9.7525200000000001e-01 -3.9352210886611427e+00 , -1.9500848298515390e+00 , 1.8913896800000001e+00 , -8.4144099999999999e-02 , 1.7637200000000000e-01 , 9.8072000000000004e-01 -3.9942360225178000e+00 , -2.1437944684374761e+00 , 1.9280924239999999e+00 , -7.5180700000000003e-02 , 1.8406900000000001e-01 , 9.8003399999999996e-01 -4.0599719405706001e+00 , -2.3564733760381955e+00 , 1.9669405840000000e+00 , -9.3318799999999993e-02 , 1.8794000000000000e-01 , 9.7773699999999997e-01 -4.1216038496651803e+00 , -2.5596379715528608e+00 , 2.0152062559999999e+00 , 8.9565900000000004e-02 , -2.1667500000000001e-01 , -9.7212699999999996e-01 -4.1855698191096309e+00 , -2.7724846580670546e+00 , 2.0686327200000001e+00 , -8.1042500000000003e-02 , 2.0676900000000001e-01 , 9.7502800000000001e-01 -4.2623575219500953e+00 , -3.0239792442882383e+00 , 2.1226825599999999e+00 , -6.6672300000000004e-02 , 2.0807899999999999e-01 , 9.7583699999999995e-01 -4.3485731340516907e+00 , -3.3047605792112487e+00 , 2.1810026400000000e+00 , -1.6906899999999999e-02 , 2.5522000000000000e-01 , 9.6673500000000001e-01 -4.4596344372740395e+00 , -3.6642940366093519e+00 , 2.2384231200000002e+00 , 2.2887000000000001e-02 , 2.3574400000000001e-01 , 9.7154600000000002e-01 -4.5402040379641093e+00 , -3.9339741760246278e+00 , 2.3190137599999998e+00 , -8.6063100000000003e-02 , -2.5277699999999997e-01 , -9.6368900000000002e-01 -4.5845938666789161e+00 , -4.0959487867544278e+00 , 2.4204532799999998e+00 , 8.2159399999999994e-02 , 2.4968899999999999e-01 , 9.6483399999999997e-01 -4.7059785832237662e+00 , -4.4934268646757713e+00 , 2.5078777600000000e+00 , 6.1450299999999999e-02 , 2.6962900000000001e-01 , 9.6100200000000002e-01 -4.8287220161180358e+00 , -4.8988640597718920e+00 , 2.6087598400000003e+00 , 2.5644400000000001e-02 , 2.5019799999999998e-01 , 9.6785500000000002e-01 -4.9759167906616248e+00 , -5.3827831356468803e+00 , 2.7206097599999999e+00 , 1.6178800000000000e-02 , 2.3497199999999999e-01 , 9.7186799999999995e-01 -5.1340137632520646e+00 , -5.9052510902042270e+00 , 2.8489769599999999e+00 , -3.4988900000000003e-02 , 2.2008900000000001e-01 , 9.7485200000000005e-01 -5.3475578239209920e+00 , -6.6039849924254810e+00 , 2.9944167999999998e+00 , -1.3688499999999999e-02 , 1.7224200000000001e-01 , 9.8495999999999995e-01 -5.6627432282538592e+00 , -7.6274035532891080e+00 , 3.1680136000000001e+00 , -4.8002699999999997e-03 , 1.7446400000000001e-01 , 9.8465199999999997e-01 -5.9999698085233062e+00 , -8.7287738534060146e+00 , 3.3812552000000000e+00 , -1.1424999999999999e-02 , 1.9933000000000001e-01 , 9.7986600000000001e-01 -6.3743708903368494e+00 , -9.9540640681506734e+00 , 3.6403192000000000e+00 , -7.0925500000000004e-03 , 2.1130800000000000e-01 , 9.7739399999999999e-01 -6.8063453278296393e+00 , -1.1373228805556950e+01 , 3.9566559999999997e+00 , -3.7192499999999999e-03 , 2.1881600000000001e-01 , 9.7575900000000004e-01 -7.2763662144797019e+00 , -1.2924541032057357e+01 , 4.3362248000000001e+00 , 6.7728099999999998e-03 , 2.3627100000000001e-01 , 9.7166399999999997e-01 -7.9315060676719522e+00 , -1.5080218872273797e+01 , 4.8336775999999997e+00 , 7.5634099999999996e-02 , 3.3590500000000001e-01 , 9.3885399999999997e-01 -8.6265277177230928e+00 , -1.7383589444167676e+01 , 5.4287656000000002e+00 , -5.4375399999999996e-01 , 8.3801400000000004e-01 , 4.5440500000000002e-02 -8.4132642696945688e+00 , -1.6866213273036514e+01 , 6.0801384000000001e+00 , 5.3388999999999998e-01 , -8.3254200000000000e-01 , -1.4776900000000001e-01 -8.3845400746195757e+00 , -1.6859832703054625e+01 , 6.4376176000000003e+00 , 5.3388999999999998e-01 , -8.3254200000000000e-01 , -1.4776900000000001e-01 -7.3424090404921083e+00 , -1.3844755368861721e+01 , 7.4510664000000002e+00 , 4.0465099999999998e-01 , 2.9055100000000000e-02 , -9.1400999999999999e-01 -7.2621533256148449e+00 , -1.3650173026044859e+01 , 7.7097040000000003e+00 , 5.0462799999999997e-01 , 3.0219099999999999e-01 , -8.0872200000000005e-01 -7.0604877797879722e+00 , -1.3051602220520275e+01 , 7.8389656000000008e+00 , 8.8380700000000001e-01 , -2.0050499999999999e-01 , 4.2270900000000000e-01 -6.9276507807528054e+00 , -1.2680809694264241e+01 , 8.0223176000000009e+00 , -8.4219800000000000e-01 , 3.3088099999999998e-01 , -4.2570100000000000e-01 -7.1837739790452346e+00 , -1.3623933555941200e+01 , 8.6505192000000015e+00 , 5.7605300000000004e-01 , 8.1574999999999998e-01 , 5.2105199999999997e-02 -6.9903500676934476e+00 , -1.3045551827813542e+01 , 8.7606447999999997e+00 , -8.9431899999999998e-01 , 2.8210700000000000e-01 , -3.4728700000000001e-01 -6.8915197586434527e+00 , -1.2786820988121706e+01 , 8.9748951999999989e+00 , -8.7568199999999996e-01 , 3.0440899999999999e-01 , -3.7485600000000002e-01 -6.8088050359026866e+00 , -1.2580003282091303e+01 , 9.2037888000000017e+00 , 2.1898500000000001e-01 , -6.6412000000000004e-01 , 7.1483600000000003e-01 -6.7467249914120826e+00 , -1.2445193461929547e+01 , 9.4587655999999996e+00 , -4.9285900000000001e-03 , -5.5358300000000005e-01 , 8.3277900000000005e-01 -6.6806198277053079e+00 , -1.2295918979285190e+01 , 9.7059943999999998e+00 , -9.9189200000000005e-02 , -6.2400100000000003e-01 , 7.7510299999999999e-01 -6.6503701814305538e+00 , -1.2271595812311865e+01 , 1.0009976000000000e+01 , -3.0246499999999998e-01 , 8.6392599999999997e-01 , -4.0267599999999998e-01 -6.4612693251341504e+00 , -1.1688942069864460e+01 , 1.0042320000000000e+01 , -3.1908100000000000e-01 , 9.0070099999999997e-01 , -2.9483100000000001e-01 -6.5691337312556186e+00 , -1.2150750135614620e+01 , 1.0592573600000001e+01 , 4.6187099999999998e-01 , -8.7482800000000005e-01 , -1.4612000000000000e-01 -6.5256021224698566e+00 , -1.2081791958749774e+01 , 1.0883212000000000e+01 , -3.6152000000000001e-01 , 9.2369800000000002e-01 , 1.2682599999999999e-01 -6.5178726092779966e+00 , -1.2140767153415133e+01 , 1.1247888000000001e+01 , 5.2213799999999999e-01 , 8.2232600000000000e-01 , -2.2616700000000001e-01 -6.3736546261893530e+00 , -1.1711265403913222e+01 , 1.1335768000000000e+01 , 7.0505799999999996e-01 , 6.6530100000000003e-01 , -2.4549499999999999e-01 -6.3164542573780027e+00 , -1.1594036591499181e+01 , 1.1599751200000000e+01 , 5.7620300000000002e-01 , 8.1558500000000000e-01 , -5.3017399999999999e-02 -6.5919391529042324e+00 , -1.2688163893058238e+01 , 1.2631296000000001e+01 , -3.9071899999999998e-01 , -8.7241999999999997e-01 , -2.9363699999999998e-01 -6.4135389112922372e+00 , -1.2134008332951744e+01 , 1.2640136000000000e+01 , 7.3755300000000001e-01 , 4.5810099999999998e-01 , 4.9614500000000000e-01 -6.3494583091793420e+00 , -1.1994616629622570e+01 , 1.2912200000000000e+01 , 7.3188600000000004e-01 , 5.2456300000000000e-01 , 4.3494500000000003e-01 -6.4102389112546723e+00 , -1.2323562403052053e+01 , 1.3516648000000002e+01 , 7.2892199999999996e-01 , 6.8243600000000004e-01 , 5.4349500000000002e-02 -6.4630932722142607e+00 , -1.2628116671330456e+01 , 1.4129624000000000e+01 , -2.1786600000000000e-01 , -9.7236599999999995e-01 , -8.3901500000000004e-02 -6.3641538543749965e+00 , -1.2366648952848445e+01 , 1.4336791999999999e+01 , 4.0379300000000001e-01 , 9.1485000000000005e-01 , -1.0680200000000000e-03 -6.4203416679031919e+00 , -1.2694191195330175e+01 , 1.5004887999999999e+01 , 4.5199400000000001e-01 , -7.9533200000000004e-01 , -4.0391700000000003e-01 -6.5287735507250888e+00 , -1.3232923892006680e+01 , 1.5874744000000002e+01 , 3.3877400000000002e-02 , 7.8116900000000000e-01 , 6.2339999999999995e-01 -6.4631228321466896e+00 , -1.3109343292063565e+01 , 1.6226368000000001e+01 , 1.2872500000000001e-01 , 9.1166800000000003e-01 , 3.9024500000000001e-01 -6.4076777612423328e+00 , -1.3023911580830262e+01 , 1.6617407999999998e+01 , -3.7966000000000000e-01 , -8.9087700000000003e-01 , -2.4939100000000000e-01 -6.6702677689464638e+00 , -1.4194615127749714e+01 , 1.8156607999999999e+01 , 4.6888800000000003e-01 , -4.0486200000000000e-01 , 7.8500300000000001e-01 -6.4973549527084904e+00 , -1.3664284292821161e+01 , 1.8185624000000001e+01 , 5.6449600000000000e-01 , 7.2543000000000002e-01 , -3.9382299999999998e-01 -6.4409959371568268e+00 , -1.3592090021844253e+01 , 1.8642496000000001e+01 , -5.5672200000000005e-01 , -6.1199199999999998e-01 , 5.6171800000000005e-01 -3.4241598793185317e+00 , -1.5377497694776605e+00 , 7.0490856000000006e+00 , -4.6345199999999998e-01 , 5.6885900000000000e-01 , -6.7942000000000002e-01 -3.3863796308258349e+00 , -1.4220598501617387e+00 , 7.0671295999999995e+00 , 3.9129799999999998e-01 , -5.6902900000000001e-01 , 7.2325099999999998e-01 -3.3468097526677720e+00 , -1.3009388146417162e+00 , 7.0748671999999999e+00 , 3.8022400000000001e-01 , -7.5828099999999998e-01 , 5.2956599999999998e-01 -5.8749136717545154e+00 , -1.1924635124282903e+01 , 1.9061304000000000e+01 , 6.4360700000000004e-01 , -9.2403200000000005e-02 , -7.5975800000000004e-01 -3.3153455157192369e+00 , -1.2562542778034942e+00 , 7.3057680000000005e+00 , -4.7971100000000000e-01 , 8.3961100000000000e-01 , -2.5481700000000002e-01 -3.3031995277266253e+00 , -1.2523070309723825e+00 , 7.4492256000000001e+00 , -5.2859800000000001e-01 , 8.3407799999999999e-01 , -1.5779099999999999e-01 -3.2909824698465231e+00 , -1.2449572799967474e+00 , 7.5937856000000004e+00 , 4.6073100000000000e-01 , -8.8678500000000005e-01 , 3.6603700000000003e-02 -3.3371026593982100e+00 , -1.5004188358403359e+00 , 8.0801312000000003e+00 , -2.2068099999999999e-01 , 5.3939400000000004e-01 , 8.1262100000000004e-01 -3.2731381483236399e+00 , -1.2756020546421576e+00 , 7.9596575999999999e+00 , 1.2343899999999999e-01 , 2.7149499999999999e-01 , 9.5449099999999998e-01 -3.2377224940745997e+00 , -1.1711373193012302e+00 , 7.9909928000000008e+00 , -1.4368800000000001e-01 , 9.6401899999999996e-01 , -2.2365199999999999e-01 -3.2094147652747846e+00 , -1.1018627169445616e+00 , 8.0705215999999993e+00 , 6.3201600000000002e-01 , -6.6840200000000005e-01 , 3.9216499999999999e-01 -3.1948201113487933e+00 , -1.0951328783596503e+00 , 8.2431511999999998e+00 , -6.0035499999999997e-01 , 6.9673799999999997e-01 , -3.9259400000000000e-01 -3.1656872605765569e+00 , -1.0207303860376045e+00 , 8.3216296000000014e+00 , -6.0035499999999997e-01 , 6.9673799999999997e-01 , -3.9259400000000000e-01 -3.0228436817427378e+00 , -3.9376669226674110e-01 , 7.5240640000000001e+00 , 4.2865300000000001e-01 , -2.0684100000000000e-01 , -8.7947299999999995e-01 -3.0083331741411388e+00 , -3.8527950644349307e-01 , 7.6790240000000010e+00 , 8.3985000000000004e-02 , 9.9585100000000004e-01 , -3.5045600000000003e-02 -3.0056767048080966e+00 , -4.3975637586421712e-01 , 7.9509112000000002e+00 , 2.3230300000000001e-01 , -9.7243800000000002e-01 , -1.9993700000000000e-02 -2.9934640887239286e+00 , -4.4507588413291277e-01 , 8.1537839999999999e+00 , -4.2509700000000000e-01 , 9.0193999999999996e-01 , -7.6138600000000001e-02 -2.9717654179881583e+00 , -4.1053012941453604e-01 , 8.2942879999999999e+00 , -8.6438599999999999e-01 , 4.3060900000000002e-01 , -2.5963999999999998e-01 -2.9296721880613759e+00 , -2.6264898597356412e-01 , 8.2235055999999993e+00 , -1.1865800000000000e-01 , -8.2590100000000000e-01 , 5.5118699999999998e-01 -2.9132332921597235e+00 , -2.6045271114808166e-01 , 8.4364039999999996e+00 , 1.5410799999999999e-01 , 1.0743200000000000e-01 , 9.8219599999999996e-01 -2.8462076691160867e+00 , 3.7843823938084276e-02 , 8.0422440000000002e+00 , 6.3721899999999998e-01 , -5.0296500000000000e-01 , -5.8393300000000004e-01 -2.7850493991770264e+00 , 3.1797431062742443e-01 , 7.6487704000000001e+00 , 2.3971899999999999e-01 , 9.7057499999999997e-01 , 2.2773900000000000e-02 -2.7749976893817982e+00 , 2.8174639789054567e-01 , 7.9411351999999997e+00 , 6.9020400000000004e-01 , -1.7015300000000000e-01 , -7.0332499999999998e-01 -2.7681082806190385e+00 , 2.1424005115418310e-01 , 8.3319463999999996e+00 , 3.7868299999999999e-01 , 9.2528999999999995e-01 , -2.0904499999999999e-02 -2.7409353410484041e+00 , 2.7813119048646473e-01 , 8.4271479999999990e+00 , 6.7120999999999997e-01 , 4.8486299999999999e-01 , -5.6069999999999998e-01 -2.7441710279341729e+00 , 9.4549817220936472e-02 , 9.1821048000000012e+00 , -4.8592800000000003e-01 , 1.5614600000000001e-01 , 8.5993699999999995e-01 -2.7193727651256197e+00 , 1.0810373898837833e-01 , 9.4654424000000006e+00 , -8.6451199999999995e-01 , -2.1447299999999999e-04 , 5.0261199999999995e-01 -2.6841598875714938e+00 , 1.9736081923045523e-01 , 9.5530728000000007e+00 , -4.5382000000000000e-01 , -1.6531000000000001e-01 , 8.7562600000000002e-01 -2.6353511587700114e+00 , 4.2632159351409915e-01 , 9.2139600000000002e+00 , 7.1764099999999997e-02 , 3.7780599999999998e-01 , 9.2310000000000003e-01 -2.6221539713453503e+00 , 2.5828701288715816e-01 , 1.0132134400000000e+01 , -6.9885600000000003e-01 , -3.5131200000000001e-01 , 6.2304099999999996e-01 -2.5629468938342534e+00 , 6.6673494753082219e-01 , 9.1479719999999993e+00 , 5.8173699999999995e-01 , 5.6767299999999998e-01 , -5.8252000000000004e-01 -2.5311416380568459e+00 , 7.1979712952409547e-01 , 9.3571056000000006e+00 , 1.3524800000000001e-01 , -9.6500200000000003e-01 , 2.2467400000000001e-01 -2.4985734197074532e+00 , 7.0987381781798331e-01 , 9.8385111999999992e+00 , -3.2708000000000001e-02 , -8.6809499999999995e-01 , 4.9531900000000001e-01 -2.4603050540296176e+00 , 8.8376450366868520e-01 , 9.6024519999999995e+00 , 4.5379500000000003e-02 , -4.1645799999999997e-02 , 9.9810100000000002e-01 -2.4239546027722541e+00 , 9.9435360304735831e-01 , 9.6165856000000005e+00 , 4.1386499999999998e-01 , 1.4351400000000000e-02 , 9.1022499999999995e-01 -2.3883089493704523e+00 , 1.1088940479834326e+00 , 9.6082967999999997e+00 , 7.4939100000000003e-01 , -2.8951500000000002e-02 , 6.6149400000000003e-01 -2.3462016924941893e+00 , 1.1518965341488205e+00 , 9.9866696000000008e+00 , 3.6703200000000002e-01 , -8.2070900000000002e-02 , -9.2658099999999999e-01 -2.2926297513733642e+00 , 1.1454874372222603e+00 , 1.0744517600000000e+01 , 3.3193400000000001e-01 , -9.2795700000000003e-01 , 1.6945700000000000e-01 -2.2455644673519997e+00 , 1.2459437671755342e+00 , 1.0948482400000000e+01 , -1.1448800000000001e-01 , 9.6315799999999996e-01 , 2.4335100000000001e-01 -2.2313282428563705e+00 , 1.4984709570645625e+00 , 1.0027468800000001e+01 , -2.7732400000000001e-01 , -7.4562600000000001e-01 , 6.0591600000000001e-01 -2.2128098628489674e+00 , 1.6717395999057107e+00 , 9.5343216000000002e+00 , -4.6059299999999997e-01 , 7.7161599999999997e-01 , 4.3870599999999998e-01 -2.1584332467710676e+00 , 1.7348511430104110e+00 , 9.9993471999999990e+00 , -9.5743100000000003e-01 , -2.8068399999999999e-01 , 6.7392300000000002e-02 -2.1109603420786112e+00 , 1.8334293743043080e+00 , 1.0214980800000001e+01 , -9.4568799999999997e-01 , -1.3123299999999999e-01 , 2.9740899999999998e-01 -2.0889772459838638e+00 , 1.9726875962413093e+00 , 9.9001312000000006e+00 , 8.1450800000000001e-01 , 2.1323300000000001e-01 , 5.3954500000000005e-01 -2.0550069651473906e+00 , 2.0887816143537488e+00 , 9.8524784000000007e+00 , -9.2647299999999999e-01 , -3.0809399999999998e-01 , -2.1616199999999999e-01 -2.0208109121065267e+00 , 2.2022784313470916e+00 , 9.8235039999999998e+00 , -9.0501299999999996e-01 , 1.5837399999999999e-01 , -3.9480300000000002e-01 -1.9731117008158154e+00 , 2.3131169723905947e+00 , 9.9998152000000005e+00 , 1.6967599999999999e-01 , -3.1378899999999998e-01 , 9.3420899999999996e-01 -1.9556510981920356e+00 , 2.4268942976076966e+00 , 9.7386400000000002e+00 , -8.5477499999999995e-01 , -3.6483599999999999e-01 , -3.6912699999999998e-01 -1.9487724447897905e+00 , 2.5306007037129654e+00 , 9.3717696000000004e+00 , -7.0694300000000002e-02 , 3.3764200000000000e-01 , 9.3861600000000001e-01 -1.9212166516289326e+00 , 2.6338509025271089e+00 , 9.3038992000000000e+00 , 2.8379399999999999e-02 , 8.4121399999999999e-02 , 9.9605100000000002e-01 -1.9046076806644852e+00 , 2.7271922212922073e+00 , 9.1101264000000004e+00 , 7.3397500000000004e-01 , -6.5685600000000000e-01 , 1.7268600000000001e-01 -1.4473283057199393e+00 , 3.1395865440163258e+00 , 1.3541815999999999e+01 , 5.2302099999999996e-01 , -7.5303100000000001e-01 , 3.9923999999999998e-01 -1.3637096265730693e+00 , 3.3387292730764528e+00 , 1.3811384000000002e+01 , 7.4490400000000001e-01 , -6.6710800000000003e-01 , 9.2174100000000005e-03 -1.7512582981320570e+00 , 3.0864644062186928e+00 , 9.6326223999999989e+00 , 1.3496000000000001e-03 , 2.6764900000000003e-01 , 9.6351600000000004e-01 -1.7485095203477161e+00 , 3.1623844547535320e+00 , 9.3395399999999995e+00 , 1.4940800000000001e-01 , 3.9594299999999999e-01 , 9.0603900000000004e-01 -1.7219249449807750e+00 , 3.2591526359635048e+00 , 9.2713056000000016e+00 , 7.1456400000000003e-02 , 9.5940099999999995e-01 , -2.7284500000000000e-01 -3.1171707417576702e+00 , 5.6009166289539647e-01 , 1.3743079199999999e+00 , -1.1105400000000000e-01 , 3.2588000000000000e-01 , 9.3886599999999998e-01 -3.1339816631103883e+00 , 5.0041389525471569e-01 , 1.3820954400000001e+00 , -1.1425600000000000e-01 , 2.6844899999999999e-01 , 9.5649399999999996e-01 -3.1506245680082818e+00 , 4.4103102623611967e-01 , 1.3912984000000002e+00 , -9.5352099999999995e-02 , 1.8197800000000000e-01 , 9.7866900000000001e-01 -3.1643140449210128e+00 , 3.8872159956866170e-01 , 1.4086341600000001e+00 , -7.1463899999999997e-02 , 1.6753199999999999e-01 , 9.8327299999999995e-01 -3.1832891263039720e+00 , 3.2116309407844468e-01 , 1.4146692800000000e+00 , -9.8448300000000002e-02 , 2.0559100000000000e-01 , 9.7367400000000004e-01 -3.1966456557373331e+00 , 2.6943347857885169e-01 , 1.4348380000000001e+00 , -4.1243900000000000e-02 , 1.8155800000000000e-01 , 9.8251500000000003e-01 -3.2161709049690561e+00 , 2.0051149579854610e-01 , 1.4447471200000002e+00 , 2.5718999999999999e-02 , -1.7705499999999999e-01 , -9.8386499999999999e-01 -3.2344601894190395e+00 , 1.3196505046870288e-01 , 1.4562515999999999e+00 , -4.2791099999999999e-02 , 1.6156499999999999e-01 , 9.8593399999999998e-01 -3.2561741992555775e+00 , 5.5114259002270183e-02 , 1.4642065600000000e+00 , -8.0841300000000005e-02 , 2.1897900000000001e-01 , 9.7237499999999999e-01 -3.2723505661283698e+00 , -6.0398027459673820e-03 , 1.4855868800000001e+00 , 9.4341900000000006e-02 , -2.2244700000000001e-01 , -9.7036900000000004e-01 -3.2909185309503459e+00 , -7.5474182402585743e-02 , 1.5032939200000000e+00 , -4.9234199999999999e-02 , 1.8431200000000000e-01 , 9.8163400000000001e-01 -3.3128280333277722e+00 , -1.5416358531488106e-01 , 1.5179589600000001e+00 , 3.8572299999999997e-02 , -1.7808499999999999e-01 , -9.8325899999999999e-01 -3.3370338444089227e+00 , -2.4096161479011524e-01 , 1.5297598400000001e+00 , -6.7787600000000003e-02 , 2.1506500000000001e-01 , 9.7424400000000000e-01 -3.3547971693696885e+00 , -3.1117457141284044e-01 , 1.5539471200000001e+00 , -8.7823499999999999e-02 , 2.5989499999999999e-01 , 9.6163500000000002e-01 -3.3793984652125841e+00 , -3.9907031132057824e-01 , 1.5709375999999999e+00 , -9.3680500000000000e-02 , 1.8215200000000001e-01 , 9.7879799999999995e-01 -3.4061214846979508e+00 , -4.9695647310902702e-01 , 1.5861819200000000e+00 , -6.6350500000000007e-02 , 1.9728399999999999e-01 , 9.7809800000000002e-01 -3.4300709979123845e+00 , -5.8480393998873881e-01 , 1.6085388000000000e+00 , -5.9500600000000001e-02 , 2.1561200000000000e-01 , 9.7466500000000000e-01 -3.4560940805119391e+00 , -6.8255608638449150e-01 , 1.6295530400000000e+00 , -4.0811000000000000e-02 , 1.8486900000000001e-01 , 9.8191499999999998e-01 -3.4862664287238534e+00 , -7.8918729097307683e-01 , 1.6495751200000000e+00 , -4.3983500000000002e-02 , 1.8758300000000000e-01 , 9.8126300000000000e-01 -3.5149380894386368e+00 , -8.9717324085224393e-01 , 1.6731196800000001e+00 , -4.4713799999999998e-02 , 1.9032399999999999e-01 , 9.8070299999999999e-01 -3.5466418662897174e+00 , -1.0138614684226819e+00 , 1.6962544799999999e+00 , -5.4780500000000003e-02 , 2.0339299999999999e-01 , 9.7756299999999996e-01 -3.5812863896695046e+00 , -1.1401936978076943e+00 , 1.7195900000000000e+00 , -4.9041899999999999e-02 , 1.7769599999999999e-01 , 9.8286300000000004e-01 -3.6221906350973549e+00 , -1.2853764681941584e+00 , 1.7402880800000000e+00 , -6.8214399999999994e-02 , 1.6720499999999999e-01 , 9.8355999999999999e-01 -3.6591054799791616e+00 , -1.4223693577656631e+00 , 1.7691917600000000e+00 , -6.1308700000000001e-02 , 1.7748600000000000e-01 , 9.8221199999999997e-01 -3.7021591378197574e+00 , -1.5779932327726889e+00 , 1.7964699200000001e+00 , -4.4726799999999997e-02 , 1.8991000000000000e-01 , 9.8078200000000004e-01 -3.7445958615439912e+00 , -1.7336360512764757e+00 , 1.8288087200000001e+00 , -5.7636000000000000e-02 , 2.0501700000000000e-01 , 9.7706000000000004e-01 -3.7863508930347720e+00 , -1.8902765890800897e+00 , 1.8666179199999999e+00 , -5.8695999999999998e-02 , 1.9162000000000001e-01 , 9.7971299999999995e-01 -3.8405895284628961e+00 , -2.0845618049025418e+00 , 1.8994557120000000e+00 , -3.5839799999999998e-02 , 1.7956000000000000e-01 , 9.8309400000000002e-01 -3.8939999427244762e+00 , -2.2795773202384035e+00 , 1.9389765440000000e+00 , -4.1512899999999998e-02 , 1.8573999999999999e-01 , 9.8172199999999998e-01 -3.9497882542095439e+00 , -2.4854439195621882e+00 , 1.9831552240000001e+00 , -5.7494499999999997e-02 , 1.9544500000000001e-01 , 9.7902800000000001e-01 -4.0079661278707306e+00 , -2.6999838758535173e+00 , 2.0321885200000001e+00 , -7.5740900000000000e-02 , 2.1785599999999999e-01 , 9.7303700000000004e-01 -4.0716072654952580e+00 , -2.9341619031081887e+00 , 2.0850652400000000e+00 , -4.2553800000000003e-02 , 2.1150700000000000e-01 , 9.7645000000000004e-01 -4.1458561759996275e+00 , -3.2077868023762814e+00 , 2.1394296800000001e+00 , 3.1482900000000001e-02 , 2.3844299999999999e-01 , 9.7064600000000001e-01 -4.2325567174407270e+00 , -3.5204848051256112e+00 , 2.1975573599999998e+00 , 6.8886100000000006e-02 , 2.5994299999999998e-01 , 9.6316400000000002e-01 -4.2576673967570313e+00 , -3.6351987242473713e+00 , 2.2923086399999999e+00 , 8.5789000000000004e-02 , 2.3247499999999999e-01 , 9.6881200000000001e-01 -4.3421247116604427e+00 , -3.9472478530331223e+00 , 2.3689597600000001e+00 , 7.3677400000000004e-02 , 2.7501599999999998e-01 , 9.5861300000000005e-01 -4.4364929203656081e+00 , -4.2986092185912881e+00 , 2.4528690399999999e+00 , 6.1230199999999999e-02 , 2.5221199999999999e-01 , 9.6573299999999995e-01 -4.5456632115329061e+00 , -4.6987542905464075e+00 , 2.5454997600000002e+00 , -7.9858600000000000e-04 , 2.3643400000000001e-01 , 9.7164700000000004e-01 -4.6672156466264001e+00 , -5.1480993340571164e+00 , 2.6495372000000001e+00 , -3.5087300000000002e-02 , 2.1075400000000000e-01 , 9.7690900000000003e-01 -4.8098711156164216e+00 , -5.6754271147675563e+00 , 2.7662917600000001e+00 , -4.6550399999999999e-02 , 2.1433500000000000e-01 , 9.7565000000000002e-01 -4.9661931458890347e+00 , -6.2517475603656028e+00 , 2.9010799199999999e+00 , -5.2565399999999998e-02 , 2.0296300000000000e-01 , 9.7777499999999995e-01 -5.1949432020916806e+00 , -7.0862190114952881e+00 , 3.0559327999999999e+00 , -4.0006399999999998e-02 , 1.6939799999999999e-01 , 9.8473500000000003e-01 -5.4788793417992530e+00 , -8.1181262512701622e+00 , 3.2439543999999998e+00 , -1.5949499999999998e-02 , 1.8017900000000001e-01 , 9.8350499999999996e-01 -5.7894285636210467e+00 , -9.2566115533395905e+00 , 3.4726296000000003e+00 , -1.3499300000000001e-02 , 1.9925699999999999e-01 , 9.7985400000000000e-01 -6.1395179751661288e+00 , -1.0540842644723453e+01 , 3.7503928000000002e+00 , -5.9139300000000004e-03 , 2.0984200000000000e-01 , 9.7771699999999995e-01 -6.5347025388055844e+00 , -1.2000997474565043e+01 , 4.0873216000000001e+00 , 3.1814700000000000e-03 , 2.2249700000000000e-01 , 9.7492800000000002e-01 -6.9824930812966164e+00 , -1.3662506793833685e+01 , 4.4951471999999999e+00 , -7.9000600000000004e-02 , -3.2727899999999999e-01 , -9.4162000000000001e-01 -7.4881725940597068e+00 , -1.5545098274166222e+01 , 4.9877535999999996e+00 , 1.4316000000000001e-01 , 3.2590100000000000e-01 , 9.3450200000000005e-01 -7.9043574750269494e+00 , -1.7127591610106148e+01 , 5.5123607999999997e+00 , 5.2681299999999998e-01 , -1.4905800000000000e-01 , -8.3680900000000003e-01 -8.8398539457723686e+00 , -2.0595537175276146e+01 , 6.3655352000000001e+00 , -7.0310600000000001e-01 , 6.9865900000000003e-01 , 1.3235700000000000e-01 -7.8421871931092895e+00 , -1.7635540089892551e+01 , 8.1848592000000000e+00 , -7.9668700000000003e-01 , -5.4376500000000005e-01 , -2.6383499999999999e-01 -6.9326699080096015e+00 , -1.4349515566215356e+01 , 7.6675735999999999e+00 , 3.5157300000000002e-01 , 4.9947799999999998e-01 , 7.9178199999999999e-01 -7.3684754469046361e+00 , -1.6084551576704019e+01 , 8.4985959999999992e+00 , -1.6135300000000000e-01 , -5.4109200000000003e-02 , -9.8541199999999995e-01 -7.5391047150980457e+00 , -1.6834473280077344e+01 , 9.0922280000000004e+00 , -2.6362500000000000e-01 , 1.8492600000000001e-01 , -9.4673399999999996e-01 -7.0664570130680771e+00 , -1.5147759913137421e+01 , 8.9096352000000003e+00 , -1.1075200000000001e-03 , 2.4933500000000000e-01 , 9.6841699999999997e-01 -6.9548346811485660e+00 , -1.4824981774214898e+01 , 9.1440823999999985e+00 , -7.2374700000000003e-01 , 9.5047900000000005e-02 , -6.8348799999999998e-01 -6.4521543892629341e+00 , -1.2993672674010122e+01 , 8.8082560000000001e+00 , -8.7133000000000005e-01 , -4.8999199999999998e-01 , -2.6296199999999999e-02 -6.4910999784514773e+00 , -1.3240030126980631e+01 , 9.2172359999999998e+00 , 2.8179399999999999e-01 , -4.6673399999999998e-01 , 8.3830300000000002e-01 -8.2351992300595747e+00 , -2.0137125815859253e+01 , 1.2385471200000000e+01 , 1.2805600000000000e-01 , 9.8951100000000003e-01 , 6.6857200000000006e-02 -6.1515203112937868e+00 , -1.2106792896076835e+01 , 9.3726744000000011e+00 , -5.2603699999999998e-01 , -8.2871499999999998e-01 , 1.9109200000000001e-01 -6.1180854899641979e+00 , -1.2069426530108244e+01 , 9.6617215999999999e+00 , 2.3888100000000001e-01 , 9.7100399999999998e-01 , 9.3002899999999993e-03 -6.6035378958000850e+00 , -1.4095235327478893e+01 , 1.0936127200000001e+01 , 9.9141199999999996e-01 , 5.7133499999999997e-02 , -1.1763700000000001e-01 -6.0953895690071498e+00 , -1.2177065118968892e+01 , 1.0339801600000001e+01 , -3.6406500000000001e-02 , 9.8191799999999996e-01 , 1.8577199999999999e-01 -5.9981799530423903e+00 , -1.1886701752761402e+01 , 1.0511037600000000e+01 , -2.1244499999999999e-01 , 9.7131400000000001e-01 , 1.0684600000000000e-01 -5.8512375649290300e+00 , -1.1390050744459252e+01 , 1.0562600800000000e+01 , 2.3700800000000000e-01 , -6.2562499999999999e-01 , 7.4324999999999997e-01 -5.7399444926401610e+00 , -1.1037069133181122e+01 , 1.0678394400000000e+01 , -2.4878500000000001e-01 , -9.3517399999999995e-01 , 2.5210199999999999e-01 -5.7491547100684857e+00 , -1.1174637554873467e+01 , 1.1072533600000000e+01 , -3.9662199999999997e-01 , -8.8800599999999996e-01 , -2.3267299999999999e-01 -5.7521611161141575e+00 , -1.1295636191092665e+01 , 1.1468617600000000e+01 , 4.5300600000000002e-01 , 8.4508799999999995e-01 , 2.8392200000000001e-01 -5.8992822234450948e+00 , -1.2017533625468133e+01 , 1.2259683200000001e+01 , -2.2990700000000000e-01 , -8.7744900000000003e-01 , -4.2098200000000002e-01 -5.7371272689321682e+00 , -1.1449579573889423e+01 , 1.2240516000000001e+01 , 2.8305000000000002e-01 , 8.7882300000000002e-01 , 3.8412700000000000e-01 -5.6940258387465761e+00 , -1.1383293191741982e+01 , 1.2544456000000000e+01 , -5.8837099999999998e-01 , -7.8986699999999999e-01 , -1.7300499999999999e-01 -5.7869723698430171e+00 , -1.1900652304205751e+01 , 1.3269232000000001e+01 , 3.1657900000000000e-01 , 8.0691299999999999e-01 , 4.9866800000000000e-01 -5.7138355048996230e+00 , -1.1716087344972392e+01 , 1.3510719999999999e+01 , 4.7801900000000003e-01 , 8.6607100000000004e-01 , 1.4634900000000001e-01 -5.8158131569573692e+00 , -1.2291676984354028e+01 , 1.4333360000000001e+01 , 5.4801800000000001e-01 , 8.3581899999999998e-01 , -3.2904900000000001e-02 -5.7200668857460073e+00 , -1.2009506202669531e+01 , 1.4517232000000000e+01 , 2.8560500000000000e-01 , 5.8105700000000005e-01 , 7.6210400000000000e-01 -6.0206357242290398e+00 , -1.3490007857155872e+01 , 1.6145144000000002e+01 , 1.6147200000000000e-01 , 9.4850100000000004e-01 , 2.7252900000000002e-01 -6.2329379454576213e+00 , -1.4609782864890079e+01 , 1.7562871999999999e+01 , -2.3457100000000000e-01 , 2.3007100000000000e-01 , 9.4448100000000001e-01 -6.1455218888300402e+00 , -1.4392776066232049e+01 , 1.7883712000000003e+01 , 4.6888800000000003e-01 , -4.0486200000000000e-01 , 7.8500300000000001e-01 -6.1155031228332231e+00 , -1.4443005111140732e+01 , 1.8449784000000001e+01 , 4.6888800000000003e-01 , -4.0486200000000000e-01 , 7.8500300000000001e-01 -5.9476596210291905e+00 , -1.3859756323004941e+01 , 1.8436575999999999e+01 , 8.1142400000000003e-01 , 3.7548399999999998e-01 , -4.4788800000000001e-01 -5.8439809324371890e+00 , -1.3568051421742583e+01 , 1.8687008000000002e+01 , 8.1142400000000003e-01 , 3.7548399999999998e-01 , -4.4788800000000001e-01 -3.2912243848322844e+00 , -1.6033230755994246e+00 , 7.1326912000000000e+00 , 6.1051999999999995e-01 , -5.5968899999999999e-01 , 5.6037000000000003e-01 -3.2449598933771835e+00 , -1.4291113757992724e+00 , 7.0915799999999996e+00 , 4.6345199999999998e-01 , -5.6886000000000003e-01 , 6.7942000000000002e-01 -3.2389931742980576e+00 , -1.4538466383157123e+00 , 7.2574080000000007e+00 , 5.4475399999999996e-01 , -7.4407000000000001e-01 , 3.8678600000000002e-01 -3.2142427449267044e+00 , -1.3909182106411859e+00 , 7.3325687999999998e+00 , 4.8703900000000000e-01 , -8.3893300000000004e-01 , 2.4286800000000000e-01 -3.1947714453484997e+00 , -1.3470178768109493e+00 , 7.4303496000000004e+00 , 6.9077800000000000e-01 , -6.9626800000000000e-01 , 1.9502800000000001e-01 -3.1956666156481242e+00 , -1.4138906368840334e+00 , 7.6625608000000005e+00 , 4.2578300000000002e-01 , -8.0072399999999999e-01 , -4.2136600000000002e-01 -3.1609805978762200e+00 , -1.2982526234840206e+00 , 7.6809792000000003e+00 , 4.0849400000000002e-01 , -9.1275499999999998e-01 , -3.2313699999999999e-03 -3.1833811789944888e+00 , -1.4879663590032535e+00 , 8.0880872000000004e+00 , 4.5684799999999998e-01 , -3.6363000000000001e-01 , -8.1182699999999997e-01 -3.1644710079847540e+00 , -1.4606017599171905e+00 , 8.2304008000000017e+00 , 4.9845299999999998e-01 , 8.1827600000000000e-01 , -2.8630400000000000e-01 -3.1221271123644918e+00 , -1.3077097319858595e+00 , 8.2054824000000011e+00 , -8.7422599999999995e-01 , 4.3563299999999999e-01 , -2.1436700000000000e-01 -3.1206158736825653e+00 , -1.3833260609712306e+00 , 8.4991783999999999e+00 , -7.2856600000000005e-01 , 2.6586700000000002e-01 , -6.3127400000000000e-01 -3.0759137231167273e+00 , -1.2118537779023066e+00 , 8.4448071999999996e+00 , 7.2234799999999999e-01 , -3.0919500000000000e-01 , 6.1855599999999999e-01 -2.9446501472881170e+00 , -5.2423237700036829e-01 , 7.5871192000000001e+00 , 5.7371600000000000e-01 , 7.6466500000000004e-01 , 2.9349399999999998e-01 -2.9078249953024713e+00 , -3.8291302703981822e-01 , 7.5323112000000005e+00 , -9.3999399999999997e-02 , 9.9322200000000005e-01 , 6.8373000000000003e-02 -2.9214100270878305e+00 , -5.5487794721657124e-01 , 7.9886944000000000e+00 , -1.8759799999999999e-01 , 9.8224299999999998e-01 , 2.5355000000000000e-03 -2.8972856085928655e+00 , -4.9384942193665493e-01 , 8.0756592000000005e+00 , -3.7299500000000002e-01 , 9.1439599999999999e-01 , -1.5733600000000000e-01 -2.8871194782441587e+00 , -5.3195754556578567e-01 , 8.3428456000000004e+00 , 7.0521000000000000e-01 , -5.4527599999999998e-01 , 4.5315800000000001e-01 -2.8617607689134656e+00 , -4.7354559327419565e-01 , 8.4481664000000016e+00 , -2.8494700000000001e-01 , -2.4161199999999999e-01 , -9.2759300000000000e-01 -2.8264162920237315e+00 , -3.4080794118982061e-01 , 8.4143352000000000e+00 , -3.1854100000000002e-01 , -2.5106699999999998e-01 , -9.1405499999999995e-01 -2.7864785456886971e+00 , -1.7359073537188729e-01 , 8.3029304000000010e+00 , -2.4314600000000000e-01 , 6.3340900000000000e-01 , 7.3462499999999997e-01 -2.7402034716172028e+00 , 5.5979139867925687e-02 , 8.0464143999999997e+00 , -3.7947100000000000e-01 , -1.1290600000000001e-01 , 9.1828900000000002e-01 -2.7038610386920201e+00 , 2.2496508114559810e-01 , 7.8971223999999998e+00 , 7.5917299999999999e-01 , -1.5771399999999999e-01 , -6.3149299999999997e-01 -2.6872808539419850e+00 , 2.1484457052621186e-01 , 8.1437688000000001e+00 , -8.7271100000000004e-02 , -7.3386799999999996e-01 , 6.7366300000000001e-01 -2.6571763216548860e+00 , 3.2245517076617602e-01 , 8.1233432000000008e+00 , -2.8125099999999997e-01 , -9.5166300000000004e-01 , 1.2342700000000000e-01 -2.6336288013805458e+00 , 3.6911590886209500e-01 , 8.2550279999999994e+00 , 3.4029700000000002e-01 , 9.3877600000000005e-01 , -5.3838299999999999e-02 -2.6311248343755302e+00 , 1.3900678510647269e-01 , 9.1361887999999993e+00 , 6.1567900000000002e-02 , -1.2522600000000000e-01 , 9.9021599999999999e-01 -2.6036450563005111e+00 , 1.7700727580933195e-01 , 9.3505536000000014e+00 , -8.7959399999999999e-01 , -4.2864500000000000e-01 , 2.0634100000000000e-01 -2.5668090927379992e+00 , 3.3579100263799311e-01 , 9.2296015999999987e+00 , -6.0409200000000003e-02 , 8.8926800000000000e-02 , 9.9420500000000001e-01 -2.5333661855044447e+00 , 4.7297833566206449e-01 , 9.1549920000000000e+00 , 1.2468700000000001e-01 , 2.4392800000000001e-01 , 9.6174400000000004e-01 -2.5012693877985246e+00 , 5.9295074706506501e-01 , 9.1269640000000010e+00 , -7.4931599999999998e-01 , 2.2647200000000001e-01 , 6.2228300000000003e-01 -2.4693679888306437e+00 , 6.9702425872413465e-01 , 9.1466096000000014e+00 , 7.8234899999999996e-01 , -5.6460999999999995e-01 , -2.6295700000000000e-01 -2.4367083399712071e+00 , 7.0262829577760910e-01 , 9.5363807999999999e+00 , -9.1644199999999995e-02 , -8.6119599999999996e-01 , 4.9994300000000003e-01 -2.4026370054408437e+00 , 7.7411963356395663e-01 , 9.7152607999999994e+00 , -8.5905500000000001e-01 , -6.0710800000000002e-02 , -5.0827100000000003e-01 -2.3693603800666501e+00 , 8.9914803252813424e-01 , 9.6804936000000001e+00 , 8.0192399999999997e-01 , 5.6781100000000001e-02 , 5.9472199999999997e-01 -2.3325855871181842e+00 , 9.7766798028954760e-01 , 9.8568464000000002e+00 , 9.9699300000000002e-01 , 6.3011300000000006e-02 , -4.5096100000000000e-02 -2.3005253725198305e+00 , 1.1094372106055705e+00 , 9.7872599999999998e+00 , 6.8336600000000003e-01 , 6.3710000000000000e-01 , -3.5653099999999999e-01 -2.2662834981315347e+00 , 1.2265956897601455e+00 , 9.7764544000000004e+00 , 8.2670699999999997e-01 , 5.4996599999999995e-01 , -1.1871000000000000e-01 -2.2380216060750464e+00 , 1.3627703862915828e+00 , 9.6504896000000002e+00 , -8.4444200000000003e-01 , -2.1291599999999999e-01 , -4.9151299999999998e-01 -2.2044187179976169e+00 , 1.4713240489899038e+00 , 9.6761672000000001e+00 , -5.0181699999999996e-01 , 4.6768500000000002e-01 , 7.2763299999999997e-01 -2.1759174516210802e+00 , 1.5957616282723155e+00 , 9.5762336000000001e+00 , -5.8056700000000006e-01 , 5.5003500000000005e-01 , 6.0033599999999998e-01 -2.1170234266379464e+00 , 1.6449604526776753e+00 , 1.0145155200000000e+01 , -9.4503700000000002e-01 , -2.0783900000000000e-01 , 2.5240299999999999e-01 -2.0754296654845215e+00 , 1.7523664980284546e+00 , 1.0279377600000000e+01 , -2.2086000000000000e-01 , -8.6097100000000004e-01 , -4.5820300000000003e-01 -2.0639704695773591e+00 , 1.9046566919726582e+00 , 9.8628056000000015e+00 , 7.2900699999999996e-01 , -6.8384900000000004e-01 , 3.0001799999999999e-02 -2.0214007713436284e+00 , 2.0100860422596085e+00 , 1.0013356000000000e+01 , -8.6915600000000004e-01 , 1.0293600000000000e-01 , -4.8370700000000000e-01 -2.0258794669475213e+00 , 2.1494916566816444e+00 , 9.4466391999999999e+00 , -8.9464699999999997e-01 , 7.5016700000000006e-02 , -4.4043100000000002e-01 -1.9256769375582057e+00 , 2.2347080209884589e+00 , 1.0412144000000000e+01 , -7.8429899999999997e-01 , -2.6741300000000001e-01 , 5.5979000000000001e-01 -1.9276949514486004e+00 , 2.3613783108197786e+00 , 9.9239783999999993e+00 , -3.3047100000000001e-01 , -9.1118200000000005e-01 , -2.4604300000000001e-01 -1.9098324440875512e+00 , 2.4737466642624955e+00 , 9.7347919999999988e+00 , 5.9764399999999995e-01 , 6.1475100000000005e-01 , 5.1468800000000003e-01 -1.9122114406642639e+00 , 2.5749619856505164e+00 , 9.3259055999999987e+00 , 1.1124299999999999e-01 , 3.5047699999999998e-01 , 9.2994200000000005e-01 -1.8930374294305072e+00 , 2.6747720947096361e+00 , 9.2058584000000003e+00 , 8.0761200000000000e-01 , -5.7256300000000004e-01 , -1.4119000000000001e-01 -1.8386362866156856e+00 , 2.7943606247262966e+00 , 9.4557807999999994e+00 , -7.0862800000000004e-01 , 2.1450600000000000e-01 , -6.7218599999999995e-01 -1.3721748738910766e+00 , 3.2393386631090388e+00 , 1.3778416000000000e+01 , 7.4490400000000001e-01 , -6.6710800000000003e-01 , 9.2174100000000005e-03 -1.7565427695924778e+00 , 3.0290873474935438e+00 , 9.6493768000000006e+00 , -6.6746899999999998e-02 , 8.7621900000000003e-02 , 9.9391499999999999e-01 -1.7284309426576283e+00 , 3.1357966716557728e+00 , 9.6038144000000010e+00 , 4.9756499999999998e-01 , -3.2746399999999998e-01 , -8.0324099999999998e-01 -1.7286622993148881e+00 , 3.2114612899061106e+00 , 9.3206431999999992e+00 , -1.1901000000000000e-01 , 9.3830499999999994e-01 , -3.2468399999999997e-01 -1.7063699200340945e+00 , 3.3089615925252804e+00 , 9.2517016000000005e+00 , 3.6730100000000000e-03 , -9.9024699999999999e-01 , 1.3927500000000001e-01 -3.0721763164766589e+00 , 5.5441958664489177e-01 , 1.3470859200000000e+00 , -7.2970300000000002e-02 , 3.1010599999999999e-01 , 9.4789699999999999e-01 -3.0796915242538416e+00 , 5.1712603993439266e-01 , 1.3743828000000000e+00 , -8.1675899999999996e-02 , 2.7285399999999999e-01 , 9.5858200000000005e-01 -3.0915997798206210e+00 , 4.6545302507946218e-01 , 1.3892381600000001e+00 , -6.5819299999999997e-02 , 1.7824100000000001e-01 , 9.8178299999999996e-01 -3.1088077798104647e+00 , 3.9740897616945126e-01 , 1.3924923199999999e+00 , -9.8628599999999997e-02 , 1.9165399999999999e-01 , 9.7649399999999997e-01 -3.1213811541389322e+00 , 3.4526593069503897e-01 , 1.4104104799999999e+00 , -4.7144999999999999e-02 , 1.8199699999999999e-01 , 9.8216800000000004e-01 -3.1381535422124895e+00 , 2.7688951382629989e-01 , 1.4172089600000000e+00 , -5.9678500000000002e-02 , 2.0080600000000001e-01 , 9.7781200000000001e-01 -3.1503609740263139e+00 , 2.2429027326820439e-01 , 1.4380640800000000e+00 , -6.1148500000000001e-02 , 2.0842700000000000e-01 , 9.7612500000000002e-01 -3.1666504025112636e+00 , 1.5457440733758476e-01 , 1.4486117599999999e+00 , -7.7988100000000005e-02 , 1.3549400000000000e-01 , 9.8770400000000003e-01 -3.1864292868773023e+00 , 7.7543576998060804e-02 , 1.4552022400000000e+00 , -3.6315399999999998e-02 , 2.0376500000000000e-01 , 9.7834600000000005e-01 -3.2006068446768605e+00 , 1.5209695340534068e-02 , 1.4756268000000001e+00 , -2.2695900000000001e-02 , 2.1821399999999999e-01 , 9.7563699999999998e-01 -3.2198331276752064e+00 , -6.3047362860532363e-02 , 1.4865738400000001e+00 , -4.7216200000000000e-02 , 2.2643099999999999e-01 , 9.7288200000000002e-01 -3.2361840465507319e+00 , -1.3327072874727675e-01 , 1.5051440800000000e+00 , -7.8398300000000004e-02 , 2.1608300000000000e-01 , 9.7322200000000003e-01 -3.2533437403749672e+00 , -2.0312852887968980e-01 , 1.5257631199999999e+00 , -4.2105099999999999e-02 , 1.6162499999999999e-01 , 9.8595400000000000e-01 -3.2768014244890162e+00 , -3.0026527422688298e-01 , 1.5335183999999999e+00 , -6.2535099999999996e-02 , 2.0655100000000001e-01 , 9.7643500000000005e-01 -3.2933582965271682e+00 , -3.7125336716375967e-01 , 1.5588975199999999e+00 , -6.4718999999999999e-02 , 2.2231200000000001e-01 , 9.7282500000000005e-01 -3.3172075457650942e+00 , -4.6837440747471204e-01 , 1.5720420800000001e+00 , -6.4542100000000005e-02 , 1.8458700000000000e-01 , 9.8069499999999998e-01 -3.3381712105652324e+00 , -5.5745321570776607e-01 , 1.5929117600000000e+00 , -3.4494100000000000e-02 , 2.0280300000000001e-01 , 9.7861200000000004e-01 -3.3598235478098344e+00 , -6.4703972608837779e-01 , 1.6166414400000000e+00 , -5.0976000000000000e-02 , 2.0506900000000000e-01 , 9.7741900000000004e-01 -3.3860271405884723e+00 , -7.5497417885917484e-01 , 1.6346459200000001e+00 , -4.3642199999999999e-02 , 1.8779000000000001e-01 , 9.8123899999999997e-01 -3.4094418275673295e+00 , -8.5283061226432411e-01 , 1.6598638399999999e+00 , -3.7356599999999997e-02 , 1.7714900000000000e-01 , 9.8347499999999999e-01 -3.4406392680073004e+00 , -9.8028606091396364e-01 , 1.6769292000000000e+00 , -4.7947700000000003e-02 , 1.7352100000000001e-01 , 9.8366200000000004e-01 -3.4689986291208994e+00 , -1.0975779544493913e+00 , 1.7016135999999999e+00 , -6.1849599999999998e-02 , 1.7873500000000000e-01 , 9.8195100000000002e-01 -3.5002442265836384e+00 , -1.2255117712906554e+00 , 1.7268034399999999e+00 , 7.0324600000000001e-02 , -1.5462999999999999e-01 , -9.8546599999999995e-01 -3.5356618036979643e+00 , -1.3722205938412859e+00 , 1.7493069600000000e+00 , -5.5224700000000002e-02 , 1.7504300000000000e-01 , 9.8301099999999997e-01 -3.5692199187437232e+00 , -1.5097878109971754e+00 , 1.7798600800000000e+00 , -4.7468999999999997e-02 , 1.9405000000000000e-01 , 9.7984199999999999e-01 -3.6044775065060315e+00 , -1.6577175556816215e+00 , 1.8121104800000001e+00 , -4.6836000000000003e-02 , 1.8981200000000001e-01 , 9.8070299999999999e-01 -3.6447465374360979e+00 , -1.8240929655364528e+00 , 1.8434176000000000e+00 , -4.7505300000000000e-02 , 2.0745900000000000e-01 , 9.7709000000000001e-01 -3.6843215896567028e+00 , -1.9914473622351245e+00 , 1.8802960000000000e+00 , -3.7936999999999999e-02 , 1.9272900000000001e-01 , 9.8051800000000000e-01 -3.7319234122599658e+00 , -2.1881178559717318e+00 , 1.9156258399999999e+00 , -3.1538499999999997e-02 , 1.8656200000000001e-01 , 9.8193699999999995e-01 -3.7797867174746624e+00 , -2.3845549486511057e+00 , 1.9574585920000001e+00 , -4.1346399999999998e-02 , 1.8451600000000001e-01 , 9.8195900000000003e-01 -3.8375821885632178e+00 , -2.6210321611955312e+00 , 1.9977194048000000e+00 , -5.7294600000000001e-02 , 1.9499000000000000e-01 , 9.7912999999999994e-01 -3.8890988891317395e+00 , -2.8368269004051179e+00 , 2.0496471039999999e+00 , -5.4129700000000003e-02 , 2.3916200000000001e-01 , 9.6947000000000005e-01 -3.9555979392692886e+00 , -3.1122774507190529e+00 , 2.0985577840000000e+00 , 3.0418899999999999e-02 , 2.8768600000000000e-01 , 9.5724200000000004e-01 -3.9977730673794367e+00 , -3.2990438395141339e+00 , 2.1713951200000001e+00 , 9.7660100000000000e-02 , 2.7453000000000000e-01 , 9.5660599999999996e-01 -4.0360884962393797e+00 , -3.4745591598795782e+00 , 2.2518214400000001e+00 , 7.2230799999999998e-02 , 2.7735700000000002e-01 , 9.5804800000000001e-01 -4.1119142635562405e+00 , -3.7897799341974014e+00 , 2.3213787200000002e+00 , 6.1456200000000002e-02 , 2.5940500000000000e-01 , 9.6381099999999997e-01 -4.1915688454957696e+00 , -4.1235799891201061e+00 , 2.3997136000000001e+00 , 3.1094199999999999e-03 , 2.3968400000000001e-01 , 9.7084599999999999e-01 -4.2809906650500302e+00 , -4.4975278771890395e+00 , 2.4864204800000000e+00 , -3.6628000000000001e-02 , 2.1682999999999999e-01 , 9.7552200000000000e-01 -4.3789367799916921e+00 , -4.9101352653333059e+00 , 2.5832964800000000e+00 , -4.4473800000000001e-02 , 2.1639900000000001e-01 , 9.7529200000000005e-01 -4.5001410287242294e+00 , -5.4129586899421342e+00 , 2.6906411200000000e+00 , -4.6610600000000002e-02 , 2.0881800000000000e-01 , 9.7684300000000002e-01 -4.6321360023308786e+00 , -5.9639994652686639e+00 , 2.8139216800000000e+00 , -5.4468999999999997e-02 , 2.0945100000000000e-01 , 9.7630099999999997e-01 -4.7932584987009168e+00 , -6.6347762434322224e+00 , 2.9552098400000002e+00 , -5.5116900000000003e-02 , 1.8512200000000001e-01 , 9.8116899999999996e-01 -4.9983978321460265e+00 , -7.4840723267025488e+00 , 3.1210263999999999e+00 , -2.9284999999999999e-02 , 1.7257800000000001e-01 , 9.8456100000000002e-01 -5.2628169993397069e+00 , -8.5739697328125164e+00 , 3.3228904000000004e+00 , -2.2233400000000000e-02 , 1.8388699999999999e-01 , 9.8269600000000001e-01 -5.5360760487329159e+00 , -9.7101454097507975e+00 , 3.5656160000000003e+00 , -1.2134200000000000e-02 , 2.0106299999999999e-01 , 9.7950300000000001e-01 -5.8472572740574638e+00 , -1.1012981220172261e+01 , 3.8588751999999999e+00 , -4.3399600000000003e-03 , 2.1320700000000001e-01 , 9.7699700000000000e-01 -6.2067503439019305e+00 , -1.2520800980380344e+01 , 4.2148256000000002e+00 , 2.0561900000000001e-02 , 2.4577099999999999e-01 , 9.6911000000000003e-01 -6.6103254841793895e+00 , -1.4222789431644276e+01 , 4.6440751999999996e+00 , 1.8262700000000001e-01 , 3.7225300000000000e-01 , 9.0998599999999996e-01 -6.7364929009978001e+00 , -1.4832419855986043e+01 , 5.0129840000000003e+00 , 3.2980399999999999e-01 , 3.3096300000000001e-01 , 8.8413399999999998e-01 -7.0054218244034345e+00 , -1.6024971563371064e+01 , 5.4807552000000008e+00 , 1.3349800000000001e-01 , 3.6007299999999998e-01 , 9.2332300000000000e-01 -7.9354565129331984e+00 , -2.0645799100199071e+01 , 8.6319136000000007e+00 , 7.4743099999999996e-01 , -5.6447899999999995e-01 , 3.5030099999999997e-01 -7.8526638948941088e+00 , -2.0448229210196384e+01 , 9.0150496000000011e+00 , 7.4743099999999996e-01 , -5.6447899999999995e-01 , 3.5030099999999997e-01 -7.8464935327394576e+00 , -2.0577242753336016e+01 , 9.4852543999999988e+00 , 7.4743099999999996e-01 , -5.6447899999999995e-01 , 3.5030099999999997e-01 -7.6518526849293513e+00 , -1.9899677730679205e+01 , 9.7238615999999993e+00 , 6.8976199999999999e-01 , -6.5217800000000004e-01 , 3.1447199999999997e-01 -7.5908210239827119e+00 , -1.9791502548340119e+01 , 1.0121183200000001e+01 , 7.5563599999999997e-01 , -6.0501499999999997e-01 , 2.5094200000000000e-01 -7.6880770204050721e+00 , -2.0369853273781121e+01 , 1.0749727999999999e+01 , 7.1407500000000002e-01 , -6.7095199999999999e-01 , 1.9980100000000001e-01 -7.5561708431157442e+00 , -1.9957062656105627e+01 , 1.1052461600000001e+01 , -1.5517400000000001e-01 , -9.6986700000000003e-01 , -1.8782499999999999e-01 -7.5033280302197918e+00 , -1.9884049500323648e+01 , 1.1471904000000000e+01 , 1.2805600000000000e-01 , 9.8951100000000003e-01 , 6.6857299999999995e-02 -5.7181070528616136e+00 , -1.2119626638492711e+01 , 8.8422224000000007e+00 , -5.2544199999999996e-01 , -7.9186599999999996e-01 , 3.1122200000000000e-01 -5.6920292149406340e+00 , -1.2109313937682202e+01 , 9.1355855999999989e+00 , 2.6642700000000002e-01 , 9.5958500000000002e-01 , 9.0624700000000002e-02 -5.6461038811738193e+00 , -1.2019511829678612e+01 , 9.3973848000000011e+00 , 2.6642700000000002e-01 , 9.5958500000000002e-01 , 9.0624700000000002e-02 -5.6285636886321821e+00 , -1.2054159168014605e+01 , 9.7170808000000015e+00 , 2.4118300000000001e-01 , 9.6086700000000003e-01 , 1.3625499999999999e-01 -5.6399967253430283e+00 , -1.2220564808136453e+01 , 1.0105978400000000e+01 , 4.1924299999999998e-02 , -9.6895500000000001e-01 , -2.4365800000000001e-01 -5.6612733842122243e+00 , -1.2441958931073325e+01 , 1.0534676800000000e+01 , -3.9496999999999999e-01 , 9.1407099999999997e-01 , -9.2047100000000007e-02 -5.8930869027048862e+00 , -1.3648401217898602e+01 , 1.1494721600000000e+01 , 7.8911200000000004e-01 , 2.2019200000000000e-01 , -5.7342700000000002e-01 -5.5701974829168766e+00 , -1.2271641918523249e+01 , 1.1102267200000000e+01 , -1.0870800000000000e-01 , 9.7422100000000000e-01 , -1.9767799999999999e-01 -5.3170484173598336e+00 , -1.1204927607280062e+01 , 1.0830182400000000e+01 , -2.4878500000000001e-01 , -9.3517399999999995e-01 , 2.5210199999999999e-01 -5.2735562588652449e+00 , -1.1120574723663578e+01 , 1.1096921600000000e+01 , -8.6901400000000004e-02 , -9.8899800000000004e-01 , -1.1971600000000000e-01 -5.2895781979550014e+00 , -1.1327222860292318e+01 , 1.1545348799999999e+01 , 1.9328900000000000e-02 , 9.6331100000000003e-01 , 2.6768999999999998e-01 -5.3144812844861828e+00 , -1.1583854936266308e+01 , 1.2042167200000000e+01 , 1.9472400000000001e-01 , -8.0003599999999997e-01 , -5.6747300000000001e-01 -5.9353837431441328e+00 , -1.4790328654583909e+01 , 1.4521392000000001e+01 , 2.9881200000000002e-01 , -8.4949300000000005e-01 , -4.3482500000000002e-01 -5.3550434532441322e+00 , -1.2075010896443571e+01 , 1.3080888000000000e+01 , 3.8721400000000000e-01 , -8.9381699999999997e-01 , -2.2617899999999999e-01 -5.3369973526149774e+00 , -1.2142125935587483e+01 , 1.3503336000000001e+01 , -5.2184200000000003e-01 , 8.3914599999999995e-01 , -1.5334600000000001e-01 -5.3129487724390465e+00 , -1.2182655544726504e+01 , 1.3918504000000000e+01 , -4.6951300000000001e-01 , 8.7634599999999996e-01 , -1.0759100000000001e-01 -5.2430559376098449e+00 , -1.1993400608918298e+01 , 1.4168623999999999e+01 , -3.9449400000000001e-01 , 9.1883700000000001e-01 , -1.0630600000000000e-02 -5.1441446028571800e+00 , -1.1647565582013069e+01 , 1.4293424000000002e+01 , -3.9449400000000001e-01 , 9.1883700000000001e-01 , -1.0630600000000000e-02 -5.3019128139577187e+00 , -1.2658166614099649e+01 , 1.5530088000000001e+01 , -4.8624400000000001e-01 , -7.8080200000000000e-01 , -3.9231899999999997e-01 -5.7931163576725453e+00 , -1.5485677502992448e+01 , 1.8392064000000001e+01 , 4.6888800000000003e-01 , -4.0486299999999997e-01 , 7.8500300000000001e-01 -5.3937319038225704e+00 , -1.3564136048153923e+01 , 1.7229863999999999e+01 , -5.6011100000000003e-01 , -8.1365600000000005e-01 , -1.5569100000000000e-01 -5.2646202086286475e+00 , -1.3077028869201291e+01 , 1.7279783999999999e+01 , 3.0627599999999999e-01 , 9.4894999999999996e-01 , 7.5424500000000005e-02 -5.2195576937412822e+00 , -1.3056557341269405e+01 , 1.7756520000000002e+01 , -8.3368200000000003e-01 , -4.2091299999999998e-01 , 3.5749999999999998e-01 -3.2622187934177176e+00 , -2.1960625226635493e+00 , 7.5996616000000001e+00 , 8.7478299999999998e-01 , -4.8206300000000002e-01 , -4.8680899999999999e-02 -3.1328980719716100e+00 , -1.5261080995072809e+00 , 7.0763752000000002e+00 , -2.8245900000000002e-01 , 8.8031899999999996e-01 , -3.8112400000000002e-01 -3.1132415277900432e+00 , -1.4803882999193774e+00 , 7.1673543999999998e+00 , -3.0724299999999999e-01 , 8.9996500000000001e-01 , -3.0929600000000002e-01 -3.1124037829093245e+00 , -1.5448108969575314e+00 , 7.3797119999999996e+00 , 5.6839600000000001e-01 , -7.7666800000000003e-01 , 2.7150200000000002e-01 -3.1205078804321262e+00 , -1.6719495701718641e+00 , 7.6726800000000006e+00 , -9.7980899999999996e-02 , -9.9488399999999999e-01 , -2.4597899999999999e-02 -3.0791975125707696e+00 , -1.4937836161336153e+00 , 7.6258800000000004e+00 , 6.5972100000000000e-01 , -7.4181100000000000e-01 , -1.2035300000000000e-01 -3.0565246219050608e+00 , -1.4371935912942635e+00 , 7.7174624000000005e+00 , -6.4822700000000000e-01 , 7.5499600000000000e-01 , -9.8913399999999999e-02 -3.0528441572030407e+00 , -1.5014177949172565e+00 , 7.9618416000000005e+00 , -2.5463799999999998e-01 , 8.2808199999999998e-01 , 4.9943900000000002e-01 -3.0262000386795203e+00 , -1.4197300477647592e+00 , 8.0295871999999999e+00 , -6.7531699999999995e-01 , -8.2972500000000005e-02 , 7.3284600000000000e-01 -2.9891045150862370e+00 , -1.2681829380986152e+00 , 8.0043880000000005e+00 , -5.1515500000000003e-01 , 3.2562700000000000e-02 , 8.5647899999999999e-01 -2.9972068312228353e+00 , -1.4279205741070653e+00 , 8.4043615999999997e+00 , 7.1719299999999997e-01 , -3.5788599999999998e-01 , 5.9795699999999996e-01 -2.9613069464312547e+00 , -1.2851508918462522e+00 , 8.3938471999999997e+00 , -7.2856600000000005e-01 , 2.6586700000000002e-01 , -6.3127400000000000e-01 -2.9395646238835220e+00 , -1.2483325081309395e+00 , 8.5350479999999997e+00 , -6.2991799999999998e-01 , 1.1412000000000000e-01 , -7.6823200000000003e-01 -2.9096682822495255e+00 , -1.1501770195250054e+00 , 8.5889616000000011e+00 , -5.2400000000000002e-01 , 1.1130500000000000e-01 , -8.4441400000000000e-01 -2.9056742254699137e+00 , -1.2553191587606269e+00 , 8.9674696000000012e+00 , -9.0344400000000002e-01 , 3.6766500000000002e-01 , -2.2048100000000001e-01 -2.7968528447428547e+00 , -5.0555975901320283e-01 , 7.9434127999999999e+00 , -5.1520400000000000e-01 , 8.4405699999999995e-01 , -1.4876800000000001e-01 -2.8447931754000431e+00 , -1.0659671221538041e+00 , 9.1090136000000008e+00 , -6.9664599999999999e-01 , 7.1643599999999996e-01 , -3.7468599999999998e-02 -2.8258086808563925e+00 , -1.0699746425766721e+00 , 9.3591335999999998e+00 , -9.7896399999999995e-01 , 1.2366199999999999e-01 , -1.6228999999999999e-01 -2.7409447772214537e+00 , -4.4753596458411771e-01 , 8.4460760000000015e+00 , 5.1301300000000005e-01 , 2.5763999999999998e-01 , 8.1880399999999998e-01 -2.7042233749325062e+00 , -2.6773942058857036e-01 , 8.3187695999999995e+00 , 3.1854100000000002e-01 , 2.5106699999999998e-01 , 9.1405499999999995e-01 -2.6621912863527184e+00 , 3.5024716464255867e-03 , 7.9906495999999994e+00 , 5.0688299999999997e-01 , -4.0145799999999998e-01 , -7.6282399999999995e-01 -2.6371196681626019e+00 , 9.4995682842069273e-02 , 8.0125208000000008e+00 , -5.5241600000000002e-01 , -2.8267900000000001e-01 , -7.8417400000000004e-01 -2.6060055506164854e+00 , 2.5898227591908407e-01 , 7.8711848000000000e+00 , -3.3903100000000003e-01 , 8.6288200000000004e-01 , 3.7482399999999999e-01 -2.5830161835910692e+00 , 3.3606266978789279e-01 , 7.9167992000000007e+00 , -8.5100999999999996e-02 , 9.4727600000000001e-01 , 3.0891099999999999e-01 -2.5662694688213969e+00 , 2.8337741372085978e-01 , 8.2789064000000003e+00 , -3.2044499999999998e-01 , -9.4312300000000004e-01 , -8.8507100000000005e-02 -2.5400767925157721e+00 , 3.8242162226885723e-01 , 8.2852920000000001e+00 , 5.4922499999999996e-01 , -5.2102999999999999e-01 , 6.5336000000000005e-01 -2.5262897888214249e+00 , 1.0723964902814487e-01 , 9.3039927999999996e+00 , 7.7205500000000005e-01 , 6.2121800000000005e-01 , -1.3423700000000000e-01 -2.4950540468598090e+00 , 2.5958196884938478e-01 , 9.2049224000000009e+00 , 1.5123600000000001e-01 , 1.3412900000000000e-01 , 9.7935600000000000e-01 -2.4657981738567702e+00 , 3.3697319614307530e-01 , 9.3193328000000015e+00 , -4.8526600000000003e-02 , -3.8439099999999998e-01 , -9.2189399999999999e-01 -2.4370257753618247e+00 , 6.1637850700349550e-01 , 8.7973776000000008e+00 , -9.7954799999999997e-01 , -1.7114699999999999e-01 , -1.0580199999999999e-01 -2.4096697842102381e+00 , 7.0709030715538290e-01 , 8.8465071999999996e+00 , -3.6409300000000000e-01 , -2.9348500000000000e-01 , 8.8391399999999998e-01 -2.3753418063958947e+00 , 6.5761130493623110e-01 , 9.4052471999999998e+00 , -6.2308500000000000e-01 , 7.1587400000000001e-01 , -3.1510300000000002e-01 -2.3553016213913813e+00 , 9.1273543171432747e-01 , 8.8595176000000002e+00 , 1.4550900000000000e-03 , -6.7328499999999999e-02 , 9.9773000000000001e-01 -2.3286845699408234e+00 , 1.0177050435004817e+00 , 8.8530903999999992e+00 , 3.0947700000000000e-01 , -4.9994300000000003e-01 , 8.0887699999999996e-01 -2.2756133959488247e+00 , 8.9013002212091163e-01 , 9.8898040000000016e+00 , 9.7348699999999999e-01 , 1.8373700000000001e-01 , -1.3624600000000001e-01 -2.2638177627660081e+00 , 1.1422701267182700e+00 , 9.2414368000000007e+00 , -5.9219500000000003e-01 , 7.2437499999999999e-01 , 3.5296699999999998e-01 -2.2154128178555852e+00 , 1.1360022076284704e+00 , 9.8535183999999987e+00 , 7.0204400000000000e-01 , -1.1832200000000000e-01 , -7.0223500000000005e-01 -2.1864107107307102e+00 , 1.2625985160743163e+00 , 9.8010711999999991e+00 , 8.7714499999999995e-01 , -5.9645900000000002e-02 , -4.7650799999999999e-01 -2.1582587896555654e+00 , 1.3843107745845014e+00 , 9.7667408000000009e+00 , 9.9964799999999998e-01 , -6.1690800000000004e-03 , -2.5792499999999999e-02 -2.1301171347697077e+00 , 1.5034125569485863e+00 , 9.7405328000000004e+00 , -8.2680200000000004e-01 , 5.3226499999999999e-01 , 1.8191199999999999e-01 -2.0589269980552936e+00 , 1.5247275815112569e+00 , 1.0526814399999999e+01 , -4.9950400000000000e-01 , 7.8345600000000004e-01 , 3.6971799999999999e-01 -2.0470656716121365e+00 , 1.6884593134581349e+00 , 1.0166943200000000e+01 , -7.5742100000000001e-01 , 5.9897100000000003e-01 , 2.5990000000000002e-01 -2.0255942226161987e+00 , 1.8224864138272843e+00 , 1.0010693600000000e+01 , 9.0607099999999996e-02 , 1.0332000000000000e-01 , 9.9051299999999998e-01 -2.0088305972876959e+00 , 1.9549444168950267e+00 , 9.7896935999999997e+00 , 3.4455400000000003e-01 , 8.9948899999999998e-01 , -2.6870600000000000e-01 -1.9953660796822148e+00 , 2.0804183633372255e+00 , 9.5663432000000004e+00 , -1.8870200000000001e-01 , 6.8537700000000001e-01 , 7.0331299999999997e-01 -1.9108024575533851e+00 , 2.1648444581075568e+00 , 1.0325720000000000e+01 , 8.2999699999999998e-01 , 3.4910300000000000e-01 , -4.3500800000000001e-01 -1.8670040047690593e+00 , 2.2852781034987362e+00 , 1.0471434400000000e+01 , -7.8429899999999997e-01 , -2.6741300000000001e-01 , 5.5979000000000001e-01 -1.8404140773179685e+00 , 2.4105318359316850e+00 , 1.0407578400000000e+01 , -7.8429899999999997e-01 , -2.6741300000000001e-01 , 5.5979000000000001e-01 -1.8984965466908881e+00 , 2.5170592165012882e+00 , 9.3781552000000001e+00 , -4.1304200000000002e-01 , -6.1173100000000002e-01 , -6.7467100000000002e-01 -1.8771656846654050e+00 , 2.6212348860165218e+00 , 9.3109296000000015e+00 , -3.7039600000000000e-01 , 4.1337099999999999e-01 , 8.3182400000000001e-01 -1.8558173364940200e+00 , 2.7239447429090369e+00 , 9.2522424000000001e+00 , -3.6627900000000002e-01 , 4.8830299999999999e-01 , 7.9208599999999996e-01 -1.8038839262653976e+00 , 2.8464752187553697e+00 , 9.4909536000000010e+00 , 5.4006399999999999e-01 , -3.2504899999999998e-01 , 7.7632100000000004e-01 -1.3246446385931532e+00 , 3.3239447519560579e+00 , 1.3777168000000000e+01 , 7.4490400000000001e-01 , -6.6710800000000003e-01 , 9.2174100000000005e-03 -1.7324645331864206e+00 , 3.0806066973296553e+00 , 9.6311871999999994e+00 , -2.9265800000000002e-02 , 3.0425500000000000e-01 , 9.5214100000000002e-01 -1.7347481986576037e+00 , 3.1595418391251462e+00 , 9.3488688000000018e+00 , 1.6920600000000000e-01 , 3.5495199999999999e-01 , 9.1944499999999996e-01 -1.7142713900645572e+00 , 3.2603283452394294e+00 , 9.2913256000000004e+00 , 2.9062100000000000e-02 , -9.7603600000000001e-01 , 2.1565999999999999e-01 -3.0282425390606500e+00 , 5.2915079907630935e-01 , 1.3598477600000001e+00 , -6.3063400000000006e-02 , 2.7287099999999997e-01 , 9.5998099999999997e-01 -3.0391574269867099e+00 , 4.7633199299677798e-01 , 1.3740749600000000e+00 , -5.7804500000000002e-02 , 3.0307499999999998e-01 , 9.5121199999999995e-01 -3.0499165849339525e+00 , 4.2378935308334520e-01 , 1.3896167200000000e+00 , -4.5496399999999999e-02 , 1.8506900000000001e-01 , 9.8167199999999999e-01 -3.0621899433718252e+00 , 3.6271425732364038e-01 , 1.4000437600000000e+00 , -9.4495399999999993e-02 , 1.9099500000000000e-01 , 9.7703200000000001e-01 -3.0753048591094680e+00 , 3.0194770348589084e-01 , 1.4122148800000001e+00 , -3.2983899999999997e-02 , 2.1553200000000000e-01 , 9.7594000000000003e-01 -3.0882507115004860e+00 , 2.4148644757873994e-01 , 1.4258024800000000e+00 , -7.8032400000000002e-02 , 1.9497800000000001e-01 , 9.7769899999999998e-01 -3.1025835269932012e+00 , 1.7161802161069772e-01 , 1.4351884799999999e+00 , -7.9819699999999993e-02 , 1.7873000000000000e-01 , 9.8065500000000005e-01 -3.1177343184803523e+00 , 1.0210641501730588e-01 , 1.4465203199999999e+00 , -8.4181699999999998e-02 , 1.8079200000000001e-01 , 9.7991200000000001e-01 -3.1299665304944431e+00 , 3.9601034250265732e-02 , 1.4656823200000000e+00 , -9.8838200000000001e-02 , 2.0346300000000000e-01 , 9.7408099999999997e-01 -3.1446438037454842e+00 , -3.0176343625380575e-02 , 1.4808621600000000e+00 , -6.5506999999999996e-02 , 2.3907400000000001e-01 , 9.6878900000000001e-01 -3.1590729305183181e+00 , -1.0060888014971603e-01 , 1.4979670400000000e+00 , -5.7783300000000003e-02 , 1.8435699999999999e-01 , 9.8115900000000000e-01 -3.1783721479742804e+00 , -1.8885782092439696e-01 , 1.5068153600000000e+00 , -8.5128300000000004e-02 , 2.2275600000000001e-01 , 9.7114999999999996e-01 -3.1922704012079262e+00 , -2.5946163998663607e-01 , 1.5282747200000000e+00 , -8.3023799999999995e-02 , 1.8694900000000000e-01 , 9.7885500000000003e-01 -3.2119753237406021e+00 , -3.4881683095739779e-01 , 1.5422117600000000e+00 , -7.7589800000000000e-02 , 2.0030200000000001e-01 , 9.7665700000000000e-01 -3.2278160169551260e+00 , -4.2909723420617185e-01 , 1.5634412799999999e+00 , -7.5671900000000000e-02 , 2.1130599999999999e-01 , 9.7448599999999996e-01 -3.2469060439099220e+00 , -5.1847095544148525e-01 , 1.5824410400000000e+00 , -7.7351900000000001e-02 , 1.9770199999999999e-01 , 9.7720600000000002e-01 -3.2671074417901225e+00 , -6.1676652431417534e-01 , 1.5995646400000001e+00 , -7.0590899999999998e-02 , 2.1440300000000001e-01 , 9.7419100000000003e-01 -3.2879081810456778e+00 , -7.1651110622552006e-01 , 1.6201597599999999e+00 , -8.0104599999999998e-02 , 1.9250100000000001e-01 , 9.7802199999999995e-01 -3.3108021789763766e+00 , -8.2510583556147354e-01 , 1.6394091200000001e+00 , -7.1838799999999994e-02 , 1.9246199999999999e-01 , 9.7867099999999996e-01 -3.3342936924281608e+00 , -9.3405696108436453e-01 , 1.6623286400000001e+00 , -8.1342300000000006e-02 , 1.8063699999999999e-01 , 9.8018000000000005e-01 -3.3587191189980259e+00 , -1.0527087134021729e+00 , 1.6846907199999999e+00 , -8.2504300000000003e-02 , 1.6864000000000001e-01 , 9.8221899999999995e-01 -3.3860863113658386e+00 , -1.1810042609184506e+00 , 1.7072535200000001e+00 , -8.9464199999999994e-02 , 1.6445199999999999e-01 , 9.8231900000000005e-01 -3.4176367505920040e+00 , -1.3280937532161858e+00 , 1.7270291200000001e+00 , -7.1821599999999999e-02 , 1.7571899999999999e-01 , 9.8181700000000005e-01 -3.4439513969271691e+00 , -1.4567406121879531e+00 , 1.7581979200000000e+00 , -6.8586999999999995e-02 , 2.0220299999999999e-01 , 9.7693900000000000e-01 -3.4753766676908606e+00 , -1.6051076372196733e+00 , 1.7874156800000001e+00 , -7.3353699999999994e-02 , 1.9246800000000000e-01 , 9.7855800000000004e-01 -3.5084644964979619e+00 , -1.7637597805627543e+00 , 1.8186333600000000e+00 , 6.4904799999999999e-02 , -2.0121300000000000e-01 , -9.7739500000000001e-01 -3.5419470034817788e+00 , -1.9224168108705180e+00 , 1.8552413600000000e+00 , -7.0937100000000003e-02 , 1.9830500000000001e-01 , 9.7757000000000005e-01 -3.5782464421004372e+00 , -2.1003463707229741e+00 , 1.8915685600000001e+00 , -6.2161700000000000e-02 , 1.8946499999999999e-01 , 9.7991799999999996e-01 -3.6180974761366951e+00 , -2.2883054603414399e+00 , 1.9316653440000000e+00 , -6.9569300000000001e-02 , 1.8144500000000000e-01 , 9.8093699999999995e-01 -3.6658953301579209e+00 , -2.5163887736409709e+00 , 1.9692305600000000e+00 , -8.0668299999999998e-02 , 1.7262500000000000e-01 , 9.8167899999999997e-01 -3.7191749331016153e+00 , -2.7641594684370601e+00 , 2.0104368159999999e+00 , -2.6457100000000001e-02 , 2.3021200000000000e-01 , 9.7278100000000001e-01 -3.7735915295799476e+00 , -3.0212925009179692e+00 , 2.0580949199999998e+00 , -3.2389099999999997e-02 , -2.9532300000000000e-01 , -9.5484800000000003e-01 -3.7877866141299705e+00 , -3.1197232343323815e+00 , 2.1417790399999999e+00 , 6.1158600000000000e-02 , 3.1353300000000001e-01 , 9.4760599999999995e-01 -3.8319781028893338e+00 , -3.3371089827277851e+00 , 2.2105968800000002e+00 , 3.2390299999999997e-02 , 2.9650500000000002e-01 , 9.5448200000000005e-01 -3.8929562689128048e+00 , -3.6334479408450298e+00 , 2.2758912000000002e+00 , -3.4626200000000003e-02 , 2.3536099999999999e-01 , 9.7129100000000002e-01 -3.9609012840948301e+00 , -3.9605381779277335e+00 , 2.3481441599999999e+00 , -4.9463800000000002e-02 , 2.1939600000000001e-01 , 9.7438100000000005e-01 -4.0346091317971435e+00 , -4.3169577509653747e+00 , 2.4288481600000003e+00 , -5.7022600000000000e-02 , 2.1486300000000000e-01 , 9.7497800000000001e-01 -4.1220090971793670e+00 , -4.7329657208158142e+00 , 2.5171628799999999e+00 , -6.9424200000000005e-02 , 2.1375900000000000e-01 , 9.7441599999999995e-01 -4.2136099602663597e+00 , -5.1784604736232938e+00 , 2.6181562400000002e+00 , -7.3700399999999999e-02 , 2.1295000000000000e-01 , 9.7428000000000003e-01 -4.3231976307712543e+00 , -5.7040128212729231e+00 , 2.7313935200000001e+00 , -7.0504899999999995e-02 , 2.0994099999999999e-01 , 9.7516899999999995e-01 -4.4472267421475484e+00 , -6.3000270438274928e+00 , 2.8616348000000000e+00 , -7.5188300000000000e-02 , 2.0555699999999999e-01 , 9.7575299999999998e-01 -4.6057701952156247e+00 , -7.0550090981149189e+00 , 3.0113511200000000e+00 , -5.4887100000000001e-02 , 1.8741400000000000e-01 , 9.8074600000000001e-01 -4.7938595522391729e+00 , -7.9509715083877239e+00 , 3.1896144000000000e+00 , 3.0229499999999999e-02 , -1.7811700000000000e-01 , -9.8354500000000000e-01 -5.0277661490539165e+00 , -9.0663458693317409e+00 , 3.4057680000000001e+00 , -2.4231400000000000e-02 , 2.0291200000000001e-01 , 9.7889700000000002e-01 -5.2740148870841406e+00 , -1.0250018442435568e+01 , 3.6651648000000003e+00 , -1.6121799999999999e-02 , 2.1122400000000000e-01 , 9.7730499999999998e-01 -5.5508411401584148e+00 , -1.1590167309105716e+01 , 3.9768319999999999e+00 , 4.8669700000000000e-03 , -2.2548699999999999e-01 , -9.7423400000000004e-01 -5.8823274128266245e+00 , -1.3196727393533280e+01 , 4.3585224000000000e+00 , 1.7297799999999999e-01 , 3.7042999999999998e-01 , 9.1261199999999998e-01 -6.0571934972956711e+00 , -1.4108571029695458e+01 , 4.7291160000000003e+00 , 2.9700199999999999e-01 , 4.4024700000000000e-01 , 8.4733300000000000e-01 -6.0761317369499865e+00 , -1.4315476924852195e+01 , 5.0501015999999996e+00 , 2.9700199999999999e-01 , 4.4024700000000000e-01 , 8.4733300000000000e-01 -6.3896173499774624e+00 , -1.5897353154588384e+01 , 5.5662224000000009e+00 , 3.3616600000000002e-01 , 2.6422499999999999e-01 , 9.0397899999999998e-01 -7.2457501865053464e+00 , -2.1110428243373779e+01 , 9.3037016000000001e+00 , 7.4743099999999996e-01 , -5.6447899999999995e-01 , 3.5030099999999997e-01 -7.1922473346330262e+00 , -2.1038503921275002e+01 , 9.7285208000000001e+00 , -7.5909300000000002e-01 , 5.6292500000000001e-01 , -3.2694499999999999e-01 -7.1598192480662322e+00 , -2.1075214147978620e+01 , 1.0187368800000000e+01 , 7.7265200000000001e-01 , -5.5852800000000002e-01 , 3.0175500000000000e-01 -6.9343036058346792e+00 , -2.0141909228746684e+01 , 1.0339687200000000e+01 , 3.6709100000000000e-01 , 7.9451700000000003e-01 , 4.8372199999999999e-01 -6.9918768064466965e+00 , -2.0630571919211636e+01 , 1.0946111199999999e+01 , 4.8101899999999997e-01 , 7.4988200000000005e-01 , -4.5419999999999999e-01 -6.9284534094064565e+00 , -2.0510147736996146e+01 , 1.1356432800000000e+01 , -3.6024699999999998e-01 , -9.3118800000000002e-01 , 5.5773900000000001e-02 -6.8234794308838644e+00 , -2.0172969735615968e+01 , 1.1684698400000000e+01 , 3.6024699999999998e-01 , 9.3118800000000002e-01 , -5.5773799999999998e-02 -5.4919179902266446e+00 , -1.3445121109050287e+01 , 9.4406071999999988e+00 , 1.1346500000000000e-01 , -8.6911200000000000e-01 , 4.8142499999999999e-01 -5.1726835250597016e+00 , -1.1914072161596403e+01 , 9.1190288000000006e+00 , 1.3816100000000001e-01 , 9.7956299999999996e-01 , 1.4617500000000000e-01 -5.1839862972148660e+00 , -1.2113081586292239e+01 , 9.5039639999999999e+00 , -1.1700700000000000e-01 , -9.8021100000000005e-01 , -1.5967600000000001e-01 -5.1513427133697229e+00 , -1.2080754475298905e+01 , 9.7942695999999998e+00 , 5.1340200000000003e-02 , 9.5264700000000002e-01 , 2.9971300000000001e-01 -5.2636682202585270e+00 , -1.2836021906564262e+01 , 1.0470009600000001e+01 , 2.9327700000000002e-02 , -8.3111999999999997e-01 , 5.5531900000000001e-01 -5.1672176167134083e+00 , -1.2465493790057332e+01 , 1.0612895200000001e+01 , -2.0702600000000002e-02 , -9.8414500000000005e-01 , 1.7615200000000000e-01 -5.1221164905775458e+00 , -1.2376161298334848e+01 , 1.0893695200000000e+01 , -1.1508500000000001e-01 , -9.4280100000000000e-01 , 3.1286000000000003e-01 -5.0902518716628045e+00 , -1.2362564796030361e+01 , 1.1217873600000001e+01 , -5.8533000000000002e-02 , -9.3430100000000005e-01 , 3.5164699999999999e-01 -4.8866333918093510e+00 , -1.1379085433849577e+01 , 1.0991060000000001e+01 , 5.6692100000000001e-01 , -6.2259500000000001e-01 , 5.3942100000000004e-01 -4.8479688489575139e+00 , -1.1316993181627110e+01 , 1.1275146400000001e+01 , -3.0970199999999998e-01 , 8.7351699999999999e-01 , 3.7557099999999999e-01 -4.8480078560087057e+00 , -1.1485071814466609e+01 , 1.1705612799999999e+01 , -3.9179999999999998e-01 , 8.0602399999999996e-01 , 4.4364199999999998e-01 -4.9695365053210629e+00 , -1.2370374919567737e+01 , 1.2613408000000000e+01 , 3.2616000000000001e-01 , 9.2523000000000000e-01 , -1.9382800000000000e-01 -4.9215874674227695e+00 , -1.2278224040463778e+01 , 1.2918024000000001e+01 , 1.2724600000000000e-01 , 9.8466399999999998e-01 , -1.1935300000000000e-01 -4.9016207021192928e+00 , -1.2357931670197518e+01 , 1.3345568000000000e+01 , 1.0071099999999999e-01 , 9.8247200000000001e-01 , 1.5686100000000000e-01 -4.9180998275641343e+00 , -1.2662113151247960e+01 , 1.3947520000000001e+01 , 3.9798899999999998e-01 , -8.7336199999999997e-01 , 2.8078999999999998e-01 -4.8655988783868160e+00 , -1.2553163745182067e+01 , 1.4266384000000002e+01 , 5.0364299999999995e-01 , -7.5785000000000002e-01 , 4.1473800000000000e-01 -4.7623065260151272e+00 , -1.2128418134128792e+01 , 1.4344384000000000e+01 , 5.2704399999999996e-01 , -6.7048700000000006e-01 , 5.2218100000000001e-01 -5.0205819014745030e+00 , -1.4007997180742340e+01 , 1.6259232000000001e+01 , 1.4158000000000001e-01 , 9.5475200000000005e-01 , 2.6154100000000002e-01 -4.8457392301895208e+00 , -1.3142733388797422e+01 , 1.6010463999999999e+01 , -8.8722000000000001e-01 , -2.8494199999999997e-01 , 3.6283300000000002e-01 -4.7829914150767525e+00 , -1.2994688412218089e+01 , 1.6342016000000001e+01 , -8.9831700000000003e-01 , -4.3742900000000001e-01 , -4.1031800000000000e-02 -4.7796781015353051e+00 , -1.3249612168861550e+01 , 1.7036631999999997e+01 , -7.3984700000000003e-01 , -6.7149899999999996e-01 , 4.1419999999999998e-02 -4.5462904741845218e+00 , -1.1941936685139487e+01 , 1.6319967999999999e+01 , 8.4727399999999997e-01 , -3.9598299999999997e-01 , -3.5401100000000002e-01 -3.1359877850495144e+00 , -2.3827337489807201e+00 , 7.6528368000000002e+00 , 4.4501900000000000e-01 , -8.9284100000000000e-01 , 6.9234699999999996e-02 -3.0481616454525868e+00 , -1.8559535778242298e+00 , 7.2920920000000002e+00 , -3.9171699999999998e-01 , 2.8250799999999998e-01 , -8.7564100000000000e-01 -3.0194385350681285e+00 , -1.7415262507250970e+00 , 7.3216175999999997e+00 , -5.3844499999999995e-01 , 4.5674399999999998e-01 , -7.0813999999999999e-01 -2.9868576753836860e+00 , -1.5915364584667433e+00 , 7.3107496000000003e+00 , -4.0370099999999998e-01 , 5.3906299999999996e-01 , -7.3921300000000001e-01 -2.9640337255271914e+00 , -1.5133613804790094e+00 , 7.3724008000000003e+00 , -3.3602799999999999e-01 , -5.3312300000000001e-01 , 7.7644400000000002e-01 -2.9485601244823356e+00 , -1.5019814698815117e+00 , 7.5098783999999998e+00 , 4.9741500000000000e-01 , 7.8295599999999999e-01 , -3.7357400000000002e-01 -2.9280188268505620e+00 , -1.4407677977675433e+00 , 7.5932656000000005e+00 , 3.8634400000000002e-01 , 9.1201699999999997e-01 , -1.3770900000000000e-01 -2.9292940082860377e+00 , -1.5685797886972681e+00 , 7.9078032000000000e+00 , -6.1601700000000004e-01 , -5.8094699999999999e-01 , 5.3200000000000003e-01 -2.8891217826655984e+00 , -1.3516632897307290e+00 , 7.8058832000000002e+00 , -4.4043700000000002e-01 , -7.0150500000000005e-01 , 5.6027300000000002e-01 -2.8611043270365331e+00 , -1.2395654044201359e+00 , 7.8292415999999996e+00 , 5.0335500000000000e-01 , 7.6119599999999998e-01 , -4.0891800000000000e-01 -2.8484146460936111e+00 , -1.2578852316919535e+00 , 8.0254480000000008e+00 , -8.1882999999999995e-01 , -5.2297899999999997e-01 , 2.3666699999999999e-01 -2.8143526416032647e+00 , -1.0834708314591825e+00 , 7.9615712000000007e+00 , 7.7326300000000003e-01 , 5.0196700000000005e-01 , -3.8741900000000001e-01 -2.8272686829499252e+00 , -1.3779965149540199e+00 , 8.5684736000000008e+00 , 4.2598100000000000e-01 , -1.2633200000000000e-01 , 8.9586800000000000e-01 -2.8438341879318454e+00 , -1.7340296152557859e+00 , 9.3082464000000016e+00 , -7.3218799999999995e-01 , 6.3859900000000003e-01 , -2.3683999999999999e-01 -2.7928920633810126e+00 , -1.3980702328519268e+00 , 9.0201144000000006e+00 , -8.2586099999999996e-01 , 1.5479599999999999e-01 , 5.4220999999999997e-01 -2.7426275292384603e+00 , -1.0407822826695301e+00 , 8.6694056000000010e+00 , -3.7824900000000000e-01 , -9.2458700000000005e-01 , 4.5465800000000001e-02 -2.7555936002282992e+00 , -1.4499022837174169e+00 , 9.5770656000000010e+00 , -5.3949000000000003e-01 , 3.0343500000000001e-01 , -7.8541600000000000e-01 -2.7216135636365655e+00 , -1.2933729087357317e+00 , 9.5614656000000018e+00 , -8.1896599999999997e-01 , 1.5410199999999999e-01 , -5.5276300000000000e-01 -2.6893826457633834e+00 , -1.1635271329563657e+00 , 9.5877256000000006e+00 , -8.1896599999999997e-01 , 1.5410199999999999e-01 , -5.5276300000000000e-01 -2.6501253509834020e+00 , -9.0794778234839901e-01 , 9.3721960000000006e+00 , -6.4309700000000003e-01 , 6.4208699999999996e-01 , 4.1731400000000002e-01 -2.6034844628679878e+00 , -4.7687555162198869e-01 , 8.7876328000000008e+00 , 4.0768799999999999e-01 , -9.1288000000000002e-01 , 2.0988000000000000e-02 -2.5515006614607847e+00 , 1.9956626156841928e-01 , 7.6384328000000004e+00 , 3.4117300000000000e-01 , -9.1018600000000005e-01 , -2.3486399999999999e-01 -2.5285926007559629e+00 , 3.2961464174143118e-01 , 7.5622632000000003e+00 , 2.4227199999999999e-01 , -9.6965400000000002e-01 , 3.2790000000000000e-02 -2.5091976000566576e+00 , 3.6301442184861643e-01 , 7.6922632000000002e+00 , 2.4227199999999999e-01 , -9.6965400000000002e-01 , 3.2790199999999999e-02 -2.4920378607699298e+00 , 2.4767989613742314e-01 , 8.1860239999999997e+00 , -2.7661799999999998e-01 , 8.8007199999999997e-01 , -3.8594699999999998e-01 -2.4693252520102176e+00 , 2.7214078661070418e-01 , 8.3763752000000000e+00 , 4.1830099999999998e-01 , -4.9525799999999998e-01 , 7.6140900000000000e-01 -2.4463750701753151e+00 , 3.5532013847963451e-01 , 8.4312144000000000e+00 , 2.5419300000000000e-01 , -8.3283600000000002e-01 , 4.9170100000000000e-01 -2.4219421000116128e+00 , 3.9276036855978469e-01 , 8.6118416000000000e+00 , 2.8080200000000000e-01 , -7.5577899999999998e-01 , 5.9156399999999998e-01 -2.3916969182745804e+00 , 2.9049957089415313e-01 , 9.2151144000000009e+00 , 1.3963600000000001e-01 , -3.5396699999999998e-01 , -9.2477500000000001e-01 -2.3654799490445337e+00 , 3.9753994410906901e-01 , 9.2401575999999999e+00 , -6.0617400000000002e-02 , 7.1242600000000000e-01 , 6.9912399999999997e-01 -2.3461783910959251e+00 , 6.2761142853384810e-01 , 8.8653832000000001e+00 , 4.3179000000000001e-01 , 5.1586500000000002e-01 , 7.3989199999999999e-01 -2.3218991101693600e+00 , 7.3235987504475841e-01 , 8.8741295999999998e+00 , -3.6409300000000000e-01 , -2.9348500000000000e-01 , 8.8391399999999998e-01 -2.2963509225028398e+00 , 8.3125882828400144e-01 , 8.9010448000000011e+00 , -6.1725400000000000e-02 , 2.3857800000000001e-01 , -9.6916000000000002e-01 -2.2729675336254842e+00 , 9.4070939032264622e-01 , 8.8859440000000003e+00 , 4.5905700000000004e-03 , -3.7263499999999999e-01 , 9.2796699999999999e-01 -2.2438327451924471e+00 , 1.0082203661839930e+00 , 9.0408831999999997e+00 , 7.9882100000000000e-01 , -1.3021099999999999e-01 , 5.8730800000000005e-01 -2.2237879134548248e+00 , 1.1365390228305607e+00 , 8.9409288000000000e+00 , -8.9106300000000005e-01 , 1.6264700000000001e-01 , -4.2373699999999997e-01 -2.2008671927359060e+00 , 1.2425900586513825e+00 , 8.9301127999999999e+00 , 6.8035999999999996e-01 , -4.2355799999999999e-02 , 7.3165300000000000e-01 -2.1052084768795449e+00 , 1.0644167212353355e+00 , 1.0481324800000001e+01 , 1.6006799999999999e-01 , 7.1658500000000003e-01 , -6.7888499999999996e-01 -2.0484602750200080e+00 , 1.1062754618967157e+00 , 1.1014272800000001e+01 , 2.1857300000000000e-02 , -9.8724800000000001e-01 , -1.5767999999999999e-01 -2.0111810776747898e+00 , 1.2302197831880448e+00 , 1.1115558400000001e+01 , 3.5733899999999999e-02 , -5.1658499999999996e-01 , 8.5548999999999997e-01 -2.0027649551009725e+00 , 1.4185852460395647e+00 , 1.0731122400000000e+01 , 6.7626600000000003e-01 , -7.1616299999999999e-01 , -1.7255400000000001e-01 -1.9884944938448881e+00 , 1.5792404714824451e+00 , 1.0476676000000001e+01 , 5.8502900000000002e-01 , -7.8625500000000004e-01 , -1.9885900000000001e-01 -1.9907321773686040e+00 , 1.7511285481672478e+00 , 1.0002186400000001e+01 , -4.6353200000000000e-01 , 2.7380199999999999e-01 , 8.4271700000000005e-01 -1.9668695569887320e+00 , 1.8739798236829588e+00 , 9.9586104000000013e+00 , 6.0688100000000000e-01 , -7.8752999999999995e-01 , -1.0719700000000000e-01 -1.9594115478382874e+00 , 2.0071487300245026e+00 , 9.6956880000000005e+00 , -4.6240599999999998e-01 , 8.8085800000000003e-01 , -1.0134300000000000e-01 -1.8993573323430757e+00 , 2.1013447359728845e+00 , 1.0134588800000000e+01 , 7.3463699999999998e-01 , 6.6444999999999999e-01 , 1.3716400000000001e-01 -1.8550747739452997e+00 , 2.2165325980116894e+00 , 1.0343753600000001e+01 , 7.6194300000000004e-01 , 2.5115999999999999e-01 , -5.9696099999999996e-01 -1.8270124007621156e+00 , 2.3408649544599411e+00 , 1.0343524800000001e+01 , -7.8429899999999997e-01 , -2.6741300000000001e-01 , 5.5979000000000001e-01 -1.8426396977123856e+00 , 2.4603806968345578e+00 , 9.8543816000000000e+00 , -5.6019699999999994e-01 , -6.5593299999999999e-01 , -5.0589600000000001e-01 -1.8531996955201133e+00 , 2.5666532604057748e+00 , 9.4565295999999996e+00 , -8.7594700000000003e-01 , -4.5404800000000001e-01 , -1.6296700000000000e-01 -1.8403344371432886e+00 , 2.6705277420272280e+00 , 9.3369192000000005e+00 , 8.3838800000000002e-01 , 4.7874400000000000e-01 , 2.6059500000000002e-01 -1.7963439440974358e+00 , 2.7899865225144866e+00 , 9.5357255999999992e+00 , -6.0383699999999996e-01 , 2.5126900000000002e-01 , -7.5646800000000003e-01 -1.7713311801275655e+00 , 2.9005053927318087e+00 , 9.5255544000000008e+00 , 5.1886900000000002e-01 , -3.8599600000000001e-01 , 7.6274600000000004e-01 -1.7338109350156086e+00 , 3.0222827910339003e+00 , 9.6370943999999987e+00 , -7.9123299999999994e-02 , 7.3667999999999997e-02 , 9.9413899999999999e-01 -1.7115721009625942e+00 , 3.1330159066963805e+00 , 9.6127687999999996e+00 , -4.7160299999999999e-01 , 4.7374300000000003e-01 , 7.4374600000000002e-01 -1.7193084931132034e+00 , 3.2095545679948385e+00 , 9.3197176000000006e+00 , 8.3546899999999993e-02 , -9.4699999999999995e-01 , 3.1017899999999998e-01 -1.7020370860273184e+00 , 3.3100888616235302e+00 , 9.2616440000000004e+00 , 2.6489599999999999e-02 , -9.7659200000000002e-01 , 2.1346499999999999e-01 -2.9832408133177264e+00 , 5.0396265033610388e-01 , 1.3727874400000000e+00 , -5.2851400000000000e-02 , 2.7275600000000000e-01 , 9.6063100000000001e-01 -2.9947875929913117e+00 , 4.4346185340043309e-01 , 1.3806571200000000e+00 , -7.6757599999999995e-02 , 1.8030700000000000e-01 , 9.8061100000000001e-01 -3.0078239725809524e+00 , 3.7447667145508201e-01 , 1.3836138400000000e+00 , -7.8132499999999994e-02 , 1.8441399999999999e-01 , 9.7973800000000000e-01 -3.0145382005333441e+00 , 3.2912578424924099e-01 , 1.4076690400000000e+00 , -1.2342400000000001e-01 , 1.8066599999999999e-01 , 9.7577000000000003e-01 -3.0271584171899519e+00 , 2.5978034227728530e-01 , 1.4139672800000000e+00 , -1.4265700000000001e-01 , 2.1384200000000000e-01 , 9.6639600000000003e-01 -3.0379149096393752e+00 , 1.9847204322711165e-01 , 1.4282173600000001e+00 , -8.9141200000000004e-02 , 1.9740800000000000e-01 , 9.7626000000000002e-01 -3.0511070219732517e+00 , 1.2881806928870665e-01 , 1.4383875200000000e+00 , -9.7367800000000004e-02 , 1.3507600000000000e-01 , 9.8604000000000003e-01 -3.0656512765192825e+00 , 4.9813535889578819e-02 , 1.4446597600000000e+00 , -8.3707400000000001e-02 , 2.3928400000000000e-01 , 9.6733499999999994e-01 -3.0767427853745346e+00 , -1.2477392847824120e-02 , 1.4646059199999999e+00 , -8.4774000000000002e-02 , 2.4775400000000000e-01 , 9.6510700000000005e-01 -3.0892030126791252e+00 , -8.3043756953595338e-02 , 1.4806510400000001e+00 , -6.2120399999999999e-02 , 2.0220199999999999e-01 , 9.7737200000000002e-01 -3.1029549138399544e+00 , -1.6284559977481594e-01 , 1.4933026400000000e+00 , -1.0957200000000000e-01 , 1.8400200000000000e-01 , 9.7680000000000000e-01 -3.1158966864834650e+00 , -2.3466201335423476e-01 , 1.5138291200000000e+00 , 1.0749300000000001e-01 , -1.7169400000000001e-01 , -9.7926800000000003e-01 -3.1316156281997456e+00 , -3.2418851119858116e-01 , 1.5260501600000000e+00 , -1.1927800000000000e-01 , 2.0112400000000000e-01 , 9.7227699999999995e-01 -3.1465697229099892e+00 , -4.0471230600556396e-01 , 1.5459401600000000e+00 , -9.7121600000000002e-02 , 1.9468700000000000e-01 , 9.7604500000000005e-01 -3.1641389284145287e+00 , -5.0376428869192535e-01 , 1.5587415199999999e+00 , -8.5808800000000005e-02 , 2.1308800000000000e-01 , 9.7325799999999996e-01 -3.1759789538762417e+00 , -5.7583587205364983e-01 , 1.5882785600000000e+00 , -9.1840400000000003e-02 , 2.0435100000000000e-01 , 9.7458000000000000e-01 -3.1963710822504936e+00 , -6.8432228706496101e-01 , 1.6022925600000000e+00 , 1.1989700000000000e-01 , -1.7547199999999999e-01 , -9.7715600000000002e-01 -3.2139167368376764e+00 , -7.8372922405019985e-01 , 1.6238257599999999e+00 , -9.4217899999999993e-02 , 1.9134300000000001e-01 , 9.7699100000000005e-01 -3.2334929581439500e+00 , -8.9297527695552636e-01 , 1.6444208800000000e+00 , 1.1604000000000000e-01 , -1.8217700000000001e-01 , -9.7639500000000001e-01 -3.2550382861667178e+00 , -1.0119561775763879e+00 , 1.6645854400000000e+00 , -9.6667199999999995e-02 , 1.7142800000000000e-01 , 9.8044299999999995e-01 -3.2784479903080208e+00 , -1.1415739123469693e+00 , 1.6850297599999999e+00 , -1.0787200000000000e-01 , 1.6366000000000000e-01 , 9.8060099999999994e-01 -3.3037737080013567e+00 , -1.2797275436157762e+00 , 1.7056477600000000e+00 , -9.6786700000000003e-02 , 1.7357500000000001e-01 , 9.8005299999999995e-01 -3.3261656869995555e+00 , -1.4097532004420144e+00 , 1.7343944000000000e+00 , -8.2707400000000000e-02 , 1.9300999999999999e-01 , 9.7770500000000005e-01 -3.3537248391443284e+00 , -1.5585006886047346e+00 , 1.7608831999999999e+00 , -8.1868600000000000e-02 , 1.9099600000000000e-01 , 9.7817100000000001e-01 -3.3796152873371450e+00 , -1.7083080234359533e+00 , 1.7923119999999999e+00 , 8.9411199999999996e-02 , -1.9533000000000000e-01 , -9.7665299999999999e-01 -3.4082456832527814e+00 , -1.8674074376272829e+00 , 1.8256606399999999e+00 , -8.4935499999999997e-02 , 2.0791999999999999e-01 , 9.7445099999999996e-01 -3.4384781964784690e+00 , -2.0366874953093186e+00 , 1.8615156800000001e+00 , -1.0188000000000000e-01 , 1.9551700000000000e-01 , 9.7539399999999998e-01 -3.4724366168177174e+00 , -2.2261488110551788e+00 , 1.8981294000000000e+00 , -1.2279600000000000e-01 , 1.6446700000000000e-01 , 9.7870900000000005e-01 -3.5144465877398909e+00 , -2.4548323640479186e+00 , 1.9315008160000000e+00 , -1.1556100000000000e-01 , 1.9893900000000000e-01 , 9.7317500000000001e-01 -3.5532851341104568e+00 , -2.6749692168510508e+00 , 1.9750250240000000e+00 , 4.1660900000000001e-02 , -2.4298000000000000e-01 , -9.6913600000000000e-01 -3.5923197834519884e+00 , -2.8936549849236526e+00 , 2.0257574720000000e+00 , 1.5745100000000001e-02 , 2.9638500000000001e-01 , 9.5493899999999998e-01 -3.6059583111725120e+00 , -3.0027570043601877e+00 , 2.1037771279999999e+00 , 2.5549200000000001e-02 , 3.1807900000000000e-01 , 9.4772000000000001e-01 -3.6497306899343509e+00 , -3.2518712750884626e+00 , 2.1626341600000001e+00 , 7.4648099999999997e-03 , 2.8727999999999998e-01 , 9.5781799999999995e-01 -3.6945796214974695e+00 , -3.5102434086809016e+00 , 2.2284484800000000e+00 , -5.1328699999999998e-02 , 2.3610500000000001e-01 , 9.7037099999999998e-01 -3.7507374038055161e+00 , -3.8293874117943245e+00 , 2.2954286399999999e+00 , -7.3901099999999997e-02 , 2.1077099999999999e-01 , 9.7473799999999999e-01 -3.8127328396268152e+00 , -4.1780047567563514e+00 , 2.3702503999999998e+00 , -7.9419900000000002e-02 , 2.1461000000000000e-01 , 9.7346600000000005e-01 -3.8813613098611910e+00 , -4.5666412395798135e+00 , 2.4533724000000001e+00 , -8.1670800000000002e-02 , 2.0562300000000000e-01 , 9.7521700000000000e-01 -3.9613808297903335e+00 , -5.0155023531728498e+00 , 2.5456807200000000e+00 , -9.1027499999999997e-02 , 2.1076300000000001e-01 , 9.7328999999999999e-01 -4.0464466691167686e+00 , -5.4946339114204816e+00 , 2.6522110400000001e+00 , -8.8784900000000000e-02 , 2.0933399999999999e-01 , 9.7380500000000003e-01 -4.1451691479811306e+00 , -6.0534062270685070e+00 , 2.7722031199999999e+00 , -8.6784000000000000e-02 , 2.0652899999999999e-01 , 9.7458400000000001e-01 -4.2638036683772071e+00 , -6.7231074229499566e+00 , 2.9097576800000002e+00 , -8.0987199999999995e-02 , 2.0222000000000001e-01 , 9.7598600000000002e-01 -4.3988839523260417e+00 , -7.4822196171674342e+00 , 3.0708152000000002e+00 , -5.9764499999999998e-02 , 1.9230100000000000e-01 , 9.7951400000000000e-01 -4.5904760114965928e+00 , -8.5452508003282386e+00 , 3.2637976000000002e+00 , -3.5959600000000001e-02 , 1.8712999999999999e-01 , 9.8167700000000002e-01 -4.7775924290105110e+00 , -9.6048703507053208e+00 , 3.4942200000000003e+00 , 2.5146900000000000e-02 , -2.1127399999999999e-01 , -9.7710300000000005e-01 -5.0057212125244064e+00 , -1.0895041687870366e+01 , 3.7743440000000001e+00 , -2.1197000000000001e-02 , 2.2009100000000001e-01 , 9.7524900000000003e-01 -5.2559796886687042e+00 , -1.2322603189967884e+01 , 4.1102328000000004e+00 , -1.1309000000000000e-01 , -3.3110899999999999e-01 , -9.3679100000000004e-01 -5.4420467316560979e+00 , -1.3437827614306668e+01 , 4.4698440000000002e+00 , 3.0845600000000001e-01 , 4.3837300000000001e-01 , 8.4420700000000004e-01 -5.4761285785780949e+00 , -1.3761998430313428e+01 , 4.7862743999999999e+00 , -3.0553200000000003e-01 , -4.8197299999999998e-01 , -8.2118899999999995e-01 -5.5257655106745638e+00 , -1.4171516184506949e+01 , 5.1257616000000006e+00 , -3.0553300000000000e-01 , -4.8197299999999998e-01 , -8.2118899999999995e-01 -6.1237297751362618e+00 , -1.7573116560558201e+01 , 5.9037648000000003e+00 , 4.3555500000000003e-01 , 5.9321699999999999e-01 , 6.7704200000000003e-01 -8.2861156669945366e+00 , -2.9626877508069537e+01 , 8.1842456000000006e+00 , 6.4887500000000001e-02 , 1.8368899999999999e-01 , 9.8084000000000005e-01 -1.0491138796530789e+01 , -4.2136461864545176e+01 , 1.0983779999999999e+01 , 5.4297300000000004e-01 , 3.0966800000000000e-01 , 7.8056700000000001e-01 -1.0339429032581242e+01 , -4.1706462584649991e+01 , 1.1710261600000001e+01 , 5.4297300000000004e-01 , 3.0966800000000000e-01 , 7.8056700000000001e-01 -1.0169496493297030e+01 , -4.1173935889076205e+01 , 1.2403952000000000e+01 , 5.4297300000000004e-01 , 3.0966800000000000e-01 , 7.8056800000000004e-01 -6.1865590978091562e+00 , -2.0012173043614283e+01 , 1.0407547200000000e+01 , 2.0372499999999999e-01 , 9.5287800000000000e-01 , 2.2476599999999999e-01 -6.1277709257670718e+00 , -1.9898874013005241e+01 , 1.0804504800000000e+01 , 3.2220599999999999e-01 , 9.4157999999999997e-01 , 9.8034200000000002e-02 -6.0901164793655189e+00 , -1.9914890051122395e+01 , 1.1249250399999999e+01 , 3.3363999999999999e-01 , 9.4148600000000005e-01 , -4.7837400000000002e-02 -5.0261544445269823e+00 , -1.3569566666822020e+01 , 9.2450767999999997e+00 , -4.0410299999999999e-01 , 3.3040100000000000e-01 , -8.5295699999999997e-01 -5.0089274718383336e+00 , -1.3647339414979163e+01 , 9.5988223999999995e+00 , -8.0594100000000002e-02 , -9.2766099999999996e-01 , 3.6462200000000000e-01 -4.8988613692054841e+00 , -1.3140135871581487e+01 , 9.7106016000000004e+00 , 2.7791000000000000e-02 , -7.1827600000000003e-01 , 6.9520300000000002e-01 -4.8633602985319904e+00 , -1.3103506700810392e+01 , 1.0016455199999999e+01 , 5.8088799999999996e-01 , -5.8906800000000004e-01 , 5.6175500000000000e-01 -4.7234868695705661e+00 , -1.2389796576123810e+01 , 1.0008426399999999e+01 , -8.2002600000000003e-01 , 5.7176300000000002e-01 , -2.5374100000000000e-02 -4.7172068878148776e+00 , -1.2541328771109923e+01 , 1.0398696800000002e+01 , 2.6717999999999997e-01 , -8.3839200000000003e-01 , 4.7509400000000002e-01 -4.6677600724652883e+00 , -1.2418601971722998e+01 , 1.0660100799999999e+01 , -2.7899499999999999e-01 , 9.6008300000000002e-01 , -2.0081499999999999e-02 -4.6414144819283756e+00 , -1.2445271650530884e+01 , 1.1001699200000001e+01 , -1.7990100000000001e-01 , 9.6235800000000005e-01 , -2.0372000000000001e-01 -4.6084997974487774e+00 , -1.2428280088898623e+01 , 1.1326252000000000e+01 , -1.7249400000000001e-01 , 9.6312699999999996e-01 , -2.0647399999999999e-01 -4.5575484494091096e+00 , -1.2288985950246783e+01 , 1.1585336800000000e+01 , -4.5465000000000000e-01 , 7.5025600000000003e-01 , -4.8000999999999999e-01 -4.5398570078115688e+00 , -1.2392426623722544e+01 , 1.1990624800000001e+01 , 3.2699899999999998e-01 , 9.1559699999999999e-01 , -2.3399700000000001e-01 -4.4794980582741264e+00 , -1.2189354166822435e+01 , 1.2215992800000000e+01 , 3.1889200000000001e-01 , 9.4557100000000005e-01 , -6.4834000000000003e-02 -4.4606339709051106e+00 , -1.2294412045482533e+01 , 1.2639200000000001e+01 , -2.7233400000000002e-01 , -9.6215799999999996e-01 , 9.2827099999999996e-03 -4.4265984577764748e+00 , -1.2294626125445339e+01 , 1.3004968000000000e+01 , -3.0173499999999999e-02 , 9.5311999999999997e-01 , 3.0108400000000002e-01 -4.3382966242725338e+00 , -1.1889444331873229e+01 , 1.3094616000000000e+01 , 1.3688800000000001e-01 , 9.8769300000000004e-01 , 7.5663700000000000e-02 -4.3976435568522181e+00 , -1.2606107465276633e+01 , 1.3987768000000001e+01 , 4.7820699999999999e-01 , -8.7046299999999999e-01 , -1.1667600000000000e-01 -4.3682424460185727e+00 , -1.2668732903590367e+01 , 1.4435280000000001e+01 , 6.3742500000000002e-01 , -6.5864699999999998e-01 , 3.9984199999999998e-01 -4.2910844690098919e+00 , -1.2361995501112714e+01 , 1.4607816000000000e+01 , 1.6208500000000001e-01 , -2.8537899999999999e-01 , 9.4460900000000003e-01 -4.2653928411190067e+00 , -1.2463556089720237e+01 , 1.5104936000000000e+01 , -3.3558900000000003e-01 , 5.3586100000000003e-01 , 7.7474699999999996e-01 -3.0510721487129464e+00 , -2.6210593259629587e+00 , 7.2897936000000003e+00 , -3.6511800000000000e-01 , -2.2876500000000000e-01 , 9.0241600000000000e-01 -3.0236422368930227e+00 , -2.5094047503972838e+00 , 7.3427088000000005e+00 , -2.5337399999999999e-01 , -9.0439800000000004e-01 , 3.4331699999999998e-01 -2.9941452523302803e+00 , -2.3676292251849986e+00 , 7.3655368000000001e+00 , 2.5337399999999999e-01 , 9.0439800000000004e-01 , -3.4331699999999998e-01 -3.0163248039701740e+00 , -2.6970778673676232e+00 , 7.8221072000000005e+00 , -3.2054899999999997e-01 , 9.4700300000000004e-01 , 2.0831499999999999e-02 -2.9694007333430865e+00 , -2.4077587203818069e+00 , 7.7091424000000002e+00 , -1.3559800000000000e-02 , -7.4395900000000004e-01 , -6.6808699999999999e-01 -2.8867679313869181e+00 , -1.7549220549963147e+00 , 7.2215176000000003e+00 , 1.7505999999999999e-01 , -1.5180500000000000e-02 , 9.8444100000000001e-01 -2.8709943336512715e+00 , -1.7356443137481183e+00 , 7.3454543999999995e+00 , 1.7505999999999999e-01 , -1.5180400000000000e-02 , 9.8444100000000001e-01 -2.8437909645770012e+00 , -1.5989855112760893e+00 , 7.3486576000000001e+00 , -2.0874899999999999e-01 , -5.0123799999999996e-01 , 8.3975299999999997e-01 -2.8180241326423028e+00 , -1.4700153743480042e+00 , 7.3560728000000006e+00 , 3.7970499999999997e-02 , -8.9963700000000002e-01 , 4.3498399999999998e-01 -2.7976065753645991e+00 , -1.4042348865558658e+00 , 7.4305160000000008e+00 , -1.8324399999999999e-01 , 8.8574799999999998e-01 , -4.2646499999999998e-01 -2.7970174519077511e+00 , -1.5506872235788087e+00 , 7.7575648000000008e+00 , -7.1742000000000000e-02 , -9.5945400000000003e-01 , 2.7258300000000002e-01 -2.7668597193252213e+00 , -1.3789513565928444e+00 , 7.7128656000000007e+00 , 6.5406699999999995e-01 , -6.8266099999999996e-01 , 3.2583699999999999e-01 -2.7504160316001700e+00 , -1.3578038712765785e+00 , 7.8511959999999998e+00 , -9.2272200000000004e-01 , -1.0607700000000000e-01 , 3.7058400000000002e-01 -2.7210619811867263e+00 , -1.1826897980814022e+00 , 7.7917911999999996e+00 , 3.0102800000000002e-01 , -8.6507299999999998e-01 , 4.0128700000000000e-01 -2.7116598090379060e+00 , -1.2745283785246651e+00 , 8.0875984000000010e+00 , -3.0867400000000000e-01 , 9.0793999999999997e-01 , -2.8348800000000002e-01 -2.7159111621091800e+00 , -1.5971695068721496e+00 , 8.7269696000000003e+00 , -9.5350400000000002e-01 , 1.9008500000000000e-01 , 2.3387600000000000e-01 -2.6954424972725102e+00 , -1.5770395437648621e+00 , 8.9068375999999994e+00 , 8.2036299999999995e-01 , 2.0071100000000000e-01 , -5.3546199999999999e-01 -2.6700604245669082e+00 , -1.4830306644861406e+00 , 8.9833087999999996e+00 , -8.9125100000000002e-01 , 6.2923599999999996e-02 , 4.4912400000000002e-01 -2.6307815668353323e+00 , -1.1257017813897900e+00 , 8.6456416000000011e+00 , 2.2147200000000000e-01 , 9.5448900000000003e-01 , -1.9975299999999999e-01 -2.6125214120169282e+00 , -1.1658432713941145e+00 , 8.9273671999999991e+00 , 6.8603300000000000e-01 , -3.9372299999999999e-01 , -6.1183399999999999e-01 -2.5997589728265971e+00 , -1.3767557848159733e+00 , 9.5168600000000012e+00 , 6.7861199999999999e-01 , -1.0063600000000000e-01 , 7.2757000000000005e-01 -2.5754454742019877e+00 , -1.3642390295502409e+00 , 9.7530023999999997e+00 , 2.2336000000000000e-01 , 6.2002099999999997e-02 , 9.7276200000000002e-01 -2.5302228553056199e+00 , -6.1015102239163310e-01 , 8.6375191999999998e+00 , 3.0878100000000003e-01 , -9.4959300000000002e-01 , -5.4097300000000001e-02 -2.5092699325561472e+00 , -6.3082502923866590e-01 , 8.9098848000000004e+00 , 4.3353000000000003e-01 , 2.8129399999999999e-01 , 8.5611000000000004e-01 -2.4764961654417541e+00 , 1.8026604925795975e-01 , 7.5371472000000006e+00 , -6.0105600000000003e-01 , 7.8494900000000001e-01 , -1.5029100000000001e-01 -2.4581530155587692e+00 , 2.4310318714273893e-01 , 7.6027192000000001e+00 , 5.5254999999999999e-01 , -8.2733400000000001e-01 , -1.0102800000000001e-01 -2.4392598474723446e+00 , 3.1578244031813885e-01 , 7.6484480000000001e+00 , 5.5254999999999999e-01 , -8.2733400000000001e-01 , -1.0102800000000001e-01 -2.4176695112684490e+00 , 2.1072372290726182e-01 , 8.1026784000000003e+00 , 3.2498699999999998e-02 , -9.9707500000000004e-01 , 6.9171499999999997e-02 -2.3953031593491323e+00 , 1.9730799333805371e-01 , 8.3791520000000013e+00 , -7.2887400000000002e-01 , -4.5411200000000001e-03 , -6.8463200000000002e-01 -2.3742603118623520e+00 , 2.9956087476220961e-01 , 8.3867647999999999e+00 , 6.7727899999999996e-01 , -1.4458499999999999e-01 , 7.2137899999999999e-01 -2.3532566253379286e+00 , 3.9805460349091271e-01 , 8.4021152000000008e+00 , 5.9192900000000004e-01 , -5.9289499999999995e-01 , 5.4598199999999997e-01 -2.3205758817902278e+00 , 2.9589433834745082e-01 , 8.9737407999999999e+00 , 7.7577099999999999e-01 , 4.2413099999999998e-01 , -4.6721800000000002e-01 -2.2911662642100610e+00 , 3.1774551809442375e-01 , 9.2445567999999998e+00 , 4.3988800000000000e-01 , 8.9719700000000002e-01 , -3.9184200000000002e-02 -2.2744111337242705e+00 , 5.0166370642407676e-01 , 9.0313152000000017e+00 , 1.9803100000000001e-01 , -6.3641599999999998e-01 , -7.4549200000000004e-01 -2.2613159213546332e+00 , 6.9462200864315160e-01 , 8.7635047999999998e+00 , -3.6409300000000000e-01 , -2.9348500000000000e-01 , 8.8391399999999998e-01 -2.2376594449691720e+00 , 7.7713822284327660e-01 , 8.8412655999999998e+00 , 4.0854600000000002e-01 , 2.6417200000000002e-01 , -8.7367200000000000e-01 -2.2149190384616748e+00 , 8.7130057950727124e-01 , 8.8874519999999997e+00 , 3.8673299999999999e-01 , 9.4217300000000004e-02 , 9.1736600000000001e-01 -2.1923324486623406e+00 , 9.6519699368999312e-01 , 8.9323072000000003e+00 , -5.7215300000000002e-01 , -4.3010700000000002e-01 , 6.9831900000000002e-01 -2.1663499842210401e+00 , 1.0455130895111804e+00 , 9.0460728000000010e+00 , 4.2940400000000001e-01 , 2.8306500000000001e-01 , 8.5760499999999995e-01 -2.1433854269651342e+00 , 1.1452541162823220e+00 , 9.0777096000000004e+00 , -2.9778700000000002e-01 , 8.5995800000000000e-01 , 4.1448099999999999e-01 -2.0439805606801573e+00 , 9.7608293749586772e-01 , 1.0514688000000001e+01 , 3.3448600000000001e-01 , -6.1655300000000002e-01 , 7.1272800000000003e-01 -2.0179229745816700e+00 , 1.1070527712906402e+00 , 1.0516206400000002e+01 , 3.3448699999999998e-01 , -6.1655300000000002e-01 , 7.1272800000000003e-01 -1.9607621534045709e+00 , 1.1574104704765054e+00 , 1.1028011200000000e+01 , -8.2869999999999999e-01 , 4.2936599999999998e-02 , 5.5804299999999996e-01 -1.9952019070756495e+00 , 1.4289826767248184e+00 , 1.0080155200000000e+01 , 1.4391299999999999e-02 , 3.3091700000000002e-01 , 9.4355000000000000e-01 -1.9662930565568424e+00 , 1.5432269745560943e+00 , 1.0145623199999999e+01 , 4.5214199999999999e-01 , -4.2123400000000000e-01 , -7.8621200000000002e-01 -1.9541732751180725e+00 , 1.6828521125070222e+00 , 9.9822600000000001e+00 , 6.0873299999999997e-01 , -3.7801600000000002e-01 , -6.9752999999999998e-01 -1.9551033775501445e+00 , 1.8304962686280060e+00 , 9.6612120000000008e+00 , -1.3819799999999999e-01 , 6.9244499999999998e-01 , 7.0811100000000005e-01 -1.9281665903049441e+00 , 1.9401903658811031e+00 , 9.7097903999999993e+00 , 3.9585199999999998e-01 , 8.2434700000000005e-01 , -4.0466500000000000e-01 -1.8927971241322765e+00 , 2.0462248886109777e+00 , 9.8701480000000004e+00 , 2.7951300000000001e-01 , 9.3348200000000003e-01 , -2.2468700000000000e-01 -1.8344221400152898e+00 , 2.1477367769047766e+00 , 1.0287760000000000e+01 , 7.0731999999999995e-01 , 5.0821799999999995e-01 , -4.9133800000000000e-01 -1.8023547878458930e+00 , 2.2701080558726874e+00 , 1.0371802400000002e+01 , -7.8429899999999997e-01 , -2.6741300000000001e-01 , 5.5979000000000001e-01 -1.8057262123766384e+00 , 2.3961358599504603e+00 , 1.0070472799999999e+01 , -2.3156900000000000e-01 , -3.6753500000000000e-01 , 9.0071900000000005e-01 -1.8405538114488733e+00 , 2.5066920795488716e+00 , 9.4566336000000000e+00 , -3.5808699999999999e-01 , -8.1091299999999999e-01 , -4.6281000000000000e-01 -1.7955053042352849e+00 , 2.6246099494481960e+00 , 9.6897288000000010e+00 , -2.9136599999999999e-02 , 6.9079999999999997e-01 , 7.2245899999999996e-01 -1.7978079793107815e+00 , 2.7260050517433636e+00 , 9.4451000000000001e+00 , -8.7301600000000001e-01 , 2.4147700000000000e-01 , -4.2371300000000001e-01 -1.7689096032281544e+00 , 2.8409263657735671e+00 , 9.5191896000000007e+00 , -5.2131899999999998e-01 , 4.1385600000000002e-02 , -8.5235799999999995e-01 -1.5908245935305940e+00 , 3.0733301385871012e+00 , 1.0940380800000000e+01 , -5.9260100000000004e-01 , -2.4844800000000000e-01 , 7.6622299999999999e-01 -1.7102071427196630e+00 , 3.0779413060916143e+00 , 9.6500735999999989e+00 , 1.8004200000000001e-01 , 9.3481999999999996e-02 , 9.7920700000000005e-01 -1.7234786212381610e+00 , 3.1556232079922255e+00 , 9.3375535999999997e+00 , 1.9602400000000000e-01 , 4.2279600000000001e-01 , 8.8476999999999995e-01 -1.7082078855327023e+00 , 3.2573270875145761e+00 , 9.2804263999999996e+00 , 7.1456400000000003e-02 , 9.5940099999999995e-01 , -2.7284500000000000e-01 -2.9424421591021783e+00 , 4.5745903276480360e-01 , 1.3651808800000000e+00 , -6.6146099999999999e-02 , 1.5063099999999999e-01 , 9.8637500000000000e-01 -2.9490420107477844e+00 , 4.0394592143542574e-01 , 1.3803253600000001e+00 , -4.7777000000000000e-02 , 1.9815900000000000e-01 , 9.7900500000000001e-01 -2.9609602215921207e+00 , 3.3513731337552999e-01 , 1.3838644800000000e+00 , -6.8226400000000006e-02 , 1.7809300000000000e-01 , 9.8164600000000002e-01 -2.9699024976603194e+00 , 2.7342941988633584e-01 , 1.3957381600000001e+00 , -1.2264500000000000e-01 , 2.3196200000000000e-01 , 9.6496199999999999e-01 -2.9769449414332221e+00 , 2.1874325506829906e-01 , 1.4156676799999999e+00 , -9.3023599999999998e-02 , 2.1415100000000001e-01 , 9.7236100000000003e-01 -2.9881825069359040e+00 , 1.4892652840006204e-01 , 1.4246772000000001e+00 , -9.6436499999999994e-02 , 1.7861800000000000e-01 , 9.7918099999999997e-01 -2.9981377792537662e+00 , 7.8478464695239003e-02 , 1.4354848800000000e+00 , -5.6045299999999999e-02 , 1.6193900000000000e-01 , 9.8520799999999997e-01 -3.0088698507543068e+00 , 7.3601671093033172e-03 , 1.4484453600000000e+00 , -8.9300400000000002e-02 , 2.4611600000000000e-01 , 9.6511800000000003e-01 -3.0151539830690783e+00 , -4.7097700187792135e-02 , 1.4746512800000000e+00 , 7.5427700000000000e-02 , -2.3400000000000001e-01 , -9.6930600000000000e-01 -3.0280162002953457e+00 , -1.2713294849091605e-01 , 1.4859633600000000e+00 , -1.3008900000000001e-01 , 1.6217599999999999e-01 , 9.7814900000000005e-01 -3.0421641332015001e+00 , -2.1529067327295248e-01 , 1.4940826400000000e+00 , -8.2480999999999999e-02 , 2.0870500000000000e-01 , 9.7449399999999997e-01 -3.0533832663196261e+00 , -2.9643363246506116e-01 , 1.5101308800000000e+00 , -9.0270600000000006e-02 , 2.0019000000000001e-01 , 9.7558999999999996e-01 -3.0653711742830394e+00 , -3.7712363060933640e-01 , 1.5285316000000000e+00 , -7.5857200000000000e-02 , 1.9614999999999999e-01 , 9.7763500000000003e-01 -3.0784968796007011e+00 , -4.6787616407929722e-01 , 1.5446547200000000e+00 , -9.8497799999999996e-02 , 2.1997500000000000e-01 , 9.7052000000000005e-01 -3.0923709191337139e+00 , -5.5815865697426936e-01 , 1.5633331200000000e+00 , -1.2146899999999999e-01 , 2.1590400000000001e-01 , 9.6882999999999997e-01 -3.1048673762364478e+00 , -6.4890079556038627e-01 , 1.5846187999999999e+00 , -1.1710900000000000e-01 , 1.8254000000000001e-01 , 9.7619900000000004e-01 -3.1218851792682267e+00 , -7.5903686886453992e-01 , 1.6002853600000000e+00 , -1.1584500000000000e-01 , 1.9637199999999999e-01 , 9.7366200000000003e-01 -3.1361130572309843e+00 , -8.5909512941915089e-01 , 1.6231643199999999e+00 , -1.0872600000000000e-01 , 1.9615700000000000e-01 , 9.7452600000000000e-01 -3.1547073577289986e+00 , -9.7936398199352270e-01 , 1.6415379999999999e+00 , 1.2235500000000001e-01 , -1.7195700000000000e-01 , -9.7747600000000001e-01 -3.1718648946393868e+00 , -1.0989053746629707e+00 , 1.6632261600000000e+00 , -1.0940600000000000e-01 , 1.7910899999999999e-01 , 9.7772700000000001e-01 -3.1919076486296740e+00 , -1.2290888972543588e+00 , 1.6854218400000001e+00 , -1.0878699999999999e-01 , 1.7379300000000000e-01 , 9.7875500000000004e-01 -3.2114852788445489e+00 , -1.3584541140398607e+00 , 1.7115622400000001e+00 , 7.5075000000000003e-02 , -1.9651700000000000e-01 , -9.7762199999999999e-01 -3.2317802537194638e+00 , -1.4993359827259942e+00 , 1.7386708799999999e+00 , -7.4477900000000000e-02 , 1.9129900000000000e-01 , 9.7870199999999996e-01 -3.2561498804620239e+00 , -1.6588215790082605e+00 , 1.7639012800000000e+00 , 7.8628199999999995e-02 , -1.9724600000000000e-01 , -9.7719599999999995e-01 -3.2776064494461514e+00 , -1.8091138562158049e+00 , 1.7972582399999999e+00 , -8.6971599999999996e-02 , 2.0215200000000000e-01 , 9.7548500000000005e-01 -3.3029313221548509e+00 , -1.9798344258887721e+00 , 1.8301607200000001e+00 , -1.0077800000000001e-01 , 1.8359800000000001e-01 , 9.7782199999999997e-01 -3.3310434572001708e+00 , -2.1697910932749780e+00 , 1.8630860800000000e+00 , -1.2873699999999999e-01 , 1.5714800000000001e-01 , 9.7914800000000002e-01 -3.3649909365255146e+00 , -2.3899007081497334e+00 , 1.8951264000000001e+00 , -1.1749200000000000e-01 , 1.9557500000000000e-01 , 9.7362499999999996e-01 -3.3991681023219522e+00 , -2.6206707909750513e+00 , 1.9322814399999999e+00 , -5.9607599999999997e-02 , 2.6193699999999998e-01 , 9.6324200000000004e-01 -3.4171269010349250e+00 , -2.7604557204637938e+00 , 1.9959805664000001e+00 , -1.2639400000000001e-03 , 3.0082100000000001e-01 , 9.5367999999999997e-01 -3.4431083269365521e+00 , -2.9514597723674454e+00 , 2.0548498080000002e+00 , -2.8757999999999999e-02 , 3.3297700000000002e-01 , 9.4249700000000003e-01 -3.4683633895235220e+00 , -3.1411891211900915e+00 , 2.1198912000000001e+00 , -5.4121500000000003e-02 , 2.8346600000000000e-01 , 9.5745400000000003e-01 -3.5075483718260667e+00 , -3.4113315296496376e+00 , 2.1788082400000000e+00 , -8.5023899999999999e-02 , 2.2986999999999999e-01 , 9.6950000000000003e-01 -3.5508130996719163e+00 , -3.7114309638326457e+00 , 2.2426871199999998e+00 , -8.8220499999999993e-02 , 2.1326100000000001e-01 , 9.7300399999999998e-01 -3.5989825541236584e+00 , -4.0422540059095189e+00 , 2.3132729599999999e+00 , -8.2813700000000004e-02 , 2.0785300000000001e-01 , 9.7464799999999996e-01 -3.6518981324564059e+00 , -4.4024214735539253e+00 , 2.3920831200000001e+00 , -8.0670000000000006e-02 , 2.0427699999999999e-01 , 9.7558400000000001e-01 -3.7152689277719713e+00 , -4.8339119213092090e+00 , 2.4774504799999999e+00 , -7.1960200000000002e-02 , 2.0466500000000001e-01 , 9.7618300000000002e-01 -3.7847787710120078e+00 , -5.3056595927564096e+00 , 2.5751699200000000e+00 , -7.2223999999999997e-02 , 2.1196300000000001e-01 , 9.7460500000000005e-01 -3.8600887234622743e+00 , -5.8269227739474045e+00 , 2.6865799199999998e+00 , -7.9665299999999994e-02 , 2.0394899999999999e-01 , 9.7573500000000002e-01 -3.9487291051099205e+00 , -6.4294421211506680e+00 , 2.8138852800000000e+00 , -7.1057700000000001e-02 , 2.0376500000000000e-01 , 9.7643800000000003e-01 -4.0509351187047047e+00 , -7.1326527144492946e+00 , 2.9608071200000001e+00 , -7.1053099999999994e-02 , 2.0976800000000001e-01 , 9.7516599999999998e-01 -4.1803699309097091e+00 , -8.0081292298994899e+00 , 3.1333712000000000e+00 , -5.2311000000000003e-02 , 1.9263600000000000e-01 , 9.7987500000000005e-01 -4.3394828785516086e+00 , -9.0858514592379258e+00 , 3.3412671999999999e+00 , -3.0315800000000000e-02 , 2.1220300000000000e-01 , 9.7675500000000004e-01 -4.5042052550491452e+00 , -1.0220577140980753e+01 , 3.5892759999999999e+00 , 2.4177500000000001e-02 , -2.1507799999999999e-01 , -9.7629800000000000e-01 -4.6957857955636673e+00 , -1.1546702173308056e+01 , 3.8887647999999997e+00 , 6.7464200000000002e-02 , 3.0451299999999998e-01 , 9.5011599999999996e-01 -4.8632185619528929e+00 , -1.2743274192865536e+01 , 4.2256520000000002e+00 , 2.9982700000000001e-01 , 4.3728800000000001e-01 , 8.4786899999999998e-01 -4.9100644176351409e+00 , -1.3206097000475411e+01 , 4.5368303999999995e+00 , -2.5044699999999998e-01 , -4.1696699999999998e-01 , -8.7373599999999996e-01 -4.9652963571169320e+00 , -1.3734390811580672e+01 , 4.8723552000000003e+00 , 2.9553699999999999e-01 , 4.6662500000000001e-01 , 8.3361799999999997e-01 -5.2403406177398066e+00 , -1.5703633702256681e+01 , 5.4131656000000001e+00 , -2.6708200000000001e-02 , 4.6229700000000001e-01 , 8.8632299999999997e-01 -5.3785192703431699e+00 , -1.6815619524646053e+01 , 5.8998647999999996e+00 , 4.6369199999999999e-01 , 7.4228200000000000e-01 , 4.8374299999999998e-01 -5.3390152724611646e+00 , -1.6778528404513043e+01 , 6.2386239999999997e+00 , 8.7212100000000004e-01 , 3.3406000000000002e-01 , 3.5750300000000002e-01 -5.3013450339046129e+00 , -1.6746583555435507e+01 , 6.5788600000000006e+00 , -9.2992300000000006e-01 , -3.5765999999999998e-01 , -8.5576299999999994e-02 -5.2617110363778403e+00 , -1.6709306557055360e+01 , 6.9188360000000007e+00 , 7.6275499999999996e-01 , 6.4256599999999997e-01 , -7.2899400000000003e-02 -5.2195876158486421e+00 , -1.6655555751320609e+01 , 7.2560560000000001e+00 , -5.9985200000000005e-01 , -7.9618699999999998e-01 , 7.9147999999999996e-02 -5.1782462787070243e+00 , -1.6605678788549803e+01 , 7.5946280000000002e+00 , -9.9468400000000001e-01 , 3.7305199999999997e-02 , -9.5975800000000000e-02 -5.1376628387167855e+00 , -1.6559786686775610e+01 , 7.9351552000000005e+00 , 9.9466900000000003e-01 , -3.7648700000000000e-02 , 9.6005499999999994e-02 -5.0914540128168628e+00 , -1.6478212918942678e+01 , 8.2670192000000000e+00 , 9.9432600000000004e-01 , -4.3449200000000000e-02 , 9.7095200000000007e-02 -5.0491435715443131e+00 , -1.6420785990793863e+01 , 8.6061528000000003e+00 , -9.9456699999999998e-01 , 3.9511800000000000e-02 , -9.6306199999999995e-02 -5.0075676035569057e+00 , -1.6366181404255812e+01 , 8.9475432000000001e+00 , 9.9454200000000004e-01 , -4.0079900000000002e-02 , 9.6331000000000000e-02 -4.9640163884120430e+00 , -1.6306140881946121e+01 , 9.2885695999999989e+00 , -9.9454200000000004e-01 , 4.0083100000000003e-02 , -9.6331700000000006e-02 -4.9260670000265048e+00 , -1.6288790407203052e+01 , 9.6462047999999996e+00 , -2.7124199999999998e-01 , 9.4250699999999998e-01 , -1.9521100000000000e-01 -4.8821576981719979e+00 , -1.6225957361186392e+01 , 9.9906632000000002e+00 , 1.1795800000000000e-03 , -9.9422400000000000e-01 , 1.0731400000000001e-01 -4.8374041761588202e+00 , -1.6156928532675643e+01 , 1.0334580800000001e+01 , 1.5859300000000000e-02 , 9.6039399999999997e-01 , 2.7819300000000002e-01 -4.4629736454512452e+00 , -1.3492297173867978e+01 , 9.6138504000000005e+00 , -1.5233900000000000e-02 , -9.1939700000000002e-01 , 3.9303700000000003e-01 -4.3991124725004163e+00 , -1.3229236735592494e+01 , 9.8255423999999998e+00 , 4.4259500000000000e-02 , -8.8138799999999995e-01 , 4.7031600000000001e-01 -4.4260744018332696e+00 , -1.3708611812923827e+01 , 1.0366446400000001e+01 , 4.9062899999999998e-03 , -9.1064699999999998e-01 , 4.1315600000000002e-01 -4.3204415230049662e+00 , -1.3107871006161414e+01 , 1.0421493600000000e+01 , 1.4585600000000001e-01 , -8.2279500000000005e-01 , 5.4930299999999999e-01 -4.2714516881487858e+00 , -1.2964040754747415e+01 , 1.0682335999999999e+01 , 4.0221699999999999e-01 , -7.5475800000000004e-01 , 5.1822999999999997e-01 -4.2174654338098021e+00 , -1.2779732268913502e+01 , 1.0921400800000001e+01 , 2.3324700000000001e-01 , -8.9176299999999997e-01 , 3.8775599999999999e-01 -4.1801876165815610e+00 , -1.2736353541428061e+01 , 1.1234409599999999e+01 , 1.5971900000000000e-01 , -9.2239000000000004e-01 , 3.5169099999999998e-01 -4.2258983674150095e+00 , -1.3446230494128796e+01 , 1.1973631200000002e+01 , 4.1804100000000000e-01 , -9.0254800000000002e-01 , 1.0319299999999999e-01 -4.0805584653575675e+00 , -1.2444995025940655e+01 , 1.1752995199999999e+01 , 1.8230900000000000e-01 , 8.2495600000000002e-01 , -5.3498699999999999e-01 -4.0197812559269517e+00 , -1.2190965924139002e+01 , 1.1946414400000000e+01 , 3.1980399999999998e-01 , 9.4198899999999997e-01 , -1.0189600000000000e-01 -3.9847290865438580e+00 , -1.2179076722701877e+01 , 1.2287992000000001e+01 , 6.3322000000000003e-02 , 9.8414999999999997e-01 , 1.6564699999999999e-01 -4.0240269821555357e+00 , -1.2906064796253542e+01 , 1.3120512000000000e+01 , -1.3108300000000001e-01 , 9.7978399999999999e-01 , 1.5113499999999999e-01 -3.9446623332719284e+00 , -1.2485064134006342e+01 , 1.3216504000000000e+01 , 3.5002899999999998e-01 , -9.2727300000000001e-01 , -1.3283300000000001e-01 -3.9945722510553456e+00 , -1.3369816710656696e+01 , 1.4221976000000000e+01 , -2.2297900000000001e-01 , 7.7836399999999994e-01 , 5.8688099999999999e-01 -3.9365700012723304e+00 , -1.3179637047289791e+01 , 1.4495184000000000e+01 , -3.5618800000000000e-01 , 8.4240000000000004e-01 , 4.0434199999999998e-01 -3.9071301641811131e+00 , -1.3297874721498491e+01 , 1.5003120000000001e+01 , -4.9314100000000000e-01 , 4.6001599999999998e-01 , 7.3837500000000000e-01 -2.9271265624960856e+00 , -2.8862912934087603e+00 , 7.2433679999999994e+00 , 2.9001700000000002e-01 , 1.5555099999999999e-01 , -9.4429600000000002e-01 -3.6737755011438056e+00 , -1.1605418695796569e+01 , 1.4499864000000001e+01 , 5.3560300000000005e-01 , 1.1865000000000001e-01 , -8.3609299999999998e-01 -2.8628383045697210e+00 , -2.4723260547272812e+00 , 7.1973272000000001e+00 , -1.6746200000000000e-01 , -5.6484299999999998e-01 , 8.0802799999999997e-01 -2.8447070904436185e+00 , -2.4250024495032108e+00 , 7.3018263999999995e+00 , 1.8803000000000000e-01 , 8.8563700000000001e-01 , -4.2460700000000001e-01 -2.8266942234698469e+00 , -2.3837670919404239e+00 , 7.4130544000000000e+00 , -7.4492699999999995e-02 , 9.6867099999999995e-01 , -2.3691400000000001e-01 -2.8156343893506115e+00 , -2.4298452368993564e+00 , 7.6088760000000004e+00 , -1.5338199999999999e-01 , -9.7389599999999998e-01 , 1.6733100000000001e-01 -2.7943471790330801e+00 , -2.3526850868835352e+00 , 7.6922008000000002e+00 , -2.7429300000000001e-01 , -8.9565899999999998e-01 , 3.5008400000000001e-01 -2.7494134564060317e+00 , -1.9212243504844086e+00 , 7.4208648000000004e+00 , -5.2847100000000002e-01 , -4.5319500000000001e-01 , -7.1786700000000003e-01 -2.7143633668388887e+00 , -1.6163823847278889e+00 , 7.2557440000000009e+00 , -2.5051499999999999e-01 , -8.3252400000000004e-01 , 4.9411200000000000e-01 -2.6998795633218653e+00 , -1.6152117372700072e+00 , 7.4007823999999998e+00 , -5.8685000000000001e-02 , -8.9257600000000004e-01 , 4.4706299999999999e-01 -2.6832974148226283e+00 , -1.5827592117236611e+00 , 7.5161287999999997e+00 , 6.3806099999999999e-01 , -7.2902800000000001e-01 , 2.4778300000000000e-01 -2.6647791191309675e+00 , -1.5204138731834353e+00 , 7.6002752000000005e+00 , -6.1230600000000002e-01 , 7.8320500000000004e-01 , -1.0803699999999999e-01 -2.6482280606697648e+00 , -1.5023654949492498e+00 , 7.7390216000000009e+00 , 3.0396299999999998e-01 , -6.4196699999999995e-01 , 7.0390699999999995e-01 -2.6466793820890206e+00 , -1.8021472460874324e+00 , 8.2745384000000008e+00 , -9.2925999999999997e-01 , 3.1737300000000002e-01 , 1.8908000000000000e-01 -2.6340352764558439e+00 , -1.9432968364646013e+00 , 8.6411800000000003e+00 , -8.8018399999999997e-01 , 2.7059699999999998e-01 , 3.8994000000000001e-01 -2.6016616113046602e+00 , -1.5909351159275178e+00 , 8.3751584000000001e+00 , 9.6757700000000002e-01 , 2.5059700000000001e-01 , -3.1557799999999997e-02 -2.5821698383542477e+00 , -1.5971253254757620e+00 , 8.5774591999999998e+00 , -7.8443600000000002e-01 , 5.2035199999999997e-02 , 6.1802299999999999e-01 -2.5613700551744358e+00 , -1.5392536234125052e+00 , 8.6968928000000005e+00 , -4.8562000000000000e-01 , -8.6967499999999998e-01 , 8.8537299999999999e-02 -2.5564847721825994e+00 , -2.2118048263671124e+00 , 9.9007135999999996e+00 , -5.2823299999999995e-01 , -2.5985100000000000e-01 , -8.0836100000000000e-01 -2.5136272382310558e+00 , -1.2246221754278168e+00 , 8.6461720000000000e+00 , -5.6466200000000000e-01 , 7.1250000000000002e-01 , 4.1653400000000002e-01 -2.4925030018090046e+00 , -1.2066306812934964e+00 , 8.8311048000000003e+00 , 2.4175600000000000e-01 , -7.0606599999999997e-01 , -6.6560100000000000e-01 -2.4729732198563621e+00 , -1.4954240909560728e+00 , 9.5332711999999997e+00 , -2.9684500000000003e-01 , 3.6698199999999997e-01 , -8.8159399999999999e-01 -2.4478539470008660e+00 , -1.3574408417266048e+00 , 9.5539775999999996e+00 , 2.2336000000000000e-01 , 6.2002099999999997e-02 , 9.7276200000000002e-01 -2.4265660782853713e+00 , -7.1394378996773922e-01 , 8.6641639999999995e+00 , 6.7222499999999996e-01 , 2.8693700000000000e-01 , -6.8248100000000000e-01 -2.4048379148902788e+00 , -6.6141748054875782e-01 , 8.7990208000000010e+00 , 6.7222499999999996e-01 , 2.8693700000000000e-01 , -6.8248100000000000e-01 -2.3958477700001746e+00 , -3.0007790715243399e-02 , 7.8149104000000005e+00 , -9.7618899999999995e-02 , -9.0463000000000005e-01 , 4.1486699999999999e-01 -2.3803038968046084e+00 , 1.2058106972662430e-01 , 7.7158087999999996e+00 , -3.3177600000000002e-01 , 9.4108999999999998e-01 , -6.5379000000000007e-02 -2.3613178195354148e+00 , 1.4658261830573904e-01 , 7.8671600000000002e+00 , 7.9193299999999994e-02 , -9.3950299999999998e-01 , 3.3326099999999997e-01 -2.3314728946355592e+00 , -2.7288499341012074e-02 , 8.4735008000000001e+00 , 6.1598900000000001e-01 , 6.8473599999999996e-02 , 7.8477300000000005e-01 -2.3111250875364191e+00 , 5.7797878121372159e-02 , 8.5330615999999999e+00 , 8.0596999999999996e-01 , -1.7484200000000000e-01 , 5.6554700000000002e-01 -2.2931537274746954e+00 , 1.6700846069099673e-01 , 8.5337168000000005e+00 , 8.0222199999999999e-01 , -1.4795400000000000e-01 , 5.7840199999999997e-01 -2.2793507947810641e+00 , 3.2999430696951615e-01 , 8.3963432000000005e+00 , 4.6035900000000002e-01 , -5.7139600000000002e-01 , 6.7939400000000005e-01 -2.2421270830958182e+00 , 2.3352411603772039e-01 , 8.9372888000000010e+00 , -1.2340700000000000e-01 , -6.0531100000000004e-01 , 7.8636499999999998e-01 -2.2188666706178144e+00 , 3.0307905338608920e-01 , 9.0615063999999990e+00 , 7.7577099999999999e-01 , 4.2413099999999998e-01 , -4.6721800000000002e-01 -2.1930780119320485e+00 , 3.6681572786221395e-01 , 9.2142096000000002e+00 , -8.6561900000000003e-01 , -9.0389399999999995e-02 , 4.9247600000000002e-01 -2.1823607811244807e+00 , 5.4461468445076466e-01 , 9.0192824000000016e+00 , -4.8892300000000000e-02 , 2.4227399999999999e-01 , 9.6897500000000003e-01 -2.1764636062547189e+00 , 7.3269702128656133e-01 , 8.7604888000000010e+00 , -1.2981099999999999e-04 , -1.7432800000000001e-01 , 9.8468800000000001e-01 -2.1457630871184805e+00 , 7.6677628606642112e-01 , 9.0179408000000016e+00 , -6.1241999999999996e-01 , 3.7802900000000000e-01 , -6.9428800000000002e-01 -2.1378731466405689e+00 , 9.2637657684439922e-01 , 8.8228368000000010e+00 , 1.4220099999999999e-01 , 3.0231500000000000e-01 , -9.4254099999999996e-01 -2.1049996125621058e+00 , 9.6535400740621458e-01 , 9.0989047999999997e+00 , -2.2937299999999999e-01 , 1.0102100000000000e-01 , -9.6808200000000000e-01 -2.0969027787717529e+00 , 1.1109656328568571e+00 , 8.9292288000000006e+00 , -5.3664900000000004e-01 , 4.6285900000000002e-01 , -7.0552700000000002e-01 -1.9831282632612357e+00 , 9.0833631016794891e-01 , 1.0444758400000001e+01 , 3.7168600000000002e-01 , -4.2965999999999999e-01 , 8.2294699999999998e-01 -1.9563791243555437e+00 , 1.0263536052062441e+00 , 1.0518889600000001e+01 , 2.3394200000000001e-01 , -5.1881500000000003e-01 , 8.2225499999999996e-01 -1.9143493609071538e+00 , 1.1082821362241035e+00 , 1.0816433600000000e+01 , -8.6960099999999999e-02 , -9.8848100000000005e-01 , 1.2386700000000000e-01 -1.9362190269712267e+00 , 1.3388745031421290e+00 , 1.0189521599999999e+01 , -3.2176500000000002e-01 , 8.4087299999999998e-01 , 4.3520100000000000e-01 -1.9233761389300801e+00 , 1.4769576447236710e+00 , 1.0092136000000000e+01 , 4.7108699999999998e-01 , -4.2927799999999999e-01 , -7.7058300000000002e-01 -1.8303923806552269e+00 , 1.4931555840551933e+00 , 1.1022301600000000e+01 , -8.2869999999999999e-01 , 4.2936599999999998e-02 , 5.5804299999999996e-01 -1.8981980871977555e+00 , 1.7408824628532367e+00 , 9.8999647999999993e+00 , -6.1645300000000003e-01 , 2.6441300000000001e-01 , 7.4166799999999999e-01 -1.8687766984187788e+00 , 1.8507347471922904e+00 , 1.0012035200000000e+01 , 5.6227899999999997e-01 , -7.2017999999999999e-02 , -8.2380500000000001e-01 -1.8774781257754358e+00 , 1.9911172700337088e+00 , 9.6776856000000002e+00 , 5.1449299999999998e-01 , 3.3705400000000002e-01 , 7.8847500000000004e-01 -1.8057315046423661e+00 , 2.0788948116188699e+00 , 1.0271972800000000e+01 , 7.0731999999999995e-01 , 5.0821799999999995e-01 , -4.9133800000000000e-01 -1.7888931354105004e+00 , 2.2045568995193667e+00 , 1.0222760000000001e+01 , -8.2679599999999998e-01 , -3.5815700000000000e-01 , 4.3374200000000002e-01 -1.7573164124985126e+00 , 2.3266541083171126e+00 , 1.0337170400000000e+01 , -7.8429899999999997e-01 , -2.6741300000000001e-01 , 5.5979000000000001e-01 -1.7749826031270657e+00 , 2.4501274039134397e+00 , 9.9524328000000004e+00 , -8.4876499999999999e-01 , -5.1336700000000002e-01 , 1.2669300000000000e-01 -1.7817278426593750e+00 , 2.5626515065788413e+00 , 9.6902071999999997e+00 , 3.8819199999999998e-01 , 7.9497899999999999e-01 , 4.6617100000000000e-01 -1.7739666462310877e+00 , 2.6727019161510106e+00 , 9.5812568000000002e+00 , -1.0124400000000000e-02 , 6.5222100000000005e-01 , 7.5796100000000000e-01 -1.7587016236086108e+00 , 2.7834500945146678e+00 , 9.5426831999999990e+00 , 3.6386299999999999e-01 , 3.2162400000000002e-01 , 8.7416300000000002e-01 -1.2790813597039579e+00 , 3.2152149691687839e+00 , 1.3738896000000000e+01 , 7.4490500000000004e-01 , -6.6710700000000001e-01 , 9.2177500000000002e-03 -1.7008515262688197e+00 , 3.0260221046721094e+00 , 9.7276784000000003e+00 , 2.5559199999999999e-01 , 8.4278399999999998e-01 , -4.7369600000000001e-01 -1.6975712109813539e+00 , 3.1260286799120616e+00 , 9.5803936000000007e+00 , -1.8798999999999999e-01 , 5.3151000000000004e-01 , 8.2592800000000000e-01 -1.7087059376149327e+00 , 3.2087423756157127e+00 , 9.3292231999999995e+00 , 3.6176799999999998e-01 , 9.4549599999999998e-02 , 9.2746099999999998e-01 -1.6989090448558610e+00 , 3.3091045959950076e+00 , 9.2613736000000006e+00 , -5.0161999999999998e-02 , -9.7640600000000000e-01 , 2.1003700000000000e-01 -2.8904448953609898e+00 , 4.8030252004979745e-01 , 1.3567922399999999e+00 , -5.3730500000000000e-02 , 2.0361699999999999e-01 , 9.7757499999999997e-01 -2.8960945947161174e+00 , 4.2667108398378994e-01 , 1.3711026399999999e+00 , -2.5815899999999999e-02 , 1.7782100000000001e-01 , 9.8372400000000004e-01 -2.9032894510586660e+00 , 3.6554278509085081e-01 , 1.3801922400000000e+00 , 7.2376899999999997e-03 , 1.6771400000000000e-01 , 9.8580900000000005e-01 -2.9102740672428302e+00 , 3.0369273087274751e-01 , 1.3909042400000000e+00 , -1.2185500000000000e-01 , 1.3060900000000000e-01 , 9.8391700000000004e-01 -2.9197568378284053e+00 , 2.3337172832872977e-01 , 1.3970319199999999e+00 , -5.9296399999999999e-02 , 2.0896000000000001e-01 , 9.7612500000000002e-01 -2.9246943138217123e+00 , 1.7989304011140406e-01 , 1.4172131200000000e+00 , -8.5733599999999993e-02 , 2.0832200000000001e-01 , 9.7429500000000002e-01 -2.9337404532217599e+00 , 1.0923946299255394e-01 , 1.4268840800000000e+00 , -7.7687999999999993e-02 , 1.6667799999999999e-01 , 9.8294599999999999e-01 -2.9425128262997839e+00 , 3.7978591445501308e-02 , 1.4386828800000000e+00 , -9.0833300000000006e-02 , 2.0806100000000000e-01 , 9.7388900000000000e-01 -2.9510278518538735e+00 , -3.3928692370560398e-02 , 1.4525076000000001e+00 , 1.0108800000000000e-01 , -2.2885200000000000e-01 , -9.6819800000000000e-01 -2.9608890614437673e+00 , -1.1407353341080828e-01 , 1.4626330400000001e+00 , -1.0903000000000000e-01 , 2.0267299999999999e-01 , 9.7315799999999997e-01 -2.9704703890961923e+00 , -1.9482690857588247e-01 , 1.4749882400000001e+00 , -7.0747199999999996e-02 , 2.0873400000000000e-01 , 9.7541000000000000e-01 -2.9766995693337144e+00 , -2.5794430726022988e-01 , 1.5003059999999999e+00 , -6.4604300000000003e-02 , 1.7133599999999999e-01 , 9.8309199999999997e-01 -2.9897734052389890e+00 , -3.5697373236679297e-01 , 1.5070129600000000e+00 , -5.2093800000000003e-02 , 1.9179299999999999e-01 , 9.8005200000000003e-01 -2.9970207333174961e+00 , -4.2885148003548412e-01 , 1.5312647200000000e+00 , 6.9944300000000001e-02 , -2.1557599999999999e-01 , -9.7397900000000004e-01 -3.0079068582751733e+00 , -5.2035512159138886e-01 , 1.5484548800000000e+00 , -8.6902599999999997e-02 , 1.6804800000000000e-01 , 9.8194099999999995e-01 -3.0199309932713110e+00 , -6.2082826838905314e-01 , 1.5635681600000000e+00 , -1.0865300000000000e-01 , 1.7915400000000001e-01 , 9.7780299999999998e-01 -3.0330285928730296e+00 , -7.3015666614762065e-01 , 1.5771100000000000e+00 , 1.0612600000000000e-01 , -1.9145799999999999e-01 , -9.7574600000000000e-01 -3.0439055195503979e+00 , -8.2204418715079886e-01 , 1.6029311200000000e+00 , -1.1853000000000000e-01 , 1.9225300000000001e-01 , 9.7416100000000005e-01 -3.0586175229381745e+00 , -9.4157196085605754e-01 , 1.6188774399999999e+00 , -1.0031200000000000e-01 , 1.7217299999999999e-01 , 9.7994599999999998e-01 -3.0714637359577273e+00 , -1.0530523989471252e+00 , 1.6427756000000000e+00 , -1.0409800000000000e-01 , 1.7886900000000000e-01 , 9.7835000000000005e-01 -3.0865724230021825e+00 , -1.1835357458411377e+00 , 1.6624201599999999e+00 , -1.0425600000000000e-01 , 1.7457500000000001e-01 , 9.7910900000000001e-01 -3.1022150994040825e+00 , -1.3142610280251246e+00 , 1.6862403200000000e+00 , -7.8937400000000005e-02 , 2.1788199999999999e-01 , 9.7277800000000003e-01 -3.1186523777433353e+00 , -1.4544498886787367e+00 , 1.7107177600000001e+00 , -6.5952999999999998e-02 , 2.1697600000000000e-01 , 9.7394599999999998e-01 -3.1342971230716938e+00 , -1.5855779893820885e+00 , 1.7430669599999999e+00 , -5.7919199999999997e-02 , 1.8162600000000001e-01 , 9.8165999999999998e-01 -3.1531565001953945e+00 , -1.7465413603758257e+00 , 1.7703066400000000e+00 , -8.0352000000000007e-02 , 1.8626300000000001e-01 , 9.7920900000000000e-01 -3.1713876759959669e+00 , -1.9075047357942330e+00 , 1.8027078400000001e+00 , -9.0731500000000007e-02 , 1.9193199999999999e-01 , 9.7720499999999999e-01 -3.1946845870236897e+00 , -2.0979705903565824e+00 , 1.8320722400000000e+00 , -1.0787099999999999e-01 , 1.5911800000000001e-01 , 9.8134900000000003e-01 -3.2228226681056880e+00 , -2.3186423601642616e+00 , 1.8601200000000000e+00 , -1.0229600000000000e-01 , 1.9650500000000001e-01 , 9.7515200000000002e-01 -3.2456255623517034e+00 , -2.5206900258403300e+00 , 1.9003719520000000e+00 , -2.9409200000000000e-02 , 2.4885800000000000e-01 , 9.6809400000000001e-01 -3.2609091053419084e+00 , -2.6721062990784485e+00 , 1.9584615679999999e+00 , -9.4084900000000003e-03 , 2.6970600000000000e-01 , 9.6289700000000000e-01 -3.2832499916307691e+00 , -2.8737488767765083e+00 , 2.0111882159999999e+00 , -8.0738500000000005e-03 , 3.0000800000000000e-01 , 9.5390200000000003e-01 -3.3015906409712055e+00 , -3.0540348690387704e+00 , 2.0742112800000001e+00 , -8.0404199999999995e-02 , 2.8990100000000002e-01 , 9.5367299999999999e-01 -3.3298145812292130e+00 , -3.3049320776938886e+00 , 2.1313915200000002e+00 , -8.1492599999999998e-02 , 2.4032600000000001e-01 , 9.6726500000000004e-01 -3.3611175848794295e+00 , -3.5770754802374469e+00 , 2.1944976800000000e+00 , -7.8541399999999997e-02 , 2.2231200000000001e-01 , 9.7180699999999998e-01 -3.3965324894646756e+00 , -3.8879981782413777e+00 , 2.2609682400000000e+00 , -7.1954299999999999e-02 , 2.0333599999999999e-01 , 9.7646200000000005e-01 -3.4387318356221184e+00 , -4.2512611362774617e+00 , 2.3326346400000002e+00 , -6.0346200000000003e-02 , 2.1121999999999999e-01 , 9.7557400000000005e-01 -3.4835373373657372e+00 , -4.6327463633078461e+00 , 2.4145710400000002e+00 , -6.2613299999999997e-02 , 2.0054100000000000e-01 , 9.7768200000000005e-01 -3.5345202368712316e+00 , -5.0764575063111277e+00 , 2.5051706400000002e+00 , -5.2251600000000002e-02 , 2.1004000000000000e-01 , 9.7629600000000005e-01 -3.5905371450698524e+00 , -5.5602784722085916e+00 , 2.6086027999999999e+00 , -5.6010799999999999e-02 , 2.0428099999999999e-01 , 9.7730899999999998e-01 -3.6569729039827399e+00 , -6.1343819718659987e+00 , 2.7246428800000002e+00 , -6.2872899999999995e-02 , 1.9617499999999999e-01 , 9.7855099999999995e-01 -3.7389735254550054e+00 , -6.8310025962639465e+00 , 2.8577743199999999e+00 , -5.7431000000000003e-02 , 2.0320099999999999e-01 , 9.7745099999999996e-01 -3.8235868773338084e+00 , -7.5674704427604258e+00 , 3.0150514399999997e+00 , -6.1678100000000000e-02 , 2.0663899999999999e-01 , 9.7647099999999998e-01 -3.9326967651904998e+00 , -8.4969199640397264e+00 , 3.2001080000000002e+00 , -4.0444000000000001e-02 , 1.9715400000000000e-01 , 9.7953800000000002e-01 -4.0513837048920314e+00 , -9.5258424555469645e+00 , 3.4205152000000001e+00 , -2.6375800000000001e-02 , 2.0982600000000001e-01 , 9.7738300000000000e-01 -4.1966853657469780e+00 , -1.0788447511420001e+01 , 3.6879616000000004e+00 , -1.2070600000000001e-02 , 2.2634099999999999e-01 , 9.7397299999999998e-01 -4.3430091357201803e+00 , -1.2086393980875135e+01 , 4.0021456000000004e+00 , 1.5240100000000001e-01 , 3.5459299999999999e-01 , 9.2251700000000003e-01 -4.3857909279982605e+00 , -1.2625913011431804e+01 , 4.3005632000000000e+00 , -2.6742600000000000e-01 , -4.7414099999999998e-01 , -8.3885299999999996e-01 -4.4053990580539750e+00 , -1.2986656326138492e+01 , 4.6013415999999996e+00 , 3.1732900000000003e-01 , 4.5174300000000001e-01 , 8.3380500000000002e-01 -4.4971199808392095e+00 , -1.3945384933862282e+01 , 4.9850600000000007e+00 , -1.3223499999999999e-01 , -3.9608900000000002e-01 , -9.0864100000000003e-01 -4.7933067277862209e+00 , -1.6583749342624447e+01 , 5.6292776000000000e+00 , 4.0869200000000001e-02 , 8.4055199999999997e-01 , 5.4018699999999997e-01 -6.5620505733848677e+00 , -3.1425260289652421e+01 , 8.2242543999999995e+00 , 9.0988600000000003e-02 , 4.4140900000000000e-01 , 8.9268099999999995e-01 -6.5846802621514442e+00 , -3.2122306990685132e+01 , 8.9483855999999999e+00 , 9.0988600000000003e-02 , 4.4140900000000000e-01 , 8.9268099999999995e-01 -7.0116818204422993e+00 , -3.6287787151388258e+01 , 1.0352614400000000e+01 , -6.1567600000000000e-01 , -2.8878799999999999e-01 , -7.3317399999999999e-01 -7.2304420736729407e+00 , -3.8786493976265625e+01 , 1.1568187200000001e+01 , -5.7539700000000005e-01 , -3.3338099999999998e-01 , -7.4684300000000003e-01 -9.4301658668311745e+00 , -5.9734905859978504e+01 , 1.8158688000000001e+01 , 1.0758100000000000e-01 , 2.5990600000000003e-01 , 9.5962199999999998e-01 -5.1081226430837123e+00 , -2.2079098183768838e+01 , 9.9317784000000007e+00 , 9.8940399999999995e-01 , -1.0358800000000000e-01 , -1.0172800000000000e-01 -5.0458935477109526e+00 , -2.1941877927199599e+01 , 1.0352021600000000e+01 , -9.6089000000000002e-01 , 2.4908100000000000e-01 , -1.2103500000000000e-01 -4.8261555210264833e+00 , -2.0289426114328258e+01 , 1.0290349600000001e+01 , 9.3286200000000000e-02 , 9.9544100000000002e-01 , 1.9884900000000000e-02 -4.7515249562077271e+00 , -1.9999260933655542e+01 , 1.0629119200000002e+01 , 3.2647199999999998e-01 , 8.9314300000000002e-01 , -3.0937399999999998e-01 -4.6958631868074185e+00 , -1.9889360528971174e+01 , 1.1025639999999999e+01 , -7.6839999999999997e-01 , -5.9312399999999998e-01 , 2.4034400000000000e-01 -4.7050864453090240e+00 , -2.0431331486266465e+01 , 1.1668360000000000e+01 , -9.5941100000000001e-01 , 1.1061799999999999e-01 , -2.5941300000000000e-01 -4.5671107501647619e+00 , -1.9485374872765984e+01 , 1.1748876800000000e+01 , 2.9985899999999999e-02 , -9.0508500000000003e-01 , 4.2417100000000002e-01 -4.5239152522896120e+00 , -1.9498481758508905e+01 , 1.2196732000000001e+01 , 2.9985899999999999e-02 , -9.0508500000000003e-01 , 4.2417100000000002e-01 -3.9022174520485611e+00 , -1.3283271637287864e+01 , 9.9310919999999996e+00 , -1.1633000000000000e-01 , 9.4779700000000000e-01 , -2.9689599999999999e-01 -3.8743501341743025e+00 , -1.3335717443068068e+01 , 1.0281156000000001e+01 , -1.2071400000000000e-01 , 8.2270799999999999e-01 , -5.5549899999999997e-01 -3.8475774951253179e+00 , -1.3416910806950302e+01 , 1.0652560800000000e+01 , 7.5092599999999995e-02 , -7.2659899999999999e-01 , 6.8294600000000005e-01 -3.7628235679885043e+00 , -1.2842180470513181e+01 , 1.0704321600000000e+01 , 2.5198399999999999e-01 , -8.1382900000000002e-01 , 5.2362900000000001e-01 -3.7236313115675559e+00 , -1.2775207774852973e+01 , 1.1002177600000000e+01 , 2.6997700000000002e-01 , -8.3901899999999996e-01 , 4.7239799999999998e-01 -3.6965859558537666e+00 , -1.2857411458298881e+01 , 1.1384127999999999e+01 , -3.6492799999999997e-01 , 8.2430999999999999e-01 , -4.3282799999999999e-01 -3.6849849064514553e+00 , -1.3156673548602287e+01 , 1.1899011200000000e+01 , 5.3133600000000003e-01 , 8.3543400000000001e-01 , -1.4047299999999999e-01 -3.5713311019222473e+00 , -1.2155700250571117e+01 , 1.1667434399999999e+01 , -2.0730100000000001e-01 , 8.6445700000000003e-01 , -4.5797500000000002e-01 -3.5446809687614600e+00 , -1.2264352628407741e+01 , 1.2076695200000001e+01 , -5.4287700000000005e-01 , 7.2647700000000004e-01 , -4.2132599999999998e-01 -3.5387545430325438e+00 , -1.2686725361437134e+01 , 1.2698376000000000e+01 , 7.3052800000000001e-02 , -9.2780899999999999e-01 , -3.6583300000000002e-01 -3.5147611399447434e+00 , -1.2875699006210224e+01 , 1.3194040000000001e+01 , 1.9554500000000000e-01 , 9.7859499999999999e-01 , 6.4139799999999997e-02 -3.4713571194081663e+00 , -1.2812657419359793e+01 , 1.3534328000000000e+01 , 3.2224999999999997e-02 , 9.9263299999999999e-01 , 1.1679500000000000e-01 -3.4332471399479121e+00 , -1.2851898920891960e+01 , 1.3953552000000000e+01 , 1.7741600000000000e-02 , 9.2619700000000005e-01 , 3.7662099999999998e-01 -3.3804326667215907e+00 , -1.2656635264039831e+01 , 1.4210744000000000e+01 , 2.6075199999999998e-01 , -8.5212800000000000e-01 , -4.5374700000000001e-01 -2.7617818118510611e+00 , -2.8726188865112690e+00 , 7.1231336000000001e+00 , -1.7129400000000000e-01 , -3.0719999999999997e-01 , 9.3610199999999999e-01 -2.7394359429460202e+00 , -2.7301471765931913e+00 , 7.1561744000000003e+00 , -9.8534800000000006e-02 , -3.0223499999999998e-01 , 9.4812700000000005e-01 -2.7164540444405363e+00 , -2.5791878387802427e+00 , 7.1785135999999996e+00 , 1.3564399999999999e-01 , -5.7284100000000004e-01 , 8.0836500000000000e-01 -2.6980599549160509e+00 , -2.5244363966264034e+00 , 7.2777088000000001e+00 , 3.8955400000000001e-01 , -8.1137899999999996e-01 , 4.3578899999999998e-01 -2.6821117913189547e+00 , -2.4902105697599870e+00 , 7.3967264000000004e+00 , 3.9229399999999998e-01 , -8.9492300000000002e-01 , 2.1264400000000000e-01 -2.6664554511537926e+00 , -2.4924610644439005e+00 , 7.5508856000000000e+00 , -8.9328299999999999e-02 , -9.3231399999999998e-01 , 3.5044399999999998e-01 -2.6616399200658316e+00 , -2.7779109559756430e+00 , 7.9776496000000003e+00 , -3.3483700000000000e-01 , -9.3165699999999996e-01 , 1.4106700000000000e-01 -2.6257431095304140e+00 , -2.2776490189211254e+00 , 7.6597112000000003e+00 , 9.7943000000000002e-02 , -6.3489799999999996e-01 , 7.6636300000000002e-01 -2.5871130817416659e+00 , -1.6285414862146421e+00 , 7.1629760000000005e+00 , 2.3260100000000000e-01 , 7.6246499999999995e-01 , -6.0377499999999995e-01 -2.5737317616788626e+00 , -1.6436482740969955e+00 , 7.3223040000000008e+00 , -6.2262699999999997e-02 , -9.2366999999999999e-01 , 3.7809700000000002e-01 -2.5620971855219636e+00 , -1.7745865555980740e+00 , 7.6133063999999999e+00 , -8.2587400000000000e-01 , 4.6387800000000001e-01 , -3.2054500000000002e-01 -2.5505699676937299e+00 , -2.0078300002989238e+00 , 8.0342672000000004e+00 , 3.7271700000000002e-01 , -8.3543699999999999e-01 , 4.0388900000000000e-01 -2.5370175779996638e+00 , -2.2540586235856619e+00 , 8.4957360000000008e+00 , 6.7627400000000004e-01 , -2.2638100000000000e-01 , -7.0100300000000004e-01 -2.5128492073514392e+00 , -1.9408243057160459e+00 , 8.3113543999999990e+00 , 1.0162100000000000e-02 , -9.9942399999999998e-01 , 3.2389000000000001e-02 -2.4931848509158212e+00 , -1.8184908865614937e+00 , 8.3451231999999997e+00 , 5.1534000000000002e-01 , -4.2992700000000000e-01 , -7.4134199999999995e-01 -2.4712880581374614e+00 , -1.4596228394469040e+00 , 8.0715095999999988e+00 , 1.2819500000000000e-01 , 8.9469699999999996e-01 , 4.2788199999999998e-01 -2.4534217018246389e+00 , -1.4477410926239127e+00 , 8.2373480000000008e+00 , -8.6520200000000003e-01 , 2.9232000000000002e-01 , -4.0739999999999998e-01 -2.4348820496822325e+00 , -1.3343586528712379e+00 , 8.2691511999999996e+00 , -8.6520200000000003e-01 , 2.9232000000000002e-01 , -4.0739999999999998e-01 -2.4148288139588563e+00 , -1.3274088830978776e+00 , 8.4522119999999994e+00 , -9.2000400000000004e-01 , -2.8033000000000002e-01 , -2.7387499999999998e-01 -2.3971980951813974e+00 , -1.1307327375612934e+00 , 8.3600160000000017e+00 , -9.3723999999999996e-01 , -4.4027999999999998e-02 , 3.4589399999999998e-01 -2.3626178779116072e+00 , -1.8114363180192776e+00 , 9.6171784000000002e+00 , 1.9399600000000000e-01 , 4.2316199999999998e-01 , 8.8504200000000000e-01 -2.3337332691281696e+00 , -1.9337636053769982e+00 , 1.0068455200000001e+01 , 1.9399600000000000e-01 , 4.2316199999999998e-01 , 8.8504200000000000e-01 -2.3482635965566701e+00 , -6.6122359776490303e-01 , 8.2134488000000001e+00 , 6.2712800000000002e-01 , -4.9600899999999998e-01 , -6.0057199999999999e-01 -2.3194538478615527e+00 , -8.3617948073289527e-01 , 8.7249936000000012e+00 , -8.5207800000000000e-01 , 2.3374799999999999e-03 , 5.2340900000000001e-01 -2.3063028035393742e+00 , -6.3271647593940017e-01 , 8.5884208000000015e+00 , 5.8091199999999998e-01 , -7.9626500000000000e-01 , -1.6882700000000000e-01 -2.3018064671013718e+00 , -2.8422227812566891e-01 , 8.1616359999999997e+00 , -8.2058600000000004e-01 , -3.0661200000000000e-02 , 5.7069999999999999e-01 -2.3022223012166783e+00 , 7.1804364731580028e-02 , 7.6783999999999999e+00 , 5.0471600000000005e-01 , 6.8562299999999998e-01 , -5.2457799999999999e-01 -2.2834012662525680e+00 , 1.0120322214622113e-01 , 7.8203079999999998e+00 , -9.7618899999999995e-02 , -9.0463000000000005e-01 , 4.1486699999999999e-01 -2.2671212835511096e+00 , 1.7058143406435078e-01 , 7.8871175999999998e+00 , -1.1360199999999999e-01 , -9.1314799999999996e-01 , 3.9147999999999999e-01 -2.2272731887750310e+00 , -1.1832902231465159e-02 , 8.5226927999999997e+00 , -6.4985300000000001e-01 , 7.1928900000000004e-02 , -7.5664900000000002e-01 -2.2064779522872993e+00 , 4.1943673232773371e-02 , 8.6586935999999994e+00 , -6.5000100000000005e-01 , 4.5654499999999998e-01 , -6.0750700000000002e-01 -2.1478979489506660e+00 , -2.1483444342863089e-01 , 9.5746736000000006e+00 , 3.3910099999999999e-01 , 6.2059200000000003e-01 , 7.0701999999999998e-01 -2.1714005041063942e+00 , 2.3621862469912558e-01 , 8.7353312000000010e+00 , 9.7202400000000000e-01 , -7.4292499999999997e-02 , 2.2282299999999999e-01 -2.1450376490593843e+00 , 2.6708112926140548e-01 , 8.9566535999999992e+00 , 3.8809900000000001e-02 , -7.8025599999999995e-01 , 6.2425600000000003e-01 -2.1420406478781482e+00 , 4.6082366887455617e-01 , 8.7265328000000011e+00 , -5.4935999999999996e-01 , 3.6615700000000001e-01 , -7.5108799999999998e-01 -2.1100778145238048e+00 , 4.7140781236205997e-01 , 9.0252416000000011e+00 , -4.1853200000000002e-01 , -9.1507299999999993e-03 , 9.0815599999999996e-01 -2.0970883705907797e+00 , 5.9598567128197111e-01 , 8.9872920000000001e+00 , 2.8976299999999999e-01 , 3.5899600000000001e-03 , -9.5709200000000005e-01 -2.0652293478039629e+00 , 6.3249358826651902e-01 , 9.2460231999999998e+00 , 6.4559400000000000e-01 , -2.4940599999999999e-01 , 7.2180699999999998e-01 -2.0610620186021094e+00 , 7.9671108443986172e-01 , 9.0640959999999993e+00 , 3.4354200000000001e-01 , -5.8396700000000001e-01 , 7.3550099999999996e-01 -2.0436327347400010e+00 , 8.9490006263238864e-01 , 9.1102823999999991e+00 , 1.9661100000000001e-01 , 1.5612000000000001e-01 , 9.6797200000000005e-01 -2.0316624440584858e+00 , 1.0165965606637712e+00 , 9.0635344000000000e+00 , -2.7592800000000001e-01 , 5.2361300000000000e-01 , 8.0603499999999995e-01 -1.9621905765608159e+00 , 9.6410338255931527e-01 , 9.8158808000000004e+00 , -6.4723900000000001e-02 , 1.7726000000000000e-01 , 9.8203300000000004e-01 -1.8959107025439352e+00 , 9.5523180341081892e-01 , 1.0479733599999999e+01 , -3.7168600000000002e-01 , 4.2965999999999999e-01 , -8.2294699999999998e-01 -1.8537375050109706e+00 , 1.0341250141546738e+00 , 1.0777995199999999e+01 , 1.1954500000000000e-01 , -8.9797899999999997e-01 , 4.2348900000000000e-01 -1.8455640698573108e+00 , 1.1925069369926447e+00 , 1.0645322400000001e+01 , 3.2011600000000001e-01 , 9.3275799999999998e-01 , 1.6579500000000000e-01 -1.8746933466988365e+00 , 1.4084509337799047e+00 , 1.0068486400000001e+01 , 4.1488700000000001e-01 , -2.8076000000000001e-01 , -8.6547300000000005e-01 -1.8532738628166807e+00 , 1.5246909199674661e+00 , 1.0124365600000001e+01 , 3.9803100000000002e-01 , -3.8847199999999998e-01 , -8.3106000000000002e-01 -1.8532803363552650e+00 , 1.6694334194066802e+00 , 9.9310192000000015e+00 , 4.7350500000000001e-01 , -5.5452400000000002e-01 , -6.8432199999999999e-01 -1.8394323622297757e+00 , 1.7922317220614994e+00 , 9.8998608000000008e+00 , 5.6854300000000002e-01 , 2.3950600000000000e-01 , -7.8701699999999997e-01 -1.8447322030939750e+00 , 1.9283926634250437e+00 , 9.6703223999999999e+00 , -4.1839999999999999e-01 , -2.3484500000000000e-01 , -8.7737600000000004e-01 -1.8132479831204829e+00 , 2.0332820876860902e+00 , 9.8416416000000009e+00 , -6.6737599999999997e-01 , 2.8499700000000000e-01 , 6.8803099999999995e-01 -1.7679855106664304e+00 , 2.1400049341255762e+00 , 1.0135067200000000e+01 , -9.4752800000000004e-01 , 2.0747499999999999e-01 , 2.4319800000000000e-01 -1.7749650615708954e+00 , 2.2673456531431944e+00 , 9.8989975999999995e+00 , -8.5365399999999994e-02 , 2.1235499999999999e-01 , 9.7345700000000002e-01 -1.7490927533082272e+00 , 2.3859110327394317e+00 , 9.9918279999999999e+00 , -7.8957900000000003e-01 , 3.2001900000000000e-01 , 5.2359599999999995e-01 -1.7417410444961854e+00 , 2.5049931477393952e+00 , 9.9067144000000003e+00 , -5.8395300000000006e-01 , 7.4305200000000005e-01 , -3.2691399999999998e-01 -1.7512576467256493e+00 , 2.6161328799362571e+00 , 9.6645608000000003e+00 , -4.9362999999999997e-02 , 6.8572800000000000e-01 , 7.2618199999999999e-01 -1.7466933305565986e+00 , 2.7248565246052405e+00 , 9.5549759999999999e+00 , 2.2605700000000001e-01 , 2.6084700000000000e-01 , 9.3854000000000004e-01 -1.7342472177201267e+00 , 2.8374219171878341e+00 , 9.5365679999999990e+00 , -5.2131899999999998e-01 , 4.1385499999999999e-02 , -8.5235799999999995e-01 -1.5571954346246057e+00 , 3.0698027430272319e+00 , 1.0957884000000000e+01 , -5.9260100000000004e-01 , -2.4844800000000000e-01 , 7.6622299999999999e-01 -1.6906916699444827e+00 , 3.0741551082961873e+00 , 9.6376455999999990e+00 , -4.3839500000000003e-02 , 3.3678999999999998e-01 , 9.4055900000000003e-01 -1.7097920829566244e+00 , 3.1548437758408134e+00 , 9.3465704000000009e+00 , 2.3065600000000000e-01 , 3.0609300000000000e-01 , 9.2363700000000004e-01 -1.7019822224293992e+00 , 3.2564046518934369e+00 , 9.2797815999999997e+00 , 8.7820800000000004e-02 , 9.7681300000000004e-01 , -1.9525400000000001e-01 -2.8431773285962123e+00 , 4.5152466301931526e-01 , 1.3619745600000002e+00 , -6.6425999999999999e-02 , 2.0019899999999999e-01 , 9.7750099999999995e-01 -2.8477242587348832e+00 , 3.9803047638185296e-01 , 1.3767664800000001e+00 , -9.7327800000000006e-02 , 1.5750500000000001e-01 , 9.8270999999999997e-01 -2.8527512426575723e+00 , 3.3602765551022307e-01 , 1.3863167999999999e+00 , -6.3810699999999998e-02 , 1.1990600000000000e-01 , 9.9073199999999995e-01 -2.8603083291251448e+00 , 2.6660029187274059e-01 , 1.3911777600000002e+00 , -7.8725799999999999e-02 , 1.5517700000000001e-01 , 9.8474499999999998e-01 -2.8649222355450816e+00 , 2.0422722489820044e-01 , 1.4040695999999999e+00 , 1.2563600000000000e-01 , -2.2164300000000001e-01 , -9.6700100000000000e-01 -2.8719963624240465e+00 , 1.3346041219883742e-01 , 1.4126797600000001e+00 , -9.5096299999999995e-02 , 2.3186499999999999e-01 , 9.6808799999999995e-01 -2.8772046989347873e+00 , 7.0740935113666747e-02 , 1.4292417600000000e+00 , 7.7194600000000002e-02 , -1.8473500000000001e-01 , -9.7975199999999996e-01 -2.8843394737953600e+00 , -9.9990277033232822e-03 , 1.4358540799999999e+00 , -7.5304999999999997e-02 , 1.8197099999999999e-01 , 9.8041599999999995e-01 -2.8890999119138061e+00 , -7.3032140291235947e-02 , 1.4560612800000001e+00 , -3.1989900000000002e-02 , 1.7359400000000000e-01 , 9.8429800000000001e-01 -2.8967563620332579e+00 , -1.5398470001759623e-01 , 1.4669511200000001e+00 , -4.4277600000000000e-02 , 1.8812599999999999e-01 , 9.8114599999999996e-01 -2.9026035705025333e+00 , -2.2589158940629384e-01 , 1.4854849600000000e+00 , -5.0008200000000003e-02 , 2.3057000000000000e-01 , 9.7177000000000002e-01 -2.9097178798760304e+00 , -3.0699649259846717e-01 , 1.5008291199999999e+00 , -7.0431099999999996e-02 , 1.9434100000000001e-01 , 9.7840199999999999e-01 -2.9165236020379619e+00 , -3.8865207961867432e-01 , 1.5186047999999999e+00 , -8.8909299999999997e-02 , 1.9420599999999999e-01 , 9.7692299999999999e-01 -2.9245124030654228e+00 , -4.7935292816900477e-01 , 1.5338969599999999e+00 , -9.4157299999999999e-02 , 1.9354900000000000e-01 , 9.7656200000000004e-01 -2.9350505375008469e+00 , -5.8956094701788597e-01 , 1.5425092000000000e+00 , -8.7622699999999998e-02 , 1.7275299999999999e-01 , 9.8106000000000004e-01 -2.9433651538884096e+00 , -6.8123567887576542e-01 , 1.5635993600000000e+00 , -8.8898099999999994e-02 , 1.8759700000000001e-01 , 9.7821499999999995e-01 -2.9517457272879977e+00 , -7.8178949768682671e-01 , 1.5827904799999999e+00 , -1.1586399999999999e-01 , 1.9606299999999999e-01 , 9.7372199999999998e-01 -2.9607256420629402e+00 , -8.8379232953654174e-01 , 1.6054520800000001e+00 , 1.0041400000000000e-01 , -1.8808000000000000e-01 , -9.7700699999999996e-01 -2.9724501508078429e+00 , -1.0133168971157782e+00 , 1.6186184799999999e+00 , -8.6148100000000005e-02 , 1.9720499999999999e-01 , 9.7657000000000005e-01 -2.9819941441709137e+00 , -1.1243737412999670e+00 , 1.6438603199999999e+00 , -7.6661400000000005e-02 , 1.7302300000000001e-01 , 9.8192999999999997e-01 -2.9950416948734273e+00 , -1.2657803099625569e+00 , 1.6615621599999999e+00 , -7.3940900000000004e-02 , 2.0094699999999999e-01 , 9.7680699999999998e-01 -3.0036909107211498e+00 , -1.3774642185361250e+00 , 1.6940933600000001e+00 , 6.2341300000000002e-02 , -2.2784799999999999e-01 , -9.7169899999999998e-01 -3.0144487240917854e+00 , -1.5089780925228746e+00 , 1.7234879200000000e+00 , -5.4618199999999999e-02 , 2.1023600000000001e-01 , 9.7612399999999999e-01 -3.0295354459877570e+00 , -1.6694010011413383e+00 , 1.7473881599999999e+00 , -6.4973400000000001e-02 , 1.7491100000000001e-01 , 9.8243800000000003e-01 -3.0451806971346698e+00 , -1.8410544094180294e+00 , 1.7735711999999999e+00 , -1.0966400000000000e-01 , 1.8349399999999999e-01 , 9.7688500000000000e-01 -3.0601526781313853e+00 , -2.0126320658310259e+00 , 1.8053213600000000e+00 , -1.1356900000000000e-01 , 1.6317499999999999e-01 , 9.8003899999999999e-01 -3.0802395348233214e+00 , -2.2247488365928110e+00 , 1.8319370399999999e+00 , -7.3333099999999998e-02 , 1.8794400000000000e-01 , 9.7943800000000003e-01 -3.0972875133829989e+00 , -2.4263501297859200e+00 , 1.8678908800000000e+00 , 1.7302100000000001e-02 , -2.5794699999999998e-01 , -9.6600399999999997e-01 -3.1099492915607603e+00 , -2.5884000318982601e+00 , 1.9200644560000000e+00 , 2.5698200000000000e-03 , 2.6153199999999999e-01 , 9.6519100000000002e-01 -3.1243211220214229e+00 , -2.7805371400474410e+00 , 1.9708497359999999e+00 , 2.8909799999999999e-02 , -2.7578500000000000e-01 , -9.6078399999999997e-01 -3.1400676318731926e+00 , -2.9824553116284811e+00 , 2.0260632319999998e+00 , -6.5582399999999999e-02 , 2.7845199999999998e-01 , 9.5820899999999998e-01 -3.1571200966793018e+00 , -3.1940411394865507e+00 , 2.0863120959999999e+00 , -8.0287600000000001e-02 , 2.5589600000000001e-01 , 9.6336500000000003e-01 -3.1797116342723317e+00 , -3.4659236425423012e+00 , 2.1435293600000001e+00 , -7.0278700000000000e-02 , 2.3846400000000001e-01 , 9.6860500000000005e-01 -3.2021572293696208e+00 , -3.7390560548650980e+00 , 2.2103909599999998e+00 , -6.9714799999999993e-02 , 2.2272200000000000e-01 , 9.7238599999999997e-01 -3.2296552989728782e+00 , -4.0617812493212231e+00 , 2.2798619200000001e+00 , -6.0334300000000000e-02 , 2.1271100000000001e-01 , 9.7525099999999998e-01 -3.2588050714760604e+00 , -4.4148919889673452e+00 , 2.3569789600000002e+00 , -5.8641499999999999e-02 , 2.0967700000000000e-01 , 9.7601099999999996e-01 -3.2953636675058835e+00 , -4.8393596094307130e+00 , 2.4398732000000001e+00 , -5.3578800000000003e-02 , 2.0225499999999999e-01 , 9.7786600000000001e-01 -3.3340259774915015e+00 , -5.2943121553386643e+00 , 2.5352973599999999e+00 , -5.2556300000000000e-02 , 2.1157300000000001e-01 , 9.7594800000000004e-01 -3.3774362968428253e+00 , -5.8096792868425524e+00 , 2.6427990399999999e+00 , -5.3385799999999997e-02 , 2.0310700000000001e-01 , 9.7770000000000001e-01 -3.4327844724929397e+00 , -6.4374219615677823e+00 , 2.7643323999999998e+00 , -5.2189300000000001e-02 , 1.9719200000000001e-01 , 9.7897500000000004e-01 -3.4953989448126475e+00 , -7.1666446907627446e+00 , 2.9054406400000001e+00 , -5.5352199999999997e-02 , 2.0244000000000001e-01 , 9.7772899999999996e-01 -3.5649392445639512e+00 , -7.9770423649029798e+00 , 3.0720424000000000e+00 , -5.1987499999999999e-02 , 2.0584300000000000e-01 , 9.7720300000000004e-01 -3.6424505759628105e+00 , -8.8975529669981093e+00 , 3.2684047999999999e+00 , -2.8841100000000001e-02 , 2.0501400000000000e-01 , 9.7833400000000004e-01 -3.7359638448272561e+00 , -1.0000977781092136e+01 , 3.5034863999999999e+00 , -1.9000699999999999e-02 , 2.1134700000000001e-01 , 9.7722600000000004e-01 -3.8407153760165520e+00 , -1.1265329725557271e+01 , 3.7853264000000002e+00 , 8.0401700000000006e-02 , 2.9372999999999999e-01 , 9.5250100000000004e-01 -3.9074350354575591e+00 , -1.2183072326156065e+01 , 4.0880391999999999e+00 , 2.8647699999999998e-01 , 4.4560499999999997e-01 , 8.4815499999999999e-01 -3.8980758802938018e+00 , -1.2372050688729299e+01 , 4.3600823999999996e+00 , 2.1257999999999999e-01 , 4.9333600000000000e-01 , 8.4346299999999996e-01 -3.9174192002159836e+00 , -1.2855092439442272e+01 , 4.6701688000000008e+00 , 2.6102999999999998e-01 , 4.7685200000000000e-01 , 8.3933000000000002e-01 -4.1790444809157954e+00 , -1.5942114432609753e+01 , 5.3152912000000008e+00 , -2.6097399999999998e-01 , 3.2181700000000002e-01 , 9.1012499999999996e-01 -5.6059305657220921e+00 , -3.2478714968574643e+01 , 8.5677352000000013e+00 , 8.2999500000000004e-02 , 5.1355700000000004e-01 , 8.5403200000000001e-01 -5.5329946137257329e+00 , -3.2404575246979363e+01 , 9.1782880000000002e+00 , 8.2999400000000001e-02 , 5.1355700000000004e-01 , 8.5403200000000001e-01 -5.4628613209242971e+00 , -3.2361065278762084e+01 , 9.7955904000000000e+00 , 2.4872200000000000e-01 , 5.6162500000000004e-01 , 7.8912300000000002e-01 -4.4931609156601535e+00 , -2.2874935989573661e+01 , 9.3450416000000018e+00 , 5.2414000000000005e-01 , -4.6142400000000000e-02 , -8.5038100000000005e-01 -4.4450070734390410e+00 , -2.2887244022397155e+01 , 9.8162343999999990e+00 , 5.2413900000000002e-01 , -4.6142400000000000e-02 , -8.5038199999999997e-01 -4.1982823532587705e+00 , -2.0337115876555984e+01 , 9.5616735999999989e+00 , 2.8742299999999998e-01 , 9.4781599999999999e-01 , -1.3796300000000000e-01 -4.1328283883609425e+00 , -2.0065889094002724e+01 , 9.9081288000000001e+00 , 2.4408700000000000e-01 , 9.2474199999999995e-01 , -2.9201700000000003e-01 -4.2538243118766017e+00 , -2.2366665257406879e+01 , 1.1078971200000000e+01 , -8.9539000000000002e-01 , 3.0257299999999998e-01 , -3.2668999999999998e-01 -4.0433981473102438e+00 , -2.0107681199833532e+01 , 1.0783018400000000e+01 , -3.5237499999999999e-01 , -9.1911699999999996e-01 , 1.7623000000000000e-01 -4.0780494991403664e+00 , -2.1281719642869955e+01 , 1.1646176799999999e+01 , 7.0748200000000006e-01 , -1.0235200000000000e-01 , 6.9928100000000004e-01 -3.8930609820187319e+00 , -1.9251244877082126e+01 , 1.1339044000000001e+01 , -3.9480599999999999e-01 , -9.0577900000000000e-01 , -1.5392600000000001e-01 -3.8462009210115484e+00 , -1.9243447097613387e+01 , 1.1768387200000001e+01 , 9.7418199999999999e-01 , 5.7021200000000001e-02 , 2.1844600000000000e-01 -3.7087222053080531e+00 , -1.7791326162434274e+01 , 1.1594530400000000e+01 , -9.5804500000000004e-01 , -1.9964999999999999e-01 , 2.0564499999999999e-01 -3.4136372897457825e+00 , -1.3608018854548844e+01 , 1.0159715200000001e+01 , 1.8565799999999999e-01 , -8.4282500000000005e-01 , 5.0514999999999999e-01 -3.3731016694605271e+00 , -1.3522536074767595e+01 , 1.0454128800000001e+01 , -3.6289199999999999e-01 , 8.0372800000000000e-01 , -4.7151999999999999e-01 -3.3323760619146259e+00 , -1.3450250097055058e+01 , 1.0756612799999999e+01 , 4.9185400000000001e-01 , -7.7627800000000002e-01 , 3.9429900000000001e-01 -3.5745006122702807e+00 , -1.8666607223397069e+01 , 1.3735672000000001e+01 , 6.9930300000000001e-01 , -3.9552100000000001e-01 , 5.9543199999999996e-01 -3.2433165667942365e+00 , -1.3133191422951572e+01 , 1.1278204000000001e+01 , -3.2719600000000001e-02 , -8.8673400000000002e-01 , 4.6112100000000000e-01 -3.3887689697937247e+00 , -1.6887245638878060e+01 , 1.3689287999999999e+01 , -9.8826300000000000e-01 , -1.4860499999999999e-01 , -3.5391899999999997e-02 -3.3235796547616667e+00 , -1.6486610731734842e+01 , 1.3898432000000000e+01 , 7.8460799999999997e-01 , 6.1491099999999999e-01 , 7.9219700000000004e-02 -3.1072633991817620e+00 , -1.2612154975241381e+01 , 1.2027596800000001e+01 , -2.1540699999999999e-01 , -9.7644500000000001e-01 , -1.2431400000000000e-02 -3.0700071471915926e+00 , -1.2615038120850778e+01 , 1.2385013600000001e+01 , -3.2434299999999999e-01 , -9.4275799999999998e-01 , -7.7518799999999999e-02 -3.0329019629414615e+00 , -1.2672009415848908e+01 , 1.2784488000000000e+01 , -1.3247999999999999e-01 , 9.5423599999999997e-01 , 2.6811099999999999e-01 -2.9986742676814746e+00 , -1.2823582785118544e+01 , 1.3258104000000001e+01 , 1.9554600000000000e-01 , 9.7859499999999999e-01 , 6.4139799999999997e-02 -2.9888666400604222e+00 , -1.3756626004315322e+01 , 1.4290512000000000e+01 , -3.2485799999999998e-01 , 7.1629100000000001e-01 , 6.1757099999999998e-01 -2.9261155590834882e+00 , -1.3156636883136558e+01 , 1.4277303999999999e+01 , 1.2470500000000000e-03 , 4.1891099999999998e-01 , 9.0802700000000003e-01 -2.8436924095060521e+00 , -1.1753947434161065e+01 , 1.3643632000000000e+01 , -6.4790300000000001e-01 , -5.3076500000000004e-01 , 5.4636200000000001e-01 -2.7949411183693234e+00 , -1.1462462528876653e+01 , 1.3804207999999999e+01 , -7.8358600000000000e-03 , 9.9560099999999996e-01 , 9.3368099999999996e-02 -2.5626252934284848e+00 , -2.7232876971099493e+00 , 7.1894024000000005e+00 , -9.8534800000000006e-02 , -3.0223600000000000e-01 , 9.4812700000000005e-01 -2.5453446155324313e+00 , -2.6034529206344574e+00 , 7.2376583999999999e+00 , 4.0581200000000001e-01 , -6.7321500000000001e-01 , 6.1814100000000005e-01 -2.5352825002832775e+00 , -2.9732137531088769e+00 , 7.7033496000000001e+00 , 6.4058999999999999e-01 , 4.0131499999999998e-01 , -6.5466899999999995e-01 -2.5152223077512872e+00 , -2.7842565341187511e+00 , 7.6988360000000009e+00 , 7.2760800000000003e-01 , 3.3671699999999999e-01 , -5.9767000000000003e-01 -2.5840695111478276e+00 , -1.2294175128326621e+01 , 1.6625000000000000e+01 , 1.2470800000000000e-01 , 9.2587900000000001e-01 , 3.5664600000000002e-01 -2.4794538514402520e+00 , -2.7350220169827848e+00 , 7.9830160000000010e+00 , -5.9704999999999997e-01 , -7.9462500000000003e-01 , 1.1000699999999999e-01 -2.4593207485768982e+00 , -1.7611769828733608e+00 , 7.1941240000000004e+00 , -4.2081499999999999e-01 , -8.9053599999999999e-01 , -1.7280100000000001e-01 -2.4431827092073313e+00 , -2.2057603849945151e+00 , 7.7931016000000000e+00 , 1.4899999999999999e-01 , -6.5193900000000005e-01 , 7.4348800000000004e-01 -2.4256768391790668e+00 , -2.0953942905249408e+00 , 7.8417944000000004e+00 , -5.7319200000000003e-01 , -8.1914399999999998e-01 , -2.1308000000000001e-02 -2.4068144206679736e+00 , -2.2574781607990131e+00 , 8.1874384000000013e+00 , -5.3225000000000000e-01 , 5.5757100000000004e-01 , 6.3704400000000005e-01 -2.3867497274299638e+00 , -2.2860687074126167e+00 , 8.3996503999999987e+00 , -6.4816099999999999e-01 , 2.0564800000000000e-01 , 7.3320900000000000e-01 -2.3698846953337172e+00 , -2.0924526412698743e+00 , 8.3609831999999997e+00 , 5.6649000000000005e-01 , -2.6133699999999999e-02 , -8.2365400000000000e-01 -2.3545346869372645e+00 , -1.9147332617478909e+00 , 8.3332672000000017e+00 , 1.8675000000000000e-01 , -8.5731599999999997e-01 , 4.7972199999999998e-01 -2.3434535342327814e+00 , -1.5705769335617870e+00 , 8.0890856000000007e+00 , 4.3258200000000002e-01 , -6.8109200000000003e-01 , -5.9075100000000003e-01 -2.3341533821784077e+00 , -1.2622130408956900e+00 , 7.8679088000000004e+00 , 2.1137800000000001e-01 , 5.9215899999999999e-01 , 7.7760399999999996e-01 -2.3137647713986920e+00 , -1.3089618972441706e+00 , 8.1058504000000013e+00 , -5.3438900000000000e-01 , -8.3742300000000003e-01 , -1.1467800000000000e-01 -2.2873951115637716e+00 , -1.4501241874402431e+00 , 8.4905463999999995e+00 , -4.3058299999999999e-01 , -8.0320999999999998e-01 , -4.1164400000000001e-01 -2.2673303847612436e+00 , -1.4270153959911540e+00 , 8.6589328000000005e+00 , -3.5379100000000002e-01 , 8.9469799999999999e-01 , -2.7266800000000002e-01 -2.2531917047480166e+00 , -1.2601819567123655e+00 , 8.6196103999999991e+00 , -8.0367800000000003e-03 , 7.7151800000000004e-01 , 6.3615699999999997e-01 -2.2256846228334930e+00 , -1.3428718630803504e+00 , 8.9622695999999991e+00 , -3.1043199999999999e-01 , 8.8488599999999995e-01 , 3.4728700000000001e-01 -2.2344977842188958e+00 , -8.4949588658321673e-01 , 8.3878360000000001e+00 , 5.8050500000000005e-01 , -5.5819900000000000e-01 , -5.9281399999999995e-01 -2.2209224289730907e+00 , -7.2549309329778167e-01 , 8.3890528000000000e+00 , -6.4410500000000004e-01 , 5.8745400000000003e-01 , 4.8992599999999997e-01 -2.2158462757264026e+00 , -4.9973258984420044e-01 , 8.2067095999999999e+00 , 2.8364000000000000e-02 , 5.2514200000000000e-01 , 8.5054200000000002e-01 -2.2024101020345386e+00 , -4.0058560681145039e-01 , 8.2374520000000011e+00 , 1.4268400000000001e-01 , 4.1019200000000000e-01 , 9.0076800000000001e-01 -2.2203145489206464e+00 , 3.0645774848399254e-02 , 7.6305391999999994e+00 , 3.7689800000000001e-01 , 9.1201600000000005e-01 , 1.6178500000000001e-01 -2.2042497935231347e+00 , 7.7921364939275151e-02 , 7.7352880000000006e+00 , -1.7155699999999999e-02 , -9.7493200000000002e-01 , 2.2184200000000001e-01 -2.1852597355622070e+00 , 1.0502570508691567e-01 , 7.8868472000000001e+00 , 3.6167300000000002e-01 , 9.0075300000000003e-01 , -2.4049200000000001e-01 -2.1256574302870348e+00 , -1.8290284638397436e-01 , 8.7376192000000010e+00 , -5.5744899999999997e-01 , 6.3282200000000000e-01 , -5.3738900000000001e-01 -2.1201861131620015e+00 , -1.3336185459514649e-02 , 8.6188824000000004e+00 , 6.6353899999999999e-01 , -4.1943500000000000e-01 , 6.1950799999999995e-01 -2.0945254435529539e+00 , 7.1314158183519716e-03 , 8.8414736000000005e+00 , 5.6444300000000003e-01 , -5.8235800000000004e-01 , 5.8503300000000003e-01 -2.0836956791700043e+00 , 1.3807890536549583e-01 , 8.8039503999999997e+00 , 3.9422900000000000e-01 , -6.7871400000000004e-01 , 6.1962099999999998e-01 -2.0849703497761416e+00 , 3.2919616432649557e-01 , 8.5986128000000015e+00 , 8.1683600000000001e-01 , 1.0612400000000000e-01 , 5.6702500000000000e-01 -2.0524821757854124e+00 , 3.2456300583690245e-01 , 8.9165512000000007e+00 , 1.3902999999999999e-01 , -2.4364100000000000e-01 , -9.5984899999999995e-01 -2.0483311936388953e+00 , 4.7937139394559947e-01 , 8.7933319999999995e+00 , -3.6762400000000001e-01 , -7.5026300000000001e-01 , 5.4950699999999997e-01 -2.0274361846601208e+00 , 5.4796265505900443e-01 , 8.9237895999999992e+00 , -2.9095500000000002e-01 , -6.8290300000000004e-01 , 6.7006600000000005e-01 -1.9950643369263983e+00 , 5.7580311742253332e-01 , 9.2026448000000016e+00 , 1.4809600000000001e-01 , -7.7963499999999997e-01 , 6.0847200000000001e-01 -2.0018517459786898e+00 , 7.6313533970752978e-01 , 8.9428216000000003e+00 , -1.6119100000000000e-01 , -1.5848999999999999e-01 , 9.7411400000000004e-01 -1.9672731499186982e+00 , 7.9484736230234909e-01 , 9.2403967999999992e+00 , 4.7534599999999999e-01 , 2.2890600000000000e-01 , 8.4949900000000000e-01 -1.9724812564246419e+00 , 9.6034139577047006e-01 , 9.0246695999999993e+00 , 4.2343500000000001e-01 , -4.6574800000000000e-02 , -9.0472799999999998e-01 -1.9575267792651265e+00 , 1.0599637339236487e+00 , 9.0679648000000004e+00 , 2.4581800000000001e-01 , -4.4044699999999998e-01 , -8.6346999999999996e-01 -1.8804215364400918e+00 , 1.0097083246418328e+00 , 9.8403312000000014e+00 , 2.0934400000000000e-01 , 1.7509500000000000e-01 , -9.6203799999999995e-01 -1.8060270290758089e+00 , 9.9873234889069074e-01 , 1.0544712800000001e+01 , -3.8733299999999998e-01 , 3.8696199999999997e-01 , -8.3679999999999999e-01 -1.7814956786545784e+00 , 1.1118499426693793e+00 , 1.0668753600000001e+01 , 1.1954500000000000e-01 , -8.9797899999999997e-01 , 4.2348999999999998e-01 -1.8160058070825582e+00 , 1.3300880388929661e+00 , 1.0125530400000001e+01 , 4.1488700000000001e-01 , -2.8076000000000001e-01 , -8.6547300000000005e-01 -1.8074002041886297e+00 , 1.4626165155991835e+00 , 1.0069994400000001e+01 , -3.0102899999999999e-01 , 5.5474000000000001e-01 , 7.7565799999999996e-01 -1.8056379644540703e+00 , 1.5999820171427355e+00 , 9.9503319999999995e+00 , 3.7223299999999998e-01 , -6.8341900000000000e-01 , -6.2799799999999995e-01 -1.8054024044435368e+00 , 1.7346740925945001e+00 , 9.8177215999999987e+00 , -5.3410100000000005e-01 , 2.1435599999999999e-01 , 8.1779500000000005e-01 -1.7904808824182079e+00 , 1.8507753797697231e+00 , 9.8374191999999994e+00 , 7.0248800000000000e-01 , 5.2204700000000000e-02 , -7.0977800000000002e-01 -1.7743171133833160e+00 , 1.9664613274248814e+00 , 9.8758680000000005e+00 , -5.7643200000000006e-01 , 5.1988699999999999e-01 , 6.3043199999999999e-01 -1.7652218147496734e+00 , 2.0869940644632918e+00 , 9.8397384000000017e+00 , -8.6693900000000002e-01 , -1.2199800000000000e-01 , 4.8325400000000002e-01 -1.7405398478097989e+00 , 2.2018702297064117e+00 , 9.9566759999999999e+00 , 9.8849200000000004e-01 , 9.5637100000000003e-02 , -1.1720300000000000e-01 -1.7321782779559043e+00 , 2.3226152639605027e+00 , 9.9059448000000003e+00 , -9.9490999999999996e-01 , -1.0075400000000000e-01 , -1.7125199999999999e-03 -1.7238230822759866e+00 , 2.4418526316126203e+00 , 9.8635544000000017e+00 , -2.1246799999999999e-01 , 4.2945000000000000e-01 , 8.7774099999999999e-01 -1.7129370200852234e+00 , 2.5596452754183643e+00 , 9.8503360000000004e+00 , -3.4484799999999999e-01 , -6.7157000000000000e-01 , -6.5580000000000005e-01 -1.7291540707346915e+00 , 2.6672969727473288e+00 , 9.5870287999999988e+00 , 8.2233000000000001e-02 , 6.3579900000000000e-01 , 7.6746199999999998e-01 -1.7211463895779049e+00 , 2.7789517539810653e+00 , 9.5492352000000018e+00 , 5.6601699999999998e-02 , 4.7004299999999999e-01 , 8.8082700000000003e-01 -1.2329720168748990e+00 , 3.2057301928347872e+00 , 1.3703120000000000e+01 , 7.4490500000000004e-01 , -6.6710700000000001e-01 , 9.2175999999999994e-03 -1.6870845442488032e+00 , 3.0148589068319351e+00 , 9.6324767999999992e+00 , -2.2338100000000000e-02 , -6.3126000000000002e-02 , 9.9775599999999998e-01 -1.6785321465504013e+00 , 3.1263714339842168e+00 , 9.5991344000000005e+00 , 3.9967400000000004e-03 , 6.4641400000000004e-01 , 7.6297599999999999e-01 -1.6993848206677482e+00 , 3.2078715979711574e+00 , 9.3281935999999988e+00 , -3.3774300000000002e-01 , -2.3754100000000000e-01 , -9.1077100000000000e-01 -1.6958114229240153e+00 , 3.3091664260023910e+00 , 9.2609992000000005e+00 , 8.3844100000000005e-02 , 9.8424699999999998e-01 , -1.5565399999999999e-01 -2.8069063798828395e+00 , 2.7667988310075575e-01 , 1.3665526400000001e+00 , -1.5642000000000000e-01 , 2.0270800000000000e-01 , 9.6666600000000003e-01 -2.8082281818753660e+00 , 2.2964165169381867e-01 , 1.3916041600000000e+00 , -1.1101900000000001e-01 , 1.6167899999999999e-01 , 9.8057899999999998e-01 -2.8123023480097573e+00 , 1.5875484694881847e-01 , 1.3990276800000001e+00 , -8.3073300000000003e-02 , 2.0218400000000000e-01 , 9.7581799999999996e-01 -2.8155550907975044e+00 , 9.5883016442328994e-02 , 1.4144280000000000e+00 , -9.0760900000000005e-02 , 2.3265700000000000e-01 , 9.6831500000000004e-01 -2.8186029300798423e+00 , 3.3372887850502853e-02 , 1.4315474400000001e+00 , -6.3366000000000006e-02 , 2.0005600000000001e-01 , 9.7773299999999996e-01 -2.8245970017815769e+00 , -4.7152622936849742e-02 , 1.4389449600000002e+00 , 7.2808600000000001e-02 , -1.9661200000000001e-01 , -9.7777400000000003e-01 -2.8276942218387560e+00 , -1.1961696257421206e-01 , 1.4541684799999999e+00 , 7.0736499999999994e-02 , -1.9770699999999999e-01 , -9.7770599999999996e-01 -2.8331553538402630e+00 , -2.0030356320705911e-01 , 1.4659194400000000e+00 , -8.1581000000000001e-02 , 2.2589100000000001e-01 , 9.7072999999999998e-01 -2.8367865356323287e+00 , -2.7299923220977895e-01 , 1.4853185600000001e+00 , 1.0814400000000000e-01 , -1.8130700000000000e-01 , -9.7746200000000005e-01 -2.8436225238852164e+00 , -3.7293233981988338e-01 , 1.4914774399999999e+00 , -1.3518300000000000e-01 , 2.0282300000000000e-01 , 9.6984000000000004e-01 -2.8466972122942793e+00 , -4.4575142714001936e-01 , 1.5154317600000000e+00 , -1.1378099999999999e-01 , 1.9715299999999999e-01 , 9.7374799999999995e-01 -2.8528926851254717e+00 , -5.4565520079418883e-01 , 1.5268540799999999e+00 , 1.1404200000000000e-01 , -1.7660699999999999e-01 , -9.7765299999999999e-01 -2.8568418651884988e+00 , -6.2807023347248236e-01 , 1.5507584800000001e+00 , -8.6878499999999997e-02 , 1.7923000000000000e-01 , 9.7996399999999995e-01 -2.8636839940088468e+00 , -7.3936703851843255e-01 , 1.5637543200000001e+00 , -1.1819900000000000e-01 , 1.5329799999999999e-01 , 9.8108600000000001e-01 -2.8725835137229967e+00 , -8.5944698108031004e-01 , 1.5757091200000000e+00 , -1.1097799999999999e-01 , 2.1592300000000000e-01 , 9.7008300000000003e-01 -2.8758596032615173e+00 , -9.5164433126726289e-01 , 1.6036892800000000e+00 , -8.6266200000000001e-02 , 2.1389500000000000e-01 , 9.7304000000000002e-01 -2.8838538848385813e+00 , -1.0734252226142500e+00 , 1.6228356800000001e+00 , -8.7741200000000005e-02 , 1.8223200000000001e-01 , 9.7933300000000001e-01 -2.8917491924031249e+00 , -1.2038002883686389e+00 , 1.6415005599999999e+00 , -6.3015100000000004e-02 , 1.7031499999999999e-01 , 9.8337300000000005e-01 -2.8990908517081770e+00 , -1.3353911826760569e+00 , 1.6645209599999999e+00 , -6.3167100000000004e-02 , 2.3195900000000000e-01 , 9.7067300000000001e-01 -2.9056533113701422e+00 , -1.4579504487977153e+00 , 1.6953122400000000e+00 , 5.3413799999999997e-02 , -2.2522200000000001e-01 , -9.7284199999999998e-01 -2.9133027210086286e+00 , -1.5992415610925135e+00 , 1.7229388000000001e+00 , -8.5938700000000007e-02 , 1.7332400000000001e-01 , 9.8110799999999998e-01 -2.9240866600416338e+00 , -1.7713286068730887e+00 , 1.7459633600000000e+00 , -1.1320800000000000e-01 , 1.5154599999999999e-01 , 9.8194599999999999e-01 -2.9342507922122087e+00 , -1.9423315799901943e+00 , 1.7742503199999999e+00 , 1.3380100000000000e-01 , -1.7393400000000001e-01 , -9.7562499999999996e-01 -2.9461061546417686e+00 , -2.1346286211717320e+00 , 1.8026423199999999e+00 , -9.9530499999999994e-02 , 1.8426699999999999e-01 , 9.7782400000000003e-01 -2.9583303108693024e+00 , -2.3378232199523481e+00 , 1.8349353600000000e+00 , 2.1543300000000001e-02 , -2.2895599999999999e-01 , -9.7319800000000001e-01 -2.9638629562934482e+00 , -2.4801907245594279e+00 , 1.8884038400000001e+00 , -1.7949000000000000e-02 , 2.5742799999999999e-01 , 9.6613099999999996e-01 -2.9723841240384079e+00 , -2.6618623674173056e+00 , 1.9371931520000001e+00 , -3.5298099999999999e-02 , 2.6760000000000000e-01 , 9.6288300000000004e-01 -2.9835055491904723e+00 , -2.8744806921504527e+00 , 1.9857335920000001e+00 , -5.8651300000000003e-02 , 2.5148500000000001e-01 , 9.6608200000000000e-01 -2.9948327605793121e+00 , -3.0977218835555584e+00 , 2.0395913440000002e+00 , -7.2493600000000005e-02 , 2.6353199999999999e-01 , 9.6192299999999997e-01 -3.0074268679411724e+00 , -3.3404118624775698e+00 , 2.0972960559999998e+00 , -7.3350499999999999e-02 , 2.5000099999999997e-01 , 9.6546299999999996e-01 -3.0201279544531392e+00 , -3.5924607428571136e+00 , 2.1613268799999998e+00 , -8.2836199999999999e-02 , 2.3676900000000001e-01 , 9.6802800000000000e-01 -3.0368803485206044e+00 , -3.8963215415156736e+00 , 2.2272389600000002e+00 , -8.4685099999999999e-02 , 2.2714599999999999e-01 , 9.7017200000000003e-01 -3.0554354213840291e+00 , -4.2395995225202148e+00 , 2.2981908799999999e+00 , -7.5502799999999995e-02 , 2.2133100000000000e-01 , 9.7227200000000003e-01 -3.0754924029209887e+00 , -4.6140998893307410e+00 , 2.3779037600000001e+00 , -6.4196699999999995e-02 , 2.1215200000000001e-01 , 9.7512600000000005e-01 -3.1006943440427630e+00 , -5.0606601099502591e+00 , 2.4646636800000001e+00 , -6.4224000000000003e-02 , 2.1126000000000000e-01 , 9.7531800000000002e-01 -3.1259862489451953e+00 , -5.5257085918426112e+00 , 2.5650881600000002e+00 , -7.0983199999999996e-02 , 2.1275900000000000e-01 , 9.7452300000000003e-01 -3.1583431905189721e+00 , -6.1046297395474056e+00 , 2.6762880800000000e+00 , -6.3874899999999998e-02 , 2.0567500000000000e-01 , 9.7653400000000001e-01 -3.1936818127721485e+00 , -6.7437611146275280e+00 , 2.8055132800000000e+00 , -5.9501199999999997e-02 , 2.0297299999999999e-01 , 9.7737499999999999e-01 -3.2368280577493387e+00 , -7.5054434138324968e+00 , 2.9553044800000001e+00 , -5.4122999999999998e-02 , 2.1096000000000001e-01 , 9.7599499999999995e-01 -3.2826111114673515e+00 , -8.3468461613606024e+00 , 3.1316031999999998e+00 , -4.4006299999999998e-02 , 2.0852299999999999e-01 , 9.7702699999999998e-01 -3.3372919062787298e+00 , -9.3413204400716570e+00 , 3.3407679999999997e+00 , -2.7777400000000001e-02 , 2.1215400000000001e-01 , 9.7684199999999999e-01 -3.3980190211930394e+00 , -1.0477495685606085e+01 , 3.5904199999999999e+00 , -3.1834699999999999e-03 , -2.4302199999999999e-01 , -9.7001599999999999e-01 -3.4525407363485301e+00 , -1.1586702174139516e+01 , 3.8781151999999999e+00 , 2.2663800000000001e-01 , 4.4820399999999999e-01 , 8.6472400000000005e-01 -3.4565014434903416e+00 , -1.2038480797116275e+01 , 4.1559616000000004e+00 , 2.5746400000000003e-01 , 4.2676999999999998e-01 , 8.6693699999999996e-01 -3.4615943408284302e+00 , -1.2525578519135896e+01 , 4.4534432000000006e+00 , 2.3617600000000000e-01 , 4.5152300000000001e-01 , 8.6043499999999995e-01 -3.5429409343823650e+00 , -1.4204067474773616e+01 , 4.8993848000000000e+00 , 2.6979099999999999e-02 , 2.8335600000000000e-01 , 9.5863500000000001e-01 -3.7046914468522454e+00 , -1.7250000477108305e+01 , 5.5790144000000002e+00 , -3.6729299999999998e-01 , 3.8530199999999998e-01 , 8.4654499999999999e-01 -4.5568981387668313e+00 , -3.2773391449514996e+01 , 8.7996656000000009e+00 , -8.0329399999999995e-02 , -7.0805399999999996e-01 , -7.0157499999999995e-01 -4.2304404452881776e+00 , -2.8330306696951308e+01 , 8.6264327999999999e+00 , -3.0544100000000001e-02 , -4.7484300000000002e-01 , 8.7953999999999999e-01 -4.4063483134388655e+00 , -3.2583189711015372e+01 , 1.0022643200000001e+01 , -3.3426400000000002e-02 , -9.9723899999999999e-01 , -6.6312899999999994e-02 -4.5339333678463500e+00 , -3.6247059945760881e+01 , 1.1448888800000001e+01 , 5.0253199999999998e-01 , 3.4554900000000000e-01 , 7.9250100000000001e-01 -4.4517939394011519e+00 , -3.6171071827807772e+01 , 1.2135455200000001e+01 , 5.0253199999999998e-01 , 3.4554800000000002e-01 , 7.9250100000000001e-01 -4.3660756047765199e+00 , -3.6032670622328418e+01 , 1.2809032000000000e+01 , -6.1520799999999998e-01 , -4.4834800000000002e-01 , -6.4846199999999998e-01 -3.5498784805745487e+00 , -2.0603320203251595e+01 , 9.3300552000000003e+00 , 2.8742299999999998e-01 , 9.4781499999999996e-01 , -1.3796300000000000e-01 -3.4706220322845049e+00 , -1.9915311664135540e+01 , 9.5605608000000011e+00 , -7.4547699999999995e-01 , -3.2545000000000002e-01 , 5.8167599999999997e-01 -3.4378517276952278e+00 , -2.0238814640005877e+01 , 1.0082027200000001e+01 , 5.6266300000000002e-01 , 4.0882499999999999e-01 , -7.1852099999999997e-01 -3.3330968865075192e+00 , -1.8872168275272220e+01 , 1.0065439200000000e+01 , -8.3167300000000000e-01 , -2.1769100000000000e-01 , 5.1081399999999999e-01 -3.2889229731236016e+00 , -1.8897252287283660e+01 , 1.0484798400000001e+01 , 9.9156299999999997e-01 , -8.8236800000000004e-02 , -9.4962699999999997e-02 -3.1736968353667496e+00 , -1.7049798102783303e+01 , 1.0222604000000000e+01 , 7.7516399999999996e-01 , 6.1481600000000003e-01 , 1.4533299999999999e-01 -3.2330954231847313e+00 , -1.9968872568733978e+01 , 1.1736687999999999e+01 , 4.1728599999999999e-01 , -1.7605199999999999e-01 , 8.9155899999999999e-01 -3.1872866468807626e+00 , -2.0086714357796151e+01 , 1.2233048800000001e+01 , 2.6323200000000002e-01 , -1.6532100000000000e-01 , 9.5046200000000003e-01 -3.0595718312448161e+00 , -1.7555544497367713e+01 , 1.1608726400000000e+01 , -9.3945900000000004e-01 , -2.6967600000000003e-01 , 2.1140300000000001e-01 -3.0067253984970992e+00 , -1.7320600219318468e+01 , 1.1915079200000001e+01 , 9.9911700000000003e-01 , 3.1087000000000000e-02 , -2.8277699999999999e-02 -2.9503025169972710e+00 , -1.6902801558340936e+01 , 1.2132241600000000e+01 , -9.0826300000000004e-01 , -2.8762500000000002e-01 , 3.0385800000000002e-01 -2.9412618877055325e+00 , -1.8471001240404089e+01 , 1.3311768000000001e+01 , -9.6645099999999995e-01 , 2.5053599999999998e-01 , -5.6610599999999997e-02 -2.8296295354842336e+00 , -1.5552221904422591e+01 , 1.2269854400000000e+01 , -9.8871500000000001e-01 , 6.3580999999999999e-02 , -1.3564899999999999e-01 -2.7554882921112291e+00 , -1.3942414525550477e+01 , 1.1805920800000001e+01 , -2.0730199999999999e-01 , 9.6358100000000002e-01 , -1.6892900000000000e-01 -2.7128002177868922e+00 , -1.3797943535474547e+01 , 1.2092700800000001e+01 , 4.5470200000000000e-01 , -7.5618799999999997e-01 , 4.7055900000000001e-01 -2.6558149645418285e+00 , -1.2659099702710549e+01 , 1.1803840800000000e+01 , 2.7759800000000001e-01 , -8.2752099999999995e-01 , 4.8800399999999999e-01 -2.6179054139222782e+00 , -1.2720478660438939e+01 , 1.2192176800000000e+01 , 6.5747400000000000e-01 , -7.2185699999999997e-01 , -2.1598899999999999e-01 -2.6026694070007204e+00 , -1.5715910801146673e+01 , 1.4428520000000001e+01 , -7.5521699999999997e-02 , -3.1622699999999998e-01 , 9.4567299999999999e-01 -2.5538500298944973e+00 , -1.5848582311347471e+01 , 1.4955904000000000e+01 , 2.1580400000000000e-02 , -6.2606099999999998e-01 , 7.7947599999999995e-01 -2.4988245317366697e+00 , -1.4201367563283867e+01 , 1.4297791999999999e+01 , 8.3310799999999996e-01 , -5.5260399999999998e-01 , -2.3648300000000001e-02 -2.4520264549281965e+00 , -1.4115562517688705e+01 , 1.4660856000000001e+01 , -1.4780399999999999e-01 , 2.9452499999999998e-01 , 9.4414500000000001e-01 -2.4020428492529855e+00 , -1.4670490337682498e+01 , 1.5495352000000000e+01 , -5.0113099999999999e-01 , 6.3428600000000002e-02 , -8.6304400000000003e-01 -2.3647325216685591e+00 , -1.2393286285787381e+01 , 1.4236120000000000e+01 , 1.3580000000000000e-01 , 4.0076200000000001e-01 , 9.0606200000000003e-01 -2.3296488786976113e+00 , -1.1288204263181616e+01 , 1.3779560000000000e+01 , 7.4998400000000007e-02 , 9.5140100000000005e-01 , -2.9868400000000001e-01 -2.3857522803931257e+00 , -3.0260957408136031e+00 , 7.4774928000000003e+00 , -4.8594900000000003e-02 , -3.0862099999999998e-01 , 9.4994299999999998e-01 -2.3686660955693961e+00 , -2.9656672960178643e+00 , 7.5840095999999999e+00 , -2.4450300000000000e-01 , -4.5728700000000000e-01 , 8.5504800000000003e-01 -2.3547523810822026e+00 , -2.7767481186475003e+00 , 7.5806607999999995e+00 , 2.7764500000000001e-02 , -5.0935699999999995e-01 , 8.6010699999999995e-01 -2.3397473390596737e+00 , -2.6437712767783523e+00 , 7.6208048000000010e+00 , 3.3228200000000002e-01 , -4.4927400000000001e-01 , 8.2930199999999998e-01 -2.3234854972458940e+00 , -2.5873885044047871e+00 , 7.7285696000000002e+00 , -2.8834900000000002e-01 , -9.4349000000000005e-01 , 1.6334699999999999e-01 -2.3027810791479557e+00 , -2.6851685277773845e+00 , 7.9871759999999998e+00 , -3.2408300000000001e-01 , -9.4592200000000004e-01 , 1.4213900000000000e-02 -2.2834685151295919e+00 , -2.6732403730021392e+00 , 8.1477000000000004e+00 , -3.9039800000000002e-01 , -8.6796700000000004e-01 , 3.0695699999999998e-01 -2.2651468324686954e+00 , -2.6278866750272245e+00 , 8.2793120000000009e+00 , 5.1342300000000000e-02 , -6.3650399999999996e-01 , 7.6956300000000000e-01 -2.2522192736220701e+00 , -2.4659861530395952e+00 , 8.2895664000000000e+00 , -4.2250500000000002e-01 , -6.2395899999999997e-02 , 9.0421099999999999e-01 -2.2454894036519444e+00 , -2.1514983537355921e+00 , 8.1256832000000010e+00 , 8.8302000000000003e-01 , -2.2674699999999999e-02 , -4.6878700000000001e-01 -2.2349576908446540e+00 , -1.9674009916340585e+00 , 8.0937967999999998e+00 , 6.3743700000000003e-01 , 7.4336300000000000e-01 , -2.0269499999999999e-01 -2.2119698827245502e+00 , -2.0138702555446617e+00 , 8.3273080000000004e+00 , 6.2020600000000004e-01 , 2.1813000000000002e-03 , -7.8443600000000002e-01 -2.1995789514268798e+00 , -1.8825919272350040e+00 , 8.3543272000000002e+00 , -5.7272199999999995e-01 , 5.1626199999999997e-02 , 8.1812200000000002e-01 -2.2127949494483392e+00 , -1.3345230249509776e+00 , 7.8467240000000000e+00 , -5.4693400000000003e-01 , -7.0153500000000002e-01 , -4.5684900000000001e-01 -2.2004529986039754e+00 , -1.2384968620219836e+00 , 7.8938568000000000e+00 , -5.4987799999999998e-01 , -8.0293499999999995e-01 , -2.3006199999999999e-01 -2.1562147300493635e+00 , -1.5642608401310243e+00 , 8.5178984000000000e+00 , -2.0491000000000001e-01 , -3.7283899999999998e-01 , 9.0498800000000001e-01 -2.1360188738425929e+00 , -1.5409239533524279e+00 , 8.6874080000000014e+00 , 7.8908400000000001e-01 , -6.1164499999999999e-01 , -5.6897400000000001e-02 -2.1030232813258878e+00 , -1.6412698017958087e+00 , 9.0466447999999993e+00 , -2.1876300000000001e-01 , -9.7577499999999995e-01 , 2.3657900000000000e-03 -2.0938012743429826e+00 , -1.4686326831861725e+00 , 9.0108584000000000e+00 , 6.9154499999999997e-01 , -7.2231400000000001e-01 , 5.2732999999999999e-03 -2.0783237694937715e+00 , -1.3645194558032072e+00 , 9.0763680000000004e+00 , -9.9229599999999998e-03 , 8.4370999999999996e-01 , 5.3670799999999996e-01 -2.0274232884919532e+00 , -1.5987300387244021e+00 , 9.7001704000000011e+00 , 2.3088500000000001e-01 , -8.9084700000000006e-01 , -3.9125900000000002e-01 -2.1209000586696352e+00 , -5.1221960009522549e-01 , 8.0981440000000013e+00 , 1.4268400000000001e-01 , 4.1019200000000000e-01 , 9.0076800000000001e-01 -2.1177280334530040e+00 , -3.4799135324746944e-01 , 8.0113664000000000e+00 , -8.3585900000000002e-01 , -1.6967699999999999e-01 , 5.2206200000000003e-01 -2.0927183014877819e+00 , -3.6013896340178997e-01 , 8.2408631999999997e+00 , 1.4874200000000001e-01 , 6.5436399999999995e-01 , 7.4140700000000004e-01 -2.1191534883033931e+00 , 5.2899461963442640e-03 , 7.7519176000000005e+00 , 3.9908700000000003e-01 , -8.6238099999999995e-01 , -3.1149300000000002e-01 -2.1184906112347739e+00 , 1.6074173906531541e-01 , 7.6431856000000007e+00 , 3.5855999999999999e-01 , 9.0938200000000002e-01 , 2.1085400000000001e-01 -1.9494060605099972e+00 , -7.6707677357411308e-01 , 9.8217256000000006e+00 , -3.2442199999999999e-01 , 3.2459600000000000e-01 , -8.8847500000000001e-01 -2.0232983878489570e+00 , -1.2105194879340031e-01 , 8.7012295999999996e+00 , 2.9562800000000000e-01 , -4.8558400000000002e-01 , 8.2268600000000003e-01 -2.0105324872755208e+00 , -2.2787800975802242e-02 , 8.7435679999999998e+00 , 5.6832700000000003e-01 , 4.9339100000000002e-01 , -6.5846000000000005e-01 -1.9177914437288923e+00 , -3.3965443848800314e-01 , 9.8019864000000005e+00 , -5.5429499999999998e-01 , -8.0737900000000001e-02 , -8.2839499999999999e-01 -1.9799198446334925e+00 , 1.4600135122324032e-01 , 8.9001920000000005e+00 , 6.4272399999999996e-01 , -4.1184799999999999e-01 , 6.4597800000000005e-01 -1.9619598089738528e+00 , 2.1891220580195769e-01 , 9.0157880000000006e+00 , 7.6023300000000002e-02 , 4.2451600000000000e-01 , 9.0222300000000000e-01 -1.9697163828697790e+00 , 4.0571930389567834e-01 , 8.8168047999999999e+00 , -6.0340300000000002e-01 , 3.0113400000000001e-01 , -7.3839299999999997e-01 -1.9511826256786000e+00 , 4.8003130729256216e-01 , 8.9287296000000005e+00 , -2.8853499999999999e-01 , -3.9412399999999997e-01 , 8.7258999999999998e-01 -1.9412367032646811e+00 , 5.8800361513615074e-01 , 8.9407416000000008e+00 , -3.0804599999999999e-01 , -3.9584900000000001e-01 , 8.6510799999999999e-01 -1.9270984188643989e+00 , 6.7911329943564969e-01 , 9.0104839999999999e+00 , 7.5260499999999994e-02 , 1.8301400000000001e-01 , -9.8022500000000001e-01 -1.9136315621359095e+00 , 7.7751125602983873e-01 , 9.0585944000000005e+00 , 3.8444600000000001e-01 , 8.1853900000000002e-01 , -4.2684200000000000e-01 -1.9099278350195890e+00 , 9.0272987462886278e-01 , 9.0047119999999996e+00 , 1.0337400000000000e-02 , -2.0664500000000000e-01 , 9.7836100000000004e-01 -1.9021997303086908e+00 , 1.0133876044819252e+00 , 8.9989088000000006e+00 , 3.3504200000000001e-01 , -4.5454299999999997e-01 , -8.2531100000000002e-01 -1.8579077668964363e+00 , 1.0402082163297319e+00 , 9.3755552000000009e+00 , 7.0462000000000002e-01 , -1.4930900000000000e-01 , 6.9369800000000004e-01 -1.7253841268566157e+00 , 8.9833664757620602e-01 , 1.0666902400000001e+01 , 5.6983899999999998e-01 , -2.4474799999999999e-01 , 7.8446300000000002e-01 -1.7176949574214770e+00 , 1.0407975793238120e+00 , 1.0639779200000000e+01 , -3.1210300000000002e-01 , 5.9072000000000002e-01 , -7.4407100000000004e-01 -1.7294461763095743e+00 , 1.2140336947380319e+00 , 1.0405904000000000e+01 , -7.2529399999999999e-01 , -5.6545599999999996e-01 , -3.9269199999999999e-01 -1.7610574722965922e+00 , 1.4047563652641806e+00 , 9.9942720000000005e+00 , 7.8604600000000002e-01 , -1.3495399999999999e-01 , -6.0325799999999996e-01 -1.7605439987245084e+00 , 1.5390238849656528e+00 , 9.9069432000000006e+00 , 4.1514600000000002e-01 , -6.2018899999999999e-01 , -6.6559699999999999e-01 -1.7602686060367783e+00 , 1.6695884923221043e+00 , 9.8170768000000006e+00 , -4.8823600000000000e-01 , 5.2975600000000000e-01 , 6.9352999999999998e-01 -1.7536502036937978e+00 , 1.7911516688748779e+00 , 9.7865944000000002e+00 , -5.6639200000000001e-01 , 6.9931599999999997e-02 , 8.2116400000000001e-01 -1.7417321714635086e+00 , 1.9069576917293780e+00 , 9.8160056000000004e+00 , 5.4952500000000004e-01 , -3.7346499999999999e-01 , -7.4736000000000002e-01 -1.7394356131211148e+00 , 2.0297103077363210e+00 , 9.7501840000000009e+00 , 6.6819899999999999e-01 , -4.5220900000000003e-01 , -5.9077700000000000e-01 -1.7294950815543935e+00 , 2.1457385978718437e+00 , 9.7547704000000000e+00 , -8.5589700000000002e-01 , -1.3378499999999999e-01 , 4.9954300000000001e-01 -1.7107980188659666e+00 , 2.2613737900416302e+00 , 9.8398527999999992e+00 , -9.1455399999999998e-01 , -2.5798900000000002e-01 , 3.1150200000000000e-01 -1.7024380362188225e+00 , 2.3797082077885237e+00 , 9.8404039999999995e+00 , 5.6774800000000003e-01 , 1.3547899999999999e-01 , -8.1197799999999998e-01 -1.6705187476937562e+00 , 2.5009878626575670e+00 , 1.0035019200000001e+01 , -7.1121400000000001e-02 , -9.0434999999999999e-01 , 4.2082500000000000e-01 -1.7035735290161049e+00 , 2.6107942102242125e+00 , 9.6595064000000015e+00 , -2.0497700000000001e-04 , 7.9122099999999995e-01 , 6.1153000000000002e-01 -1.7008633751611271e+00 , 2.7236098679021037e+00 , 9.6128000000000000e+00 , 2.9164700000000000e-03 , 2.6074500000000000e-01 , 9.6540300000000001e-01 -1.2173973350290797e+00 , 3.1086928958083604e+00 , 1.3687208000000000e+01 , -7.4490400000000001e-01 , 6.6710700000000001e-01 , -9.2176399999999992e-03 -1.5302132730028828e+00 , 3.0620092643335535e+00 , 1.0902868000000000e+01 , -5.9260100000000004e-01 , -2.4844800000000000e-01 , 7.6622299999999999e-01 -1.6660517682503992e+00 , 3.0756546056291310e+00 , 9.6767703999999988e+00 , -3.4929399999999999e-01 , 2.6088800000000001e-01 , -8.9996200000000004e-01 -1.6938789935360892e+00 , 3.1561809882339009e+00 , 9.3655919999999995e+00 , -6.5263199999999999e-01 , -3.6487199999999997e-01 , -6.6403299999999998e-01 -1.6957891466536723e+00 , 3.2565181398774046e+00 , 9.2790224000000006e+00 , 1.4867700000000000e-01 , 9.8304199999999997e-01 , -1.0734500000000000e-01 -2.7516064741984123e+00 , 2.5821175484846548e-01 , 1.3790284800000001e+00 , -7.5385999999999995e-02 , 2.4415700000000001e-01 , 9.6680100000000002e-01 -2.7537117132420024e+00 , 1.8720172844664718e-01 , 1.3853911999999999e+00 , -8.0089099999999996e-02 , 2.4844100000000000e-01 , 9.6533100000000005e-01 -2.7560266178378372e+00 , 1.2418223482292312e-01 , 1.3998565599999999e+00 , -5.8248500000000002e-02 , 2.4472200000000000e-01 , 9.6784199999999998e-01 -2.7570756480469409e+00 , 6.0492286321807587e-02 , 1.4160192000000000e+00 , -9.5614900000000003e-02 , 1.8703600000000001e-01 , 9.7768900000000003e-01 -2.7601242415611091e+00 , -1.9144689095302425e-02 , 1.4219243200000000e+00 , -7.7694200000000005e-02 , 1.9411200000000001e-01 , 9.7789800000000004e-01 -2.7601715454927351e+00 , -7.4506032279835654e-02 , 1.4475811200000002e+00 , 1.0319900000000000e-01 , -1.9429700000000000e-01 , -9.7549900000000000e-01 -2.7632080321565868e+00 , -1.6398234461331240e-01 , 1.4520957600000000e+00 , -1.0071600000000000e-01 , 1.7378099999999999e-01 , 9.7962099999999996e-01 -2.7648938681631856e+00 , -2.3684951272554544e-01 , 1.4702312800000001e+00 , -1.1972300000000000e-01 , 1.9439100000000001e-01 , 9.7359099999999998e-01 -2.7683268588580234e+00 , -3.2742332887542158e-01 , 1.4799365600000001e+00 , 1.2454300000000000e-01 , -1.8802600000000000e-01 , -9.7423599999999999e-01 -2.7699710761551795e+00 , -4.0897916013940749e-01 , 1.4970830400000001e+00 , -1.1684700000000001e-01 , 2.0721300000000001e-01 , 9.7129299999999996e-01 -2.7727449090300982e+00 , -5.0058857373329335e-01 , 1.5120548800000000e+00 , 1.2327700000000000e-01 , -2.0610899999999999e-01 , -9.7073299999999996e-01 -2.7751876202799171e+00 , -5.9271079301103091e-01 , 1.5296600000000000e+00 , -1.2345500000000000e-01 , 1.8509700000000001e-01 , 9.7493500000000000e-01 -2.7787529696619071e+00 , -6.9377379899823666e-01 , 1.5452880800000000e+00 , 1.5500400000000000e-01 , -1.6673600000000000e-01 , -9.7374200000000000e-01 -2.7826836015406817e+00 , -8.1409695526256964e-01 , 1.5549964800000000e+00 , -1.1025600000000001e-01 , 2.0032300000000000e-01 , 9.7350599999999998e-01 -2.7840624995510854e+00 , -9.0655154692370532e-01 , 1.5813084799999999e+00 , -8.9689400000000002e-02 , 2.5492999999999999e-01 , 9.6279099999999995e-01 -2.7878206483535859e+00 , -1.0182082175688958e+00 , 1.6023549600000000e+00 , -7.8344700000000003e-02 , 2.0991699999999999e-01 , 9.7457499999999997e-01 -2.7901336391077622e+00 , -1.1302215053973028e+00 , 1.6266191999999999e+00 , -8.4729399999999996e-02 , 1.9827700000000001e-01 , 9.7647700000000004e-01 -2.7946855502040657e+00 , -1.2612000305005773e+00 , 1.6468316000000001e+00 , -6.0626800000000002e-02 , 1.9561100000000001e-01 , 9.7880599999999995e-01 -2.7976640189713136e+00 , -1.3933994876931726e+00 , 1.6711738400000000e+00 , -7.0255399999999996e-02 , 2.2359899999999999e-01 , 9.7214599999999995e-01 -2.8011538407555472e+00 , -1.5258030226931720e+00 , 1.6998934399999999e+00 , -8.5787199999999994e-02 , 2.0207100000000000e-01 , 9.7560700000000000e-01 -2.8058950096780699e+00 , -1.6870815304157163e+00 , 1.7225404799999999e+00 , -1.1737700000000000e-01 , 1.4649400000000001e-01 , 9.8222299999999996e-01 -2.8138558270018121e+00 , -1.8891666073152504e+00 , 1.7383859200000000e+00 , 1.4450099999999999e-01 , -1.5533000000000000e-01 , -9.7723700000000002e-01 -2.8184257762935485e+00 , -2.0615051963981275e+00 , 1.7693893599999999e+00 , -9.8512100000000005e-02 , 2.3672099999999999e-01 , 9.6657000000000004e-01 -2.8221227728377745e+00 , -2.2246507660825854e+00 , 1.8089717599999999e+00 , -3.5350800000000002e-02 , 2.4689200000000000e-01 , 9.6839799999999998e-01 -2.8253629662379955e+00 , -2.3968450605939404e+00 , 1.8509076799999999e+00 , -2.3606499999999999e-02 , 2.4743799999999999e-01 , 9.6861600000000003e-01 -2.8301767977146155e+00 , -2.5901344182815027e+00 , 1.8939615999999999e+00 , -4.3405399999999997e-02 , 2.6654099999999997e-01 , 9.6284599999999998e-01 -2.8332396259964647e+00 , -2.7821339356708057e+00 , 1.9429600560000000e+00 , -6.4682199999999995e-02 , 2.4114099999999999e-01 , 9.6833199999999997e-01 -2.8387798920139544e+00 , -3.0059751766823082e+00 , 1.9926240808000000e+00 , -6.4140500000000003e-02 , 2.6167800000000002e-01 , 9.6302200000000004e-01 -2.8423914519296574e+00 , -3.2183649250062620e+00 , 2.0512425680000002e+00 , -7.8650600000000001e-02 , 2.5554600000000000e-01 , 9.6359200000000000e-01 -2.8472887194187422e+00 , -3.4611931863978782e+00 , 2.1119154400000002e+00 , -8.5660500000000001e-02 , 2.3675299999999999e-01 , 9.6778600000000004e-01 -2.8553229114216667e+00 , -3.7658874379956240e+00 , 2.1718412799999998e+00 , -9.0808399999999997e-02 , 2.3101099999999999e-01 , 9.6870400000000001e-01 -2.8621594676605557e+00 , -4.0794410198593809e+00 , 2.2402940800000000e+00 , -9.4144000000000005e-02 , 2.2344000000000000e-01 , 9.7016000000000002e-01 -2.8715752285127913e+00 , -4.4451155415658183e+00 , 2.3140467199999999e+00 , -9.0186000000000002e-02 , 2.2248799999999999e-01 , 9.7075500000000003e-01 -2.8813985232828023e+00 , -4.8407911225615567e+00 , 2.3971416799999998e+00 , -8.6279999999999996e-02 , 2.1051300000000001e-01 , 9.7377599999999997e-01 -2.8941111984120176e+00 , -5.3180141928244709e+00 , 2.4871588800000000e+00 , -8.4573899999999994e-02 , 2.1049300000000001e-01 , 9.7392999999999996e-01 -2.9074202818056882e+00 , -5.8456802769468243e+00 , 2.5904454399999999e+00 , -8.5822999999999997e-02 , 2.1365899999999999e-01 , 9.7313099999999997e-01 -2.9218669198925422e+00 , -6.4350021752113786e+00 , 2.7094838399999999e+00 , -8.1603700000000001e-02 , 2.0857400000000001e-01 , 9.7459600000000002e-01 -2.9413680792384747e+00 , -7.1474118558485209e+00 , 2.8457779199999997e+00 , -6.0472600000000001e-02 , 2.0935999999999999e-01 , 9.7596700000000003e-01 -2.9599840244478353e+00 , -7.9197226352757415e+00 , 3.0060980800000001e+00 , -6.1422299999999999e-02 , 2.1845999999999999e-01 , 9.7391099999999997e-01 -2.9813170468820651e+00 , -8.8139290111727036e+00 , 3.1944816000000000e+00 , -4.7230599999999998e-02 , 2.1753600000000001e-01 , 9.7490900000000003e-01 -3.0052270676177639e+00 , -9.8498604827034129e+00 , 3.4176760000000002e+00 , -2.3833300000000002e-02 , 2.3026099999999999e-01 , 9.7283699999999995e-01 -3.0347868523568313e+00 , -1.1077670311702976e+01 , 3.6857671999999999e+00 , 1.2882199999999999e-01 , 3.4017799999999998e-01 , 9.3149499999999996e-01 -3.0271008480149977e+00 , -1.1564493333859302e+01 , 3.9506760000000001e+00 , -2.7186199999999999e-01 , -4.2914200000000002e-01 , -8.6135200000000001e-01 -3.0103821277296090e+00 , -1.1848769426188186e+01 , 4.2169575999999998e+00 , 3.2210600000000000e-01 , 4.6335300000000001e-01 , 8.2556200000000002e-01 -3.0172465961086745e+00 , -1.2800717244586290e+01 , 4.5586807999999994e+00 , -9.6613099999999993e-02 , -4.0634700000000001e-01 , -9.0859699999999999e-01 -3.1042559206316751e+00 , -1.6160090975069135e+01 , 5.2107504000000002e+00 , -7.7204800000000004e-02 , 2.2161400000000001e-01 , 9.7207399999999999e-01 -3.1687808815454872e+00 , -1.9234540137321630e+01 , 5.9445328000000002e+00 , -2.5192300000000001e-01 , 7.3678999999999994e-01 , 6.2743599999999999e-01 -3.4807835155251956e+00 , -3.0696682505491097e+01 , 8.0469656000000001e+00 , -3.2300200000000001e-03 , 1.2375899999999999e-01 , 9.9230700000000005e-01 -3.4090559633832536e+00 , -3.0565738406265645e+01 , 8.6132039999999996e+00 , -1.1111100000000000e-01 , -5.7936799999999997e-02 , 9.9211800000000006e-01 -3.2537987191939961e+00 , -2.7318992502324324e+01 , 8.5995904000000003e+00 , 1.9932000000000000e-01 , 9.2749300000000001e-01 , 3.1627200000000000e-01 -3.2090602632993077e+00 , -2.8035743971026271e+01 , 9.2801872000000003e+00 , 1.3547099999999999e-02 , -5.7404900000000003e-01 , 8.1870900000000002e-01 -3.1434176935337499e+00 , -2.7934870380570032e+01 , 9.8091936000000004e+00 , 2.0186000000000001e-01 , 3.7419200000000002e-01 , 9.0511500000000000e-01 -3.0776898809958428e+00 , -2.7856086039572972e+01 , 1.0343961600000000e+01 , -4.3853999999999999e-01 , -3.1395600000000001e-01 , -8.4209000000000001e-01 -2.8651334251977643e+00 , -1.9884607644320550e+01 , 8.8405896000000013e+00 , -5.6777400000000000e-01 , -4.0072600000000003e-01 , 7.1906300000000001e-01 -2.8259209813987622e+00 , -2.0393314217160292e+01 , 9.3953775999999998e+00 , 5.9553800000000001e-01 , -3.2297500000000001e-01 , -7.3554200000000003e-01 -2.7128377192136375e+00 , -1.5993354131309786e+01 , 8.5213719999999995e+00 , -9.6895299999999995e-01 , -2.0552899999999999e-01 , 1.3743200000000000e-01 -2.6712578864223548e+00 , -1.5886753860668065e+01 , 8.8362008000000003e+00 , -8.7788800000000000e-01 , -4.7044700000000000e-01 , 8.9400199999999999e-02 -2.6374172130728986e+00 , -1.6464938156245360e+01 , 9.3794551999999989e+00 , 5.8722700000000005e-01 , 6.7773200000000000e-01 , 4.4254199999999999e-01 -2.6002345533971720e+00 , -1.7216555516504208e+01 , 1.0010184000000001e+01 , 5.9151699999999996e-01 , 6.8215700000000001e-01 , 4.2984899999999998e-01 -2.5570890536176454e+00 , -1.7405485219602408e+01 , 1.0465194400000000e+01 , -8.8560099999999997e-01 , -4.6442499999999998e-01 , 4.4789100000000000e-03 -2.5098470257229852e+00 , -1.6984764355065838e+01 , 1.0693328800000000e+01 , -9.4776099999999996e-01 , -3.1380999999999998e-01 , 5.7196700000000003e-02 -2.4635826797808891e+00 , -1.4648783570581962e+01 , 1.0119342400000001e+01 , -4.1679699999999997e-01 , -8.6289800000000005e-01 , 2.8580800000000001e-01 -2.4235283811519173e+00 , -1.4571904671740334e+01 , 1.0434306399999999e+01 , 4.7208800000000001e-01 , 7.6213799999999998e-01 , -4.4303399999999998e-01 -2.3757561573826038e+00 , -1.6316572752854942e+01 , 1.1578150400000000e+01 , -9.7395399999999999e-01 , -1.6511899999999999e-01 , 1.5539900000000001e-01 -2.3440399618425127e+00 , -1.4194224116869087e+01 , 1.0964155200000000e+01 , 5.7608499999999996e-01 , 6.8754000000000004e-01 , -4.4205699999999998e-01 -2.3037340496773235e+00 , -1.4063808026480011e+01 , 1.1254783200000000e+01 , 3.1495800000000002e-01 , 9.2315199999999997e-01 , -2.2043699999999999e-01 -2.2612779228293984e+00 , -1.4114117598731351e+01 , 1.1639115200000001e+01 , -2.4645700000000001e-01 , -9.3129200000000001e-01 , 2.6824399999999998e-01 -2.2017028889887924e+00 , -1.5399258588723598e+01 , 1.2699935999999999e+01 , -9.5153799999999999e-01 , -1.3987900000000000e-01 , -2.7387899999999998e-01 -2.1826085648374618e+00 , -1.3706346514266921e+01 , 1.2149401600000001e+01 , -2.5738400000000000e-01 , -9.6630400000000005e-01 , 3.0874299999999999e-03 -2.1308050241524485e+00 , -1.4165502846025436e+01 , 1.2789479999999999e+01 , 3.3913899999999997e-02 , 5.1589399999999996e-01 , 8.5598099999999999e-01 -2.0526257045769891e+00 , -1.5707924419498323e+01 , 1.4119224000000001e+01 , -1.0327100000000000e-01 , 7.7150099999999999e-01 , 6.2779099999999999e-01 -1.9949909479668682e+00 , -1.5987760774218593e+01 , 1.4731264000000001e+01 , 2.3630200000000001e-01 , 8.5523300000000002e-01 , -4.6123399999999998e-01 -1.9777142135959924e+00 , -1.4722549133724229e+01 , 1.4350416000000001e+01 , -1.8884000000000001e-01 , -3.9213800000000000e-02 , 9.8122500000000001e-01 -2.0099036813518558e+00 , -1.2034173548239764e+01 , 1.2944127999999999e+01 , -2.8097600000000000e-01 , -7.4122100000000002e-01 , 6.0962600000000000e-01 -1.9678301803480747e+00 , -1.2004288552287870e+01 , 1.3294504000000000e+01 , -2.7704500000000000e-02 , -9.5855000000000001e-01 , 2.8357399999999999e-01 -1.9383029692149092e+00 , -1.1607354448504006e+01 , 1.3382072000000001e+01 , -2.7704500000000000e-02 , -9.5855000000000001e-01 , 2.8357399999999999e-01 -1.8922288787122759e+00 , -1.1682061116788137e+01 , 1.3818144000000000e+01 , -8.2221400000000000e-02 , 9.7197900000000004e-01 , -2.2021700000000000e-01 -1.8483555248362427e+00 , -1.1630681229661866e+01 , 1.4169248000000000e+01 , 4.4637399999999999e-01 , 7.6727000000000001e-01 , 4.6048699999999998e-01 -2.2007711547181303e+00 , -3.0071824098506594e+00 , 7.5107936000000004e+00 , -7.3759800000000000e-02 , -6.7589600000000005e-01 , 7.3329599999999995e-01 -2.1891796204631691e+00 , -2.8660643258615925e+00 , 7.5499808000000002e+00 , 3.4403299999999998e-01 , -4.5667400000000002e-01 , 8.2042099999999996e-01 -2.1717529226607457e+00 , -2.8416991958290749e+00 , 7.6882799999999998e+00 , 2.3953400000000000e-01 , -5.7738000000000000e-01 , 7.8054800000000002e-01 -2.1590547192572611e+00 , -2.7451510035256979e+00 , 7.7642207999999995e+00 , -3.1908399999999998e-01 , 7.5259600000000004e-01 , -5.7600799999999996e-01 -2.1455412025917417e+00 , -2.6398013456332734e+00 , 7.8309888000000001e+00 , 1.4873900000000001e-01 , -9.2468099999999998e-01 , 3.5048899999999999e-01 -2.1253836231443501e+00 , -2.6534803069634227e+00 , 8.0117824000000013e+00 , 4.1838900000000001e-01 , 8.8454400000000000e-01 , -2.0623400000000000e-01 -2.1050981874551944e+00 , -2.6544831918239753e+00 , 8.1869392000000012e+00 , 3.8566000000000000e-01 , 8.7140600000000001e-01 , -3.0318000000000001e-01 -2.1119047538568205e+00 , -2.2693270559791205e+00 , 7.9655855999999998e+00 , -4.7200900000000001e-01 , -8.1579699999999999e-01 , -3.3418999999999999e-01 -2.1123500094895697e+00 , -2.0150483526000942e+00 , 7.8627712000000001e+00 , 5.4969400000000002e-01 , -1.4240900000000001e-02 , -8.3524399999999999e-01 -2.0995370209401356e+00 , -1.9233728948599627e+00 , 7.9303087999999997e+00 , 4.3164500000000000e-01 , 3.7260500000000002e-01 , -8.2149200000000000e-01 -2.0857087796721316e+00 , -1.8585063296708464e+00 , 8.0279543999999987e+00 , -5.8248500000000003e-01 , -5.7059000000000004e-01 , 5.7891199999999998e-01 -2.0732918835491021e+00 , -1.7642462603598705e+00 , 8.0926424000000008e+00 , -7.5845499999999999e-01 , -5.5046200000000001e-01 , 3.4890800000000000e-01 -2.0564270349824607e+00 , -1.7218443738341200e+00 , 8.2204376000000003e+00 , 6.1226499999999995e-01 , 7.7907800000000005e-01 , -1.3479700000000000e-01 -2.0678468088805602e+00 , -1.3897869746776284e+00 , 7.9789599999999998e+00 , -3.3806599999999998e-01 , -9.2922099999999996e-01 , -1.4919700000000000e-01 -2.0693497045378670e+00 , -1.1856667814198008e+00 , 7.8856616000000006e+00 , 4.7944399999999998e-01 , 7.8125800000000001e-01 , 3.9971299999999998e-01 -2.0390598822165376e+00 , -1.2653446936107109e+00 , 8.1741367999999994e+00 , -3.3613599999999999e-01 , -9.4179000000000002e-01 , -6.6378100000000001e-03 -2.0229044146536239e+00 , -1.2223957705249839e+00 , 8.3047919999999991e+00 , -7.6214499999999996e-01 , -6.4083199999999996e-01 , 9.2028200000000004e-02 -2.0009271521341225e+00 , -1.2112730649772097e+00 , 8.4870832000000007e+00 , 5.6742099999999995e-01 , 7.9984999999999995e-01 , -1.9563500000000000e-01 -1.9813017192495226e+00 , -1.1786734139895918e+00 , 8.6446952000000010e+00 , -7.6732599999999995e-01 , -6.3044900000000004e-01 , 1.1724200000000000e-01 -2.0009284447194586e+00 , -8.5113890187320251e-01 , 8.3350872000000003e+00 , -2.8543499999999999e-02 , 2.1264900000000000e-01 , 9.7671200000000002e-01 -1.8727671877504324e+00 , -1.5661247273253589e+00 , 9.7446927999999993e+00 , 2.4261300000000000e-01 , -9.0050300000000005e-01 , -3.6087900000000001e-01 -2.0307710887922372e+00 , -3.3036691590127454e-01 , 7.8589232000000004e+00 , -8.9810500000000004e-01 , -1.8887100000000000e-02 , -4.3937599999999999e-01 -2.0098990566306791e+00 , -3.1680236055503164e-01 , 8.0325096000000009e+00 , -7.2884000000000004e-01 , -6.3289499999999999e-01 , -2.6122099999999998e-01 -2.0239316079600775e+00 , -9.4394778753718711e-02 , 7.8217848000000005e+00 , 7.5313500000000000e-01 , -5.8823899999999996e-01 , 2.9455399999999998e-01 -2.0439330273973173e+00 , 1.5270605509777169e-01 , 7.5399552000000005e+00 , -1.1719599999999999e-01 , 8.0253399999999997e-01 , 5.8498300000000003e-01 -2.0353227015360953e+00 , 2.2635553356709681e-01 , 7.5874416000000000e+00 , -7.6050600000000002e-01 , -5.8357899999999996e-01 , 2.8472100000000000e-01 -1.8168878800489825e+00 , -7.3758173474388977e-01 , 9.8819000000000017e+00 , 5.7436699999999996e-01 , 3.3581100000000003e-01 , -7.4654799999999999e-01 -1.8122300558941757e+00 , -5.8042482655560379e-01 , 9.8493168000000004e+00 , -4.3725000000000003e-01 , -2.1713700000000000e-01 , 8.7273400000000001e-01 -1.7997832582726609e+00 , -4.6489471298373486e-01 , 9.9088671999999995e+00 , -5.5429499999999998e-01 , -8.0738000000000004e-02 , -8.2839499999999999e-01 -1.8629574823725523e+00 , -3.7390306346073654e-02 , 9.1876896000000006e+00 , 4.1762100000000002e-01 , 1.2903200000000000e-02 , 9.0852999999999995e-01 -1.8644496747470551e+00 , 1.1406272369950776e-01 , 9.1123208000000009e+00 , 2.2076499999999999e-01 , 4.7875400000000001e-01 , 8.4974000000000005e-01 -1.8781484336124468e+00 , 3.0448317826452542e-01 , 8.9167176000000001e+00 , 2.8640399999999999e-01 , 2.3329700000000000e-01 , 9.2927199999999999e-01 -1.8830707680654866e+00 , 4.5690743215631935e-01 , 8.8046784000000002e+00 , 8.8747399999999999e-01 , 3.2153900000000002e-01 , 3.3015600000000001e-01 -1.8575039345466047e+00 , 5.0360451920020410e-01 , 9.0046391999999997e+00 , 8.0309299999999995e-01 , -5.4235900000000004e-01 , 2.4675700000000000e-01 -1.8347735145145889e+00 , 5.6544619815741326e-01 , 9.1749808000000002e+00 , 6.6225099999999995e-02 , -9.9103300000000005e-01 , 1.1604700000000000e-01 -1.8137085002251618e+00 , 6.3901163681030693e-01 , 9.3248136000000006e+00 , -2.7511000000000002e-01 , 1.1005600000000000e-01 , -9.5509299999999997e-01 -1.8420750405790702e+00 , 8.4396134750396068e-01 , 8.9936672000000009e+00 , 4.1765999999999998e-01 , -2.3605799999999999e-01 , 8.7740399999999996e-01 -1.8199693656844487e+00 , 9.1347340097278962e-01 , 9.1600464000000006e+00 , -4.7558499999999998e-01 , -4.3023800000000001e-01 , -7.6727699999999999e-01 -1.8328562793887324e+00 , 1.0661772252898012e+00 , 8.9826119999999996e+00 , 2.7049000000000001e-01 , -6.5718399999999999e-01 , -7.0352300000000001e-01 -1.6417286414582213e+00 , 8.0642646378048188e-01 , 1.0746254400000000e+01 , 4.5487800000000000e-01 , -8.6341100000000004e-01 , 2.1819200000000000e-01 -1.6473316775409499e+00 , 9.6751187879047085e-01 , 1.0629940800000000e+01 , -6.2095100000000003e-01 , 3.8922699999999999e-01 , -6.8038500000000002e-01 -1.6398651364601600e+00 , 1.1021006814927019e+00 , 1.0642847200000000e+01 , -5.8213199999999998e-01 , 6.3713699999999995e-01 , 5.0515299999999996e-01 -1.7211201579996651e+00 , 1.3639655043073873e+00 , 9.8254592000000009e+00 , -3.3270400000000000e-01 , -2.5167400000000001e-01 , 9.0882799999999997e-01 -1.6956959792392010e+00 , 1.4598101311352401e+00 , 1.0005878400000000e+01 , 5.3144899999999995e-01 , -3.9412799999999998e-01 , -7.4981699999999996e-01 -1.7007183248624280e+00 , 1.5948220466884122e+00 , 9.9075984000000012e+00 , 2.1171699999999999e-01 , -4.3869399999999997e-01 , -8.7334100000000003e-01 -1.7087526326471274e+00 , 1.7293398575511998e+00 , 9.7758928000000012e+00 , 3.5191699999999998e-01 , -5.1404399999999995e-01 , 7.8224899999999997e-01 -1.6869161091713143e+00 , 1.8357279283737309e+00 , 9.9198288000000012e+00 , -4.6116200000000002e-01 , 4.0282800000000002e-01 , -7.9060699999999995e-01 -1.7002482842697295e+00 , 1.9671333177795376e+00 , 9.7527216000000010e+00 , -4.3988800000000000e-01 , 6.6341200000000000e-01 , 6.0529599999999995e-01 -1.7034358457043188e+00 , 2.0885296977674597e+00 , 9.6760631999999998e+00 , 7.2128099999999995e-01 , -2.1243500000000001e-01 , -6.5926099999999999e-01 -1.6939791122557510e+00 , 2.2032025981961398e+00 , 9.7109136000000014e+00 , 6.9225999999999999e-01 , 4.2138300000000001e-01 , -5.8584300000000000e-01 -1.6593995277565403e+00 , 2.3165828313361483e+00 , 9.9606176000000008e+00 , 9.3560100000000002e-01 , 3.5099000000000002e-01 , 3.8167500000000000e-02 -1.6607898481519798e+00 , 2.4367472943279980e+00 , 9.8985504000000013e+00 , -1.9152600000000000e-01 , 1.1783500000000000e-01 , 9.7438800000000003e-01 -1.6384080005804040e+00 , 2.5598287012939425e+00 , 1.0040884800000001e+01 , 6.8860599999999994e-02 , -8.8412100000000005e-01 , 4.6215600000000001e-01 -1.6891873409729687e+00 , 2.6628605359234081e+00 , 9.5617464000000005e+00 , -3.4292200000000002e-03 , -5.0083100000000003e-01 , -8.6553800000000003e-01 -1.6849241157935790e+00 , 2.7765010481342260e+00 , 9.5451480000000011e+00 , 5.6601800000000001e-02 , 4.7004200000000002e-01 , 8.8082700000000003e-01 -1.1892860377473875e+00 , 3.1992621993517814e+00 , 1.3656424000000001e+01 , 7.4490500000000004e-01 , -6.6710700000000001e-01 , 9.2177500000000002e-03 -1.6630437615827109e+00 , 3.0132327252641762e+00 , 9.6403496000000004e+00 , 3.0789600000000000e-01 , 9.2551200000000000e-01 , 2.2051599999999999e-01 -1.6546014628584893e+00 , 3.1320046299428226e+00 , 9.6588615999999998e+00 , -6.4648700000000003e-01 , -2.0117900000000000e-01 , -7.3592199999999997e-01 -1.6865693531790587e+00 , 3.2091469803568620e+00 , 9.3475895999999992e+00 , 5.8133999999999997e-01 , 5.7241399999999998e-02 , 8.1164499999999995e-01 -1.6927159690801341e+00 , 3.3092180839789749e+00 , 9.2606143999999997e+00 , 1.1360099999999999e-01 , 9.9018899999999999e-01 , -8.1362799999999999e-02 -2.6993458385450233e+00 , 2.7136659022323650e-01 , 1.3541152799999998e+00 , -5.3533499999999998e-02 , 2.5997500000000001e-01 , 9.6413000000000004e-01 -2.6982134833407687e+00 , 2.1668932088028403e-01 , 1.3723319199999999e+00 , -7.5639499999999998e-02 , 2.1862999999999999e-01 , 9.7287199999999996e-01 -2.6969274643187373e+00 , 1.6227802501101962e-01 , 1.3918631200000000e+00 , -6.6472199999999995e-02 , 1.9031999999999999e-01 , 9.7946900000000003e-01 -2.6966384399153238e+00 , 9.0782657380842346e-02 , 1.4006084799999998e+00 , 9.0332099999999999e-02 , -2.0627300000000001e-01 , -9.7431599999999996e-01 -2.6971231292643076e+00 , 1.8627041945857625e-02 , 1.4115066399999998e+00 , -9.8757800000000007e-02 , 2.1637999999999999e-01 , 9.7130200000000000e-01 -2.6973926671703561e+00 , -5.3147725886268038e-02 , 1.4242258400000001e+00 , -8.9406799999999995e-02 , 2.2025400000000001e-01 , 9.7133599999999998e-01 -2.6963707108458577e+00 , -1.2554508437529899e-01 , 1.4388451199999999e+00 , -1.0691500000000000e-01 , 1.7023300000000000e-01 , 9.7958699999999999e-01 -2.6981792294428022e+00 , -2.1575844826264134e-01 , 1.4447543999999999e+00 , -1.1140200000000000e-01 , 1.8353200000000000e-01 , 9.7668100000000002e-01 -2.6966356006248438e+00 , -2.8833583566925736e-01 , 1.4636262400000000e+00 , -1.0540300000000000e-01 , 1.7020199999999999e-01 , 9.7975599999999996e-01 -2.6978187630221706e+00 , -3.7964161421688258e-01 , 1.4744983999999999e+00 , -8.3936999999999998e-02 , 2.0310600000000001e-01 , 9.7555199999999997e-01 -2.6972008655458075e+00 , -4.6191067542263031e-01 , 1.4929157600000000e+00 , -1.3185400000000000e-01 , 1.9399400000000000e-01 , 9.7210099999999999e-01 -2.6971472235178453e+00 , -5.6269919250825096e-01 , 1.5038898400000000e+00 , -1.1353400000000000e-01 , 1.7358399999999999e-01 , 9.7825300000000004e-01 -2.6977463861530051e+00 , -6.6392840183274870e-01 , 1.5180296799999999e+00 , 1.2954499999999999e-01 , -1.7761299999999999e-01 , -9.7553699999999999e-01 -2.6983467753056551e+00 , -7.7502607983811389e-01 , 1.5306760800000001e+00 , -8.0715899999999993e-02 , 2.1875000000000000e-01 , 9.7243700000000000e-01 -2.6964169181116695e+00 , -8.5828267207594955e-01 , 1.5597253599999998e+00 , -4.1925700000000003e-02 , 2.4386099999999999e-01 , 9.6890399999999999e-01 -2.6962390007353938e+00 , -9.7020664663663547e-01 , 1.5786512799999999e+00 , -7.6498800000000006e-02 , 2.0276500000000000e-01 , 9.7623499999999996e-01 -2.6959620728936766e+00 , -1.0918071784408099e+00 , 1.5968939199999999e+00 , -8.7134600000000006e-02 , 2.0257100000000000e-01 , 9.7538300000000000e-01 -2.6949084192776094e+00 , -1.2043861921051926e+00 , 1.6229084800000000e+00 , -8.6902999999999994e-02 , 1.9358700000000001e-01 , 9.7722699999999996e-01 -2.6950603547124494e+00 , -1.3359064561394551e+00 , 1.6447464000000001e+00 , -6.2998799999999994e-02 , 2.0699999999999999e-01 , 9.7631100000000004e-01 -2.6944218640682056e+00 , -1.4583761446512225e+00 , 1.6744560800000001e+00 , -1.0377599999999999e-01 , 1.9233300000000000e-01 , 9.7582700000000000e-01 -2.6952981243466878e+00 , -1.6200454817547043e+00 , 1.6943741600000000e+00 , 1.2165800000000000e-01 , -1.5453500000000001e-01 , -9.8046800000000001e-01 -2.6959506271821447e+00 , -1.8021343027931929e+00 , 1.7130327999999999e+00 , -1.4679000000000000e-01 , 1.2532199999999999e-01 , 9.8119699999999999e-01 -2.6971259298670471e+00 , -1.9943042100835298e+00 , 1.7344755199999999e+00 , -8.1423400000000007e-02 , 2.2368099999999999e-01 , 9.7125499999999998e-01 -2.6958248159549316e+00 , -2.1466841552900684e+00 , 1.7737053599999999e+00 , -2.9226700000000001e-02 , 2.7083200000000002e-01 , 9.6218300000000001e-01 -2.6928560173600999e+00 , -2.3001237405489992e+00 , 1.8178741599999999e+00 , -2.9092699999999999e-02 , 2.3340800000000000e-01 , 9.7194400000000003e-01 -2.6918885998180975e+00 , -2.4929190061643904e+00 , 1.8568315200000001e+00 , 5.2279800000000001e-02 , -2.4249599999999999e-01 , -9.6874300000000002e-01 -2.6900530493097650e+00 , -2.6754272883926484e+00 , 1.9044686159999999e+00 , -5.9404600000000002e-02 , 2.4243300000000001e-01 , 9.6834799999999999e-01 -2.6888288535088787e+00 , -2.8988464061456796e+00 , 1.9495068560000000e+00 , -6.6020999999999996e-02 , 2.4762600000000001e-01 , 9.6660400000000002e-01 -2.6855618403368315e+00 , -3.1018492018933150e+00 , 2.0058038344000000e+00 , -7.2501200000000002e-02 , 2.4863800000000000e-01 , 9.6587900000000004e-01 -2.6847912334915107e+00 , -3.3662960280641894e+00 , 2.0580880559999999e+00 , -8.3665100000000006e-02 , 2.3643300000000000e-01 , 9.6803899999999998e-01 -2.6830249885829729e+00 , -3.6498119697117870e+00 , 2.1156875199999998e+00 , -9.6752299999999999e-02 , 2.2408400000000001e-01 , 9.6975500000000003e-01 -2.6810937823567889e+00 , -3.9443867240968409e+00 , 2.1815424000000001e+00 , -9.5155199999999995e-02 , 2.2682900000000000e-01 , 9.6927500000000000e-01 -2.6788834430838788e+00 , -4.2794055218477078e+00 , 2.2521864799999998e+00 , -9.0105800000000000e-02 , 2.2516900000000001e-01 , 9.7014400000000001e-01 -2.6771945086913487e+00 , -4.6544726323650369e+00 , 2.3296695999999999e+00 , -8.9463699999999993e-02 , 2.1538800000000000e-01 , 9.7242200000000001e-01 -2.6755513839101246e+00 , -5.0917670450004620e+00 , 2.4145575199999998e+00 , -8.7687699999999993e-02 , 2.0657400000000001e-01 , 9.7449399999999997e-01 -2.6735249647492689e+00 , -5.6003849273045212e+00 , 2.5090009599999998e+00 , -8.8535900000000001e-02 , 2.1115200000000001e-01 , 9.7343500000000005e-01 -2.6702129930998320e+00 , -6.1279609092649672e+00 , 2.6197162399999998e+00 , -8.0839999999999995e-02 , 2.1164900000000000e-01 , 9.7399700000000000e-01 -2.6689032845135436e+00 , -6.8005619486559397e+00 , 2.7436249600000000e+00 , -7.4763800000000005e-02 , 2.0871200000000001e-01 , 9.7511499999999995e-01 -2.6648972032171829e+00 , -7.5334630614277032e+00 , 2.8891823200000002e+00 , -6.3103099999999995e-02 , 2.1679999999999999e-01 , 9.7417399999999998e-01 -2.6597069139283152e+00 , -8.3355897424856860e+00 , 3.0598016000000001e+00 , -5.7990100000000003e-02 , 2.2266600000000000e-01 , 9.7316899999999995e-01 -2.6544520720804323e+00 , -9.2813034285445664e+00 , 3.2607192000000000e+00 , -4.6931100000000003e-02 , 2.2616100000000000e-01 , 9.7295900000000002e-01 -2.6468335268330905e+00 , -1.0389205275047296e+01 , 3.4996488000000001e+00 , 5.9675899999999997e-02 , 2.9688399999999998e-01 , 9.5304699999999998e-01 -2.6302088370253416e+00 , -1.1116811778647802e+01 , 3.7582032000000001e+00 , 3.2579000000000002e-01 , 4.4224599999999997e-01 , 8.3563100000000001e-01 -2.6053982518395378e+00 , -1.1446235421546273e+01 , 4.0155095999999997e+00 , 3.0120200000000003e-01 , 4.4998199999999999e-01 , 8.4070999999999996e-01 -2.5807502262002968e+00 , -1.1935966239442724e+01 , 4.2985975999999999e+00 , -1.6256599999999999e-01 , -3.2335199999999997e-01 , -9.3220999999999998e-01 -2.5666578946403167e+00 , -1.4250649512366085e+01 , 4.7863471999999998e+00 , -7.5594800000000004e-02 , 2.2066800000000000e-01 , 9.7241500000000003e-01 -2.5480922237732555e+00 , -1.7760991061799288e+01 , 5.4995688000000005e+00 , -1.7086799999999999e-01 , 2.6945999999999998e-01 , 9.4773200000000002e-01 -2.4718936270592491e+00 , -3.2762349802754429e+01 , 8.5412256000000006e+00 , 3.9968199999999998e-01 , 5.5177500000000002e-01 , 7.3198300000000005e-01 -2.3965147731432763e+00 , -3.2928844069728612e+01 , 9.1957184000000005e+00 , -3.5160999999999998e-01 , -9.3205800000000005e-01 , -8.7394600000000003e-02 -2.3204361015531574e+00 , -3.2807058974791168e+01 , 9.8049296000000012e+00 , -3.5160999999999998e-01 , -9.3205800000000005e-01 , -8.7394700000000006e-02 -2.2419819296158106e+00 , -3.3265038512084992e+01 , 1.0535092800000001e+01 , -3.5160999999999998e-01 , -9.3205800000000005e-01 , -8.7394700000000006e-02 -2.1644975507745383e+00 , -3.3190865765098096e+01 , 1.1165738400000000e+01 , -3.5160999999999998e-01 , -9.3205800000000005e-01 , -8.7394399999999997e-02 -2.0889821835819169e+00 , -3.2983862060327375e+01 , 1.1766161600000000e+01 , -3.5160999999999998e-01 , -9.3205800000000005e-01 , -8.7394500000000000e-02 -2.1457709716353857e+00 , -2.2108484375276060e+01 , 9.5491831999999999e+00 , -3.3902300000000002e-01 , 1.5881600000000001e-01 , 9.2727599999999999e-01 -2.1838117058290365e+00 , -1.5758053018955088e+01 , 8.2115664000000006e+00 , 8.2965500000000003e-01 , 3.0947999999999998e-01 , -4.6464499999999997e-01 -2.1405139780987694e+00 , -1.5884617819140754e+01 , 8.5912496000000012e+00 , 8.2965500000000003e-01 , 3.0947999999999998e-01 , -4.6464499999999997e-01 -2.0965039497647182e+00 , -1.6023530262392594e+01 , 8.9834543999999994e+00 , -8.7788800000000000e-01 , -4.7044700000000000e-01 , 8.9400199999999999e-02 -2.0515393989605069e+00 , -1.6124859171533149e+01 , 9.3719567999999995e+00 , -8.7788800000000000e-01 , -4.7044700000000000e-01 , 8.9400199999999999e-02 -2.0094173099081969e+00 , -1.6080234006523824e+01 , 9.7163111999999998e+00 , 7.8604300000000005e-01 , 4.8525499999999999e-01 , 3.8296799999999998e-01 -2.0024197802816563e+00 , -1.4658222648334618e+01 , 9.5419343999999988e+00 , 5.0279300000000005e-01 , 7.9893700000000001e-01 , -3.2999800000000001e-01 -1.9642650513281148e+00 , -1.4562812981638196e+01 , 9.8442000000000007e+00 , -4.6249899999999999e-01 , -8.7835600000000003e-01 , 1.2077000000000000e-01 -1.9203827765358514e+00 , -1.4652886517623063e+01 , 1.0225380800000000e+01 , -4.1679800000000000e-01 , -8.6289800000000005e-01 , 2.8580800000000001e-01 -1.7300942494969518e+00 , -1.9064787292618391e+01 , 1.2514296000000000e+01 , -9.3882299999999996e-01 , 6.5351599999999996e-02 , -3.3814400000000000e-01 -1.8479678375035222e+00 , -1.4316748769462603e+01 , 1.0776747200000001e+01 , 5.0914899999999996e-01 , 6.5102300000000002e-01 , -5.6297100000000000e-01 -1.8276241580038155e+00 , -1.3749548185975371e+01 , 1.0857940000000001e+01 , -6.8063200000000001e-01 , -7.1843400000000002e-01 , -1.4350099999999999e-01 -1.7833098396933829e+00 , -1.3787288373019445e+01 , 1.1224935199999999e+01 , -6.5799900000000000e-01 , -7.5292499999999996e-01 , 1.1892800000000000e-02 -1.7277356369655588e+00 , -1.4102573983866446e+01 , 1.1745642400000001e+01 , -2.7565600000000001e-01 , -9.6032200000000001e-01 , 4.2376100000000000e-02 -1.6968890115800546e+00 , -1.3802047745918266e+01 , 1.1950064800000002e+01 , -2.7565600000000001e-01 , -9.6032200000000001e-01 , 4.2376100000000000e-02 -1.6539265918403392e+00 , -1.3779346548546572e+01 , 1.2306452000000000e+01 , 1.1574500000000000e-01 , 9.8790000000000000e-01 , 1.0323300000000001e-01 -1.4884846000740373e+00 , -1.6082263820515028e+01 , 1.4048400000000001e+01 , -2.5042799999999998e-01 , -9.6623000000000003e-01 , -6.0713299999999998e-02 -1.4405174297740695e+00 , -1.6001789293416987e+01 , 1.4437464000000000e+01 , 2.1164500000000000e-01 , 9.7728499999999996e-01 , -1.0981299999999999e-02 -1.2453286325956283e+00 , -1.8449959736081343e+01 , 1.6453400000000002e+01 , -8.7154399999999999e-01 , -1.9132099999999999e-01 , -4.5145099999999999e-01 -1.3374398906982561e+00 , -1.5913491563192963e+01 , 1.5280799999999999e+01 , -3.5338900000000001e-01 , -8.2960999999999996e-01 , 4.3227700000000002e-01 -1.3451603361642559e+00 , -1.4919112367158348e+01 , 1.5058344000000002e+01 , -4.0105400000000002e-01 , 2.0426700000000000e-01 , 8.9298999999999995e-01 -1.5092570505513794e+00 , -1.1661112291830614e+01 , 1.3171160000000000e+01 , -1.8290500000000001e-01 , 9.2821699999999996e-01 , -3.2397399999999998e-01 -1.4497815593663876e+00 , -1.1864600463493106e+01 , 1.3697920000000000e+01 , 1.0428000000000000e-01 , -9.5170800000000000e-01 , 2.8875099999999998e-01 -1.4049296243727367e+00 , -1.1840796676467400e+01 , 1.4070032000000001e+01 , 3.5943599999999998e-01 , -7.4022500000000002e-01 , 5.6821900000000003e-01 -1.3794283894191728e+00 , -1.1540884718072935e+01 , 1.4230608000000000e+01 , -3.5943599999999998e-01 , 7.4022500000000002e-01 , -5.6821900000000003e-01 -1.1922275359533723e+00 , -1.3269672441876709e+01 , 1.6066000000000003e+01 , -8.1458299999999995e-01 , -8.2633399999999996e-02 , 5.7413099999999995e-01 -1.9995761954255322e+00 , -2.9738133175691575e+00 , 7.6967664000000005e+00 , -1.5734999999999999e-01 , -6.0630600000000001e-01 , 7.7950900000000001e-01 -1.9914684019474980e+00 , -2.8382073974201054e+00 , 7.7409144000000003e+00 , -1.5629599999999999e-01 , -6.2293100000000001e-01 , 7.6650399999999996e-01 -1.9828331989066190e+00 , -2.7174159607287862e+00 , 7.7957640000000001e+00 , -3.4194500000000000e-01 , -6.8761000000000005e-01 , 6.4051999999999998e-01 -1.9715045535960223e+00 , -2.6192849278053183e+00 , 7.8693024000000005e+00 , 4.8791499999999999e-01 , 8.0190499999999998e-01 , -3.4480000000000000e-01 -1.8570982596575856e+00 , -3.5750063481996994e+00 , 8.9829344000000013e+00 , -5.3230900000000003e-01 , 7.1152599999999999e-01 , 4.5867000000000002e-01 -1.9372903087509632e+00 , -2.5567468510473308e+00 , 8.1513504000000001e+00 , -8.7692300000000001e-01 , 9.6655000000000005e-02 , 4.7081200000000001e-01 -1.9569550864437721e+00 , -2.1678594051923987e+00 , 7.9196280000000003e+00 , 7.2247300000000003e-01 , 8.8239300000000007e-02 , -6.8574500000000005e-01 -1.9575549180079719e+00 , -1.9846784130082828e+00 , 7.8908512000000002e+00 , -5.9958299999999998e-01 , -4.2430899999999999e-01 , 6.7857400000000001e-01 -1.9522536092120082e+00 , -1.8518037742097513e+00 , 7.9115264000000005e+00 , 4.3149900000000002e-01 , 6.3365899999999997e-01 , -6.4209499999999997e-01 -1.9330938885676763e+00 , -1.8331699879606620e+00 , 8.0632000000000001e+00 , -3.6514500000000000e-01 , -6.4321799999999996e-01 , 6.7300800000000005e-01 -1.9293649752089690e+00 , -1.6990640177642953e+00 , 8.0797464000000012e+00 , -1.9653499999999999e-01 , -7.8907700000000003e-01 , 5.8200600000000002e-01 -1.9159371299872614e+00 , -1.6363977659357052e+00 , 8.1823840000000008e+00 , -1.9476299999999999e-01 , -9.1454700000000000e-01 , 3.5450300000000001e-01 -1.8867555706898351e+00 , -1.6787743572777512e+00 , 8.4243711999999995e+00 , 1.2194500000000000e-01 , 8.2609100000000002e-01 , -5.5018500000000004e-01 -1.9379577669054522e+00 , -1.1606231239442391e+00 , 7.9186608000000005e+00 , -4.7824100000000003e-01 , -8.7553400000000003e-01 , -6.8746600000000005e-02 -1.9114628659165598e+00 , -1.1949633667500672e+00 , 8.1484072000000012e+00 , -6.2122999999999995e-01 , -7.8300899999999996e-01 , 3.1142800000000002e-02 -1.8814467460596334e+00 , -1.2336783717333160e+00 , 8.3977784000000000e+00 , -8.1413700000000000e-01 , -5.4653200000000002e-01 , 1.9617200000000001e-01 -1.8618178299988868e+00 , -1.2032654007618611e+00 , 8.5550888000000000e+00 , -8.2333800000000001e-01 , -4.5649099999999998e-01 , 3.3723999999999998e-01 -1.8757696628716736e+00 , -9.7257596964361648e-01 , 8.4065664000000009e+00 , -2.1332499999999999e-01 , 3.5386299999999998e-01 , 9.1064500000000004e-01 -1.9410880531362680e+00 , -4.6383016384260944e-01 , 7.7834503999999995e+00 , -9.3605000000000005e-01 , -1.9152600000000000e-01 , -2.9517500000000002e-01 -1.9335598486133165e+00 , -3.8043217997770462e-01 , 7.8321536000000007e+00 , -9.3605000000000005e-01 , -1.9152600000000000e-01 , -2.9517599999999999e-01 -1.8917766166093180e+00 , -4.7531170025020586e-01 , 8.1955296000000004e+00 , 6.6062999999999997e-02 , -3.3007199999999998e-01 , -9.4164099999999995e-01 -1.8857499226029120e+00 , -3.7442928779959272e-01 , 8.2259392000000009e+00 , -6.6104399999999996e-01 , -3.7736800000000001e-02 , -7.4939800000000001e-01 -1.9082781327383247e+00 , -1.4561986862160436e-01 , 8.0066656000000016e+00 , -8.8861400000000001e-01 , 1.6645099999999999e-01 , -4.2738599999999999e-01 -1.8329071019167025e+00 , -3.6288869205571883e-01 , 8.6619279999999996e+00 , -4.5272899999999999e-01 , 4.3235899999999999e-01 , 7.7980899999999997e-01 -1.8735903749982425e+00 , -6.0638900730168199e-02 , 8.2787815999999985e+00 , -9.8338800000000004e-01 , -7.4430600000000000e-02 , -1.6555400000000001e-01 -1.8520311093725497e+00 , -2.7932515418757742e-02 , 8.4522848000000010e+00 , 3.8737800000000000e-01 , 7.3968100000000003e-01 , -5.5028200000000005e-01 -1.8316672559107570e+00 , 1.2529150917914622e-02 , 8.6171664000000003e+00 , 5.8215899999999998e-01 , 7.6118799999999998e-01 , -2.8580200000000000e-01 -1.8293498427818247e+00 , 1.2663201251209300e-01 , 8.6190904000000010e+00 , 6.4854599999999996e-01 , 6.2034900000000004e-01 , -4.4108399999999998e-01 -1.6844839397075635e+00 , -2.5427232649828957e-01 , 9.8808496000000012e+00 , 4.4821400000000000e-01 , 1.2174400000000000e-01 , 8.8559699999999997e-01 -1.6899109062693498e+00 , -9.1601161681869492e-02 , 9.8092976000000007e+00 , -6.2633300000000003e-01 , -5.1969600000000005e-01 , -5.8105399999999996e-01 -1.8404663408214454e+00 , 5.1365929800714016e-01 , 8.4659504000000005e+00 , -1.0943000000000000e-01 , -3.3884900000000003e-02 , 9.9341699999999999e-01 -1.8391889580356806e+00 , 6.2156362370072960e-01 , 8.4583688000000006e+00 , -1.5924500000000001e-02 , -4.9879099999999998e-01 , 8.6657600000000001e-01 -1.8020621862976327e+00 , 6.2965781779282337e-01 , 8.7646903999999992e+00 , 8.7811700000000004e-01 , -2.1425699999999999e-02 , -4.7796600000000000e-01 -1.8102173252658722e+00 , 7.6523899054748235e-01 , 8.6752088000000001e+00 , 7.4137500000000001e-01 , -6.5170099999999997e-01 , 1.6015299999999999e-01 -1.7722926700052390e+00 , 7.8718926882972107e-01 , 8.9815616000000009e+00 , 7.2493799999999997e-01 , 1.7564199999999999e-01 , 6.6604399999999997e-01 -1.7586749339330292e+00 , 8.6990464278538937e-01 , 9.0888063999999993e+00 , 7.9935900000000004e-01 , 8.1166299999999997e-02 , 5.9534699999999996e-01 -1.7766249977057349e+00 , 1.0237791351587848e+00 , 8.9130047999999995e+00 , 5.6056300000000003e-01 , -5.8147199999999999e-01 , -5.8962700000000001e-01 -1.6796471841682088e+00 , 9.5221979531072298e-01 , 9.7335024000000008e+00 , -5.1287099999999997e-01 , 6.5332699999999999e-01 , 5.5689100000000002e-01 -1.7200804901958124e+00 , 1.1485562302029102e+00 , 9.3621496000000004e+00 , -6.1782499999999996e-01 , 3.1954100000000002e-01 , -7.1846100000000002e-01 -1.6677177920812052e+00 , 1.1848447218330251e+00 , 9.7893399999999993e+00 , -1.6283300000000001e-01 , -4.1566100000000000e-01 , 8.9482499999999998e-01 -1.6645740399280331e+00 , 1.3047777095719297e+00 , 9.7989391999999995e+00 , 3.8329900000000000e-01 , 3.8232200000000000e-01 , -8.4077999999999997e-01 -1.5974048500611482e+00 , 1.3451034005940161e+00 , 1.0348412800000000e+01 , -2.5909900000000002e-01 , -7.9530699999999999e-01 , -5.4804600000000003e-01 -1.6488540606900468e+00 , 1.5337861130000425e+00 , 9.8939951999999991e+00 , 3.3869400000000000e-01 , -6.3323700000000005e-01 , -6.9591400000000003e-01 -1.6568249683034950e+00 , 1.6642194302579039e+00 , 9.8052519999999994e+00 , -7.3911899999999997e-01 , 6.3932500000000003e-01 , -2.1205199999999999e-01 -1.6419950739386415e+00 , 1.7739585819058188e+00 , 9.9093248000000003e+00 , 5.6736200000000003e-01 , -4.1662399999999999e-01 , 7.1029900000000001e-01 -1.6593761964785461e+00 , 1.9076169709838404e+00 , 9.7437360000000002e+00 , -4.5999800000000002e-01 , 3.2606900000000000e-01 , 8.2588200000000001e-01 -1.6678506033835991e+00 , 2.0301955135695180e+00 , 9.6582688000000001e+00 , -3.5344900000000001e-01 , 3.5330499999999998e-01 , 8.6616899999999997e-01 -1.6626267830617556e+00 , 2.1450098717535528e+00 , 9.6841752000000003e+00 , -6.9492100000000001e-01 , -1.4822500000000000e-01 , 7.0364300000000002e-01 -1.6541161198489496e+00 , 2.2605069969429663e+00 , 9.7285936000000000e+00 , 6.9484599999999996e-01 , 4.4730900000000001e-01 , -5.6311999999999995e-01 -1.6315520021400380e+00 , 2.3757297015917946e+00 , 9.9056744000000005e+00 , 3.9143699999999998e-01 , 8.0518000000000001e-01 , -4.4549100000000003e-01 -1.5972945607808562e+00 , 2.4991001947645621e+00 , 1.0162856000000001e+01 , 6.1671900000000002e-01 , 7.6251100000000005e-01 , -1.9553499999999999e-01 -1.6582971964857141e+00 , 2.6085020611646907e+00 , 9.6437400000000011e+00 , -2.0457200000000000e-01 , 6.0548100000000005e-01 , 7.6911900000000000e-01 -1.6630360390406578e+00 , 2.7211935304752837e+00 , 9.5874552000000008e+00 , 9.9587700000000001e-02 , -2.1818899999999999e-01 , -9.7081200000000001e-01 -1.6383923937702753e+00 , 2.8474339168766898e+00 , 9.7660751999999995e+00 , -8.9387899999999998e-01 , 8.8139999999999996e-02 , 4.3955899999999998e-01 -1.5055659505986270e+00 , 3.0551984341319498e+00 , 1.0837441600000002e+01 , 5.9260100000000004e-01 , 2.4844800000000000e-01 , -7.6622299999999999e-01 -1.6404646878073637e+00 , 3.0792223549335551e+00 , 9.7153440000000000e+00 , 7.8108999999999995e-01 , 4.5950900000000000e-01 , 4.2278800000000000e-01 -1.6826976348199540e+00 , 3.1542964294750639e+00 , 9.3538607999999996e+00 , -7.1769600000000000e-01 , -2.7442899999999998e-01 , -6.4000100000000004e-01 -1.6846738285235257e+00 , 3.2608759327886956e+00 , 9.3193640000000002e+00 , 8.2016699999999998e-02 , 9.8633700000000002e-01 , -1.4287100000000000e-01 -2.6420889110291976e+00 , 2.5603539149381249e-01 , 1.3659265600000001e+00 , 4.6701800000000002e-02 , -2.3898200000000000e-01 , -9.6989999999999998e-01 -2.6411091480202806e+00 , 1.8505791870360455e-01 , 1.3718119199999999e+00 , -3.4048799999999997e-02 , 2.1657399999999999e-01 , 9.7567199999999998e-01 -2.6382646139123804e+00 , 1.2212798814369208e-01 , 1.3856480799999999e+00 , 7.4681800000000007e-02 , -1.8619500000000000e-01 , -9.7967000000000004e-01 -2.6367793569013216e+00 , 4.9848944435785247e-02 , 1.3954854399999999e+00 , -8.5339300000000007e-02 , 1.9043700000000000e-01 , 9.7798300000000005e-01 -2.6335073926536205e+00 , -1.3422307078640561e-02 , 1.4127650400000000e+00 , 9.7498799999999997e-02 , -1.8280299999999999e-01 , -9.7830300000000003e-01 -2.6321467075336749e+00 , -9.3592295708668782e-02 , 1.4203965599999999e+00 , 8.3407400000000007e-02 , -1.8217400000000000e-01 , -9.7972199999999998e-01 -2.6299295654933306e+00 , -1.6678372958394228e-01 , 1.4361078400000000e+00 , -1.0920000000000001e-01 , 1.7119999999999999e-01 , 9.7916599999999998e-01 -2.6269708374697540e+00 , -2.4812657946670003e-01 , 1.4480709599999999e+00 , -1.0316100000000000e-01 , 1.8864400000000001e-01 , 9.7661200000000004e-01 -2.6252300368238086e+00 , -3.3858190740436767e-01 , 1.4572479199999999e+00 , -8.0444299999999996e-02 , 1.9913200000000000e-01 , 9.7666500000000001e-01 -2.6216480187616553e+00 , -4.2102736463981838e-01 , 1.4741749600000000e+00 , -7.6521000000000006e-02 , 1.8752600000000000e-01 , 9.7927399999999998e-01 -2.6192593275025575e+00 , -5.1253722909358679e-01 , 1.4885186400000001e+00 , -7.8041399999999997e-02 , 1.6923400000000000e-01 , 9.8248100000000005e-01 -2.6169304411871170e+00 , -6.1400980303324815e-01 , 1.5008634400000000e+00 , -8.6145399999999997e-02 , 1.6507900000000000e-01 , 9.8251100000000002e-01 -2.6142801803798457e+00 , -7.1492144289230408e-01 , 1.5159413600000000e+00 , -5.6978300000000003e-02 , 1.9943100000000000e-01 , 9.7825399999999996e-01 -2.6097853109453131e+00 , -8.0781328795766827e-01 , 1.5387672800000001e+00 , -3.4492700000000001e-02 , 2.2913800000000001e-01 , 9.7278299999999995e-01 -2.6063789722418780e+00 , -9.0958916450105765e-01 , 1.5599219200000001e+00 , -3.0089899999999999e-02 , 2.1908000000000000e-01 , 9.7524299999999997e-01 -2.6028799685716630e+00 , -1.0221545220103532e+00 , 1.5801935999999999e+00 , -6.4068700000000006e-02 , 1.8134200000000000e-01 , 9.8133099999999995e-01 -2.5993170564030885e+00 , -1.1433706149393541e+00 , 1.5996790400000001e+00 , -8.1059800000000001e-02 , 1.9762299999999999e-01 , 9.7692100000000004e-01 -2.5952502883003317e+00 , -1.2658985582572275e+00 , 1.6231154399999999e+00 , -5.9350699999999999e-02 , 2.0760100000000001e-01 , 9.7641100000000003e-01 -2.5910578794494401e+00 , -1.3969624124535018e+00 , 1.6462720799999999e+00 , -9.4073599999999993e-02 , 1.9940900000000000e-01 , 9.7538999999999998e-01 -2.5865283022264061e+00 , -1.5394913908249213e+00 , 1.6704718400000000e+00 , -1.2490900000000001e-01 , 1.7282000000000000e-01 , 9.7700100000000001e-01 -2.5823731600895705e+00 , -1.7210054872442972e+00 , 1.6856662400000000e+00 , -1.5241900000000000e-01 , 1.3274300000000000e-01 , 9.7936100000000004e-01 -2.5776768634175014e+00 , -1.9136228199696603e+00 , 1.7036239200000001e+00 , 6.8965100000000001e-02 , -2.2405300000000000e-01 , -9.7213400000000005e-01 -2.5713359933734345e+00 , -2.0562642889974505e+00 , 1.7427050399999999e+00 , 1.0681899999999999e-04 , 2.8009899999999999e-01 , 9.5997100000000002e-01 -2.5656091820291160e+00 , -2.2091381295761003e+00 , 1.7837621600000000e+00 , -2.3279299999999999e-02 , 2.4800500000000000e-01 , 9.6847899999999998e-01 -2.5586641701632500e+00 , -2.3923425821299764e+00 , 1.8216379199999999e+00 , -3.5910800000000000e-02 , 2.3759200000000000e-01 , 9.7070100000000004e-01 -2.5510079542048048e+00 , -2.5753940802190662e+00 , 1.8653844799999999e+00 , -4.8423099999999997e-02 , 2.3851200000000000e-01 , 9.6993200000000002e-01 -2.5438481805353637e+00 , -2.7783370556663645e+00 , 1.9106258320000000e+00 , -5.1284600000000000e-02 , 2.3110300000000000e-01 , 9.7157700000000002e-01 -2.5350028367822315e+00 , -3.0009240752182382e+00 , 1.9581234640000000e+00 , -6.8279500000000007e-02 , 2.4089300000000000e-01 , 9.6814699999999998e-01 -2.5262855619550750e+00 , -3.2350941411557841e+00 , 2.0114472800000001e+00 , -7.2147400000000000e-02 , 2.3806300000000000e-01 , 9.6856699999999996e-01 -2.5167551701597097e+00 , -3.4985046097882710e+00 , 2.0669761040000001e+00 , -8.2267000000000007e-02 , 2.2625700000000001e-01 , 9.7058699999999998e-01 -2.5061541288105467e+00 , -3.7929055293932539e+00 , 2.1266376800000000e+00 , -7.6112100000000002e-02 , 2.1864300000000000e-01 , 9.7283200000000003e-01 -2.4942836500176231e+00 , -4.1179339583594414e+00 , 2.1920516000000001e+00 , -7.9842399999999994e-02 , 2.2160299999999999e-01 , 9.7186300000000003e-01 -2.4820826795457296e+00 , -4.4625121393464529e+00 , 2.2658437600000001e+00 , -8.0019300000000002e-02 , 2.1857299999999999e-01 , 9.7253400000000001e-01 -2.4679915259485350e+00 , -4.8793453313884951e+00 , 2.3441848800000002e+00 , -8.2354700000000003e-02 , 2.1064500000000000e-01 , 9.7408700000000004e-01 -2.4518748692361809e+00 , -5.3364459973355656e+00 , 2.4330612000000000e+00 , 7.4859700000000001e-02 , -2.0659900000000000e-01 , -9.7555800000000004e-01 -2.4341356552479625e+00 , -5.8655776395084249e+00 , 2.5329896000000001e+00 , -7.0989399999999994e-02 , 2.1006800000000000e-01 , 9.7510600000000003e-01 -2.4134437927746766e+00 , -6.4552841467372541e+00 , 2.6478617600000001e+00 , -6.9458900000000004e-02 , 2.0951000000000000e-01 , 9.7533599999999998e-01 -2.3904448134819649e+00 , -7.1059546279505739e+00 , 2.7811450400000002e+00 , -6.7531200000000000e-02 , 2.1211600000000000e-01 , 9.7490800000000000e-01 -2.3633686589353688e+00 , -7.8999431376070355e+00 , 2.9347832000000000e+00 , -5.0192500000000001e-02 , 2.1532999999999999e-01 , 9.7525099999999998e-01 -2.3312361838719333e+00 , -8.7847301071083130e+00 , 3.1160968000000002e+00 , 4.4482700000000000e-02 , -2.2449000000000000e-01 , -9.7346100000000002e-01 -2.2947701633442712e+00 , -9.7488571381272759e+00 , 3.3297544000000001e+00 , 1.7816599999999998e-02 , 2.7589900000000001e-01 , 9.6102100000000001e-01 -2.2549614915249472e+00 , -1.0635560941561083e+01 , 3.5739360000000002e+00 , 2.8582400000000002e-01 , 4.8804500000000001e-01 , 8.2469199999999998e-01 -2.2216296772138437e+00 , -1.0947080603741449e+01 , 3.8176911999999996e+00 , 2.7898899999999999e-01 , 4.2178199999999999e-01 , 8.6270800000000003e-01 -2.1891700138918782e+00 , -1.1139256057785470e+01 , 4.0639320000000003e+00 , 3.4743700000000000e-01 , 4.3967800000000001e-01 , 8.2823300000000000e-01 -2.1236138063484398e+00 , -1.2817917533525151e+01 , 4.4512280000000004e+00 , -2.0269900000000000e-02 , 2.4546399999999999e-01 , 9.6919400000000000e-01 -2.0153589858825671e+00 , -1.5984799236168072e+01 , 5.0581408000000003e+00 , -7.3556600000000000e-02 , 2.1359900000000001e-01 , 9.7414800000000001e-01 -1.5595882667797032e+00 , -2.9365151102308737e+01 , 7.6159272000000007e+00 , 8.2368799999999998e-01 , 4.8303900000000000e-01 , 2.9700399999999999e-01 -1.4762352489811001e+00 , -2.9782526510790483e+01 , 8.2461464000000007e+00 , 8.2368799999999998e-01 , 4.8303900000000000e-01 , 2.9700399999999999e-01 -1.4095683269811001e+00 , -2.9625088913479530e+01 , 8.7921152000000014e+00 , -8.6773599999999995e-01 , -4.6879900000000002e-01 , -1.6511200000000001e-01 -1.3539963553871530e+00 , -2.9162018787578361e+01 , 9.2759543999999998e+00 , -9.4404699999999997e-01 , -3.2751200000000003e-01 , 3.8876599999999997e-02 -1.1716187550552131e+00 , -3.2167137931930050e+01 , 1.0490580800000002e+01 , 9.7186600000000001e-01 , 1.0199100000000000e-01 , 2.1230900000000000e-01 -1.1020321648295788e+00 , -3.1949806493940670e+01 , 1.1069580000000000e+01 , 9.7186600000000001e-01 , 1.0199100000000000e-01 , 2.1230900000000000e-01 -1.1354537881562958e+00 , -2.9252904149446525e+01 , 1.1023622400000001e+01 , 3.7799400000000000e-01 , -1.6620699999999999e-02 , 9.2565900000000001e-01 -1.6118495515930547e+00 , -1.6727904822815031e+01 , 8.2352992000000000e+00 , -6.8461899999999998e-01 , -7.2883200000000004e-01 , 1.0059100000000000e-02 -1.4715396989297886e+00 , -1.8789621149254110e+01 , 9.1871280000000013e+00 , -3.3027899999999999e-01 , -2.7378400000000003e-01 , 9.0330400000000000e-01 -1.4314329441453721e+00 , -1.8579047681560525e+01 , 9.5228815999999998e+00 , -3.6588399999999999e-01 , -3.9513399999999999e-01 , 8.4261399999999997e-01 -1.5695520730344068e+00 , -1.4896971262981797e+01 , 8.7228719999999988e+00 , -1.6596000000000000e-01 , -6.4819599999999999e-01 , 7.4316899999999997e-01 -1.5172568501781092e+00 , -1.5089029089648278e+01 , 9.1234696000000000e+00 , -6.5414299999999995e-02 , -8.8530399999999998e-01 , 4.6038899999999999e-01 -1.5130520136637764e+00 , -1.4394720515793590e+01 , 9.2119527999999988e+00 , 9.1112299999999993e-02 , 8.9097000000000004e-01 , -4.4482600000000000e-01 -1.4677203323535388e+00 , -1.4468639998844726e+01 , 9.5731552000000004e+00 , -2.8605900000000001e-01 , -7.6213900000000001e-01 , 5.8078799999999997e-01 -1.4294851394251209e+00 , -1.4408901363601135e+01 , 9.8879112000000013e+00 , -4.1447800000000001e-01 , -8.8779500000000000e-01 , 2.0007200000000000e-01 -1.3876127576678776e+00 , -1.4381840710236229e+01 , 1.0218818400000000e+01 , 5.9232799999999997e-01 , 6.6266400000000003e-01 , -4.5828500000000000e-01 -1.4008415949468163e+00 , -1.3532890054167451e+01 , 1.0187327200000000e+01 , 7.6340900000000000e-01 , 2.2550100000000001e-01 , -6.0527299999999995e-01 -1.3623216696988312e+00 , -1.3489126423003555e+01 , 1.0501927200000001e+01 , 7.7686400000000000e-01 , -5.0714599999999999e-01 , -3.7320999999999999e-01 -1.3136146051558981e+00 , -1.3570945966421069e+01 , 1.0881038400000000e+01 , 3.5821999999999998e-01 , 9.3176199999999998e-01 , 5.9141600000000003e-02 -1.2625534984712252e+00 , -1.3680832660171935e+01 , 1.1284048800000001e+01 , 1.8678000000000000e-01 , 9.8024199999999995e-01 , 6.5100000000000005e-02 -1.1683025331510395e+00 , -1.4330687262509084e+01 , 1.1985612000000000e+01 , -3.7925599999999998e-01 , 8.4148800000000001e-01 , 3.8478899999999999e-01 -1.1730144245405920e+00 , -1.3680837423009391e+01 , 1.2002564000000001e+01 , 7.2007100000000004e-02 , 9.6350300000000000e-01 , 2.5783000000000000e-01 -3.2592102014476376e-02 , -2.6977451381975516e+01 , 2.0052840000000000e+01 , -3.4757600000000000e-01 , -9.3696800000000002e-01 , 3.5800499999999999e-02 -8.9527978780469497e-01 , -1.5846071298337687e+01 , 1.4050896000000002e+01 , 4.4592500000000002e-01 , 8.9144100000000004e-01 , -8.0524600000000002e-02 -8.5355148392035796e-01 , -1.5702042444601027e+01 , 1.4398360000000000e+01 , 6.6199799999999998e-01 , 5.9580800000000000e-01 , -4.5472099999999999e-01 -8.0108825933587524e-01 , -1.5665137639255942e+01 , 1.4817792000000001e+01 , -5.8701700000000001e-01 , -6.4059699999999997e-01 , 4.9502099999999999e-01 -8.8450596037444096e-01 , -1.4184049954336512e+01 , 1.4271168000000001e+01 , -3.1611800000000001e-01 , 3.5022999999999999e-01 , 8.8170800000000005e-01 -9.4100887933519628e-01 , -1.3058492342191727e+01 , 1.3908832000000000e+01 , 4.2639600000000000e-01 , -5.4368000000000005e-01 , 7.2291000000000005e-01 -9.7935507938781607e-01 , -1.2178027449894614e+01 , 1.3675663999999999e+01 , 4.5740799999999998e-01 , -8.5818899999999998e-01 , 2.3300299999999999e-01 -9.0762363527975887e-01 , -1.2394080973997355e+01 , 1.4232272000000000e+01 , 2.7299800000000002e-01 , -4.0290999999999999e-01 , 8.7357700000000005e-01 -9.3249797010451885e-01 , -1.1689739265932875e+01 , 1.4091768000000000e+01 , 2.1557399999999999e-01 , -6.6118200000000005e-01 , 7.1858699999999998e-01 -9.0076057631529172e-01 , -1.1524902756998394e+01 , 1.4360400000000000e+01 , 2.1557399999999999e-01 , -6.6118200000000005e-01 , 7.1858599999999995e-01 --6.6767179570919444e-01 , -2.4728731662429787e+01 , 2.5847200000000001e+01 , 1.5182000000000001e-01 , -9.8789000000000005e-01 , 3.2009099999999999e-02 -1.8269885031474011e+00 , -2.6826533850468355e+00 , 7.6609696000000005e+00 , -5.6478600000000001e-01 , -3.0720599999999998e-01 , 7.6592499999999997e-01 -1.6492292942098024e+00 , -3.9267877435187648e+00 , 8.9844736000000012e+00 , -6.9194199999999995e-01 , 6.7430599999999996e-01 , 2.5792900000000002e-01 -1.8432434574285794e+00 , -2.2422378350748158e+00 , 7.5683888000000001e+00 , -3.1719200000000003e-02 , -2.3874100000000001e-01 , 9.7056500000000001e-01 -1.8380548761351538e+00 , -2.1330677129160422e+00 , 7.6189848000000007e+00 , 5.9608899999999998e-01 , 9.6339700000000000e-02 , -7.9711799999999999e-01 -1.8320972935483877e+00 , -2.0313117574441213e+00 , 7.6747703999999999e+00 , 6.1186600000000002e-01 , 3.0947000000000002e-01 , -7.2790699999999997e-01 -1.8253688838140107e+00 , -1.9358773518073367e+00 , 7.7359431999999995e+00 , -5.4881199999999997e-01 , -4.8814999999999997e-01 , 6.7861300000000002e-01 -1.8061446012075379e+00 , -1.9226048610055293e+00 , 7.8873256000000005e+00 , 1.7331299999999999e-01 , 9.6792400000000001e-01 , -1.8189600000000000e-01 -1.4832234204565806e+00 , -3.8862218013141332e+00 , 1.0320364000000000e+01 , -1.4926300000000001e-01 , -5.5691400000000002e-01 , 8.1704800000000000e-01 -1.7632138645738860e+00 , -1.9159843115151611e+00 , 8.2324912000000001e+00 , -3.5383700000000001e-01 , 5.2865499999999999e-01 , -7.7157200000000004e-01 -1.7680041524209209e+00 , -1.7465341057478270e+00 , 8.2102456000000004e+00 , 8.6665699999999998e-02 , -7.7374600000000004e-01 , 6.2753999999999999e-01 -1.7644033522348832e+00 , -1.6302931951684152e+00 , 8.2488816000000007e+00 , 2.3027100000000000e-01 , 8.9652399999999999e-01 , -3.7844499999999998e-01 -1.7947719160865974e+00 , -1.3212418418156724e+00 , 8.0290256000000007e+00 , 4.7189599999999998e-01 , 8.7538700000000003e-01 , 1.0493900000000000e-01 -1.8056679663274080e+00 , -1.1361965447817512e+00 , 7.9589608000000007e+00 , -4.5886300000000002e-01 , -8.7611700000000003e-01 , -1.4786400000000000e-01 -1.7656250495207246e+00 , -1.2281446853698732e+00 , 8.2740496000000014e+00 , -4.2086200000000001e-01 , -7.4268500000000004e-01 , 5.2085800000000004e-01 -1.7621664167322248e+00 , -1.1187193890041245e+00 , 8.3104703999999998e+00 , -8.7475400000000003e-01 , -4.2696499999999998e-01 , 2.2914499999999999e-01 -1.7566704747447244e+00 , -1.0199684193542522e+00 , 8.3620128000000005e+00 , 7.8198199999999995e-01 , 2.2003800000000001e-01 , -5.8316999999999997e-01 -1.7408400020981674e+00 , -9.7102177462854078e-01 , 8.4909312000000003e+00 , -9.2947500000000005e-01 , -3.3917999999999998e-01 , 1.4502999999999999e-01 -1.7839491303158439e+00 , -6.5183237594175258e-01 , 8.1765183999999991e+00 , -2.3976500000000001e-01 , 4.6436600000000000e-01 , 8.5257099999999997e-01 -1.7355633704862448e+00 , -7.4738176885302288e-01 , 8.5510224000000008e+00 , -7.3653299999999999e-01 , 3.6122199999999999e-01 , -5.7187299999999996e-01 -1.7129046338534633e+00 , -7.2520204714025560e-01 , 8.7405728000000007e+00 , -7.8779299999999997e-01 , 4.1647200000000001e-01 , -4.5379900000000001e-01 -1.8009811519620271e+00 , -2.4234046037564072e-01 , 8.0728928000000000e+00 , -9.1059500000000004e-01 , -1.2348199999999999e-01 , -3.9442300000000002e-01 -1.7186284389526361e+00 , -4.5840349442906314e-01 , 8.7168191999999998e+00 , -3.1170199999999998e-01 , 2.9320200000000002e-01 , 9.0381100000000003e-01 -1.7585760705899527e+00 , -1.8694890628236971e-01 , 8.4125359999999993e+00 , -1.9697999999999999e-01 , -8.7593799999999999e-01 , 4.4037700000000002e-01 -1.7551082036972054e+00 , -8.8465962993218294e-02 , 8.4473760000000002e+00 , -1.4883600000000000e-01 , -9.2085200000000000e-01 , 3.6038599999999998e-01 -1.7418328511157757e+00 , -2.7965384841492025e-02 , 8.5656552000000001e+00 , -3.0398700000000001e-01 , -7.9976899999999995e-01 , 5.1765000000000005e-01 -1.7412632693170758e+00 , 8.1875766769186953e-02 , 8.5783951999999992e+00 , -4.0512199999999998e-01 , -7.9528600000000005e-01 , 4.5099499999999998e-01 -1.5553244433162299e+00 , -3.8823550173796306e-01 , 1.0026387200000000e+01 , -4.4821400000000000e-01 , -1.2174400000000000e-01 , -8.8559699999999997e-01 -1.5706307086243454e+00 , -2.0654081944610292e-01 , 9.9195688000000004e+00 , -6.2633300000000003e-01 , -5.1969600000000005e-01 , -5.8105399999999996e-01 -1.6885775473476841e+00 , 2.5863780191120012e-01 , 9.0123455999999997e+00 , 6.3259600000000005e-01 , -3.1612300000000003e-02 , -7.7383700000000000e-01 -1.7450595851442039e+00 , 5.2372392414509239e-01 , 8.5798407999999995e+00 , -7.0420300000000002e-01 , 7.0899599999999996e-01 , -3.7706600000000000e-02 -1.6516405713606699e+00 , 3.9316433172050891e-01 , 9.3190728000000007e+00 , 7.0952599999999999e-01 , -5.4153499999999999e-01 , 4.5090300000000000e-01 -1.6660710277445241e+00 , 5.4462964282194881e-01 , 9.2148752000000016e+00 , -3.8972000000000001e-01 , -7.9235800000000001e-01 , 4.6934799999999999e-01 -1.6493224639852391e+00 , 6.2147888526021622e-01 , 9.3555664000000007e+00 , -8.1350800000000001e-01 , 1.1450900000000000e-01 , -5.7016900000000004e-01 -1.6403789114638956e+00 , 7.1970077404015131e-01 , 9.4353447999999993e+00 , -8.8205400000000000e-01 , 1.2251700000000000e-01 , -4.5494000000000001e-01 -1.6670296982423716e+00 , 8.8808979750624384e-01 , 9.2333144000000011e+00 , -7.1416999999999997e-01 , 4.7600700000000001e-01 , -5.1320399999999999e-01 -1.5698415566377841e+00 , 8.2437855128526127e-01 , 1.0013678400000000e+01 , 7.8576000000000001e-01 , -4.6931400000000001e-01 , 4.0289599999999998e-01 -1.6249486116536149e+00 , 1.0425854431202404e+00 , 9.5853439999999992e+00 , 9.8794899999999997e-01 , -1.2778900000000001e-01 , -8.7328699999999995e-02 -1.6445812216301421e+00 , 1.1878194105914317e+00 , 9.4460568000000009e+00 , -9.6247400000000005e-01 , -2.7098800000000001e-01 , -1.4457899999999999e-02 -1.5989166304969580e+00 , 1.2401573306861313e+00 , 9.8120328000000008e+00 , 3.5554999999999998e-01 , -2.6631400000000000e-01 , 8.9591399999999999e-01 -1.5939227213006750e+00 , 1.3544604463465753e+00 , 9.8618072000000012e+00 , 1.5240699999999999e-02 , -3.8160500000000003e-01 , 9.2420000000000002e-01 -1.5954816531262999e+00 , 1.4759027591787470e+00 , 9.8588224000000011e+00 , 5.0947200000000004e-01 , -1.3561200000000001e-01 , -8.4973399999999999e-01 -1.6100534510754216e+00 , 1.6106888771157586e+00 , 9.7509224000000003e+00 , -4.4330500000000000e-01 , 7.1299999999999997e-01 , 5.4324099999999997e-01 -1.5880112159210760e+00 , 1.7099568310408422e+00 , 9.9385280000000016e+00 , 4.3783300000000003e-01 , -4.9883200000000000e-01 , 7.4797599999999997e-01 -1.5916487376976580e+00 , 1.8332323581823025e+00 , 9.9187264000000006e+00 , -8.5243299999999994e-02 , 7.9634000000000005e-01 , 5.9881200000000001e-01 -1.6130146402707040e+00 , 1.9644767373645253e+00 , 9.7630800000000004e+00 , 4.3474400000000002e-01 , -5.5530000000000002e-01 , -7.0897100000000002e-01 -1.6927160041549176e+00 , 2.1128982221035892e+00 , 9.1306767999999998e+00 , -7.1511300000000000e-01 , -2.1180399999999999e-01 , -6.6614799999999996e-01 -1.6176395037741906e+00 , 2.2003406508615342e+00 , 9.7436632000000003e+00 , 6.9225999999999999e-01 , 4.2138300000000001e-01 , -5.8584400000000003e-01 -1.6121724939670499e+00 , 2.3176634077230496e+00 , 9.7977847999999987e+00 , -5.5122899999999997e-01 , -4.9664000000000003e-01 , 6.7044400000000004e-01 -1.5920755829014093e+00 , 2.4358279515876409e+00 , 9.9636440000000004e+00 , 5.9314999999999996e-01 , 4.6269300000000002e-01 , -6.5885400000000005e-01 -1.5709007440063039e+00 , 2.5609590515555061e+00 , 1.0148035999999999e+01 , -7.6904099999999997e-01 , -6.3894099999999998e-01 , 1.8162000000000001e-02 -1.6432898447562856e+00 , 2.6626433008259660e+00 , 9.5772320000000004e+00 , -1.0875799999999999e-01 , 5.0190999999999997e-01 , 8.5805500000000001e-01 -1.1281764036771582e+00 , 3.0159017887746806e+00 , 1.3734632000000001e+01 , -7.4490400000000001e-01 , 6.6710700000000001e-01 , -9.2176399999999992e-03 -1.6224146076340704e+00 , 2.9063467552758038e+00 , 9.7599391999999998e+00 , -9.3423699999999998e-01 , -1.8277700000000000e-01 , 3.0625700000000000e-01 -1.6380460894873190e+00 , 3.0136834387395273e+00 , 9.6477856000000006e+00 , -5.7851500000000000e-01 , -7.7272200000000002e-01 , 2.6119199999999998e-01 -1.6454376081567608e+00 , 3.1249049317810687e+00 , 9.5953176000000013e+00 , 5.0906499999999999e-01 , 4.4270799999999999e-01 , 7.3814800000000003e-01 -1.6772807216325265e+00 , 3.2093121056558029e+00 , 9.3464559999999999e+00 , 6.5161199999999997e-01 , 1.5121699999999999e-01 , 7.4332699999999996e-01 -1.6885545966174571e+00 , 3.3082578052554394e+00 , 9.2602191999999999e+00 , 1.1360099999999999e-01 , 9.9018899999999999e-01 , -8.1362799999999999e-02 -2.6061206762708169e+00 , 5.1275898615498039e-01 , 1.3043845599999999e+00 , -8.2193100000000005e-02 , 1.7082800000000001e-01 , 9.8186700000000005e-01 -2.5871411809218015e+00 , 2.2529745036791526e-01 , 1.3650477599999999e+00 , -1.5893200000000000e-02 , 1.7200900000000000e-01 , 9.8496700000000004e-01 -2.5823678772656176e+00 , 1.6327114479084326e-01 , 1.3776192800000000e+00 , 7.5880900000000001e-02 , -1.7554100000000000e-01 , -9.8154300000000005e-01 -2.5789815367111313e+00 , 9.1837669152880386e-02 , 1.3859871200000000e+00 , -4.8988799999999999e-02 , 1.7992200000000000e-01 , 9.8246000000000000e-01 -2.5743180545631463e+00 , 1.9752677709616639e-02 , 1.3961562399999998e+00 , -6.2102200000000003e-02 , 1.8455299999999999e-01 , 9.8085900000000004e-01 -2.5704592150417906e+00 , -5.1946362594496698e-02 , 1.4083720799999999e+00 , -6.3818500000000000e-02 , 1.7858800000000000e-01 , 9.8185199999999995e-01 -2.5658370893312559e+00 , -1.3286237015435098e-01 , 1.4168439200000000e+00 , -9.6262899999999998e-02 , 1.6542799999999999e-01 , 9.8151299999999997e-01 -2.5609207290462042e+00 , -2.1435798669063555e-01 , 1.4276453600000001e+00 , -6.0324099999999999e-02 , 2.2542100000000001e-01 , 9.7239200000000003e-01 -2.5562826656536055e+00 , -2.8688350950456254e-01 , 1.4461407200000000e+00 , -6.9293800000000003e-02 , 2.0617900000000000e-01 , 9.7605799999999998e-01 -2.5507802081613313e+00 , -3.6954847470128671e-01 , 1.4616013600000000e+00 , 7.0385199999999995e-02 , -1.7924399999999999e-01 , -9.8128400000000005e-01 -2.5454942948989419e+00 , -4.6025552548787152e-01 , 1.4740470400000001e+00 , 6.5404599999999993e-02 , -1.8866800000000000e-01 , -9.7985999999999995e-01 -2.5398335074040328e+00 , -5.5249234582971329e-01 , 1.4893319200000001e+00 , -5.1120300000000000e-02 , 1.5683600000000000e-01 , 9.8630099999999998e-01 -2.5342530499435822e+00 , -6.5363717414081135e-01 , 1.5026158400000000e+00 , -4.6539700000000003e-02 , 1.6427800000000001e-01 , 9.8531599999999997e-01 -2.5283071188323394e+00 , -7.5523810249218482e-01 , 1.5188377600000000e+00 , -3.7527600000000001e-02 , 2.1088199999999999e-01 , 9.7679099999999996e-01 -2.5216496205343617e+00 , -8.4682804419731861e-01 , 1.5424218400000000e+00 , -4.5966699999999999e-02 , 2.2834199999999999e-01 , 9.7249500000000000e-01 -2.5152992994887016e+00 , -9.5866617490258843e-01 , 1.5603909599999999e+00 , 5.9245800000000001e-02 , -1.8853600000000001e-01 , -9.8027799999999998e-01 -2.5078236505848936e+00 , -1.0801872887307047e+00 , 1.5775530400000000e+00 , -3.9867600000000003e-02 , 1.7742200000000000e-01 , 9.8332699999999995e-01 -2.5002024954116377e+00 , -1.2113094927764925e+00 , 1.5944374400000001e+00 , -4.5437600000000002e-02 , 2.0103799999999999e-01 , 9.7852899999999998e-01 -2.4925172725271243e+00 , -1.3240973590161094e+00 , 1.6232412800000000e+00 , -6.8669499999999994e-02 , 1.7164299999999999e-01 , 9.8276300000000005e-01 -2.4846608238513022e+00 , -1.4854782682082521e+00 , 1.6374736800000000e+00 , -1.1750600000000000e-01 , 1.6696400000000000e-01 , 9.7893600000000003e-01 -2.4749100922173701e+00 , -1.6376609614054849e+00 , 1.6600593600000000e+00 , -1.3574400000000000e-01 , 1.2458100000000000e-01 , 9.8287999999999998e-01 -2.4656532535538185e+00 , -1.8389067281747247e+00 , 1.6711364000000000e+00 , 8.4266999999999995e-02 , -2.1680199999999999e-01 , -9.7257199999999999e-01 -2.4561183995925946e+00 , -1.9615986817362545e+00 , 1.7136339199999999e+00 , 1.8207899999999999e-02 , 2.7728700000000001e-01 , 9.6061500000000000e-01 -2.4443443245227696e+00 , -2.1047578821284345e+00 , 1.7542147200000000e+00 , -1.7942600000000000e-02 , 2.5527200000000000e-01 , 9.6670299999999998e-01 -2.4336727455254845e+00 , -2.2874974219792970e+00 , 1.7883475200000001e+00 , -3.3462400000000003e-02 , 2.3138800000000001e-01 , 9.7228599999999998e-01 -2.4212537495679669e+00 , -2.4700499930608588e+00 , 1.8282252800000001e+00 , 3.8141399999999999e-02 , -2.2812299999999999e-01 , -9.7288500000000000e-01 -2.4071766899059228e+00 , -2.6624465957875412e+00 , 1.8716484000000000e+00 , 4.5726500000000003e-02 , -2.3324300000000001e-01 , -9.7134299999999996e-01 -2.3936011634431256e+00 , -2.8856953481728072e+00 , 1.9148753759999999e+00 , -5.4267400000000000e-02 , 2.2259999999999999e-01 , 9.7339799999999999e-01 -2.3780700736453113e+00 , -3.1094996857309649e+00 , 1.9654699200000001e+00 , 6.4198300000000000e-02 , -2.3677200000000001e-01 , -9.6944200000000003e-01 -2.3607593510358371e+00 , -3.3626448447291244e+00 , 2.0176379839999998e+00 , -6.3864500000000005e-02 , 2.2897500000000001e-01 , 9.7133499999999995e-01 -2.3434951061620324e+00 , -3.6359849238958244e+00 , 2.0749467680000002e+00 , -6.1065899999999999e-02 , 2.1720999999999999e-01 , 9.7421300000000000e-01 -2.3229884142407404e+00 , -3.9510382659258605e+00 , 2.1353570400000002e+00 , -6.3621600000000000e-02 , 2.1829399999999999e-01 , 9.7380699999999998e-01 -2.3012092931850061e+00 , -4.2748175382528570e+00 , 2.2049007999999999e+00 , -7.3977000000000001e-02 , 2.2529500000000000e-01 , 9.7147799999999995e-01 -2.2767843457142036e+00 , -4.6505035337693492e+00 , 2.2797246400000000e+00 , -7.0367899999999997e-02 , 2.1157799999999999e-01 , 9.7482500000000005e-01 -2.2493409419840220e+00 , -5.0873401450094127e+00 , 2.3613708799999999e+00 , -6.8645800000000007e-02 , 2.0580100000000001e-01 , 9.7618300000000002e-01 -2.2175128965874880e+00 , -5.5846811088785033e+00 , 2.4527494399999998e+00 , -6.2679799999999994e-02 , 2.0815900000000001e-01 , 9.7608499999999998e-01 -2.1832255950722987e+00 , -6.1127634320067887e+00 , 2.5595980000000003e+00 , -6.0737600000000003e-02 , 2.0848300000000000e-01 , 9.7613799999999995e-01 -2.1419703821792409e+00 , -6.7643544156967934e+00 , 2.6791595199999998e+00 , -6.3653500000000002e-02 , 2.0848300000000000e-01 , 9.7595200000000004e-01 -2.0962427046348830e+00 , -7.4646569284182593e+00 , 2.8194804800000002e+00 , -5.0391699999999998e-02 , 2.1563399999999999e-01 , 9.7517299999999996e-01 -2.0436712067372302e+00 , -8.2671986761826961e+00 , 2.9832128800000000e+00 , -4.5104999999999999e-02 , 2.1783700000000000e-01 , 9.7494199999999998e-01 -1.9822352495170643e+00 , -9.1910124873851711e+00 , 3.1756472000000002e+00 , -1.7761800000000001e-02 , 2.3126200000000000e-01 , 9.7272899999999995e-01 -1.9128066421585199e+00 , -1.0205116383419622e+01 , 3.4026896000000004e+00 , 1.9445999999999999e-01 , 3.8607399999999997e-01 , 9.0173899999999996e-01 -1.8696468075678252e+00 , -1.0549083357783651e+01 , 3.6362736000000000e+00 , -3.8999000000000000e-01 , -5.3935900000000003e-01 , -7.4632399999999999e-01 -1.8264433290186741e+00 , -1.0837136447802511e+01 , 3.8786976000000002e+00 , -3.1009799999999998e-01 , -4.6691199999999999e-01 , -8.2815000000000005e-01 -1.7659995355335103e+00 , -1.1471542662706748e+01 , 4.1586759999999998e+00 , 3.0528400000000000e-01 , 4.2854300000000001e-01 , 8.5038400000000003e-01 -1.5894520983702209e+00 , -1.4271844829157509e+01 , 4.6675167999999996e+00 , -5.6677100000000001e-02 , 2.0899000000000001e-01 , 9.7627399999999998e-01 -1.3460664065025147e+00 , -1.8090182641238933e+01 , 5.3904832000000003e+00 , -2.2530300000000000e-01 , 1.9377000000000000e-01 , 9.5482599999999995e-01 -7.6717005830955087e-01 , -2.7568911086971145e+01 , 6.9865608000000003e+00 , -8.5239299999999996e-01 , -3.6342200000000002e-01 , -3.7596700000000000e-01 -6.9825638094347231e-01 , -2.7574709707486765e+01 , 7.5175536000000003e+00 , -8.7448000000000004e-01 , -4.8037600000000003e-01 , -6.7256099999999999e-02 -6.2930958416154681e-01 , -2.7571707476730815e+01 , 8.0501375999999993e+00 , 5.6742099999999995e-01 , 8.2247400000000004e-01 , 3.9619399999999999e-02 -5.6621654097211005e-01 , -2.7466921383975833e+01 , 8.5672256000000004e+00 , -3.8799800000000001e-01 , -9.1951400000000005e-01 , 6.2864100000000006e-02 -5.0178820008490321e-01 , -2.7393709965227373e+01 , 9.0904600000000002e+00 , -4.0534500000000001e-01 , -9.1159900000000005e-01 , 6.8438399999999996e-02 -4.3142387334385091e-01 , -2.7402455527926158e+01 , 9.6330072000000015e+00 , -4.0277299999999999e-01 , -9.1109700000000005e-01 , 8.7609300000000001e-02 -3.6834151998962317e-01 , -2.7290026970963385e+01 , 1.0151176800000000e+01 , -3.6040499999999998e-01 , -9.2334000000000005e-01 , 1.3248199999999999e-01 -3.0566502371524318e-01 , -2.7188552127644421e+01 , 1.0672944800000002e+01 , -3.7480500000000000e-01 , -9.1476299999999999e-01 , 1.5076400000000001e-01 -2.4231188727529540e-01 , -2.7077876304968548e+01 , 1.1193246400000001e+01 , 2.7159599999999999e-02 , -9.7437799999999997e-01 , 2.2327300000000000e-01 -8.5597822128467915e-01 , -1.8211812635040332e+01 , 9.1410248000000003e+00 , 1.4356800000000000e-01 , 1.4128299999999999e-01 , 9.7950400000000004e-01 -8.0805519208596821e-01 , -1.8179611594240704e+01 , 9.5225487999999991e+00 , -3.3585900000000002e-01 , -5.0238099999999997e-01 , 7.9675099999999999e-01 -1.0104909608534378e+00 , -1.5099541477617461e+01 , 8.8948464000000005e+00 , 2.4113699999999998e-02 , -8.6127600000000004e-01 , 5.0756400000000002e-01 -9.8190827434229866e-01 , -1.4924302875790218e+01 , 9.1736287999999995e+00 , 2.4113699999999998e-02 , -8.6127600000000004e-01 , 5.0756500000000004e-01 -9.5220002736513987e-01 , -1.4755447120277697e+01 , 9.4519015999999993e+00 , -1.0838600000000000e-01 , -7.7225600000000005e-01 , 6.2599800000000005e-01 -9.2056806878629405e-01 , -1.4619346468573799e+01 , 9.7410840000000007e+00 , 2.1572100000000000e-01 , -8.5411999999999999e-01 , 4.7322599999999998e-01 -9.3267098830856976e-01 , -1.3999832965461046e+01 , 9.8304824000000011e+00 , 6.2056100000000003e-01 , -5.4861499999999996e-01 , 5.6029099999999998e-01 -9.2049801051482705e-01 , -1.3668355890338749e+01 , 1.0023880800000001e+01 , 6.1736800000000003e-01 , -6.1606399999999994e-01 , 4.8920599999999997e-01 -8.3094825054396804e-01 , -1.4145881398776279e+01 , 1.0575267999999999e+01 , -8.7430799999999997e-01 , 4.3466600000000000e-01 , -2.1599099999999999e-01 -7.0461232048283384e-01 , -1.4955576467073119e+01 , 1.1309684800000001e+01 , -7.7364100000000002e-01 , 6.2835300000000005e-01 , -8.1561599999999998e-02 -6.9289917374197341e-01 , -1.4593126644778465e+01 , 1.1503998400000000e+01 , 6.7897399999999997e-01 , -7.3251299999999997e-01 , -4.9185500000000000e-02 -7.4050299014156784e-01 , -1.3696141237640337e+01 , 1.1412551200000001e+01 , 3.9646399999999998e-01 , -8.7202400000000002e-01 , -2.8703800000000002e-01 -5.7167781603040169e-01 , -1.4821440691062442e+01 , 1.2379449600000001e+01 , 6.5299700000000002e-02 , -9.2354700000000001e-01 , 3.7788600000000000e-01 -5.3957621991608384e-01 , -1.4653812898117621e+01 , 1.2677264000000001e+01 , 1.3643000000000000e-01 , -9.1611699999999996e-01 , 3.7698399999999999e-01 -3.7440099537020921e-01 , -1.5641696041176179e+01 , 1.3652160000000000e+01 , 5.5685700000000005e-01 , 7.5373599999999996e-01 , 3.4898699999999999e-01 -3.3075262612513834e-01 , -1.5539653577987536e+01 , 1.4017824000000001e+01 , -7.2381700000000004e-01 , -6.7714700000000005e-01 , 1.3251700000000000e-01 -2.9435195127284186e-01 , -1.5377672437240665e+01 , 1.4350000000000000e+01 , -6.2886399999999998e-01 , -1.7009500000000000e-01 , 7.5868199999999997e-01 -4.8604120577187371e-01 , -1.3379184966903518e+01 , 1.3474216000000000e+01 , -5.7213599999999998e-01 , 6.0168800000000000e-01 , -5.5734399999999995e-01 -5.2952027006341451e-01 , -1.2637008901468684e+01 , 1.3367303999999999e+01 , 4.2639600000000000e-01 , -5.4368000000000005e-01 , 7.2291000000000005e-01 -4.9335137581368427e-01 , -1.2528781203083698e+01 , 1.3681176000000001e+01 , 4.5524500000000001e-01 , -5.2541300000000002e-01 , 7.1881399999999995e-01 -4.6560802570434889e-01 , -1.2346899429712336e+01 , 1.3945231999999999e+01 , -1.7385100000000001e-01 , -3.9221600000000001e-01 , 9.0329499999999996e-01 -4.3938253043310360e-01 , -1.2160465362337895e+01 , 1.4206376000000001e+01 , -1.7385100000000001e-01 , -3.9221600000000001e-01 , 9.0329499999999996e-01 -1.6831918541334390e-01 , -1.3703784977103046e+01 , 1.5837720000000001e+01 , -9.2078099999999996e-01 , 2.0450699999999999e-01 , 3.3217500000000000e-01 --1.4742388290892747e+00 , -2.4579403167258182e+01 , 2.5230376000000000e+01 , 1.5182000000000001e-01 , -9.8789000000000005e-01 , 3.2009099999999999e-02 -1.5647952091189734e+00 , -3.5296825410579622e+00 , 8.1283767999999998e+00 , 3.7893500000000002e-01 , 3.7798699999999998e-02 , 9.2465100000000000e-01 -1.6852895044307847e+00 , -2.5867872909722962e+00 , 7.4793960000000004e+00 , 2.2406200000000001e-02 , -6.2001900000000004e-03 , 9.9973000000000001e-01 -1.6763297515477751e+00 , -2.5156280723360913e+00 , 7.5724656000000001e+00 , 2.2406200000000001e-02 , -6.2001199999999999e-03 , 9.9973000000000001e-01 -1.4220957894515220e+00 , -3.9589076648620711e+00 , 9.0980623999999999e+00 , -6.9194299999999997e-01 , 6.7430500000000004e-01 , 2.5792900000000002e-01 -1.6772244855578566e+00 , -2.2585098704664999e+00 , 7.6472104000000005e+00 , 2.0349600000000001e-01 , -2.9324400000000000e-01 , 9.3412899999999999e-01 -1.6854608812272853e+00 , -2.0824717082471205e+00 , 7.6320264000000000e+00 , 2.1770600000000001e-01 , -3.0961600000000000e-01 , 9.2560399999999998e-01 -1.6869502066079298e+00 , -1.9581104801097688e+00 , 7.6645680000000000e+00 , 1.7835000000000001e-01 , -5.1531899999999997e-01 , 8.3823499999999995e-01 -1.6845493322193530e+00 , -1.8491605145603924e+00 , 7.7094439999999995e+00 , 4.8934000000000000e-01 , 6.6437700000000000e-01 , -5.6493400000000005e-01 -1.6303398442652033e+00 , -2.0266971907705456e+00 , 8.0762520000000002e+00 , -5.0390999999999997e-01 , 6.6465300000000005e-01 , -5.5164400000000002e-01 -1.6494822436679524e+00 , -1.8037419215882600e+00 , 7.9958912000000000e+00 , -4.3722299999999997e-01 , -8.7686900000000001e-01 , 1.9984299999999999e-01 -1.6378539059258301e+00 , -1.7487332036690506e+00 , 8.1083464000000003e+00 , -4.1306500000000002e-01 , -4.8568800000000001e-01 , 7.7037900000000004e-01 -1.6209451790991727e+00 , -1.7110198937853838e+00 , 8.2444824000000008e+00 , -5.5287799999999998e-01 , -6.3325900000000002e-01 , 5.4157900000000003e-01 -1.6094827805575380e+00 , -1.6508097261430930e+00 , 8.3564071999999996e+00 , -3.1638800000000000e-01 , -7.4089099999999997e-01 , 5.9243500000000004e-01 -1.5948507917413204e+00 , -1.5999859620235197e+00 , 8.4843272000000010e+00 , -4.1710100000000000e-01 , -6.2681500000000001e-01 , 6.5812599999999999e-01 -1.6015716861790819e+00 , -1.4497651107783067e+00 , 8.4777231999999998e+00 , 9.1689799999999999e-01 , -3.7514100000000000e-01 , 1.3626400000000000e-01 -1.5974393468735371e+00 , -1.3487109240987634e+00 , 8.5356823999999989e+00 , 6.1944299999999997e-01 , -6.3937100000000002e-01 , -4.5551599999999998e-01 -1.6423591917986564e+00 , -1.0406998130621918e+00 , 8.2821616000000002e+00 , 6.0463500000000003e-01 , 2.5197000000000003e-01 , -7.5559799999999999e-01 -1.6400709868072079e+00 , -9.4329356944157627e-01 , 8.3329655999999996e+00 , 6.2112400000000001e-01 , -3.1586399999999998e-01 , -7.1724100000000002e-01 -1.6726746125502565e+00 , -7.0380398188226545e-01 , 8.1530768000000009e+00 , 4.3588199999999999e-01 , -4.7073599999999999e-01 , -7.6708200000000004e-01 -1.5922789019510857e+00 , -9.1242425997999632e-01 , 8.7131688000000018e+00 , -3.5692800000000002e-01 , 8.9595400000000003e-01 , -2.6432600000000001e-01 -1.5589788897363370e+00 , -9.2446965710819384e-01 , 8.9677608000000006e+00 , -1.9413100000000000e-01 , 9.7320499999999999e-01 , -1.2322900000000001e-01 -1.5279799066959998e+00 , -9.1863510166743589e-01 , 9.2062120000000007e+00 , 7.5682799999999995e-02 , 9.4591199999999998e-01 , -3.1547100000000000e-01 -1.6265407748158220e+00 , -4.5837308283036826e-01 , 8.5866632000000003e+00 , -3.3159600000000002e-03 , 2.9068500000000003e-01 , 9.5681300000000002e-01 -1.4917408402444887e+00 , -8.0147611317059519e-01 , 9.5217376000000016e+00 , 1.8369600000000000e-02 , -5.5843799999999999e-01 , 8.2934300000000005e-01 -1.6764127402090194e+00 , -8.4946176674422169e-02 , 8.3110111999999994e+00 , -2.1179300000000002e-02 , -6.2176500000000001e-01 , 7.8291699999999997e-01 -1.6715065105121794e+00 , -1.1758650592237352e-03 , 8.3726728000000001e+00 , -3.1863300000000000e-01 , -6.6740800000000000e-01 , 6.7308199999999996e-01 -1.6594488780601302e+00 , 6.0080910334563642e-02 , 8.4896519999999995e+00 , -4.2506800000000000e-01 , -5.8809800000000001e-01 , 6.8808199999999997e-01 -1.6246674946230493e+00 , 6.1583263196826943e-02 , 8.7584815999999996e+00 , -5.3132400000000002e-01 , -8.4469899999999998e-01 , 6.4646400000000007e-02 -1.6104945083094622e+00 , 1.2803534284754425e-01 , 8.8850496000000003e+00 , 7.1101199999999998e-01 , 3.6957600000000002e-01 , -5.9822699999999995e-01 -1.6426939210050724e+00 , 3.1715498018942201e-01 , 8.6922128000000001e+00 , -9.0261300000000000e-01 , 4.2826900000000001e-01 , -4.3297099999999998e-02 -1.6617787309296834e+00 , 4.6393966774906348e-01 , 8.5920920000000010e+00 , 6.5220800000000001e-01 , -6.7427700000000002e-01 , 3.4637499999999999e-01 -1.6395364084086292e+00 , 5.0948548440953623e-01 , 8.7817880000000006e+00 , 1.3733799999999999e-01 , -9.6354899999999999e-01 , 2.2958999999999999e-01 -1.5375092818715828e+00 , 3.8476818079400799e-01 , 9.5323768000000015e+00 , 6.7762299999999998e-01 , -3.9611800000000003e-01 , 6.1961100000000002e-01 -1.5327014377224071e+00 , 4.9028022574925068e-01 , 9.5965032000000008e+00 , -5.9297100000000003e-01 , 5.9016400000000002e-01 , -5.4780600000000002e-01 -1.4662024534664697e+00 , 4.7477341320784783e-01 , 1.0106165600000001e+01 , -4.3676799999999999e-01 , 7.2409999999999997e-01 , 5.3377200000000002e-01 -1.5172279677415128e+00 , 6.9034367093448168e-01 , 9.7798759999999998e+00 , -9.8079099999999997e-01 , 1.1071499999999999e-01 , 1.6059599999999999e-01 -1.5676631036873669e+00 , 8.9421071346440928e-01 , 9.4480328000000000e+00 , 4.8638500000000001e-01 , 1.1569900000000000e-01 , -8.6604999999999999e-01 -1.5039471220311653e+00 , 9.0300071687661365e-01 , 9.9471184000000008e+00 , 8.0293700000000001e-01 , 3.3536700000000003e-01 , 4.9276900000000001e-01 -1.5885371960037011e+00 , 1.1454921748666504e+00 , 9.3663096000000010e+00 , -3.0250699999999998e-02 , -1.1856500000000000e-01 , 9.9248499999999995e-01 -1.5776197018384841e+00 , 1.2397993891212411e+00 , 9.4789519999999996e+00 , -9.2022099999999996e-01 , -3.6289700000000003e-01 , 1.4662800000000001e-01 -1.5519038409512322e+00 , 1.3188133753927480e+00 , 9.7022712000000002e+00 , 2.3933499999999999e-01 , 3.2197000000000003e-02 , -9.7040300000000002e-01 -1.5338487490046913e+00 , 1.4135774343509770e+00 , 9.8736320000000006e+00 , -1.1856999999999999e-01 , 2.1333900000000000e-01 , 9.6975699999999998e-01 -1.5549447921173150e+00 , 1.5517595740438852e+00 , 9.7470847999999997e+00 , 4.3667200000000000e-01 , -7.1250700000000000e-01 , -5.4922800000000005e-01 -1.5297930742601684e+00 , 1.6458151485621162e+00 , 9.9766648000000018e+00 , 7.1664900000000004e-02 , -4.0921700000000000e-01 , 9.0961800000000004e-01 -1.5213690257507670e+00 , 1.7587544145493930e+00 , 1.0071637600000001e+01 , -1.7673000000000000e-01 , -9.8181700000000005e-01 , 6.9302199999999994e-02 -1.5704101289625385e+00 , 1.9081043604264829e+00 , 9.7429768000000010e+00 , 1.9956699999999999e-01 , 6.7501599999999995e-01 , 7.1030099999999996e-01 -1.6559926392275044e+00 , 2.0609376232156622e+00 , 9.1231784000000005e+00 , 5.4237299999999999e-01 , -5.8181499999999997e-01 , -6.0607200000000006e-01 -1.6742716836876399e+00 , 2.1711954036294054e+00 , 9.0155488000000013e+00 , -8.8389600000000002e-01 , -3.6898199999999998e-01 , -2.8736899999999999e-01 -1.5809375448118632e+00 , 2.2596663820808933e+00 , 9.7615096000000001e+00 , 7.0910399999999996e-01 , 5.4005700000000001e-01 , -4.5333200000000001e-01 -1.5774058698567446e+00 , 2.3767755327193036e+00 , 9.8255216000000001e+00 , -5.1753800000000003e-02 , -8.2463600000000004e-01 , 5.6329099999999999e-01 -1.5407830183771418e+00 , 2.5000941779392596e+00 , 1.0145196800000001e+01 , -7.6904099999999997e-01 , -6.3894099999999998e-01 , 1.8161699999999999e-02 -1.6120639745260232e+00 , 2.6082868071482790e+00 , 9.6275368000000014e+00 , 4.9662400000000001e-01 , -3.9256700000000000e-01 , -7.7411600000000003e-01 -1.6265210758700193e+00 , 2.7197626855420687e+00 , 9.5514816000000007e+00 , -7.3164300000000002e-02 , 2.6288099999999998e-01 , 9.6204999999999996e-01 -1.6018484971391729e+00 , 2.8491244229597603e+00 , 9.7824760000000008e+00 , -4.4481100000000001e-01 , -3.4397499999999998e-01 , 8.2693700000000003e-01 -1.5838244437035780e+00 , 2.9821694796057572e+00 , 9.9594008000000009e+00 , -9.4369800000000004e-01 , -1.4626600000000001e-01 , 2.9671700000000001e-01 -1.6319345036953186e+00 , 3.0700226881221857e+00 , 9.6204543999999999e+00 , 8.4117699999999995e-01 , 6.7627900000000005e-02 , 5.3651499999999996e-01 -1.6619390506876910e+00 , 3.1619309169184286e+00 , 9.4136608000000006e+00 , -9.0358000000000005e-01 , -2.1435100000000001e-01 , -3.7094100000000002e-01 -1.6797181329106936e+00 , 3.2599138096509979e+00 , 9.3082880000000010e+00 , 1.4966199999999999e-01 , 9.8404700000000001e-01 , -9.6194299999999996e-02 -2.5281332870576816e+00 , 1.9781129851387802e-01 , 1.3635574400000001e+00 , 4.8328700000000002e-02 , -1.7406199999999999e-01 , -9.8354799999999998e-01 -2.5227790663041931e+00 , 1.2624420191058361e-01 , 1.3708655200000002e+00 , -4.9382900000000000e-02 , 1.8648100000000001e-01 , 9.8121700000000001e-01 -2.5156125184702471e+00 , 6.3732761721256859e-02 , 1.3858186400000001e+00 , 6.1767200000000001e-02 , -1.5510299999999999e-01 , -9.8596499999999998e-01 -2.5103736321092232e+00 , -1.6798916260563956e-02 , 1.3908220800000000e+00 , 8.3364300000000002e-02 , -1.8721800000000000e-01 , -9.7877499999999995e-01 -2.5027151274947910e+00 , -8.0641017808869009e-02 , 1.4096263200000001e+00 , 4.8107799999999999e-02 , -1.4381900000000000e-01 , -9.8843400000000003e-01 -2.4964497511712267e+00 , -1.6992305241729344e-01 , 1.4131113599999998e+00 , 5.7532699999999999e-02 , -1.7915000000000000e-01 , -9.8213799999999996e-01 -2.4888330107019412e+00 , -2.4259608743574690e-01 , 1.4302172799999999e+00 , -5.3031200000000001e-02 , 2.4164700000000000e-01 , 9.6891400000000005e-01 -2.4809912042555249e+00 , -3.1487967310293374e-01 , 1.4492461599999999e+00 , -7.1898100000000006e-02 , 1.9993900000000001e-01 , 9.7716700000000001e-01 -2.4737969341851751e+00 , -4.0582500562999968e-01 , 1.4601256000000000e+00 , 7.7928100000000000e-02 , -1.7630599999999999e-01 , -9.8124599999999995e-01 -2.4652270459186623e+00 , -4.9724019720222890e-01 , 1.4736144000000000e+00 , 7.7936000000000005e-02 , -1.9098100000000001e-01 , -9.7849500000000000e-01 -2.4567280259487259e+00 , -5.9863707865566340e-01 , 1.4850034399999998e+00 , -4.9051299999999999e-02 , 1.7880099999999999e-01 , 9.8266200000000004e-01 -2.4485391767103497e+00 , -6.9002808741290611e-01 , 1.5039834400000001e+00 , -5.1004200000000000e-02 , 1.7857500000000001e-01 , 9.8260400000000003e-01 -2.4393397102199805e+00 , -7.9129105678169687e-01 , 1.5211424000000000e+00 , -5.7804200000000000e-02 , 2.1270000000000000e-01 , 9.7540600000000000e-01 -2.4297521745091299e+00 , -8.9297226044354749e-01 , 1.5414421599999999e+00 , -6.4427600000000002e-02 , 2.0925600000000000e-01 , 9.7573600000000005e-01 -2.4190515885857766e+00 , -1.0054481684449366e+00 , 1.5606322399999999e+00 , -6.1193499999999998e-02 , 1.9405700000000001e-01 , 9.7907999999999995e-01 -2.4082878688086868e+00 , -1.1265746548377922e+00 , 1.5790360800000001e+00 , -3.6710000000000000e-02 , 1.9789000000000001e-01 , 9.7953699999999999e-01 -2.3967562165952785e+00 , -1.2386884521169792e+00 , 1.6051088800000000e+00 , -7.6067599999999999e-02 , 1.9045599999999999e-01 , 9.7874399999999995e-01 -2.3848636273657502e+00 , -1.3892042395939668e+00 , 1.6197208800000000e+00 , -9.3164899999999995e-02 , 1.5226500000000001e-01 , 9.8393900000000001e-01 -2.3715957014926752e+00 , -1.5500479348268610e+00 , 1.6354498399999999e+00 , -1.3053400000000001e-01 , 1.3530200000000001e-01 , 9.8216800000000004e-01 -2.3570395133865056e+00 , -1.7323333756215975e+00 , 1.6498964800000000e+00 , -8.9665499999999995e-02 , 1.8326200000000001e-01 , 9.7896600000000000e-01 -2.3422576300949887e+00 , -1.8839548166758684e+00 , 1.6794699200000001e+00 , -6.5250300000000002e-03 , 2.6777000000000001e-01 , 9.6346100000000001e-01 -2.3283339657521456e+00 , -2.0072074689020871e+00 , 1.7234920800000000e+00 , 1.7926500000000001e-02 , -2.8612199999999999e-01 , -9.5802600000000004e-01 -2.3116931868916955e+00 , -2.1792721186032944e+00 , 1.7566389600000001e+00 , 3.9399000000000003e-02 , -2.3539099999999999e-01 , -9.7110200000000002e-01 -2.2943729393979266e+00 , -2.3512304383635803e+00 , 1.7953539999999999e+00 , -4.2471399999999999e-02 , 2.2790299999999999e-01 , 9.7275699999999998e-01 -2.2756468132603200e+00 , -2.5542896094930532e+00 , 1.8323072800000000e+00 , 3.5825999999999997e-02 , -2.2926400000000000e-01 , -9.7270500000000004e-01 -2.2560753012541297e+00 , -2.7460066452956493e+00 , 1.8779352000000000e+00 , -4.7014399999999998e-02 , 2.1834899999999999e-01 , 9.7473799999999999e-01 -2.2339696404884424e+00 , -2.9894379817224168e+00 , 1.9193012000000000e+00 , -6.2041899999999997e-02 , 2.2869000000000000e-01 , 9.7152000000000005e-01 -2.2118279957622189e+00 , -3.2123963711634422e+00 , 1.9726831520000001e+00 , 5.3989000000000002e-02 , -2.3169999999999999e-01 , -9.7128800000000004e-01 -2.1868407753773829e+00 , -3.4755656294401636e+00 , 2.0261253199999998e+00 , -6.5775000000000000e-02 , 2.2934900000000000e-01 , 9.7111899999999995e-01 -2.1587351409590978e+00 , -3.7587648873852819e+00 , 2.0849383599999998e+00 , -6.5845000000000001e-02 , 2.2065799999999999e-01 , 9.7312600000000005e-01 -2.1273546418296094e+00 , -4.0923748177251706e+00 , 2.1457622399999998e+00 , -6.6790400000000000e-02 , 2.1519400000000000e-01 , 9.7428499999999996e-01 -2.0944523296980573e+00 , -4.4474207790916367e+00 , 2.2158571999999999e+00 , -7.1586700000000003e-02 , 2.2407600000000000e-01 , 9.7193900000000000e-01 -2.0568033887524413e+00 , -4.8422352729754277e+00 , 2.2930720000000000e+00 , -6.7212800000000003e-02 , 2.1799600000000000e-01 , 9.7363299999999997e-01 -2.0139988131310123e+00 , -5.2881494243959333e+00 , 2.3790591999999999e+00 , -6.2402899999999997e-02 , 2.1176300000000001e-01 , 9.7532700000000006e-01 -1.9667571848832250e+00 , -5.7846249431728589e+00 , 2.4766746400000001e+00 , -6.0554299999999998e-02 , 2.1242800000000001e-01 , 9.7529900000000003e-01 -1.9111638309377752e+00 , -6.3729171137874054e+00 , 2.5858559200000002e+00 , -5.9809700000000000e-02 , 2.0498100000000000e-01 , 9.7693700000000006e-01 -1.8462789686517422e+00 , -7.0743545953953699e+00 , 2.7112175199999999e+00 , -5.4535100000000003e-02 , 2.1690000000000001e-01 , 9.7466900000000001e-01 -1.7785271809502801e+00 , -7.7729563208321579e+00 , 2.8605625600000000e+00 , -4.7245799999999998e-02 , 2.1772400000000000e-01 , 9.7486600000000001e-01 -1.6953047713957965e+00 , -8.6445739840882112e+00 , 3.0332389600000003e+00 , -4.1121100000000001e-02 , 2.2241300000000000e-01 , 9.7408499999999998e-01 -1.6025768508905740e+00 , -9.5965058375014589e+00 , 3.2374128000000004e+00 , 6.6584199999999996e-02 , 3.0907400000000002e-01 , 9.4870399999999999e-01 -1.5333202726510069e+00 , -1.0159797322522833e+01 , 3.4627496000000000e+00 , 3.2780999999999999e-01 , 4.6777099999999999e-01 , 8.2081099999999996e-01 -1.4834200569178664e+00 , -1.0429576588997383e+01 , 3.6941079999999999e+00 , -3.0207600000000001e-01 , -4.9680999999999997e-01 , -8.1359099999999995e-01 -1.4353727287365294e+00 , -1.0662901075013393e+01 , 3.9329024000000001e+00 , 3.0036099999999999e-01 , 4.7978399999999999e-01 , 8.2437300000000002e-01 -1.2166951611623360e+00 , -1.3020010865552610e+01 , 4.3560264000000002e+00 , -4.7095499999999998e-02 , 2.0436299999999999e-01 , 9.7776200000000002e-01 -1.0140948643413155e+00 , -1.5034505094849887e+01 , 4.8280823999999996e+00 , -5.6677100000000001e-02 , 2.0899000000000001e-01 , 9.7627399999999998e-01 -7.1010310503128116e-02 , -2.5682167420178768e+01 , 6.3891951999999996e+00 , 4.6997400000000000e-01 , 3.6051000000000000e-01 , 8.0570299999999995e-01 --8.8291464206279091e-02 , -2.6744201776322875e+01 , 7.0291176000000002e+00 , 7.2054900000000000e-01 , 5.4472799999999999e-01 , 4.2904700000000001e-01 --2.1918651189627969e-01 , -2.7444036713087819e+01 , 7.6539495999999998e+00 , 2.6522299999999999e-02 , 9.9184899999999998e-01 , 1.2462400000000000e-01 --2.8078236185803052e-01 , -2.7334596399405665e+01 , 8.1681048000000001e+00 , 1.5286900000000001e-02 , -9.7357700000000003e-01 , 2.2784599999999999e-01 --3.3664262683620683e-01 , -2.7164144429798949e+01 , 8.6702168000000004e+00 , 2.3609100000000000e-01 , 9.6791799999999995e-01 , -8.5997900000000002e-02 --4.1941319960698697e-01 , -2.7280458950546091e+01 , 9.2293623999999994e+00 , -2.3257300000000000e-01 , -9.6714100000000003e-01 , 1.0271000000000000e-01 --4.8183512714252830e-01 , -2.7182752652224501e+01 , 9.7486032000000016e+00 , 5.7068800000000003e-02 , 9.8655999999999999e-01 , -1.5310900000000000e-01 --5.4395215789090212e-01 , -2.7076813674794067e+01 , 1.0266616800000000e+01 , -8.2077600000000001e-02 , -9.6987500000000004e-01 , 2.2935700000000001e-01 --6.0624053083115248e-01 , -2.6971652236824553e+01 , 1.0785847199999999e+01 , -9.1031699999999993e-02 , 9.7333999999999998e-01 , -2.1053100000000000e-01 --6.7025773901448726e-01 , -2.6876179392217455e+01 , 1.1309019200000000e+01 , -1.0377400000000001e-01 , 9.9141800000000002e-01 , -7.9510800000000006e-02 -2.2797983846755865e-01 , -1.7964739643245522e+01 , 9.1899879999999996e+00 , -2.4609200000000001e-01 , -4.2205100000000001e-01 , 8.7253199999999997e-01 -2.1747213637849350e-01 , -1.7595254089870764e+01 , 9.4615736000000012e+00 , -2.7462300000000001e-01 , -5.1927500000000004e-01 , 8.0928100000000003e-01 --8.5770690743818756e-01 , -2.6555719939510713e+01 , 1.2880896000000002e+01 , -2.6335300000000000e-01 , 9.3244600000000000e-01 , -2.4736700000000000e-01 --9.2075014737627647e-01 , -2.6442646762426715e+01 , 1.3407448000000000e+01 , -2.8690900000000003e-01 , 9.3476499999999996e-01 , -2.0951800000000001e-01 -2.1137736568624410e-01 , -1.6331914247477137e+01 , 1.0159694400000001e+01 , 1.2425100000000001e-03 , -8.7347600000000003e-01 , 4.8686600000000002e-01 -1.2800122663617519e-01 , -1.6595533360291327e+01 , 1.0641214399999999e+01 , 1.2421200000000000e-03 , -8.7347600000000003e-01 , 4.8686600000000002e-01 -1.6167423074014420e-01 , -1.5913814578835826e+01 , 1.0743612800000001e+01 , -8.4073200000000003e-01 , 5.4054800000000003e-01 , 3.1273099999999998e-02 -8.3435762608223829e-03 , -1.6719431377089379e+01 , 1.1476573600000000e+01 , 8.3511999999999997e-01 , -4.9799199999999999e-01 , -2.3362100000000000e-01 --1.2806944754768264e+00 , -2.6182939812952498e+01 , 1.6232711999999999e+01 , -1.6046299999999999e-01 , 9.6109699999999998e-01 , -2.2481799999999999e-01 -1.3964187552872009e-01 , -1.4917507931092473e+01 , 1.1420361600000000e+01 , -6.6438699999999995e-01 , 7.2980599999999995e-01 , -1.6115900000000000e-01 --1.4145133970420503e+00 , -2.5951993987921430e+01 , 1.7349879999999999e+01 , -1.6380500000000001e-01 , 9.6522300000000005e-01 , -2.0374700000000001e-01 -7.5045533229580741e-02 , -1.4654490403781818e+01 , 1.2042791200000000e+01 , -5.7125900000000000e-02 , -9.4401500000000005e-01 , 3.2491799999999998e-01 -1.4387437024010463e-03 , -1.4808316087695463e+01 , 1.2512216000000000e+01 , 1.1692600000000000e-01 , -9.3244499999999997e-01 , 3.4186899999999998e-01 -1.7077617116485033e-02 , -1.4332614767951974e+01 , 1.2636808000000000e+01 , 3.8843499999999997e-01 , -7.1070900000000004e-01 , 5.8652499999999996e-01 -8.3946834569692541e-04 , -1.4088764009999618e+01 , 1.2884848000000002e+01 , 3.1246299999999999e-01 , -7.3581799999999997e-01 , 6.0078200000000004e-01 --8.0108352167327368e-02 , -1.4270606604533551e+01 , 1.3393304000000001e+01 , -5.1785999999999999e-01 , 6.2447299999999994e-01 , -5.8468299999999995e-01 --5.7592588129133926e-02 , -1.3772712683032179e+01 , 1.3481912000000001e+01 , -5.9546399999999999e-01 , 6.8591999999999997e-01 , -4.1825499999999999e-01 --7.3706739583321745e-02 , -1.3533399744893947e+01 , 1.3728080000000000e+01 , -6.0960099999999995e-01 , 6.4483100000000004e-01 , -4.6106399999999997e-01 --8.8252680496907487e-02 , -1.3281459546915977e+01 , 1.3963328000000001e+01 , 3.7617699999999998e-01 , -4.6798800000000002e-01 , 7.9967400000000000e-01 --2.0813837035744305e+00 , -2.5005224305684166e+01 , 2.2818720000000003e+01 , 3.1041000000000002e-01 , -9.3273899999999998e-01 , 1.8342400000000000e-01 --2.1191970761775112e+00 , -2.4641486116228641e+01 , 2.3287968000000003e+01 , 2.5877299999999998e-01 , -9.5615099999999997e-01 , 1.3715800000000000e-01 --2.1118982571413181e+00 , -2.4017746805742192e+01 , 2.3555247999999999e+01 , 1.5182000000000001e-01 , -9.8789000000000005e-01 , 3.2009000000000003e-02 --2.3412731376591118e+00 , -2.4742213663470995e+01 , 2.4891024000000002e+01 , 1.5182000000000001e-01 , -9.8789000000000005e-01 , 3.2009099999999999e-02 -1.3891688423551143e+00 , -3.4759453476511002e+00 , 7.9781279999999999e+00 , 2.1816700000000000e-01 , 3.4636199999999999e-02 , 9.7529699999999997e-01 -1.3943768925730238e+00 , -3.3181043566928334e+00 , 8.0195824000000009e+00 , 2.1816700000000000e-01 , 3.4636199999999999e-02 , 9.7529600000000005e-01 -1.5039887255884419e+00 , -2.6159833732101569e+00 , 7.5698864000000006e+00 , -1.4954700000000001e-01 , -1.6644500000000000e-03 , 9.8875299999999999e-01 -1.4929697229937144e+00 , -2.5576464566973920e+00 , 7.6778696000000002e+00 , -8.5394200000000003e-02 , -3.5222499999999997e-02 , 9.9572400000000005e-01 -1.5228091014272174e+00 , -2.2967938012504092e+00 , 7.5928704000000007e+00 , 1.8255199999999999e-01 , -2.4375100000000000e-01 , 9.5250199999999996e-01 -1.5257282985829899e+00 , -2.1724716809983571e+00 , 7.6308199999999999e+00 , -2.4857899999999999e-01 , 6.3308900000000001e-01 , -7.3307999999999995e-01 -1.5041263537187128e+00 , -2.1699743444650235e+00 , 7.7914272000000002e+00 , -5.4268200000000000e-01 , 8.0019499999999999e-01 , -2.5531199999999998e-01 -1.4970820093936203e+00 , -2.0996790131225396e+00 , 7.8858696000000004e+00 , -4.3114000000000002e-01 , 8.6877099999999996e-01 , -2.4362900000000001e-01 -1.4669754590328381e+00 , -2.1318650389762182e+00 , 8.0938903999999994e+00 , -4.9515100000000001e-01 , 7.2195799999999999e-01 , -4.8332500000000000e-01 -1.4717733765214407e+00 , -2.0013681911616734e+00 , 8.1259744000000005e+00 , 3.8330300000000000e-01 , -4.5440100000000000e-01 , 8.0411400000000000e-01 -1.4555083085572942e+00 , -1.9641080389864376e+00 , 8.2652824000000003e+00 , -1.0157700000000000e-01 , -2.1930600000000000e-01 , 9.7035400000000005e-01 -1.4770249259473069e+00 , -1.7615549711988283e+00 , 8.2053472000000003e+00 , 2.3221400000000000e-01 , 2.3320900000000000e-01 , -9.4429399999999997e-01 -1.4860608598855285e+00 , -1.6191948845443735e+00 , 8.2129288000000003e+00 , -2.4817900000000001e-01 , -3.1097900000000001e-01 , 9.1744199999999998e-01 -1.4812913144609545e+00 , -1.5342614325888397e+00 , 8.2909184000000007e+00 , 7.0834900000000001e-01 , 9.9380099999999999e-02 , -6.9883099999999998e-01 -1.4998383118320195e+00 , -1.3567911224196236e+00 , 8.2428808000000000e+00 , -3.1142999999999998e-01 , 4.1421599999999997e-01 , 8.5524000000000000e-01 -1.5210462758934256e+00 , -1.1766909373726060e+00 , 8.1820927999999995e+00 , 4.8345399999999999e-01 , -1.5823999999999999e-01 , -8.6094800000000005e-01 -1.5328053105276616e+00 , -1.0336302895435434e+00 , 8.1674080000000000e+00 , -7.8623699999999996e-01 , -1.7984800000000001e-01 , 5.9117399999999998e-01 -1.5325790154046626e+00 , -9.3734474707845106e-01 , 8.2183679999999999e+00 , 6.1147499999999999e-01 , -2.6751200000000003e-01 , -7.4467099999999997e-01 -1.4103818339329699e+00 , -1.2718232811695547e+00 , 8.9564559999999993e+00 , 6.7608199999999996e-01 , -6.1273000000000000e-01 , -4.0923799999999999e-01 -1.4632967496054254e+00 , -9.8252316901773318e-01 , 8.7119104000000007e+00 , -2.6330700000000001e-01 , 9.0400199999999997e-01 , -3.3682400000000001e-01 -1.4690122138937189e+00 , -8.6131641617957921e-01 , 8.7350192000000000e+00 , 3.7888500000000003e-01 , -8.9953499999999997e-01 , 2.1744500000000000e-01 -1.4336504768721738e+00 , -8.7113747614371206e-01 , 8.9896528000000000e+00 , -1.1506200000000000e-01 , 9.6384599999999998e-01 , -2.4033800000000000e-01 -1.4305064531078364e+00 , -7.7522054455137379e-01 , 9.0645015999999998e+00 , 8.3281900000000005e-04 , -9.7984300000000002e-01 , 1.9976800000000000e-01 -1.4089005247796949e+00 , -7.3516983211477394e-01 , 9.2481344000000014e+00 , 4.9451400000000001e-01 , 8.4885699999999997e-01 , -1.8681000000000000e-01 -1.3885797650529863e+00 , -6.8423646759396739e-01 , 9.4228336000000006e+00 , 1.8369600000000000e-02 , -5.5843900000000002e-01 , 8.2934300000000005e-01 -1.5574420736511552e+00 , -9.8674042733204015e-02 , 8.4599600000000006e+00 , -4.5970899999999998e-01 , 3.3808100000000002e-01 , -8.2120000000000004e-01 -1.5628228696917046e+00 , 9.2853567002291193e-03 , 8.4751752000000007e+00 , 4.2344500000000002e-01 , 5.9445899999999996e-01 , -6.8360299999999996e-01 -1.5493408043747312e+00 , 6.4968846311668438e-02 , 8.6116440000000001e+00 , 6.0515699999999994e-01 , 7.5035300000000005e-01 , -2.6599899999999999e-01 -1.5611239066168023e+00 , 1.8978255162806090e-01 , 8.5854360000000014e+00 , -1.3413100000000000e-01 , -5.5454300000000001e-01 , 8.2127399999999995e-01 -1.5744291811123214e+00 , 3.1631614922632312e-01 , 8.5469664000000005e+00 , 6.2202700000000000e-01 , -5.4373099999999996e-01 , 5.6341699999999995e-01 -1.3613005767786657e+00 , -7.7173564549757323e-02 , 9.9372384000000018e+00 , 4.8332500000000000e-01 , -6.1681399999999997e-01 , 6.2123899999999999e-01 -1.5498749149502644e+00 , 4.4645528799213952e-01 , 8.8029416000000005e+00 , -7.3840200000000000e-01 , 6.7421200000000003e-01 , -1.4130800000000001e-02 -1.5409772794171681e+00 , 5.2587225257675319e-01 , 8.9053296000000000e+00 , -8.4558599999999995e-01 , 5.2798800000000001e-01 , 7.8823500000000005e-02 -1.4400569382078392e+00 , 4.2531890356985524e-01 , 9.6074440000000010e+00 , 3.2541999999999999e-01 , -8.3888799999999997e-01 , 4.3631300000000001e-01 -1.4030519233091214e+00 , 4.6536785467322450e-01 , 9.9089920000000014e+00 , -5.9120200000000001e-01 , 7.9426099999999999e-01 , 1.4010500000000001e-01 -1.3942627665875391e+00 , 5.6500053914957227e-01 , 1.0022175200000001e+01 , -4.3676799999999999e-01 , 7.2409999999999997e-01 , 5.3377200000000002e-01 -1.4197069298251730e+00 , 7.2163783130293124e-01 , 9.9143584000000011e+00 , -5.8688799999999997e-01 , 4.9778800000000001e-01 , 6.3856900000000005e-01 -1.4480190559518005e+00 , 8.7872172196071552e-01 , 9.7830584000000016e+00 , 3.1413600000000003e-01 , -5.6261699999999998e-02 , 9.4770900000000002e-01 -1.4128360694508206e+00 , 9.4036943139445728e-01 , 1.0081528000000000e+01 , -6.6813000000000000e-01 , -4.4198100000000001e-01 , 5.9854399999999996e-01 -1.5142097704802502e+00 , 1.1888735339220586e+00 , 9.4498215999999999e+00 , 5.3688899999999995e-01 , -6.8715400000000004e-01 , 4.8945899999999998e-01 -1.4660075210369912e+00 , 1.2379889842890321e+00 , 9.8361504000000011e+00 , 2.6689499999999999e-01 , -1.4262800000000000e-01 , 9.5311299999999999e-01 -1.4414485549790297e+00 , 1.3255293295962098e+00 , 1.0059875200000000e+01 , 7.3257799999999995e-01 , -4.9504199999999998e-01 , 4.6718599999999999e-01 -1.4993902141570685e+00 , 1.4970035890533868e+00 , 9.7216984000000011e+00 , 3.4641300000000003e-01 , -8.7667300000000004e-02 , 9.3397699999999995e-01 -1.4875788290847267e+00 , 1.5997408543662188e+00 , 9.8601848000000007e+00 , -5.2191500000000002e-01 , -7.0265400000000000e-01 , 4.8361399999999999e-01 -1.4463147472923588e+00 , 1.6851895109961599e+00 , 1.0212256000000000e+01 , -9.5643500000000004e-01 , 2.7605900000000000e-01 , -9.4993900000000006e-02 -1.4472952511639419e+00 , 1.8074280106620630e+00 , 1.0265805600000000e+01 , -9.0994399999999998e-01 , -4.1366300000000000e-01 , -2.9746700000000001e-02 -1.5903618126609123e+00 , 1.9974110569586534e+00 , 9.2998224000000000e+00 , 1.5654799999999999e-01 , 8.4448599999999996e-01 , 5.1218799999999998e-01 -1.6400861836864054e+00 , 2.1224562551999631e+00 , 8.9876976000000006e+00 , -6.8876099999999996e-01 , 4.9936700000000001e-01 , 5.2558700000000003e-01 -1.6354894592402489e+00 , 2.2231053886983321e+00 , 9.0751824000000010e+00 , -8.8389600000000002e-01 , -3.6898199999999998e-01 , -2.8736899999999999e-01 -1.5583025416453213e+00 , 2.3208174920395348e+00 , 9.7070864000000014e+00 , 8.0636500000000000e-01 , 5.0936099999999995e-01 , -3.0054300000000000e-01 -1.5753637742116249e+00 , 2.4374807741487299e+00 , 9.6362520000000007e+00 , -3.0066700000000002e-01 , -5.9125399999999995e-01 , -7.4834400000000001e-01 -1.5163052786011195e+00 , 2.5639650059366836e+00 , 1.0140766400000000e+01 , -7.6904200000000000e-01 , -6.3894099999999998e-01 , 1.8161900000000002e-02 -1.6012614310368958e+00 , 2.6644094697895109e+00 , 9.5612160000000017e+00 , -3.3240999999999998e-01 , 5.0885400000000003e-01 , 7.9408500000000004e-01 -1.5939529647703654e+00 , 2.9058151428804417e+00 , 9.7354160000000007e+00 , 7.6596799999999998e-01 , 1.4768100000000001e-01 , -6.2568599999999996e-01 -1.4557745452882551e+00 , 3.1301141352564263e+00 , 1.0887725600000000e+01 , -5.9260199999999996e-01 , -2.4844800000000000e-01 , 7.6622299999999999e-01 -1.6193260901673856e+00 , 3.1336615228015594e+00 , 9.6648312000000001e+00 , -9.7121900000000005e-01 , -1.9056300000000001e-01 , -1.4289700000000000e-01 -1.6633160926842496e+00 , 3.2136971715372566e+00 , 9.3757632000000015e+00 , 7.9680799999999996e-01 , 1.2122800000000000e-01 , 5.9194700000000000e-01 -1.6866944567754305e+00 , 3.3072440448027685e+00 , 9.2495176000000008e+00 , 1.4946799999999999e-01 , 9.8742900000000000e-01 , -5.1421500000000002e-02 -2.4763254083484414e+00 , 2.4113097124513327e-01 , 1.3567329600000000e+00 , 8.8538900000000004e-02 , -1.8594500000000000e-01 , -9.7856299999999996e-01 -2.4690680378904846e+00 , 1.7041963540419158e-01 , 1.3625725600000000e+00 , -9.7835900000000003e-02 , 1.8014200000000000e-01 , 9.7876300000000005e-01 -2.4609785141362961e+00 , 1.0773171025728634e-01 , 1.3764888000000000e+00 , -7.7358700000000002e-02 , 1.9921600000000000e-01 , 9.7689700000000002e-01 -2.4522399139948257e+00 , 3.6730725818590937e-02 , 1.3858488000000000e+00 , -6.5835199999999997e-02 , 1.6082099999999999e-01 , 9.8478500000000002e-01 -2.4442632507643642e+00 , -3.4911670660872751e-02 , 1.3974614399999998e+00 , 7.0894499999999999e-02 , -1.8334800000000001e-01 , -9.8048800000000003e-01 -2.4345487989791330e+00 , -1.1475886207064789e-01 , 1.4048974400000001e+00 , -4.9410200000000001e-02 , 1.7177300000000001e-01 , 9.8389700000000002e-01 -2.4255176902225646e+00 , -1.9620782292474948e-01 , 1.4150946400000000e+00 , -4.8989800000000000e-02 , 2.2174500000000000e-01 , 9.7387299999999999e-01 -2.4157286756834888e+00 , -2.6865267368581947e-01 , 1.4328609600000000e+00 , 8.3011199999999993e-02 , -1.9631100000000001e-01 , -9.7702199999999995e-01 -2.4060732809325973e+00 , -3.6832083197449572e-01 , 1.4368067199999999e+00 , -9.9084900000000004e-02 , 1.7086200000000001e-01 , 9.8029999999999995e-01 -2.3951335225454065e+00 , -4.5040076031470422e-01 , 1.4539677599999998e+00 , -8.8816500000000007e-02 , 2.0751200000000000e-01 , 9.7419199999999995e-01 -2.3839324226920469e+00 , -5.3202431204140543e-01 , 1.4733533599999999e+00 , -9.7826300000000005e-02 , 1.8336900000000000e-01 , 9.7816499999999995e-01 -2.3732123628334252e+00 , -6.3310739084244894e-01 , 1.4858073599999999e+00 , 6.9653000000000007e-02 , -1.7105899999999999e-01 , -9.8279600000000000e-01 -2.3611293134883438e+00 , -7.3359661632372530e-01 , 1.5009684800000000e+00 , 6.6473000000000004e-02 , -1.9671200000000000e-01 , -9.7820499999999999e-01 -2.3486227260187720e+00 , -8.3552997230364134e-01 , 1.5193723200000000e+00 , 7.8279699999999994e-02 , -2.0374300000000001e-01 , -9.7589000000000004e-01 -2.3350926320900180e+00 , -9.4622369164807729e-01 , 1.5362577600000000e+00 , 6.5447800000000000e-02 , -2.0831500000000000e-01 , -9.7587000000000002e-01 -2.3218400196383242e+00 , -1.0479474825630390e+00 , 1.5608371200000000e+00 , -4.9275199999999998e-02 , 2.0705699999999999e-01 , 9.7708700000000004e-01 -2.3067120900541895e+00 , -1.1696827384571753e+00 , 1.5805617599999999e+00 , 7.9043299999999997e-02 , -1.6584499999999999e-01 , -9.8297900000000005e-01 -2.2906796765647983e+00 , -1.3102457899617059e+00 , 1.5962647200000000e+00 , -1.1296900000000000e-01 , 1.6069800000000001e-01 , 9.8051800000000000e-01 -2.2735888750456033e+00 , -1.4704530877622473e+00 , 1.6090598400000000e+00 , -1.2719700000000000e-01 , 1.4558199999999999e-01 , 9.8113499999999998e-01 -2.2548037497306361e+00 , -1.6316723680107992e+00 , 1.6269967200000000e+00 , -1.0541499999999999e-01 , 1.7713300000000001e-01 , 9.7852499999999998e-01 -2.2347643764870879e+00 , -1.8132971809535405e+00 , 1.6435472799999999e+00 , -1.6305600000000000e-02 , 2.5871800000000000e-01 , 9.6581499999999998e-01 -2.2186934017164788e+00 , -1.9155604476222838e+00 , 1.6912094400000000e+00 , -3.5558899999999997e-02 , 2.7964699999999998e-01 , 9.5944399999999996e-01 -2.1971882253118400e+00 , -2.0880487487510706e+00 , 1.7211988800000000e+00 , -4.0090399999999998e-02 , 2.4468599999999999e-01 , 9.6877300000000000e-01 -2.1759516994618409e+00 , -2.2493511030536153e+00 , 1.7592816000000000e+00 , 4.9517499999999999e-02 , -2.2753200000000001e-01 , -9.7251100000000001e-01 -2.1532476277171551e+00 , -2.4317813652238280e+00 , 1.7976003999999999e+00 , 4.8360700000000000e-02 , -2.3053699999999999e-01 , -9.7186099999999997e-01 -2.1279078942793777e+00 , -2.6230335027035858e+00 , 1.8390319200000000e+00 , -6.0140800000000001e-02 , 2.2478000000000001e-01 , 9.7255199999999997e-01 -2.1009489566090975e+00 , -2.8460982608013889e+00 , 1.8803220000000000e+00 , -6.7789600000000005e-02 , 2.1960299999999999e-01 , 9.7323099999999996e-01 -2.0721239993571210e+00 , -3.0676842630970675e+00 , 1.9285697840000000e+00 , -6.5867099999999998e-02 , 2.4128700000000000e-01 , 9.6821599999999997e-01 -2.0394232117552300e+00 , -3.3305601221604633e+00 , 1.9765523679999999e+00 , -6.6920300000000002e-02 , 2.2917799999999999e-01 , 9.7108099999999997e-01 -2.0056813303891126e+00 , -3.5927025957428960e+00 , 2.0332390239999998e+00 , -7.5720800000000005e-02 , 2.3293400000000000e-01 , 9.6953999999999996e-01 -1.9677481368835985e+00 , -3.8956046320745017e+00 , 2.0922912640000000e+00 , -8.1663799999999995e-02 , 2.1879999999999999e-01 , 9.7234699999999996e-01 -1.9242820409703263e+00 , -4.2496297442782236e+00 , 2.1546240800000001e+00 , -8.1491900000000006e-02 , 2.2528599999999999e-01 , 9.7087900000000005e-01 -1.8794009396859099e+00 , -4.6022756830049563e+00 , 2.2287968800000000e+00 , -8.0472399999999999e-02 , 2.2711899999999999e-01 , 9.7053699999999998e-01 -1.8273729164110744e+00 , -5.0269263975342904e+00 , 2.3077006400000002e+00 , 7.7984399999999995e-02 , -2.1953200000000000e-01 , -9.7248400000000002e-01 -1.7668122399975743e+00 , -5.5130814811053028e+00 , 2.3957356000000001e+00 , -7.1229100000000004e-02 , 2.1678500000000001e-01 , 9.7361699999999995e-01 -1.7006176844492531e+00 , -6.0483957545587206e+00 , 2.4967872000000000e+00 , -6.9231500000000001e-02 , 2.1526000000000001e-01 , 9.7409999999999997e-01 -1.6226685576483533e+00 , -6.6760148518372660e+00 , 2.6115615999999999e+00 , -6.2374699999999998e-02 , 2.1516199999999999e-01 , 9.7458400000000001e-01 -1.5395383004554006e+00 , -7.3331973811956743e+00 , 2.7471204000000000e+00 , -5.2488300000000002e-02 , 2.2409699999999999e-01 , 9.7315200000000002e-01 -1.4400166148948506e+00 , -8.1215290355325944e+00 , 2.9028104800000003e+00 , -5.2422299999999998e-02 , 2.2413500000000000e-01 , 9.7314699999999998e-01 -1.3293609244538205e+00 , -8.9898364660778238e+00 , 3.0862072000000000e+00 , -2.1823700000000001e-02 , 2.4869400000000000e-01 , 9.6833599999999997e-01 -1.2230837709039966e+00 , -9.7718017205839249e+00 , 3.2982632000000001e+00 , 2.1583500000000000e-01 , 5.2702599999999999e-01 , 8.2198499999999997e-01 -1.1700700878347745e+00 , -1.0001251635541404e+01 , 3.5182544000000000e+00 , 2.2873399999999999e-01 , 4.9896299999999999e-01 , 8.3589300000000000e-01 -1.1062385060898472e+00 , -1.0329459315408805e+01 , 3.7518072000000000e+00 , -2.6057700000000000e-01 , -5.1480700000000001e-01 , -8.1674599999999997e-01 -1.0246097939407588e+00 , -1.0798057196409820e+01 , 4.0072104000000000e+00 , 1.1267800000000000e-01 , 3.6665500000000001e-01 , 9.2350800000000000e-01 -7.1475431237347453e-01 , -1.3309052711211260e+01 , 4.4586432000000000e+00 , -3.6048299999999998e-02 , 2.1008099999999999e-01 , 9.7701899999999997e-01 --4.6114252813679935e-01 , -2.3392684641764721e+01 , 5.7969255999999998e+00 , 1.5902100000000000e-01 , 2.4360999999999999e-01 , 9.5674800000000004e-01 --6.2273525715189715e-01 , -2.4248577025303035e+01 , 6.3577767999999999e+00 , -2.5474400000000003e-01 , -2.7233800000000002e-01 , -9.2786700000000000e-01 --8.9601107759493681e-01 , -2.6011366986139496e+01 , 7.0785695999999998e+00 , -5.1067500000000002e-02 , -5.1808600000000005e-01 , -8.5380299999999998e-01 --1.2089501426218927e+00 , -2.8031461783157706e+01 , 7.9056296000000001e+00 , -2.7304600000000001e-01 , 9.4978499999999999e-01 , -1.5281900000000001e-01 --1.2774022765894681e+00 , -2.7975620005067778e+01 , 8.4420304000000002e+00 , -2.7346700000000002e-01 , 9.4957100000000005e-01 , -1.5339600000000000e-01 --1.3013195294387296e+00 , -2.7555582851787090e+01 , 8.9089799999999997e+00 , -2.8161199999999997e-01 , 9.5147199999999998e-01 , -1.2408200000000000e-01 --1.4239533611376269e+00 , -2.7926802103113701e+01 , 9.5331672000000012e+00 , -2.4799800000000000e-01 , 9.6476600000000001e-01 , -8.7879799999999994e-02 --1.4862971724576290e+00 , -2.7812101531471463e+01 , 1.0062922400000000e+01 , -2.7041900000000002e-01 , 9.5822700000000005e-01 , -9.3144000000000005e-02 --1.5492271325685127e+00 , -2.7707282380139830e+01 , 1.0595943200000001e+01 , -2.4902099999999999e-01 , 9.4653699999999996e-01 , -2.0507900000000001e-01 --1.6118417269742369e+00 , -2.7594334542784498e+01 , 1.1127726400000000e+01 , 2.4925200000000000e-01 , -9.4826200000000005e-01 , 1.9665299999999999e-01 --1.6793662432862431e+00 , -2.7510926995399206e+01 , 1.1669337600000000e+01 , 1.9882500000000000e-01 , -9.5898200000000000e-01 , 2.0204600000000000e-01 --1.7430149124977001e+00 , -2.7408163607932611e+01 , 1.2208036800000000e+01 , 2.4635199999999999e-01 , -9.3580900000000000e-01 , 2.5213700000000000e-01 --1.8063746783516552e+00 , -2.7294942363348511e+01 , 1.2745799999999999e+01 , 2.5811899999999999e-01 , -9.4140299999999999e-01 , 2.1710800000000000e-01 --3.8953692630455317e-01 , -1.7043407992923431e+01 , 9.7888511999999999e+00 , -1.4595800000000000e-01 , -6.4139699999999999e-01 , 7.5319800000000003e-01 --3.6965883214158080e-01 , -1.6550823939370446e+01 , 9.9931488000000002e+00 , 1.2424900000000000e-03 , -8.7347600000000003e-01 , 4.8686600000000002e-01 --2.0073683049720747e+00 , -2.7013095459321150e+01 , 1.4397320000000001e+01 , -8.2825700000000002e-02 , -9.9394499999999997e-01 , 7.2197600000000001e-02 --4.9779939893241520e-01 , -1.6698937959309561e+01 , 1.0817016000000001e+01 , 1.2428800000000000e-03 , -8.7347600000000003e-01 , 4.8686600000000002e-01 --2.1376238999235309e+00 , -2.6783761847502895e+01 , 1.5502528000000000e+01 , 1.1583100000000000e-01 , -9.6877599999999997e-01 , 2.1921700000000000e-01 --2.2034395798511985e+00 , -2.6667324407952304e+01 , 1.6060904000000001e+01 , 1.4469199999999999e-01 , -9.6605700000000005e-01 , 2.1400300000000000e-01 --2.2732380058640178e+00 , -2.6568354403662248e+01 , 1.6632384000000002e+01 , 1.5464700000000001e-01 , -9.6459700000000004e-01 , 2.1362999999999999e-01 --2.3401322052622007e+00 , -2.6448952133635601e+01 , 1.7200223999999999e+01 , -1.3702600000000001e-01 , 9.6675999999999995e-01 , -2.1586600000000000e-01 --2.4118953072256248e+00 , -2.6355261689911458e+01 , 1.7786992000000001e+01 , -1.3928199999999999e-01 , 9.6848999999999996e-01 , -2.0646300000000001e-01 --2.4799939293358193e+00 , -2.6231540613140957e+01 , 1.8365231999999999e+01 , -1.3866700000000001e-01 , 9.7001300000000001e-01 , -1.9961400000000001e-01 --2.5494833981402669e+00 , -2.6114150043626040e+01 , 1.8954080000000001e+01 , -5.0049500000000002e-01 , -8.6489400000000005e-01 , 3.8267599999999999e-02 --5.9323196502488384e-01 , -1.4639697779521207e+01 , 1.2964304000000000e+01 , -5.1091299999999995e-01 , 7.1378699999999995e-01 , -4.7903600000000002e-01 --6.7215898111796246e-01 , -1.4767330310103354e+01 , 1.3447176000000001e+01 , -9.0488500000000005e-01 , -2.7216600000000002e-01 , -3.2727499999999998e-01 --6.9002472861357633e-01 , -1.4552460597512251e+01 , 1.3729952000000001e+01 , -6.3358300000000001e-01 , 6.2539199999999995e-01 , -4.5547399999999999e-01 --2.8483198295630938e+00 , -2.5678638440840640e+01 , 2.1415656000000002e+01 , -3.5711799999999999e-01 , -8.7974799999999997e-01 , 3.1386199999999997e-01 --2.9176792520585346e+00 , -2.5525036212836817e+01 , 2.2026136000000001e+01 , 9.5056900000000000e-02 , -9.4681800000000005e-01 , 3.0741000000000002e-01 --2.9772292720052143e+00 , -2.5316175670077325e+01 , 2.2607496000000001e+01 , 9.7236000000000003e-02 , -8.8595100000000004e-01 , 4.5347199999999999e-01 -1.4052873841796982e+00 , -2.8327924495019836e+00 , 6.9101000000000008e+00 , 1.7798800000000001e-01 , -8.5665400000000003e-01 , 4.8421500000000001e-01 -1.4083424950680206e+00 , -2.7230654582270004e+00 , 6.9705447999999999e+00 , -1.7555100000000001e-01 , 8.9943600000000001e-01 , -4.0024599999999999e-01 --3.2380633670853465e+00 , -2.5046777375255903e+01 , 2.4679696000000003e+01 , 1.5182000000000001e-01 , -9.8789000000000005e-01 , 3.2009200000000002e-02 -1.1186560152326650e+00 , -3.9008897460747756e+00 , 8.2250447999999992e+00 , 8.4596099999999996e-01 , -3.1980199999999998e-01 , -4.2670599999999997e-01 -1.2291610269897122e+00 , -3.2684009226106969e+00 , 7.8779136000000003e+00 , 8.4511400000000003e-01 , 3.1517299999999998e-01 , -4.3179600000000001e-01 -1.2249365888916364e+00 , -3.1742735073964488e+00 , 7.9700055999999995e+00 , 8.4511400000000003e-01 , 3.1517299999999998e-01 , -4.3179600000000001e-01 -1.3348464029417069e+00 , -2.5771674306907775e+00 , 7.6052152000000008e+00 , 4.6515000000000001e-01 , 1.8857299999999999e-01 , -8.6491399999999996e-01 -1.3564243754381717e+00 , -2.3832927637530315e+00 , 7.5865264000000003e+00 , 5.6808000000000003e-01 , 1.5789100000000000e-02 , -8.2282200000000005e-01 -1.2464956437270942e+00 , -2.7585581547780960e+00 , 8.1142743999999993e+00 , -4.7844100000000001e-01 , 5.4176999999999997e-01 , -6.9107099999999999e-01 -1.2960958238005884e+00 , -2.4440590773159876e+00 , 7.9783048000000010e+00 , 6.9077999999999995e-01 , -3.9105800000000002e-01 , 6.0819100000000004e-01 -1.2926397435072552e+00 , -2.3567582910475577e+00 , 8.0630231999999999e+00 , 6.5327900000000005e-01 , -4.5147599999999999e-01 , 6.0777899999999996e-01 -1.3040787938749965e+00 , -2.2114385834872818e+00 , 8.0857783999999988e+00 , -5.8452000000000004e-01 , 5.0943000000000005e-01 , -6.3151900000000005e-01 -1.3032829454613528e+00 , -2.1149607609943244e+00 , 8.1586512000000013e+00 , 4.5350299999999999e-01 , -5.4847800000000002e-01 , 7.0250100000000004e-01 -1.3154288825379399e+00 , -1.9708772585225587e+00 , 8.1754367999999999e+00 , 4.6560800000000002e-01 , -2.3406199999999999e-01 , 8.5347799999999996e-01 -1.3418763378631251e+00 , -1.7750074037688917e+00 , 8.1255896000000014e+00 , -3.5452499999999998e-01 , -5.1842500000000000e-02 , 9.3360799999999999e-01 -1.3473910199696668e+00 , -1.6597201357829441e+00 , 8.1666799999999995e+00 , -3.8192300000000001e-01 , -4.9915700000000002e-01 , 7.7780300000000002e-01 -1.3359018111120382e+00 , -1.6064447280245249e+00 , 8.2863423999999988e+00 , 4.4498399999999999e-01 , 8.6211999999999997e-02 , -8.9137900000000003e-01 -1.3996907548782820e+00 , -1.2869259179249828e+00 , 8.0518016000000010e+00 , -6.7097200000000001e-01 , 6.6508599999999996e-01 , 3.2780700000000002e-01 -1.4458284916733422e+00 , -1.0377422820220010e+00 , 7.8912880000000003e+00 , 7.7622800000000003e-01 , -4.0561900000000001e-01 , -4.8264299999999999e-01 -1.4254344221827466e+00 , -1.0213112310850478e+00 , 8.0527896000000005e+00 , 7.7622800000000003e-01 , -4.0561900000000001e-01 , -4.8264299999999999e-01 -1.4315847029904702e+00 , -9.1591239950790859e-01 , 8.0871199999999988e+00 , -8.7018799999999996e-01 , 1.3863600000000001e-01 , 4.7281400000000001e-01 -1.4648498541767010e+00 , -7.2210927468006370e-01 , 7.9809880000000000e+00 , -6.8414900000000001e-01 , 4.2545699999999997e-01 , 5.9239100000000000e-01 -1.4537482715104022e+00 , -6.7278767031784392e-01 , 8.0969168000000007e+00 , -6.8414900000000001e-01 , 4.2545699999999997e-01 , 5.9239100000000000e-01 -1.3355339186120343e+00 , -9.4284275878303081e-01 , 8.7603848000000006e+00 , 1.1869300000000001e-01 , -9.9155499999999996e-01 , -5.2249100000000000e-02 -1.2242598110771050e+00 , -1.1703925574610015e+00 , 9.3991112000000001e+00 , 7.5428700000000004e-01 , -6.5324300000000002e-01 , 6.5767999999999993e-02 -1.2909121282001719e+00 , -8.7740575663440179e-01 , 9.1283784000000008e+00 , 8.9730299999999999e-02 , -9.3298300000000001e-01 , 3.4855599999999998e-01 -1.2795296855870639e+00 , -8.0717271400289192e-01 , 9.2584407999999989e+00 , 1.6023699999999999e-01 , -9.0710299999999999e-01 , 3.8921499999999998e-01 -1.2497502953527397e+00 , -7.8485530316041752e-01 , 9.4893520000000002e+00 , -8.7567699999999998e-02 , -4.4293700000000002e-04 , 9.9615799999999999e-01 -1.4372100828281813e+00 , -1.9978881533900061e-01 , 8.5543296000000009e+00 , 2.1906200000000001e-01 , -1.3173399999999999e-01 , -9.6677700000000000e-01 -1.4722686563297778e+00 , -2.1879000558604478e-02 , 8.4224056000000012e+00 , 5.9840700000000002e-01 , -3.7633899999999998e-01 , 7.0730300000000002e-01 -1.4796275943655721e+00 , 8.0316092672253259e-02 , 8.4463152000000008e+00 , 2.6715299999999997e-01 , -4.6509200000000001e-01 , 8.4399000000000002e-01 -1.4697669373533446e+00 , 1.4458620584040638e-01 , 8.5629407999999998e+00 , -9.6582999999999997e-01 , -3.3806900000000001e-02 , 2.5696300000000000e-01 -1.4552435932104906e+00 , 1.9989944492426637e-01 , 8.7079064000000006e+00 , -9.3844399999999994e-01 , 2.0704200000000000e-01 , 2.7650799999999998e-01 -1.3050603794878466e+00 , -2.9064590418319991e-02 , 9.6317176000000000e+00 , -8.0801100000000003e-01 , -2.0201200000000000e-01 , 5.5345200000000006e-01 -1.2499638883612203e+00 , -3.5967369448071107e-02 , 1.0023142399999999e+01 , -4.8300900000000002e-01 , 2.7615600000000001e-01 , -8.3092800000000000e-01 -1.2577097314150343e+00 , 9.0351866668149983e-02 , 1.0056224800000001e+01 , 2.9395600000000000e-01 , -2.2838899999999999e-02 , 9.5554600000000001e-01 -1.3599262251581492e+00 , 3.9061155214416132e-01 , 9.5287368000000008e+00 , -3.2549499999999998e-01 , -9.1335299999999997e-01 , -2.4462000000000000e-01 -1.3564956154709167e+00 , 4.8731931181288402e-01 , 9.6232728000000005e+00 , 1.9044499999999999e-02 , -8.0317899999999998e-01 , 5.9543299999999999e-01 -1.3185111767293649e+00 , 5.2948303610354563e-01 , 9.9245920000000005e+00 , -8.0866199999999999e-01 , 3.5310799999999998e-01 , 4.7051100000000001e-01 -1.3380748278108441e+00 , 6.6783312428523844e-01 , 9.8881607999999996e+00 , 9.5297599999999996e-02 , 6.1539500000000003e-01 , 7.8243700000000005e-01 -1.4306231510440901e+00 , 9.1366111076105194e-01 , 9.3888360000000013e+00 , 1.2795000000000001e-01 , 9.3932199999999993e-02 , -9.8732200000000003e-01 -1.3712157297744088e+00 , 9.3322823793962906e-01 , 9.8369304000000000e+00 , -9.1770700000000005e-01 , 3.7374600000000001e-02 , 3.9549699999999999e-01 -1.3869962772375106e+00 , 1.0614860457723905e+00 , 9.8128336000000012e+00 , 8.1220199999999998e-01 , 1.7883799999999998e-02 , -5.8310200000000001e-01 -1.3812198129843214e+00 , 1.1644947963970962e+00 , 9.9276079999999993e+00 , -8.4423199999999998e-01 , 3.5113499999999997e-01 , -4.0494000000000002e-01 -1.3221583629456526e+00 , 1.2137222900550291e+00 , 1.0385967200000001e+01 , -1.5026500000000001e-01 , -1.5981999999999999e-01 , 9.7564200000000001e-01 -1.4154322868551350e+00 , 1.4218396900922814e+00 , 9.8577511999999992e+00 , 2.2674900000000001e-02 , 1.4542200000000000e-01 , 9.8911000000000004e-01 -1.3833843381267332e+00 , 1.5056706637530144e+00 , 1.0151052000000000e+01 , -7.8822899999999996e-01 , 4.8757899999999998e-01 , -3.7544899999999998e-01 -1.4211777775590573e+00 , 1.6507096238954646e+00 , 9.9830503999999998e+00 , -4.0572100000000000e-01 , -7.3787599999999998e-01 , 5.3937800000000002e-01 -1.3614951962130335e+00 , 1.7287042655168892e+00 , 1.0468106400000000e+01 , 4.6269100000000002e-01 , -4.8468200000000000e-01 , 7.4229400000000001e-01 -1.5809140547272795e+00 , 1.9641819310171054e+00 , 9.0538208000000004e+00 , 3.4595500000000001e-01 , -9.3493000000000004e-01 , -7.8875799999999996e-02 -1.5805733672817173e+00 , 2.0653348180704976e+00 , 9.1236464000000002e+00 , -1.4083100000000001e-01 , 1.2685800000000000e-01 , -9.8187300000000000e-01 -1.6096419092291403e+00 , 2.1764787650621558e+00 , 8.9963607999999997e+00 , -5.6892500000000001e-01 , 5.7590799999999998e-01 , -5.8707299999999996e-01 -1.6047360506352750e+00 , 2.2779619077434003e+00 , 9.1037408000000006e+00 , -8.2421100000000003e-01 , -2.2201000000000001e-01 , -5.2094799999999997e-01 -1.5156166866391143e+00 , 2.3809549062561524e+00 , 9.8172744000000005e+00 , -7.7618100000000001e-01 , -3.8491500000000001e-01 , 4.9938199999999999e-01 -1.5613502077481682e+00 , 2.4960532175179311e+00 , 9.5708672000000004e+00 , 6.3031000000000004e-01 , -2.5877699999999998e-01 , -7.3194599999999999e-01 -1.5449269104057179e+00 , 2.6166210209500247e+00 , 9.7757888000000008e+00 , -2.3909600000000000e-01 , 1.1955900000000000e-02 , 9.7092199999999995e-01 -1.5850848923764576e+00 , 2.7225752915598198e+00 , 9.5565984000000004e+00 , 3.2601400000000003e-01 , 2.3166900000000001e-02 , 9.4508099999999995e-01 -1.5618555452891252e+00 , 2.8539730599063433e+00 , 9.8190944000000009e+00 , -2.8186200000000000e-01 , -2.9307299999999997e-01 , 9.1359900000000005e-01 -1.5768578357527514e+00 , 2.9708524817708417e+00 , 9.7910560000000011e+00 , -8.1169599999999997e-01 , -1.8928199999999999e-02 , 5.8377400000000002e-01 -1.5760080729880692e+00 , 3.0990732996636465e+00 , 9.8950040000000001e+00 , -9.3900899999999998e-01 , 2.4092100000000000e-01 , -2.4539700000000000e-01 -1.6170523762420257e+00 , 3.1918292882013342e+00 , 9.6579048000000007e+00 , 9.6958999999999995e-01 , 1.7223400000000000e-01 , 1.7386799999999999e-01 -1.6761461687956605e+00 , 3.2558364950983889e+00 , 9.2767447999999995e+00 , 2.1138599999999999e-01 , 9.7431199999999996e-01 , -7.7673000000000006e-02 -2.4617893837751823e+00 , 5.0884190401006135e-01 , 1.3015432800000000e+00 , -5.5026899999999997e-02 , 2.2821800000000000e-01 , 9.7205399999999997e-01 -2.4170069713665194e+00 , 2.0801081909128039e-01 , 1.3483484799999998e+00 , 1.0874100000000000e-01 , -2.1784999999999999e-01 , -9.6990600000000005e-01 -2.4069893915525156e+00 , 1.4622666355848857e-01 , 1.3610000799999999e+00 , 9.3574900000000003e-02 , -1.7519999999999999e-01 , -9.8007599999999995e-01 -2.3962826462020406e+00 , 7.5092004434274440e-02 , 1.3692982400000000e+00 , -1.1102400000000000e-01 , 1.9022500000000001e-01 , 9.7544200000000003e-01 -2.3859140880445788e+00 , -4.3041470821356675e-03 , 1.3735705600000001e+00 , -7.3669600000000002e-02 , 1.9061800000000001e-01 , 9.7889599999999999e-01 -2.3751579614983007e+00 , -6.8084418623056919e-02 , 1.3919972800000000e+00 , -7.4189000000000005e-02 , 1.8017900000000001e-01 , 9.8083200000000004e-01 -2.3632483852562807e+00 , -1.4766561168225856e-01 , 1.4002943999999999e+00 , -5.4416199999999998e-02 , 1.6789699999999999e-01 , 9.8430200000000001e-01 -2.3520313734740346e+00 , -2.2885731643314644e-01 , 1.4112528799999999e+00 , 9.2022300000000001e-02 , -1.9062399999999999e-01 , -9.7733999999999999e-01 -2.3394887600601679e+00 , -3.1061485660949728e-01 , 1.4244151199999999e+00 , -9.8581000000000002e-02 , 1.9328799999999999e-01 , 9.7617699999999996e-01 -2.3266713698854007e+00 , -3.9188690906945078e-01 , 1.4399048800000001e+00 , -8.4649900000000000e-02 , 1.8447900000000000e-01 , 9.7918400000000005e-01 -2.3129862032302686e+00 , -4.8219549106002146e-01 , 1.4525606400000002e+00 , -1.0203300000000000e-01 , 2.0436499999999999e-01 , 9.7356299999999996e-01 -2.2989688956807957e+00 , -5.7301708535054852e-01 , 1.4678486399999999e+00 , 9.1904100000000002e-02 , -2.1680300000000000e-01 , -9.7187999999999997e-01 -2.2849865886465563e+00 , -6.7375335961359761e-01 , 1.4813426399999998e+00 , -6.9532700000000003e-02 , 2.0551300000000000e-01 , 9.7618099999999997e-01 -2.2695949637227768e+00 , -7.7490265504392708e-01 , 1.4977475999999998e+00 , -7.5950000000000004e-02 , 2.0236899999999999e-01 , 9.7636000000000001e-01 -2.2538271759693869e+00 , -8.7649960579436303e-01 , 1.5171924800000001e+00 , -6.9659700000000005e-02 , 2.0874899999999999e-01 , 9.7548500000000005e-01 -2.2370081957519581e+00 , -9.8679886299642083e-01 , 1.5353196800000000e+00 , -5.5874300000000002e-02 , 2.1592800000000001e-01 , 9.7480900000000004e-01 -2.2197328950589785e+00 , -1.0984852268647423e+00 , 1.5569932799999999e+00 , 7.8129400000000002e-02 , -1.7258999999999999e-01 , -9.8189000000000004e-01 -2.1991153390035301e+00 , -1.2476286415765578e+00 , 1.5660173600000000e+00 , -1.2180600000000000e-01 , 1.5465300000000001e-01 , 9.8043100000000005e-01 -2.1794156029865634e+00 , -1.3783660182694355e+00 , 1.5874912800000001e+00 , -1.3539899999999999e-01 , 1.3877000000000000e-01 , 9.8102500000000004e-01 -2.1560266927073148e+00 , -1.5492305931252166e+00 , 1.5987524000000000e+00 , -1.1492400000000000e-01 , 1.7183300000000001e-01 , 9.7840000000000005e-01 -2.1309992007653125e+00 , -1.7190159922377157e+00 , 1.6150481600000000e+00 , -4.7419299999999998e-02 , 2.3712200000000000e-01 , 9.7032200000000002e-01 -2.1112169977110526e+00 , -1.8317941641920150e+00 , 1.6571743999999999e+00 , 4.5682200000000001e-04 , 2.7963800000000000e-01 , 9.6010499999999999e-01 -2.0866102538886468e+00 , -1.9834016250397539e+00 , 1.6899708000000000e+00 , -3.2934100000000001e-02 , 2.6566400000000001e-01 , 9.6350300000000000e-01 -2.0615990066498786e+00 , -2.1441533242746154e+00 , 1.7247151199999999e+00 , -4.9095300000000001e-02 , 2.3852300000000001e-01 , 9.6989499999999995e-01 -2.0330806253772953e+00 , -2.3260431384497284e+00 , 1.7592420799999999e+00 , -5.2486999999999999e-02 , 2.4013399999999999e-01 , 9.6931999999999996e-01 -2.0047960737698101e+00 , -2.4966903951984332e+00 , 1.8021639199999999e+00 , -6.6357399999999997e-02 , 2.3293400000000000e-01 , 9.7022600000000003e-01 -1.9720535758201736e+00 , -2.7083104369848279e+00 , 1.8410505600000000e+00 , -9.5283099999999996e-02 , 2.1279999999999999e-01 , 9.7243900000000005e-01 -1.9346606995606397e+00 , -2.9594566583416961e+00 , 1.8777199200000001e+00 , -8.0750699999999995e-02 , 2.3363000000000000e-01 , 9.6896599999999999e-01 -1.9001062972284257e+00 , -3.1711893147541241e+00 , 1.9314882320000000e+00 , -8.2094399999999998e-02 , 2.3601100000000000e-01 , 9.6827600000000003e-01 -1.8566884516663975e+00 , -3.4528977216773669e+00 , 1.9785696559999999e+00 , -8.3199200000000001e-02 , 2.2630000000000000e-01 , 9.7049799999999997e-01 -1.8131343831193401e+00 , -3.7347716921785805e+00 , 2.0353943200000000e+00 , -8.9714900000000000e-02 , 2.2378400000000001e-01 , 9.7050099999999995e-01 -1.7631813702163752e+00 , -4.0571099279548477e+00 , 2.0955476080000000e+00 , -8.7543899999999994e-02 , 2.1990699999999999e-01 , 9.7158500000000003e-01 -1.7066244542069768e+00 , -4.4195295152422700e+00 , 2.1608505600000001e+00 , -8.4748000000000004e-02 , 2.2491300000000000e-01 , 9.7068600000000005e-01 -1.6473970529444013e+00 , -4.8020686984469210e+00 , 2.2364076000000002e+00 , -8.5955500000000004e-02 , 2.2498000000000001e-01 , 9.7056500000000001e-01 -1.5788663425984879e+00 , -5.2454513830401348e+00 , 2.3189451200000000e+00 , 8.0270400000000006e-02 , -2.2087100000000001e-01 , -9.7199400000000002e-01 -1.5006881084830994e+00 , -5.7490788187819524e+00 , 2.4113959199999999e+00 , 7.9065499999999997e-02 , -2.1669800000000000e-01 , -9.7303200000000001e-01 -1.4122628491132421e+00 , -6.3239705657747347e+00 , 2.5168269599999999e+00 , -7.7243099999999995e-02 , 2.1873799999999999e-01 , 9.7272099999999995e-01 -1.3133568782776979e+00 , -6.9587135486522769e+00 , 2.6391548800000000e+00 , 6.0821199999999999e-02 , -2.2698699999999999e-01 , -9.7199700000000000e-01 -1.2011356663860289e+00 , -7.6738744662007434e+00 , 2.7811221600000002e+00 , -5.9923400000000002e-02 , 2.2463700000000000e-01 , 9.7259799999999996e-01 -1.0677582877863414e+00 , -8.5310721439341108e+00 , 2.9461888800000002e+00 , -6.1325499999999998e-02 , 2.2983000000000001e-01 , 9.7129699999999997e-01 -9.2110194185911776e-01 , -9.4559890206006756e+00 , 3.1413063999999999e+00 , -6.0686400000000001e-02 , -4.5792300000000002e-01 , -8.8691799999999998e-01 -8.5048164012711447e-01 , -9.7697616713965036e+00 , 3.3553696000000000e+00 , 1.8890199999999999e-01 , 5.8614200000000005e-01 , 7.8787900000000000e-01 -7.9256206760238035e-01 , -9.9754812084891000e+00 , 3.5761928000000003e+00 , -2.2432099999999999e-01 , -5.4269900000000004e-01 , -8.0941799999999997e-01 -6.9897613939200709e-01 , -1.0434299684596985e+01 , 3.8191991999999999e+00 , 1.7261499999999999e-01 , 4.9102499999999999e-01 , 8.5387299999999999e-01 -4.3888933044422762e-01 , -1.2068987886913991e+01 , 4.1670064000000000e+00 , -5.4455600000000000e-02 , 2.1377800000000000e-01 , 9.7536299999999998e-01 --9.2013680334918302e-01 , -2.1415525172891691e+01 , 5.2879600000000000e+00 , 1.7974599999999999e-01 , 2.1184800000000001e-01 , 9.6063100000000001e-01 --1.0805813503195836e+00 , -2.2113179216234748e+01 , 5.7857976000000004e+00 , 1.6416200000000000e-01 , 2.1764600000000001e-01 , 9.6212299999999995e-01 --1.5634392482406860e+00 , -2.4983532230052944e+01 , 6.5885319999999998e+00 , -3.2389200000000001e-01 , -2.0896500000000001e-01 , -9.2272799999999999e-01 --2.1414114251499301e+00 , -2.8391538809526132e+01 , 7.5744000000000007e+00 , 1.9273399999999999e-01 , 9.4569300000000001e-01 , -2.6176100000000002e-01 --2.2129235489908572e+00 , -2.8339394664048427e+01 , 8.1183511999999993e+00 , -1.9273399999999999e-01 , -9.4569300000000001e-01 , 2.6176100000000002e-01 --2.2650698344279716e+00 , -2.8165749182999967e+01 , 8.6418560000000006e+00 , 1.9390499999999999e-01 , 9.7383200000000003e-01 , -1.1853800000000000e-01 --2.3511497181573473e+00 , -2.8205694870140594e+01 , 9.2055568000000001e+00 , 2.3469899999999999e-01 , 9.7179599999999999e-01 , -2.3015500000000001e-02 --2.4233629279698645e+00 , -2.8154541763744078e+01 , 9.7550720000000002e+00 , -3.0993500000000002e-01 , -9.4000099999999998e-01 , 1.4261099999999999e-01 --2.4857791653848835e+00 , -2.8043357676513974e+01 , 1.0293365600000000e+01 , -3.2845800000000003e-01 , -9.2352400000000001e-01 , 1.9803699999999999e-01 --2.5493149416114536e+00 , -2.7933037222475352e+01 , 1.0832553599999999e+01 , 3.5116700000000001e-01 , 9.1342400000000001e-01 , -2.0576500000000000e-01 --2.6136206113178595e+00 , -2.7832529320399885e+01 , 1.1375912000000000e+01 , 3.7050400000000000e-01 , 9.0861400000000003e-01 , -1.9273499999999999e-01 --2.6791893462062992e+00 , -2.7732595800031948e+01 , 1.1921267200000001e+01 , 3.6984000000000000e-01 , 8.9422699999999999e-01 , -2.5214300000000001e-01 --2.7440253121435862e+00 , -2.7632089279084404e+01 , 1.2469160000000000e+01 , -4.6829999999999999e-01 , -8.1257900000000005e-01 , 3.4700199999999998e-01 --1.0342818976905837e+00 , -1.7426234078907481e+01 , 9.6645816000000000e+00 , -3.1763000000000002e-01 , -5.8370500000000003e-01 , 7.4726199999999998e-01 --9.7181934366504485e-01 , -1.6760326875699370e+01 , 9.8205920000000013e+00 , -1.4595800000000000e-01 , -6.4139699999999999e-01 , 7.5319800000000003e-01 --2.9404617006708529e+00 , -2.7310586514607390e+01 , 1.4123592000000000e+01 , 7.4521999999999999e-01 , 6.3985000000000003e-01 , -1.8772100000000000e-01 --3.0050415511325346e+00 , -2.7198779861056060e+01 , 1.4680512000000000e+01 , 6.1200500000000002e-01 , 7.6615999999999995e-01 , -1.9608300000000001e-01 --3.0644399232338264e+00 , -2.7048145844447205e+01 , 1.5225368000000000e+01 , -5.5420599999999998e-01 , -8.2640199999999997e-01 , 9.9575600000000000e-02 --3.1395262017946486e+00 , -2.6982400658616712e+01 , 1.5809640000000000e+01 , 5.5079599999999995e-01 , 8.2395900000000000e-01 , -1.3309599999999999e-01 --3.2090645622111431e+00 , -2.6885394125977992e+01 , 1.6387256000000001e+01 , 5.6906299999999999e-01 , 8.1471899999999997e-01 , -1.1135700000000000e-01 --3.2768179585989614e+00 , -2.6768925020040349e+01 , 1.6961335999999999e+01 , 5.8664700000000003e-01 , 8.0157800000000001e-01 , -1.1540200000000000e-01 --3.3475477867792209e+00 , -2.6668658206958497e+01 , 1.7549351999999999e+01 , -3.7257699999999999e-01 , -9.1792399999999996e-01 , 1.3639000000000001e-01 --3.4171868036086224e+00 , -2.6556497599082853e+01 , 1.8138615999999999e+01 , 4.0577000000000002e-01 , 9.0611900000000001e-01 , -1.1957800000000000e-01 --3.4921107727755283e+00 , -2.6459097170026933e+01 , 1.8743064000000000e+01 , -6.5745299999999995e-01 , -7.5296900000000000e-01 , -2.8170799999999999e-02 --3.5620294395635090e+00 , -2.6341369142291008e+01 , 1.9344287999999999e+01 , 7.9425500000000004e-01 , 5.9699100000000005e-01 , 1.1296100000000001e-01 --3.6023063216532334e+00 , -2.6069389437222540e+01 , 1.9863039999999998e+01 , -8.9845699999999995e-01 , -4.1023799999999999e-01 , -1.5645800000000001e-01 --3.7097867437130914e+00 , -2.6111338692970818e+01 , 2.0575752000000001e+01 , 7.5073299999999998e-01 , 6.0919500000000004e-01 , -2.5550299999999998e-01 --3.7818363186283870e+00 , -2.5982051599591298e+01 , 2.1196424000000004e+01 , 4.3181900000000001e-01 , 9.0057799999999999e-01 , 4.9916099999999998e-02 --3.8536145856609760e+00 , -2.5847297632147669e+01 , 2.1823855999999999e+01 , 1.9741200000000000e-01 , 9.7126100000000004e-01 , 1.3296900000000000e-01 --3.9119128103661840e+00 , -2.5641366795126544e+01 , 2.2411975999999999e+01 , -4.1633800000000004e-03 , -9.9880300000000000e-01 , 4.8736700000000001e-02 -1.1972185744205275e+00 , -3.0303121849678911e+00 , 6.9710544000000008e+00 , 4.0155600000000000e-02 , -8.6521999999999999e-01 , 4.9978200000000000e-01 -1.2095942641801229e+00 , -2.8867339085689370e+00 , 7.0117080000000005e+00 , -1.7798800000000001e-01 , 8.5665400000000003e-01 , -4.8421500000000001e-01 -1.2059355400268295e+00 , -2.8148184639303198e+00 , 7.1043928000000003e+00 , -1.7555100000000001e-01 , 8.9943600000000001e-01 , -4.0024599999999999e-01 -1.1807286692605157e+00 , -2.8299772628144781e+00 , 7.2661856000000009e+00 , -1.0901600000000000e-01 , 9.0455200000000002e-01 , -4.1219099999999997e-01 -1.1772408508373777e+00 , -2.7539841832300365e+00 , 7.3580383999999999e+00 , 3.9008999999999999e-01 , -8.7665000000000004e-01 , 2.8162900000000002e-01 -1.2029052753749943e+00 , -2.5605333112844377e+00 , 7.3486888000000006e+00 , -3.9300299999999999e-01 , -4.6161200000000002e-01 , 7.9527499999999995e-01 -1.1969805417623274e+00 , -2.4995826182513055e+00 , 7.4496831999999999e+00 , -4.4796399999999997e-01 , -2.0872199999999999e-01 , 8.6934699999999998e-01 -1.1922528223903208e+00 , -2.4275761354757979e+00 , 7.5425447999999999e+00 , 4.6515000000000001e-01 , 1.8857299999999999e-01 , -8.6491399999999996e-01 -1.0539443097167560e+00 , -2.8644852897490711e+00 , 8.1219080000000012e+00 , -2.7761100000000000e-01 , -4.3910500000000002e-01 , 8.5446999999999995e-01 -1.0578805166894087e+00 , -2.7516190762630641e+00 , 8.1928048000000011e+00 , -2.5729900000000000e-01 , -3.7977899999999998e-01 , 8.8857500000000000e-01 -1.0765813326784270e+00 , -2.5885704811871655e+00 , 8.2102976000000005e+00 , -1.8230500000000000e-02 , -2.9629200000000000e-01 , 9.5492299999999997e-01 -1.0770169935183720e+00 , -2.4895827648003701e+00 , 8.2906063999999997e+00 , 4.6575000000000000e-01 , -3.8194000000000000e-01 , 7.9824700000000004e-01 -1.1080657174212345e+00 , -2.2866255028172526e+00 , 8.2557663999999988e+00 , 5.1003100000000001e-01 , -5.3401699999999996e-01 , 6.7430900000000005e-01 -1.1091654612243664e+00 , -2.1935835733941831e+00 , 8.3383424000000019e+00 , 4.5865099999999998e-01 , -1.7224300000000001e-01 , 8.7176299999999995e-01 -1.1253213857911049e+00 , -2.0471909813336771e+00 , 8.3569376000000002e+00 , 3.7775700000000001e-01 , -3.4757600000000000e-01 , 8.5819000000000001e-01 -1.2101931648525079e+00 , -1.6757315031914808e+00 , 8.0948056000000008e+00 , 3.2866400000000001e-01 , -2.0424900000000001e-01 , -9.2209700000000006e-01 -1.2597899644814570e+00 , -1.4288497418270460e+00 , 7.9657416000000003e+00 , 1.1346100000000001e-01 , -4.4557200000000002e-01 , -8.8802700000000001e-01 -1.2907275578388280e+00 , -1.2490056833173080e+00 , 7.9110791999999996e+00 , -1.8347400000000000e-01 , 4.6878700000000001e-01 , 8.6404700000000001e-01 -1.2678589236749107e+00 , -1.2409924483677437e+00 , 8.0830015999999993e+00 , -2.1828900000000001e-01 , 9.7396199999999999e-01 , -6.1217800000000003e-02 -1.2384430785448630e+00 , -1.2454909450683136e+00 , 8.2810072000000012e+00 , 1.3443200000000000e-01 , -8.6612400000000000e-01 , 4.8141200000000001e-01 -1.1089677619253364e+00 , -1.5420760762004608e+00 , 8.9210543999999992e+00 , -2.0321000000000000e-01 , 9.4441500000000000e-01 , 2.5842900000000002e-01 -1.1835544297867555e+00 , -1.2319562432604019e+00 , 8.6737944000000002e+00 , 6.6413699999999998e-01 , -4.2700199999999999e-01 , -6.1367000000000005e-01 -1.1969731994958608e+00 , -1.1051449624676666e+00 , 8.6947296000000005e+00 , 3.6634200000000000e-01 , -9.2684599999999995e-01 , 8.2153799999999999e-02 -1.1795346957044701e+00 , -1.0629336422808060e+00 , 8.8530695999999995e+00 , -2.5743500000000002e-01 , -9.5217499999999999e-01 , 1.6459299999999999e-01 -1.1631701149456042e+00 , -1.0164404134307188e+00 , 9.0118255999999999e+00 , 2.2575100000000001e-01 , -8.4545899999999996e-01 , 4.8397899999999999e-01 -1.1513002794023344e+00 , -9.5563369982230473e-01 , 9.1529847999999987e+00 , 9.9241400000000002e-01 , 3.3995100000000000e-02 , -1.1814600000000000e-01 -1.1316436026388126e+00 , -9.1064612226522357e-01 , 9.3299407999999993e+00 , 9.8384299999999994e-02 , -9.1904500000000000e-01 , 3.8167600000000002e-01 -1.1177503491198539e+00 , -8.4587762790370569e-01 , 9.4797736000000015e+00 , 4.3341200000000002e-01 , 1.9349000000000000e-01 , -8.8017900000000004e-01 -1.1528746585581342e+00 , -6.6501509564474404e-01 , 9.3994128000000003e+00 , 4.3341200000000002e-01 , 1.9349000000000000e-01 , -8.8017900000000004e-01 -1.1667363877524246e+00 , -5.3677697049662676e-01 , 9.4169991999999993e+00 , 1.1465899999999999e-02 , -2.4160300000000001e-01 , 9.7030799999999995e-01 -1.1901590003815392e+00 , -3.8707555419114659e-01 , 9.3849879999999999e+00 , 1.6120000000000001e-01 , -3.8092599999999999e-01 , 9.1044499999999995e-01 -1.1862165546286656e+00 , -2.9863181077576684e-01 , 9.4911200000000004e+00 , 2.6241900000000001e-01 , 7.5230799999999998e-01 , -6.0429200000000005e-01 -1.1556277319401935e+00 , -2.6546371811590497e-01 , 9.7388271999999994e+00 , -5.1975000000000005e-01 , 8.5103700000000004e-01 , -7.4815099999999995e-02 -1.1087532078057285e+00 , -2.5759458980029937e-01 , 1.0073540800000000e+01 , 3.1375399999999998e-01 , -7.1832499999999999e-01 , 6.2094099999999997e-01 -1.1342225848450576e+00 , -1.0202395047902968e-01 , 1.0034260000000000e+01 , -3.6882599999999999e-01 , 1.5013799999999999e-01 , -9.1729300000000003e-01 -1.1259555316110710e+00 , -1.2557385605964644e-02 , 1.0176116000000000e+01 , 2.4271200000000001e-01 , -2.0039999999999999e-02 , 9.6989099999999995e-01 -1.1661727676193503e+00 , 1.6595245782686807e-01 , 1.0053552000000000e+01 , -1.9056999999999999e-01 , -1.2169099999999999e-01 , -9.7410200000000002e-01 -1.2493099282416675e+00 , 4.1012526146654249e-01 , 9.6915800000000001e+00 , 7.8150600000000003e-01 , 6.0788200000000003e-01 , 1.4046000000000000e-01 -1.2147575623606941e+00 , 4.5682607305207457e-01 , 9.9739712000000011e+00 , 6.3972600000000002e-01 , -7.1250199999999997e-01 , -2.8825400000000001e-01 -1.2265934760108050e+00 , 5.8133213805124417e-01 , 9.9989312000000012e+00 , 7.7353200000000000e-01 , 5.4682399999999998e-01 , 3.2036199999999998e-01 -1.2813908833966154e+00 , 7.6376317722459097e-01 , 9.7829855999999999e+00 , 3.2778499999999999e-01 , -3.3585500000000001e-01 , -8.8303900000000002e-01 -1.3726933377072612e+00 , 9.8855276038036921e-01 , 9.3423896000000006e+00 , 3.6522700000000002e-01 , -3.7871300000000002e-01 , -8.5040300000000002e-01 -1.2896505534099443e+00 , 9.8333452878331640e-01 , 9.9206608000000003e+00 , 9.9916400000000005e-01 , 2.6125900000000001e-02 , -3.1447799999999998e-02 -1.3168532855047150e+00 , 1.1209368015575962e+00 , 9.8557856000000008e+00 , -7.3045499999999997e-01 , 1.5196699999999999e-01 , -6.6583899999999996e-01 -1.2951273062352566e+00 , 1.2055941872021756e+00 , 1.0081611200000001e+01 , -4.8670200000000002e-01 , 2.3422699999999999e-01 , -8.4158100000000002e-01 -1.3542117126730773e+00 , 1.3721535038630770e+00 , 9.8194271999999998e+00 , 2.3357800000000001e-01 , 2.5991399999999998e-01 , 9.3695600000000001e-01 -1.3075395099507963e+00 , 1.4411881452314850e+00 , 1.0204809600000001e+01 , 8.1446300000000005e-01 , -5.5257500000000004e-01 , -1.7695100000000000e-01 -1.3564334355378627e+00 , 1.5928502943517293e+00 , 9.9982760000000006e+00 , -5.2869299999999997e-01 , -7.2041699999999997e-01 , -4.4886799999999999e-01 -1.3922974099750653e+00 , 1.7280177970461730e+00 , 9.8704600000000013e+00 , 5.4439599999999999e-01 , 5.0827299999999997e-01 , 6.6730199999999995e-01 -1.3810749326862841e+00 , 1.8331946495965645e+00 , 1.0047530400000001e+01 , -7.2486700000000004e-01 , -5.7402500000000001e-01 , 3.8087199999999999e-01 -1.5622071512419891e+00 , 2.0269206075453545e+00 , 8.9501431999999994e+00 , -5.8465800000000001e-01 , 8.1127600000000000e-01 , 2.3152899999999998e-03 -1.5529222363481066e+00 , 2.1236280091795487e+00 , 9.1013903999999997e+00 , 9.0181999999999998e-02 , 5.3892300000000004e-01 , 8.3751399999999998e-01 -1.5851433990749824e+00 , 2.2324270634961012e+00 , 8.9736784000000007e+00 , -5.6892500000000001e-01 , 5.7590699999999995e-01 , -5.8707299999999996e-01 -1.4995814516345214e+00 , 2.3280891616435486e+00 , 9.6568648000000010e+00 , 4.8955700000000002e-01 , -5.3628500000000001e-01 , -6.8755599999999994e-01 -1.5286066378749528e+00 , 2.4424884247768235e+00 , 9.5562655999999997e+00 , 3.8837500000000003e-01 , -6.6917300000000002e-01 , -6.3353899999999996e-01 -1.4640618623101775e+00 , 2.5690203721322575e+00 , 1.0123086400000000e+01 , -7.6904099999999997e-01 , -6.3894099999999998e-01 , 1.8162000000000001e-02 -1.5536812782835792e+00 , 2.7901877033100302e+00 , 9.6957608000000004e+00 , -6.4526200000000000e-01 , -7.8287899999999994e-02 , 7.5993999999999995e-01 -1.5568962972206195e+00 , 2.9126788160313146e+00 , 9.7826528000000010e+00 , -8.5940700000000003e-01 , -2.2549500000000000e-02 , 5.1079399999999997e-01 -1.5701173022438384e+00 , 3.0314722642038330e+00 , 9.7953824000000012e+00 , -9.0622999999999998e-01 , 3.2171499999999997e-01 , -2.7431100000000003e-01 -1.6077751842085541e+00 , 3.1307470159491682e+00 , 9.6215360000000008e+00 , -8.5908700000000005e-01 , -2.8854299999999999e-01 , -4.2274499999999998e-01 -1.6420217018719556e+00 , 3.2265394191071683e+00 , 9.4665968000000014e+00 , -9.6179499999999996e-01 , -3.7072899999999998e-03 , -2.7374500000000002e-01 -1.6835989010046253e+00 , 3.3072956821177417e+00 , 9.2491431999999989e+00 , 1.4946799999999999e-01 , 9.8742799999999997e-01 , -5.1421300000000003e-02 -2.3556392999076574e+00 , 1.7709631296872685e-01 , 1.3399099200000000e+00 , -1.2884799999999999e-01 , 2.2171099999999999e-01 , 9.6656200000000003e-01 -2.3444406831610074e+00 , 1.1448911557807495e-01 , 1.3535515999999999e+00 , 1.1872099999999999e-01 , -2.2493800000000000e-01 , -9.6711300000000000e-01 -2.3320182861817020e+00 , 5.2238702520287728e-02 , 1.3686856800000000e+00 , -9.8684999999999995e-02 , 1.8086500000000000e-01 , 9.7854399999999997e-01 -2.3189353417544996e+00 , -1.8305872080419228e-02 , 1.3793644000000000e+00 , -7.7957200000000004e-02 , 2.2343499999999999e-01 , 9.7159600000000002e-01 -2.3055834768158237e+00 , -8.9477981862875478e-02 , 1.3921699200000002e+00 , -6.3768699999999998e-02 , 1.8331600000000001e-01 , 9.8098399999999997e-01 -2.2908989815782035e+00 , -1.7942672701455553e-01 , 1.3958671200000001e+00 , -7.6318300000000006e-02 , 1.3259399999999999e-01 , 9.8822800000000000e-01 -2.2764982961173015e+00 , -2.5931127395621267e-01 , 1.4073560000000001e+00 , 1.1892800000000001e-01 , -1.9928499999999999e-01 , -9.7269799999999995e-01 -2.2617488935248744e+00 , -3.4078395729017963e-01 , 1.4214812800000001e+00 , 1.0316900000000000e-01 , -1.8874099999999999e-01 , -9.7659300000000004e-01 -2.2455765746376888e+00 , -4.3976758346831524e-01 , 1.4274061599999999e+00 , -9.0358999999999995e-02 , 1.8477900000000000e-01 , 9.7861699999999996e-01 -2.2296149405719889e+00 , -5.3076047025225126e-01 , 1.4414316000000000e+00 , 8.3270800000000006e-02 , -2.2996200000000000e-01 , -9.6963100000000002e-01 -2.2129099470219864e+00 , -6.1277813283449278e-01 , 1.4629242400000000e+00 , -6.4083000000000001e-02 , 2.1912499999999999e-01 , 9.7358999999999996e-01 -2.1946755083475571e+00 , -7.1212671376798609e-01 , 1.4771264799999999e+00 , 7.8765100000000005e-02 , -1.8196300000000001e-01 , -9.8014599999999996e-01 -2.1770527251470488e+00 , -8.1295364612073717e-01 , 1.4946972800000000e+00 , 8.3015199999999997e-02 , -2.2055800000000000e-01 , -9.7183500000000000e-01 -2.1580093568502337e+00 , -9.1417466056867758e-01 , 1.5152820000000000e+00 , -5.2886099999999998e-02 , 2.1509800000000001e-01 , 9.7515900000000000e-01 -2.1368507397777758e+00 , -1.0251201521839910e+00 , 1.5345282400000000e+00 , 7.3051500000000005e-02 , -1.9126299999999999e-01 , -9.7881700000000005e-01 -2.1148903032369786e+00 , -1.1539812602831039e+00 , 1.5490414399999999e+00 , -9.5075400000000004e-02 , 1.5444700000000000e-01 , 9.8341599999999996e-01 -2.0905867822557305e+00 , -1.2943639315832112e+00 , 1.5638396000000001e+00 , -1.2196400000000000e-01 , 1.3564799999999999e-01 , 9.8322100000000001e-01 -2.0623994645028381e+00 , -1.4635801453634749e+00 , 1.5717352800000000e+00 , -1.2435800000000000e-01 , 1.6220799999999999e-01 , 9.7888900000000001e-01 -2.0343349175174290e+00 , -1.6235500579320621e+00 , 1.5886394400000001e+00 , 6.4413100000000001e-02 , -2.3252000000000000e-01 , -9.7045599999999999e-01 -2.0099296655772880e+00 , -1.7448419964171729e+00 , 1.6243915200000001e+00 , 1.6046000000000001e-02 , 2.5232500000000002e-01 , 9.6750999999999998e-01 -1.9825229256086072e+00 , -1.8958179423725716e+00 , 1.6544808000000000e+00 , -4.0599499999999997e-02 , 2.7408800000000000e-01 , 9.6084700000000001e-01 -1.9543679148710731e+00 , -2.0367160611982520e+00 , 1.6922369600000000e+00 , -3.8617600000000002e-02 , 2.3483999999999999e-01 , 9.7126699999999999e-01 -1.9220000518978337e+00 , -2.2069707208803511e+00 , 1.7257228800000000e+00 , 5.0688700000000003e-02 , -2.2227200000000000e-01 , -9.7366600000000003e-01 -1.8871409293224755e+00 , -2.3972449764976638e+00 , 1.7594167999999999e+00 , -6.5472400000000000e-02 , 2.1833200000000000e-01 , 9.7367599999999999e-01 -1.8485963806983918e+00 , -2.6083326968203302e+00 , 1.7944107199999999e+00 , -8.4968900000000000e-02 , 2.2068299999999999e-01 , 9.7163800000000000e-01 -1.8083151106066226e+00 , -2.8280388451995542e+00 , 1.8337559999999999e+00 , -8.3471400000000001e-02 , 2.3265200000000000e-01 , 9.6897100000000003e-01 -1.7660227201084711e+00 , -3.0492881009344197e+00 , 1.8807754400000001e+00 , -7.9038499999999998e-02 , 2.4104700000000001e-01 , 9.6728999999999998e-01 -1.7199049654215277e+00 , -3.2998790189538783e+00 , 1.9289144400000000e+00 , -8.2064499999999999e-02 , 2.3177600000000001e-01 , 9.6930200000000000e-01 -1.6676587123996107e+00 , -3.5804376405222955e+00 , 1.9798476080000000e+00 , -8.5163000000000003e-02 , 2.2108100000000000e-01 , 9.7153000000000000e-01 -1.6111740176861500e+00 , -3.8907081704782147e+00 , 2.0352422720000001e+00 , -8.4748799999999999e-02 , 2.2083900000000001e-01 , 9.7162099999999996e-01 -1.5492052402761016e+00 , -4.2215094679292129e+00 , 2.0981877519999999e+00 , -7.7145400000000003e-02 , 2.1744600000000000e-01 , 9.7301899999999997e-01 -1.4794325125683767e+00 , -4.6030665065797187e+00 , 2.1658820799999998e+00 , -8.4313299999999994e-02 , 2.2045500000000001e-01 , 9.7174600000000000e-01 -1.4037843801123753e+00 , -5.0044802194291922e+00 , 2.2443656800000000e+00 , 8.0480599999999999e-02 , -2.2684699999999999e-01 , -9.7060000000000002e-01 -1.3187420219564276e+00 , -5.4655037035472960e+00 , 2.3307356000000001e+00 , -7.5980599999999995e-02 , 2.1864700000000001e-01 , 9.7284199999999998e-01 -1.2184469880406277e+00 , -6.0078047668493593e+00 , 2.4267525600000002e+00 , -7.9145199999999999e-02 , 2.1512600000000001e-01 , 9.7337399999999996e-01 -1.1068358562199339e+00 , -6.6102855801107463e+00 , 2.5378214400000001e+00 , 6.3441700000000004e-02 , -2.2480900000000001e-01 , -9.7233499999999995e-01 -9.8349898521887735e-01 , -7.2722863750498394e+00 , 2.6672806400000000e+00 , -6.0557899999999998e-02 , 2.2355600000000000e-01 , 9.7280800000000001e-01 -8.3770112801795249e-01 , -8.0546013524774871e+00 , 2.8165955199999999e+00 , -6.5274200000000004e-02 , 2.1971900000000000e-01 , 9.7337700000000005e-01 -6.6266594547818913e-01 , -8.9992356696888773e+00 , 2.9922359199999997e+00 , -3.5413300000000002e-02 , 3.3201799999999998e-01 , 9.4260800000000000e-01 -5.5901629423537069e-01 , -9.4665671930823247e+00 , 3.1961560000000002e+00 , 1.0801600000000000e-01 , 5.6752800000000003e-01 , 8.1623800000000002e-01 -4.8004668567529607e-01 , -9.7657967004610402e+00 , 3.4122159999999999e+00 , 1.2449800000000000e-01 , 6.3178599999999996e-01 , 7.6507899999999995e-01 -4.0606870616963220e-01 , -1.0019870414749354e+01 , 3.6369704000000000e+00 , 1.0276700000000000e-01 , 5.6006800000000001e-01 , 8.2204800000000000e-01 -1.9684770925644157e-01 , -1.1078122801775482e+01 , 3.9213063999999997e+00 , -6.8347900000000003e-02 , 2.7391199999999999e-01 , 9.5932300000000004e-01 --1.1843456912961554e+00 , -1.9008482783753511e+01 , 4.7936376000000003e+00 , 5.0924100000000005e-01 , 2.1142900000000001e-01 , 8.3424900000000002e-01 --1.5056527673233009e+00 , -2.0548722902031024e+01 , 5.3230704000000006e+00 , 1.6754100000000000e-01 , 2.1891700000000000e-01 , 9.6125200000000000e-01 --1.7023125022434984e+00 , -2.1331818943956506e+01 , 5.8214488000000006e+00 , -2.0186899999999999e-01 , -1.7886500000000000e-01 , -9.6294100000000005e-01 --2.6327033886705475e+00 , -2.6214532264642216e+01 , 6.8961224000000003e+00 , 3.6315799999999998e-01 , 1.7216200000000001e-01 , 9.1568400000000005e-01 --3.0383863989269511e+00 , -2.8045653550418034e+01 , 7.6870424000000002e+00 , 3.0927199999999999e-01 , 9.3332300000000001e-01 , -1.8236900000000000e-01 --3.0976151135278025e+00 , -2.7928835904051013e+01 , 8.2172656000000011e+00 , -6.4784200000000003e-01 , -7.5574399999999997e-01 , 9.5669900000000002e-02 --3.1295573563995669e+00 , -2.7661851944082773e+01 , 8.7187224000000008e+00 , 6.6445799999999999e-01 , 7.3796399999999995e-01 , -1.1792000000000000e-01 --3.2100122830172229e+00 , -2.7657044032379389e+01 , 9.2684040000000003e+00 , 7.0762400000000003e-01 , 6.9998800000000005e-01 , -9.6354400000000007e-02 --3.2687107566955600e+00 , -2.7532372488345338e+01 , 9.7953615999999997e+00 , 7.5138000000000005e-01 , 6.5325200000000005e-01 , -9.3220100000000000e-02 --3.3248831553181963e+00 , -2.7398699664357139e+01 , 1.0320436800000000e+01 , -7.6301699999999995e-01 , -6.3934000000000002e-01 , 9.5132499999999995e-02 --3.3795900713468923e+00 , -2.7256028322670630e+01 , 1.0843275999999999e+01 , -7.7567500000000000e-01 , -6.2025399999999997e-01 , 1.1667200000000000e-01 --3.4369814496749207e+00 , -2.7124194326699904e+01 , 1.1369224800000000e+01 , -7.9763399999999995e-01 , -5.9242099999999998e-01 , 1.1321100000000001e-01 --3.4892008516128854e+00 , -2.6973378443672811e+01 , 1.1890680800000000e+01 , -8.4375000000000000e-01 , -5.0926700000000003e-01 , 1.6950799999999999e-01 --3.5426213339016774e+00 , -2.6823442723125535e+01 , 1.2412688000000001e+01 , -8.4264099999999997e-01 , -5.2089700000000005e-01 , 1.3646700000000000e-01 --3.5945997574627659e+00 , -2.6663345965494077e+01 , 1.2932376000000001e+01 , -8.8250300000000004e-01 , -4.6048299999999998e-01 , 9.5622799999999994e-02 --3.5694481191737708e+00 , -2.6139874529219490e+01 , 1.3322480000000001e+01 , -9.0142000000000000e-01 , -4.2825200000000002e-01 , 6.3579100000000000e-02 --3.7187168102450538e+00 , -2.6441575574484279e+01 , 1.4012104000000001e+01 , -9.0942999999999996e-01 , -4.1294100000000000e-01 , 4.9166099999999997e-02 --3.7470420560935294e+00 , -2.6169401572846311e+01 , 1.4492688000000001e+01 , -9.0899200000000002e-01 , -4.1630099999999998e-01 , 2.0643600000000002e-02 --3.8287381710799977e+00 , -2.6142242716388100e+01 , 1.5073943999999999e+01 , -9.0137699999999998e-01 , -4.3042000000000002e-01 , 4.7518199999999997e-02 --3.8820196019160074e+00 , -2.5983046782846859e+01 , 1.5604760000000001e+01 , -9.0670899999999999e-01 , -4.1959900000000000e-01 , 4.2611700000000002e-02 --3.9419426351197755e+00 , -2.5850240365367657e+01 , 1.6151176000000000e+01 , -9.1755799999999998e-01 , -3.9567999999999998e-01 , 3.9035899999999998e-02 --4.0057745795315691e+00 , -2.5735841453237299e+01 , 1.6710695999999999e+01 , -9.2447000000000001e-01 , -3.7759599999999999e-01 , 5.2687100000000001e-02 --4.0666025802093007e+00 , -2.5600141139790534e+01 , 1.7265743999999998e+01 , -9.3666400000000005e-01 , -3.4549400000000002e-01 , 5.7402799999999997e-02 --4.1169434332703725e+00 , -2.5418807727929721e+01 , 1.7801760000000002e+01 , -9.5401700000000000e-01 , -2.8965900000000000e-01 , 7.7132699999999998e-02 --4.1742537122098078e+00 , -2.5263293593807177e+01 , 1.8355872000000002e+01 , -9.6456100000000000e-01 , -2.5255800000000000e-01 , 7.6390899999999998e-02 --4.2123402976717461e+00 , -2.5025675692310152e+01 , 1.8868696000000000e+01 , -9.5484199999999997e-01 , -2.9697499999999999e-01 , 9.0887599999999995e-03 --4.2253700970416084e+00 , -2.4682381281414226e+01 , 1.9320679999999999e+01 , -9.5607200000000003e-01 , -2.9247200000000001e-01 , -1.9651600000000002e-02 --4.4453569572965330e+00 , -2.5170218182621152e+01 , 2.0288400000000003e+01 , -9.5291099999999995e-01 , -3.0132700000000001e-01 , -3.4102500000000001e-02 --4.4472949531447528e+00 , -2.4778515222494359e+01 , 2.0724992000000000e+01 , -8.6396499999999998e-01 , -5.0236599999999998e-01 , -3.4527799999999997e-02 --4.8606103891509838e+00 , -2.5981495844153319e+01 , 2.2234031999999999e+01 , 1.9741300000000001e-01 , 9.7126100000000004e-01 , 1.3296800000000000e-01 -1.0373507069778158e+00 , -2.9994531000410882e+00 , 6.8687600000000000e+00 , 9.8524100000000003e-02 , 6.7596299999999998e-01 , -7.3031999999999997e-01 -1.0343454366335776e+00 , -2.9301854130423299e+00 , 6.9642112000000003e+00 , 9.8524000000000000e-02 , 6.7596299999999998e-01 , -7.3031900000000005e-01 -1.0383900343354817e+00 , -2.8354429336861839e+00 , 7.0400479999999996e+00 , 2.5519799999999998e-01 , 7.8293000000000001e-01 , -5.6735700000000000e-01 -1.0299161112114796e+00 , -2.7871485703909862e+00 , 7.1514736000000001e+00 , -1.7717600000000000e-01 , -9.5238000000000000e-01 , 2.4815400000000001e-01 -9.9271199980281710e-01 , -2.8398104171300806e+00 , 7.3458911999999996e+00 , -2.2001199999999999e-03 , 9.9997899999999995e-01 , 6.1582099999999999e-03 -9.9323026299580386e-01 , -2.7545266569330602e+00 , 7.4320344000000000e+00 , -2.6614100000000002e-01 , 9.5975999999999995e-01 , -8.9615100000000003e-02 -9.4871469317312584e-01 , -2.8293312468703249e+00 , 7.6573191999999999e+00 , -1.3027800000000000e-01 , -9.9146000000000001e-01 , 5.9314800000000003e-03 -1.0333958053134742e+00 , -2.4527956642645456e+00 , 7.4835976000000004e+00 , -6.2589399999999995e-01 , 7.6226700000000003e-01 , -1.6494100000000000e-01 -9.0148628645709827e-01 , -2.8171512946986024e+00 , 7.9870408000000008e+00 , -4.1437600000000002e-01 , -8.7533200000000000e-01 , 2.4917000000000000e-01 -8.9922830887237382e-01 , -2.7364414624354465e+00 , 8.0867351999999997e+00 , -3.8499000000000000e-01 , -7.4124599999999996e-01 , 5.4985200000000001e-01 -8.8480452177093238e-01 , -2.6966433132577237e+00 , 8.2285080000000015e+00 , -1.2233500000000000e-01 , -5.0025299999999995e-01 , 8.5719400000000001e-01 -9.3468892106118062e-01 , -2.4497669216996583e+00 , 8.1574135999999999e+00 , -2.5531700000000001e-02 , -3.2268500000000000e-01 , 9.4616199999999995e-01 -9.1659817344896544e-01 , -2.4202518622819449e+00 , 8.3106056000000006e+00 , 2.5217000000000001e-01 , -2.6254899999999998e-01 , 9.3138500000000002e-01 -9.1837145809704146e-01 , -2.3266064923148342e+00 , 8.3963432000000005e+00 , 1.8218799999999999e-01 , -2.2602500000000000e-01 , 9.5693300000000003e-01 -1.0437178103247322e+00 , -1.8605646067515615e+00 , 8.0483592000000002e+00 , 2.7796999999999999e-01 , 2.3344999999999999e-01 , 9.3179100000000004e-01 -1.0551402653503605e+00 , -1.7448968612544369e+00 , 8.0926320000000000e+00 , -5.2672600000000003e-01 , 5.6993499999999997e-03 , 8.5001599999999999e-01 -9.3891341557097840e-01 , -2.0043407768159334e+00 , 8.6036256000000009e+00 , -6.1086399999999999e-02 , -4.7097699999999998e-01 , 8.8002800000000003e-01 -1.0884197244841980e+00 , -1.4900215155146039e+00 , 8.1420424000000011e+00 , 6.0041599999999995e-01 , -7.6186199999999996e-02 , -7.9605000000000004e-01 -1.1071864589907587e+00 , -1.3577648122290613e+00 , 8.1542519999999996e+00 , 8.1417100000000006e-02 , -9.6112200000000003e-01 , 2.6384800000000003e-01 -1.0960306092170826e+00 , -1.3087513310257517e+00 , 8.2792183999999995e+00 , -5.7632099999999997e-01 , 7.2744299999999995e-01 , -3.7239899999999998e-01 -1.0881921409925095e+00 , -1.2499288611376862e+00 , 8.3955944000000002e+00 , 4.2231000000000002e-01 , -7.4844999999999995e-01 , 5.1134800000000002e-01 -8.2453868250148976e-01 , -1.8636625296044924e+00 , 9.5304528000000008e+00 , -9.7966399999999998e-01 , 1.7848500000000000e-02 , 1.9984800000000000e-01 -1.0913166777359140e+00 , -1.0822807101459762e+00 , 8.5589992000000006e+00 , 3.8866200000000001e-01 , -8.9266100000000004e-01 , 2.2824900000000001e-01 -1.1180706434294496e+00 , -9.3126730370327282e-01 , 8.5342784000000016e+00 , -5.8182999999999996e-01 , -4.6882699999999999e-01 , 6.6458600000000001e-01 -9.1566375175745107e-01 , -1.3449102651944602e+00 , 9.4631336000000008e+00 , -3.4734900000000002e-01 , 9.2234899999999997e-01 , 1.6917900000000000e-01 -1.0144658203731114e+00 , -1.0164157035676555e+00 , 9.1488664000000011e+00 , 9.9241400000000002e-01 , 3.3995100000000000e-02 , -1.1814600000000000e-01 -1.0405608409309399e+00 , -8.6534486448503722e-01 , 9.1295120000000001e+00 , -8.7053999999999998e-01 , 1.7024000000000000e-01 , 4.6171200000000001e-01 -1.0468001213686970e+00 , -7.6279310326632865e-01 , 9.1971536000000000e+00 , -8.5715200000000003e-01 , -1.3202100000000000e-01 , 4.9785600000000002e-01 -1.0949594313699957e+00 , -5.6854938330514448e-01 , 9.0806111999999999e+00 , 9.8986399999999997e-01 , -1.4196700000000001e-01 , -3.8148499999999998e-03 -1.0542622810644142e+00 , -5.6670754477668472e-01 , 9.3550879999999985e+00 , -2.2789699999999999e-01 , -1.8874700000000001e-02 , 9.7350199999999998e-01 -1.0951134307661907e+00 , -3.9352352400605151e-01 , 9.2695064000000009e+00 , -5.9043000000000001e-01 , -5.9512799999999999e-01 , 5.4517400000000005e-01 -1.0703737881461888e+00 , -3.5235714544690966e-01 , 9.4790455999999992e+00 , 1.3275200000000001e-01 , -6.3568300000000000e-01 , 7.6044999999999996e-01 -1.0753103375346087e+00 , -2.5081226756458808e-01 , 9.5572224000000006e+00 , 5.7884800000000000e-02 , -5.7912900000000000e-01 , 8.1317899999999999e-01 -1.0977969683089324e+00 , -1.1450132001443958e-01 , 9.5481744000000006e+00 , 2.2827000000000000e-01 , -9.0634400000000004e-02 , -9.6936999999999995e-01 -1.0120285115419199e+00 , -1.7378174363341392e-01 , 1.0063109600000001e+01 , -6.7294400000000004e-02 , 4.5686700000000002e-01 , 8.8698600000000005e-01 -1.0069239275565458e+00 , -8.0809003030072102e-02 , 1.0196708000000001e+01 , -1.0751900000000000e-01 , -1.1162800000000000e-02 , 9.9414000000000002e-01 -1.0402619194924183e+00 , 7.7194993891283037e-02 , 1.0144801600000001e+01 , 1.5363700000000000e-01 , 2.7009600000000000e-01 , 9.5049700000000004e-01 -1.0799258056533856e+00 , 2.4341063821939635e-01 , 1.0050692000000002e+01 , -2.5009300000000001e-01 , -2.1967700000000001e-01 , -9.4297200000000003e-01 -1.2592940859161210e+00 , 6.1521127344591986e-01 , 9.2359456000000009e+00 , -1.2308600000000000e-01 , -6.6651800000000005e-01 , 7.3525799999999997e-01 -1.2790604336218827e+00 , 7.3407724613072367e-01 , 9.2293312000000007e+00 , -1.0315800000000000e-01 , -6.7284900000000003e-01 , 7.3255199999999998e-01 -1.1978750971903318e+00 , 7.1626188862951468e-01 , 9.7560183999999985e+00 , -9.3970699999999996e-01 , 3.1654399999999999e-01 , 1.2942600000000001e-01 -1.1564707504490530e+00 , 7.6331402486548106e-01 , 1.0086166400000000e+01 , 4.2924299999999999e-01 , -1.4968200000000001e-01 , 8.9069900000000002e-01 -1.2606863030065709e+00 , 9.9213998338252352e-01 , 9.6261536000000003e+00 , 7.6173400000000002e-01 , -5.6861399999999995e-01 , -3.1054700000000002e-01 -1.2088323041696054e+00 , 1.0342161868613162e+00 , 1.0024203200000001e+01 , -7.5716499999999998e-01 , -3.4343899999999999e-01 , -5.5565299999999995e-01 -1.2116717376960293e+00 , 1.1427247624652057e+00 , 1.0120673600000000e+01 , -6.8829899999999999e-01 , 7.2241500000000000e-02 , -7.2182100000000005e-01 -1.2816265704389398e+00 , 1.3170003103398544e+00 , 9.8305968000000004e+00 , 3.6064499999999999e-01 , 1.2528900000000001e-01 , 9.2425000000000002e-01 -1.2957573829361315e+00 , 1.4340957012623652e+00 , 9.8614224000000004e+00 , -1.4242899999999999e-02 , 1.0697600000000000e-01 , 9.9416000000000004e-01 -1.2453996910187131e+00 , 1.5030157038148084e+00 , 1.0277079200000001e+01 , -7.2424900000000003e-01 , 4.3672000000000000e-01 , -5.3360900000000000e-01 -1.3379843140707053e+00 , 1.6776593953491794e+00 , 9.8355472000000006e+00 , 4.4996999999999998e-01 , 8.2956500000000000e-01 , -3.3067999999999997e-01 -1.3287343114909898e+00 , 1.7818635938053566e+00 , 1.0013480800000000e+01 , -4.6140199999999998e-01 , -5.0655399999999995e-01 , 7.2836199999999995e-01 -1.4812035187804127e+00 , 1.9643671822585251e+00 , 9.1757608000000008e+00 , -6.3164100000000001e-01 , -6.2490900000000005e-01 , -4.5882200000000001e-01 -1.5185512138428634e+00 , 2.0790077874225910e+00 , 9.0412472000000008e+00 , 6.7599299999999996e-01 , -2.9779699999999998e-01 , 6.7405499999999996e-01 -1.5281588316434744e+00 , 2.1807312634119249e+00 , 9.0896696000000006e+00 , 7.0803600000000000e-01 , -5.3082300000000004e-01 , 4.6573799999999999e-01 -1.4692215575038274e+00 , 2.2763340043952716e+00 , 9.5885056000000013e+00 , 4.9585499999999999e-01 , -5.9275800000000001e-01 , -6.3463800000000004e-01 -1.4744726726177595e+00 , 2.3900737421293643e+00 , 9.6745552000000004e+00 , -5.6996300000000000e-02 , 6.3600000000000004e-02 , 9.9634699999999998e-01 -1.5102140907416288e+00 , 2.5031476149926091e+00 , 9.5530103999999998e+00 , -4.8555700000000002e-01 , 1.8122300000000000e-01 , 8.5521499999999995e-01 -1.4444200943325203e+00 , 2.6347533177879994e+00 , 1.0139476800000001e+01 , 4.5451300000000000e-01 , 2.1766600000000000e-01 , 8.6373599999999995e-01 -1.5401517718705824e+00 , 2.8522613862520041e+00 , 9.7216464000000009e+00 , -8.7324900000000005e-01 , -2.8393000000000002e-02 , 4.8644700000000002e-01 -1.5476467995824303e+00 , 2.9755044340925449e+00 , 9.8079248000000003e+00 , -8.4007500000000002e-01 , -4.6985500000000002e-01 , -2.7112999999999998e-01 -1.5712932677787803e+00 , 3.0897662919541800e+00 , 9.7687272000000007e+00 , 4.1807200000000000e-01 , -1.1996999999999999e-01 , 9.0045699999999995e-01 -1.6121054234517811e+00 , 3.1866879968704822e+00 , 9.5944544000000000e+00 , -9.0989200000000003e-01 , -1.9905900000000001e-01 , -3.6396600000000001e-01 -1.6688040334872702e+00 , 3.2590596872397164e+00 , 9.2859072000000005e+00 , 2.1138599999999999e-01 , 9.7431199999999996e-01 , -7.7672900000000003e-02 -2.3694243476290042e+00 , 5.2386323053300488e-01 , 1.2878735199999998e+00 , -2.2156400000000000e-02 , 3.9753899999999998e-01 , 9.1731799999999997e-01 -2.3057592996600453e+00 , 2.1774005557903942e-01 , 1.3254237600000001e+00 , -9.4420500000000004e-02 , 2.2704400000000000e-01 , 9.6929699999999996e-01 -2.2930795793849619e+00 , 1.6470134094781819e-01 , 1.3440761600000000e+00 , -7.5595700000000002e-02 , 2.4895300000000001e-01 , 9.6556100000000000e-01 -2.2778200341713881e+00 , 8.6022192633560923e-02 , 1.3455924800000001e+00 , -6.1986899999999998e-02 , 2.2934900000000000e-01 , 9.7136900000000004e-01 -2.2642148398791684e+00 , 2.2958992395154310e-02 , 1.3617166400000000e+00 , -6.5897100000000000e-02 , 2.1115600000000001e-01 , 9.7522900000000001e-01 -2.2489499107018287e+00 , -4.7348754876539889e-02 , 1.3731556000000000e+00 , -1.0076300000000001e-01 , 1.9570399999999999e-01 , 9.7547300000000003e-01 -2.2334143006327469e+00 , -1.1827378265274158e-01 , 1.3867224000000000e+00 , -9.0853100000000006e-02 , 1.7176400000000000e-01 , 9.8094000000000003e-01 -2.2155322887140434e+00 , -2.0688634153874297e-01 , 1.3910508799999999e+00 , -8.2357500000000000e-02 , 1.2669800000000001e-01 , 9.8851699999999998e-01 -2.1983203068415791e+00 , -2.9707153397224806e-01 , 1.3982435199999999e+00 , 7.9774999999999999e-02 , -1.9392599999999999e-01 , -9.7776700000000005e-01 -2.1809264612214214e+00 , -3.6872342503457567e-01 , 1.4183675199999999e+00 , 7.4121900000000004e-02 , -1.8639100000000000e-01 , -9.7967599999999999e-01 -2.1615164957331925e+00 , -4.6740831751130774e-01 , 1.4251285600000001e+00 , -6.7220500000000002e-02 , 1.9323499999999999e-01 , 9.7884700000000002e-01 -2.1429442202600639e+00 , -5.4863722923987757e-01 , 1.4448500800000001e+00 , -5.2605699999999998e-02 , 2.2817499999999999e-01 , 9.7219800000000001e-01 -2.1234560140492205e+00 , -6.3881692813439672e-01 , 1.4621411200000001e+00 , -6.7563700000000004e-02 , 2.0273200000000000e-01 , 9.7690100000000002e-01 -2.1012603747586631e+00 , -7.4824295615041958e-01 , 1.4729321600000000e+00 , -7.6948400000000000e-02 , 1.8155399999999999e-01 , 9.8036599999999996e-01 -2.0793411976759253e+00 , -8.4869926235307247e-01 , 1.4914171199999999e+00 , -6.4917299999999997e-02 , 2.2306699999999999e-01 , 9.7263900000000003e-01 -2.0580986192458544e+00 , -9.4855150816337330e-01 , 1.5130636799999999e+00 , -7.4536900000000003e-02 , 2.2973700000000000e-01 , 9.7039399999999998e-01 -2.0329513558591832e+00 , -1.0684339657890112e+00 , 1.5293011999999999e+00 , -8.3980399999999997e-02 , 1.7582900000000001e-01 , 9.8083200000000004e-01 -2.0048436016300397e+00 , -1.2071153082568213e+00 , 1.5411634400000001e+00 , -1.0128700000000000e-01 , 1.2692400000000001e-01 , 9.8672700000000002e-01 -1.9736286701862378e+00 , -1.3654423577135471e+00 , 1.5497663200000000e+00 , -1.2669900000000001e-01 , 1.1374099999999999e-01 , 9.8539900000000002e-01 -1.9417658481292839e+00 , -1.5248239436863731e+00 , 1.5635348800000000e+00 , -7.8578200000000001e-02 , 2.2527000000000000e-01 , 9.7112299999999996e-01 -1.9127508530485109e+00 , -1.6546481745421771e+00 , 1.5928098399999999e+00 , 1.0796699999999999e-02 , 2.6721600000000001e-01 , 9.6357599999999999e-01 -1.8831607221865105e+00 , -1.7856607551153427e+00 , 1.6266431200000000e+00 , 3.8656099999999999e-02 , -2.6275399999999999e-01 , -9.6408799999999995e-01 -1.8493659539238121e+00 , -1.9350877300844318e+00 , 1.6577973600000000e+00 , -3.2168700000000001e-02 , 2.3854800000000001e-01 , 9.7059799999999996e-01 -1.8132100361939960e+00 , -2.1047626029343469e+00 , 1.6880468000000000e+00 , -4.2757000000000003e-02 , 2.3953800000000000e-01 , 9.6994499999999995e-01 -1.7753507510617759e+00 , -2.2743264699194299e+00 , 1.7237375200000000e+00 , -6.2690999999999997e-02 , 2.1656500000000001e-01 , 9.7425300000000004e-01 -1.7330325886218008e+00 , -2.4739334409512646e+00 , 1.7569832000000001e+00 , -7.2295100000000001e-02 , 2.0513600000000001e-01 , 9.7606000000000004e-01 -1.6859745426130892e+00 , -2.6931881276914158e+00 , 1.7918044799999999e+00 , -6.7704100000000003e-02 , 2.0556199999999999e-01 , 9.7629900000000003e-01 -1.6370614984867169e+00 , -2.9230271272417347e+00 , 1.8316905600000000e+00 , -6.2147599999999997e-02 , 2.3685600000000001e-01 , 9.6955499999999994e-01 -1.5861746463729685e+00 , -3.1522899772724227e+00 , 1.8792456000000000e+00 , -6.7181199999999996e-02 , 2.3482400000000000e-01 , 9.6971399999999996e-01 -1.5323281956348695e+00 , -3.4018689792139112e+00 , 1.9307551359999999e+00 , -6.8783600000000000e-02 , 2.2212399999999999e-01 , 9.7258900000000004e-01 -1.4682457242608287e+00 , -3.7010943872974416e+00 , 1.9813697520000000e+00 , -6.2127099999999998e-02 , 2.0663799999999999e-01 , 9.7644299999999995e-01 -1.3987828815189145e+00 , -4.0199487830579708e+00 , 2.0388241360000001e+00 , -6.7646999999999999e-02 , 2.1427800000000000e-01 , 9.7442700000000004e-01 -1.3237470449437652e+00 , -4.3690509024177198e+00 , 2.1030455920000000e+00 , -7.2390499999999997e-02 , 2.1118400000000001e-01 , 9.7476200000000002e-01 -1.2376593635323700e+00 , -4.7685908835873763e+00 , 2.1728532000000000e+00 , 7.2354000000000002e-02 , -2.2217500000000001e-01 , -9.7231800000000002e-01 -1.1456749196675005e+00 , -5.1868352122625536e+00 , 2.2539534400000001e+00 , -6.9005700000000003e-02 , 2.1989200000000000e-01 , 9.7307999999999995e-01 -1.0386755411443644e+00 , -5.6867970577179667e+00 , 2.3425739200000000e+00 , -7.3539999999999994e-02 , 2.1088199999999999e-01 , 9.7474099999999997e-01 -9.1201478559882010e-01 , -6.2762308988501445e+00 , 2.4414747999999999e+00 , -5.1052899999999998e-02 , 2.2116800000000000e-01 , 9.7389800000000004e-01 -7.8284854470710141e-01 , -6.8645596753597271e+00 , 2.5611257599999999e+00 , -5.1033099999999998e-02 , 2.2096800000000000e-01 , 9.7394499999999995e-01 -6.2961527523163396e-01 , -7.5728702807793127e+00 , 2.6967355199999998e+00 , -5.5198400000000002e-02 , 2.1478500000000000e-01 , 9.7509999999999997e-01 -4.3921812467639376e-01 , -8.4526624234573671e+00 , 2.8534385599999998e+00 , -6.0590199999999997e-02 , 2.1943799999999999e-01 , 9.7374300000000003e-01 -2.3456728698708540e-01 , -9.3892929195123820e+00 , 3.0409568000000000e+00 , 5.1250799999999999e-02 , 5.0206700000000004e-01 , 8.6330899999999999e-01 -1.5384039163256591e-01 , -9.6481303944480299e+00 , 3.2518584000000001e+00 , 4.0395100000000003e-02 , 6.5235399999999999e-01 , 7.5683699999999998e-01 -1.0163681941290648e-01 , -9.7500778039577689e+00 , 3.4673151999999998e+00 , -1.7485000000000001e-02 , 6.7040000000000000e-01 , 7.4179399999999995e-01 --1.5765785033877933e-02 , -1.0183799661706802e+01 , 3.7030935999999999e+00 , -6.8403900000000004e-02 , 5.2493900000000004e-01 , 8.4838700000000000e-01 --3.6127895848068547e-01 , -1.1753034758303151e+01 , 4.0310367999999999e+00 , -2.1860199999999999e-01 , 2.9007699999999997e-01 , 9.3170200000000003e-01 --1.8662982191695816e+00 , -1.9033071982989028e+01 , 4.9001647999999998e+00 , 2.3187700000000000e-01 , 2.1342100000000000e-01 , 9.4904400000000000e-01 --2.0243638099685946e+00 , -1.9524274107446892e+01 , 5.3323368000000002e+00 , 1.4053099999999999e-01 , 2.3224100000000000e-01 , 9.6245300000000000e-01 --3.0793351425604722e+00 , -2.4336206842712496e+01 , 6.3050072000000004e+00 , -8.8195199999999996e-01 , -2.5601499999999999e-01 , -3.9574900000000002e-01 --3.2053449938545304e+00 , -2.4585865690756400e+01 , 6.8204208000000000e+00 , -8.8195199999999996e-01 , -2.5601499999999999e-01 , -3.9574900000000002e-01 --3.2577626695043991e+00 , -2.4484221355862100e+01 , 7.2927783999999996e+00 , 9.8261799999999999e-01 , 1.3361999999999999e-01 , 1.2886700000000001e-01 --3.3023057861930916e+00 , -2.4344052665365048e+01 , 7.7576896000000009e+00 , 9.8060499999999995e-01 , 1.5800500000000001e-01 , 1.1596600000000000e-01 --3.3767290696261805e+00 , -2.4344919569649345e+01 , 8.2483408000000011e+00 , -9.7541599999999995e-01 , -2.1286099999999999e-01 , -5.7037699999999997e-02 --3.4643157315161188e+00 , -2.4397586178909641e+01 , 8.7535623999999999e+00 , 9.7465700000000000e-01 , 2.1762899999999999e-01 , 5.1780199999999998e-02 --3.5012186935148693e+00 , -2.4222866912783324e+01 , 9.2125559999999993e+00 , 9.7588900000000001e-01 , 2.1447600000000000e-01 , 4.0499300000000002e-02 --3.5513442012374741e+00 , -2.4108554679861605e+01 , 9.6846327999999993e+00 , 9.7825099999999998e-01 , 2.0675900000000000e-01 , 1.6577700000000001e-02 --3.6067766487275357e+00 , -2.4016222919143733e+01 , 1.0163043200000001e+01 , 9.7940899999999997e-01 , 2.0188400000000001e-01 , 7.2485599999999996e-04 --3.6558347136571561e+00 , -2.3896706888581463e+01 , 1.0635224000000001e+01 , 9.7757099999999997e-01 , 2.1057300000000001e-01 , 3.8532100000000001e-03 --3.7085799919004172e+00 , -2.3786745858070468e+01 , 1.1111408800000001e+01 , 9.7581899999999999e-01 , 2.1846199999999999e-01 , -7.2357200000000002e-03 --3.7590388476453009e+00 , -2.3669742201901450e+01 , 1.1586813600000001e+01 , -9.7126999999999997e-01 , -2.2802600000000001e-01 , 6.8110699999999996e-02 --3.8043463886105267e+00 , -2.3533654731751973e+01 , 1.2057507200000002e+01 , 9.7731500000000004e-01 , 2.1076500000000001e-01 , -2.0817200000000001e-02 --3.8449916431145308e+00 , -2.3370836166059039e+01 , 1.2519496000000000e+01 , 9.7788399999999998e-01 , 2.0853600000000000e-01 , -1.5988599999999999e-02 --3.8105049896905419e+00 , -2.2907549843861187e+01 , 1.2865816000000001e+01 , 9.8296600000000001e-01 , 1.8373000000000000e-01 , 4.6345500000000003e-03 --3.9936030326573366e+00 , -2.3321905332404214e+01 , 1.3558351999999999e+01 , 9.7841900000000004e-01 , 9.1872499999999996e-02 , 1.8508500000000000e-01 --4.0021118614992970e+00 , -2.3030752095348983e+01 , 1.3973832000000000e+01 , 9.7000100000000000e-01 , 7.9488799999999998e-02 , 2.2973600000000000e-01 --4.3590556877749984e+00 , -2.4099318062983954e+01 , 1.4997192000000000e+01 , -9.0185099999999996e-01 , -2.6127499999999998e-01 , -3.4409499999999998e-01 --4.4217373770270987e+00 , -2.4003680610526757e+01 , 1.5527072000000000e+01 , -9.7692999999999997e-01 , -2.1035100000000001e-01 , -3.6874600000000000e-02 --4.4805735210302995e+00 , -2.3888799575717545e+01 , 1.6053311999999998e+01 , -8.7681600000000004e-01 , -1.5029600000000001e-01 , 4.5673300000000000e-01 --4.5352376774019074e+00 , -2.3754714900649212e+01 , 1.6575080000000000e+01 , -9.6593499999999999e-01 , -5.9284200000000002e-02 , 2.5190299999999999e-01 --4.3323953173658891e+00 , -2.2667194338247278e+01 , 1.6588079999999998e+01 , -9.4005700000000003e-01 , 4.7289800000000000e-02 , 3.3772200000000002e-01 --4.3815609996563767e+00 , -2.2522020234754571e+01 , 1.7092376000000002e+01 , 9.9494600000000000e-01 , -2.5243499999999999e-02 , -9.7184800000000002e-02 --4.4465622031685204e+00 , -2.2428550814953372e+01 , 1.7632032000000002e+01 , 9.9292000000000002e-01 , 4.3784100000000001e-03 , -1.1870300000000000e-01 --4.4875836206602608e+00 , -2.2246601642855865e+01 , 1.8125720000000001e+01 , 9.9187899999999996e-01 , 9.9412399999999998e-02 , -7.9330399999999995e-02 --4.5405494922118264e+00 , -2.2106760831177791e+01 , 1.8650608000000002e+01 , 9.9216400000000005e-01 , 1.2474100000000000e-01 , 7.1590700000000000e-03 --4.4264252080474034e+00 , -2.1381462151236928e+01 , 1.8796416000000001e+01 , 9.9928600000000001e-01 , 2.9987900000000001e-02 , 2.2976600000000000e-02 -7.8269234939305710e-01 , -3.2859928227824797e+00 , 6.9891088000000003e+00 , -2.7616299999999999e-01 , 6.1743700000000001e-01 , -7.3655000000000004e-01 -8.3667329386180689e-01 , -3.0254036302851279e+00 , 6.9553400000000005e+00 , 1.7372599999999999e-01 , -5.8922900000000000e-01 , 7.8906799999999999e-01 -8.4547203946585836e-01 , -2.9219722479761048e+00 , 7.0279008000000003e+00 , -1.9941800000000001e-01 , 8.9130799999999999e-01 , -4.0718900000000002e-01 -8.5156770519786917e-01 , -2.8261454705355407e+00 , 7.1042888000000000e+00 , -1.9941800000000001e-01 , 8.9130799999999999e-01 , -4.0718900000000002e-01 -8.3214997968228799e-01 , -2.8165201107084190e+00 , 7.2480688000000004e+00 , -1.5845300000000001e-01 , 9.8205299999999995e-01 , -1.0229600000000000e-01 -7.7768881719459415e-01 , -2.9123035654534277e+00 , 7.4830464000000010e+00 , 2.5295800000000000e-02 , -9.8504499999999995e-01 , 1.7043200000000000e-01 -7.7311279497113450e-01 , -2.8468560885397185e+00 , 7.5908528000000004e+00 , -7.6171900000000001e-02 , -9.8288200000000003e-01 , 1.6775000000000001e-01 -7.4541459257532527e-01 , -2.8561636024785102e+00 , 7.7653544000000005e+00 , 3.8880300000000001e-01 , 9.0500599999999998e-01 , -1.7261699999999999e-01 -7.4397481476254734e-01 , -2.7794900764095356e+00 , 7.8662968000000006e+00 , -3.7337300000000001e-01 , -8.9761199999999997e-01 , 2.3427700000000001e-01 -7.1726937501334231e-01 , -2.7799797899192233e+00 , 8.0426287999999992e+00 , -3.8964700000000002e-01 , -8.4813700000000003e-01 , 3.5894300000000001e-01 -7.2533741229644422e-01 , -2.6763463492283037e+00 , 8.1212736000000003e+00 , 5.1183699999999999e-01 , 7.4286200000000002e-01 , -4.3148500000000001e-01 -7.1613025057454660e-01 , -2.6206133811043371e+00 , 8.2483928000000013e+00 , 6.5899300000000005e-01 , 4.1792200000000002e-01 , -6.2535499999999999e-01 -7.1219288196807407e-01 , -2.5489984855444288e+00 , 8.3605672000000002e+00 , 3.7208000000000002e-01 , 3.7200299999999997e-01 , -8.5039399999999998e-01 -7.8458595556158905e-01 , -2.2643346782145830e+00 , 8.2394280000000002e+00 , 3.9217200000000002e-01 , 2.2999700000000001e-01 , -8.9067600000000002e-01 -7.5825085025055583e-01 , -2.2582232339649142e+00 , 8.4222496000000007e+00 , -5.2445500000000000e-01 , 7.4910900000000002e-02 , -8.4813600000000000e-01 -8.0667366191734224e-01 , -2.0453347095458581e+00 , 8.3666616000000005e+00 , -1.9407099999999999e-01 , -4.4986100000000001e-01 , 8.7175800000000003e-01 -8.1660059766129556e-01 , -1.9373132954146994e+00 , 8.4306216000000003e+00 , -2.1967300000000001e-01 , -4.1596699999999998e-01 , 8.8244900000000004e-01 -9.9275488587149741e-01 , -1.3996587457451581e+00 , 7.9429864000000006e+00 , -5.5706299999999997e-01 , 2.9396699999999998e-01 , 7.7669999999999995e-01 -1.0435460594799255e+00 , -1.1970926620119759e+00 , 7.8577480000000008e+00 , 4.1241000000000000e-01 , 1.3164600000000001e-01 , -9.0143600000000002e-01 -1.0283089784551269e+00 , -1.1653225149489899e+00 , 7.9963800000000003e+00 , -4.7848799999999997e-02 , 9.4946200000000003e-01 , 3.1021500000000002e-01 -9.4293721417867005e-01 , -1.3033024791014896e+00 , 8.3842584000000002e+00 , -9.6396400000000004e-01 , -2.1883300000000000e-01 , 1.5128000000000000e-01 -9.4360360571096380e-01 , -1.2263399611816239e+00 , 8.4765168000000006e+00 , 2.1521100000000001e-01 , -8.6779700000000004e-01 , 4.4789800000000002e-01 -8.3112043462121932e-01 , -1.4164639390204945e+00 , 8.9845360000000003e+00 , 4.3845600000000001e-01 , 7.8559699999999999e-01 , 4.3657000000000001e-01 -5.3395093389173587e-01 , -2.0188141050091737e+00 , 1.0189854400000000e+01 , 3.7119700000000000e-01 , -8.1128599999999995e-01 , 4.5169399999999998e-01 -6.9272238408709863e-01 , -1.5589957335345432e+00 , 9.7127231999999992e+00 , 9.9113300000000004e-01 , -4.2605100000000000e-02 , -1.2586000000000000e-01 -6.8297310911530595e-01 , -1.4877631054212666e+00 , 9.8639392000000008e+00 , 9.8109999999999997e-01 , -4.6142400000000000e-02 , 1.8791700000000000e-01 -9.8255181872278752e-01 , -7.5009454483162319e-01 , 8.8142984000000002e+00 , 6.4531700000000003e-01 , -4.8432900000000001e-01 , -5.9075599999999995e-01 -1.0109886284159908e+00 , -6.1089020398755167e-01 , 8.7998007999999999e+00 , 6.1117699999999997e-01 , 3.1700499999999998e-01 , -7.2523800000000005e-01 -1.0252981401396304e+00 , -5.0108902970898983e-01 , 8.8366480000000003e+00 , 6.1117699999999997e-01 , 3.1700499999999998e-01 , -7.2523800000000005e-01 -9.2535700745000482e-01 , -6.2012016553989202e-01 , 9.3470696000000011e+00 , 1.3806099999999999e-01 , 2.7670800000000001e-01 , -9.5098499999999997e-01 -9.2498478841965581e-01 , -5.3515486483782038e-01 , 9.4577568000000003e+00 , -4.0045600000000001e-02 , -4.7686899999999999e-01 , 8.7806200000000001e-01 -9.5761017587197683e-01 , -3.8546619346691857e-01 , 9.4276903999999995e+00 , -3.2283699999999999e-01 , -6.9255699999999998e-01 , 6.4509000000000005e-01 -9.4518797370532348e-01 , -3.2010237956189336e-01 , 9.5913552000000006e+00 , 2.3013500000000001e-01 , -6.6927300000000001e-01 , 7.0647800000000005e-01 -9.5673057548189044e-01 , -2.0984337939416253e-01 , 9.6509783999999996e+00 , -5.0389200000000001e-01 , 7.9926399999999997e-01 , -3.2752199999999998e-01 -1.0096685678428705e+00 , -2.8861026229250797e-02 , 9.5275824000000000e+00 , -4.9457000000000001e-02 , 5.3099800000000003e-02 , 9.9736400000000003e-01 -8.9915091165153616e-01 , -1.1770281592517007e-01 , 1.0138176800000000e+01 , -1.0751900000000000e-01 , -1.1162800000000000e-02 , 9.9414000000000002e-01 -9.5586237682369801e-01 , 6.7907052778696464e-02 , 1.0001656000000001e+01 , -2.7722100000000000e-01 , 4.0045799999999998e-01 , 8.7337399999999998e-01 -9.6362514153898782e-01 , 1.7754840337734179e-01 , 1.0083722399999999e+01 , -8.8966299999999998e-02 , 6.4588100000000004e-01 , 7.5823700000000005e-01 -9.1122151531052165e-01 , 2.0096743139532802e-01 , 1.0457550400000001e+01 , 8.9991399999999999e-01 , 4.2196600000000001e-01 , -1.1000100000000000e-01 -1.1934567392521469e+00 , 6.9063078072037265e-01 , 9.2115368000000011e+00 , -1.2308600000000000e-01 , -6.6651800000000005e-01 , 7.3525799999999997e-01 -1.1965883269699966e+00 , 7.8219255056859160e-01 , 9.3029943999999993e+00 , -1.3408900000000001e-01 , -5.2567900000000001e-01 , 8.4004900000000005e-01 -1.2080978591714961e+00 , 8.8635383243282506e-01 , 9.3533928000000000e+00 , -2.7799999999999999e-03 , -2.8383199999999997e-01 , 9.5887000000000000e-01 -1.2290440710016159e+00 , 1.0008546351580450e+00 , 9.3622535999999990e+00 , -4.5416000000000001e-01 , 6.9536200000000004e-01 , 5.5696599999999996e-01 -1.2856782680877914e+00 , 1.1546567149792422e+00 , 9.1785168000000006e+00 , 6.7146799999999995e-01 , 6.1516999999999999e-01 , 4.1315499999999999e-01 -1.1092220951952996e+00 , 1.0689536906314256e+00 , 1.0228064000000000e+01 , 7.6278299999999999e-01 , -6.4285099999999995e-01 , -7.0034100000000002e-02 -1.1790739883976904e+00 , 1.2403082421224072e+00 , 9.9814384000000000e+00 , -7.9851000000000005e-01 , -2.6506400000000002e-01 , -5.4048399999999996e-01 -1.2126895681608110e+00 , 1.3726270739934741e+00 , 9.9233335999999994e+00 , -3.1709700000000002e-01 , -3.8230300000000000e-01 , -8.6792499999999995e-01 -1.2501572437172512e+00 , 1.5054635985447005e+00 , 9.8422656000000011e+00 , -6.7325200000000002e-02 , 2.4937100000000000e-02 , 9.9741899999999994e-01 -1.2664657815913811e+00 , 1.6208250738382839e+00 , 9.8807560000000016e+00 , 6.2087800000000004e-01 , -4.8424299999999998e-01 , -6.1645799999999995e-01 -1.2843397485030366e+00 , 1.7389179990147814e+00 , 9.9067976000000009e+00 , 7.5219100000000005e-01 , 5.9529299999999996e-01 , -2.8255200000000003e-01 -1.3273799641078230e+00 , 1.8681613154336345e+00 , 9.7879983999999993e+00 , -9.1573800000000005e-01 , -1.9098899999999999e-01 , -3.5347800000000001e-01 -1.4619103069712622e+00 , 2.0291187572594520e+00 , 9.1030232000000009e+00 , -8.1735100000000005e-01 , 1.9147900000000001e-01 , -5.4339000000000004e-01 -1.4673974600854593e+00 , 2.1299942398771057e+00 , 9.1937944000000016e+00 , 1.7817400000000000e-01 , 7.6419800000000004e-01 , 6.1988399999999999e-01 -1.3806654744873068e+00 , 2.2175560202734057e+00 , 9.8681408000000008e+00 , -4.6107999999999999e-01 , 8.2055299999999998e-01 , -3.3778500000000000e-01 -1.4369429591021032e+00 , 2.3374424574438852e+00 , 9.6477648000000009e+00 , 3.3041900000000002e-01 , -2.1166099999999999e-01 , -9.1979500000000003e-01 -1.4766949309943831e+00 , 2.4506501722687406e+00 , 9.5277279999999998e+00 , -1.8803700000000001e-01 , 4.8260100000000000e-01 , 8.5541699999999998e-01 -1.4974591659950947e+00 , 2.5625832379934175e+00 , 9.5290695999999997e+00 , 2.6322499999999999e-01 , 2.7010299999999998e-01 , 9.2615199999999998e-01 -1.5239716819105356e+00 , 2.7927552986420929e+00 , 9.6389144000000009e+00 , -6.2761000000000000e-01 , 4.3133800000000000e-01 , -6.4811500000000000e-01 -1.5417823309497192e+00 , 2.9087682637776702e+00 , 9.6651536000000000e+00 , 5.1938399999999996e-01 , 5.5463499999999999e-02 , -8.5273900000000002e-01 -1.5561789887316888e+00 , 3.0285725475089427e+00 , 9.7200448000000002e+00 , -7.5976800000000000e-01 , 6.2457399999999996e-01 , 1.8072099999999999e-01 -1.5454912810979193e+00 , 3.1723251082655728e+00 , 9.9674607999999996e+00 , -9.6089899999999995e-01 , -1.5700000000000000e-01 , 2.2808999999999999e-01 -1.6219630327692127e+00 , 3.2383163308942651e+00 , 9.5471032000000005e+00 , -8.5617799999999999e-01 , -3.8903900000000002e-01 , -3.4001100000000001e-01 -1.6805339683272800e+00 , 3.3083934563918422e+00 , 9.2486648000000002e+00 , 1.4946799999999999e-01 , 9.8742799999999997e-01 , -5.1421300000000003e-02 -2.3179222277127725e+00 , 5.1834698110616184e-01 , 1.2969454400000000e+00 , -2.2156400000000000e-02 , 3.9753899999999998e-01 , 9.1731799999999997e-01 -2.2424250995432859e+00 , 1.8997116337420228e-01 , 1.3164215200000000e+00 , -4.2254699999999999e-02 , 2.4660000000000001e-01 , 9.6819599999999995e-01 -2.2290170770790532e+00 , 1.4478590366684818e-01 , 1.3422405600000000e+00 , -4.0985899999999999e-02 , 2.4742400000000001e-01 , 9.6804000000000001e-01 -2.2120651689094215e+00 , 7.4953276170753425e-02 , 1.3503900000000000e+00 , -8.5978600000000002e-02 , 1.7254000000000000e-01 , 9.8124299999999998e-01 -2.1943622610266189e+00 , -4.1150510370702165e-03 , 1.3546935200000001e+00 , -7.8826300000000002e-02 , 2.1177900000000000e-01 , 9.7413400000000006e-01 -2.1769020137313344e+00 , -7.4156839215250514e-02 , 1.3669936000000000e+00 , -7.0952100000000004e-02 , 2.2881599999999999e-01 , 9.7088099999999999e-01 -2.1591823527510750e+00 , -1.4483484697003002e-01 , 1.3813206400000000e+00 , -6.9854200000000005e-02 , 1.6353799999999999e-01 , 9.8406099999999996e-01 -2.1375022453865178e+00 , -2.4271714863262339e-01 , 1.3810221600000001e+00 , -5.2925100000000003e-02 , 1.4032000000000000e-01 , 9.8869099999999999e-01 -2.1176222668035476e+00 , -3.2304387726641126e-01 , 1.3944152800000000e+00 , -7.0802400000000001e-02 , 2.1003200000000000e-01 , 9.7512699999999997e-01 -2.0974820955731319e+00 , -4.0292460793359508e-01 , 1.4100340000000000e+00 , -3.6836500000000001e-02 , 1.9121299999999999e-01 , 9.8085699999999998e-01 -2.0764144860914637e+00 , -4.9281961085394377e-01 , 1.4231255199999999e+00 , -2.3244600000000001e-02 , 2.1647100000000000e-01 , 9.7601199999999999e-01 -2.0540166694743962e+00 , -5.8217778428690226e-01 , 1.4386204800000000e+00 , -5.9239800000000002e-02 , 1.9413000000000000e-01 , 9.7918499999999997e-01 -2.0306227920962314e+00 , -6.8143680215658398e-01 , 1.4521945600000001e+00 , -7.0007899999999998e-02 , 1.9652100000000000e-01 , 9.7799700000000001e-01 -2.0041174255556369e+00 , -7.9046307225800838e-01 , 1.4640006400000001e+00 , -5.4998199999999997e-02 , 2.1500100000000000e-01 , 9.7506400000000004e-01 -1.9799322416840692e+00 , -8.9052979885829675e-01 , 1.4839551200000001e+00 , -7.0629100000000000e-02 , 2.4591399999999999e-01 , 9.6671499999999999e-01 -1.9543676495279529e+00 , -9.8996355429801142e-01 , 1.5067176000000000e+00 , -7.7415600000000001e-02 , 2.0368800000000001e-01 , 9.7597000000000000e-01 -1.9241617253391139e+00 , -1.1186921464131885e+00 , 1.5201242399999999e+00 , -1.1890199999999999e-01 , 1.4075499999999999e-01 , 9.8287899999999995e-01 -1.8899079129976357e+00 , -1.2661110924742847e+00 , 1.5295352000000000e+00 , -1.2585099999999999e-01 , 1.1996500000000000e-01 , 9.8476900000000001e-01 -1.8506672943612861e+00 , -1.4433087557462989e+00 , 1.5323255200000001e+00 , -8.9784600000000006e-02 , 1.5749800000000000e-01 , 9.8342900000000000e-01 -1.8169768063761058e+00 , -1.5826548673165863e+00 , 1.5555310400000000e+00 , 9.1616000000000006e-03 , -2.7822599999999997e-01 , -9.6047199999999999e-01 -1.7880258482391151e+00 , -1.6834223760877602e+00 , 1.5973057600000000e+00 , -1.2257900000000000e-02 , 2.5447900000000001e-01 , 9.6700100000000000e-01 -1.7477355921401259e+00 , -1.8515158933461704e+00 , 1.6187224800000000e+00 , -3.2144300000000001e-02 , 2.3241400000000001e-01 , 9.7208600000000001e-01 -1.7132661475840478e+00 , -1.9811405783983447e+00 , 1.6584276000000000e+00 , -3.7555100000000001e-02 , 2.3454900000000001e-01 , 9.7137899999999999e-01 -1.6717040893099537e+00 , -2.1491947800491840e+00 , 1.6902713599999999e+00 , 5.6554300000000002e-02 , -2.1545800000000001e-01 , -9.7487400000000002e-01 -1.6245184217089124e+00 , -2.3382431051267787e+00 , 1.7221525600000001e+00 , -6.5131800000000004e-02 , 2.1734300000000001e-01 , 9.7392000000000001e-01 -1.5737226020430932e+00 , -2.5460734465601647e+00 , 1.7549208800000000e+00 , -5.5863299999999998e-02 , 2.1180199999999999e-01 , 9.7571500000000000e-01 -1.5200826787575110e+00 , -2.7645294295553580e+00 , 1.7923275999999999e+00 , -5.1389900000000002e-02 , 2.0349500000000001e-01 , 9.7772700000000001e-01 -1.4635548426011076e+00 , -2.9924526670485871e+00 , 1.8347720800000000e+00 , -5.1444700000000003e-02 , 2.1943199999999999e-01 , 9.7427100000000000e-01 -1.4000562270926067e+00 , -3.2495911443187611e+00 , 1.8783647200000000e+00 , -6.0903199999999998e-02 , 2.2625700000000001e-01 , 9.7216199999999997e-01 -1.3334471168337760e+00 , -3.5168786871069120e+00 , 1.9288201119999999e+00 , -5.6378200000000003e-02 , 2.2627600000000000e-01 , 9.7243000000000002e-01 -1.2605075879708656e+00 , -3.8149176713880557e+00 , 1.9834886480000000e+00 , -5.5889399999999999e-02 , 2.1538399999999999e-01 , 9.7492900000000005e-01 -1.1790679615560493e+00 , -4.1423227307329222e+00 , 2.0433305599999998e+00 , -6.0541699999999997e-02 , 2.0887600000000001e-01 , 9.7606700000000002e-01 -1.0846745118728940e+00 , -4.5291571479569770e+00 , 2.1059000800000001e+00 , -6.1921900000000002e-02 , 2.0947199999999999e-01 , 9.7585200000000005e-01 -9.8334079454482914e-01 , -4.9357775866279265e+00 , 2.1794364000000002e+00 , -6.4567600000000003e-02 , 2.2280800000000001e-01 , 9.7272199999999998e-01 -8.7275099686113466e-01 , -5.3814358826802717e+00 , 2.2628277600000000e+00 , 7.0019200000000004e-02 , -2.1726899999999999e-01 , -9.7359700000000005e-01 -7.3851689371039853e-01 , -5.9276985668155495e+00 , 2.3529905599999998e+00 , 6.0169899999999998e-02 , -2.1855600000000000e-01 , -9.7396799999999994e-01 -6.0194534929087196e-01 , -6.4731616908749352e+00 , 2.4624869600000001e+00 , -4.4251899999999997e-02 , 2.2828799999999999e-01 , 9.7258800000000001e-01 -4.4195014770472651e-01 , -7.1178049772740781e+00 , 2.5858611200000001e+00 , -4.9981900000000003e-02 , 2.1719800000000000e-01 , 9.7484700000000002e-01 -2.4566858109410195e-01 , -7.9114040501035259e+00 , 2.7264212800000003e+00 , -5.1106100000000002e-02 , 2.1102299999999999e-01 , 9.7614400000000001e-01 -1.4327153467062592e-02 , -8.8448284391148082e+00 , 2.8927963200000000e+00 , -4.0186300000000001e-02 , 3.0287700000000001e-01 , 9.5218199999999997e-01 --1.5809033261578920e-01 , -9.4906421836989789e+00 , 3.0922288000000000e+00 , -1.7267600000000001e-02 , 5.1967500000000000e-01 , 8.5418899999999998e-01 --2.7197637585122569e-01 , -9.8571169437990651e+00 , 3.3094016000000002e+00 , -1.2236500000000000e-01 , 6.6059400000000001e-01 , 7.4070400000000003e-01 --3.5118442239830472e-01 , -1.0056964805188764e+01 , 3.5337712000000003e+00 , -1.7266999999999999e-01 , 6.1096700000000004e-01 , 7.7259500000000003e-01 --6.4313582938841884e-01 , -1.1184302289837055e+01 , 3.8158919999999998e+00 , -2.6906999999999998e-01 , 3.0074299999999998e-01 , 9.1496200000000005e-01 --2.1294499330210579e+00 , -1.7470492603448527e+01 , 4.5100504000000008e+00 , 4.1514699999999999e-01 , 2.2643500000000000e-01 , 8.8112400000000002e-01 --2.3386473159674610e+00 , -1.8126669559804458e+01 , 4.9239911999999997e+00 , 4.2440899999999998e-01 , 2.3117199999999999e-01 , 8.7546400000000002e-01 --3.1035902684575518e+00 , -2.1119889378532736e+01 , 5.6149567999999999e+00 , -3.5308899999999999e-01 , -5.9648400000000001e-01 , -7.2078799999999998e-01 --3.5896967439017642e+00 , -2.2876054201500970e+01 , 6.2600064000000000e+00 , 9.9200600000000005e-01 , 7.5547199999999995e-02 , 1.0107900000000000e-01 --3.7214440037742458e+00 , -2.3123374276925695e+01 , 6.7540583999999999e+00 , -9.7880999999999996e-01 , -1.2849099999999999e-01 , -1.5943900000000000e-01 --3.7229983779114750e+00 , -2.2831978569748941e+01 , 7.1725960000000004e+00 , 9.6977899999999995e-01 , 1.0410800000000001e-01 , 2.2065599999999999e-01 --3.7097695918296703e+00 , -2.2484210201982691e+01 , 7.5733288000000005e+00 , -9.7321800000000003e-01 , -1.0362900000000000e-01 , -2.0520200000000000e-01 --3.9392856515911108e+00 , -2.3111398003196634e+01 , 8.1585783999999997e+00 , 9.7416899999999995e-01 , 1.6982200000000000e-01 , 1.4884400000000000e-01 --3.9922359988853806e+00 , -2.3024505549292883e+01 , 8.6156375999999995e+00 , 9.6132600000000001e-01 , 2.2131300000000001e-01 , 1.6392699999999999e-01 --4.0464259874954429e+00 , -2.2939349996482505e+01 , 9.0739032000000002e+00 , -9.5719900000000002e-01 , -2.8939399999999998e-01 , -4.6743399999999999e-03 --4.0999355240901378e+00 , -2.2857027735936395e+01 , 9.5342175999999998e+00 , -9.5282599999999995e-01 , -3.0334200000000000e-01 , -1.0355000000000000e-02 --4.1479095173833924e+00 , -2.2746523979043250e+01 , 9.9883856000000009e+00 , -9.4844499999999998e-01 , -3.1502799999999997e-01 , 3.4784700000000002e-02 --4.1950019670689231e+00 , -2.2637751598731818e+01 , 1.0444092800000000e+01 , -9.5834799999999998e-01 , -2.7964699999999998e-01 , 5.8021499999999997e-02 --4.2514177744740742e+00 , -2.2559414156120862e+01 , 1.0910553600000000e+01 , -9.6740099999999996e-01 , -2.5016500000000003e-01 , 3.9397200000000000e-02 --4.3039040090607914e+00 , -2.2462771135085152e+01 , 1.1373686399999999e+01 , -9.6959600000000001e-01 , -2.4438199999999999e-01 , 1.2706000000000000e-02 --4.3461013700590012e+00 , -2.2330510040318831e+01 , 1.1826596000000000e+01 , -9.7330899999999998e-01 , -2.2492000000000001e-01 , 4.5604300000000000e-02 --4.3911884283326517e+00 , -2.2208597318258214e+01 , 1.2284851200000000e+01 , -9.7063800000000000e-01 , -2.3601700000000000e-01 , 4.6453800000000003e-02 --4.3581751571115461e+00 , -2.1806095352147139e+01 , 1.2634624000000001e+01 , 9.8941599999999996e-01 , 1.4504900000000001e-01 , 3.9989600000000002e-03 --4.5071233174703753e+00 , -2.2050747538807549e+01 , 1.3243856000000001e+01 , -9.7122500000000000e-01 , -2.3247599999999999e-01 , -5.1733300000000003e-02 --4.5207598159922933e+00 , -2.1811250701275060e+01 , 1.3659856000000000e+01 , 9.7228800000000004e-01 , 2.1389700000000000e-01 , 9.4364699999999996e-02 --4.6218379563915217e+00 , -2.1875884194492077e+01 , 1.4213656000000000e+01 , -9.5491800000000004e-01 , 5.9936799999999998e-02 , -2.9075499999999999e-01 --4.6703450634798607e+00 , -2.1756468709725986e+01 , 1.4690808000000001e+01 , -4.9820300000000001e-01 , 8.2079700000000000e-01 , -2.7944099999999999e-01 --4.7335224654565282e+00 , -2.1681942560707814e+01 , 1.5194688000000001e+01 , 4.8986200000000002e-01 , -8.1926800000000000e-01 , 2.9805300000000001e-01 --4.7841328581138214e+00 , -2.1561573934915732e+01 , 1.5681200000000000e+01 , -6.6663899999999998e-01 , 7.4320799999999998e-01 , -5.6874800000000003e-02 --4.8344168083884247e+00 , -2.1441245251216536e+01 , 1.6172912000000004e+01 , -9.3175399999999997e-01 , -8.7277900000000005e-02 , 3.5244399999999998e-01 --4.8672813096966907e+00 , -2.1258703742748576e+01 , 1.6634464000000001e+01 , -9.5917600000000003e-01 , -2.3079400000000000e-01 , 1.6344800000000001e-01 --4.8948856636616114e+00 , -2.1059709239844150e+01 , 1.7089255999999999e+01 , 9.8101000000000005e-01 , 5.0626499999999998e-02 , -1.8723600000000001e-01 --4.9132603553718672e+00 , -2.0825629721695819e+01 , 1.7525224000000001e+01 , 9.8630099999999998e-01 , 2.6510800000000001e-02 , -1.6281399999999999e-01 --4.9472667144555862e+00 , -2.0643213564018193e+01 , 1.7996240000000000e+01 , 9.8516400000000004e-01 , 3.0273999999999999e-02 , -1.6892599999999999e-01 -6.1718418278268916e-01 , -3.2336957600550704e+00 , 6.8760607999999994e+00 , -4.0496700000000002e-01 , 6.7306200000000005e-01 , -6.1886099999999999e-01 --4.8194321836496599e+00 , -1.9676694735497179e+01 , 1.8530695999999999e+01 , 9.9470099999999995e-01 , 2.9081300000000001e-02 , 9.8610400000000001e-02 --5.2205376603481106e+00 , -2.0594933737806773e+01 , 1.9800951999999999e+01 , -9.8878999999999995e-01 , -1.0315600000000000e-01 , -1.0794800000000000e-01 --7.1874611943658575e+00 , -2.6115725390702863e+01 , 2.4612824000000000e+01 , -3.7740999999999997e-02 , 9.9632100000000001e-01 , -7.6941300000000004e-02 -6.1019039706169909e-01 , -2.9690188950991603e+00 , 7.2923208000000006e+00 , 6.3691600000000001e-02 , -9.8167300000000002e-01 , 1.7961500000000000e-01 -6.1136105340810021e-01 , -2.8922406687885811e+00 , 7.3890511999999999e+00 , 1.5318300000000000e-02 , -9.9648099999999995e-01 , 8.2402400000000001e-02 -5.8165312832633687e-01 , -2.9059773412756256e+00 , 7.5622112000000001e+00 , 4.7208200000000000e-01 , 8.1855599999999995e-01 , -3.2726699999999997e-01 -6.1636690160048380e-01 , -2.7342921048742648e+00 , 7.5785184000000001e+00 , 7.7762200000000004e-01 , 5.8428599999999997e-01 , -2.3219300000000001e-01 -5.7457491286598650e-01 , -2.7788217189037594e+00 , 7.7860088000000003e+00 , -7.2005200000000003e-01 , -6.8656099999999998e-01 , 1.0078700000000000e-01 -5.7531733248755779e-01 , -2.7012919900798718e+00 , 7.8863896000000002e+00 , -7.4219800000000002e-01 , -6.4463000000000004e-01 , 1.8328800000000001e-01 -5.3733385833937786e-01 , -2.7295885895327130e+00 , 8.0909784000000009e+00 , -2.7421299999999998e-01 , -9.0415599999999996e-01 , 3.2758199999999998e-01 -5.8764537317585952e-01 , -2.5198402319908748e+00 , 8.0623472000000014e+00 , -7.9807099999999997e-01 , -1.4870700000000001e-01 , 5.8392599999999995e-01 -6.0348883256418873e-01 , -2.4022682097636023e+00 , 8.1222512000000009e+00 , -8.1130300000000000e-01 , -7.1842000000000003e-02 , 5.8019500000000002e-01 -5.9158082842910220e-01 , -2.3589145787470560e+00 , 8.2611224000000014e+00 , -5.6887699999999997e-01 , -1.0740500000000000e-01 , 8.1537899999999996e-01 -6.2771900427507177e-01 , -2.1929997818465816e+00 , 8.2648975999999994e+00 , 6.2828099999999998e-01 , 4.8510499999999998e-02 , -7.7647299999999997e-01 -5.3953670315996960e-01 , -2.3356985759005102e+00 , 8.6234895999999992e+00 , 5.7201900000000006e-01 , 2.1675699999999999e-02 , 8.1995399999999996e-01 -6.4463147484212557e-01 , -1.9995615058192180e+00 , 8.4222391999999999e+00 , 6.7516399999999999e-01 , 3.6067100000000002e-01 , -6.4348200000000000e-01 -8.8530533391633881e-01 , -1.3461723085948329e+00 , 7.8008288000000006e+00 , -5.6044499999999997e-01 , 1.6356900000000001e-02 , 8.2803000000000004e-01 -9.0171569495620929e-01 , -1.2434370070118761e+00 , 7.8451535999999997e+00 , 3.4945700000000002e-01 , -5.8276399999999995e-01 , -7.3366600000000004e-01 -9.1415851875241438e-01 , -1.1467798924661969e+00 , 7.8953856000000000e+00 , 3.4945700000000002e-01 , -5.8276399999999995e-01 , -7.3366600000000004e-01 -5.8672024676161505e-01 , -1.8255353539965475e+00 , 9.0364840000000015e+00 , 7.6182099999999997e-01 , -3.5401500000000002e-01 , -5.4249599999999998e-01 -5.8197751734199588e-01 , -1.7540306555357312e+00 , 9.1637592000000012e+00 , 9.9706600000000001e-01 , -3.8546299999999999e-02 , -6.6128400000000004e-02 -6.0439917458122250e-01 , -1.6233145403905560e+00 , 9.2060040000000001e+00 , 9.8053000000000001e-01 , -1.1098200000000000e-01 , 1.6200100000000001e-01 -6.6191338179619885e-01 , -1.4177939016781562e+00 , 9.1262879999999988e+00 , -4.7917700000000002e-01 , 5.1771199999999995e-01 , 7.0877599999999996e-01 -6.6440819310905064e-01 , -1.3310058768468860e+00 , 9.2308392000000001e+00 , 4.1297600000000001e-01 , 8.7334900000000004e-01 , 2.5828800000000002e-01 -5.8049488948124961e-01 , -1.4212672956898693e+00 , 9.6398295999999988e+00 , 5.5042300000000000e-01 , 6.5378400000000003e-01 , -5.1923100000000000e-01 -8.5570201599718754e-01 , -7.8218579876281824e-01 , 8.7755064000000012e+00 , -1.8907399999999999e-01 , 5.7614900000000002e-01 , 7.9517499999999997e-01 -8.9580592824781680e-01 , -6.2829643979568894e-01 , 8.7362672000000003e+00 , 4.0080199999999999e-01 , 4.3922000000000003e-02 , -9.1511100000000001e-01 -8.6540317066970185e-01 , -6.1175072253089935e-01 , 8.9541784000000000e+00 , -5.4098100000000003e-02 , -9.3040400000000001e-01 , 3.6252200000000001e-01 -7.9040277140181181e-01 , -6.7295501261498636e-01 , 9.3459256000000011e+00 , -3.5278300000000001e-01 , 2.2824400000000000e-01 , -9.0744100000000005e-01 -8.4338388798072739e-01 , -4.9365115005232063e-01 , 9.2563399999999998e+00 , 3.3486500000000002e-01 , 3.4691699999999998e-01 , 8.7607900000000005e-01 -8.9678831347066090e-01 , -3.1947173680307905e-01 , 9.1625215999999998e+00 , -8.7798399999999999e-01 , -4.1792000000000001e-01 , -2.3342499999999999e-01 -8.4172505221849070e-01 , -3.3130213845793532e-01 , 9.4926384000000006e+00 , -3.6968499999999999e-01 , -2.4331700000000001e-01 , 8.9673300000000000e-01 -8.0546184447322022e-01 , -3.0668053281363594e-01 , 9.7599391999999998e+00 , -5.8675100000000001e-02 , 9.8935099999999998e-01 , 1.3319600000000001e-01 -6.8763593948897728e-01 , -4.0401799523753557e-01 , 1.0368963200000000e+01 , -2.2277400000000000e-01 , 7.4128000000000005e-01 , -6.3314700000000002e-01 -9.2476463804913944e-01 , 5.7623907552195375e-02 , 9.5065536000000002e+00 , 7.2665199999999996e-01 , 5.3908900000000004e-01 , -4.2586400000000002e-01 -8.6938694453820498e-01 , 6.1583384160158516e-02 , 9.8674751999999994e+00 , -4.3142500000000000e-01 , 8.1535400000000002e-01 , 3.8609500000000002e-01 -8.4815248304662894e-01 , 1.2346302082653504e-01 , 1.0085771200000000e+01 , -1.8022099999999999e-01 , -9.6400200000000003e-01 , 1.9550200000000001e-01 -8.4866282403295346e-01 , 2.1883673442476725e-01 , 1.0216644800000001e+01 , -5.0639000000000001e-01 , -8.0368300000000004e-01 , 3.1251200000000001e-01 -1.1038902641547450e+00 , 6.5024361461941305e-01 , 9.1922136000000005e+00 , -1.6282199999999999e-01 , 9.5762700000000001e-01 , 2.3757200000000001e-01 -1.0881331235219203e+00 , 7.1488895693359211e-01 , 9.3832199999999997e+00 , -2.0810600000000001e-01 , 7.2351900000000002e-01 , -6.5818900000000002e-01 -1.1176167300421715e+00 , 8.3762205598667316e-01 , 9.3662576000000008e+00 , -6.7657500000000004e-01 , 3.9417600000000003e-01 , -6.2199000000000004e-01 -9.7768270147428415e-01 , 7.7024912306156423e-01 , 1.0161472800000000e+01 , 3.5716799999999999e-01 , -9.6754199999999999e-02 , 9.2901500000000004e-01 -1.1994721044672889e+00 , 1.1010952508667518e+00 , 9.2157696000000016e+00 , 6.7146799999999995e-01 , 6.1516999999999999e-01 , 4.1315400000000002e-01 -1.2368652253799035e+00 , 1.2255940441801720e+00 , 9.1512688000000004e+00 , -7.8774200000000005e-01 , -5.9251399999999999e-01 , -1.6849400000000000e-01 -1.0707300339656969e+00 , 1.1656086833598249e+00 , 1.0119862400000001e+01 , 6.9182600000000005e-01 , 3.5289799999999999e-01 , 6.2995299999999999e-01 -1.0999257888714966e+00 , 1.2928294088781165e+00 , 1.0114558400000000e+01 , -3.2057500000000000e-01 , 7.7678000000000003e-01 , 5.4207499999999997e-01 -1.1836905912551012e+00 , 1.4600006408515742e+00 , 9.8132496000000007e+00 , -3.2333899999999999e-01 , -1.4489299999999999e-01 , -9.3512399999999996e-01 -1.2182844054792328e+00 , 1.5850228512726763e+00 , 9.7718368000000009e+00 , 6.0530899999999999e-01 , -1.5062000000000000e-01 , -7.8161099999999994e-01 -1.2237208094432199e+00 , 1.6906611100178162e+00 , 9.8809639999999987e+00 , -7.9496200000000003e-02 , -4.3540400000000001e-01 , 8.9671800000000002e-01 -1.2198403933528152e+00 , 1.7959010382676912e+00 , 1.0049371200000000e+01 , 6.5089300000000005e-01 , 3.1569000000000003e-01 , -6.9041900000000000e-01 -1.3681321059131681e+00 , 1.9666720808487701e+00 , 9.3475272000000018e+00 , -9.1420699999999999e-01 , 8.2269999999999999e-03 , -4.0516500000000000e-01 -1.4231248147499178e+00 , 2.0854159450865897e+00 , 9.1633640000000014e+00 , 7.9245200000000005e-01 , -8.1503999999999993e-02 , 6.0446400000000000e-01 -1.3638127678053538e+00 , 2.1729108533552894e+00 , 9.6640408000000004e+00 , -6.8927899999999998e-01 , 7.2023499999999996e-01 , -7.8461100000000006e-02 -1.4025747607506291e+00 , 2.2888403032187719e+00 , 9.5783863999999994e+00 , -2.2387599999999999e-01 , 3.2197999999999999e-01 , 9.1989600000000005e-01 -1.4248215071152377e+00 , 2.4013540331079333e+00 , 9.5934664000000005e+00 , -6.3715800000000000e-01 , -3.9550000000000002e-01 , -6.6152000000000000e-01 -1.4377125827396600e+00 , 2.5146347671699782e+00 , 9.6683360000000000e+00 , 5.2167799999999998e-01 , 2.0844399999999999e-01 , 8.2728699999999999e-01 -1.4843922343547826e+00 , 2.6239558863373325e+00 , 9.5252216000000001e+00 , 1.1165500000000000e-01 , -2.0209099999999999e-01 , -9.7298099999999998e-01 -1.4893013141676446e+00 , 2.7417647844384812e+00 , 9.6577592000000010e+00 , 3.9703400000000000e-01 , -6.7329499999999998e-01 , 6.2372899999999998e-01 -1.5135825141940278e+00 , 2.8557902723867552e+00 , 9.6649767999999998e+00 , -9.3294699999999997e-01 , -1.7670300000000000e-01 , 3.1366600000000000e-01 -1.5311041039851760e+00 , 2.9737003461827749e+00 , 9.7111008000000005e+00 , 7.6062700000000005e-01 , 1.6903599999999999e-01 , -6.2679600000000002e-01 -1.5450076619342021e+00 , 3.0964501810137826e+00 , 9.7963184000000005e+00 , -9.8486099999999999e-01 , -1.7087100000000000e-01 , -2.9205800000000001e-02 -1.5785024946615613e+00 , 3.2059806949911973e+00 , 9.7357383999999989e+00 , 6.9608999999999999e-01 , 3.3588100000000003e-02 , 7.1716899999999995e-01 -1.6640388495244580e+00 , 3.2570750303266198e+00 , 9.2644832000000008e+00 , 2.6174199999999997e-01 , 9.6350000000000002e-01 , -5.6206399999999997e-02 -2.2769152547845213e+00 , 5.3624492041662219e-01 , 1.2663912799999999e+00 , -9.6225900000000003e-02 , 1.6965300000000000e-01 , 9.8079499999999997e-01 -2.2637499556163898e+00 , 4.9939646339139010e-01 , 1.2914791999999999e+00 , -9.6225900000000003e-02 , 1.6965200000000000e-01 , 9.8079499999999997e-01 -2.1789274377702870e+00 , 1.8071807978117937e-01 , 1.3201499200000000e+00 , 6.8744299999999994e-02 , -2.8097200000000000e-01 , -9.5725099999999996e-01 -2.1629853683926621e+00 , 1.2802614902634191e-01 , 1.3398423200000000e+00 , -4.9396500000000003e-02 , 2.2694300000000001e-01 , 9.7265500000000005e-01 -2.1423482495290607e+00 , 4.9827418116670463e-02 , 1.3425515200000000e+00 , -1.0167500000000000e-01 , 1.5958400000000000e-01 , 9.8193399999999997e-01 -2.1224500235283137e+00 , -2.8974949997639055e-02 , 1.3477161600000001e+00 , -6.6570599999999994e-02 , 2.0642199999999999e-01 , 9.7619599999999995e-01 -2.1033229311938628e+00 , -9.0218102239755016e-02 , 1.3664475999999999e+00 , -7.4526099999999998e-02 , 2.1992300000000001e-01 , 9.7266600000000003e-01 -2.0834315057784338e+00 , -1.6066782242909872e-01 , 1.3814340000000001e+00 , -6.3076199999999999e-02 , 1.7058000000000001e-01 , 9.8332299999999995e-01 -2.0611701248306074e+00 , -2.4876740220016336e-01 , 1.3873848799999999e+00 , -9.2867500000000006e-02 , 1.4777100000000001e-01 , 9.8465199999999997e-01 -2.0375363130438231e+00 , -3.3734680643108650e-01 , 1.3959451199999999e+00 , -4.6877400000000000e-02 , 1.9489899999999999e-01 , 9.7970199999999996e-01 -2.0136146226047380e+00 , -4.2542215578250842e-01 , 1.4069337600000000e+00 , -2.7570799999999999e-02 , 2.1122299999999999e-01 , 9.7704899999999995e-01 -1.9899384378766813e+00 , -5.0556337633989967e-01 , 1.4257203199999999e+00 , -5.3183700000000000e-02 , 1.8469099999999999e-01 , 9.8135700000000003e-01 -1.9619952857138012e+00 , -6.1346976732554870e-01 , 1.4323118400000001e+00 , -9.3103900000000003e-02 , 1.9384899999999999e-01 , 9.7660300000000000e-01 -1.9370238943655793e+00 , -7.0298883836807269e-01 , 1.4517068000000000e+00 , -7.8854499999999994e-02 , 2.0806500000000000e-01 , 9.7493099999999999e-01 -1.9090006756258144e+00 , -8.0129741891979034e-01 , 1.4690280000000000e+00 , 7.7109800000000006e-02 , -2.0193900000000001e-01 , -9.7635799999999995e-01 -1.8788302323443764e+00 , -9.1036627627432587e-01 , 1.4851147199999999e+00 , -7.7543899999999999e-02 , 2.3266400000000001e-01 , 9.6946100000000002e-01 -1.8493005475568216e+00 , -1.0187746692524438e+00 , 1.5046656800000000e+00 , -1.1546300000000000e-01 , 1.9761100000000001e-01 , 9.7345700000000002e-01 -1.8112783697487895e+00 , -1.1645592963899247e+00 , 1.5108370400000000e+00 , -1.2723100000000001e-01 , 1.5320500000000001e-01 , 9.7997000000000001e-01 -1.7744251832066498e+00 , -1.3022332064677449e+00 , 1.5258432000000000e+00 , -1.3669700000000001e-01 , 1.1834799999999999e-01 , 9.8351800000000000e-01 -1.7279562054940032e+00 , -1.4880589093562722e+00 , 1.5264609600000001e+00 , -2.5406999999999999e-02 , 2.2404299999999999e-01 , 9.7424800000000000e-01 -1.6961786120976812e+00 , -1.5881472456307235e+00 , 1.5657303199999999e+00 , 5.7435799999999999e-03 , 2.8322799999999998e-01 , 9.5903499999999997e-01 -1.6576590032142551e+00 , -1.7261907908124812e+00 , 1.5944041599999998e+00 , -3.5092600000000002e-02 , 2.5036300000000000e-01 , 9.6751600000000004e-01 -1.6175589745561818e+00 , -1.8643424724631279e+00 , 1.6274064799999999e+00 , -4.8311100000000003e-02 , 2.4032500000000001e-01 , 9.6948999999999996e-01 -1.5711921528862280e+00 , -2.0318319768943809e+00 , 1.6557860000000000e+00 , -5.0315100000000001e-02 , 2.1926999999999999e-01 , 9.7436599999999995e-01 -1.5173789370790494e+00 , -2.2283890679408502e+00 , 1.6806326400000000e+00 , -7.8906900000000002e-02 , 2.1124899999999999e-01 , 9.7424200000000005e-01 -1.4676762765234219e+00 , -2.4056488564482619e+00 , 1.7177980800000001e+00 , -6.5568000000000001e-02 , 2.1818399999999999e-01 , 9.7370299999999999e-01 -1.4112290756397070e+00 , -2.6026656020352119e+00 , 1.7555791999999999e+00 , -6.5246899999999997e-02 , 2.1485099999999999e-01 , 9.7446500000000003e-01 -1.3470812876605720e+00 , -2.8392219782565782e+00 , 1.7904628800000000e+00 , -5.4202800000000002e-02 , 2.1554000000000001e-01 , 9.7499000000000002e-01 -1.2829427917962186e+00 , -3.0652498390775360e+00 , 1.8354647200000000e+00 , 6.1047799999999999e-02 , -2.2026499999999999e-01 , -9.7352799999999995e-01 -1.2097303139733637e+00 , -3.3313185734581046e+00 , 1.8800775999999999e+00 , -6.5601900000000005e-02 , 2.3717500000000000e-01 , 9.6924900000000003e-01 -1.1384855725477578e+00 , -3.5768371438716660e+00 , 1.9374632400000000e+00 , -7.0193300000000000e-02 , 2.2763400000000000e-01 , 9.7121400000000002e-01 -1.0465801503743948e+00 , -3.9110858532207606e+00 , 1.9875397600000000e+00 , -7.5380600000000006e-02 , 2.1633200000000000e-01 , 9.7340599999999999e-01 -9.4586486672922443e-01 , -4.2763657700108748e+00 , 2.0450214959999999e+00 , -6.5980700000000003e-02 , 2.1182200000000001e-01 , 9.7507900000000003e-01 -8.3841467193553476e-01 , -4.6596179559193160e+00 , 2.1120475200000000e+00 , -6.9745699999999994e-02 , 2.1774700000000000e-01 , 9.7350999999999999e-01 -7.1858827285631821e-01 , -5.0938417526883422e+00 , 2.1869649600000001e+00 , -7.4936699999999995e-02 , 2.2495699999999999e-01 , 9.7148299999999999e-01 -5.8305828298225815e-01 , -5.5763902479473542e+00 , 2.2716188800000001e+00 , -7.2924100000000006e-02 , 2.2448100000000001e-01 , 9.7174600000000000e-01 -4.3675115919692220e-01 , -6.0981682066441767e+00 , 2.3700517600000000e+00 , 5.7197900000000003e-02 , -2.3324000000000000e-01 , -9.7073500000000001e-01 -2.7294411662328644e-01 , -6.6778882464593270e+00 , 2.4828792800000001e+00 , -5.4976299999999999e-02 , 2.2757200000000000e-01 , 9.7220799999999996e-01 -7.5604951153130262e-02 , -7.3880616731225501e+00 , 2.6103614400000001e+00 , -6.1035100000000002e-02 , 2.2187000000000001e-01 , 9.7316400000000003e-01 --1.5907113397428185e-01 , -8.2252045360013710e+00 , 2.7584886399999999e+00 , 6.0508899999999997e-02 , -2.2355000000000000e-01 , -9.7281300000000004e-01 --4.1884227902960802e-01 , -9.1509789477219829e+00 , 2.9358523200000000e+00 , -6.1979300000000001e-02 , 3.5897699999999999e-01 , 9.3128599999999995e-01 --5.9737393922356485e-01 , -9.7288874064555024e+00 , 3.1441664000000000e+00 , -1.2024600000000001e-01 , 5.6953299999999996e-01 , 8.1312600000000002e-01 --7.7039709856909422e-01 , -1.0272146820986286e+01 , 3.3727064000000002e+00 , -2.7679300000000001e-01 , 4.9721100000000001e-01 , 8.2229399999999997e-01 --8.9149490016600330e-01 , -1.0598804648568963e+01 , 3.6121248000000001e+00 , 3.6170000000000002e-01 , -4.5132100000000003e-01 , -8.1577100000000002e-01 --2.3440376649681589e+00 , -1.6045250655116821e+01 , 4.1648432000000000e+00 , -4.2245100000000002e-01 , -2.2502500000000000e-01 , -8.7800800000000001e-01 --2.5948060399059294e+00 , -1.6794003853955449e+01 , 4.5533352000000002e+00 , -4.2035099999999997e-01 , -2.2126799999999999e-01 , -8.7996900000000000e-01 --2.8099351559706891e+00 , -1.7392807619732039e+01 , 4.9558879999999998e+00 , -1.7774899999999999e-01 , -1.9303600000000001e-01 , -9.6495699999999995e-01 --3.9123237022643238e+00 , -2.1278203653903439e+01 , 5.7526632000000006e+00 , -8.9283699999999999e-01 , -1.8064900000000000e-01 , -4.1256399999999999e-01 --4.0377820988905464e+00 , -2.1481166126247413e+01 , 6.2100656000000001e+00 , -8.9052900000000002e-01 , -1.5882099999999999e-01 , -4.2630200000000001e-01 --4.0749381375672336e+00 , -2.1358070167882172e+01 , 6.6288112000000003e+00 , -8.7353099999999995e-01 , -2.6516299999999998e-01 , -4.0820499999999998e-01 --4.1254173230723232e+00 , -2.1288079684023703e+01 , 7.0550240000000004e+00 , -9.4025400000000003e-01 , -2.2335099999999999e-01 , -2.5697700000000001e-01 --4.3439673172610176e+00 , -2.1810749462457583e+01 , 7.5918720000000004e+00 , -9.3483200000000000e-01 , -1.9637499999999999e-01 , -2.9584800000000000e-01 --4.4453027883386707e+00 , -2.1909710341664820e+01 , 8.0648432000000003e+00 , -9.0353200000000000e-01 , -2.1221999999999999e-01 , -3.7228000000000000e-01 --4.4165040431727798e+00 , -2.1549235415351120e+01 , 8.4426544000000003e+00 , -9.3814900000000001e-01 , -1.8290300000000001e-01 , -2.9397899999999999e-01 --4.6554294777433167e+00 , -2.2119012172177229e+01 , 9.0367336000000016e+00 , -9.3644899999999998e-01 , -3.1565900000000002e-01 , -1.5304599999999999e-01 --4.7075161807844275e+00 , -2.2034809760392850e+01 , 9.4857119999999995e+00 , -9.3416399999999999e-01 , -3.2730300000000001e-01 , -1.4216200000000001e-01 --4.7484586527513777e+00 , -2.1914497539611929e+01 , 9.9263080000000006e+00 , -9.4220999999999999e-01 , -3.1896099999999999e-01 , 1.0249100000000000e-01 --4.7763465235168008e+00 , -2.1747607310850114e+01 , 1.0353342399999999e+01 , -9.3520999999999999e-01 , -3.0948199999999998e-01 , 1.7205799999999999e-01 --4.7642289338544224e+00 , -2.1450893393649093e+01 , 1.0737664000000001e+01 , -9.5852599999999999e-01 , -1.7041000000000001e-01 , 2.2844700000000001e-01 --4.7435496484931186e+00 , -2.1128886351556929e+01 , 1.1107488000000000e+01 , -9.5560599999999996e-01 , -1.3144000000000000e-01 , 2.6370700000000002e-01 --4.7297433865977601e+00 , -2.0830556740669110e+01 , 1.1478944799999999e+01 , 9.8439800000000000e-01 , 5.2885700000000001e-02 , -1.6782200000000000e-01 --4.7765823171384207e+00 , -2.0732981184909445e+01 , 1.1921506400000002e+01 , 9.8502500000000004e-01 , 8.1078100000000000e-02 , -1.5216099999999999e-01 --4.7194937961454713e+00 , -2.0302147456050111e+01 , 1.2232747200000000e+01 , 9.9585900000000005e-01 , 8.3238699999999999e-02 , -3.6558100000000003e-02 --4.8883091987019496e+00 , -2.0585420500280751e+01 , 1.2835968000000001e+01 , 9.6624399999999999e-01 , 1.4231700000000000e-01 , 2.1475000000000000e-01 --4.8913439159900198e+00 , -2.0344305151497270e+01 , 1.3225344000000000e+01 , -9.4108999999999998e-01 , -1.4819099999999999e-01 , -3.0395699999999998e-01 --5.7407475835830644e+00 , -2.2699172168082171e+01 , 1.4827152000000000e+01 , -6.0033400000000003e-01 , 5.6614399999999998e-01 , -5.6487200000000004e-01 --5.8049167428590600e+00 , -2.2619753526707420e+01 , 1.5349752000000001e+01 , 4.4990400000000003e-01 , -8.9149699999999998e-01 , -5.3109299999999998e-02 --5.8614691160029864e+00 , -2.2512474306856646e+01 , 1.5864760000000000e+01 , 6.3079300000000005e-01 , -7.6775899999999997e-01 , -1.1245700000000000e-01 --5.6019261059417698e+00 , -2.1463864692614834e+01 , 1.5880776000000001e+01 , -8.0816100000000002e-01 , 5.6827200000000000e-01 , -1.5473600000000001e-01 --5.1813483927926915e+00 , -1.9963774876209730e+01 , 1.5605696000000000e+01 , -9.6559899999999999e-01 , -1.0193600000000000e-01 , 2.3922099999999999e-01 --5.2067873657407180e+00 , -1.9781744328181798e+01 , 1.6039895999999999e+01 , 9.7261299999999995e-01 , 1.3265399999999999e-01 , -1.9085800000000000e-01 --5.2623534507886198e+00 , -1.9685088932303195e+01 , 1.6529008000000001e+01 , -9.5915300000000003e-01 , -2.2659299999999999e-01 , 1.6935800000000001e-01 --5.3119293817978610e+00 , -1.9570346948946767e+01 , 1.7014064000000001e+01 , 9.7394099999999995e-01 , 6.5756300000000004e-02 , -2.1705900000000000e-01 --5.2765549412457098e+00 , -1.9212995903262527e+01 , 1.7346032000000001e+01 , -9.7220700000000004e-01 , -6.3201800000000002e-02 , 2.2542999999999999e-01 --5.3634024263202047e+00 , -1.9197068344245668e+01 , 1.7907111999999998e+01 , 9.9733200000000000e-01 , 7.1425400000000000e-02 , -1.5075500000000000e-02 --5.2576087470254738e+00 , -1.8648442392065785e+01 , 1.8101904000000001e+01 , 9.8772499999999996e-01 , 1.4101600000000000e-01 , 6.7183099999999996e-02 --5.6007635486412237e+00 , -1.9318084995573095e+01 , 1.9184543999999999e+01 , 9.8366600000000004e-01 , 7.2081400000000004e-02 , 1.6493800000000000e-01 --5.5879655622718412e+00 , -1.9016351854097245e+01 , 1.9573192000000002e+01 , 9.8040499999999997e-01 , 9.6962199999999998e-02 , 1.7147599999999999e-01 -4.6502553780022304e-01 , -2.5510740290903584e+00 , 7.6703608000000010e+00 , -8.9066699999999999e-01 , -3.5768699999999998e-01 , 2.8066300000000000e-01 -3.8952017256696636e-01 , -2.6689931613159326e+00 , 7.9543536000000001e+00 , -9.5767700000000000e-01 , -2.8162999999999999e-01 , 5.9487800000000000e-02 -3.4628225225763720e-01 , -2.7018354696045419e+00 , 8.1668464000000007e+00 , -4.0277299999999999e-01 , 5.3808699999999998e-01 , -7.4043000000000003e-01 -4.8231324817966570e-01 , -2.3043641184385226e+00 , 7.9445984000000003e+00 , -9.5266499999999998e-01 , 1.5807800000000000e-01 , 2.5969399999999998e-01 -4.3218613414608287e-01 , -2.3531088887223621e+00 , 8.1768824000000002e+00 , 6.0005600000000003e-01 , -3.8734099999999999e-01 , -6.9992799999999999e-01 -5.2119102035057829e-01 , -2.0743840068052206e+00 , 8.0561591999999997e+00 , -7.5583299999999998e-01 , -1.2834900000000000e-02 , 6.5463899999999997e-01 -2.8090864214107314e-01 , -2.5554369780423425e+00 , 8.7952040000000000e+00 , 4.5887000000000000e-01 , -6.6564299999999998e-01 , -5.8852199999999999e-01 -2.0660403109740377e-01 , -2.6457243619320590e+00 , 9.1165015999999994e+00 , -5.2849999999999997e-01 , -2.3313000000000000e-01 , -8.1629499999999999e-01 -7.3773603604265148e-01 , -1.3888093034676769e+00 , 7.7843239999999998e+00 , 6.1589799999999995e-01 , -3.8665899999999997e-01 , -6.8641399999999997e-01 -7.6660446906856383e-01 , -1.2618374475918630e+00 , 7.7988112000000003e+00 , 6.1589899999999997e-01 , -3.8665899999999997e-01 , -6.8641300000000005e-01 -5.5250297364293788e-01 , -1.6576785155251827e+00 , 8.5078519999999997e+00 , 1.5665499999999999e-01 , 4.3532300000000002e-01 , -8.8653999999999999e-01 -5.8639643705365407e-01 , -1.5148212904553020e+00 , 8.5179399999999994e+00 , 9.4178200000000004e-02 , -8.1807799999999997e-01 , 5.6734300000000004e-01 -5.9071827058476045e-01 , -1.4348999692446931e+00 , 8.6151488000000001e+00 , 1.4895600000000001e-01 , -8.7339699999999998e-01 , 4.6367100000000000e-01 -5.4673191927043874e-01 , -1.4544704141648541e+00 , 8.8616911999999992e+00 , 3.0215599999999998e-01 , 9.3047400000000002e-01 , -2.0717300000000000e-01 -5.4686030790969498e-01 , -1.3784658767495306e+00 , 8.9754672000000006e+00 , 7.1108199999999999e-01 , 4.5786399999999999e-01 , -5.3359500000000004e-01 -6.1319782347293739e-01 , -1.1737034306455230e+00 , 8.8833751999999997e+00 , -1.8758100000000000e-01 , 2.5631399999999999e-01 , 9.4821800000000001e-01 -4.7234975947366298e-01 , -1.3685373275825197e+00 , 9.4515583999999997e+00 , -7.5484300000000004e-01 , -6.3592300000000002e-01 , -1.6066800000000001e-01 -6.7456486794434989e-01 , -9.0866699788586658e-01 , 8.9101655999999991e+00 , -2.0356099999999999e-01 , 4.3593100000000001e-01 , 8.7665700000000002e-01 -7.6219447026962039e-01 , -6.7513948085133224e-01 , 8.7335007999999998e+00 , 1.8907399999999999e-01 , -5.7614900000000002e-01 , -7.9517499999999997e-01 -7.6150706236275711e-01 , -6.0385265737343019e-01 , 8.8447391999999994e+00 , -4.0080199999999999e-01 , -4.3922500000000003e-02 , 9.1511100000000001e-01 -5.1906289865103439e-01 , -9.5263612524019026e-01 , 9.8024024000000001e+00 , 5.5949000000000004e-01 , -7.7777700000000005e-01 , 2.8641499999999998e-01 -6.4620185124992235e-01 , -6.5174941274730225e-01 , 9.4836112000000004e+00 , 5.0613200000000003e-01 , -5.3241099999999997e-01 , 6.7850500000000002e-01 -6.7984508272671151e-01 , -5.1462007753488592e-01 , 9.4863047999999992e+00 , 5.4335999999999995e-01 , -2.5567699999999999e-01 , 7.9961899999999997e-01 -7.5177059695621340e-01 , -3.1747939531241398e-01 , 9.3470487999999996e+00 , -9.2574800000000002e-01 , -3.7811699999999998e-01 , -4.1374799999999998e-03 -7.5825086699064426e-01 , -2.2679552452184337e-01 , 9.4453911999999995e+00 , -7.5486900000000001e-01 , -2.5611400000000001e-01 , 6.0380299999999998e-01 -6.7496890774729001e-01 , -2.7049293455342660e-01 , 9.8905944000000012e+00 , 3.8295299999999999e-01 , -8.8755099999999998e-01 , 2.5612600000000002e-01 -6.1254550047751599e-01 , -2.7559138057863430e-01 , 1.0273616000000001e+01 , -2.6508199999999998e-01 , 9.5215200000000000e-01 , -1.5211400000000000e-01 -8.0777994125783548e-01 , 9.2294540490269972e-02 , 9.6378328000000018e+00 , 7.0381000000000005e-01 , 5.1078199999999996e-01 , -4.9371399999999999e-01 -8.0808663287880056e-01 , 1.7815088139768109e-01 , 9.7689352000000014e+00 , -8.1457000000000002e-01 , -5.7954899999999998e-01 , -2.4464199999999998e-02 -7.0612667801897477e-01 , 1.3414783407931630e-01 , 1.0324555199999999e+01 , 5.7877699999999999e-01 , 5.9331000000000000e-01 , -5.5946399999999996e-01 -1.0089088618373387e+00 , 6.0741112488301119e-01 , 9.1912568000000014e+00 , -1.6282199999999999e-01 , 9.5762700000000001e-01 , 2.3757100000000000e-01 -1.0525281648175622e+00 , 7.4050352970732680e-01 , 9.1286072000000011e+00 , -3.4016200000000002e-01 , -7.4419900000000005e-01 , 5.7485399999999998e-01 -7.7936839608908759e-01 , 5.1194062029067067e-01 , 1.0460306400000000e+01 , 8.9868300000000001e-01 , 3.9563999999999999e-01 , -1.8931000000000001e-01 -1.0153333286932824e+00 , 8.6698412765935373e-01 , 9.5481432000000002e+00 , -9.6181600000000000e-01 , 2.4604999999999999e-01 , -1.1987399999999999e-01 -1.0976631667955150e+00 , 1.0375594106247901e+00 , 9.3108463999999991e+00 , -1.6928000000000001e-01 , 2.1905200000000000e-01 , 9.6091700000000002e-01 -1.1749454704399496e+00 , 1.1977574493061716e+00 , 9.0789575999999990e+00 , -4.3864300000000001e-01 , -7.5947900000000002e-01 , -4.8039900000000002e-01 -1.1365025157034787e+00 , 1.2490878436346164e+00 , 9.3940359999999998e+00 , -4.6848200000000001e-01 , -2.4195800000000001e-01 , -8.4969499999999998e-01 -9.9413446355987478e-01 , 1.2235137385557815e+00 , 1.0232816800000000e+01 , -4.6958100000000003e-01 , -7.5025600000000003e-01 , -4.6541300000000002e-01 -1.0872440102867715e+00 , 1.3963060112112582e+00 , 9.9244984000000009e+00 , -6.3707999999999998e-01 , -3.4964699999999999e-01 , -6.8693199999999999e-01 -1.1374942701411088e+00 , 1.5301164976237260e+00 , 9.8246376000000009e+00 , -2.3465200000000000e-01 , 4.1580400000000001e-01 , 8.7866100000000003e-01 -1.1846902640597838e+00 , 1.6591279743812903e+00 , 9.7319320000000005e+00 , 6.3730100000000001e-01 , -1.4539099999999999e-01 , -7.5677499999999998e-01 -1.0802482016714152e+00 , 1.7076508874503147e+00 , 1.0451164800000001e+01 , -3.3262199999999997e-01 , -6.7794699999999997e-01 , -6.5555300000000005e-01 -1.2222225378996918e+00 , 1.8831035253183508e+00 , 9.8450008000000011e+00 , -7.7989299999999995e-01 , -2.5178299999999998e-01 , -5.7303800000000005e-01 -1.2927314103983609e+00 , 2.0137671285977281e+00 , 9.6126231999999998e+00 , -8.7360700000000002e-01 , 4.2402099999999998e-01 , -2.3878300000000000e-01 -1.3187036742371712e+00 , 2.1262189709193442e+00 , 9.6229295999999991e+00 , -6.8927899999999998e-01 , 7.2023499999999996e-01 , -7.8461100000000006e-02 -1.3507884929485698e+00 , 2.2403025158437648e+00 , 9.6004760000000005e+00 , -1.3494700000000001e-01 , 3.1226000000000000e-02 , 9.9036100000000005e-01 -1.3306683829478054e+00 , 2.3492059246771944e+00 , 9.8942760000000014e+00 , -3.3571499999999999e-01 , 9.1421399999999997e-01 , 2.2695599999999999e-01 -1.4264146067657999e+00 , 2.4629245645450757e+00 , 9.4777871999999999e+00 , 9.9157700000000001e-02 , 2.1508800000000000e-01 , 9.7154799999999997e-01 -1.4507843617116767e+00 , 2.5727074765832882e+00 , 9.5008440000000007e+00 , -1.0711800000000000e-01 , 7.3528600000000000e-02 , 9.9152399999999996e-01 -1.3798108356122962e+00 , 2.7114903512786679e+00 , 1.0148192000000000e+01 , -3.6487399999999998e-01 , -6.9029399999999996e-01 , -6.2478900000000004e-01 -1.4836012468314750e+00 , 2.8027535915137074e+00 , 9.6535784000000007e+00 , -7.6424899999999996e-01 , 1.5470000000000000e-01 , -6.2609199999999998e-01 -1.5050692598654247e+00 , 2.9187163213450726e+00 , 9.7014288000000004e+00 , 5.1938399999999996e-01 , 5.5463499999999999e-02 , -8.5273900000000002e-01 -1.5064845414930741e+00 , 3.0502062180189355e+00 , 9.8905944000000012e+00 , 2.4043900000000001e-01 , -5.9710300000000005e-01 , 7.6528300000000005e-01 -1.5344023803308242e+00 , 3.1693981392621300e+00 , 9.9031471999999994e+00 , -9.4289000000000001e-01 , 6.0216899999999997e-02 , 3.2761499999999999e-01 -1.6035268994514849e+00 , 3.2469521786240811e+00 , 9.5965968000000004e+00 , -3.8681399999999999e-01 , -4.9646800000000002e-01 , -7.7710699999999999e-01 -1.6776290261334184e+00 , 3.3074225805930282e+00 , 9.2379423999999997e+00 , 1.4946799999999999e-01 , 9.8742799999999997e-01 , -5.1421399999999999e-02 -2.2228081208903689e+00 , 5.1828386707597707e-01 , 1.2605184000000000e+00 , -9.6226000000000006e-02 , 1.6965200000000000e-01 , 9.8079499999999997e-01 -2.2071566232854232e+00 , 4.7384293465376115e-01 , 1.2790740800000000e+00 , -9.6225900000000003e-02 , 1.6965200000000000e-01 , 9.8079499999999997e-01 -2.1139966724460821e+00 , 1.6491369256384503e-01 , 1.3174687999999999e+00 , 7.6789700000000002e-02 , -2.5429299999999999e-01 , -9.6407399999999999e-01 -2.0929350292472706e+00 , 9.6221723995707942e-02 , 1.3251127999999999e+00 , -7.8516799999999998e-02 , 2.3503599999999999e-01 , 9.6880999999999995e-01 -2.0731284655140829e+00 , 3.5477527521470043e-02 , 1.3408833599999999e+00 , -6.0227900000000001e-02 , 1.8401699999999999e-01 , 9.8107599999999995e-01 -2.0500274138018351e+00 , -4.3082717491605305e-02 , 1.3465815200000000e+00 , 7.8833700000000007e-02 , -1.9441900000000001e-01 , -9.7774600000000000e-01 -2.0266753704878688e+00 , -1.2120571091775778e-01 , 1.3544054399999998e+00 , -1.0248699999999999e-01 , 2.3090600000000000e-01 , 9.6756399999999998e-01 -2.0045886269544950e+00 , -1.9138947201358825e-01 , 1.3702529600000000e+00 , -1.3392999999999999e-01 , 1.8802300000000000e-01 , 9.7299100000000005e-01 -1.9774931503773745e+00 , -2.8763175017280584e-01 , 1.3716496800000000e+00 , -6.7437100000000000e-02 , 1.8160000000000001e-01 , 9.8105799999999999e-01 -1.9538301193914338e+00 , -3.5794403312234424e-01 , 1.3918277600000000e+00 , -6.8967299999999995e-02 , 1.8632199999999999e-01 , 9.8006499999999996e-01 -1.9266687161902651e+00 , -4.4571045607995430e-01 , 1.4036536000000002e+00 , -1.0063600000000000e-01 , 2.0752300000000001e-01 , 9.7304000000000002e-01 -1.9001970047028010e+00 , -5.3398437456901915e-01 , 1.4183394400000000e+00 , 1.0956399999999999e-01 , -1.8380900000000000e-01 , -9.7683699999999996e-01 -1.8679461914509239e+00 , -6.4150120033247848e-01 , 1.4259459999999999e+00 , -1.0782100000000000e-01 , 2.0225099999999999e-01 , 9.7338000000000002e-01 -1.8380567100572740e+00 , -7.3902082341442155e-01 , 1.4414950399999999e+00 , -1.0018700000000000e-01 , 2.0424300000000001e-01 , 9.7377999999999998e-01 -1.8033105655622754e+00 , -8.5559636619661505e-01 , 1.4510016800000001e+00 , -1.0942499999999999e-01 , 2.2521900000000000e-01 , 9.6814400000000000e-01 -1.7725721820653755e+00 , -9.5491163342412211e-01 , 1.4732368800000000e+00 , -1.3384599999999999e-01 , 2.1006800000000000e-01 , 9.6848199999999995e-01 -1.7324149472470654e+00 , -1.0906767069163923e+00 , 1.4812563200000000e+00 , -1.5189000000000000e-01 , 1.8117400000000000e-01 , 9.7165100000000004e-01 -1.6934935003502214e+00 , -1.2173518743137270e+00 , 1.4977018400000000e+00 , -1.4810300000000001e-01 , 1.4316100000000001e-01 , 9.7855499999999995e-01 -1.6450834996718036e+00 , -1.3913041203071468e+00 , 1.4988468799999999e+00 , -7.2867199999999993e-02 , 1.9392200000000001e-01 , 9.7830700000000004e-01 -1.6086634084063469e+00 , -1.4998783310445325e+00 , 1.5319438400000001e+00 , 1.4767199999999999e-02 , 2.7175300000000002e-01 , 9.6225400000000005e-01 -1.5699713467397483e+00 , -1.6179116653239136e+00 , 1.5650168799999999e+00 , -5.1165400000000000e-02 , 2.7797400000000000e-01 , 9.5922499999999999e-01 -1.5213044790244372e+00 , -1.7746828658879856e+00 , 1.5881319199999999e+00 , -6.8642599999999998e-02 , 2.3943800000000001e-01 , 9.6848199999999995e-01 -1.4749262159579870e+00 , -1.9213336564938976e+00 , 1.6197968000000000e+00 , -6.7641699999999999e-02 , 2.5233699999999998e-01 , 9.6527200000000002e-01 -1.4231297000609802e+00 , -2.0871648181979969e+00 , 1.6499744800000000e+00 , -8.4711599999999998e-02 , 2.1563900000000000e-01 , 9.7279199999999999e-01 -1.3637953375514822e+00 , -2.2829734728667610e+00 , 1.6773285599999999e+00 , -7.9222500000000001e-02 , 2.1695999999999999e-01 , 9.7296099999999996e-01 -1.3026408861175023e+00 , -2.4784931633388192e+00 , 1.7110360000000000e+00 , -6.5221399999999999e-02 , 2.2423000000000001e-01 , 9.7235099999999997e-01 -1.2387111938803739e+00 , -2.6836694990298193e+00 , 1.7488722400000001e+00 , -7.6543600000000003e-02 , 2.2310700000000000e-01 , 9.7178399999999998e-01 -1.1689514032633899e+00 , -2.9073032152218872e+00 , 1.7887614400000000e+00 , -7.7040100000000000e-02 , 2.2418399999999999e-01 , 9.7149700000000005e-01 -1.0880501714822670e+00 , -3.1720335911417976e+00 , 1.8278103200000000e+00 , -7.8705499999999998e-02 , 2.1943399999999999e-01 , 9.7244799999999998e-01 -1.0061080309985704e+00 , -3.4349269455722018e+00 , 1.8757626400000000e+00 , -8.3642300000000003e-02 , 2.3253699999999999e-01 , 9.6898399999999996e-01 -9.1476168181993756e-01 , -3.7285369151068464e+00 , 1.9273495519999999e+00 , -8.7967600000000007e-02 , 2.3149800000000001e-01 , 9.6884999999999999e-01 -8.1390490999489074e-01 , -4.0504549913864976e+00 , 1.9839808800000001e+00 , 5.3484400000000001e-02 , 1.1531100000000000e-01 , 9.9188900000000002e-01 -7.0221549966690122e-01 , -4.4122186393089855e+00 , 2.0460689840000001e+00 , -8.3732799999999996e-02 , 2.1920700000000001e-01 , 9.7207900000000003e-01 -5.7213100908486458e-01 , -4.8327955756214891e+00 , 2.1126850400000001e+00 , -7.7941999999999997e-02 , 2.2632200000000000e-01 , 9.7092900000000004e-01 -4.3275855068480373e-01 , -5.2825162813437885e+00 , 2.1908514399999999e+00 , 7.8684500000000004e-02 , -2.2614300000000001e-01 , -9.7091099999999997e-01 -2.7217279618407830e-01 , -5.8006519630037117e+00 , 2.2779764000000000e+00 , -7.2978299999999996e-02 , 2.3002700000000001e-01 , 9.7044399999999997e-01 -1.0074853607311396e-01 , -6.3469829522898475e+00 , 2.3809790400000002e+00 , -7.3791599999999999e-02 , 2.3690300000000000e-01 , 9.6872700000000000e-01 --1.0035949534106203e-01 , -6.9922880900404145e+00 , 2.4976108799999999e+00 , -7.3069200000000001e-02 , 2.3345199999999999e-01 , 9.6961900000000001e-01 --3.2947233796758724e-01 , -7.7249575957211611e+00 , 2.6331540799999997e+00 , -6.7529599999999995e-02 , 2.2421300000000000e-01 , 9.7219800000000001e-01 --6.1496109900099993e-01 , -8.6452063640146513e+00 , 2.7901056799999999e+00 , -6.8761799999999998e-02 , 2.4450300000000000e-01 , 9.6720700000000004e-01 --9.3334367206769375e-01 , -9.6606337596922316e+00 , 2.9790768000000001e+00 , -2.1783200000000000e-01 , 4.0562999999999999e-01 , 8.8770099999999996e-01 --1.3721054529876717e+00 , -1.1082064242978728e+01 , 3.2086464000000001e+00 , -3.6489800000000000e-01 , 3.9733099999999999e-01 , 8.4200799999999998e-01 --1.8838143153599121e+00 , -1.2726586047609105e+01 , 3.4957072000000000e+00 , -2.5071300000000002e-01 , 3.2026399999999999e-01 , 9.1354999999999997e-01 --2.5179648673578567e+00 , -1.4761282782377034e+01 , 3.8603208000000002e+00 , 3.8401700000000000e-01 , 1.9726500000000000e-01 , 9.0200800000000003e-01 --2.8523413828654780e+00 , -1.5727648108960899e+01 , 4.2311952000000002e+00 , -4.0033400000000002e-01 , -2.1552099999999999e-01 , -8.9066400000000001e-01 --3.0147014957872100e+00 , -1.6089199031105874e+01 , 4.5890591999999994e+00 , 4.0613199999999999e-01 , 2.3976300000000000e-01 , 8.8180000000000003e-01 --4.2390419881743275e+00 , -2.0004621710593931e+01 , 5.3160816000000004e+00 , -9.4456700000000005e-01 , -2.5353700000000001e-01 , -2.0859500000000000e-01 --4.3947115244699546e+00 , -2.0292021331159969e+01 , 5.7594440000000002e+00 , 9.9402500000000005e-01 , 7.5465500000000005e-02 , 7.8867900000000005e-02 --4.4833366807749675e+00 , -2.0353175442370190e+01 , 6.1849807999999999e+00 , 9.7913300000000003e-01 , 8.2566399999999998e-02 , 1.8569200000000000e-01 --4.4604396421526236e+00 , -2.0052578578849747e+01 , 6.5592872000000009e+00 , 9.8190400000000000e-01 , 4.3426800000000002e-02 , 1.8433500000000000e-01 --4.4172320208522180e+00 , -1.9687803330624821e+01 , 6.9141664000000000e+00 , 9.8175800000000002e-01 , 2.1351100000000000e-03 , 1.9012499999999999e-01 --4.7537134525768545e+00 , -2.0539035848627119e+01 , 7.4922504000000005e+00 , -9.5160800000000001e-01 , -9.7568100000000005e-02 , -2.9141600000000001e-01 --4.8081580649178761e+00 , -2.0481415757729621e+01 , 7.9140432000000001e+00 , -9.1321099999999999e-01 , -1.0738200000000001e-01 , -3.9308300000000002e-01 --4.9867801630756432e+00 , -2.0813155192638582e+01 , 8.4271583999999997e+00 , -9.4510799999999995e-01 , -1.5540599999999999e-01 , -2.8743800000000003e-01 --5.1498105912612013e+00 , -2.1085705192920429e+01 , 8.9422808000000007e+00 , 9.7009400000000001e-01 , 1.3530400000000001e-01 , 2.0151900000000000e-01 --5.1990626209101229e+00 , -2.1001352625351551e+01 , 9.3766055999999995e+00 , 9.7552099999999997e-01 , 1.8500000000000000e-01 , 1.1888500000000000e-01 --5.2522180925637674e+00 , -2.0929676231515934e+01 , 9.8161512000000002e+00 , 9.6921400000000002e-01 , 2.1250100000000000e-01 , -1.2436999999999999e-01 --5.1672529173350865e+00 , -2.0442150194707274e+01 , 1.0129992000000001e+01 , 9.8130799999999996e-01 , 5.9676500000000000e-02 , -1.8296000000000001e-01 --5.3556090643981547e+00 , -2.0771936555140140e+01 , 1.0698102400000000e+01 , 9.6452000000000004e-01 , 7.2508900000000001e-02 , -2.5385700000000000e-01 --5.1852059257259260e+00 , -2.0041065924796676e+01 , 1.0915607999999999e+01 , -9.6345499999999995e-01 , -2.0844600000000001e-02 , 2.6705600000000002e-01 --5.0953510203964951e+00 , -1.9551487538226922e+01 , 1.1198602400000000e+01 , 9.7912600000000005e-01 , -7.0305199999999998e-02 , -1.9070999999999999e-01 --5.1323967900732148e+00 , -1.9439405212175668e+01 , 1.1615049600000001e+01 , 9.9897199999999997e-01 , 5.6736099999999999e-03 , -4.4966300000000001e-02 --4.9402311208663283e+00 , -1.8669317299816136e+01 , 1.1762584000000000e+01 , 9.9609700000000001e-01 , 3.4674299999999998e-02 , 8.1170500000000007e-02 --5.2407558844494737e+00 , -1.9300606099635438e+01 , 1.2491520000000000e+01 , 9.9248599999999998e-01 , 8.0579899999999996e-02 , 9.2075000000000004e-02 --5.2484541587099480e+00 , -1.9101396583242739e+01 , 1.2877880000000001e+01 , -9.8461100000000001e-01 , -1.0321500000000000e-01 , -1.4102400000000001e-01 --5.7197504365420926e+00 , -2.0181151918287480e+01 , 1.3874408000000001e+01 , 9.8082400000000003e-01 , 1.3478999999999999e-01 , 1.4076900000000001e-01 --5.7416792065271736e+00 , -1.9302930534758847e+01 , 1.5488176000000001e+01 , -9.6418700000000002e-01 , -1.5375800000000001e-01 , 2.1610599999999999e-01 --5.9049388466387418e+00 , -1.9495303877253697e+01 , 1.6137447999999999e+01 , -9.6028400000000003e-01 , -1.5484000000000001e-01 , 2.3211899999999999e-01 --5.7894468618394779e+00 , -1.8958400847164345e+01 , 1.6355328000000000e+01 , -9.6028400000000003e-01 , -1.5484000000000001e-01 , 2.3211899999999999e-01 --5.6400468008533773e+00 , -1.8339070258956923e+01 , 1.6504463999999999e+01 , -9.6293899999999999e-01 , 4.2877400000000003e-02 , 2.6629000000000003e-01 --5.6461956202587462e+00 , -1.8123947712254072e+01 , 1.6906528000000002e+01 , 9.7358900000000004e-01 , -1.9294499999999999e-02 , -2.2749000000000000e-01 --5.6665162042636785e+00 , -1.7941516306860979e+01 , 1.7333656000000001e+01 , 9.8019000000000001e-01 , 5.2537100000000003e-02 , -1.9096399999999999e-01 --5.6774954758860572e+00 , -1.7735543814768850e+01 , 1.7747576000000002e+01 , 9.9017299999999997e-01 , 1.2200200000000000e-01 , 6.8364800000000003e-02 --5.5448303237755363e+00 , -1.7174997715748002e+01 , 1.7896608000000001e+01 , 9.8675800000000002e-01 , 3.3963599999999997e-02 , 1.5860099999999999e-01 --5.9433393447840812e+00 , -1.7907645412092439e+01 , 1.9044975999999998e+01 , 9.7207900000000003e-01 , 1.0337900000000000e-01 , 2.1065300000000001e-01 --5.8815164421363475e+00 , -1.7516918574390953e+01 , 1.9337320000000002e+01 , 9.7207900000000003e-01 , 1.0337900000000000e-01 , 2.1065300000000001e-01 --5.3237835926271515e-02 , -3.2107319056581680e+00 , 8.5914160000000006e+00 , -4.1665000000000002e-01 , 8.3503200000000000e-01 , 3.5933799999999999e-01 -9.7789427936280982e-02 , -2.7995560788781013e+00 , 8.3771968000000001e+00 , 7.7621600000000002e-01 , -2.9859100000000000e-01 , 5.5527599999999999e-01 --1.8764338398643154e-01 , -3.3520723649904056e+00 , 9.1577584000000005e+00 , 9.9236899999999995e-01 , 1.0362700000000000e-01 , -6.6821300000000000e-02 --1.7556758561035668e-01 , -3.2429256057796056e+00 , 9.2645976000000001e+00 , -9.6567800000000004e-01 , 2.5853300000000001e-01 , -2.5025100000000002e-02 -1.5431829077268389e-01 , -2.4631722465914372e+00 , 8.6095328000000002e+00 , -3.5143099999999999e-01 , 4.4243600000000001e-02 , 9.3516800000000000e-01 -2.2249579993681201e-01 , -2.2491125236458638e+00 , 8.5639496000000008e+00 , 4.5872800000000002e-01 , -9.8231100000000002e-02 , -8.8313100000000000e-01 -2.3787379314385371e-01 , -2.1446870305892158e+00 , 8.6428647999999999e+00 , -4.5872800000000002e-01 , 9.8231200000000005e-02 , 8.8313100000000000e-01 -3.8937760571230506e-01 , -1.7684750778583873e+00 , 8.3763856000000008e+00 , 9.5279400000000000e-02 , -1.8054100000000001e-01 , 9.7894199999999998e-01 -3.8987889778253582e-01 , -1.6986026907079514e+00 , 8.4861263999999998e+00 , 7.7514299999999994e-02 , -6.4734100000000006e-01 , 7.5824899999999995e-01 -4.1066685167991368e-01 , -1.5906080592386025e+00 , 8.5469767999999995e+00 , 1.9336300000000001e-01 , -7.1454899999999999e-01 , 6.7233200000000004e-01 -4.4879524897026024e-01 , -1.4480171921142682e+00 , 8.5566592000000004e+00 , -1.9562299999999999e-01 , 7.5543199999999999e-01 , -6.2534299999999998e-01 -4.1991053965139247e-01 , -1.4348247270085910e+00 , 8.7530007999999988e+00 , 4.9354700000000001e-02 , -9.1503599999999996e-01 , 4.0034199999999998e-01 -4.2742376315483877e-01 , -1.3507546761075293e+00 , 8.8503655999999999e+00 , -1.9503599999999999e-01 , 7.5488800000000000e-01 , -6.2618300000000005e-01 -4.1465292131999765e-01 , -1.3018881740944988e+00 , 9.0058559999999996e+00 , 1.6995099999999999e-01 , -7.3425300000000004e-01 , 6.5725900000000004e-01 -4.6455349150105629e-01 , -1.1410997986442655e+00 , 8.9818424000000014e+00 , 5.9607500000000002e-01 , -2.7240100000000000e-01 , 7.5530900000000001e-01 -5.5948585129258377e-01 , -9.0166693388169383e-01 , 8.8149744000000005e+00 , -2.6152100000000001e-02 , 4.2236800000000002e-01 , 9.0604700000000005e-01 -6.3665299484778171e-01 , -6.9897504614582084e-01 , 8.6938040000000001e+00 , 2.5495600000000002e-01 , -5.5260500000000001e-01 , -7.9349000000000003e-01 -6.8271116318912850e-01 , -5.5393842445515951e-01 , 8.6645696000000001e+00 , -4.0080199999999999e-01 , -4.3922400000000000e-02 , 9.1511100000000001e-01 -4.6047256713054807e-01 , -8.4990851435937742e-01 , 9.4986911999999997e+00 , 5.7741200000000004e-01 , -3.3921299999999999e-01 , -7.4265000000000003e-01 -4.8439513573929038e-01 , -7.3397773652725951e-01 , 9.5521783999999990e+00 , -2.3220199999999999e-01 , 4.3834499999999998e-01 , -8.6829500000000004e-01 -4.6779358724722275e-01 , -6.7951023128031895e-01 , 9.7399504000000015e+00 , -8.9056500000000005e-01 , 1.9506300000000001e-02 , 4.5443800000000001e-01 -5.4973819764303444e-01 , -4.7395044027780120e-01 , 9.5971480000000007e+00 , -3.8132199999999999e-01 , 4.3160900000000002e-01 , -8.1750000000000000e-01 -5.3789175831182034e-01 , -4.1037998778568907e-01 , 9.7731159999999999e+00 , 1.9454199999999999e-01 , -6.3650700000000004e-01 , 7.4633200000000000e-01 -6.5868125502283159e-01 , -1.5564589713997190e-01 , 9.4821448000000004e+00 , 6.2707800000000002e-01 , 5.2587299999999997e-02 , -7.7717999999999998e-01 -6.8420036388700445e-01 , -4.0314687162886997e-02 , 9.5224760000000011e+00 , -3.4168599999999999e-01 , 6.8699099999999999e-02 , 9.3730000000000002e-01 -7.3803881593547360e-01 , 1.1287822098649403e-01 , 9.4563424000000005e+00 , -3.1859399999999999e-01 , 1.6441500000000001e-01 , 9.3352299999999999e-01 -3.9802146065780919e-01 , -2.4684491252579832e-01 , 1.0886997600000001e+01 , -6.6792499999999999e-01 , 4.0610399999999998e-02 , -7.4312000000000000e-01 -6.6725972052064986e-01 , 1.8742332448403620e-01 , 1.0006232000000001e+01 , -3.9777299999999999e-01 , -9.1434599999999999e-01 , 7.5823199999999993e-02 -8.9173381385704142e-01 , 5.4366373283772762e-01 , 9.2661888000000001e+00 , -2.5306700000000001e-02 , 9.9497199999999997e-01 , 9.6899700000000005e-02 -9.6417610064174974e-01 , 7.0527567249356515e-01 , 9.1087848000000005e+00 , 6.4840999999999996e-02 , -8.8217500000000004e-01 , 4.6643600000000002e-01 -6.9860302067653191e-01 , 4.9498503435361374e-01 , 1.0337867200000000e+01 , -6.7620199999999997e-01 , -3.0803999999999998e-01 , 6.6922499999999996e-01 -6.7951334464523905e-01 , 5.6973614667002215e-01 , 1.0583577600000000e+01 , -4.1253800000000002e-01 , -9.1091699999999998e-01 , -6.6301399999999996e-03 -9.4045122445292595e-01 , 9.2638256423319265e-01 , 9.6214423999999994e+00 , -9.0870200000000001e-01 , -4.0332899999999999e-01 , 1.0764300000000000e-01 -1.0741403809100201e+00 , 1.1375300310753982e+00 , 9.1748663999999991e+00 , -3.9892800000000000e-01 , -6.8297200000000002e-01 , -6.1188699999999996e-01 -1.0840255549172357e+00 , 1.2297912334765411e+00 , 9.2712536000000014e+00 , -1.8690999999999999e-01 , 1.7633400000000000e-02 , -9.8221899999999995e-01 -8.5099446606104445e-01 , 1.1293971860698533e+00 , 1.0499316800000001e+01 , -2.0549000000000001e-01 , -9.2897099999999999e-01 , 3.0787300000000001e-01 -8.2914921512898832e-01 , 1.2184225039298524e+00 , 1.0778432000000000e+01 , -7.5135700000000005e-01 , 3.1205300000000002e-01 , -5.8145199999999997e-01 -8.9103606131401825e-01 , 1.3698639484932638e+00 , 1.0663148000000000e+01 , -8.5327100000000000e-01 , 1.0017500000000000e-01 , 5.1175599999999999e-01 -8.6930500271744915e-01 , 1.4677486303099427e+00 , 1.0959891200000001e+01 , 9.9883599999999995e-01 , 3.4965999999999997e-02 , -3.3230599999999999e-02 -9.8559062272953102e-01 , 1.6455010302464996e+00 , 1.0565200800000001e+01 , -4.0494799999999997e-01 , -5.6886999999999999e-01 , -7.1582400000000002e-01 -1.1389531455930322e+00 , 1.8265554330781795e+00 , 9.9523703999999995e+00 , -8.7535499999999999e-01 , -1.7894099999999999e-01 , -4.4914799999999999e-01 -1.1709896931805657e+00 , 1.9449969174576245e+00 , 9.9568112000000006e+00 , -7.8707000000000005e-01 , -3.2636799999999999e-01 , -5.2345500000000000e-01 -1.2337992533536379e+00 , 2.0712246004377048e+00 , 9.7956424000000002e+00 , -8.5470599999999997e-01 , 3.8670399999999999e-01 , -3.4632000000000002e-01 -1.2343561347792962e+00 , 2.1805237008071083e+00 , 9.9798784000000005e+00 , 5.5646499999999999e-01 , -7.2018400000000005e-01 , 4.1434399999999999e-01 -1.2268803839773774e+00 , 2.2948415646381317e+00 , 1.0213660000000001e+01 , 7.1802900000000003e-01 , -6.5057200000000004e-01 , 2.4736700000000000e-01 -1.3558726181140908e+00 , 2.4158884440195423e+00 , 9.6456224000000006e+00 , -8.2425700000000002e-01 , -7.6813099999999995e-02 , 5.6098099999999995e-01 -1.3951184971572832e+00 , 2.5267715156220292e+00 , 9.5982711999999992e+00 , 5.5912499999999998e-01 , 2.6025700000000002e-01 , 7.8717599999999999e-01 -1.4405893772299536e+00 , 2.6340149944744686e+00 , 9.5078328000000010e+00 , 2.6646500000000001e-01 , -3.1445699999999999e-01 , 9.1110500000000005e-01 -1.4373798946234975e+00 , 2.7560834915983006e+00 , 9.7335647999999999e+00 , 1.3520699999999999e-01 , -6.0129600000000005e-01 , 7.8750399999999998e-01 -1.4690664486660747e+00 , 2.8689646661920953e+00 , 9.7314016000000017e+00 , -6.0468100000000002e-01 , 4.7887100000000002e-02 , -7.9502700000000004e-01 -1.5020133476375830e+00 , 2.9814285547303867e+00 , 9.7274495999999999e+00 , -3.5356300000000002e-01 , -7.3445000000000005e-01 , 5.7928999999999997e-01 -1.5136814077711751e+00 , 3.1104741609758273e+00 , 9.8750359999999997e+00 , 9.6967499999999995e-01 , -1.4500700000000000e-01 , -1.9673199999999999e-01 -1.5627734216929461e+00 , 3.2124699639277088e+00 , 9.7540320000000005e+00 , 6.4608500000000002e-01 , -1.6577800000000001e-01 , 7.4504499999999996e-01 -1.6591136750781619e+00 , 3.2571590234864383e+00 , 9.2533032000000013e+00 , 6.2932500000000002e-01 , -5.1953300000000002e-01 , -5.7795799999999997e-01 -2.1680394159886398e+00 , 5.1023781986895145e-01 , 1.2616031200000000e+00 , -9.6225900000000003e-02 , 1.6965300000000000e-01 , 9.8079499999999997e-01 -2.0460522041703326e+00 , 1.5230793462566261e-01 , 1.3142000800000000e+00 , -1.0427699999999999e-01 , 2.1426700000000001e-01 , 9.7119299999999997e-01 -2.0228177772671101e+00 , 8.3844047006857325e-02 , 1.3225034400000000e+00 , -7.5491900000000001e-02 , 2.4556800000000001e-01 , 9.6643500000000004e-01 -2.0008527824665605e+00 , 2.3299006333554528e-02 , 1.3388324800000000e+00 , 8.2208100000000006e-02 , -1.9918600000000000e-01 , -9.7650700000000001e-01 -1.9740738952518004e+00 , -6.2543471621061109e-02 , 1.3391891999999999e+00 , -1.1787599999999999e-01 , 1.5332000000000001e-01 , 9.8112100000000002e-01 -1.9485275530891302e+00 , -1.4040029933759568e-01 , 1.3478742399999999e+00 , -1.0904500000000000e-01 , 1.9837600000000000e-01 , 9.7404100000000005e-01 -1.9216538489145714e+00 , -2.1881270780235340e-01 , 1.3587630399999999e+00 , -9.3985100000000002e-02 , 2.2404700000000000e-01 , 9.7003600000000001e-01 -1.8971330821375423e+00 , -2.8831199067373348e-01 , 1.3774965600000000e+00 , -9.5564200000000002e-02 , 1.8733800000000000e-01 , 9.7763599999999995e-01 -1.8654213572598588e+00 , -3.8471538743879607e-01 , 1.3823398400000000e+00 , 1.1892999999999999e-01 , -1.9143299999999999e-01 , -9.7427399999999997e-01 -1.8344210795469436e+00 , -4.8058194033629276e-01 , 1.3900410399999998e+00 , -1.2974900000000000e-01 , 2.1134100000000000e-01 , 9.6876200000000001e-01 -1.8019692878634883e+00 , -5.7788877427293750e-01 , 1.4008601599999999e+00 , -1.1143300000000000e-01 , 1.9983799999999999e-01 , 9.7347200000000000e-01 -1.7691681299025741e+00 , -6.7457667920090980e-01 , 1.4146131199999998e+00 , -1.0258399999999999e-01 , 2.1632299999999999e-01 , 9.7091799999999995e-01 -1.7349709874199273e+00 , -7.7170673706066406e-01 , 1.4311772000000000e+00 , -1.1830200000000000e-01 , 1.9926099999999999e-01 , 9.7277899999999995e-01 -1.6969134222227198e+00 , -8.8784993955629865e-01 , 1.4421284000000001e+00 , -1.2396600000000001e-01 , 2.0880599999999999e-01 , 9.7006800000000004e-01 -1.6601531325721361e+00 , -9.9501811008616592e-01 , 1.4609991999999998e+00 , -1.4643200000000001e-01 , 1.8251800000000001e-01 , 9.7223700000000002e-01 -1.6166928715123152e+00 , -1.1292667662037368e+00 , 1.4705609600000000e+00 , -1.3509599999999999e-01 , 1.6202000000000000e-01 , 9.7749600000000003e-01 -1.5669869402750038e+00 , -1.2841262905737714e+00 , 1.4765908799999998e+00 , -1.2447300000000000e-01 , 1.7591399999999999e-01 , 9.7650400000000004e-01 -1.5185190205592942e+00 , -1.4287918596081184e+00 , 1.4913474400000000e+00 , -1.2526000000000001e-02 , 2.8963100000000003e-01 , 9.5705600000000002e-01 -1.4806189557919336e+00 , -1.5267043715476554e+00 , 1.5295539200000001e+00 , 2.8402600000000000e-02 , -2.7457100000000001e-01 , -9.6114699999999997e-01 -1.4291820015353389e+00 , -1.6817980648915332e+00 , 1.5498578400000000e+00 , -8.6345099999999994e-02 , 2.3949899999999999e-01 , 9.6704999999999997e-01 -1.3808666351409857e+00 , -1.8176888140710838e+00 , 1.5818492800000001e+00 , -7.2450799999999996e-02 , 2.5821800000000000e-01 , 9.6336599999999994e-01 -1.3271657982671368e+00 , -1.9728169581811974e+00 , 1.6120508800000000e+00 , -7.4424699999999996e-02 , 2.3764600000000000e-01 , 9.6849700000000005e-01 -1.2639911827252681e+00 , -2.1570098106612461e+00 , 1.6382640799999999e+00 , -7.5852100000000006e-02 , 2.1287700000000001e-01 , 9.7413000000000005e-01 -1.2010913555400822e+00 , -2.3409877879239449e+00 , 1.6708795200000000e+00 , -6.7380999999999996e-02 , 2.2118900000000000e-01 , 9.7290100000000002e-01 -1.1284780805370418e+00 , -2.5536333728909799e+00 , 1.7014305599999999e+00 , -7.7829999999999996e-02 , 2.1923400000000001e-01 , 9.7256299999999996e-01 -1.0549423696363558e+00 , -2.7668585712591147e+00 , 1.7394737600000001e+00 , -8.1058900000000003e-02 , 2.1962400000000001e-01 , 9.7221100000000005e-01 -9.7242901835038809e-01 , -3.0093450284599221e+00 , 1.7779069599999999e+00 , -8.3171999999999996e-02 , 2.2446300000000000e-01 , 9.7092699999999998e-01 -8.8587267077515386e-01 , -3.2610447570561112e+00 , 1.8224678400000001e+00 , -8.0088900000000005e-02 , 2.3295099999999999e-01 , 9.6918499999999996e-01 -7.8696909478836163e-01 , -3.5513477973671357e+00 , 1.8677775200000000e+00 , -5.1463200000000001e-02 , -1.7787200000000000e-01 , -9.8270700000000000e-01 -6.8578923921807355e-01 , -3.8416241322899403e+00 , 1.9232862719999999e+00 , 6.5540000000000001e-02 , 2.4347400000000000e-01 , 9.6769099999999997e-01 -5.6671346909622278e-01 , -4.1905064544656110e+00 , 1.9791721280000001e+00 , 4.8210800000000002e-03 , 1.2198900000000000e-01 , 9.9251999999999996e-01 -4.3043467749299014e-01 , -4.5875929638194819e+00 , 2.0398849360000000e+00 , -9.1043200000000005e-02 , 2.2432800000000000e-01 , 9.7025200000000000e-01 -2.8500304168526625e-01 , -5.0140186936743874e+00 , 2.1111364799999999e+00 , -8.7311399999999997e-02 , 2.2934700000000000e-01 , 9.6942099999999998e-01 -1.1862456158852086e-01 , -5.4983954819790890e+00 , 2.1907110400000001e+00 , -8.3704100000000004e-02 , 2.3171300000000000e-01 , 9.6917600000000004e-01 --6.1680599904887501e-02 , -6.0218549258291318e+00 , 2.2840947200000001e+00 , -8.0563700000000002e-02 , 2.4187700000000001e-01 , 9.6695600000000004e-01 --2.6037637795443569e-01 , -6.5925283575146132e+00 , 2.3922235199999999e+00 , -6.6929100000000005e-02 , 2.2385700000000000e-01 , 9.7232099999999999e-01 --5.0618140361696851e-01 , -7.3095444621779340e+00 , 2.5123039999999999e+00 , -6.6282099999999997e-02 , 2.1948100000000001e-01 , 9.7336299999999998e-01 --7.9014468674518268e-01 , -8.1341925153843455e+00 , 2.6539655199999999e+00 , 1.0304300000000001e-02 , -1.7024100000000000e-01 , -9.8534900000000003e-01 --1.1085423977012288e+00 , -9.0537478604379604e+00 , 2.8231433600000000e+00 , -4.5124800000000000e-02 , 2.9899199999999998e-01 , 9.5318800000000004e-01 --1.5332408776005177e+00 , -1.0296685626435934e+01 , 3.0244655200000001e+00 , 3.4898299999999999e-01 , -4.0482600000000002e-01 , -8.4517799999999998e-01 --2.0246870835403188e+00 , -1.1721579935077532e+01 , 3.2732304000000001e+00 , -1.8603800000000001e-01 , 2.1750600000000000e-01 , 9.5816599999999996e-01 --2.6294113347656358e+00 , -1.3476215998776707e+01 , 3.5848560000000003e+00 , 1.9629700000000000e-01 , 1.8539700000000001e-01 , 9.6285799999999999e-01 --3.0419912678515590e+00 , -1.4597444907149558e+01 , 3.9290232000000000e+00 , 3.8401600000000002e-01 , 1.9726500000000000e-01 , 9.0200800000000003e-01 --3.2358637047552667e+00 , -1.5029371183251833e+01 , 4.2682920000000006e+00 , 3.8401700000000000e-01 , 1.9726500000000000e-01 , 9.0200800000000003e-01 --3.6798585098167704e+00 , -1.6211405319493654e+01 , 4.6892840000000007e+00 , 2.3579600000000001e-01 , 2.6733699999999999e-01 , 9.3430800000000003e-01 --4.6379137069728174e+00 , -1.8914283108386918e+01 , 5.3146360000000001e+00 , -9.8475500000000005e-01 , -1.1692300000000000e-01 , -1.2879099999999999e-01 --4.7220844634318215e+00 , -1.8962861591660062e+01 , 5.7146512000000005e+00 , -9.8608200000000001e-01 , -1.6586699999999999e-01 , -1.1397300000000001e-02 --4.7669273386058286e+00 , -1.8895548719769700e+01 , 6.1023320000000005e+00 , 9.5792100000000002e-01 , 2.7891300000000002e-01 , 6.7791100000000007e-02 --4.7975888919015839e+00 , -1.8783551747107524e+01 , 6.4828783999999997e+00 , -9.5601599999999998e-01 , -2.6083600000000001e-01 , -1.3415600000000000e-01 --4.8790366250962887e+00 , -1.8820436146051307e+01 , 6.8887072000000007e+00 , -9.2628900000000003e-01 , -3.5746699999999998e-01 , -1.1918600000000000e-01 --4.9921940723160025e+00 , -1.8945881617913457e+01 , 7.3168232000000000e+00 , -9.3908999999999998e-01 , -3.2890200000000003e-01 , -9.9671099999999999e-02 --5.0365053254395784e+00 , -1.8871245144586958e+01 , 7.7095583999999997e+00 , -9.5041299999999995e-01 , -3.0778899999999998e-01 , -4.4517899999999999e-02 --5.0820534576231120e+00 , -1.8799406164815583e+01 , 8.1038016000000006e+00 , -9.5924299999999996e-01 , -2.8231499999999998e-01 , -1.2290100000000000e-02 --5.1243950627355765e+00 , -1.8721399197354337e+01 , 8.4977847999999998e+00 , -9.5698799999999995e-01 , -2.8919800000000001e-01 , -2.3190499999999999e-02 --5.1654502341081354e+00 , -1.8636127851032317e+01 , 8.8910815999999997e+00 , -9.4583399999999995e-01 , -3.2453900000000002e-01 , 8.5532600000000000e-03 --5.2041170560582239e+00 , -1.8543793217441877e+01 , 9.2833800000000011e+00 , -9.4339300000000004e-01 , -3.3122000000000001e-01 , 1.7410800000000001e-02 --5.2515191533579637e+00 , -1.8472754515964542e+01 , 9.6837800000000005e+00 , -9.4267699999999999e-01 , -3.3335599999999999e-01 , 1.5278300000000000e-02 --5.2883595774418390e+00 , -1.8376866196001579e+01 , 1.0078252000000001e+01 , -9.4508899999999996e-01 , -3.2646599999999998e-01 , 1.5030000000000000e-02 --5.3376252524448420e+00 , -1.8310768215741223e+01 , 1.0485006400000000e+01 , -9.6804800000000002e-01 , -2.3807400000000001e-01 , 7.8760399999999994e-02 --5.3783306128768391e+00 , -1.8218846814358841e+01 , 1.0885084000000001e+01 , -9.6686600000000000e-01 , -2.2022700000000001e-01 , 1.2911000000000000e-01 --5.4259393262806057e+00 , -1.8146788843640550e+01 , 1.1295925600000000e+01 , 9.7263200000000005e-01 , 2.3021000000000000e-01 , -3.1464300000000001e-02 --5.3779504755929368e+00 , -1.7824445525345165e+01 , 1.1604556000000001e+01 , 9.8421999999999998e-01 , 1.6175000000000000e-01 , 7.1754399999999996e-02 --5.5543431093471609e+00 , -1.8080285089895387e+01 , 1.2162672000000001e+01 , -9.6169700000000002e-01 , -1.9054900000000000e-01 , -1.9705100000000000e-01 --5.5852154774390623e+00 , -1.7957825442760512e+01 , 1.2563904000000001e+01 , 9.5684499999999995e-01 , 1.9907400000000000e-01 , 2.1170100000000000e-01 --5.6527272317496093e+00 , -1.7926305660687785e+01 , 1.3011519999999999e+01 , -9.8056299999999996e-01 , -1.7242199999999999e-01 , -9.3636600000000000e-02 --5.6885250733430253e+00 , -1.7815668210928429e+01 , 1.3426168000000001e+01 , -9.4895200000000002e-01 , -3.1534299999999998e-01 , 6.9432900000000004e-03 --5.7336780385981729e+00 , -1.7723268885559321e+01 , 1.3854232000000001e+01 , -9.4911000000000001e-01 , -3.1444400000000000e-01 , 1.7781000000000002e-02 --5.7794838886187003e+00 , -1.7630789676004433e+01 , 1.4287599999999999e+01 , -9.4961600000000002e-01 , -3.1197300000000000e-01 , 3.0024100000000001e-02 --5.8191742338102292e+00 , -1.7521365736747168e+01 , 1.4716704000000002e+01 , -9.4975500000000002e-01 , -3.1059500000000001e-01 , 3.8674500000000001e-02 --5.8595959668249940e+00 , -1.7413045094300386e+01 , 1.5151320000000000e+01 , -9.6645899999999996e-01 , -2.4823799999999999e-01 , 6.5843399999999996e-02 --5.9045272341857498e+00 , -1.7311793263633696e+01 , 1.5596648000000002e+01 , -9.7245800000000004e-01 , -2.1748400000000001e-01 , 8.3823400000000006e-02 --5.9503565633808808e+00 , -1.7210299018153840e+01 , 1.6048216000000000e+01 , 9.9217299999999997e-01 , 8.4992200000000004e-02 , -9.1487899999999997e-02 --5.9968622012076285e+00 , -1.7107562369102361e+01 , 1.6506335999999997e+01 , 9.9378599999999995e-01 , 7.4441400000000005e-02 , -8.2749699999999995e-02 --5.9432977545089036e+00 , -1.6772416145155475e+01 , 1.6805648000000001e+01 , -9.8389199999999999e-01 , -6.2653000000000000e-02 , 1.6742499999999999e-01 --6.0326134731916419e+00 , -1.6764204758172408e+01 , 1.7343432000000000e+01 , 9.9638199999999999e-01 , 7.2497599999999995e-02 , 4.4352599999999999e-02 --5.9187642515538705e+00 , -1.6293532296623539e+01 , 1.7538119999999999e+01 , 9.8805799999999999e-01 , 7.7470499999999998e-02 , 1.3318800000000000e-01 --6.2901257416693763e+00 , -1.6900978925438938e+01 , 1.8586440000000000e+01 , 9.7339299999999995e-01 , 1.0691400000000000e-01 , 2.0267299999999999e-01 --6.2768522064105330e+00 , -1.6648705202451914e+01 , 1.8971551999999999e+01 , 9.7339299999999995e-01 , 1.0691400000000000e-01 , 2.0267299999999999e-01 --2.6758180985049895e-01 , -3.2464245561886376e+00 , 8.5477568000000002e+00 , -4.8725499999999999e-01 , -3.7003200000000003e-01 , 7.9098599999999997e-01 --2.6587259815989350e-01 , -3.1689004678658677e+00 , 8.6746575999999997e+00 , -4.8725600000000002e-01 , -3.7003200000000003e-01 , 7.9098599999999997e-01 --3.0931105223769872e-01 , -3.1842638002586270e+00 , 8.9000880000000002e+00 , 5.3034400000000004e-01 , 8.2105300000000003e-01 , 2.1120600000000000e-01 --1.7405364533961842e-01 , -2.8390412346052107e+00 , 8.7450967999999989e+00 , 4.4128800000000001e-01 , 7.6208200000000004e-02 , 8.9412400000000003e-01 -6.7174674963824010e-02 , -2.2920368972627898e+00 , 8.3441247999999995e+00 , 6.5119700000000003e-01 , -7.0179800000000003e-01 , -2.8882900000000000e-01 --7.3804222741329362e-03 , -2.3715088566547600e+00 , 8.6347216000000007e+00 , -2.6551600000000002e-03 , 7.5514000000000003e-01 , 6.5555799999999997e-01 -1.0586954234232993e-01 , -2.0834548600530640e+00 , 8.4969631999999997e+00 , -7.1613000000000004e-01 , 3.0544900000000003e-01 , 6.2758199999999997e-01 -1.2874038536217003e-01 , -1.9748469986239670e+00 , 8.5665912000000013e+00 , -6.3882799999999995e-01 , 8.7267700000000004e-02 , -7.6438399999999995e-01 -1.1190163178529766e-01 , -1.9373741810360494e+00 , 8.7279055999999997e+00 , -6.1214000000000002e-01 , 1.6107399999999999e-01 , -7.7417000000000002e-01 -2.4507969103222194e-01 , -1.6262328741068299e+00 , 8.5245543999999995e+00 , 1.6141100000000000e-01 , -7.7126099999999997e-01 , 6.1571399999999998e-01 -2.2765695422244270e-01 , -1.5932079375676453e+00 , 8.6900288000000003e+00 , 2.4146000000000001e-01 , -8.1789800000000001e-01 , 5.2224499999999996e-01 --4.3138478535579505e-02 , -2.0036187775070848e+00 , 9.5096735999999993e+00 , -4.6427200000000002e-01 , 8.1419500000000000e-01 , -3.4862300000000002e-01 -2.6434130342326312e-01 , -1.3934483910911069e+00 , 8.8408183999999999e+00 , 2.3633700000000001e-02 , -8.3531100000000003e-01 , 5.4927000000000004e-01 -2.5888613528706772e-01 , -1.3342383060733853e+00 , 8.9806983999999996e+00 , -6.0754700000000002e-02 , -7.5599200000000000e-01 , 6.5175499999999997e-01 -1.2762757693929050e-01 , -1.4841410303063460e+00 , 9.4682607999999995e+00 , -1.8288399999999999e-01 , 3.1186799999999998e-01 , 9.3235800000000002e-01 -2.6867883645907020e-01 , -1.1762426016084984e+00 , 9.2083544000000010e+00 , -3.0095899999999998e-01 , -9.0073700000000001e-01 , 3.1320300000000001e-01 -2.6020318961152733e-01 , -1.1178888629893171e+00 , 9.3644168000000008e+00 , 7.0655900000000005e-01 , 4.0073700000000001e-01 , -5.8325300000000002e-01 -2.4417247061025038e-01 , -1.0688024143014960e+00 , 9.5466248000000000e+00 , 5.4267700000000002e-02 , -6.5114399999999995e-01 , 7.5701099999999999e-01 --1.8350772509423852e-02 , -1.3983638179157056e+00 , 1.0474221600000000e+01 , 2.2025800000000001e-01 , 1.8557799999999999e-01 , 9.5762599999999998e-01 -3.3122142052775394e-01 , -7.8461645905750377e-01 , 9.5632960000000011e+00 , 4.0671299999999999e-01 , 1.5110199999999999e-01 , -9.0097300000000002e-01 -2.6062802629493875e-01 , -8.1191495386967949e-01 , 9.9239680000000003e+00 , -4.7162900000000002e-01 , -4.1943599999999998e-01 , 7.7565399999999995e-01 -3.6468113882010522e-01 , -5.8250751633849340e-01 , 9.7408968000000016e+00 , -1.5632199999999999e-01 , 6.9196000000000002e-01 , -7.0480900000000002e-01 -3.6245073401620997e-01 , -5.0533634380774339e-01 , 9.8915616000000011e+00 , -7.5997599999999998e-01 , -3.7171199999999999e-01 , 5.3316699999999995e-01 -3.6134632614005779e-01 , -4.2508242044718036e-01 , 1.0041945600000000e+01 , 1.3505500000000001e-01 , -9.7966399999999998e-01 , 1.4838899999999999e-01 -4.4803667077751586e-01 , -2.2874768451591709e-01 , 9.9018264000000009e+00 , 2.5516199999999999e-02 , 9.9733400000000005e-01 , 6.8361199999999997e-02 -6.3023308389131860e-01 , 8.6196673801523183e-02 , 9.4168640000000003e+00 , -5.1874500000000001e-01 , 2.0580799999999999e-01 , 8.2978700000000005e-01 -6.6153902343190762e-01 , 2.0292377443424248e-01 , 9.4442264000000016e+00 , -2.1715300000000001e-01 , 3.9166499999999999e-01 , 8.9411600000000002e-01 -5.4937570291983273e-01 , 1.4685634690608240e-01 , 9.9958008000000014e+00 , 6.6157100000000002e-01 , 7.4709199999999998e-01 , -6.4635799999999993e-02 -5.1659878250469604e-01 , 1.9553001075112086e-01 , 1.0272544800000000e+01 , 4.3007200000000001e-01 , -6.6586000000000001e-01 , 6.0964600000000002e-01 -6.8334473712620980e-01 , 4.6676393835119079e-01 , 9.8045135999999999e+00 , 9.9883400000000000e-01 , -4.5985400000000003e-02 , 1.4714400000000001e-02 -6.3273290329241760e-01 , 4.9840931994378046e-01 , 1.0156324800000000e+01 , -9.8229100000000003e-01 , 1.5294900000000000e-01 , 1.0822000000000000e-01 -6.4895205049090277e-01 , 6.0564759282876279e-01 , 1.0254636000000000e+01 , -9.8208099999999998e-01 , -1.6665400000000000e-01 , 8.7995100000000007e-02 -6.5955222549143033e-01 , 7.0820153349578807e-01 , 1.0381162399999999e+01 , -9.7524100000000002e-01 , -1.9578499999999999e-01 , 1.0283000000000000e-01 -9.6051604489947562e-01 , 1.0738031045488157e+00 , 9.2981064000000000e+00 , 1.9947799999999999e-01 , 4.3222700000000003e-02 , 9.7894899999999996e-01 -1.0615402311569158e+00 , 1.2403631435998808e+00 , 9.0185127999999999e+00 , -5.7054700000000003e-01 , -7.8431200000000001e-01 , 2.4357799999999999e-01 -1.0345311404007340e+00 , 1.2992162494175856e+00 , 9.2837855999999999e+00 , 1.0304600000000000e-01 , -2.9208099999999998e-01 , 9.5082599999999995e-01 -6.7097581615348556e-01 , 1.1221965888172569e+00 , 1.1073417599999999e+01 , -6.2106499999999998e-01 , 6.4924800000000005e-01 , -4.3903799999999998e-01 -7.7581245818956202e-01 , 1.3027715716984467e+00 , 1.0790423199999999e+01 , 7.1267999999999998e-01 , -6.3278999999999996e-01 , -3.0275999999999997e-01 -8.2790274370782457e-01 , 1.4432827015322653e+00 , 1.0745308000000001e+01 , -9.1084200000000004e-01 , 7.7455999999999997e-02 , 4.0542299999999998e-01 -8.1069652232295297e-01 , 1.5462761652358168e+00 , 1.1031484800000001e+01 , -9.0907400000000005e-01 , -3.9439200000000002e-01 , 1.3431399999999999e-01 -9.7627187851379671e-01 , 1.7383759077097269e+00 , 1.0423375999999999e+01 , 5.0260300000000002e-01 , 5.4361800000000005e-01 , 6.7221299999999995e-01 -1.1078374718291126e+00 , 1.8989873069131669e+00 , 9.9521312000000002e+00 , -8.2676099999999997e-01 , -4.0340500000000001e-01 , -3.9208399999999999e-01 -1.1112930250567992e+00 , 2.0067859675714894e+00 , 1.0129534400000001e+01 , -9.1256499999999996e-01 , -1.9165800000000000e-01 , -3.6123800000000000e-01 -1.1829010344450315e+00 , 2.1338124350783660e+00 , 9.9478568000000003e+00 , 4.6732200000000002e-01 , -1.7210000000000000e-01 , 8.6717400000000000e-01 -1.1220031999894731e+00 , 2.2382179421075232e+00 , 1.0489967200000001e+01 , -5.7946500000000001e-01 , 6.0667899999999997e-01 , -5.4420599999999997e-01 -1.1693696102228617e+00 , 2.3645251296211494e+00 , 1.0447119199999999e+01 , -8.8545600000000002e-01 , 1.8367600000000001e-01 , -4.2688599999999999e-01 -1.2396520762950125e+00 , 2.4870085743332355e+00 , 1.0258421600000000e+01 , 6.8434300000000003e-01 , -3.8284200000000002e-01 , 6.2056999999999995e-01 -1.3944660488849001e+00 , 2.5880810428489447e+00 , 9.5440560000000012e+00 , 6.2106899999999998e-01 , 1.2532199999999999e-01 , 7.7367200000000003e-01 -1.2778069819805697e+00 , 2.7400230278260738e+00 , 1.0499940799999999e+01 , 6.1351299999999998e-02 , -8.4226599999999999e-02 , 9.9455600000000000e-01 -1.4300148888052093e+00 , 2.8191871221281817e+00 , 9.7606047999999994e+00 , -4.2117500000000002e-01 , -5.7279999999999998e-01 , 7.0321500000000003e-01 -1.4838966969401692e+00 , 2.9221368859967183e+00 , 9.6348376000000009e+00 , -7.7578100000000005e-01 , 4.4280700000000001e-01 , 4.4953900000000002e-01 -1.5212635147457838e+00 , 3.0322230812887074e+00 , 9.6200280000000014e+00 , -2.2375800000000001e-02 , 7.0621900000000004e-01 , 7.0764000000000005e-01 -1.5276999807121201e+00 , 3.1663522632834344e+00 , 9.8285896000000008e+00 , -9.4276800000000005e-01 , -1.9044300000000000e-01 , -2.7371299999999998e-01 -1.5943564981401754e+00 , 3.2501973892865701e+00 , 9.5949536000000002e+00 , -3.8681399999999999e-01 , -4.9646800000000002e-01 , -7.7710699999999999e-01 -1.7059904789995972e+00 , 3.2705770744252316e+00 , 8.9820712000000000e+00 , 9.9888699999999997e-01 , -2.7755100000000001e-02 , -3.8148899999999999e-02 -2.1132673287062205e+00 , 5.0329468551410450e-01 , 1.2628875200000000e+00 , -1.1312999999999999e-01 , 1.9080700000000000e-01 , 9.7508700000000004e-01 -2.0002792584638973e+00 , 1.9221371285771993e-01 , 1.2916892799999999e+00 , -8.8033700000000006e-02 , 1.9353699999999999e-01 , 9.7713499999999998e-01 -1.9765791304137057e+00 , 1.3222953432468554e-01 , 1.3051333600000001e+00 , -7.6122599999999999e-02 , 2.3526000000000000e-01 , 9.6894700000000000e-01 -1.9512059341105863e+00 , 6.5029940522864260e-02 , 1.3139920800000000e+00 , -7.2902099999999997e-02 , 2.3392299999999999e-01 , 9.6951799999999999e-01 -1.9255301087722518e+00 , -3.8333393435268093e-03 , 1.3250826400000000e+00 , -9.9280099999999996e-02 , 1.7976800000000001e-01 , 9.7868599999999994e-01 -1.8955135749564485e+00 , -8.9377083596739570e-02 , 1.3262765599999999e+00 , -6.1514899999999997e-02 , 1.5937699999999999e-01 , 9.8529900000000004e-01 -1.8693613586359341e+00 , -1.5740311858515454e-01 , 1.3414137600000000e+00 , -9.8652699999999996e-02 , 2.2066900000000000e-01 , 9.7034699999999996e-01 -1.8402810691366633e+00 , -2.3553062888430709e-01 , 1.3532666400000000e+00 , -8.0596399999999999e-02 , 1.8531700000000001e-01 , 9.7936800000000002e-01 -1.8067258563253994e+00 , -3.3010052216446883e-01 , 1.3563346400000000e+00 , -1.1405300000000000e-01 , 1.7392299999999999e-01 , 9.7813200000000000e-01 -1.7744103234509123e+00 , -4.1668331889382149e-01 , 1.3676311200000000e+00 , -9.8749699999999996e-02 , 1.9450799999999999e-01 , 9.7591799999999995e-01 -1.7417544679055981e+00 , -5.0377017492734488e-01 , 1.3816617600000001e+00 , -1.0382500000000000e-01 , 1.9565900000000000e-01 , 9.7516099999999994e-01 -1.7071003806586065e+00 , -5.9969825415004285e-01 , 1.3935416800000000e+00 , -7.8155699999999995e-02 , 1.9100700000000001e-01 , 9.7847200000000001e-01 -1.6710390416831147e+00 , -6.9604954723243084e-01 , 1.4083346400000001e+00 , -8.6152999999999993e-02 , 2.0675499999999999e-01 , 9.7459200000000001e-01 -1.6318426598624174e+00 , -8.0213042101848409e-01 , 1.4215624000000000e+00 , -8.5594500000000004e-02 , 1.7407200000000000e-01 , 9.8100600000000004e-01 -1.5894970952436778e+00 , -9.1681892027588052e-01 , 1.4335244800000000e+00 , -1.0866500000000000e-01 , 1.8168400000000001e-01 , 9.7733499999999995e-01 -1.5421678428188685e+00 , -1.0503450233642213e+00 , 1.4405580000000000e+00 , -1.0021300000000000e-01 , 1.7145500000000000e-01 , 9.8008200000000001e-01 -1.4960600809235944e+00 , -1.1747735070584651e+00 , 1.4561184800000000e+00 , -1.4136299999999999e-01 , 1.3828399999999999e-01 , 9.8025200000000001e-01 -1.4391618158304229e+00 , -1.3372138390205346e+00 , 1.4598718399999999e+00 , -3.4780699999999998e-02 , 2.3335300000000000e-01 , 9.7177000000000002e-01 -1.4012421224541174e+00 , -1.4252403895198409e+00 , 1.4997724799999999e+00 , 1.7147300000000001e-02 , -2.5673000000000001e-01 , -9.6633100000000005e-01 -1.3478516736940893e+00 , -1.5695455295211684e+00 , 1.5205059200000000e+00 , -6.5592200000000003e-02 , 2.4237000000000000e-01 , 9.6796400000000005e-01 -1.2910055487080525e+00 , -1.7230297774389007e+00 , 1.5424051999999999e+00 , -4.9437500000000002e-02 , 2.4315700000000001e-01 , 9.6872599999999998e-01 -1.2383212186611983e+00 , -1.8573124512585495e+00 , 1.5761167999999999e+00 , -4.7048199999999998e-02 , 2.4324599999999999e-01 , 9.6882299999999999e-01 -1.1733397949880824e+00 , -2.0298699282493047e+00 , 1.6017444800000000e+00 , -6.6922200000000001e-02 , 2.1551200000000001e-01 , 9.7420499999999999e-01 -1.1057061333846914e+00 , -2.2123244046419597e+00 , 1.6303871200000000e+00 , 6.1354400000000003e-02 , -2.2129199999999999e-01 , -9.7327600000000003e-01 -1.0392777561969582e+00 , -2.3845491137157868e+00 , 1.6678583199999999e+00 , -6.1448000000000003e-02 , 2.1034300000000000e-01 , 9.7569499999999998e-01 -9.5410678042371133e-01 , -2.6152861532933827e+00 , 1.6955327200000001e+00 , -7.0042900000000005e-02 , 2.0458699999999999e-01 , 9.7633899999999996e-01 -8.7100719169535012e-01 , -2.8355117426175509e+00 , 1.7336799199999999e+00 , -6.7399700000000007e-02 , 2.2186800000000001e-01 , 9.7274499999999997e-01 -7.7784664234850465e-01 , -3.0848892334137217e+00 , 1.7724968800000001e+00 , -5.3473899999999998e-02 , 2.1685199999999999e-01 , 9.7473900000000002e-01 -6.7339222540915711e-01 , -3.3630424683831190e+00 , 1.8136787999999999e+00 , 7.7991099999999994e-02 , 2.7165200000000000e-01 , 9.5923000000000003e-01 -5.6462732720931630e-01 , -3.6510786650271827e+00 , 1.8629123999999999e+00 , 1.3130700000000000e-02 , 1.3470699999999999e-01 , 9.9079799999999996e-01 -4.4533425083197953e-01 , -3.9674276587203368e+00 , 1.9168640640000001e+00 , -9.1309600000000005e-02 , 6.0853999999999998e-02 , 9.9396099999999998e-01 -3.0277294316570069e-01 , -4.3517910969890679e+00 , 1.9708931040000000e+00 , -1.4859800000000001e-01 , 1.2179700000000000e-01 , 9.8136900000000005e-01 -4.3794475789997911e-01 , -3.8617173562503888e+00 , 2.1658997599999998e+00 , 8.7794600000000000e-01 , 5.1606699999999998e-02 , 4.7597099999999998e-01 --1.1614952230502240e-02 , -5.1859597660086774e+00 , 2.1114703200000000e+00 , -6.8676000000000001e-02 , 2.1764700000000001e-01 , 9.7360899999999995e-01 --1.9969470746863571e-01 , -5.6845194456842432e+00 , 2.1950509600000001e+00 , -5.8447800000000001e-02 , 2.2277800000000000e-01 , 9.7311599999999998e-01 --4.0928190507831408e-01 , -6.2411438226668210e+00 , 2.2915120000000000e+00 , -5.8235700000000001e-02 , 2.3240000000000000e-01 , 9.7087500000000004e-01 -4.7804885630156169e-01 , -3.4995874128200830e+00 , 2.6490400799999998e+00 , 7.7779399999999999e-01 , 6.2682499999999997e-01 , -4.6125399999999997e-02 -4.6630726670266576e-01 , -3.4794074508674164e+00 , 2.7572292000000003e+00 , -7.5676600000000005e-01 , -6.5132900000000005e-01 , 5.5460099999999998e-02 -4.6443820826005222e-01 , -3.4297742152181243e+00 , 2.8661650400000003e+00 , 7.1831999999999996e-01 , 6.9391199999999997e-01 , -5.0016300000000000e-02 -4.6287807952975202e-01 , -3.3773724177990969e+00 , 2.9730697600000000e+00 , 6.0348700000000000e-01 , 7.9737000000000002e-01 , -2.0739899999999999e-03 -6.2307225234571595e-01 , -2.8608123385586186e+00 , 3.0783240000000003e+00 , 6.9279199999999996e-01 , -7.1342200000000000e-01 , 1.0520400000000001e-01 -5.2259726662639006e-01 , -3.1006471655886827e+00 , 3.1787672000000002e+00 , -6.6153600000000001e-01 , 6.9584100000000004e-01 , -2.7960099999999999e-01 -4.0760578235521772e-01 , -3.3770737751196638e+00 , 3.2895479999999999e+00 , -3.8938400000000001e-01 , 9.0874100000000002e-01 , -1.5023400000000001e-01 --3.4215370296545276e+00 , -1.4059444826932648e+01 , 3.9780904000000001e+00 , -2.0326200000000000e-01 , -2.2804600000000000e-01 , -9.5219699999999996e-01 --3.7190526835475746e+00 , -1.4737981623202941e+01 , 4.3308479999999996e+00 , 3.8401600000000002e-01 , 1.9726600000000000e-01 , 9.0200800000000003e-01 --4.8672330539903079e+00 , -1.7745324483848197e+01 , 4.9228888000000000e+00 , 9.9850700000000003e-01 , 3.1111900000000001e-02 , 4.4890899999999997e-02 --5.1633653472502905e+00 , -1.8371584391497233e+01 , 5.3664904000000000e+00 , 9.9955300000000002e-01 , 2.9042100000000001e-02 , 7.0881599999999996e-03 --5.2303989563406388e+00 , -1.8367027070757782e+01 , 5.7543480000000002e+00 , 9.8830200000000001e-01 , 2.7671899999999999e-02 , 1.4997800000000000e-01 --5.0583313420375537e+00 , -1.7719225613040951e+01 , 6.0496144000000003e+00 , 9.6484400000000003e-01 , -9.6648999999999999e-02 , 2.4440899999999999e-01 --5.0147775000966730e+00 , -1.7424734586454083e+01 , 6.3819776000000008e+00 , 9.6082400000000001e-01 , -2.7187500000000000e-02 , 2.7582400000000001e-01 --5.3801708773305981e+00 , -1.8209245021883458e+01 , 6.9060855999999999e+00 , -9.2236499999999999e-01 , -2.0014899999999999e-01 , -3.3042800000000000e-01 --5.4279709591229244e+00 , -1.8149853557003002e+01 , 7.2907712000000000e+00 , -9.5133500000000004e-01 , -2.8273199999999998e-01 , -1.2257500000000000e-01 --5.4249158599287730e+00 , -1.7960243015521481e+01 , 7.6475016000000009e+00 , -9.5744899999999999e-01 , -2.7126800000000001e-01 , -9.8511199999999993e-02 --5.5193770370293036e+00 , -1.8020351726677042e+01 , 8.0615255999999995e+00 , -9.4046300000000005e-01 , -3.3745000000000003e-01 , -4.0700000000000000e-02 --5.5677680187558014e+00 , -1.7961186158383100e+01 , 8.4504543999999999e+00 , -9.3834200000000001e-01 , -3.4233599999999997e-01 , -4.8175700000000002e-02 --5.6137334712227780e+00 , -1.7893570267976280e+01 , 8.8391231999999995e+00 , -9.4275900000000001e-01 , -3.3341599999999999e-01 , 6.3131600000000000e-03 --5.6492570767525541e+00 , -1.7802084086231908e+01 , 9.2224672000000005e+00 , -9.4455100000000003e-01 , -3.2804899999999998e-01 , 1.4418700000000000e-02 --5.6945586507391761e+00 , -1.7730937933318803e+01 , 9.6136735999999985e+00 , -9.4516100000000003e-01 , -3.2581700000000002e-01 , 2.2672500000000002e-02 --5.7365930939514342e+00 , -1.7653399277257229e+01 , 1.0005129600000000e+01 , -9.4963500000000001e-01 , -2.9708000000000001e-01 , 9.9684700000000001e-02 --5.7651334623236679e+00 , -1.7541396780083382e+01 , 1.0386445600000002e+01 , -9.5717900000000000e-01 , -2.5047199999999997e-01 , 1.4516299999999999e-01 --5.7129668782592722e+00 , -1.7233381072608825e+01 , 1.0692985600000000e+01 , -9.6590500000000001e-01 , -3.7985499999999998e-02 , 2.5609700000000002e-01 --5.7514174162099065e+00 , -1.7145777781875502e+01 , 1.1082975200000000e+01 , 9.9218799999999996e-01 , 6.6253000000000006e-02 , -1.0570300000000001e-01 --5.6480539610608735e+00 , -1.6721268714971568e+01 , 1.1330640799999999e+01 , 9.9489000000000005e-01 , 8.8794100000000001e-02 , 4.8052499999999998e-02 --5.8520726580868976e+00 , -1.7020379269943806e+01 , 1.1894435200000000e+01 , -9.7055999999999998e-01 , -1.1869200000000001e-01 , -2.0958299999999999e-01 --5.8753487357320342e+00 , -1.6893514667026139e+01 , 1.2276645600000000e+01 , 9.7564099999999998e-01 , 9.8222599999999993e-02 , 1.9615700000000000e-01 --6.0702768772645417e+00 , -1.7158947903209334e+01 , 1.2856976000000000e+01 , 9.7404299999999999e-01 , 1.9918500000000000e-01 , 1.0754700000000000e-01 --6.1116544029444011e+00 , -1.7067374986947961e+01 , 1.3271312000000000e+01 , -9.6546799999999999e-01 , -2.4787500000000001e-01 , -8.0187599999999998e-02 --6.1585373083449699e+00 , -1.6984240017956559e+01 , 1.3695008000000001e+01 , -9.4911000000000001e-01 , -3.1444400000000000e-01 , 1.7781000000000002e-02 --6.2101074158176459e+00 , -1.6910438295813666e+01 , 1.4129520000000001e+01 , -9.4961600000000002e-01 , -3.1197399999999997e-01 , 3.0024100000000001e-02 --6.2506075965819026e+00 , -1.6811153350902252e+01 , 1.4555503999999999e+01 , 9.7444399999999998e-01 , 2.2148000000000001e-01 , -3.7498700000000003e-02 --6.2704141813491372e+00 , -1.6661619592306213e+01 , 1.4956112000000001e+01 , 9.8023099999999996e-01 , 1.8598200000000001e-01 , -6.7519300000000004e-02 --6.3212322946965429e+00 , -1.6578963983737829e+01 , 1.5403312000000001e+01 , 9.5362400000000003e-01 , 2.4751600000000001e-01 , 1.7128099999999999e-01 --6.2634584039873413e+00 , -1.6262489667382894e+01 , 1.5700127999999999e+01 , 9.8427399999999998e-01 , -1.5973700000000000e-02 , -1.7592200000000000e-01 --6.2481764385189482e+00 , -1.6037398777803993e+01 , 1.6056536000000001e+01 , 9.8871500000000001e-01 , 9.9081900000000007e-03 , -1.4947900000000000e-01 --6.2421710936544326e+00 , -1.5829362831619061e+01 , 1.6426359999999999e+01 , 9.8990100000000003e-01 , 5.1745800000000002e-02 , -1.3198199999999999e-01 --6.2814840606554085e+00 , -1.5716042245379931e+01 , 1.6869816000000000e+01 , 9.8128199999999999e-01 , 5.2161699999999998e-02 , -1.8537899999999999e-01 --6.2656208631482713e+00 , -1.5487013385598356e+01 , 1.7229863999999999e+01 , 9.9250499999999997e-01 , 1.1751700000000000e-01 , 3.3527300000000003e-02 --6.1253919039606188e+00 , -1.5003565419722868e+01 , 1.7382536000000002e+01 , 9.9250499999999997e-01 , 1.1751700000000000e-01 , 3.3527300000000003e-02 --6.5534905602379823e+00 , -1.5667718333691866e+01 , 1.8500848000000001e+01 , 9.6903399999999995e-01 , 8.1181699999999996e-02 , 2.3320099999999999e-01 --6.4913669588627059e+00 , -1.5337628458548497e+01 , 1.8798184000000003e+01 , 9.6903399999999995e-01 , 8.1181699999999996e-02 , 2.3320099999999999e-01 --4.5300056395179089e-01 , -3.2192380559974643e+00 , 8.4481248000000004e+00 , -6.2558300000000000e-01 , -7.6778400000000002e-01 , 1.3839799999999999e-01 --4.1655530885191805e-01 , -3.0811693191373593e+00 , 8.5140191999999999e+00 , 4.8725499999999999e-01 , 3.7003200000000003e-01 , -7.9098599999999997e-01 --3.8689334293542377e-01 , -2.9565939834620787e+00 , 8.5905632000000001e+00 , -4.8725600000000002e-01 , -3.7003200000000003e-01 , 7.9098599999999997e-01 --9.3523865989291188e-03 , -2.1829067398736859e+00 , 7.9734792000000008e+00 , 4.1780099999999998e-01 , 8.8166299999999997e-01 , -2.1934699999999999e-01 --1.1127978492325008e-01 , -2.3122410635621611e+00 , 8.3006424000000010e+00 , 8.7591900000000000e-02 , 9.4205399999999995e-01 , 3.2382400000000000e-01 --1.8369490852529013e-01 , -2.3801265171116608e+00 , 8.5754104000000009e+00 , -5.8846000000000002e-03 , 8.8065599999999999e-01 , 4.7371900000000000e-01 --3.8363381610918923e-01 , -2.6724039352443603e+00 , 9.1321744000000002e+00 , -9.8669499999999999e-01 , 1.5812300000000001e-01 , 3.7807800000000003e-02 --3.3911519737591567e-01 , -2.5220234534241408e+00 , 9.1766031999999988e+00 , -7.1561500000000000e-01 , -4.9583400000000000e-01 , 4.9197900000000000e-01 --1.9127286473701188e-01 , -2.1910902855949139e+00 , 8.9849935999999992e+00 , -5.3849499999999995e-01 , 7.9447000000000001e-01 , -2.8078599999999998e-01 -7.6659514345842839e-02 , -1.6626442002366035e+00 , 8.5081536000000000e+00 , -5.6647999999999998e-01 , 4.1019099999999997e-01 , -7.1473299999999995e-01 -2.8465912391327786e-02 , -1.6816137182971604e+00 , 8.7462824000000001e+00 , 5.0697300000000001e-01 , -6.1378200000000005e-01 , 6.0518600000000000e-01 --2.1821101411121413e-01 , -2.0254825406104073e+00 , 9.4639448000000002e+00 , -5.7386999999999999e-01 , 7.3847499999999999e-01 , -3.5401800000000000e-01 --1.8774588059373265e-01 , -1.9023042888283581e+00 , 9.5337080000000007e+00 , -5.7386899999999996e-01 , 7.3847499999999999e-01 , -3.5401800000000000e-01 --3.2241808494836910e-01 , -2.0446326161784079e+00 , 1.0015987200000000e+01 , -2.7509800000000001e-01 , 9.6024399999999999e-01 , -4.7470199999999997e-02 --4.1072493646373465e-01 , -2.1042684250271453e+00 , 1.0396845600000001e+01 , -8.4203600000000001e-01 , 5.1750300000000005e-01 , -1.5220300000000000e-01 --3.7918564793483833e-01 , -1.9706323105967596e+00 , 1.0476551199999999e+01 , -8.4203600000000001e-01 , 5.1750300000000005e-01 , -1.5220300000000000e-01 -1.0735357423793168e-01 , -1.1488730139491854e+00 , 9.3413600000000017e+00 , -5.2925800000000001e-01 , -7.6335799999999998e-01 , 3.7036599999999997e-01 -1.0089261660601112e-01 , -1.0872139315590093e+00 , 9.4984728000000000e+00 , -4.2593500000000001e-01 , -6.0971500000000001e-01 , 6.6845100000000002e-01 --3.0206808942057961e-02 , -1.2042417312355234e+00 , 1.0006949600000000e+01 , -8.7662700000000005e-01 , -4.0613400000000000e-01 , -2.5803100000000001e-01 -1.8930705039973184e-01 , -8.1358554502110714e-01 , 9.5368279999999999e+00 , -8.7368199999999993e-02 , 2.7214499999999998e-03 , 9.9617199999999995e-01 -2.4985901733378846e-01 , -6.5534954120725697e-01 , 9.5024144000000010e+00 , -3.5834300000000002e-01 , -3.5310700000000000e-02 , 9.3292200000000003e-01 -2.7802618771758714e-01 , -5.4339719493684591e-01 , 9.5634312000000001e+00 , -6.7758900000000000e-01 , -1.1251500000000000e-01 , 7.2678299999999996e-01 -2.8881606071635479e-01 , -4.5502318157256250e-01 , 9.6776128000000003e+00 , -9.1794100000000001e-01 , -2.3655200000000001e-01 , 3.1847599999999998e-01 -2.6127052731509925e-01 , -4.1331137521464667e-01 , 9.9103440000000003e+00 , -4.9758799999999997e-01 , -7.2406800000000004e-01 , 4.7763099999999997e-01 -1.8487218197595934e-01 , -4.3113262178837264e-01 , 1.0311555200000001e+01 , 2.8935499999999997e-01 , 9.5627399999999996e-01 , -4.2582599999999998e-02 -7.7107220859566450e-02 , -4.7738416605386025e-01 , 1.0828476800000001e+01 , 7.6666999999999996e-01 , -3.6070500000000000e-01 , 5.3113900000000003e-01 -5.6467521566673717e-01 , 1.8822286717679559e-01 , 9.3769488000000010e+00 , -5.2588699999999999e-01 , 3.5984500000000003e-01 , 7.7068499999999995e-01 -5.8576198954657022e-01 , 2.8720521944618094e-01 , 9.4511320000000012e+00 , -5.6848500000000003e-02 , 4.2637199999999997e-01 , 9.0276000000000001e-01 -4.9849244995410591e-01 , 2.6705293441149291e-01 , 9.9069223999999991e+00 , -8.6466399999999999e-01 , -2.5611200000000001e-01 , -4.3216100000000002e-01 -3.7261438939282243e-01 , 2.1660971843897703e-01 , 1.0520387200000000e+01 , -5.8781800000000002e-02 , -3.8789800000000002e-01 , 9.1982600000000003e-01 -6.2295518277447637e-01 , 5.6020253703459932e-01 , 9.7810824000000007e+00 , 9.8917800000000000e-01 , 6.2470499999999998e-02 , -1.3275999999999999e-01 -4.9688502438669024e-01 , 5.2243298664174298e-01 , 1.0415212000000000e+01 , -1.7135400000000001e-01 , 9.8515299999999995e-01 , 1.0533600000000001e-02 -5.5341489865534266e-01 , 6.6632716228184563e-01 , 1.0377304000000001e+01 , -9.7524100000000002e-01 , -1.9578499999999999e-01 , 1.0283000000000000e-01 -8.8036605410109381e-01 , 1.0421904103343174e+00 , 9.2716696000000010e+00 , 1.5489600000000001e-01 , 2.1708300000000000e-01 , 9.6378500000000000e-01 -9.4071884777272508e-01 , 1.1714133957863022e+00 , 9.1828223999999992e+00 , 6.7178899999999997e-01 , -4.3508900000000000e-01 , 5.9949799999999998e-01 -8.7815089511587341e-01 , 1.2037241667404526e+00 , 9.5986143999999989e+00 , -3.6581300000000000e-01 , 6.2541800000000003e-01 , 6.8922700000000003e-01 -1.0030658905195258e+00 , 1.3801569749318996e+00 , 9.2361016000000014e+00 , -2.4284200000000000e-01 , -9.3687699999999996e-01 , 2.5157400000000002e-01 -7.3018926652401794e-01 , 1.2854129051123444e+00 , 1.0594393600000000e+01 , 6.9801500000000005e-01 , -1.5685899999999999e-02 , -7.1591099999999996e-01 -7.7370122307530820e-01 , 1.4154751826878145e+00 , 1.0600987200000000e+01 , 7.5676100000000002e-01 , -1.6588300000000000e-01 , -6.3229400000000002e-01 -7.2159933766166851e-01 , 1.4943082691725031e+00 , 1.1049674400000001e+01 , -8.3511400000000002e-01 , -3.1655200000000000e-01 , -4.4986599999999999e-01 -8.6030880962703593e-01 , 1.6730468915589018e+00 , 1.0617221600000001e+01 , -2.5041900000000000e-01 , -5.7221699999999998e-01 , -7.8093400000000002e-01 -9.5918727571350315e-01 , 1.8225522027288699e+00 , 1.0352656000000000e+01 , 4.3426300000000001e-01 , 6.9498099999999996e-01 , 5.7307600000000003e-01 -1.0109391767701847e+00 , 1.9494259951442718e+00 , 1.0308289600000000e+01 , 8.3084899999999995e-01 , -5.3525699999999998e-01 , -1.5228300000000000e-01 -1.0688003836513535e+00 , 2.0757488899855359e+00 , 1.0230861600000001e+01 , -7.3831199999999997e-01 , 6.3936300000000001e-01 , 2.1473200000000001e-01 -9.6077962623501101e-01 , 2.1723508867811616e+00 , 1.1029862400000001e+01 , -4.6528399999999998e-01 , -8.2611400000000001e-01 , 3.1787799999999999e-01 -1.1012144137324527e+00 , 2.3129334230777743e+00 , 1.0508531200000000e+01 , -8.1535400000000002e-01 , 3.4971500000000000e-01 , -4.6140799999999998e-01 -1.1727421715770210e+00 , 2.4367071079752320e+00 , 1.0352864000000000e+01 , -8.8545600000000002e-01 , 1.8367600000000001e-01 , -4.2688599999999999e-01 -1.3393043856032423e+00 , 2.5431598796085009e+00 , 9.6202776000000014e+00 , -8.3720600000000001e-01 , -4.8690900000000000e-04 , -5.4688700000000001e-01 -1.3730666734669359e+00 , 2.6536847904513814e+00 , 9.6437608000000008e+00 , -7.2328400000000004e-01 , 6.1602400000000002e-01 , -3.1204900000000002e-01 -1.3772272969436439e+00 , 2.7746729263216934e+00 , 9.8604240000000001e+00 , -8.0457699999999999e-01 , -1.0741199999999999e-01 , -5.8405300000000004e-01 -1.4316325045034204e+00 , 2.8809769759987591e+00 , 9.7566944000000007e+00 , -5.1509699999999999e-02 , 6.8834300000000004e-01 , 7.2355400000000003e-01 -1.4588012097308778e+00 , 2.9997708529847027e+00 , 9.8356303999999994e+00 , -3.9168399999999998e-01 , -6.9157900000000005e-01 , 6.0687899999999995e-01 -1.4895907112053781e+00 , 3.1201815805022051e+00 , 9.9022632000000002e+00 , -9.4054400000000005e-01 , 7.4053099999999997e-02 , 3.3150000000000002e-01 -1.5494746429542325e+00 , 3.2157909021182114e+00 , 9.7518792000000012e+00 , 6.4608500000000002e-01 , -1.6577800000000001e-01 , 7.4504499999999996e-01 -1.6566610928696912e+00 , 3.2551019664337253e+00 , 9.2214688000000002e+00 , 6.7363700000000004e-01 , -6.1909199999999998e-01 , -4.0365600000000001e-01 -1.9328966560480647e+00 , 1.9137330410610476e-01 , 1.2941842399999999e+00 , -6.6402900000000001e-02 , 2.2727000000000000e-01 , 9.7156500000000001e-01 -1.9041120153729989e+00 , 1.1641490131890952e-01 , 1.2954748800000000e+00 , -4.4740500000000002e-02 , 1.9129800000000000e-01 , 9.8051200000000005e-01 -1.8790683468196003e+00 , 5.6996684037766920e-02 , 1.3114232800000001e+00 , -7.1020899999999998e-02 , 2.2561700000000001e-01 , 9.7162400000000004e-01 -1.8512670854491762e+00 , -1.0631433776140842e-02 , 1.3229683200000000e+00 , -4.9799499999999997e-02 , 1.6035700000000000e-01 , 9.8580199999999996e-01 -1.8206116824402563e+00 , -8.7380391552782211e-02 , 1.3307183999999999e+00 , 8.1509499999999999e-02 , -1.4313899999999999e-01 , -9.8633999999999999e-01 -1.7855325958069748e+00 , -1.8066746075140738e-01 , 1.3292811200000001e+00 , -5.8975500000000000e-02 , 1.9847000000000001e-01 , 9.7833099999999995e-01 -1.7558710327244347e+00 , -2.4901224915903164e-01 , 1.3473833600000000e+00 , 5.8349400000000003e-02 , -1.6568500000000000e-01 , -9.8445099999999996e-01 -1.7190648399443202e+00 , -3.4325427697329003e-01 , 1.3513915200000000e+00 , -9.1900099999999998e-02 , 1.5818199999999999e-01 , 9.8312400000000000e-01 -1.6845869839871608e+00 , -4.2853510835758080e-01 , 1.3634451200000002e+00 , -6.9105299999999995e-02 , 1.8706000000000000e-01 , 9.7991499999999998e-01 -1.6470468400167206e+00 , -5.2367933364679597e-01 , 1.3733261600000000e+00 , -5.7794100000000001e-02 , 1.8411200000000000e-01 , 9.8120499999999999e-01 -1.6081416403987796e+00 , -6.1821951292383392e-01 , 1.3859153599999998e+00 , -6.5330500000000000e-02 , 1.8090500000000001e-01 , 9.8132799999999998e-01 -1.5661157505726817e+00 , -7.2251819805293449e-01 , 1.3968374400000001e+00 , -7.6663200000000001e-02 , 1.7754000000000000e-01 , 9.8112299999999997e-01 -1.5208964433290597e+00 , -8.3645218175745173e-01 , 1.4067007999999999e+00 , -7.5852000000000003e-02 , 1.7452699999999999e-01 , 9.8172700000000002e-01 -1.4780055005309516e+00 , -9.4143557495661945e-01 , 1.4246096000000001e+00 , -8.6277400000000004e-02 , 1.6820499999999999e-01 , 9.8196899999999998e-01 -1.4291419771088836e+00 , -1.0642048706544487e+00 , 1.4372591199999998e+00 , 1.1263300000000000e-01 , -1.3752200000000001e-01 , -9.8407400000000000e-01 -1.3674565717488361e+00 , -1.2250157806130915e+00 , 1.4375461600000001e+00 , -7.5888399999999995e-02 , 1.7442900000000000e-01 , 9.8174099999999997e-01 -1.3164704878061666e+00 , -1.3480455562456228e+00 , 1.4589784799999999e+00 , -5.6340899999999996e-03 , 2.9320299999999999e-01 , 9.5603400000000005e-01 -1.2706349065589158e+00 , -1.4540290951208963e+00 , 1.4923552000000000e+00 , -1.9322700000000002e-02 , 2.5386300000000001e-01 , 9.6704699999999999e-01 -1.2089873162915126e+00 , -1.6058656018114235e+00 , 1.5108880000000000e+00 , -4.0296899999999997e-02 , 2.1060699999999999e-01 , 9.7674000000000005e-01 -1.1496024428998255e+00 , -1.7486056525579934e+00 , 1.5380756799999999e+00 , -3.4503100000000002e-02 , 2.3867500000000000e-01 , 9.7048599999999996e-01 -1.0896644018621875e+00 , -1.8903966835389774e+00 , 1.5699163199999999e+00 , -4.4481899999999998e-02 , 2.2691100000000000e-01 , 9.7289899999999996e-01 -1.0162893430019193e+00 , -2.0713302832046336e+00 , 1.5943594399999999e+00 , 5.8373000000000001e-02 , -2.0241400000000001e-01 , -9.7755899999999996e-01 -9.4219100625727537e-01 , -2.2509991658655926e+00 , 1.6248730400000000e+00 , 5.6208000000000001e-02 , -2.2199500000000000e-01 , -9.7342600000000001e-01 -8.6133779837934288e-01 , -2.4503740421440448e+00 , 1.6563070400000000e+00 , -5.6200300000000002e-02 , 1.9590500000000000e-01 , 9.7901099999999996e-01 -7.6555447305731827e-01 , -2.6880693318417892e+00 , 1.6840615200000000e+00 , -5.0318099999999998e-02 , 2.1259800000000001e-01 , 9.7584300000000002e-01 -6.7482906539893039e-01 , -2.9052777958774696e+00 , 1.7249657599999999e+00 , 4.5426800000000003e-02 , -2.1805700000000000e-01 , -9.7487800000000002e-01 -5.7702386346527379e-01 , -3.1427356372917226e+00 , 1.7693217600000000e+00 , -5.4253000000000003e-02 , 2.1106000000000000e-01 , 9.7596600000000000e-01 -4.6387463237718585e-01 , -3.4177807088357417e+00 , 1.8135394400000000e+00 , 3.3562900000000000e-02 , 4.1408099999999998e-01 , 9.0962100000000001e-01 -3.5263907506180137e-01 , -3.6820597890416789e+00 , 1.8694446400000000e+00 , -1.4416599999999999e-01 , 2.5641300000000000e-01 , 9.5575600000000005e-01 -4.1245735540019490e-01 , -3.4527797964322993e+00 , 2.0241246720000001e+00 , -9.8170900000000005e-01 , 9.1493500000000005e-02 , -1.6696000000000000e-01 -4.0236651232490450e-01 , -3.4242535109827372e+00 , 2.1371999200000000e+00 , 3.6812299999999998e-01 , -8.8239999999999996e-01 , 2.9300999999999999e-01 -3.8298878974141415e-01 , -3.4229394769659427e+00 , 2.2449657599999999e+00 , 6.1697199999999996e-01 , 7.8521799999999997e-01 , -5.2712599999999998e-02 -3.7844736761677900e-01 , -3.3809576773250773e+00 , 2.3575187199999998e+00 , -8.3784499999999995e-01 , -5.4581100000000005e-01 , 1.0269100000000000e-02 -3.6453711010629331e-01 , -3.3660455695360367e+00 , 2.4654717599999998e+00 , 8.1037300000000001e-01 , 5.8554600000000001e-01 , -2.0768700000000001e-02 -3.4753217997733121e-01 , -3.3587431657270770e+00 , 2.5718533600000000e+00 , -8.0055399999999999e-01 , -5.9904800000000002e-01 , 1.5939700000000001e-02 -3.3159541085949473e-01 , -3.3504283706625673e+00 , 2.6782568000000002e+00 , -7.5676600000000005e-01 , -6.5132900000000005e-01 , 5.5460099999999998e-02 -3.1248201324553038e-01 , -3.3495807199971992e+00 , 2.7837970400000001e+00 , 7.1831999999999996e-01 , 6.9391199999999997e-01 , -5.0016400000000003e-02 -3.0204342539071871e-01 , -3.3277146823004102e+00 , 2.8900829600000000e+00 , -6.3934700000000000e-01 , -7.6805500000000004e-01 , -3.6418800000000001e-02 -2.8736004802865289e-01 , -3.3143281802583084e+00 , 2.9955857600000000e+00 , 6.0348599999999997e-01 , 7.9737100000000005e-01 , -2.0740200000000002e-03 -2.6279970883929504e-01 , -3.3271275006661929e+00 , 3.1007359999999999e+00 , -4.3821800000000000e-01 , -8.9600999999999997e-01 , -7.1634000000000003e-02 -2.2807386349514980e-01 , -3.3688770729717206e+00 , 3.2075752000000000e+00 , -3.8938400000000001e-01 , 9.0874100000000002e-01 , -1.5023400000000001e-01 -1.9323904194369090e-01 , -3.4071575444562523e+00 , 3.3158183999999999e+00 , -3.8938400000000001e-01 , 9.0874100000000002e-01 , -1.5023400000000001e-01 -2.0076187266148460e-01 , -3.3377400607030117e+00 , 3.4195272000000001e+00 , -3.8938400000000001e-01 , 9.0874100000000002e-01 , -1.5023400000000001e-01 -1.9829053941636721e-01 , -3.2964952893864972e+00 , 3.5236000000000001e+00 , -3.8938400000000001e-01 , 9.0874100000000002e-01 , -1.5023400000000001e-01 --1.4683569498782996e+00 , -7.4287571509122685e+00 , 4.0289359999999999e+00 , -9.5375600000000005e-01 , 8.8523199999999996e-02 , -2.8725099999999998e-01 --5.2975849430375979e+00 , -1.6870838711581182e+01 , 5.3028112000000007e+00 , 9.8762799999999995e-01 , 1.3363000000000000e-01 , 8.2055500000000003e-02 --5.3309376983471752e+00 , -1.6790585153097719e+01 , 5.6573056000000008e+00 , 9.8762799999999995e-01 , 1.3363000000000000e-01 , 8.2055500000000003e-02 --5.3627560805920140e+00 , -1.6704290338842618e+01 , 6.0101984000000002e+00 , -9.7041100000000002e-01 , -1.1720999999999999e-01 , -2.1110100000000001e-01 --5.4468855691385798e+00 , -1.6745220159424843e+01 , 6.3845048000000002e+00 , 9.6011000000000002e-01 , 7.6375600000000002e-02 , 2.6898899999999998e-01 --5.6979963271103271e+00 , -1.7186308567106177e+01 , 6.8400352000000000e+00 , -9.0664400000000001e-01 , -1.3560000000000000e-01 , -3.9951199999999998e-01 --5.7230959297491069e+00 , -1.7079763276101009e+01 , 7.2003328000000009e+00 , -9.2712799999999995e-01 , -1.0185600000000000e-01 , -3.6063600000000001e-01 --5.9200541017625490e+00 , -1.7380201588033966e+01 , 7.6540432000000003e+00 , -9.5474099999999995e-01 , -2.5153900000000001e-01 , -1.5873699999999999e-01 --5.9685345802618812e+00 , -1.7325829347428346e+01 , 8.0344648000000003e+00 , -9.4922399999999996e-01 , -2.9171799999999998e-01 , -1.1779000000000001e-01 --6.0027675533596323e+00 , -1.7236522192054945e+01 , 8.4073880000000010e+00 , -9.4265200000000005e-01 , -3.3342400000000000e-01 , 1.5362100000000000e-02 --6.0467729704025555e+00 , -1.7169676250436332e+01 , 8.7876744000000002e+00 , -9.4549700000000003e-01 , -3.2522400000000001e-01 , 1.6256900000000001e-02 --6.0801175495613560e+00 , -1.7076899436259936e+01 , 9.1619288000000001e+00 , -9.4610399999999995e-01 , -3.2335999999999998e-01 , 1.8024499999999999e-02 --6.1149414225932794e+00 , -1.6987818177473045e+01 , 9.5386063999999990e+00 , 9.7574000000000005e-01 , 2.0514600000000000e-01 , -7.6465800000000000e-02 --6.1632304773956808e+00 , -1.6928631947568700e+01 , 9.9275352000000012e+00 , 9.8013799999999995e-01 , 9.4649300000000006e-02 , -1.7427200000000001e-01 --6.0432309461891318e+00 , -1.6493534744784988e+01 , 1.0178809599999999e+01 , -9.7555999999999998e-01 , 8.3188900000000007e-03 , 2.1957599999999999e-01 --5.9894719263790748e+00 , -1.6209602739774873e+01 , 1.0477040000000001e+01 , -9.7679899999999997e-01 , -4.2029799999999999e-02 , 2.0999300000000001e-01 --6.0300545876598406e+00 , -1.6133467636784399e+01 , 1.0856452800000000e+01 , 9.8958900000000005e-01 , 7.2674400000000000e-02 , -1.2422700000000000e-01 --5.9182627425195315e+00 , -1.5726456909063216e+01 , 1.1092907200000001e+01 , 9.9332100000000001e-01 , -1.2411500000000001e-02 , 1.1471400000000000e-01 --6.1236396919371945e+00 , -1.6005256438890466e+01 , 1.1636400800000001e+01 , 9.9866100000000002e-01 , 1.5276900000000000e-02 , 4.9434400000000003e-02 --6.1479638765844609e+00 , -1.5891019780845660e+01 , 1.2008668800000001e+01 , 9.9321800000000005e-01 , 3.7147600000000003e-02 , 1.1017500000000000e-01 --6.0727343510412215e+00 , -1.5565382924420380e+01 , 1.2275480800000000e+01 , 9.9028000000000005e-01 , 1.1031900000000001e-02 , 1.3865000000000000e-01 --6.5657393033254419e+00 , -1.5726124008251599e+01 , 1.4640160000000000e+01 , 9.9866299999999997e-01 , -5.1690600000000003e-02 , -9.2955900000000005e-04 --7.2488241498623491e+00 , -1.6909615044026545e+01 , 1.5914368000000001e+01 , -9.5910399999999996e-01 , -9.7426799999999994e-02 , 2.6575799999999999e-01 --6.5287937523384301e+00 , -1.5298524539638429e+01 , 1.5331864000000001e+01 , 9.9350499999999997e-01 , -3.5372700000000000e-02 , -1.0814900000000000e-01 --6.5039898785804375e+00 , -1.5072246270371146e+01 , 1.5669656000000002e+01 , 9.9845300000000003e-01 , -4.2112399999999998e-03 , -5.5439599999999999e-02 --6.5332727391076144e+00 , -1.4949252183621635e+01 , 1.6084304000000003e+01 , 9.9779600000000002e-01 , 2.1946600000000000e-02 , -6.2623700000000004e-02 --6.5112759714918180e+00 , -1.4725877478217342e+01 , 1.6428024000000001e+01 , 9.8704199999999997e-01 , 1.4347100000000000e-02 , -1.5981899999999999e-01 --6.5810150916504639e+00 , -1.4677087960495832e+01 , 1.6913808000000000e+01 , 9.7994999999999999e-01 , 1.0548200000000001e-02 , -1.9896200000000000e-01 --6.4502704737568006e+00 , -1.4248407955238015e+01 , 1.7092896000000000e+01 , 9.9652399999999997e-01 , 6.4815200000000003e-02 , -5.2339400000000001e-02 --6.8631688154567847e+00 , -1.4828407569635651e+01 , 1.8141840000000002e+01 , 9.7301400000000005e-01 , 6.6439899999999996e-02 , 2.2097300000000000e-01 --6.8351653755756772e+00 , -1.4585457314984978e+01 , 1.8499704000000001e+01 , 9.7301400000000005e-01 , 6.6439899999999996e-02 , 2.2097300000000000e-01 --6.4102438351276225e-01 , -3.0548208243138504e+00 , 8.6232296000000019e+00 , -4.0106300000000000e-01 , -3.9561000000000002e-01 , 8.2622099999999998e-01 --5.5791881721849723e-01 , -2.8423722703598413e+00 , 8.6097719999999995e+00 , -1.8936200000000000e-01 , -1.0224700000000000e-01 , 9.7656900000000002e-01 --1.7479343623957000e-01 , -2.1164402988637843e+00 , 8.0256664000000004e+00 , 1.4965800000000001e-01 , 9.8480199999999996e-01 , 8.8137800000000002e-02 --4.5490976849926623e-01 , -2.5347360897250546e+00 , 8.6882608000000001e+00 , 8.1815899999999997e-01 , -4.8627700000000001e-01 , 3.0684000000000000e-01 --3.8245568160430121e-01 , -2.3471129127753594e+00 , 8.6810328000000005e+00 , 4.8754900000000001e-01 , -8.5821199999999997e-01 , 1.6052700000000000e-01 --4.3555351597707537e-01 , -2.3038318849987283e+00 , 9.0637216000000009e+00 , 7.4786200000000003e-01 , -6.6306699999999996e-01 , 3.2316699999999997e-02 --4.8900463022834195e-01 , -2.3222542019175636e+00 , 9.3192808000000014e+00 , -8.1485099999999999e-01 , 5.7845999999999997e-01 , 3.7442499999999997e-02 --7.2898918432223736e-01 , -2.6318176312013764e+00 , 9.9872416000000008e+00 , 6.3265800000000005e-01 , -1.3855000000000001e-01 , -7.6193699999999998e-01 --6.9693346046104621e-01 , -2.5053881701737541e+00 , 1.0078761600000000e+01 , 6.3265800000000005e-01 , -1.3855000000000001e-01 , -7.6193699999999998e-01 --6.4334547248351726e-01 , -2.3445208441422682e+00 , 1.0119196800000001e+01 , 6.3265800000000005e-01 , -1.3855000000000001e-01 , -7.6193699999999998e-01 --5.8507286786106860e-01 , -2.1788094700009752e+00 , 1.0147744800000000e+01 , -7.3995800000000000e-01 , 1.9460100000000000e-01 , 6.4388800000000002e-01 --7.4701910383872550e-01 , -2.3405994482652330e+00 , 1.0696251199999999e+01 , 7.9456800000000005e-01 , -4.0021400000000001e-01 , 4.5660800000000001e-01 --5.3454113028233596e-01 , -1.9463290328141998e+00 , 1.0353269600000001e+01 , -6.3963800000000004e-01 , -7.0587400000000000e-01 , 3.0431000000000002e-01 --2.0275503050048549e-02 , -1.1300065236073413e+00 , 9.2391383999999999e+00 , -7.7545500000000003e-02 , -3.5544900000000001e-01 , 9.3147300000000000e-01 -2.3777837392260137e-02 , -9.9989286546602996e-01 , 9.2671664000000007e+00 , -5.2925800000000001e-01 , -7.6335799999999998e-01 , 3.7036599999999997e-01 -4.5511303085187249e-02 , -9.0174507095910128e-01 , 9.3531535999999988e+00 , 6.3853400000000005e-01 , 1.8541099999999999e-01 , -7.4692499999999995e-01 --7.8828689058907386e-04 , -8.9535112631788127e-01 , 9.6227112000000012e+00 , -1.1203500000000000e-01 , -3.9764200000000000e-01 , 9.1067500000000001e-01 -9.8224166539079061e-02 , -6.9227396568085187e-01 , 9.5028615999999992e+00 , -3.3745199999999997e-01 , 2.0064499999999999e-01 , 9.1971099999999995e-01 -1.5103476991911702e-01 , -5.5322234376698765e-01 , 9.5033504000000004e+00 , -5.8251799999999998e-01 , -7.0981000000000002e-02 , 8.0971300000000002e-01 -2.1076369222996627e-01 , -4.0710175536773230e-01 , 9.4824464000000006e+00 , 7.7045600000000003e-01 , -3.6038100000000001e-01 , -5.2585499999999996e-01 -1.9531902815347402e-01 , -3.5436286997749722e-01 , 9.6776544000000015e+00 , -8.1324200000000002e-01 , -5.3166500000000005e-01 , 2.3657800000000001e-01 -2.0292578135489969e-01 , -2.7096360872721670e-01 , 9.8086424000000001e+00 , 7.7253099999999997e-01 , 5.5816399999999999e-01 , -3.0273600000000001e-01 --1.2444158678595407e-01 , -5.7363228722258208e-01 , 1.0971799200000001e+01 , 8.3649899999999999e-01 , -5.4782799999999998e-01 , 1.2371999999999999e-02 -4.2950581158309920e-01 , 1.3812462266629133e-01 , 9.4209616000000000e+00 , 5.5690799999999996e-01 , -1.7736900000000000e-01 , -8.1141500000000000e-01 -5.1224933605378498e-01 , 3.0084846637239671e-01 , 9.3081631999999992e+00 , 5.1449199999999995e-01 , -2.6648100000000002e-01 , -8.1503700000000001e-01 -5.7888797574462214e-01 , 4.4324435774119531e-01 , 9.2386080000000010e+00 , -9.7096899999999997e-01 , -4.8944599999999998e-02 , 2.3414499999999999e-01 -2.7012804939073121e-01 , 2.0399497076430095e-01 , 1.0430635199999999e+01 , -5.8781399999999998e-02 , -3.8789800000000002e-01 , 9.1982600000000003e-01 -3.1518068802755073e-01 , 3.3415202381829490e-01 , 1.0459089600000000e+01 , -5.5626500000000001e-01 , 3.3614100000000002e-01 , -7.5998600000000005e-01 -5.6808935833991514e-01 , 6.5769599874056950e-01 , 9.7473239999999990e+00 , -9.0564500000000003e-01 , -3.9752900000000002e-01 , 1.4757500000000001e-01 -3.6699233501807882e-01 , 5.6152248034976426e-01 , 1.0644760800000000e+01 , -2.8728799999999999e-01 , 3.5047699999999999e-03 , 9.5783799999999997e-01 -5.5607147552309910e-01 , 8.1309353877165136e-01 , 1.0136596000000001e+01 , -4.1522399999999998e-01 , 3.5633900000000000e-03 , 9.0971199999999997e-01 -8.1651481964661810e-01 , 1.1086287518232343e+00 , 9.3242832000000000e+00 , 1.1704000000000001e-01 , 2.0217599999999999e-01 , 9.7233099999999995e-01 -8.6958961557235104e-01 , 1.2269035066301746e+00 , 9.2849503999999996e+00 , -6.4781300000000000e-02 , -1.0179100000000001e-01 , -9.9269399999999997e-01 -6.6940208837000914e-01 , 1.1693259467595958e+00 , 1.0258213600000001e+01 , -3.7941300000000000e-01 , 4.5330599999999999e-01 , 8.0657299999999998e-01 -5.9689317780667239e-01 , 1.2168600065010446e+00 , 1.0757996000000000e+01 , -5.9356699999999996e-01 , 5.4520800000000003e-01 , 5.9196800000000005e-01 -6.8311337393911731e-01 , 1.3705992238902729e+00 , 1.0606634400000001e+01 , -5.5251200000000000e-01 , 6.6957100000000006e-02 , 8.3081099999999997e-01 -7.0790651559105977e-01 , 1.4876795523645352e+00 , 1.0713442400000002e+01 , -8.8838099999999998e-01 , -4.5899600000000002e-01 , 1.0067400000000001e-02 -7.6055229130994806e-01 , 1.6201631855859218e+00 , 1.0697093600000001e+01 , 5.9091000000000005e-01 , -3.7075100000000000e-01 , -7.1649700000000005e-01 -8.5142741981245451e-01 , 1.7657534670949619e+00 , 1.0506264000000000e+01 , -4.0516700000000000e-01 , -6.5475099999999997e-01 , -6.3807599999999998e-01 -9.4403119728758633e-01 , 1.9054334700613058e+00 , 1.0291743200000001e+01 , -1.0473100000000000e-01 , 7.5196399999999997e-01 , 6.5083100000000005e-01 -1.0175119539622890e+00 , 2.0340365421428994e+00 , 1.0155180800000000e+01 , 2.9224400000000000e-01 , -8.3357199999999998e-01 , -4.6877600000000003e-01 -1.0180333167443580e+00 , 2.1446782283779955e+00 , 1.0382961600000000e+01 , 8.1642599999999999e-01 , -5.7174199999999997e-01 , 8.0998399999999998e-02 -9.4840522517405734e-01 , 2.2545234940744554e+00 , 1.0997643199999999e+01 , -6.1671200000000004e-01 , -6.7277500000000001e-01 , 4.0870699999999999e-01 -1.0846025585811156e+00 , 2.3874906985791697e+00 , 1.0527199200000000e+01 , -8.2299400000000000e-01 , 3.3963100000000002e-01 , -4.5533699999999999e-01 -1.1393688099495960e+00 , 2.5111679030161573e+00 , 1.0483425600000000e+01 , 7.6001500000000000e-01 , -2.2387099999999999e-01 , 6.1012999999999995e-01 -1.3370103597266914e+00 , 2.6065422750689260e+00 , 9.5970751999999990e+00 , 6.7469699999999999e-01 , 3.8102599999999998e-01 , 6.3214099999999995e-01 -1.2332105516058642e+00 , 2.7562531670648243e+00 , 1.0481387200000000e+01 , -1.0357600000000000e-01 , -1.2838700000000000e-01 , 9.8630099999999998e-01 -1.3930978456235068e+00 , 2.8321934586611919e+00 , 9.7645775999999991e+00 , -7.6460899999999998e-01 , -4.2274299999999998e-01 , -4.8648000000000002e-01 -1.4481311329861299e+00 , 2.9361947874242835e+00 , 9.6811696000000005e+00 , -2.5465700000000002e-01 , 9.4541699999999995e-01 , 2.0331500000000000e-01 -1.4702274301634457e+00 , 3.0579991824238681e+00 , 9.8108368000000006e+00 , -6.3303799999999999e-01 , 7.7040600000000004e-01 , 7.5745000000000007e-02 -1.5197505921770977e+00 , 3.1643906621596440e+00 , 9.7644528000000008e+00 , 5.4935900000000004e-01 , -7.8847100000000003e-01 , 2.7661900000000000e-01 -1.5792645374877405e+00 , 3.2587471046490224e+00 , 9.6341719999999995e+00 , 3.4477700000000000e-01 , 9.2759999999999998e-01 , -1.4383000000000001e-01 -1.7100394824732055e+00 , 3.2642881269915915e+00 , 8.9306120000000000e+00 , 9.7129699999999997e-01 , -1.5324299999999999e-01 , -1.8193300000000001e-01 -1.8625882123814901e+00 , 1.7644193945870112e-01 , 1.2841669599999999e+00 , -1.8172899999999999e-02 , 2.3752499999999999e-01 , 9.7121100000000005e-01 -1.8356301269168562e+00 , 1.1789842201200273e-01 , 1.2987488000000000e+00 , -2.9286699999999999e-02 , 1.9178200000000001e-01 , 9.8099999999999998e-01 -1.8033586738932992e+00 , 4.2583387661416783e-02 , 1.3028027199999999e+00 , -6.5793900000000002e-02 , 1.9270899999999999e-01 , 9.7904800000000003e-01 -1.7734165769619379e+00 , -2.3770243643097544e-02 , 1.3149020800000000e+00 , -9.3972600000000003e-02 , 1.6500999999999999e-01 , 9.8180500000000004e-01 -1.7380061890778646e+00 , -1.0771204915322130e-01 , 1.3175904799999998e+00 , -8.7575399999999998e-02 , 1.6632600000000000e-01 , 9.8217399999999999e-01 -1.7048850273660281e+00 , -1.8372990418155011e-01 , 1.3285292000000000e+00 , -4.9313200000000001e-02 , 2.0165700000000000e-01 , 9.7821400000000003e-01 -1.6704674325165354e+00 , -2.5925714101414243e-01 , 1.3415687200000002e+00 , 9.2677099999999998e-02 , -1.6783300000000001e-01 , -9.8144900000000002e-01 -1.6314515689814277e+00 , -3.5320428458649111e-01 , 1.3465399200000001e+00 , -8.9871199999999998e-02 , 1.5099099999999999e-01 , 9.8444200000000004e-01 -1.5910706497988194e+00 , -4.4654738214666256e-01 , 1.3542171999999999e+00 , -6.7777299999999999e-02 , 1.9142700000000001e-01 , 9.7916400000000003e-01 -1.5529871385649336e+00 , -5.3197548222082336e-01 , 1.3700449600000000e+00 , -5.5466399999999999e-02 , 1.8139600000000000e-01 , 9.8184499999999997e-01 -1.5081297021949531e+00 , -6.3449239192517792e-01 , 1.3786624000000001e+00 , -7.4568300000000004e-02 , 1.8994700000000000e-01 , 9.7895900000000002e-01 -1.4655778555501806e+00 , -7.2910325713930701e-01 , 1.3954303200000000e+00 , -8.0841800000000005e-02 , 1.8258300000000000e-01 , 9.7986099999999998e-01 -1.4171384972119410e+00 , -8.4166317643396393e-01 , 1.4061277599999999e+00 , -7.7884499999999995e-02 , 1.7662200000000000e-01 , 9.8119299999999998e-01 -1.3654905622340998e+00 , -9.6273664568782102e-01 , 1.4160670399999999e+00 , 1.0879800000000001e-01 , -1.5573600000000001e-01 , -9.8178900000000002e-01 -1.3028706498551537e+00 , -1.1116610752997995e+00 , 1.4172089600000000e+00 , -1.3122900000000001e-01 , 1.5387200000000001e-01 , 9.7933800000000004e-01 -1.2452331960942427e+00 , -1.2432337636078179e+00 , 1.4317107199999999e+00 , -3.4763900000000000e-02 , 2.4569900000000000e-01 , 9.6872300000000000e-01 -1.1965988782767283e+00 , -1.3475031568153404e+00 , 1.4624791200000000e+00 , -2.5647500000000000e-02 , 2.9021999999999998e-01 , 9.5661600000000002e-01 -1.1408328193398458e+00 , -1.4693052958832897e+00 , 1.4889741599999999e+00 , -3.9373900000000003e-02 , 2.4979299999999999e-01 , 9.6749799999999997e-01 -1.0748367889175521e+00 , -1.6195826245149227e+00 , 1.5090264000000000e+00 , -5.3108400000000000e-02 , 2.1964400000000001e-01 , 9.7413300000000003e-01 -1.0111198665465053e+00 , -1.7607920091187865e+00 , 1.5376295199999999e+00 , -5.0660900000000002e-02 , 2.4644600000000000e-01 , 9.6783200000000003e-01 -9.3993815338274112e-01 , -1.9200897821976080e+00 , 1.5644927200000001e+00 , -5.8640200000000003e-02 , 2.1478700000000001e-01 , 9.7489899999999996e-01 -8.5718695006220602e-01 , -2.1072747452745695e+00 , 1.5875193599999999e+00 , -6.7456699999999994e-02 , 2.1395900000000001e-01 , 9.7451100000000002e-01 -7.7462734726724825e-01 , -2.2951955102532668e+00 , 1.6174557599999999e+00 , -6.4674999999999996e-02 , 2.2811400000000001e-01 , 9.7148400000000001e-01 -6.8623234249798082e-01 , -2.4917060135165814e+00 , 1.6509375200000000e+00 , -6.3466999999999996e-02 , 2.0366699999999999e-01 , 9.7698099999999999e-01 -5.8693189181927208e-01 , -2.7165527321643861e+00 , 1.6837474399999999e+00 , -5.7699300000000002e-02 , 2.2464300000000001e-01 , 9.7273100000000001e-01 -4.8562898312420710e-01 , -2.9407866628450021e+00 , 1.7244270400000001e+00 , -6.0300399999999997e-02 , 2.2555000000000000e-01 , 9.7236400000000001e-01 -3.6594318112766855e-01 , -3.2136337369461643e+00 , 1.7623953600000000e+00 , -2.8625299999999999e-02 , 3.8508199999999998e-01 , 9.2243799999999998e-01 -2.5846782104481947e-01 , -3.4462604411102875e+00 , 1.8180842399999999e+00 , -2.9648500000000000e-01 , 2.2500600000000001e-01 , 9.2815400000000003e-01 -9.5198183085117405e-02 , -3.8227457514504755e+00 , 1.8540432800000000e+00 , 2.2500600000000001e-01 , -2.7843200000000001e-01 , -9.3372800000000000e-01 --6.2458032709210354e-02 , -4.1790242561788595e+00 , 1.9072266959999999e+00 , -7.2634799999999999e-02 , 2.1062100000000000e-01 , 9.7486600000000001e-01 --2.3738207791116661e-01 , -4.5735028066583805e+00 , 1.9673358880000000e+00 , 5.0609700000000001e-02 , -2.1573300000000001e-01 , -9.7514000000000001e-01 --4.3715761386426122e-01 , -5.0240498225658579e+00 , 2.0337429039999999e+00 , -7.1605699999999994e-02 , 2.2432800000000000e-01 , 9.7187999999999997e-01 --6.5057575627339093e-01 , -5.5021508517470101e+00 , 2.1133194400000002e+00 , -5.8192300000000002e-02 , 2.4147600000000000e-01 , 9.6866099999999999e-01 --8.7460699947633547e-01 , -5.9978854764645329e+00 , 2.2085418400000001e+00 , 4.8568899999999998e-02 , -2.3453399999999999e-01 , -9.7089400000000003e-01 --1.1543421012404504e+00 , -6.6267745738001285e+00 , 2.3108040000000001e+00 , -1.5235300000000000e-02 , 4.9748799999999999e-01 , 8.6733700000000002e-01 --1.4916941332678646e+00 , -7.3872852567447502e+00 , 2.4273661600000001e+00 , -8.0418999999999996e-01 , 4.5027000000000000e-01 , 3.8798899999999997e-01 --1.8497191992369575e+00 , -8.1840121505276979e+00 , 2.5705658400000000e+00 , -9.3036700000000000e-02 , 1.8137100000000000e-01 , 9.7900399999999999e-01 --1.6350280541624924e+00 , -7.5713217887747053e+00 , 2.7851095199999998e+00 , -8.6805600000000005e-01 , 4.7917300000000002e-01 , 1.2989100000000001e-01 --1.3214017988217628e+00 , -6.7258576774553944e+00 , 2.9797039200000000e+00 , -2.4599099999999999e-01 , -9.5454700000000003e-01 , 1.6831199999999999e-01 --1.3327323054943196e+00 , -6.6763490247588884e+00 , 3.1492312000000000e+00 , 5.2718299999999996e-01 , 8.0818800000000002e-01 , -2.6250800000000002e-01 --1.3748519797847560e+00 , -6.7007831683630261e+00 , 3.3193855999999999e+00 , 5.2718299999999996e-01 , 8.0818800000000002e-01 , -2.6250800000000002e-01 --1.3593843738154359e+00 , -6.5884763706254983e+00 , 3.4848808000000000e+00 , 5.2718299999999996e-01 , 8.0818800000000002e-01 , -2.6250800000000002e-01 --1.7410212231660811e+00 , -7.4098013251405970e+00 , 3.7064839999999997e+00 , -9.6245800000000004e-01 , 2.7004499999999998e-01 , -2.7390600000000001e-02 --5.4087670612968886e+00 , -1.5843896720368740e+01 , 4.5892879999999998e+00 , -9.3598700000000001e-01 , -3.2085599999999997e-01 , 1.4484500000000000e-01 --5.5179068200532564e+00 , -1.5945712989886939e+01 , 4.9461431999999999e+00 , 9.9358999999999997e-01 , 1.1288500000000000e-01 , -5.9788000000000003e-03 --5.5666296027490159e+00 , -1.5907943844193902e+01 , 5.2920992000000000e+00 , 9.9115500000000001e-01 , 1.2887999999999999e-01 , 3.1664400000000002e-02 --5.5812349308980771e+00 , -1.5789827002085513e+01 , 5.6274264000000001e+00 , 9.9401899999999999e-01 , 9.9461499999999994e-02 , -4.5097400000000003e-02 --5.5371876407131726e+00 , -1.5543836728449811e+01 , 5.9405600000000005e+00 , -9.6285100000000001e-01 , -1.8453400000000000e-01 , -1.9714499999999999e-01 --5.6925974712331060e+00 , -1.5743001939713640e+01 , 6.3262960000000001e+00 , 9.6831299999999998e-01 , 1.4230400000000001e-01 , 2.0523000000000000e-01 --5.7797820052466999e+00 , -1.5785612201069707e+01 , 6.6917000000000009e+00 , 9.7225200000000001e-01 , 2.1575900000000001e-01 , 9.0407600000000005e-02 --5.8165450861671708e+00 , -1.5719420470036031e+01 , 7.0384567999999996e+00 , -9.3159400000000003e-01 , -3.6349999999999999e-01 , -1.6626000000000000e-04 --5.8439475742226072e+00 , -1.5629259282996529e+01 , 7.3801696000000003e+00 , -9.3621500000000002e-01 , -3.5041400000000000e-01 , 2.6678299999999999e-02 --5.8761708465996261e+00 , -1.5551960224183912e+01 , 7.7254600000000000e+00 , -9.3311900000000003e-01 , -3.5910500000000001e-01 , 1.8248100000000000e-02 --5.9153980730529554e+00 , -1.5487223037337561e+01 , 8.0750039999999998e+00 , -9.1286800000000001e-01 , -4.0496599999999999e-01 , 5.1719500000000002e-02 --5.9383116883728029e+00 , -1.5389891111593879e+01 , 8.4163943999999997e+00 , -9.0740600000000005e-01 , -4.1625400000000001e-01 , 5.7856499999999998e-02 --5.9767524478112799e+00 , -1.5321704927554929e+01 , 8.7677687999999989e+00 , -9.0165700000000004e-01 , -4.2708200000000002e-01 , 6.7941199999999993e-02 --6.0034634901363670e+00 , -1.5230766886087640e+01 , 9.1133504000000016e+00 , -8.9776900000000004e-01 , -4.3450299999999997e-01 , 7.2242000000000001e-02 --6.0279060093176469e+00 , -1.5133744884499993e+01 , 9.4579544000000002e+00 , -8.9346999999999999e-01 , -4.4295899999999999e-01 , 7.4155799999999994e-02 --6.0670175528760666e+00 , -1.5066437481812933e+01 , 9.8153088000000004e+00 , -8.9937000000000000e-01 , -4.1141400000000000e-01 , 1.4789099999999999e-01 --6.0954214108178917e+00 , -1.4975524245339795e+01 , 1.0165726400000000e+01 , -8.9268099999999995e-01 , -4.2411799999999999e-01 , 1.5246000000000001e-01 --6.1290179620685450e+00 , -1.4895638452459821e+01 , 1.0523268000000000e+01 , 9.8710600000000004e-01 , 1.4867800000000000e-01 , -5.9293499999999999e-02 --6.0620235792248049e+00 , -1.4611039696096789e+01 , 1.0790828800000000e+01 , -9.6633100000000005e-01 , -2.5116899999999998e-01 , -5.5840099999999997e-02 --6.2453902247080801e+00 , -1.4828287517379792e+01 , 1.1291193600000000e+01 , 9.8074300000000003e-01 , 1.8107100000000001e-01 , 7.3188699999999995e-02 --6.2937564014404259e+00 , -1.4770814764702578e+01 , 1.1671604800000001e+01 , 9.4952999999999999e-01 , 2.4561900000000000e-01 , 1.9510000000000000e-01 --6.2693090783374821e+00 , -1.4572092618958578e+01 , 1.1983219999999999e+01 , -9.6572300000000000e-01 , -2.2755700000000001e-01 , -1.2488900000000000e-01 --6.4490822612804379e+00 , -1.4767282846107783e+01 , 1.2509512000000001e+01 , -9.6228700000000000e-01 , -2.2746000000000000e-01 , -1.4921599999999999e-01 --6.4883302599609021e+00 , -1.4686738699259124e+01 , 1.2896080000000001e+01 , -9.5929500000000001e-01 , -2.7752399999999999e-01 , -5.2285699999999997e-02 --6.5166047343453730e+00 , -1.4582853176175867e+01 , 1.3273600000000000e+01 , -9.3718299999999999e-01 , -3.4631499999999998e-01 , 4.1883600000000000e-02 --6.5366796988143765e+00 , -1.4463404433723014e+01 , 1.3646128000000001e+01 , -9.3393899999999996e-01 , -3.5330000000000000e-01 , 5.4187600000000002e-02 --6.5801631617022913e+00 , -1.4385522817052095e+01 , 1.4049544000000001e+01 , -9.2942499999999995e-01 , -3.6384100000000003e-01 , 6.1562899999999997e-02 --6.6115326236466760e+00 , -1.4283644177125371e+01 , 1.4443600000000000e+01 , -9.4643500000000003e-01 , -3.1240499999999999e-01 , 8.1633899999999995e-02 --6.6487146272119748e+00 , -1.4189735173068943e+01 , 1.4848991999999999e+01 , 9.6708000000000005e-01 , 2.3745100000000000e-01 , -9.1504600000000005e-02 --6.6876514312252144e+00 , -1.4095545193234386e+01 , 1.5260832000000001e+01 , 9.9328799999999995e-01 , 1.0021099999999999e-01 , -5.7767199999999998e-02 --6.7263651009077776e+00 , -1.4000885520872234e+01 , 1.5679952000000000e+01 , 9.9750099999999997e-01 , 6.9574899999999995e-02 , -1.2262199999999999e-02 --6.7288910116196234e+00 , -1.3837661733196924e+01 , 1.6052376000000002e+01 , 9.9782000000000004e-01 , 4.7020100000000002e-02 , -4.6307599999999997e-02 --6.7822999471097738e+00 , -1.3762641031348640e+01 , 1.6502696000000000e+01 , 9.8403799999999997e-01 , 5.6318399999999998e-02 , -1.6881399999999999e-01 --6.7579946036405438e+00 , -1.3548560956519516e+01 , 1.6843192000000002e+01 , 9.9990599999999996e-01 , 5.0808900000000002e-03 , 1.2750400000000000e-02 --6.6175585305735662e+00 , -1.3136804908736941e+01 , 1.7008864000000003e+01 , 9.8969099999999999e-01 , 8.9278800000000005e-02 , 1.1198300000000000e-01 --6.9749310627499792e+00 , -1.3570888644914442e+01 , 1.7950792000000000e+01 , 9.7086300000000003e-01 , 4.7528599999999997e-02 , 2.3487300000000000e-01 --6.9721679330489330e+00 , -1.3386643050572935e+01 , 1.8344016000000000e+01 , -9.4433800000000001e-01 , -9.4262299999999993e-02 , -3.1518200000000002e-01 --8.1916996994463487e-01 , -2.9469343419563074e+00 , 8.6569152000000003e+00 , -3.7909300000000001e-01 , 1.3416200000000000e-02 , 9.2526100000000000e-01 --5.9936735705230326e-01 , -2.4658837187947702e+00 , 8.5511784000000013e+00 , -6.5013799999999999e-01 , 5.6818100000000005e-01 , -5.0447100000000000e-01 --1.4016375911826944e+00 , -3.2584013988102809e+00 , 1.1071202400000001e+01 , -9.7703700000000004e-01 , 9.3856700000000001e-02 , 1.9128400000000001e-01 --8.0000727697106377e-01 , -2.3002674177711278e+00 , 9.9839343999999990e+00 , -4.9174200000000001e-02 , -7.7114900000000000e-02 , 9.9580900000000006e-01 --7.2617724834356112e-01 , -2.1217352993048371e+00 , 9.9898728000000006e+00 , -4.4231300000000001e-01 , -4.4410499999999999e-02 , 8.9576000000000000e-01 --6.6133076592449225e-01 , -1.9553174140772156e+00 , 1.0007511200000000e+01 , 4.6510299999999999e-01 , 4.5725700000000002e-01 , -7.5802000000000003e-01 --7.0790447581633842e-01 , -1.9462624861531452e+00 , 1.0279689600000001e+01 , 8.1818999999999997e-01 , 1.8064500000000000e-01 , -5.4583199999999998e-01 --6.8731815490080894e-01 , -1.8407281551818309e+00 , 1.0402066400000001e+01 , -7.1855700000000000e-01 , -6.1070400000000002e-01 , 3.3273999999999998e-01 --1.8017663908307169e-01 , -1.0887230544780611e+00 , 9.3624928000000001e+00 , 1.3938300000000001e-01 , 8.5618200000000000e-01 , -4.9751899999999999e-01 --1.0300277746235764e-01 , -9.2071887683766152e-01 , 9.3221407999999997e+00 , -1.3938300000000001e-01 , -8.5618200000000000e-01 , 4.9751899999999999e-01 --1.5788565851010539e-01 , -9.2427817100066090e-01 , 9.6089936000000016e+00 , 3.4662399999999999e-01 , -5.0958199999999998e-01 , 7.8751400000000005e-01 --2.5844430866123380e-01 , -9.8006246256542751e-01 , 1.0022143999999999e+01 , -2.6759100000000002e-01 , -6.8198499999999995e-01 , -6.8065500000000001e-01 -2.5317267374028729e-02 , -5.5802468292054375e-01 , 9.4421567999999994e+00 , 2.4289500000000000e-01 , 6.0951200000000005e-01 , 7.5465000000000004e-01 -1.4224584438580345e-01 , -3.4952239668213947e-01 , 9.2792512000000009e+00 , -3.7109500000000001e-01 , 4.9069499999999999e-01 , 7.8835800000000000e-01 -1.8898585155940029e-01 , -2.2821287686521741e-01 , 9.3010808000000011e+00 , -1.8710199999999999e-01 , 4.8608499999999999e-01 , 8.5364799999999996e-01 -4.3605342292584837e-02 , -3.2577711448803370e-01 , 9.8609335999999992e+00 , 2.7281499999999997e-01 , 9.5494400000000002e-01 , -1.1685200000000000e-01 -3.3937076673522926e-01 , 7.5624512545168665e-02 , 9.1705296000000001e+00 , 4.9508300000000000e-01 , -7.0059000000000005e-01 , -5.1387400000000005e-01 --1.4181600551572249e-02 , -2.3627839193220002e-01 , 1.0366612800000000e+01 , -8.2161499999999998e-01 , 5.5490300000000004e-01 , -1.3050999999999999e-01 -5.0372737717429739e-01 , 3.8324914195734761e-01 , 8.9774536000000005e+00 , -7.4564900000000001e-01 , 6.3312700000000000e-01 , 2.0774400000000001e-01 -5.9109982596603916e-01 , 5.3774295835183783e-01 , 8.8511872000000000e+00 , -9.5789100000000005e-01 , -6.1448599999999999e-02 , 2.8047899999999998e-01 -5.0479059267223136e-01 , 5.1929217344725864e-01 , 9.2735000000000003e+00 , 9.6734399999999998e-01 , 6.8803000000000003e-02 , -2.4394900000000000e-01 -5.3153447107550233e-01 , 6.1622720885526339e-01 , 9.3439703999999999e+00 , 8.0425800000000003e-01 , 9.3515399999999999e-02 , -5.8687599999999995e-01 -2.8182330277871981e-01 , 4.6552035481386245e-01 , 1.0339832800000000e+01 , -5.5626500000000001e-01 , 3.3614100000000002e-01 , -7.5998600000000005e-01 -5.2739533959122986e-01 , 7.6249147779268167e-01 , 9.6843208000000001e+00 , -9.1260600000000003e-01 , -4.0447000000000000e-01 , 5.9620100000000002e-02 -3.1767629617408111e-01 , 6.6959050140063270e-01 , 1.0601444799999999e+01 , -2.4820900000000001e-01 , 8.2875699999999997e-02 , 9.6515499999999999e-01 -5.0849957826452008e-01 , 9.0884071057469518e-01 , 1.0111532000000000e+01 , 3.0322800000000000e-01 , -4.8740400000000003e-02 , -9.5167100000000004e-01 -4.8486833022327080e-01 , 9.7840855148196604e-01 , 1.0393808800000000e+01 , -7.3199899999999996e-01 , 5.5621600000000004e-01 , -3.9344899999999999e-01 -5.1322881592778780e-01 , 1.0906112540352535e+00 , 1.0487720800000000e+01 , -7.3096300000000003e-01 , 5.2017800000000003e-01 , 4.4171100000000002e-01 -5.5076675875314862e-01 , 1.2088414647172341e+00 , 1.0550255999999999e+01 , -7.3130200000000001e-01 , 5.3122599999999998e-01 , 4.2778100000000002e-01 -6.1135085413595380e-01 , 1.3425246701736593e+00 , 1.0520480800000000e+01 , 4.2161399999999999e-01 , -5.4347800000000002e-01 , -7.2586099999999998e-01 -6.6762078227435073e-01 , 1.4714208817406300e+00 , 1.0508187999999999e+01 , -7.6427900000000004e-01 , 2.7641700000000002e-01 , 5.8264099999999996e-01 -7.0247742604152141e-01 , 1.5892678002075249e+00 , 1.0584066399999999e+01 , 7.8053700000000004e-01 , -3.1675599999999998e-01 , -5.3891299999999998e-01 -7.6971385048652463e-01 , 1.7214383143116438e+00 , 1.0516580800000000e+01 , -3.4750999999999999e-01 , -4.8528100000000002e-01 , -8.0233399999999999e-01 -8.1539680572134210e-01 , 1.8446121444111707e+00 , 1.0547406400000000e+01 , -4.0516700000000000e-01 , -6.5475099999999997e-01 , -6.3807499999999995e-01 -9.4682977238869315e-01 , 1.9911784112137929e+00 , 1.0169813600000001e+01 , -2.7444900000000001e-02 , 8.4095399999999998e-01 , 5.4040999999999995e-01 -1.0175981033958321e+00 , 2.1131809564143911e+00 , 1.0063161600000001e+01 , -2.9280699999999998e-01 , -8.9881999999999995e-01 , -3.2617200000000002e-01 -9.0754122281218530e-01 , 2.2086772780940964e+00 , 1.0861507200000000e+01 , 6.6848700000000005e-01 , 6.8909100000000001e-01 , -2.7978399999999998e-01 -9.0523719654205181e-01 , 2.3347123286055194e+00 , 1.1149275200000000e+01 , -7.2369000000000006e-01 , -6.8998700000000002e-01 , 1.3817200000000000e-02 -7.5438222726211879e-01 , 2.4755054413652506e+00 , 1.2263884800000001e+01 , -9.6772000000000002e-01 , -1.4636900000000000e-01 , -2.0517099999999999e-01 -1.1288725067342413e+00 , 2.5842483121268796e+00 , 1.0511880000000000e+01 , -2.3150999999999999e-01 , 1.4080300000000001e-01 , 9.6258900000000003e-01 -1.1822635335454093e+00 , 2.7051509143031884e+00 , 1.0496196800000002e+01 , 1.1794200000000001e-01 , 1.0198000000000000e-01 , 9.8777000000000004e-01 -1.3279935279394217e+00 , 2.7930446170481265e+00 , 9.9147536000000009e+00 , -8.8482700000000003e-01 , -2.0790400000000001e-01 , -4.1696200000000000e-01 -1.4000681004470810e+00 , 2.8928569045999653e+00 , 9.7509432000000000e+00 , -5.1509800000000001e-02 , 6.8834300000000004e-01 , 7.2355400000000003e-01 -1.4405630853722668e+00 , 3.0052103243014985e+00 , 9.7796576000000002e+00 , 2.1414200000000000e-01 , -7.8701800000000000e-01 , 5.7857300000000000e-01 -1.3499869820165795e+00 , 3.2150398509988305e+00 , 1.0728044000000001e+01 , 6.4463700000000002e-01 , 2.4621299999999999e-03 , -7.6448499999999997e-01 -1.5350153336222401e+00 , 3.2222404422149435e+00 , 9.7597519999999989e+00 , -6.4608500000000002e-01 , 1.6577800000000001e-01 , -7.4504499999999996e-01 -1.6481141647259825e+00 , 3.2604366933018247e+00 , 9.2408543999999999e+00 , 7.0891899999999997e-01 , -5.3005199999999997e-01 , -4.6527299999999999e-01 -1.8492703042146790e+00 , 2.8695661524275229e-01 , 1.2553891199999998e+00 , -4.7016099999999998e-02 , 2.3829100000000000e-01 , 9.7005500000000000e-01 -1.8205791516614431e+00 , 2.2896376724391243e-01 , 1.2670849600000000e+00 , -6.7835800000000002e-02 , 2.3267299999999999e-01 , 9.7018599999999999e-01 -1.7942286500297289e+00 , 1.7990277729443638e-01 , 1.2867274399999999e+00 , -4.0395300000000002e-02 , 2.4859700000000001e-01 , 9.6776399999999996e-01 -1.7636573021180215e+00 , 1.1395216670072172e-01 , 1.2954613600000000e+00 , -9.2169799999999996e-02 , 1.9154800000000000e-01 , 9.7714599999999996e-01 -1.7266759054238217e+00 , 3.1379134252907503e-02 , 1.2940469600000000e+00 , -1.1961200000000000e-01 , 1.8110399999999999e-01 , 9.7616300000000000e-01 -1.6920013580308415e+00 , -4.2205222929271091e-02 , 1.3008818400000002e+00 , -9.4724299999999997e-02 , 2.0511599999999999e-01 , 9.7414299999999998e-01 -1.6585488950682132e+00 , -1.0887781426909804e-01 , 1.3159462399999999e+00 , 1.0566700000000000e-01 , -2.0351600000000000e-01 , -9.7335300000000002e-01 -1.6206717015894241e+00 , -1.9207811772239536e-01 , 1.3218232799999998e+00 , -1.1267099999999999e-01 , 1.8409000000000000e-01 , 9.7643000000000002e-01 -1.5777460952459936e+00 , -2.8414370135342670e-01 , 1.3247675200000000e+00 , -1.1780800000000000e-01 , 1.7569499999999999e-01 , 9.7736999999999996e-01 -1.5381387101900903e+00 , -3.6828897734605137e-01 , 1.3360889599999999e+00 , -6.9905400000000006e-02 , 2.0155899999999999e-01 , 9.7697900000000004e-01 -1.4982331985443593e+00 , -4.5191105277097998e-01 , 1.3499396799999999e+00 , 8.8421799999999995e-02 , -1.8959599999999999e-01 , -9.7787299999999999e-01 -1.4532239572693917e+00 , -5.4430350639708402e-01 , 1.3613651199999999e+00 , -9.4523999999999997e-02 , 1.9790099999999999e-01 , 9.7565400000000002e-01 -1.4061261063318389e+00 , -6.4646809479494394e-01 , 1.3712492800000000e+00 , -9.2854800000000001e-02 , 2.0133599999999999e-01 , 9.7511099999999995e-01 -1.3548695540867648e+00 , -7.5727516381325133e-01 , 1.3795401599999999e+00 , -1.0623600000000000e-01 , 1.9413600000000000e-01 , 9.7520499999999999e-01 -1.3021022790912453e+00 , -8.6832480235002096e-01 , 1.3915531999999999e+00 , -1.2390300000000000e-01 , 1.7549500000000001e-01 , 9.7665199999999996e-01 -1.2422934834981700e+00 , -9.9709051709779750e-01 , 1.3984837600000000e+00 , -1.4664300000000000e-01 , 1.4729900000000001e-01 , 9.7816099999999995e-01 -1.1753046074667228e+00 , -1.1444068713498745e+00 , 1.4013458400000001e+00 , -1.1595100000000000e-01 , 2.0690100000000000e-01 , 9.7146699999999997e-01 -1.1104871339485185e+00 , -1.2835897056305314e+00 , 1.4134722399999999e+00 , -5.1831599999999999e-02 , 3.1348799999999999e-01 , 9.4817700000000005e-01 -1.0680641100820543e+00 , -1.3599226359163876e+00 , 1.4576982400000000e+00 , -6.3251399999999999e-02 , 2.9010500000000000e-01 , 9.5490200000000003e-01 -9.9444645942185317e-01 , -1.5166262444912788e+00 , 1.4705869599999999e+00 , -7.8991800000000001e-02 , 2.3259299999999999e-01 , 9.6936100000000003e-01 -9.3084226979955753e-01 , -1.6470845262843912e+00 , 1.4998712799999998e+00 , -5.8010100000000002e-02 , 2.4332000000000001e-01 , 9.6821000000000002e-01 -8.5490743067343056e-01 , -1.8037166644921330e+00 , 1.5231631200000000e+00 , -7.4608400000000005e-02 , 2.4196599999999999e-01 , 9.6741200000000005e-01 -7.7534557312941721e-01 , -1.9703054500771962e+00 , 1.5489395200000000e+00 , -7.8402299999999994e-02 , 2.2813400000000000e-01 , 9.7046800000000000e-01 -6.9001264635976223e-01 , -2.1466912583116589e+00 , 1.5775572000000000e+00 , -7.3059299999999994e-02 , 2.2646500000000000e-01 , 9.7127500000000000e-01 -6.0095558607249067e-01 , -2.3317694057262832e+00 , 1.6096682400000000e+00 , -8.0897700000000003e-02 , 2.2913100000000000e-01 , 9.7002800000000000e-01 -4.9498536892004852e-01 , -2.5541798389093149e+00 , 1.6373405599999999e+00 , 7.7661599999999997e-02 , -2.1886100000000000e-01 , -9.7265999999999997e-01 -3.8804684045786275e-01 , -2.7760013057372630e+00 , 1.6730084000000001e+00 , -8.3662500000000001e-02 , 2.2824900000000001e-01 , 9.7000200000000003e-01 -2.6488095482889973e-01 , -3.0345597443209478e+00 , 1.7072972000000000e+00 , -8.4872900000000001e-02 , 2.3472799999999999e-01 , 9.6834900000000002e-01 -1.4359349671467414e-01 , -3.2844816411342332e+00 , 1.7532776800000001e+00 , -1.5110100000000001e-01 , 3.6003900000000000e-01 , 9.2061999999999999e-01 -1.6687482176607205e-03 , -3.5804281628960863e+00 , 1.7983127999999999e+00 , 1.1023600000000000e-01 , -2.2504900000000000e-01 , -9.6809100000000003e-01 --1.6230276599077387e-01 , -3.9239265727069510e+00 , 1.8450150400000001e+00 , -1.0052800000000001e-01 , 2.2475600000000001e-01 , 9.6921599999999997e-01 --3.4755205838113312e-01 , -4.3134308794350691e+00 , 1.8960356720000000e+00 , 4.6137200000000003e-02 , 1.5419200000000000e-01 , 9.8696300000000003e-01 --5.5126807284862389e-01 , -4.7397228617478975e+00 , 1.9554727119999999e+00 , -2.0279800000000001e-02 , -1.2971500000000000e-01 , -9.9134400000000000e-01 --7.6532873081832298e-01 , -5.1841352083333403e+00 , 2.0282283040000002e+00 , -6.8726300000000004e-02 , 2.3667600000000000e-01 , 9.6915499999999999e-01 --9.9089118186971614e-01 , -5.6464037433963350e+00 , 2.1152891999999999e+00 , -5.6895800000000003e-02 , 2.4383099999999999e-01 , 9.6814800000000001e-01 --1.2546648207710680e+00 , -6.1912823714362499e+00 , 2.2110607199999999e+00 , -5.7646999999999997e-02 , 2.3321900000000001e-01 , 9.7071399999999997e-01 --1.5711270769047805e+00 , -6.8484362416014957e+00 , 2.3180382399999999e+00 , 7.9442400000000002e-01 , -5.5791999999999997e-01 , -2.4003300000000000e-01 --1.9667900212079976e+00 , -7.6745887813081222e+00 , 2.4389309600000000e+00 , 5.6488499999999997e-01 , -3.9855099999999999e-01 , -7.2253800000000001e-01 --2.4040152178389649e+00 , -8.5825769296046808e+00 , 2.5874377600000003e+00 , -9.3725600000000006e-02 , 2.0990200000000001e-01 , 9.7321999999999997e-01 --2.9060156809403379e+00 , -9.6185441985830433e+00 , 2.7666141600000000e+00 , 3.1383700000000000e-02 , 2.0945800000000001e-01 , 9.7731400000000002e-01 --1.6231186158083784e+00 , -6.6645086597059144e+00 , 3.0143119999999999e+00 , -5.3129899999999997e-01 , -8.0538900000000002e-01 , 2.6281199999999999e-01 --1.6159408230807601e+00 , -6.5753812379034233e+00 , 3.1841439999999999e+00 , 5.2718299999999996e-01 , 8.0818800000000002e-01 , -2.6250800000000002e-01 --1.6205423076773156e+00 , -6.5126873071810039e+00 , 3.3520624000000003e+00 , 5.2718299999999996e-01 , 8.0818800000000002e-01 , -2.6250800000000002e-01 --1.6228373600131962e+00 , -6.4482842911865976e+00 , 3.5183999999999997e+00 , 5.2718299999999996e-01 , 8.0818800000000002e-01 , -2.6250800000000002e-01 --1.6459516740778706e+00 , -6.4273854102778127e+00 , 3.6857152000000002e+00 , -5.2718299999999996e-01 , -8.0818800000000002e-01 , 2.6250800000000002e-01 --1.6545709356311598e+00 , -6.3757566554367742e+00 , 3.8505240000000001e+00 , -5.2718299999999996e-01 , -8.0818800000000002e-01 , 2.6250800000000002e-01 --5.9155147514984607e+00 , -1.5348447955474352e+01 , 4.9796832000000002e+00 , -8.8283299999999998e-01 , -4.2870000000000003e-01 , 1.9189400000000001e-01 --5.8923441942399979e+00 , -1.5160702262207284e+01 , 5.3003359999999997e+00 , -8.8714300000000001e-01 , -3.1776100000000002e-01 , 3.3467200000000003e-01 --5.8447514491417021e+00 , -1.4921209125591623e+01 , 5.6083008000000003e+00 , 9.7732900000000000e-01 , 2.0985000000000001e-01 , -2.8130900000000000e-02 --5.8691856262471065e+00 , -1.4835221417928366e+01 , 5.9348711999999999e+00 , -9.0103100000000003e-01 , -2.7404400000000001e-01 , -3.3622000000000002e-01 --6.1237980855058005e+00 , -1.5223962035664975e+01 , 6.3489368000000006e+00 , -8.9504099999999998e-01 , -3.1743800000000000e-01 , -3.1326599999999999e-01 --6.1665224273953889e+00 , -1.5171288079879393e+01 , 6.6908159999999999e+00 , -9.3673399999999996e-01 , -3.1801000000000001e-01 , -1.4628700000000000e-01 --6.1573487292662072e+00 , -1.5012908500391902e+01 , 7.0099192000000006e+00 , -9.3996800000000003e-01 , -3.3077800000000002e-01 , -8.3940899999999999e-02 --6.2442839981354172e+00 , -1.5049419664528887e+01 , 7.3743040000000004e+00 , -7.8519399999999995e-01 , -6.1699499999999996e-01 , -5.2793300000000001e-02 --6.2829464554682861e+00 , -1.4990085985787516e+01 , 7.7184920000000004e+00 , -4.8242900000000000e-01 , -8.6501799999999995e-01 , -1.3786300000000001e-01 --6.3157564843957221e+00 , -1.4914603712254049e+01 , 8.0595184000000000e+00 , -4.9319299999999999e-01 , -8.4213600000000000e-01 , 2.1809899999999999e-01 --6.3500430449404384e+00 , -1.4843877586571857e+01 , 8.4032592000000008e+00 , -5.5153900000000000e-01 , -7.8750399999999998e-01 , 2.7503100000000003e-01 --6.3819619176730882e+00 , -1.4765986246697153e+01 , 8.7464280000000016e+00 , -7.4456400000000000e-01 , -6.3468999999999998e-01 , 2.0686399999999999e-01 --6.4190266359820960e+00 , -1.4701447389187322e+01 , 9.0958159999999992e+00 , -8.7592499999999995e-01 , -4.7588999999999998e-01 , 7.9269400000000004e-02 --6.4502389258856656e+00 , -1.4620759936885396e+01 , 9.4418344000000012e+00 , -8.7770400000000004e-01 , -4.6361400000000003e-01 , 1.2123500000000000e-01 --6.4782212648519302e+00 , -1.4535067016279449e+01 , 9.7877176000000006e+00 , -9.2833600000000005e-01 , -3.4949700000000000e-01 , 1.2666300000000000e-01 --6.4676674375178855e+00 , -1.4374073135474610e+01 , 1.0104200000000001e+01 , -9.3789000000000000e-01 , -2.2284999999999999e-01 , 2.6589600000000002e-01 --6.5042390947414290e+00 , -1.4303067415142205e+01 , 1.0459266400000001e+01 , -9.7262599999999999e-01 , -2.1255499999999999e-01 , 9.3910199999999999e-02 --6.4003061186961503e+00 , -1.3971930426966056e+01 , 1.0696677600000001e+01 , 9.8732900000000001e-01 , 1.5157799999999999e-01 , 4.6959700000000000e-02 --6.5776551535075019e+00 , -1.4158140035771513e+01 , 1.1178613600000000e+01 , -9.7170900000000004e-01 , -2.0447899999999999e-01 , -1.1819800000000000e-01 --6.6241232796469998e+00 , -1.4101131451110220e+01 , 1.1551859200000001e+01 , -9.6094299999999999e-01 , -2.1692000000000000e-01 , -1.7185400000000001e-01 --6.6228515974285038e+00 , -1.3955071328775837e+01 , 1.1882194400000001e+01 , 9.3753500000000001e-01 , 2.4627800000000000e-01 , 2.4571299999999999e-01 --6.8091632959206674e+00 , -1.4145750640451134e+01 , 1.2403224000000000e+01 , -8.9255099999999998e-01 , -4.1593300000000000e-01 , -1.7421900000000001e-01 --6.8418012369420254e+00 , -1.4058030230386617e+01 , 1.2778872000000000e+01 , -9.1435900000000003e-01 , -3.9964400000000000e-01 , 6.5054899999999999e-02 --6.8859196299323866e+00 , -1.3986962580531371e+01 , 1.3169600000000001e+01 , 9.0613299999999997e-01 , 4.2082799999999998e-01 , -4.2739300000000001e-02 --6.9258356504769640e+00 , -1.3908357807496362e+01 , 1.3561680000000001e+01 , 9.0955100000000000e-01 , 4.1157700000000003e-01 , -5.7639299999999997e-02 --6.9676083983935762e+00 , -1.3829492720293629e+01 , 1.3960000000000001e+01 , 9.1610400000000003e-01 , 3.9442899999999997e-01 , -7.1962399999999996e-02 --6.9835360696084106e+00 , -1.3704852555043129e+01 , 1.4332943999999999e+01 , 9.2478499999999997e-01 , 3.5563699999999998e-01 , -1.3525899999999999e-01 --7.0189026690224736e+00 , -1.3611000011306237e+01 , 1.4733032000000000e+01 , 9.0757800000000000e-01 , 3.8475999999999999e-01 , -1.6811300000000001e-01 --6.9702796056598828e+00 , -1.3375542628433587e+01 , 1.5032240000000002e+01 , 8.9743700000000004e-01 , 3.4918399999999999e-01 , -2.6958799999999999e-01 --6.9720423626063770e+00 , -1.3223412357258033e+01 , 1.5396552000000000e+01 , 9.4266700000000003e-01 , 7.5139600000000001e-02 , -3.2516699999999998e-01 --6.9843709914608567e+00 , -1.3086688299336362e+01 , 1.5777608000000001e+01 , 9.8782599999999998e-01 , 7.2441199999999997e-02 , -1.3766400000000001e-01 --6.9974750936152113e+00 , -1.2949803091915223e+01 , 1.6164487999999999e+01 , 9.9168699999999999e-01 , 5.1599699999999998e-02 , -1.1787400000000001e-01 --7.0336172216375168e+00 , -1.2847936882139757e+01 , 1.6588600000000000e+01 , -9.7269899999999998e-01 , -1.5031299999999999e-02 , 2.3158100000000001e-01 --6.8777956522354238e+00 , -1.2438792262801961e+01 , 1.6739192000000003e+01 , -9.6247099999999997e-01 , 2.2769500000000002e-02 , 2.7042600000000000e-01 --7.2897332298423088e+00 , -1.2925640170546643e+01 , 1.7734264000000000e+01 , -9.6997500000000003e-01 , -9.9385100000000004e-02 , -2.2196900000000000e-01 --7.3005385899637592e+00 , -1.2770779970467197e+01 , 1.8147560000000002e+01 , 9.6007399999999998e-01 , 1.5618599999999999e-01 , 2.3208500000000001e-01 --1.6250441445429087e+00 , -3.3298986134236488e+00 , 1.0795155200000000e+01 , 9.8240300000000003e-01 , -1.0757899999999999e-01 , -1.5268399999999999e-01 --1.5918296303412394e+00 , -3.2020139287064122e+00 , 1.0920506400000001e+01 , -9.7703700000000004e-01 , 9.3856700000000001e-02 , 1.9128400000000001e-01 --1.5204392461322058e+00 , -3.0225968525284559e+00 , 1.0972464800000001e+01 , -9.7703700000000004e-01 , 9.3856700000000001e-02 , 1.9128400000000001e-01 --1.6268876600217421e+00 , -2.9956166805215565e+00 , 1.1584307200000001e+01 , -9.8139299999999996e-01 , 1.2424499999999999e-01 , 1.4639500000000000e-01 --8.0336782524894268e-01 , -1.8330228728839866e+00 , 1.0030817600000001e+01 , 4.6510299999999999e-01 , 4.5725800000000000e-01 , -7.5802099999999994e-01 --1.5064675869002238e+00 , -2.6616893915589914e+00 , 1.1739059200000002e+01 , 8.1729600000000002e-01 , -3.1354900000000002e-01 , -4.8343999999999998e-01 --3.4380042763448593e-01 , -1.1099532739795692e+00 , 9.3434191999999996e+00 , -6.5716499999999997e-02 , -9.3140599999999996e-01 , 3.5800100000000001e-01 --8.6108742499156854e-01 , -1.6832370429572840e+00 , 1.0682908000000001e+01 , -9.6801899999999996e-01 , -2.5046900000000000e-01 , -1.4288500000000001e-02 --3.5953422214903386e-01 , -9.9632040444714054e-01 , 9.6879711999999998e+00 , -8.2032599999999997e-02 , -8.6050300000000002e-01 , 5.0279700000000005e-01 --8.1298695657041042e-01 , -1.4656174519066965e+00 , 1.0940599200000001e+01 , 7.9932700000000001e-01 , 4.5973000000000003e-01 , 3.8694299999999998e-01 --2.1343454693594399e-01 , -6.8778062608838519e-01 , 9.6536512000000005e+00 , 4.3159599999999998e-01 , 2.9495000000000000e-02 , 9.0158499999999997e-01 --1.0866941277453801e-02 , -3.8753166616048418e-01 , 9.3003736000000004e+00 , 2.2370200000000001e-01 , 6.1921599999999999e-01 , 7.5268100000000004e-01 -1.0594727881708810e-01 , -1.9385563717923970e-01 , 9.1534528000000002e+00 , 9.9216700000000005e-02 , 2.1094599999999999e-01 , 9.7244900000000001e-01 -1.3427957647525690e-01 , -9.8317680133628738e-02 , 9.2279271999999999e+00 , -4.2662800000000001e-01 , -1.6855300000000000e-02 , -9.0427000000000002e-01 -2.1407777202771650e-01 , 5.1924208977002895e-02 , 9.1632184000000017e+00 , 4.7925299999999998e-01 , -6.3425399999999998e-01 , -6.0666200000000003e-01 -3.1295935047162748e-01 , 2.1910788886364929e-01 , 9.0391151999999995e+00 , -6.9408499999999995e-01 , 6.8920099999999995e-01 , 2.0796100000000001e-01 -4.6616715599627145e-01 , 4.3599365662890133e-01 , 8.7516488000000017e+00 , -6.9191499999999995e-01 , 2.9256799999999999e-01 , 6.6004399999999996e-01 -4.2754944183523236e-01 , 4.5935272741898792e-01 , 9.0121895999999992e+00 , 7.6009800000000005e-01 , -6.4007300000000000e-01 , 1.1206400000000000e-01 -5.2016591764766007e-01 , 6.1142898084918684e-01 , 8.8855488000000005e+00 , -9.7873800000000000e-01 , -1.9307600000000000e-01 , -6.9231399999999998e-02 -4.5066981484711754e-01 , 6.1468065357816704e-01 , 9.2505160000000011e+00 , 9.4838400000000000e-01 , 1.8237700000000001e-01 , -2.5943400000000000e-01 -4.3734739524361954e-01 , 6.7343989005743676e-01 , 9.4549903999999998e+00 , -9.4984599999999997e-01 , -1.2366400000000000e-01 , 2.8722700000000001e-01 -2.0702168463658643e-01 , 5.5744881622488873e-01 , 1.0374350400000001e+01 , 7.0329799999999998e-01 , -3.0473499999999998e-01 , -6.4226799999999995e-01 -5.0646380338180030e-01 , 8.7784244298708169e-01 , 9.5725103999999988e+00 , 9.8576900000000001e-01 , 6.3936999999999994e-02 , 1.5547000000000000e-01 -6.3968131634979097e-01 , 1.0533117407263526e+00 , 9.2965879999999999e+00 , -3.9060999999999998e-02 , -1.6406399999999999e-01 , 9.8567600000000000e-01 -3.4511832359702765e-01 , 9.2049277149478681e-01 , 1.0508708000000000e+01 , 7.2611899999999996e-01 , -2.7079300000000001e-01 , -6.3199899999999998e-01 -7.4757367308342682e-01 , 1.2774424960001602e+00 , 9.2620496000000010e+00 , 1.5310599999999999e-01 , 3.8473800000000002e-01 , 9.1023900000000002e-01 -5.2269061670815620e-01 , 1.2166840866598623e+00 , 1.0282778400000000e+01 , 7.6756599999999997e-01 , -3.9019999999999999e-01 , -5.0851500000000005e-01 -5.2619914288377290e-01 , 1.3100402714497981e+00 , 1.0483373600000000e+01 , 7.5331899999999996e-01 , -4.8890000000000000e-01 , -4.3987100000000001e-01 -6.0016652515673652e-01 , 1.4455450354520090e+00 , 1.0412788800000000e+01 , -6.3345399999999996e-01 , 5.8304699999999998e-01 , 5.0871599999999995e-01 -4.3999224389848002e-01 , 1.4684406664623721e+00 , 1.1293346400000001e+01 , -4.0354000000000001e-01 , -7.4955600000000000e-01 , -5.2471100000000004e-01 -6.9429887229223275e-01 , 1.6843178369151814e+00 , 1.0484892000000000e+01 , -3.7698100000000001e-01 , 2.4835699999999999e-01 , 8.9230299999999996e-01 -7.3722757931510041e-01 , 1.8035421224259747e+00 , 1.0537703199999999e+01 , -1.8869600000000000e-01 , 6.0438199999999997e-01 , 7.7402599999999999e-01 -8.8361365731812658e-01 , 1.9534671127039074e+00 , 1.0132519200000001e+01 , -3.1571900000000003e-01 , -9.4527700000000003e-01 , -8.2298999999999997e-02 -9.7333200561791444e-01 , 2.0776789641935278e+00 , 9.9565616000000006e+00 , -2.1190700000000001e-01 , 9.7295100000000001e-01 , 9.1991000000000003e-02 -8.3937762462355381e-01 , 2.1628958001300687e+00 , 1.0846354399999999e+01 , -5.9767099999999995e-01 , -7.7060200000000001e-01 , 2.2127400000000000e-01 -8.7719657743916968e-01 , 2.2878013818680860e+00 , 1.0942076000000000e+01 , -7.3337500000000000e-01 , -5.7074599999999998e-01 , 3.6933700000000003e-01 -6.6515505792094998e-01 , 2.4176875917385834e+00 , 1.2342592000000002e+01 , -9.6772000000000002e-01 , -1.4636900000000000e-01 , -2.0517099999999999e-01 -1.0232484496504735e+00 , 2.5406899440507806e+00 , 1.0779097600000000e+01 , 8.7214000000000003e-01 , -2.5776600000000000e-01 , 4.1584800000000000e-01 -1.1250780888333842e+00 , 2.6571263054691339e+00 , 1.0519690400000000e+01 , -3.0947200000000002e-01 , 2.9029400000000000e-01 , 9.0551499999999996e-01 -1.1862106727304171e+00 , 2.7756029601759589e+00 , 1.0483072000000000e+01 , -1.0357600000000000e-01 , -1.2838700000000000e-01 , 9.8630099999999998e-01 -1.3703120639484085e+00 , 2.8418343179829924e+00 , 9.6863488000000011e+00 , -1.0492500000000000e-01 , 1.8540799999999999e-01 , 9.7704400000000002e-01 -1.4314422243927054e+00 , 2.9426030313538725e+00 , 9.6040016000000001e+00 , 7.0493399999999995e-01 , -2.6494200000000001e-01 , -6.5793199999999996e-01 -1.4787011430524055e+00 , 3.0473756866671469e+00 , 9.6018384000000001e+00 , 7.1919900000000003e-01 , -5.0999499999999998e-01 , -4.7186699999999998e-01 -1.5010590559445687e+00 , 3.1739828319343335e+00 , 9.7817480000000003e+00 , 5.8333800000000002e-01 , -7.6491900000000002e-01 , -2.7315699999999998e-01 -1.5593232832048276e+00 , 3.2736039365067846e+00 , 9.7141687999999995e+00 , -9.3211800000000000e-01 , 3.6121599999999998e-01 , -2.6072800000000000e-02 -1.7226135338196500e+00 , 3.2474391475375715e+00 , 8.8075071999999999e+00 , -7.5894499999999998e-01 , -6.4860899999999999e-01 , 5.7526099999999997e-02 -1.8137126487145743e+00 , 3.4726984876547351e-01 , 1.2467571199999998e+00 , -6.0971299999999999e-02 , 2.2678400000000001e-01 , 9.7203499999999998e-01 -1.7841721824535064e+00 , 2.9116347200831449e-01 , 1.2571082400000000e+00 , -4.3632400000000002e-02 , 2.3176600000000000e-01 , 9.7179199999999999e-01 -1.7518769684989239e+00 , 2.2575478448277719e-01 , 1.2628563200000000e+00 , -4.9722599999999999e-02 , 2.4727700000000000e-01 , 9.6766799999999997e-01 -1.7183664983218665e+00 , 1.6177637311523729e-01 , 1.2701956000000001e+00 , -9.2951599999999995e-02 , 2.3156599999999999e-01 , 9.6836800000000001e-01 -1.6845523522177945e+00 , 9.6144674991641255e-02 , 1.2797667200000000e+00 , -1.3667499999999999e-01 , 1.7909400000000000e-01 , 9.7429200000000005e-01 -1.6479777405506277e+00 , 2.3406092495511066e-02 , 1.2851331200000000e+00 , -9.4855800000000004e-02 , 1.9909700000000000e-01 , 9.7537799999999997e-01 -1.6110636127976627e+00 , -5.0929372772611003e-02 , 1.2930350399999999e+00 , -9.5842899999999995e-02 , 1.9409199999999999e-01 , 9.7628999999999999e-01 -1.5728551180680821e+00 , -1.2478441253740735e-01 , 1.3030367199999999e+00 , 1.1699300000000000e-01 , -1.9245300000000001e-01 , -9.7430700000000003e-01 -1.5291273053823702e+00 , -2.1503886798291338e-01 , 1.3042306400000001e+00 , -1.2753500000000001e-01 , 1.9488000000000000e-01 , 9.7250000000000003e-01 -1.4892953882121134e+00 , -2.8893648062064514e-01 , 1.3189663999999999e+00 , -9.9447400000000005e-02 , 2.0620300000000000e-01 , 9.7344299999999995e-01 -1.4438292021728012e+00 , -3.8012695560969290e-01 , 1.3257066399999999e+00 , -1.0195200000000000e-01 , 1.8559899999999999e-01 , 9.7732200000000002e-01 -1.3942790805738157e+00 , -4.8008270526362473e-01 , 1.3302472800000000e+00 , -1.2790399999999999e-01 , 2.1117100000000000e-01 , 9.6904500000000005e-01 -1.3469976892720146e+00 , -5.7207621305937062e-01 , 1.3431411999999998e+00 , -9.7159300000000004e-02 , 2.1635099999999999e-01 , 9.7146900000000003e-01 -1.2966347184127744e+00 , -6.7279098075900468e-01 , 1.3542640000000001e+00 , -1.0868800000000001e-01 , 2.1408199999999999e-01 , 9.7075000000000000e-01 -1.2437637927696186e+00 , -7.7380190558219342e-01 , 1.3686804800000001e+00 , -1.2421300000000000e-01 , 1.7977299999999999e-01 , 9.7583399999999998e-01 -1.1784365188639616e+00 , -9.0910876002222274e-01 , 1.3682946400000000e+00 , -1.4620600000000000e-01 , 1.7422199999999999e-01 , 9.7379199999999999e-01 -1.1142226791528311e+00 , -1.0372924195853406e+00 , 1.3771512800000001e+00 , -1.3281100000000001e-01 , 1.5662699999999999e-01 , 9.7868800000000000e-01 -1.0456575763498961e+00 , -1.1737968021594649e+00 , 1.3859319999999999e+00 , -9.4081300000000007e-02 , 2.6965099999999997e-01 , 9.5835099999999995e-01 -9.9087001572620581e-01 , -1.2758223280428709e+00 , 1.4159412000000000e+00 , -4.9282600000000003e-02 , 2.9971300000000001e-01 , 9.5275600000000005e-01 -9.2407259641858341e-01 , -1.4034579411950068e+00 , 1.4375274400000000e+00 , 7.5098600000000001e-02 , -2.9794199999999998e-01 , -9.5162500000000005e-01 -8.5279361882250093e-01 , -1.5402896114210809e+00 , 1.4599519200000000e+00 , -5.6546699999999998e-02 , 2.4975400000000000e-01 , 9.6665699999999999e-01 -7.7696614816959175e-01 , -1.6872434981332813e+00 , 1.4838251200000001e+00 , -6.1387499999999998e-02 , 2.4221200000000001e-01 , 9.6827900000000000e-01 -6.9951238232993695e-01 , -1.8331369415581862e+00 , 1.5126320799999999e+00 , -8.6208800000000002e-02 , 2.2647900000000001e-01 , 9.7019400000000000e-01 -6.0655783532237484e-01 , -2.0159490297359079e+00 , 1.5340872800000001e+00 , -8.2919400000000004e-02 , 2.2293900000000000e-01 , 9.7129900000000002e-01 -5.1176680821480058e-01 , -2.1984436418007327e+00 , 1.5619956799999999e+00 , -8.2335199999999997e-02 , 2.2996900000000001e-01 , 9.6970900000000004e-01 -4.0916953788420685e-01 , -2.3994884845623199e+00 , 1.5909991999999999e+00 , 9.0871099999999996e-02 , -2.2481899999999999e-01 , -9.7015399999999996e-01 -2.9555297830412663e-01 , -2.6188328951558564e+00 , 1.6217322400000000e+00 , 8.1796900000000006e-02 , -2.2672600000000001e-01 , -9.7051799999999999e-01 -1.7387618133670313e-01 , -2.8563121165567784e+00 , 1.6555831999999999e+00 , -9.0872700000000001e-02 , 2.3471900000000001e-01 , 9.6780600000000006e-01 -4.6000078418807933e-02 , -3.1028368580937942e+00 , 1.6959175200000001e+00 , -7.6357599999999998e-02 , 2.5358199999999997e-01 , 9.6429600000000004e-01 --9.6257609451070092e-02 , -3.3758875320990338e+00 , 1.7385377600000000e+00 , -1.0755400000000000e-01 , 2.2973700000000000e-01 , 9.6729200000000004e-01 --2.6454252757009700e-01 , -3.7054360131593969e+00 , 1.7798164000000001e+00 , 9.7482600000000003e-02 , -2.2032199999999999e-01 , -9.7054399999999996e-01 --4.5192336350148521e-01 , -4.0713903609429067e+00 , 1.8260433599999999e+00 , 2.7694000000000000e-02 , 2.7154400000000001e-01 , 9.6202699999999997e-01 --6.5031509145624433e-01 , -4.4549528252971822e+00 , 1.8826276799999999e+00 , 1.1534999999999999e-01 , 1.3643100000000000e-01 , 9.8391099999999998e-01 --8.7978323872184827e-01 , -4.9031887851680667e+00 , 1.9436663199999999e+00 , -9.5923300000000003e-02 , 1.3490500000000000e-01 , 9.8620500000000000e-01 --1.1218078492733694e+00 , -5.3692082146033897e+00 , 2.0190871200000000e+00 , 5.8612800000000000e-02 , -2.4497400000000000e-01 , -9.6775699999999998e-01 --1.3617238874121149e+00 , -5.8241144105947473e+00 , 2.1133038399999999e+00 , -6.3339199999999998e-02 , 2.3569599999999999e-01 , 9.6976099999999998e-01 --1.6961681965490247e+00 , -6.4739092729878678e+00 , 2.2055258400000000e+00 , -1.9551600000000000e-01 , 5.4311200000000004e-01 , 8.1657999999999997e-01 --2.0783918307367673e+00 , -7.2148117076138547e+00 , 2.3149910399999998e+00 , 3.6603200000000002e-01 , -2.1592600000000001e-01 , -9.0520500000000004e-01 --2.5315850763465573e+00 , -8.0930773461810848e+00 , 2.4442505600000000e+00 , -1.0912100000000000e-01 , 2.1841300000000000e-01 , 9.6973600000000004e-01 --7.5177005949235198e-01 , -4.2887559432922773e+00 , 2.8018628799999998e+00 , -8.3516900000000005e-01 , -5.4999299999999995e-01 , -9.2517999999999997e-05 --3.5550461956945032e+00 , -1.0051370363277028e+01 , 2.7991536799999999e+00 , 2.6247900000000002e-01 , 2.1103700000000000e-01 , 9.4157800000000003e-01 --3.9445723335625136e+00 , -1.0755986674812229e+01 , 3.0343236800000000e+00 , 2.3064599999999999e-01 , 1.9388200000000000e-01 , 9.5352599999999998e-01 --4.1580556772197879e+00 , -1.1090017648239948e+01 , 3.2913160000000001e+00 , 2.3064599999999999e-01 , 1.9388200000000000e-01 , 9.5352599999999998e-01 --4.5751517495740126e+00 , -1.1828130970260652e+01 , 3.5757871999999997e+00 , 1.7886199999999999e-01 , 2.4851100000000001e-01 , 9.5197200000000004e-01 --5.2011031301479118e+00 , -1.2977862393987859e+01 , 3.9123312000000001e+00 , 2.8706599999999999e-01 , 3.0209300000000000e-01 , 9.0902899999999998e-01 --5.9055459203345677e+00 , -1.4265855685719380e+01 , 4.3049520000000001e+00 , 3.4149700000000000e-01 , -1.4193400000000000e-01 , -9.2910400000000004e-01 --6.3443188386166653e+00 , -1.5005604125711120e+01 , 4.6981656000000003e+00 , -9.3616800000000000e-01 , -3.0182399999999998e-01 , 1.8025400000000000e-01 --6.3750641429401167e+00 , -1.4931931731817215e+01 , 5.0308200000000003e+00 , 9.8019299999999998e-01 , -1.9546900000000000e-01 , -3.1831400000000003e-02 --6.0350286376843858e+00 , -1.4137493227454872e+01 , 5.2676072000000005e+00 , -9.7773800000000000e-01 , 1.2146500000000000e-01 , 1.7110100000000000e-01 --5.9782100971733474e+00 , -1.3900586769598199e+01 , 5.5599615999999994e+00 , -9.5510799999999996e-01 , -1.4857200000000001e-01 , -2.5630999999999998e-01 --6.3502287260547199e+00 , -1.4490657592456966e+01 , 5.9878592000000008e+00 , -8.9503600000000005e-01 , -1.2688400000000000e-01 , -4.2756499999999997e-01 --6.4123037698818912e+00 , -1.4479152667344003e+01 , 6.3267848000000004e+00 , -9.2286699999999999e-01 , -1.9095000000000001e-01 , -3.3444600000000002e-01 --6.4334611483175088e+00 , -1.4390484530148434e+01 , 6.6518991999999999e+00 , 9.8692899999999995e-01 , 4.5482700000000001e-02 , 1.5460299999999999e-01 --6.6625001706073235e+00 , -1.4691801844666745e+01 , 7.0677120000000002e+00 , 7.5500500000000004e-01 , 4.8011300000000001e-01 , 4.4660899999999998e-01 --7.0203251580759130e+00 , -1.5226256199753411e+01 , 7.5588104000000005e+00 , 8.8660100000000006e-03 , -9.9941500000000005e-01 , 3.3028599999999998e-02 --7.0634902994235471e+00 , -1.5168790297407423e+01 , 7.9137623999999995e+00 , -8.1722000000000003e-02 , 9.9535799999999997e-01 , -5.0828400000000003e-02 --7.0895208897332669e+00 , -1.5080685548204396e+01 , 8.2614032000000002e+00 , 2.2716199999999999e-02 , -9.3330700000000000e-01 , 3.5836000000000001e-01 --7.1318361981069209e+00 , -1.5020606725668980e+01 , 8.6190071999999986e+00 , 1.8965499999999999e-01 , -9.5226800000000000e-01 , 2.3920200000000000e-01 --6.8187253106470163e+00 , -1.4319489530151660e+01 , 8.7610504000000002e+00 , 2.1495300000000001e-01 , -8.9679900000000001e-01 , 3.8671299999999997e-01 --7.2896936022059418e+00 , -1.5031807418643922e+01 , 9.3889607999999996e+00 , -5.4293899999999995e-01 , -6.8895200000000001e-01 , 4.8016900000000001e-01 --6.8735522188794747e+00 , -1.4154239965995899e+01 , 9.4433007999999994e+00 , -9.7811300000000001e-01 , 2.0780100000000001e-01 , 1.0632400000000000e-02 --6.7298253699384318e+00 , -1.3768664000607135e+01 , 9.6641136000000003e+00 , 9.9414199999999997e-01 , 1.0972400000000000e-02 , -1.0752700000000000e-01 --6.6948340517407257e+00 , -1.3577460968071595e+01 , 9.9565096000000004e+00 , -9.6342200000000000e-01 , 2.0734099999999999e-03 , 2.6798100000000002e-01 --6.7350722606675042e+00 , -1.3516112174714552e+01 , 1.0305221599999999e+01 , 9.9276600000000004e-01 , 7.1583400000000005e-02 , -9.6392500000000006e-02 --6.6117718432245294e+00 , -1.3173727260253665e+01 , 1.0523767200000002e+01 , 9.9398399999999998e-01 , 1.0077000000000000e-01 , 4.2920899999999998e-02 --6.8002598058318338e+00 , -1.3366757796822746e+01 , 1.1001096000000000e+01 , 9.8333000000000004e-01 , 1.1532800000000000e-01 , 1.4057900000000001e-01 --6.8407280547288778e+00 , -1.3303227214838895e+01 , 1.1360353600000000e+01 , 9.9010299999999996e-01 , 8.0057299999999998e-02 , 1.1526900000000000e-01 --6.8642890303024302e+00 , -1.3207936589832954e+01 , 1.1707016800000000e+01 , -9.6803399999999995e-01 , -7.6567800000000005e-02 , -2.3884600000000000e-01 --7.2303457360955310e+00 , -1.3682937218666122e+01 , 1.2386469600000002e+01 , -9.2781599999999997e-01 , -2.6982899999999999e-01 , -2.5758300000000001e-01 --7.2603969430495301e+00 , -1.3593843529727971e+01 , 1.2759008000000000e+01 , -8.7233499999999997e-01 , -4.8887300000000000e-01 , -5.8950699999999997e-03 --7.2932401190469953e+00 , -1.3505634146653385e+01 , 1.3136840000000001e+01 , -8.8405699999999998e-01 , -4.6130599999999999e-01 , 7.5100299999999995e-02 --7.3168410920218019e+00 , -1.3402817447491028e+01 , 1.3510408000000000e+01 , -8.9185499999999995e-01 , -4.4444699999999998e-01 , 8.4034399999999995e-02 --7.3383374536081050e+00 , -1.3293631669046437e+01 , 1.3884183999999999e+01 , -8.6169099999999998e-01 , -5.0741800000000004e-01 , 3.9929800000000001e-03 --7.3703817877478226e+00 , -1.3198893438318066e+01 , 1.4273976000000001e+01 , -8.7789499999999998e-01 , -4.6851799999999999e-01 , 9.8953399999999997e-02 --7.6008414897274132e+00 , -1.3416773814606241e+01 , 1.4903487999999999e+01 , -9.5229500000000000e-01 , -1.7884100000000000e-01 , 2.4728600000000001e-01 --7.3719747228500214e+00 , -1.2908354469754881e+01 , 1.4993760000000000e+01 , -9.3709200000000004e-01 , -1.6451399999999999e-01 , 3.0788500000000002e-01 --7.1923946228549855e+00 , -1.2482402735731206e+01 , 1.5132808000000001e+01 , 9.9195699999999998e-01 , 1.8252200000000000e-02 , -1.2525300000000000e-01 --7.2248535703306764e+00 , -1.2385095670290045e+01 , 1.5535288000000000e+01 , 9.9108600000000002e-01 , 2.7771500000000001e-02 , -1.3029600000000000e-01 --7.1794479724457627e+00 , -1.2167268938338447e+01 , 1.5840736000000001e+01 , 9.9467799999999995e-01 , 4.1669499999999998e-02 , -9.4233499999999998e-02 --7.2702485648216619e+00 , -1.2152779405282269e+01 , 1.6330784000000001e+01 , -9.6431699999999998e-01 , -5.2052899999999996e-03 , 2.6469799999999999e-01 --7.1498392257820473e+00 , -1.1820212567296215e+01 , 1.6536704000000000e+01 , -9.5691300000000001e-01 , 6.3145199999999999e-02 , 2.8342400000000001e-01 --7.0039194285741146e+00 , -1.1454353964862436e+01 , 1.6702272000000001e+01 , 9.9174600000000002e-01 , 9.2818999999999999e-02 , 8.8459800000000005e-02 --7.5265489820483022e+00 , -1.2057870579973715e+01 , 1.7848455999999999e+01 , -9.3184999999999996e-01 , -1.2744000000000000e-01 , -3.3972700000000000e-01 --7.4038091350336703e+00 , -1.1719525562639594e+01 , 1.8062799999999999e+01 , -9.3706000000000000e-01 , -1.1817800000000001e-01 , -3.2856000000000002e-01 --1.7808283068727895e+00 , -3.1441323921915387e+00 , 1.0777444000000001e+01 , 9.8159900000000000e-01 , -5.2626199999999998e-02 , -1.8356000000000000e-01 --1.5448493797630585e+00 , -2.3608442025038991e+00 , 1.1505953600000000e+01 , 7.3207800000000001e-01 , -4.0812300000000001e-01 , -5.4543399999999997e-01 --1.5631311481117494e+00 , -2.2955751944969984e+00 , 1.1752225600000001e+01 , -4.7649399999999997e-01 , 4.5240799999999998e-01 , 7.5384399999999996e-01 --1.3484518121535984e+00 , -1.9618429691508581e+00 , 1.1493941600000001e+01 , -3.2243400000000000e-01 , 3.5641600000000001e-01 , 8.7692899999999996e-01 --1.2836595470643761e+00 , -1.8028004719673438e+00 , 1.1554032800000000e+01 , -1.6366700000000001e-01 , 3.6397499999999999e-01 , 9.1691599999999995e-01 --4.0371407659673952e-01 , -7.4502847852030207e-01 , 9.7189423999999995e+00 , -5.3251800000000005e-01 , -3.4785500000000003e-01 , -7.7163499999999996e-01 --1.9585708777161237e-01 , -4.5286505274398925e-01 , 9.3898760000000010e+00 , 5.6942800000000005e-01 , 3.4254600000000002e-01 , 7.4727100000000002e-01 --2.0408079002336166e-01 , -3.9727229628350624e-01 , 9.5692032000000005e+00 , 6.1236800000000002e-01 , 4.0512900000000002e-01 , 6.7887799999999998e-01 -2.2639071912049502e-03 , -1.1727911101116950e-01 , 9.2162791999999989e+00 , -5.3039599999999998e-01 , 8.0749199999999993e-03 , -8.4771200000000002e-01 -4.4535625966026560e-02 , -1.1826995392457018e-02 , 9.2638384000000009e+00 , -4.2662800000000001e-01 , -1.6855300000000000e-02 , -9.0427000000000002e-01 -1.4266822111190236e-01 , 1.4926240463031193e-01 , 9.1620640000000009e+00 , 5.2688100000000004e-01 , -3.0824499999999999e-01 , 7.9207399999999994e-01 -3.6369183183250375e-01 , 4.2384804903064843e-01 , 8.7221960000000003e+00 , 4.6284999999999998e-01 , -1.5945100000000000e-02 , -8.8629300000000000e-01 -3.6680980632256377e-01 , 4.8672729346026378e-01 , 8.8610463999999993e+00 , -7.9494399999999998e-01 , -1.6025500000000001e-01 , 5.8513499999999996e-01 -2.9200734923262783e-01 , 4.8265312729424803e-01 , 9.2254104000000012e+00 , -8.4134900000000001e-01 , 1.6851800000000000e-01 , 5.1355099999999998e-01 -4.1718179480896400e-01 , 6.5649732031895169e-01 , 9.0240247999999994e+00 , 9.8159500000000000e-01 , 1.8519400000000000e-01 , -4.6631899999999997e-02 -4.0280164447553957e-01 , 7.0984780317257257e-01 , 9.2277816000000001e+00 , 9.6698799999999996e-01 , -4.9305300000000003e-02 , -2.5000600000000001e-01 -4.0943946217330196e-01 , 7.8467815904645044e-01 , 9.3739951999999995e+00 , -9.5066700000000004e-01 , -4.0035700000000000e-02 , 3.0761899999999998e-01 --4.9326800223985368e-01 , 1.7066398749478284e-01 , 1.2410712000000002e+01 , 3.7996300000000000e-01 , -2.7422600000000003e-01 , 8.8341800000000004e-01 -5.9410683061830660e-01 , 1.0631433048631695e+00 , 9.1301152000000005e+00 , 6.3063199999999997e-01 , -5.2280400000000005e-01 , -5.7356700000000005e-01 -6.3585786804070432e-01 , 1.1626312507530070e+00 , 9.1637696000000002e+00 , 8.0599299999999996e-01 , -1.4410500000000001e-01 , -5.7411599999999996e-01 -6.5540605372929361e-01 , 1.2477932457195671e+00 , 9.2744152000000000e+00 , -4.0079199999999998e-01 , 2.1705700000000000e-01 , 8.9008500000000002e-01 -4.2255039490318058e-01 , 1.1838057582072792e+00 , 1.0282674399999999e+01 , -4.5820800000000000e-01 , -3.8412299999999999e-01 , -8.0155799999999999e-01 -4.3253871893860629e-01 , 1.2784372615651112e+00 , 1.0464643199999999e+01 , -7.1882699999999999e-01 , 4.9005100000000001e-01 , 4.9308999999999997e-01 -5.1141025248430250e-01 , 1.4121018081889263e+00 , 1.0396512800000000e+01 , 7.2956299999999996e-01 , -4.7210700000000000e-01 , -4.9482700000000002e-01 -3.2463757971496854e-01 , 1.4212066570755875e+00 , 1.1355777600000000e+01 , -2.8361399999999998e-01 , -8.4650800000000004e-01 , -4.5054100000000002e-01 -5.3187557600635738e-01 , 1.6164384325126988e+00 , 1.0793200000000001e+01 , -7.6328799999999997e-01 , -5.7730300000000001e-01 , -2.9002099999999997e-01 -6.4346693593243809e-01 , 1.7612309762106968e+00 , 1.0587020000000001e+01 , -2.8046800000000000e-01 , -6.3081399999999999e-01 , -7.2347200000000000e-01 -8.4369735035597837e-01 , 1.9260680088071820e+00 , 9.9827487999999995e+00 , 5.8313599999999999e-01 , 6.0647099999999998e-01 , 5.4050500000000001e-01 -9.0629478163879562e-01 , 2.0400823342712506e+00 , 9.9506440000000005e+00 , 7.6780800000000005e-01 , -3.4064600000000000e-01 , 5.4261499999999996e-01 -9.4627066132501003e-01 , 2.1495471233894676e+00 , 1.0017630400000000e+01 , 7.2604700000000000e-01 , 6.1802199999999996e-01 , -3.0150300000000002e-01 -8.1232451341741685e-01 , 2.2431147753285963e+00 , 1.0917251200000001e+01 , -6.5017300000000000e-01 , -6.6269900000000004e-01 , 3.7162499999999998e-01 -5.6158287886569425e-01 , 2.3619025902519288e+00 , 1.2470512000000001e+01 , -9.7428099999999995e-01 , -1.2370399999999999e-01 , -1.8834699999999999e-01 -7.4804862274011574e-01 , 2.5059648690235714e+00 , 1.1881414400000001e+01 , -8.6249299999999995e-01 , -3.6275299999999999e-01 , 3.5286800000000001e-01 -1.0717447172698735e+00 , 2.6089232687513371e+00 , 1.0511484800000000e+01 , -3.3648600000000001e-01 , 3.1822900000000001e-02 , 9.4115000000000004e-01 -1.1299852012029097e+00 , 2.7276848718911304e+00 , 1.0507293600000001e+01 , 1.5593699999999999e-01 , 2.5496500000000000e-01 , 9.5429399999999998e-01 -1.1849747581998775e+00 , 2.8470672293091561e+00 , 1.0521292000000001e+01 , -1.7461199999999999e-01 , -1.1287100000000000e-01 , 9.7814699999999999e-01 -1.3650984901816281e+00 , 2.9089140697826221e+00 , 9.7652016000000010e+00 , -2.7534599999999998e-01 , 3.7231700000000001e-01 , -8.8632100000000003e-01 -1.4209421468581740e+00 , 3.0137651729876991e+00 , 9.7441416000000007e+00 , -8.2402399999999998e-01 , 5.2877300000000005e-01 , -2.0343000000000000e-01 -1.4724571073776986e+00 , 3.1193294734867898e+00 , 9.7415623999999994e+00 , 6.5743499999999999e-01 , -3.6352899999999999e-01 , -6.6002000000000005e-01 -1.5240605951467208e+00 , 3.2265352825178395e+00 , 9.7470952000000004e+00 , 6.4608500000000002e-01 , -1.6577800000000001e-01 , 7.4504499999999996e-01 -1.6838915684513671e+00 , 3.2182606533481501e+00 , 8.9232383999999989e+00 , 5.0892599999999999e-01 , -8.6058699999999999e-01 , -1.9601299999999999e-02 -1.6811685899784155e+00 , 2.2576826699307340e-01 , 1.2583666400000000e+00 , -1.2496300000000000e-01 , 2.4614100000000000e-01 , 9.6114500000000003e-01 -1.6454986418421966e+00 , 1.6199941073498247e-01 , 1.2662643999999998e+00 , -1.2464799999999999e-01 , 2.1956400000000001e-01 , 9.6760199999999996e-01 -1.6070219273623612e+00 , 9.0106189692692240e-02 , 1.2701623199999998e+00 , -1.0541300000000001e-01 , 2.0320400000000000e-01 , 9.7344600000000003e-01 -1.5682499314162093e+00 , 1.7643758982484936e-02 , 1.2763908800000001e+00 , -9.4899200000000003e-02 , 1.9219200000000000e-01 , 9.7675800000000002e-01 -1.5245608923164289e+00 , -6.2829623075655316e-02 , 1.2787735200000001e+00 , -1.1233600000000001e-01 , 1.9923399999999999e-01 , 9.7349200000000002e-01 -1.4841324788943284e+00 , -1.3637063291034668e-01 , 1.2898401600000000e+00 , -1.1180600000000000e-01 , 1.7537500000000000e-01 , 9.7813200000000000e-01 -1.4371979484818058e+00 , -2.2528015571049176e-01 , 1.2917672800000002e+00 , -8.2903199999999996e-02 , 1.9830999999999999e-01 , 9.7662700000000002e-01 -1.3951368839507439e+00 , -2.9884438611381947e-01 , 1.3076678400000001e+00 , -7.9680000000000001e-02 , 1.9453500000000001e-01 , 9.7765400000000002e-01 -1.3437699135312351e+00 , -3.9701428988723331e-01 , 1.3101305599999999e+00 , -1.2234700000000000e-01 , 1.7889800000000000e-01 , 9.7623099999999996e-01 -1.2909721100778926e+00 , -4.9555913006764163e-01 , 1.3157080799999998e+00 , -8.5444099999999995e-02 , 2.1328000000000000e-01 , 9.7324800000000000e-01 -1.2441876138347037e+00 , -5.7785909456381335e-01 , 1.3346735199999999e+00 , -9.4252299999999997e-02 , 2.0048500000000000e-01 , 9.7515200000000002e-01 -1.1820463875910754e+00 , -6.9365281551956315e-01 , 1.3369407199999999e+00 , -9.8334800000000000e-02 , 1.8491099999999999e-01 , 9.7782300000000000e-01 -1.1269424225718043e+00 , -7.9322754856422106e-01 , 1.3527216799999999e+00 , -1.2241000000000000e-01 , 1.6177800000000001e-01 , 9.7920600000000002e-01 -1.0600151002825551e+00 , -9.1875657803291055e-01 , 1.3583595200000000e+00 , -1.3636999999999999e-01 , 1.4637900000000001e-01 , 9.7978399999999999e-01 -9.8104803732694124e-01 , -1.0709522930228008e+00 , 1.3555775200000000e+00 , -1.0930400000000000e-01 , 1.7236399999999999e-01 , 9.7894999999999999e-01 -9.0809757969597427e-01 , -1.2058200883208356e+00 , 1.3662812000000000e+00 , -2.0403899999999999e-02 , 2.9069699999999998e-01 , 9.5659799999999995e-01 -8.5283143754848934e-01 , -1.2971613191107370e+00 , 1.4018294400000000e+00 , 2.7775700000000000e-03 , 2.6592900000000003e-01 , 9.6398899999999998e-01 -7.8166918691044662e-01 , -1.4232092422877902e+00 , 1.4250349600000001e+00 , -3.9513500000000000e-02 , 2.3810200000000001e-01 , 9.7043599999999997e-01 -7.0990213119295498e-01 , -1.5504090833507509e+00 , 1.4530015999999999e+00 , -4.8244200000000001e-02 , 2.3640300000000000e-01 , 9.7045700000000001e-01 -6.2481448626194380e-01 , -1.7027206801875456e+00 , 1.4746450400000000e+00 , -6.6297499999999995e-02 , 2.1692900000000001e-01 , 9.7393300000000005e-01 -5.3110573516631687e-01 , -1.8739599190966749e+00 , 1.4954377600000002e+00 , 7.1097499999999994e-02 , -2.2098599999999999e-01 , -9.7268200000000005e-01 -4.3560761133622905e-01 , -2.0449570249490634e+00 , 1.5222780800000000e+00 , 6.6295800000000002e-02 , -2.1720800000000001e-01 , -9.7387100000000004e-01 -3.2737388703092685e-01 , -2.2424859744655432e+00 , 1.5464695200000000e+00 , -7.6978800000000000e-02 , 2.1854799999999999e-01 , 9.7278500000000001e-01 -2.1318465824706889e-01 , -2.4494779301685305e+00 , 1.5751204800000000e+00 , 7.1645200000000006e-02 , -2.1668899999999999e-01 , -9.7360800000000003e-01 -8.8930397203724310e-02 , -2.6746609084270405e+00 , 1.6062331200000000e+00 , -7.8972899999999999e-02 , 2.1308400000000000e-01 , 9.7383699999999995e-01 --4.5507766649899750e-02 , -2.9178149404429341e+00 , 1.6408204000000000e+00 , -6.1308799999999997e-02 , 2.3150200000000001e-01 , 9.7090100000000001e-01 --1.8612761332501204e-01 , -3.1689497678110783e+00 , 1.6818868800000000e+00 , -8.0903199999999995e-02 , 2.2537399999999999e-01 , 9.7090799999999999e-01 --3.5875458538361160e-01 , -3.4845116816733821e+00 , 1.7178427999999999e+00 , -8.7557899999999994e-02 , 2.1856300000000001e-01 , 9.7188699999999995e-01 --5.3797838392749231e-01 , -3.8084144442984362e+00 , 1.7637224000000000e+00 , -6.0942799999999998e-02 , 2.1890899999999999e-01 , 9.7384000000000004e-01 --7.3322891769253618e-01 , -4.1599406575882929e+00 , 1.8166240800000000e+00 , 4.0238699999999999e-01 , 1.2544000000000000e-01 , 9.0683499999999995e-01 --8.7587733676332702e-01 , -4.3988695949177927e+00 , 1.9020718320000001e+00 , -5.8780299999999996e-01 , -5.7013899999999995e-01 , 5.7395799999999997e-01 --8.3843494349608205e-01 , -4.2669762540607916e+00 , 2.0534920880000000e+00 , 6.1172300000000002e-01 , 6.9000799999999995e-01 , -3.8688899999999998e-01 --8.3404355089544113e-01 , -4.2067145980013452e+00 , 2.1901546399999998e+00 , 6.1658999999999997e-01 , 7.2336800000000001e-01 , -3.1073600000000001e-01 --8.1027569010435752e-01 , -4.1065626825937223e+00 , 2.3286649600000002e+00 , -6.1380699999999999e-01 , -7.1787000000000001e-01 , 3.2848699999999997e-01 --8.1264760457897767e-01 , -4.0612017098355784e+00 , 2.4584153600000000e+00 , 5.6620700000000002e-01 , 7.8300300000000000e-01 , -2.5752000000000003e-01 --8.1904049472789087e-01 , -4.0225452250121503e+00 , 2.5856562400000001e+00 , -8.1953100000000001e-01 , -5.6512700000000005e-01 , 9.4867300000000002e-02 --8.2311552797026577e-01 , -3.9810843520556674e+00 , 2.7115201600000001e+00 , -8.0982200000000004e-01 , -5.8396000000000003e-01 , 5.6388300000000002e-02 --8.2599540311935238e-01 , -3.9388187977883256e+00 , 2.8363950400000002e+00 , -8.3567400000000003e-01 , -5.4854300000000000e-01 , 2.7385600000000000e-02 --8.8162004656785609e-01 , -3.9958831972425095e+00 , 2.9576122400000000e+00 , -8.3341500000000002e-01 , -5.4888499999999996e-01 , -6.4377199999999996e-02 --9.0181296362689389e-01 , -3.9869879988160086e+00 , 3.0817871999999999e+00 , -5.2310400000000001e-01 , -8.4709000000000001e-01 , -9.3809699999999996e-02 --9.2085743221232841e-01 , -3.9750161099300225e+00 , 3.2056616000000000e+00 , 4.6094099999999999e-01 , 8.8735299999999995e-01 , 1.1784200000000000e-02 --9.3988427766877880e-01 , -3.9619794962601942e+00 , 3.3295463999999999e+00 , 4.6094099999999999e-01 , 8.8735299999999995e-01 , 1.1784200000000000e-02 --9.2705504841489983e-01 , -3.8915181868432418e+00 , 3.4501239999999997e+00 , 4.6094099999999999e-01 , 8.8735299999999995e-01 , 1.1784200000000000e-02 --6.2218851121307370e+00 , -1.3641292907739658e+01 , 4.3387624000000002e+00 , 9.7002900000000003e-01 , 3.1680899999999998e-02 , -2.4091599999999999e-01 --6.2656768415049466e+00 , -1.3601675266133725e+01 , 4.6526448000000000e+00 , 9.6999500000000005e-01 , 1.5634200000000001e-01 , -1.8619300000000000e-01 --6.2615992683470711e+00 , -1.3475738833322794e+01 , 4.9568031999999995e+00 , 9.5859700000000003e-01 , 2.5559900000000002e-01 , -1.2554299999999999e-01 --6.2594293583691005e+00 , -1.3353478675418891e+01 , 5.2586008000000000e+00 , 9.7220600000000001e-01 , 2.3368200000000000e-01 , 1.4447800000000000e-02 --6.2703128343898449e+00 , -1.3254769272109449e+01 , 5.5616880000000002e+00 , -8.8481900000000002e-01 , -2.0984200000000000e-01 , -4.1600700000000002e-01 --6.5544138853458769e+00 , -1.3645136798481300e+01 , 5.9508144000000005e+00 , -9.1518699999999997e-01 , -1.5749299999999999e-01 , -3.7098399999999998e-01 --6.5753122754333209e+00 , -1.3561934154221918e+01 , 6.2644783999999998e+00 , -9.7139200000000003e-01 , -1.3745199999999999e-01 , -1.9365900000000000e-01 --6.5621357493976884e+00 , -1.3421207213085431e+01 , 6.5652464000000004e+00 , 9.5982299999999998e-01 , 1.6445299999999999e-01 , 2.2736400000000001e-01 --6.6480862219155270e+00 , -1.3452106871885489e+01 , 6.9048584000000002e+00 , 8.7180999999999997e-01 , 4.2851000000000000e-01 , 2.3733299999999999e-01 --6.6920143511034116e+00 , -1.3407105002657065e+01 , 7.2294840000000002e+00 , -5.0231700000000001e-01 , -8.6422399999999999e-01 , -2.8191999999999998e-02 --6.7212761628616224e+00 , -1.3339180458605396e+01 , 7.5496999999999996e+00 , -2.6532699999999998e-01 , -9.4282900000000003e-01 , 2.0168100000000000e-01 --6.7437006945546614e+00 , -1.3257348330963817e+01 , 7.8667856000000000e+00 , -3.0132599999999998e-01 , -9.2972800000000000e-01 , 2.1168000000000001e-01 --6.7837101893307246e+00 , -1.3205503546541811e+01 , 8.1946144000000007e+00 , -3.8468500000000000e-01 , -8.9922700000000000e-01 , 2.0834600000000000e-01 --6.8005522193731167e+00 , -1.3113519994403122e+01 , 8.5107847999999997e+00 , -3.3729300000000001e-01 , -8.9420999999999995e-01 , 2.9431700000000000e-01 --6.8340825317920793e+00 , -1.3051235904066289e+01 , 8.8389360000000003e+00 , -4.1469200000000001e-01 , -8.7865700000000002e-01 , 2.3662800000000000e-01 --6.8654669096017251e+00 , -1.2982786588295411e+01 , 9.1671288000000004e+00 , 9.6356500000000000e-01 , 1.7707400000000001e-01 , -2.0046700000000001e-01 --6.8734152217424693e+00 , -1.2875523554821090e+01 , 9.4815208000000002e+00 , 9.6424799999999999e-01 , 7.5222899999999995e-02 , -2.5409900000000002e-01 --6.9099041772160348e+00 , -1.2812778058724172e+01 , 9.8165152000000013e+00 , 9.7850300000000001e-01 , 8.6481500000000003e-02 , -1.8722500000000000e-01 --6.9480569999284274e+00 , -1.2753341071930787e+01 , 1.0156148000000000e+01 , 9.9617400000000000e-01 , 7.5766299999999995e-02 , -4.3548799999999999e-02 --6.8152318566316463e+00 , -1.2418681886782389e+01 , 1.0364574399999999e+01 , 9.9403100000000000e-01 , 9.7406400000000004e-02 , 4.9135999999999999e-02 --7.0206988559058079e+00 , -1.2623749578906898e+01 , 1.0841851200000001e+01 , 9.8672899999999997e-01 , 1.0443800000000000e-01 , 1.2433100000000000e-01 --7.0493560670674036e+00 , -1.2545197067499306e+01 , 1.1183574400000001e+01 , 9.8774300000000004e-01 , 8.7270500000000001e-02 , 1.2941300000000000e-01 --7.0200008932756788e+00 , -1.2374873972612976e+01 , 1.1476615200000001e+01 , 9.9704999999999999e-01 , 6.0821899999999998e-02 , 4.6825300000000000e-02 --7.1442440126945748e+00 , -1.2441444243312905e+01 , 1.1910274400000000e+01 , 9.7138599999999997e-01 , 1.2615699999999999e-01 , 2.0122899999999999e-01 --7.1681975035574155e+00 , -1.2352069523288257e+01 , 1.2259267200000000e+01 , -9.5836299999999996e-01 , -1.9828100000000001e-01 , -2.0548500000000000e-01 --7.2099329610202432e+00 , -1.2287522434319287e+01 , 1.2628696000000001e+01 , 8.1083799999999995e-01 , 5.8526400000000001e-01 , -2.9747500000000000e-03 --7.2534204566751814e+00 , -1.2223754962033947e+01 , 1.3004448000000002e+01 , 5.6028800000000001e-01 , 8.0734899999999998e-01 , -1.8510799999999999e-01 --7.2927290037505710e+00 , -1.2151287847182989e+01 , 1.3381864000000000e+01 , -5.6983899999999998e-01 , -7.9881400000000002e-01 , 1.9282199999999999e-01 --7.3240983550782239e+00 , -1.2065114240334474e+01 , 1.3755328000000000e+01 , -5.5813699999999999e-01 , -8.0553100000000000e-01 , 1.9900300000000001e-01 --7.3271887583686972e+00 , -1.1935749527249714e+01 , 1.4101960000000000e+01 , -7.0329500000000000e-01 , -6.5844000000000003e-01 , 2.6801700000000001e-01 --7.3609836942642382e+00 , -1.1850173725974958e+01 , 1.4487904000000000e+01 , -9.3780600000000003e-01 , -3.2696599999999998e-01 , 1.1667100000000000e-01 --7.4018212005094277e+00 , -1.1770164018740934e+01 , 1.4886640000000000e+01 , 9.6013599999999999e-01 , 9.9844100000000005e-02 , -2.6109300000000002e-01 --7.4283945725096494e+00 , -1.1669435468048801e+01 , 1.5275392000000000e+01 , 9.8694499999999996e-01 , 4.1383799999999998e-02 , -1.5564800000000001e-01 --7.3636312011224714e+00 , -1.1436648736196304e+01 , 1.5553904000000001e+01 , 9.9482999999999999e-01 , 3.8011999999999997e-02 , -9.4176700000000002e-02 --7.4454898467363240e+00 , -1.1409735056807088e+01 , 1.6023567999999997e+01 , 9.6857599999999999e-01 , -2.8196499999999999e-02 , -2.4711500000000000e-01 --7.4022700702452440e+00 , -1.1206252509211327e+01 , 1.6336503999999998e+01 , -9.4318400000000002e-01 , 4.0309800000000000e-02 , 3.2981500000000002e-01 --7.2289223731769354e+00 , -1.0822842974117178e+01 , 1.6468688000000000e+01 , 9.8590699999999998e-01 , 1.5951099999999999e-01 , 5.0437299999999997e-02 --7.7277566033796941e+00 , -1.1353197823924381e+01 , 1.7550912000000000e+01 , -9.3540699999999999e-01 , -1.8269800000000000e-01 , -3.0271399999999998e-01 --7.6779185930787275e+00 , -1.1130015757419830e+01 , 1.7873104000000001e+01 , 9.2492900000000000e-01 , 1.9796500000000000e-01 , 3.2452399999999998e-01 --1.6140461004914242e+00 , -2.1921830752529505e+00 , 1.1153050400000000e+01 , -9.6403499999999998e-01 , -4.3533199999999999e-03 , 2.6574100000000000e-01 --1.5917438163185040e+00 , -2.0876803994271604e+00 , 1.1312836000000001e+01 , 4.5870600000000000e-01 , -1.1111700000000000e-02 , -8.8851899999999995e-01 --1.5394343066891993e+00 , -1.9488789155811235e+00 , 1.1412093600000000e+01 , -3.4413400000000000e-01 , -3.0680400000000002e-01 , 8.8737999999999995e-01 --1.4622630415573457e+00 , -1.7837934333716055e+00 , 1.1457437600000000e+01 , 2.7139799999999997e-01 , -2.8428699999999999e-03 , -9.6246299999999996e-01 --6.7677205730453194e-01 , -8.7562638808007609e-01 , 9.9452776000000007e+00 , -5.3251800000000005e-01 , -3.4785600000000000e-01 , -7.7163599999999999e-01 --5.1098536460229438e-01 , -6.3703695285115858e-01 , 9.7471783999999992e+00 , -4.3716699999999997e-01 , -8.5873699999999997e-02 , -8.9527100000000004e-01 --4.3910419500813447e-01 , -4.9961630520832578e-01 , 9.7541983999999999e+00 , 2.7572000000000002e-01 , 2.9593300000000000e-01 , 9.1454999999999997e-01 -1.4159916521211047e-01 , 1.3841294923554082e-01 , 8.5492960000000000e+00 , -7.4234100000000003e-01 , -2.1274999999999999e-01 , 6.3534800000000002e-01 -1.6371184343586576e-01 , 2.1469298232214018e-01 , 8.6374880000000012e+00 , -5.7943900000000004e-01 , 5.1317000000000002e-02 , 8.1339799999999995e-01 --7.6574951382129886e-02 , 4.7803894964774774e-02 , 9.3811296000000013e+00 , 8.2731100000000002e-01 , -5.2596400000000001e-02 , 5.5927700000000002e-01 --1.5168581338739617e-01 , 4.4675306806222670e-02 , 9.7395968000000011e+00 , -6.5427000000000002e-01 , -2.9984100000000002e-01 , 6.9428100000000004e-01 --9.8545021828656765e-02 , 1.6032117011741343e-01 , 9.7768079999999991e+00 , -2.1397300000000000e-01 , -6.9060200000000005e-01 , 6.9085799999999997e-01 --9.3222061451725846e-02 , 2.3488499121709694e-01 , 9.9424904000000005e+00 , -3.8729500000000000e-01 , -5.2278899999999995e-01 , 7.5940399999999997e-01 -3.7367045786809649e-01 , 6.9269015926474120e-01 , 8.8359927999999996e+00 , -8.0606599999999995e-01 , -3.7563400000000002e-01 , 4.5733600000000002e-01 -3.8793814946531624e-01 , 7.6568739675772202e-01 , 8.9536584000000001e+00 , -4.8107699999999998e-01 , -5.1269100000000001e-01 , 7.1113499999999996e-01 -3.6374812440780802e-01 , 8.1126179437496670e-01 , 9.1852352000000010e+00 , 9.8486099999999999e-01 , 4.9361600000000002e-03 , -1.7327699999999999e-01 -3.8576233840370611e-01 , 8.9457110315926269e-01 , 9.2924904000000002e+00 , -8.1663900000000000e-01 , 3.5740600000000000e-01 , 4.5316899999999999e-01 -2.9041973652902464e-01 , 8.9754537975965243e-01 , 9.7665015999999998e+00 , 9.7347799999999995e-01 , 2.2823099999999999e-01 , -1.5846599999999999e-02 -2.1451543091648184e-01 , 9.2324875845763810e-01 , 1.0204643200000000e+01 , 6.9205200000000000e-01 , -2.7206799999999998e-01 , 6.6861300000000001e-01 -5.5041733441771745e-01 , 1.2157477099194991e+00 , 9.3142992000000007e+00 , 4.6998600000000001e-02 , 2.6683600000000002e-01 , 9.6259499999999998e-01 -2.9941947535489821e-01 , 1.1431578080704763e+00 , 1.0349785599999999e+01 , 7.1596199999999999e-01 , -5.1154200000000005e-01 , -4.7510400000000003e-01 -3.9873111601457456e-01 , 1.2850819796878756e+00 , 1.0226878400000000e+01 , -7.3486499999999999e-01 , 5.1348700000000003e-01 , 4.4306200000000001e-01 -4.5346542040899829e-01 , 1.3997244235441477e+00 , 1.0259472000000001e+01 , -7.7205100000000004e-01 , 3.8531700000000002e-01 , 5.0543899999999997e-01 -5.0978728883355373e-01 , 1.5170571747153254e+00 , 1.0279398400000000e+01 , 6.9240100000000004e-01 , -6.3807600000000006e-02 , -7.1868600000000005e-01 -2.8032508563047664e-01 , 1.5155845580730003e+00 , 1.1398407199999999e+01 , -2.8762199999999999e-01 , -8.1130199999999997e-01 , -5.0898200000000005e-01 -4.2012943268265590e-01 , 1.6767248402148114e+00 , 1.1126540800000001e+01 , -3.1383800000000001e-01 , -8.6321300000000001e-01 , -3.9543600000000001e-01 -7.0382685999307149e-01 , 1.8725156707262505e+00 , 1.0245744000000000e+01 , -3.4697000000000000e-01 , -7.0017600000000002e-01 , -6.2399199999999999e-01 -8.0908763558755803e-01 , 1.9993305735669213e+00 , 1.0054404800000000e+01 , -6.6970900000000000e-01 , -4.0051700000000003e-02 , -7.4154299999999995e-01 -9.1024789273237117e-01 , 2.1192052058075155e+00 , 9.8698879999999996e+00 , -3.9442100000000002e-01 , 4.5315400000000000e-01 , -7.9942700000000000e-01 -8.0320559075750686e-01 , 2.2084257337562354e+00 , 1.0616649600000001e+01 , -3.1789499999999998e-01 , -9.4804200000000005e-01 , 1.2609499999999999e-02 -7.6766811524261991e-01 , 2.3233276762032036e+00 , 1.1089766400000000e+01 , 5.1782300000000003e-01 , 8.4323800000000004e-01 , -1.4425299999999999e-01 -7.3071987373971448e-01 , 2.4537219172434943e+00 , 1.1602600799999999e+01 , 8.6489499999999997e-01 , 3.5221000000000002e-01 , -3.5763899999999998e-01 -7.6065212101633439e-01 , 2.5926160522067301e+00 , 1.1808240000000000e+01 , -8.6249299999999995e-01 , -3.6275299999999999e-01 , 3.5286800000000001e-01 -1.0698213014723696e+00 , 2.6827949402352687e+00 , 1.0529892800000001e+01 , -2.9911500000000002e-01 , 1.4906600000000000e-01 , 9.4250199999999995e-01 -1.1357592868653352e+00 , 2.7981125094568799e+00 , 1.0504974400000002e+01 , -2.0158100000000001e-01 , -2.1026500000000000e-02 , 9.7924599999999995e-01 -1.3333532632807010e+00 , 2.8599883293600037e+00 , 9.7000560000000000e+00 , -1.0492500000000000e-01 , 1.8540799999999999e-01 , 9.7704400000000002e-01 -1.4382342689474159e+00 , 2.9372287953859577e+00 , 9.3837815999999989e+00 , -8.6724800000000002e-01 , 4.9785299999999999e-01 , -4.8315900000000002e-03 -1.4514598990266590e+00 , 3.0623126313710722e+00 , 9.6385088000000003e+00 , 9.4468600000000003e-01 , -3.2696199999999997e-01 , -2.5777499999999998e-02 -1.4717117834203362e+00 , 3.1921007816822602e+00 , 9.8706576000000013e+00 , 7.3542700000000005e-01 , -6.5045500000000001e-01 , -1.8988400000000000e-01 -1.5395785075786490e+00 , 3.2874182211133167e+00 , 9.7838176000000008e+00 , 5.6540400000000002e-01 , -1.2816100000000000e-01 , 8.1479599999999996e-01 -1.7254829565940590e+00 , 3.2432137879637741e+00 , 8.7660631999999996e+00 , 7.6029999999999998e-01 , 6.4710400000000001e-01 , -5.6577299999999997e-02 -1.5629779467155493e+00 , 1.4082540914494390e-01 , 1.2436984799999999e+00 , 1.1568600000000000e-01 , -2.1832499999999999e-01 , -9.6899500000000005e-01 -1.5284319486407121e+00 , 8.5232420310259460e-02 , 1.2608356000000001e+00 , 9.7011200000000006e-02 , -1.8294299999999999e-01 , -9.7832600000000003e-01 -1.4839150833548347e+00 , 6.6180306581313797e-03 , 1.2616696799999998e+00 , -8.3430799999999999e-02 , 1.8453200000000000e-01 , 9.7927900000000001e-01 -1.4452894394815001e+00 , -5.6646376293094658e-02 , 1.2767049600000000e+00 , -9.7356300000000007e-02 , 1.8459500000000001e-01 , 9.7798099999999999e-01 -1.3954565658695204e+00 , -1.4475331270377056e-01 , 1.2767351199999999e+00 , -8.8935200000000006e-02 , 1.3537900000000000e-01 , 9.8679399999999995e-01 -1.3452505596130946e+00 , -2.3329667866162218e-01 , 1.2798031200000000e+00 , -9.1381699999999996e-02 , 1.9222700000000001e-01 , 9.7708700000000004e-01 -1.3010097615545893e+00 , -3.0553063841980377e-01 , 1.2965637600000000e+00 , -8.7552699999999997e-02 , 1.8715100000000001e-01 , 9.7842200000000001e-01 -1.2453783730188819e+00 , -4.0229411640767454e-01 , 1.2998356000000000e+00 , -7.8117800000000001e-02 , 1.8644800000000000e-01 , 9.7935399999999995e-01 -1.1930610734486213e+00 , -4.9111690137232022e-01 , 1.3115865599999998e+00 , -6.0328699999999999e-02 , 1.9811000000000001e-01 , 9.7832100000000000e-01 -1.1366178549219002e+00 , -5.8863919078979032e-01 , 1.3214416000000000e+00 , -7.3469699999999999e-02 , 1.7414499999999999e-01 , 9.8197500000000004e-01 -1.0749591987223945e+00 , -6.9472104922218714e-01 , 1.3298822399999999e+00 , -1.0139600000000000e-01 , 1.4985999999999999e-01 , 9.8349399999999998e-01 -1.0004328458538896e+00 , -8.2673544862755177e-01 , 1.3280539199999999e+00 , 1.0629000000000000e-01 , -1.5206600000000001e-01 , -9.8263900000000004e-01 -9.3292116455109042e-01 , -9.4247177012840666e-01 , 1.3400430399999999e+00 , -1.1243200000000000e-01 , 1.2530400000000000e-01 , 9.8572700000000002e-01 -8.4962328456956926e-01 , -1.0920435822755628e+00 , 1.3387763200000000e+00 , -2.6417000000000000e-02 , 2.0197499999999999e-01 , 9.7903399999999996e-01 -7.9156859854423023e-01 , -1.1816686012366726e+00 , 1.3717152000000001e+00 , -2.1074400000000000e-02 , 3.1673099999999998e-01 , 9.4828100000000004e-01 -7.2536854819052188e-01 , -1.2888514417471129e+00 , 1.4000531199999999e+00 , 9.5927800000000004e-03 , 2.4614700000000000e-01 , 9.6918499999999996e-01 -6.4210311902611128e-01 , -1.4305217019413630e+00 , 1.4169343999999999e+00 , -3.6488399999999997e-02 , 2.3340300000000000e-01 , 9.7169499999999998e-01 -5.6215301078060032e-01 , -1.5631580324123582e+00 , 1.4424944800000001e+00 , -5.2667899999999997e-02 , 2.2385400000000000e-01 , 9.7319900000000004e-01 -4.6374237341024171e-01 , -1.7318273648913838e+00 , 1.4592093600000000e+00 , -7.9116000000000006e-02 , 2.1196599999999999e-01 , 9.7406899999999996e-01 -3.6458670270444360e-01 , -1.9002763197647319e+00 , 1.4820997600000001e+00 , -4.8798000000000001e-02 , 2.1936800000000001e-01 , 9.7442099999999998e-01 -2.5964686971196671e-01 , -2.0774107413636722e+00 , 1.5081309599999999e+00 , 5.7786499999999998e-02 , -2.0607700000000001e-01 , -9.7682800000000003e-01 -1.4384875885667903e-01 , -2.2720162278715970e+00 , 1.5346748800000001e+00 , -5.7888000000000002e-02 , 2.0482800000000001e-01 , 9.7708499999999998e-01 -2.3136720666020016e-02 , -2.4750458835553344e+00 , 1.5658010400000000e+00 , -6.3109399999999996e-02 , 2.0614900000000000e-01 , 9.7648299999999999e-01 --1.2186848636796066e-01 , -2.7237588719934784e+00 , 1.5916315200000000e+00 , -5.7833500000000003e-02 , 2.0767400000000000e-01 , 9.7648699999999999e-01 --2.6498384124134189e-01 , -2.9627400158001524e+00 , 1.6292514400000000e+00 , -6.1927299999999998e-02 , 2.1058700000000000e-01 , 9.7561200000000003e-01 --4.3168274364754655e-01 , -3.2457750316419505e+00 , 1.6645324000000001e+00 , -7.2817400000000004e-02 , 2.0621700000000001e-01 , 9.7579300000000002e-01 --6.1417477249541053e-01 , -3.5568530503600044e+00 , 1.7048126400000001e+00 , -6.0016199999999999e-02 , 2.0531500000000000e-01 , 9.7685400000000000e-01 --8.1359601800814918e-01 , -3.8936151569908848e+00 , 1.7510739200000001e+00 , 9.3653399999999998e-03 , 2.1165400000000001e-01 , 9.7729999999999995e-01 --1.0394633113289671e+00 , -4.2740775790784369e+00 , 1.8014255200000000e+00 , 1.0354200000000000e-01 , 3.5429899999999998e-01 , 9.2938200000000004e-01 --1.2953372719660412e+00 , -4.7094144410571799e+00 , 1.8575439199999999e+00 , -2.3187300000000000e-01 , -1.6072699999999999e-02 , 9.7261299999999995e-01 --1.0136188431773423e+00 , -4.1223465573758222e+00 , 2.0857087920000001e+00 , 7.0369499999999996e-01 , 5.1971900000000004e-01 , -4.8446499999999998e-01 --9.9331035447262650e-01 , -4.0346534599846908e+00 , 2.2248896000000000e+00 , 7.9479200000000005e-01 , 5.8034300000000005e-01 , -1.7750700000000000e-01 --9.9581256414390218e-01 , -3.9901678212894787e+00 , 2.3555520799999998e+00 , -5.6266799999999995e-01 , -7.8284100000000001e-01 , 2.6563900000000001e-01 --1.0161517698292597e+00 , -3.9799227789172518e+00 , 2.4811362400000001e+00 , 5.0532200000000005e-01 , 8.4325300000000003e-01 , -1.8323400000000001e-01 --1.0311194929848249e+00 , -3.9591658498298754e+00 , 2.6073194399999999e+00 , 4.7927100000000000e-01 , 8.6712000000000000e-01 , -1.3565400000000000e-01 --1.0395880682676788e+00 , -3.9270211419824141e+00 , 2.7334163199999999e+00 , -5.1785599999999998e-01 , -8.5026199999999996e-01 , 9.4226699999999997e-02 --1.0521821647611276e+00 , -3.9013792724953102e+00 , 2.8580145600000000e+00 , 4.9565300000000001e-01 , 8.6797000000000002e-01 , -3.0911999999999999e-02 --1.0528589212323891e+00 , -3.8561097466815948e+00 , 2.9824235200000002e+00 , -5.0603500000000001e-01 , -8.5863999999999996e-01 , -8.1648899999999996e-02 --1.1141206428495209e+00 , -3.9188161246221611e+00 , 3.1060607999999998e+00 , 5.3605199999999997e-01 , 8.4363299999999997e-01 , -3.0503400000000000e-02 --1.1376229862241045e+00 , -3.9149531164804117e+00 , 3.2308816000000000e+00 , 4.6094099999999999e-01 , 8.8735200000000003e-01 , 1.1784299999999999e-02 --6.0165920875720875e+00 , -1.2398347320829453e+01 , 3.7265560000000000e+00 , 7.6161500000000004e-01 , 3.9658599999999999e-01 , 5.1250499999999999e-01 --6.3465529062645718e+00 , -1.2863484185349760e+01 , 4.0512959999999998e+00 , -9.1466700000000001e-01 , 3.0986300000000001e-02 , -4.0301799999999999e-01 --7.0205823338979432e+00 , -1.3913662814633481e+01 , 4.4451856000000003e+00 , -9.5342199999999999e-01 , 1.0519800000000000e-01 , 2.8270099999999998e-01 --6.8453299571390289e+00 , -1.3494106346014114e+01 , 4.7306863999999997e+00 , -8.4280299999999997e-01 , 5.3366599999999997e-01 , -6.9879700000000003e-02 --6.4184033237990921e+00 , -1.2654039714665727e+01 , 4.9492528000000000e+00 , 9.8948700000000001e-01 , 7.3871699999999998e-02 , 1.2433000000000000e-01 --6.4005312536154779e+00 , -1.2515013820605118e+01 , 5.2372496000000002e+00 , -9.1311399999999998e-01 , -9.1566499999999995e-02 , -3.9728900000000000e-01 --6.7407261432466825e+00 , -1.2974160475778399e+01 , 5.6207080000000005e+00 , -8.8427000000000000e-01 , -1.7036499999999999e-01 , -4.3479000000000001e-01 --6.8135942813878980e+00 , -1.2984793084293374e+01 , 5.9427023999999999e+00 , -9.6363299999999996e-01 , -1.8600100000000000e-01 , -1.9187199999999999e-01 --6.8371220545830536e+00 , -1.2910082085367668e+01 , 6.2503343999999998e+00 , -9.7563000000000000e-01 , -1.8921199999999999e-01 , -1.1110700000000000e-01 --6.8516886005336790e+00 , -1.2822518570802133e+01 , 6.5552000000000001e+00 , -8.6516400000000004e-01 , -2.4589900000000001e-01 , -4.3706499999999998e-01 --7.2792437576930151e+00 , -1.3405595384021847e+01 , 7.0272768000000001e+00 , -8.1964599999999999e-01 , -5.3389299999999995e-01 , -2.0769799999999999e-01 --7.3262393071908214e+00 , -1.3365353806028445e+01 , 7.3591407999999996e+00 , 7.6844900000000005e-01 , 6.3869100000000001e-01 , 3.9481799999999997e-02 --7.2587238535446978e+00 , -1.3139861727234184e+01 , 7.6390880000000001e+00 , -7.4768199999999996e-01 , -6.5850600000000004e-01 , 8.5681900000000005e-02 --7.3909928479199642e+00 , -1.3233844926620860e+01 , 8.0142679999999995e+00 , 7.3188600000000004e-01 , 6.4193999999999996e-01 , -2.2859399999999999e-01 --7.3381560865464088e+00 , -1.3034355373111023e+01 , 8.2990303999999995e+00 , -7.0679199999999998e-01 , -7.0735300000000001e-01 , -9.8181899999999992e-03 --7.3358773440047536e+00 , -1.2914726034751117e+01 , 8.6085552000000014e+00 , 7.7875499999999998e-01 , 6.1392100000000005e-01 , -1.2900300000000001e-01 --7.4967214546024241e+00 , -1.3047821882282300e+01 , 9.0150703999999990e+00 , -8.3453300000000004e-04 , -8.6693600000000004e-01 , 4.9841800000000003e-01 --7.2749520607244662e+00 , -1.2586576914549314e+01 , 9.1909656000000002e+00 , -8.9493599999999995e-01 , -1.2702100000000000e-01 , 4.2773299999999997e-01 --7.1137225079834430e+00 , -1.2225573514018336e+01 , 9.3938904000000001e+00 , 9.8627699999999996e-01 , 8.8063900000000001e-02 , -1.3965100000000000e-01 --7.0951287178720168e+00 , -1.2081732249531083e+01 , 9.6847264000000006e+00 , 9.5543500000000003e-01 , 4.7452900000000001e-04 , -2.9520000000000002e-01 --7.1477784217471072e+00 , -1.2047624241646345e+01 , 1.0027250400000000e+01 , 9.9572700000000003e-01 , 4.9415000000000001e-02 , -7.8017199999999995e-02 --7.0045952378491911e+00 , -1.1719566827389547e+01 , 1.0226504000000000e+01 , 9.9381799999999998e-01 , 1.0947999999999999e-02 , 1.1047700000000001e-01 --7.2067084271403594e+00 , -1.1904535579676393e+01 , 1.0688264000000000e+01 , 9.8622399999999999e-01 , 9.9141900000000005e-02 , 1.3241400000000000e-01 --7.2391533974117710e+00 , -1.1836089026161352e+01 , 1.1025962400000001e+01 , 9.9444299999999997e-01 , 5.8680200000000002e-02 , 8.7410900000000000e-02 --7.2203970766729615e+00 , -1.1692002584605103e+01 , 1.1323912000000000e+01 , 9.9941800000000003e-01 , 3.4028999999999997e-02 , -2.4574499999999999e-03 --9.8791839031115725e+00 , -1.5417287664295579e+01 , 1.3990680000000001e+01 , -2.7240399999999998e-01 , 7.2294499999999995e-01 , -6.3493800000000000e-01 --7.7177785309748721e+00 , -1.2169323667940537e+01 , 1.2411128000000000e+01 , -8.6013899999999999e-01 , -4.8582999999999998e-01 , -1.5534000000000001e-01 --9.9580230823153091e+00 , -1.5226238324117492e+01 , 1.4874472000000001e+01 , -1.2215500000000000e-01 , 2.8380200000000000e-01 , 9.5106999999999997e-01 --7.7833215222081691e+00 , -1.2008793127107362e+01 , 1.3146408000000001e+01 , -9.0408400000000000e-01 , -4.0810400000000002e-01 , 1.2681899999999999e-01 --7.7550884295153590e+00 , -1.1713057045309757e+01 , 1.3803584000000001e+01 , -8.7280700000000000e-01 , -4.7905399999999998e-01 , 9.3360100000000001e-02 --7.9143364587589176e+00 , -1.1801154835146070e+01 , 1.4323064000000000e+01 , -1.6214699999999999e-02 , -7.9756899999999997e-01 , 6.0301000000000005e-01 --7.8218188004370361e+00 , -1.1543004596186977e+01 , 1.4575264000000001e+01 , -8.5950800000000005e-01 , -3.6317899999999997e-01 , 3.5964800000000002e-01 --7.6498717835672547e+00 , -1.1177812468564293e+01 , 1.4732928000000001e+01 , -8.7694300000000003e-01 , 2.2237799999999999e-03 , 4.8058899999999999e-01 --7.5322444691338486e+00 , -1.0889104592753494e+01 , 1.4946960000000001e+01 , 9.3711100000000003e-01 , -1.1036200000000000e-01 , -3.3112599999999998e-01 --7.5636469122231631e+00 , -1.0798056392902959e+01 , 1.5339456000000000e+01 , 9.9467499999999998e-01 , 4.4291100000000000e-02 , -9.3054300000000006e-02 --7.6009321685321058e+00 , -1.0711490270765161e+01 , 1.5745680000000002e+01 , 9.9258900000000005e-01 , 3.9706699999999998e-02 , -1.1484600000000000e-01 --7.6189919630770735e+00 , -1.0598318293257503e+01 , 1.6134639999999997e+01 , -9.6647200000000000e-01 , 9.6917300000000008e-03 , 2.5658900000000001e-01 --7.4539386865920036e+00 , -1.0248849153375968e+01 , 1.6286583999999998e+01 , -9.5551500000000000e-01 , 3.6316399999999999e-02 , 2.9269899999999999e-01 --7.9320367270657464e+00 , -1.0713984306499404e+01 , 1.7311920000000001e+01 , -9.6115899999999999e-01 , -1.6624900000000001e-02 , -2.7549299999999999e-01 --7.9061526595749818e+00 , -1.0532819501596316e+01 , 1.7668744000000000e+01 , -9.3895300000000004e-01 , -1.2833600000000001e-01 , -3.1921500000000003e-01 --1.7123609498465995e+00 , -2.2128128424399360e+00 , 1.0502613600000000e+01 , 3.3201999999999998e-01 , 9.4320800000000005e-01 , 1.1036300000000001e-02 --1.7618740886806057e+00 , -2.1934451196020701e+00 , 1.0783226400000000e+01 , -5.7148200000000005e-01 , -7.8422499999999995e-01 , 2.4165900000000001e-01 --1.6056534063371242e+00 , -1.9524228627898479e+00 , 1.0689969600000001e+01 , 7.3285500000000003e-01 , 6.5986699999999998e-01 , -1.6583100000000001e-01 --1.7874451518172076e+00 , -2.0703353057109588e+00 , 1.1235938400000000e+01 , -9.6748100000000004e-01 , -1.1479600000000000e-01 , 2.2539300000000001e-01 --1.8130359589197029e+00 , -2.0187405542708863e+00 , 1.1497113600000000e+01 , -5.1216499999999998e-01 , -4.5121300000000003e-02 , 8.5770100000000005e-01 --1.6257785670631240e+00 , -1.7463518137889928e+00 , 1.1334322400000001e+01 , -6.7863200000000001e-01 , 6.7892099999999997e-02 , 7.3133400000000004e-01 --1.5805742368085944e+00 , -1.6219685149428882e+00 , 1.1455388800000001e+01 , 2.7139799999999997e-01 , -2.8430100000000000e-03 , -9.6246299999999996e-01 --6.9844219259521800e-01 , -6.7622482379653492e-01 , 9.7919711999999990e+00 , -4.6926400000000001e-01 , -2.2926700000000000e-01 , -8.5277700000000001e-01 --5.7447937040091102e-01 , -4.9263442800410040e-01 , 9.6967175999999995e+00 , 2.7572000000000002e-01 , 2.9593300000000000e-01 , 9.1454999999999997e-01 --4.8426876774300220e-01 , -3.4324245467187309e-01 , 9.6668696000000018e+00 , 1.3404500000000000e-01 , 2.6332200000000000e-01 , 9.5535000000000003e-01 --3.6336274223532383e-01 , -1.6692512778442126e-01 , 9.5612160000000017e+00 , 1.0286000000000000e-02 , -2.0388800000000001e-01 , 9.7894000000000003e-01 -1.8496367205669562e-01 , 3.8578226376627667e-01 , 8.4371424000000008e+00 , -8.7565300000000001e-01 , -1.3698000000000000e-02 , 4.8274699999999998e-01 --2.4984872840054617e-01 , 6.2033759537992950e-02 , 9.6361376000000014e+00 , -1.8170300000000000e-01 , -6.9606900000000005e-01 , 6.9460200000000005e-01 -2.1249902793493325e-01 , 5.1791699180769202e-01 , 8.6614184000000005e+00 , -7.6507599999999998e-01 , -1.5679699999999999e-01 , 6.2455899999999998e-01 -2.8629539409819471e-01 , 6.3568176135527521e-01 , 8.6239887999999993e+00 , -6.1189700000000002e-01 , -3.7556600000000002e-02 , 7.9004500000000000e-01 -3.0588450202228445e-01 , 7.0912525651118385e-01 , 8.7239120000000003e+00 , -8.7966299999999997e-01 , 2.4573100000000000e-01 , 4.0719600000000000e-01 -3.0686616776410069e-01 , 7.6809511446031720e-01 , 8.8797871999999991e+00 , -9.5423300000000000e-01 , -2.6722200000000002e-01 , 1.3428300000000001e-01 -3.3749314719209411e-01 , 8.5184191632353601e-01 , 8.9594199999999997e+00 , -4.9545499999999998e-01 , -3.0797400000000003e-01 , 8.1220499999999995e-01 -3.5179141244187306e-01 , 9.2547355362276607e-01 , 9.0855096000000000e+00 , -8.9543700000000004e-01 , 9.2940599999999998e-02 , 4.3537799999999999e-01 -3.9480713486917862e-01 , 1.0204501061273215e+00 , 9.1339319999999997e+00 , -6.8888300000000002e-01 , 5.4798199999999997e-01 , 4.7450599999999998e-01 -3.9043869332695369e-01 , 1.0848212071000234e+00 , 9.3260096000000008e+00 , -5.8040599999999998e-01 , 1.7614199999999999e-01 , 7.9504900000000001e-01 -5.5457210425123904e-01 , 1.2545622008964534e+00 , 9.0018936000000007e+00 , 4.0181299999999998e-01 , -1.4923200000000000e-01 , -9.0347999999999995e-01 -5.6496352761440671e-01 , 1.3288832508867610e+00 , 9.1516431999999988e+00 , 8.3520200000000000e-01 , 5.3295599999999999e-01 , 1.3562800000000000e-01 -3.8798909862343844e-01 , 1.3055133779686132e+00 , 9.9307383999999992e+00 , -8.9294099999999998e-01 , 4.3347500000000000e-01 , 1.2147800000000000e-01 -4.6834967468789479e-01 , 1.4276967322186844e+00 , 9.8744535999999989e+00 , 8.3690900000000001e-01 , 5.4733600000000004e-01 , 2.6617300000000002e-03 -4.3804943472652602e-01 , 1.4972890161981849e+00 , 1.0202864800000000e+01 , -8.8178900000000004e-01 , 4.6687500000000000e-02 , 4.6932699999999999e-01 -1.6008263037707682e-01 , 1.4745596634103224e+00 , 1.1458987199999999e+01 , 5.9266900000000000e-01 , 8.0406800000000000e-01 , 4.7103199999999998e-02 -3.4732289012458373e-01 , 1.6497697940120279e+00 , 1.1040470400000000e+01 , -2.9486999999999999e-02 , -9.8576200000000003e-01 , -1.6554099999999999e-01 -5.8197053749185357e-01 , 1.8280926539345110e+00 , 1.0405072000000001e+01 , -5.7456900000000000e-01 , -6.9447599999999998e-01 , -4.3309799999999998e-01 -7.2604149153081354e-01 , 1.9646254192091595e+00 , 1.0085771200000000e+01 , -7.1249499999999999e-01 , 1.6114700000000000e-03 , -7.0167599999999997e-01 -7.7183477391837751e-01 , 2.0724404219404975e+00 , 1.0156345600000000e+01 , 5.7424900000000001e-01 , -7.4305800000000005e-02 , 8.1530199999999997e-01 -8.5429999131691914e-01 , 2.1869633656793450e+00 , 1.0073031200000001e+01 , -3.7981799999999999e-01 , 3.3121099999999998e-01 , -8.6373400000000000e-01 -6.8054632070283438e-01 , 2.2808266976363871e+00 , 1.1144824000000002e+01 , 1.4689600000000000e-01 , 9.7424699999999997e-01 , 1.7106800000000000e-01 -7.5715051667820932e-01 , 2.4063075038703921e+00 , 1.1119916000000000e+01 , -4.2966900000000002e-01 , 5.4837899999999995e-01 , 7.1740199999999998e-01 -7.0273586414594313e-01 , 2.5419357972958831e+00 , 1.1734056799999999e+01 , 8.6489499999999997e-01 , 3.5221000000000002e-01 , -3.5763899999999998e-01 -6.1732329022446097e-01 , 2.7028041552852065e+00 , 1.2572224000000000e+01 , 9.7508200000000000e-01 , 1.5482000000000001e-01 , 1.5889200000000001e-01 -1.0846593281039361e+00 , 2.7521672281577589e+00 , 1.0487377600000000e+01 , 2.6286300000000001e-01 , -2.4893799999999999e-01 , -9.3216600000000005e-01 -1.1432419119539567e+00 , 2.8694191836145482e+00 , 1.0523195200000000e+01 , -1.6756299999999999e-01 , -6.1824400000000002e-01 , 7.6791799999999999e-01 -1.3217256231503138e+00 , 2.9313315075658997e+00 , 9.8408720000000010e+00 , -7.8221700000000005e-01 , 6.1430099999999999e-01 , -1.0378400000000000e-01 -1.4285106077513308e+00 , 3.0073195099255807e+00 , 9.5346024000000007e+00 , -8.6436199999999996e-01 , 4.4882100000000003e-01 , 2.2680000000000000e-01 -1.4802641546417021e+00 , 3.1097699401281353e+00 , 9.5640135999999991e+00 , -9.2963399999999996e-01 , 3.5214499999999999e-01 , 1.0851400000000000e-01 -1.5143725348775432e+00 , 3.2308003800572611e+00 , 9.7240175999999998e+00 , 4.6579399999999999e-01 , -7.2854300000000005e-01 , -5.0225600000000004e-01 -1.6788483957487386e+00 , 3.2214405151295296e+00 , 8.9220943999999989e+00 , -4.9632399999999999e-01 , 8.5319199999999995e-01 , -1.6039100000000001e-01 -1.4881537064571169e+00 , 1.4746446653933076e-01 , 1.2396008799999998e+00 , -5.3844700000000002e-02 , 1.9825300000000001e-01 , 9.7867099999999996e-01 -1.4478656841660649e+00 , 8.4627108527112416e-02 , 1.2511438400000001e+00 , 4.3826700000000003e-02 , -1.8884100000000001e-01 , -9.8102900000000004e-01 -1.4011987822735232e+00 , 7.2959517640593941e-03 , 1.2526351999999998e+00 , -7.2895900000000000e-02 , 1.8632899999999999e-01 , 9.7977899999999996e-01 -1.3567131330858850e+00 , -6.4117496808237195e-02 , 1.2628896000000001e+00 , -8.0921900000000005e-02 , 1.9876800000000000e-01 , 9.7670000000000001e-01 -1.3073300195444091e+00 , -1.4244494093856508e-01 , 1.2693968799999999e+00 , -9.2155200000000007e-02 , 1.6168800000000000e-01 , 9.8253000000000001e-01 -1.2575912666709328e+00 , -2.2126893769000633e-01 , 1.2786383199999998e+00 , -9.1966300000000001e-02 , 1.9605800000000001e-01 , 9.7626999999999997e-01 -1.2001542412763522e+00 , -3.1624429702021573e-01 , 1.2798322400000000e+00 , 9.4501399999999999e-02 , -1.9034899999999999e-01 , -9.7715799999999997e-01 -1.1460231783158492e+00 , -4.0329122218064883e-01 , 1.2895052800000000e+00 , -5.6503600000000001e-02 , 1.9493600000000000e-01 , 9.7918700000000003e-01 -1.0904735411749624e+00 , -4.9072121027944604e-01 , 1.3021912000000000e+00 , -6.5070799999999998e-02 , 1.9736999999999999e-01 , 9.7816700000000001e-01 -1.0259997572296629e+00 , -5.9506041112790387e-01 , 1.3081244000000001e+00 , -7.2435899999999998e-02 , 1.6983500000000001e-01 , 9.8280699999999999e-01 -9.6106578841606027e-01 , -6.9969451502311619e-01 , 1.3178036799999999e+00 , -1.3543600000000000e-01 , 1.5075100000000000e-01 , 9.7924999999999995e-01 -8.8221757926060507e-01 , -8.3017618212473465e-01 , 1.3173928799999999e+00 , -1.0271700000000000e-01 , 1.8059200000000000e-01 , 9.7818000000000005e-01 -8.1146253348718211e-01 , -9.4341834352834297e-01 , 1.3305176799999998e+00 , -7.9193200000000005e-02 , 1.1938799999999999e-01 , 9.8968400000000001e-01 -7.2282833980212202e-01 , -1.0903790696682174e+00 , 1.3305395199999999e+00 , 5.7710100000000000e-02 , -2.7419700000000002e-01 , -9.5994000000000002e-01 -6.6637852488829030e-01 , -1.1704891853762480e+00 , 1.3688666399999998e+00 , -1.7798399999999999e-02 , 2.8379199999999999e-01 , 9.5872100000000005e-01 -5.7938791798500833e-01 , -1.3094870542342951e+00 , 1.3824043200000000e+00 , -4.2446100000000000e-02 , 2.5885700000000000e-01 , 9.6498300000000004e-01 -4.9563977497472278e-01 , -1.4404526339502217e+00 , 1.4049265600000000e+00 , -6.4593800000000007e-02 , 2.3433899999999999e-01 , 9.7000699999999995e-01 -4.0636682811761604e-01 , -1.5794462489659056e+00 , 1.4285626400000000e+00 , -7.5430499999999998e-02 , 2.1752700000000000e-01 , 9.7313499999999997e-01 -3.0252566231261691e-01 , -1.7453538093253380e+00 , 1.4472743200000000e+00 , -4.6522200000000000e-02 , 2.1775500000000000e-01 , 9.7489400000000004e-01 -2.0190560269541535e-01 , -1.9020767538492045e+00 , 1.4753730400000000e+00 , 5.2631600000000001e-02 , -2.1740599999999999e-01 , -9.7466100000000000e-01 -8.1552291937581511e-02 , -2.0932655117802819e+00 , 1.4968251200000000e+00 , 6.3228999999999994e-02 , -2.0756900000000000e-01 , -9.7617500000000001e-01 --4.8762339751023287e-02 , -2.3017435124488017e+00 , 1.5199276799999999e+00 , -6.5585900000000003e-02 , 2.1236600000000000e-01 , 9.7498700000000005e-01 --1.8615271082452889e-01 , -2.5194977527259645e+00 , 1.5481730400000000e+00 , -6.4269499999999993e-02 , 2.1535399999999999e-01 , 9.7441900000000004e-01 --3.2559677960202160e-01 , -2.7365434765949646e+00 , 1.5847956000000001e+00 , -5.4215399999999997e-02 , 2.2033100000000000e-01 , 9.7391700000000003e-01 --4.9463623919014932e-01 , -3.0066187574981855e+00 , 1.6154121600000000e+00 , -7.1381200000000006e-02 , 2.1191499999999999e-01 , 9.7467800000000004e-01 --6.7114069405382581e-01 , -3.2853063774063482e+00 , 1.6544111200000000e+00 , 6.8465200000000000e-03 , 1.5178500000000000e-01 , 9.8838999999999999e-01 --8.7471763020497351e-01 , -3.6083730963713805e+00 , 1.6939332000000000e+00 , 1.0024100000000000e-01 , 9.5933400000000002e-02 , 9.9032799999999999e-01 --1.0746055741687006e+00 , -3.9202184454235578e+00 , 1.7478208000000000e+00 , 2.4766199999999999e-02 , 4.0496599999999999e-01 , 9.1399600000000003e-01 --1.1160158812508767e+00 , -3.9460580756778763e+00 , 1.8689662400000000e+00 , 1.1793000000000000e-02 , 6.9931299999999996e-01 , 7.1471899999999999e-01 --1.2931558243571262e+00 , -4.2109840305307644e+00 , 1.9497334719999999e+00 , 5.7939200000000002e-01 , -1.2795300000000001e-01 , -8.0494299999999996e-01 --1.9159027669349631e+00 , -5.2535049586366487e+00 , 1.9232786799999999e+00 , -6.8650000000000003e-02 , 2.4814000000000000e-01 , 9.6628899999999995e-01 --2.2594986949606195e+00 , -5.7937127211041171e+00 , 2.0040799616000000e+00 , 7.4508099999999994e-02 , -2.3891899999999999e-01 , -9.6817699999999995e-01 --2.6616958195893776e+00 , -6.4290681629448869e+00 , 2.0955921200000001e+00 , -6.8574999999999997e-02 , 2.3030600000000001e-01 , 9.7069899999999998e-01 --3.1263347196985958e+00 , -7.1603604195635491e+00 , 2.2035144799999999e+00 , -5.8857000000000000e-02 , 2.2544500000000001e-01 , 9.7247600000000001e-01 --3.6477341377769070e+00 , -7.9769829751754795e+00 , 2.3343423200000002e+00 , 3.5756599999999999e-02 , 2.7540799999999999e-01 , 9.6066200000000002e-01 --4.2683281467141203e+00 , -8.9510263902194893e+00 , 2.4900552800000000e+00 , 3.4973599999999999e-01 , 2.2854200000000000e-01 , 9.0854400000000002e-01 --4.3994417590057608e+00 , -9.0876671620199900e+00 , 2.7114889600000001e+00 , 3.7477500000000002e-01 , 2.6009700000000002e-01 , 8.8988400000000001e-01 --4.5669369903759005e+00 , -9.2842205083773166e+00 , 2.9386603199999999e+00 , 3.7477500000000002e-01 , 2.6009700000000002e-01 , 8.8988400000000001e-01 --4.9108333021876653e+00 , -9.7693941291102124e+00 , 3.1766351999999998e+00 , 3.4080500000000002e-01 , 1.6628499999999999e-01 , 9.2531099999999999e-01 --5.6288761951729951e+00 , -1.0861623907406914e+01 , 3.4521832000000003e+00 , -2.4945300000000001e-01 , -1.5927900000000000e-01 , -9.5519799999999999e-01 --6.4274362638223508e+00 , -1.2067674007637651e+01 , 3.7781815999999999e+00 , -9.4080200000000003e-01 , -1.4146700000000001e-01 , -3.0802299999999999e-01 --6.5529367026781458e+00 , -1.2168349911125047e+01 , 4.0792199999999994e+00 , -9.6534900000000001e-01 , -1.6148199999999999e-01 , -2.0499899999999999e-01 --6.5844669822717989e+00 , -1.2114361843732834e+01 , 4.3722296000000007e+00 , 9.9116300000000002e-01 , 1.0530500000000000e-01 , 8.0658599999999997e-02 --6.6116047915422858e+00 , -1.2055344884170363e+01 , 4.6645007999999999e+00 , 9.9636100000000005e-01 , 4.7935800000000001e-02 , -7.0484599999999994e-02 --6.6264577824743487e+00 , -1.1975267501668357e+01 , 4.9536416000000001e+00 , 9.9419700000000000e-01 , 7.7823400000000001e-02 , 7.4268399999999998e-02 --6.5432786742791809e+00 , -1.1741718941870067e+01 , 5.2186024000000000e+00 , 9.7676499999999999e-01 , 1.1838500000000000e-01 , 1.7864900000000000e-01 --6.8065995606462977e+00 , -1.2052426184789887e+01 , 5.5700912000000002e+00 , -8.9877300000000004e-01 , 1.9233699999999999e-02 , -4.3799199999999999e-01 --7.0189699128922278e+00 , -1.2277357307578487e+01 , 5.9208727999999997e+00 , -9.1584800000000000e-01 , -1.5444499999999999e-03 , -4.0152100000000002e-01 --7.0225132692501759e+00 , -1.2177690564550932e+01 , 6.2145792000000002e+00 , -9.6259300000000003e-01 , 9.6050399999999994e-02 , -2.5335500000000000e-01 --7.2574478667610798e+00 , -1.2431602191469413e+01 , 6.5910175999999998e+00 , -9.3556200000000000e-01 , 3.1285399999999998e-02 , -3.5177500000000000e-01 --7.4296753647961786e+00 , -1.2477656533898436e+01 , 7.2585207999999994e+00 , 9.6547799999999995e-01 , -1.2909200000000001e-01 , 2.2624500000000000e-01 --7.4217892603013542e+00 , -1.2357421103197261e+01 , 7.5564912000000009e+00 , 9.9634599999999995e-01 , 6.6600099999999995e-02 , 5.3473300000000001e-02 --7.5056351767390534e+00 , -1.2374099166175986e+01 , 7.8982456000000001e+00 , 9.9280100000000004e-01 , 4.7391999999999997e-02 , -1.1000400000000000e-01 --7.4021962004402244e+00 , -1.2111718876904382e+01 , 8.1478456000000001e+00 , 9.9362200000000001e-01 , -9.6979899999999994e-02 , -5.7540599999999997e-02 --8.3001390255117702e+00 , -1.3316797926483508e+01 , 8.9367999999999999e+00 , -2.8252300000000001e-02 , -9.7418199999999999e-01 , 2.2398999999999999e-01 --7.4100894902789562e+00 , -1.1798475009262058e+01 , 9.0525520000000004e+00 , 9.7462700000000002e-01 , -1.8049299999999999e-01 , -1.3237900000000000e-01 --7.2827556941902394e+00 , -1.1508966799848857e+01 , 9.2729800000000004e+00 , -9.8448199999999997e-01 , 1.5017000000000000e-01 , 9.0796100000000005e-02 --7.1815080637969135e+00 , -1.1258809510009574e+01 , 9.5031840000000010e+00 , -9.5799400000000001e-01 , 1.4749499999999999e-01 , 2.4595400000000001e-01 --7.2892460377686632e+00 , -1.1303676085591650e+01 , 9.8739024000000004e+00 , 9.9660700000000002e-01 , -8.2280699999999998e-02 , -1.9571900000000001e-03 --7.0655548928897911e+00 , -1.0883320387955973e+01 , 1.0010485600000001e+01 , 9.8953400000000002e-01 , -1.0080100000000000e-02 , 1.4394999999999999e-01 --7.3901626430911040e+00 , -1.1226719104035753e+01 , 1.0550692800000000e+01 , 9.8068500000000003e-01 , 5.3614700000000001e-03 , 1.9552200000000000e-01 --7.4206861389034309e+00 , -1.1159899237922486e+01 , 1.0881038400000000e+01 , 9.9310399999999999e-01 , 1.1790000000000000e-02 , 1.1663800000000001e-01 --7.3713629558844165e+00 , -1.0981814393781068e+01 , 1.1148526400000000e+01 , 9.9771600000000005e-01 , -1.7398299999999999e-03 , 6.7530499999999993e-02 --1.0115737738788456e+01 , -1.4579601708737915e+01 , 1.3797240000000000e+01 , -3.4110800000000002e-01 , 7.9602799999999996e-01 , -4.9998500000000001e-01 --7.8856423474645929e+00 , -1.1447492494520114e+01 , 1.2221348799999999e+01 , -9.5536299999999996e-01 , -9.9035200000000004e-02 , -2.7834199999999998e-01 --1.0191466738025179e+01 , -1.4392378743942981e+01 , 1.4662832000000002e+01 , 2.3064999999999999e-01 , -4.2196600000000001e-01 , 8.7678100000000003e-01 --1.0238370305036151e+01 , -1.4309141848027487e+01 , 1.5113152000000001e+01 , 8.8112499999999996e-02 , -3.4281699999999998e-01 , 9.3526100000000001e-01 --9.7699505184298108e+00 , -1.3550225400560658e+01 , 1.5064584000000000e+01 , 8.8112499999999996e-02 , -3.4281699999999998e-01 , 9.3526100000000001e-01 --7.9670778195956196e+00 , -1.1074026775430935e+01 , 1.3636248000000002e+01 , 9.8498200000000002e-01 , 1.3060400000000000e-01 , -1.1293000000000000e-01 --8.7591454219356670e+00 , -1.1965402484237995e+01 , 1.4808432000000000e+01 , -2.8079399999999999e-01 , -9.3816999999999995e-01 , 2.0246700000000001e-01 --8.1540383163590189e+00 , -1.1062581957827208e+01 , 1.4527944000000000e+01 , -9.5691400000000004e-01 , 1.8547900000000000e-01 , 2.2341400000000000e-01 --7.7431390356383343e+00 , -1.0416707994326446e+01 , 1.4427168000000000e+01 , 9.8251200000000005e-01 , -1.5208500000000000e-01 , -1.0743000000000000e-01 --7.7771502002249626e+00 , -1.0334253366733680e+01 , 1.4813424000000001e+01 , 9.9855000000000005e-01 , 3.0078700000000002e-03 , -5.3752599999999998e-02 --7.7744224931361590e+00 , -1.0205322215933430e+01 , 1.5164008000000001e+01 , 9.9827200000000005e-01 , 5.0937700000000002e-02 , -2.9291899999999999e-02 --7.7633237737038741e+00 , -1.0063244342541392e+01 , 1.5507936000000001e+01 , 9.9500400000000000e-01 , 2.8278200000000000e-02 , -9.5744200000000002e-02 --7.8264342296923779e+00 , -1.0008940799143534e+01 , 1.5948480000000002e+01 , -9.5441399999999998e-01 , 1.1761300000000001e-02 , 2.9825400000000002e-01 --7.6585661457756657e+00 , -9.6744045060931523e+00 , 1.6100631999999997e+01 , -9.3217799999999995e-01 , 9.3160499999999993e-02 , 3.4980800000000001e-01 --7.5336571828516750e+00 , -9.3943970185621666e+00 , 1.6304887999999998e+01 , 9.9909899999999996e-01 , 4.2145400000000000e-02 , -4.9047300000000004e-03 --8.1056261191548629e+00 , -9.9293581096400505e+00 , 1.7453880000000002e+01 , -9.4917099999999999e-01 , -2.8554000000000000e-02 , -3.1346299999999999e-01 --7.9406209387901079e+00 , -9.5958796744497761e+00 , 1.7621216000000000e+01 , -9.4917099999999999e-01 , -2.8554000000000000e-02 , -3.1346299999999999e-01 --1.9495824254400995e+00 , -2.1548590569749422e+00 , 1.0686953600000001e+01 , 7.3285500000000003e-01 , 6.5986599999999995e-01 , -1.6583100000000001e-01 --1.8782106640183631e+00 , -2.0105805117451023e+00 , 1.0759535200000000e+01 , -8.4211900000000006e-02 , -7.8677699999999995e-01 , 6.1146599999999995e-01 --1.8370115811723711e+00 , -1.8965913229040154e+00 , 1.0886124000000001e+01 , -8.5170800000000002e-01 , -3.0692700000000001e-01 , 4.2472199999999999e-01 --1.8072512569828971e+00 , -1.7933358237583650e+00 , 1.1036029600000001e+01 , -9.4583300000000003e-01 , -2.6597999999999999e-01 , 1.8615799999999999e-01 --1.8505261422172703e+00 , -1.7602986727705483e+00 , 1.1327812000000000e+01 , 6.9310400000000005e-01 , -2.6243499999999997e-01 , -6.7136799999999996e-01 --1.7770045679663795e+00 , -1.6129102348609528e+00 , 1.1400435200000000e+01 , 6.9310400000000005e-01 , -2.6243499999999997e-01 , -6.7136799999999996e-01 --5.2459184942889703e-02 , 7.3108974987726727e-02 , 8.1363535999999996e+00 , 8.1727700000000003e-01 , 1.5807700000000001e-02 , -5.7602799999999998e-01 --3.6098549564528959e-02 , 1.3698540736224452e-01 , 8.2355175999999997e+00 , -8.5861299999999996e-01 , -4.9800999999999998e-02 , 5.1019999999999999e-01 --5.6828653520955097e-01 , -2.8845490495173243e-01 , 9.5045464000000006e+00 , 5.9603899999999999e-01 , 5.7710400000000002e-02 , 8.0087900000000001e-01 --4.7042862886529768e-01 , -1.4171490991670632e-01 , 9.4632168000000014e+00 , 4.4611899999999999e-01 , -1.9886699999999999e-01 , 8.7259900000000001e-01 -7.4787130598378937e-02 , 3.8445919063006717e-01 , 8.4123488000000002e+00 , 9.1423500000000002e-01 , 3.6883100000000002e-01 , -1.6774500000000001e-01 --3.9953469788044194e-01 , 4.3501537547536717e-02 , 9.6492624000000013e+00 , -3.5995100000000002e-01 , -1.8124199999999999e-01 , 9.1519799999999996e-01 -8.0350881303740129e-02 , 4.9500244256707426e-01 , 8.6934399999999989e+00 , -4.1600399999999998e-01 , 3.7949600000000000e-01 , 8.2639200000000002e-01 -9.8293066721868882e-02 , 5.6473974768012747e-01 , 8.8062280000000008e+00 , 5.0747699999999996e-01 , -8.3689000000000002e-01 , 2.0513999999999999e-01 -2.2075186985107220e-01 , 7.1544151815879409e-01 , 8.6580487999999995e+00 , -6.7455900000000002e-01 , 6.3842299999999996e-01 , -3.7065799999999999e-01 -1.8136491508540220e-01 , 7.4385173097921276e-01 , 8.9171440000000004e+00 , 1.6128700000000001e-01 , -8.3248200000000006e-01 , 5.3005700000000000e-01 -2.2144257437024706e-01 , 8.3123122507295455e-01 , 8.9799287999999997e+00 , 8.6891099999999999e-01 , 1.6800599999999999e-01 , -4.6558400000000000e-01 -2.7273710431456299e-01 , 9.2792629873440480e-01 , 9.0122935999999996e+00 , -2.9247600000000001e-01 , -4.3099799999999999e-01 , 8.5363800000000001e-01 -3.3742871796897833e-01 , 1.0329707537953468e+00 , 9.0046391999999997e+00 , -2.9308400000000001e-01 , -1.7868899999999999e-01 , 9.3923999999999996e-01 -3.7930047892916341e-01 , 1.1233827285862312e+00 , 9.0617768000000005e+00 , 2.7744000000000002e-01 , -2.4991099999999999e-01 , 9.2766999999999999e-01 -2.2690776682282543e-01 , 1.0990438125661046e+00 , 9.6990055999999996e+00 , 9.8838400000000004e-01 , -1.4492900000000000e-01 , 4.5755299999999999e-02 -5.1333344900802769e-01 , 1.3322059300883589e+00 , 9.0253560000000004e+00 , -5.6835000000000002e-01 , -4.8598100000000000e-01 , 6.6392799999999996e-01 -5.4140351227245476e-01 , 1.4149558396534374e+00 , 9.1258511999999996e+00 , 9.7206400000000004e-01 , -9.7026899999999999e-03 , 2.3451600000000000e-01 -3.0898791019243976e-01 , 1.3734011809676223e+00 , 1.0082183199999999e+01 , -8.7712699999999999e-01 , -4.3436200000000003e-01 , -2.0488500000000001e-01 -4.3253810382980573e-01 , 1.5124371580842797e+00 , 9.8974168000000002e+00 , -5.3003299999999998e-01 , -8.4688900000000000e-01 , 4.2933699999999998e-02 -1.4344197218268540e-01 , 1.4789657432320040e+00 , 1.1140008800000000e+01 , 2.9957899999999999e-02 , -9.1153099999999998e-01 , 4.1013800000000000e-01 -2.0411166759028365e-01 , 1.6025945849103445e+00 , 1.1202658400000001e+01 , -1.2578200000000000e-01 , -9.6618800000000005e-01 , -2.2507600000000000e-01 -4.3168640759595234e-01 , 1.7782754674092038e+00 , 1.0642233599999999e+01 , -6.2423899999999999e-01 , -6.2161900000000003e-01 , -4.7319699999999998e-01 -6.1081266311259630e-01 , 1.9256175037322796e+00 , 1.0225952800000000e+01 , -4.9058000000000002e-01 , -5.2328300000000005e-01 , -6.9678300000000004e-01 -6.9236266622162690e-01 , 2.0409386126236333e+00 , 1.0167484000000000e+01 , 5.5705099999999996e-01 , -2.7202000000000000e-02 , 8.3003300000000002e-01 -7.8787131024871626e-01 , 2.1556617558632132e+00 , 1.0045804000000000e+01 , -4.5397599999999999e-01 , 2.6567700000000000e-01 , -8.5048299999999999e-01 -8.4039268671765743e-01 , 2.2617473515423692e+00 , 1.0103950400000000e+01 , 4.1859700000000000e-01 , 2.0174200000000000e-01 , 8.8548099999999996e-01 -7.1009705896829867e-01 , 2.3667418663600972e+00 , 1.0992547200000001e+01 , 6.1292899999999995e-01 , -4.7815500000000000e-01 , -6.2903500000000001e-01 -6.4976917869381623e-01 , 2.4942166963586585e+00 , 1.1628195200000000e+01 , 8.6489499999999997e-01 , 3.5221000000000002e-01 , -3.5763899999999998e-01 -6.9263358378257633e-01 , 2.6298291186970135e+00 , 1.1804506400000001e+01 , -8.7546900000000005e-01 , -3.0443100000000001e-01 , 3.7533400000000000e-01 -1.0399126225897066e+00 , 2.7060433024349106e+00 , 1.0417552000000001e+01 , 5.1834599999999997e-01 , -2.4799099999999999e-01 , -8.1842400000000004e-01 -1.0980758034027360e+00 , 2.8214381161812851e+00 , 1.0465142400000000e+01 , -3.4414000000000000e-01 , -1.2733000000000000e-01 , 9.3024399999999996e-01 -1.4165794986431486e+00 , 2.8305578598714067e+00 , 9.0288919999999990e+00 , -7.4430300000000005e-01 , 6.4615999999999996e-01 , 1.6879300000000000e-01 -1.4469413712314154e+00 , 2.9338663240084188e+00 , 9.1739408000000005e+00 , -7.3933599999999999e-01 , 6.6948399999999997e-01 , 7.1924600000000005e-02 -1.4583430518966356e+00 , 3.0558659993070765e+00 , 9.4604192000000005e+00 , -9.4321999999999995e-01 , 2.9356399999999999e-01 , 1.5542300000000001e-01 -1.4671715383519111e+00 , 3.1921248540780991e+00 , 9.7960272000000010e+00 , 7.4737600000000004e-01 , -6.3889499999999999e-01 , 1.8232499999999999e-01 -1.6079282341034637e+00 , 3.2176439760595619e+00 , 9.2201480000000000e+00 , 6.1762499999999998e-01 , -6.2938099999999997e-01 , -4.7161399999999998e-01 -1.7224179219897897e+00 , 3.2443115415762640e+00 , 8.7655847999999992e+00 , 7.6029999999999998e-01 , 6.4710400000000001e-01 , -5.6577400000000000e-02 -1.4519155299010582e+00 , 2.0867968096539902e-01 , 1.2194789600000000e+00 , -2.2839999999999999e-02 , 1.9382300000000000e-01 , 9.8077099999999995e-01 -1.4133143069766070e+00 , 1.5522527254993523e-01 , 1.2358028000000001e+00 , -7.9169299999999998e-02 , 2.1151100000000000e-01 , 9.7416400000000003e-01 -1.3673059882978458e+00 , 8.6198490683822016e-02 , 1.2417505599999998e+00 , -9.5434000000000005e-02 , 1.6659499999999999e-01 , 9.8139600000000005e-01 -1.3173963158354978e+00 , 9.1756404662692859e-03 , 1.2440791199999999e+00 , -1.0961400000000000e-01 , 2.0468800000000001e-01 , 9.7267000000000003e-01 -1.2708140657064042e+00 , -5.9935648492558169e-02 , 1.2547848799999999e+00 , 1.0367300000000000e-01 , -1.8211800000000000e-01 , -9.7779600000000000e-01 -1.2119415059122323e+00 , -1.5269768539085904e-01 , 1.2508630400000000e+00 , -9.0667999999999999e-02 , 1.7572199999999999e-01 , 9.8025600000000002e-01 -1.1589806081605389e+00 , -2.3012681911541177e-01 , 1.2610394399999998e+00 , -1.1702300000000000e-01 , 1.8884999999999999e-01 , 9.7500799999999999e-01 -1.0982846613273924e+00 , -3.2368293582462471e-01 , 1.2633721599999999e+00 , -7.4223600000000001e-02 , 2.0706300000000000e-01 , 9.7550800000000004e-01 -1.0445857629309678e+00 , -4.0202569941316790e-01 , 1.2794235199999999e+00 , -6.5738699999999997e-02 , 2.1456200000000000e-01 , 9.7449600000000003e-01 -9.8205816441468530e-01 , -4.9633512516365474e-01 , 1.2881116800000001e+00 , -8.1599199999999997e-02 , 1.9280100000000000e-01 , 9.7783900000000001e-01 -9.1915150270016399e-01 , -5.8997858414939941e-01 , 1.3000363199999998e+00 , -1.1923599999999999e-01 , 1.5808100000000000e-01 , 9.8020099999999999e-01 -8.3758567864450950e-01 , -7.1778523577176934e-01 , 1.2965086399999999e+00 , -1.0347300000000000e-01 , 1.7050899999999999e-01 , 9.7990800000000000e-01 -7.6405641400772284e-01 , -8.2932950457036592e-01 , 1.3069232000000000e+00 , -8.1791799999999998e-02 , 1.8368399999999999e-01 , 9.7957700000000003e-01 -6.7548991186690310e-01 , -9.6547397753574238e-01 , 1.3079278400000001e+00 , -1.0331600000000001e-01 , 1.6850899999999999e-01 , 9.8027100000000000e-01 -5.8139944008684963e-01 , -1.1107499151933147e+00 , 1.3099495999999999e+00 , -4.9233300000000001e-02 , 2.9750700000000002e-01 , 9.5345000000000002e-01 -5.2656385476934719e-01 , -1.1802396320947883e+00 , 1.3538646400000001e+00 , -3.2947299999999999e-02 , 3.0929000000000001e-01 , 9.5039700000000005e-01 -4.4012674688784248e-01 , -1.3085668347790249e+00 , 1.3730671999999999e+00 , -5.4240200000000002e-02 , 2.3938000000000001e-01 , 9.6940999999999999e-01 -3.4218370807172627e-01 , -1.4539445889020848e+00 , 1.3895168800000000e+00 , -7.4424900000000002e-02 , 2.3392700000000000e-01 , 9.6940199999999999e-01 -2.3961971691874595e-01 , -1.6082495339999374e+00 , 1.4081204000000000e+00 , -6.1348300000000001e-02 , 2.3470299999999999e-01 , 9.7012900000000002e-01 -1.3927753375905216e-01 , -1.7534132581749060e+00 , 1.4356814400000000e+00 , -5.8946300000000000e-02 , 2.2551599999999999e-01 , 9.7245499999999996e-01 -1.9303744626400832e-02 , -1.9321308232465975e+00 , 1.4558855200000000e+00 , -8.0340800000000004e-02 , 2.2282299999999999e-01 , 9.7154300000000005e-01 --1.0257951974495771e-01 , -2.1114795231634398e+00 , 1.4830513599999999e+00 , -7.7159300000000000e-02 , 2.2511600000000001e-01 , 9.7127200000000002e-01 --2.4450456722339853e-01 , -2.3258659321647634e+00 , 1.5060031199999999e+00 , -8.5062899999999997e-02 , 2.2284100000000001e-01 , 9.7113700000000003e-01 --3.9456485270783892e-01 , -2.5483850767074472e+00 , 1.5342734400000000e+00 , -6.5846600000000005e-02 , 2.3055100000000001e-01 , 9.7082999999999997e-01 --5.5585834693124880e-01 , -2.7877297047791938e+00 , 1.5661931199999999e+00 , -8.1131599999999998e-02 , 2.2325100000000000e-01 , 9.7137899999999999e-01 --7.3872363855634360e-01 , -3.0612124774528464e+00 , 1.5980223200000001e+00 , 6.2802800000000001e-03 , 2.2917699999999999e-01 , 9.7336500000000004e-01 --9.2910309898357868e-01 , -3.3432220533828758e+00 , 1.6386364000000000e+00 , 9.1655000000000000e-02 , 1.4172399999999999e-01 , 9.8565400000000003e-01 --1.1590015997032026e+00 , -3.6857377445394546e+00 , 1.6761855999999999e+00 , -1.3608500000000001e-01 , -2.4022499999999999e-02 , -9.9040600000000001e-01 --1.4112476473499727e+00 , -4.0621243715522963e+00 , 1.7200215999999999e+00 , -4.1885299999999998e-01 , 6.7898300000000000e-01 , 6.0294599999999998e-01 --1.7079873989097480e+00 , -4.5083980204569141e+00 , 1.7658835200000000e+00 , -1.1369000000000000e-01 , 1.7106499999999999e-01 , 9.7867800000000005e-01 --2.0037203556265233e+00 , -4.9434103739483000e+00 , 1.8309209600000000e+00 , 7.1128700000000003e-02 , -2.5106899999999999e-01 , -9.6535199999999999e-01 --2.3173624030765723e+00 , -5.4045601222354058e+00 , 1.9100392719999999e+00 , -8.4179599999999993e-02 , 2.5998700000000002e-01 , 9.6193600000000001e-01 --2.7110601540605268e+00 , -5.9859945692488719e+00 , 1.9916305480000001e+00 , -8.1200200000000000e-02 , 2.5145400000000001e-01 , 9.6445700000000001e-01 --3.1614928059351772e+00 , -6.6524145536491375e+00 , 2.0872947919999998e+00 , -6.5860900000000000e-02 , 2.3407600000000001e-01 , 9.6998499999999999e-01 --3.6873158583663193e+00 , -7.4299920480492769e+00 , 2.2001313599999999e+00 , -9.1439999999999994e-03 , 2.3759000000000000e-01 , 9.7132200000000002e-01 --4.2574015693929246e+00 , -8.2659280601823166e+00 , 2.3406468000000000e+00 , 2.0530100000000001e-01 , 2.7998200000000001e-01 , 9.3779599999999996e-01 --4.5023741951099128e+00 , -8.5781580193839968e+00 , 2.5410984800000000e+00 , -2.5522099999999998e-01 , -2.8859000000000001e-01 , -9.2281000000000002e-01 --4.6597685237686814e+00 , -8.7452330218866337e+00 , 2.7586654400000001e+00 , 2.5008500000000000e-01 , 3.3146100000000001e-01 , 9.0971999999999997e-01 --4.8601389666662760e+00 , -8.9791071963396121e+00 , 2.9833605599999999e+00 , 3.1755000000000000e-01 , 3.2912799999999998e-01 , 8.8929000000000002e-01 --5.4336298051114680e+00 , -9.7848963732652336e+00 , 3.2253280000000002e+00 , 9.3066700000000002e-02 , 3.8464900000000002e-01 , 9.1835900000000004e-01 --6.5418389385028721e+00 , -1.1401752210143423e+01 , 3.5277392000000001e+00 , -9.6420300000000003e-01 , -2.2356999999999999e-01 , -1.4258199999999999e-01 --6.7070754088069755e+00 , -1.1555581982923082e+01 , 3.8203119999999999e+00 , -9.6954300000000004e-01 , -1.0323800000000000e-01 , -2.2210199999999999e-01 --6.7377806051124391e+00 , -1.1505140696263808e+01 , 4.1061351999999998e+00 , 9.8126599999999997e-01 , 8.7752399999999994e-02 , 1.7151200000000000e-01 --6.7542051489462906e+00 , -1.1432491604377882e+01 , 4.3893792000000005e+00 , 9.9820900000000001e-01 , 5.7944000000000002e-02 , 1.4868599999999999e-02 --6.7792837581244676e+00 , -1.1373163339531450e+01 , 4.6732784000000009e+00 , 9.9503900000000001e-01 , 9.5658699999999999e-02 , -2.7316099999999999e-02 --6.7787830739718924e+00 , -1.1275648055624877e+01 , 4.9515511999999999e+00 , 9.8205100000000001e-01 , 1.6049500000000000e-01 , 9.9087499999999995e-02 --6.8558742461693001e+00 , -1.1293715860395519e+01 , 5.2464639999999996e+00 , -9.7016500000000006e-01 , -1.6830600000000001e-01 , -1.7451000000000000e-01 --6.9656630228491228e+00 , -1.1357780551725046e+01 , 5.5530352000000001e+00 , -9.6547200000000000e-01 , -1.1305900000000001e-01 , -2.3469300000000001e-01 --6.9921507096100708e+00 , -1.1297782883886590e+01 , 5.8400439999999998e+00 , 9.9387000000000003e-01 , 5.4546900000000002e-02 , 9.6158199999999999e-02 --7.0143657523265119e+00 , -1.1233735651025938e+01 , 6.1269384000000002e+00 , 9.9600500000000003e-01 , 8.4259500000000001e-02 , 2.9572000000000001e-02 --7.0410145885869238e+00 , -1.1174513456487356e+01 , 6.4151640000000008e+00 , 9.9595699999999998e-01 , 8.3697499999999994e-02 , 3.2638100000000003e-02 --7.0690201301859599e+00 , -1.1119068082651980e+01 , 6.7055008000000003e+00 , 9.9543999999999999e-01 , 8.9365799999999995e-02 , 3.3361799999999997e-02 --7.1014856514510392e+00 , -1.1066224635291055e+01 , 6.9976680000000009e+00 , 9.9537200000000003e-01 , 9.0735200000000002e-02 , 3.1651199999999997e-02 --7.1240698408988941e+00 , -1.1001403310258445e+01 , 7.2879008000000010e+00 , 9.9577599999999999e-01 , 8.7614700000000004e-02 , 2.7464599999999999e-02 --7.1444819096153633e+00 , -1.0932639871639408e+01 , 7.5777592000000000e+00 , 9.9647300000000005e-01 , 8.1011200000000005e-02 , 2.1859600000000000e-02 --7.1798537016909005e+00 , -1.0883781242213635e+01 , 7.8760728000000002e+00 , 9.9663400000000002e-01 , 7.7752299999999996e-02 , 2.5996700000000001e-02 --7.1995564253224558e+00 , -1.0813282283629139e+01 , 8.1687912000000011e+00 , 9.9627500000000002e-01 , 8.0246700000000004e-02 , 3.1563899999999999e-02 --7.2285688613195518e+00 , -1.0754963675436601e+01 , 8.4678223999999993e+00 , 9.9631000000000003e-01 , 7.8532900000000003e-02 , 3.4621399999999997e-02 --7.2543926696001417e+00 , -1.0691435745091852e+01 , 8.7672279999999994e+00 , 9.9600500000000003e-01 , 8.8053999999999993e-02 , 1.4824100000000000e-02 --7.2896928642574075e+00 , -1.0638742453515421e+01 , 9.0740487999999999e+00 , 9.9895699999999998e-01 , 3.8490400000000001e-02 , 2.4549499999999998e-02 --7.2857446193485238e+00 , -1.0533630823853716e+01 , 9.3590815999999997e+00 , 9.9347700000000005e-01 , 4.8351999999999999e-02 , -1.0327300000000000e-01 --7.3370609864428644e+00 , -1.0502435992419022e+01 , 9.6823551999999999e+00 , 9.9996700000000005e-01 , -6.1238300000000002e-03 , 5.2742500000000003e-03 --7.2288423167481177e+00 , -1.0259970290536593e+01 , 9.8971048000000010e+00 , 9.8555700000000002e-01 , 1.0624200000000000e-01 , 1.3186999999999999e-01 --7.4483588681842345e+00 , -1.0444413276818626e+01 , 1.0347185600000000e+01 , 9.6967199999999998e-01 , 3.2192400000000003e-02 , 2.4228000000000000e-01 --7.4847176223272420e+00 , -1.0387021430266975e+01 , 1.0671738400000001e+01 , 9.8378900000000002e-01 , 3.2270100000000003e-02 , 1.7640200000000000e-01 --7.4704872546060130e+00 , -1.0265627292029752e+01 , 1.0961024800000001e+01 , 9.9206899999999998e-01 , 7.4299500000000004e-02 , 1.0138999999999999e-01 --7.6034458497840554e+00 , -1.0328987472380206e+01 , 1.1371928799999999e+01 , 9.8857099999999998e-01 , 6.9665000000000005e-02 , 1.3369800000000001e-01 --7.6344631470233306e+00 , -1.0261302056088876e+01 , 1.1706424000000000e+01 , 9.9185900000000005e-01 , 1.0513900000000000e-01 , 7.1848300000000004e-02 --7.6624212996585186e+00 , -1.0187245074485062e+01 , 1.2041782400000001e+01 , 9.9439599999999995e-01 , 1.0234600000000001e-01 , 2.6474899999999999e-02 --7.6861736214972858e+00 , -1.0107761961932601e+01 , 1.2378430400000001e+01 , 9.9460400000000004e-01 , 1.0195700000000001e-01 , 1.9155599999999998e-02 --7.7287430455555519e+00 , -1.0049570444846449e+01 , 1.2737271999999999e+01 , 9.9487400000000004e-01 , 9.8636900000000000e-02 , 2.2262700000000000e-02 --7.7502481908940375e+00 , -9.9644215487880139e+00 , 1.3081512000000000e+01 , 9.9576100000000001e-01 , 8.8564199999999996e-02 , 2.4814200000000002e-02 --7.7967252777724916e+00 , -9.9063217935877308e+00 , 1.3454872000000002e+01 , 9.9653499999999995e-01 , 7.9959000000000002e-02 , 2.2919200000000001e-02 --7.8269355016948783e+00 , -9.8274367904887932e+00 , 1.3818872000000001e+01 , 9.9807000000000001e-01 , 4.4833600000000001e-02 , 4.2974400000000003e-02 --7.8530452800955750e+00 , -9.7410353258204978e+00 , 1.4184120000000000e+01 , 9.9911600000000000e-01 , 2.5918099999999999e-02 , 3.3094899999999997e-02 --7.8861094689543094e+00 , -9.6611583445050169e+00 , 1.4562992000000001e+01 , 9.9982199999999999e-01 , 1.8139700000000002e-02 , -5.1614499999999997e-03 --7.9100306194586452e+00 , -9.5677553011739285e+00 , 1.4937184000000000e+01 , 9.9931300000000001e-01 , 1.7558100000000000e-02 , -3.2636100000000001e-02 --7.8910243042956356e+00 , -9.4233316720914129e+00 , 1.5268008000000000e+01 , 9.9800400000000000e-01 , 4.2685200000000000e-02 , -4.6542000000000000e-02 --7.9799344809980948e+00 , -9.4008929162039365e+00 , 1.5734760000000001e+01 , -9.2104100000000000e-01 , -2.3141799999999999e-05 , 3.8946500000000001e-01 --7.8726497160935480e+00 , -9.1538201173523923e+00 , 1.5966784000000001e+01 , -8.9785599999999999e-01 , 6.6123899999999999e-02 , 4.3529499999999999e-01 --7.7039729675602331e+00 , -8.8384540965738871e+00 , 1.6118624000000001e+01 , -6.0588900000000001e-01 , -1.6745900000000001e-02 , 7.9537300000000000e-01 --8.1306937622757616e+00 , -9.1780395311221739e+00 , 1.7050984000000000e+01 , -9.8093500000000000e-01 , -4.3607699999999999e-02 , -1.8938099999999999e-01 --8.1254579126708428e+00 , -9.0363542559819727e+00 , 1.7433911999999999e+01 , -9.6060500000000004e-01 , -3.0719100000000002e-03 , -2.7790199999999998e-01 --2.0192550727325482e+00 , -2.3720126902322791e+00 , 9.3149648000000003e+00 , -8.5742600000000002e-01 , -5.0901700000000005e-01 , -7.5649599999999997e-02 --1.9016171067054133e+00 , -2.1289003738103442e+00 , 9.4873967999999991e+00 , -7.6842400000000000e-01 , 6.3482499999999997e-01 , 8.0753300000000000e-02 --2.0556191255716696e+00 , -2.2272254062193753e+00 , 9.8940680000000008e+00 , 8.7591100000000000e-01 , 3.8485599999999998e-01 , -2.9097499999999998e-01 --1.9714352989655968e+00 , -2.0787261636310088e+00 , 9.9481479999999998e+00 , 9.0354699999999999e-01 , -3.7224400000000002e-01 , -2.1221999999999999e-01 --1.9265230044160888e+00 , -1.9698630538026638e+00 , 1.0060624000000001e+01 , -5.0603699999999996e-01 , 8.4518400000000005e-01 , 1.7201800000000000e-01 --1.9431775438153887e+00 , -1.9208924482458896e+00 , 1.0273792800000001e+01 , 1.4007300000000000e-01 , 9.9014100000000005e-01 , -9.8955000000000006e-04 --2.1416271429274021e+00 , -2.0472963598301481e+00 , 1.0800417600000001e+01 , 2.2969200000000001e-01 , -6.6450799999999999e-01 , 7.1110499999999999e-01 --2.3988562365677621e+00 , -2.2207502207596743e+00 , 1.1449887200000001e+01 , 1.1580500000000001e-01 , 7.8145100000000001e-01 , 6.1312599999999995e-01 --1.0814919914305339e+00 , -9.0804769413279729e-01 , 9.3396232000000019e+00 , 2.1096300000000001e-01 , 5.7695099999999999e-01 , -7.8906399999999999e-01 --1.9309064504764959e+00 , -1.6329974253146338e+00 , 1.1051837600000001e+01 , -8.9405500000000004e-01 , 3.1501000000000001e-01 , 3.1848900000000002e-01 --1.4990718586737688e+00 , -1.1690800755677508e+00 , 1.0458309600000000e+01 , -9.3455500000000002e-01 , 1.3295399999999999e-01 , -3.3004699999999998e-01 --1.2971937401243183e-01 , 1.1523791895335056e-01 , 8.0285368000000013e+00 , -7.9212899999999997e-01 , -2.2933200000000001e-01 , 5.6563099999999999e-01 --1.4327164996241848e-01 , 1.5010858914959746e-01 , 8.1882079999999995e+00 , 8.1727799999999995e-01 , 1.5807600000000002e-02 , -5.7602799999999998e-01 --7.6816622062332751e-02 , 2.5414904744731359e-01 , 8.1917648000000014e+00 , -7.9952000000000001e-01 , -7.8009700000000001e-02 , 5.9555199999999997e-01 --4.8588284146155125e-02 , 3.2538676392678867e-01 , 8.2719904000000000e+00 , -7.3931100000000005e-01 , -3.2201100000000003e-02 , 6.7259300000000000e-01 --1.1466357566717544e-01 , 3.2066225433401319e-01 , 8.5559520000000013e+00 , -9.2497799999999997e-01 , -1.9085199999999999e-01 , 3.2862000000000002e-01 --4.6407599094591134e-03 , 4.6010559651980465e-01 , 8.4651808000000006e+00 , -5.2134100000000005e-01 , -8.2643400000000000e-01 , -2.1262500000000001e-01 -4.6652354694813880e-02 , 5.5241039580404205e-01 , 8.4968488000000004e+00 , 4.7878599999999999e-01 , 7.7654000000000001e-01 , -4.0957399999999999e-01 --1.6302641837242029e+00 , -6.5134534198011407e-01 , 1.2536240000000001e+01 , -5.2236099999999996e-01 , 6.3136300000000001e-01 , -5.7316599999999995e-01 --1.6185151867608263e+00 , -5.4985206834626865e-01 , 1.2773776000000002e+01 , -5.2236099999999996e-01 , 6.3136300000000001e-01 , -5.7316599999999995e-01 --3.6310660938010031e-01 , 4.2858184994406923e-01 , 9.9767064000000012e+00 , -4.5382800000000001e-01 , -4.2136899999999999e-01 , 7.8516699999999995e-01 --1.1681998351537337e+00 , -4.7488799684455518e-02 , 1.2206331199999999e+01 , 5.8079000000000003e-01 , -4.2352200000000001e-01 , 6.9520599999999999e-01 -2.5927646967820661e-01 , 9.7600779216571287e-01 , 8.7684864000000005e+00 , 8.3538299999999999e-01 , -4.3825500000000001e-01 , -3.3176499999999998e-01 -3.4020131550798971e-01 , 1.0854613409256149e+00 , 8.7229136000000000e+00 , -6.2418600000000002e-01 , 5.1760700000000004e-01 , 5.8521400000000001e-01 -2.6679801273886983e-01 , 1.1011302100697264e+00 , 9.0959719999999997e+00 , 1.8591199999999999e-01 , 1.9164200000000001e-01 , -9.6369600000000000e-01 -3.5246719390464087e-01 , 1.2141909361441074e+00 , 9.0377216000000011e+00 , 1.9304099999999999e-01 , 1.9221800000000000e-01 , 9.6217900000000001e-01 -3.7126855418906168e-01 , 1.2900024119618028e+00 , 9.1703007999999997e+00 , 3.6745699999999998e-01 , -7.1711899999999995e-01 , 5.9221199999999996e-01 -4.3098211216320781e-01 , 1.3881430636040388e+00 , 9.1852976000000002e+00 , -9.4111000000000000e-01 , 1.2873999999999999e-01 , 3.1263099999999999e-01 -4.5096725448735442e-01 , 1.4665428341794506e+00 , 9.3257079999999988e+00 , -9.6686000000000005e-01 , -2.5475900000000001e-01 , -1.6756000000000000e-02 -3.9546328614175841e-01 , 1.5148360673356751e+00 , 9.7116728000000005e+00 , 4.9016799999999999e-01 , 8.5729400000000000e-01 , 1.5742300000000001e-01 -8.9797310473685332e-02 , 1.4736953777698618e+00 , 1.0960099200000000e+01 , 3.2866499999999998e-01 , -3.4563400000000000e-01 , -8.7892899999999996e-01 -1.4338223073563316e-01 , 1.5890348238900813e+00 , 1.1053876000000001e+01 , -1.0428200000000000e-01 , -9.6848599999999996e-01 , 2.2618500000000000e-01 -2.1509211095744107e-01 , 1.7113342396900524e+00 , 1.1085928800000001e+01 , -1.2133300000000000e-01 , 8.2716599999999996e-01 , -5.4870200000000002e-01 -4.6819764576610212e-01 , 1.8822540516786801e+00 , 1.0444082400000001e+01 , 6.2137699999999996e-01 , 5.9045700000000001e-01 , 5.1502599999999998e-01 -5.8728953155016250e-01 , 2.0062209616813207e+00 , 1.0267885600000000e+01 , -2.6943600000000001e-01 , -3.9128000000000002e-01 , -8.7994600000000001e-01 -6.7858157530157537e-01 , 2.1191831335807692e+00 , 1.0189261600000000e+01 , 1.1187400000000000e-01 , 6.1009599999999997e-01 , 7.8439000000000003e-01 -7.6813460320626992e-01 , 2.2305162231804965e+00 , 1.0107444800000001e+01 , 4.6989700000000001e-01 , 5.6391799999999997e-03 , 8.8270300000000002e-01 -6.3244591311947373e-01 , 2.3283509018767123e+00 , 1.0996249600000001e+01 , -4.2262100000000002e-01 , 6.6052900000000003e-01 , 6.2055899999999997e-01 -7.1738943419222179e-01 , 2.4484464088025337e+00 , 1.0962210400000000e+01 , -7.4062700000000004e-01 , 3.1904399999999999e-01 , 5.9133899999999995e-01 -6.3509105341001049e-01 , 2.5832729182990000e+00 , 1.1719257600000001e+01 , 8.6489499999999997e-01 , 3.5221000000000002e-01 , -3.5763899999999998e-01 -6.7287052366585076e-01 , 2.7208321669476749e+00 , 1.1946300000000001e+01 , 8.2218599999999997e-01 , 4.7834599999999999e-01 , -3.0853799999999998e-01 -1.0346726311801706e+00 , 2.7808386439664634e+00 , 1.0497798399999999e+01 , -3.0258900000000000e-01 , 3.1006100000000002e-02 , 9.5261700000000005e-01 -1.0817160491326838e+00 , 2.9003791803053285e+00 , 1.0637397600000000e+01 , 3.3699000000000001e-01 , 5.5292100000000000e-01 , -7.6204799999999995e-01 -1.4163038612401431e+00 , 2.8902650273482289e+00 , 9.1091072000000004e+00 , -8.4364700000000004e-01 , 5.2161999999999997e-01 , -1.2717200000000001e-01 -1.4344565328594727e+00 , 3.0040149109207439e+00 , 9.3560656000000009e+00 , -8.9875700000000003e-01 , 4.2639300000000002e-01 , -1.0210300000000000e-01 -1.4725547197151032e+00 , 3.1139586063015772e+00 , 9.4988472000000002e+00 , -9.0418500000000002e-01 , 3.7772299999999998e-01 , 1.9943800000000000e-01 -1.5163147234583525e+00 , 3.2255275273641764e+00 , 9.6297624000000006e+00 , -1.1418399999999999e-01 , 9.6689800000000004e-01 , -2.2818900000000000e-01 -1.6786527839188783e+00 , 3.2183129091682225e+00 , 8.8801720000000000e+00 , -8.6833700000000003e-01 , 4.7619000000000000e-01 , 1.3868600000000000e-01 -1.4237948493722778e+00 , 2.8601451201819605e-01 , 1.2125910400000000e+00 , 1.2552600000000000e-01 , -1.9696100000000000e-01 , -9.7234200000000004e-01 -1.3807687163059743e+00 , 2.2589046086161546e-01 , 1.2212188799999999e+00 , -7.9848699999999995e-02 , 1.9474800000000000e-01 , 9.7759799999999997e-01 -1.3329025570565847e+00 , 1.5872610762879957e-01 , 1.2254932800000000e+00 , -9.6660099999999999e-02 , 2.1010599999999999e-01 , 9.7288900000000000e-01 -1.2811503883073390e+00 , 8.3547573436869582e-02 , 1.2260465599999999e+00 , -1.0598900000000000e-01 , 1.8796800000000000e-01 , 9.7643999999999997e-01 -1.2290537921877442e+00 , 7.8747594009702659e-03 , 1.2293360799999999e+00 , -1.0451199999999999e-01 , 1.8822600000000000e-01 , 9.7654900000000000e-01 -1.1756280082019903e+00 , -6.7261018531433958e-02 , 1.2350279999999998e+00 , -9.5189899999999994e-02 , 1.9684699999999999e-01 , 9.7580199999999995e-01 -1.1208369558845246e+00 , -1.4288578053558698e-01 , 1.2432284000000000e+00 , -9.0021699999999996e-02 , 1.9327500000000000e-01 , 9.7700600000000004e-01 -1.0620100670196191e+00 , -2.2734034772005618e-01 , 1.2489255199999998e+00 , -8.4121399999999999e-02 , 1.8291800000000000e-01 , 9.7952300000000003e-01 -1.0028267046151265e+00 , -3.1118803813320062e-01 , 1.2575564799999999e+00 , -5.6941800000000001e-02 , 2.1099499999999999e-01 , 9.7582700000000000e-01 -9.4223096651337057e-01 , -3.9544936956193766e-01 , 1.2691004800000001e+00 , 7.9060699999999998e-02 , -2.1718699999999999e-01 , -9.7292299999999998e-01 -8.7167900106162999e-01 , -4.9660628482063984e-01 , 1.2737648799999999e+00 , -1.1095700000000000e-01 , 1.7246000000000000e-01 , 9.7874700000000003e-01 -7.8738040288369882e-01 , -6.2061617234754562e-01 , 1.2674198400000001e+00 , -1.4979100000000001e-01 , 1.6850699999999999e-01 , 9.7425300000000004e-01 -7.1104620319352807e-01 , -7.3041571740116185e-01 , 1.2753280000000000e+00 , -8.8705699999999998e-02 , 1.8844600000000000e-01 , 9.7806899999999997e-01 -6.4185090989538862e-01 , -8.2308430203319594e-01 , 1.2960375200000001e+00 , -1.1523799999999999e-01 , 1.6830899999999999e-01 , 9.7897500000000004e-01 -5.3540738668505039e-01 , -9.8201703889558756e-01 , 1.2855303999999999e+00 , -7.7274800000000005e-02 , 1.8799600000000000e-01 , 9.7912500000000002e-01 -4.6031319287151962e-01 , -1.0831715068398946e+00 , 1.3102917599999999e+00 , -2.2969600000000000e-02 , 3.0988300000000002e-01 , 9.5049700000000004e-01 -3.7881776177673832e-01 , -1.1925847295565104e+00 , 1.3348284800000001e+00 , -1.2428200000000000e-02 , 2.8282600000000002e-01 , 9.5909100000000003e-01 -2.8312254577817164e-01 , -1.3262798350577509e+00 , 1.3518023200000000e+00 , -6.1275900000000001e-02 , 2.2808600000000001e-01 , 9.7171099999999999e-01 -1.8570228979381209e-01 , -1.4609400918670330e+00 , 1.3741186399999998e+00 , -6.9971900000000004e-02 , 2.2561400000000001e-01 , 9.7170100000000004e-01 -8.2691665260510305e-02 , -1.6035143363113189e+00 , 1.3981572000000000e+00 , -6.7404599999999995e-02 , 2.3385200000000000e-01 , 9.6993300000000005e-01 --3.6940748873551588e-02 , -1.7707765360064567e+00 , 1.4173181600000000e+00 , -9.4128400000000001e-02 , 2.3465400000000000e-01 , 9.6751100000000001e-01 --1.7345431104823428e-01 , -1.9633841223782800e+00 , 1.4335255199999999e+00 , -8.8383699999999996e-02 , 2.3270299999999999e-01 , 9.6852400000000005e-01 --3.0690984458283355e-01 , -2.1476254031450921e+00 , 1.4603367199999999e+00 , -8.9808799999999994e-02 , 2.2808700000000001e-01 , 9.6948999999999996e-01 --4.6653870926070695e-01 , -2.3745566798049058e+00 , 1.4804784000000000e+00 , -8.0118800000000004e-02 , 2.3097899999999999e-01 , 9.6965500000000004e-01 --6.1918238660944214e-01 , -2.5840698107202149e+00 , 1.5147391200000000e+00 , -8.0112699999999995e-02 , 2.3311000000000001e-01 , 9.6914500000000003e-01 --8.0342378573404893e-01 , -2.8444822370178233e+00 , 1.5426371200000000e+00 , -5.7935599999999997e-03 , 3.0454300000000001e-01 , 9.5248100000000002e-01 --9.6945961115683943e-01 , -3.0688602857103211e+00 , 1.5899321600000000e+00 , 1.3799300000000000e-01 , 3.2229900000000000e-01 , 9.3652599999999997e-01 --1.0071091407430055e+00 , -3.0867641784094086e+00 , 1.6985518399999999e+00 , -1.5606699999999999e-03 , -9.9099199999999998e-01 , 1.3391600000000001e-01 --1.0809239115421163e+00 , -3.1630830049142418e+00 , 1.7941267999999999e+00 , 2.8070000000000001e-01 , 9.1719499999999998e-01 , -2.8277300000000000e-01 --9.7891272379049044e-01 , -2.9617643405855150e+00 , 1.9507918799999999e+00 , 2.0879000000000000e-01 , -9.3954199999999999e-01 , 2.7141900000000002e-01 --9.5705649257629233e-01 , -2.8888258643174192e+00 , 2.0750294480000000e+00 , 1.2211500000000000e-01 , -9.1612400000000005e-01 , 3.8184400000000002e-01 --9.5566065754527285e-01 , -2.8476036550053729e+00 , 2.1903626400000000e+00 , -1.6456100000000001e-01 , -8.8901300000000005e-01 , 4.2728899999999997e-01 --9.6875275399966965e-01 , -2.8312310918331391e+00 , 2.3004612000000000e+00 , -4.9006499999999997e-01 , -8.2964800000000005e-01 , 2.6743200000000000e-01 --9.8173990717189730e-01 , -2.8128635121427958e+00 , 2.4099472000000000e+00 , 5.1950799999999997e-01 , 8.2519799999999999e-01 , -2.2171900000000000e-01 --9.6502968730102889e-01 , -2.7492982303469349e+00 , 2.5234351199999998e+00 , 5.0961800000000002e-01 , 8.2672999999999996e-01 , -2.3834300000000000e-01 --9.9794225565230787e-01 , -2.7628780403618940e+00 , 2.6281922399999997e+00 , 5.0782899999999997e-01 , 8.2784800000000003e-01 , -2.3827899999999999e-01 --9.8943017009982359e-01 , -2.7146210225125991e+00 , 2.7377801599999998e+00 , 6.1449500000000001e-01 , 7.8862600000000005e-01 , 2.1578400000000001e-02 --9.9135462251737172e-01 , -2.6813089281465485e+00 , 2.8447358400000002e+00 , 5.9213499999999997e-01 , 8.0361700000000003e-01 , 5.9801600000000003e-02 --1.0799787178504943e+00 , -2.7757617865595456e+00 , 2.9473328799999998e+00 , 5.9213499999999997e-01 , 8.0361700000000003e-01 , 5.9801500000000000e-02 --1.0744437050350024e+00 , -2.7309309166111237e+00 , 3.0550383999999999e+00 , 5.9213499999999997e-01 , 8.0361700000000003e-01 , 5.9801500000000000e-02 --1.0784884860451376e+00 , -2.7018687827648273e+00 , 3.1615448000000002e+00 , 5.9213499999999997e-01 , 8.0361700000000003e-01 , 5.9801500000000000e-02 --6.8060787758732015e+00 , -1.0897574576182434e+01 , 3.5706600000000002e+00 , -8.8250099999999998e-01 , -4.2226799999999998e-01 , -2.0707999999999999e-01 --6.8726839603484002e+00 , -1.0900889052464571e+01 , 3.8509504000000003e+00 , -9.1787700000000005e-01 , -3.9291300000000001e-01 , -5.5865300000000000e-02 --6.9133420858893544e+00 , -1.0866260305627646e+01 , 4.1300863999999997e+00 , -8.1739099999999998e-01 , -5.7607299999999995e-01 , 3.4969500000000000e-03 --6.9507881598475709e+00 , -1.0827584756024363e+01 , 4.4092951999999999e+00 , -9.1358899999999998e-01 , -3.9187699999999998e-01 , 1.0857000000000000e-01 --6.9673462859308977e+00 , -1.0758464545516807e+01 , 4.6851343999999999e+00 , -9.1331200000000001e-01 , -3.8551999999999997e-01 , 1.3128699999999999e-01 --6.8725115990629764e+00 , -1.0536348264135492e+01 , 4.9384160000000001e+00 , -8.9480999999999999e-01 , -4.4259100000000001e-01 , -5.8547700000000001e-02 --7.0645974441361847e+00 , -1.0710582923450195e+01 , 5.2500207999999997e+00 , -7.3771500000000001e-01 , -6.3644599999999996e-01 , -2.2519600000000001e-01 --7.1512077070589921e+00 , -1.0738751216910083e+01 , 5.5447360000000003e+00 , -8.7085400000000002e-01 , -4.9053700000000000e-01 , -3.1406700000000003e-02 --7.1692327521725421e+00 , -1.0670246711330856e+01 , 5.8231856000000004e+00 , -8.5817200000000005e-01 , -5.0956199999999996e-01 , 6.2352299999999999e-02 --7.2017643463442180e+00 , -1.0623359111044111e+01 , 6.1067416000000003e+00 , -8.6534699999999998e-01 , -4.8748799999999998e-01 , 1.1631800000000000e-01 --7.2188692868850737e+00 , -1.0555729243433019e+01 , 6.3863351999999995e+00 , -8.6129800000000001e-01 , -4.9791099999999999e-01 , 1.0124500000000000e-01 --7.2516901436023868e+00 , -1.0507414666208938e+01 , 6.6718152000000002e+00 , -8.7014300000000000e-01 , -4.8328399999999999e-01 , 9.6370899999999995e-02 --7.2823939698416051e+00 , -1.0455933172472724e+01 , 6.9577320000000000e+00 , -8.6433400000000005e-01 , -4.9249399999999999e-01 , 1.0186800000000000e-01 --7.3030883733407777e+00 , -1.0391535244686395e+01 , 7.2413088000000005e+00 , -8.5780199999999995e-01 , -5.0131800000000004e-01 , 1.1338500000000000e-01 --7.3205748575792846e+00 , -1.0323070128748887e+01 , 7.5246464000000008e+00 , -8.5342099999999999e-01 , -5.0826700000000002e-01 , 1.1548700000000001e-01 --7.3426432139235445e+00 , -1.0258176073741492e+01 , 7.8104176000000001e+00 , -8.5373900000000003e-01 , -5.1093699999999997e-01 , 1.0036399999999999e-01 --7.3787339857943977e+00 , -1.0212052400588478e+01 , 8.1054656000000005e+00 , -8.5020700000000005e-01 , -5.1870700000000003e-01 , 8.9954900000000004e-02 --7.4059916213435528e+00 , -1.0154014768174076e+01 , 8.3982568000000004e+00 , -8.4694100000000005e-01 , -5.2509300000000003e-01 , 8.3476900000000007e-02 --7.4241675072747135e+00 , -1.0083195692741127e+01 , 8.6878552000000013e+00 , -8.5477099999999995e-01 , -5.0641199999999997e-01 , 1.1363800000000000e-01 --7.4577129014840402e+00 , -1.0030783376942825e+01 , 8.9883319999999998e+00 , -8.5061699999999996e-01 , -5.0836899999999996e-01 , 1.3420699999999999e-01 --7.4567246033259629e+00 , -9.9356735684449067e+00 , 9.2707856000000000e+00 , -6.8648699999999996e-01 , -6.5137599999999996e-01 , 3.2317800000000002e-01 --7.4956383477175645e+00 , -9.8887108074614929e+00 , 9.5799880000000002e+00 , -8.1724100000000000e-01 , -5.3440500000000002e-01 , 2.1570400000000001e-01 --7.3627011007642906e+00 , -9.6299861864786305e+00 , 9.7752584000000002e+00 , -8.6044100000000001e-01 , -5.0361999999999996e-01 , 7.7509599999999998e-02 --7.6241162913481055e+00 , -9.8532501829460166e+00 , 1.0245099200000000e+01 , -8.3824299999999996e-01 , -5.2100100000000005e-01 , -1.6095499999999999e-01 --7.6587402105587756e+00 , -9.7970877850177516e+00 , 1.0563911200000000e+01 , -8.9447399999999999e-01 , -4.4555600000000001e-01 , 3.7358400000000000e-02 --7.6299033666463281e+00 , -9.6634689070321578e+00 , 1.0837961600000000e+01 , -7.2359499999999999e-01 , -6.8815800000000005e-01 , 5.3386400000000001e-02 --7.7771178977952111e+00 , -9.7381656817634319e+00 , 1.1252734400000001e+01 , -8.4883200000000003e-01 , -5.2712099999999995e-01 , -4.0333200000000000e-02 --7.8074630187249507e+00 , -9.6717022836589148e+00 , 1.1581353600000000e+01 , -7.3105900000000001e-01 , -6.2720799999999999e-01 , 2.6863100000000001e-01 --7.8445635136197431e+00 , -9.6122217638400578e+00 , 1.1921319200000001e+01 , -6.0010100000000000e-01 , -7.9693599999999998e-01 , 6.9079399999999999e-02 --7.8726731589206462e+00 , -9.5410818258444596e+00 , 1.2257894400000000e+01 , -7.9620199999999997e-01 , -5.7869999999999999e-01 , 1.7655000000000001e-01 --7.9026457300767081e+00 , -9.4696509956039066e+00 , 1.2600823999999999e+01 , -7.8695000000000004e-01 , -5.9089400000000003e-01 , 1.7763100000000001e-01 --7.9233871029867640e+00 , -9.3856524926598279e+00 , 1.2939448000000001e+01 , -7.9074800000000001e-01 , -5.8535499999999996e-01 , 1.7910000000000001e-01 --7.9571357876895643e+00 , -9.3154858601578265e+00 , 1.3296272000000000e+01 , -8.0113900000000005e-01 , -5.7563600000000004e-01 , 1.6376399999999999e-01 --7.9806829077372434e+00 , -9.2317802106919746e+00 , 1.3648831999999999e+01 , -6.9198599999999999e-01 , -7.1799000000000002e-01 , -7.5135099999999996e-02 --8.0162132640431842e+00 , -9.1596295941026984e+00 , 1.4020424000000000e+01 , -8.0385499999999999e-01 , -5.7214699999999996e-01 , 1.6268099999999999e-01 --8.0487278651268799e+00 , -9.0808933656603319e+00 , 1.4393888000000000e+01 , 6.9139300000000004e-01 , 6.3969299999999996e-01 , -3.3581100000000003e-01 --8.0698756199137680e+00 , -8.9896552888496419e+00 , 1.4762984000000001e+01 , -7.3563100000000003e-01 , -6.7227599999999998e-01 , 8.3018800000000004e-02 --8.0594634403632401e+00 , -8.8604185781943183e+00 , 1.5101088000000001e+01 , -6.4000999999999997e-01 , -7.0488700000000004e-01 , 3.0581399999999997e-01 --8.1436622950325575e+00 , -8.8308594946135415e+00 , 1.5556608000000001e+01 , -8.0858699999999994e-01 , -4.5616400000000001e-01 , 3.7162000000000001e-01 --8.0520293289421794e+00 , -8.6128409794606302e+00 , 1.5809744000000002e+01 , -6.5792499999999998e-01 , -2.8873300000000002e-01 , 6.9553399999999999e-01 --7.8756260333231758e+00 , -8.3062761689837039e+00 , 1.5956488000000002e+01 , -6.5792499999999998e-01 , -2.8873300000000002e-01 , 6.9553399999999999e-01 --2.0500935594181389e+00 , -2.2100925288112183e+00 , 8.8524248000000014e+00 , 7.1880299999999997e-01 , -2.9715599999999998e-01 , -6.2850700000000004e-01 --2.0348310223417032e+00 , -2.1404325694056139e+00 , 8.9959136000000015e+00 , -9.5815600000000001e-01 , -2.8558000000000000e-01 , 1.9508800000000000e-02 --2.1620178741645288e+00 , -2.2114833819850537e+00 , 9.3328632000000002e+00 , 9.0719600000000000e-01 , 4.1440700000000003e-01 , 7.2544200000000003e-02 --1.9158241140877204e+00 , -1.9099888139208785e+00 , 9.1637488000000005e+00 , 6.0427500000000001e-01 , -7.0962300000000000e-01 , -3.6233599999999999e-01 --1.6985236922185387e+00 , -1.6413257094466767e+00 , 9.0204471999999996e+00 , -7.7919200000000000e-01 , 6.1610699999999996e-01 , -1.1520100000000000e-01 --1.8485836693992463e+00 , -1.7316145910862542e+00 , 9.4046440000000011e+00 , 2.2576399999999999e-01 , 1.5870500000000001e-01 , 9.6116800000000002e-01 --1.6164819886882196e+00 , -1.4534674817503550e+00 , 9.2272512000000013e+00 , 4.2452200000000002e-02 , -4.4323299999999999e-01 , 8.9540100000000000e-01 --1.5536965456000766e+00 , -1.3391242886492978e+00 , 9.2969831999999997e+00 , -9.6107999999999992e-03 , -4.0504499999999999e-01 , 9.1424600000000000e-01 --1.4507741362667508e+00 , -1.1877391383538245e+00 , 9.3008312000000011e+00 , -6.9995500000000002e-02 , -2.3032000000000000e-01 , 9.7059399999999996e-01 --1.6707860142176125e+00 , -1.3307914735005628e+00 , 9.8298584000000009e+00 , -9.3883899999999998e-01 , 3.4396700000000002e-01 , 1.6361899999999999e-02 --2.3812414822094299e+00 , -1.9030465886795609e+00 , 1.1206974400000000e+01 , -2.1196000000000001e-01 , 9.7368800000000000e-01 , 8.3698300000000003e-02 --1.9101828964884469e+00 , -1.4164811810101834e+00 , 1.0613072000000001e+01 , -9.4501900000000005e-01 , 1.0983900000000001e-01 , -3.0801600000000001e-01 --1.6272329341090725e+00 , -1.1041400741961267e+00 , 1.0315840000000001e+01 , -9.5799699999999999e-01 , 1.0410000000000000e-01 , -2.6721600000000001e-01 --2.3765283826564998e-01 , 1.3446776650914938e-01 , 7.9797712000000010e+00 , 6.6174599999999995e-01 , 1.6300799999999999e-01 , -7.3179200000000000e-01 --1.9282010727151633e-01 , 2.1671165736997677e-01 , 8.0285784000000007e+00 , -6.6623100000000002e-01 , -1.5467700000000001e-01 , 7.2952799999999995e-01 --1.6907885768630759e-01 , 2.8165975335294458e-01 , 8.1188712000000010e+00 , -7.5645600000000002e-01 , -1.5137000000000000e-01 , 6.3628700000000005e-01 --1.1324329483013251e-01 , 3.7207648208415978e-01 , 8.1473984000000002e+00 , 7.0950500000000005e-01 , 3.3236399999999999e-01 , -6.2139900000000003e-01 --1.0528867501265537e-01 , 4.2528219297650094e-01 , 8.2708672000000014e+00 , 7.1056399999999997e-01 , 2.5938899999999998e-01 , -6.5407700000000002e-01 --6.0862823038152936e-02 , 5.0712525965718935e-01 , 8.3229088000000004e+00 , 7.6039199999999996e-01 , 2.8680600000000001e-01 , -5.8270599999999995e-01 --1.1189138369696572e-01 , 5.1873544029159291e-01 , 8.5804648000000014e+00 , 8.7033600000000000e-01 , -2.8661599999999998e-01 , -4.0045900000000001e-01 --5.9511942367554616e-01 , 2.2516849511762960e-01 , 9.8030159999999995e+00 , -8.7984399999999996e-01 , -1.7723100000000000e-01 , 4.4097999999999998e-01 --4.9220971503010480e-01 , 3.6106885735861205e-01 , 9.7616344000000019e+00 , -8.9526600000000001e-01 , 8.9990999999999995e-03 , 4.4544099999999998e-01 --4.8947785302150137e-01 , 4.2810383098436922e-01 , 9.9473680000000009e+00 , -7.8674299999999997e-01 , -4.2255900000000002e-01 , 4.4997700000000002e-01 --1.7182637164238370e+00 , -3.0350000224901175e-01 , 1.3105536000000001e+01 , 4.9630400000000002e-01 , 2.1342900000000001e-01 , 8.4150499999999995e-01 --1.2694221498219567e+00 , 7.7932710713431996e-02 , 1.2290789600000000e+01 , 5.8079000000000003e-01 , -4.2352200000000001e-01 , 6.9520599999999999e-01 -2.5212001205736478e-01 , 1.0844946172014169e+00 , 8.6887912000000007e+00 , -3.0102699999999999e-01 , 3.5815999999999998e-01 , 8.8380099999999995e-01 -3.1332277491968163e-01 , 1.1774350704319532e+00 , 8.6993679999999998e+00 , 3.0102699999999999e-01 , -3.5815999999999998e-01 , -8.8380099999999995e-01 -2.3013008220823217e-01 , 1.1907757186160555e+00 , 9.1009327999999989e+00 , -1.2106900000000000e-02 , -2.6085100000000000e-02 , 9.9958599999999997e-01 -3.5405775912204862e-01 , 1.3187885612902779e+00 , 8.9458583999999988e+00 , 1.9669100000000000e-01 , 4.6625800000000001e-01 , 8.6250599999999999e-01 -5.7881922267013519e-01 , 1.4924862399996042e+00 , 8.4856791999999999e+00 , -6.2340099999999998e-01 , 7.3863699999999999e-01 , -2.5649000000000000e-01 -4.2918834889530499e-01 , 1.4837330942918689e+00 , 9.1112496000000007e+00 , 5.5506200000000006e-01 , 1.4391299999999999e-02 , -8.3168500000000001e-01 -4.5919131679551461e-01 , 1.5651663676623322e+00 , 9.2214376000000016e+00 , 7.9054999999999997e-01 , 3.9625000000000000e-02 , -6.1111400000000005e-01 -2.2048359989241484e-01 , 1.5439202861781327e+00 , 1.0198164000000000e+01 , 2.5385300000000000e-01 , 9.5179999999999998e-01 , 1.7215200000000000e-01 -3.8249629658032802e-02 , 1.5647137501592188e+00 , 1.1053033600000001e+01 , -5.0019499999999995e-01 , -7.5356299999999998e-01 , 4.2655399999999999e-01 -6.1390084175251491e-02 , 1.6693218134594212e+00 , 1.1266233600000001e+01 , 3.9094200000000001e-01 , 8.9634599999999998e-01 , 2.0911399999999999e-01 -3.4892516352155512e-01 , 1.8491647647230716e+00 , 1.0549528000000000e+01 , -2.7485500000000002e-01 , -9.2804500000000001e-01 , -2.5136900000000001e-01 -4.9075061832474476e-01 , 1.9765684850606111e+00 , 1.0316193600000000e+01 , 7.0820200000000000e-01 , 6.5293299999999999e-01 , 2.6856600000000003e-01 -5.1500021724375999e-01 , 2.0774324608601229e+00 , 1.0511058400000000e+01 , 7.6061599999999996e-01 , 2.2759599999999999e-01 , -6.0799999999999998e-01 -6.6800147042747438e-01 , 2.1982834512506964e+00 , 1.0210685600000000e+01 , 3.0623400000000001e-01 , 9.6615300000000001e-02 , 9.4704100000000002e-01 -5.5650937918757770e-01 , 2.2950073504099060e+00 , 1.0977935200000001e+01 , -4.2262100000000002e-01 , 6.6052900000000003e-01 , 6.2055899999999997e-01 -6.4988614616453910e-01 , 2.4121857364539228e+00 , 1.0925935200000000e+01 , 5.9955800000000004e-01 , -4.1355900000000001e-01 , -6.8520099999999995e-01 -7.1288864108968264e-01 , 2.5301171771523525e+00 , 1.1002968000000001e+01 , -8.4189300000000000e-01 , -1.1611200000000001e-01 , 5.2700400000000003e-01 -6.4631310321976021e-01 , 2.6688344087342295e+00 , 1.1708888800000000e+01 , 6.6207400000000005e-01 , 5.8479300000000001e-01 , -4.6869499999999997e-01 -1.3509342738265158e+00 , 2.6552235542544187e+00 , 8.6031471999999987e+00 , 1.5667300000000001e-01 , -7.7934000000000003e-01 , 6.0669899999999999e-01 -1.0554631045774450e+00 , 2.8479263611923429e+00 , 1.0466296800000000e+01 , 1.6509799999999999e-01 , 1.8547800000000000e-02 , -9.8610299999999995e-01 -1.3499739812906468e+00 , 2.8647264022923524e+00 , 9.2369751999999998e+00 , 9.4242400000000004e-01 , -3.1994800000000001e-01 , -9.7313600000000000e-02 -1.4472019737767545e+00 , 2.9358472646681464e+00 , 9.0257199999999997e+00 , 6.4296500000000001e-01 , -7.0216299999999998e-01 , -3.0588100000000001e-01 -1.4814869661556986e+00 , 3.0408306798957860e+00 , 9.1904560000000011e+00 , -9.2805400000000005e-01 , 3.2329500000000000e-01 , 1.8492200000000000e-01 -1.4708669832828143e+00 , 3.1867723315585148e+00 , 9.6701456000000015e+00 , -7.4805800000000000e-01 , 6.3618799999999998e-01 , 1.8887899999999999e-01 -1.6237158170866453e+00 , 3.1996530641638636e+00 , 9.0446376000000015e+00 , -2.7187600000000001e-01 , 9.5406999999999997e-01 , 1.2583400000000000e-01 -1.7216234969127104e+00 , 3.2443096765004915e+00 , 8.7549039999999998e+00 , 7.6029999999999998e-01 , 6.4710400000000001e-01 , -5.6577299999999997e-02 -1.4796935620105769e+00 , 4.6495476342279463e-01 , 1.1851069599999999e+00 , -7.6259199999999999e-02 , 1.6643200000000000e-01 , 9.8309999999999997e-01 -1.4398362734097803e+00 , 4.1450347575360613e-01 , 1.1949973599999999e+00 , -8.0159700000000000e-02 , 2.0036000000000001e-01 , 9.7643800000000003e-01 -1.3916094502881879e+00 , 3.4838022235312494e-01 , 1.1937774399999999e+00 , -8.8080199999999997e-02 , 2.0185200000000000e-01 , 9.7544699999999995e-01 -1.3477340035140519e+00 , 2.9014264243822474e-01 , 1.2010605599999999e+00 , -8.1601900000000005e-02 , 1.8617700000000001e-01 , 9.7912200000000005e-01 -1.2943903300796271e+00 , 2.1637117268499440e-01 , 1.1977148799999999e+00 , -1.0272199999999999e-01 , 1.8929499999999999e-01 , 9.7653299999999998e-01 -1.2489570255669369e+00 , 1.5797697223240537e-01 , 1.2091247199999999e+00 , -9.1265600000000002e-02 , 1.7456500000000000e-01 , 9.8040700000000003e-01 -1.1939878635307957e+00 , 8.4173122298648595e-02 , 1.2105131199999999e+00 , -8.2816000000000001e-02 , 1.5168799999999999e-01 , 9.8495299999999997e-01 -1.1397136000447972e+00 , 9.8203862154859767e-03 , 1.2146606400000000e+00 , -7.8379699999999997e-02 , 1.7380899999999999e-01 , 9.8165500000000006e-01 -1.0877377361542040e+00 , -5.6606539840944770e-02 , 1.2269586399999999e+00 , -7.5516000000000000e-02 , 1.6803699999999999e-01 , 9.8288399999999998e-01 -1.0223984350577389e+00 , -1.4657279031513903e-01 , 1.2250086400000000e+00 , -9.4686999999999993e-02 , 1.7342900000000000e-01 , 9.8028400000000004e-01 -9.6036303023431091e-01 , -2.2860041392714825e-01 , 1.2315367200000000e+00 , -5.9815699999999999e-02 , 2.0348200000000000e-01 , 9.7724999999999995e-01 -8.9793300524470210e-01 , -3.1103698825066539e-01 , 1.2412056000000000e+00 , -9.0257199999999996e-02 , 2.0093000000000000e-01 , 9.7543899999999994e-01 -8.2930670172436738e-01 , -4.0211523111039016e-01 , 1.2488277600000002e+00 , -8.9028599999999999e-02 , 1.9723599999999999e-01 , 9.7630499999999998e-01 -7.6030133500579455e-01 , -4.9252750720537186e-01 , 1.2596874400000000e+00 , -1.3295199999999999e-01 , 1.6573599999999999e-01 , 9.7716700000000001e-01 -6.7168501286299365e-01 , -6.1502504781335032e-01 , 1.2546580000000001e+00 , -1.0576099999999999e-01 , 1.9131300000000001e-01 , 9.7581499999999999e-01 -5.9209312368770894e-01 , -7.2231211354594116e-01 , 1.2638016799999998e+00 , 8.3723199999999998e-02 , -1.9857800000000000e-01 , -9.7650300000000001e-01 -5.0029351044975390e-01 , -8.4501986672136953e-01 , 1.2676330400000000e+00 , -1.0598900000000000e-01 , 1.5054300000000001e-01 , 9.8290500000000003e-01 -3.9813478505147182e-01 , -9.8499138366863415e-01 , 1.2678254400000000e+00 , -1.2690800000000000e-02 , 2.0888000000000001e-01 , 9.7785900000000003e-01 -3.2953500455987461e-01 , -1.0674583040904895e+00 , 1.3024252000000001e+00 , -2.1014999999999999e-02 , 3.2786900000000002e-01 , 9.4449000000000005e-01 -2.3989963409333592e-01 , -1.1824160035095646e+00 , 1.3240499200000000e+00 , -4.2784200000000001e-02 , 2.5739099999999998e-01 , 9.6536000000000000e-01 -1.3387401664450116e-01 , -1.3224710176985370e+00 , 1.3388730400000000e+00 , -6.6345899999999999e-02 , 2.1740799999999999e-01 , 9.7382299999999999e-01 -1.7283632190018494e-02 , -1.4783564821260966e+00 , 1.3518761600000000e+00 , -6.6747899999999999e-02 , 2.2639100000000001e-01 , 9.7174700000000003e-01 --9.6107401527729674e-02 , -1.6261016701171123e+00 , 1.3743692800000000e+00 , 8.2666500000000004e-02 , -2.2416400000000000e-01 , -9.7103899999999999e-01 --2.2731331677848710e-01 , -1.7993496873622488e+00 , 1.3929748799999999e+00 , -8.6739200000000002e-02 , 2.2069400000000000e-01 , 9.7147799999999995e-01 --3.7035795300413055e-01 , -1.9879542029451831e+00 , 1.4118602400000000e+00 , 8.1989800000000002e-02 , -2.2877300000000000e-01 , -9.7002100000000002e-01 --5.2043191734391936e-01 , -2.1848599014235655e+00 , 1.4354817600000001e+00 , 8.3796899999999994e-02 , -2.2628999999999999e-01 , -9.7044900000000001e-01 --6.8264210772504708e-01 , -2.3987953571484137e+00 , 1.4616138400000001e+00 , -7.0430599999999996e-02 , 2.2752800000000001e-01 , 9.7122100000000000e-01 --8.6317614028821188e-01 , -2.6362463433331031e+00 , 1.4883085600000001e+00 , -7.7638100000000002e-02 , 2.2017600000000001e-01 , 9.7236599999999995e-01 --1.0571952760488976e+00 , -2.8912445827521971e+00 , 1.5199203999999999e+00 , -5.4644800000000000e-02 , 3.1823400000000002e-01 , 9.4643600000000006e-01 --1.2422694708128117e+00 , -3.1287033143149010e+00 , 1.5667110399999999e+00 , -1.7874799999999999e-01 , -7.3951100000000003e-01 , -6.4897899999999997e-01 --1.2802947654827226e+00 , -3.1448581962416275e+00 , 1.6786670399999999e+00 , 2.7991100000000002e-01 , 8.1639799999999996e-01 , 5.0511899999999998e-01 --1.3183885252233822e+00 , -3.1597854084187524e+00 , 1.7914290399999999e+00 , 1.3379600000000000e-01 , 6.5891200000000005e-01 , 7.4022600000000005e-01 --1.5162055852902339e+00 , -3.4092396684363102e+00 , 1.8550167200000001e+00 , -1.0162100000000000e-01 , 5.1916899999999999e-01 , 8.4860800000000003e-01 --2.4720251574918812e+00 , -4.7597348946744260e+00 , 1.7203533600000001e+00 , -8.2431299999999999e-02 , 2.5961299999999998e-01 , 9.6218800000000004e-01 --2.8548098447138734e+00 , -5.2601559770148505e+00 , 1.7847876000000000e+00 , -8.2186899999999993e-02 , 2.5857500000000000e-01 , 9.6248900000000004e-01 --3.2632799232286454e+00 , -5.7932675930636250e+00 , 1.8658836800000000e+00 , -6.7883100000000002e-02 , 2.5282100000000002e-01 , 9.6512900000000001e-01 --1.1625207324408562e+00 , -2.7425454378594791e+00 , 2.4252123200000000e+00 , -5.1251000000000002e-01 , -8.3088600000000001e-01 , 2.1670700000000001e-01 --1.1554583350046417e+00 , -2.6968213179010476e+00 , 2.5377184800000001e+00 , 5.1303200000000004e-01 , 8.2694900000000005e-01 , -2.3011400000000001e-01 --1.1534531261103718e+00 , -2.6577676715728193e+00 , 2.6476922400000000e+00 , 4.2233999999999999e-01 , 8.9333600000000002e-01 , -1.5355700000000000e-01 --1.1736436841902749e+00 , -2.6513444800466353e+00 , 2.7543068000000002e+00 , -5.6353200000000003e-01 , -8.2595200000000002e-01 , -1.5342800000000000e-02 --1.1746180119399035e+00 , -2.6179034550193379e+00 , 2.8620965599999999e+00 , 5.9213499999999997e-01 , 8.0361700000000003e-01 , 5.9801500000000000e-02 --1.2354068369391760e+00 , -2.6664006451664779e+00 , 2.9668214399999999e+00 , 5.9213499999999997e-01 , 8.0361700000000003e-01 , 5.9801600000000003e-02 --7.0691794055259418e+00 , -1.0603698649294348e+01 , 3.0652407999999998e+00 , 3.0204399999999998e-01 , 7.9790200000000000e-01 , 5.2165300000000003e-01 --7.1234763477964744e+00 , -1.0587115222022810e+01 , 3.3416936000000002e+00 , 3.4040599999999997e-02 , 9.1520599999999996e-01 , 4.0154699999999999e-01 --7.3164244559949250e+00 , -1.0759190135449025e+01 , 3.6270696000000000e+00 , 2.0510800000000001e-01 , 9.7726999999999997e-01 , 5.3613899999999999e-02 --7.3335266342799432e+00 , -1.0692620860299694e+01 , 3.9064655999999998e+00 , -3.7210900000000002e-01 , -9.2376899999999995e-01 , 9.0474499999999999e-02 --7.3482321763749869e+00 , -1.0622170075267224e+01 , 4.1843743999999994e+00 , 6.2202199999999996e-01 , 7.7068099999999995e-01 , -1.3834600000000000e-01 --7.3781205761597679e+00 , -1.0572093791955613e+01 , 4.4635207999999995e+00 , -3.8063900000000001e-01 , -9.0175899999999998e-01 , 2.0480200000000001e-01 --7.3674382375593161e+00 , -1.0469840480469550e+01 , 4.7360319999999998e+00 , -3.7206000000000000e-01 , -9.2742599999999997e-01 , 3.8106099999999997e-02 --7.4479281340512298e+00 , -1.0486846339304696e+01 , 5.0244552000000002e+00 , 3.4681499999999998e-01 , 9.3385399999999996e-01 , 8.7388199999999999e-02 --7.6203416521593716e+00 , -1.0620451628193324e+01 , 5.3364967999999999e+00 , 2.0327400000000001e-01 , 9.7525899999999999e-01 , 8.6886900000000003e-02 --7.6388274179998827e+00 , -1.0554385662130231e+01 , 5.6182847999999996e+00 , 2.6266400000000001e-01 , 9.5778600000000003e-01 , -1.1685100000000000e-01 --7.6794359777992174e+00 , -1.0516860533295491e+01 , 5.9064584000000000e+00 , -2.2029799999999999e-01 , -9.5189800000000002e-01 , 2.1297500000000000e-01 --7.6856479079546069e+00 , -1.0434914794292755e+01 , 6.1853448000000002e+00 , -2.1874900000000000e-01 , -9.5259899999999997e-01 , 2.1143400000000001e-01 --7.7265519287827011e+00 , -1.0395932110443450e+01 , 6.4755360000000000e+00 , -2.2226899999999999e-01 , -9.5357300000000000e-01 , 2.0320900000000000e-01 --7.7385364584661129e+00 , -1.0321629564928323e+01 , 6.7574487999999997e+00 , 2.1423300000000001e-01 , 9.5840300000000000e-01 , -1.8859600000000001e-01 --7.7855381400770032e+00 , -1.0290780428704622e+01 , 7.0534119999999998e+00 , 2.2163200000000000e-01 , 9.5370299999999997e-01 , -2.0329500000000000e-01 --7.8112593032153583e+00 , -1.0231423243134463e+01 , 7.3425735999999997e+00 , -2.1685800000000000e-01 , -9.5372100000000004e-01 , 2.0830199999999999e-01 --7.8327160869533685e+00 , -1.0167975721772473e+01 , 7.6318184000000002e+00 , -2.0458000000000001e-01 , -9.5530499999999996e-01 , 2.1340100000000001e-01 --7.8587774705685707e+00 , -1.0107987141724088e+01 , 7.9240168000000004e+00 , 2.0295800000000000e-01 , 9.5830899999999997e-01 , -2.0112900000000000e-01 --7.8863622335335322e+00 , -1.0050429670755266e+01 , 8.2196368000000000e+00 , 1.9965300000000000e-01 , 9.5869499999999996e-01 , -2.0258899999999999e-01 --7.9185880911796129e+00 , -9.9971980724060288e+00 , 8.5190216000000003e+00 , 2.0380499999999999e-01 , 9.5433699999999999e-01 , -2.1841600000000000e-01 --7.9399250597006343e+00 , -9.9312007205881496e+00 , 8.8157752000000009e+00 , -1.9505700000000001e-01 , -9.5762800000000003e-01 , 2.1190100000000001e-01 --7.9462520319645016e+00 , -9.8450230806563663e+00 , 9.1050927999999995e+00 , -2.0134199999999999e-01 , -9.4039399999999995e-01 , 2.7407999999999999e-01 --8.0178441556644007e+00 , -9.8357763203859498e+00 , 9.4361871999999991e+00 , -2.2623499999999999e-01 , -9.0729700000000002e-01 , 3.5444199999999998e-01 --7.9040655240420019e+00 , -9.6097456306228679e+00 , 9.6547744000000009e+00 , -2.3079000000000000e-01 , -9.6485799999999999e-01 , 1.2563500000000000e-01 --7.9260002981367847e+00 , -9.5413226942370990e+00 , 9.9580072000000008e+00 , 2.2361000000000000e-01 , 9.7415900000000000e-01 , -3.1822799999999998e-02 --8.1863688070930767e+00 , -9.7451464363694562e+00 , 1.0429834400000001e+01 , -1.3409299999999999e-01 , -9.8934699999999998e-01 , -5.6673800000000003e-02 --8.1876490873871770e+00 , -9.6482680714527831e+00 , 1.0731122400000000e+01 , -1.7845200000000000e-01 , -9.8346999999999996e-01 , -3.0696100000000000e-02 --8.3650586381990539e+00 , -9.7493749135560126e+00 , 1.1166383200000000e+01 , -3.4316600000000003e-02 , -9.9899899999999997e-01 , 2.8708100000000000e-02 --8.4318782064377622e+00 , -9.7244106900561231e+00 , 1.1529114400000001e+01 , 2.4136100000000001e-03 , -9.9416700000000002e-01 , 1.0782600000000001e-01 --8.4707149063311373e+00 , -9.6647409286908204e+00 , 1.1874924800000001e+01 , 1.6079000000000000e-02 , 9.8202999999999996e-01 , -1.8804000000000001e-01 --8.4925677964491424e+00 , -9.5862522803851569e+00 , 1.2212436000000000e+01 , 2.2184499999999999e-02 , 9.7803499999999999e-01 , -2.0725499999999999e-01 --8.5411322803946597e+00 , -9.5340830424679144e+00 , 1.2576904000000001e+01 , 1.8366299999999999e-02 , 9.7568200000000005e-01 , -2.1842200000000001e-01 --8.5676875871152163e+00 , -9.4559533758554331e+00 , 1.2927384000000000e+01 , 1.7607000000000001e-02 , 9.7611700000000001e-01 , -2.1652900000000000e-01 --8.5890728951133664e+00 , -9.3713956559567517e+00 , 1.3279320000000000e+01 , 1.9290399999999999e-02 , 9.7365100000000004e-01 , -2.2722500000000001e-01 --8.6304316372954180e+00 , -9.3066130301600261e+00 , 1.3655280000000001e+01 , 2.0446099999999998e-02 , 9.7603499999999999e-01 , -2.1665000000000001e-01 --8.6485367325198457e+00 , -9.2152038597288577e+00 , 1.4015536000000001e+01 , -1.1843899999999999e-02 , -9.7519000000000000e-01 , 2.2105100000000000e-01 --8.6988863796041525e+00 , -9.1542281355697650e+00 , 1.4412815999999999e+01 , -3.7394200000000002e-02 , -9.5874999999999999e-01 , 2.8177900000000000e-01 --8.7025758147328780e+00 , -9.0438945879957338e+00 , 1.4769952000000000e+01 , 4.1491000000000000e-02 , 9.5427399999999996e-01 , -2.9604000000000003e-01 --8.6084008297765422e+00 , -8.8316109677368129e+00 , 1.5026832000000001e+01 , -8.1976599999999997e-02 , -9.4437000000000004e-01 , 3.1850499999999998e-01 --8.7185158505195552e+00 , -8.8260134678908493e+00 , 1.5510743999999999e+01 , -2.0556900000000000e-01 , -8.5415300000000005e-01 , 4.7766500000000001e-01 --8.5928387394882417e+00 , -8.5817278316311150e+00 , 1.5738087999999999e+01 , -1.3870800000000000e-01 , -8.2538000000000000e-01 , 5.4727300000000001e-01 --8.4142074482963807e+00 , -8.2840601367253885e+00 , 1.5899288000000000e+01 , -2.6506700000000000e-01 , -2.7953299999999998e-01 , 9.2282200000000003e-01 --2.1945682907079913e+00 , -2.1127304679316090e+00 , 8.7198247999999996e+00 , 6.9921599999999995e-01 , 5.5484000000000000e-01 , -4.5083299999999998e-01 --2.1176172702836107e+00 , -1.9868143204760647e+00 , 8.7868008000000000e+00 , -1.4038700000000001e-01 , -1.8729899999999999e-01 , 9.7221999999999997e-01 --2.2176644517902364e+00 , -2.0291031889416598e+00 , 9.0772936000000009e+00 , -8.7766599999999995e-01 , -4.5890799999999998e-01 , 1.3822200000000001e-01 --1.8973678901640083e+00 , -1.6733882697346960e+00 , 8.8241472000000005e+00 , 1.5242100000000000e-01 , -7.5387999999999999e-01 , 6.3908699999999996e-01 --2.3111364301550630e+00 , -2.0046285408386657e+00 , 9.5477272000000006e+00 , 7.5692499999999996e-01 , 6.3864100000000001e-01 , 1.3857400000000000e-01 --1.9168628818856539e+00 , -1.5863250589590021e+00 , 9.1783400000000004e+00 , 6.2614400000000003e-01 , -5.2808299999999997e-01 , 5.7364800000000005e-01 --1.8943378056614324e+00 , -1.5109801349618732e+00 , 9.3146632000000018e+00 , 3.1674300000000000e-01 , -2.3409800000000000e-01 , 9.1916900000000001e-01 --1.7131616277875050e+00 , -1.2937624940102350e+00 , 9.2193159999999992e+00 , -1.8477299999999999e-02 , -2.1191299999999999e-01 , 9.7711400000000004e-01 --1.6366901887033571e+00 , -1.1716575959007836e+00 , 9.2724912000000010e+00 , -3.4463199999999999e-01 , -1.2803400000000001e-01 , 9.2996599999999996e-01 --1.5640825755341590e+00 , -1.0547291050105305e+00 , 9.3307728000000001e+00 , -4.8571199999999998e-01 , -7.0485300000000001e-02 , 8.7127299999999996e-01 --1.5772053110631110e+00 , -1.0101467104037223e+00 , 9.5229128000000003e+00 , -1.0059500000000000e-01 , -8.2878700000000005e-01 , 5.5044800000000005e-01 --1.6167015303504568e+00 , -9.8622291473986667e-01 , 9.7649623999999999e+00 , -1.7500299999999999e-01 , 2.1362100000000001e-01 , 9.6111400000000002e-01 --1.5255449683736035e+00 , -8.5154837716278697e-01 , 9.7940719999999999e+00 , 6.3898099999999999e-02 , -2.8390900000000002e-01 , 9.5672000000000001e-01 --3.7393883148905260e-01 , 1.3405978701114996e-01 , 7.9802495999999996e+00 , 6.6174599999999995e-01 , 1.6300799999999999e-01 , -7.3179200000000000e-01 --2.9338249263135685e-01 , 2.4145746418120928e-01 , 7.9718359999999997e+00 , 6.2649999999999995e-01 , 1.0861400000000000e-01 , -7.7181599999999995e-01 --2.6449490016886879e-01 , 3.0782017885112900e-01 , 8.0544328000000007e+00 , -4.0798800000000002e-01 , -3.6076399999999997e-01 , 8.3868699999999996e-01 --2.2482995809247575e-01 , 3.8278754245634294e-01 , 8.1187776000000014e+00 , 6.6798900000000005e-01 , 3.5776000000000002e-01 , -6.5253300000000003e-01 --1.8930832612263471e-01 , 4.5416663081000053e-01 , 8.1907455999999996e+00 , -6.7558499999999999e-01 , -2.8675600000000001e-01 , 6.7923199999999995e-01 --1.7392662781058554e-01 , 5.1166977700878391e-01 , 8.3055407999999993e+00 , 8.5671399999999998e-01 , 3.3525899999999997e-01 , -3.9197300000000002e-01 --1.1452575395691866e-01 , 6.0229669345030934e-01 , 8.3306047999999997e+00 , 8.2423900000000005e-01 , 3.6957699999999999e-01 , -4.2900100000000002e-01 --6.0146310758722166e-01 , 3.1776271944306345e-01 , 9.5075520000000004e+00 , -5.1634400000000003e-01 , 7.8539700000000001e-01 , 3.4138099999999999e-01 --6.1822108762048922e-01 , 3.6651073758949249e-01 , 9.7301535999999995e+00 , 9.5485399999999998e-01 , -9.6844799999999995e-02 , -2.8084500000000001e-01 --5.7359737263770727e-01 , 4.5805676683053087e-01 , 9.8251159999999995e+00 , -8.2775399999999999e-01 , 1.8180399999999999e-01 , 5.3081999999999996e-01 --5.1580219873042354e-01 , 5.5906521948218368e-01 , 9.8908127999999991e+00 , -9.1363600000000000e-01 , -2.5494600000000001e-01 , 3.1665800000000000e-01 --1.8245735548287931e+00 , -1.6057145156248076e-01 , 1.3191440000000000e+01 , -6.6449800000000003e-01 , -4.3837999999999999e-01 , -6.0519800000000001e-01 -1.5228103297637197e-01 , 1.0799687377748857e+00 , 8.6819063999999990e+00 , -3.0102699999999999e-01 , 3.5815999999999998e-01 , 8.8380099999999995e-01 -2.5775904505874059e-01 , 1.1939336138346528e+00 , 8.5901992000000007e+00 , -3.1273899999999999e-01 , 2.2774800000000001e-01 , 9.2213100000000003e-01 -2.9165505802561897e-01 , 1.2681496516603330e+00 , 8.6759368000000006e+00 , -5.0102199999999997e-01 , 8.4256999999999999e-02 , 8.6132299999999995e-01 -5.6319077811272522e-01 , 1.4623744768920484e+00 , 8.1273368000000019e+00 , -2.4465500000000001e-02 , 9.7175199999999995e-01 , 2.3473100000000000e-01 -3.2797876762701983e-01 , 1.4048811045108880e+00 , 8.9407104000000004e+00 , -4.4912600000000003e-01 , -1.2349200000000000e-01 , 8.8489300000000004e-01 -4.5992195803556779e-01 , 1.5255987251464491e+00 , 8.7616848000000012e+00 , -4.9303300000000001e-03 , -9.9939500000000003e-01 , 3.4421899999999998e-02 -4.3483832129107625e-01 , 1.5780941655964136e+00 , 9.0274256000000008e+00 , -7.0297500000000002e-01 , -4.2123600000000000e-01 , 5.7305099999999998e-01 -1.7826859391908401e-01 , 1.5481721575386964e+00 , 1.0020521600000000e+01 , -3.0365399999999998e-01 , -9.5016000000000000e-01 , 7.0639300000000002e-02 --3.2052895124849989e-02 , 1.5571814092767462e+00 , 1.0932123200000001e+01 , 5.5138200000000004e-01 , 7.5338200000000000e-01 , 3.5832000000000003e-01 --3.5825712848911451e-02 , 1.6492379561148978e+00 , 1.1235397600000001e+01 , 3.8374599999999998e-01 , 8.9815400000000001e-01 , -2.1461400000000000e-01 -1.8783901412784942e-01 , 1.8084536554958941e+00 , 1.0782144799999999e+01 , 8.1601400000000004e-02 , -7.0743100000000003e-01 , 7.0205600000000001e-01 -3.1195362670500759e-01 , 1.9331362941914734e+00 , 1.0642212800000001e+01 , -5.8067800000000003e-01 , 1.7424100000000001e-02 , -8.1394699999999998e-01 -5.4772407453453997e-01 , 2.0726266922751129e+00 , 1.0077825600000001e+01 , 7.5716499999999998e-01 , 6.4280599999999999e-01 , -1.1619400000000001e-01 -6.1250943777704658e-01 , 2.1751147344466464e+00 , 1.0120736000000001e+01 , 6.3996100000000000e-02 , -4.7528199999999998e-01 , 8.7750300000000003e-01 -5.8257794435170385e-01 , 2.2714177534103022e+00 , 1.0544910400000001e+01 , -8.7985300000000000e-01 , 2.8184599999999999e-01 , -3.8265199999999999e-01 -5.8508286420918587e-01 , 2.3799328004043945e+00 , 1.0867976000000001e+01 , -4.4635999999999998e-01 , 2.4295000000000000e-01 , 8.6124199999999995e-01 -6.5321335189420693e-01 , 2.4938728131748462e+00 , 1.0936813600000001e+01 , 6.4589700000000005e-01 , -8.9192599999999997e-02 , -7.5819599999999998e-01 -5.9137933306036206e-01 , 2.6253750190166092e+00 , 1.1602673600000001e+01 , 6.7247199999999996e-01 , 5.2284900000000001e-01 , -5.2384200000000003e-01 -4.2991200618804415e-01 , 2.7975079312485538e+00 , 1.2817871999999999e+01 , 9.7508200000000000e-01 , 1.5482000000000001e-01 , 1.5889200000000001e-01 -1.3601316646051376e+00 , 2.7077898192774823e+00 , 8.6130479999999991e+00 , 3.9759400000000000e-02 , -7.6495899999999994e-01 , 6.4285099999999995e-01 -1.3735166108394061e+00 , 2.8045158789701801e+00 , 8.8535584000000007e+00 , 6.7277500000000001e-01 , -5.6443800000000000e-01 , -4.7831400000000002e-01 -1.4016590978916417e+00 , 2.9028433306437607e+00 , 9.0419231999999994e+00 , -5.6279699999999999e-01 , 7.1953699999999995e-02 , -8.2345699999999999e-01 -1.4659506791916252e+00 , 2.9877859328249254e+00 , 9.0345183999999996e+00 , 3.2831900000000003e-01 , 5.4114399999999996e-01 , -7.7419000000000004e-01 -1.4917123686359335e+00 , 3.1000359167437441e+00 , 9.2704008000000009e+00 , -9.0383000000000002e-01 , 2.7543600000000001e-01 , -3.2745500000000000e-01 -1.5052747779079252e+00 , 3.2339542012169606e+00 , 9.6270480000000003e+00 , -1.1418399999999999e-01 , 9.6689800000000004e-01 , -2.2818900000000000e-01 -1.6831888008664939e+00 , 3.2119635113933809e+00 , 8.8075071999999999e+00 , -9.0718699999999999e-02 , 8.4985800000000000e-01 , 5.1914600000000000e-01 -1.3625174753398608e+00 , 4.1178685023996575e-01 , 1.1755410399999999e+00 , 8.1555699999999995e-02 , -1.8375600000000000e-01 , -9.7958299999999998e-01 -1.3167163444477223e+00 , 3.5444290923160127e-01 , 1.1815574400000000e+00 , 7.2471900000000006e-02 , -1.8170300000000000e-01 , -9.8067899999999997e-01 -1.2696690008363185e+00 , 2.9749365136189354e-01 , 1.1892700800000000e+00 , -4.0036599999999999e-02 , 1.5539100000000000e-01 , 9.8704099999999995e-01 -1.2223346127802004e+00 , 2.3994501897924825e-01 , 1.1992124799999999e+00 , -6.2577400000000005e-02 , 1.7040800000000000e-01 , 9.8338400000000004e-01 -1.1665653105628182e+00 , 1.6794210453860692e-01 , 1.1988505599999999e+00 , -3.3009799999999999e-02 , 1.4228399999999999e-01 , 9.8927500000000002e-01 -1.1140720887970801e+00 , 1.0281102601527015e-01 , 1.2069698400000000e+00 , -6.7760000000000001e-02 , 1.3580100000000001e-01 , 9.8841599999999996e-01 -1.0519446624547095e+00 , 2.2441369507895992e-02 , 1.2058768000000000e+00 , -5.5971699999999999e-02 , 1.4510200000000001e-01 , 9.8783200000000004e-01 -9.9315184857539629e-01 , -5.0036491277260176e-02 , 1.2130600800000000e+00 , -6.8419999999999995e-02 , 1.6106899999999999e-01 , 9.8456900000000003e-01 -9.3033269474625779e-01 , -1.3029169131234175e-01 , 1.2176360800000001e+00 , -9.1911800000000002e-02 , 1.6552200000000000e-01 , 9.8191399999999995e-01 -8.6508134352773380e-01 , -2.1095502997469096e-01 , 1.2249992800000000e+00 , -7.0833499999999994e-02 , 1.7024400000000001e-01 , 9.8285299999999998e-01 -7.8999096709484351e-01 , -3.0652706248026673e-01 , 1.2247694400000000e+00 , -8.8754700000000006e-02 , 2.0314599999999999e-01 , 9.7511800000000004e-01 -7.2392571972426523e-01 , -3.8793901987980517e-01 , 1.2387147999999999e+00 , -1.0270200000000000e-01 , 1.8532999999999999e-01 , 9.7729500000000002e-01 -6.3256313265228492e-01 , -5.0772490656097835e-01 , 1.2307702400000000e+00 , -1.1275000000000000e-01 , 1.5094099999999999e-01 , 9.8209199999999996e-01 -5.4918256719704783e-01 , -6.1223572598502152e-01 , 1.2370757600000000e+00 , -8.0809500000000006e-02 , 1.6865300000000000e-01 , 9.8235700000000004e-01 -4.6531110068348758e-01 , -7.1699461731585190e-01 , 1.2473301600000002e+00 , -8.7211800000000006e-02 , 2.0119899999999999e-01 , 9.7565999999999997e-01 -3.7507860967631124e-01 , -8.2900662862856711e-01 , 1.2571539999999999e+00 , -8.5214899999999996e-02 , 1.5000600000000000e-01 , 9.8500600000000005e-01 -2.6860545842765227e-01 , -9.6638275464928514e-01 , 1.2587608000000001e+00 , -4.4162699999999999e-02 , 2.3122400000000001e-01 , 9.7189800000000004e-01 -1.8596573314657117e-01 , -1.0624557981011677e+00 , 1.2860722400000000e+00 , -3.4033899999999999e-02 , 3.2797100000000001e-01 , 9.4407500000000000e-01 -8.8080513496437751e-02 , -1.1838291759635533e+00 , 1.3056960000000000e+00 , -3.5726700000000000e-02 , 2.5575300000000001e-01 , 9.6608200000000000e-01 --2.3319028423872457e-02 , -1.3201452951586981e+00 , 1.3221092799999998e+00 , -6.7970600000000006e-02 , 2.2289500000000001e-01 , 9.7246999999999995e-01 --1.4528953583295179e-01 , -1.4722612865152009e+00 , 1.3369032800000000e+00 , -7.4097399999999994e-02 , 2.1555600000000000e-01 , 9.7367599999999999e-01 --2.8004805467725014e-01 , -1.6409661362631880e+00 , 1.3509453599999999e+00 , 7.3989700000000005e-02 , -2.1107799999999999e-01 , -9.7466500000000000e-01 --4.1672018108233688e-01 , -1.8102817354715066e+00 , 1.3720500800000002e+00 , -6.8835800000000003e-02 , 2.1915399999999999e-01 , 9.7325899999999999e-01 --5.7130100600566758e-01 , -2.0027528117291684e+00 , 1.3903748800000000e+00 , -7.6356599999999997e-02 , 2.1204700000000001e-01 , 9.7427200000000003e-01 --7.3399654543738801e-01 , -2.2034055208291985e+00 , 1.4138154400000000e+00 , -5.4324299999999999e-02 , 2.1403000000000000e-01 , 9.7531500000000004e-01 --9.0380144081265712e-01 , -2.4121740163130578e+00 , 1.4429021600000000e+00 , -6.2780199999999994e-02 , 2.2055200000000000e-01 , 9.7335300000000002e-01 --1.0980936745496277e+00 , -2.6531567346253428e+00 , 1.4702000800000001e+00 , -7.1165000000000006e-02 , 2.2671900000000000e-01 , 9.7135700000000003e-01 --1.3242982998309616e+00 , -2.9346395723883072e+00 , 1.4952588800000000e+00 , -1.6583199999999999e-02 , 5.3342400000000001e-01 , 8.4568500000000002e-01 --1.4165256749324162e+00 , -3.0262361566633524e+00 , 1.5848694399999999e+00 , -5.9419899999999998e-02 , 6.4795300000000000e-01 , 7.5935900000000001e-01 --1.4381103171399863e+00 , -3.0162860228687185e+00 , 1.7034200799999999e+00 , 7.4446600000000002e-02 , 8.5989099999999996e-01 , 5.0502000000000002e-01 --1.5350561961397573e+00 , -3.1122453944364912e+00 , 1.7966914400000000e+00 , -1.2944199999999999e-02 , 7.1464600000000000e-01 , 6.9936699999999996e-01 --1.9219693989651940e+00 , -3.6047064149359427e+00 , 1.8101417600000000e+00 , -3.9280199999999998e-01 , -4.5058799999999999e-01 , -8.0167100000000002e-01 --2.8903130119223306e+00 , -4.8828442536173275e+00 , 1.6946549600000000e+00 , 7.9227699999999998e-02 , -2.6184499999999999e-01 , -9.6185299999999996e-01 --3.2958638152171194e+00 , -5.3809403194675118e+00 , 1.7657597599999999e+00 , -7.6273300000000002e-02 , 2.5906000000000001e-01 , 9.6284499999999995e-01 --3.7595285272707448e+00 , -5.9498379542436011e+00 , 1.8472052800000001e+00 , -6.4811800000000003e-02 , 2.5325999999999999e-01 , 9.6522500000000000e-01 --4.2892859047704759e+00 , -6.5990176712716444e+00 , 1.9429980160000000e+00 , 1.0179199999999999e-02 , 2.6352300000000001e-01 , 9.6459899999999998e-01 --4.8224994557971401e+00 , -7.2454386325381641e+00 , 2.0675341679999999e+00 , 1.3540900000000000e-01 , 2.5010800000000000e-01 , 9.5870299999999997e-01 --4.8949727029193042e+00 , -7.2745613596585752e+00 , 2.2712143199999999e+00 , 1.3321400000000000e-01 , 2.6058500000000001e-01 , 9.5621599999999995e-01 --5.4013745564729652e+00 , -7.8704483438318960e+00 , 2.4414945600000002e+00 , 9.8174999999999998e-02 , 2.6275399999999999e-01 , 9.5985500000000001e-01 --6.2074797992992323e+00 , -8.8483627129289069e+00 , 2.6227467999999998e+00 , -5.3493400000000002e-03 , 3.7491700000000000e-01 , 9.2704299999999995e-01 --7.3440331437639088e+00 , -1.0238232261748824e+01 , 2.8391208799999998e+00 , -2.3200599999999999e-01 , 6.3216300000000003e-01 , 7.3928600000000000e-01 --7.8661593938408174e+00 , -1.0822768951037000e+01 , 3.1149840000000002e+00 , -1.1156800000000000e-01 , 9.6875400000000000e-01 , 2.2151599999999999e-01 --7.9401474023275345e+00 , -1.0826306616958181e+01 , 3.4032200000000001e+00 , 3.6790499999999997e-02 , -9.9930399999999997e-01 , -6.1441200000000003e-03 --8.0943085873366432e+00 , -1.0933216802275515e+01 , 3.6985384000000003e+00 , 4.5988099999999997e-02 , -9.9870700000000001e-01 , 2.1676800000000000e-02 --8.1440285412266711e+00 , -1.0904139012380591e+01 , 3.9907887999999998e+00 , 6.6979200000000003e-02 , -9.9052799999999996e-01 , 1.1986500000000000e-01 --8.1699184224138577e+00 , -1.0846566929110022e+01 , 4.2814791999999997e+00 , 7.9916200000000007e-02 , -9.7257199999999999e-01 , 2.1844000000000000e-01 --8.1794822070079309e+00 , -1.0769025289559142e+01 , 4.5695383999999999e+00 , -8.0918599999999993e-02 , 9.7391600000000000e-01 , -2.1199200000000001e-01 --8.0562864558309197e+00 , -1.0526632759485933e+01 , 4.8341767999999998e+00 , -8.6151400000000003e-02 , 9.9461100000000002e-01 , -5.7687799999999997e-02 --8.3079545486950881e+00 , -1.0746679373121937e+01 , 5.1638256000000000e+00 , 7.4840400000000001e-02 , -9.9568699999999999e-01 , 5.4829700000000002e-02 --8.4255835223794868e+00 , -1.0799811752759545e+01 , 5.4761687999999999e+00 , 1.9615000000000000e-02 , -9.9752900000000000e-01 , 6.7469299999999996e-02 --8.4553204405602287e+00 , -1.0745247922531892e+01 , 5.7721527999999998e+00 , 4.1178399999999997e-02 , -9.8328400000000005e-01 , 1.7736199999999999e-01 --8.4818494394803068e+00 , -1.0686616904153063e+01 , 6.0680016000000006e+00 , -5.2150599999999998e-02 , 9.8187500000000005e-01 , -1.8221300000000001e-01 --8.5051663868176401e+00 , -1.0623939083007876e+01 , 6.3636008000000004e+00 , 6.5418400000000002e-02 , -9.7487699999999999e-01 , 2.1292200000000000e-01 --8.5385602662379050e+00 , -1.0571750730217001e+01 , 6.6629648000000001e+00 , -5.8046599999999997e-02 , 9.7576300000000005e-01 , -2.1098900000000001e-01 --8.5553615142908619e+00 , -1.0500907678466648e+01 , 6.9582831999999994e+00 , -5.6298500000000001e-02 , 9.7648999999999997e-01 , -2.0808299999999999e-01 --8.5813058228215642e+00 , -1.0440449682116260e+01 , 7.2580944000000001e+00 , -5.0193799999999997e-02 , 9.7674499999999997e-01 , -2.0844799999999999e-01 --8.6174985437398597e+00 , -1.0391205663958008e+01 , 7.5632824000000003e+00 , -5.4108999999999997e-02 , 9.7651399999999999e-01 , -2.0854800000000001e-01 --8.6437913373915709e+00 , -1.0330075502359756e+01 , 7.8663384000000010e+00 , -5.5335500000000003e-02 , 9.7666900000000001e-01 , -2.0749600000000001e-01 --8.6726722351768846e+00 , -1.0271358826712079e+01 , 8.1726808000000002e+00 , -5.1512000000000002e-02 , 9.7548400000000002e-01 , -2.1395800000000001e-01 --8.6994367985788976e+00 , -1.0208424834782919e+01 , 8.4793664000000000e+00 , -5.5258300000000003e-02 , 9.7584099999999996e-01 , -2.1137900000000001e-01 --8.7208929194071345e+00 , -1.0141316203266816e+01 , 8.7867695999999995e+00 , 4.7741899999999997e-02 , -9.6506599999999998e-01 , 2.5762000000000002e-01 --8.7333588867362781e+00 , -1.0061497753804623e+01 , 9.0906991999999995e+00 , 3.1497299999999999e-02 , -9.6614000000000000e-01 , 2.5608799999999998e-01 --8.7943851495898642e+00 , -1.0035274276972503e+01 , 9.4239048000000007e+00 , -8.9278800000000005e-02 , 9.5960199999999996e-01 , -2.6682000000000000e-01 --8.6505189386785659e+00 , -9.7823034998321692e+00 , 9.6403704000000019e+00 , 8.4006499999999998e-02 , -9.7463200000000005e-01 , 2.0744799999999999e-01 --8.7688567051548372e+00 , -9.8178052562029059e+00 , 1.0013356000000000e+01 , -1.1406600000000000e-01 , 9.8517699999999997e-01 , -1.2812299999999999e-01 --9.0450831431063250e+00 , -1.0020874849713687e+01 , 1.0495978400000000e+01 , 8.4949700000000003e-02 , -9.9632600000000004e-01 , 1.0873900000000001e-02 --8.9548873298950582e+00 , -9.8250816799538665e+00 , 1.0749135200000000e+01 , -6.3404799999999997e-02 , 9.9777499999999997e-01 , -2.0627800000000002e-02 --9.2144750401499227e+00 , -1.0002918696968429e+01 , 1.1244664000000000e+01 , 8.0276299999999995e-02 , -9.9069399999999996e-01 , 1.0991300000000000e-01 --9.2576167576313182e+00 , -9.9466153140082962e+00 , 1.1599210400000000e+01 , 4.7646000000000001e-02 , -9.9260800000000005e-01 , 1.1161799999999999e-01 --9.2767713631091411e+00 , -9.8641627856034688e+00 , 1.1941141600000000e+01 , -6.2675099999999997e-02 , 9.7514000000000001e-01 , -2.1254300000000001e-01 --9.3106536411230891e+00 , -9.7959545311720166e+00 , 1.2298818400000002e+01 , 5.9519700000000002e-02 , -9.7516499999999995e-01 , 2.1333400000000000e-01 --9.3403328505964556e+00 , -9.7212595533301585e+00 , 1.2657919999999999e+01 , -5.6568800000000002e-02 , 9.7360899999999995e-01 , -2.2110099999999999e-01 --9.3660204139267922e+00 , -9.6411288042984022e+00 , 1.3018592000000000e+01 , 4.8881399999999998e-02 , -9.7387500000000005e-01 , 2.2176199999999999e-01 --9.3864202184171042e+00 , -9.5535804821399690e+00 , 1.3380200000000000e+01 , 5.7184100000000002e-02 , -9.7412500000000002e-01 , 2.1865699999999999e-01 --9.4206785709253964e+00 , -9.4788056477665155e+00 , 1.3759800000000000e+01 , -4.8113400000000001e-02 , 9.7446999999999995e-01 , -2.1930300000000000e-01 --9.4691632370551790e+00 , -9.4165605052369656e+00 , 1.4158536000000000e+01 , 5.4729199999999999e-02 , -9.6635000000000004e-01 , 2.5134299999999998e-01 --9.4629093334121261e+00 , -9.2976958673791774e+00 , 1.4512760000000000e+01 , -2.7014699999999999e-02 , 9.4888300000000003e-01 , -3.1447000000000003e-01 --9.4158132728844031e+00 , -9.1368923603610490e+00 , 1.4830688000000000e+01 , 4.0883900000000001e-02 , -9.4651200000000002e-01 , 3.2006899999999999e-01 --9.4313778299258466e+00 , -9.0365532588225985e+00 , 1.5214760000000000e+01 , -3.3112099999999998e-02 , -9.1710599999999998e-01 , 3.9726499999999998e-01 --9.4772407146822992e+00 , -8.9621145900356272e+00 , 1.5637624000000001e+01 , 6.0267399999999999e-02 , -8.4588600000000003e-01 , 5.2994799999999997e-01 --9.2558588077760042e+00 , -8.6340166806022776e+00 , 1.5779792000000000e+01 , -7.7418799999999996e-02 , 8.1625400000000004e-01 , -5.7248200000000005e-01 --9.0568159898896621e+00 , -8.3281577622323457e+00 , 1.5938392000000000e+01 , -7.7746099999999999e-02 , -6.7496299999999998e-01 , 7.3374499999999998e-01 --2.4638906312385025e+00 , -2.1278499399107433e+00 , 8.7349256000000004e+00 , -6.8699200000000005e-01 , -5.3034700000000001e-01 , 4.9676399999999998e-01 --2.3494058692087600e+00 , -1.9716803341725151e+00 , 8.7650128000000009e+00 , -6.8699200000000005e-01 , -5.3034700000000001e-01 , 4.9676399999999998e-01 --2.2919671147179272e+00 , -1.8679713400955227e+00 , 8.8598295999999994e+00 , -6.6914099999999999e-01 , -5.6482100000000002e-01 , 4.8293700000000001e-01 --2.3239756882318687e+00 , -1.8441320636131602e+00 , 9.0662175999999999e+00 , 6.8897799999999998e-01 , 7.0433299999999999e-01 , -1.7094899999999999e-01 --2.2857590256477689e+00 , -1.7565758906745659e+00 , 9.1874399999999987e+00 , 2.0024200000000000e-01 , 8.2554899999999998e-01 , -5.2761000000000002e-01 --2.3509475695216686e+00 , -1.7587648892951058e+00 , 9.4472424000000004e+00 , -4.2754999999999999e-01 , -9.0314200000000000e-01 , 3.9191999999999998e-02 --2.1703042567132993e+00 , -1.5483935831718196e+00 , 9.3810463999999989e+00 , -1.0133499999999999e-01 , -6.9995100000000005e-02 , 9.9238700000000002e-01 --1.9482775411629700e+00 , -1.3057681285616041e+00 , 9.2465744000000001e+00 , 2.5198999999999999e-01 , -4.1048499999999999e-01 , 8.7635799999999997e-01 --1.8889326095479220e+00 , -1.2025110436470796e+00 , 9.3343296000000002e+00 , -8.7176399999999998e-01 , 3.0077100000000001e-01 , -3.8673500000000000e-01 --1.9244283434735667e+00 , -1.1765453726709647e+00 , 9.5610288000000008e+00 , 8.2513900000000001e-02 , -9.8331000000000002e-01 , 1.6215399999999999e-01 --1.8678938382385541e+00 , -1.0741338890114047e+00 , 9.6545144000000001e+00 , 7.3636199999999996e-01 , -2.1083700000000000e-01 , -6.4289900000000000e-01 --1.8037791630375599e+00 , -9.6660974524512833e-01 , 9.7381095999999996e+00 , 3.4134700000000001e-01 , 4.6323400000000001e-02 , -9.3879500000000005e-01 --1.6835857695094920e+00 , -8.1425974736325424e-01 , 9.7293631999999999e+00 , -3.6873499999999998e-01 , -2.0194000000000001e-01 , 9.0733399999999997e-01 --1.5281230251977918e+00 , -6.3776063670386529e-01 , 9.6583104000000013e+00 , -2.2102300000000000e-01 , 1.9511400000000001e-05 , 9.7526900000000005e-01 --1.7892290436612237e+00 , -7.7533757382551372e-01 , 1.0284733600000001e+01 , -8.9791699999999997e-01 , -4.0167300000000000e-01 , -1.8001300000000001e-01 --1.6311828855200066e+00 , -5.9540722168446569e-01 , 1.0210186400000000e+01 , 8.3781399999999995e-01 , 4.3994299999999997e-01 , 3.2329300000000000e-01 --1.9467608784591226e+00 , -7.6039975619884714e-01 , 1.0978777600000001e+01 , -9.1865699999999995e-01 , -7.1411500000000003e-02 , -3.8854699999999998e-01 --1.0844815064908468e+00 , -8.3628931865353362e-02 , 9.6099504000000007e+00 , -3.1715599999999999e-01 , 9.2564999999999997e-01 , 2.0635899999999999e-01 --9.8251360809163391e-01 , 4.5034464059547252e-02 , 9.6009543999999991e+00 , -5.5296800000000002e-01 , 6.7294799999999999e-01 , 4.9129200000000001e-01 --8.7585652426369842e-01 , 1.7522142722453005e-01 , 9.5794783999999993e+00 , 4.0269800000000000e-01 , -7.9593599999999998e-01 , -4.5201900000000000e-01 --6.4885896215714611e-01 , 3.8248882961188579e-01 , 9.3127496000000001e+00 , 6.3858800000000004e-01 , -7.0648000000000000e-01 , -3.0510999999999999e-01 --5.8503209204832496e-01 , 4.8007318126065202e-01 , 9.3627528000000009e+00 , -8.6400800000000000e-01 , -4.1065400000000002e-01 , 2.9129699999999997e-01 --6.1881312129710908e-01 , 5.1747229919232507e-01 , 9.6202256000000013e+00 , -8.9068700000000001e-01 , -4.2551000000000000e-01 , 1.6005600000000000e-01 --6.1934391964889501e-01 , 5.7898263737715494e-01 , 9.8147368000000004e+00 , -9.4678899999999999e-01 , -2.3907500000000001e-01 , 2.1548500000000001e-01 --1.6927403278024866e+00 , 2.5548168383805470e-02 , 1.2446384000000002e+01 , 3.6738900000000002e-01 , 5.7750000000000001e-01 , 7.2905399999999998e-01 --1.7576495260719471e+00 , 8.0558852592746755e-02 , 1.2884744000000001e+01 , 4.9630400000000002e-01 , 2.1342900000000001e-01 , 8.4150499999999995e-01 -1.6755805048345573e-01 , 1.1959901973528044e+00 , 8.5653535999999999e+00 , -3.1273899999999999e-01 , 2.2774800000000001e-01 , 9.2213100000000003e-01 -3.3715776638026718e-02 , 1.1832652302343143e+00 , 9.0691711999999995e+00 , -5.1191399999999998e-01 , -4.3620900000000001e-01 , 7.4004400000000004e-01 -3.8110663386754839e-01 , 1.4098217460367333e+00 , 8.3757511999999998e+00 , -3.7669500000000000e-01 , 9.1521699999999995e-01 , -1.4310100000000001e-01 -3.4316801034684929e-01 , 1.4476291765640286e+00 , 8.6501760000000001e+00 , -3.6258400000000002e-01 , -2.0431900000000000e-01 , 9.0927800000000003e-01 -2.9285668798207665e-01 , 1.4843356249500315e+00 , 8.9744688000000004e+00 , -6.9090799999999997e-01 , -3.7356099999999998e-01 , 6.1894899999999997e-01 -1.1426265526130797e-02 , 1.4359766310140383e+00 , 9.9708928000000014e+00 , -2.3027000000000000e-01 , -8.8841400000000004e-01 , 3.9711000000000002e-01 -3.6967542441640022e-02 , 1.5211505633568039e+00 , 1.0135587200000000e+01 , 4.7358800000000001e-01 , 8.2676200000000000e-01 , -3.0361100000000002e-01 --6.2368411223030407e-01 , 1.3808018062087903e+00 , 1.2391680000000001e+01 , 7.2988100000000000e-01 , -2.8629599999999999e-01 , 6.2073199999999995e-01 --5.0574991661776814e-02 , 1.6597039661599824e+00 , 1.0936345599999999e+01 , 5.2794800000000003e-02 , 9.1746399999999995e-01 , 3.9429900000000001e-01 -9.3392414721631178e-02 , 1.7906751462661619e+00 , 1.0763351999999999e+01 , -2.5742399999999999e-01 , 7.9963799999999996e-01 , 5.4250500000000001e-01 -1.7886649284356237e-01 , 1.9030755488423361e+00 , 1.0775551199999999e+01 , 4.4540400000000002e-01 , 8.4391899999999997e-01 , 2.9902499999999999e-01 -4.1450167784060388e-01 , 2.0429714779710837e+00 , 1.0255322400000001e+01 , -4.6354699999999999e-01 , -4.4431799999999999e-01 , -7.6661900000000005e-01 -5.3023248668067557e-01 , 2.1519007331445232e+00 , 1.0130272800000000e+01 , -3.6910900000000002e-01 , -3.3956999999999998e-01 , 8.6513099999999998e-01 -5.4074785853095597e-01 , 2.2481724395997968e+00 , 1.0394266400000001e+01 , 7.1626599999999996e-01 , 6.4451800000000004e-01 , -2.6750600000000002e-01 -5.7704727940209399e-01 , 2.3524107270411894e+00 , 1.0576817600000000e+01 , 7.4329999999999996e-01 , -5.5563399999999996e-01 , 3.7252500000000000e-01 -5.9166264482600139e-01 , 2.4616976951816776e+00 , 1.0869400799999999e+01 , 6.4589700000000005e-01 , -8.9192700000000000e-02 , -7.5819599999999998e-01 -6.6194276969675792e-01 , 2.5743512106392274e+00 , 1.0937583200000001e+01 , 6.4116300000000004e-01 , 3.8912099999999999e-01 , -6.6143399999999997e-01 -5.7235070588529546e-01 , 2.7153724103851253e+00 , 1.1755449600000000e+01 , 6.5124400000000005e-01 , 6.4530699999999996e-01 , -3.9932600000000001e-01 -4.5176134266620149e-01 , 2.8911056470879068e+00 , 1.2807472000000001e+01 , 9.7508200000000000e-01 , 1.5482000000000001e-01 , 1.5889200000000001e-01 -1.3724857791876706e+00 , 2.7601948138338797e+00 , 8.6228136000000006e+00 , -6.0274300000000003e-01 , -6.7378199999999999e-01 , 4.2745600000000000e-01 -1.3461484615430339e+00 , 2.8750707470348593e+00 , 9.0977712000000004e+00 , -9.6785699999999997e-01 , 1.2125400000000000e-01 , 2.2034200000000001e-01 -1.4251100166272748e+00 , 2.9527130225981524e+00 , 9.0203848000000004e+00 , 5.2242699999999997e-01 , -6.7826799999999998e-01 , 5.1674200000000003e-01 -1.4832882938954679e+00 , 3.0406970854784698e+00 , 9.0636904000000005e+00 , -1.5671900000000000e-01 , 5.8690900000000001e-01 , -7.9434000000000005e-01 -1.5097690515336080e+00 , 3.1548649562422870e+00 , 9.3197904000000005e+00 , 5.2178700000000000e-01 , -8.3471099999999998e-01 , 1.7605599999999999e-01 -1.6238318287184605e+00 , 3.1985729823911804e+00 , 8.9918575999999995e+00 , 4.0971899999999999e-02 , 9.8841800000000002e-01 , 1.4612400000000000e-01 -1.7196453588143514e+00 , 3.2463917846693806e+00 , 8.7542384000000002e+00 , 7.6029999999999998e-01 , 6.4710400000000001e-01 , -5.6577299999999997e-02 -1.2968259923449061e+00 , 4.3276697291668054e-01 , 1.1760776800000001e+00 , -6.0324700000000002e-02 , 1.5882299999999999e-01 , 9.8546199999999995e-01 -1.2443638541270774e+00 , 3.7018896109741739e-01 , 1.1757625599999999e+00 , -5.5812700000000000e-02 , 1.8088199999999999e-01 , 9.8192000000000002e-01 -1.1962088023921074e+00 , 3.1449016150889508e-01 , 1.1841564000000000e+00 , -2.6050100000000000e-02 , 1.6359799999999999e-01 , 9.8618300000000003e-01 -1.1431735669315335e+00 , 2.5072421320447913e-01 , 1.1884006400000000e+00 , 4.2546000000000000e-02 , -1.6359799999999999e-01 , -9.8560899999999996e-01 -1.0888398597948212e+00 , 1.8744846986359032e-01 , 1.1947456800000000e+00 , 6.4737799999999998e-02 , -1.7157300000000000e-01 , -9.8304199999999997e-01 -1.0295944185348975e+00 , 1.1725583833921371e-01 , 1.1973425600000001e+00 , -6.3449300000000000e-02 , 1.1841400000000001e-01 , 9.9093500000000001e-01 -9.6532747145271780e-01 , 3.9222087267409611e-02 , 1.1969036799999999e+00 , -7.9836199999999996e-02 , 1.4661299999999999e-01 , 9.8596700000000004e-01 -8.9967060021913392e-01 , -3.9231365190315781e-02 , 1.1992759199999998e+00 , -6.7304199999999995e-02 , 1.3998700000000000e-01 , 9.8786300000000005e-01 -8.2790063828592975e-01 , -1.2537580906516110e-01 , 1.1990928800000000e+00 , -7.3236599999999999e-02 , 1.5487899999999999e-01 , 9.8521499999999995e-01 -7.6042038001337087e-01 , -2.0462334133379878e-01 , 1.2077196799999999e+00 , -8.7274800000000000e-02 , 1.6521200000000000e-01 , 9.8238899999999996e-01 -6.8679631485117110e-01 , -2.9151503387958932e-01 , 1.2139940000000000e+00 , -8.9301699999999998e-02 , 1.6770800000000000e-01 , 9.8178399999999999e-01 -6.0804123180074421e-01 , -3.8492238162119063e-01 , 1.2184431199999999e+00 , -1.2877600000000000e-01 , 1.7713599999999999e-01 , 9.7572499999999995e-01 -5.1236835120046775e-01 , -5.0213326276063608e-01 , 1.2118120800000001e+00 , -1.1984499999999999e-01 , 1.6987300000000000e-01 , 9.7815200000000002e-01 -4.3155504037810788e-01 , -5.9700837480172186e-01 , 1.2243399199999998e+00 , -9.0834799999999993e-02 , 2.0539299999999999e-01 , 9.7445499999999996e-01 -3.3855039666860764e-01 , -7.0733268620183409e-01 , 1.2313526399999999e+00 , 7.9172800000000002e-02 , -1.9016500000000000e-01 , -9.7855499999999995e-01 -2.3915401227547095e-01 , -8.2486328644386386e-01 , 1.2381386400000001e+00 , -6.7940100000000003e-02 , 1.8618499999999999e-01 , 9.8016300000000001e-01 -1.2245746901975263e-01 , -9.6661449732661575e-01 , 1.2369832000000001e+00 , -6.0270400000000002e-02 , 2.5291799999999998e-01 , 9.6560900000000005e-01 -3.6482926792782200e-02 , -1.0611032870307007e+00 , 1.2661406400000002e+00 , -3.3238999999999998e-02 , 3.2096799999999998e-01 , 9.4650699999999999e-01 --6.6753627670175231e-02 , -1.1787968598926755e+00 , 1.2871517600000000e+00 , -4.8609100000000002e-02 , 2.6432899999999998e-01 , 9.6320700000000004e-01 --1.8742037655929655e-01 , -1.3193366817427461e+00 , 1.3016358399999999e+00 , -6.9623599999999994e-02 , 2.2088099999999999e-01 , 9.7281300000000004e-01 --3.0885584228316887e-01 , -1.4607433023168421e+00 , 1.3222975200000000e+00 , -5.6435800000000001e-02 , 2.0928400000000000e-01 , 9.7622500000000001e-01 --4.5503994391852265e-01 , -1.6334939107680553e+00 , 1.3348669600000000e+00 , -7.4817400000000006e-02 , 2.1088199999999999e-01 , 9.7464399999999995e-01 --6.0313022267809169e-01 , -1.8057926100568005e+00 , 1.3545988800000002e+00 , -7.4719900000000006e-02 , 2.1521000000000001e-01 , 9.7370500000000004e-01 --7.7638551296638614e-01 , -2.0108885873331932e+00 , 1.3694833600000000e+00 , -5.7177800000000001e-02 , 2.1554799999999999e-01 , 9.7481799999999996e-01 --9.4559450332008499e-01 , -2.2064735008604952e+00 , 1.3955988000000001e+00 , -5.7855900000000002e-02 , 2.1269800000000000e-01 , 9.7540400000000005e-01 --1.1402430228644453e+00 , -2.4343913751850597e+00 , 1.4191922400000001e+00 , -6.5459299999999998e-02 , 2.1256800000000001e-01 , 9.7495100000000001e-01 --1.3544217076969201e+00 , -2.6854750684258430e+00 , 1.4448407200000000e+00 , -5.7084999999999997e-02 , 2.5708399999999998e-01 , 9.6470199999999995e-01 --1.5955124978439086e+00 , -2.9681184644995202e+00 , 1.4714844800000000e+00 , -1.5918399999999999e-01 , 6.5616600000000003e-01 , 7.3763500000000004e-01 --1.7651967605452348e+00 , -3.1535065422335187e+00 , 1.5375567200000000e+00 , -4.2712200000000001e-03 , 9.0108299999999997e-01 , 4.3362499999999998e-01 --1.7873940747305501e+00 , -3.1424708894626843e+00 , 1.6613687200000000e+00 , -8.4464300000000006e-02 , 8.3992699999999998e-01 , 5.3608699999999998e-01 --1.8705535446782164e+00 , -3.2112715584869242e+00 , 1.7659417600000000e+00 , 6.7249400000000001e-02 , 8.5945000000000005e-01 , 5.0677700000000003e-01 --2.0287502288537311e+00 , -3.3749118998731262e+00 , 1.8528212799999999e+00 , 7.3312699999999997e-01 , 2.2858800000000001e-01 , 6.4052500000000001e-01 --3.3325275627015092e+00 , -5.0051796863133706e+00 , 1.6676856799999999e+00 , -7.6425000000000007e-02 , 2.5943100000000002e-01 , 9.6273299999999995e-01 --3.7670595162853235e+00 , -5.5063066337391051e+00 , 1.7439114400000000e+00 , -6.7331400000000000e-02 , 2.6105099999999998e-01 , 9.6297400000000000e-01 --4.2745338676550224e+00 , -6.0937095743131398e+00 , 1.8295731200000001e+00 , -2.5129700000000001e-02 , 2.5210300000000002e-01 , 9.6737399999999996e-01 --4.8640100917113855e+00 , -6.7746262202238796e+00 , 1.9290497440000001e+00 , 8.6723400000000006e-02 , 2.7953600000000001e-01 , 9.5621000000000000e-01 --5.0612773490911920e+00 , -6.9579547389936813e+00 , 2.1101058400000001e+00 , 4.0705600000000002e-02 , 3.7737799999999999e-01 , 9.2516399999999999e-01 --5.3760622111514333e+00 , -7.2833813019445799e+00 , 2.2881611199999998e+00 , 1.2206100000000000e-01 , 3.0158099999999999e-01 , 9.4559499999999996e-01 --5.9986564705140744e+00 , -7.9835647388453150e+00 , 2.4588043200000000e+00 , -4.1397799999999998e-02 , 3.6348500000000000e-01 , 9.3067999999999995e-01 --7.0204030029958453e+00 , -9.1607991491765954e+00 , 2.6429695999999998e+00 , -4.4446199999999998e-02 , 3.5450799999999999e-01 , 9.3399600000000005e-01 --8.5767856218670619e+00 , -1.0970003476149811e+01 , 2.8701742399999999e+00 , -1.8311300000000000e-01 , 9.7872700000000001e-01 , 9.2541499999999999e-02 --8.7021651298581055e+00 , -1.1030967766024489e+01 , 3.1679512000000001e+00 , -6.5791400000000000e-02 , 9.9782899999999997e-01 , -3.0671000000000001e-03 --8.8570922308883997e+00 , -1.1125723842380301e+01 , 3.4709344000000000e+00 , -3.8476099999999999e-02 , 9.9924500000000005e-01 , -5.4817499999999996e-03 --8.9361394057428392e+00 , -1.1128907553977168e+01 , 3.7754880000000002e+00 , -1.5563600000000000e-02 , 9.9826000000000004e-01 , -5.6867099999999997e-02 --8.9861362473356081e+00 , -1.1095322936683720e+01 , 4.0793967999999996e+00 , -4.1123699999999999e-02 , 9.9687300000000001e-01 , -6.7473500000000006e-02 --9.0244143102215997e+00 , -1.1050449125193094e+01 , 4.3833368000000004e+00 , 9.6182199999999995e-02 , -9.8863800000000002e-01 , 1.1552000000000000e-01 --9.0397204201462369e+00 , -1.0976512163130977e+01 , 4.6839592000000003e+00 , 1.9947899999999999e-01 , -9.7924800000000001e-01 , 3.5785100000000000e-02 --9.2747629668682059e+00 , -1.1157650617884384e+01 , 5.0205760000000001e+00 , 2.4881400000000001e-01 , -9.6835099999999996e-01 , 1.9701400000000001e-02 --9.5955076043162499e+00 , -1.1433731986839847e+01 , 5.3844200000000004e+00 , -1.5734400000000001e-01 , 9.8655099999999996e-01 , -4.4271999999999999e-02 --9.6211303210044825e+00 , -1.1369102140812535e+01 , 5.6997584000000003e+00 , -1.8259700000000001e-01 , 9.8307699999999998e-01 , 1.4750700000000000e-02 --9.5684406213093833e+00 , -1.1214953605606905e+01 , 5.9965432000000005e+00 , -1.7408299999999999e-01 , 9.5748299999999997e-01 , -2.3004600000000000e-01 --1.0409904552720972e+01 , -1.2068378357611060e+01 , 6.5296680000000000e+00 , 1.3842900000000000e-01 , -9.8399199999999998e-01 , 1.1223500000000000e-01 --1.0470370976007278e+01 , -1.1836570456712575e+01 , 7.5356392000000003e+00 , -9.8071200000000003e-01 , -1.9499200000000000e-01 , 1.3515900000000001e-02 --1.0243273040509234e+01 , -1.1486939724864641e+01 , 7.7808400000000004e+00 , -9.8135899999999998e-01 , 5.3609299999999999e-02 , 1.8455400000000000e-01 --1.0521087604897520e+01 , -1.1691074054220934e+01 , 8.2153103999999999e+00 , -9.1461800000000004e-01 , -3.5367999999999999e-01 , 1.9592100000000001e-01 --1.0591807267407054e+01 , -1.1665191963607203e+01 , 8.5764296000000009e+00 , 8.1859099999999996e-01 , 5.0409400000000004e-01 , -2.7531499999999998e-01 --1.0067716032601432e+01 , -1.1001880236024041e+01 , 8.6761864000000006e+00 , -1.3756099999999999e-01 , -7.1385399999999999e-01 , 6.8664999999999998e-01 --9.8527066190813137e+00 , -1.0675848736202362e+01 , 8.8962088000000001e+00 , 2.9303099999999999e-02 , -9.0024999999999999e-01 , 4.3438700000000002e-01 --9.8038969928330637e+00 , -1.0527686377576744e+01 , 9.1888544000000003e+00 , 3.6253899999999999e-02 , -9.2988099999999996e-01 , 3.6607000000000001e-01 --9.8589557851727410e+00 , -1.0489546206881577e+01 , 9.5350600000000014e+00 , 4.2752400000000003e-02 , -9.5324299999999995e-01 , 2.9916399999999999e-01 --9.6541968170162384e+00 , -1.0179430002483091e+01 , 9.7424047999999992e+00 , 1.4160200000000001e-01 , -9.7012100000000001e-01 , 1.9701199999999999e-01 --9.9637140135937940e+00 , -1.0402013630213904e+01 , 1.0237008000000001e+01 , -8.5439500000000002e-02 , 9.8311599999999999e-01 , -1.6181400000000001e-01 --9.9938318789324523e+00 , -1.0333530421658795e+01 , 1.0581060800000001e+01 , -8.6835999999999997e-02 , 9.8862399999999995e-01 , -1.2281100000000000e-01 --9.8854724890535035e+00 , -1.0123167889016644e+01 , 1.0841903200000001e+01 , 1.0994700000000000e-01 , -9.8951100000000003e-01 , 9.3703800000000004e-02 --1.0991112345110574e+01 , -1.1137553597886566e+01 , 1.1895475200000000e+01 , -9.9574300000000004e-01 , 4.6852300000000000e-02 , -7.9372700000000004e-02 --1.1009879274777662e+01 , -1.1046543876038454e+01 , 1.2269469600000001e+01 , 9.9730700000000005e-01 , -5.1216800000000000e-02 , 5.2489700000000000e-02 --1.1051215322373290e+01 , -1.0977161859934768e+01 , 1.2663016000000001e+01 , 9.9733499999999997e-01 , -5.1372500000000001e-02 , 5.1813900000000003e-02 --1.1087396530468588e+01 , -1.0900230041928662e+01 , 1.3058111999999999e+01 , -9.8184499999999997e-01 , 1.8509999999999999e-01 , 4.1447699999999997e-02 --1.1112451937013992e+01 , -1.0810654230311661e+01 , 1.3449984000000001e+01 , 9.8982400000000004e-01 , -1.3546800000000001e-01 , -4.3563299999999999e-02 --1.0481817035687934e+01 , -1.0087161531086775e+01 , 1.3328304000000001e+01 , -9.6020799999999995e-01 , 2.1813600000000000e-01 , 1.7440500000000000e-01 --1.0933289709595439e+01 , -1.0408291728884871e+01 , 1.4062336000000000e+01 , 1.2083300000000000e-01 , -8.6429500000000004e-01 , 4.8825600000000002e-01 --1.0609368466881488e+01 , -9.9845543768418796e+00 , 1.4168623999999999e+01 , -1.7417999999999999e-02 , -9.3367000000000000e-01 , 3.5770999999999997e-01 --1.0303980577291389e+01 , -9.5829849155868327e+00 , 1.4276992000000000e+01 , -8.4616999999999998e-02 , 9.1786299999999998e-01 , -3.8777299999999998e-01 --1.0334255581485840e+01 , -9.4980220293303859e+00 , 1.4676456000000000e+01 , -7.8318899999999997e-02 , 9.1211500000000001e-01 , -4.0238400000000002e-01 --1.0175130672527720e+01 , -9.2365675067815687e+00 , 1.4906608000000000e+01 , -4.7976499999999998e-02 , 9.5064800000000005e-01 , -3.0654100000000001e-01 --1.0333534780467534e+01 , -9.2649635757311817e+00 , 1.5438048000000002e+01 , 4.7512499999999999e-02 , -8.7878599999999996e-01 , 4.7484599999999999e-01 --1.0209854100109144e+01 , -9.0349094517596154e+00 , 1.5705120000000001e+01 , 5.3884000000000001e-02 , -8.5221499999999994e-01 , 5.2040900000000001e-01 --9.9662321803577747e+00 , -8.6982178317975833e+00 , 1.5847080000000002e+01 , 4.2265600000000000e-02 , -8.3340700000000001e-01 , 5.5104100000000000e-01 --1.0692355562746206e+01 , -9.2212917311064899e+00 , 1.7006575999999999e+01 , -5.1378899999999998e-02 , 9.9855700000000003e-01 , -1.5619700000000000e-02 --1.0528071704089019e+01 , -8.9491667854244277e+00 , 1.7248584000000001e+01 , -5.1378899999999998e-02 , 9.9855700000000003e-01 , -1.5619700000000000e-02 --2.4937342846924846e+00 , -1.8208595903341500e+00 , 8.8029104000000018e+00 , -4.4121300000000002e-01 , -7.1551399999999998e-01 , 5.4163700000000004e-01 --2.4558433407420939e+00 , -1.7382401333415722e+00 , 8.9259632000000000e+00 , -6.8043399999999998e-01 , -5.7969400000000004e-01 , 4.4829000000000002e-01 --2.5384213635808850e+00 , -1.7554145997669428e+00 , 9.1972887999999990e+00 , -4.7359600000000002e-01 , -8.7434000000000001e-01 , 1.0600200000000000e-01 --2.6058277876088223e+00 , -1.7572891552251697e+00 , 9.4581623999999991e+00 , 8.5987700000000000e-01 , 5.0409999999999999e-01 , 8.0588000000000007e-02 --2.6516825674828777e+00 , -1.7384320061431406e+00 , 9.7000768000000015e+00 , 7.9235199999999995e-01 , 6.0596899999999998e-01 , -7.0565299999999997e-02 --2.5700183631890212e+00 , -1.6155079359413640e+00 , 9.7795535999999998e+00 , -4.8714099999999999e-01 , 9.4291000000000000e-02 , -8.6821800000000005e-01 --2.0977972742003201e+00 , -1.1852981346180504e+00 , 9.3225048000000008e+00 , -8.3052800000000004e-01 , 4.9583300000000002e-01 , -2.5371899999999997e-01 --1.8383623113204686e+00 , -9.3001734439737938e-01 , 9.1323200000000000e+00 , 5.2208600000000005e-01 , -2.3412200000000000e-01 , -8.2013000000000003e-01 --1.8202174133809428e+00 , -8.6442094902534539e-01 , 9.2773064000000005e+00 , -4.6828599999999998e-01 , 2.3281299999999999e-01 , 8.5235300000000003e-01 --1.7255328649143835e+00 , -7.3971705783696340e-01 , 9.3103888000000001e+00 , -9.1149599999999997e-01 , -3.3848200000000001e-01 , 2.3367700000000000e-01 --1.8151159247665980e+00 , -7.5259190413486188e-01 , 9.6226488000000003e+00 , -7.2968800000000000e-01 , -6.5342800000000001e-01 , 2.0146400000000000e-01 --1.7378929112682657e+00 , -6.4026704080142016e-01 , 9.6854128000000017e+00 , 8.6491100000000001e-02 , 1.3489599999999999e-01 , 9.8707800000000001e-01 --1.7414501392702255e+00 , -5.8539435244608207e-01 , 9.8779480000000000e+00 , -9.4780100000000000e-01 , -2.5466800000000001e-01 , 1.9188000000000000e-01 --2.0491948188791307e+00 , -7.4223046238895174e-01 , 1.0583348800000001e+01 , -9.6753800000000001e-01 , -2.0027100000000000e-01 , -1.5414700000000001e-01 --1.1847174050631812e+00 , -8.4783342102972004e-02 , 9.3140184000000001e+00 , -7.2124800000000000e-01 , 5.3740800000000000e-01 , 4.3702999999999997e-01 --1.0461663536843089e+00 , 6.1652673473146180e-02 , 9.2482591999999997e+00 , 5.9634200000000004e-01 , -6.8730999999999998e-01 , -4.1470499999999999e-01 --1.0621988239051854e+00 , 1.0514649402982656e-01 , 9.4554584000000013e+00 , -6.1032799999999998e-01 , 7.0573900000000001e-01 , 3.5976700000000000e-01 --9.8566211277888494e-01 , 2.1002089695775372e-01 , 9.4969128000000005e+00 , 4.8426399999999997e-01 , -7.8801299999999996e-01 , -3.8016499999999998e-01 --7.7965972242876536e-01 , 3.9574831706219382e-01 , 9.2874255999999988e+00 , 2.3073500000000000e-01 , -8.4983500000000001e-01 , -4.7385800000000000e-01 --6.8619793675705054e-01 , 5.0816238454012530e-01 , 9.2855951999999995e+00 , 8.3952000000000004e-01 , -4.9947300000000000e-02 , -5.4102799999999995e-01 --8.8611739777664766e-01 , 4.4695908785614313e-01 , 9.8772616000000006e+00 , 5.2306799999999997e-03 , -4.3915700000000002e-01 , 8.9839500000000005e-01 --6.4757982832747540e-01 , 6.4394017430149675e-01 , 9.5830143999999997e+00 , 9.3974100000000005e-01 , -2.0249199999999998e-02 , -3.4128599999999998e-01 --7.5686307560815358e-01 , 6.4459683417561919e-01 , 1.0016195200000000e+01 , -5.0342299999999995e-01 , -6.7754800000000004e-02 , 8.6137900000000001e-01 --5.5695871392017660e-01 , 8.1575368163087081e-01 , 9.7858039999999988e+00 , 9.6311300000000000e-01 , -2.2646900000000000e-01 , 1.4534500000000000e-01 --6.1912005935831216e-01 , 8.4794313468820759e-01 , 1.0137854400000000e+01 , -9.6931699999999998e-01 , 4.5964300000000000e-02 , -2.4147900000000000e-01 -1.1648432875875048e-01 , 1.2735726183871194e+00 , 8.6180295999999998e+00 , -1.8660299999999999e-01 , -7.3464500000000002e-02 , 9.7968500000000003e-01 -1.8914049584341441e-01 , 1.3610512387495133e+00 , 8.6197559999999989e+00 , 2.3113000000000000e-01 , 4.1465299999999999e-01 , -8.8013799999999998e-01 -2.1963927065053612e-01 , 1.4306682757178448e+00 , 8.7240992000000013e+00 , -4.8929899999999998e-01 , -6.6600199999999998e-01 , 5.6305200000000000e-01 -2.2390622070257948e-01 , 1.4902351188602423e+00 , 8.9047264000000013e+00 , -8.1216699999999997e-01 , -4.1470600000000002e-01 , 4.1037099999999999e-01 -2.4131059471300120e-01 , 1.5582282744725255e+00 , 9.0561816000000004e+00 , -6.4257600000000004e-01 , -5.6227099999999997e-01 , 5.2052699999999996e-01 --2.0914590437653846e-01 , 1.4615276896661769e+00 , 1.0530236000000000e+01 , -6.1124400000000001e-01 , 7.9097899999999999e-01 , -2.7056400000000001e-02 --8.5469399868363860e-01 , 1.3348252526077284e+00 , 1.2672791999999999e+01 , -6.5873300000000001e-01 , 4.4692100000000001e-01 , -6.0525399999999996e-01 --1.7491312525436520e-01 , 1.6402970909300962e+00 , 1.0982147200000000e+01 , 6.3105500000000003e-01 , 7.5688999999999995e-01 , 1.6996200000000000e-01 -3.8092249814901891e-02 , 1.7874992326851351e+00 , 1.0614569599999999e+01 , 3.5978399999999999e-01 , -8.2899500000000004e-01 , -4.2816199999999999e-01 -1.0429996598163838e-01 , 1.8916604039487994e+00 , 1.0697707200000000e+01 , 2.5033800000000000e-01 , -9.2330000000000001e-01 , -2.9128799999999999e-01 -3.1884029844821837e-01 , 2.0235428160236890e+00 , 1.0280771200000000e+01 , 7.0807399999999998e-01 , 4.0715699999999999e-01 , 5.7693499999999998e-01 -4.4402016518899523e-01 , 2.1317155083196795e+00 , 1.0138166400000001e+01 , 5.6296100000000004e-01 , -4.4289799999999997e-02 , 8.2529600000000003e-01 -5.0700860374018486e-01 , 2.2310802995865089e+00 , 1.0212619999999999e+01 , -4.6450599999999997e-01 , -8.3091400000000004e-01 , 3.0629600000000001e-01 -4.8238613299397248e-01 , 2.3274195813752034e+00 , 1.0627580000000000e+01 , -5.7025400000000004e-01 , 6.9232099999999996e-01 , 4.4215599999999999e-01 -5.7239649406970483e-01 , 2.4332509815521202e+00 , 1.0618688000000001e+01 , -8.3496000000000004e-01 , 5.4773700000000003e-01 , 5.3162700000000000e-02 -5.7099875074262174e-01 , 2.5456280728219602e+00 , 1.0991694400000002e+01 , -9.5647200000000002e-02 , -6.2730699999999995e-01 , 7.7287600000000001e-01 -6.4978993290532272e-01 , 2.6569698468401861e+00 , 1.1049934400000000e+01 , -9.5647200000000002e-02 , -6.2730699999999995e-01 , 7.7287600000000001e-01 -5.0275762088252418e-01 , 2.8183548716346967e+00 , 1.2162131200000001e+01 , -8.8828900000000000e-01 , -4.3229600000000001e-01 , 1.5512500000000001e-01 -9.4817557270671537e-01 , 2.8431193998430553e+00 , 1.0477518400000001e+01 , -2.3297399999999999e-01 , -3.3016200000000002e-02 , 9.7192199999999995e-01 -1.3431263479652169e+00 , 2.8266797475309726e+00 , 8.8569384000000007e+00 , -6.2021800000000005e-01 , 5.3087700000000004e-01 , 5.7749399999999995e-01 -1.3753222141334094e+00 , 2.9228724892461928e+00 , 9.0461144000000004e+00 , -7.9657800000000001e-01 , -9.9237800000000001e-02 , -5.9633599999999998e-01 -1.4505982800225130e+00 , 3.0004001259935213e+00 , 8.9990024000000002e+00 , -2.2563400000000000e-01 , -5.2029800000000004e-01 , 8.2363799999999998e-01 -1.4803369177698817e+00 , 3.1084582494460093e+00 , 9.2359976000000010e+00 , 5.7280299999999995e-01 , -8.1560600000000005e-01 , 8.1753199999999998e-02 -1.5013386501204078e+00 , 3.2350027137871917e+00 , 9.5734464000000017e+00 , -3.4065400000000001e-01 , 6.3910900000000004e-01 , -6.8956200000000001e-01 -1.6734927112631977e+00 , 3.2204079217572295e+00 , 8.8368040000000008e+00 , -8.7005999999999994e-01 , 4.5088400000000001e-01 , 1.9924400000000000e-01 -1.1720857207151172e+00 , 3.8910170847908798e-01 , 1.1698574399999999e+00 , -6.3833600000000004e-02 , 1.8484800000000001e-01 , 9.8069200000000001e-01 -1.1126048696785578e+00 , 3.2080326592022246e-01 , 1.1660479200000000e+00 , -6.9091399999999997e-02 , 2.1084300000000000e-01 , 9.7507500000000003e-01 -1.0666540028078915e+00 , 2.7318096247074330e-01 , 1.1834013600000000e+00 , -7.4712399999999998e-02 , 1.8058900000000000e-01 , 9.8071699999999995e-01 -1.0008907850408750e+00 , 1.9640379634143157e-01 , 1.1782533600000000e+00 , -8.5150400000000001e-02 , 1.7453199999999999e-01 , 9.8096300000000003e-01 -9.4411715172927368e-01 , 1.3490432161229360e-01 , 1.1876830400000000e+00 , -7.8560199999999997e-02 , 1.4219000000000001e-01 , 9.8671699999999996e-01 -8.7665670979785681e-01 , 5.8228795119820376e-02 , 1.1879763200000000e+00 , -8.2807199999999997e-02 , 1.3183500000000001e-01 , 9.8780699999999999e-01 -8.0312338995445409e-01 , -2.5132087999348851e-02 , 1.1854096000000001e+00 , -7.5400099999999998e-02 , 1.5510499999999999e-01 , 9.8501600000000000e-01 -7.3860913880303447e-01 , -9.4355347558340519e-02 , 1.1970180799999999e+00 , -8.6220199999999997e-02 , 1.5933000000000000e-01 , 9.8345300000000002e-01 -6.5376368176275679e-01 , -1.9399530302574552e-01 , 1.1902788799999999e+00 , -8.4525299999999998e-02 , 1.7618300000000001e-01 , 9.8072199999999998e-01 -1.9811651349317572e-01 , -7.0643795677384302e-01 , 1.2058466399999999e+00 , -8.7613800000000006e-02 , 1.9434999999999999e-01 , 9.7701199999999999e-01 -1.0510477072292823e-01 , -8.0620524085736012e-01 , 1.2230804800000001e+00 , -1.0727500000000000e-01 , 1.7452300000000001e-01 , 9.7879200000000000e-01 --2.7703745311713490e-02 , -9.5929788006864447e-01 , 1.2148852799999998e+00 , -6.2004600000000000e-02 , 2.6081799999999999e-01 , 9.6339500000000000e-01 --1.0512700544938847e-01 , -1.0362420683355555e+00 , 1.2539320799999998e+00 , -3.5150399999999998e-02 , 2.8772500000000001e-01 , 9.5706800000000003e-01 --2.2950446895009868e-01 , -1.1741808476962903e+00 , 1.2647688799999999e+00 , -7.1935499999999999e-02 , 2.5493199999999999e-01 , 9.6427900000000000e-01 --3.5458192458173832e-01 , -1.3119643998150945e+00 , 1.2814764800000000e+00 , -5.9060799999999997e-02 , 2.4571899999999999e-01 , 9.6753999999999996e-01 --4.8741225690664658e-01 , -1.4574636102323830e+00 , 1.3004637600000000e+00 , 8.1414700000000007e-02 , -2.2169900000000001e-01 , -9.7171099999999999e-01 --6.4606918110070533e-01 , -1.6331245998509112e+00 , 1.3117373600000000e+00 , -8.1414299999999995e-02 , 2.2725300000000001e-01 , 9.7042700000000004e-01 --8.0568545586555196e-01 , -1.8092877936533425e+00 , 1.3309087200000000e+00 , -6.7444000000000004e-02 , 2.2761500000000001e-01 , 9.7141299999999997e-01 --9.7331686613215229e-01 , -1.9927104550952452e+00 , 1.3544844800000000e+00 , -6.1248799999999999e-02 , 2.2768600000000000e-01 , 9.7180699999999998e-01 --1.1672576427948576e+00 , -2.2065307087917247e+00 , 1.3743963200000000e+00 , -7.0799600000000004e-02 , 2.2322200000000000e-01 , 9.7219299999999997e-01 --1.3755840760505471e+00 , -2.4359160160399496e+00 , 1.3982851200000002e+00 , 8.1883399999999995e-02 , -2.2053800000000001e-01 , -9.7193499999999999e-01 --1.6178571799593104e+00 , -2.7047175866469928e+00 , 1.4195791200000001e+00 , -9.5947400000000002e-02 , 2.6086100000000001e-01 , 9.6059600000000001e-01 --1.8810284797437360e+00 , -2.9961133677802421e+00 , 1.4455333600000000e+00 , -5.9276099999999998e-02 , 6.1157399999999995e-01 , 7.8896400000000000e-01 --2.0121167015631602e+00 , -3.1197923218886174e+00 , 1.5309901600000000e+00 , 1.8157799999999999e-01 , 8.8137900000000002e-01 , 4.3611899999999998e-01 --2.0026169026981648e+00 , -3.0693931757489787e+00 , 1.6671937600000000e+00 , -3.0674200000000001e-01 , -8.6848400000000003e-01 , -3.8941700000000001e-01 --2.1593704343053162e+00 , -3.2217262137278935e+00 , 1.7525486400000001e+00 , 5.4989500000000002e-01 , 6.6954999999999998e-01 , 4.9931799999999998e-01 --2.2121120100505101e+00 , -3.2463185568434634e+00 , 1.8722079199999999e+00 , -8.0227499999999996e-01 , -5.3086100000000003e-01 , -2.7302199999999999e-01 --2.2316289610735547e+00 , -3.2291366828954891e+00 , 2.0007334745600001e+00 , -8.9575000000000005e-01 , -4.4246000000000002e-01 , -4.3145599999999999e-02 --2.2354071134433964e+00 , -3.1951604227618269e+00 , 2.1317045600000002e+00 , -9.5827499999999999e-01 , -2.8545799999999999e-01 , 1.4892700000000000e-02 --2.2505706964977374e+00 , -3.1751647800726284e+00 , 2.2593073600000002e+00 , -9.6532700000000005e-01 , -2.6026700000000003e-01 , 2.0110900000000001e-02 --2.2645686056953584e+00 , -3.1532243882325730e+00 , 2.3863215200000001e+00 , -9.6392999999999995e-01 , -2.6570500000000002e-01 , 1.5471000000000000e-02 --2.2763768870220566e+00 , -3.1293651350148055e+00 , 2.5127720000000000e+00 , -9.6998899999999999e-01 , -2.4255800000000000e-01 , 1.6963499999999999e-02 --2.2807314651371140e+00 , -3.0972566236223438e+00 , 2.6395729600000002e+00 , -9.6835099999999996e-01 , -2.4941099999999999e-01 , 9.5560500000000000e-03 --2.2966013713874620e+00 , -3.0778073976448095e+00 , 2.7643188800000003e+00 , -9.6972000000000003e-01 , -2.4403800000000000e-01 , 9.3892200000000002e-03 --2.3039104325808584e+00 , -3.0491841241466373e+00 , 2.8890315200000001e+00 , -9.6610300000000005e-01 , -2.5807799999999997e-01 , 6.3356200000000001e-03 --2.3165544980926311e+00 , -3.0278500510959043e+00 , 3.0133385600000002e+00 , -9.6858599999999995e-01 , -2.4814000000000000e-01 , 1.6381900000000001e-02 --2.3279886827507585e+00 , -3.0035329498656216e+00 , 3.1368552000000003e+00 , -9.6795399999999998e-01 , -2.5082100000000002e-01 , 1.2413000000000000e-02 --2.3383383152222308e+00 , -2.9782319692959778e+00 , 3.2601887999999999e+00 , -9.7136800000000001e-01 , -2.3705100000000001e-01 , 1.5831899999999999e-02 --2.3465466591417830e+00 , -2.9520300209924955e+00 , 3.3832624000000000e+00 , 9.7286099999999998e-01 , 2.3033799999999999e-01 , -2.2065299999999999e-02 --2.3535553149001007e+00 , -2.9228471106705038e+00 , 3.5055456000000000e+00 , -9.7479300000000002e-01 , -2.2181500000000001e-01 , 2.4020500000000000e-02 --2.3725502122130777e+00 , -2.9087640914406148e+00 , 3.6293160000000002e+00 , -9.7530399999999995e-01 , -2.2046399999999999e-01 , 1.3312700000000000e-02 --2.3697196769900550e+00 , -2.8686517751680380e+00 , 3.7499663999999999e+00 , -9.7155599999999998e-01 , -2.3532900000000001e-01 , -2.6457000000000001e-02 --2.3855038927865362e+00 , -2.8515621602487329e+00 , 3.8736015999999998e+00 , -9.2276599999999998e-01 , -3.8351499999999999e-01 , -3.7677400000000000e-02 --2.4143941872981545e+00 , -2.8471890037511969e+00 , 3.9998160000000000e+00 , -8.8670700000000002e-01 , -4.6010400000000001e-01 , -4.5336899999999999e-02 --1.0520557254939519e+01 , -1.1503142572385343e+01 , 5.8545624000000007e+00 , -9.0702199999999997e-02 , 9.7912699999999997e-01 , -1.8189100000000000e-01 --1.0590673587363622e+01 , -1.1481807251263019e+01 , 6.1930616000000001e+00 , -9.0702099999999994e-02 , 9.7912699999999997e-01 , -1.8189100000000000e-01 --1.0620373381015677e+01 , -1.1418003869651814e+01 , 6.5243536000000004e+00 , 1.3842900000000000e-01 , -9.8399199999999998e-01 , 1.1223500000000000e-01 --1.0653553827185707e+01 , -1.1356922240793720e+01 , 6.8574968000000007e+00 , -9.7014900000000004e-01 , -2.3751400000000000e-01 , 4.8979399999999999e-02 --1.0683440956459304e+01 , -1.1291671220634774e+01 , 7.1909000000000001e+00 , -9.5781000000000005e-01 , -2.7860400000000002e-01 , 7.0565299999999997e-02 --1.0709178030222896e+01 , -1.1222289370139942e+01 , 7.5245008000000002e+00 , -9.4816400000000001e-01 , -3.1674000000000002e-01 , 2.5687700000000001e-02 --1.0737270428017336e+01 , -1.1155422380068613e+01 , 7.8607848000000002e+00 , -9.6521500000000005e-01 , -2.6076800000000000e-01 , -1.8957200000000000e-02 --1.0762267860375204e+01 , -1.1083407500225112e+01 , 8.1971312000000012e+00 , -8.9451800000000004e-01 , -4.2515300000000000e-01 , 1.3814000000000001e-01 --1.0796482735008270e+01 , -1.1021410738854831e+01 , 8.5396864000000008e+00 , -9.4317200000000001e-01 , -3.0257099999999998e-01 , 1.3739100000000001e-01 --1.0784726081160265e+01 , -1.0911893600959166e+01 , 8.8643847999999998e+00 , 1.7050500000000000e-02 , -9.0997200000000000e-01 , 4.1432000000000002e-01 --1.0768533567607250e+01 , -1.0797561617433839e+01 , 9.1876479999999994e+00 , -1.4562700000000000e-02 , -9.2890200000000001e-01 , 3.7003999999999998e-01 --1.0804615500417555e+01 , -1.0735253578433785e+01 , 9.5366512000000014e+00 , -4.9763300000000003e-02 , 9.5705700000000005e-01 , -2.8559600000000002e-01 --1.0571093936615354e+01 , -1.0407888907440208e+01 , 9.7514216000000005e+00 , -9.8786700000000005e-02 , 9.8195800000000000e-01 , -1.6124600000000000e-01 --1.0911278011099595e+01 , -1.0642514745749500e+01 , 1.0264027200000001e+01 , 4.6778100000000003e-02 , -9.9012500000000003e-01 , 1.3215199999999999e-01 --1.0940854586492396e+01 , -1.0570420009374407e+01 , 1.0620872000000000e+01 , -2.8958399999999999e-02 , 9.9495999999999996e-01 , -9.6003300000000000e-02 --1.0973096410072085e+01 , -1.0499311229561389e+01 , 1.0982729600000001e+01 , -1.2842700000000001e-01 , 9.9133300000000002e-01 , -2.7649900000000002e-02 --1.1055546618529885e+01 , -1.0476284556912796e+01 , 1.1379822400000000e+01 , 4.9102099999999999e-01 , -8.7095900000000004e-01 , -1.8126300000000001e-02 --1.1084482739308568e+01 , -1.0399497038645558e+01 , 1.1749563200000001e+01 , 9.9523799999999996e-01 , -5.6354899999999999e-02 , 7.9536499999999996e-02 --1.1123132866045237e+01 , -1.0330801496211718e+01 , 1.2129662400000001e+01 , 9.9603500000000000e-01 , -5.3825100000000001e-02 , 7.0840100000000003e-02 --1.1148750190961877e+01 , -1.0249446795414070e+01 , 1.2507016000000000e+01 , -9.8166299999999995e-01 , 1.4427100000000001e-01 , 1.2459600000000000e-01 --1.1184103575636497e+01 , -1.0173981343987020e+01 , 1.2895040000000002e+01 , -9.8184499999999997e-01 , 1.8509999999999999e-01 , 4.1447699999999997e-02 --1.1214295226232871e+01 , -1.0092047068504126e+01 , 1.3284727999999999e+01 , -9.6020799999999995e-01 , 2.1813700000000000e-01 , 1.7440500000000000e-01 --1.1231224731133748e+01 , -9.9985850235148863e+00 , 1.3671192000000001e+01 , -9.9088100000000001e-01 , 2.9187800000000002e-03 , 1.3471200000000000e-01 --1.1223950862154943e+01 , -9.8805641693224189e+00 , 1.4042368000000000e+01 , -3.4364899999999997e-02 , -9.4198300000000001e-01 , 3.3389600000000003e-01 --1.1251535846353372e+01 , -9.7915966321971712e+00 , 1.4446512000000000e+01 , 1.0846700000000001e-02 , -8.8927800000000001e-01 , 4.5723900000000001e-01 --1.1207410770538127e+01 , -9.6381230798036093e+00 , 1.4796056000000000e+01 , 4.7279399999999999e-02 , -8.8159299999999996e-01 , 4.6963700000000003e-01 --1.1204364123245963e+01 , -9.5196645199428822e+00 , 1.5184496000000001e+01 , -2.9894100000000001e-03 , -9.1010899999999995e-01 , 4.1435899999999998e-01 --1.1240507510717780e+01 , -9.4345435503225730e+00 , 1.5615056000000001e+01 , 5.8392199999999998e-02 , -8.3833500000000005e-01 , 5.4201900000000003e-01 --1.0943673726153891e+01 , -9.0603985915746019e+00 , 1.5738192000000000e+01 , 4.7459500000000002e-02 , -8.6463699999999999e-01 , 5.0015100000000001e-01 --1.0773508335849936e+01 , -8.7973958017193183e+00 , 1.5973128000000001e+01 , -4.1605600000000000e-02 , 9.8308399999999996e-01 , -1.7836900000000000e-01 --1.1571660221470724e+01 , -9.3472844655855791e+00 , 1.7179008000000003e+01 , 1.8316099999999999e-01 , -9.8282400000000003e-01 , -2.2556699999999999e-02 --2.6953918270859996e+00 , -1.7132505427578057e+00 , 8.9092400000000005e+00 , -4.8248900000000000e-01 , -8.2141200000000003e-01 , 3.0411500000000002e-01 --2.7489013086885743e+00 , -1.5996242753014474e+00 , 9.5039744000000006e+00 , -4.2628199999999999e-01 , -8.5578500000000002e-01 , 2.9311399999999999e-01 --2.7118596729151792e+00 , -1.5159035987211005e+00 , 9.6428456000000011e+00 , 3.6916800000000000e-02 , -8.2067500000000004e-01 , 5.7020199999999999e-01 --2.6155138702911636e+00 , -1.3884541386983345e+00 , 9.7057032000000003e+00 , 3.6916800000000000e-02 , -8.2067500000000004e-01 , 5.7020199999999999e-01 --1.9797765442162496e+00 , -8.6204427961596819e-01 , 9.0389695999999997e+00 , -4.2825900000000000e-01 , 4.7209400000000001e-01 , 7.7053300000000002e-01 --1.8825345580285795e+00 , -7.4194733622223730e-01 , 9.0760767999999992e+00 , -7.6298500000000002e-01 , -6.4468000000000003e-01 , 4.7345199999999997e-02 --1.8078137979738433e+00 , -6.3758960613633286e-01 , 9.1409416000000014e+00 , -6.5827500000000005e-01 , -1.5817999999999999e-02 , 7.5261100000000003e-01 --2.1693285372519684e+00 , -8.4074671385395616e-01 , 9.8420887999999991e+00 , -1.5982099999999999e-01 , 1.3124600000000000e-01 , 9.7838199999999997e-01 --1.9040125509298216e+00 , -6.0065797419899747e-01 , 9.6357424000000016e+00 , -2.8831000000000001e-01 , 1.7732100000000001e-01 , 9.4097500000000001e-01 --1.9024746757421322e+00 , -5.4427493871573285e-01 , 9.8210808000000007e+00 , -2.0489599999999999e-01 , 5.9041900000000003e-01 , 7.8065600000000002e-01 --1.6481331087627740e+00 , -3.1778637770991747e-01 , 9.6081199999999995e+00 , 6.9352999999999998e-01 , -5.0971900000000003e-01 , -5.0911899999999999e-01 --1.5975436059033052e+00 , -2.2965340324546535e-01 , 9.7137944000000012e+00 , 9.7213300000000002e-01 , -2.2000400000000001e-01 , -8.0968899999999996e-02 --1.2231036494553780e+00 , 6.5844211016975684e-02 , 9.2734687999999998e+00 , -3.8573200000000002e-01 , 6.5010699999999999e-01 , 6.5465399999999996e-01 --1.1258775958581695e+00 , 1.7952856422634533e-01 , 9.2840039999999995e+00 , 4.8579299999999997e-01 , -6.7219600000000002e-01 , -5.5871099999999996e-01 --9.4968855552843934e-01 , 3.3968519264792785e-01 , 9.1520696000000008e+00 , 4.1913200000000000e-01 , -7.4947799999999998e-01 , -5.1245600000000002e-01 --8.4941583709780888e-01 , 4.5200278040822228e-01 , 9.1459335999999993e+00 , 3.4160000000000001e-01 , -8.3734100000000000e-01 , -4.2681200000000002e-01 --8.7460045886611937e-02 , 9.4341932090101133e-01 , 7.8844864000000001e+00 , -9.0641200000000000e-01 , -4.1214200000000001e-01 , 9.2497700000000002e-02 --1.0271798779352381e+00 , 4.6100565548517558e-01 , 9.8589055999999999e+00 , 5.0345099999999998e-01 , 3.9404600000000001e-01 , -7.6893699999999998e-01 --8.5264753293466589e-01 , 6.1650968717968757e-01 , 9.7140647999999992e+00 , -3.7099300000000002e-01 , -8.6171699999999996e-01 , -3.4613400000000000e-01 --2.0071518214947748e-01 , 1.0180597989292324e+00 , 8.5680991999999989e+00 , -6.5742500000000004e-01 , 6.9492600000000004e-01 , 2.9132400000000003e-01 --6.0907627979718937e-01 , 8.6215583337521218e-01 , 9.6097216000000003e+00 , -6.6644999999999999e-01 , 2.7650300000000000e-01 , 6.9238100000000002e-01 --5.4374154305985778e-01 , 9.5481436339600356e-01 , 9.6724752000000009e+00 , -9.1885799999999995e-01 , 4.2276700000000000e-04 , 3.9458799999999999e-01 --5.8846089253915679e-01 , 9.9654772895515720e-01 , 9.9860247999999991e+00 , -9.3153300000000006e-01 , 3.5368300000000003e-01 , -8.4582800000000000e-02 -1.0004248756184309e-01 , 1.3673510539448515e+00 , 8.5951184000000005e+00 , -3.4083900000000000e-01 , -5.6906500000000004e-01 , 7.4832699999999996e-01 -9.6628869920023286e-02 , 1.4197877965391226e+00 , 8.7861456000000011e+00 , -2.9737200000000003e-01 , -7.4623499999999998e-01 , 5.9557000000000004e-01 -1.7697046408811157e-01 , 1.5089283230335728e+00 , 8.7766711999999991e+00 , -3.4902300000000003e-01 , -8.4599700000000000e-01 , 4.0307900000000002e-01 -1.7240342531956987e-01 , 1.5651705321960891e+00 , 8.9863351999999992e+00 , 8.4274800000000005e-01 , 4.8440899999999998e-01 , -2.3478399999999999e-01 -1.1413577234777672e-01 , 1.6071527506569252e+00 , 9.3509279999999997e+00 , 3.4010600000000002e-01 , 1.7694199999999999e-01 , -9.2359100000000005e-01 --1.5303471816617531e-01 , 1.5900553373408788e+00 , 1.0321092000000000e+01 , 3.3848099999999998e-01 , -7.7059200000000005e-01 , 5.4001800000000000e-01 --8.6390056074516419e-01 , 1.4687112614188251e+00 , 1.2639719999999999e+01 , 7.1005300000000005e-01 , -4.0553499999999998e-01 , 5.7564499999999996e-01 --9.5440202589924805e-02 , 1.7682727807432728e+00 , 1.0701461600000000e+01 , -3.7174800000000002e-01 , 8.4165599999999996e-01 , 3.9168599999999998e-01 -7.8730298195708981e-02 , 1.8948857472915752e+00 , 1.0460556000000000e+01 , -3.9899400000000002e-01 , 6.4788299999999999e-01 , 6.4888400000000002e-01 -6.8454410606491711e-02 , 1.9809133888779640e+00 , 1.0790496000000001e+01 , -2.5033699999999998e-01 , 9.2330000000000001e-01 , 2.9128799999999999e-01 -3.1709570104279794e-01 , 2.1103575324160899e+00 , 1.0273855200000000e+01 , -6.7998099999999995e-01 , -8.5791500000000007e-02 , -7.2819400000000001e-01 -4.3196747423553727e-01 , 2.2130025369310169e+00 , 1.0180681600000000e+01 , 5.7780100000000001e-01 , -6.0663399999999999e-02 , 8.1391999999999998e-01 -3.8939774052948395e-01 , 2.3053790157738248e+00 , 1.0656450400000001e+01 , -5.7025400000000004e-01 , 6.9232099999999996e-01 , 4.4215599999999999e-01 -4.8785001764262792e-01 , 2.4093498380762912e+00 , 1.0629587200000000e+01 , -8.3496000000000004e-01 , 5.4773600000000000e-01 , 5.3162300000000003e-02 -5.7873717458036311e-01 , 2.5128451035409163e+00 , 1.0630356800000001e+01 , -9.3261499999999997e-01 , 3.0032999999999999e-01 , 2.0008000000000001e-01 -5.6231976694257568e-01 , 2.6283322420376902e+00 , 1.1084129600000001e+01 , -9.5647200000000002e-02 , -6.2730699999999995e-01 , 7.7287600000000001e-01 -4.8844369460601089e-01 , 2.7682001788150759e+00 , 1.1841655200000000e+01 , -5.7064099999999995e-01 , -6.6647800000000001e-01 , 4.7976799999999997e-01 -4.9445458657991859e-01 , 2.9122391482868055e+00 , 1.2304881600000000e+01 , -9.0559500000000004e-01 , -4.2376599999999998e-01 , 1.7908400000000001e-02 -1.2827449807475721e+00 , 2.8039694477198651e+00 , 8.9105296000000003e+00 , -2.9905500000000002e-01 , 7.9009900000000000e-01 , 5.3507899999999997e-01 -1.3561440012927748e+00 , 2.8800045008250019e+00 , 8.8872336000000018e+00 , -4.7930600000000001e-01 , 4.6351599999999998e-01 , 7.4526400000000004e-01 -1.4135195330731518e+00 , 2.9642115540688754e+00 , 8.9537832000000002e+00 , 1.1081500000000000e-01 , 3.5040600000000000e-01 , 9.3001900000000004e-01 -1.4664315610515213e+00 , 3.0533565154060067e+00 , 9.0491512000000007e+00 , 9.0879000000000001e-02 , 3.0330200000000002e-01 , -9.4855100000000003e-01 -1.5251555837937221e+00 , 3.1420666747620078e+00 , 9.1225231999999998e+00 , -5.4930000000000001e-01 , 8.2954799999999995e-01 , -1.0059200000000000e-01 -1.6122961039785537e+00 , 3.2070583296866717e+00 , 9.0104423999999987e+00 , 6.9153200000000004e-01 , 5.9630399999999995e-01 , 4.0768300000000002e-01 -1.7143444700984323e+00 , 3.2496149085444417e+00 , 8.7638584000000002e+00 , 7.6029999999999998e-01 , 6.4710400000000001e-01 , -5.6577299999999997e-02 -1.0335696883555356e+00 , 3.3572524545502280e-01 , 1.1547191999999999e+00 , -7.8074500000000005e-02 , 2.0637200000000000e-01 , 9.7535400000000005e-01 -9.8087280047380432e-01 , 2.8301081092727531e-01 , 1.1664493600000001e+00 , -7.7918699999999994e-02 , 2.0508499999999999e-01 , 9.7563800000000001e-01 -1.7374482357636811e-01 , -5.7474436004067231e-01 , 1.1849676000000000e+00 , -5.8005500000000002e-02 , 2.0962500000000001e-01 , 9.7606000000000004e-01 -6.8330021641656913e-02 , -6.8697947818800476e-01 , 1.1903776799999999e+00 , 1.0253800000000000e-01 , -1.8993800000000000e-01 , -9.7642700000000004e-01 --5.0464675044496587e-02 , -8.1330238898998308e-01 , 1.1915612000000000e+00 , -7.2211600000000001e-02 , 2.1072700000000000e-01 , 9.7487400000000002e-01 --1.6612804960294270e-01 , -9.3355744909072325e-01 , 1.2024437600000000e+00 , -4.8851899999999997e-02 , 2.6270500000000002e-01 , 9.6363900000000002e-01 --2.6948714851182975e-01 , -1.0378735081456116e+00 , 1.2265572000000000e+00 , -5.3837999999999997e-02 , 3.0570700000000001e-01 , 9.5060199999999995e-01 --3.9823111175813564e-01 , -1.1720177387463862e+00 , 1.2395135200000000e+00 , -5.1041299999999998e-02 , 2.6871499999999998e-01 , 9.6186700000000003e-01 --5.1680588942368111e-01 , -1.2911545141123768e+00 , 1.2658567199999999e+00 , -8.7381200000000006e-02 , 2.4913199999999999e-01 , 9.6451900000000002e-01 --6.8499737850665898e-01 , -1.4701914229803821e+00 , 1.2688987199999999e+00 , 9.4939999999999997e-02 , -2.3083699999999999e-01 , -9.6835000000000004e-01 --8.4919627124957842e-01 , -1.6418080130583790e+00 , 1.2832788000000002e+00 , 7.8852000000000005e-02 , -2.4029800000000001e-01 , -9.6749099999999999e-01 --1.0092805370999440e+00 , -1.8050881795137976e+00 , 1.3082866399999999e+00 , -6.1223699999999999e-02 , 2.3623400000000000e-01 , 9.6976499999999999e-01 --1.2026758142211236e+00 , -2.0067325522051833e+00 , 1.3255329599999999e+00 , -7.1104700000000007e-02 , 2.3310200000000000e-01 , 9.6984899999999996e-01 --1.4093230222220394e+00 , -2.2230436348575200e+00 , 1.3461717599999998e+00 , -8.8520500000000002e-02 , 2.2482600000000000e-01 , 9.7036999999999995e-01 --1.6456934690739731e+00 , -2.4691391185205420e+00 , 1.3655012000000000e+00 , 8.8904800000000006e-02 , -2.3073600000000000e-01 , -9.6894599999999997e-01 --1.9028637647483881e+00 , -2.7379998842069000e+00 , 1.3885808800000001e+00 , -7.2587600000000002e-02 , 2.6846700000000001e-01 , 9.6055000000000001e-01 --2.1953640589982939e+00 , -3.0445305266227578e+00 , 1.4121732800000000e+00 , 1.0610500000000000e-01 , 7.6526700000000003e-01 , 6.3490700000000000e-01 --2.2992478303875785e+00 , -3.1259471580501197e+00 , 1.5129524000000001e+00 , -3.9982800000000002e-01 , -9.0939400000000004e-01 , -1.1463200000000000e-01 --2.3086159535604978e+00 , -3.0976882194589948e+00 , 1.6459434399999999e+00 , -7.1898200000000001e-01 , -6.8517499999999998e-01 , -1.1661800000000000e-01 --2.3157936146549059e+00 , -3.0686138488825936e+00 , 1.7781711200000001e+00 , -8.1843100000000002e-01 , -5.7343800000000000e-01 , 3.6587599999999998e-02 --2.3289700646819442e+00 , -3.0441299576517258e+00 , 1.9074297039999999e+00 , -8.5350199999999998e-01 , -5.1723399999999997e-01 , 6.3266299999999998e-02 --2.3389281044069801e+00 , -3.0188238779704601e+00 , 2.0361520639999999e+00 , -8.6968000000000001e-01 , -4.8876999999999998e-01 , 6.9000300000000001e-02 --2.3487504846598277e+00 , -2.9915696129110527e+00 , 2.1640589600000002e+00 , -8.4840300000000002e-01 , -5.2512199999999998e-01 , 6.6769999999999996e-02 --2.3563844689952056e+00 , -2.9634897231739608e+00 , 2.2913040000000002e+00 , -8.6273500000000003e-01 , -5.0136599999999998e-01 , 6.5736500000000003e-02 --2.3617756577237801e+00 , -2.9335438635694526e+00 , 2.4176816799999998e+00 , -8.6167199999999999e-01 , -5.0037699999999996e-01 , 8.4529300000000002e-02 --2.3797134209256301e+00 , -2.9173470898526173e+00 , 2.5416788000000001e+00 , -8.6844500000000002e-01 , -4.9482900000000002e-01 , 3.0789899999999999e-02 --2.3817165255754995e+00 , -2.8835946435519171e+00 , 2.6666004800000001e+00 , -8.6087400000000003e-01 , -5.0688299999999997e-01 , 4.4332400000000001e-02 --2.4037630210665473e+00 , -2.8717325540191583e+00 , 2.7892965599999999e+00 , -8.5979499999999998e-01 , -5.0794799999999996e-01 , 5.2363100000000003e-02 --2.4034482688098802e+00 , -2.8351757195854033e+00 , 2.9128423200000002e+00 , -8.6389099999999996e-01 , -5.0110200000000005e-01 , 5.0877800000000001e-02 --2.4222574989164922e+00 , -2.8203334801183768e+00 , 3.0351993600000000e+00 , -8.6545300000000003e-01 , -4.9811600000000000e-01 , 5.3598800000000002e-02 --2.4249947425837588e+00 , -2.7881942414742209e+00 , 3.1572703999999998e+00 , -8.6599800000000005e-01 , -4.9765399999999999e-01 , 4.8868599999999998e-02 --2.4416049863346254e+00 , -2.7703276450760024e+00 , 3.2792623999999999e+00 , -8.6264700000000005e-01 , -5.0032699999999997e-01 , 7.4257299999999998e-02 --2.4410107498863534e+00 , -2.7353589426098894e+00 , 3.4002768000000003e+00 , -8.5949100000000000e-01 , -5.0600299999999998e-01 , 7.2358099999999995e-02 --2.4543632047551709e+00 , -2.7145610935784097e+00 , 3.5217280000000004e+00 , -8.6995599999999995e-01 , -4.8959799999999998e-01 , 5.8905300000000001e-02 --2.4579781138103201e+00 , -2.6837458111068342e+00 , 3.6422536000000001e+00 , -8.6664500000000000e-01 , -4.9888700000000002e-01 , 6.1602000000000002e-03 --2.4746161733825787e+00 , -2.6669460056534966e+00 , 3.7642456000000002e+00 , -8.4546100000000002e-01 , -5.3369500000000003e-01 , -1.9117400000000000e-02 --2.5054345330514307e+00 , -2.6638975014233361e+00 , 3.8887960000000001e+00 , -8.6222200000000004e-01 , -4.9577900000000003e-01 , -1.0380900000000000e-01 --1.1640265948384760e+01 , -1.1909984092979231e+01 , 5.7201216000000006e+00 , -4.4153299999999999e-02 , 9.4241500000000000e-01 , 3.3151900000000001e-01 --1.1974386713297385e+01 , -1.2148347030816060e+01 , 6.1308591999999997e+00 , 1.1549600000000000e-02 , 9.9803600000000003e-01 , 6.1563199999999998e-02 --1.2209360701398751e+01 , -1.2285327648261511e+01 , 6.5343375999999997e+00 , -3.1709399999999999e-01 , -9.4462699999999999e-01 , -8.4449300000000005e-02 --1.2238229997867679e+01 , -1.2211487199228550e+01 , 6.8944376000000007e+00 , -4.7206900000000002e-01 , -8.7123200000000001e-01 , 1.3455800000000001e-01 --1.2277188623385776e+01 , -1.2148075062395444e+01 , 7.2588119999999998e+00 , 5.6075699999999995e-01 , 8.0371999999999999e-01 , -1.9896200000000000e-01 --1.2325301336281614e+01 , -1.2093946617730900e+01 , 7.6280744000000000e+00 , 5.9221999999999997e-01 , 7.9040900000000003e-01 , -1.5661400000000000e-01 --1.2202380229659532e+01 , -1.1872185505876717e+01 , 7.9431320000000003e+00 , 4.8907699999999998e-01 , 8.3377299999999999e-01 , -2.5617400000000001e-01 --1.2409083501182863e+01 , -1.1970645756239751e+01 , 8.3697920000000003e+00 , 2.9751699999999998e-01 , 8.6944699999999997e-01 , -3.9439299999999999e-01 --1.2154853668084565e+01 , -1.1622943183257021e+01 , 8.6318720000000013e+00 , 8.2866999999999996e-02 , 8.7004400000000004e-01 , -4.8596000000000000e-01 --1.1845235772428648e+01 , -1.1226013026747641e+01 , 8.8603704000000008e+00 , 1.1825600000000000e-01 , -8.7666900000000003e-01 , 4.6633300000000000e-01 --1.1807463798900359e+01 , -1.1089882547737176e+01 , 9.1909656000000002e+00 , -9.7379300000000002e-02 , 9.3408300000000000e-01 , -3.4351999999999999e-01 --1.1808171785771322e+01 , -1.0991116048694483e+01 , 9.5387623999999995e+00 , 1.0056900000000001e-01 , -9.5135400000000003e-01 , 2.9122399999999998e-01 --1.1624331702596946e+01 , -1.0719144131353231e+01 , 9.8000520000000009e+00 , 6.5667600000000007e-02 , -9.7804300000000000e-01 , 1.9778599999999999e-01 --1.1960169580074110e+01 , -1.0930190902103867e+01 , 1.0314716799999999e+01 , 4.7352400000000003e-02 , -9.8425099999999999e-01 , 1.7031700000000000e-01 --1.1960825935042413e+01 , -1.0828538213755769e+01 , 1.0671530400000002e+01 , 5.3800099999999997e-02 , -9.8857799999999996e-01 , 1.4077999999999999e-01 --1.2747567739057349e+01 , -1.1442043338108194e+01 , 1.1463958399999999e+01 , 8.0285099999999998e-01 , 5.9301999999999999e-01 , -6.1298100000000001e-02 --1.2679082216876672e+01 , -1.1271067634365821e+01 , 1.1805421600000001e+01 , 7.8656800000000004e-01 , 6.1728799999999995e-01 , -1.6282700000000001e-02 --1.2812009510702877e+01 , -1.1280663489098023e+01 , 1.2267119200000000e+01 , 6.5075300000000003e-01 , 7.2290100000000002e-01 , -2.3223700000000000e-01 --1.2783245004550185e+01 , -1.1143546860262450e+01 , 1.2637536000000001e+01 , 6.2775099999999995e-01 , 7.4821499999999996e-01 , -2.1471699999999999e-01 --1.2876371442409324e+01 , -1.1112348742091189e+01 , 1.3088688000000001e+01 , 5.4500199999999999e-01 , 7.6634800000000003e-01 , -3.4012199999999998e-01 --1.2488252192387145e+01 , -1.0659287897338540e+01 , 1.3222640000000000e+01 , -3.7841100000000000e-01 , -8.2105300000000003e-01 , 4.2740699999999998e-01 --1.2793163198578423e+01 , -1.0810891134211841e+01 , 1.3828128000000001e+01 , 1.6888700000000001e-01 , 9.1157999999999995e-01 , -3.7483200000000000e-01 --1.2585642447082529e+01 , -1.0516493166411212e+01 , 1.4079184000000000e+01 , 8.8341500000000003e-02 , 9.2999600000000004e-01 , -3.5679600000000000e-01 --1.2237511377587287e+01 , -1.0104349159322117e+01 , 1.4217504000000000e+01 , -1.4900099999999999e-01 , 8.8905400000000001e-01 , -4.3287500000000001e-01 --1.2289688196064315e+01 , -1.0034883198611450e+01 , 1.4656592000000002e+01 , 6.0503000000000001e-02 , -9.2178199999999999e-01 , 3.8295800000000002e-01 --1.2126218238931894e+01 , -9.7822998817373463e+00 , 1.4927928000000000e+01 , 4.1243700000000001e-02 , -9.0411200000000003e-01 , 4.2530000000000001e-01 --1.2295963150848198e+01 , -9.8050043679012280e+00 , 1.5474760000000000e+01 , 4.9090099999999998e-02 , -8.7563100000000005e-01 , 4.8048000000000002e-01 --1.2062549590774807e+01 , -9.4949053168268591e+00 , 1.5688064000000001e+01 , 4.6825400000000003e-02 , -8.7293500000000002e-01 , 4.8558400000000002e-01 --1.1774273402772778e+01 , -9.1413623584313921e+00 , 1.5844168000000000e+01 , 6.2451699999999999e-02 , -8.5640899999999998e-01 , 5.1250700000000005e-01 --1.2673785178097432e+01 , -9.7455953930385117e+00 , 1.7090816000000004e+01 , 1.4142900000000000e-01 , -9.8866699999999996e-01 , 5.0358899999999998e-02 --2.9741109152198399e+00 , -1.4494832935469915e+00 , 9.8532791999999993e+00 , 7.9235199999999995e-01 , 6.0596899999999998e-01 , -7.0565500000000003e-02 --2.0616199819373664e+00 , -7.0627178165541737e-01 , 9.0463120000000004e+00 , 9.9954600000000005e-01 , 2.2652300000000000e-02 , 1.9872200000000000e-02 --1.9851767728548615e+00 , -6.0465284734626223e-01 , 9.1137663999999994e+00 , 9.9954600000000005e-01 , 2.2652300000000000e-02 , 1.9872200000000000e-02 --2.1381977247313735e+00 , -6.5677805114563625e-01 , 9.5022376000000008e+00 , 7.5789200000000001e-02 , 4.3297600000000003e-01 , 8.9821399999999996e-01 --2.0615490265705221e+00 , -5.5261314247708881e-01 , 9.5770967999999996e+00 , -3.7844299999999997e-01 , -5.6259400000000004e-01 , 7.3502999999999996e-01 --1.7486993170340921e+00 , -2.9783775468350582e-01 , 9.3009455999999986e+00 , -7.9838299999999995e-01 , 4.2754599999999997e-02 , 6.0063000000000000e-01 --1.7214690177047891e+00 , -2.2947645468623667e-01 , 9.4405552000000004e+00 , 7.6449299999999998e-01 , -4.0701199999999998e-01 , -4.9989099999999997e-01 --1.3108400809199883e+00 , 7.8514229723184670e-02 , 8.9803239999999995e+00 , 2.3636699999999999e-01 , -6.1163599999999996e-01 , -7.5500500000000004e-01 --1.2594148600873618e+00 , 1.5901714247692067e-01 , 9.0693896000000009e+00 , 2.3636699999999999e-01 , -6.1163599999999996e-01 , -7.5500500000000004e-01 --1.1454452458118478e+00 , 2.7647759832947738e-01 , 9.0548192000000007e+00 , -3.2072400000000001e-01 , 7.7893500000000004e-01 , 5.3888400000000003e-01 --9.5052960538273235e-01 , 4.3942220174336133e-01 , 8.8985383999999996e+00 , 3.1278099999999998e-01 , -8.7858300000000000e-01 , -3.6091499999999999e-01 --9.1401307934137543e-01 , 5.1034292831756756e-01 , 9.0053568000000013e+00 , 3.4160000000000001e-01 , -8.3734100000000000e-01 , -4.2681200000000002e-01 --2.0512848814592344e-01 , 9.4984460818559135e-01 , 7.8965399999999999e+00 , -9.2921200000000004e-01 , -3.3398400000000000e-01 , 1.5817700000000001e-01 --1.3826142886042758e-01 , 1.0267776203147907e+00 , 7.9184632000000006e+00 , -9.2618900000000004e-01 , -1.8623500000000001e-01 , 3.2785900000000001e-01 --8.9798202398757532e-01 , 6.7750561169357049e-01 , 9.5275408000000006e+00 , -9.4280299999999995e-01 , -2.0976600000000001e-01 , 2.5907599999999997e-01 --3.4845586006191764e-01 , 1.0093523684290817e+00 , 8.6356472000000011e+00 , -7.3024699999999998e-01 , 5.1106900000000000e-01 , 4.5337499999999997e-01 --3.5459488207051937e-01 , 1.0557080402099577e+00 , 8.8222647999999992e+00 , -7.7961100000000005e-01 , 1.7714700000000000e-01 , 6.0068800000000000e-01 --7.4144392968890216e-01 , 9.2947326779116834e-01 , 9.8207480000000000e+00 , -8.0687699999999996e-01 , 5.8333800000000002e-01 , -9.3090699999999998e-02 --1.6341039157346637e-01 , 1.2478950804009716e+00 , 8.7786992000000001e+00 , -6.7485200000000001e-01 , 6.9993799999999995e-01 , -2.3379700000000000e-01 --2.5714797946161383e-02 , 1.3591852865006571e+00 , 8.6542528000000001e+00 , 2.5085900000000000e-01 , -1.6687700000000000e-01 , 9.5353100000000002e-01 -7.2503192070420885e-02 , 1.4523241246290777e+00 , 8.6104583999999988e+00 , -2.2202600000000000e-01 , -6.5709099999999998e-01 , 7.2037200000000001e-01 --7.4260684546228362e-02 , 1.4501052129740057e+00 , 9.1531304000000002e+00 , -6.6412099999999996e-01 , -9.3144400000000002e-02 , 7.4180000000000001e-01 -1.4703729896869322e-01 , 1.5893257081690864e+00 , 8.8109496000000007e+00 , -6.2915900000000002e-01 , -5.4552400000000001e-01 , 5.5368099999999998e-01 -1.6315161658333910e-01 , 1.6530038603556312e+00 , 8.9723368000000008e+00 , 8.6289600000000000e-01 , 4.2554700000000001e-01 , 2.7261900000000000e-01 --2.1985955863148376e-01 , 1.5989222958320171e+00 , 1.0208543200000001e+01 , -3.0298100000000000e-01 , -4.4168600000000002e-01 , 8.4446200000000005e-01 --1.7419799053361062e-01 , 1.6873376699874394e+00 , 1.0346187200000001e+01 , -8.3337399999999995e-01 , 5.5202099999999998e-01 , 2.7583699999999999e-02 -3.6938887425361266e-01 , 1.8991865824496863e+00 , 9.0629624000000000e+00 , 8.8325500000000001e-01 , 2.0295199999999999e-01 , -4.2269600000000002e-01 --3.3953956904633209e-03 , 1.8884622483295836e+00 , 1.0411156000000000e+01 , -6.8183899999999997e-01 , 6.7528100000000002e-01 , 2.8123300000000001e-01 -6.4708904924440480e-02 , 1.9852041615537557e+00 , 1.0494771999999999e+01 , -6.4358899999999997e-01 , 6.6487900000000000e-01 , 3.7911699999999998e-01 -5.3654764255732235e-01 , 2.1398018691732217e+00 , 9.2757464000000009e+00 , -4.1855499999999997e-02 , -8.5463099999999997e-03 , 9.9908699999999995e-01 -2.8040950880908277e-01 , 2.1918220987472581e+00 , 1.0406860800000000e+01 , -3.9349800000000001e-01 , 6.3390299999999999e-01 , -6.6582699999999995e-01 -4.5402708190801300e-01 , 2.2950932941437632e+00 , 1.0123783200000000e+01 , 2.3454100000000000e-01 , -3.9671499999999998e-01 , 8.8747299999999996e-01 -4.4942558269409583e-01 , 2.3891962717533688e+00 , 1.0468647199999999e+01 , -8.9332999999999996e-01 , 1.1237700000000000e-01 , 4.3512400000000001e-01 -5.3655510222651026e-01 , 2.4887187792475487e+00 , 1.0491080000000000e+01 , -7.2902299999999998e-01 , 3.3788800000000002e-01 , 5.9527900000000000e-01 -4.8414485472181723e-01 , 2.6015290042885546e+00 , 1.1076704000000001e+01 , -9.5647300000000005e-02 , -6.2730699999999995e-01 , 7.7287600000000001e-01 -4.3649221228467372e-01 , 2.7308633212444473e+00 , 1.1703200000000001e+01 , 5.3970399999999996e-01 , 6.9105399999999995e-01 , -4.8079499999999997e-01 -5.1183701689408934e-01 , 2.8524013316243222e+00 , 1.1842944800000001e+01 , 5.4989200000000005e-01 , 6.8763799999999997e-01 , -4.7410099999999999e-01 -9.0716581860393397e-01 , 2.8788441356803407e+00 , 1.0466910400000002e+01 , 4.1532500000000000e-01 , 5.5169599999999996e-01 , -7.2328199999999998e-01 -1.3173690770233757e+00 , 2.8497806477460852e+00 , 8.8396223999999997e+00 , -6.2021800000000005e-01 , 5.3087700000000004e-01 , 5.7749399999999995e-01 -1.3582936915741903e+00 , 2.9396249785055404e+00 , 8.9991687999999996e+00 , -7.2093300000000005e-01 , -3.2525199999999999e-01 , -6.1193699999999995e-01 -1.4188370077491421e+00 , 3.0236528414798980e+00 , 9.0655000000000001e+00 , 5.9904899999999997e-02 , -6.7803100000000005e-01 , 7.3258800000000002e-01 -1.4442017871203436e+00 , 3.1359815406035145e+00 , 9.3649160000000009e+00 , -9.4901800000000003e-01 , 2.9019200000000001e-01 , 1.2310200000000000e-01 -1.5517740482764109e+00 , 3.1904391767914033e+00 , 9.1522256000000013e+00 , 3.8137999999999998e-02 , 9.9917199999999995e-01 , 1.4147200000000000e-02 -1.6684380674999537e+00 , 3.2236066812874791e+00 , 8.8357640000000011e+00 , -8.8401200000000002e-01 , -4.6687200000000001e-01 , 2.3544499999999999e-02 -2.2701478820442200e-01 , -3.7713012382140088e-01 , 1.1388872800000001e+00 , -5.1435000000000002e-02 , 1.6574800000000001e-01 , 9.8482599999999998e-01 -1.4855487320653560e-01 , -4.4995495064498181e-01 , 1.1612483199999999e+00 , -3.8151600000000001e-02 , 1.6981800000000000e-01 , 9.8473699999999997e-01 -4.5276056229288653e-02 , -5.5142145884202343e-01 , 1.1678928799999999e+00 , -9.0802400000000005e-02 , 1.8320500000000001e-01 , 9.7887199999999996e-01 --7.6191214152552700e-02 , -6.7513450452850066e-01 , 1.1656558399999999e+00 , -1.0073799999999999e-01 , 1.8807699999999999e-01 , 9.7697400000000001e-01 --1.9342498709104916e-01 , -7.9073109539053821e-01 , 1.1729337600000000e+00 , -5.2545799999999997e-02 , 2.0727999999999999e-01 , 9.7686899999999999e-01 --3.2422142161872625e-01 , -9.2228832122920945e-01 , 1.1772039999999999e+00 , -7.6853199999999997e-02 , 2.4426700000000001e-01 , 9.6665800000000002e-01 --4.3294218614563906e-01 , -1.0228736118216393e+00 , 1.2029065600000000e+00 , -8.5890300000000003e-02 , 2.6912500000000000e-01 , 9.5926800000000001e-01 --5.7204480312532802e-01 , -1.1611444465701206e+00 , 1.2142134400000000e+00 , -6.2674199999999999e-02 , 2.5955600000000001e-01 , 9.6369199999999999e-01 --7.1993527771248411e-01 , -1.3060036886125443e+00 , 1.2278738400000000e+00 , 7.8060900000000003e-02 , -2.2276199999999999e-01 , -9.7174300000000002e-01 --8.7568110836817281e-01 , -1.4583871320715036e+00 , 1.2446240799999999e+00 , -7.8215699999999999e-02 , 2.2540600000000000e-01 , 9.7111999999999998e-01 --1.0594210055670055e+00 , -1.6396102106179247e+00 , 1.2546205600000000e+00 , -6.3193899999999997e-02 , 2.3574100000000001e-01 , 9.6975900000000004e-01 --1.2371184703491251e+00 , -1.8134219089899482e+00 , 1.2763076799999999e+00 , -6.4668400000000001e-02 , 2.3376400000000000e-01 , 9.7014100000000003e-01 --1.4370772061264621e+00 , -2.0088095209676000e+00 , 1.2968331200000001e+00 , 8.7869600000000006e-02 , -2.1773400000000001e-01 , -9.7204500000000005e-01 --1.6788119538011399e+00 , -2.2485961700216697e+00 , 1.3094191999999998e+00 , 8.9196600000000001e-02 , -2.1889500000000001e-01 , -9.7166300000000005e-01 --1.9300828905332184e+00 , -2.4958338927716257e+00 , 1.3304355200000000e+00 , -8.7464700000000006e-02 , 2.1317000000000000e-01 , 9.7309199999999996e-01 --2.2297416978188789e+00 , -2.7931722790598004e+00 , 1.3454063199999999e+00 , 6.5975799999999996e-03 , 3.2869799999999999e-01 , 9.4441200000000003e-01 --2.4921912392758854e+00 , -3.0460929278944215e+00 , 1.3885153600000000e+00 , 1.1168200000000000e-02 , 9.5840499999999995e-01 , 2.8519499999999998e-01 --2.4894954243896930e+00 , -3.0043737460920497e+00 , 1.5276330400000000e+00 , 5.4845500000000003e-01 , 7.5920299999999996e-01 , 3.5043900000000000e-01 --2.4978404277559960e+00 , -2.9750372658816300e+00 , 1.6609485600000000e+00 , 7.9493800000000003e-01 , 6.0565100000000005e-01 , -3.5494100000000001e-02 --2.5112344931328749e+00 , -2.9523590004479621e+00 , 1.7917306399999999e+00 , 6.8243500000000001e-01 , 7.1758800000000000e-01 , -1.3910900000000001e-01 --2.5234566861699133e+00 , -2.9277665639406658e+00 , 1.9217227360000000e+00 , 6.9586300000000001e-01 , 7.0230400000000004e-01 , -1.5014500000000000e-01 --2.5199195570561379e+00 , -2.8864286385486908e+00 , 2.0538563999999999e+00 , 6.8808400000000003e-01 , 7.1251600000000004e-01 , -1.3733600000000001e-01 --2.5203952770852851e+00 , -2.8517829422379819e+00 , 2.1835828799999999e+00 , 7.0250699999999999e-01 , 6.9534700000000005e-01 , -1.5157799999999999e-01 --2.5552433135343131e+00 , -2.8520980596879930e+00 , 2.3063236800000002e+00 , 6.2826700000000002e-01 , 7.6886800000000000e-01 , -1.1884000000000000e-01 --2.5386465169761543e+00 , -2.7990187325874434e+00 , 2.4362883200000001e+00 , -6.1894300000000002e-01 , -7.7428500000000000e-01 , 1.3187699999999999e-01 --2.5565851143855900e+00 , -2.7817185294781686e+00 , 2.5604840800000002e+00 , 6.2454900000000002e-01 , 7.6587300000000003e-01 , -1.5289600000000000e-01 --2.5724091452238396e+00 , -2.7634378832568185e+00 , 2.6847266400000001e+00 , 6.3197700000000001e-01 , 7.6002700000000001e-01 , -1.5154100000000001e-01 --2.5786504431519770e+00 , -2.7359988845955661e+00 , 2.8090617600000001e+00 , 7.1840899999999996e-01 , 6.8704399999999999e-01 , -1.0890200000000000e-01 --2.5911498884526027e+00 , -2.7138077967056793e+00 , 2.9323537599999998e+00 , 7.1631800000000001e-01 , 6.8684100000000003e-01 , -1.2303900000000000e-01 --2.5950720975207497e+00 , -2.6824711732113435e+00 , 3.0554128000000000e+00 , 7.1839699999999995e-01 , 6.8620300000000001e-01 , -1.1415500000000001e-01 --2.6117962452927399e+00 , -2.6655084227922456e+00 , 3.1782159999999999e+00 , 7.1391300000000002e-01 , 6.8870799999999999e-01 , -1.2652600000000000e-01 --2.6199124406422314e+00 , -2.6394469679086647e+00 , 3.3005823999999997e+00 , 7.1151399999999998e-01 , 6.9094999999999995e-01 , -1.2781200000000001e-01 --2.6258553992963289e+00 , -2.6114381397311837e+00 , 3.4224912000000001e+00 , 6.9890099999999999e-01 , 7.0139799999999997e-01 , -1.3992499999999999e-01 --2.6382073240171815e+00 , -2.5895036590869926e+00 , 3.5445663999999999e+00 , 6.9458100000000000e-01 , 7.0972199999999996e-01 , -1.1769300000000001e-01 --2.6408679760823315e+00 , -2.5585798313389887e+00 , 3.6658303999999999e+00 , -4.2931200000000003e-01 , -8.9627500000000004e-01 , 1.1128000000000000e-01 --2.6575437845353189e+00 , -2.5405991872760163e+00 , 3.7884256000000001e+00 , -4.2931200000000003e-01 , -8.9627500000000004e-01 , 1.1128000000000000e-01 --2.6720975959805440e+00 , -2.5205754414781696e+00 , 3.9110624000000000e+00 , -5.6461600000000001e-01 , -7.9344000000000003e-01 , -2.2729300000000000e-01 --1.2598998442308751e+01 , -1.1968182938107686e+01 , 5.8749359999999999e+00 , -3.8428299999999999e-01 , -9.2090399999999994e-01 , -6.5291199999999994e-02 --1.2828166849737165e+01 , -1.2086689921989334e+01 , 6.2760536000000000e+00 , -3.8428299999999999e-01 , -9.2090399999999994e-01 , -6.5291100000000005e-02 --1.2821326089988633e+01 , -1.1980143028622786e+01 , 6.6325240000000001e+00 , -5.2979399999999999e-01 , -8.4773600000000005e-01 , 2.5735500000000001e-02 --1.2838736921918509e+01 , -1.1896870112764688e+01 , 6.9947976000000001e+00 , 6.0604499999999994e-01 , 7.7864999999999995e-01 , -1.6252600000000000e-01 --1.2860607733514428e+01 , -1.1816199123381045e+01 , 7.3586000000000000e+00 , 5.6585900000000000e-01 , 7.9925599999999997e-01 , -2.0246800000000001e-01 --1.2921440595003432e+01 , -1.1772607823480039e+01 , 7.7359224000000006e+00 , 6.0278399999999999e-01 , 7.7686699999999997e-01 , -1.8201400000000001e-01 --1.2895962455860897e+01 , -1.1648594080331010e+01 , 8.0880976000000011e+00 , 5.1090800000000003e-01 , 8.2700700000000005e-01 , -2.3459099999999999e-01 --1.2947348542260908e+01 , -1.1594545547506423e+01 , 8.4667303999999994e+00 , 4.5419500000000002e-01 , 8.5513799999999995e-01 , -2.4989300000000000e-01 --1.2898470036603532e+01 , -1.1447769947499669e+01 , 8.8104504000000006e+00 , -1.4857400000000001e-01 , -9.3347899999999995e-01 , 3.2640799999999998e-01 --1.2977286729811395e+01 , -1.1418064271412804e+01 , 9.2045583999999998e+00 , -1.8346000000000001e-01 , -9.4237400000000004e-01 , 2.7977500000000000e-01 --1.2873507057383767e+01 , -1.1223847018855745e+01 , 9.5265632000000000e+00 , -2.9185800000000001e-02 , 9.7238400000000003e-01 , -2.3155300000000001e-01 --1.2920386360631952e+01 , -1.1163239585097127e+01 , 9.9122784000000017e+00 , 1.5737999999999999e-02 , -9.8141000000000000e-01 , 1.9127700000000000e-01 --1.3095516682188549e+01 , -1.1213819234384591e+01 , 1.0361756000000002e+01 , 4.1663800000000001e-02 , -9.9486200000000002e-01 , 9.2268000000000003e-02 --1.2978131903456086e+01 , -1.1006625192645524e+01 , 1.0677333600000001e+01 , -1.3447499999999999e-02 , -9.9975400000000003e-01 , -1.7645500000000001e-02 --1.3134454757503599e+01 , -1.1036912682773977e+01 , 1.1131241599999999e+01 , -8.1093000000000004e-01 , -5.8465000000000000e-01 , 2.4040800000000001e-02 --1.3182684622915646e+01 , -1.0972260131256688e+01 , 1.1536820799999999e+01 , 8.0285099999999998e-01 , 5.9301999999999999e-01 , -6.1298199999999997e-02 --1.3210806753676177e+01 , -1.0888495010644062e+01 , 1.1935993600000000e+01 , -7.7349299999999999e-01 , -6.3079399999999997e-01 , 6.1709899999999998e-02 --1.3262533126923081e+01 , -1.0824392063494326e+01 , 1.2353772000000001e+01 , 6.2775199999999998e-01 , 7.4821400000000005e-01 , -2.1471699999999999e-01 --1.3358852346944150e+01 , -1.0795241875474813e+01 , 1.2804768000000001e+01 , 6.2821099999999996e-01 , 7.4026099999999995e-01 , -2.3950800000000000e-01 --1.3283962653928572e+01 , -1.0621832548968444e+01 , 1.3154312000000001e+01 , 4.7548299999999999e-01 , 8.3033000000000001e-01 , -2.9063299999999997e-01 --1.3311149576202700e+01 , -1.0532211298401066e+01 , 1.3572288000000000e+01 , -4.0450100000000000e-01 , -8.5749200000000003e-01 , 3.1794000000000000e-01 --1.3361194901074352e+01 , -1.0459649770025136e+01 , 1.4011376000000000e+01 , 1.1694499999999999e-01 , 8.9956700000000001e-01 , -4.2083599999999999e-01 --1.3375931667880133e+01 , -1.0356065525142279e+01 , 1.4432784000000000e+01 , -3.0389900000000001e-02 , -9.2436799999999997e-01 , 3.8029099999999999e-01 --1.3252042205701615e+01 , -1.0141175392874464e+01 , 1.4756328000000002e+01 , -5.8859599999999998e-02 , 9.0526499999999999e-01 , -4.2075099999999999e-01 --1.3360686352079096e+01 , -1.0109854520559852e+01 , 1.5257504000000001e+01 , 1.5551600000000000e-02 , -9.2096999999999996e-01 , 3.8932400000000000e-01 --1.3225609777490929e+01 , -9.8847167822997228e+00 , 1.5576368000000000e+01 , -9.5186300000000001e-03 , 9.1013400000000000e-01 , -4.1420400000000002e-01 --1.2900856225060666e+01 , -9.5127222880708882e+00 , 1.5737048000000001e+01 , 4.9140400000000001e-02 , -8.8144500000000003e-01 , 4.6972399999999997e-01 --1.3796981927475541e+01 , -1.0081834536379155e+01 , 1.6926704000000001e+01 , -1.1703800000000000e-01 , 9.9104099999999995e-01 , -6.4336800000000000e-02 --1.3560881739386714e+01 , -9.7750428620518015e+00 , 1.7177032000000001e+01 , -7.9523700000000003e-02 , 9.9666699999999997e-01 , -1.8210500000000001e-02 --2.3752976555372571e+00 , -6.4627558565200394e-01 , 9.5406447999999990e+00 , -2.4708600000000000e-01 , -1.5065200000000001e-01 , 9.5721100000000003e-01 --2.3064624267112919e+00 , -5.5162135404835633e-01 , 9.6351496000000019e+00 , -2.4708600000000000e-01 , -1.5065200000000001e-01 , 9.5721100000000003e-01 --1.9202852506544015e+00 , -2.6209575696028420e-01 , 9.2783671999999999e+00 , 8.7264399999999998e-01 , -4.6324199999999999e-01 , -1.5459400000000001e-01 --1.8031108771199258e+00 , -1.4170418658725792e-01 , 9.2895472000000012e+00 , 6.4811200000000002e-01 , -6.0284499999999996e-01 , -4.6532699999999999e-01 --1.7421607592938062e+00 , -5.4113280967883703e-02 , 9.3789143999999993e+00 , -8.1932499999999997e-01 , 2.2376699999999999e-01 , 5.2785899999999997e-01 --1.4631822115873185e+00 , 1.5731366293979021e-01 , 9.1333808000000012e+00 , -4.1396699999999997e-01 , -4.2885299999999998e-01 , -8.0294299999999996e-01 --1.3497319848444667e+00 , 2.7089749810204022e-01 , 9.1310928000000011e+00 , 2.3636699999999999e-01 , -6.1163599999999996e-01 , -7.5500500000000004e-01 --3.1013361941302264e-01 , 8.9144414799955496e-01 , 7.6053503999999998e+00 , 4.9609999999999999e-01 , 4.0760999999999997e-01 , -7.6664100000000002e-01 --2.1933525643725993e-01 , 9.7836425315947340e-01 , 7.5870880000000005e+00 , 4.9609999999999999e-01 , 4.0760999999999997e-01 , -7.6664100000000002e-01 --2.7468137308163332e-01 , 9.8719339215859803e-01 , 7.8193720000000004e+00 , 8.9452699999999996e-01 , 4.3586500000000000e-01 , -9.9212599999999998e-02 --2.9516837462430390e-01 , 1.0172223124165927e+00 , 8.0009352000000007e+00 , -9.2618900000000004e-01 , -1.8623500000000001e-01 , 3.2785900000000001e-01 --4.7665959591479679e-01 , 9.7101024835588245e-01 , 8.4864904000000010e+00 , -4.9053799999999997e-01 , 6.5376900000000004e-01 , 5.7615899999999998e-01 --3.7818761837089365e-01 , 1.0646759685796199e+00 , 8.4664599999999997e+00 , -4.0119300000000002e-01 , 5.1073299999999999e-01 , 7.6039199999999996e-01 --3.4896988758629544e-01 , 1.1244893203944006e+00 , 8.5798407999999995e+00 , -7.3024599999999995e-01 , 5.1106900000000000e-01 , 4.5337499999999997e-01 --2.2313934064834839e-03 , 1.3259436185651245e+00 , 8.0515623999999999e+00 , -3.0931199999999998e-01 , -6.0561299999999996e-01 , 7.3318399999999995e-01 --2.3220087959876423e-01 , 1.2740493849742478e+00 , 8.6935648000000008e+00 , 5.7709600000000005e-01 , -6.9894199999999995e-01 , -4.2242200000000002e-01 --1.2506387159778631e-01 , 1.3691511258052036e+00 , 8.6456104000000007e+00 , 3.7839400000000001e-01 , -4.1327300000000000e-01 , -8.2826599999999995e-01 --6.9415096178531144e-02 , 1.4418533141902565e+00 , 8.7073864000000007e+00 , -1.1101200000000000e-01 , -7.7687499999999998e-01 , 6.1979200000000001e-01 --5.5941156806760262e-04 , 1.5206497985608380e+00 , 8.7389919999999996e+00 , 2.0691200000000001e-01 , 7.6892099999999997e-01 , -6.0493600000000003e-01 --4.8356044073535598e-01 , 1.4124799357832463e+00 , 1.0091220800000000e+01 , -2.5822899999999999e-01 , -5.9255999999999998e-01 , 7.6301399999999997e-01 -6.1633583031691197e-02 , 1.6532013328692741e+00 , 8.9885504000000012e+00 , -9.2796000000000001e-01 , -3.5299100000000000e-01 , -1.1953200000000000e-01 -6.7658913165545842e-02 , 1.7146681695796986e+00 , 9.1895096000000009e+00 , -3.8523400000000002e-01 , -9.1992300000000005e-01 , 7.3052400000000003e-02 -3.0308868983445647e-01 , 1.8405534502019592e+00 , 8.7894216000000007e+00 , 6.5927000000000002e-01 , 5.9439100000000000e-01 , -4.6050300000000000e-01 -2.2950977973223696e-01 , 1.8841003358261676e+00 , 9.2112248000000001e+00 , 3.2439099999999998e-01 , -5.5059400000000001e-02 , 9.4431900000000002e-01 -3.3886677165798296e-01 , 1.9735377295558085e+00 , 9.1356272000000001e+00 , -2.5999400000000000e-01 , -5.6877500000000003e-01 , 7.8032000000000001e-01 --2.0718958350850247e-02 , 1.9798897711379264e+00 , 1.0455439199999999e+01 , -7.2984099999999996e-01 , 6.5371500000000005e-01 , 1.9997000000000001e-01 -4.5492532736686764e-01 , 2.1318897426788039e+00 , 9.2822984000000002e+00 , -1.1391000000000000e-01 , -3.5666600000000000e-02 , 9.9285100000000004e-01 -1.6513078185100372e-01 , 2.1776116891133075e+00 , 1.0490924000000001e+01 , -5.7422700000000004e-01 , 7.4933799999999995e-01 , -3.2978200000000002e-01 -3.2687214132982878e-01 , 2.2792172023518908e+00 , 1.0270818400000000e+01 , 6.6266999999999998e-01 , -5.7931999999999995e-01 , 4.7461300000000001e-01 -3.7997183192833384e-01 , 2.3732889338864034e+00 , 1.0417031999999999e+01 , 4.6760600000000002e-01 , -8.8315200000000005e-01 , -3.7248999999999997e-02 -7.5544038244405143e-01 , 2.4597633914199180e+00 , 9.3768864000000001e+00 , 3.9203700000000002e-01 , 3.8460500000000002e-02 , -9.1914499999999999e-01 -5.4798003032463161e-01 , 2.5661600720491178e+00 , 1.0503684800000000e+01 , -7.2902299999999998e-01 , 3.3788699999999999e-01 , 5.9527900000000000e-01 -8.9910096684414720e-01 , 2.6260546984078346e+00 , 9.4529104000000004e+00 , 4.3397700000000000e-01 , 7.1497500000000003e-01 , 5.4815700000000001e-01 -4.2348243350300496e-01 , 2.8228395175496090e+00 , 1.1867072800000001e+01 , -5.6605499999999997e-01 , -7.5815999999999995e-01 , 3.2368900000000000e-01 -4.8918636200836119e-01 , 2.9474414152857311e+00 , 1.2077953600000001e+01 , 5.8466499999999999e-01 , 7.5758999999999999e-01 , -2.9021500000000000e-01 -1.2777181921899166e+00 , 2.8225902758287069e+00 , 8.7910648000000009e+00 , 2.4243700000000001e-01 , -4.3553799999999998e-01 , -8.6690900000000004e-01 -1.3379643696133874e+00 , 2.8998705233793487e+00 , 8.8501992000000005e+00 , 6.6477600000000003e-01 , -4.4090600000000002e-01 , -6.0305399999999998e-01 -1.3693005918374421e+00 , 2.9959643484604381e+00 , 9.0808712000000007e+00 , 6.4964900000000003e-01 , 1.6296800000000000e-01 , -7.4256200000000006e-01 -1.4422344018679716e+00 , 3.0733992013030509e+00 , 9.0960344000000006e+00 , -8.9277400000000000e-03 , -2.3628099999999999e-01 , 9.7164399999999995e-01 -1.5330103350262623e+00 , 3.1376846236583682e+00 , 8.9970368000000001e+00 , -3.7231900000000001e-01 , 9.1508999999999996e-01 , -1.5488299999999999e-01 -1.6146830309183315e+00 , 3.2048786912105558e+00 , 8.9474599999999995e+00 , -1.2999000000000000e-02 , -9.9853499999999995e-01 , -5.2529100000000002e-02 -1.7076692547842898e+00 , 3.2559445187779525e+00 , 8.7938311999999996e+00 , 7.6029899999999995e-01 , 6.4710400000000001e-01 , -5.6577400000000000e-02 -3.1727704978667659e-01 , -1.5046517255461023e-01 , 1.1290083200000001e+00 , -2.2912900000000000e-02 , 9.0354000000000004e-02 , 9.9564600000000003e-01 -2.2119600274682538e-01 , -2.4173933631043942e-01 , 1.1297987199999999e+00 , -4.4358799999999997e-02 , 1.1619599999999999e-01 , 9.9223499999999998e-01 -1.2254143622093561e-01 , -3.3319560952506810e-01 , 1.1343871999999999e+00 , -5.0542200000000002e-02 , 1.5289900000000001e-01 , 9.8694899999999997e-01 -1.7546368699041137e-02 , -4.3195390002258982e-01 , 1.1383443999999998e+00 , -5.5339399999999997e-02 , 1.8923100000000001e-01 , 9.8037200000000002e-01 --9.4880784696222076e-02 , -5.3786407967269589e-01 , 1.1420478400000000e+00 , -9.2147300000000001e-02 , 1.7948200000000000e-01 , 9.7943599999999997e-01 --2.1481164903730665e-01 , -6.5083455235649268e-01 , 1.1460060799999998e+00 , 7.6005400000000001e-02 , -1.7315600000000000e-01 , -9.8195699999999997e-01 --3.3640282286964895e-01 , -7.6378079462064719e-01 , 1.1550020800000000e+00 , -7.5949199999999994e-02 , 1.7674200000000001e-01 , 9.8132299999999995e-01 --4.8431632910801525e-01 , -9.0449559953083636e-01 , 1.1523032799999999e+00 , -7.8392699999999996e-02 , 2.2985600000000000e-01 , 9.7006199999999998e-01 --5.9643127679981855e-01 , -1.0034131667879445e+00 , 1.1802574400000001e+00 , -4.4735600000000000e-02 , 2.7912399999999998e-01 , 9.5921299999999998e-01 --7.4685659944943428e-01 , -1.1437245510291332e+00 , 1.1895810400000000e+00 , -4.4663599999999998e-02 , 2.4510499999999999e-01 , 9.6846699999999997e-01 --9.0616729255211403e-01 , -1.2915567004595743e+00 , 1.2018686400000000e+00 , -7.2207900000000005e-02 , 2.0557900000000001e-01 , 9.7597299999999998e-01 --1.0803871986060423e+00 , -1.4536274778314375e+00 , 1.2140564000000000e+00 , -5.3469700000000002e-02 , 2.2377900000000001e-01 , 9.7317200000000004e-01 --1.2495291219256686e+00 , -1.6083974864663726e+00 , 1.2372026400000000e+00 , -5.8289100000000003e-02 , 2.2231500000000001e-01 , 9.7323099999999996e-01 --1.4549415448399738e+00 , -1.7983963628769306e+00 , 1.2516960799999999e+00 , 7.8330100000000000e-02 , -2.1237500000000001e-01 , -9.7404400000000002e-01 --1.6948852293997927e+00 , -2.0241947486635832e+00 , 1.2603197600000000e+00 , -7.9316200000000003e-02 , 2.0927000000000001e-01 , 9.7463599999999995e-01 --1.9453324530680511e+00 , -2.2564411974987406e+00 , 1.2768412000000000e+00 , -6.9455799999999998e-02 , 2.1368899999999999e-01 , 9.7443000000000002e-01 --2.2114379172322884e+00 , -2.5027385409079148e+00 , 1.2993374400000000e+00 , -8.5681400000000005e-02 , 2.0151800000000000e-01 , 9.7572999999999999e-01 --2.5495956727397173e+00 , -2.8207528289538732e+00 , 1.3089075200000000e+00 , 8.7709999999999996e-02 , 4.8669800000000002e-01 , 8.6915600000000004e-01 --2.8835024347259353e+00 , -3.1311034110762819e+00 , 1.3363198399999998e+00 , -2.2652700000000001e-01 , 3.5142699999999999e-01 , 9.0839700000000001e-01 --3.3561984643701903e+00 , -3.5786532141162537e+00 , 1.3382916800000000e+00 , 5.7633599999999996e-01 , -3.4893000000000002e-01 , 7.3897599999999997e-01 --3.8398013433332752e+00 , -4.0312896679695154e+00 , 1.3601275200000000e+00 , -2.5369799999999998e-01 , 3.0258600000000002e-01 , 9.1873800000000005e-01 --4.3126084706542516e+00 , -4.4675076609569757e+00 , 1.4077459999999999e+00 , -4.8266200000000002e-02 , 2.4376999999999999e-01 , 9.6863100000000002e-01 --4.8191576801275824e+00 , -4.9300694937044929e+00 , 1.4702957600000000e+00 , -5.1728200000000002e-02 , 2.5764999999999999e-01 , 9.6485299999999996e-01 --5.3868908319091657e+00 , -5.4491778653574148e+00 , 1.5447961600000000e+00 , -1.7817800000000002e-02 , 2.7541599999999999e-01 , 9.6116000000000001e-01 --6.0088652495974344e+00 , -6.0145860262543565e+00 , 1.6361476800000001e+00 , 4.6348899999999998e-02 , 3.2842500000000002e-01 , 9.4339200000000001e-01 --6.2819905566561225e+00 , -6.2274050598714101e+00 , 1.8075095200000000e+00 , 5.8969599999999997e-02 , 3.7156000000000000e-01 , 9.2653399999999997e-01 --2.7922956019066092e+00 , -2.7416359921577449e+00 , 2.4456316800000000e+00 , 6.1177599999999999e-01 , 7.7861499999999995e-01 , -1.3960200000000000e-01 --7.3329952287403390e+00 , -7.1345115921885078e+00 , 2.1351178399999999e+00 , 8.1674899999999995e-02 , 2.9375800000000002e-01 , 9.5238400000000001e-01 --8.3528572090226234e+00 , -8.0579926266296358e+00 , 2.2985330400000001e+00 , -1.0403300000000001e-02 , 2.3899200000000001e-01 , 9.7096600000000000e-01 --9.9911555216771575e+00 , -9.5630793858035652e+00 , 2.4789148000000001e+00 , -6.0482000000000001e-02 , 2.8237200000000001e-01 , 9.5739600000000002e-01 --1.2172297370542640e+01 , -1.1566205740553334e+01 , 2.7223299200000000e+00 , -3.0047700000000000e-02 , 3.9876899999999998e-01 , 9.1655900000000001e-01 --1.2999419660202001e+01 , -1.2256383170399202e+01 , 3.0679759999999998e+00 , 2.0368200000000000e-01 , 5.7799199999999995e-01 , 7.9021500000000000e-01 --1.3357099355859866e+01 , -1.2494215977930249e+01 , 3.4395784000000003e+00 , -1.7691100000000001e-01 , 9.7660100000000005e-01 , -1.2228700000000001e-01 --1.3878496285855825e+01 , -1.2881856560468753e+01 , 3.8336239999999999e+00 , -1.9297500000000001e-01 , -9.8119999999999996e-01 , 2.6674600000000000e-03 --3.0334030400194791e+00 , -2.6944553743651705e+00 , 3.4610751999999998e+00 , -7.7867099999999995e-02 , -9.7407999999999995e-01 , 2.1237900000000001e-01 --3.0842182853926543e+00 , -2.7060931865815592e+00 , 3.5927183999999999e+00 , 7.9059000000000004e-02 , 9.7253599999999996e-01 , -2.1891300000000000e-01 --3.0022845685242627e+00 , -2.5965911189402116e+00 , 3.7110288000000002e+00 , 1.2659899999999999e-01 , 9.8534600000000006e-01 , -1.1430200000000000e-01 --1.4069514801915265e+01 , -1.2643617154571139e+01 , 5.3707335999999994e+00 , 5.2193000000000001e-01 , 8.5211999999999999e-01 , -3.8482400000000000e-02 --1.4036045094780842e+01 , -1.2510343143119783e+01 , 5.7442912000000002e+00 , 5.1645399999999997e-01 , 8.5427900000000001e-01 , -5.9012599999999998e-02 --1.4150488534854770e+01 , -1.2510090508908778e+01 , 6.1427360000000002e+00 , -5.2190099999999995e-01 , -8.4274499999999997e-01 , 1.3191200000000000e-01 --1.4168338785114774e+01 , -1.2422555942721157e+01 , 6.5259032000000001e+00 , -5.2170499999999997e-01 , -8.4279999999999999e-01 , 1.3233200000000001e-01 --1.4203648758284199e+01 , -1.2350445544450350e+01 , 6.9134799999999998e+00 , -5.2239999999999998e-01 , -8.4351299999999996e-01 , 1.2483700000000000e-01 --1.4233768745092263e+01 , -1.2274099626663725e+01 , 7.3015664000000005e+00 , 5.3028500000000001e-01 , 8.3462599999999998e-01 , -1.4898700000000001e-01 --1.4274942250998834e+01 , -1.2206042936798864e+01 , 7.6937815999999994e+00 , 5.0148300000000001e-01 , 8.4356299999999995e-01 , -1.9213800000000000e-01 --1.4302175247478928e+01 , -1.2126140570383876e+01 , 8.0845720000000014e+00 , -4.7068399999999999e-01 , -8.5246400000000000e-01 , 2.2751099999999999e-01 --1.4332932981953643e+01 , -1.2047695510412051e+01 , 8.4778167999999994e+00 , 4.3613099999999999e-01 , 8.6907199999999996e-01 , -2.3345900000000000e-01 --1.4243682652725617e+01 , -1.1865560023684040e+01 , 8.8318016000000004e+00 , -3.3435500000000001e-01 , -8.7815299999999996e-01 , 3.4213199999999999e-01 --1.4249040728201678e+01 , -1.1765316716798479e+01 , 9.2176520000000011e+00 , -2.8912399999999999e-01 , -9.1218100000000002e-01 , 2.9040199999999999e-01 --1.4035320267320490e+01 , -1.1480040076147880e+01 , 9.5196992000000016e+00 , -6.1625100000000002e-02 , -9.8471399999999998e-01 , 1.6291100000000000e-01 --1.4310727003484324e+01 , -1.1607060499846369e+01 , 1.0016216000000000e+01 , 2.6236199999999998e-01 , 9.5244099999999998e-01 , -1.5499499999999999e-01 --1.4360722000149522e+01 , -1.1542076009088904e+01 , 1.0428243200000001e+01 , -2.7009100000000003e-01 , -9.6042600000000000e-01 , 6.8060800000000005e-02 --1.4389899209921815e+01 , -1.1458864332347815e+01 , 1.0835122399999999e+01 , -3.1569399999999997e-01 , -9.4558600000000004e-01 , 7.8768099999999994e-02 --1.4617463934261725e+01 , -1.1536075139458339e+01 , 1.1341425599999999e+01 , -3.4218700000000002e-01 , -9.3616900000000003e-01 , 8.0602599999999996e-02 --1.4671924446166319e+01 , -1.1470000886943989e+01 , 1.1773649600000001e+01 , 3.7922899999999998e-01 , 9.2052199999999995e-01 , -9.3936199999999997e-02 --1.4690705872145703e+01 , -1.1374208306325544e+01 , 1.2192395200000002e+01 , -4.2011799999999999e-01 , -8.9258499999999996e-01 , 1.6368300000000000e-01 --1.4732931783301581e+01 , -1.1295201626331410e+01 , 1.2628280000000000e+01 , -4.1864699999999999e-01 , -8.9248099999999997e-01 , 1.6796800000000001e-01 --1.4770020058216911e+01 , -1.1210654209741870e+01 , 1.3066328000000000e+01 , -3.7221500000000002e-01 , -9.0490199999999998e-01 , 2.0641999999999999e-01 --1.4792902681121152e+01 , -1.1113475174384330e+01 , 1.3501672000000001e+01 , 3.1885100000000000e-01 , 8.9795599999999998e-01 , -3.0332999999999999e-01 --1.4684926823669180e+01 , -1.0913260723878098e+01 , 1.3859639999999999e+01 , -2.9308099999999998e-01 , -8.9409000000000005e-01 , 3.3868500000000001e-01 --1.4608185242760115e+01 , -1.0737470423077465e+01 , 1.4237264000000001e+01 , -4.2067199999999999e-02 , -9.4633699999999998e-01 , 3.2043400000000000e-01 --1.4583879346207219e+01 , -1.0601915513639408e+01 , 1.4651808000000001e+01 , 3.5393800000000000e-03 , -9.2412399999999995e-01 , 3.8207700000000000e-01 --1.4539072448310367e+01 , -1.0450235046433175e+01 , 1.5055847999999999e+01 , 4.8360100000000003e-02 , -9.3046300000000004e-01 , 3.6318000000000000e-01 --7.4055976119658720e+00 , -4.9823768486934332e+00 , 1.0282393600000001e+01 , -5.6367299999999998e-01 , 8.1722099999999998e-01 , 1.2009200000000000e-01 --1.4154090736124015e+01 , -9.9225426724440968e+00 , 1.5649064000000001e+01 , -1.8192200000000000e-01 , 9.6775100000000003e-01 , -1.7424999999999999e-01 --1.5036234805001730e+01 , -1.0451744038509638e+01 , 1.6781624000000001e+01 , -6.4514400000000000e-02 , 9.8699300000000001e-01 , -1.4725099999999999e-01 --1.4844293569868618e+01 , -1.0182045588718518e+01 , 1.7096536000000000e+01 , -2.6976799999999999e-02 , 9.9525900000000000e-01 , -9.3446000000000001e-02 --7.0220658597009304e+00 , -3.6363948242203783e+00 , 1.3887928000000000e+01 , 8.5425499999999999e-01 , -3.3353600000000000e-01 , -3.9874900000000002e-01 --6.8943043562664599e+00 , -3.4680365757918459e+00 , 1.4060464000000001e+01 , 8.5425499999999999e-01 , -3.3353600000000000e-01 , -3.9874900000000002e-01 --6.5857622058147953e+00 , -3.1882422549240639e+00 , 1.4012936000000002e+01 , 5.8625400000000005e-01 , -6.9584699999999999e-01 , -4.1485400000000000e-01 --2.5484173271248363e+00 , -5.8940921355206433e-01 , 9.4908496000000007e+00 , -2.4708600000000000e-01 , -1.5065200000000001e-01 , 9.5721100000000003e-01 --2.4840106546184266e+00 , -5.0002464264000945e-01 , 9.5951200000000014e+00 , -2.4708600000000000e-01 , -1.5065200000000001e-01 , 9.5721100000000003e-01 --2.3942994493256435e+00 , -3.9617244787939709e-01 , 9.6659128000000010e+00 , -2.4708600000000000e-01 , -1.5065200000000001e-01 , 9.5721100000000003e-01 --2.3220626068982151e+00 , -3.0212328098827168e-01 , 9.7581607999999989e+00 , -3.4710099999999999e-01 , -5.8726199999999995e-01 , 7.3119299999999998e-01 --1.8680214019995600e+00 , 3.8755859368477807e-03 , 9.3025991999999995e+00 , 4.7122999999999998e-01 , -1.2948799999999999e-01 , 8.7245399999999995e-01 --4.0008028051863356e+00 , -1.1061549759659521e+00 , 1.2650639999999999e+01 , 4.5954600000000001e-01 , 3.8678400000000002e-01 , -7.9951000000000005e-01 --1.7333415741034401e+00 , 1.7851754919686025e-01 , 9.4708712000000013e+00 , -9.8834599999999995e-01 , 1.5012600000000001e-01 , -2.5177499999999998e-02 --4.4066115363013303e-01 , 9.0183766855934655e-01 , 7.6290832000000002e+00 , 4.9610100000000001e-01 , 4.0760900000000000e-01 , -7.6664100000000002e-01 --3.4176710687183576e-01 , 9.9038505508510566e-01 , 7.6048096000000003e+00 , -3.1372100000000003e-01 , -5.4019600000000001e-02 , 9.4797799999999999e-01 --2.9446565476591280e-01 , 1.0502424455541655e+00 , 7.6643080000000001e+00 , 7.0955400000000002e-01 , 3.4585500000000002e-01 , -6.1393600000000004e-01 --2.7768803261320940e-01 , 1.0972472511530686e+00 , 7.7746936000000009e+00 , -9.2161400000000004e-01 , -8.4463300000000005e-02 , 3.7880599999999998e-01 --2.4820627291661834e-01 , 1.1497380539543411e+00 , 7.8676072000000001e+00 , -9.2708199999999996e-01 , -5.9219399999999998e-02 , 3.7015199999999998e-01 --4.9444759855014020e-01 , 1.0795958402191062e+00 , 8.4682696000000011e+00 , -4.0119300000000002e-01 , 5.1073299999999999e-01 , 7.6039199999999996e-01 --8.8476817889663550e-01 , 9.5630028946260226e-01 , 9.3751911999999997e+00 , 7.6256299999999999e-01 , 3.5873100000000002e-01 , -5.3833900000000001e-01 --2.9827800735614485e-01 , 1.2562468609958770e+00 , 8.4330031999999999e+00 , 6.7042500000000005e-01 , -5.6128400000000001e-01 , -4.8527399999999998e-01 --2.2165736236828959e-01 , 1.3343760146636667e+00 , 8.4524096000000011e+00 , -4.7470299999999999e-01 , 8.5519000000000001e-01 , 2.0810200000000001e-01 --2.6503602854085839e-01 , 1.3666164258103386e+00 , 8.7191071999999998e+00 , -9.6235199999999999e-01 , -8.4121100000000004e-02 , 2.5846300000000000e-01 --1.4188016292297601e-01 , 1.4627875467696938e+00 , 8.6430000000000007e+00 , -4.3118700000000003e-02 , -2.9046400000000000e-01 , 9.5591400000000004e-01 --1.5102053786574210e-01 , 1.5111240260436340e+00 , 8.8546088000000012e+00 , -2.2976300000000000e-01 , -7.8265499999999999e-01 , 5.7849799999999996e-01 --5.2685475858961306e-01 , 1.4441995470295974e+00 , 9.9179256000000002e+00 , 5.9523800000000004e-01 , -1.6802100000000000e-01 , -7.8578700000000001e-01 --1.1223117388076931e-01 , 1.6355349790764715e+00 , 9.1747104000000004e+00 , 4.1108699999999998e-01 , -8.7966400000000000e-01 , -2.3916100000000001e-01 -6.6261471032224906e-02 , 1.7451710474274431e+00 , 8.9558840000000011e+00 , -2.6463599999999998e-01 , 1.4276200000000000e-01 , 9.5372299999999999e-01 -1.8231817770511460e-01 , 1.8335948649601941e+00 , 8.8766879999999997e+00 , -1.4874299999999999e-01 , 6.0398900000000000e-01 , 7.8298999999999996e-01 -2.2345689917752409e-01 , 1.9031763850390624e+00 , 8.9883839999999999e+00 , 4.7518500000000002e-01 , 7.7477200000000002e-01 , -4.1704700000000000e-01 -2.8108979569067882e-01 , 1.9777642657349501e+00 , 9.0599464000000012e+00 , -2.3020699999999999e-01 , -5.2452399999999999e-01 , 8.1968200000000002e-01 --3.8863358594843689e-02 , 1.9903006395182388e+00 , 1.0218641600000000e+01 , -4.6649000000000002e-01 , 8.0585799999999996e-01 , -3.6466500000000002e-01 -3.6579773000001858e-01 , 2.1248820145514236e+00 , 9.3075495999999998e+00 , 2.2921800000000001e-01 , 4.9096200000000001e-01 , -8.4048599999999996e-01 -4.5461839799828563e-01 , 2.2069008737691767e+00 , 9.2961615999999996e+00 , -1.1391000000000000e-01 , -3.5666600000000000e-02 , 9.9285100000000004e-01 -5.4698503685758593e-01 , 2.2873931383903514e+00 , 9.2726784000000002e+00 , 3.9606400000000003e-01 , -1.0960499999999999e-01 , 9.1165799999999997e-01 -6.2743282293286762e-01 , 2.3674770322788690e+00 , 9.2867911999999997e+00 , -2.0660999999999999e-01 , 4.9961499999999998e-01 , 8.4124699999999997e-01 -7.8846217359889637e-01 , 2.4446410077118048e+00 , 9.0084768000000004e+00 , 3.7566100000000002e-01 , -9.1480899999999998e-01 , 1.4833600000000000e-01 -8.7307939131851642e-01 , 2.5196148999752750e+00 , 8.9875728000000006e+00 , -7.0428800000000003e-01 , 6.5931300000000004e-01 , 2.6322099999999998e-01 -9.4674737133912901e-01 , 2.5942655512125326e+00 , 9.0048887999999998e+00 , -8.5216800000000004e-01 , 4.4442500000000001e-01 , 2.7621499999999999e-01 -3.5144155542775235e-01 , 2.7929449025310720e+00 , 1.1808739200000002e+01 , 5.0176900000000002e-01 , 7.3258100000000004e-01 , -4.5994900000000000e-01 -1.1513218515110752e+00 , 2.7303334042427272e+00 , 8.7910544000000002e+00 , -2.1563599999999999e-01 , 2.5321399999999999e-01 , 9.4307099999999999e-01 -1.2235419665042695e+00 , 2.8017511665643582e+00 , 8.8025672000000004e+00 , 1.3264899999999999e-01 , -1.3482300000000000e-01 , 9.8195100000000002e-01 -1.3027794751336468e+00 , 2.8706248373326728e+00 , 8.7818608000000005e+00 , 5.6268799999999997e-01 , -2.1408500000000000e-01 , -7.9846700000000004e-01 -1.3674105300742982e+00 , 2.9455903244687311e+00 , 8.8304392000000007e+00 , -9.6293499999999999e-01 , 2.0555799999999999e-01 , 1.7464600000000000e-01 -1.3984130313873491e+00 , 3.0425609266069786e+00 , 9.0812039999999996e+00 , 1.8757099999999999e-01 , -6.7371400000000004e-01 , 7.1479099999999995e-01 -1.4570851321742144e+00 , 3.1304540850385281e+00 , 9.1979232000000000e+00 , -7.2194199999999997e-01 , 5.7658799999999999e-01 , 3.8255200000000000e-01 -1.5593179914626680e+00 , 3.1840097667920233e+00 , 9.0376072000000001e+00 , 4.8034700000000000e-02 , -8.9619800000000005e-01 , 4.4104500000000002e-01 -1.6681265235748011e+00 , 3.2235647512553238e+00 , 8.8038775999999999e+00 , -2.9865399999999998e-01 , 7.0903300000000002e-01 , 6.3880899999999996e-01 -5.5971890982763228e-01 , 1.9293778567336095e-01 , 1.1091079200000000e+00 , -3.3186100000000003e-02 , 1.6139700000000001e-01 , 9.8633199999999999e-01 -4.8143885576802159e-01 , 1.2388467491052557e-01 , 1.1132887199999999e+00 , -2.1150400000000000e-02 , 1.1668199999999999e-01 , 9.9294400000000005e-01 -3.9133177054329682e-01 , 4.2034812732607563e-02 , 1.1094178399999999e+00 , -4.8570500000000003e-02 , 1.1301000000000000e-01 , 9.9240600000000001e-01 -3.0550006396472762e-01 , -3.2899818615323984e-02 , 1.1144566400000000e+00 , -5.0311500000000002e-02 , 1.2710399999999999e-01 , 9.9061299999999997e-01 -2.2505157397241704e-01 , -1.0104482955667660e-01 , 1.1280255200000000e+00 , -4.0498300000000001e-02 , 1.1878600000000000e-01 , 9.9209400000000003e-01 -1.1893969670978999e-01 , -1.9701583578398063e-01 , 1.1244343999999999e+00 , -6.8113999999999994e-02 , 1.0105600000000001e-01 , 9.9254600000000004e-01 -5.4585360200785082e-03 , -2.9919218636686207e-01 , 1.1200820000000000e+00 , -7.8524499999999997e-02 , 1.5133199999999999e-01 , 9.8535899999999998e-01 --1.0963376063430097e-01 , -4.0142984227866618e-01 , 1.1203628000000001e+00 , -7.6248499999999997e-02 , 1.6511999999999999e-01 , 9.8332200000000003e-01 --2.2531737156122489e-01 , -5.0373430590771795e-01 , 1.1255024800000000e+00 , -7.9849400000000001e-02 , 1.6604500000000000e-01 , 9.8287999999999998e-01 --3.6232549257122937e-01 , -6.2705338896507712e-01 , 1.1218874400000001e+00 , 6.7778099999999994e-02 , -1.8174399999999999e-01 , -9.8100699999999996e-01 --4.8130107245169196e-01 , -7.2934603020240107e-01 , 1.1368998399999999e+00 , -8.5502200000000000e-02 , 1.5962499999999999e-01 , 9.8346800000000001e-01 --6.5342337768447667e-01 , -8.8705472743800717e-01 , 1.1237428000000000e+00 , -5.4452700000000000e-02 , 2.1871800000000000e-01 , 9.7426800000000002e-01 --7.6187632586433685e-01 , -9.7535064181175635e-01 , 1.1577383200000000e+00 , -2.7502099999999999e-03 , 2.8660200000000002e-01 , 9.5804599999999995e-01 --8.9177748309494653e-01 , -1.0833704216615074e+00 , 1.1841886399999999e+00 , -5.2153800000000000e-02 , 2.2347700000000001e-01 , 9.7331299999999998e-01 --1.0894476640009509e+00 , -1.2615703587958036e+00 , 1.1798414399999999e+00 , -8.3475900000000006e-02 , 2.0902200000000001e-01 , 9.7434200000000004e-01 --1.2690718129705103e+00 , -1.4176587439414048e+00 , 1.1942194399999999e+00 , -4.8772500000000003e-02 , 2.1776300000000001e-01 , 9.7478200000000004e-01 --1.4648331153356686e+00 , -1.5887334145069136e+00 , 1.2097924000000000e+00 , -6.6937300000000005e-02 , 2.1479899999999999e-01 , 9.7436199999999995e-01 --1.6888441468234707e+00 , -1.7860254414856307e+00 , 1.2210327200000000e+00 , 6.6409399999999993e-02 , -2.0783900000000000e-01 , -9.7590600000000005e-01 --1.9232717950123916e+00 , -1.9910319058710519e+00 , 1.2391619999999999e+00 , -6.7648700000000006e-02 , 1.9778100000000001e-01 , 9.7790900000000003e-01 --2.2026787448944356e+00 , -2.2368845828221344e+00 , 1.2504834400000000e+00 , 7.6067499999999996e-02 , -2.0209600000000000e-01 , -9.7640700000000002e-01 --2.5193101806664124e+00 , -2.5173954804175329e+00 , 1.2610467200000000e+00 , -9.0459200000000003e-02 , 2.1329400000000001e-01 , 9.7279099999999996e-01 --2.8837641268626095e+00 , -2.8395411680011788e+00 , 1.2708300000000001e+00 , -1.5330700000000000e-01 , 2.8196100000000002e-01 , 9.4709800000000000e-01 --3.3005238101866610e+00 , -3.2103108438621328e+00 , 1.2810719200000000e+00 , 2.1913099999999999e-01 , 4.8192300000000000e-02 , 9.7450499999999995e-01 --3.7370317769804275e+00 , -3.5933288491046680e+00 , 1.3054089599999998e+00 , 4.6508899999999997e-01 , -5.4414700000000005e-01 , -6.9828000000000001e-01 --4.2946900298132302e+00 , -4.0870708079096554e+00 , 1.3182383999999998e+00 , 6.3898099999999999e-02 , -2.4220400000000000e-01 , -9.6811899999999995e-01 --4.7683658067910146e+00 , -4.4943999206984335e+00 , 1.3773187199999999e+00 , -4.4093399999999998e-02 , 2.4346599999999999e-01 , 9.6890699999999996e-01 --5.3338909343624330e+00 , -4.9834121056645468e+00 , 1.4382741600000000e+00 , 3.9610899999999998e-02 , -2.4860599999999999e-01 , -9.6779400000000004e-01 --3.8041531268837963e+00 , -3.4908661709529163e+00 , 1.9155973440000000e+00 , 9.9969600000000003e-01 , 1.5879200000000000e-02 , 1.8876600000000000e-02 --6.6203319832157792e+00 , -6.0864657213323898e+00 , 1.6126936000000001e+00 , 8.2599900000000004e-02 , 3.5269400000000001e-01 , 9.3208599999999997e-01 --3.5062927971895563e+00 , -3.1326214146179785e+00 , 2.2604898400000000e+00 , 9.9833799999999995e-01 , 4.2820999999999998e-02 , -3.8579200000000001e-02 --7.1665956685870995e+00 , -6.4749767158089746e+00 , 1.9868736400000000e+00 , 1.0864100000000000e-01 , 3.5127900000000001e-01 , 9.2994600000000005e-01 --8.0577552356081839e+00 , -7.2319143479908004e+00 , 2.1346893599999999e+00 , 1.3023800000000000e-02 , 2.9081200000000001e-01 , 9.5669199999999999e-01 --9.2834917798498822e+00 , -8.2830709553763331e+00 , 2.3003083200000001e+00 , -3.1135900000000001e-02 , 2.2788200000000000e-01 , 9.7319100000000003e-01 --1.1255589464684691e+01 , -9.9940797431693777e+00 , 2.4888935999999999e+00 , -5.0296399999999998e-02 , 2.2222500000000001e-01 , 9.7369700000000003e-01 --1.4156652323852530e+01 , -1.2516327387069456e+01 , 2.7482425600000000e+00 , 2.0104200000000000e-01 , 9.4204900000000003e-01 , 2.6856300000000000e-01 --1.4193583459912055e+01 , -1.2448259648181251e+01 , 3.1306152000000003e+00 , -2.0663000000000001e-01 , -9.6679400000000004e-01 , -1.5037500000000001e-01 --1.4443043612002981e+01 , -1.2567696515147752e+01 , 3.5176616000000003e+00 , 3.0040299999999998e-01 , 9.4897900000000002e-01 , 9.5898399999999995e-02 --1.4501733301138511e+01 , -1.2516879397350943e+01 , 3.9047600000000000e+00 , -3.6279400000000001e-01 , -9.2754899999999996e-01 , 8.9624899999999993e-02 --1.4523079341015222e+01 , -1.2434085841915861e+01 , 4.2901943999999999e+00 , 3.6073499999999997e-01 , 9.1900300000000001e-01 , -1.5907299999999999e-01 --1.4477412875878922e+01 , -1.2292927547983288e+01 , 4.6686712000000004e+00 , 3.4302199999999999e-01 , 9.3896900000000005e-01 , -2.5944499999999999e-02 --1.4724141717938039e+01 , -1.2403852108005715e+01 , 5.0774848000000006e+00 , -3.0388799999999999e-01 , -9.5268600000000003e-01 , -6.4655299999999997e-03 --1.4769543782412466e+01 , -1.2341109429472999e+01 , 5.4687120000000000e+00 , -3.3552700000000002e-01 , -9.4056399999999996e-01 , 5.2549600000000002e-02 --1.4810675965098230e+01 , -1.2273256593456333e+01 , 5.8601264000000004e+00 , 3.9079000000000003e-01 , 9.0675300000000003e-01 , -1.5837399999999999e-01 --1.4845536907350468e+01 , -1.2201267402592107e+01 , 6.2519776000000000e+00 , 3.9025700000000002e-01 , 9.0832199999999996e-01 , -1.5050500000000000e-01 --1.4883659511173764e+01 , -1.2129939383260766e+01 , 6.6452743999999999e+00 , 4.0870899999999999e-01 , 8.9602099999999996e-01 , -1.7350099999999999e-01 --1.4924222836663684e+01 , -1.2061228427502609e+01 , 7.0407551999999995e+00 , -4.1221300000000000e-01 , -8.9550900000000000e-01 , 1.6775999999999999e-01 --1.4951800185942705e+01 , -1.1980674281224577e+01 , 7.4347799999999999e+00 , -4.1403499999999999e-01 , -8.9411799999999997e-01 , 1.7067099999999999e-01 --1.4989592911156027e+01 , -1.1908356189601593e+01 , 7.8331624000000000e+00 , -4.2057899999999998e-01 , -8.9079299999999995e-01 , 1.7205100000000001e-01 --1.5022081326117647e+01 , -1.1831843073006844e+01 , 8.2323664000000001e+00 , -3.9765499999999998e-01 , -8.9377399999999996e-01 , 2.0745800000000000e-01 --1.5055973990245164e+01 , -1.1755731338574240e+01 , 8.6344823999999996e+00 , 3.5065099999999999e-01 , 9.0482300000000004e-01 , -2.4153400000000000e-01 --1.5085631201226903e+01 , -1.1675386570656068e+01 , 9.0373888000000004e+00 , -3.7974100000000000e-01 , -8.9207400000000003e-01 , 2.4495000000000000e-01 --1.5015458995542566e+01 , -1.1513778503689238e+01 , 9.4065264000000006e+00 , -3.3253899999999997e-01 , -9.2949400000000004e-01 , 1.5955800000000001e-01 --1.5198525242544719e+01 , -1.1553477080972407e+01 , 9.8714168000000004e+00 , -3.0978200000000000e-01 , -9.4836500000000001e-01 , 6.8115899999999993e-02 --1.5273223657246366e+01 , -1.1505873257931590e+01 , 1.0302621600000000e+01 , -3.2473700000000000e-01 , -9.4576300000000002e-01 , 8.8921299999999998e-03 --1.5240761507419769e+01 , -1.1373387122277190e+01 , 1.0693110400000000e+01 , 2.9093599999999997e-01 , 9.4976200000000000e-01 , -1.1535800000000000e-01 --1.5396456392312793e+01 , -1.1386356647896470e+01 , 1.1169919200000001e+01 , -2.7210699999999999e-01 , -9.5932499999999998e-01 , 7.5185900000000000e-02 --1.5422297602963276e+01 , -1.1296568723317950e+01 , 1.1594208000000000e+01 , 2.5380399999999997e-01 , 9.5582400000000001e-01 , -1.4827199999999999e-01 --1.5465635064512128e+01 , -1.1218360388038766e+01 , 1.2031122400000001e+01 , -3.1067000000000000e-01 , -9.3276499999999996e-01 , 1.8284600000000001e-01 --1.5501788771727476e+01 , -1.1134758958264229e+01 , 1.2469992000000000e+01 , -3.1440899999999999e-01 , -9.3159800000000004e-01 , 1.8240500000000001e-01 --1.5539679380036191e+01 , -1.1049917887173894e+01 , 1.2914695999999999e+01 , 2.7879100000000001e-01 , 9.4156899999999999e-01 , -1.8900400000000001e-01 --1.5578361990933118e+01 , -1.0964834125044819e+01 , 1.3365640000000001e+01 , -2.6373600000000003e-01 , -9.3813100000000005e-01 , 2.2439600000000001e-01 --1.5610830539934192e+01 , -1.0873238005834422e+01 , 1.3818664000000002e+01 , -2.2173999999999999e-01 , -9.2422499999999996e-01 , 3.1086799999999998e-01 --7.7130308714082449e+00 , -5.0011363496633132e+00 , 9.3700328000000006e+00 , -6.2575499999999995e-01 , 7.7471400000000001e-01 , 9.0824500000000002e-02 --7.5063690566364176e+00 , -4.7857348971348435e+00 , 9.4871575999999997e+00 , 6.2575499999999995e-01 , -7.7471400000000001e-01 , -9.0824500000000002e-02 --5.4342868032697051e+00 , -3.2362866974282758e+00 , 8.3493352000000005e+00 , 8.2694100000000004e-01 , 2.8603000000000001e-03 , -5.6228199999999995e-01 --7.4813807635855216e+00 , -4.6357479362674310e+00 , 9.9680743999999990e+00 , 5.2552699999999997e-01 , -8.3207299999999995e-01 , -1.7741599999999999e-01 --7.4606557113732404e+00 , -4.5537218432740536e+00 , 1.0205756000000001e+01 , -5.6367299999999998e-01 , 8.1722099999999998e-01 , 1.2009200000000000e-01 --1.5907042494572270e+01 , -1.0358435664232399e+01 , 1.6753232000000001e+01 , -5.5544600000000000e-02 , 9.8261900000000002e-01 , -1.7712900000000001e-01 --7.3920105093143977e+00 , -4.3688763435383517e+00 , 1.0668795200000002e+01 , 5.4612799999999995e-01 , -8.3758500000000002e-01 , -1.3951500000000000e-02 --5.9458477489045807e+00 , -3.3141780085454426e+00 , 9.7772448000000001e+00 , -7.0414900000000002e-01 , 7.0892100000000002e-01 , -4.0062700000000000e-02 --5.7785584042005285e+00 , -3.1419455643646534e+00 , 9.8666951999999988e+00 , -8.6909499999999995e-01 , 3.6185299999999998e-01 , 3.3724900000000002e-01 --5.7657949992818445e+00 , -3.0736199029985052e+00 , 1.0082100000000001e+01 , -5.6569999999999998e-01 , -5.0647299999999999e-02 , 8.2305399999999995e-01 --5.5749052405337336e+00 , -2.8857372174857403e+00 , 1.0143616000000000e+01 , 5.4903800000000003e-01 , -3.3720300000000002e-02 , -8.3511700000000000e-01 --6.1188205855780069e+00 , -3.1797753003309568e+00 , 1.0865979200000000e+01 , 6.8126699999999996e-01 , -7.2952700000000004e-01 , 6.0537899999999999e-02 --5.2887855827938788e+00 , -2.5789294885732685e+00 , 1.0336119999999999e+01 , -4.3777600000000000e-01 , -9.4389599999999997e-03 , 8.9903500000000003e-01 --5.1979915711613289e+00 , -2.4608930325336704e+00 , 1.0477549600000001e+01 , -4.0646100000000002e-01 , -3.7403799999999998e-01 , 8.3359799999999995e-01 --7.1943026618612329e+00 , -3.5739376083939165e+00 , 1.2996440000000000e+01 , 6.4354999999999996e-01 , -6.4871400000000001e-01 , -4.0621900000000000e-01 --7.1845257104458344e+00 , -3.4874243221417993e+00 , 1.3290968000000001e+01 , 6.4354999999999996e-01 , -6.4871299999999998e-01 , -4.0621900000000000e-01 --6.9037276376439536e+00 , -3.2353471971813033e+00 , 1.3294920000000001e+01 , -7.0531200000000005e-01 , 6.3620500000000002e-01 , 3.1269599999999997e-01 --6.9645273190360317e+00 , -3.1896162550202050e+00 , 1.3672336000000000e+01 , 8.5425600000000002e-01 , -3.3353699999999997e-01 , -3.9874900000000002e-01 --6.9107453546450355e+00 , -3.0734690162018614e+00 , 1.3928280000000001e+01 , 5.8625400000000005e-01 , -6.9584699999999999e-01 , -4.1485400000000000e-01 --4.0367310701343966e+00 , -8.6086250188152036e-01 , 1.2595624000000001e+01 , -3.9620800000000000e-01 , -3.9113599999999998e-01 , 8.3068100000000000e-01 --1.7098900553679597e+00 , 3.6027056634970145e-01 , 9.3660808000000007e+00 , 4.6447600000000000e-01 , -1.5424399999999999e-01 , 8.7204999999999999e-01 --4.7651311971440347e-01 , 1.0016966333512305e+00 , 7.6374760000000004e+00 , -7.7614000000000005e-01 , 6.9616499999999998e-02 , 6.2670599999999999e-01 --3.6395603339193228e-01 , 1.0914707395244334e+00 , 7.5958551999999999e+00 , -1.6865300000000000e-01 , -2.9980099999999998e-01 , 9.3897600000000003e-01 --3.4203432565275094e-01 , 1.1377026711409892e+00 , 7.6982536000000001e+00 , -8.7518300000000004e-01 , 1.1388000000000000e-01 , 4.7019899999999998e-01 --3.0302364931152903e-01 , 1.1937019534381799e+00 , 7.7737056000000004e+00 , -9.1637100000000005e-01 , -1.2278300000000000e-01 , 3.8103700000000001e-01 --3.1175684459433795e-01 , 1.2290889595065368e+00 , 7.9369439999999996e+00 , 9.9949399999999999e-01 , 2.7066699999999999e-02 , -1.6684000000000001e-02 --2.4291303270614462e-01 , 1.2980501867999714e+00 , 7.9671560000000010e+00 , -3.0333500000000002e-01 , -7.8791199999999995e-01 , 5.3589399999999998e-01 --4.5859446901713508e-01 , 1.2545596652573352e+00 , 8.5274456000000001e+00 , 6.7989699999999997e-01 , -5.5935699999999999e-01 , -4.7419299999999998e-01 --1.8142939362075783e-01 , 1.4068799702488426e+00 , 8.1673352000000001e+00 , -1.6024400000000000e-01 , -9.5122099999999998e-01 , 2.6362900000000000e-01 --2.7491834974534468e-01 , 1.4168855472899444e+00 , 8.5237952000000003e+00 , -5.8612399999999998e-01 , 8.0992699999999995e-01 , 2.1848599999999999e-02 --1.3696104367673057e-01 , 1.5133788262294698e+00 , 8.4208248000000001e+00 , -5.5887100000000001e-01 , 7.8512700000000002e-01 , 2.6690599999999998e-01 --1.8894784708066492e-01 , 1.5451589126662215e+00 , 8.7150408000000006e+00 , 1.6686000000000001e-01 , 8.5615500000000000e-01 , -4.8903600000000003e-01 --2.0463145643948977e-01 , 1.5923236225638371e+00 , 8.9457960000000014e+00 , 7.0460199999999995e-01 , -6.7033799999999999e-01 , -2.3277300000000001e-01 -4.1054208129945202e-02 , 1.7172411999345667e+00 , 8.5905216000000006e+00 , -9.1426200000000002e-01 , 7.3080900000000002e-04 , 4.0512199999999998e-01 --1.5527916073359016e-02 , 1.7559862281888794e+00 , 8.9235919999999993e+00 , 6.1307000000000000e-02 , 5.8326999999999996e-01 , 8.0996199999999996e-01 -1.3921640152668546e-01 , 1.8512252171844406e+00 , 8.7599896000000008e+00 , 1.6391599999999999e-02 , 6.7208400000000001e-01 , 7.4029400000000001e-01 -1.8451590382072669e-01 , 1.9177652903596227e+00 , 8.8627624000000012e+00 , -6.6767500000000002e-01 , -5.5605599999999999e-01 , 4.9498700000000001e-01 -1.7648253584991536e-01 , 1.9763975684725865e+00 , 9.1099080000000008e+00 , -4.3720799999999999e-01 , -2.7889700000000001e-01 , 8.5502400000000001e-01 -2.4812674711364724e-01 , 2.0520121738296422e+00 , 9.1526519999999998e+00 , 4.4727099999999997e-01 , 9.2809299999999997e-02 , -8.8956999999999997e-01 -3.0126004889808833e-01 , 2.1261304420685718e+00 , 9.2525440000000003e+00 , -4.8455599999999999e-01 , -4.5788400000000001e-01 , 7.4535099999999999e-01 -3.6986627320476750e-01 , 2.2030690035665832e+00 , 9.3117616000000005e+00 , 2.7174500000000001e-01 , 6.9820499999999996e-01 , -6.6231700000000004e-01 -4.4528886526154365e-01 , 2.2807218463544499e+00 , 9.3496176000000002e+00 , 5.6387799999999999e-01 , -3.1278200000000000e-01 , 7.6433600000000002e-01 -5.5296124000279878e-01 , 2.3599384224425455e+00 , 9.2861984000000000e+00 , 1.9967299999999999e-01 , 2.6391300000000001e-01 , 9.4365299999999996e-01 -7.1332608017231958e-01 , 2.4353027468155175e+00 , 9.0304104000000009e+00 , 6.9418199999999997e-01 , 3.9735600000000001e-03 , 7.1978799999999998e-01 -8.4875474364640224e-01 , 2.5059879058742598e+00 , 8.8409536000000006e+00 , 4.6707100000000001e-01 , -8.1695399999999996e-01 , -3.3827600000000002e-01 -8.9310028003022279e-01 , 2.5799823259236176e+00 , 8.9699760000000008e+00 , 8.8805599999999996e-01 , -7.8157199999999996e-02 , -4.5304299999999997e-01 -9.4634672345001580e-01 , 2.6556887288956070e+00 , 9.0777824000000003e+00 , 5.4268600000000000e-01 , -4.9316700000000002e-01 , 6.7991100000000004e-01 -1.0989005560740965e+00 , 2.7122959932304944e+00 , 8.7799367999999998e+00 , 1.3412399999999999e-01 , -2.3815400000000000e-01 , -9.6192200000000005e-01 -1.1730141728031578e+00 , 2.7817853362793872e+00 , 8.7928224000000004e+00 , 3.5209699999999999e-01 , -1.2781000000000001e-01 , -9.2719600000000002e-01 -1.2554005941679760e+00 , 2.8487197840835798e+00 , 8.7631616000000001e+00 , -1.6856599999999999e-01 , 2.8453800000000001e-01 , 9.4372900000000004e-01 -1.3241386771587131e+00 , 2.9196683405592694e+00 , 8.8032120000000003e+00 , -4.8604700000000001e-01 , 4.0080600000000000e-01 , 7.7660300000000004e-01 -1.3561750777131432e+00 , 3.0126378717312532e+00 , 9.0448872000000016e+00 , 6.4964800000000000e-01 , 1.6296800000000000e-01 , -7.4256200000000006e-01 -1.4226079360135389e+00 , 3.0922991654295986e+00 , 9.1224191999999995e+00 , 2.0026300000000000e-01 , -8.4634799999999999e-01 , 4.9354799999999999e-01 -1.5230654022842292e+00 , 3.1481690612462430e+00 , 8.9942288000000001e+00 , -3.0155999999999999e-01 , -6.9473300000000004e-01 , 6.5300000000000002e-01 -1.6064914788437177e+00 , 3.2132779061386838e+00 , 8.9557696000000000e+00 , -1.2999000000000000e-02 , -9.9853499999999995e-01 , -5.2529100000000002e-02 -1.7069168219343618e+00 , 3.2569698722508260e+00 , 8.7829423999999996e+00 , 7.6029999999999998e-01 , 6.4710400000000001e-01 , -5.6577400000000000e-02 -5.4003630625886090e-01 , 2.8155469424297075e-01 , 1.0862393600000000e+00 , -1.1610100000000000e-02 , 1.8593899999999999e-01 , 9.8249299999999995e-01 -4.7135147594170124e-01 , 2.2782776337377819e-01 , 1.1000370399999999e+00 , -2.0462200000000000e-02 , 1.6418400000000000e-01 , 9.8621800000000004e-01 -3.9194552435128238e-01 , 1.6113563373541662e-01 , 1.1051996000000002e+00 , 6.1655300000000003e-02 , -1.3960800000000001e-01 , -9.8828600000000000e-01 -3.0442001877392499e-01 , 8.8903159716676505e-02 , 1.1074491200000001e+00 , -7.0076500000000000e-02 , 1.3541700000000001e-01 , 9.8830700000000005e-01 -2.0968707536374653e-01 , 1.0190414872883968e-02 , 1.1076227999999999e+00 , -5.2384300000000002e-02 , 1.5529299999999999e-01 , 9.8647899999999999e-01 -1.0869352067417504e-01 , -7.5956714142332959e-02 , 1.1064548799999998e+00 , -8.5817199999999996e-02 , 1.5453100000000000e-01 , 9.8425399999999996e-01 --6.5635678354247773e-04 , -1.6836070895717947e-01 , 1.1040972000000000e+00 , -9.0135400000000004e-02 , 1.4176400000000000e-01 , 9.8578800000000000e-01 --1.1743212163150885e-01 , -2.6794717100183973e-01 , 1.1013869599999999e+00 , -9.4625799999999996e-02 , 1.4194200000000001e-01 , 9.8534200000000005e-01 --2.4265236360839282e-01 , -3.7361736118795896e-01 , 1.0982950400000000e+00 , -8.5515200000000000e-02 , 1.6689300000000001e-01 , 9.8226000000000002e-01 --3.6158430553560850e-01 , -4.7230384994250629e-01 , 1.1048709600000000e+00 , -8.4222800000000000e-02 , 1.7952399999999999e-01 , 9.8014199999999996e-01 --4.9601774147616196e-01 , -5.8492456699410855e-01 , 1.1074751200000001e+00 , -7.6074400000000000e-02 , 1.8899700000000000e-01 , 9.7902599999999995e-01 --6.3903091627195696e-01 , -7.0338053147284407e-01 , 1.1109123200000000e+00 , -8.4169599999999997e-02 , 1.6214799999999999e-01 , 9.8316999999999999e-01 --8.0366157614933798e-01 , -8.4234809358090557e-01 , 1.1080231999999999e+00 , -3.8635200000000001e-02 , 2.5401000000000001e-01 , 9.6643000000000001e-01 --9.2829895638815918e-01 , -9.4079041077185543e-01 , 1.1356830400000000e+00 , -3.2944000000000001e-02 , 3.0008499999999999e-01 , 9.5334399999999997e-01 --1.1035539539730199e+00 , -1.0860289040609636e+00 , 1.1416016800000000e+00 , 7.8645000000000007e-02 , -2.3685300000000001e-01 , -9.6835700000000002e-01 --1.2796851142975636e+00 , -1.2308189244148884e+00 , 1.1548075999999998e+00 , -6.3744099999999998e-02 , 2.3201500000000000e-01 , 9.7062099999999996e-01 --1.4788953089275481e+00 , -1.3964486476651681e+00 , 1.1651046400000000e+00 , -6.3395099999999996e-02 , 2.3539299999999999e-01 , 9.6982999999999997e-01 --1.6871543880200321e+00 , -1.5671173508503453e+00 , 1.1800806399999999e+00 , -6.0221499999999997e-02 , 2.2084699999999999e-01 , 9.7344799999999998e-01 --1.9187773498850937e+00 , -1.7581104762794455e+00 , 1.1945761600000000e+00 , -6.8058800000000003e-02 , 2.0730100000000001e-01 , 9.7590699999999997e-01 --2.1892308400239688e+00 , -1.9834294687743110e+00 , 1.2043157600000001e+00 , -7.7444200000000005e-02 , 2.0813699999999999e-01 , 9.7502900000000003e-01 --2.4834383030336573e+00 , -2.2273055535169588e+00 , 1.2170120799999999e+00 , -9.2084700000000005e-02 , 2.0922099999999999e-01 , 9.7352300000000003e-01 --2.8477128911233400e+00 , -2.5329564097080253e+00 , 1.2191336800000001e+00 , -9.4980700000000001e-02 , 2.0419300000000001e-01 , 9.7431199999999996e-01 --3.2435988743134070e+00 , -2.8646783668709999e+00 , 1.2274037600000001e+00 , -1.1143900000000000e-02 , 9.5030199999999995e-02 , 9.9541199999999996e-01 --3.7042380652755469e+00 , -3.2490543759337731e+00 , 1.2345340000000000e+00 , 1.4484900000000001e-01 , 2.7482200000000001e-01 , -9.5052199999999998e-01 --4.2364180568130294e+00 , -3.6947929131498007e+00 , 1.2433386400000002e+00 , -8.6271600000000004e-02 , 2.2663900000000001e-01 , 9.7015099999999999e-01 --4.7424379924696378e+00 , -4.1099731174193233e+00 , 1.2829096000000000e+00 , -4.8266200000000002e-02 , 2.4376999999999999e-01 , 9.6863100000000002e-01 --5.2749081526612231e+00 , -4.5429729768047364e+00 , 1.3390768799999999e+00 , -4.0616300000000001e-02 , 2.4565200000000001e-01 , 9.6850700000000001e-01 --3.7705507175354187e+00 , -3.1508952182526828e+00 , 1.8288160000000000e+00 , 9.9958599999999997e-01 , 8.8133699999999992e-03 , -2.7381300000000001e-02 --3.7514206364022034e+00 , -3.0954984098681138e+00 , 1.9813693360000000e+00 , 9.9833799999999995e-01 , 4.2820999999999998e-02 , -3.8579299999999997e-02 --7.0780616698871572e+00 , -5.9872578188670991e+00 , 1.6174588800000000e+00 , 1.1927400000000001e-01 , 3.5198099999999999e-01 , 9.2837700000000001e-01 --3.8212640587403426e+00 , -3.0810583153443138e+00 , 2.2647694399999998e+00 , 9.9833799999999995e-01 , 4.2820999999999998e-02 , -3.8579200000000001e-02 --7.8953631326681499e+00 , -6.5819251076468746e+00 , 1.9751114480000000e+00 , 7.2185600000000003e-02 , 3.4293099999999999e-01 , 9.3658300000000005e-01 --8.8813738731800242e+00 , -7.3713968756552450e+00 , 2.1309724000000001e+00 , -1.8061000000000001e-02 , 2.6300299999999999e-01 , 9.6462599999999998e-01 --1.0440051592428798e+01 , -8.6400378920104970e+00 , 2.2951072799999999e+00 , -4.2985500000000003e-02 , 2.2633300000000001e-01 , 9.7310099999999999e-01 --1.2987911951507511e+01 , -1.0731710599606391e+01 , 2.4899585599999998e+00 , -2.6322700000000001e-02 , 3.1728800000000001e-01 , 9.4796400000000003e-01 --1.5015749897580690e+01 , -1.2355150928743830e+01 , 2.8060031200000002e+00 , 3.5053400000000001e-01 , 9.3078200000000000e-01 , 1.0377699999999999e-01 --1.5194353325229244e+01 , -1.2404301695169053e+01 , 3.1985375999999999e+00 , 3.8689899999999999e-01 , 9.1513199999999995e-01 , 1.1332700000000000e-01 --1.5407825262888782e+01 , -1.2480364208353151e+01 , 3.5976584000000003e+00 , -3.9875800000000000e-01 , -9.1505700000000001e-01 , -6.0525400000000000e-02 --1.5432636818184740e+01 , -1.2398273147671764e+01 , 3.9946888000000000e+00 , -2.7549000000000001e-01 , -9.5957599999999998e-01 , 5.7613200000000003e-02 --1.5460540598784782e+01 , -1.2319249562608665e+01 , 4.3914488000000000e+00 , 2.2646200000000000e-01 , 9.7263999999999995e-01 , -5.1834800000000000e-02 --1.5587483870685404e+01 , -1.2320151271632737e+01 , 4.7972256000000000e+00 , 2.0240200000000000e-01 , 9.7772700000000001e-01 , -5.5527899999999998e-02 --1.5797122582630568e+01 , -1.2387902569465121e+01 , 5.2173232000000009e+00 , 1.9190900000000000e-01 , 9.7491300000000003e-01 , -1.1276300000000000e-01 --1.5824726106969994e+01 , -1.2306695814647291e+01 , 5.6200736000000004e+00 , -2.3002300000000001e-01 , -9.6152300000000002e-01 , 1.5020900000000001e-01 --1.5854532070484954e+01 , -1.2227187676183453e+01 , 6.0238952000000001e+00 , -2.1368400000000001e-01 , -9.5715399999999995e-01 , 1.9543600000000000e-01 --1.5878976567333890e+01 , -1.2142719508365971e+01 , 6.4273216000000000e+00 , -2.2229099999999999e-01 , -9.5534600000000003e-01 , 1.9468299999999999e-01 --1.5898173225312330e+01 , -1.2054301216420139e+01 , 6.8305503999999999e+00 , 2.3208100000000001e-01 , 9.5228599999999997e-01 , -1.9821500000000000e-01 --1.5927222322038457e+01 , -1.1973291989916262e+01 , 7.2369200000000005e+00 , -2.4213599999999999e-01 , -9.4947800000000004e-01 , 1.9965400000000000e-01 --1.5943378408738827e+01 , -1.1881551405041900e+01 , 7.6414280000000003e+00 , 2.4976100000000001e-01 , 9.4815099999999997e-01 , -1.9654199999999999e-01 --1.5969529488236983e+01 , -1.1798087093141056e+01 , 8.0500959999999999e+00 , -2.6769199999999999e-01 , -9.4065500000000002e-01 , 2.0858900000000000e-01 --1.6005911102891510e+01 , -1.1721737087279044e+01 , 8.4635168000000007e+00 , -2.9061700000000001e-01 , -9.3030700000000000e-01 , 2.2376299999999999e-01 --1.5956304612453170e+01 , -1.1579599714769804e+01 , 8.8527471999999996e+00 , 3.2557300000000000e-01 , 8.9203200000000005e-01 , -3.1349900000000003e-01 --1.5957530542835464e+01 , -1.1474613739778199e+01 , 9.2576712000000008e+00 , -2.8133000000000002e-01 , -9.4786599999999999e-01 , 1.4967900000000001e-01 --1.5688867403914763e+01 , -1.1168797856658443e+01 , 9.5679344000000004e+00 , -2.9653400000000002e-01 , -9.4926500000000003e-01 , 1.0470500000000001e-01 --1.6262733829037320e+01 , -1.1489716522549120e+01 , 1.0187452000000000e+01 , -2.0210200000000000e-01 , -9.7857899999999998e-01 , 3.9231799999999997e-02 --1.6133660457302160e+01 , -1.1287835829074297e+01 , 1.0552856000000000e+01 , 2.1465300000000001e-01 , 9.7666100000000000e-01 , -7.5447999999999999e-03 --1.6516411922868645e+01 , -1.1459568833066387e+01 , 1.1131480800000000e+01 , -1.6844100000000001e-01 , -9.7916000000000003e-01 , 1.1346400000000000e-01 --1.6534057015584253e+01 , -1.1361529716734090e+01 , 1.1566897600000001e+01 , -1.7357200000000000e-01 , -9.7528400000000004e-01 , 1.3672300000000001e-01 --1.6554339126326980e+01 , -1.1263568854888248e+01 , 1.2006620000000002e+01 , 1.5573100000000001e-01 , 9.6681799999999996e-01 , -2.0251000000000000e-01 --1.6583097667872938e+01 , -1.1171952875090021e+01 , 1.2455224000000001e+01 , 1.6232300000000000e-01 , 9.6571799999999997e-01 , -2.0258399999999999e-01 --1.6612511856440101e+01 , -1.1079196418644255e+01 , 1.2909288000000000e+01 , 1.6801600000000000e-01 , 9.6528099999999994e-01 , -2.0000799999999999e-01 --1.6651625609961314e+01 , -1.0991462280263111e+01 , 1.3373232000000002e+01 , 1.6737700000000000e-01 , 9.6632399999999996e-01 , -1.9545399999999999e-01 --1.6675584680644196e+01 , -1.0892113858775838e+01 , 1.3834887999999999e+01 , 2.2392599999999999e-01 , 9.5628899999999994e-01 , -1.8806700000000001e-01 --8.2244688980815432e+00 , -4.9500196698067080e+00 , 9.3354216000000001e+00 , -6.2575499999999995e-01 , 7.7471400000000001e-01 , 9.0824500000000002e-02 --5.5961550469239691e+00 , -3.0897112018403563e+00 , 7.9882575999999998e+00 , -7.0334900000000000e-01 , 4.3470300000000001e-01 , 5.6243600000000005e-01 --5.3887152450097053e+00 , -2.8989299520211684e+00 , 8.0518847999999998e+00 , 9.3673499999999998e-01 , -3.3748800000000001e-01 , -9.2891399999999999e-02 --5.5751445609246106e+00 , -2.9739674944658709e+00 , 8.3669632000000007e+00 , -6.2830500000000000e-01 , -2.7133200000000002e-01 , 7.2911700000000002e-01 --5.4329049868469355e+00 , -2.8278767652932046e+00 , 8.4689040000000002e+00 , 8.3755100000000005e-01 , 3.7993300000000001e-02 , -5.4503699999999999e-01 --5.2889661224438171e+00 , -2.6818978684497861e+00 , 8.5653952000000011e+00 , 9.1773099999999996e-01 , -3.8054700000000002e-01 , -1.1381500000000000e-01 --6.1390430254313415e+00 , -3.1838215342117602e+00 , 9.3869640000000008e+00 , -6.4463499999999996e-01 , 7.5992899999999997e-01 , -8.3385299999999996e-02 --5.4484622961275386e+00 , -2.6809834388282230e+00 , 9.0840016000000006e+00 , -9.0066999999999997e-01 , -4.1841299999999998e-01 , -1.1715399999999999e-01 --5.4946071893473292e+00 , -2.6572401284546858e+00 , 9.3290463999999993e+00 , 9.9023600000000001e-01 , 5.4514699999999999e-02 , 1.2829699999999999e-01 --5.4942232871449139e+00 , -2.6018125985073848e+00 , 9.5409568000000000e+00 , -9.5788099999999998e-01 , 5.3757399999999997e-02 , -2.8209000000000001e-01 --5.8998664348027896e+00 , -2.7981886989052995e+00 , 1.0097710400000000e+01 , 6.4102300000000001e-01 , -2.4876200000000001e-02 , -7.6711799999999997e-01 --5.6539118459423943e+00 , -2.5865479407521645e+00 , 1.0114953600000000e+01 , 5.2689200000000003e-01 , -1.4727399999999999e-01 , -8.3707500000000001e-01 --5.5913732537111338e+00 , -2.4886283683096115e+00 , 1.0287572800000000e+01 , -5.9951600000000005e-01 , -1.4777799999999999e-01 , 7.8660200000000002e-01 --4.8905119205194465e+00 , -2.0080809619459412e+00 , 9.8709176000000003e+00 , -6.6411600000000004e-01 , 3.7176799999999999e-01 , 6.4864400000000000e-01 --5.0225968503659777e+00 , -2.0302080552588171e+00 , 1.0212474400000000e+01 , -9.3870100000000001e-01 , -3.8837199999999998e-03 , -3.4471099999999999e-01 --7.8163534047262289e+00 , -3.6088380994206615e+00 , 1.3185927999999999e+01 , 6.4354999999999996e-01 , -6.4871299999999998e-01 , -4.0621900000000000e-01 --5.1588358691220328e+00 , -1.9922670763944370e+00 , 1.0803891200000001e+01 , -8.7951900000000005e-01 , -1.1778600000000000e-01 , 4.6105499999999999e-01 --7.3047108266903393e+00 , -3.1527143026380884e+00 , 1.3287536000000001e+01 , -5.7802200000000004e-01 , 7.5450300000000003e-01 , 3.1083000000000000e-01 --7.1030585847323078e+00 , -2.9575670337817188e+00 , 1.3382175999999999e+01 , -7.0531200000000005e-01 , 6.3620500000000002e-01 , 3.1269599999999997e-01 --6.6064999531876403e+00 , -2.6020844789160158e+00 , 1.3144328000000000e+01 , 7.9237000000000002e-01 , -5.7132700000000003e-01 , -2.1385799999999999e-01 --5.0016077849666383e+00 , -1.6501568505770492e+00 , 1.1613167200000001e+01 , -8.8341899999999995e-01 , -3.8707500000000000e-01 , 2.6408999999999999e-01 --4.1861796586495856e+00 , -7.5048025706534727e-01 , 1.2436920000000001e+01 , -3.1905600000000001e-01 , -3.3775300000000003e-01 , 8.8550899999999999e-01 --1.7921311245561640e+00 , 4.3471851046919641e-01 , 9.2437247999999990e+00 , 4.6447600000000000e-01 , -1.5424399999999999e-01 , 8.7204999999999999e-01 --1.7518058064386155e+00 , 5.0203088031841880e-01 , 9.3703448000000016e+00 , 4.4915300000000002e-01 , -2.4425600000000000e-01 , 8.5941800000000002e-01 --3.9406671353344560e+00 , -4.1295970878030230e-01 , 1.2941840000000001e+01 , -3.0874800000000002e-01 , -3.8933600000000002e-01 , 8.6780800000000002e-01 --3.6088996742542712e-01 , 1.2005155082065166e+00 , 7.5527471999999998e+00 , -6.5968899999999997e-01 , -3.9642100000000002e-01 , 6.3848400000000005e-01 --3.9072087910380304e-01 , 1.2238199583900533e+00 , 7.7411120000000002e+00 , 9.1823699999999997e-01 , -1.8455400000000000e-01 , -3.5040100000000002e-01 --6.0825624402747591e-01 , 1.1743464976375737e+00 , 8.2554856000000001e+00 , -5.0669100000000000e-01 , 7.9306200000000004e-01 , 3.3810899999999999e-01 --4.1686792117308125e-01 , 1.2914028207663231e+00 , 8.0867767999999991e+00 , 5.6688899999999998e-01 , -5.4288300000000000e-01 , 6.1960899999999997e-01 --3.0561628501525817e-01 , 1.3751056731643962e+00 , 8.0463728000000003e+00 , -2.2838500000000000e-01 , -8.0364599999999997e-01 , 5.4954000000000003e-01 --3.1125155262656046e-01 , 1.4155212592586177e+00 , 8.2194080000000014e+00 , 5.6537099999999996e-01 , -8.2033699999999998e-01 , -8.6048700000000006e-02 --9.4845793524229061e-01 , 1.2408625886306948e+00 , 9.6145367999999998e+00 , 1.4683700000000000e-01 , 4.3942799999999999e-01 , -8.8619499999999995e-01 --8.8072350336939476e-01 , 1.3196414675330206e+00 , 9.6985063999999994e+00 , -3.7085600000000002e-01 , 4.7791699999999999e-02 , 9.2745999999999995e-01 --3.3646068740044477e-01 , 1.5457971822941567e+00 , 8.8079439999999991e+00 , -1.8437799999999999e-01 , -7.8293699999999999e-01 , 5.9414999999999996e-01 -1.6615450942581322e-02 , 1.7005965026204226e+00 , 8.2549759999999992e+00 , -1.7447299999999999e-01 , 4.8931599999999997e-01 , 8.5447600000000001e-01 -2.7249259489578126e-02 , 1.7506885807892050e+00 , 8.4162904000000012e+00 , -8.7154900000000002e-01 , -4.8978500000000003e-01 , 2.2654799999999999e-02 --5.7360329569149116e-01 , 1.6509988482206976e+00 , 9.9804504000000005e+00 , -5.8406400000000003e-01 , -2.8482900000000000e-01 , 7.6009300000000002e-01 -3.5312329136844678e-02 , 1.8556028865881653e+00 , 8.7964416000000014e+00 , -9.4410200000000005e-04 , 7.4909599999999998e-01 , 6.6246099999999997e-01 -1.2386927992511931e-01 , 1.9300234941258836e+00 , 8.7947152000000006e+00 , 5.3079200000000004e-01 , -3.8525900000000002e-01 , -7.5487499999999996e-01 -9.9462880241499629e-02 , 1.9834182308620396e+00 , 9.0808815999999997e+00 , -9.8615600000000003e-01 , 1.0636300000000000e-01 , 1.2721700000000000e-01 -1.5775432967533343e-01 , 2.0549667611716336e+00 , 9.1638424000000001e+00 , 7.0535000000000003e-01 , 6.3681699999999994e-02 , -7.0599299999999998e-01 -2.5107422120446454e-01 , 2.1314893588151058e+00 , 9.1577584000000005e+00 , -2.9088100000000000e-01 , -4.8644999999999999e-01 , 8.2386599999999999e-01 -3.2053100665877121e-01 , 2.2054359811405155e+00 , 9.2181200000000008e+00 , -4.2171999999999998e-01 , -6.1057799999999995e-01 , 6.7033299999999996e-01 -3.3081219649838589e-01 , 2.2759559219974403e+00 , 9.4543768000000004e+00 , -3.2102999999999998e-01 , -3.8320300000000002e-01 , 8.6607999999999996e-01 -4.7761589416131089e-01 , 2.3543545472644887e+00 , 9.2845551999999998e+00 , 1.9967299999999999e-01 , 2.6391300000000001e-01 , 9.4365299999999996e-01 -5.9191879380287671e-01 , 2.4291297944126433e+00 , 9.2004920000000006e+00 , 1.6104599999999999e-01 , 3.9556599999999997e-01 , 9.0420800000000001e-01 -7.8879981923585785e-01 , 2.4966846963610911e+00 , 8.8241575999999995e+00 , -2.2285699999999999e-02 , 9.5578900000000000e-01 , 2.9320800000000002e-01 -8.5631340796503719e-01 , 2.5665021567657895e+00 , 8.8741400000000006e+00 , -1.6452300000000000e-02 , -9.2308199999999996e-01 , 3.8425100000000001e-01 -9.2176839544884959e-01 , 2.6370313841911992e+00 , 8.9324943999999995e+00 , -7.8354299999999999e-01 , 3.0296600000000001e-01 , 5.4246899999999998e-01 -9.8954185361940405e-01 , 2.7092678925887741e+00 , 8.9892783999999999e+00 , -9.5322899999999999e-01 , 2.2744900000000001e-01 , -1.9905200000000001e-01 -1.1228775099765351e+00 , 2.7648212058539987e+00 , 8.7717000000000009e+00 , -1.8350400000000000e-01 , 2.1086500000000000e-01 , 9.6013700000000002e-01 -1.1945307118615545e+00 , 2.8331464555684804e+00 , 8.8046264000000001e+00 , 1.0438400000000000e-01 , -2.9107000000000000e-01 , 9.5099000000000000e-01 -1.2767130744371413e+00 , 2.8978471977524678e+00 , 8.7849183999999987e+00 , -5.1780099999999996e-01 , -2.7609999999999999e-02 , 8.5505600000000004e-01 -1.3555857084608542e+00 , 2.9632703178437247e+00 , 8.7839096000000012e+00 , -3.7088700000000002e-01 , -1.8328900000000001e-01 , 9.1041099999999997e-01 -1.3873074437347122e+00 , 3.0581795189343297e+00 , 9.0456672000000005e+00 , 6.1866800000000000e-01 , -4.2429200000000000e-01 , -6.6123100000000001e-01 -1.4640047218059604e+00 , 3.1292038743016377e+00 , 9.0719999999999992e+00 , 4.1731699999999999e-01 , -4.1001300000000002e-01 , -8.1100899999999998e-01 -1.5560900624080809e+00 , 3.1891917713718119e+00 , 9.0046184000000018e+00 , -2.8285500000000002e-01 , 9.4658200000000003e-01 , 1.5484200000000001e-01 -1.6580662926894214e+00 , 3.2351294152471550e+00 , 8.8538600000000010e+00 , -1.6081400000000001e-01 , -3.0946200000000000e-02 , 9.8650000000000004e-01 -5.3369862187831218e-01 , 3.8280913830728114e-01 , 1.0762314399999999e+00 , -3.2224200000000001e-02 , 2.0848400000000000e-01 , 9.7749500000000000e-01 -4.6524986424756332e-01 , 3.3084912862669058e-01 , 1.0883027200000002e+00 , -3.7519799999999999e-02 , 2.0087600000000000e-01 , 9.7889800000000005e-01 -3.8409074743935556e-01 , 2.6694262590504536e-01 , 1.0910805600000000e+00 , -3.2643999999999999e-02 , 1.9629400000000000e-01 , 9.8000200000000004e-01 -2.9481414280524953e-01 , 1.9748558611061195e-01 , 1.0909453600000001e+00 , 9.0979599999999994e-02 , -2.0530200000000001e-01 , -9.7446100000000002e-01 -1.9932004004801129e-01 , 1.2048617485032964e-01 , 1.0889641600000000e+00 , -8.4638099999999994e-02 , 1.7817100000000000e-01 , 9.8035300000000003e-01 -1.0240239658072170e-01 , 4.4227515428941322e-02 , 1.0902963999999999e+00 , -1.0398800000000000e-01 , 1.9215299999999999e-01 , 9.7584000000000004e-01 --2.8489799960622619e-03 , -3.8347099785493555e-02 , 1.0901352000000000e+00 , 1.1116800000000000e-01 , -1.8586300000000000e-01 , -9.7626700000000000e-01 --1.2123122368963113e-01 , -1.3430111276669399e-01 , 1.0840252000000001e+00 , 7.7020500000000006e-02 , -1.7426000000000000e-01 , -9.8168299999999997e-01 --2.3540158727812655e-01 , -2.2323603994556418e-01 , 1.0873313599999999e+00 , -9.2584299999999994e-02 , 1.6273599999999999e-01 , 9.8231599999999997e-01 --3.7071369411196153e-01 , -3.3131274423075574e-01 , 1.0806628799999998e+00 , -9.9072800000000003e-02 , 1.7392299999999999e-01 , 9.7976300000000005e-01 --5.0673928388362866e-01 , -4.4031933144267743e-01 , 1.0797664000000000e+00 , -8.2661899999999996e-02 , 1.9406999999999999e-01 , 9.7749900000000001e-01 --6.4545396557763235e-01 , -5.4820501530764165e-01 , 1.0838795999999999e+00 , 7.7879400000000001e-02 , -2.0395400000000000e-01 , -9.7587800000000002e-01 --7.9283970048935171e-01 , -6.6288888257227629e-01 , 1.0893354400000002e+00 , 9.0432399999999996e-02 , -1.7647199999999999e-01 , -9.8014299999999999e-01 --9.6877874102217065e-01 , -8.0391531339682532e-01 , 1.0843621600000000e+00 , -8.1563700000000003e-02 , 2.5806499999999999e-01 , 9.6267800000000003e-01 --1.1117045294528651e+00 , -9.1128574426354181e-01 , 1.1059390400000000e+00 , -9.2961500000000002e-02 , 2.9033399999999998e-01 , 9.5239900000000000e-01 --1.2983847120829162e+00 , -1.0583733301634091e+00 , 1.1107854399999999e+00 , -5.8291200000000001e-02 , 2.6157500000000000e-01 , 9.6342099999999997e-01 --1.4799427049817422e+00 , -1.1971218682976539e+00 , 1.1264852799999998e+00 , 6.5974400000000002e-02 , -2.4438799999999999e-01 , -9.6743100000000004e-01 --1.6926901873211988e+00 , -1.3633946538707078e+00 , 1.1359617599999998e+00 , -5.3727400000000002e-02 , 2.3463300000000001e-01 , 9.7059799999999996e-01 --1.9135221044407449e+00 , -1.5345958079411921e+00 , 1.1508493600000000e+00 , 7.1517700000000003e-02 , -2.1929699999999999e-01 , -9.7303300000000004e-01 --2.1821156686481471e+00 , -1.7449575408257729e+00 , 1.1562199199999998e+00 , -8.3193299999999998e-02 , 2.1739300000000000e-01 , 9.7253199999999995e-01 --2.4673348234025658e+00 , -1.9683671576369912e+00 , 1.1670307200000001e+00 , -8.8649599999999995e-02 , 2.1319099999999999e-01 , 9.7297999999999996e-01 --2.8080168645046122e+00 , -2.2365520739092970e+00 , 1.1703972000000000e+00 , -9.7443900000000000e-02 , 2.0849400000000001e-01 , 9.7315700000000005e-01 --3.1903620521732927e+00 , -2.5376527024164464e+00 , 1.1754339200000001e+00 , 2.9539300000000001e-02 , 1.9096600000000000e-01 , 9.8115200000000002e-01 --3.6136197181028900e+00 , -2.8701373770411713e+00 , 1.1845921600000000e+00 , -6.3831499999999999e-02 , -1.8871900000000000e-02 , 9.9778199999999995e-01 --4.2323048578250777e+00 , -3.3663919924702057e+00 , 1.1561086400000000e+00 , -3.2098300000000002e-01 , 2.5385799999999997e-01 , 9.1242900000000005e-01 --4.7099555089332501e+00 , -3.7354764438615096e+00 , 1.1933531199999998e+00 , -4.7364200000000002e-02 , 2.3845900000000000e-01 , 9.6999700000000000e-01 --5.2230625646901760e+00 , -4.1281536803826731e+00 , 1.2429424000000000e+00 , -4.4093399999999998e-02 , 2.4346599999999999e-01 , 9.6890699999999996e-01 --3.7324878201583971e+00 , -2.8218307060637402e+00 , 1.7468421599999999e+00 , -9.5886000000000005e-01 , 5.9187600000000000e-02 , -2.7764100000000003e-01 --6.4940653206710817e+00 , -5.1029467082948665e+00 , 1.3615824800000000e+00 , 1.2633399999999999e-02 , 2.5346900000000000e-01 , 9.6726100000000004e-01 --3.7682800869882396e+00 , -2.7791164912871418e+00 , 2.0302358159999998e+00 , -9.4777599999999995e-01 , -1.1431999999999999e-02 , -3.1873200000000002e-01 --7.5176720534159340e+00 , -5.8455175509765631e+00 , 1.6263706400000000e+00 , 1.0082500000000000e-01 , 3.7707299999999999e-01 , 9.2067900000000003e-01 --7.8911393401002332e+00 , -6.0955067878905318e+00 , 1.8077955200000000e+00 , 7.2185500000000000e-02 , 3.4293099999999999e-01 , 9.3658300000000005e-01 --8.7225258440254620e+00 , -6.7154407945221628e+00 , 1.9580968400000001e+00 , -8.3577700000000005e-03 , 3.0304799999999998e-01 , 9.5293899999999998e-01 --9.9689309043094347e+00 , -7.6620189966578049e+00 , 2.1113330399999999e+00 , -3.8138800000000000e-02 , 2.6208599999999999e-01 , 9.6429100000000001e-01 --1.2126929410774146e+01 , -9.3291197386655114e+00 , 2.2673288800000000e+00 , 8.3153500000000005e-02 , 1.3000200000000001e-01 , 9.8802100000000004e-01 --1.5642204024367512e+01 , -1.2058060522397351e+01 , 2.4709941600000001e+00 , 2.5301499999999999e-01 , 8.4503399999999995e-01 , 4.7106399999999998e-01 --1.6723646275994628e+01 , -1.2815432547121681e+01 , 2.8553948000000000e+00 , 6.4461400000000002e-02 , 8.6014199999999996e-01 , 5.0596399999999997e-01 --1.7371679205374278e+01 , -1.3220148183162143e+01 , 3.2804479999999998e+00 , 9.3167000000000000e-02 , -9.9161100000000002e-01 , 8.9599700000000004e-02 --1.7615200305159505e+01 , -1.3301877502108251e+01 , 3.7187872000000000e+00 , 9.3167000000000000e-02 , -9.9161100000000002e-01 , 8.9599700000000004e-02 --1.7131933050551531e+01 , -1.2816699869466685e+01 , 4.1268832000000000e+00 , 1.6151299999999999e-01 , -9.8063299999999998e-01 , 1.1077900000000000e-01 --1.6846648376132308e+01 , -1.2489230978465546e+01 , 4.5272208000000003e+00 , -1.4631100000000000e-01 , 9.8351000000000000e-01 , -1.0630800000000000e-01 --1.7887108137849111e+01 , -1.3181799687496063e+01 , 5.0418023999999999e+00 , -1.2561200000000000e-01 , 9.8568800000000001e-01 , -1.1243200000000000e-01 --1.7894316775399115e+01 , -1.3076615134596542e+01 , 5.4780511999999995e+00 , -1.3259899999999999e-01 , 9.8599400000000004e-01 , -1.0115900000000000e-01 --1.8001939564251252e+01 , -1.3048238845485955e+01 , 5.9279448000000006e+00 , -1.3073599999999999e-01 , 9.8770400000000003e-01 , -8.5721199999999997e-02 --1.8037482394955145e+01 , -1.2965033549587469e+01 , 6.3702984000000002e+00 , -5.7403799999999998e-02 , 9.7935099999999997e-01 , -1.9384799999999999e-01 --1.8075226294768335e+01 , -1.2882486662966034e+01 , 6.8141287999999998e+00 , -6.0698500000000002e-02 , 9.7797000000000001e-01 , -1.9972799999999999e-01 --1.8107840811923456e+01 , -1.2795928772287377e+01 , 7.2581671999999999e+00 , -5.9689800000000001e-02 , 9.7675400000000001e-01 , -2.0588500000000001e-01 --1.8124169119269983e+01 , -1.2697580284250208e+01 , 7.7006144000000001e+00 , -8.6905700000000002e-02 , 9.6624600000000005e-01 , -2.4252000000000001e-01 --1.8160386888539250e+01 , -1.2612092377703153e+01 , 8.1486359999999998e+00 , -8.9609200000000000e-02 , 9.6787699999999999e-01 , -2.3491500000000001e-01 --1.8139792999232480e+01 , -1.2485970156007449e+01 , 8.5840423999999995e+00 , 2.8613900000000001e-02 , -9.7056200000000004e-01 , 2.3914600000000000e-01 --1.8163187311856564e+01 , -1.2390454739317329e+01 , 9.0320224000000007e+00 , 2.6391600000000001e-02 , -9.7637499999999999e-01 , 2.1446699999999999e-01 --1.7744234133819674e+01 , -1.1980094508075773e+01 , 9.3452599999999997e+00 , -1.6065900000000000e-01 , 9.6691300000000002e-01 , -1.9816300000000001e-01 --1.8271775120383541e+01 , -1.2242151617842058e+01 , 9.9557192000000008e+00 , 2.7075900000000000e-02 , -9.8515699999999995e-01 , 1.6950799999999999e-01 --1.8185334615306854e+01 , -1.2068141115746561e+01 , 1.0374038400000000e+01 , 6.8587300000000004e-02 , -9.8543099999999995e-01 , 1.5563299999999999e-01 --1.8451577254076273e+01 , -1.2140384214811714e+01 , 1.0923179200000002e+01 , -9.5632099999999998e-02 , 9.8300600000000005e-01 , -1.5669500000000000e-01 --1.8489653153968842e+01 , -1.2050964691250408e+01 , 1.1395817600000001e+01 , -7.6636499999999996e-02 , 9.8209500000000005e-01 , -1.7209300000000000e-01 --1.8529330273359257e+01 , -1.1961498347610807e+01 , 1.1873489600000001e+01 , -9.5096799999999995e-02 , 9.7893900000000000e-01 , -1.8065500000000001e-01 --1.8570702970622239e+01 , -1.1870996216503604e+01 , 1.2356091200000000e+01 , 9.5375799999999997e-02 , -9.7453299999999998e-01 , 2.0295099999999999e-01 --1.8611678290994046e+01 , -1.1780360475492744e+01 , 1.2844600000000000e+01 , 1.1521500000000000e-01 , -9.6830000000000005e-01 , 2.2163300000000000e-01 --7.1558700591347808e+00 , -4.0094115141317355e+00 , 7.7495567999999997e+00 , 5.7448399999999999e-01 , -7.9713999999999996e-01 , -1.8583900000000000e-01 --7.1053852343935731e+00 , -3.9218091121237473e+00 , 7.9421232000000002e+00 , 5.7448399999999999e-01 , -7.9713999999999996e-01 , -1.8583900000000000e-01 --1.8516570927758423e+01 , -1.1355954495723600e+01 , 1.4228320000000000e+01 , 1.1488900000000001e-01 , -9.6795600000000004e-01 , 2.2329700000000000e-01 --5.8896805743925844e+00 , -3.0190402071829281e+00 , 7.7071975999999998e+00 , -5.9920700000000005e-01 , -4.7613800000000001e-01 , 6.4361699999999999e-01 --7.0631490001770665e+00 , -3.7259858397805239e+00 , 8.5805584000000010e+00 , -6.9222700000000004e-01 , 6.9077699999999997e-01 , 2.0892100000000000e-01 --5.3831883829045459e+00 , -2.5964529318897371e+00 , 7.7941104000000001e+00 , -9.1514799999999996e-01 , 3.1704300000000002e-01 , 2.4897300000000000e-01 --5.7082603744457741e+00 , -2.7553370715394188e+00 , 8.1852023999999997e+00 , 3.6766199999999999e-01 , 5.4122499999999996e-01 , -7.5624100000000005e-01 --5.6633715587546227e+00 , -2.6766154492354683e+00 , 8.3536199999999994e+00 , -3.7594699999999998e-01 , -6.3894600000000001e-01 , 6.7112700000000003e-01 --5.4093567102254134e+00 , -2.4695591486152679e+00 , 8.3814191999999998e+00 , -5.1465700000000003e-01 , -4.6980600000000000e-01 , 7.1722399999999997e-01 --5.4752741118037260e+00 , -2.4605097287684830e+00 , 8.6231048000000001e+00 , -2.7582099999999998e-01 , -7.2971200000000003e-01 , 6.2565400000000004e-01 --5.3557897371993359e+00 , -2.3366468367081188e+00 , 8.7363607999999999e+00 , -8.4354899999999999e-01 , -5.2188699999999999e-01 , 1.2672100000000000e-01 --5.4378643129972213e+00 , -2.3356796585873898e+00 , 8.9976920000000007e+00 , 9.8221700000000001e-01 , 1.6477000000000000e-01 , -9.0003299999999994e-02 --5.3874780728189204e+00 , -2.2532968874134687e+00 , 9.1643831999999996e+00 , 9.9023600000000001e-01 , 5.4514699999999999e-02 , 1.2829699999999999e-01 --6.0506264341404741e+00 , -2.5907221691632190e+00 , 9.9042080000000006e+00 , -9.5763100000000001e-01 , 2.6348700000000003e-01 , -1.1626800000000000e-01 --5.8436164322803181e+00 , -2.4119023394701484e+00 , 9.9610544000000001e+00 , -9.6373500000000001e-01 , 1.9541000000000000e-01 , -1.8173900000000001e-01 --5.7009086351382328e+00 , -2.2725186836593867e+00 , 1.0066676800000000e+01 , 7.0516400000000001e-01 , 8.0446900000000002e-02 , -7.0446600000000004e-01 --5.1845842404803690e+00 , -1.9224630550759398e+00 , 9.8378143999999992e+00 , 7.0656399999999997e-01 , 8.6887500000000006e-02 , -7.0229500000000000e-01 --5.0359836694051356e+00 , -1.7847712093765140e+00 , 9.9205360000000002e+00 , 8.1820499999999996e-01 , 3.4714699999999998e-01 , -4.5829100000000000e-01 --5.5332687399427511e+00 , -2.0030772887954784e+00 , 1.0607092000000000e+01 , -6.3010800000000000e-01 , -1.5911900000000001e-01 , 7.6002999999999998e-01 --5.3969821677208687e+00 , -1.8697598539866371e+00 , 1.0712891200000000e+01 , 6.4274600000000004e-01 , 3.2676799999999999e-02 , -7.6538200000000001e-01 --5.1985047641653859e+00 , -1.7015621247003190e+00 , 1.0752109600000001e+01 , 9.2550699999999997e-01 , -1.7302500000000001e-01 , -3.3689599999999997e-01 --5.1484434803140822e+00 , -1.6150112273640151e+00 , 1.0939392800000000e+01 , -9.2824600000000002e-01 , -3.2761299999999999e-01 , 1.7615100000000000e-01 --5.2362662927965191e+00 , -1.5997164494841369e+00 , 1.1275874399999999e+01 , -8.8341899999999995e-01 , -3.8707500000000000e-01 , 2.6408999999999999e-01 --5.1850214412647668e+00 , -1.5094768858054013e+00 , 1.1471196800000001e+01 , -8.8341899999999995e-01 , -3.8707500000000000e-01 , 2.6408999999999999e-01 --6.3455285370194900e+00 , -2.0298761929830089e+00 , 1.3041368000000000e+01 , -9.1712600000000000e-01 , 2.0280800000000002e-02 , -3.9808100000000002e-01 --4.0464013488586401e+00 , -2.9134975160827548e-01 , 1.2727080000000001e+01 , -3.0874800000000002e-01 , -3.8933600000000002e-01 , 8.6780800000000002e-01 --3.9702335855908188e+00 , -1.8460292346215557e-01 , 1.2909496000000001e+01 , -3.6162800000000000e-01 , -4.6030799999999999e-01 , 8.1076599999999999e-01 --2.6529261861104505e+00 , 4.0853867798557109e-01 , 1.1138355199999999e+01 , -2.4035100000000001e-01 , 9.5910200000000001e-01 , -1.4951700000000001e-01 --2.4069400176967877e+00 , 5.6600021269426914e-01 , 1.0992120800000000e+01 , 5.7468200000000003e-01 , 1.2382500000000000e-01 , 8.0895499999999998e-01 --1.1303994959654524e+00 , 1.0969915789455547e+00 , 9.0987800000000014e+00 , 1.4185800000000001e-01 , 2.5423499999999999e-01 , 9.5668200000000003e-01 --3.6794890509014122e-01 , 1.4145265420691602e+00 , 7.9704839999999999e+00 , -4.9527800000000000e-01 , -7.1971499999999999e-01 , 4.8652800000000002e-01 --1.8349685721331288e+00 , 9.5981793186817788e-01 , 1.0760450400000000e+01 , -5.9010199999999999e-02 , 8.7104499999999996e-01 , 4.8764600000000002e-01 --1.0870207297648569e+00 , 1.2656634163383869e+00 , 9.6290031999999997e+00 , 5.0555200000000000e-01 , 2.2155900000000001e-01 , -8.3386400000000005e-01 --9.8333271899593688e-01 , 1.3527571114411694e+00 , 9.6512487999999994e+00 , 5.0555200000000000e-01 , 2.2155900000000001e-01 , -8.3386400000000005e-01 --8.7928051498831072e-01 , 1.4403051614184896e+00 , 9.6705512000000002e+00 , -4.2729299999999998e-01 , -1.8671399999999999e-01 , 8.8462399999999997e-01 --5.5299417146374541e-02 , 1.7226379452845875e+00 , 8.2120136000000006e+00 , -1.7447299999999999e-01 , 4.8931599999999997e-01 , 8.5447600000000001e-01 --2.3206342703051774e-02 , 1.7773230359045153e+00 , 8.3269024000000016e+00 , -7.8210299999999999e-01 , -5.7830700000000002e-01 , 2.3211300000000001e-01 -5.8425958089335372e-02 , 1.8439730330032491e+00 , 8.3378328000000010e+00 , -7.8210299999999999e-01 , -5.7830700000000002e-01 , 2.3211300000000001e-01 --9.7248466515736265e-02 , 1.8594847406622230e+00 , 8.8875560000000000e+00 , 2.7644900000000000e-01 , 6.2880300000000000e-01 , 7.2676099999999999e-01 -5.5798694396115067e-02 , 1.9452452991169129e+00 , 8.7450656000000002e+00 , -5.5670399999999998e-01 , 3.5342099999999999e-01 , 7.5178100000000003e-01 -1.1828468374768963e-01 , 2.0119106983517883e+00 , 8.8099616000000012e+00 , 6.9603199999999998e-01 , -1.7484500000000000e-01 , -6.9639700000000004e-01 --4.3300261810253371e-02 , 2.0456391283858566e+00 , 9.4541064000000006e+00 , -5.3768700000000003e-01 , -5.4503200000000002e-02 , -8.4138100000000005e-01 -1.8026949820300509e-01 , 2.1387362879776273e+00 , 9.1206512000000011e+00 , 5.4523299999999997e-01 , 9.8752099999999995e-02 , -8.3244799999999997e-01 -2.1778913215540441e-01 , 2.2065930663563829e+00 , 9.2704424000000003e+00 , 3.8089099999999998e-01 , 6.1572300000000002e-01 , -6.8978799999999996e-01 -2.8044360971019366e-01 , 2.2783426441065133e+00 , 9.3606104000000006e+00 , 6.8118800000000002e-01 , 2.7117999999999998e-01 , -6.8003300000000000e-01 -3.6190636701643686e-01 , 2.3528436965141788e+00 , 9.3999431999999992e+00 , -2.9978600000000000e-01 , -1.3513800000000001e-01 , -9.4438599999999995e-01 -4.8772000625660317e-01 , 2.4268473541763869e+00 , 9.2986784000000000e+00 , 2.0154200000000000e-01 , 4.2885499999999999e-01 , 8.8060499999999997e-01 -6.6720669214990158e-01 , 2.4948311639291956e+00 , 9.0050863999999997e+00 , 1.9751500000000000e-01 , -3.6981999999999998e-01 , 9.0786599999999995e-01 -8.0194363869324281e-01 , 2.5582653228003962e+00 , 8.8374696000000004e+00 , -1.6452200000000000e-02 , -9.2308199999999996e-01 , 3.8424999999999998e-01 -8.3588314435792554e-01 , 2.6312878913646216e+00 , 9.0174208000000000e+00 , -2.2580400000000000e-01 , -4.9320900000000001e-01 , 8.4009400000000001e-01 -9.1663336566811737e-01 , 2.6994834547481488e+00 , 9.0358391999999998e+00 , 3.0733300000000002e-01 , 2.9093599999999997e-01 , 9.0603699999999998e-01 -1.0617213168508224e+00 , 2.7520475226723580e+00 , 8.7901184000000008e+00 , -4.7124899999999997e-02 , 2.5163400000000002e-01 , 9.6667499999999995e-01 -1.1443463080097902e+00 , 2.8162660289692791e+00 , 8.7839200000000002e+00 , -3.4475499999999998e-01 , 4.1620100000000000e-02 , 9.3776999999999999e-01 -1.2226405368506961e+00 , 2.8812079252526237e+00 , 8.7962024000000003e+00 , 4.1723900000000003e-01 , 4.8538100000000001e-03 , 9.0878400000000004e-01 -1.2953858909816933e+00 , 2.9490085750513551e+00 , 8.8372720000000005e+00 , -2.6315499999999997e-01 , -5.1483900000000005e-01 , 8.1589800000000001e-01 -1.3475936178049042e+00 , 3.0282163308359564e+00 , 8.9885920000000006e+00 , -9.7936199999999995e-01 , -1.2656700000000001e-01 , 1.5758100000000000e-01 -1.4122658445637488e+00 , 3.1068734238887643e+00 , 9.0976672000000001e+00 , -1.9410600000000000e-01 , -8.1361300000000003e-01 , -5.4804799999999998e-01 -1.5156403075254183e+00 , 3.1575195090631274e+00 , 8.9705791999999995e+00 , -5.6615800000000005e-01 , -2.1317600000000000e-01 , 7.9625500000000005e-01 -1.6052236570508100e+00 , 3.2153129951193011e+00 , 8.9234463999999996e+00 , 1.4800800000000000e-01 , 9.0827300000000000e-01 , 3.9132400000000001e-01 -1.7025007450867939e+00 , 3.2622187615449447e+00 , 8.8028271999999994e+00 , 1.0989300000000000e-01 , -9.1547299999999998e-01 , 3.8708300000000001e-01 -4.3840502981745733e-01 , 4.0894132811486061e-01 , 1.0538287999999998e+00 , -4.3889900000000003e-02 , 2.0679200000000000e-01 , 9.7740000000000005e-01 -3.6780642064169800e-01 , 3.5936818733188791e-01 , 1.0667570400000002e+00 , 4.6906700000000003e-02 , -2.2169700000000001e-01 , -9.7398700000000005e-01 -2.7773380814843129e-01 , 2.9169169764575087e-01 , 1.0647696000000000e+00 , 1.1497000000000000e-01 , -2.3169799999999999e-01 , -9.6597000000000000e-01 -1.8619758027027000e-01 , 2.2369729538499672e-01 , 1.0661008000000001e+00 , -9.0067300000000003e-02 , 2.0228499999999999e-01 , 9.7517600000000004e-01 -8.7504320039331285e-02 , 1.5023032325065344e-01 , 1.0651502399999999e+00 , -1.0820600000000000e-01 , 1.9761600000000001e-01 , 9.7428899999999996e-01 --2.5233851510757965e-02 , 6.4281042863540749e-02 , 1.0572108800000000e+00 , -1.1321700000000000e-01 , 1.8636400000000000e-01 , 9.7593600000000003e-01 --1.3273755900781570e-01 , -1.5715246571327057e-02 , 1.0588166399999999e+00 , 7.7476000000000003e-02 , -1.8784000000000001e-01 , -9.7913899999999998e-01 --2.4277870552535630e-01 , -9.4867625289752233e-02 , 1.0641175199999999e+00 , -8.6665400000000004e-02 , 1.7226700000000000e-01 , 9.8123000000000005e-01 --3.7972594123377501e-01 , -1.9927524206392677e-01 , 1.0542510400000000e+00 , -1.0913600000000000e-01 , 1.5080199999999999e-01 , 9.8252099999999998e-01 --5.1841667426455684e-01 , -3.0460930553754606e-01 , 1.0499308800000000e+00 , -8.8508799999999999e-02 , 1.7687300000000000e-01 , 9.8024599999999995e-01 --6.5284112750093115e-01 , -4.0188393801910172e-01 , 1.0549239200000000e+00 , -8.5459099999999996e-02 , 1.8235299999999999e-01 , 9.7951200000000005e-01 --8.0872811480254558e-01 , -5.1886411675287869e-01 , 1.0523717600000000e+00 , -8.5314100000000004e-02 , 1.9172300000000000e-01 , 9.7773399999999999e-01 --9.7438793289164849e-01 , -6.4249441691705877e-01 , 1.0516437599999999e+00 , -8.3820699999999998e-02 , 2.0232700000000001e-01 , 9.7572400000000004e-01 --1.1696859071374370e+00 , -7.9020409411869519e-01 , 1.0410628000000002e+00 , -8.1554799999999997e-02 , 2.3395199999999999e-01 , 9.6882199999999996e-01 --1.3100977467839248e+00 , -8.8783289646907049e-01 , 1.0693674399999999e+00 , 6.3561999999999994e-02 , -2.8209899999999999e-01 , -9.5727700000000004e-01 --1.5092142737612630e+00 , -1.0346081772685407e+00 , 1.0731104000000000e+00 , -4.9104900000000000e-02 , 2.5381900000000002e-01 , 9.6600399999999997e-01 --1.6963306263844786e+00 , -1.1692838039460662e+00 , 1.0920186400000000e+00 , -5.4924500000000001e-02 , 2.4547099999999999e-01 , 9.6784700000000001e-01 --1.9145549490323956e+00 , -1.3283261421584363e+00 , 1.1045943199999999e+00 , -6.4632300000000004e-02 , 2.3417700000000000e-01 , 9.7004299999999999e-01 --2.1641814486569713e+00 , -1.5123254068067000e+00 , 1.1130640800000000e+00 , -7.9962599999999995e-02 , 2.1872000000000000e-01 , 9.7250599999999998e-01 --2.4546047270550453e+00 , -1.7274942566935620e+00 , 1.1162163199999999e+00 , -8.7254899999999996e-02 , 2.1049000000000001e-01 , 9.7369399999999995e-01 --2.7790733989400174e+00 , -1.9676677094255455e+00 , 1.1197699999999999e+00 , -9.3052700000000002e-02 , 2.0740300000000000e-01 , 9.7382000000000002e-01 --3.1520298961658497e+00 , -2.2446234018820785e+00 , 1.1201787200000000e+00 , 5.6350400000000000e-03 , 1.3246900000000000e-01 , 9.9117100000000002e-01 --3.5371284865403156e+00 , -2.5269585875684530e+00 , 1.1334168800000000e+00 , 3.8652399999999998e-01 , 2.9277500000000001e-02 , 9.2181500000000005e-01 --4.0728838042281952e+00 , -2.9296705658753801e+00 , 1.1178408000000000e+00 , 7.9280099999999998e-01 , -5.9998899999999999e-01 , -1.0714600000000001e-01 --3.6907746233502579e+00 , -2.5810250932297256e+00 , 1.3803607200000001e+00 , 9.8287800000000003e-01 , -9.8220900000000000e-02 , 1.5589300000000000e-01 --3.7065112291075488e+00 , -2.5571556749737319e+00 , 1.5218464800000000e+00 , -9.6284099999999995e-01 , 2.2637900000000000e-01 , -1.4727599999999999e-01 --3.8317685352482878e+00 , -2.6219683995623901e+00 , 1.6372032800000000e+00 , 9.8109500000000005e-01 , -5.2817999999999997e-02 , 1.8618100000000001e-01 --3.7469636004062492e+00 , -2.5185165097157682e+00 , 1.7998655200000000e+00 , 9.7585699999999997e-01 , -1.9059199999999998e-02 , 2.1757599999999999e-01 --3.7967053592086222e+00 , -2.5225723177840251e+00 , 1.9325255280000000e+00 , -9.3805700000000003e-01 , -2.6582399999999999e-02 , -3.4545999999999999e-01 --3.9904147266254384e+00 , -2.6396428444069819e+00 , 2.0426957440000000e+00 , -9.3805700000000003e-01 , -2.6582399999999999e-02 , -3.4545999999999999e-01 --4.0052217312124219e+00 , -2.6155955981887331e+00 , 2.1852177600000000e+00 , -9.0369999999999995e-01 , -8.5795800000000005e-02 , -4.1948200000000002e-01 --8.6801368325695361e+00 , -6.1906293090902711e+00 , 1.7840367200000000e+00 , 1.6317700000000001e-02 , 3.7171799999999999e-01 , 9.2820199999999997e-01 --9.6891416248800759e+00 , -6.9027881793526618e+00 , 1.9339423199999999e+00 , -2.4128799999999999e-02 , 2.9385400000000000e-01 , 9.5554600000000001e-01 --1.1411108044816304e+01 , -8.1490311835683880e+00 , 2.0743060240000002e+00 , -9.4296799999999993e-03 , 2.3242399999999999e-01 , 9.7256900000000002e-01 --1.4160673732998244e+01 , -1.0153903117448845e+01 , 2.2352531999999998e+00 , 6.0746599999999998e-02 , 6.0741700000000003e-02 , 9.9630300000000005e-01 --1.8603220022646649e+01 , -1.3399863922884913e+01 , 2.4630100800000001e+00 , 6.9246400000000000e-02 , -9.9511400000000005e-01 , 7.0372599999999993e-02 --1.8720498302037868e+01 , -1.3376203894841078e+01 , 2.9134985599999998e+00 , -9.5308699999999996e-02 , 9.9301099999999998e-01 , -6.9603999999999999e-02 --1.9516885565242479e+01 , -1.3854181345787737e+01 , 3.3754312000000000e+00 , -6.7130200000000001e-02 , 9.9618399999999996e-01 , -5.5769899999999997e-02 --1.9321778319547569e+01 , -1.3594866487306110e+01 , 3.8346847999999998e+00 , -4.5371799999999997e-02 , 9.9765199999999998e-01 , -5.1305499999999997e-02 --1.9009892154375713e+01 , -1.3253622103219881e+01 , 4.2774232000000003e+00 , -5.4168399999999998e-02 , 9.9552600000000002e-01 , -7.7419299999999996e-02 --1.9833918132236850e+01 , -1.3738687812354209e+01 , 4.7927432000000003e+00 , 3.2079799999999999e-02 , -9.9378900000000003e-01 , 1.0655299999999999e-01 --1.9878394733552014e+01 , -1.3655383407095833e+01 , 5.2652464000000005e+00 , -4.4602299999999998e-02 , 9.9150300000000002e-01 , -1.2220200000000001e-01 --1.9941154759936875e+01 , -1.3584486685252212e+01 , 5.7406096000000000e+00 , 7.8868599999999997e-02 , -9.8805600000000005e-01 , 1.3237900000000000e-01 --1.9981522628962839e+01 , -1.3496847595809760e+01 , 6.2146208000000005e+00 , -4.8133700000000001e-02 , 9.7971200000000003e-01 , -1.9454500000000000e-01 --2.0030766371844251e+01 , -1.3415676805626161e+01 , 6.6914816000000004e+00 , -4.7462200000000003e-02 , 9.7879400000000005e-01 , -1.9927500000000001e-01 --2.0056312187836014e+01 , -1.3317923416215283e+01 , 7.1660127999999998e+00 , -4.6587499999999997e-02 , 9.7722399999999998e-01 , -2.0703500000000000e-01 --2.0092794458903455e+01 , -1.3226419335116342e+01 , 7.6436432000000005e+00 , 5.1093000000000000e-02 , -9.7130000000000005e-01 , 2.3230500000000001e-01 --2.0121906336110644e+01 , -1.3129919398300437e+01 , 8.1217416000000000e+00 , -7.5706800000000005e-02 , -9.7075400000000001e-01 , 2.2782800000000000e-01 --2.0102111366093332e+01 , -1.2999332501103767e+01 , 8.5897104000000013e+00 , -8.1973500000000005e-02 , -9.7314599999999996e-01 , 2.1509800000000001e-01 --2.0092156437857462e+01 , -1.2876215825503511e+01 , 9.0606119999999990e+00 , -3.2862400000000002e-03 , -9.7615399999999997e-01 , 2.1705500000000000e-01 --1.9806193963061972e+01 , -1.2566224667383093e+01 , 9.4532951999999995e+00 , -5.7944400000000000e-02 , 9.8037500000000000e-01 , -1.8843399999999999e-01 --2.0285483219252864e+01 , -1.2770547190273110e+01 , 1.0070888800000001e+01 , -4.8618600000000000e-04 , -9.8592900000000006e-01 , 1.6716400000000001e-01 --2.0305186197302909e+01 , -1.2663926655608725e+01 , 1.0559023200000000e+01 , 5.1833900000000002e-02 , -9.8535200000000001e-01 , 1.6246700000000000e-01 --2.0391795035641721e+01 , -1.2601015949907383e+01 , 1.1074062399999999e+01 , 6.1313199999999998e-02 , -9.8663999999999996e-01 , 1.5094099999999999e-01 --2.0429196063338960e+01 , -1.2504456017147721e+01 , 1.1576944000000001e+01 , 6.3963900000000004e-02 , -9.8682800000000004e-01 , 1.4858900000000000e-01 --7.3123904149489292e+00 , -3.9051318580702947e+00 , 6.9161528000000008e+00 , -2.4312200000000000e-01 , 6.7628600000000005e-01 , 6.9536299999999995e-01 --7.3287931146802094e+00 , -3.8635807149725947e+00 , 7.1347192000000001e+00 , -6.4375099999999996e-01 , 7.0257700000000001e-01 , 3.0326599999999998e-01 --7.1448600258142108e+00 , -3.6938850356827162e+00 , 7.2678080000000005e+00 , -6.4375099999999996e-01 , 7.0257700000000001e-01 , 3.0326599999999998e-01 --7.1477104886276059e+00 , -3.6425512777545324e+00 , 7.4798640000000001e+00 , -6.4375099999999996e-01 , 7.0257700000000001e-01 , 3.0326599999999998e-01 --6.4038580861415983e+00 , -3.1260069220360771e+00 , 7.3353663999999998e+00 , 3.2183699999999998e-01 , -9.4594599999999995e-01 , -4.0102300000000000e-02 --6.1519923709392561e+00 , -2.9207551589032539e+00 , 7.4064712000000004e+00 , -5.3875899999999999e-01 , 8.4158500000000003e-01 , 3.8393700000000003e-02 --6.2299399946210983e+00 , -2.9208827035382434e+00 , 7.6422184000000000e+00 , 6.1579600000000001e-01 , 6.3122999999999996e-01 , -4.7153299999999998e-01 --6.0879716952411069e+00 , -2.7849703583531458e+00 , 7.7620471999999996e+00 , -5.3068499999999996e-01 , -7.2567800000000005e-01 , 4.3790899999999999e-01 --6.1358927078981811e+00 , -2.7652905070854077e+00 , 7.9865520000000005e+00 , -6.5546000000000004e-01 , -6.5116399999999997e-01 , 3.8256800000000002e-01 --6.1958124254461993e+00 , -2.7512263709083866e+00 , 8.2227776000000006e+00 , -5.2298000000000000e-01 , -7.7657699999999996e-01 , 3.5131299999999999e-01 --5.9444780615995443e+00 , -2.5526190168039715e+00 , 8.2713560000000008e+00 , 1.8486000000000000e-01 , 7.6447299999999996e-01 , -6.1758199999999996e-01 --6.0140441763657293e+00 , -2.5436300902018676e+00 , 8.5172120000000007e+00 , -2.8043000000000001e-01 , -7.3621899999999996e-01 , 6.1590699999999998e-01 --5.9309652206448407e+00 , -2.4446984025712268e+00 , 8.6675648000000010e+00 , 3.2915899999999998e-01 , 6.6792799999999997e-01 , -6.6747699999999999e-01 --5.8153018239630496e+00 , -2.3275843490861288e+00 , 8.7939560000000014e+00 , -4.0890100000000001e-01 , -6.1418600000000001e-01 , 6.7496299999999998e-01 --5.7061781250063870e+00 , -2.2141198817123477e+00 , 8.9219176000000004e+00 , 4.5658199999999999e-01 , 7.0386700000000002e-01 , -5.4415400000000003e-01 --5.6167732252828753e+00 , -2.1140438115601450e+00 , 9.0634823999999998e+00 , -5.2525400000000000e-01 , -7.6773800000000003e-01 , 3.6699599999999999e-01 --5.5796050674467716e+00 , -2.0413122495868823e+00 , 9.2426952000000000e+00 , -5.9363600000000005e-01 , -5.8420200000000000e-01 , 5.5344700000000002e-01 --5.6060647779920627e+00 , -2.0030200887669514e+00 , 9.4745424000000007e+00 , -4.4034699999999999e-01 , -7.3873999999999995e-01 , 5.1025299999999996e-01 --5.4649774089294256e+00 , -1.8742262536855181e+00 , 9.5746840000000013e+00 , 8.0364400000000002e-01 , -2.0141200000000001e-01 , -5.5999100000000002e-01 --5.7273366649177007e+00 , -1.9605488971955438e+00 , 1.0012596800000001e+01 , 7.8794799999999998e-01 , -5.8403200000000000e-01 , 1.9504900000000000e-01 --5.3543663617854005e+00 , -1.7076891771185787e+00 , 9.9136823999999990e+00 , -6.8233699999999997e-01 , 7.3126600000000000e-02 , 7.2737099999999999e-01 --5.7623663640927543e+00 , -1.8652697853288531e+00 , 1.0504371200000000e+01 , -7.8195400000000004e-01 , 5.4504600000000000e-02 , 6.2094800000000006e-01 --5.5313072099313247e+00 , -1.6880373692271573e+00 , 1.0526856000000000e+01 , -5.2166400000000002e-01 , 5.1158300000000001e-01 , 6.8275200000000003e-01 --5.3577975161967935e+00 , -1.5414654342295284e+00 , 1.0595714400000000e+01 , -7.3839200000000005e-01 , 3.9518599999999998e-01 , 5.4644800000000004e-01 --5.2247215867755523e+00 , -1.4166513566874781e+00 , 1.0700754400000001e+01 , 9.9177199999999999e-01 , 1.2800700000000001e-01 , -1.5874800000000001e-03 --5.4069278523580069e+00 , -1.4474529343888891e+00 , 1.1125636000000000e+01 , -8.7093399999999999e-01 , -4.6022700000000000e-01 , 1.7223700000000000e-01 --5.9802666559608841e+00 , -1.6624040828043900e+00 , 1.1981275199999999e+01 , 7.4808399999999997e-01 , 6.7351400000000006e-02 , 6.6017700000000001e-01 --6.5070697916869840e+00 , -1.8436109828770628e+00 , 1.2829832000000000e+01 , -8.8398399999999999e-01 , -1.1197900000000000e-01 , -4.5390900000000001e-01 --6.5311664827590690e+00 , -1.7806985972245015e+00 , 1.3158056000000000e+01 , -8.8605000000000000e-01 , 1.6159200000000001e-01 , -4.3451499999999998e-01 --5.3707494896427352e+00 , -8.0751321469007120e-01 , 1.3603384000000000e+01 , 9.5677299999999998e-01 , -1.0856300000000001e-01 , -2.6981300000000003e-01 --5.1766614902748120e+00 , -6.4943728755150332e-01 , 1.3659960000000000e+01 , 5.5507899999999999e-01 , 4.9552600000000002e-01 , 6.6808699999999999e-01 --2.8476400135693947e+00 , 3.9850247634355696e-01 , 1.0894163200000001e+01 , -1.7920600000000000e-01 , -8.9816499999999999e-01 , -4.0147699999999997e-01 --2.8070135210730509e+00 , 4.7453702314030544e-01 , 1.1079938400000000e+01 , -2.4035100000000001e-01 , 9.5910200000000001e-01 , -1.4951700000000001e-01 --2.5553784177287815e+00 , 6.2627481417233666e-01 , 1.0938124000000000e+01 , -2.4035100000000001e-01 , 9.5910200000000001e-01 , -1.4951700000000001e-01 --1.4150402897373739e+00 , 1.0798078932690793e+00 , 9.3427639999999990e+00 , -6.3385400000000003e-01 , -5.8118700000000001e-01 , -5.1034500000000005e-01 --1.2954922417384021e+00 , 1.1689638472311845e+00 , 9.3469967999999994e+00 , 4.2570999999999998e-01 , 9.5956399999999997e-02 , 8.9975799999999995e-01 --2.9114084654460228e+00 , 7.0920835207148158e-01 , 1.2343663200000002e+01 , -8.3772000000000002e-01 , -3.0895899999999998e-01 , 4.5029900000000000e-01 --3.0104092409979790e+00 , 7.5483266289268403e-01 , 1.2828272000000000e+01 , -4.1636899999999999e-01 , 6.5249400000000002e-01 , -6.3315800000000000e-01 --2.9107229299641979e+00 , 8.6465121515836874e-01 , 1.2973040000000001e+01 , 7.9916299999999996e-01 , 1.6619600000000001e-01 , -5.7768299999999995e-01 --1.0023869280892330e+00 , 1.4667515232052071e+00 , 9.6701352000000007e+00 , -2.8263800000000000e-01 , -1.3751700000000000e-01 , 9.4931800000000000e-01 --9.0056051814598170e-01 , 1.5498370140909905e+00 , 9.6984440000000003e+00 , -1.9170499999999999e-01 , -3.4151599999999999e-01 , 9.2011799999999999e-01 --9.4044716633408409e-02 , 1.8003881094084377e+00 , 8.2839711999999999e+00 , -7.8210299999999999e-01 , -5.7830700000000002e-01 , 2.3211300000000001e-01 --1.3945898781330168e-01 , 1.8361792872010827e+00 , 8.5678704000000003e+00 , 6.2283200000000005e-01 , 5.8036399999999999e-01 , -5.2465099999999998e-01 --6.5624168536033700e-02 , 1.9016678117425103e+00 , 8.6082640000000001e+00 , -3.6590499999999998e-01 , -6.7880600000000002e-01 , 6.3666000000000000e-01 -7.8094257278116253e-04 , 1.9646517154700784e+00 , 8.6662648000000004e+00 , -5.2907000000000004e-01 , 2.9301199999999999e-01 , 7.9638500000000001e-01 -1.0089577129789173e-01 , 2.0338279812037952e+00 , 8.6462448000000016e+00 , 7.4615799999999999e-01 , -1.1831800000000001e-01 , -6.5517099999999995e-01 --1.2077767488358759e-01 , 2.0597340220444238e+00 , 9.4126624000000003e+00 , 1.0167200000000000e-01 , 5.4640699999999998e-01 , 8.3132499999999998e-01 -1.8282939847383162e-02 , 2.1381685702746807e+00 , 9.3151520000000012e+00 , 5.7147999999999997e-02 , 6.7827199999999999e-01 , 7.3258500000000004e-01 -1.2518497137307039e-01 , 2.2127572938539095e+00 , 9.2918248000000006e+00 , -3.7851499999999999e-01 , 8.2570900000000003e-01 , 4.1824800000000001e-01 -2.1377541719971127e-01 , 2.2837147228281682e+00 , 9.3150896000000003e+00 , -9.6783700000000000e-02 , -4.9281799999999998e-01 , 8.6473299999999997e-01 -2.8947676756583940e-01 , 2.3552810614865232e+00 , 9.3755032000000007e+00 , -3.5496400000000000e-01 , -1.8925800000000001e-01 , 9.1552299999999998e-01 -4.3132472630006391e-01 , 2.4263517015952778e+00 , 9.2367568000000002e+00 , -4.1949799999999998e-01 , -4.6133500000000000e-01 , -7.8178700000000001e-01 -5.2516305524388796e-01 , 2.4949772414666018e+00 , 9.2337512000000004e+00 , 2.0769899999999999e-01 , 4.7690100000000002e-01 , 8.5406499999999996e-01 -7.0795656329976175e-01 , 2.5563847675264193e+00 , 8.9292911999999998e+00 , -7.3807999999999996e-01 , -1.5726899999999999e-01 , -6.5612800000000004e-01 -8.1488731732420150e-01 , 2.6186922298193931e+00 , 8.8608279999999997e+00 , -1.6452200000000000e-02 , -9.2308199999999996e-01 , 3.8425100000000001e-01 -8.3628636289838854e-01 , 2.6937866119030951e+00 , 9.1010887999999994e+00 , 3.8840199999999998e-02 , -3.9327099999999997e-02 , -9.9847100000000000e-01 -9.4262820415360915e-01 , 2.7553401265332629e+00 , 9.0287568000000000e+00 , 4.1305500000000001e-01 , 3.5136600000000001e-01 , 8.4019500000000003e-01 -1.0909963996990579e+00 , 2.8024484058727959e+00 , 8.7724696000000009e+00 , 4.7125000000000000e-02 , -2.5163400000000002e-01 , -9.6667499999999995e-01 -1.1643704004484321e+00 , 2.8676503881375002e+00 , 8.8166072000000000e+00 , -4.9320300000000000e-01 , -9.2226800000000005e-03 , 8.6986500000000000e-01 -1.2549998003122127e+00 , 2.9250001269124923e+00 , 8.7780336000000005e+00 , 3.6377199999999998e-01 , 1.9905100000000001e-01 , -9.0997200000000000e-01 -1.3333231443567337e+00 , 2.9883954591804400e+00 , 8.7984384000000002e+00 , -3.2328400000000002e-01 , -4.3547300000000000e-01 , 8.4014900000000003e-01 -1.3553005661952531e+00 , 3.0876326353970684e+00 , 9.1323407999999997e+00 , -4.4239800000000001e-01 , -2.6715200000000000e-01 , 8.5610399999999998e-01 -1.4730419634391749e+00 , 3.1289241206005167e+00 , 8.9460248000000000e+00 , 5.5681199999999997e-01 , 5.8194999999999997e-01 , -5.9270100000000003e-01 -1.5516737593162637e+00 , 3.1964461928375671e+00 , 8.9817488000000001e+00 , -3.1885100000000000e-01 , 9.4760800000000001e-01 , 1.9306100000000000e-02 -1.6624728403200892e+00 , 3.2318947838427441e+00 , 8.7913351999999989e+00 , 5.0853200000000001e-02 , 8.0799900000000002e-01 , 5.8698499999999998e-01 -2.6936654049409259e-01 , 3.9222699061692934e-01 , 1.0454775999999999e+00 , -7.5509900000000005e-02 , 2.5334299999999998e-01 , 9.6442499999999998e-01 -1.7710110141234470e-01 , 3.2699232749974683e-01 , 1.0445499199999999e+00 , -9.6529799999999999e-02 , 2.2759599999999999e-01 , 9.6895900000000001e-01 -8.3420386264706492e-02 , 2.6245764545182038e-01 , 1.0468348000000001e+00 , -6.3049200000000000e-02 , 2.1031500000000000e-01 , 9.7559799999999997e-01 --1.8506045744445920e-02 , 1.9148689957576437e-01 , 1.0470188800000000e+00 , 1.0613400000000001e-01 , -1.7571000000000001e-01 , -9.7870400000000002e-01 --1.3445769978272581e-01 , 1.0908837753836953e-01 , 1.0402120799999999e+00 , 8.2026000000000002e-02 , -1.7831800000000000e-01 , -9.8054799999999998e-01 --2.4515643243140284e-01 , 3.2604141844622125e-02 , 1.0427476000000000e+00 , -6.5441299999999994e-02 , 1.6859800000000000e-01 , 9.8351000000000000e-01 --3.7109193637802651e-01 , -5.6084039405136288e-02 , 1.0394851200000002e+00 , -8.8494100000000006e-02 , 1.6192899999999999e-01 , 9.8282599999999998e-01 --5.0550263364358861e-01 , -1.5080911765638705e-01 , 1.0360437600000001e+00 , -9.9813600000000002e-02 , 1.4510100000000001e-01 , 9.8436900000000005e-01 --6.6219859481428145e-01 , -2.6337971667332605e-01 , 1.0236116000000000e+00 , -7.6051999999999995e-02 , 1.4964200000000000e-01 , 9.8581099999999999e-01 --7.9891092357782600e-01 , -3.5695840708117776e-01 , 1.0306711200000001e+00 , -6.9930400000000004e-02 , 1.6339699999999999e-01 , 9.8407900000000004e-01 --9.6705725041038582e-01 , -4.7502295580025011e-01 , 1.0254004000000001e+00 , -8.5927199999999995e-02 , 1.7348600000000000e-01 , 9.8108099999999998e-01 --1.1290497047120120e+00 , -5.8695875176586343e-01 , 1.0308115199999999e+00 , 9.1948400000000000e-02 , -1.6244500000000001e-01 , -9.8242399999999996e-01 --1.3446896578025425e+00 , -7.4137055255036843e-01 , 1.0141944000000001e+00 , -8.7796100000000002e-02 , 2.2087300000000001e-01 , 9.7134299999999996e-01 --1.5034480399064525e+00 , -8.4675076228895696e-01 , 1.0370213600000000e+00 , -3.0538099999999999e-02 , 2.5739000000000001e-01 , 9.6582500000000004e-01 --1.7080561299526056e+00 , -9.8847394259643240e-01 , 1.0435650399999998e+00 , -4.9310600000000003e-02 , 2.5448100000000001e-01 , 9.6582000000000001e-01 --1.9075986342306974e+00 , -1.1228351980125217e+00 , 1.0613698399999998e+00 , -5.2297299999999998e-02 , 2.4186099999999999e-01 , 9.6890100000000001e-01 --2.1545260869083789e+00 , -1.2937657404532215e+00 , 1.0668163200000000e+00 , 6.6684999999999994e-02 , -2.2153700000000001e-01 , -9.7286899999999998e-01 --2.4188219702563565e+00 , -1.4760165082225574e+00 , 1.0755492000000000e+00 , -7.6674000000000006e-02 , 2.0173700000000000e-01 , 9.7643400000000002e-01 --2.7321242687737897e+00 , -1.6948469048833799e+00 , 1.0767576800000001e+00 , -8.1563099999999999e-02 , 1.9319700000000001e-01 , 9.7776399999999997e-01 --3.0886837957372215e+00 , -1.9430217208700427e+00 , 1.0759350400000001e+00 , -8.0223400000000000e-02 , 1.7901400000000001e-01 , 9.8057000000000005e-01 --3.4868486333506707e+00 , -2.2220418895172838e+00 , 1.0764737600000001e+00 , 3.2949600000000001e-01 , 3.1305699999999997e-01 , 8.9074500000000001e-01 --3.8818138495326391e+00 , -2.4922425893202469e+00 , 1.0951303200000000e+00 , -7.5345499999999999e-01 , 4.6067200000000003e-01 , 4.6913500000000002e-01 --3.6999450985864346e+00 , -2.3169698609905174e+00 , 1.2976952799999999e+00 , -9.6734500000000001e-01 , 2.2610400000000000e-01 , -1.1454600000000000e-01 --3.6670617828090810e+00 , -2.2569175057010957e+00 , 1.4499450400000000e+00 , -9.4909399999999999e-01 , 1.8940799999999999e-01 , -2.5168499999999999e-01 --3.7947744450415346e+00 , -2.3195114054695196e+00 , 1.5599583200000000e+00 , -9.2123200000000005e-01 , 1.6829500000000000e-01 , -3.5072500000000001e-01 --3.7160379574404692e+00 , -2.2260123234962323e+00 , 1.7193632800000000e+00 , -8.7419500000000006e-01 , 1.3501600000000000e-01 , -4.6642699999999998e-01 --3.9395746563485003e+00 , -2.3587431902774760e+00 , 1.8139647999999999e+00 , -9.5098300000000002e-01 , 1.1171100000000000e-01 , -2.8836000000000001e-01 --3.9062261891731769e+00 , -2.2995197467185582e+00 , 1.9621676079999999e+00 , -8.5047600000000001e-01 , 1.1870699999999999e-01 , -5.1244400000000001e-01 --3.9455367355651934e+00 , -2.2952002441961534e+00 , 2.0964650960000002e+00 , -8.3316400000000002e-01 , 1.4700199999999999e-01 , -5.3313100000000002e-01 --8.6274565495138624e+00 , -5.6773250418548082e+00 , 1.6182732000000000e+00 , 3.1533899999999997e-02 , 3.9773999999999998e-01 , 9.1695599999999999e-01 --9.5880774988232549e+00 , -6.3151261211691061e+00 , 1.7523198400000000e+00 , 7.0378999999999997e-03 , 3.6574499999999999e-01 , 9.3068799999999996e-01 --1.0906326423394459e+01 , -7.2004378451716171e+00 , 1.8939449600000000e+00 , -3.4054200000000000e-02 , 2.6740300000000000e-01 , 9.6298300000000003e-01 --1.3353635880546296e+01 , -8.8793773879577849e+00 , 2.0138018400000002e+00 , 2.0369100000000001e-01 , -2.2231399999999998e-02 , 9.7878299999999996e-01 --1.6846475115695885e+01 , -1.1274558375143899e+01 , 2.1870928799999998e+00 , 8.3375800000000000e-02 , 9.0335100000000002e-01 , 4.2071999999999998e-01 --2.0915331914300499e+01 , -1.4040246664658032e+01 , 2.4908747999999998e+00 , -6.7130200000000001e-02 , 9.9618399999999996e-01 , -5.5769899999999997e-02 --2.1240755358017651e+01 , -1.4148765473678719e+01 , 2.9788594399999999e+00 , 6.2350000000000003e-02 , -9.9662499999999998e-01 , 5.3396199999999998e-02 --2.1328262910038944e+01 , -1.4090843966626153e+01 , 3.4742936000000002e+00 , -1.6532900000000000e-01 , 9.8606499999999997e-01 , 1.8509000000000001e-02 --2.1349808826305193e+01 , -1.3986125073487200e+01 , 3.9686887999999998e+00 , -1.5786600000000001e-01 , 9.8741900000000005e-01 , -9.0144900000000000e-03 --2.3361493230653480e+01 , -1.5242198918076713e+01 , 4.5776608000000003e+00 , -1.7585500000000001e-01 , 9.8441500000000004e-01 , -1.2269000000000000e-03 --2.3464950992821986e+01 , -1.5184114991013494e+01 , 5.1181072000000007e+00 , 1.5704599999999999e-01 , -9.8491799999999996e-01 , 7.2609099999999996e-02 --2.3415159387786566e+01 , -1.5021428018050084e+01 , 5.6462608000000003e+00 , -1.1665000000000000e-01 , -9.7094199999999997e-01 , 2.0896000000000001e-01 --2.3468410046649819e+01 , -1.4928866217361954e+01 , 6.1838056000000003e+00 , -1.1609000000000000e-01 , -9.7158699999999998e-01 , 2.0625599999999999e-01 --2.3505596248907235e+01 , -1.4825513808073776e+01 , 6.7207783999999995e+00 , -1.1609000000000000e-01 , -9.7158699999999998e-01 , 2.0625599999999999e-01 --2.3509393235026781e+01 , -1.4698945207416237e+01 , 7.2532792000000006e+00 , 3.8954400000000000e-01 , -9.0026899999999999e-01 , 1.9434599999999999e-01 --2.3539352293568847e+01 , -1.4590413750173308e+01 , 7.7910216000000005e+00 , 3.9038400000000001e-01 , -8.9991600000000005e-01 , 1.9430000000000000e-01 --2.3543331090798276e+01 , -1.4464518695891549e+01 , 8.3251448000000003e+00 , 3.9035700000000001e-01 , -8.9992300000000003e-01 , 1.9431999999999999e-01 --2.3618253568220524e+01 , -1.4383353596144726e+01 , 8.8755231999999999e+00 , -3.9035900000000001e-01 , 8.9991699999999997e-01 , -1.9434499999999999e-01 --2.1717462995377982e+01 , -1.3038794337741315e+01 , 8.9503824000000005e+00 , -1.7241699999999999e-01 , 9.6088300000000004e-01 , -2.1673799999999999e-01 --2.3767473205549646e+01 , -1.4218349872758356e+01 , 9.9891760000000005e+00 , -1.5689300000000000e-01 , 9.6389700000000000e-01 , -2.1514300000000000e-01 --2.3723199410386197e+01 , -1.4059328180986999e+01 , 1.0519045600000000e+01 , -1.3990900000000001e-01 , 9.7345000000000004e-01 , -1.8116599999999999e-01 --2.3824317051992626e+01 , -1.3991325631652771e+01 , 1.1093520800000000e+01 , -1.3990900000000001e-01 , 9.7345000000000004e-01 , -1.8116599999999999e-01 --5.7479301683273851e+00 , -2.6694665495773950e+00 , 5.7516648000000004e+00 , -5.8224699999999996e-01 , 2.9374600000000001e-01 , 7.5809099999999996e-01 --5.9474609279617106e+00 , -2.7503857894358417e+00 , 5.9926431999999998e+00 , 6.6607499999999997e-01 , 4.1200599999999998e-01 , -6.2176799999999999e-01 --5.7019725841818234e+00 , -2.5586406475999972e+00 , 6.0796912000000001e+00 , 8.4117799999999998e-01 , -1.4002500000000001e-01 , -5.2231499999999997e-01 --7.2126455980585522e+00 , -3.4287974471467244e+00 , 6.8404303999999998e+00 , 4.7181600000000001e-01 , -4.0702300000000002e-01 , -7.8212599999999999e-01 --7.1279137854063261e+00 , -3.3278116419428834e+00 , 7.0119368000000000e+00 , -6.4375099999999996e-01 , 7.0257700000000001e-01 , 3.0326599999999998e-01 --5.4977175764852868e+00 , -2.3111072542819890e+00 , 6.5139120000000004e+00 , 9.8656400000000000e-01 , 1.5698799999999999e-01 , 4.5247000000000002e-02 --6.0567988910590937e+00 , -2.5983296909928137e+00 , 6.9400624000000004e+00 , -6.4448000000000005e-01 , 6.9529500000000000e-01 , 3.1813500000000000e-01 --5.7607211544039743e+00 , -2.3810595885130184e+00 , 6.9854688000000005e+00 , 6.3218899999999995e-02 , -9.3427099999999996e-01 , 3.5091600000000001e-01 --6.5643154858240997e+00 , -2.8006596007486735e+00 , 7.5667456000000000e+00 , -5.6542700000000001e-01 , 8.2468699999999995e-01 , -1.3543700000000001e-02 --5.6381921648509392e+00 , -2.2217525007216956e+00 , 7.2857792000000003e+00 , -9.8625099999999999e-01 , 5.6608600000000002e-02 , 1.5525500000000000e-01 --6.2071442099001448e+00 , -2.5007463244338437e+00 , 7.7770543999999999e+00 , 6.6724399999999995e-01 , -7.4475999999999998e-01 , -1.0837800000000000e-02 --5.7987195738109696e+00 , -2.2234983748806973e+00 , 7.7435664000000006e+00 , -9.1658099999999998e-01 , 2.5519900000000001e-01 , -3.0781999999999998e-01 --5.5777048566686638e+00 , -2.0551358884116908e+00 , 7.8042296000000002e+00 , 9.9438300000000002e-01 , -7.5825299999999998e-02 , 7.3846300000000004e-02 --6.3927071534398223e+00 , -2.4573534211881425e+00 , 8.4904632000000007e+00 , 7.5037900000000002e-01 , 4.2058699999999999e-01 , -5.0993900000000003e-01 --6.1325833242516019e+00 , -2.2653050121063236e+00 , 8.5346943999999993e+00 , 4.4488600000000000e-01 , -8.5413600000000001e-01 , 2.6931100000000002e-01 --5.6904180091032108e+00 , -1.9776201816712731e+00 , 8.4494664000000004e+00 , -2.0466699999999999e-01 , -6.9861600000000001e-01 , -6.8559999999999999e-01 --5.9113714382997253e+00 , -2.0473467405198242e+00 , 8.7993640000000006e+00 , 9.1986799999999994e-02 , -9.7483200000000003e-01 , 2.0308000000000001e-01 --6.2117328136630743e+00 , -2.1548069843658091e+00 , 9.2190976000000013e+00 , -2.1708800000000000e-01 , -8.9057900000000001e-01 , 3.9967799999999998e-01 --5.9692320777500854e+00 , -1.9765392392234542e+00 , 9.2597096000000008e+00 , -1.1536600000000000e-01 , -8.5709199999999996e-01 , 5.0207900000000005e-01 --5.0685962770020074e+00 , -1.4608755861093070e+00 , 8.7911584000000005e+00 , 8.4990600000000005e-01 , -5.0486699999999995e-01 , 1.5089200000000000e-01 --4.8250815918769057e+00 , -1.2897560894094200e+00 , 8.7964936000000016e+00 , -8.4230300000000002e-01 , 4.6138200000000001e-01 , -2.7866200000000002e-01 --5.5460391481621079e+00 , -1.6051021712231477e+00 , 9.5756095999999999e+00 , -8.7154399999999999e-01 , 3.6315500000000001e-01 , 3.2943699999999998e-01 --5.4601812777429357e+00 , -1.5096713833825111e+00 , 9.7197431999999999e+00 , -9.6749300000000005e-01 , 1.6498900000000000e-01 , 1.9166700000000000e-01 --5.3352749983780736e+00 , -1.3962229203419425e+00 , 9.8299103999999993e+00 , -7.8368199999999999e-01 , 1.5101800000000001e-01 , 6.0252499999999998e-01 --5.4192410893790202e+00 , -1.3839877179970390e+00 , 1.0125676000000000e+01 , -9.2477100000000001e-01 , 3.6736000000000002e-01 , -9.9222699999999997e-02 --5.0143502180772108e+00 , -1.1368394079504984e+00 , 9.9789007999999999e+00 , 9.9493100000000001e-01 , 6.4800499999999997e-02 , -7.6895199999999997e-02 --5.3142638167582934e+00 , -1.2227948275627720e+00 , 1.0484361600000000e+01 , -9.4979300000000000e-01 , -1.5928800000000001e-01 , -2.6929500000000001e-01 --5.6152096562210865e+00 , -1.3055425820166211e+00 , 1.1016082400000000e+01 , 7.3271699999999995e-01 , 6.6973700000000003e-01 , 1.2074400000000000e-01 --6.2802522017679365e+00 , -1.5460972165735267e+00 , 1.1941131200000001e+01 , -8.1263200000000002e-01 , 5.0505999999999995e-01 , -2.9076400000000002e-01 --6.6632071792194889e+00 , -1.6490875759808117e+00 , 1.2618400000000001e+01 , 8.4139399999999998e-01 , 3.6247600000000002e-01 , 4.0083299999999999e-01 --6.8390360182292458e+00 , -1.6546567871996696e+00 , 1.3106576000000000e+01 , -9.7144900000000001e-01 , 5.3078500000000001e-02 , -2.3123400000000000e-01 --5.3419565269619858e+00 , -5.1584776553555889e-01 , 1.3497199999999999e+01 , 9.5677400000000001e-01 , -1.0856200000000001e-01 , -2.6981200000000000e-01 --5.2471481413359022e+00 , -4.0227678878491169e-01 , 1.3691160000000000e+01 , 5.5508000000000002e-01 , 4.9552600000000002e-01 , 6.6808699999999999e-01 --5.0356713688952661e+00 , -2.4632980281980243e-01 , 1.3724959999999999e+01 , -6.3685199999999997e-01 , -1.1608900000000000e-01 , -7.6219599999999998e-01 --3.0133048587915887e+00 , 5.2904793004656492e-01 , 1.1095673600000000e+01 , -2.4035100000000001e-01 , 9.5910200000000001e-01 , -1.4951700000000001e-01 --3.4023578089651227e+00 , 4.6221221629423748e-01 , 1.1940528000000000e+01 , -3.6276200000000001e-02 , -9.7424599999999995e-01 , 2.2255100000000000e-01 --1.5056337570148526e+00 , 1.1383475249418091e+00 , 9.2608744000000005e+00 , 4.5009199999999999e-01 , -3.2448399999999999e-01 , -8.3194199999999996e-01 --1.3895582314469404e+00 , 1.2223335977732770e+00 , 9.2756007999999994e+00 , -4.6832200000000002e-01 , 3.3855299999999999e-01 , 8.1612300000000004e-01 --1.3270786865425230e+00 , 1.2907059337855302e+00 , 9.3753159999999998e+00 , 6.0164899999999999e-01 , -3.1556699999999999e-01 , -7.3378200000000005e-01 --3.1759035180284734e+00 , 8.2004358241277786e-01 , 1.2768784000000000e+01 , -5.0843300000000002e-01 , 5.3939199999999998e-01 , -6.7123200000000005e-01 --3.1201463022607028e+00 , 9.1451118985584734e-01 , 1.2996648000000000e+01 , 2.7980400000000000e-01 , -3.9461499999999999e-01 , 8.7520799999999999e-01 --1.1271861239379799e+00 , 1.5002399371752673e+00 , 9.6674311999999993e+00 , -2.8263800000000000e-01 , -1.3751700000000000e-01 , 9.4931800000000000e-01 --1.0427882888746645e+00 , 1.5759662838241404e+00 , 9.7345423999999987e+00 , -6.9392899999999993e-02 , -4.3469000000000002e-01 , 8.9790300000000001e-01 --2.0214724808902496e-01 , 1.8185151048801049e+00 , 8.3139855999999988e+00 , -8.6051000000000000e-01 , -5.0853400000000004e-01 , 3.0265500000000001e-02 --7.1746745877761864e-02 , 1.8915109014179603e+00 , 8.2350600000000007e+00 , -7.8210299999999999e-01 , -5.7830700000000002e-01 , 2.3211300000000001e-01 --1.2033164381032213e-01 , 1.9281810538887791e+00 , 8.5279239999999987e+00 , 5.1525600000000005e-01 , 4.3903700000000001e-01 , -7.3604199999999997e-01 --5.7336729128012021e-02 , 1.9880956340520652e+00 , 8.5963039999999999e+00 , 3.1502200000000002e-01 , 5.3316100000000000e-01 , -7.8517599999999999e-01 --1.8972541302282764e-02 , 2.0453996058348181e+00 , 8.7202720000000014e+00 , 5.1184700000000005e-01 , 5.0917800000000002e-01 , -6.9191800000000003e-01 -7.9919461576445139e-02 , 2.1112379167126658e+00 , 8.7097784000000011e+00 , -7.8027599999999997e-01 , 1.6914499999999999e-01 , 6.0212900000000003e-01 --8.0052938207623825e-02 , 2.1502031781067803e+00 , 9.3328215999999991e+00 , 1.0167200000000000e-01 , 5.4640699999999998e-01 , 8.3132499999999998e-01 -2.6406901749488343e-02 , 2.2218955169227770e+00 , 9.3213712000000015e+00 , -1.5004899999999999e-01 , 4.2521900000000001e-02 , 9.8776399999999998e-01 -1.0698616867397481e-01 , 2.2909658337424266e+00 , 9.3757216000000003e+00 , -1.9499800000000001e-02 , -1.4125599999999999e-01 , 9.8978100000000002e-01 -2.3037652156524491e-01 , 2.3607483162612350e+00 , 9.3109608000000001e+00 , -1.8640499999999999e-01 , -2.4100199999999999e-01 , 9.5245500000000005e-01 -3.1475298351608183e-01 , 2.4300365633721657e+00 , 9.3513960000000012e+00 , 5.0897000000000003e-01 , -3.9303800000000000e-01 , 7.6581399999999999e-01 -4.6751254934942788e-01 , 2.4955960285854184e+00 , 9.1823648000000002e+00 , -2.5096600000000002e-01 , -4.1612800000000000e-01 , -8.7398699999999996e-01 -6.0879900958162403e-01 , 2.5575012173516471e+00 , 9.0296200000000013e+00 , 5.4510300000000000e-01 , -1.2439400000000000e-02 , 8.3827700000000005e-01 -7.0192898014108795e-01 , 2.6211931239418176e+00 , 9.0230575999999996e+00 , -1.2781899999999999e-01 , 5.5645199999999995e-01 , -8.2098899999999997e-01 -7.8638833386549623e-01 , 2.6845758825097503e+00 , 9.0447312000000011e+00 , -2.6027700000000001e-02 , -1.8388299999999999e-01 , 9.8260400000000003e-01 -8.9232551033042351e-01 , 2.7442518976672425e+00 , 8.9840680000000006e+00 , -1.4616999999999999e-01 , -8.8963100000000003e-02 , 9.8525099999999999e-01 -9.9642615035986726e-01 , 2.8024658249451799e+00 , 8.9210232000000005e+00 , -7.8210100000000005e-01 , -1.1410300000000000e-01 , -6.1261699999999997e-01 -1.1256093574784636e+00 , 2.8495604431596662e+00 , 8.7448991999999990e+00 , -5.0116899999999998e-01 , -2.4590899999999999e-02 , 8.6499999999999999e-01 -1.1886884002175928e+00 , 2.9157815271916627e+00 , 8.8393624000000006e+00 , 2.6204000000000000e-01 , 1.6416300000000000e-01 , 9.5099199999999995e-01 -1.2653988155965714e+00 , 2.9794123134038770e+00 , 8.8816592000000014e+00 , -1.9925100000000001e-01 , -2.2079399999999999e-01 , 9.5475100000000002e-01 -1.3194031660600005e+00 , 3.0575517070920850e+00 , 9.0438888000000013e+00 , 8.5255700000000001e-01 , 4.1714299999999999e-01 , -3.1486199999999998e-01 -1.4099332675357741e+00 , 3.1171606724398089e+00 , 9.0323032000000012e+00 , 1.9143800000000000e-01 , 7.9070900000000000e-01 , 5.8148999999999995e-01 -1.5033114089565638e+00 , 3.1721791518840590e+00 , 8.9880096000000016e+00 , -3.0155999999999999e-01 , -6.9473300000000004e-01 , 6.5300000000000002e-01 -1.6121659054134154e+00 , 3.2120193534049815e+00 , 8.8400695999999996e+00 , 1.0802500000000000e-01 , 8.0794800000000000e-01 , -5.7926800000000001e-01 -1.6956654373622433e+00 , 3.2706170011897604e+00 , 8.8430440000000008e+00 , -8.3872100000000005e-01 , -5.4007000000000005e-01 , 6.9793900000000006e-02 -1.5852246862550601e-01 , 4.1696845509241354e-01 , 1.0128704800000001e+00 , -8.0590899999999993e-02 , 2.1065300000000001e-01 , 9.7423300000000002e-01 -8.3247993530115139e-02 , 3.7172139678457072e-01 , 1.0304475200000001e+00 , 6.5383899999999995e-02 , -2.0295400000000000e-01 , -9.7700299999999995e-01 --2.6108629489178359e-02 , 2.9835310861007236e-01 , 1.0224457600000001e+00 , -9.3094499999999997e-02 , 1.9982400000000000e-01 , 9.7539900000000002e-01 --1.3021646344094817e-01 , 2.3091949216403984e-01 , 1.0238882400000000e+00 , -8.2109699999999994e-02 , 1.5418100000000001e-01 , 9.8462499999999997e-01 --2.4264163932668303e-01 , 1.5714140800877296e-01 , 1.0237353599999999e+00 , -7.5799199999999997e-02 , 1.5456700000000001e-01 , 9.8507000000000000e-01 --3.6337080445226988e-01 , 7.8156995936018214e-02 , 1.0222887199999999e+00 , -7.9814099999999999e-02 , 1.7469199999999999e-01 , 9.8138300000000001e-01 --4.9255050707710435e-01 , -6.9335958240546169e-03 , 1.0203605599999999e+00 , -8.1755599999999998e-02 , 1.4656700000000000e-01 , 9.8581700000000005e-01 --6.2914137433183148e-01 , -9.7028307945251857e-02 , 1.0183762400000000e+00 , -8.8280499999999998e-02 , 1.3583000000000001e-01 , 9.8679099999999997e-01 --7.8323400040409386e-01 , -1.9893717940399203e-01 , 1.0119604799999999e+00 , -7.3568999999999996e-02 , 1.4055799999999999e-01 , 9.8733499999999996e-01 --9.3803474513865481e-01 , -3.0070308247425048e-01 , 1.0114165600000000e+00 , -7.5643199999999994e-02 , 1.4352200000000001e-01 , 9.8675199999999996e-01 --1.1253720997195913e+00 , -4.2570335249402547e-01 , 9.9922360000000010e-01 , -7.7676899999999993e-02 , 1.6318800000000000e-01 , 9.8353199999999996e-01 --1.2917194910081595e+00 , -5.3280232646169701e-01 , 1.0066512800000000e+00 , -9.2272400000000004e-02 , 1.4540200000000000e-01 , 9.8506000000000005e-01 --1.5277288410189596e+00 , -6.9278637568148538e-01 , 9.8439944000000001e-01 , -6.4203399999999994e-02 , 2.0790900000000001e-01 , 9.7603899999999999e-01 --1.6817795141456600e+00 , -7.8652648091083899e-01 , 1.0132885599999999e+00 , -3.7328699999999999e-02 , 2.3049700000000001e-01 , 9.7235700000000003e-01 --1.9148560316014107e+00 , -9.3941115133498387e-01 , 1.0110827200000001e+00 , -6.4057699999999995e-02 , 2.5267499999999998e-01 , 9.6542899999999998e-01 --2.1350067677420199e+00 , -1.0800509839131971e+00 , 1.0249760800000001e+00 , -4.5730500000000000e-02 , 2.4554400000000001e-01 , 9.6830600000000000e-01 --2.3874479754013027e+00 , -1.2436736697760176e+00 , 1.0338243999999999e+00 , -6.1873499999999998e-02 , 2.1206700000000001e-01 , 9.7529399999999999e-01 --2.6907340174399748e+00 , -1.4420308420402850e+00 , 1.0333751200000001e+00 , -6.8007200000000004e-02 , 1.9372000000000000e-01 , 9.7869700000000004e-01 --3.0117182417078006e+00 , -1.6511808382400988e+00 , 1.0388413599999999e+00 , -5.9615300000000003e-02 , 1.7253199999999999e-01 , 9.8319800000000002e-01 --3.3922868186434814e+00 , -1.9006358344914287e+00 , 1.0370577599999999e+00 , -2.2821500000000002e-03 , 1.6803000000000001e-01 , 9.8577899999999996e-01 --3.8247197809559283e+00 , -2.1841406223481457e+00 , 1.0343756000000000e+00 , -3.1646500000000000e-01 , 2.5548100000000001e-01 , 9.1355299999999995e-01 --3.6643759300595260e+00 , -2.0328200805525505e+00 , 1.2294078399999999e+00 , 8.8763199999999998e-01 , -4.0485199999999999e-01 , 2.1955500000000000e-01 --4.9894535826063633e+00 , -2.9533349831932867e+00 , 9.9982159999999998e-01 , -1.2086300000000000e-01 , 1.3476600000000000e-01 , 9.8347899999999999e-01 --3.6863466684722912e+00 , -1.9819134490741486e+00 , 1.5037577600000001e+00 , -9.2668499999999998e-01 , 2.1182000000000001e-01 , -3.1046200000000002e-01 --3.7311556061410025e+00 , -1.9808838880600979e+00 , 1.6310350400000000e+00 , -9.2698000000000003e-01 , 1.8450400000000000e-01 , -3.2659700000000003e-01 --3.8577644633584969e+00 , -2.0381392809128238e+00 , 1.7414622399999999e+00 , -8.6653999999999998e-01 , 2.9086600000000001e-01 , -4.0559299999999998e-01 --3.8821592999672143e+00 , -2.0228587943880427e+00 , 1.8753622400000001e+00 , -8.8092300000000001e-01 , 2.6842600000000000e-01 , -3.8977099999999998e-01 --3.8888142389109444e+00 , -1.9940074200295275e+00 , 2.0118664000000002e+00 , -8.8092300000000001e-01 , 2.6842600000000000e-01 , -3.8977099999999998e-01 --9.0785495507277449e+00 , -5.5380928117107402e+00 , 1.3856075200000000e+00 , -8.6447799999999995e-03 , 4.3255300000000002e-01 , 9.0156700000000001e-01 --9.4438417350611168e+00 , -5.7294728240965505e+00 , 1.5857201599999999e+00 , -2.0387200000000001e-02 , 4.0822100000000000e-01 , 9.1265499999999999e-01 --1.0571343675851537e+01 , -6.4355155274107911e+00 , 1.7197511999999999e+00 , -9.7204400000000003e-03 , 3.7397399999999997e-01 , 9.2738799999999999e-01 --1.2450895849882832e+01 , -7.6382866444564232e+00 , 1.8365099199999999e+00 , 1.8609200000000001e-01 , 3.3765099999999998e-01 , 9.2269199999999996e-01 --1.3268733974093546e+01 , -8.1114758780461766e+00 , 2.0961054639999999e+00 , 6.9618500000000005e-01 , -1.1997900000000000e-01 , 7.0776499999999998e-01 --1.3385380549437812e+01 , -8.1118714604198097e+00 , 2.4171429600000001e+00 , 6.6148200000000001e-01 , -1.9428000000000001e-01 , 7.2436000000000000e-01 --1.3800709240915012e+01 , -8.3092558805903955e+00 , 2.7348889600000001e+00 , 4.5688800000000002e-01 , -1.6211100000000001e-01 , 8.7462799999999996e-01 --2.5247884425385759e+01 , -1.5722852056267357e+01 , 3.0597288000000002e+00 , 6.9091600000000003e-02 , -9.9750099999999997e-01 , 1.4784500000000001e-02 --2.5305632299060477e+01 , -1.5626426700359019e+01 , 3.6263936000000001e+00 , 8.7034600000000004e-02 , -9.9524900000000005e-01 , 4.3635199999999999e-02 --2.5311192372395478e+01 , -1.5496395346538073e+01 , 4.1912383999999996e+00 , 8.7034600000000004e-02 , -9.9524900000000005e-01 , 4.3635199999999999e-02 --2.6497025396567011e+01 , -1.6122504497916804e+01 , 4.8256800000000002e+00 , -5.7584700000000003e-02 , 9.9733200000000000e-01 , -4.4866799999999998e-02 --2.6574723380114449e+01 , -1.6032882225725892e+01 , 5.4171800000000001e+00 , -5.9380299999999997e-02 , 9.9606600000000001e-01 , -6.5769700000000000e-02 --2.6765371200808218e+01 , -1.6015287375095220e+01 , 6.0224288000000001e+00 , -8.0953200000000003e-02 , 9.9140700000000004e-01 , -1.0275400000000000e-01 --2.6825518528237115e+01 , -1.5913830420069154e+01 , 6.6184631999999999e+00 , 3.6331999999999998e-01 , -9.1127700000000000e-01 , 1.9383700000000001e-01 --2.6866626237778920e+01 , -1.5800555300434581e+01 , 7.2141023999999998e+00 , -5.4478800000000001e-02 , -9.6698399999999995e-01 , 2.4894600000000000e-01 --2.6934880871402978e+01 , -1.5703076313012438e+01 , 7.8154408000000002e+00 , -6.0500499999999999e-02 , -9.6233100000000005e-01 , 2.6506299999999999e-01 --2.6476593557498976e+01 , -1.5282599129847103e+01 , 8.3242815999999991e+00 , -4.5614099999999998e-02 , -9.7074499999999997e-01 , 2.3574200000000001e-01 --2.6378043868833959e+01 , -1.5085091322649447e+01 , 8.8878784000000000e+00 , -3.3233699999999998e-02 , -9.7952499999999998e-01 , 1.9856299999999999e-01 --2.6454562814768892e+01 , -1.4993956664823745e+01 , 9.4873240000000010e+00 , 3.7191399999999999e-02 , -9.8209599999999997e-01 , 1.8467200000000000e-01 --2.6479137756305192e+01 , -1.4869583774688930e+01 , 1.0078231199999999e+01 , 5.5546100000000001e-02 , -9.8648400000000003e-01 , 1.5415699999999999e-01 --2.7235335262258136e+01 , -1.5178862000586829e+01 , 1.0864117600000000e+01 , 2.8407500000000002e-01 , 8.7358700000000000e-01 , -3.9515400000000001e-01 --2.7274623479573322e+01 , -1.5059381713425328e+01 , 1.1480286400000001e+01 , 3.0761899999999998e-01 , 8.3914299999999997e-01 , -4.4856400000000002e-01 --6.0252671042351515e+00 , -2.5338610105831032e+00 , 5.6488399999999999e+00 , 6.3834999999999997e-01 , -1.5075300000000000e-01 , -7.5483900000000004e-01 --5.9254769281944588e+00 , -2.4351815436157160e+00 , 5.7909560000000004e+00 , 7.2318499999999997e-01 , 1.3933000000000001e-01 , -6.7645500000000003e-01 --5.9966666531651400e+00 , -2.4347775047580065e+00 , 5.9885768000000006e+00 , 6.6607499999999997e-01 , 4.1200599999999998e-01 , -6.2176799999999999e-01 --5.7123838503571971e+00 , -2.2308812810641419e+00 , 6.0599416000000002e+00 , 6.9240400000000002e-01 , 4.9099399999999999e-01 , -5.2867900000000001e-01 --5.6492544684922512e+00 , -2.1561873024062219e+00 , 6.2069559999999999e+00 , -7.4394899999999997e-01 , -4.2828500000000003e-01 , 5.1294399999999996e-01 --5.6359522263148181e+00 , -2.1075853516526468e+00 , 6.3719831999999998e+00 , 7.4515500000000001e-01 , 6.3660600000000001e-01 , -1.9868800000000000e-01 --5.7390558843520427e+00 , -2.1243788380513271e+00 , 6.5881160000000003e+00 , -8.2360400000000000e-01 , -5.2770300000000003e-01 , -2.0786199999999999e-01 --5.7543311285959460e+00 , -2.0912687635094436e+00 , 6.7702928000000009e+00 , -9.5955800000000002e-01 , -1.4312700000000000e-01 , -2.4240999999999999e-01 --5.8834409854964846e+00 , -2.1193825360759639e+00 , 7.0089936000000002e+00 , -9.5451699999999995e-01 , -2.9725299999999999e-01 , 2.3185799999999999e-02 --5.9086421111501588e+00 , -2.0897595391413564e+00 , 7.2033384000000007e+00 , -9.0986100000000003e-01 , -1.8760800000000000e-01 , 3.7007499999999999e-01 --5.7467107965686033e+00 , -1.9606136333790385e+00 , 7.3044680000000008e+00 , -9.2165799999999998e-01 , 2.6332499999999998e-01 , 2.8496899999999997e-01 --5.7415414942572403e+00 , -1.9139786568741259e+00 , 7.4843359999999999e+00 , 9.2023699999999997e-01 , -3.0798400000000000e-02 , -3.9014799999999999e-01 --5.6094343345726871e+00 , -1.8017127726011197e+00 , 7.5953872000000002e+00 , 9.8982700000000001e-01 , -1.1894800000000000e-01 , 7.8069799999999995e-02 --5.7948244324816658e+00 , -1.8536612094101290e+00 , 7.8882824000000005e+00 , 9.9089600000000000e-01 , -1.7291899999999999e-02 , 1.3351700000000000e-01 --5.7804051485846095e+00 , -1.8016705889416627e+00 , 8.0703759999999996e+00 , 9.9604599999999999e-01 , 4.7684900000000002e-02 , 7.4960299999999994e-02 --5.7376092046946603e+00 , -1.7338255638824265e+00 , 8.2370464000000005e+00 , -8.7385800000000002e-01 , -4.6157799999999999e-01 , -1.5270000000000000e-01 --5.2268776477072336e+00 , -1.4322416681294885e+00 , 8.0984560000000005e+00 , 3.6970599999999998e-01 , -5.1319099999999995e-01 , -7.7456700000000001e-01 --5.1747507054893012e+00 , -1.3627386095955778e+00 , 8.2489960000000018e+00 , -4.6957199999999999e-01 , -3.5990400000000000e-01 , 8.0620800000000004e-01 --4.8912231174894059e+00 , -1.1797728394895750e+00 , 8.2373584000000015e+00 , 6.2823899999999999e-01 , -5.7567500000000005e-01 , -5.2336800000000006e-01 --4.7340456635227417e+00 , -1.0609923992341317e+00 , 8.3070383999999997e+00 , -6.8053600000000003e-01 , 5.6893099999999996e-01 , 4.6172299999999999e-01 --4.8173334625354567e+00 , -1.0578092800692871e+00 , 8.5528008000000000e+00 , -8.4669200000000000e-01 , -4.5556900000000000e-01 , -2.7489900000000000e-01 --5.0266313740565467e+00 , -1.1107520874171199e+00 , 8.9041232000000008e+00 , -8.1577999999999995e-01 , 1.6967099999999999e-01 , -5.5291500000000005e-01 --5.2894562676820431e+00 , -1.1858784588265401e+00 , 9.3131655999999996e+00 , -8.9095599999999997e-01 , 4.4452399999999997e-01 , -9.2708299999999993e-02 --5.3393600822504714e+00 , -1.1598197775767174e+00 , 9.5635872000000006e+00 , 7.3301499999999997e-01 , -6.7703899999999995e-01 , -6.5632700000000002e-02 --5.3169518434428999e+00 , -1.0991318292750760e+00 , 9.7589408000000013e+00 , -9.5156499999999999e-01 , -2.2209699999999999e-01 , 2.1259400000000001e-01 --5.3863882873644728e+00 , -1.0788471786168499e+00 , 1.0039792800000001e+01 , 9.3775100000000000e-01 , 2.9868400000000001e-01 , 1.7723200000000000e-01 --5.5460646423006201e+00 , -1.0948946543032485e+00 , 1.0410948000000001e+01 , 6.5303900000000004e-01 , 6.3289399999999996e-01 , 4.1591499999999998e-01 --5.7031727370984902e+00 , -1.1071743915456804e+00 , 1.0796049600000000e+01 , -6.2848700000000002e-01 , -7.4284099999999997e-01 , -2.3063300000000000e-01 --5.9953142670972071e+00 , -1.1724217570901145e+00 , 1.1326907200000001e+01 , 8.3130499999999996e-01 , -2.6087100000000002e-01 , 4.9079400000000001e-01 --6.3872106003019038e+00 , -1.2739668811754870e+00 , 1.1983064000000001e+01 , -7.5992999999999999e-01 , 5.1171199999999994e-01 , -4.0082000000000001e-01 --6.5269683793285509e+00 , -1.2648385058491112e+00 , 1.2409672000000000e+01 , 8.5674499999999998e-01 , -2.9525099999999999e-01 , 4.2286400000000002e-01 --6.6579442285361026e+00 , -1.2484119527438295e+00 , 1.2842623999999999e+01 , -9.2251300000000003e-01 , 2.1550700000000000e-01 , -3.2019799999999998e-01 --6.0025889677571254e+00 , -9.1813746077516578e-01 , 1.2424128000000000e+01 , 6.6019099999999997e-01 , -7.4705299999999997e-01 , 7.7839099999999994e-02 --6.7835413863270020e+00 , -1.1498442646948148e+00 , 1.3605464000000001e+01 , 5.2065700000000004e-01 , -8.4750300000000001e-01 , -1.0322700000000000e-01 --5.2838786258204884e+00 , -2.9996849514987334e-01 , 1.3052704000000000e+01 , -4.8971500000000001e-02 , 9.2020199999999996e-01 , 3.8836900000000002e-01 --5.2286048565758305e+00 , -2.0615217202937286e-01 , 1.3292944000000000e+01 , 4.6996800000000000e-01 , 7.0220400000000005e-01 , 5.3482700000000005e-01 --4.7828864478808342e+00 , 1.7205325234384006e-02 , 1.3005175999999999e+01 , -3.1863000000000002e-01 , 9.0273099999999995e-01 , -2.8905399999999998e-01 --4.4772315200515784e+00 , 1.8953298519608230e-01 , 1.2887551999999999e+01 , -5.0799499999999997e-01 , -6.1795900000000004e-01 , 6.0005699999999995e-01 --4.4646457995305822e+00 , 2.6773909731788126e-01 , 1.3183536000000000e+01 , -4.9845000000000000e-01 , -7.0045800000000003e-01 , 5.1079100000000000e-01 --2.6242619910113856e+00 , 8.9311463149292636e-01 , 1.0735272000000000e+01 , 1.2982400000000000e-02 , 6.6595099999999996e-01 , 7.4588200000000004e-01 --1.5087973202233518e+00 , 1.2715804827496933e+00 , 9.2468864000000011e+00 , -4.7383599999999998e-01 , 3.5280000000000000e-01 , 8.0685300000000004e-01 --1.3694749468292309e+00 , 1.3579893825139577e+00 , 9.2258992000000006e+00 , -4.2172500000000002e-01 , 4.0459699999999998e-01 , 8.1144899999999998e-01 --3.6162833495673423e+00 , 8.1832391309073937e-01 , 1.3167000000000002e+01 , -2.7980400000000000e-01 , 3.9461499999999999e-01 , -8.7520799999999999e-01 --1.5296105506196604e+00 , 1.4170239257446162e+00 , 9.9221791999999986e+00 , 4.4421899999999997e-01 , -6.5808299999999997e-01 , 6.0794400000000004e-01 --3.1822986253313212e+00 , 1.0854838026933242e+00 , 1.3094096000000000e+01 , 7.9916299999999996e-01 , 1.6619600000000001e-01 , -5.7768299999999995e-01 --2.9978553622723769e+00 , 1.2080096212005544e+00 , 1.3103975999999999e+01 , 7.9916299999999996e-01 , 1.6619600000000001e-01 , -5.7768299999999995e-01 --2.9536782087690412e+00 , 1.3010780795943209e+00 , 1.3375000000000000e+01 , 7.1788399999999997e-01 , -4.0062100000000000e-01 , 5.6933800000000001e-01 --1.3941527867073855e-01 , 1.9176793459440731e+00 , 8.1923887999999998e+00 , -7.8210299999999999e-01 , -5.7830700000000002e-01 , 2.3211300000000001e-01 --2.2751394806679492e-01 , 1.9475790864001721e+00 , 8.5591760000000008e+00 , 3.2876300000000003e-01 , 4.6404499999999999e-01 , -8.2254300000000002e-01 --2.0774376360630020e-01 , 1.9988758966915696e+00 , 8.7231216000000007e+00 , 5.0396500000000000e-01 , 1.1613200000000000e-01 , -8.5588100000000000e-01 --1.1482357468340076e-01 , 2.0632362505458981e+00 , 8.7356432000000002e+00 , 4.9449700000000002e-01 , 3.9718999999999999e-01 , -7.7311900000000000e-01 --3.0321786198848955e-02 , 2.1250486162962430e+00 , 8.7653352000000009e+00 , -6.1564599999999997e-02 , -5.3931499999999999e-01 , 8.3985100000000001e-01 -6.3037872964980535e-02 , 2.1875550851366246e+00 , 8.7740192000000015e+00 , 3.6583100000000002e-01 , -6.1986199999999998e-02 , 9.2861499999999997e-01 -3.8692488064826502e-03 , 2.2405778187031848e+00 , 9.1563231999999992e+00 , -1.0415500000000000e-01 , 8.2740800000000003e-01 , 5.5185799999999996e-01 -1.1033891468282420e-01 , 2.3056781483258546e+00 , 9.1437808000000000e+00 , 8.9423799999999998e-01 , 4.8283699999999999e-02 , -4.4498100000000002e-01 -1.4309837125636982e-01 , 2.3702152938063139e+00 , 9.3235240000000008e+00 , -9.8704699999999992e-03 , -3.1299900000000003e-01 , 9.4970200000000005e-01 -1.8011017047925404e-01 , 2.4366511777097837e+00 , 9.5030591999999992e+00 , -1.4215500000000000e-01 , -6.8135100000000004e-01 , 7.1801999999999999e-01 -3.7603703397356236e-01 , 2.5003803367968787e+00 , 9.2287384000000010e+00 , 2.3781600000000000e-01 , 4.4390099999999999e-01 , 8.6394199999999999e-01 -4.8373114551916130e-01 , 2.5637328461826141e+00 , 9.1972471999999996e+00 , -4.5080900000000002e-01 , 7.0484800000000003e-01 , 5.4768700000000003e-01 -5.2330487381524571e-01 , 2.6332348245764563e+00 , 9.3820031999999998e+00 , 7.3001000000000005e-01 , -3.9374900000000002e-01 , 5.5861300000000003e-01 -6.5245287157435694e-01 , 2.6925170688667377e+00 , 9.2769112000000007e+00 , -1.3013600000000000e-01 , 8.7751800000000002e-01 , 4.6154800000000001e-01 -8.2549372767470652e-01 , 2.7394483203976021e+00 , 8.9986591999999987e+00 , -3.4135700000000002e-01 , 6.9732000000000005e-01 , 6.3025399999999998e-01 -9.2463008398668256e-01 , 2.7969042472082015e+00 , 8.9676983999999997e+00 , 3.2718000000000003e-01 , 3.3530900000000002e-01 , 8.8347100000000001e-01 -1.0645443593598405e+00 , 2.8410063484677579e+00 , 8.7632031999999995e+00 , -3.1868400000000002e-01 , 6.9600099999999998e-02 , 9.4530199999999998e-01 -1.1385740695814452e+00 , 2.9020679889131404e+00 , 8.8185415999999996e+00 , -4.1827900000000001e-01 , -1.9375400000000001e-01 , 8.8741300000000001e-01 -1.2331705830429682e+00 , 2.9552429743715152e+00 , 8.7811848000000001e+00 , 3.3288400000000001e-01 , 3.5185499999999997e-01 , -8.7486299999999995e-01 -1.3041325602097316e+00 , 3.0187908699163257e+00 , 8.8535064000000006e+00 , 3.3732099999999998e-01 , 7.4888200000000005e-01 , -5.7042999999999999e-01 -1.3151557241862719e+00 , 3.1244877347544646e+00 , 9.2697664000000017e+00 , 1.2420100000000001e-01 , 9.5641200000000004e-01 , -2.6429399999999997e-01 -1.4679795789643411e+00 , 3.1403027960051215e+00 , 8.9118607999999995e+00 , 4.9144399999999999e-01 , 6.2261200000000005e-01 , -6.0896499999999998e-01 -1.5588948399591203e+00 , 3.1941641103835434e+00 , 8.8876184000000009e+00 , 4.4007499999999999e-01 , 8.9447600000000005e-01 , -7.9037800000000005e-02 -1.6584954843093320e+00 , 3.2360865616626331e+00 , 8.7902120000000004e+00 , -3.3268500000000001e-01 , 6.9504999999999995e-01 , 6.3735900000000001e-01 --1.8258185590694698e-02 , 4.1661817861282802e-01 , 1.0102777600000001e+00 , -6.0695399999999997e-02 , 2.1523000000000000e-01 , 9.7467499999999996e-01 --1.2305018954154079e-01 , 3.5187915094662170e-01 , 1.0091576799999999e+00 , -7.0150799999999999e-02 , 1.9647000000000001e-01 , 9.7799700000000001e-01 --2.3713101779946966e-01 , 2.8181905160337939e-01 , 1.0060106400000000e+00 , -5.3566900000000001e-02 , 1.9318299999999999e-01 , 9.7969899999999999e-01 --3.5171101175988273e-01 , 2.1155165112298802e-01 , 1.0070142399999999e+00 , -8.4773799999999996e-02 , 1.7287600000000000e-01 , 9.8128899999999997e-01 --4.8252790942034052e-01 , 1.3014033956634163e-01 , 1.0018891200000000e+00 , -8.6345800000000000e-02 , 1.8165300000000001e-01 , 9.7956500000000002e-01 --6.2176959491969308e-01 , 4.3699831959667979e-02 , 9.9638023999999992e-01 , -7.9541799999999996e-02 , 1.7556400000000000e-01 , 9.8124900000000004e-01 --7.6263344328370986e-01 , -4.1700617744529822e-02 , 9.9570319999999990e-01 , -8.1752800000000000e-02 , 1.5072600000000000e-01 , 9.8518899999999998e-01 --9.1898736101520218e-01 , -1.3993999288471315e-01 , 9.9125408000000004e-01 , -7.2958499999999996e-02 , 1.4690100000000000e-01 , 9.8645700000000003e-01 --1.0939321585346882e+00 , -2.4765692583207333e-01 , 9.8315351999999989e-01 , -9.5282800000000001e-02 , 1.4423600000000000e-01 , 9.8494499999999996e-01 --1.2845849391204198e+00 , -3.6677134415080026e-01 , 9.7319968000000001e-01 , -7.9392799999999999e-02 , 1.6979500000000000e-01 , 9.8227600000000004e-01 --1.4781896062956328e+00 , -4.8645230493293656e-01 , 9.7028559999999997e-01 , 9.2940099999999998e-02 , -1.6047300000000000e-01 , -9.8265499999999995e-01 --1.6966792429840889e+00 , -6.2193778409194689e-01 , 9.6267904000000004e-01 , -5.2840699999999997e-02 , 2.0303800000000000e-01 , 9.7774399999999995e-01 --1.9091523350289763e+00 , -7.5103583709076105e-01 , 9.6696903999999995e-01 , -6.8877400000000005e-02 , 2.3690100000000000e-01 , 9.6908899999999998e-01 --2.1166183733172153e+00 , -8.7379192500310277e-01 , 9.8272607999999995e-01 , -5.2852499999999997e-02 , 2.5946200000000003e-01 , 9.6430600000000000e-01 --2.3492185468661475e+00 , -1.0130078965571121e+00 , 9.9581760000000008e-01 , -3.3909700000000001e-02 , 2.3813899999999999e-01 , 9.7063900000000003e-01 --2.6243441466994675e+00 , -1.1806240794957423e+00 , 1.0011049599999999e+00 , -6.1699900000000002e-02 , 2.1273600000000001e-01 , 9.7516000000000003e-01 --2.9341939457432282e+00 , -1.3694774251844581e+00 , 1.0042291200000000e+00 , -4.3036300000000000e-02 , 1.9005100000000000e-01 , 9.8083100000000001e-01 --3.2708636795662178e+00 , -1.5735937120169323e+00 , 1.0102288800000001e+00 , 6.1435200000000002e-02 , 4.9834000000000000e-04 , 9.9811099999999997e-01 --3.7008408716066992e+00 , -1.8398981518384687e+00 , 9.9861624000000004e-01 , -1.3129099999999999e-01 , 4.8303400000000002e-01 , 8.6570199999999997e-01 --4.3096095721571075e+00 , -2.2241011017816552e+00 , 9.4869519999999996e-01 , 5.4645600000000003e-02 , -3.5748500000000000e-01 , -9.3231900000000001e-01 --5.2408687835239407e+00 , -2.8217493203436677e+00 , 8.2980239999999994e-01 , 1.4542900000000000e-01 , -1.6687700000000000e-01 , -9.7519400000000001e-01 --4.8109953420024025e+00 , -2.4921151135888007e+00 , 1.1188724799999998e+00 , -4.4144000000000000e-01 , 2.4661700000000002e-02 , 8.9695199999999997e-01 --3.8150721775445149e+00 , -1.7245311497899567e+00 , 1.7998468000000001e+00 , 8.0642899999999995e-01 , -3.9250800000000002e-01 , 4.4227800000000000e-01 --3.8296831564657454e+00 , -1.7037019050661715e+00 , 1.9317231680000000e+00 , -8.0717300000000003e-01 , 3.9066299999999998e-01 , -4.4255400000000000e-01 --4.9142121869494835e+00 , -2.3769560202788487e+00 , 1.8898016000000000e+00 , 6.8047199999999997e-01 , 2.7532400000000001e-01 , -6.7908400000000002e-01 --9.7212121340872226e+00 , -5.4384895226648400e+00 , 1.3687064799999999e+00 , 6.5997699999999996e-03 , 4.5576200000000000e-01 , 8.9007700000000001e-01 --1.0415503556828018e+01 , -5.8243980118266139e+00 , 1.5396346400000001e+00 , 1.7753000000000001e-02 , 4.7092099999999998e-01 , 8.8199700000000003e-01 --1.1802260335502972e+01 , -6.6434375131663845e+00 , 1.6687964000000000e+00 , -2.9556300000000001e-02 , 3.6059400000000003e-01 , 9.3225499999999994e-01 --1.3335171019680031e+01 , -7.5418825369050602e+00 , 1.8417057600000000e+00 , -7.6210800000000001e-01 , -1.8837100000000001e-01 , -6.1944200000000005e-01 --1.3429004647969657e+01 , -7.5249941578542359e+00 , 2.1585511199999998e+00 , 9.7576099999999999e-01 , -1.1545300000000000e-01 , 1.8590699999999999e-01 --1.3340502555851094e+01 , -7.3962271390940053e+00 , 2.4844663200000001e+00 , 9.7576099999999999e-01 , -1.1545300000000000e-01 , 1.8590699999999999e-01 --1.3680783055661728e+01 , -7.5319625086981894e+00 , 2.7974720000000000e+00 , -9.1432800000000003e-01 , 1.9977200000000001e-01 , -3.5227100000000000e-01 --2.8570010924820583e+01 , -1.6560016252057494e+01 , 3.1602239999999999e+00 , -1.4451900000000001e-01 , 9.8936000000000002e-01 , 1.6754300000000000e-02 --2.8609952026901148e+01 , -1.6440456080710216e+01 , 3.7822583999999999e+00 , -1.5835199999999999e-01 , 9.8734599999999995e-01 , 8.5174699999999992e-03 --3.1348046857530903e+01 , -1.7946500160803037e+01 , 4.5188488000000007e+00 , -8.7671900000000003e-01 , -4.7027700000000000e-01 , 1.0101499999999999e-01 --3.1336721700280734e+01 , -1.7784076540805025e+01 , 5.1906783999999995e+00 , -8.7671900000000003e-01 , -4.7027700000000000e-01 , 1.0101499999999999e-01 --3.1359442787317569e+01 , -1.7643198339297960e+01 , 5.8637040000000002e+00 , -8.7459100000000001e-01 , -4.7511199999999998e-01 , 9.6742300000000003e-02 --3.1408845249292810e+01 , -1.7516748515641364e+01 , 6.5389032000000000e+00 , 5.0213699999999994e-01 , 8.5924100000000003e-01 , -9.7786700000000004e-02 --3.1455313873207601e+01 , -1.7389067282128114e+01 , 7.2152776000000003e+00 , 2.4116100000000001e-02 , -9.7191399999999994e-01 , 2.3409600000000000e-01 --3.1501844481953611e+01 , -1.7261080267842576e+01 , 7.8931703999999998e+00 , -4.9789899999999998e-01 , 8.5582999999999998e-01 , -1.4018200000000000e-01 --3.1394188990079613e+01 , -1.7043580916934655e+01 , 8.5480896000000008e+00 , -5.9349099999999999e-01 , 7.9150699999999996e-01 , -1.4589700000000000e-01 --2.8956160837356155e+01 , -1.5498933384013359e+01 , 8.7767544000000015e+00 , 2.6173800000000003e-01 , 9.5948299999999997e-01 , -1.0433800000000000e-01 --3.1674844860120331e+01 , -1.6892911269123008e+01 , 9.9473576000000001e+00 , -8.0234000000000005e-01 , 5.7022099999999998e-01 , -1.7634800000000000e-01 --3.1892643969513578e+01 , -1.6858111595855700e+01 , 1.0674348799999999e+01 , -8.0893800000000005e-01 , 5.4246700000000003e-01 , -2.2660400000000000e-01 --3.1913056591313712e+01 , -1.6710822991845593e+01 , 1.1363952000000001e+01 , -8.0893800000000005e-01 , 5.4246700000000003e-01 , -2.2660400000000000e-01 --3.1966748270868472e+01 , -1.6582059178440634e+01 , 1.2065640000000000e+01 , -8.1739600000000001e-01 , 5.2609799999999995e-01 , -2.3470099999999999e-01 --6.2402993988124127e+00 , -2.3491220530157362e+00 , 5.5237592000000006e+00 , -9.5171300000000003e-01 , -1.3338800000000001e-01 , 2.7649499999999999e-01 --6.2806213255818655e+00 , -2.3308093483504289e+00 , 5.7114896000000002e+00 , -9.3521200000000004e-01 , -2.8417100000000001e-01 , -2.1124599999999999e-01 --5.7900515219400619e+00 , -2.0252476841036833e+00 , 5.7305840000000003e+00 , -5.5422899999999997e-01 , -5.2528200000000003e-01 , 6.4568499999999995e-01 --5.9931644081203537e+00 , -2.0949869270476089e+00 , 5.9683071999999999e+00 , -5.9886200000000001e-02 , -8.8839500000000005e-01 , 4.5515600000000001e-01 --6.1663902043754000e+00 , -2.1461673816743936e+00 , 6.2043248000000002e+00 , -2.7320600000000000e-01 , -6.3294799999999996e-01 , 7.2438599999999997e-01 --5.9687529768020209e+00 , -2.0023024046105249e+00 , 6.3070560000000002e+00 , -5.7992999999999995e-01 , -7.1444200000000002e-01 , 3.9147700000000002e-01 --5.9182211771190918e+00 , -1.9350858294141928e+00 , 6.4617247999999998e+00 , 5.5375700000000005e-01 , 7.5590800000000002e-01 , -3.4922100000000000e-01 --5.8654047006265468e+00 , -1.8672045083448978e+00 , 6.6149168000000005e+00 , -9.2949999999999999e-01 , 1.3029700000000000e-01 , 3.4504000000000001e-01 --6.2400777698180505e+00 , -2.0175943402763794e+00 , 6.9585432000000003e+00 , -6.7440800000000001e-01 , -7.2359399999999996e-01 , -1.4692000000000000e-01 --5.7169869020780144e+00 , -1.7110219915888689e+00 , 6.9000120000000003e+00 , -9.3337400000000004e-01 , 3.5288199999999997e-01 , -6.5483299999999994e-02 --5.9552472191061776e+00 , -1.7882892093995260e+00 , 7.1929799999999995e+00 , 7.8220000000000001e-01 , 1.7568900000000001e-01 , -5.9774200000000000e-01 --5.6874141344272990e+00 , -1.6140653111884093e+00 , 7.2399880000000003e+00 , 9.9992899999999996e-01 , -8.3326100000000007e-03 , 8.5223399999999998e-03 --5.7397013152960215e+00 , -1.5985494869459935e+00 , 7.4481647999999998e+00 , -8.9377499999999999e-01 , -3.3960000000000001e-01 , 2.9298299999999999e-01 --5.7970454527277990e+00 , -1.5835281823486711e+00 , 7.6633200000000006e+00 , -9.1761099999999995e-01 , -3.7417699999999998e-01 , -1.3409799999999999e-01 --5.7924257215989616e+00 , -1.5381082079323716e+00 , 7.8475456000000001e+00 , -7.9157900000000003e-01 , -5.7715000000000005e-01 , -2.0075200000000001e-01 --5.9410995262713637e+00 , -1.5646697965729741e+00 , 8.1267024000000010e+00 , -8.0801400000000001e-01 , -5.6906699999999999e-01 , -1.5256700000000001e-01 --5.2243595906217868e+00 , -1.1844402776861851e+00 , 7.8742840000000003e+00 , 2.6517900000000000e-01 , -4.8747299999999999e-01 , -8.3189599999999997e-01 --5.1811671923835059e+00 , -1.1223724485929596e+00 , 8.0281935999999998e+00 , -3.6461300000000002e-01 , -1.0923400000000000e-01 , 9.2473000000000005e-01 --5.2809134107892968e+00 , -1.1259425269316408e+00 , 8.2790727999999998e+00 , -2.3772399999999999e-01 , -5.9224600000000005e-01 , 7.6989099999999999e-01 --4.9760421480551598e+00 , -9.4420000680777871e-01 , 8.2553504000000011e+00 , -5.1616300000000004e-01 , 5.8670400000000000e-01 , 6.2398299999999995e-01 --4.8389465630902171e+00 , -8.4036717501782787e-01 , 8.3414624000000011e+00 , 6.0192100000000004e-01 , 3.8950699999999999e-01 , 6.9711900000000004e-01 --5.2281781395618649e+00 , -9.6893025396646992e-01 , 8.8166592000000001e+00 , 9.0021300000000004e-01 , 4.2710999999999999e-01 , -8.4819599999999995e-02 --5.0300251340351281e+00 , -8.3671829211338800e-01 , 8.8616600000000005e+00 , 6.7747199999999996e-01 , 6.0560499999999995e-01 , -4.1746299999999997e-01 --5.1473219423475465e+00 , -8.4196781140947197e-01 , 9.1531616000000007e+00 , -9.3675600000000003e-01 , 1.8660099999999999e-01 , 2.9608699999999999e-01 --4.9167610365603389e+00 , -6.9740316237070177e-01 , 9.1661928000000010e+00 , 7.0129900000000001e-01 , 1.3515099999999999e-01 , -6.9993799999999995e-01 --6.0132877852358693e+00 , -1.1056895425058588e+00 , 1.0305076000000000e+01 , -8.0441700000000005e-01 , -4.8859999999999998e-01 , -3.3790900000000001e-01 --5.7250863587615273e+00 , -9.3253642375995138e-01 , 1.0287895199999999e+01 , -3.3398499999999998e-01 , -7.8527000000000002e-01 , -5.2134999999999998e-01 --5.4225646082593073e+00 , -7.5710651153711295e-01 , 1.0248198400000000e+01 , 8.5991399999999996e-02 , -5.7409599999999998e-02 , -9.9464100000000000e-01 --5.2625565966300245e+00 , -6.4051128507409194e-01 , 1.0328715200000001e+01 , -3.0480099999999999e-01 , -1.6456999999999999e-01 , 9.3808999999999998e-01 --4.9859320743146425e+00 , -4.7908550818617890e-01 , 1.0293022400000000e+01 , -3.0926199999999998e-01 , -9.2997300000000005e-02 , 9.4641900000000001e-01 --5.7410604199143922e+00 , -7.1412101321489763e-01 , 1.1279004799999999e+01 , -8.5215300000000005e-01 , 4.2111199999999999e-01 , -3.1064399999999998e-01 --5.9382514627377176e+00 , -7.2779826006685777e-01 , 1.1743489600000002e+01 , -8.8447900000000002e-01 , 4.6637099999999998e-01 , 1.3988900000000000e-02 --5.8553777065955845e+00 , -6.3340321001116973e-01 , 1.1929275200000001e+01 , -7.1270699999999998e-01 , 6.2447900000000001e-01 , 3.1949200000000000e-01 --5.6534204424581649e+00 , -4.9671560373603452e-01 , 1.1986745599999999e+01 , -8.3113800000000004e-01 , 3.6089800000000000e-01 , 4.2303900000000000e-01 --5.5792193438702791e+00 , -4.0623166661816379e-01 , 1.2182910399999999e+01 , 7.7075400000000005e-01 , -5.4757100000000003e-01 , -3.2573700000000000e-01 --5.5473052842269892e+00 , -3.2878188250300600e-01 , 1.2431824000000001e+01 , -3.5326000000000003e-02 , -9.0921500000000000e-01 , 4.1482500000000000e-01 --5.3595198313062840e+00 , -1.9861104192010215e-01 , 1.2501400000000000e+01 , -8.7371200000000004e-01 , -2.0557200000000000e-01 , 4.4086999999999998e-01 --5.2231431058016096e+00 , -8.5264259871148163e-02 , 1.2629320000000000e+01 , 7.1778799999999998e-01 , -1.3788800000000001e-01 , -6.8247100000000005e-01 --5.1854515994085730e+00 , -3.9119230458459775e-03 , 1.2882975999999999e+01 , 4.6640900000000002e-01 , -6.6183499999999995e-01 , -5.8688799999999997e-01 --4.8520601313480922e+00 , 1.7114763283684775e-01 , 1.2753184000000001e+01 , 2.8490199999999999e-01 , 1.1033800000000000e-02 , -9.5849300000000004e-01 --4.7467973236465655e+00 , 2.7345351065233747e-01 , 1.2919792000000001e+01 , 4.7541699999999998e-01 , 3.4988999999999998e-01 , -8.0718999999999996e-01 --4.6391635520627625e+00 , 3.7735952242126292e-01 , 1.3084216000000000e+01 , 5.9361399999999998e-01 , 6.9554499999999997e-01 , -4.0477099999999999e-01 --1.6958842015686040e+00 , 1.2627618068425588e+00 , 9.1210360000000001e+00 , -4.7730899999999998e-01 , 4.3160900000000002e-01 , 7.6543399999999995e-01 --1.5541067329405327e+00 , 1.3458538545211280e+00 , 9.1051864000000009e+00 , 4.6416099999999999e-01 , -5.5393499999999996e-01 , -6.9116699999999998e-01 --1.5246295711831244e+00 , 1.3999377884073709e+00 , 9.2587007999999997e+00 , 4.1787000000000002e-01 , -4.6837699999999999e-01 , -7.7846499999999996e-01 --1.3769206155195390e+00 , 1.4830839350228531e+00 , 9.2285824000000005e+00 , -5.3654800000000002e-01 , 3.6936099999999999e-01 , 7.5874200000000003e-01 --1.6149253059189923e+00 , 1.4767439651593453e+00 , 9.8314704000000006e+00 , 6.6962900000000003e-01 , -5.2151800000000004e-01 , 5.2878700000000001e-01 --1.4511545387307341e+00 , 1.5648831086360628e+00 , 9.7821223999999987e+00 , -7.7622899999999995e-01 , 4.3718499999999999e-01 , -4.5424399999999998e-01 --3.1266140113025500e+00 , 1.2815511611251764e+00 , 1.2993528000000001e+01 , 7.9916299999999996e-01 , 1.6619600000000001e-01 , -5.7768299999999995e-01 --3.0293827612509920e+00 , 1.3810234924792839e+00 , 1.3165440000000000e+01 , -8.2959099999999997e-01 , 5.1380999999999999e-01 , -2.1858100000000000e-01 --1.1368938907232429e+00 , 1.7894554770966506e+00 , 9.9203071999999999e+00 , 2.3664700000000000e-01 , -1.8336600000000000e-01 , 9.5413599999999998e-01 --9.9598399896781808e-01 , 1.8693939584904582e+00 , 9.8938912000000006e+00 , 2.9148700000000000e-01 , -2.2318700000000000e-01 , 9.3017399999999995e-01 --2.2901385566957533e-01 , 2.0349665520037328e+00 , 8.5762216000000002e+00 , -2.6146900000000001e-01 , -5.0672499999999998e-01 , 8.2150100000000004e-01 --1.8133957527299494e-01 , 2.0895820838387502e+00 , 8.6835599999999999e+00 , 4.7948400000000002e-01 , -6.8601300000000004e-02 , -8.7486500000000000e-01 --9.6016702134211318e-02 , 2.1484432259410151e+00 , 8.7145936000000006e+00 , -7.3352200000000006e-02 , -4.7430499999999998e-01 , 8.7729900000000005e-01 -2.7327969872286362e-02 , 2.2113316917230321e+00 , 8.6577783999999998e+00 , 5.1332299999999999e-03 , -1.6539000000000001e-01 , 9.8621499999999995e-01 -8.9364241140278633e-02 , 2.2681231646252424e+00 , 8.7420912000000008e+00 , 3.0769800000000003e-01 , -4.0517500000000001e-01 , 8.6090400000000000e-01 --4.1434096389812325e-02 , 2.3187473803015650e+00 , 9.3080175999999994e+00 , -6.9617399999999996e-02 , 7.3362499999999997e-01 , 6.7597900000000000e-01 -1.3552461176232367e-01 , 2.3838640464238958e+00 , 9.1208695999999989e+00 , 6.5161999999999998e-01 , -4.2506800000000000e-01 , -6.2825799999999998e-01 -8.4258974728724567e-02 , 2.4482068284588192e+00 , 9.5346960000000003e+00 , -4.5451700000000003e-03 , -5.0459900000000002e-01 , 8.6334200000000005e-01 -2.1384722162798742e-01 , 2.5123842748818217e+00 , 9.4697999999999993e+00 , 6.5452200000000005e-01 , -7.6498700000000003e-02 , 7.5216300000000003e-01 -1.8594333499400961e-01 , 2.5869064299753273e+00 , 9.8653535999999988e+00 , 7.7641400000000005e-01 , 5.6537099999999996e-01 , -2.7845500000000001e-01 -5.5364766183949587e-01 , 2.6242090106075215e+00 , 9.0538103999999997e+00 , 5.8973500000000000e-03 , -7.7256100000000005e-01 , 6.3491299999999995e-01 -5.9655449781716574e-01 , 2.6903553254150427e+00 , 9.2278960000000012e+00 , 4.6967799999999998e-01 , -6.5902000000000005e-01 , -5.8744799999999997e-01 -6.9591037707894743e-01 , 2.7506073199005221e+00 , 9.2213960000000004e+00 , -3.4021200000000001e-01 , 7.5550099999999998e-01 , 5.5988800000000005e-01 -8.7343402522277325e-01 , 2.7899718541569705e+00 , 8.9223648000000004e+00 , -4.7472199999999998e-01 , -8.0134300000000006e-02 , -8.7648000000000004e-01 -9.5344769171112764e-01 , 2.8494938732673396e+00 , 8.9713488000000012e+00 , 6.1968400000000001e-01 , -1.3228899999999999e-01 , 7.7362299999999995e-01 -1.0988885123691379e+00 , 2.8870940030376877e+00 , 8.7462927999999991e+00 , -3.9343000000000000e-01 , 8.5903900000000005e-02 , 9.1533299999999995e-01 -1.1807423344328294e+00 , 2.9426945563923788e+00 , 8.7709720000000004e+00 , 2.4793599999999999e-01 , 2.2125400000000001e-01 , 9.4317200000000001e-01 -1.2513404380114088e+00 , 3.0053834383341416e+00 , 8.8547544000000009e+00 , -5.2339700000000003e-02 , -8.6105600000000004e-01 , 5.0580899999999995e-01 -1.3207329449350582e+00 , 3.0708840526435419e+00 , 8.9574856000000000e+00 , -8.8438600000000001e-01 , -2.0838999999999999e-01 , -4.1765400000000003e-01 -1.3981940092934537e+00 , 3.1348792334167763e+00 , 9.0281224000000009e+00 , -6.3763799999999995e-02 , 8.5453800000000002e-01 , 5.1546099999999995e-01 -1.4873277616550238e+00 , 3.1910535221617233e+00 , 9.0361095999999996e+00 , 5.9737600000000002e-01 , -3.1248300000000001e-01 , 7.3857700000000004e-01 -1.6143903680009726e+00 , 3.2119184750477490e+00 , 8.7873312000000006e+00 , 5.6003900000000002e-02 , 7.7493100000000004e-01 , 6.2956000000000001e-01 -1.6995985087405594e+00 , 3.2674137296852717e+00 , 8.8016311999999992e+00 , -2.4317500000000000e-01 , -9.2775799999999997e-01 , 2.8307399999999999e-01 --1.3899047295087286e-01 , 4.4847050168006075e-01 , 9.7396511999999991e-01 , -7.5471300000000005e-02 , 2.1072199999999999e-01 , 9.7462800000000005e-01 --2.2568147070142741e-01 , 4.0353024608428889e-01 , 9.9066648000000002e-01 , -6.7767400000000005e-02 , 2.3960200000000001e-01 , 9.6850300000000000e-01 --3.4198184752856919e-01 , 3.3599144868823694e-01 , 9.8898271999999987e-01 , -1.0063999999999999e-01 , 2.0715300000000000e-01 , 9.7311800000000004e-01 --4.8122700244022587e-01 , 2.5323243662049522e-01 , 9.7544191999999996e-01 , 8.7400500000000006e-02 , -1.9850400000000001e-01 , -9.7619500000000003e-01 --5.9954499650580084e-01 , 1.8742817580784998e-01 , 9.8192839999999992e-01 , -8.8201299999999996e-02 , 1.9049900000000000e-01 , 9.7771699999999995e-01 --7.4991146161526334e-01 , 9.9698212414236931e-02 , 9.7291576000000002e-01 , -8.9074600000000004e-02 , 2.0929000000000000e-01 , 9.7378799999999999e-01 --8.9409043763514573e-01 , 1.6936548549267849e-02 , 9.7408264000000000e-01 , -7.8924700000000000e-02 , 1.8736100000000000e-01 , 9.7911499999999996e-01 --1.0625987516154152e+00 , -8.0392180058102003e-02 , 9.6630136000000011e-01 , -9.3971600000000002e-02 , 1.7679100000000000e-01 , 9.7975199999999996e-01 --1.2477796364571323e+00 , -1.8917597585122037e-01 , 9.5603759999999993e-01 , -9.5730499999999996e-02 , 1.6681199999999999e-01 , 9.8133099999999995e-01 --1.4437834922226149e+00 , -3.0236089345397987e-01 , 9.4796719999999990e-01 , -9.2635499999999996e-02 , 1.7697700000000000e-01 , 9.7984599999999999e-01 --1.6566647394872800e+00 , -4.2667099410167708e-01 , 9.3903359999999991e-01 , -7.4918100000000001e-02 , 1.9245399999999999e-01 , 9.7844200000000003e-01 --1.8725580737680136e+00 , -5.5036073823282061e-01 , 9.3784799999999979e-01 , -7.6269500000000004e-02 , 1.9911499999999999e-01 , 9.7700399999999998e-01 --2.1375542754081573e+00 , -7.0570469290417570e-01 , 9.2191519999999993e-01 , -6.0404699999999999e-02 , 2.3783699999999999e-01 , 9.6942499999999998e-01 --2.3414512969621031e+00 , -8.1659520512081984e-01 , 9.4461839999999997e-01 , -6.8285600000000002e-02 , 2.7097100000000002e-01 , 9.6016199999999996e-01 --2.5876736144667873e+00 , -9.5519805733181418e-01 , 9.5779520000000007e-01 , -4.8786299999999998e-02 , 2.7790599999999999e-01 , 9.5936900000000003e-01 --2.8844777120506446e+00 , -1.1245982544183337e+00 , 9.6015079999999986e-01 , -3.5754399999999999e-02 , 2.2646800000000000e-01 , 9.7336199999999995e-01 --3.1765984470663824e+00 , -1.2871066334794321e+00 , 9.7660048000000010e-01 , 2.3026700000000000e-01 , 1.4987900000000001e-01 , 9.6151600000000004e-01 --3.5371440352963370e+00 , -1.4927413885984899e+00 , 9.8052543999999986e-01 , -1.5845200000000001e-01 , -9.0818200000000002e-02 , 9.8318099999999997e-01 --4.0940093863864329e+00 , -1.8210481321594849e+00 , 9.3447839999999993e-01 , -2.1364100000000000e-01 , 3.7794200000000000e-01 , 9.0084200000000003e-01 --5.0132979741638755e+00 , -2.3764553471879486e+00 , 8.0121280000000006e-01 , -1.7898800000000001e-01 , 1.9840600000000000e-01 , 9.6363799999999999e-01 --5.0190426256048024e+00 , -2.3431430042504990e+00 , 9.6533832000000008e-01 , -2.4343899999999999e-01 , 5.1700700000000002e-02 , 9.6853699999999998e-01 --4.9793562428606615e+00 , -2.2811067421473918e+00 , 1.1394655199999999e+00 , -2.4343899999999999e-01 , 5.1700700000000002e-02 , 9.6853699999999998e-01 --3.5975323467910698e+00 , -1.3802017947981957e+00 , 1.6316496800000000e+00 , 8.9001699999999995e-01 , -2.8938300000000000e-01 , 3.5231699999999999e-01 --3.6042588831530660e+00 , -1.3551850825903387e+00 , 1.7596362400000001e+00 , 7.9221299999999995e-01 , -5.5523900000000004e-01 , 2.5319599999999998e-01 --3.7236702687820964e+00 , -1.3990010651400331e+00 , 1.8645046400000000e+00 , -7.7003900000000003e-01 , 5.5445699999999998e-01 , -3.1562299999999999e-01 --3.8144645131841601e+00 , -1.4253221665413505e+00 , 1.9780047279999999e+00 , -7.7003900000000003e-01 , 5.5445699999999998e-01 , -3.1562299999999999e-01 --1.0435935251310712e+01 , -5.4137034141017288e+00 , 1.0809207999999999e+00 , -3.6160400000000001e-03 , -4.7326400000000002e-01 , -8.8091299999999995e-01 --1.0498258985865874e+01 , -5.3920724495911614e+00 , 1.3382812799999999e+00 , -3.6160200000000002e-03 , -4.7326400000000002e-01 , -8.8091299999999995e-01 --1.1446680603756622e+01 , -5.8984599740296462e+00 , 1.4948397600000001e+00 , -2.9206800000000002e-02 , 5.0494300000000003e-01 , 8.6265800000000004e-01 --1.3376562194667081e+01 , -6.9791076648352508e+00 , 1.5957291200000001e+00 , -9.2819399999999996e-01 , 3.8765700000000000e-02 , -3.7007200000000001e-01 --1.3455082034656593e+01 , -6.9529603433016511e+00 , 1.9090425360000001e+00 , 9.9309700000000001e-01 , 1.1071700000000000e-01 , -3.8729000000000000e-02 --1.3421159561712516e+01 , -6.8611811141835233e+00 , 2.2295404799999998e+00 , 9.8115399999999997e-01 , 1.8512300000000001e-01 , 5.5366199999999997e-02 --1.3435346464201428e+01 , -6.7980002048693144e+00 , 2.5453520799999998e+00 , -9.5587999999999995e-01 , -6.7062099999999999e-02 , -2.8600199999999998e-01 --1.5031180953778566e+01 , -7.6441094272963408e+00 , 2.8381547199999999e+00 , 3.6328700000000003e-01 , 1.2787899999999999e-01 , 9.2285899999999998e-01 --1.4993777176468413e+01 , -7.5443768319631594e+00 , 3.1830727999999997e+00 , 2.5655600000000001e-01 , 1.9081999999999999e-01 , 9.4750500000000004e-01 --3.5301504249579231e+01 , -1.8960348359354693e+01 , 4.0454096000000002e+00 , -3.6292300000000000e-01 , 9.3170900000000001e-01 , -1.4363799999999999e-02 --3.6023356967962670e+01 , -1.9198252601541395e+01 , 4.8183791999999999e+00 , 6.8435299999999999e-01 , 9.4796099999999994e-02 , -7.2296300000000002e-01 --3.2145549749730478e+01 , -1.6868417652952498e+01 , 5.3201376000000007e+00 , -8.6640200000000001e-01 , -4.9262800000000001e-01 , 8.1643199999999999e-02 --3.2099267856207675e+01 , -1.6689463695354611e+01 , 5.9917072000000005e+00 , 8.5875100000000004e-01 , 5.0691699999999995e-01 , -7.4706400000000006e-02 --3.6083256248612493e+01 , -1.8722158568189123e+01 , 7.0792039999999998e+00 , -3.5299199999999997e-01 , -2.4726500000000001e-01 , 9.0236200000000000e-01 --3.3472935850766881e+01 , -1.7132823066072852e+01 , 7.5087032000000002e+00 , -3.1667200000000001e-01 , -8.6177599999999999e-01 , -3.9631000000000000e-01 --3.0807238803631606e+01 , -1.5536082310048180e+01 , 7.8282016000000008e+00 , -1.8906800000000001e-01 , -3.9664899999999997e-01 , 8.9828900000000000e-01 --3.0746455719637254e+01 , -1.5356947811851612e+01 , 8.4670112000000000e+00 , -3.0175700000000000e-01 , -4.9529299999999998e-01 , 8.1463300000000005e-01 --3.1002094059855047e+01 , -1.5198299302108676e+01 , 9.8164840000000009e+00 , -9.2083599999999999e-01 , 3.8986700000000002e-01 , -8.0898900000000006e-03 --3.0928650038781221e+01 , -1.5010952974145869e+01 , 1.0456271200000002e+01 , -8.6659200000000003e-01 , 4.8719200000000001e-01 , -1.0799499999999999e-01 --3.1007895643317859e+01 , -1.4904273355493274e+01 , 1.1132250400000000e+01 , -8.5302199999999995e-01 , 5.1642200000000005e-01 , -7.5254000000000001e-02 --3.1482278718342023e+01 , -1.4997740238383336e+01 , 1.1916316800000001e+01 , 8.1777999999999995e-01 , -5.2210000000000001e-01 , 2.4217400000000000e-01 --3.1610973962855333e+01 , -1.4910953275314579e+01 , 1.2625368000000000e+01 , -7.9572200000000004e-01 , 5.6248600000000004e-01 , -2.2458200000000000e-01 --8.2605187267886251e+00 , -2.9923383774993555e+00 , 6.2955743999999996e+00 , -3.6672100000000002e-01 , -1.4848999999999999e-02 , 9.3021200000000004e-01 --8.2209515350675542e+00 , -2.9236940741206485e+00 , 6.4971991999999998e+00 , -2.2828100000000001e-01 , -6.6146800000000006e-02 , 9.7134600000000004e-01 --6.5280674712800639e+00 , -2.0371027305200728e+00 , 6.1361736000000002e+00 , 4.2048700000000000e-01 , 7.1809999999999996e-01 , -5.5454800000000004e-01 --6.3980246936038725e+00 , -1.9325560457006086e+00 , 6.2717583999999995e+00 , 8.3715499999999998e-02 , 9.2301299999999997e-01 , -3.7555100000000002e-01 --6.1520439900479040e+00 , -1.7716649130682849e+00 , 6.3586087999999998e+00 , -4.5370300000000002e-01 , -7.4578000000000000e-01 , 4.8781799999999997e-01 --6.9092601132355753e+00 , -2.0954964033329553e+00 , 6.8401600000000000e+00 , -2.0019200000000001e-01 , -9.5512399999999997e-01 , 2.1831400000000001e-01 --6.6036003449797249e+00 , -1.9063888204393518e+00 , 6.9058672000000003e+00 , -4.0144299999999999e-01 , -8.3783399999999997e-01 , 3.6997000000000002e-01 --5.6950964261616566e+00 , -1.4350887312212302e+00 , 6.6931664000000008e+00 , -9.3988400000000005e-01 , 1.9091000000000000e-01 , 2.8314499999999998e-01 --6.2347128090898920e+00 , -1.6482550919623331e+00 , 7.1168936000000000e+00 , -3.6189399999999999e-01 , -4.6821400000000002e-01 , 8.0610700000000002e-01 --5.7119410580656202e+00 , -1.3648168845841879e+00 , 7.0488880000000007e+00 , -9.2710000000000004e-01 , -5.1906700000000000e-02 , -3.7120300000000001e-01 --5.9912162058369685e+00 , -1.4521809562210595e+00 , 7.3673256000000000e+00 , -4.8194599999999999e-01 , -8.3488399999999996e-01 , 2.6588699999999998e-01 --5.9988650014260871e+00 , -1.4137153868900865e+00 , 7.5565640000000007e+00 , 6.3368899999999995e-01 , 7.2531000000000001e-01 , -2.6900499999999999e-01 --6.3843136968242025e+00 , -1.5436127196314899e+00 , 7.9574319999999998e+00 , -6.5899500000000000e-01 , -7.4950799999999995e-01 , -6.2960100000000005e-02 --6.2312212695240774e+00 , -1.4312207938460668e+00 , 8.0683584000000010e+00 , -8.5367300000000002e-01 , -4.4726399999999999e-01 , 2.6682899999999998e-01 --6.1356939038654890e+00 , -1.3442822534096748e+00 , 8.2092992000000002e+00 , -5.9292999999999996e-01 , -8.2561599999999999e-02 , 8.0101000000000000e-01 --5.5975933764587120e+00 , -1.0675205743431002e+00 , 8.0745672000000006e+00 , -2.4081800000000000e-01 , -4.0704699999999999e-01 , 8.8109000000000004e-01 --6.4717797219324815e+00 , -1.3974798072737404e+00 , 8.8275167999999997e+00 , -9.7514900000000004e-01 , -1.6553300000000001e-01 , -1.4724999999999999e-01 --4.8473983782127288e+00 , -6.6508022265178601e-01 , 7.9553415999999997e+00 , 6.8807799999999997e-01 , -2.3701600000000000e-01 , -6.8583700000000003e-01 --4.9373924219105954e+00 , -6.6268350428987954e-01 , 8.1957687999999997e+00 , -8.2226299999999997e-01 , -4.4629900000000000e-01 , -3.5312900000000003e-01 --5.2400317730849215e+00 , -7.4440566396853436e-01 , 8.5951704000000007e+00 , -9.0539199999999997e-01 , -2.7925699999999998e-01 , -3.1981399999999999e-01 --5.3572013191512662e+00 , -7.4839844914766074e-01 , 8.8771144000000000e+00 , -9.3018400000000001e-01 , -1.3668700000000000e-01 , 3.4069500000000003e-01 --5.2413063354461906e+00 , -6.5755403013757352e-01 , 8.9890703999999992e+00 , -8.4202299999999997e-01 , -1.3739199999999999e-01 , 5.2165200000000000e-01 --5.0689845514116110e+00 , -5.4354559842298800e-01 , 9.0541535999999994e+00 , -8.4202299999999997e-01 , -1.3739199999999999e-01 , 5.2165200000000000e-01 --5.8136302017146848e+00 , -7.8527433234941046e-01 , 9.8667992000000009e+00 , -8.7296099999999999e-01 , -4.3123099999999998e-01 , -2.2799000000000000e-01 --5.9201447491918957e+00 , -7.7519050094835151e-01 , 1.0183978400000001e+01 , 6.0134800000000002e-02 , -2.7871099999999999e-01 , -9.5849099999999998e-01 --5.6356190782003086e+00 , -6.1520858931610656e-01 , 1.0169189600000001e+01 , 4.0801799999999999e-01 , -2.4622500000000000e-01 , -8.7914400000000004e-01 --5.3900912681369064e+00 , -4.7291788287854519e-01 , 1.0179433600000001e+01 , 3.7286300000000000e-01 , 9.1814099999999992e-03 , -9.2784100000000003e-01 --5.2421346086830676e+00 , -3.6733226975795441e-01 , 1.0271276000000000e+01 , -3.0926199999999998e-01 , -9.2997600000000000e-02 , 9.4641900000000001e-01 --5.1501563539762012e+00 , -2.8283011430977023e-01 , 1.0415180800000000e+01 , 9.8115799999999997e-01 , 1.6213100000000000e-01 , -1.0508600000000000e-01 --5.3993192536021350e+00 , -3.1584059263758180e-01 , 1.0899113600000000e+01 , 9.2560200000000004e-01 , -3.0314500000000000e-01 , 2.2663800000000001e-01 --5.2063517164575925e+00 , -1.9374944681640427e-01 , 1.0950739199999999e+01 , -8.4416700000000000e-01 , -5.2482600000000001e-01 , 1.0927500000000000e-01 --5.7722657216125404e+00 , -3.2513659908040671e-01 , 1.1801105600000000e+01 , -7.0975200000000005e-01 , 4.6517500000000001e-01 , 5.2902300000000002e-01 --5.7529828452235723e+00 , -2.5620246983297079e-01 , 1.2057788000000000e+01 , -7.7387399999999995e-01 , 5.0923099999999999e-01 , 3.7656699999999999e-01 --5.5265949679707118e+00 , -1.1994788152930580e-01 , 1.2086689600000001e+01 , -8.3729900000000002e-01 , 3.5815399999999997e-01 , 4.1310599999999997e-01 --5.5328455351794297e+00 , -5.7389800903188792e-02 , 1.2380052800000000e+01 , -8.2698499999999997e-01 , -1.0889300000000000e-01 , 5.5157800000000001e-01 --5.6949948320428332e+00 , -3.8466364350430382e-02 , 1.2871536000000001e+01 , -9.4904299999999997e-01 , -2.7130399999999999e-01 , 1.6034699999999999e-01 --5.3957632670375739e+00 , 1.1843527707791646e-01 , 1.2812984000000000e+01 , -1.0044000000000000e-01 , -3.9400099999999999e-01 , 9.1360600000000003e-01 --5.6240572253369168e+00 , 1.2543826262531810e-01 , 1.3415664000000000e+01 , -8.7914199999999998e-01 , 2.1366800000000000e-01 , 4.2597699999999999e-01 --4.9499539752272366e+00 , 3.8442707759456307e-01 , 1.2858016000000001e+01 , -4.8739800000000000e-01 , -5.3627100000000005e-01 , 6.8909799999999999e-01 --5.0530141880215176e+00 , 4.2793389382176694e-01 , 1.3315512000000000e+01 , -4.8925500000000000e-01 , -4.1567700000000002e-01 , 7.6670799999999995e-01 --4.8117156031098238e+00 , 5.6470448412335239e-01 , 1.3307919999999999e+01 , 5.9361399999999998e-01 , 6.9554499999999997e-01 , -4.0477099999999999e-01 --1.5826325908571950e+00 , 1.4256429185147059e+00 , 8.9470232000000003e+00 , 5.5562699999999998e-01 , -6.9746200000000003e-01 , -4.5257599999999998e-01 --1.5668729341701795e+00 , 1.4731152040711124e+00 , 9.1174896000000007e+00 , 4.6416099999999999e-01 , -5.5393499999999996e-01 , -6.9116599999999995e-01 --1.4352399514911154e+00 , 1.5476214858180612e+00 , 9.1148376000000013e+00 , -4.2495800000000000e-01 , 4.4585100000000000e-01 , 7.8779900000000003e-01 --1.2219176316241360e+00 , 1.6381373390645055e+00 , 8.9771831999999989e+00 , -9.0804900000000000e-01 , 4.1220800000000002e-01 , 7.4370699999999998e-02 --1.4087734314644336e+00 , 1.6474428735014013e+00 , 9.4894455999999998e+00 , 9.8786900000000000e-01 , -9.8336199999999999e-02 , 1.2018700000000000e-01 --1.3463577954098329e+00 , 1.7096392936470433e+00 , 9.6059359999999998e+00 , -9.0587399999999996e-01 , -4.2201499999999997e-01 , 3.6004800000000003e-02 --3.1550906230811693e+00 , 1.4545913345470503e+00 , 1.3055719999999999e+01 , -8.2959099999999997e-01 , 5.1380999999999999e-01 , -2.1858100000000000e-01 --1.2776643904851768e+00 , 1.8268747502825495e+00 , 9.9547728000000006e+00 , 1.0602300000000001e-01 , 1.3843400000000000e-01 , 9.8468000000000000e-01 --1.0903102808787208e+00 , 1.9099660804211540e+00 , 9.8485264000000008e+00 , -1.7825600000000000e-01 , -1.3358900000000001e-01 , -9.7487400000000002e-01 --3.5085599292869807e-01 , 2.0592592119784583e+00 , 8.6339208000000003e+00 , 5.1039400000000001e-01 , 1.6333400000000001e-01 , -8.4428700000000001e-01 --2.2747150034959462e-01 , 2.1201713948045202e+00 , 8.5936623999999995e+00 , 5.1039400000000001e-01 , 1.6333400000000001e-01 , -8.4428700000000001e-01 --1.6810617742358014e-01 , 2.1737017060755188e+00 , 8.6822808000000009e+00 , 5.8427799999999996e-01 , 3.1199199999999999e-01 , -7.4918600000000002e-01 --1.4088203667631216e-01 , 2.2266506413795208e+00 , 8.8454879999999996e+00 , -7.6301600000000003e-01 , -5.0299000000000005e-01 , 4.0596399999999999e-01 --1.2994584715985402e-01 , 2.2803811599415083e+00 , 9.0565351999999990e+00 , -7.3192100000000004e-01 , 6.0739600000000005e-01 , 3.0880700000000000e-01 --1.2026483498901674e-01 , 2.3381050345113477e+00 , 9.2871343999999993e+00 , -6.4570099999999997e-01 , -7.5949400000000000e-01 , -7.8988299999999997e-02 -7.1357624128574715e-02 , 2.3994070593702421e+00 , 9.0736431999999994e+00 , 1.0889800000000000e-02 , 7.8396500000000002e-01 , 6.2070899999999996e-01 -2.1245774481325252e-02 , 2.4617224099255095e+00 , 9.4776520000000009e+00 , -2.8276200000000001e-01 , -6.3701099999999999e-01 , -7.1712100000000001e-01 -1.1996473254087570e-01 , 2.5240694695192252e+00 , 9.5024975999999999e+00 , 2.3238100000000000e-01 , 1.1742700000000000e-01 , -9.6550999999999998e-01 -2.0581325134941708e-01 , 2.5880850672346725e+00 , 9.5645024000000003e+00 , 4.0437400000000001e-01 , -3.1822899999999998e-01 , 8.5744500000000001e-01 -4.4644469937018516e-01 , 2.6334486881883241e+00 , 9.1611280000000015e+00 , -7.1248500000000003e-01 , 6.4315900000000004e-01 , 2.8055799999999997e-01 -5.6285259732163540e-01 , 2.6889927914319838e+00 , 9.1085455999999994e+00 , -5.4704600000000003e-01 , 5.7725400000000004e-01 , -6.0623199999999999e-01 -6.2758280765462393e-01 , 2.7507118510721105e+00 , 9.2231535999999998e+00 , -2.2323599999999999e-01 , 8.5462700000000003e-01 , 4.6880600000000000e-01 -7.3682675323353242e-01 , 2.8054765198967502e+00 , 9.1862336000000013e+00 , 1.9110900000000000e-01 , 6.4843099999999998e-01 , 7.3689600000000000e-01 -8.7647460267929023e-01 , 2.8491288041023735e+00 , 9.0269159999999999e+00 , 5.8989899999999995e-01 , -1.3858899999999999e-01 , 7.9549499999999995e-01 -1.0122518034381840e+00 , 2.8902243444693467e+00 , 8.8645720000000008e+00 , -6.9817799999999997e-01 , -1.6640199999999999e-01 , -6.9631799999999999e-01 -1.1206346433687586e+00 , 2.9353489791406857e+00 , 8.7902015999999996e+00 , -3.8201299999999999e-01 , -2.6926299999999997e-01 , 8.8406099999999999e-01 -1.2124044028160865e+00 , 2.9865077859301836e+00 , 8.7843672000000002e+00 , -2.7214699999999997e-01 , -2.7298299999999998e-01 , 9.2272200000000004e-01 -1.2110624138847377e+00 , 3.0875015247179052e+00 , 9.2326383999999990e+00 , -3.5539399999999999e-01 , -9.3167999999999995e-01 , 7.5277499999999997e-02 -1.3358978588021655e+00 , 3.1239914684725658e+00 , 9.0820256000000015e+00 , 1.7092599999999999e-01 , 9.5066600000000001e-01 , 2.5888000000000000e-01 -1.4569935689873414e+00 , 3.1569961688020989e+00 , 8.9185584000000002e+00 , -5.2885199999999999e-01 , -5.3336399999999995e-01 , 6.6017999999999999e-01 -1.5589586395513002e+00 , 3.1982518684122967e+00 , 8.8446560000000005e+00 , -5.7558400000000003e-02 , -9.9791900000000000e-01 , 2.9066900000000000e-02 -1.6555933498900219e+00 , 3.2412815504645707e+00 , 8.7890055999999994e+00 , 3.4124700000000002e-01 , -5.5487799999999998e-01 , -7.5872300000000004e-01 --3.5064090247465396e-01 , 4.4440501338971083e-01 , 9.5605840000000009e-01 , -5.0333099999999999e-02 , 2.5449800000000000e-01 , 9.6576300000000004e-01 --4.6129816841702098e-01 , 3.8645690429545199e-01 , 9.6107119999999990e-01 , -7.4085100000000001e-02 , 2.2739899999999999e-01 , 9.7097999999999995e-01 --6.0379042237551683e-01 , 3.0840910380224407e-01 , 9.4905919999999977e-01 , 7.6063699999999998e-02 , -2.0569999999999999e-01 , -9.7565400000000002e-01 --7.4114489091898772e-01 , 2.3427850697353403e-01 , 9.4711440000000002e-01 , -9.4150899999999996e-02 , 1.9788500000000001e-01 , 9.7569300000000003e-01 --8.8687457602889586e-01 , 1.5722984443869881e-01 , 9.4467039999999991e-01 , 8.3482799999999996e-02 , -2.0926000000000000e-01 , -9.7428999999999999e-01 --1.0411655426574753e+00 , 7.4307229868132874e-02 , 9.4286079999999983e-01 , -6.9335499999999994e-02 , 2.0696300000000001e-01 , 9.7588900000000001e-01 --1.2130348597057079e+00 , -1.9214133143823808e-02 , 9.3743199999999982e-01 , -9.3464000000000005e-02 , 1.8853700000000001e-01 , 9.7760899999999995e-01 --1.4114862433804656e+00 , -1.2692090121108190e-01 , 9.2441119999999999e-01 , -1.0491600000000000e-01 , 1.7602100000000001e-01 , 9.7877999999999998e-01 --1.6347387126425663e+00 , -2.5053191030547683e-01 , 9.0620079999999992e-01 , -1.0445300000000000e-01 , 1.8164400000000000e-01 , 9.7780100000000003e-01 --1.8530476266891016e+00 , -3.6769709934105554e-01 , 8.9996079999999989e-01 , -7.9209299999999996e-02 , 1.8851399999999999e-01 , 9.7887100000000005e-01 --2.0813841998950364e+00 , -4.8999356052522280e-01 , 8.9777679999999993e-01 , -8.6476899999999995e-02 , 2.0270400000000000e-01 , 9.7541400000000000e-01 --2.3689210077056577e+00 , -6.4737056804079707e-01 , 8.7746559999999985e-01 , -8.8430400000000006e-02 , 2.4241099999999999e-01 , 9.6613499999999997e-01 --2.5692932195222333e+00 , -7.4743378359043566e-01 , 9.0721999999999992e-01 , -5.7183299999999999e-02 , 2.6229400000000003e-01 , 9.6329200000000004e-01 --2.8451381142504379e+00 , -8.9260384025359985e-01 , 9.1312719999999992e-01 , -1.3615199999999999e-02 , 2.6805600000000002e-01 , 9.6330700000000002e-01 --3.1313386297614416e+00 , -1.0422819011184972e+00 , 9.2602319999999994e-01 , -8.6402599999999996e-02 , -2.4230900000000000e-01 , -9.6634399999999998e-01 --3.4208707911549583e+00 , -1.1908101379127096e+00 , 9.4918400000000003e-01 , 1.3746900000000001e-01 , 4.5208100000000001e-01 , 8.8131999999999999e-01 --3.4645511022220452e+00 , -1.1884906405614286e+00 , 1.0673498399999999e+00 , -2.0833399999999999e-01 , 9.6560199999999996e-01 , -1.5559600000000001e-01 --3.4796204705452860e+00 , -1.1686456839845420e+00 , 1.1942444000000001e+00 , -1.6950799999999999e-01 , -9.7196300000000002e-01 , 1.6295499999999999e-01 --3.4935704381697681e+00 , -1.1478840645930815e+00 , 1.3206553599999999e+00 , -9.7395900000000002e-01 , -7.7948900000000002e-02 , -2.1290300000000001e-01 --3.5053463348912723e+00 , -1.1262785013001584e+00 , 1.4465047200000001e+00 , -9.8381300000000005e-01 , -1.0687500000000000e-01 , -1.4384000000000000e-01 --3.5139141521159738e+00 , -1.1037997860947892e+00 , 1.5720191999999999e+00 , -9.6429200000000004e-01 , -4.4981199999999999e-02 , -2.6099400000000000e-01 --3.5305825301323877e+00 , -1.0847564834090164e+00 , 1.6946154400000000e+00 , 9.9792899999999995e-01 , 6.2827700000000000e-02 , 1.3795600000000000e-02 --3.5358323580484523e+00 , -1.0605334145503500e+00 , 1.8189838400000000e+00 , 9.7970100000000004e-01 , 7.0074200000000003e-02 , -1.8781800000000001e-01 --3.5388720345959852e+00 , -1.0344403816149792e+00 , 1.9425857600000001e+00 , -9.7620799999999996e-01 , 1.8358600000000000e-01 , -1.1538700000000000e-01 --3.5750031570510181e+00 , -1.0284258370786596e+00 , 2.0595918960000001e+00 , 9.3986800000000004e-01 , -3.2364300000000001e-01 , 1.0910200000000000e-01 --1.1349658528690375e+01 , -5.3955544348861615e+00 , 1.0234451999999998e+00 , 1.0968000000000000e-02 , 2.5236700000000001e-01 , 9.6756900000000001e-01 --1.1458353422827273e+01 , -5.3948687078792652e+00 , 1.2882177600000000e+00 , -2.1087200000000000e-01 , -2.1197600000000000e-01 , 9.5425300000000002e-01 --1.3020612852389661e+01 , -6.2029740481755713e+00 , 1.3973189599999998e+00 , 5.0468299999999999e-01 , 1.3895099999999999e-01 , 8.5204899999999995e-01 --1.3780442249107809e+01 , -6.5540126465146926e+00 , 1.6378824000000001e+00 , 7.6444500000000004e-01 , 5.5856399999999995e-01 , 3.2191599999999998e-01 --1.3565253498339528e+01 , -6.3649714024822206e+00 , 1.9737657920000000e+00 , -9.4346300000000005e-01 , -3.3128099999999999e-01 , 1.1435200000000000e-02 --1.3819242189507714e+01 , -6.4332767246077349e+00 , 2.2762864000000000e+00 , 8.4050499999999995e-01 , 5.1966400000000001e-01 , 1.5330400000000000e-01 --1.3857961051851754e+01 , -6.3836109665567022e+00 , 2.5935997600000000e+00 , 8.4050400000000003e-01 , 5.1966400000000001e-01 , 1.5330400000000000e-01 --3.8746757149083095e+01 , -1.9619366942956265e+01 , 2.6533633600000002e+00 , 4.5634200000000003e-01 , -2.3667799999999999e-02 , -8.8949000000000000e-01 --3.8829095874128718e+01 , -1.9486435340611830e+01 , 3.4536600000000002e+00 , 4.5634200000000003e-01 , -2.3667899999999999e-02 , -8.8949000000000000e-01 --3.2817663296955992e+01 , -1.6148205712954319e+01 , 4.0817264000000009e+00 , -8.0245599999999995e-01 , -5.9601999999999999e-01 , 2.8721000000000000e-02 --3.2924442219812754e+01 , -1.6052275186417930e+01 , 4.7669512000000003e+00 , -7.8666800000000003e-01 , -6.1684700000000003e-01 , -2.5576300000000000e-02 --3.2889775796944711e+01 , -1.5885120057637700e+01 , 5.4461024000000000e+00 , 7.1931400000000001e-01 , 6.9066899999999998e-01 , 7.4592599999999995e-02 --3.3076074072897512e+01 , -1.5830352098601271e+01 , 6.1415920000000002e+00 , 7.0288099999999998e-01 , 6.8063600000000002e-01 , -2.0662200000000000e-01 --3.5586578072868861e+01 , -1.6956741034406260e+01 , 7.0884808000000001e+00 , -4.1977700000000000e-02 , 3.0931300000000000e-01 , 9.5003300000000002e-01 --3.3029008100100057e+01 , -1.5504503046568171e+01 , 7.5004248000000002e+00 , -4.6663700000000002e-01 , -5.8809999999999996e-01 , 6.6059800000000002e-01 --3.1199285595084469e+01 , -1.4438056981328085e+01 , 7.9190664000000002e+00 , 5.8122499999999999e-01 , -1.0309599999999999e-01 , -8.0718599999999996e-01 --3.2265059178859708e+01 , -1.4823576631941947e+01 , 8.7400112000000014e+00 , -4.3658700000000000e-01 , -8.7989600000000001e-01 , 1.8754899999999999e-01 --3.1476591643662523e+01 , -1.4287684551295634e+01 , 9.2650135999999996e+00 , -9.5492900000000003e-01 , 2.7669100000000002e-01 , 1.0748300000000000e-01 --2.9736971059655001e+01 , -1.3156276867029408e+01 , 1.0192412800000000e+01 , -8.7575700000000001e-01 , 3.8932000000000000e-01 , 2.8544799999999998e-01 --3.0546544331904713e+01 , -1.3406402507235786e+01 , 1.1012712799999999e+01 , -7.9685600000000001e-01 , 5.9200100000000000e-01 , 1.2064400000000000e-01 --3.0777177980151500e+01 , -1.3372676464341035e+01 , 1.1715950400000001e+01 , 8.1990099999999999e-01 , -5.7212499999999999e-01 , 2.0857600000000000e-02 --3.0201561550603472e+01 , -1.2957788190374389e+01 , 1.2206320800000000e+01 , 8.1990099999999999e-01 , -5.7212499999999999e-01 , 2.0857500000000001e-02 --8.9579903838147938e+00 , -2.9128864561598817e+00 , 6.4937048000000006e+00 , 5.3584699999999996e-01 , 3.1973099999999999e-01 , -7.8143499999999999e-01 --8.3512318806535433e+00 , -2.5830505928767016e+00 , 6.5262880000000001e+00 , 1.8426200000000001e-01 , -3.5718899999999998e-02 , -9.8222799999999999e-01 --7.8354216170247106e+00 , -2.2987208481504160e+00 , 6.5667439999999999e+00 , 5.3036899999999998e-01 , -1.0705700000000000e-01 , -8.4097999999999995e-01 --7.9583063299791661e+00 , -2.3096978816814460e+00 , 6.8179248000000001e+00 , 7.8983099999999995e-01 , -6.0988200000000004e-01 , -6.4891500000000005e-02 --3.1476627930673551e+01 , -1.2655809302160392e+01 , 1.6642679999999999e+01 , -7.9843500000000001e-01 , 5.5984599999999995e-01 , -2.2152900000000000e-01 --8.0179813132413678e+00 , -2.1938196203696023e+00 , 7.4805295999999997e+00 , -8.7620600000000004e-01 , 4.6202300000000002e-01 , -1.3710400000000000e-01 --7.9559440687049534e+00 , -2.1187633950890223e+00 , 7.6712759999999998e+00 , -8.7958499999999995e-01 , 4.4209700000000002e-01 , -1.7572900000000000e-01 --9.7639577878681365e+00 , -2.8489122358245709e+00 , 8.7262832000000010e+00 , 2.2530400000000000e-01 , -9.3957100000000005e-01 , 2.5776900000000003e-01 --6.3374765200331318e+00 , -1.3335287159274434e+00 , 7.3289392000000007e+00 , 8.4661500000000001e-01 , 5.3198599999999996e-01 , 1.5295100000000001e-02 --6.3276130602325384e+00 , -1.2872792386136171e+00 , 7.5131856000000008e+00 , 9.9364799999999998e-01 , 1.0845900000000000e-01 , 3.0021900000000001e-02 --6.3235900076517808e+00 , -1.2429989232297762e+00 , 7.7021743999999996e+00 , -9.2172100000000001e-01 , -3.8447799999999999e-01 , -5.1060700000000001e-02 --7.9455430827701452e+00 , -1.8669764629615906e+00 , 8.7862496000000014e+00 , -8.6066299999999996e-01 , 5.0669900000000001e-01 , 5.0154200000000003e-02 --6.2030167442139472e+00 , -1.1080703249602077e+00 , 8.0234407999999995e+00 , -8.8914099999999996e-01 , 9.7507300000000005e-02 , 4.4712400000000002e-01 --5.9776956391011229e+00 , -9.7445777645844611e-01 , 8.0864335999999994e+00 , 2.4192600000000000e-01 , -2.9005399999999998e-01 , 9.2592699999999994e-01 --5.9786631441737113e+00 , -9.3188945777689014e-01 , 8.2817040000000013e+00 , 2.4192600000000000e-01 , -2.9005399999999998e-01 , 9.2592699999999994e-01 --5.0372603295382534e+00 , -5.2007267275680880e-01 , 7.8756463999999999e+00 , 9.0354100000000004e-01 , 2.3606400000000000e-01 , 3.5761500000000002e-01 --5.1877794867143612e+00 , -5.3821137948341757e-01 , 8.1540128000000003e+00 , -8.4332099999999999e-01 , -3.7882500000000002e-01 , -3.8118500000000000e-01 --5.2913097795103443e+00 , -5.3724807144440234e-01 , 8.4107888000000006e+00 , -8.9467399999999997e-01 , -3.2470399999999999e-01 , -3.0680099999999999e-01 --5.1704912104509164e+00 , -4.5006723475996369e-01 , 8.5161720000000010e+00 , -9.1097799999999995e-01 , -3.6000300000000002e-01 , -2.0128900000000000e-01 --5.3056034142688402e+00 , -4.5673683380817476e-01 , 8.8073511999999994e+00 , 9.9258800000000003e-01 , 9.5706200000000005e-02 , -7.4892700000000006e-02 --5.2990167719428793e+00 , -4.1049793040336313e-01 , 9.0013736000000009e+00 , -9.6172500000000005e-01 , -1.6839299999999999e-01 , 2.1617000000000000e-01 --5.5943155251955172e+00 , -4.7116336583151508e-01 , 9.4383295999999994e+00 , -7.5084300000000004e-01 , -2.6453599999999999e-01 , -6.0519100000000003e-01 --5.9262285565044355e+00 , -5.4039162169322452e-01 , 9.9251328000000001e+00 , -9.3473600000000001e-01 , -1.2566600000000000e-01 , 3.3238099999999998e-01 --5.7848170220237369e+00 , -4.4036570800691655e-01 , 1.0035414400000001e+01 , -2.1826699999999999e-01 , -1.9588800000000001e-01 , 9.5602699999999996e-01 --5.8023558882247155e+00 , -3.9540830798415483e-01 , 1.0281156000000001e+01 , -1.5921199999999999e-01 , -3.0021900000000001e-01 , 9.4048900000000002e-01 --5.4617539083735762e+00 , -2.2984987443171256e-01 , 1.0211112000000000e+01 , -3.8377899999999998e-01 , -3.0762000000000000e-01 , 8.7068000000000001e-01 --5.3608978738072963e+00 , -1.4548470704068661e-01 , 1.0350960799999999e+01 , -3.2645900000000000e-01 , -2.1977200000000000e-01 , 9.1930699999999999e-01 --5.1929828674116942e+00 , -3.8999653565097159e-02 , 1.0425196000000001e+01 , -7.7852200000000005e-01 , -5.0181699999999996e-01 , 3.7693900000000002e-01 --4.1586070201447187e+00 , 3.3646042811387633e-01 , 9.6371464000000007e+00 , -9.2830599999999996e-01 , -2.2458900000000001e-01 , 2.9632300000000000e-01 --5.8846180358909850e+00 , -1.4433794221841456e-01 , 1.1615184800000000e+01 , 7.5995000000000001e-01 , -3.8290400000000002e-01 , -5.2522400000000002e-01 --4.6354726177624634e+00 , 2.8884781667202053e-01 , 1.0569225599999999e+01 , -4.7663899999999998e-01 , 7.9105400000000003e-01 , 3.8346799999999998e-01 --4.5004623260938530e+00 , 3.8140022723993061e-01 , 1.0662128800000000e+01 , 1.5054200000000001e-01 , 1.5028900000000001e-01 , 9.7711300000000001e-01 --5.4241146718269073e+00 , 1.7385935398404895e-01 , 1.1943585600000000e+01 , -8.1969099999999995e-01 , 3.9350000000000002e-01 , 4.1625099999999998e-01 --5.2496521903283693e+00 , 2.8468850263986156e-01 , 1.2024965600000002e+01 , -9.3089000000000000e-01 , -3.6529699999999998e-01 , -1.2930400000000001e-03 --5.4808069561521133e+00 , 2.8638307870362856e-01 , 1.2590112000000001e+01 , -7.3192500000000005e-01 , -1.8459200000000001e-01 , 6.5590499999999996e-01 --5.4079858353822878e+00 , 3.7231508091167642e-01 , 1.2805600000000000e+01 , -1.3709399999999999e-01 , 2.6997399999999999e-01 , 9.5305799999999996e-01 --5.1327953861413755e+00 , 5.1034865684471686e-01 , 1.2769408000000000e+01 , -5.1405000000000001e-01 , -1.9257700000000000e-01 , 8.3586300000000002e-01 --1.5906780614746756e+00 , 1.4327718339317417e+00 , 8.4114855999999989e+00 , -2.6653500000000002e-01 , -4.7663499999999998e-02 , 9.6264600000000000e-01 --1.5308232042380814e+00 , 1.4850388590402399e+00 , 8.5044928000000013e+00 , -3.9480700000000002e-01 , -6.7181199999999996e-02 , 9.1630500000000004e-01 --1.6311506250532855e+00 , 1.5026578441547860e+00 , 8.8235127999999996e+00 , -6.2649900000000003e-01 , 7.7716300000000005e-01 , 5.9308100000000002e-02 --1.6573706587055694e+00 , 1.5394535519936450e+00 , 9.0532488000000004e+00 , 5.1705999999999996e-01 , -7.4793699999999996e-01 , -4.1621999999999998e-01 --1.3409880668647074e+00 , 1.6465057871870243e+00 , 8.7772328000000002e+00 , -5.8545199999999997e-01 , 7.8183400000000003e-01 , 2.1443100000000001e-01 --1.3627373083102259e+00 , 1.6859024298536547e+00 , 9.0050239999999988e+00 , 9.9340700000000004e-01 , 9.8837099999999997e-02 , -5.8078200000000003e-02 --1.3572808792237434e+00 , 1.7312256620905748e+00 , 9.1995248000000007e+00 , -9.7645300000000002e-01 , 7.7193399999999995e-02 , 2.0144799999999999e-01 --1.2450520670165908e+00 , 1.7975443637856023e+00 , 9.2258887999999999e+00 , -9.9311199999999999e-01 , 7.1510099999999993e-02 , 9.2814599999999997e-02 --1.2936277644881318e+00 , 1.8381999473870665e+00 , 9.5279775999999998e+00 , -9.8917100000000002e-01 , -1.7575600000000000e-02 , -1.4571300000000001e-01 --1.3956318132002683e+00 , 1.8748737455928404e+00 , 9.9412216000000004e+00 , 7.3887300000000003e-02 , 1.7055200000000001e-01 , 9.8257499999999998e-01 --1.2588168557288713e+00 , 1.9470591844631548e+00 , 9.9386943999999993e+00 , 1.6953500000000000e-02 , -2.2641300000000000e-03 , 9.9985400000000002e-01 --2.6835389080869581e+00 , 1.8499413571002410e+00 , 1.2926240000000000e+01 , -7.1788399999999997e-01 , 4.0062100000000000e-01 , -5.6933800000000001e-01 --3.3863563715582812e-01 , 2.1488474622959757e+00 , 8.6332136000000013e+00 , 4.4358500000000001e-01 , 4.7689799999999999e-01 , -7.5881500000000002e-01 --3.9519685560199891e-01 , 2.1919389639726985e+00 , 8.9667832000000001e+00 , 5.0506200000000001e-01 , 8.1479999999999997e-01 , 2.8462999999999999e-01 --2.0101900177388510e-01 , 2.2551353076452663e+00 , 8.7843048000000010e+00 , -8.9885999999999999e-01 , -2.9132400000000003e-01 , 3.2738699999999998e-01 --1.7072479002563368e-01 , 2.3080677634068509e+00 , 8.9480944000000004e+00 , -8.0989400000000000e-01 , -1.2039999999999999e-01 , 5.7408599999999999e-01 --1.0177123946529143e-01 , 2.3630864702630103e+00 , 9.0356103999999995e+00 , 3.5829100000000003e-01 , 4.9843100000000001e-01 , 7.8942699999999999e-01 --3.4490008389207460e-03 , 2.4199571508987519e+00 , 9.0542680000000004e+00 , 7.4576699999999996e-03 , 6.3276100000000002e-01 , 7.7431200000000000e-01 --1.0760719713091227e-01 , 2.4822816523427180e+00 , 9.5838256000000008e+00 , 3.8583299999999998e-01 , 4.4311200000000001e-01 , -8.0918800000000002e-01 -4.6071697694409774e-02 , 2.5397462414488210e+00 , 9.4749376000000005e+00 , -1.4679200000000000e-02 , 6.9658799999999998e-01 , 7.1732099999999999e-01 -1.1196332251091934e-01 , 2.6019129619398900e+00 , 9.5972936000000004e+00 , -3.5190100000000002e-01 , -4.8504700000000001e-01 , 8.0055900000000002e-01 -4.3055031863252680e-01 , 2.6370000734657548e+00 , 8.9909007999999986e+00 , 7.9749499999999995e-01 , -3.6981399999999998e-01 , 4.7669699999999998e-01 -3.7984403326876270e-01 , 2.7121940428203710e+00 , 9.4534407999999992e+00 , 5.2997700000000003e-01 , -4.9230699999999999e-01 , 6.9047599999999998e-01 -5.9711503245284225e-01 , 2.7483664874385347e+00 , 9.0943287999999995e+00 , 8.2964300000000002e-01 , -4.4892300000000002e-01 , -3.3190399999999998e-01 -6.7407286512508735e-01 , 2.8066673849574464e+00 , 9.1682208000000003e+00 , 3.2415400000000000e-01 , -6.3965600000000000e-01 , -6.9696800000000003e-01 -8.0425641845197404e-01 , 2.8516801222728514e+00 , 9.0610592000000008e+00 , 3.4786699999999998e-01 , -3.6217899999999997e-01 , 8.6476299999999995e-01 -9.0936483795494971e-01 , 2.9006508967576821e+00 , 9.0313775999999990e+00 , 3.3919400000000000e-01 , -6.2543600000000005e-02 , 9.3863500000000000e-01 -1.0697640259542460e+00 , 2.9277429330950260e+00 , 8.7679247999999994e+00 , -5.2044699999999999e-01 , 1.4133000000000001e-01 , -8.4211700000000000e-01 -1.1522928197367053e+00 , 2.9802650182226174e+00 , 8.8037944000000010e+00 , 6.9750999999999997e-03 , 6.6249800000000003e-01 , 7.4903100000000000e-01 -1.3199552624946356e+00 , 2.9896649768687693e+00 , 8.4435072000000009e+00 , -9.7492700000000002e-02 , 7.2427900000000001e-01 , 6.8257999999999996e-01 -1.2866641768218279e+00 , 3.1065407941629872e+00 , 9.0534256000000006e+00 , 8.1871099999999997e-01 , 5.7071000000000005e-01 , 6.3259099999999999e-02 -1.4049122559011509e+00 , 3.1408464908357052e+00 , 8.9221672000000005e+00 , 3.7998600000000000e-02 , -2.5488899999999998e-01 , 9.6622300000000005e-01 -1.4330291396546435e+00 , 3.2427395302854451e+00 , 9.3179288000000007e+00 , -7.8061700000000003e-03 , 9.7400500000000001e-01 , 2.2639000000000001e-01 -1.6188713932594438e+00 , 3.2107469651354807e+00 , 8.7244944000000011e+00 , -4.2612499999999998e-02 , -9.7803499999999999e-01 , 2.0403700000000000e-01 -1.6915144517194227e+00 , 3.2769064988622336e+00 , 8.8522688000000009e+00 , 6.7402899999999999e-01 , -6.2306700000000004e-01 , 3.9682800000000001e-01 --3.5424581391815613e-01 , 5.5180887455167693e-01 , 9.2446319999999993e-01 , -4.6931100000000003e-02 , 2.2842000000000001e-01 , 9.7243100000000005e-01 --4.6672386819830303e-01 , 4.9567128041582231e-01 , 9.2751040000000007e-01 , -6.7067699999999994e-02 , 2.0544299999999999e-01 , 9.7636800000000001e-01 --5.8062553943498463e-01 , 4.4132178008049006e-01 , 9.3385439999999997e-01 , -6.3518400000000003e-02 , 1.9013600000000000e-01 , 9.7970100000000004e-01 --7.1853513022067128e-01 , 3.7186657402545853e-01 , 9.2863359999999995e-01 , -1.0188500000000000e-01 , 1.8820000000000001e-01 , 9.7683200000000003e-01 --8.8848824875009180e-01 , 2.8265990755862580e-01 , 9.0810399999999980e-01 , -8.5644399999999996e-02 , 1.8818699999999999e-01 , 9.7839200000000004e-01 --1.0296819648205342e+00 , 2.1427714397964071e-01 , 9.1274239999999995e-01 , -7.1131299999999995e-02 , 1.9248299999999999e-01 , 9.7871900000000001e-01 --1.1961797993389740e+00 , 1.3126766768283393e-01 , 9.0790639999999989e-01 , -8.9749499999999996e-02 , 1.9424900000000000e-01 , 9.7683799999999998e-01 --1.3802875346746752e+00 , 3.8809703477042046e-02 , 8.9984640000000016e-01 , -9.8432000000000006e-02 , 1.8359700000000001e-01 , 9.7806099999999996e-01 --1.5810510519504288e+00 , -6.2935173738217109e-02 , 8.8960240000000002e-01 , -1.0335500000000000e-01 , 1.7295900000000000e-01 , 9.7949100000000000e-01 --1.8017583203796463e+00 , -1.7470774898685848e-01 , 8.7801679999999993e-01 , -9.2121099999999997e-02 , 1.6586699999999999e-01 , 9.8183600000000004e-01 --2.0403849939129532e+00 , -2.9534424880622634e-01 , 8.6603600000000003e-01 , -7.0680999999999994e-02 , 1.8265200000000001e-01 , 9.8063400000000001e-01 --2.2731028283406971e+00 , -4.1052774652174850e-01 , 8.6656639999999996e-01 , -1.0856499999999999e-01 , 1.8593000000000001e-01 , 9.7654700000000005e-01 --2.6424981099929887e+00 , -6.0449039936869253e-01 , 8.1582479999999991e-01 , -5.3048100000000001e-02 , 2.3295199999999999e-01 , 9.7104000000000001e-01 --2.8373087690565768e+00 , -6.9262370094312908e-01 , 8.5329599999999983e-01 , -1.3374600000000000e-02 , 2.7060499999999998e-01 , 9.6259700000000004e-01 --3.0945982734534416e+00 , -8.1547283831940787e-01 , 8.7378399999999989e-01 , 6.2985799999999998e-03 , 2.5838600000000000e-01 , 9.6602100000000002e-01 --3.3691295097873706e+00 , -9.4660284510719173e-01 , 8.9693439999999991e-01 , -2.4200400000000000e-01 , -3.3527299999999999e-01 , -9.1050900000000001e-01 --3.7585501560332784e+00 , -1.1404014537750022e+00 , 8.9020560000000004e-01 , -3.8862999999999998e-01 , 3.4397699999999998e-01 , 8.5477899999999996e-01 --4.6727284045997797e+00 , -1.6281005465477945e+00 , 7.2516800000000003e-01 , -8.3590800000000007e-02 , -4.6901500000000002e-01 , -8.7922599999999995e-01 --5.0363582189698128e+00 , -1.7991514686670689e+00 , 7.6830719999999997e-01 , -5.6004200000000004e-01 , 1.3417100000000001e-01 , 8.1752800000000003e-01 --4.8114832998720400e+00 , -1.6391005565797916e+00 , 9.9405063999999999e-01 , -3.7773800000000002e-01 , 5.6796800000000003e-01 , 7.3124999999999996e-01 --4.7851656579282258e+00 , -1.5907359766779954e+00 , 1.1554232799999999e+00 , -3.7773800000000002e-01 , 5.6796800000000003e-01 , 7.3124999999999996e-01 --3.7299013771803127e+00 , -9.7999476582417566e-01 , 1.5659913599999999e+00 , 9.8128000000000004e-01 , 7.7195700000000006e-02 , 1.7643700000000001e-01 --3.6736450740896718e+00 , -9.2112570183149778e-01 , 1.7068104799999999e+00 , 9.9708100000000000e-01 , 6.9108500000000003e-02 , -3.2444899999999999e-02 --3.7316141366636808e+00 , -9.2537426510519571e-01 , 1.8209036800000000e+00 , 9.8971799999999999e-01 , 1.1529100000000000e-01 , -8.4651199999999996e-02 --1.0189927993283870e+01 , -4.3490976812737134e+00 , 7.6239999999999997e-01 , 6.5181099999999997e-03 , 3.7166800000000000e-01 , 9.2834300000000003e-01 --1.1719760518645137e+01 , -5.1051593823820145e+00 , 7.6782879999999998e-01 , 5.5088800000000004e-01 , -1.5173300000000001e-01 , -8.2067000000000001e-01 --1.2463051711339492e+01 , -5.4346573686818402e+00 , 9.4484719999999989e-01 , -9.8308300000000001e-02 , 4.7161300000000000e-01 , 8.7630900000000000e-01 --1.2785369858814875e+01 , -5.5380792513924018e+00 , 1.2008130399999999e+00 , -4.0362999999999996e-03 , 6.4192000000000005e-01 , 7.6676100000000003e-01 --1.4329087350611339e+01 , -6.2717107589738230e+00 , 1.3409748800000001e+00 , 7.4477099999999996e-01 , 6.4057299999999995e-01 , -1.8703700000000001e-01 --1.4012685330141334e+01 , -6.0385949861941590e+00 , 1.6958280800000001e+00 , -4.9040200000000000e-01 , -8.6097500000000005e-01 , -1.3500799999999999e-01 --1.3893009410319735e+01 , -5.9076153794964243e+00 , 2.0236820480000000e+00 , -7.1013400000000004e-01 , -7.0406599999999997e-01 , -5.0929399999999998e-04 --1.4490956721133163e+01 , -6.1411482815102350e+00 , 2.3127196799999998e+00 , -5.0935799999999998e-01 , -8.3685699999999996e-01 , -2.0056299999999999e-01 --1.4844861906396289e+01 , -6.2478852202920354e+00 , 2.6297855200000000e+00 , 4.1832900000000001e-01 , 5.4619300000000004e-01 , 7.2572300000000001e-01 --3.9145847198290589e+01 , -1.8233753885945198e+01 , 2.7942313599999999e+00 , 6.1662899999999998e-01 , 7.3009299999999997e-03 , -7.8722000000000003e-01 --3.3651104140959902e+01 , -1.5209542885281106e+01 , 4.2097296000000002e+00 , 7.1931400000000001e-01 , 6.9066899999999998e-01 , 7.4592599999999995e-02 --3.4220298447381964e+01 , -1.5335217461615024e+01 , 4.9243655999999998e+00 , 7.4002500000000004e-01 , 6.7030599999999996e-01 , -5.5257500000000001e-02 --3.4348402117989671e+01 , -1.5246113995113465e+01 , 5.6291112000000005e+00 , 6.5988100000000005e-01 , 7.1936400000000000e-01 , -2.1696299999999999e-01 --3.4502636227817838e+01 , -1.5168398445642897e+01 , 6.3402943999999994e+00 , -3.6618899999999999e-01 , 9.2850800000000000e-01 , -6.1463100000000000e-02 --3.3905703392594752e+01 , -1.4735648817717038e+01 , 6.9765872000000009e+00 , 9.7004699999999999e-01 , -2.3351800000000000e-01 , -6.6923300000000005e-02 --3.3476632146511946e+01 , -1.4386195724359791e+01 , 7.6114552000000000e+00 , 8.3740499999999995e-01 , -5.2169900000000002e-01 , -1.6304299999999999e-01 --3.3959953611973702e+01 , -1.4312549658337613e+01 , 9.0543720000000008e+00 , 7.4904199999999999e-01 , -2.8375499999999998e-01 , -5.9868100000000002e-01 --3.0780557904359206e+01 , -1.2716306655122093e+01 , 9.1652152000000005e+00 , -7.9118999999999995e-01 , -1.2562999999999999e-01 , 5.9852799999999995e-01 --3.0415635641074374e+01 , -1.2414217319016831e+01 , 9.7253487999999990e+00 , 8.0396299999999998e-01 , -2.9744100000000001e-01 , -5.1494799999999996e-01 --9.2858861618584942e+00 , -2.8380299445062258e+00 , 5.6779288000000001e+00 , -6.3544400000000001e-01 , 7.7111499999999999e-01 , 3.9903700000000000e-02 --9.1784550187273712e+00 , -2.7419188481357226e+00 , 5.8774839999999999e+00 , 7.0811199999999996e-01 , -7.0605099999999998e-01 , 8.3634599999999996e-03 --9.0302759000995358e+00 , -2.6280079681407127e+00 , 6.0634152000000006e+00 , 6.8354899999999996e-01 , -7.2967300000000002e-01 , -1.8377500000000001e-02 --9.3048896507674943e+00 , -2.6992632600272577e+00 , 6.3627272000000001e+00 , -4.9417200000000000e-01 , 2.1845899999999999e-01 , 8.4146900000000002e-01 --9.0392578450534540e+00 , -2.5350147316939431e+00 , 6.5125495999999998e+00 , -4.9509199999999998e-01 , 3.7727500000000003e-01 , 7.8265499999999999e-01 --8.1285273999675844e+00 , -2.0986739588029293e+00 , 6.4483296000000001e+00 , 4.3592999999999998e-01 , -1.3171700000000000e-01 , -8.9029000000000003e-01 --7.9615702923782656e+00 , -1.9836943651875014e+00 , 6.6012927999999995e+00 , -5.6879299999999999e-01 , 3.3027700000000000e-02 , 8.2181700000000002e-01 --7.7299106253793557e+00 , -1.8412521330257050e+00 , 6.7253232000000009e+00 , -8.9671900000000004e-01 , 2.7786300000000003e-01 , 3.4451199999999998e-01 --7.7132796542805480e+00 , -1.7903306292962342e+00 , 6.9236200000000006e+00 , -8.6205799999999999e-01 , 5.0056599999999996e-01 , -7.9308100000000006e-02 --7.9742452959460213e+00 , -1.8525903479416619e+00 , 7.2334776000000005e+00 , -8.8780800000000004e-01 , 3.9966699999999999e-01 , -2.2817299999999999e-01 --7.8418169751917599e+00 , -1.7532160318854126e+00 , 7.3913703999999996e+00 , -8.8780800000000004e-01 , 3.9966699999999999e-01 , -2.2817299999999999e-01 --5.1693603576095359e+00 , -5.6929404737116096e-01 , 6.7493888000000002e+00 , 5.3760500000000000e-01 , -6.8191600000000005e-02 , -8.4043500000000004e-01 --6.3597129226685123e+00 , -9.9423349222784951e-01 , 7.5115216000000009e+00 , -9.5107299999999995e-01 , 3.0610700000000002e-01 , 4.1935399999999998e-02 --7.9334910469063384e+00 , -1.5521407396789595e+00 , 8.5279760000000007e+00 , -8.2314799999999999e-01 , 5.6482200000000005e-01 , 5.8330100000000003e-02 --7.7576959026775629e+00 , -1.4365262434571453e+00 , 8.6597336000000009e+00 , 7.7396399999999999e-01 , -6.0219999999999996e-01 , -1.9579400000000000e-01 --7.6834575854577061e+00 , -1.3599411639345385e+00 , 8.8448640000000012e+00 , -8.9792300000000005e-02 , 5.6641900000000001e-01 , 8.1921100000000002e-01 --6.3853518766175998e+00 , -8.3409261024577530e-01 , 8.3061439999999997e+00 , -5.1332400000000000e-01 , 3.8389400000000001e-01 , -7.6754400000000000e-01 --5.9162985719275438e+00 , -6.2078674830070169e-01 , 8.2211655999999991e+00 , -1.4917300000000000e-01 , 4.9855200000000000e-01 , -8.5392800000000002e-01 --6.0890640631373607e+00 , -6.3984513162428858e-01 , 8.5271544000000006e+00 , 2.8881099999999998e-01 , -7.1837300000000004e-01 , 6.3287300000000002e-01 --5.4574948909566672e+00 , -3.7382640322095950e-01 , 8.3115832000000012e+00 , 3.3546399999999998e-01 , 9.3181400000000003e-01 , -1.3851700000000000e-01 --5.3349573776000687e+00 , -2.9046638705164929e-01 , 8.4194519999999997e+00 , -9.1097799999999995e-01 , -3.6000300000000002e-01 , -2.0128900000000000e-01 --6.2734718450369602e+00 , -5.6870026151741282e-01 , 9.2783568000000010e+00 , -6.1738700000000002e-01 , -6.6174500000000003e-01 , 4.2535499999999998e-01 --6.7943705472819698e+00 , -6.9585321153589463e-01 , 9.8800175999999986e+00 , 4.9783500000000003e-01 , 6.7751799999999995e-01 , 5.4141499999999998e-01 --5.7220388538769473e+00 , -2.9049448499490627e-01 , 9.3011847999999997e+00 , -5.0985499999999995e-01 , -8.0770600000000004e-01 , 2.9607200000000000e-01 --5.6182961835880354e+00 , -2.1089449796848614e-01 , 9.4338055999999995e+00 , 6.3043700000000003e-01 , 7.7540900000000001e-01 , 3.5920000000000001e-02 --6.2097767361911131e+00 , -3.5184468307552619e-01 , 1.0131125600000001e+01 , 6.2148999999999999e-01 , 1.8552500000000000e-01 , -7.6113799999999998e-01 --5.8146894267997205e+00 , -1.7762487472484478e-01 , 1.0036641600000001e+01 , -1.8733100000000000e-01 , -2.4962300000000001e-01 , 9.5004999999999995e-01 --5.9373399444695014e+00 , -1.6473474662691157e-01 , 1.0374849600000001e+01 , -1.7512500000000000e-01 , -1.4333699999999999e-01 , 9.7405600000000003e-01 --5.6438787790640434e+00 , -2.4700450540882546e-02 , 1.0352520799999999e+01 , 2.9958099999999999e-01 , -7.1172899999999997e-02 , -9.5141200000000004e-01 --4.3756298255861843e+00 , 3.9983406606864236e-01 , 9.4152416000000017e+00 , -4.9017899999999998e-01 , -2.9398500000000001e-02 , 8.7112599999999996e-01 --4.2255078491940923e+00 , 4.8777551263576546e-01 , 9.4779535999999993e+00 , 7.2341699999999998e-01 , 9.2160300000000001e-02 , -6.8423299999999998e-01 --5.9311326816272771e+00 , 5.4188169025957578e-02 , 1.1373176800000000e+01 , -8.2836600000000005e-01 , -7.8035599999999997e-02 , 5.5472600000000005e-01 --4.7097604518167966e+00 , 4.4687031149410017e-01 , 1.0394308000000001e+01 , 1.5054200000000001e-01 , 1.5028900000000001e-01 , 9.7711300000000001e-01 --4.4965691764163633e+00 , 5.5488877718684515e-01 , 1.0406746400000001e+01 , -1.6654700000000000e-01 , 6.5119300000000002e-01 , 7.4041199999999996e-01 --5.6995551779127460e+00 , 2.9466528866132813e-01 , 1.1952124000000000e+01 , 7.6022500000000004e-01 , -6.3087000000000004e-01 , 1.5512000000000001e-01 --5.7534564564676609e+00 , 3.4243331393530152e-01 , 1.2298932800000001e+01 , -9.8492599999999997e-01 , -5.1534500000000004e-03 , -1.7290100000000000e-01 --5.6644776462021529e+00 , 4.2880216540337068e-01 , 1.2493600000000001e+01 , -9.5190799999999998e-01 , -7.5179599999999999e-02 , 2.9701800000000000e-01 --5.7092739421655567e+00 , 4.8400219270969580e-01 , 1.2852919999999999e+01 , 5.5230199999999996e-01 , -4.1347800000000001e-01 , -7.2387699999999999e-01 --1.8809567798697158e+00 , 1.4225662836622670e+00 , 8.4359256000000009e+00 , -9.7552000000000000e-02 , -2.4085400000000000e-02 , 9.9493900000000002e-01 --1.7570588231216537e+00 , 1.4874366563404706e+00 , 8.4523159999999997e+00 , -2.1750900000000001e-01 , 1.8558999999999999e-02 , 9.7588200000000003e-01 --1.6265272091257637e+00 , 1.5529280319789938e+00 , 8.4573807999999993e+00 , -2.0965600000000001e-01 , -2.0551500000000000e-02 , 9.7755899999999996e-01 --1.5406039040578410e+00 , 1.6080419260131336e+00 , 8.5173784000000001e+00 , -5.5405199999999999e-01 , 6.8988400000000005e-02 , 8.2961900000000000e-01 --1.4711577840240011e+00 , 1.6611018459912028e+00 , 8.6005576000000001e+00 , -8.0953200000000003e-01 , 2.3104000000000000e-01 , 5.3970200000000002e-01 --1.4467414653456756e+00 , 1.7052353922933077e+00 , 8.7510352000000005e+00 , -6.9284599999999996e-01 , 7.0995500000000000e-01 , 1.2620600000000001e-01 --1.3550073676641068e+00 , 1.7624121934050412e+00 , 8.8066960000000005e+00 , -8.1710899999999997e-01 , -5.4125199999999996e-01 , 1.9844400000000001e-01 --1.4147201289619953e+00 , 1.7956094744965854e+00 , 9.0957536000000001e+00 , -8.8642699999999996e-01 , -2.4927700000000000e-01 , 3.9001100000000000e-01 --1.3344066166481903e+00 , 1.8530084237282742e+00 , 9.1764264000000004e+00 , 8.4308300000000003e-01 , 1.7532500000000001e-01 , -5.0840200000000002e-01 --1.3438264392790384e+00 , 1.8977503740540451e+00 , 9.4070256000000008e+00 , -9.5809500000000003e-01 , 1.3696500000000000e-01 , -2.5158500000000000e-01 --1.4868985218675932e+00 , 1.9294058205289293e+00 , 9.8814632000000007e+00 , -2.1398300000000001e-01 , 2.9976700000000001e-01 , 9.2970500000000000e-01 --1.3525724850566938e+00 , 1.9975891718975327e+00 , 9.8901576000000002e+00 , 3.1127700000000003e-01 , -2.8269499999999997e-01 , -9.0729800000000005e-01 --1.2295459466210938e+00 , 2.0639839266338527e+00 , 9.9139319999999991e+00 , -4.7123100000000001e-02 , 4.2627600000000002e-02 , 9.9797899999999995e-01 --1.0678455377428078e+00 , 2.1324455939717275e+00 , 9.8613391999999997e+00 , -4.4596500000000000e-01 , -6.9171800000000006e-02 , -8.9237400000000000e-01 --6.8554142843593802e-01 , 2.2132055171705565e+00 , 9.3582184000000002e+00 , 3.4641000000000000e-01 , 9.3781000000000003e-01 , 2.2616700000000000e-02 --3.0070229645029478e-01 , 2.2841818920292534e+00 , 8.8070704000000006e+00 , -7.3621499999999995e-01 , -3.1531100000000001e-01 , -5.9880400000000000e-01 --2.0409074956571249e-01 , 2.3367710451867492e+00 , 8.8304703999999994e+00 , -9.1637999999999997e-01 , -2.5671200000000000e-01 , 3.0715900000000002e-01 --3.0516192893862515e-01 , 2.3887352051558541e+00 , 9.2987096000000005e+00 , 8.0782799999999999e-01 , 2.5145000000000001e-02 , -5.8888099999999999e-01 --2.5309847087364723e-03 , 2.4418119739633459e+00 , 8.8519983999999994e+00 , 4.7727100000000000e-01 , -7.3583200000000004e-01 , 4.8037800000000003e-01 --5.9079397069993833e-01 , 2.5192476379860786e+00 , 1.0554883999999999e+01 , 3.2013100000000000e-01 , 4.3749600000000000e-01 , 8.4030499999999997e-01 --4.5087053228760166e-02 , 2.5594052650229329e+00 , 9.4950928000000001e+00 , 2.2529700000000000e-01 , 6.6835900000000004e-01 , 7.0889899999999995e-01 -9.7755854964409528e-02 , 2.6123758959507910e+00 , 9.4142952000000015e+00 , -8.5560800000000006e-02 , 7.3255700000000001e-01 , 6.7530699999999999e-01 -5.0161600263256112e-02 , 2.6849907191453437e+00 , 9.8594463999999995e+00 , -2.0441400000000001e-01 , -3.1778000000000001e-01 , 9.2586800000000002e-01 -3.0172395024580601e-01 , 2.7232298802101109e+00 , 9.4599095999999996e+00 , 3.5705500000000001e-01 , -3.1851099999999999e-01 , 8.7810200000000005e-01 -4.9198033242407080e-01 , 2.7619559310570292e+00 , 9.2026032000000004e+00 , -4.6956300000000001e-01 , 6.2853899999999996e-01 , 6.2004000000000004e-01 -6.0589381838837175e-01 , 2.8109076217990348e+00 , 9.1694688000000006e+00 , -4.0734399999999998e-01 , 4.8915900000000001e-01 , 7.7122900000000005e-01 -7.1796932160446114e-01 , 2.8584043595461726e+00 , 9.1339527999999994e+00 , 1.9985800000000001e-01 , 2.2588700000000000e-01 , 9.5343199999999995e-01 -8.5372000480220467e-01 , 2.8979346305112372e+00 , 9.0060327999999998e+00 , -5.0704300000000002e-01 , 1.6822100000000001e-01 , -8.4534500000000001e-01 -9.9458224043891175e-01 , 2.9307015943219783e+00 , 8.8350983999999997e+00 , 4.6596199999999999e-01 , 1.2969899999999999e-02 , 8.8471000000000000e-01 -1.0945724119086273e+00 , 2.9749102036466710e+00 , 8.8123120000000004e+00 , -1.1148800000000000e-01 , -1.5950800000000001e-01 , 9.8088100000000000e-01 -1.2999858197862282e+00 , 2.9663995004870993e+00 , 8.3027119999999996e+00 , -1.0304000000000001e-01 , 4.8132100000000000e-01 , 8.7046699999999999e-01 -1.3695689771332977e+00 , 3.0174328082598407e+00 , 8.3758447999999994e+00 , 9.7633800000000004e-01 , -2.0065800000000000e-01 , 8.0630300000000002e-02 -1.3449777688020403e+00 , 3.1319973527877281e+00 , 8.9655664000000002e+00 , 6.2280200000000001e-02 , 4.1667100000000001e-01 , 9.0692099999999998e-01 -1.4400983137677823e+00 , 3.1789647079184347e+00 , 8.9660136000000001e+00 , -4.2462499999999997e-01 , -5.5280200000000002e-01 , 7.1701000000000004e-01 -1.5578412276134952e+00 , 3.2044028837151268e+00 , 8.8117192000000006e+00 , 2.4408299999999999e-01 , 9.6843000000000001e-01 , 5.0673599999999999e-02 -1.6526912154707114e+00 , 3.2464765392665078e+00 , 8.7878095999999992e+00 , -4.5780399999999999e-02 , -4.5800400000000002e-01 , 8.8777099999999998e-01 --4.4575434417740745e-01 , 6.1899816864677848e-01 , 9.1167120000000001e-01 , -2.7288900000000001e-02 , 2.0260900000000001e-01 , 9.7887900000000005e-01 --5.6815912734891993e-01 , 5.6236153026547187e-01 , 9.1011119999999979e-01 , -3.9079400000000000e-02 , 1.7246500000000001e-01 , 9.8424000000000000e-01 --6.9990232932948615e-01 , 5.0159074680965099e-01 , 9.0713679999999997e-01 , -5.8328699999999997e-02 , 1.6280800000000001e-01 , 9.8493200000000003e-01 --8.4103746258388012e-01 , 4.3679275868194090e-01 , 9.0323679999999995e-01 , 9.2981400000000006e-02 , -1.6361100000000001e-01 , -9.8213300000000003e-01 --9.9850950726350485e-01 , 3.6212943744450921e-01 , 8.9432399999999990e-01 , -7.3523300000000000e-02 , 1.6626400000000000e-01 , 9.8333599999999999e-01 --1.1576431088741836e+00 , 2.8859581455764105e-01 , 8.9064239999999995e-01 , -6.9449899999999995e-02 , 1.6651700000000000e-01 , 9.8358999999999996e-01 --1.3432413528733220e+00 , 2.0066395270201953e-01 , 8.7838079999999996e-01 , -8.8497000000000006e-02 , 1.8295200000000000e-01 , 9.7913099999999997e-01 --1.5385512936288395e+00 , 1.0923537299787967e-01 , 8.6782479999999995e-01 , -9.4918400000000000e-02 , 1.7252000000000001e-01 , 9.8042200000000002e-01 --1.7606011523958562e+00 , 3.9289589461812824e-03 , 8.5110159999999979e-01 , -8.9316000000000006e-02 , 1.5744100000000000e-01 , 9.8348100000000005e-01 --1.9846350118426592e+00 , -1.0080337174692655e-01 , 8.4215759999999995e-01 , -7.6712500000000003e-02 , 1.6061200000000000e-01 , 9.8403200000000002e-01 --2.2196987290120020e+00 , -2.0959674741645662e-01 , 8.3702000000000010e-01 , -6.7513400000000001e-02 , 1.7332100000000000e-01 , 9.8254900000000001e-01 --2.4818465788789812e+00 , -3.3166920719358917e-01 , 8.2865839999999991e-01 , -8.9370099999999994e-02 , 1.7474200000000001e-01 , 9.8055000000000003e-01 --2.7893668315226785e+00 , -4.7600189437717866e-01 , 8.1088479999999996e-01 , -5.5408800000000001e-02 , 2.0913300000000001e-01 , 9.7631599999999996e-01 --3.0398465899193425e+00 , -5.8690155000851307e-01 , 8.2885599999999982e-01 , 2.4471600000000000e-02 , 2.7763199999999999e-01 , 9.6037600000000001e-01 --3.3095932605100344e+00 , -7.0614241912156972e-01 , 8.4883440000000010e-01 , 3.1217000000000002e-02 , 2.5383299999999998e-01 , 9.6674400000000005e-01 --3.6239897576187019e+00 , -8.4707258122252016e-01 , 8.6226080000000005e-01 , -5.9355499999999999e-02 , 2.9691600000000001e-01 , 9.5305700000000004e-01 --4.4769036714866992e+00 , -1.2715023555855978e+00 , 7.0281839999999995e-01 , -3.9695599999999998e-02 , 5.1057200000000003e-01 , 8.5891799999999996e-01 --5.0742795723877352e+00 , -1.5537112143697906e+00 , 6.6086479999999992e-01 , -3.8124700000000000e-01 , 3.9655899999999999e-01 , 8.3509999999999995e-01 --5.0437418850916202e+00 , -1.5038120513895890e+00 , 8.3075919999999992e-01 , -3.8124700000000000e-01 , 3.9655899999999999e-01 , 8.3509999999999995e-01 --4.9381686459776226e+00 , -1.4163863940904942e+00 , 1.0184209599999998e+00 , -1.1852799999999999e-01 , 5.1134199999999996e-01 , 8.5116400000000003e-01 --3.6291162631383633e+00 , -7.1200836867620287e-01 , 1.5104418399999999e+00 , 9.8128000000000004e-01 , 7.7195700000000006e-02 , 1.7643700000000001e-01 --3.6446050400294316e+00 , -6.9323530215581997e-01 , 1.6319492000000000e+00 , 9.9708100000000000e-01 , 6.9108500000000003e-02 , -3.2444899999999999e-02 --3.6394265171879114e+00 , -6.6502006219901855e-01 , 1.7572588000000000e+00 , 9.8622699999999996e-01 , -6.3178200000000004e-02 , -1.5285799999999999e-01 --6.1887247598521853e+00 , -1.9124979412632559e+00 , 1.3775537600000001e+00 , -8.4138900000000005e-01 , 4.5072099999999998e-01 , 2.9818800000000001e-01 --1.1272167943470311e+01 , -4.3953091200547192e+00 , 6.5002800000000005e-01 , 1.0925400000000000e-01 , 3.4789799999999999e-01 , 9.3114500000000000e-01 --1.3298781390860777e+01 , -5.3337926457344684e+00 , 6.0314479999999993e-01 , 6.1436299999999998e-03 , 5.2573800000000004e-01 , 8.5062499999999996e-01 --1.1801244873065903e+01 , -4.5382873245053972e+00 , 1.1186613599999999e+00 , 7.1420099999999997e-01 , 2.2065899999999999e-01 , -6.6424899999999998e-01 --1.1787955558340657e+01 , -4.4729748439959787e+00 , 1.3982539200000002e+00 , 7.1420099999999997e-01 , 2.2065899999999999e-01 , -6.6424799999999995e-01 --1.1591561071403694e+01 , -4.3210423481245321e+00 , 1.6935130400000000e+00 , -9.4339399999999995e-01 , 2.9203200000000001e-01 , -1.5724500000000000e-01 --1.1755327430597722e+01 , -4.3407840201958710e+00 , 1.9506735280000000e+00 , 7.1420099999999997e-01 , 2.2065899999999999e-01 , -6.6424899999999998e-01 --1.4874323012228459e+01 , -5.7518154707340665e+00 , 2.0342499040000002e+00 , 5.7397699999999996e-01 , 8.0831900000000001e-01 , 1.3103500000000001e-01 --1.5122552981517842e+01 , -5.7977516172162433e+00 , 2.3539889600000001e+00 , 5.7397699999999996e-01 , 8.0831900000000001e-01 , 1.3103500000000001e-01 --3.9465983380159422e+01 , -1.6993165964190982e+01 , 2.1426869599999998e+00 , -7.6201200000000002e-01 , 8.2869099999999998e-03 , 6.4750900000000000e-01 --3.9528296232406973e+01 , -1.6854328511286745e+01 , 2.9343921599999998e+00 , -7.5671400000000000e-01 , 8.1045300000000001e-02 , 6.4870399999999995e-01 --3.8073550725948017e+01 , -1.6025189211347314e+01 , 3.7027087999999999e+00 , -7.6384099999999999e-01 , -1.9994300000000001e-01 , 6.1365300000000000e-01 --3.7354598900827590e+01 , -1.5381409194524039e+01 , 5.1857384000000000e+00 , 2.4264600000000000e-01 , 9.2970500000000000e-01 , 2.7707900000000002e-01 --3.7734881835701898e+01 , -1.5392046998546729e+01 , 5.9583232000000006e+00 , 2.4264600000000000e-01 , 9.2970500000000000e-01 , 2.7707900000000002e-01 --3.8075066950774051e+01 , -1.5381154217297428e+01 , 6.7408192000000007e+00 , 2.4264600000000000e-01 , 9.2970500000000000e-01 , 2.7707900000000002e-01 --3.2869776012308947e+01 , -1.2957527372914587e+01 , 6.9317736000000005e+00 , 6.3977799999999996e-01 , -3.5633500000000001e-01 , -6.8096299999999998e-01 --3.2191978509795810e+01 , -1.2524801693019453e+01 , 7.5061863999999998e+00 , -8.1921200000000005e-01 , -6.3958600000000004e-02 , 5.6991199999999997e-01 --3.2451060785703561e+01 , -1.2497309379503472e+01 , 8.1933559999999996e+00 , -6.1835799999999996e-01 , -7.3952399999999996e-01 , 2.6596500000000001e-01 --3.2613522690915325e+01 , -1.2428212234939016e+01 , 8.8758456000000017e+00 , -8.4900600000000004e-01 , -2.2672999999999999e-01 , 4.7726499999999999e-01 --3.1442487036462246e+01 , -1.1796634662759407e+01 , 9.3197071999999999e+00 , -7.0246500000000001e-01 , -1.9961000000000001e-01 , 6.8315300000000001e-01 --8.7275325528392305e+00 , -2.2338084036031249e+00 , 5.3492367999999999e+00 , -9.2850299999999997e-01 , 2.9077999999999998e-01 , -2.3093100000000000e-01 --8.6872346030196752e+00 , -2.1724334234915101e+00 , 5.5519119999999997e+00 , 9.9747399999999997e-01 , 2.5540600000000000e-02 , 6.6285499999999997e-02 --8.5868962699512696e+00 , -2.0868754100058444e+00 , 5.7396631999999999e+00 , 7.7961100000000005e-01 , -6.1302000000000001e-01 , -1.2811300000000000e-01 --8.8210733614681480e+00 , -2.1367012148677480e+00 , 6.0116128000000000e+00 , -7.8515400000000002e-01 , 6.1571900000000002e-01 , 6.6512399999999999e-02 --8.7886816262514014e+00 , -2.0782022866774952e+00 , 6.2192904000000002e+00 , 7.3248800000000003e-01 , -6.7375499999999999e-01 , -9.7553600000000004e-02 --8.3804142111899491e+00 , -1.8705871932377418e+00 , 6.3144400000000003e+00 , -5.5333100000000002e-01 , 5.0248499999999996e-01 , 6.6432899999999995e-01 --8.1846049005653647e+00 , -1.7492708384171118e+00 , 6.4629832000000000e+00 , 5.8982000000000001e-01 , -2.4227299999999999e-01 , -7.7033499999999999e-01 --8.3017025729878569e+00 , -1.7495350206917557e+00 , 6.7107112000000004e+00 , 5.5232899999999996e-01 , -2.2602600000000000e-01 , -8.0240000000000000e-01 --7.7685713392372016e+00 , -1.5014449103537877e+00 , 6.7330088000000003e+00 , -6.6190700000000002e-01 , 9.1826300000000000e-02 , 7.4394000000000005e-01 --7.7961279657503706e+00 , -1.4687869826422237e+00 , 6.9471864000000005e+00 , -9.3145500000000003e-01 , 2.3104300000000000e-01 , 2.8108699999999998e-01 --7.6653951730911558e+00 , -1.3754441440035663e+00 , 7.1010960000000001e+00 , 9.7797199999999995e-01 , -2.0248700000000000e-01 , 5.0699899999999999e-02 --7.6955192587200330e+00 , -1.3429458742049434e+00 , 7.3191736000000001e+00 , 9.7797199999999995e-01 , -2.0248700000000000e-01 , 5.0699899999999999e-02 --7.9111688695930606e+00 , -1.3777465343330406e+00 , 7.6221776000000006e+00 , -8.7743400000000005e-01 , 4.5387000000000000e-01 , -1.5527900000000000e-01 --5.4077227491571236e+00 , -4.3006866588219728e-01 , 6.6885800000000009e+00 , 3.8827099999999998e-01 , 2.2604199999999999e-01 , -8.9339299999999999e-01 --5.1639810013877243e+00 , -3.0775859774355840e-01 , 6.7363056000000006e+00 , -8.7985999999999998e-01 , -1.0806800000000000e-01 , 4.6278300000000000e-01 --5.0260243983668778e+00 , -2.2487240629741923e-01 , 6.8293024000000004e+00 , -7.3654799999999998e-01 , -2.7660699999999999e-01 , 6.1724000000000001e-01 --7.4589210098310570e+00 , -1.0355226617557358e+00 , 8.2630984000000005e+00 , 8.2648900000000003e-01 , -5.2214400000000005e-01 , -2.1043300000000001e-01 --9.1632823132818473e+00 , -1.5734962357050910e+00 , 9.4086376000000005e+00 , -4.3923899999999999e-01 , 7.3712500000000003e-01 , -5.1353300000000002e-01 --7.4873912710281960e+00 , -9.5255287776461595e-01 , 8.7162784000000002e+00 , -4.0193499999999999e-01 , 6.6812000000000005e-01 , 6.2614999999999998e-01 --6.0318375573510785e+00 , -4.1987049267356280e-01 , 8.0817119999999996e+00 , -2.9375600000000002e-01 , -8.7403800000000004e-02 , 9.5187600000000006e-01 --6.6710249475180330e+00 , -5.8868266808876291e-01 , 8.6674503999999999e+00 , -3.9234400000000003e-01 , -4.6110400000000001e-01 , 7.9589600000000005e-01 --6.2194301447665605e+00 , -3.9792636491499334e-01 , 8.5933087999999991e+00 , 1.9132700000000000e-01 , -8.1935199999999997e-01 , 5.4042199999999996e-01 --6.3009684116074940e+00 , -3.8039305903451659e-01 , 8.8526640000000008e+00 , 3.2584299999999999e-01 , -8.6548499999999995e-01 , 3.8047599999999998e-01 --6.0694810876440073e+00 , -2.6285599130479165e-01 , 8.9057040000000001e+00 , 3.3755299999999999e-01 , -8.9297599999999999e-01 , 2.9774499999999998e-01 --5.8624939334159736e+00 , -1.5490773370101563e-01 , 8.9691752000000005e+00 , -2.2053500000000001e-01 , -8.8491699999999995e-01 , 4.1022599999999998e-01 --6.0389436824996228e+00 , -1.6311986311280835e-01 , 9.3071127999999987e+00 , -3.5465099999999999e-01 , -1.6548000000000000e-02 , 9.3485200000000002e-01 --6.0220477025043309e+00 , -1.1198758886550797e-01 , 9.5118159999999996e+00 , 6.4865000000000006e-02 , -9.9780899999999995e-01 , 1.3009000000000000e-02 --5.5301963853506821e+00 , 7.8053635109130326e-02 , 9.3478496000000000e+00 , 3.8544200000000001e-01 , 9.1211000000000000e-03 , 9.2268700000000003e-01 --4.8157210627036378e+00 , 3.2727688151131518e-01 , 8.9822895999999997e+00 , 7.0511100000000004e-01 , 4.4216200000000000e-01 , -5.5435699999999999e-01 --5.9208272100099482e+00 , 6.0409318984128602e-02 , 1.0109764000000000e+01 , -4.4381999999999999e-01 , 1.0809299999999999e-01 , 8.8957299999999995e-01 --5.7032579075026186e+00 , 1.7070111973992286e-01 , 1.0155492800000001e+01 , -2.8750599999999998e-01 , 1.1585100000000000e-01 , 9.5074700000000001e-01 --5.6589912735027097e+00 , 2.3176213733438900e-01 , 1.0352073600000001e+01 , -3.6975300000000000e-01 , 3.6415100000000001e-03 , 9.2912300000000003e-01 --4.3087202779318030e+00 , 6.3674324785884862e-01 , 9.3405280000000008e+00 , -5.4378500000000003e-02 , 2.2344100000000000e-01 , 9.7319900000000004e-01 --4.9073624882443987e+00 , 5.7598511503929917e-01 , 1.0350014400000001e+01 , 9.5590400000000006e-02 , 2.9044100000000000e-01 , 9.5210600000000001e-01 --4.4547675799152087e+00 , 7.3526715881928761e-01 , 1.0125135200000001e+01 , 2.6384400000000002e-01 , 2.1874299999999999e-01 , 9.3943500000000002e-01 --4.0523036380027069e+00 , 8.7843642219521767e-01 , 9.9308112000000008e+00 , 3.0890899999999999e-01 , 3.3542499999999997e-01 , -8.8997999999999999e-01 --4.1931412167691091e+00 , 8.9336275149409494e-01 , 1.0306864800000001e+01 , -1.7982000000000001e-01 , -4.1673900000000003e-01 , 8.9106300000000005e-01 --3.9546089776988920e+00 , 9.9645729893972268e-01 , 1.0273928000000000e+01 , 4.8671300000000001e-01 , 4.7128300000000001e-01 , -7.3552899999999999e-01 --5.6426776138580967e+00 , 6.8769726862788461e-01 , 1.2465728000000000e+01 , -4.9363299999999999e-01 , 5.4572100000000001e-01 , 6.7713800000000002e-01 --5.5731187324732794e+00 , 7.6700324454104862e-01 , 1.2689744000000001e+01 , -4.9363299999999999e-01 , 5.4571999999999998e-01 , 6.7713800000000002e-01 --1.8585205755926149e+00 , 1.5608534865458115e+00 , 8.4103311999999999e+00 , 2.0463400000000000e-02 , -3.0160200000000002e-02 , 9.9933600000000000e-01 --1.7585137815689995e+00 , 1.6171615416222194e+00 , 8.4581607999999999e+00 , -1.2761200000000000e-01 , 1.9719700000000000e-02 , 9.9162799999999995e-01 --1.5893841915315798e+00 , 1.6847277906583171e+00 , 8.4132639999999999e+00 , -3.9670499999999997e-01 , 1.3048000000000001e-01 , 9.0862500000000002e-01 --1.5263496672383750e+00 , 1.7335061775956788e+00 , 8.5054392000000014e+00 , -5.6042499999999995e-01 , 1.0221000000000000e-01 , 8.2187399999999999e-01 --1.4558876279888762e+00 , 1.7832819043545760e+00 , 8.5883479999999999e+00 , 8.3589000000000002e-01 , -1.7032200000000000e-01 , -5.2180400000000005e-01 --5.3506862955077814e+00 , 1.2428280853658842e+00 , 1.4455872000000001e+01 , -9.5521000000000000e-01 , 9.1566300000000007e-03 , -2.9578599999999999e-01 --1.4637192891018138e+00 , 1.8632195033901895e+00 , 8.9834335999999997e+00 , -8.4002699999999997e-01 , -5.0380999999999998e-01 , 2.0132200000000000e-01 --1.5351989243578164e+00 , 1.8983472278495290e+00 , 9.3006440000000001e+00 , -8.7295699999999998e-01 , -4.1623900000000003e-01 , 2.5434400000000001e-01 --1.4773335768263354e+00 , 1.9511108166091893e+00 , 9.4273056000000004e+00 , -5.8765199999999995e-01 , -6.9861700000000004e-01 , -4.0816700000000000e-01 --1.2829820727109071e+00 , 2.0198370080583343e+00 , 9.3302943999999997e+00 , 7.4870700000000001e-01 , -8.3807499999999993e-03 , 6.6284799999999999e-01 --1.4619567282645893e+00 , 2.0518252276963600e+00 , 9.8672360000000019e+00 , -2.2535500000000000e-01 , 3.0811699999999997e-01 , 9.2427199999999998e-01 --1.3308259353101919e+00 , 2.1154600748515886e+00 , 9.8843023999999993e+00 , -4.6078300000000000e-01 , 1.8133199999999999e-01 , 8.6879099999999998e-01 --1.2354777199567830e+00 , 2.1759565834330390e+00 , 9.9624792000000006e+00 , 2.9234700000000002e-01 , 1.6116800000000001e-02 , -9.5617700000000005e-01 --7.7545550316845668e-01 , 2.2531078991393132e+00 , 9.3368152000000002e+00 , -4.2609399999999997e-01 , -9.0264000000000000e-01 , -6.0703600000000003e-02 --6.3191965987074772e-01 , 2.3105124175721148e+00 , 9.2939879999999988e+00 , 3.8043700000000003e-01 , 2.8581000000000001e-01 , 8.7953400000000004e-01 --2.6205696510431187e-01 , 2.3683146682927618e+00 , 8.7691312000000003e+00 , -4.4812999999999997e-01 , 1.2904399999999999e-01 , 8.8460600000000000e-01 --3.4675741090434764e-01 , 2.4193506083459750e+00 , 9.1888128000000009e+00 , 8.0357000000000001e-01 , 4.6375300000000003e-01 , 3.7310700000000002e-01 --1.6322003509644745e-01 , 2.4700215002531594e+00 , 9.0315128000000016e+00 , 4.3760700000000002e-01 , -5.7131100000000004e-03 , 8.9914799999999995e-01 -1.8840320721645432e-02 , 2.5168285744783985e+00 , 8.8599752000000009e+00 , 7.3020600000000002e-01 , 3.3209600000000000e-01 , 5.9708600000000001e-01 --9.1543835077299462e-02 , 2.5800281723806946e+00 , 9.3978008000000006e+00 , 2.6306600000000002e-01 , 6.4620599999999995e-01 , 7.1638900000000005e-01 -2.9305428365050901e-02 , 2.6311466610914516e+00 , 9.3769072000000016e+00 , -1.5196499999999999e-01 , 5.8846699999999996e-01 , 7.9411200000000004e-01 -5.3641937839793652e-02 , 2.6933152927220108e+00 , 9.6168663999999993e+00 , -5.0707599999999997e-01 , -7.7414600000000000e-01 , 3.7890900000000000e-01 -8.8574785814033774e-02 , 2.7573910269115514e+00 , 9.8475280000000005e+00 , -2.0441400000000001e-01 , -3.1778000000000001e-01 , 9.2586800000000002e-01 -2.0217225406694572e-01 , 2.8125606798925937e+00 , 9.8609648000000014e+00 , 3.4068599999999999e-01 , -5.5995000000000003e-02 , 9.3850800000000001e-01 -5.5887855226260497e-01 , 2.8148644025212013e+00 , 9.1000383999999990e+00 , -5.0016499999999997e-01 , 5.4438699999999995e-01 , 6.7340800000000001e-01 -6.6294245560116005e-01 , 2.8615754189676865e+00 , 9.0958159999999992e+00 , -1.4835400000000001e-01 , 5.0574500000000000e-01 , 8.4983100000000000e-01 -7.4955132064541496e-01 , 2.9122080253448632e+00 , 9.1495528000000004e+00 , 5.3464599999999995e-01 , -1.0253000000000000e-01 , 8.3883399999999997e-01 -8.9639075829608150e-01 , 2.9441492153825175e+00 , 8.9809896000000009e+00 , -3.2707100000000000e-01 , 1.3588000000000000e-01 , -9.3518000000000001e-01 -1.0372439614194551e+00 , 2.9725530118533436e+00 , 8.8094624000000010e+00 , -4.1139199999999998e-01 , -1.5117400000000000e-01 , -8.9883400000000002e-01 -1.2260523959872505e+00 , 2.9728371204540678e+00 , 8.4032072000000007e+00 , -6.9955999999999996e-01 , -7.1447799999999995e-01 , -1.1727300000000000e-02 -1.3280025173427998e+00 , 3.0049532675565569e+00 , 8.3366471999999998e+00 , -6.7603899999999995e-01 , 4.1907699999999998e-01 , 6.0609000000000002e-01 -1.2764213024567461e+00 , 3.1303990253619078e+00 , 9.0378879999999988e+00 , 9.9462799999999996e-01 , 7.2729199999999994e-02 , 7.3659699999999995e-02 -1.3963033088451764e+00 , 3.1595391660720065e+00 , 8.9182464000000010e+00 , 1.4172499999999999e-01 , -1.5711800000000001e-01 , 9.7735799999999995e-01 -1.4565573100896669e+00 , 3.2328756349711738e+00 , 9.1317063999999988e+00 , 7.2074800000000006e-01 , -4.1396899999999998e-01 , -5.5601400000000001e-01 -1.6209354576558208e+00 , 3.2127146542047216e+00 , 8.6820000000000004e+00 , -5.4539599999999999e-01 , -8.0431100000000000e-01 , 2.3585300000000001e-01 -1.6871403670990062e+00 , 3.2831826067049978e+00 , 8.8719456000000001e+00 , 6.7754199999999998e-01 , 7.0386199999999999e-01 , -2.1334100000000000e-01 --5.3720774001573623e-01 , 6.9046977744722682e-01 , 8.9905600000000008e-01 , -2.1748000000000000e-02 , 1.6547600000000001e-01 , 9.8597400000000002e-01 --6.6955419694141716e-01 , 6.3335547185196983e-01 , 8.9301359999999996e-01 , -4.9551499999999998e-02 , 1.7334700000000000e-01 , 9.8361299999999996e-01 --8.1025905828262701e-01 , 5.7219319778044242e-01 , 8.8617039999999991e-01 , -7.5590500000000005e-02 , 1.6043900000000000e-01 , 9.8414699999999999e-01 --9.6143317926385041e-01 , 5.0708351758970727e-01 , 8.7858880000000017e-01 , -7.6880699999999996e-02 , 1.5091399999999999e-01 , 9.8555300000000001e-01 --1.1142721552906218e+00 , 4.4202049174191615e-01 , 8.7614480000000006e-01 , -7.8007900000000005e-02 , 1.6221800000000000e-01 , 9.8366699999999996e-01 --1.3003000470090269e+00 , 3.5961078756159970e-01 , 8.5958800000000002e-01 , -9.4452599999999998e-02 , 1.6255900000000001e-01 , 9.8216800000000004e-01 --1.4891869265289177e+00 , 2.7753731238263701e-01 , 8.4935439999999995e-01 , -8.2770700000000003e-02 , 1.7460000000000001e-01 , 9.8115399999999997e-01 --1.6888148288380944e+00 , 1.9201950812856472e-01 , 8.4081600000000001e-01 , -8.6995600000000006e-02 , 1.6822999999999999e-01 , 9.8190200000000005e-01 --1.9061881080501304e+00 , 9.8402068264549669e-02 , 8.3046799999999998e-01 , -8.0697000000000005e-02 , 1.6616200000000000e-01 , 9.8279099999999997e-01 --2.1504893215036622e+00 , -8.7938722608837949e-03 , 8.1547119999999995e-01 , -8.2152299999999998e-02 , 1.6244800000000001e-01 , 9.8329100000000003e-01 --2.4159134894901380e+00 , -1.2355060856184075e-01 , 8.0060960000000003e-01 , -7.5189000000000006e-02 , 1.7360500000000001e-01 , 9.8194099999999995e-01 --2.6915117433751252e+00 , -2.4203574344257373e-01 , 7.9141600000000012e-01 , -9.7820199999999996e-02 , 1.3704200000000000e-01 , 9.8572300000000002e-01 --3.0477418896620048e+00 , -3.9896957656095511e-01 , 7.5864559999999992e-01 , -4.5731700000000000e-02 , 2.2218900000000000e-01 , 9.7393099999999999e-01 --3.3198804565191846e+00 , -5.1059871424874759e-01 , 7.7367359999999996e-01 , -9.3380200000000007e-03 , 2.9448400000000002e-01 , 9.5561099999999999e-01 --3.5234332415798955e+00 , -5.8607245987163425e-01 , 8.2469599999999987e-01 , 7.1166399999999996e-03 , 2.9443000000000003e-01 , 9.5564700000000002e-01 --3.9669146302006837e+00 , -7.7958150811924920e-01 , 7.9731279999999982e-01 , -1.1652700000000001e-01 , 2.7630800000000000e-01 , 9.5397900000000002e-01 --4.7810999318154144e+00 , -1.1516983186101082e+00 , 6.6338159999999990e-01 , 5.6248699999999999e-02 , 3.2657599999999998e-01 , 9.4349600000000000e-01 --5.4605147532907061e+00 , -1.4497626486459212e+00 , 6.0423680000000002e-01 , 2.9311700000000002e-01 , 2.4590200000000001e-01 , 9.2391199999999996e-01 --6.1715431411133164e+00 , -1.7589681055369311e+00 , 5.6214800000000009e-01 , -2.4771199999999999e-01 , 9.2196599999999995e-01 , 2.9768800000000001e-01 --6.1961653162756658e+00 , -1.7339286546540826e+00 , 7.3388319999999996e-01 , 5.8148500000000003e-01 , -7.1044700000000005e-01 , -3.9640900000000001e-01 --6.0350596372753440e+00 , -1.6206021113911517e+00 , 9.5128479999999982e-01 , -8.2873799999999997e-01 , 5.3824899999999998e-01 , 1.5323700000000001e-01 --6.0528483055064690e+00 , -1.5935195255884076e+00 , 1.1188048799999999e+00 , -8.1591599999999997e-01 , 5.7812699999999995e-01 , -7.0676599999999999e-03 --9.5684502655424026e+00 , -3.1967182513352475e+00 , 5.4868000000000006e-01 , -8.0198300000000000e-02 , 2.7043600000000001e-01 , 9.5939200000000002e-01 --1.0964443349003318e+01 , -3.7922094402820594e+00 , 5.2057920000000002e-01 , -3.4343800000000001e-02 , 5.1655899999999999e-01 , 8.5556299999999996e-01 --1.2517686053367216e+01 , -4.4490130730068556e+00 , 5.1824959999999987e-01 , -1.8384500000000001e-01 , 3.5806600000000000e-01 , 9.1541799999999995e-01 --1.4923150055070757e+01 , -5.4805820973245307e+00 , 4.4497119999999990e-01 , 4.6955700000000000e-01 , 7.8205999999999998e-01 , 4.0975499999999998e-01 --1.7097037997317592e+01 , -6.3892934878010035e+00 , 4.9334159999999994e-01 , -1.7869399999999999e-01 , 8.4467899999999996e-01 , 5.0456599999999996e-01 --1.7305648170346618e+01 , -6.4040121240639500e+00 , 8.4487199999999985e-01 , -1.7869399999999999e-01 , 8.4467899999999996e-01 , 5.0456599999999996e-01 --3.3953872675643268e+01 , -1.3396614235329253e+01 , 1.0321468800000000e+00 , -9.6891000000000005e-01 , -2.4519800000000000e-01 , -3.3031199999999997e-02 --4.3026347789801129e+01 , -1.7158132731046958e+01 , 1.3757358399999999e+00 , -3.4905500000000000e-01 , 3.1159999999999999e-01 , 8.8377899999999998e-01 --3.9867951989125636e+01 , -1.5634707676195241e+01 , 2.2854009600000000e+00 , -8.5703499999999999e-01 , 2.5277500000000001e-02 , 5.1463800000000004e-01 --3.9933129800024496e+01 , -1.5498488391766521e+01 , 3.0741016000000001e+00 , -8.7022400000000000e-01 , 3.3946299999999999e-02 , 4.9148599999999998e-01 --3.8834087656806176e+01 , -1.4875052820221370e+01 , 3.8415903999999998e+00 , -7.8723100000000001e-01 , -1.0228100000000000e-01 , 6.0811700000000002e-01 --3.8632669073721424e+01 , -1.4633262210818991e+01 , 4.5998232000000003e+00 , -8.2520800000000005e-01 , -3.4165400000000001e-01 , 4.4978299999999999e-01 --3.8129373680253579e+01 , -1.4268349288474216e+01 , 5.3326175999999998e+00 , 8.2520800000000005e-01 , 3.4165400000000001e-01 , -4.4978299999999999e-01 --3.1914994682792013e+01 , -1.1318810775386753e+01 , 6.8946455999999996e+00 , -8.9678999999999998e-01 , 2.1595100000000000e-01 , 3.8617800000000002e-01 --3.3181304380026198e+01 , -1.1688209455348122e+01 , 7.6949360000000002e+00 , -9.4558699999999996e-01 , 2.9492200000000002e-01 , 1.3743000000000000e-01 --3.1873402146786361e+01 , -1.1038724536859009e+01 , 8.1620311999999995e+00 , -8.6936500000000005e-01 , 2.7974700000000002e-01 , 4.0736600000000001e-01 --3.3176456805143616e+01 , -1.1274491577782072e+01 , 9.6809304000000012e+00 , 9.9441400000000002e-01 , 8.4306400000000004e-02 , 6.3507800000000003e-02 --8.7128282299001132e+00 , -1.8378298989050759e+00 , 5.3572655999999998e+00 , -8.1134300000000004e-01 , -8.2745299999999994e-02 , 5.7868399999999998e-01 --8.8132388351488586e+00 , -1.8314218727643028e+00 , 5.5890192000000001e+00 , 9.9912800000000002e-01 , -2.7418399999999999e-02 , -3.1490600000000001e-02 --8.7380626189295132e+00 , -1.7594112459725437e+00 , 5.7832287999999998e+00 , -9.0317800000000004e-01 , 1.4122799999999999e-01 , 4.0536899999999998e-01 --8.3848700166590842e+00 , -1.5858175924581266e+00 , 5.9034008000000000e+00 , 7.3654799999999998e-01 , -5.6663999999999999e-02 , -6.7400800000000005e-01 --8.4746926298298124e+00 , -1.5756290993731956e+00 , 6.1350816000000004e+00 , -5.6215000000000004e-01 , 4.8344300000000001e-01 , 6.7102200000000001e-01 --8.1084919422401303e+00 , -1.4002474983408049e+00 , 6.2351295999999996e+00 , 6.3107400000000002e-01 , -6.1833400000000005e-01 , -4.6840999999999999e-01 --8.1732143902079883e+00 , -1.3809173477131433e+00 , 6.4596552000000003e+00 , -6.7698800000000003e-01 , 4.6706199999999998e-01 , 5.6880699999999995e-01 --7.9622130952296057e+00 , -1.2638752113279681e+00 , 6.5953647999999996e+00 , -6.9445999999999997e-01 , 4.8628600000000000e-01 , 5.3033100000000000e-01 --6.0090092455637212e+00 , -5.4044303054574616e-01 , 6.1020304000000003e+00 , 1.6240499999999999e-01 , -5.7848999999999995e-01 , -7.9935900000000004e-01 --5.9414468113652728e+00 , -4.8280194282135502e-01 , 6.2444376000000004e+00 , 1.8143799999999999e-01 , 9.5085399999999998e-01 , 2.5091300000000000e-01 --5.4303194954127507e+00 , -2.7404702102612921e-01 , 6.2090880000000004e+00 , 3.9266899999999999e-01 , -8.2183799999999996e-01 , -4.1278700000000002e-01 --5.8746929446778893e+00 , -3.9044361934689809e-01 , 6.5537232000000003e+00 , 5.1082899999999998e-01 , -8.2313599999999998e-01 , -2.4799399999999999e-01 --5.7813003264134109e+00 , -3.2375483467701649e-01 , 6.6832967999999999e+00 , 6.3836899999999996e-01 , -7.0630300000000001e-01 , -3.0597500000000000e-01 --5.4698273144366469e+00 , -1.8724805251040966e-01 , 6.7105240000000004e+00 , -1.7877100000000001e-01 , 2.2218599999999999e-01 , 9.5847499999999997e-01 --5.2936189212491831e+00 , -9.5606111456915777e-02 , 6.7919039999999997e+00 , 8.9408100000000001e-01 , 3.1463600000000003e-01 , -3.1878499999999999e-01 --7.7015539312232431e+00 , -8.2895420563707578e-01 , 8.1614696000000002e+00 , 8.2648900000000003e-01 , -5.2214400000000005e-01 , -2.1043200000000001e-01 --7.3733334959137320e+00 , -6.7973881808827885e-01 , 8.2079368000000006e+00 , -4.1616899999999998e-02 , 5.8648599999999995e-01 , 8.0889000000000000e-01 --6.3663882190301457e+00 , -3.2401512320049797e-01 , 7.8747312000000003e+00 , -9.3549599999999999e-01 , -8.9644399999999999e-02 , 3.4177700000000000e-01 --5.0292451373092319e+00 , 1.2447461327324372e-01 , 7.3135056000000001e+00 , 3.8260299999999997e-02 , -4.8759900000000000e-01 , 8.7222900000000003e-01 --4.2661137936990201e+00 , 3.8865869953612431e-01 , 7.0325807999999999e+00 , -2.6558900000000002e-01 , 5.5879199999999996e-01 , 7.8563000000000005e-01 --4.5966654326837357e+00 , 3.2266065983888459e-01 , 7.3881360000000003e+00 , -1.4696400000000000e-02 , 4.7157900000000003e-01 , 8.8170099999999996e-01 --4.1677360894340252e+00 , 4.8100964254128664e-01 , 7.2800592000000002e+00 , 5.3750299999999995e-01 , 2.7236199999999999e-01 , -7.9806600000000005e-01 --3.9623200781150132e+00 , 5.7220959112051206e-01 , 7.3022216000000002e+00 , -3.8663599999999998e-01 , 1.6940000000000000e-01 , 9.0654100000000004e-01 --3.8259507694566555e+00 , 6.4345258712792353e-01 , 7.3634463999999999e+00 , -5.2063999999999999e-01 , -1.7984000000000000e-01 , 8.3462099999999995e-01 --3.7296236920981896e+00 , 7.0142354265361440e-01 , 7.4503800000000000e+00 , 5.7382200000000005e-01 , 5.9144900000000000e-01 , -5.6649499999999997e-01 --6.1498914939843079e+00 , 7.9849908454827423e-02 , 9.3773751999999995e+00 , -3.4037200000000001e-01 , 1.8126800000000001e-01 , 9.2265299999999995e-01 --6.8751670551225228e+00 , -6.6991391541685541e-02 , 1.0148649600000001e+01 , 2.9876799999999998e-01 , -9.4865299999999997e-01 , -1.0390300000000000e-01 --5.0147511126651843e+00 , 4.6736241883107854e-01 , 8.9341688000000001e+00 , 9.7505100000000000e-01 , 2.1258299999999999e-01 , -6.3908999999999994e-02 --5.0703284456880038e+00 , 4.9481651332764720e-01 , 9.1797856000000007e+00 , 9.7505100000000000e-01 , 2.1258299999999999e-01 , -6.3908999999999994e-02 --5.9421541580064794e+00 , 3.2098818504050941e-01 , 1.0117886400000000e+01 , -2.5614100000000001e-01 , 1.2758700000000001e-01 , 9.5818199999999998e-01 --4.8857055158625409e+00 , 6.2619279003066253e-01 , 9.4390992000000011e+00 , -2.9998300000000000e-01 , -2.6082100000000003e-01 , 9.1759599999999997e-01 --4.6527538587305077e+00 , 7.2525119282189388e-01 , 9.4428951999999988e+00 , -2.7279399999999999e-03 , 2.6533200000000000e-02 , 9.9964399999999998e-01 --4.3534586105331439e+00 , 8.3823254855122742e-01 , 9.3771255999999994e+00 , -5.0303500000000001e-01 , -3.9989799999999999e-02 , 8.6334000000000000e-01 --6.3055452343833664e+00 , 4.4405624262592447e-01 , 1.1452268800000001e+01 , -8.3978200000000003e-01 , -1.5308400000000000e-01 , 5.2089500000000000e-01 --6.0182910085834926e+00 , 5.6372309736761594e-01 , 1.1443460000000000e+01 , -8.3978200000000003e-01 , -1.5308400000000000e-01 , 5.2089500000000000e-01 --4.3274436696364589e+00 , 9.7729188796754851e-01 , 9.9938351999999995e+00 , -2.7602500000000002e-01 , -2.9849700000000001e-01 , 9.1362500000000002e-01 --4.3352892068971380e+00 , 1.0228527645164136e+00 , 1.0228833600000002e+01 , 4.3719599999999997e-01 , -8.0653799999999998e-02 , -8.9574299999999996e-01 --4.1355344655296022e+00 , 1.1110427944029644e+00 , 1.0245390400000000e+01 , -4.7719400000000001e-01 , 7.7508400000000005e-02 , 8.7537299999999996e-01 --3.9911106062859227e+00 , 1.1864716613168986e+00 , 1.0318564800000001e+01 , -4.4036300000000000e-01 , -2.0441699999999999e-01 , 8.7423899999999999e-01 --5.1337078792638966e+00 , 1.0282821677701552e+00 , 1.1882589600000001e+01 , -9.0958300000000003e-01 , 1.8193799999999999e-01 , -3.7357400000000002e-01 --5.2761388111435394e+00 , 1.0635799963678347e+00 , 1.2343621600000001e+01 , 6.9851700000000003e-02 , 6.6085000000000005e-01 , 7.4726099999999995e-01 --1.8381122883864642e+00 , 1.6965287802129110e+00 , 8.3924120000000002e+00 , 7.8834899999999999e-03 , -9.5744899999999994e-02 , 9.9537500000000001e-01 --1.7432843897455705e+00 , 1.7481801642190780e+00 , 8.4476568000000007e+00 , -1.0816700000000000e-01 , -3.7057699999999999e-01 , 9.2248200000000002e-01 --1.5981573870604744e+00 , 1.8062680184433684e+00 , 8.4349063999999991e+00 , -2.4552299999999999e-01 , -2.8213500000000002e-01 , 9.2742599999999997e-01 --1.5267966539604476e+00 , 1.8540707189427790e+00 , 8.5187512000000005e+00 , 6.3322599999999996e-01 , 3.1804399999999999e-01 , -7.0560000000000000e-01 --5.4905016673321221e+00 , 1.3815932026749103e+00 , 1.4308504000000001e+01 , -9.3511900000000003e-01 , -1.0445100000000000e-01 , -3.3859000000000000e-01 --1.5671874296407142e+00 , 1.9281075581390872e+00 , 8.9566640000000000e+00 , -8.9205900000000005e-01 , -4.1080000000000000e-01 , 1.8834600000000001e-01 --1.5156771302221754e+00 , 1.9757871727398251e+00 , 9.0830864000000009e+00 , -9.1962600000000005e-01 , -3.1084000000000001e-01 , 2.4013899999999999e-01 --1.6725906150896486e+00 , 2.0048448139374124e+00 , 9.5416744000000016e+00 , -8.6243400000000003e-01 , -4.9310500000000002e-01 , 1.1426000000000000e-01 --1.3375240244664379e+00 , 2.0812352317147478e+00 , 9.2281247999999998e+00 , 2.2591500000000000e-01 , 6.7701899999999995e-02 , -9.7179199999999999e-01 --1.2032203573450158e+00 , 2.1378029189758028e+00 , 9.2266064000000014e+00 , -3.8533100000000001e-02 , 5.6760800000000000e-02 , 9.9764399999999998e-01 --1.4011527092783824e+00 , 2.1724881055409671e+00 , 9.7992407999999998e+00 , -3.9407700000000001e-01 , 2.4114900000000000e-01 , 8.8687700000000003e-01 --1.3049834092707422e+00 , 2.2300333904743375e+00 , 9.8787592000000011e+00 , -5.8374300000000001e-01 , 1.6284499999999999e-01 , 7.9544099999999995e-01 --1.2373536071607090e+00 , 2.2857716931183556e+00 , 1.0011733600000001e+01 , 3.7801899999999999e-01 , 5.5876900000000000e-02 , -9.2410999999999999e-01 --9.2872542199924979e-01 , 2.3481055757256835e+00 , 9.6807639999999999e+00 , -6.3912700000000000e-01 , -6.2302800000000003e-01 , -4.5094699999999999e-01 --3.4657369371145119e-01 , 2.4036297365433992e+00 , 8.7629847999999999e+00 , -4.7084500000000001e-01 , 1.8945300000000001e-01 , 8.6163299999999998e-01 --2.4279594150913253e-01 , 2.4500248872500032e+00 , 8.7782520000000002e+00 , -4.7084500000000001e-01 , 1.8945400000000001e-01 , 8.6163299999999998e-01 --2.7284777795070170e-01 , 2.5013785635235593e+00 , 9.0846984000000006e+00 , -5.6533699999999998e-01 , -2.0695800000000000e-01 , -7.9847500000000005e-01 --1.2364078347392038e-01 , 2.5473484749166020e+00 , 9.0021431999999990e+00 , 3.6900800000000000e-01 , 2.3296200000000000e-01 , 8.9975700000000003e-01 -3.1414846442396671e-02 , 2.5906403075234623e+00 , 8.8969887999999990e+00 , -8.9701799999999998e-01 , -3.1551000000000001e-01 , -3.0953500000000000e-01 --5.3087003830104784e-02 , 2.6549352803142039e+00 , 9.3772504000000012e+00 , -7.9385600000000001e-01 , -6.0790999999999995e-01 , 1.5468700000000000e-02 --1.0373601228636042e-01 , 2.7235648988577896e+00 , 9.8124904000000015e+00 , 3.6495100000000003e-01 , 1.7017399999999999e-01 , -9.1534199999999999e-01 --9.2903700304267645e-03 , 2.7794576859214555e+00 , 9.8887327999999997e+00 , -4.3218000000000001e-01 , -4.5164199999999999e-01 , 7.8053899999999998e-01 -7.2215342566398721e-02 , 2.8371524248871847e+00 , 1.0002727200000001e+01 , -1.9502600000000000e-01 , -4.6912500000000001e-01 , 8.6132799999999998e-01 -3.6962052298015813e-01 , 2.8517249942316516e+00 , 9.4639343999999994e+00 , -5.0599200000000000e-01 , 6.1709400000000003e-01 , -6.0263400000000000e-01 -5.9163338490210604e-01 , 2.8709962836858147e+00 , 9.1063095999999994e+00 , -3.9750199999999999e-02 , 3.2577200000000001e-02 , 9.9867899999999998e-01 -7.0331650541086566e-01 , 2.9133093384824829e+00 , 9.0818696000000010e+00 , 9.6338699999999999e-02 , 2.5009599999999998e-01 , 9.6341600000000005e-01 -7.8646523037308058e-01 , 2.9627417981133570e+00 , 9.1552208000000004e+00 , -7.8763499999999997e-01 , -1.5925800000000001e-01 , -5.9520399999999996e-01 -9.6897199821188096e-01 , 2.9764454563502154e+00 , 8.8458311999999992e+00 , 2.9099399999999997e-01 , 3.7438300000000002e-01 , 8.8043199999999999e-01 -1.0964720671222763e+00 , 3.0047634849354612e+00 , 8.7237352000000001e+00 , -9.9173899999999999e-03 , -1.7066200000000001e-01 , 9.8528000000000004e-01 -1.2889055093501587e+00 , 2.9954149600320026e+00 , 8.2862280000000013e+00 , -1.0304000000000001e-01 , 4.8132100000000000e-01 , 8.7046699999999999e-01 -1.3728355415661502e+00 , 3.0338318637253128e+00 , 8.2998311999999999e+00 , -5.9330099999999997e-01 , 6.9968500000000000e-01 , 3.9803800000000000e-01 -1.3332438941299318e+00 , 3.1558716889810898e+00 , 8.9709016000000013e+00 , 1.0784900000000000e-01 , 1.1539700000000000e-01 , 9.8744699999999996e-01 -1.4314264620715438e+00 , 3.1955753845753332e+00 , 8.9623008000000013e+00 , -1.3466700000000001e-01 , -5.8698200000000000e-01 , 7.9832099999999995e-01 -1.5484172712385020e+00 , 3.2200334023348729e+00 , 8.8398824000000005e+00 , 7.2858199999999995e-01 , -4.5122899999999999e-01 , 5.1532500000000003e-01 -1.6496176195073020e+00 , 3.2537590758902297e+00 , 8.7969511999999987e+00 , 1.9960600000000001e-01 , -4.3299199999999999e-01 , 8.7902000000000002e-01 --5.3132710981627751e-01 , 7.9955451034554392e-01 , 8.6728399999999994e-01 , -2.9103899999999999e-02 , 1.7994700000000000e-01 , 9.8324599999999995e-01 --6.3422346987673217e-01 , 7.6315474751204704e-01 , 8.8073120000000005e-01 , -2.6221600000000001e-02 , 1.8002899999999999e-01 , 9.8331199999999996e-01 --7.6876069497302524e-01 , 7.0957142810880969e-01 , 8.7594720000000015e-01 , -8.3569000000000004e-02 , 1.7363500000000001e-01 , 9.8125799999999996e-01 --9.2831803974410931e-01 , 6.4414824935870785e-01 , 8.5974399999999984e-01 , -9.3436199999999997e-02 , 1.6552400000000000e-01 , 9.8177000000000003e-01 --1.0895215833512375e+00 , 5.7983135338918590e-01 , 8.4867839999999983e-01 , -7.2029599999999999e-02 , 1.7610100000000001e-01 , 9.8173299999999997e-01 --1.2456192974299860e+00 , 5.1948460783957451e-01 , 8.4787759999999990e-01 , -8.8678999999999994e-02 , 1.6510900000000001e-01 , 9.8228000000000004e-01 --1.4428219842358501e+00 , 4.3807376532879783e-01 , 8.2861679999999982e-01 , -9.7352300000000003e-02 , 1.6120999999999999e-01 , 9.8210699999999995e-01 --1.6349348349429986e+00 , 3.6285825124658833e-01 , 8.2010960000000011e-01 , -8.5925199999999993e-02 , 1.7356800000000000e-01 , 9.8106599999999999e-01 --1.8537276938408187e+00 , 2.7472571738320029e-01 , 8.0503999999999998e-01 , -8.5416300000000001e-02 , 1.7905099999999999e-01 , 9.8012500000000002e-01 --2.0834180491034830e+00 , 1.8339727991391186e-01 , 7.9287199999999980e-01 , -7.7516500000000002e-02 , 1.7985400000000001e-01 , 9.8063400000000001e-01 --2.3331098157928096e+00 , 8.4367174829635738e-02 , 7.8036079999999997e-01 , -8.0766500000000005e-02 , 1.7396300000000001e-01 , 9.8143499999999995e-01 --2.6189316484690117e+00 , -3.1529800735628832e-02 , 7.6076719999999987e-01 , -7.0144600000000001e-02 , 1.8211400000000000e-01 , 9.8077199999999998e-01 --2.8999468405848017e+00 , -1.4072432137382318e-01 , 7.5437120000000002e-01 , -9.0917799999999993e-02 , 1.6719700000000001e-01 , 9.8172300000000001e-01 --3.2707472280501699e+00 , -2.9168739692547252e-01 , 7.2173599999999993e-01 , -5.9067599999999998e-02 , 2.4922900000000001e-01 , 9.6664099999999997e-01 --3.6360792719882529e+00 , -4.3643784132859897e-01 , 7.0536639999999995e-01 , -3.0795300000000001e-02 , 3.2288699999999998e-01 , 9.4593700000000003e-01 --3.8068145984755768e+00 , -4.8843989323875858e-01 , 7.7444319999999989e-01 , -4.3677899999999999e-02 , 3.1640499999999999e-01 , 9.4761799999999996e-01 --4.6096984750101155e+00 , -8.2920082724885624e-01 , 6.2991439999999987e-01 , -1.3722200000000001e-01 , 1.9514300000000001e-01 , 9.7112799999999999e-01 --5.1307307124921371e+00 , -1.0350026885749335e+00 , 6.0929119999999992e-01 , -1.4952599999999999e-01 , 3.2352900000000001e-01 , 9.3432899999999997e-01 --5.8750281423637389e+00 , -1.3376028169848992e+00 , 5.4022480000000006e-01 , -4.1216100000000000e-01 , 3.7252400000000002e-01 , 8.3147400000000005e-01 --6.6154825571052580e+00 , -1.6333010783206623e+00 , 5.0086079999999988e-01 , 4.8664200000000002e-01 , -3.0620500000000000e-01 , -8.1818000000000002e-01 --5.9101629170866667e+00 , -1.2842074671164969e+00 , 8.7151679999999998e-01 , -8.4109400000000001e-01 , 5.0506099999999998e-01 , 1.9358400000000001e-01 --5.9285411041240437e+00 , -1.2578810741311446e+00 , 1.0351649599999999e+00 , -8.6120300000000005e-01 , 4.4617600000000002e-01 , -2.4342600000000000e-01 --5.9344603958713398e+00 , -1.2264293146622318e+00 , 1.2005093599999999e+00 , -8.6120300000000005e-01 , 4.4617600000000002e-01 , -2.4342600000000000e-01 --7.5742027359186874e+00 , -1.8168301368676647e+00 , 1.4197101599999999e+00 , -4.1266599999999998e-01 , -7.6763599999999999e-01 , -4.9034899999999998e-01 --1.7190162914990790e+01 , -5.7916943571219486e+00 , 2.0372239999999997e-01 , 3.6929200000000001e-01 , -5.7433999999999996e-01 , -7.3058699999999999e-01 --2.2217595440814410e+01 , -7.6992127826972538e+00 , 4.0400559999999985e-01 , 1.8009900000000001e-01 , 1.5523200000000001e-01 , 9.7132300000000005e-01 --4.0090200004673392e+01 , -1.4534659414315588e+01 , 8.5180879999999992e-01 , 9.9590500000000004e-01 , 7.7688199999999999e-02 , 4.6238399999999999e-02 --4.0174060705817524e+01 , -1.4407830223897232e+01 , 1.6373717600000000e+00 , -9.6533500000000005e-01 , 2.2583900000000001e-02 , 2.6003399999999999e-01 --4.0245209489827630e+01 , -1.4275134627869168e+01 , 2.4231042399999998e+00 , -9.5281899999999997e-01 , 8.6410200000000006e-02 , 2.9098099999999999e-01 --3.4368201326223151e+01 , -1.1841599873328486e+01 , 3.1913928000000000e+00 , -3.7057400000000001e-01 , -7.4876299999999996e-01 , 5.4957100000000003e-01 --3.4795732169055057e+01 , -1.1867810813503842e+01 , 3.8765343999999997e+00 , 4.1921000000000003e-01 , -8.9500500000000005e-01 , -1.5241299999999999e-01 --3.4979045737509580e+01 , -1.1798451835689074e+01 , 4.5664600000000002e+00 , 2.4048500000000000e-01 , -9.7045099999999995e-01 , 1.9795299999999998e-02 --3.4810231140874009e+01 , -1.1596314667234262e+01 , 5.2421272000000005e+00 , -5.4285399999999995e-01 , 8.3950999999999998e-01 , -2.3080900000000001e-02 --3.3144094595883658e+01 , -1.0837368847405562e+01 , 5.7965096000000003e+00 , 8.4316300000000000e-01 , -8.6565400000000001e-02 , -5.3064299999999998e-01 --3.4984633303034727e+01 , -1.1382986671074203e+01 , 6.6220512000000005e+00 , -7.6725399999999999e-01 , 5.0822999999999996e-01 , 3.9118100000000000e-01 --3.2956497414955493e+01 , -1.0504361872396865e+01 , 7.0782888000000002e+00 , -8.4743400000000002e-01 , -3.4683999999999998e-01 , 4.0194200000000002e-01 --3.2306875397564092e+01 , -1.0137323979667951e+01 , 7.6421039999999998e+00 , -8.4743400000000002e-01 , -3.4683999999999998e-01 , 4.0194200000000002e-01 --3.2308885231815523e+01 , -1.0008578534789921e+01 , 8.2807263999999989e+00 , 9.4109399999999999e-01 , 3.0397800000000003e-01 , 1.4812200000000000e-01 --3.3043092114118039e+01 , -1.0004412685122009e+01 , 9.6994424000000006e+00 , -9.6668799999999999e-01 , -2.4870800000000001e-01 , -6.0490700000000001e-02 --8.9364211772200370e+00 , -1.5331227029477916e+00 , 5.4148608000000005e+00 , 8.6014999999999997e-01 , 2.9489799999999999e-01 , -4.1614499999999999e-01 --8.8136926312753712e+00 , -1.4480876655569159e+00 , 5.5994816000000007e+00 , -7.9884200000000005e-01 , -2.3873800000000001e-01 , 5.5213699999999999e-01 --8.7742878816882968e+00 , -1.3922525657097760e+00 , 5.8007216000000001e+00 , -8.0053799999999997e-01 , -3.2324199999999997e-01 , 5.0463199999999997e-01 --8.6836483732324492e+00 , -1.3190492832893659e+00 , 5.9883895999999996e+00 , 8.3468299999999995e-01 , 4.9738199999999999e-01 , -2.3646300000000001e-01 --7.7225972425560627e+00 , -9.5809418800336088e-01 , 5.9296400000000009e+00 , 1.0868300000000000e-01 , -4.8408400000000001e-01 , -8.6824599999999996e-01 --7.7530385203290795e+00 , -9.2863780986640077e-01 , 6.1325856000000005e+00 , -8.2727499999999998e-01 , 2.6475399999999999e-01 , -4.9550200000000000e-01 --7.9121423255275189e+00 , -9.4007630471887804e-01 , 6.3791696000000009e+00 , -8.2727499999999998e-01 , 2.6475399999999999e-01 , -4.9550200000000000e-01 --7.9908903226337884e+00 , -9.2484355579040223e-01 , 6.6066280000000006e+00 , -9.6726199999999996e-01 , 1.9943200000000000e-01 , -1.5694200000000000e-01 --5.9815531685619483e+00 , -2.5045354731062064e-01 , 6.0926288000000000e+00 , -1.6263200000000000e-01 , 5.7156600000000002e-01 , 8.0427800000000005e-01 --5.2685392349816826e+00 , 5.0366884481451990e-03 , 5.9897520000000002e+00 , 7.1192599999999995e-01 , -6.4519700000000002e-01 , 2.7727700000000000e-01 --5.2744382661829441e+00 , 3.4661005892841823e-02 , 6.1460640000000000e+00 , 7.1192599999999995e-01 , -6.4519700000000002e-01 , 2.7727700000000000e-01 --5.5092955854794718e+00 , -5.0562004042071784e-03 , 6.3995016000000007e+00 , -8.8939199999999996e-01 , 4.4099899999999997e-01 , 1.2042300000000000e-01 --5.3893187503587123e+00 , 6.3871971489124713e-02 , 6.5089823999999998e+00 , -8.7927500000000003e-01 , 4.7202499999999997e-01 , -6.3772400000000007e-02 --5.4687660081037581e+00 , 7.3183937305152824e-02 , 6.7068944000000004e+00 , -8.1449199999999999e-01 , -5.4686499999999999e-02 , -5.7759199999999999e-01 --5.5812685010001912e+00 , 7.4278888452097291e-02 , 6.9254816000000003e+00 , 5.3647900000000004e-01 , -1.4838899999999999e-01 , 8.3076499999999998e-01 --7.5359528704097851e+00 , -4.4946968862601988e-01 , 8.0723623999999994e+00 , 7.7592300000000003e-01 , -5.2971199999999996e-01 , -3.4256300000000001e-01 --4.7346772387085823e+00 , 3.8212005593785614e-01 , 6.8263696000000005e+00 , 1.3867599999999999e-01 , 9.9032500000000001e-01 , -5.1319099999999999e-03 --5.1415160901164878e+00 , 3.0152161075402750e-01 , 7.2038376000000000e+00 , -2.6257300000000000e-01 , -4.8541099999999997e-02 , 9.6369000000000005e-01 --4.5440227863891725e+00 , 4.9855646447935942e-01 , 7.0338912000000002e+00 , -3.6160999999999999e-02 , 7.3215200000000003e-01 , 6.8018100000000004e-01 --4.3984599288104764e+00 , 5.6941344202953736e-01 , 7.1056824000000001e+00 , 1.0245300000000000e-01 , -4.1789100000000001e-01 , -9.0270200000000000e-01 --4.3570018617245880e+00 , 6.1203065945981705e-01 , 7.2364623999999997e+00 , 6.2133799999999995e-01 , -2.3029300000000000e-01 , -7.4893500000000002e-01 --4.1753212971600009e+00 , 6.9149209804091161e-01 , 7.2796328000000008e+00 , -7.2631900000000005e-01 , 5.4811699999999998e-02 , 6.8516900000000003e-01 --4.0868334537695610e+00 , 7.4589013776114044e-01 , 7.3787760000000002e+00 , 4.6358500000000002e-01 , 1.0520200000000000e-01 , -8.7978500000000004e-01 --4.0061444761036169e+00 , 7.9813891590866559e-01 , 7.4814031999999999e+00 , 6.2099800000000005e-01 , 7.1484700000000001e-01 , -3.2148800000000000e-01 --4.2308096691504016e+00 , 7.7535757833389840e-01 , 7.7999968000000006e+00 , 6.0897100000000004e-01 , 7.1724800000000000e-01 , -3.3868799999999999e-01 --4.0111453299552888e+00 , 8.6196542435839785e-01 , 7.8076824000000009e+00 , 3.5101500000000002e-01 , -6.1902800000000002e-01 , 7.0256200000000002e-01 --5.7004783660441998e+00 , 5.0159801284262184e-01 , 9.2529080000000015e+00 , 2.4665699999999999e-01 , -4.3013099999999999e-01 , 8.6841699999999999e-01 --5.1315954301306492e+00 , 6.7477042787641728e-01 , 9.0216536000000005e+00 , 9.7505100000000000e-01 , 2.1258299999999999e-01 , -6.3908999999999994e-02 --5.0884288521893071e+00 , 7.2623423277773025e-01 , 9.1914335999999999e+00 , 9.9207699999999999e-01 , 3.8261000000000003e-02 , -1.1966200000000000e-01 --5.0420864257572244e+00 , 7.7857314526229637e-01 , 9.3609743999999999e+00 , -6.8644700000000003e-01 , -9.1508500000000007e-02 , 7.2139900000000001e-01 --4.7054689485044854e+00 , 8.9248937448994892e-01 , 9.2814455999999996e+00 , 2.2291399999999999e-02 , 2.4723000000000001e-01 , 9.6870000000000001e-01 --4.5335445631681823e+00 , 9.7034867946716252e-01 , 9.3356607999999994e+00 , 5.4309399999999997e-01 , -1.3762500000000000e-02 , -8.3955900000000006e-01 --4.4676842964342898e+00 , 1.0259171646592256e+00 , 9.4832160000000005e+00 , 7.4653599999999998e-01 , -6.3658099999999995e-02 , -6.6229300000000002e-01 --6.2595572945009135e+00 , 7.2334624131561598e-01 , 1.1409514400000001e+01 , -7.7668599999999999e-01 , -1.1987800000000000e-01 , 6.1837500000000001e-01 --5.1034160909680306e+00 , 9.9506129132481158e-01 , 1.0543620800000001e+01 , 7.5541899999999995e-01 , -1.3817599999999999e-01 , 6.4050799999999997e-01 --4.4461269342692189e+00 , 1.1637237889933929e+00 , 1.0119113600000000e+01 , -2.9302899999999998e-01 , -4.3275200000000000e-02 , 9.5512399999999997e-01 --4.2798228459233201e+00 , 1.2392086219759810e+00 , 1.0176147200000001e+01 , 3.5515900000000000e-01 , 7.3827699999999996e-02 , -9.3188599999999999e-01 --4.1626036086447780e+00 , 1.3065070983424709e+00 , 1.0282216800000000e+01 , -1.3531299999999999e-01 , 1.0989500000000001e-01 , 9.8468999999999995e-01 --5.6230631624756571e+00 , 1.1230041748890736e+00 , 1.2163992800000001e+01 , -2.1778700000000001e-01 , 7.5224899999999995e-01 , 6.2184499999999998e-01 --5.3927483349668677e+00 , 1.2196800689513432e+00 , 1.2197574400000001e+01 , -8.3947899999999998e-01 , 2.6286100000000001e-01 , -4.7558299999999998e-01 --2.0296201539467793e+00 , 1.7631241544281044e+00 , 8.4607296000000005e+00 , -3.9194000000000000e-02 , 2.8857299999999999e-02 , 9.9881500000000001e-01 --1.8926070724906761e+00 , 1.8177378086565252e+00 , 8.4711607999999998e+00 , 2.8908499999999998e-01 , 3.0576799999999998e-01 , -9.0715800000000002e-01 --1.7947564013441117e+00 , 1.8672503708147219e+00 , 8.5269879999999993e+00 , 2.4199300000000001e-01 , 4.9871199999999999e-01 , -8.3230199999999999e-01 --1.6903741390927727e+00 , 1.9175733542767059e+00 , 8.5724152000000000e+00 , 4.1133300000000000e-01 , 7.1495100000000000e-01 , -5.6537599999999999e-01 --1.7070133655917972e+00 , 1.9533813461008860e+00 , 8.7834831999999992e+00 , 7.7470499999999998e-01 , 3.8491300000000001e-01 , -5.0167099999999998e-01 --1.5331845929086132e+00 , 2.0111146136371865e+00 , 8.7329287999999998e+00 , -9.4638400000000000e-01 , -3.0986700000000000e-01 , 9.1328000000000006e-02 --1.6483962064526549e+00 , 2.0409121258650922e+00 , 9.0986760000000011e+00 , 9.8198900000000000e-01 , -7.6556700000000005e-02 , -1.7273500000000000e-01 --1.5697200128280278e+00 , 2.0902125997607892e+00 , 9.1915271999999995e+00 , -8.6124400000000001e-01 , 2.4200599999999999e-02 , 5.0761500000000004e-01 --1.5119872022976626e+00 , 2.1377146571572685e+00 , 9.3183968000000004e+00 , -2.7749699999999999e-01 , 5.7428800000000002e-01 , 7.7018699999999995e-01 --1.2494846539720044e+00 , 2.1983079341351073e+00 , 9.1165120000000002e+00 , -1.7015600000000000e-01 , 5.4092200000000001e-01 , 8.2368100000000000e-01 --1.2165287959520636e+00 , 2.2453864891045359e+00 , 9.2834216000000005e+00 , 4.1699599999999998e-01 , -2.4979100000000001e-01 , 8.7390999999999996e-01 --1.3901270101894556e+00 , 2.2878621329959277e+00 , 9.8208623999999993e+00 , -5.8374300000000001e-01 , 1.6284499999999999e-01 , 7.9544099999999995e-01 --1.2971878102935901e+00 , 2.3420254825561848e+00 , 9.9092520000000004e+00 , 9.6253500000000006e-02 , 3.4020000000000000e-01 , 9.3541399999999997e-01 --1.0658686348608852e+00 , 2.3964747893582019e+00 , 9.7387335999999998e+00 , 1.8671900000000000e-01 , 8.6196499999999998e-01 , 4.7133100000000000e-01 --5.1186042300854506e-01 , 2.4431083974589329e+00 , 8.9131192000000006e+00 , -7.9991299999999999e-01 , -2.3046800000000001e-01 , -5.5409699999999995e-01 --2.9954711853465943e-01 , 2.4856254091200167e+00 , 8.7162056000000003e+00 , 4.8691699999999999e-01 , -2.8638000000000002e-01 , -8.2516500000000004e-01 --3.5421881074428141e-01 , 2.5358329486972431e+00 , 9.0697016000000001e+00 , -1.7769500000000001e-02 , -4.1506900000000002e-01 , 9.0961599999999998e-01 --2.6555416081782024e-01 , 2.5827628896889854e+00 , 9.1318207999999998e+00 , 6.2884700000000004e-01 , 1.0195400000000000e-01 , 7.7081599999999995e-01 --8.6274090791362390e-02 , 2.6223985760957316e+00 , 8.9820607999999993e+00 , 4.8659400000000003e-01 , 8.8404600000000000e-02 , 8.6914400000000003e-01 --1.4484677563710191e-01 , 2.6837363313646034e+00 , 9.3952215999999993e+00 , -7.7221300000000004e-01 , -3.4815800000000002e-01 , -5.3148099999999998e-01 --1.1104402372766575e-01 , 2.7400381901856861e+00 , 9.6081095999999988e+00 , 9.2017099999999996e-01 , 3.8962700000000000e-01 , -3.8420299999999998e-02 --1.0241290754637467e-01 , 2.8044594647227910e+00 , 9.9086175999999995e+00 , -4.9820100000000000e-01 , -3.0145800000000000e-01 , 8.1296900000000005e-01 -3.5442997501576645e-02 , 2.8497328588015467e+00 , 9.8676208000000010e+00 , -1.9502600000000000e-01 , -4.6912500000000001e-01 , 8.6132799999999998e-01 -9.3285442329558688e-01 , 2.7310428481230016e+00 , 7.5726839999999997e+00 , 8.0195399999999994e-01 , 1.8267100000000000e-01 , -5.6877100000000003e-01 -3.2001438430161988e-01 , 2.9334271800176248e+00 , 9.7376415999999999e+00 , -6.6927099999999995e-01 , 5.6299399999999999e-01 , -4.8488500000000001e-01 -6.1759229925497205e-01 , 2.9270982275596289e+00 , 9.1425744000000009e+00 , -1.8306500000000001e-01 , 1.0934500000000000e-01 , -9.7700100000000001e-01 -7.3691102810946640e-01 , 2.9649848087902915e+00 , 9.0978232000000006e+00 , 5.2242800000000000e-01 , 1.2073900000000000e-01 , 8.4409199999999995e-01 -8.6662350790734477e-01 , 2.9950883672875097e+00 , 9.0008535999999992e+00 , -4.3618400000000002e-01 , -4.5269799999999999e-01 , -7.7769400000000000e-01 -9.6340075766791711e-01 , 3.0375420866437670e+00 , 9.0214455999999998e+00 , 8.1619699999999995e-01 , 3.8310799999999999e-02 , 5.7650299999999999e-01 -1.2275453434790800e+00 , 2.9975250380161675e+00 , 8.3258000000000010e+00 , 6.0353599999999996e-01 , 4.7520200000000001e-01 , 6.4025600000000005e-01 -1.3291330193548498e+00 , 3.0254928885714234e+00 , 8.2702120000000008e+00 , 3.0331700000000000e-01 , -4.9700699999999998e-01 , -8.1300799999999995e-01 -1.2809246354909489e+00 , 3.1457223457360515e+00 , 8.9515472000000003e+00 , 2.7309600000000001e-01 , 5.1017000000000001e-01 , 8.1556499999999998e-01 -1.3787299964765691e+00 , 3.1845961594917473e+00 , 8.9545112000000007e+00 , -3.5422000000000002e-02 , -6.2323899999999999e-01 , 7.8122899999999995e-01 -1.4534716091136963e+00 , 3.2421825188689612e+00 , 9.0982079999999996e+00 , 7.9152400000000001e-01 , 5.3726200000000002e-01 , -2.9127100000000000e-01 -1.6148410893301817e+00 , 3.2221120116203914e+00 , 8.6904552000000006e+00 , 4.7528999999999999e-01 , 8.5447099999999998e-01 , -2.0971000000000001e-01 -1.6863764631884628e+00 , 3.2842268579267415e+00 , 8.8611608000000004e+00 , 3.8722499999999999e-01 , 7.6405900000000004e-01 , -5.1601500000000000e-01 --6.1068203283960365e-01 , 8.8007578546288179e-01 , 8.6000399999999999e-01 , -4.4943499999999997e-02 , 1.9592499999999999e-01 , 9.7958900000000004e-01 --7.4580819560969314e-01 , 8.3122997701190426e-01 , 8.5223519999999997e-01 , -4.6452199999999999e-02 , 1.7821100000000001e-01 , 9.8289499999999996e-01 --8.8252662377567237e-01 , 7.8228212008492459e-01 , 8.4890719999999997e-01 , -7.9560000000000006e-02 , 1.8344600000000000e-01 , 9.7980500000000004e-01 --1.0364806572174086e+00 , 7.2544195630771013e-01 , 8.3960959999999996e-01 , -7.8069899999999998e-02 , 1.7172699999999999e-01 , 9.8204599999999997e-01 --1.2009236550755267e+00 , 6.6579855895080642e-01 , 8.2997920000000014e-01 , -7.2871300000000000e-02 , 1.8267900000000001e-01 , 9.8046800000000001e-01 --1.3827869000784210e+00 , 5.9859789047580025e-01 , 8.1600159999999988e-01 , -9.0233800000000003e-02 , 1.5429000000000001e-01 , 9.8389700000000002e-01 --1.5843117492633376e+00 , 5.2306619844606317e-01 , 7.9865439999999999e-01 , -9.5761299999999994e-02 , 1.6217400000000001e-01 , 9.8210500000000001e-01 --1.7965784554451272e+00 , 4.4519360673365482e-01 , 7.8320000000000012e-01 , -9.4448500000000005e-02 , 1.7639600000000000e-01 , 9.7977800000000004e-01 --2.0186902605646821e+00 , 3.6406360446388542e-01 , 7.7056400000000003e-01 , -8.2100699999999999e-02 , 1.8398600000000001e-01 , 9.7949399999999998e-01 --2.2606727686820376e+00 , 2.7610523010357801e-01 , 7.5668000000000002e-01 , -7.7306700000000006e-02 , 1.8776200000000001e-01 , 9.7916800000000004e-01 --2.5227303794595448e+00 , 1.8054697693958666e-01 , 7.4295199999999983e-01 , -7.7786599999999997e-02 , 1.8413700000000000e-01 , 9.7981799999999997e-01 --2.7959043571347060e+00 , 8.2192014618890363e-02 , 7.3405999999999993e-01 , -7.9466400000000006e-02 , 1.8817700000000001e-01 , 9.7891499999999998e-01 --3.1505610027186597e+00 , -5.0519335182137581e-02 , 7.0063439999999999e-01 , -1.0910800000000000e-01 , 1.8119399999999999e-01 , 9.7737600000000002e-01 --3.5369896914140577e+00 , -1.9327593166898538e-01 , 6.6852960000000006e-01 , -3.2655900000000002e-02 , 2.6708500000000002e-01 , 9.6311999999999998e-01 --3.9614017460904245e+00 , -3.5035266743830551e-01 , 6.3629999999999987e-01 , -1.0591299999999999e-01 , 2.9657899999999998e-01 , 9.4911699999999999e-01 --4.4179929372571412e+00 , -5.1677510248886849e-01 , 6.0883359999999986e-01 , -1.4577599999999999e-01 , 2.4702199999999999e-01 , 9.5798200000000000e-01 --4.9515993276822270e+00 , -7.1242387659162221e-01 , 5.7265199999999994e-01 , -7.6581600000000000e-02 , 1.7530200000000001e-01 , 9.8153199999999996e-01 --5.4885350271340423e+00 , -9.0625382690836709e-01 , 5.5537759999999992e-01 , -7.7698199999999995e-02 , -1.9635100000000000e-01 , -9.7745000000000004e-01 --6.2254050837178294e+00 , -1.1779650422943453e+00 , 4.9887440000000005e-01 , 4.9646899999999999e-01 , -2.9557600000000001e-01 , -8.1618199999999996e-01 --5.8014086758532661e+00 , -9.6936872115433470e-01 , 7.9194640000000005e-01 , 5.6965900000000003e-01 , -8.0506000000000000e-01 , -1.6543099999999999e-01 --5.8194397478358768e+00 , -9.4475470049378663e-01 , 9.5246000000000008e-01 , -8.7901300000000004e-01 , 4.2761900000000003e-01 , -2.1089800000000000e-01 --5.8260018642380969e+00 , -9.1395321270888097e-01 , 1.1144400000000001e+00 , -8.7901300000000004e-01 , 4.2761900000000003e-01 , -2.1089800000000000e-01 --1.0244139087559542e+01 , -2.6363296345599512e+00 , 3.1362959999999984e-01 , -6.6817500000000002e-02 , 2.6086100000000001e-01 , 9.6306099999999994e-01 --6.0200768435527277e+00 , -9.2588459219766994e-01 , 1.3985835999999998e+00 , -9.2801199999999995e-01 , 3.7238599999999999e-01 , -1.1111500000000000e-02 --1.3435521283564249e+01 , -3.7823996981525863e+00 , 2.3164640000000003e-01 , -1.9640099999999999e-01 , 2.4317900000000001e-01 , 9.4989000000000001e-01 --1.5783072739744810e+01 , -4.6274786912865880e+00 , 1.5830559999999982e-01 , 2.3378099999999999e-01 , -5.8897699999999997e-01 , -7.7359699999999998e-01 --4.0412740866142904e+01 , -1.3329322297831295e+01 , 2.1464239999999979e-01 , -9.6533500000000005e-01 , 2.2583900000000001e-02 , 2.6003399999999999e-01 --4.0493227647986672e+01 , -1.3201862237731698e+01 , 9.9874935999999992e-01 , -9.6533500000000005e-01 , 2.2583900000000001e-02 , 2.6003399999999999e-01 --4.0561001816601632e+01 , -1.3069586171791743e+01 , 1.7830372800000001e+00 , 9.0888899999999995e-01 , -1.4517300000000000e-01 , -3.9095400000000002e-01 --3.6324297816126524e+01 , -1.1404648722189753e+01 , 2.6185888799999999e+00 , -3.1729099999999999e-01 , -8.0020500000000006e-01 , 5.0891900000000001e-01 --3.5733652186479937e+01 , -1.1056049576271059e+01 , 3.3205815999999997e+00 , -5.7120899999999997e-01 , 8.1642499999999996e-01 , 8.4677500000000003e-02 --3.3981415676887671e+01 , -1.0174808572565208e+01 , 4.6321984000000000e+00 , -7.8187099999999995e-03 , -7.2753599999999996e-01 , 6.8602500000000000e-01 --3.3392169368435049e+01 , -9.8418161237332207e+00 , 5.2565416000000003e+00 , -8.2054899999999997e-01 , 4.9847700000000000e-01 , 2.7967799999999998e-01 --3.4304851321192515e+01 , -1.0021445872123206e+01 , 5.9779792000000000e+00 , -8.2055000000000000e-01 , 4.9847700000000000e-01 , 2.7967799999999998e-01 --3.3555765818082016e+01 , -9.6378218162561087e+00 , 6.5714656000000007e+00 , -7.6304399999999994e-01 , -5.8059000000000005e-01 , 2.8404000000000001e-01 --3.3561721876118611e+01 , -9.5100248718775156e+00 , 7.2255319999999994e+00 , 7.4742299999999995e-01 , 5.8328800000000003e-01 , -3.1801699999999999e-01 --3.3595682337192514e+01 , -9.3906530857457504e+00 , 7.8845592000000000e+00 , -8.9495499999999995e-01 , -2.4619500000000000e-01 , 3.7208100000000000e-01 --9.4881322720776406e+00 , -1.4581760333508949e+00 , 4.8889952000000001e+00 , 7.6772600000000002e-01 , 4.2964400000000003e-01 , -4.7539799999999999e-01 --9.2842768333775716e+00 , -1.3493313630016153e+00 , 5.0722743999999995e+00 , 7.6772600000000002e-01 , 4.2964400000000003e-01 , -4.7539799999999999e-01 --9.1453465061791483e+00 , -1.2630823702874259e+00 , 5.2612319999999997e+00 , 6.7299399999999998e-01 , 5.1393800000000001e-01 , -5.3192700000000004e-01 --9.2167546886085532e+00 , -1.2427029137943246e+00 , 5.4894496000000004e+00 , 6.9245900000000005e-01 , 5.4759800000000003e-01 , -4.6971900000000000e-01 --9.0425573959955212e+00 , -1.1456418551882108e+00 , 5.6657919999999997e+00 , 6.9557700000000000e-01 , 5.3399500000000000e-01 , -4.8064800000000002e-01 --8.8361687036140211e+00 , -1.0398714251553520e+00 , 5.8289368000000001e+00 , -7.4556500000000003e-01 , 6.2756900000000004e-01 , -2.2425200000000001e-01 --8.9556317491952058e+00 , -1.0337016844292015e+00 , 6.0712048000000003e+00 , -9.8401000000000005e-01 , -6.2214600000000002e-02 , 1.6689499999999999e-01 --9.1185059965456432e+00 , -1.0400458633507559e+00 , 6.3317975999999998e+00 , 7.8094600000000003e-01 , 3.8274100000000000e-01 , -4.9359199999999998e-01 --7.8768041794048873e+00 , -6.3159656193685754e-01 , 6.1786263999999997e+00 , 8.6757399999999996e-01 , 4.5546700000000001e-01 , 1.9966100000000001e-01 --7.8156305060355269e+00 , -5.7400474723086736e-01 , 6.3563104000000008e+00 , -8.6573599999999995e-01 , -4.2182599999999998e-01 , -2.6937800000000001e-01 --6.4587874589095318e+00 , -1.4663592389129487e-01 , 6.0949895999999999e+00 , 9.8634299999999997e-01 , 8.0763299999999996e-02 , 1.4354400000000000e-01 --6.3502822189985526e+00 , -8.0688951652699181e-02 , 6.2293888000000006e+00 , -9.3245400000000001e-01 , -6.4566199999999997e-03 , 3.6123200000000000e-01 --5.6097982853339667e+00 , 1.6005502727712639e-01 , 6.1224352000000000e+00 , -9.2433699999999994e-02 , -4.7787400000000002e-01 , 8.7355200000000000e-01 --5.1171977106318476e+00 , 3.2703117994401332e-01 , 6.0865760000000000e+00 , -3.9698400000000000e-01 , 7.4798900000000001e-01 , -5.3189900000000001e-01 --5.2882375519630660e+00 , 3.1034834309778492e-01 , 6.3098536000000003e+00 , -3.9698400000000000e-01 , 7.4798900000000001e-01 , -5.3189900000000001e-01 --5.2778851731964735e+00 , 3.4492025987136610e-01 , 6.4625672000000005e+00 , 6.7347299999999999e-01 , -6.9351399999999996e-01 , 2.5587799999999999e-01 --5.2565770256866982e+00 , 3.8145834434020576e-01 , 6.6115784000000000e+00 , 9.2994299999999996e-01 , 4.1990600000000003e-02 , -3.6529899999999998e-01 --5.7073367765358709e+00 , 2.9719454031123949e-01 , 6.9878400000000003e+00 , -9.7427900000000001e-01 , -2.1670400000000001e-01 , 6.1801500000000002e-02 --7.5176870433448766e+00 , -1.2880080066980559e-01 , 8.0656856000000001e+00 , -5.3842899999999999e-02 , 5.7360400000000000e-01 , 8.1736100000000000e-01 --5.2115578508389122e+00 , 4.9010828685176877e-01 , 7.0761360000000000e+00 , 6.8803900000000001e-02 , -9.0175799999999995e-01 , -4.2673100000000003e-01 --4.9733778503220352e+00 , 5.8185340881022896e-01 , 7.1132744000000008e+00 , 2.8182100000000002e-02 , 6.8212600000000001e-01 , 7.3069200000000001e-01 --4.7093032948039957e+00 , 6.7855959894839013e-01 , 7.1278448000000001e+00 , -6.6483000000000003e-01 , 6.3009099999999996e-01 , 4.0123199999999998e-01 --4.3409034605036263e+00 , 7.9802058985714353e-01 , 7.0720904000000004e+00 , 3.6440400000000001e-01 , -6.8486999999999998e-01 , -6.3100100000000003e-01 --4.1663969694586829e+00 , 8.6947611071527620e-01 , 7.1214176000000000e+00 , -7.9711399999999999e-01 , 4.4853199999999999e-01 , 4.0426299999999998e-01 --4.1313921813124281e+00 , 9.0827916623769367e-01 , 7.2529672000000005e+00 , 7.3500699999999997e-01 , -2.0909600000000000e-01 , -6.4501500000000001e-01 --4.1961390563605248e+00 , 9.2453657366629804e-01 , 7.4516071999999998e+00 , -6.2059100000000000e-01 , -7.4385400000000002e-01 , 2.4808900000000000e-01 --4.2468747768941828e+00 , 9.4501474199480096e-01 , 7.6478240000000000e+00 , -5.9890200000000005e-01 , -7.4112699999999998e-01 , 3.0339200000000000e-01 --4.1186015695961755e+00 , 1.0054715656356428e+00 , 7.7222983999999997e+00 , 3.9921699999999997e-02 , -2.3557200000000000e-01 , 9.7103700000000004e-01 --4.0304426628754024e+00 , 1.0571473927140398e+00 , 7.8236775999999999e+00 , -8.9377300000000004e-01 , 4.1937400000000002e-01 , -1.5904599999999999e-01 --5.1267972656511862e+00 , 8.6797931021915620e-01 , 8.8221816000000004e+00 , -8.5702800000000001e-01 , 3.9950700000000000e-01 , -3.2541799999999999e-01 --5.0134609314724754e+00 , 9.3014314178276991e-01 , 8.9335552000000007e+00 , 7.1309299999999998e-01 , -6.7926799999999998e-01 , 1.7347699999999999e-01 --5.2022301697880842e+00 , 9.3438748787434567e-01 , 9.2885279999999995e+00 , -9.5345299999999999e-01 , -2.9296000000000000e-01 , -7.1429000000000006e-02 --5.0896781326415823e+00 , 9.9790766018410926e-01 , 9.4064848000000012e+00 , -8.4340199999999999e-01 , -5.3717300000000001e-01 , -1.0912399999999999e-02 --4.5783843884835518e+00 , 1.1326586546343764e+00 , 9.1777680000000004e+00 , -9.3503599999999998e-01 , -7.5188699999999997e-02 , 3.4649000000000002e-01 --4.5903761748562060e+00 , 1.1714525087315684e+00 , 9.3941192000000004e+00 , 9.6763999999999994e-01 , -6.2794600000000006e-02 , -2.4439700000000000e-01 --4.4907182946721509e+00 , 1.2306334722252710e+00 , 9.5141144000000004e+00 , -9.4377100000000003e-01 , -1.9998600000000000e-01 , 2.6325399999999999e-01 --4.8741835670470133e+00 , 1.2115097213805648e+00 , 1.0096306400000000e+01 , 4.3354799999999999e-01 , 6.9630800000000004e-01 , 5.7200700000000004e-01 --6.2694697241372932e+00 , 1.0393791223876612e+00 , 1.1711135200000001e+01 , 6.9332600000000000e-01 , -4.0709200000000001e-01 , -5.9462199999999998e-01 --4.5782335129808471e+00 , 1.3503114336986473e+00 , 1.0268644800000001e+01 , -1.8319500000000000e-01 , -5.1204300000000001e-02 , 9.8174200000000000e-01 --4.2512404276595186e+00 , 1.4442816797183204e+00 , 1.0161857600000001e+01 , 4.4185000000000002e-01 , 1.7821200000000001e-01 , -8.7920900000000002e-01 --5.1390031973316903e+00 , 1.3705361230493649e+00 , 1.1366676800000000e+01 , -8.2496999999999998e-01 , 4.9656899999999998e-01 , -2.6989500000000000e-01 --5.3716998431404157e+00 , 1.3955415192673504e+00 , 1.1904928800000000e+01 , -8.9997600000000000e-01 , 3.0349799999999999e-01 , -3.1294000000000000e-01 --5.1637804413175603e+00 , 1.4799407736543879e+00 , 1.1957115999999999e+01 , -9.5803000000000005e-01 , 1.9985700000000001e-01 , -2.0551400000000000e-01 --2.0145224627836047e+00 , 1.8972528464701182e+00 , 8.4603552000000004e+00 , -2.2208700000000001e-01 , 8.8646300000000001e-03 , 9.7498700000000005e-01 --1.8441892830565321e+00 , 1.9516575369616755e+00 , 8.4294359999999990e+00 , -5.9057499999999996e-01 , 6.1419000000000001e-02 , 8.0464199999999997e-01 --1.8348094982023966e+00 , 1.9886193887368524e+00 , 8.5990807999999994e+00 , 7.5604000000000005e-01 , -1.0678900000000000e-01 , -6.4575400000000005e-01 --1.7023914967963560e+00 , 2.0375285106356325e+00 , 8.6118519999999990e+00 , -7.6267900000000000e-01 , 1.1701499999999999e-01 , 6.3610400000000000e-01 --1.7117243516670233e+00 , 2.0745650230411368e+00 , 8.8147663999999999e+00 , 8.0719099999999999e-01 , -1.7432100000000000e-01 , -5.6396400000000002e-01 --1.6248394298091116e+00 , 2.1213230804198830e+00 , 8.8914664000000005e+00 , 9.9752399999999997e-01 , 3.4952200000000003e-02 , 6.1030800000000003e-02 --1.6248774530193377e+00 , 2.1614524010634857e+00 , 9.0958992000000016e+00 , -9.5913400000000004e-01 , -1.1402000000000000e-01 , 2.5896300000000000e-01 --1.5157178299613241e+00 , 2.2101418578225211e+00 , 9.1447895999999993e+00 , 8.1522300000000003e-01 , 1.6608899999999999e-01 , -5.5482100000000001e-01 --1.0904628161872609e+00 , 2.2701942770503827e+00 , 8.6903511999999985e+00 , 4.9851400000000001e-01 , 8.1570299999999996e-01 , 2.9344999999999999e-01 --1.0213363819919237e+00 , 2.3124770600355085e+00 , 8.7831919999999997e+00 , 6.6160500000000000e-01 , -7.4716199999999999e-01 , 6.3471600000000003e-02 --1.1084666871403277e+00 , 2.3538276799836586e+00 , 9.1437704000000011e+00 , 7.5762900000000000e-01 , -5.3578599999999998e-01 , 3.7273600000000001e-01 --1.0658699718211722e+00 , 2.4005122032201358e+00 , 9.3002488000000003e+00 , 3.2528299999999999e-01 , -3.5395399999999999e-01 , 8.7687400000000004e-01 --1.0190688399394729e+00 , 2.4480755326972683e+00 , 9.4567168000000006e+00 , 7.6828399999999997e-01 , 6.3999499999999998e-01 , -1.2068300000000001e-02 --5.8729199334553384e-01 , 2.4863720505198561e+00 , 8.8851431999999999e+00 , -1.0489800000000001e-01 , 9.8340099999999997e-01 , -1.4804700000000001e-01 --3.7127567207287715e-01 , 2.5240750176687219e+00 , 8.6914744000000006e+00 , 5.5703400000000003e-01 , 3.3446999999999999e-01 , 7.6015999999999995e-01 --3.0722052719825532e-01 , 2.5669809525480085e+00 , 8.7916160000000012e+00 , -6.5119800000000005e-01 , 4.6348399999999998e-02 , 7.5749100000000003e-01 --3.4057328558914746e-01 , 2.6183382694368063e+00 , 9.1079320000000017e+00 , 6.7131900000000000e-01 , 7.9658699999999999e-02 , 7.3687599999999998e-01 --1.5750907709385364e-01 , 2.6541207811428307e+00 , 8.9609176000000019e+00 , 1.5870400000000001e-01 , 1.3142400000000001e-01 , 9.7853999999999997e-01 --4.9161022102383267e-02 , 2.6941978906639195e+00 , 8.9721392000000009e+00 , 3.8621499999999997e-01 , -6.9739899999999994e-02 , 9.1976899999999995e-01 --2.6431685462055388e-01 , 2.7791422573214737e+00 , 9.7800528000000000e+00 , 7.5947900000000002e-01 , 3.8678000000000001e-01 , -5.2306100000000000e-01 --1.5522615845779786e-01 , 2.8261825060606673e+00 , 9.8207167999999996e+00 , -5.4749700000000001e-01 , -1.5634700000000001e-01 , 8.2207200000000002e-01 --5.1423690781814191e-02 , 2.8738167870815490e+00 , 9.8790295999999991e+00 , -5.1850200000000002e-01 , -1.9657600000000000e-01 , 8.3217399999999997e-01 -8.7505211357068236e-01 , 2.7455446933342218e+00 , 7.5848936000000000e+00 , -4.6378200000000003e-01 , -8.1077099999999999e-02 , 8.8223200000000002e-01 -9.5914720340412751e-01 , 2.7735257262970698e+00 , 7.5783415999999999e+00 , -4.6378200000000003e-01 , -8.1077099999999999e-02 , 8.8223200000000002e-01 -1.3715263340083035e+00 , 2.7085906744058010e+00 , 6.5218680000000004e+00 , -2.6388899999999998e-01 , 2.4778700000000001e-01 , -9.3218299999999998e-01 -6.4442861383181005e-01 , 2.9830596835443774e+00 , 9.1889064000000005e+00 , 9.7158900000000006e-02 , 3.7980500000000000e-01 , -9.1995000000000005e-01 -7.9460656438359889e-01 , 3.0049493728995156e+00 , 9.0344663999999995e+00 , 5.9606499999999996e-01 , 5.5768300000000004e-01 , 5.7766399999999996e-01 -9.5326175518393774e-01 , 3.0199515379726805e+00 , 8.8265495999999999e+00 , 2.9410900000000001e-01 , 4.7819699999999998e-01 , 8.2754300000000003e-01 -1.0579808719739030e+00 , 3.0527669380498388e+00 , 8.8062383999999998e+00 , -4.3418899999999999e-01 , -6.4662799999999998e-01 , -6.2717699999999998e-01 -1.2778149785991215e+00 , 3.0244389593404835e+00 , 8.2698376000000007e+00 , 8.3249900000000002e-02 , 5.6310300000000002e-01 , 8.2218300000000000e-01 -1.3578738621567794e+00 , 3.0608826516652154e+00 , 8.3149319999999989e+00 , 8.6123099999999997e-01 , 6.5422999999999995e-02 , 5.0398500000000002e-01 -1.3227221874845989e+00 , 3.1787183609197145e+00 , 8.9661176000000005e+00 , -4.5286800000000002e-02 , 6.5355099999999999e-01 , 7.5552600000000003e-01 -1.4203120296693954e+00 , 3.2153731244342278e+00 , 8.9791384000000001e+00 , -2.0160100000000000e-01 , -6.7951799999999996e-01 , 7.0541699999999996e-01 -1.5332610440493140e+00 , 3.2399456439398584e+00 , 8.8985488000000004e+00 , 7.7080599999999999e-01 , -3.3415600000000001e-01 , 5.4240100000000002e-01 -1.6397940248211740e+00 , 3.2653080392704901e+00 , 8.8363775999999987e+00 , 9.9050899999999997e-01 , 1.2961000000000000e-01 , 4.5749100000000001e-02 --5.9090036897831499e-01 , 9.9313929811261592e-01 , 8.3513759999999992e-01 , -4.4202800000000000e-02 , 1.6852800000000001e-01 , 9.8470500000000005e-01 --7.1118065378359674e-01 , 9.5497078534432922e-01 , 8.3610479999999998e-01 , -4.4202800000000000e-02 , 1.6852800000000001e-01 , 9.8470500000000005e-01 --8.5631632778712019e-01 , 9.0577256930580519e-01 , 8.2445679999999988e-01 , -7.1375900000000006e-02 , 1.7229100000000000e-01 , 9.8245700000000002e-01 --1.0040591378353296e+00 , 8.5755269703329606e-01 , 8.1710400000000005e-01 , -8.0172099999999996e-02 , 1.5693199999999999e-01 , 9.8434999999999995e-01 --1.1690525057652712e+00 , 8.0256124725752875e-01 , 8.0409360000000007e-01 , -7.7990500000000004e-02 , 1.7808599999999999e-01 , 9.8091899999999999e-01 --1.3268738169146475e+00 , 7.5150249736987407e-01 , 8.0159760000000002e-01 , -7.2649599999999995e-02 , 1.6812800000000000e-01 , 9.8308399999999996e-01 --1.5120343675714909e+00 , 6.8910367256417149e-01 , 7.8966879999999984e-01 , -8.9757299999999998e-02 , 1.6019800000000001e-01 , 9.8299599999999998e-01 --1.7246296961531824e+00 , 6.1766826884528059e-01 , 7.6920159999999993e-01 , -1.0797900000000001e-01 , 1.4944600000000000e-01 , 9.8285599999999995e-01 --1.9660057032007936e+00 , 5.3451782617878907e-01 , 7.4242160000000013e-01 , -8.8027200000000000e-02 , 1.7240700000000000e-01 , 9.8108499999999998e-01 --2.1914457522667652e+00 , 4.6043622261848149e-01 , 7.3242719999999983e-01 , -8.6311499999999999e-02 , 1.7475299999999999e-01 , 9.8082199999999997e-01 --2.4547684126890896e+00 , 3.7227031768617858e-01 , 7.1296879999999985e-01 , -8.9144299999999996e-02 , 1.7751400000000001e-01 , 9.8007299999999997e-01 --2.7381906327183252e+00 , 2.7767214968225207e-01 , 6.9418639999999998e-01 , -6.9072999999999996e-02 , 1.8830700000000000e-01 , 9.7967800000000005e-01 --3.0157863827518581e+00 , 1.8867158190159583e-01 , 6.8860159999999992e-01 , -1.0311400000000000e-01 , 1.9618300000000000e-01 , 9.7513099999999997e-01 --3.4121208437768535e+00 , 5.2327230238067735e-02 , 6.4406880000000011e-01 , -1.0490200000000000e-01 , 1.8497800000000000e-01 , 9.7712800000000000e-01 --3.8131941002188849e+00 , -8.2155057432070855e-02 , 6.1302479999999981e-01 , -8.3885899999999999e-02 , 2.3282900000000001e-01 , 9.6889300000000000e-01 --4.2532992098493283e+00 , -2.2871663891784966e-01 , 5.8221999999999996e-01 , 1.2021100000000000e-01 , -2.2315199999999999e-01 , -9.6734299999999995e-01 --4.7620897720947672e+00 , -3.9932060021651683e-01 , 5.4389600000000016e-01 , -9.8821900000000004e-02 , 1.6534099999999999e-01 , 9.8127299999999995e-01 --5.3764976615384885e+00 , -6.0682601753106713e-01 , 4.8963920000000005e-01 , -1.4943200000000000e-02 , 2.8641299999999997e-01 , 9.5799000000000001e-01 --5.9966245033302314e+00 , -8.1187431650425523e-01 , 4.5685840000000000e-01 , -2.3979700000000001e-01 , 3.9106299999999999e-01 , 8.8857600000000003e-01 --6.9220324706812946e+00 , -1.1274387777139023e+00 , 3.5853679999999999e-01 , -1.5066800000000000e-01 , -3.4102800000000000e-01 , -9.2789999999999995e-01 --7.7227582482516670e+00 , -1.3899585495308102e+00 , 3.2873039999999998e-01 , 2.0482700000000001e-01 , 6.4439100000000005e-01 , 7.3675400000000002e-01 --8.8800393220152039e+00 , -1.7777602204168450e+00 , 2.3884320000000003e-01 , -1.5490399999999999e-01 , 2.2886400000000001e-01 , 9.6105499999999999e-01 --7.7257513150508235e+00 , -1.3128464725243147e+00 , 7.2668639999999995e-01 , -3.6149100000000001e-01 , -7.3619000000000001e-01 , -5.7214299999999996e-01 --7.6210428581192158e+00 , -1.2371732879223600e+00 , 9.4542959999999998e-01 , -2.7351400000000001e-02 , 8.0727400000000005e-01 , 5.8954300000000004e-01 --1.2926673112722039e+01 , -3.0983337982070482e+00 , 1.1484399999999995e-01 , 7.9133400000000007e-02 , 1.6490199999999999e-01 , 9.8312999999999995e-01 --3.9029875180713262e+01 , -1.0658373752611343e+01 , 4.2221472000000002e+00 , 4.1359899999999999e-01 , -6.3542699999999996e-01 , -6.5205000000000002e-01 --3.4716875226413386e+01 , -8.9096745791175334e+00 , 6.1062007999999999e+00 , -9.7728999999999999e-01 , 9.6640500000000004e-02 , 1.8858400000000000e-01 --9.5111618598731553e+00 , -9.4096218414412069e-01 , 5.5697688000000003e+00 , 7.9314899999999999e-01 , 5.6398400000000001e-02 , -6.0641100000000003e-01 --8.7508287591670317e+00 , -6.4737414144971073e-01 , 5.8242152000000003e+00 , 6.6510700000000000e-01 , -7.0705600000000002e-01 , -2.4021899999999999e-01 --8.5086890097156349e+00 , -5.4155547124178405e-01 , 5.9689104000000004e+00 , 7.0447899999999997e-01 , -7.0153600000000005e-01 , -1.0749900000000000e-01 --9.0029048378506573e+00 , -6.3245820158501154e-01 , 6.3135144000000007e+00 , -9.3702700000000005e-01 , 3.4734500000000001e-01 , 3.6505999999999997e-02 --6.2243980983048299e+00 , 1.3603489019465886e-01 , 5.6928736000000004e+00 , -1.0512700000000000e-01 , 2.5806099999999998e-01 , 9.6039200000000002e-01 --8.1207179877445395e+00 , -3.2024215620084595e-01 , 6.4650527999999996e+00 , -7.5056800000000001e-01 , -6.5997600000000001e-01 , 3.2864200000000003e-02 --8.4753309993262480e+00 , -3.7056315562803777e-01 , 6.7879208000000002e+00 , -7.1756799999999998e-01 , -1.4896999999999999e-01 , 6.8037099999999995e-01 --8.3452494350269504e+00 , -2.9719799967455796e-01 , 6.9531456000000000e+00 , -9.8638400000000004e-01 , -1.5028600000000000e-01 , 6.6795400000000005e-02 --8.4024270620812906e+00 , -2.7006808860746334e-01 , 7.1862512000000009e+00 , -9.7751600000000005e-01 , 2.0897400000000000e-02 , 2.0982300000000001e-01 --5.8634671136389667e+00 , 3.8735302179476383e-01 , 6.3901208000000000e+00 , 6.3934100000000005e-01 , 5.3981999999999997e-01 , -5.4757400000000001e-01 --5.5991526855273168e+00 , 4.8381815252156168e-01 , 6.4457192000000001e+00 , 4.0219300000000002e-01 , 5.8965900000000004e-01 , -7.0038800000000001e-01 --5.7263232940457458e+00 , 4.8555603068958852e-01 , 6.6643688000000001e+00 , 6.7629700000000004e-01 , 7.3567199999999999e-01 , 3.7531299999999997e-02 --5.8110089502411553e+00 , 4.9799066893892130e-01 , 6.8713911999999997e+00 , 9.8154600000000003e-01 , 9.7806599999999994e-02 , 1.6432300000000000e-01 --5.7443708420233444e+00 , 5.4668574072700560e-01 , 7.0113648000000000e+00 , -5.9720799999999996e-01 , 3.4169600000000000e-01 , 7.2566299999999995e-01 --5.8042131990255283e+00 , 5.6769700613158158e-01 , 7.2135616000000002e+00 , -7.0072000000000001e-01 , -6.7743299999999995e-01 , 2.2377400000000000e-01 --6.6728549786723619e+00 , 4.1250232395183106e-01 , 7.8442696000000005e+00 , -1.7669199999999999e-01 , 6.7348100000000000e-01 , 7.1777700000000000e-01 --4.4904669221208815e+00 , 9.1797342757971601e-01 , 6.8555416000000005e+00 , -3.2333699999999999e-01 , 6.6279500000000002e-01 , 6.7539300000000002e-01 --4.2365284056390760e+00 , 1.0013931839319976e+00 , 6.8652552000000009e+00 , 8.7881699999999996e-01 , -2.2381200000000001e-01 , 4.2141200000000001e-01 --3.9395522680298800e+00 , 1.0920504234805883e+00 , 6.8410231999999995e+00 , -2.2904600000000000e-01 , 7.7723600000000004e-01 , 5.8603899999999998e-01 --4.5640785043527394e+00 , 9.9481795826978403e-01 , 7.3688128000000006e+00 , -6.1078500000000002e-01 , -3.5983399999999999e-01 , 7.0530899999999996e-01 --4.5053820396316935e+00 , 1.0380372949187961e+00 , 7.4957240000000001e+00 , 4.6134100000000000e-01 , 5.4825199999999996e-01 , 6.9755599999999995e-01 --4.4626196501968991e+00 , 1.0786696929543707e+00 , 7.6327335999999999e+00 , -2.7081300000000003e-01 , 7.4304999999999999e-01 , 6.1199400000000004e-01 --4.4247330879299076e+00 , 1.1184898631898157e+00 , 7.7752136000000007e+00 , 6.9215400000000005e-01 , 3.0867400000000000e-01 , -6.5241400000000005e-01 --3.9403907659582540e+00 , 1.2401446646875445e+00 , 7.6022616000000003e+00 , -8.2593600000000000e-01 , 1.5445999999999999e-01 , 5.4219200000000001e-01 --4.5908462385025839e+00 , 1.1559206381686660e+00 , 8.2417784000000012e+00 , -6.6695899999999997e-01 , 6.4527100000000004e-01 , -3.7254599999999999e-01 --4.1732362979883266e+00 , 1.2637382597511557e+00 , 8.1071088000000007e+00 , 5.9598499999999999e-02 , -5.0404000000000004e-01 , 8.6162099999999997e-01 --4.6857244838392305e+00 , 1.2122504056968690e+00 , 8.6855879999999992e+00 , 6.3074100000000000e-01 , -7.5769699999999995e-01 , -1.6751400000000000e-01 --5.4533159809425857e+00 , 1.1265903383589726e+00 , 9.5038079999999994e+00 , 2.0962800000000001e-01 , -2.9934500000000003e-01 , 9.3083199999999999e-01 --4.6403926700261007e+00 , 1.2966912416411660e+00 , 9.0405815999999994e+00 , 9.7640300000000002e-01 , -1.9419800000000001e-01 , 9.4474500000000003e-02 --4.6544205795660583e+00 , 1.3343794206224375e+00 , 9.2562776000000007e+00 , 9.9201799999999996e-01 , 9.4176999999999993e-03 , -1.2574299999999999e-01 --4.6480423056698914e+00 , 1.3762020154678447e+00 , 9.4599408000000000e+00 , 9.7377199999999997e-01 , 1.2196300000000000e-01 , -1.9207700000000000e-01 --4.5914951688030410e+00 , 1.4256794111224580e+00 , 9.6227319999999992e+00 , -9.3452599999999997e-01 , 1.5328000000000000e-01 , -3.2119399999999998e-01 --4.7482650786286671e+00 , 1.4475375862816673e+00 , 9.9929096000000008e+00 , -4.6522900000000000e-01 , -8.8392099999999996e-01 , -4.7385900000000002e-02 --4.8140552690027292e+00 , 1.4846463171860660e+00 , 1.0289538400000001e+01 , -5.9599899999999995e-01 , -7.6306900000000000e-01 , 2.5002000000000002e-01 --5.2548709336279593e+00 , 1.4787948850234605e+00 , 1.0983343200000000e+01 , 1.7393600000000001e-01 , -8.3351799999999998e-01 , -5.2439899999999995e-01 --4.8928578288002340e+00 , 1.5708707738614782e+00 , 1.0864065600000000e+01 , 3.8338400000000000e-01 , -6.8894500000000003e-01 , -6.1511899999999997e-01 --4.7806997941839375e+00 , 1.6342930383135754e+00 , 1.1002520799999999e+01 , 5.0175400000000003e-01 , -5.7733199999999996e-01 , -6.4415100000000003e-01 --4.7075823459407884e+00 , 1.6935313347972596e+00 , 1.1185664800000000e+01 , -5.1308299999999996e-01 , 7.6042900000000002e-01 , 3.9811400000000002e-01 --5.1224046860588599e+00 , 1.7081723026807962e+00 , 1.1944573600000000e+01 , -9.5803000000000005e-01 , 1.9985700000000001e-01 , -2.0551400000000000e-01 --1.9091374712466989e+00 , 2.0373796183134969e+00 , 8.3561784000000010e+00 , 6.9128000000000001e-01 , -4.6885300000000002e-01 , -5.4982699999999995e-01 --1.8301365709726412e+00 , 2.0788488173542152e+00 , 8.4365704000000008e+00 , 6.8326900000000002e-01 , -1.1044200000000000e-01 , -7.2176600000000002e-01 --1.8446723063927757e+00 , 2.1138596992139433e+00 , 8.6388607999999998e+00 , -8.5623600000000000e-01 , 3.0548900000000001e-01 , 4.1657800000000000e-01 --1.9971033335003279e+00 , 2.1417439985768847e+00 , 9.0346119999999992e+00 , -1.8120800000000001e-01 , -1.7953300000000000e-01 , 9.6691800000000006e-01 --1.5952115960826623e+00 , 2.2029318034471639e+00 , 8.6862120000000012e+00 , 6.3609099999999996e-01 , 5.0209099999999995e-01 , -5.8591199999999999e-01 --1.6285864987420822e+00 , 2.2400025813358759e+00 , 8.9316104000000003e+00 , -9.4804500000000003e-01 , -2.3693700000000001e-01 , 2.1230199999999999e-01 --1.6087021284249809e+00 , 2.2815227958439679e+00 , 9.1103240000000003e+00 , 8.8927299999999998e-01 , -6.8506200000000003e-02 , -4.5221800000000001e-01 --1.1076876271744100e+00 , 2.3333376998823527e+00 , 8.5573663999999994e+00 , -1.4234800000000000e-01 , 7.4421000000000004e-01 , 6.5260200000000002e-01 --1.0838546078020364e+00 , 2.3737005190049771e+00 , 8.7206360000000007e+00 , 7.3895299999999997e-01 , 6.7301599999999995e-01 , 3.1589199999999998e-02 --1.0284764030843747e+00 , 2.4144963095929572e+00 , 8.8400695999999996e+00 , 6.6160500000000000e-01 , -7.4716199999999999e-01 , 6.3471600000000003e-02 --1.0808241072224205e+00 , 2.4574794676790401e+00 , 9.1476392000000004e+00 , 6.2569300000000005e-01 , -7.4685800000000002e-01 , 2.2519200000000000e-01 --9.8106687329455466e-01 , 2.5006752095435010e+00 , 9.2041424000000003e+00 , -4.6863500000000002e-01 , -4.8258699999999999e-01 , 7.3992599999999997e-01 -5.2608156993928845e-01 , 2.4851588887978120e+00 , 6.6501831999999999e+00 , -1.2819500000000000e-01 , -1.6630000000000000e-01 , -9.7770699999999999e-01 --5.2463974779782152e-01 , 2.5719002397173760e+00 , 8.8223687999999996e+00 , 3.5157800000000000e-01 , 8.1306199999999995e-01 , 4.6402900000000002e-01 --3.3733177173505924e-01 , 2.6048077492541322e+00 , 8.6830816000000013e+00 , 5.5703400000000003e-01 , 3.3446999999999999e-01 , 7.6015999999999995e-01 --4.9127058061248707e-01 , 2.6646815182241808e+00 , 9.2425496000000003e+00 , 7.7451700000000001e-01 , 1.9606899999999999e-01 , 6.0139900000000002e-01 --2.5531497733604747e-01 , 2.6918090036434235e+00 , 8.9953728000000002e+00 , 5.3771599999999997e-01 , 2.3533599999999999e-01 , 8.0961600000000000e-01 --1.1508740670112427e-01 , 2.7270577493900139e+00 , 8.9419791999999987e+00 , 4.1382500000000000e-01 , 3.3418900000000001e-01 , 8.4679800000000005e-01 --4.9878477296109303e-01 , 2.8355000771055510e+00 , 1.0130959199999999e+01 , 2.2494300000000000e-01 , 9.7413099999999997e-01 , 2.1682199999999999e-02 --2.1235412803769105e-01 , 2.8529627525329975e+00 , 9.7516920000000002e+00 , 7.5947900000000002e-01 , 3.8678000000000001e-01 , -5.2306100000000000e-01 --1.4226159020400653e-01 , 2.9049800733332214e+00 , 9.8983319999999999e+00 , 4.8727799999999999e-01 , 2.0389399999999999e-01 , -8.4911000000000003e-01 -8.1740593763856872e-01 , 2.7630610878249779e+00 , 7.5962920000000000e+00 , -4.6378200000000003e-01 , -8.1076999999999996e-02 , 8.8223200000000002e-01 -1.2293423959341292e+00 , 2.7087274122316050e+00 , 6.6397728000000003e+00 , 5.8838900000000005e-01 , -8.0774900000000005e-01 , 3.6613600000000003e-02 -2.5460510300141359e-01 , 3.0206910290151932e+00 , 9.8406120000000001e+00 , 6.6096100000000002e-01 , -5.3557600000000005e-01 , 5.2563099999999996e-01 -5.9516128748051655e-01 , 2.9902739824538465e+00 , 9.1298656000000005e+00 , -3.8509900000000002e-01 , -6.6192299999999996e-02 , -9.2049899999999996e-01 -7.3283111667268597e-01 , 3.0145837317861393e+00 , 9.0269055999999992e+00 , 5.1050899999999999e-01 , 6.0976200000000003e-01 , 6.0627699999999995e-01 -8.8654457804847864e-01 , 3.0298787646386414e+00 , 8.8510519999999993e+00 , -4.5753600000000000e-01 , -5.0898900000000002e-01 , -7.2910299999999995e-01 -1.0031356043962609e+00 , 3.0555185137632095e+00 , 8.7923647999999996e+00 , -1.9518700000000000e-01 , -6.2444800000000000e-01 , -7.5628499999999999e-01 -1.2086213003825874e+00 , 3.0349147152591138e+00 , 8.3491999999999997e+00 , -8.5249600000000003e-01 , 6.1517900000000000e-02 , -5.1910100000000003e-01 -1.3120662063989088e+00 , 3.0577304410046793e+00 , 8.2947872000000000e+00 , 5.6125700000000001e-01 , -1.0885300000000001e-01 , -8.2045199999999996e-01 -1.2738222926271809e+00 , 3.1705461514307292e+00 , 8.9361759999999997e+00 , -4.7222699999999999e-02 , 7.9938399999999998e-01 , 5.9896099999999997e-01 -1.3791728923255078e+00 , 3.1989690502120371e+00 , 8.9100096000000004e+00 , 4.5138900000000003e-02 , 7.1613499999999997e-01 , 6.9650100000000004e-01 -1.4513131199409246e+00 , 3.2545424693808940e+00 , 9.0747664000000015e+00 , -4.4776100000000002e-01 , -8.4158100000000002e-01 , -3.0207899999999999e-01 -1.5967844085654281e+00 , 3.2452033931936053e+00 , 8.7906696000000011e+00 , -3.5159699999999999e-01 , 7.2502400000000000e-01 , -5.9221699999999999e-01 -1.6771567819293942e+00 , 3.2968002201581728e+00 , 8.9216160000000002e+00 , -7.8362600000000004e-01 , -6.0945700000000003e-01 , 1.2038400000000000e-01 --6.8040721474772026e-01 , 1.0717597271646280e+00 , 8.1625119999999995e-01 , -4.8985800000000003e-02 , 1.4683499999999999e-01 , 9.8794700000000002e-01 --8.0182022315841328e-01 , 1.0370851837212411e+00 , 8.1850800000000001e-01 , -5.4766200000000001e-02 , 1.4151300000000000e-01 , 9.8841999999999997e-01 --9.5795624307278793e-01 , 9.8854872745908406e-01 , 8.0254399999999992e-01 , -7.5451699999999997e-02 , 1.4427599999999999e-01 , 9.8665700000000001e-01 --1.1068471425645914e+00 , 9.4494559239693365e-01 , 7.9677200000000004e-01 , -8.9144299999999996e-02 , 1.6004900000000000e-01 , 9.8307599999999995e-01 --1.2829283909178439e+00 , 8.9078598224798156e-01 , 7.8025679999999986e-01 , -6.3913999999999999e-02 , 1.7296400000000001e-01 , 9.8285199999999995e-01 --1.4518085269725152e+00 , 8.4161974731657652e-01 , 7.7424559999999998e-01 , -7.6487100000000002e-02 , 1.6327700000000001e-01 , 9.8361100000000001e-01 --1.6569790089876499e+00 , 7.7847125948917872e-01 , 7.5432959999999993e-01 , -9.6333000000000002e-02 , 1.5073100000000000e-01 , 9.8387000000000002e-01 --1.8718686336820789e+00 , 7.1296209982141145e-01 , 7.3644159999999981e-01 , -1.0282600000000000e-01 , 1.5051300000000001e-01 , 9.8324599999999995e-01 --2.0986593918740484e+00 , 6.4423504628912198e-01 , 7.2112240000000005e-01 , -8.8351499999999999e-02 , 1.6323499999999999e-01 , 9.8262300000000002e-01 --2.3632028872010924e+00 , 5.6340041630172544e-01 , 6.9562159999999995e-01 , -8.4093299999999996e-02 , 1.6518900000000000e-01 , 9.8267000000000004e-01 --2.6387998784761919e+00 , 4.8076763230847841e-01 , 6.7464479999999982e-01 , -8.1862000000000004e-02 , 1.7580799999999999e-01 , 9.8101499999999997e-01 --2.9435933957189695e+00 , 3.8820950804195586e-01 , 6.5088079999999993e-01 , -8.9720499999999995e-02 , 1.9077600000000000e-01 , 9.7752499999999998e-01 --3.2877850147252783e+00 , 2.8354666070846735e-01 , 6.2187519999999985e-01 , -1.0054100000000001e-01 , 1.8159900000000001e-01 , 9.7821899999999995e-01 --3.6636428993532757e+00 , 1.6973015381482970e-01 , 5.9337920000000000e-01 , -8.7690000000000004e-02 , 1.6986899999999999e-01 , 9.8155700000000001e-01 --4.0692282404083180e+00 , 4.8031637627888868e-02 , 5.6684879999999982e-01 , -8.2750599999999994e-02 , 1.6504300000000000e-01 , 9.8280900000000004e-01 --4.5331040932633133e+00 , -9.2557653318230848e-02 , 5.3425520000000004e-01 , -9.2487200000000006e-02 , 1.6093600000000000e-01 , 9.8262200000000000e-01 --5.1041660110246383e+00 , -2.6649743751093347e-01 , 4.8191199999999990e-01 , -1.0466200000000001e-01 , 1.6332900000000000e-01 , 9.8100399999999999e-01 --5.7842349013380208e+00 , -4.7459402599202427e-01 , 4.1597600000000012e-01 , 1.3923400000000001e-02 , 4.2558200000000002e-01 , 9.0481299999999998e-01 --6.5251498606103500e+00 , -6.9996757114567165e-01 , 3.5668560000000005e-01 , 1.5132000000000001e-01 , -2.7355699999999999e-01 , -9.4987800000000000e-01 --7.2437114190431835e+00 , -9.1102497135263460e-01 , 3.3107039999999999e-01 , 4.9521400000000000e-02 , 4.9516600000000000e-01 , 8.6738599999999999e-01 --7.7089654886992580e+00 , -1.0324087603297967e+00 , 3.9879519999999991e-01 , 2.0482700000000001e-01 , 6.4439100000000005e-01 , 7.3675400000000002e-01 --9.4914432773662281e+00 , -1.5910349616614106e+00 , 1.6015679999999999e-01 , -7.5741500000000003e-02 , 1.8775000000000000e-01 , 9.7929200000000005e-01 --1.1221253490932096e+01 , -2.1201494618965109e+00 , 3.1919999999985293e-04 , 8.0089700000000000e-02 , -2.1867400000000001e-01 , -9.7250599999999998e-01 --7.5496774340056536e+00 , -8.6781817548918694e-01 , 1.0178125599999999e+00 , 3.0901800000000000e-02 , 6.6802600000000001e-01 , 7.4349600000000005e-01 --9.1125680745078768e+00 , -4.6052792463214809e-01 , 5.5097192000000001e+00 , -4.3202499999999999e-01 , 3.1275599999999998e-01 , 8.4589499999999995e-01 --8.6066954054855245e+00 , -2.9625946750671650e-01 , 5.6055552000000004e+00 , 5.7070399999999999e-01 , -1.0199999999999999e-01 , -8.1479599999999996e-01 --8.3450507805570027e+00 , -1.9452837617587404e-01 , 5.7446240000000000e+00 , 7.5461299999999998e-01 , -5.4096000000000000e-01 , -3.7137799999999999e-01 --8.4348892202447914e+00 , -1.7745653056268251e-01 , 5.9683695999999999e+00 , -9.3450800000000001e-01 , -1.8993900000000000e-01 , 3.0102899999999999e-01 --8.8043245419654745e+00 , -2.2485583708798984e-01 , 6.2761471999999996e+00 , 9.7513600000000000e-01 , -1.9864799999999999e-01 , 9.8227300000000003e-02 --6.2405833868146541e+00 , 4.0490910498878319e-01 , 5.7116456000000007e+00 , 4.7201900000000002e-01 , -3.6121399999999998e-01 , -8.0418999999999996e-01 --6.2598337566440776e+00 , 4.3276365132844341e-01 , 5.8826840000000002e+00 , 4.7201900000000002e-01 , -3.6121500000000001e-01 , -8.0418999999999996e-01 --6.3056966829605123e+00 , 4.5443544751110143e-01 , 6.0647880000000001e+00 , -9.1863499999999998e-01 , 3.9251399999999997e-01 , 4.5196600000000003e-02 --6.1748475441803645e+00 , 5.1485308869522295e-01 , 6.1870399999999997e+00 , 9.2181100000000005e-01 , -3.2519199999999998e-01 , -2.1098700000000001e-01 --8.2721463874143879e+00 , 9.5465256321715986e-02 , 7.1521912000000007e+00 , -9.4588899999999998e-01 , 4.3279600000000001e-02 , 3.2159100000000002e-01 --6.4007440111440257e+00 , 5.3143932931080107e-01 , 6.6164455999999996e+00 , -5.3994900000000001e-01 , -8.2488099999999998e-01 , 1.6740800000000000e-01 --5.9139475441750555e+00 , 6.6637637472808464e-01 , 6.5889792000000007e+00 , 1.4765200000000001e-01 , 9.6860100000000005e-01 , -2.0002500000000001e-01 --5.6450319782898388e+00 , 7.5427741886382926e-01 , 6.6399391999999997e+00 , -3.7390499999999999e-01 , 6.7331399999999997e-01 , -6.3784300000000005e-01 --5.7205176265795927e+00 , 7.7037734220209808e-01 , 6.8407632000000005e+00 , -9.1608100000000003e-01 , 3.8557999999999998e-01 , -1.1010300000000001e-01 --4.9888448324830472e+00 , 9.4643646743436793e-01 , 6.6585760000000001e+00 , -5.6607600000000002e-01 , 1.1416600000000000e-01 , 8.1640900000000005e-01 --6.0964584292136319e+00 , 7.6396979008283772e-01 , 7.3717248000000000e+00 , 6.0853299999999999e-01 , 7.4866100000000002e-01 , -2.6304899999999998e-01 --5.9658002556244067e+00 , 8.2292147073002297e-01 , 7.4866551999999995e+00 , 1.8944300000000000e-01 , -7.6627299999999998e-01 , 6.1395200000000005e-01 --4.1394404429475005e+00 , 1.1943335462007556e+00 , 6.6736143999999999e+00 , 6.9128299999999998e-01 , -5.7147199999999998e-01 , -4.4220599999999999e-01 --4.1275578841193310e+00 , 1.2240266105991209e+00 , 6.8129847999999997e+00 , 8.7881699999999996e-01 , -2.2381200000000001e-01 , 4.2141200000000001e-01 --4.2722439343006826e+00 , 1.2274189915967606e+00 , 7.0466624000000007e+00 , -9.4070500000000001e-01 , 1.1137500000000000e-01 , -3.2042300000000001e-01 --4.4203868982713939e+00 , 1.2311134104942165e+00 , 7.2916239999999997e+00 , -7.1092299999999997e-01 , -1.2460800000000000e-01 , -6.9214299999999995e-01 --4.3099891431827890e+00 , 1.2807096412235579e+00 , 7.3821560000000002e+00 , 7.4497500000000005e-01 , -6.6679600000000006e-01 , 1.9887999999999999e-02 --4.2154030726127028e+00 , 1.3263822846487523e+00 , 7.4814759999999998e+00 , 1.3154700000000000e-01 , 2.0899499999999999e-01 , -9.6902900000000003e-01 --4.1194583454262323e+00 , 1.3725765287614053e+00 , 7.5783832000000002e+00 , -5.0450600000000001e-01 , -7.5331899999999996e-01 , -4.2188199999999998e-01 --4.3926425131868596e+00 , 1.3618505270483745e+00 , 7.9359040000000007e+00 , 5.3645699999999996e-01 , -8.2774599999999998e-01 , 1.6446800000000000e-01 --4.2986660230961276e+00 , 1.4096927527266283e+00 , 8.0405800000000003e+00 , 7.3834400000000000e-01 , 6.2439900000000004e-01 , 2.5490000000000002e-01 --4.1861385422142581e+00 , 1.4591476779518269e+00 , 8.1308623999999998e+00 , 7.4226000000000003e-01 , 6.6875300000000004e-01 , -4.2662699999999998e-02 --5.3390784128397231e+00 , 1.3346001877058340e+00 , 9.2166744000000005e+00 , -9.6434799999999998e-01 , -2.3893800000000001e-01 , -1.1376000000000000e-01 --4.5343420932731178e+00 , 1.4815903099402787e+00 , 8.7740504000000001e+00 , 8.0497200000000002e-01 , -5.4085399999999995e-01 , -2.4391900000000000e-01 --4.4502231930315546e+00 , 1.5297964284697700e+00 , 8.8995056000000012e+00 , 7.6753499999999997e-01 , -6.3127299999999997e-01 , -1.1128399999999999e-01 --4.6916776033454797e+00 , 1.5388516641915766e+00 , 9.3092864000000013e+00 , -9.7946400000000000e-01 , 1.7528700000000000e-01 , 9.9622900000000000e-02 --4.3364938774725061e+00 , 1.6197031031856688e+00 , 9.2013655999999990e+00 , -7.8033900000000000e-01 , 5.8854499999999998e-01 , -2.1139100000000000e-01 --4.9648172419780057e+00 , 1.5909856844045864e+00 , 9.9946256000000009e+00 , -7.1952199999999999e-01 , -6.9438900000000003e-01 , -1.0602500000000001e-02 --5.3673817329664297e+00 , 1.5934219086647123e+00 , 1.0616504000000001e+01 , -2.3877000000000001e-01 , 6.0563400000000001e-01 , 7.5907599999999997e-01 --5.2521799128681588e+00 , 1.6536070734677220e+00 , 1.0755343999999999e+01 , 3.0300100000000002e-01 , -5.8212699999999995e-01 , -7.5453199999999998e-01 --5.0111201410515900e+00 , 1.7249687392256345e+00 , 1.0765712800000001e+01 , -5.7095099999999999e-01 , 3.4098099999999998e-01 , 7.4682499999999996e-01 --4.8992834176275064e+00 , 1.7834848934315022e+00 , 1.0906091999999999e+01 , -6.4437599999999995e-01 , 3.7705400000000000e-01 , 6.6528900000000002e-01 --4.7985095000439975e+00 , 1.8419763143859655e+00 , 1.1059835200000000e+01 , 7.7652800000000000e-01 , -1.8528400000000000e-01 , -6.0222500000000001e-01 --5.2033150863823829e+00 , 1.8651526429881333e+00 , 1.1789405600000002e+01 , -8.6252600000000001e-01 , 2.5627400000000000e-01 , -4.3631799999999998e-01 --5.2614447409482281e+00 , 1.9178660214423302e+00 , 1.2154580800000002e+01 , 9.0293500000000004e-01 , -3.8618999999999998e-01 , 1.8858700000000000e-01 --4.0766281423769959e+00 , 2.0422578979835748e+00 , 1.1022104000000001e+01 , 2.5305499999999997e-01 , -9.6723400000000004e-01 , 2.0549899999999999e-02 --3.9129031177816929e+00 , 2.1029304506602826e+00 , 1.1089381599999999e+01 , -2.5305600000000000e-01 , 9.6723400000000004e-01 , -2.0549899999999999e-02 --5.7501789080234307e+00 , 2.0837538435213157e+00 , 1.3759072000000002e+01 , -9.6858599999999995e-01 , -1.4715800000000001e-01 , -2.0046400000000000e-01 --4.0745282225575696e+00 , 2.2062708265943156e+00 , 1.1873500000000000e+01 , -9.3993300000000002e-02 , 9.9543599999999999e-01 , -1.6508200000000001e-02 --1.7547259097917567e+00 , 2.3152805362094981e+00 , 8.9463056000000005e+00 , 3.4393000000000001e-01 , -7.8286699999999998e-01 , 5.1848899999999998e-01 --1.7161939031514666e+00 , 2.3553716166134073e+00 , 9.1007871999999992e+00 , -9.5522300000000004e-01 , -7.4408299999999997e-02 , 2.8637800000000002e-01 --2.0383948883139595e+00 , 2.3964812175397077e+00 , 9.8000416000000001e+00 , 4.8198999999999997e-01 , 5.3678899999999996e-01 , 6.9249099999999997e-01 --1.0423333249587330e+00 , 2.4348512681798353e+00 , 8.5006968000000001e+00 , -1.7216300000000001e-01 , 8.2448699999999997e-01 , 5.3905599999999998e-01 --1.8027015830362338e+00 , 2.4882964403693730e+00 , 9.9265679999999996e+00 , 1.2870599999999999e-01 , 6.3807100000000005e-01 , 7.5914400000000004e-01 --1.2836328434366142e+00 , 2.5215601388465734e+00 , 9.3170344000000007e+00 , -8.9806299999999994e-01 , -3.7598999999999999e-01 , -2.2828799999999999e-01 --1.1431670179647950e+00 , 2.5616535900819111e+00 , 9.3140807999999993e+00 , -8.8058999999999998e-01 , -4.3285899999999999e-01 , 1.9285700000000000e-01 -4.5807353259620887e-01 , 2.5178705529410599e+00 , 6.6715447999999995e+00 , 6.2022500000000001e-02 , 6.1539699999999997e-01 , 7.8577399999999997e-01 -5.3767697196769881e-01 , 2.5399823181199652e+00 , 6.6665320000000001e+00 , -1.2819500000000000e-01 , -1.6630000000000000e-01 , -9.7770699999999999e-01 -6.2171321494316545e-01 , 2.5607992550666427e+00 , 6.6507551999999999e+00 , 2.1229300000000001e-01 , 3.7889400000000001e-01 , 9.0076199999999995e-01 --1.0423560431713876e+00 , 2.7562771526149272e+00 , 1.0185652800000000e+01 , 2.0707500000000000e-02 , 2.2008200000000000e-01 , 9.7526100000000004e-01 --4.2339458620973947e-01 , 2.7423432609118015e+00 , 9.1787039999999998e+00 , -6.7527899999999996e-01 , 2.0485099999999999e-02 , -7.3727799999999999e-01 --2.0126577069813623e-01 , 2.7648639586144066e+00 , 8.9584320000000002e+00 , 4.1382500000000000e-01 , 3.3418900000000001e-01 , 8.4679800000000005e-01 --5.7124430330267240e-01 , 2.8731584509668542e+00 , 1.0086312000000000e+01 , 2.5161099999999997e-01 , 9.6268600000000004e-01 , 9.9639099999999994e-02 --4.2653582069655549e-01 , 2.9115863886715383e+00 , 1.0065501599999999e+01 , 4.7038099999999999e-01 , -3.4702400000000000e-01 , 8.1136699999999995e-01 --2.0698382278548255e-01 , 2.9328419329077242e+00 , 9.8489216000000006e+00 , -5.4749700000000001e-01 , -1.5634700000000001e-01 , 8.2207200000000002e-01 -7.8811843742289422e-01 , 2.7762408780795789e+00 , 7.5289624000000002e+00 , -8.6472099999999996e-01 , -4.3652900000000000e-01 , 2.4839600000000001e-01 -1.2239775454414492e+00 , 2.7128979133334861e+00 , 6.5381128000000004e+00 , 3.4505900000000000e-01 , -8.4600699999999995e-01 , 4.0645700000000001e-01 -1.2360263462278940e+00 , 2.7458749864424536e+00 , 6.6938215999999997e+00 , -5.8138800000000002e-01 , 7.1081399999999995e-01 , -3.9589400000000002e-01 -2.8099522619048889e-01 , 3.0842978385146917e+00 , 9.9089504000000002e+00 , 6.9390700000000005e-01 , -6.1420799999999998e-01 , 3.7582300000000002e-01 -5.5023995333722042e-01 , 3.0696999218413432e+00 , 9.4249136000000000e+00 , 5.3477300000000005e-01 , -6.5473499999999996e-01 , 5.3417199999999998e-01 -8.3655154305929869e-01 , 3.0353754495742216e+00 , 8.8149432000000001e+00 , -6.0543199999999997e-01 , -3.0046899999999999e-01 , -7.3700100000000002e-01 -9.5399293000671248e-01 , 3.0591183281485952e+00 , 8.7576080000000012e+00 , -3.0311800000000000e-01 , -7.4253400000000003e-01 , -5.9729600000000005e-01 -1.0483107190709235e+00 , 3.0920536947504806e+00 , 8.7883296000000009e+00 , 3.0375200000000002e-01 , 1.6181599999999999e-01 , 9.3890899999999999e-01 -1.2663818960146600e+00 , 3.0565557541028889e+00 , 8.2739352000000004e+00 , -5.4800400000000005e-01 , -5.5681400000000003e-01 , -6.2421899999999997e-01 -1.3427991322285497e+00 , 3.0910090881347445e+00 , 8.3400688000000009e+00 , -8.0692100000000000e-01 , 2.5214100000000000e-02 , -5.9012200000000004e-01 -1.3187880152097642e+00 , 3.1993773662206850e+00 , 8.9412927999999994e+00 , -4.5286800000000002e-02 , 6.5355200000000002e-01 , 7.5552600000000003e-01 -1.4113183346989973e+00 , 3.2361313352525869e+00 , 8.9959239999999987e+00 , 4.9762099999999998e-01 , 7.2010900000000000e-01 , -4.8354500000000000e-01 -1.5214088596054594e+00 , 3.2587343006132037e+00 , 8.9471480000000003e+00 , 6.3659399999999999e-01 , 6.6465700000000003e-02 , 7.6832900000000004e-01 -1.6367203269308404e+00 , 3.2725905552326013e+00 , 8.8455295999999990e+00 , 2.5295300000000000e-02 , 1.6068099999999999e-01 , 9.8668199999999995e-01 --7.6106512742635157e-01 , 1.1586565037615801e+00 , 8.0343840000000011e-01 , -4.2852399999999999e-02 , 1.4684800000000001e-01 , 9.8823000000000005e-01 --8.9239660782742103e-01 , 1.1245414976185779e+00 , 8.0109839999999988e-01 , -5.5949499999999999e-02 , 1.2981899999999999e-01 , 9.8995800000000000e-01 --1.0408188744201707e+00 , 1.0844895325107275e+00 , 7.9198799999999991e-01 , -1.0470800000000000e-01 , 1.3692799999999999e-01 , 9.8503200000000002e-01 --1.2339966588977234e+00 , 1.0291850232129849e+00 , 7.6086079999999989e-01 , -8.7045499999999998e-02 , 1.5529999999999999e-01 , 9.8402500000000004e-01 --1.3867641945819886e+00 , 9.9025780648691497e-01 , 7.6168239999999998e-01 , -6.8444699999999997e-02 , 1.6425799999999999e-01 , 9.8404000000000003e-01 --1.5834437351804800e+00 , 9.3641881849896857e-01 , 7.4234880000000003e-01 , -7.5490000000000002e-02 , 1.6144900000000001e-01 , 9.8399000000000003e-01 --1.7740521701037650e+00 , 8.8665651529143763e-01 , 7.3400799999999999e-01 , -9.7822699999999999e-02 , 1.5766900000000000e-01 , 9.8263500000000004e-01 --2.0268426447862344e+00 , 8.1516231681476814e-01 , 6.9941760000000008e-01 , -1.0371800000000000e-01 , 1.5640100000000001e-01 , 9.8223300000000002e-01 --2.2658685386375215e+00 , 7.5078041072721247e-01 , 6.8196640000000008e-01 , -8.1607899999999997e-02 , 1.5937000000000001e-01 , 9.8384000000000005e-01 --2.5247722444237999e+00 , 6.8175148198041446e-01 , 6.6356879999999996e-01 , -8.4732399999999999e-02 , 1.5624499999999999e-01 , 9.8407699999999998e-01 --2.8216768277552537e+00 , 6.0105386748298595e-01 , 6.3711119999999988e-01 , -9.8357600000000003e-02 , 1.5172200000000000e-01 , 9.8351699999999997e-01 --3.1578925981860930e+00 , 5.0808450787586734e-01 , 6.0460079999999983e-01 , -9.5034599999999997e-02 , 1.6585200000000000e-01 , 9.8156100000000002e-01 --3.5155450514916096e+00 , 4.1140534780887883e-01 , 5.7545999999999986e-01 , -9.8499299999999998e-02 , 1.7415600000000001e-01 , 9.7977899999999996e-01 --3.9139223227767417e+00 , 3.0424562186300297e-01 , 5.4357359999999999e-01 , -7.9440800000000006e-02 , 1.6888900000000001e-01 , 9.8242799999999997e-01 --4.3331052139132149e+00 , 1.9188576085705011e-01 , 5.1833280000000004e-01 , -8.4252400000000005e-02 , 1.6331300000000001e-01 , 9.8297000000000001e-01 --4.8601017282487575e+00 , 4.8747765943099708e-02 , 4.7015999999999991e-01 , -9.8975099999999996e-02 , 1.6031000000000001e-01 , 9.8209199999999996e-01 --5.4946262571427962e+00 , -1.2605383162365369e-01 , 4.0527439999999992e-01 , 9.9476800000000004e-02 , -1.5129000000000001e-01 , -9.8347099999999998e-01 --6.1724268222372576e+00 , -3.0974358163673266e-01 , 3.5026880000000005e-01 , -8.1730800000000006e-02 , 2.8675899999999999e-01 , 9.5450999999999997e-01 --7.0462941056718353e+00 , -5.5013842187564777e-01 , 2.6184799999999986e-01 , -6.1610400000000003e-02 , 1.8344400000000000e-01 , 9.8109800000000003e-01 --7.9666676326377814e+00 , -7.9735859871047365e-01 , 1.9286479999999995e-01 , -3.5542200000000002e-01 , 4.7684700000000002e-01 , 8.0392300000000005e-01 --9.0952755451094109e+00 , -1.1033439526456097e+00 , 1.0399680000000000e-01 , -8.5244500000000001e-02 , 1.6531599999999999e-01 , 9.8255000000000003e-01 --1.0396483488876369e+01 , -1.4529177052451980e+00 , 1.4889599999999836e-02 , -8.5103799999999993e-02 , 1.8178400000000000e-01 , 9.7964899999999999e-01 --1.1931014676986862e+01 , -1.8622877350954070e+00 , -7.8127999999999975e-02 , 6.5263399999999999e-02 , -1.9229399999999999e-01 , -9.7916499999999995e-01 --1.3807160141785211e+01 , -2.3615521881731443e+00 , -1.8431199999999981e-01 , 2.1663600000000000e-01 , 1.9694800000000001e-01 , 9.5618000000000003e-01 --1.5881832916106529e+01 , -2.9053832540861864e+00 , -2.5893200000000016e-01 , -6.7730799999999999e-03 , 1.1790800000000000e-01 , 9.9300200000000005e-01 --5.8030459115548290e+01 , -1.3678803345843106e+01 , -2.4091920000000000e-01 , -1.2227600000000000e-02 , 4.9709799999999998e-01 , 8.6760800000000005e-01 --8.8968987619419053e+00 , -4.5095333412344285e-02 , 5.4884616000000008e+00 , -4.6020200000000000e-01 , 3.6375400000000002e-01 , 8.0987500000000001e-01 --8.6644715709505320e+00 , 4.2678044884376654e-02 , 5.6416224000000001e+00 , 5.4559999999999997e-01 , -8.1844300000000003e-01 , -1.8019800000000000e-01 --8.5679015948310511e+00 , 1.0128293339824257e-01 , 5.8213448000000003e+00 , -8.5396300000000003e-01 , 2.9204200000000002e-01 , -4.3064999999999998e-01 --8.8930050759313861e+00 , 7.1802067829915162e-02 , 6.1116295999999997e+00 , -6.6141899999999998e-01 , -7.4135600000000001e-01 , 1.1364800000000000e-01 --8.8579505486124273e+00 , 1.1821199600436927e-01 , 6.3126096000000000e+00 , 7.6354200000000005e-01 , -6.3229100000000005e-01 , 1.3119300000000000e-01 --8.7114675787178637e+00 , 1.8709498327093566e-01 , 6.4801640000000003e+00 , -9.5851399999999998e-01 , 8.7639599999999998e-02 , 2.7123799999999998e-01 --6.3638553447690285e+00 , 6.8501437213511052e-01 , 5.9319591999999997e+00 , 9.2181100000000005e-01 , -3.2519199999999998e-01 , -2.1098700000000001e-01 --8.2954527436032937e+00 , 3.4602119544328880e-01 , 6.7622432000000003e+00 , -9.0032400000000001e-01 , -2.9763499999999998e-02 , 4.3420199999999998e-01 --8.4707539216659544e+00 , 3.5282056236118109e-01 , 7.0326535999999997e+00 , -9.2521399999999998e-01 , 1.1216600000000000e-02 , 3.7928000000000001e-01 --8.4951103941284209e+00 , 3.8712361551641195e-01 , 7.2556295999999998e+00 , -9.5621800000000001e-01 , 7.0362200000000000e-02 , 2.8407100000000002e-01 --8.2025220355112030e+00 , 4.8136628789521674e-01 , 7.3537223999999997e+00 , -9.5621800000000001e-01 , 7.0362200000000000e-02 , 2.8407100000000002e-01 --6.6033159957236620e+00 , 8.0400697463765636e-01 , 6.8930960000000008e+00 , -4.3416100000000002e-01 , -7.4009700000000000e-01 , 5.1357500000000000e-01 --6.8996864592809644e+00 , 7.8668565989621908e-01 , 7.2076647999999999e+00 , 7.6784500000000000e-01 , -5.2256700000000000e-01 , -3.7059199999999998e-01 --5.2205755690233291e+00 , 1.1065515179777150e+00 , 6.6238399999999995e+00 , 1.8544099999999999e-03 , -3.3471299999999998e-01 , 9.4231799999999999e-01 --5.0072539638188038e+00 , 1.1714202340297888e+00 , 6.6803848000000006e+00 , 7.1631100000000003e-02 , -3.0112299999999997e-01 , 9.5089100000000004e-01 --5.0047818952893639e+00 , 1.2017842979344799e+00 , 6.8368944000000003e+00 , 7.1631100000000003e-02 , -3.0112299999999997e-01 , 9.5089100000000004e-01 --6.2770358939066693e+00 , 1.0314752859954168e+00 , 7.6648488000000006e+00 , -1.2862299999999999e-01 , 3.3867300000000000e-01 , 9.3207099999999998e-01 --6.1402259238239960e+00 , 1.0881902342031711e+00 , 7.7805384000000002e+00 , -4.0082899999999999e-01 , -4.1223100000000001e-01 , 8.1816999999999995e-01 --5.4283026350369878e+00 , 1.2299160786521122e+00 , 7.5660176000000003e+00 , -3.1210399999999999e-01 , 6.4390199999999997e-01 , -6.9855599999999995e-01 --5.5065986202653479e+00 , 1.2520275856667429e+00 , 7.7908240000000006e+00 , 3.2933299999999999e-01 , -9.4092100000000001e-01 , 7.8783800000000001e-02 --4.7009120423427007e+00 , 1.3997218102624753e+00 , 7.4783664000000005e+00 , 3.8887400000000000e-01 , -2.3604500000000000e-01 , 8.9053899999999997e-01 --4.4468430305270150e+00 , 1.4653799216684624e+00 , 7.4842736000000007e+00 , 1.7972099999999999e-01 , 2.9256500000000002e-01 , 9.3920499999999996e-01 --4.5047281287411574e+00 , 1.4887234850467617e+00 , 7.6879263999999994e+00 , 7.1201599999999998e-01 , 6.9168499999999999e-01 , -1.2085000000000000e-01 --5.2650404603028660e+00 , 1.4242138042393027e+00 , 8.3807744000000000e+00 , 3.3350000000000002e-01 , 9.4220199999999998e-01 , 3.2137100000000002e-02 --4.5126702100036766e+00 , 1.5522449574018160e+00 , 8.0384063999999995e+00 , -5.5733999999999995e-01 , -7.8805199999999997e-01 , -2.6143100000000002e-01 --4.6904700882660970e+00 , 1.5648272629808146e+00 , 8.3475152000000001e+00 , -6.9055500000000003e-01 , -6.7694699999999997e-01 , -2.5470900000000002e-01 --4.8272303164109998e+00 , 1.5837719524691238e+00 , 8.6389855999999998e+00 , 6.1104899999999995e-01 , 6.7614600000000002e-01 , -4.1163699999999998e-01 --5.9789420899907295e+00 , 1.4964057579045869e+00 , 9.7462319999999991e+00 , -9.4463500000000000e-01 , -3.0757699999999999e-01 , 1.1428800000000000e-01 --5.5967043188334271e+00 , 1.5795345208299301e+00 , 9.6659439999999996e+00 , -7.6779600000000003e-01 , -1.5362500000000001e-01 , -6.2200400000000000e-01 --4.6739089387147263e+00 , 1.7117858837061697e+00 , 9.1121024000000013e+00 , -7.5406499999999999e-01 , 4.3930599999999997e-01 , -4.8825800000000003e-01 --4.4101091761082314e+00 , 1.7744078766284404e+00 , 9.0892119999999998e+00 , -7.5406499999999999e-01 , 4.3930599999999997e-01 , -4.8825800000000003e-01 --4.5116954160853400e+00 , 1.8046233031671042e+00 , 9.3861424000000007e+00 , -8.4129600000000004e-01 , -5.0442500000000001e-02 , -5.3821600000000003e-01 --5.9382654706110873e+00 , 1.7303372090271834e+00 , 1.0937094400000001e+01 , 3.1998700000000002e-01 , 7.8776800000000002e-01 , 5.2633600000000003e-01 --5.2638505692235569e+00 , 1.8305866812143610e+00 , 1.0550859200000001e+01 , 4.6579100000000001e-01 , -3.9789400000000003e-01 , -7.9039199999999998e-01 --5.0889120416136953e+00 , 1.8898076785657536e+00 , 1.0629171200000002e+01 , -4.1778199999999999e-01 , 3.6464400000000002e-01 , 8.3216199999999996e-01 --4.9268497848857207e+00 , 1.9475327366081350e+00 , 1.0718340800000000e+01 , 6.9691999999999998e-01 , -1.6016600000000000e-01 , -6.9903499999999996e-01 -3.7792134131757327e-01 , 2.2902243631337127e+00 , 5.2979231999999996e+00 , -2.6828800000000003e-01 , 3.2523999999999997e-01 , 9.0677500000000000e-01 --4.7346283516087038e+00 , 2.0556108059031080e+00 , 1.1032327199999999e+01 , -9.2530400000000002e-01 , -1.5274199999999999e-01 , 3.4710600000000003e-01 --5.2375429227595243e+00 , 2.0856192761104713e+00 , 1.1880301599999999e+01 , -8.6252600000000001e-01 , 2.5627400000000000e-01 , -4.3631799999999998e-01 --4.1189263641128235e+00 , 2.1795708557321669e+00 , 1.0856629600000002e+01 , -1.6470199999999999e-01 , 7.0781700000000003e-01 , 6.8692699999999995e-01 --4.0021586812332854e+00 , 2.2337065222427359e+00 , 1.0981606400000000e+01 , 2.2390199999999999e-01 , -9.7276899999999999e-01 , -5.9900700000000001e-02 --5.6677683504216683e+00 , 2.2537215315289090e+00 , 1.3365952000000002e+01 , -9.6858599999999995e-01 , -1.4715800000000001e-01 , -2.0046400000000000e-01 --5.6848020691667740e+00 , 2.3198483885825496e+00 , 1.3748568000000001e+01 , -9.6858599999999995e-01 , -1.4715800000000001e-01 , -2.0046400000000000e-01 --5.1116796091375596e+00 , 2.3915425542507576e+00 , 1.3346503999999999e+01 , -9.7885000000000000e-01 , -5.9080399999999998e-02 , -1.9586100000000001e-01 --1.7146515146464658e+00 , 2.4358649494907305e+00 , 8.9367064000000003e+00 , -9.1492799999999996e-01 , 3.9341399999999999e-01 , 9.0181300000000006e-02 --1.9283807565952431e+00 , 2.4781748858442771e+00 , 9.4595143999999998e+00 , -6.1770400000000003e-01 , 6.4108600000000004e-01 , -4.5546599999999998e-01 --2.0171320158843731e+00 , 2.5249568573413566e+00 , 9.8256152000000014e+00 , 2.4913399999999999e-01 , -1.5020800000000001e-01 , 9.5674999999999999e-01 --1.6578154992321643e+00 , 2.5579900947140848e+00 , 9.5128664000000001e+00 , -2.5923299999999999e-01 , 9.3892299999999995e-01 , -2.2632200000000000e-01 --1.5878213746635770e+00 , 2.6000232451336887e+00 , 9.6415767999999993e+00 , -2.5368400000000002e-01 , -8.8984099999999999e-01 , -3.7924600000000003e-01 --1.2646196499719502e+00 , 2.6281020215948860e+00 , 9.3492224000000004e+00 , -7.2572199999999998e-01 , -6.8320300000000000e-01 , -8.0994200000000002e-02 -4.0085114822705137e-01 , 2.5536493336725887e+00 , 6.6735520000000008e+00 , -1.1140400000000000e-01 , 5.8830199999999999e-01 , 8.0093099999999995e-01 -4.7068668241252953e-01 , 2.5737980248827723e+00 , 6.6883096000000002e+00 , -1.3970900000000000e-01 , -4.7124300000000002e-01 , -8.7086799999999998e-01 -5.5130562002429961e-01 , 2.5937269876964630e+00 , 6.6832240000000001e+00 , 8.5403999999999994e-02 , 4.6709400000000001e-01 , 8.8007400000000002e-01 --3.6247954808398930e-01 , 2.7259341204474614e+00 , 8.6412008000000000e+00 , -5.0264299999999995e-01 , -4.5809599999999999e-02 , 8.6328000000000005e-01 --1.0162671267562078e+00 , 2.8548727682089372e+00 , 1.0227377600000001e+01 , -3.8928200000000002e-01 , -7.4430700000000005e-01 , -5.4264800000000002e-01 --2.8395467614351544e-01 , 2.8067095346377471e+00 , 8.9639856000000009e+00 , -5.8050100000000004e-01 , -3.6345800000000000e-01 , -7.2864099999999998e-01 --1.8379159066663986e-01 , 2.8397368145123014e+00 , 9.0070312000000001e+00 , 4.4374400000000003e-01 , 4.0846800000000000e-01 , 7.9764999999999997e-01 --5.0883464157453506e-01 , 2.9524498863526487e+00 , 1.0050463199999999e+01 , 2.3320500000000000e-01 , 9.6902699999999997e-01 , 8.1254499999999993e-02 -8.4257527698090828e-01 , 2.7367933782852760e+00 , 7.0496575999999997e+00 , -2.5397599999999998e-01 , -1.4733299999999999e-01 , 9.5592299999999997e-01 --1.6400760361888356e-01 , 3.0042995851584413e+00 , 9.8596544000000002e+00 , 4.0674500000000002e-01 , 1.1492900000000000e-01 , -9.0628399999999998e-01 -1.1849528595166601e+00 , 2.7275122998319867e+00 , 6.5338072000000000e+00 , 4.9252200000000002e-01 , -5.0704700000000003e-01 , 7.0733699999999999e-01 -1.2427012333360759e+00 , 2.7458581052983977e+00 , 6.5528599999999999e+00 , 3.4505900000000000e-01 , -8.4600699999999995e-01 , 4.0645700000000001e-01 -1.3081854403036688e+00 , 2.7628793403380025e+00 , 6.5511856000000002e+00 , 1.5330999999999999e-02 , -4.6100000000000002e-01 , 8.8726799999999995e-01 -2.6020195068302665e-01 , 3.1647309597456292e+00 , 1.0135108799999999e+01 , -4.5945000000000003e-01 , -3.6519700000000002e-02 , -8.8745300000000005e-01 -7.2843939721506024e-01 , 3.0672180131713267e+00 , 8.9762888000000007e+00 , -8.0201500000000003e-01 , -2.4984000000000001e-01 , -5.4254199999999997e-01 -8.8615741835897421e-01 , 3.0732014165926529e+00 , 8.7919280000000004e+00 , -4.3729200000000001e-01 , 6.9928100000000007e-02 , -8.9659699999999998e-01 -1.0113690069378336e+00 , 3.0893934823864928e+00 , 8.7040272000000005e+00 , 2.9537600000000003e-01 , 1.1823500000000001e-01 , 9.4803700000000002e-01 -1.2007784680151676e+00 , 3.0680033548222112e+00 , 8.3325703999999998e+00 , -9.6557899999999997e-01 , 1.3300699999999999e-01 , 2.2353100000000001e-01 -1.2858137914599308e+00 , 3.0963086877760366e+00 , 8.3700000000000010e+00 , 6.1913999999999997e-02 , -3.8938800000000001e-01 , 9.1899100000000000e-01 -1.3993178187612489e+00 , 3.1082598851858054e+00 , 8.2743304000000002e+00 , 8.5694199999999998e-01 , -5.1511700000000005e-01 , -1.7488400000000001e-02 -1.3680287822972583e+00 , 3.2238967517281871e+00 , 8.9364775999999999e+00 , -3.2076100000000002e-01 , -8.2076800000000005e-01 , 4.7270800000000002e-01 -1.4662651147042354e+00 , 3.2531377717435621e+00 , 8.9602936000000000e+00 , -4.3677600000000000e-01 , 8.8993000000000000e-01 , 1.3134399999999999e-01 -1.5834135378096910e+00 , 3.2640662117742885e+00 , 8.8603495999999993e+00 , 2.6639499999999999e-01 , -4.8452499999999998e-01 , 8.3322799999999997e-01 -1.6810898533077105e+00 , 3.2935969486536836e+00 , 8.8802032000000004e+00 , 6.7754199999999998e-01 , 7.0386199999999999e-01 , -2.1334100000000000e-01 --7.1547596744845254e-01 , 1.2752260210651531e+00 , 7.9093759999999991e-01 , -8.4970800000000006e-03 , 1.7017099999999999e-01 , 9.8537799999999998e-01 --8.4640685904583846e-01 , 1.2447884637720958e+00 , 7.8585199999999977e-01 , -4.3096099999999998e-02 , 1.5844600000000000e-01 , 9.8642700000000005e-01 --9.9643189313748959e-01 , 1.2094499531968430e+00 , 7.7343439999999997e-01 , -8.2988999999999993e-02 , 1.4942500000000000e-01 , 9.8528400000000005e-01 --1.1636656193944059e+00 , 1.1683373457548281e+00 , 7.5505760000000000e-01 , -1.0952000000000001e-01 , 1.4866399999999999e-01 , 9.8280400000000001e-01 --1.3336163915078441e+00 , 1.1273318803379770e+00 , 7.4188079999999990e-01 , -7.3191099999999995e-02 , 1.5990599999999999e-01 , 9.8441500000000004e-01 --1.5140866453547508e+00 , 1.0846683455276378e+00 , 7.2877680000000011e-01 , -6.7478499999999997e-02 , 1.6811300000000001e-01 , 9.8345499999999997e-01 --1.7041444992445012e+00 , 1.0394140050089402e+00 , 7.1657759999999993e-01 , -9.0320499999999998e-02 , 1.6894899999999999e-01 , 9.8147799999999996e-01 --1.9326004783071555e+00 , 9.8356074185912257e-01 , 6.9102480000000011e-01 , -1.0826700000000000e-01 , 1.5927900000000000e-01 , 9.8127900000000001e-01 --2.1708444783520608e+00 , 9.2657651515701933e-01 , 6.6830079999999992e-01 , -9.0196600000000002e-02 , 1.6847100000000001e-01 , 9.8157099999999997e-01 --2.4300031153047508e+00 , 8.6388298559243459e-01 , 6.4439120000000005e-01 , -7.6682799999999995e-02 , 1.6255900000000001e-01 , 9.8371500000000001e-01 --2.6922836187157255e+00 , 8.0198493349594013e-01 , 6.2904079999999984e-01 , -8.7407399999999996e-02 , 1.5473400000000001e-01 , 9.8408200000000001e-01 --3.0194863023660909e+00 , 7.2176930327994770e-01 , 5.9324400000000010e-01 , -9.6683500000000006e-02 , 1.5006700000000001e-01 , 9.8393699999999995e-01 --3.3600865327362959e+00 , 6.4027359508814130e-01 , 5.6404079999999990e-01 , -9.6710299999999999e-02 , 1.5868399999999999e-01 , 9.8258199999999996e-01 --3.7492370198539193e+00 , 5.4659323813069505e-01 , 5.2725599999999995e-01 , -8.6348900000000006e-02 , 1.6552500000000001e-01 , 9.8241800000000001e-01 --4.1611962687661954e+00 , 4.4764838021110753e-01 , 4.9634719999999977e-01 , -7.9458699999999993e-02 , 1.6965600000000000e-01 , 9.8229500000000003e-01 --4.6423501099834761e+00 , 3.3251233313493733e-01 , 4.5464320000000003e-01 , -8.9957200000000001e-02 , 1.7237200000000000e-01 , 9.8091600000000001e-01 --5.1932083073896917e+00 , 1.9987841582700172e-01 , 4.0609600000000001e-01 , -9.1665999999999997e-02 , 1.6269800000000001e-01 , 9.8240899999999998e-01 --5.8446161447467979e+00 , 4.2458294979470734e-02 , 3.4481919999999988e-01 , 9.3577400000000005e-02 , -1.5032499999999999e-01 , -9.8419800000000002e-01 --6.5870282446251558e+00 , -1.3637310180486129e-01 , 2.7906000000000009e-01 , 9.3939800000000004e-02 , -1.5130600000000000e-01 , -9.8401300000000003e-01 --7.4708909807859385e+00 , -3.4907866999894743e-01 , 1.9944799999999985e-01 , -6.5033300000000002e-02 , 2.1242500000000000e-01 , 9.7501099999999996e-01 --8.2830634221533135e+00 , -5.3644193650388150e-01 , 1.7137840000000004e-01 , -1.0116500000000000e-01 , 1.9341100000000000e-01 , 9.7588799999999998e-01 --9.5582635950364647e+00 , -8.4366062121778418e-01 , 5.5647199999999897e-02 , -8.9072299999999993e-02 , 1.6606799999999999e-01 , 9.8208300000000004e-01 --1.1332374472551930e+01 , -1.2762046038174084e+00 , -1.2978480000000037e-01 , -8.7376200000000001e-02 , 1.6204499999999999e-01 , 9.8290699999999998e-01 --1.3157996867454518e+01 , -1.7106174377062726e+00 , -2.6180240000000010e-01 , -8.6419499999999996e-02 , -2.9900300000000002e-01 , -9.5033100000000004e-01 --1.4094619695640187e+01 , -1.9003964534265223e+00 , -1.5448479999999964e-01 , 7.2253900000000004e-01 , 5.8220200000000000e-01 , 3.7279800000000002e-01 --1.4169318239526220e+01 , -1.8637851342712142e+00 , 1.3776559999999982e-01 , 7.2253800000000001e-01 , 5.8220200000000000e-01 , 3.7279899999999999e-01 --1.4129478781903178e+01 , -1.7985778924061004e+00 , 4.4883999999999991e-01 , 7.2253800000000001e-01 , 5.8220200000000000e-01 , 3.7279899999999999e-01 --5.4791136877667057e+01 , -1.1538520605205443e+01 , -2.8982647999999998e+00 , -1.2227699999999999e-02 , 4.9709700000000001e-01 , 8.6760899999999996e-01 --2.2264410656352133e+01 , -3.2929663601632715e+00 , 2.2579834399999998e+00 , 4.9515600000000000e-02 , 1.8286400000000000e-01 , 9.8189099999999996e-01 --8.2267509220942419e+00 , 3.9275433168030949e-01 , 5.1800600000000001e+00 , 4.9382199999999998e-01 , -6.4292499999999997e-01 , -5.8548000000000000e-01 --8.2459442903331581e+00 , 4.2477728510598523e-01 , 5.3770775999999998e+00 , -2.9471700000000001e-01 , 7.5056900000000004e-01 , 5.9142899999999998e-01 --8.3313403095237657e+00 , 4.4506116220607739e-01 , 5.5912655999999998e+00 , -6.3767300000000005e-01 , 7.6418100000000000e-01 , 9.6956799999999996e-02 --7.9954190499246529e+00 , 5.4147262442787736e-01 , 5.7040639999999998e+00 , 4.2542400000000002e-01 , 6.1626000000000003e-01 , -6.6274999999999995e-01 --7.6787761537134465e+00 , 6.3221677824565714e-01 , 5.8109447999999997e+00 , 8.1295200000000001e-01 , 1.3250799999999999e-01 , -5.6705399999999995e-01 --7.8239793861265223e+00 , 6.4130139676904929e-01 , 6.0411384000000004e+00 , 8.1295200000000001e-01 , 1.3250799999999999e-01 , -5.6705399999999995e-01 --7.5430090471667963e+00 , 7.2386251153802750e-01 , 6.1472080000000000e+00 , -9.1629499999999997e-01 , 7.5977600000000006e-02 , 3.9323200000000003e-01 --8.6182269220563956e+00 , 5.8144849720581582e-01 , 6.6865727999999995e+00 , -8.6992899999999995e-01 , 8.7007600000000001e-03 , 4.9310100000000001e-01 --1.0398817592296844e+01 , 3.3268038043804515e-01 , 7.5120728000000003e+00 , 3.1955499999999998e-01 , 4.4797500000000001e-01 , 8.3498700000000003e-01 --8.6468258994764433e+00 , 6.5447890341780046e-01 , 7.1220208000000005e+00 , 7.8225900000000004e-01 , 4.0992699999999999e-01 , -4.6907399999999999e-01 --6.8723601230488267e+00 , 9.6775020075954865e-01 , 6.6575879999999996e+00 , -5.0591200000000003e-01 , -4.9701600000000001e-01 , 7.0500200000000002e-01 --6.9108075557526938e+00 , 9.9581816562630987e-01 , 6.8572160000000002e+00 , 4.3238799999999999e-01 , 5.6271000000000004e-01 , -7.0455500000000004e-01 --6.8222911865794451e+00 , 1.0433749019561231e+00 , 7.0067367999999997e+00 , 6.9739899999999999e-01 , 4.8064200000000001e-01 , -5.3161899999999995e-01 --6.4293527048964876e+00 , 1.1332877580742049e+00 , 7.0203815999999994e+00 , -7.3384199999999999e-01 , -2.6672699999999999e-01 , 6.2476699999999996e-01 --5.5324629637809979e+00 , 1.2918846617730768e+00 , 6.7867559999999996e+00 , 9.5464999999999994e-03 , -3.1871800000000000e-01 , 9.4780200000000003e-01 --5.1570580830251105e+00 , 1.3734383829631476e+00 , 6.7709792000000002e+00 , 7.1631100000000003e-02 , -3.0112299999999997e-01 , 9.5089100000000004e-01 --5.0329573119882580e+00 , 1.4197192154683758e+00 , 6.8690512000000004e+00 , 7.1413300000000002e-01 , -6.0286300000000004e-01 , 3.5576700000000000e-01 --4.9984038595361246e+00 , 1.4534200190893667e+00 , 7.0120823999999997e+00 , -6.6030999999999995e-01 , 5.0139900000000004e-01 , -5.5909699999999996e-01 --5.3872306428237113e+00 , 1.4356182521222993e+00 , 7.3888640000000008e+00 , 5.3564900000000004e-01 , -8.0864499999999995e-01 , 2.4325400000000000e-01 --5.7120358710101220e+00 , 1.4287462727335456e+00 , 7.7492343999999997e+00 , -4.0551999999999999e-01 , 5.5328699999999997e-01 , -7.2761799999999999e-01 --5.2443435775692722e+00 , 1.5162726886887241e+00 , 7.6562999999999999e+00 , 2.1365400000000001e-01 , -8.7188900000000003e-01 , 4.4063799999999997e-01 --4.8697363608408191e+00 , 1.5902971342710268e+00 , 7.6029688000000002e+00 , 3.7373000000000001e-01 , 8.1097300000000005e-01 , -4.5016400000000001e-01 --4.8031753692986170e+00 , 1.6296882006736588e+00 , 7.7336344000000006e+00 , 3.6870000000000003e-01 , 8.2265500000000003e-01 , -4.3278000000000000e-01 --4.7697648839489410e+00 , 1.6643160918121482e+00 , 7.8862752000000000e+00 , -6.2572499999999998e-01 , -7.6314700000000002e-01 , 1.6147800000000001e-01 --3.1548506798411333e+00 , 1.8552854896603985e+00 , 6.9493912000000000e+00 , -3.4668599999999999e-01 , -3.7217000000000000e-01 , 8.6098699999999995e-01 --5.4695893297509039e+00 , 1.6648644889217439e+00 , 8.7463136000000006e+00 , -8.8373800000000002e-01 , -4.5319500000000001e-01 , 1.1671400000000000e-01 --5.1166749125579640e+00 , 1.7338251826335116e+00 , 8.6895400000000009e+00 , -3.7610900000000003e-01 , -7.8577600000000003e-01 , 4.9101699999999998e-01 --5.8883735116194060e+00 , 1.7056980687472871e+00 , 9.4815000000000005e+00 , -7.1429699999999996e-01 , -3.2084099999999999e-01 , -6.2196499999999999e-01 --5.8796346676186406e+00 , 1.7483344990004202e+00 , 9.7002432000000010e+00 , 9.7155899999999995e-01 , 1.6120200000000001e-01 , 1.7345800000000000e-01 --5.4320869351671908e+00 , 1.8238399903395643e+00 , 9.5644400000000012e+00 , 7.5504000000000002e-02 , -2.1225600000000000e-01 , 9.7429299999999996e-01 --4.7864283094219564e+00 , 1.9091131431930661e+00 , 9.2400224000000009e+00 , 4.4646700000000000e-01 , -1.7661900000000000e-01 , 8.7719599999999998e-01 --5.7288385519457838e+00 , 1.8888059389004166e+00 , 1.0282092000000000e+01 , -8.1738800000000000e-01 , 1.0548100000000001e-01 , 5.6634799999999996e-01 --5.4775584375071249e+00 , 1.9477015828114417e+00 , 1.0301259200000001e+01 , -3.0194199999999999e-01 , 4.8489199999999999e-01 , 8.2079899999999995e-01 --5.4324300131890926e+00 , 1.9955073491934563e+00 , 1.0506014400000000e+01 , -5.8557300000000001e-01 , -2.8928999999999999e-01 , 7.5724199999999997e-01 --5.2405094434578494e+00 , 2.0507320985911246e+00 , 1.0573354400000001e+01 , -6.9594199999999995e-01 , -4.9865500000000001e-01 , 5.1672799999999997e-01 --5.0932557821421955e+00 , 2.1041394767572048e+00 , 1.0680172800000001e+01 , 8.3518400000000004e-01 , 5.4663600000000001e-01 , -6.0470500000000003e-02 -3.4027543640174662e-01 , 2.3345970560164639e+00 , 5.2782256000000007e+00 , -4.0914800000000001e-01 , 2.5134499999999999e-01 , 8.7716799999999995e-01 -3.7708285516243190e-01 , 2.3486459232717958e+00 , 5.3136583999999996e+00 , 3.5243500000000000e-01 , -4.1231999999999998e-02 , -9.3492799999999998e-01 --5.0023684620451316e+00 , 2.2529152093024480e+00 , 1.1385261600000002e+01 , 7.5512299999999999e-01 , 6.4703400000000000e-01 , 1.0552499999999999e-01 -5.0070674753997668e-01 , 2.3789573701067268e+00 , 5.3271055999999994e+00 , -2.4143200000000001e-01 , -3.6207200000000000e-01 , 9.0034099999999995e-01 --2.7022651544527951e+00 , 2.3738277958125371e+00 , 9.2244640000000011e+00 , 3.7854399999999999e-01 , 9.1784800000000000e-01 , -1.1941400000000001e-01 --5.7613249209757340e+00 , 2.4179646374320858e+00 , 1.3212552000000001e+01 , -9.7885000000000000e-01 , -5.9080399999999998e-02 , -1.9586100000000001e-01 --5.8146979747941998e+00 , 2.4831238955470392e+00 , 1.3635208000000000e+01 , -9.6858599999999995e-01 , -1.4715800000000001e-01 , -2.0046400000000000e-01 --5.4291084373753513e+00 , 2.5440642609374553e+00 , 1.3498239999999999e+01 , -9.6858599999999995e-01 , -1.4715800000000001e-01 , -2.0046400000000000e-01 -2.2345701066042567e-01 , 2.4642448211849461e+00 , 6.1286959999999997e+00 , -4.3126999999999999e-01 , -3.1504300000000002e-01 , -8.4543100000000004e-01 --1.4082981951508757e+00 , 2.5419293856436318e+00 , 8.5535704000000017e+00 , -2.2710400000000000e-01 , -9.7376900000000000e-01 , 1.4051900000000001e-02 --1.1400062116005203e+00 , 2.5665813729431544e+00 , 8.3589240000000000e+00 , 1.1299900000000000e-01 , 6.1328499999999997e-01 , 7.8173700000000002e-01 --1.4382114332729583e+00 , 2.6179882562201238e+00 , 9.0089655999999998e+00 , 4.4529200000000002e-01 , -3.0081599999999997e-01 , -8.4334200000000004e-01 --1.3205673057391927e+00 , 2.6512058771707441e+00 , 9.0461248000000012e+00 , 7.1307200000000004e-01 , 6.8872500000000003e-01 , -1.3109499999999999e-01 --1.4405125516681281e+00 , 2.7027323340472580e+00 , 9.4712872000000008e+00 , -2.5572600000000001e-01 , -9.6611499999999995e-01 , 3.5010800000000002e-02 --1.4630854599556251e+00 , 2.7499089814932587e+00 , 9.7586288000000003e+00 , 5.9002100000000002e-01 , 6.4920699999999998e-01 , 4.8000700000000002e-01 -4.5568706073289666e-01 , 2.6060195452495689e+00 , 6.6184215999999996e+00 , -1.1476100000000000e-01 , 7.2354200000000002e-01 , 6.8067400000000000e-01 -5.1074496316130813e-01 , 2.6257809747976437e+00 , 6.6597408000000007e+00 , -1.8571099999999999e-01 , 5.8964799999999995e-01 , 7.8601900000000002e-01 -6.1047127562640324e-01 , 2.6395001241535128e+00 , 6.6173503999999994e+00 , 2.0713000000000001e-01 , 2.7982899999999999e-01 , 9.3744000000000005e-01 -7.0307894208737709e-01 , 2.6538391327882613e+00 , 6.5818031999999995e+00 , 2.0713000000000001e-01 , 2.7982899999999999e-01 , 9.3744000000000005e-01 --7.4506439226310395e-01 , 2.9123313807611320e+00 , 9.7640784000000007e+00 , -1.7174400000000001e-01 , 5.4294600000000004e-01 , 8.2201800000000003e-01 --1.7782657315608441e-01 , 2.8674747933921467e+00 , 8.8244384000000000e+00 , -8.3696899999999996e-01 , -2.9178599999999999e-01 , 4.6297400000000000e-01 -7.3396534624620635e-01 , 2.7386094770927256e+00 , 7.0038664000000006e+00 , -4.6892099999999998e-01 , 7.6988500000000001e-02 , 8.7987800000000005e-01 -7.9696154348139436e-01 , 2.7591884589735014e+00 , 7.0404016000000000e+00 , -3.2431800000000000e-01 , -8.9406399999999997e-02 , 9.4171400000000005e-01 -8.0727691697981108e-01 , 2.7930111288811381e+00 , 7.2104832000000005e+00 , -8.2506599999999997e-01 , 4.7730000000000000e-01 , -3.0241000000000001e-01 -7.6108072032545571e-01 , 2.8435009972678325e+00 , 7.5460912000000002e+00 , -9.3595899999999999e-01 , -5.6938999999999997e-02 , 3.4747400000000001e-01 -1.2046727877980750e+00 , 2.7605152668612685e+00 , 6.5489807999999998e+00 , 4.9252099999999999e-01 , -5.0704600000000000e-01 , 7.0733800000000002e-01 -1.2569269689222313e+00 , 2.7798325087948532e+00 , 6.5875024000000000e+00 , -1.1550500000000000e-02 , -3.6707099999999998e-01 , 9.3012099999999998e-01 -1.3266923697008477e+00 , 2.7936265976771772e+00 , 6.5759792000000008e+00 , 3.0638599999999998e-02 , -3.7457699999999999e-01 , 9.2669000000000001e-01 -4.3752622063919855e-01 , 3.1709322670683449e+00 , 9.7293839999999996e+00 , -7.4327500000000002e-01 , 4.7479500000000002e-01 , -4.7128799999999998e-01 -8.0870266780902256e-01 , 3.0944923339783932e+00 , 8.8547232000000005e+00 , 7.0003899999999997e-01 , -1.2893800000000000e-01 , 7.0236799999999999e-01 -9.4224961932319395e-01 , 3.1046276489780338e+00 , 8.7490696000000003e+00 , 3.7867899999999999e-01 , 1.4112700000000000e-01 , 9.1470499999999999e-01 -1.1019880310863004e+00 , 3.0984141153565004e+00 , 8.5204255999999994e+00 , -9.1231399999999996e-01 , -9.9796200000000002e-02 , -3.9714500000000003e-01 -1.2627526481495526e+00 , 3.0854368325880848e+00 , 8.2478727999999997e+00 , 3.0306300000000003e-01 , -8.8576400000000000e-03 , 9.5293000000000005e-01 -1.3534939845120595e+00 , 3.1062292165253824e+00 , 8.2544871999999998e+00 , -1.3405400000000001e-01 , 7.4632900000000002e-01 , 6.5193800000000002e-01 -1.3203712053783776e+00 , 3.2168252944716267e+00 , 8.8965104000000004e+00 , 1.2099600000000001e-01 , 6.3936099999999996e-01 , 7.5932699999999997e-01 -1.4263774963446119e+00 , 3.2378257033741145e+00 , 8.8810456000000002e+00 , 5.0360499999999997e-01 , -7.8961499999999996e-01 , -3.5055700000000001e-01 -1.5152735464469520e+00 , 3.2732805587582199e+00 , 8.9653376000000016e+00 , -6.1766900000000002e-01 , 9.0539899999999998e-04 , 7.8643799999999997e-01 -1.6348516257296737e+00 , 3.2777615777911620e+00 , 8.8444479999999999e+00 , 6.7125100000000004e-01 , 3.5484199999999999e-01 , 6.5077600000000002e-01 --7.9749727943244686e-01 , 1.3641896596673977e+00 , 7.7230080000000001e-01 , 4.6632199999999999e-02 , -1.8416800000000000e-01 , -9.8178799999999999e-01 --9.3058385689214740e-01 , 1.3372670669800284e+00 , 7.6837999999999984e-01 , -3.9884200000000002e-02 , 1.8990799999999999e-01 , 9.8099099999999995e-01 --1.0817480752733091e+00 , 1.3065013631108489e+00 , 7.5733519999999976e-01 , -9.2952499999999993e-02 , 1.8144399999999999e-01 , 9.7899899999999995e-01 --1.2687680081019543e+00 , 1.2653676138208749e+00 , 7.2935919999999999e-01 , -9.4322600000000006e-02 , 1.5609700000000001e-01 , 9.8322799999999999e-01 --1.4398633029435581e+00 , 1.2300606045719886e+00 , 7.1786719999999993e-01 , -7.6858899999999994e-02 , 1.6974900000000001e-01 , 9.8248599999999997e-01 --1.6313987597334156e+00 , 1.1903680143913764e+00 , 7.0135199999999998e-01 , -8.1570299999999998e-02 , 1.7529200000000000e-01 , 9.8113200000000000e-01 --1.8414044669162259e+00 , 1.1464657915404282e+00 , 6.8106159999999982e-01 , -9.7266199999999997e-02 , 1.8444099999999999e-01 , 9.7801899999999997e-01 --2.0800000018622802e+00 , 1.0948801213405699e+00 , 6.5343920000000000e-01 , -9.6673499999999996e-02 , 1.6920099999999999e-01 , 9.8082899999999995e-01 --2.3215674316983774e+00 , 1.0449205443746137e+00 , 6.3325279999999995e-01 , -8.0793199999999996e-02 , 1.7008899999999999e-01 , 9.8211099999999996e-01 --2.5840503946346800e+00 , 9.9035539971938769e-01 , 6.1207839999999991e-01 , -7.3149599999999995e-02 , 1.7133300000000001e-01 , 9.8249399999999998e-01 --2.8664855296541685e+00 , 9.3234763519326802e-01 , 5.9066480000000010e-01 , -8.7645299999999995e-02 , 1.6606699999999999e-01 , 9.8221199999999997e-01 --3.1890822476277840e+00 , 8.6505924931466716e-01 , 5.6204399999999999e-01 , -1.0336400000000000e-01 , 1.4932200000000001e-01 , 9.8337100000000000e-01 --3.5880805329270720e+00 , 7.7881384901240458e-01 , 5.1261279999999987e-01 , -9.6910399999999994e-02 , 1.6564300000000001e-01 , 9.8141299999999998e-01 --3.9907606500004205e+00 , 6.9434647990184528e-01 , 4.7650399999999982e-01 , -8.1220000000000001e-02 , 1.6987300000000000e-01 , 9.8211300000000001e-01 --4.4263133855495269e+00 , 6.0432090358656798e-01 , 4.4268320000000005e-01 , -8.5476899999999995e-02 , 1.7195199999999999e-01 , 9.8138999999999998e-01 --4.9503210894967431e+00 , 4.9459907212536947e-01 , 3.9234719999999990e-01 , -8.8320399999999993e-02 , 1.7186899999999999e-01 , 9.8115300000000005e-01 --5.5260415440127204e+00 , 3.7463075968408610e-01 , 3.4337359999999983e-01 , -8.9986800000000006e-02 , 1.6412199999999999e-01 , 9.8232699999999995e-01 --6.2408925072212558e+00 , 2.2290093454670346e-01 , 2.7045919999999990e-01 , -9.4624700000000006e-02 , 1.5646900000000000e-01 , 9.8314000000000001e-01 --7.0683105084587403e+00 , 4.8870695734430702e-02 , 1.8929759999999995e-01 , -9.0676300000000001e-02 , 1.5474199999999999e-01 , 9.8378500000000002e-01 --7.9897889513471885e+00 , -1.4374371420344412e-01 , 1.1179680000000003e-01 , -6.0832400000000002e-02 , 2.1085100000000001e-01 , 9.7562400000000005e-01 --9.1821549099066431e+00 , -3.9416774926280107e-01 , -4.7247999999999735e-03 , -8.7688799999999997e-02 , 1.7220299999999999e-01 , 9.8115100000000000e-01 --1.0401922239845970e+01 , -6.4452751533623465e-01 , -8.4721599999999953e-02 , 8.4075300000000006e-02 , -1.6678799999999999e-01 , -9.8240200000000000e-01 --1.2301548056875838e+01 , -1.0452346904501701e+00 , -2.7592560000000033e-01 , -8.5887900000000003e-02 , 1.6010700000000000e-01 , 9.8335600000000001e-01 --1.4401996677282739e+01 , -1.4807549004402221e+00 , -4.4042240000000010e-01 , 9.2838699999999996e-01 , 3.5465500000000000e-01 , 1.1098100000000000e-01 --1.4370294127542607e+01 , -1.4183326306428738e+00 , -1.2374240000000025e-01 , 9.2838699999999996e-01 , 3.5465500000000000e-01 , 1.1098100000000000e-01 --1.7364268490340322e+01 , -1.9683208531388221e+00 , 2.8056000000000081e-02 , -3.8380400000000002e-02 , 2.7320299999999997e-01 , 9.6118999999999999e-01 --8.7595977994662064e+00 , 6.0513042138917661e-01 , 5.1137911999999996e+00 , -6.9017200000000001e-01 , -6.9049300000000002e-01 , 2.1652299999999999e-01 --8.3048370187054612e+00 , 7.1190159627820293e-01 , 5.2243431999999999e+00 , -5.7971499999999998e-01 , -5.3812199999999999e-01 , 6.1184600000000000e-01 --8.3727266130310678e+00 , 7.3664785359962370e-01 , 5.4328320000000003e+00 , 5.0951199999999996e-01 , 6.2097899999999995e-01 , -5.9563699999999997e-01 --8.5471170715538705e+00 , 7.4523629493467181e-01 , 5.6701703999999999e+00 , 6.1317200000000005e-01 , 5.3515299999999999e-01 , -5.8106100000000005e-01 --7.9178562011335920e+00 , 8.7407778272425873e-01 , 5.7113128000000000e+00 , 6.1952099999999999e-01 , 3.5874400000000001e-01 , -6.9820899999999997e-01 --7.8075631374372527e+00 , 9.2502804496652158e-01 , 5.8717952000000002e+00 , -7.6893199999999995e-01 , -3.2866299999999998e-01 , 5.4838299999999995e-01 --7.6534943591297999e+00 , 9.8072632334572463e-01 , 6.0177488000000006e+00 , -8.3860900000000005e-01 , -8.3243200000000003e-02 , 5.3833600000000004e-01 --7.8241712413882407e+00 , 9.9109686168396283e-01 , 6.2594240000000001e+00 , -7.7420500000000003e-01 , -2.2549800000000000e-01 , 5.9140300000000001e-01 --7.5670117930977661e+00 , 1.0595695318236913e+00 , 6.3695600000000008e+00 , 6.8268300000000004e-01 , 2.2763300000000000e-01 , -6.9435400000000003e-01 --7.5731240057384142e+00 , 1.0934387520945430e+00 , 6.5627088000000002e+00 , 5.2194799999999997e-01 , 1.1489700000000000e-01 , -8.4520399999999996e-01 --8.4184781676589449e+00 , 1.0209774446290873e+00 , 7.0661832000000002e+00 , -7.2932799999999998e-01 , -3.4876000000000001e-01 , -5.8859700000000004e-01 --9.5481875024639145e+00 , 9.1893029824140759e-01 , 7.7152159999999999e+00 , 3.3502799999999999e-01 , 1.6818500000000000e-01 , 9.2707600000000001e-01 --9.4729160990349630e+00 , 9.7005551818065117e-01 , 7.9218847999999999e+00 , -3.3502799999999999e-01 , -1.6818500000000000e-01 , -9.2707600000000001e-01 --9.5072093218624598e+00 , 1.0088820522451756e+00 , 8.1756759999999993e+00 , 3.3502799999999999e-01 , 1.6818500000000000e-01 , 9.2707600000000001e-01 --6.5615706303306087e+00 , 1.3861217989826289e+00 , 7.1034047999999999e+00 , -4.8821100000000001e-01 , 8.5353299999999999e-01 , 1.8201800000000001e-01 --6.7396450328919695e+00 , 1.4001107237367036e+00 , 7.3720056000000005e+00 , 8.0788599999999999e-01 , -1.3451900000000000e-01 , -5.7378099999999999e-01 --4.9197520918072133e+00 , 1.6265923503348509e+00 , 6.6762144000000001e+00 , -1.8733000000000000e-01 , 6.8246600000000002e-01 , 7.0650400000000002e-01 --4.7772473986109301e+00 , 1.6692436895168634e+00 , 6.7602152000000002e+00 , -1.3866300000000001e-01 , 6.7852800000000002e-01 , 7.2136800000000001e-01 --4.7712475381191108e+00 , 1.6976997035258332e+00 , 6.9132616000000002e+00 , 6.9052300000000000e-01 , -6.8376699999999999e-02 , 7.2007200000000005e-01 --5.3508769857395224e+00 , 1.6716637228641282e+00 , 7.3929304000000000e+00 , 5.3564900000000004e-01 , -8.0864499999999995e-01 , 2.4325400000000000e-01 --4.0209229694511492e+00 , 1.8225784033034951e+00 , 6.8025224000000009e+00 , -3.9007599999999998e-01 , -8.8436899999999999e-02 , 9.1652599999999995e-01 --5.7661180053037304e+00 , 1.6990491527230245e+00 , 7.9936239999999996e+00 , 9.9867799999999995e-01 , 5.0288300000000001e-02 , 1.0661900000000000e-02 --5.2524399960057409e+00 , 1.7753958704288608e+00 , 7.8655480000000004e+00 , -2.7306300000000000e-01 , -8.4480400000000000e-01 , 4.6015499999999998e-01 --5.0323179588810207e+00 , 1.8252482977164370e+00 , 7.9069712000000001e+00 , 4.1000599999999998e-01 , 4.6033900000000000e-01 , 7.8739000000000003e-01 --3.5282762385285542e+00 , 1.9680734539202145e+00 , 7.0816584000000002e+00 , -6.3470100000000002e-02 , -3.4014200000000000e-01 , 9.3823000000000001e-01 --3.1967846840027132e+00 , 2.0169758513547151e+00 , 6.9998832000000002e+00 , -3.4668599999999999e-01 , -3.7217000000000000e-01 , 8.6098699999999995e-01 --3.1819823093549848e+00 , 2.0440433776485656e+00 , 7.1321192000000000e+00 , 6.8166099999999996e-01 , 4.4859900000000003e-01 , -5.7801199999999997e-01 --5.5871471062928926e+00 , 1.9266222929371812e+00 , 9.0717816000000013e+00 , -8.6717699999999998e-01 , -1.1575800000000000e-01 , -4.8436000000000001e-01 --5.8559971415306906e+00 , 1.9509991505458772e+00 , 9.4937615999999991e+00 , -7.1429699999999996e-01 , -3.2084099999999999e-01 , -6.2196499999999999e-01 --5.8136894412128770e+00 , 1.9932987692115118e+00 , 9.6863904000000005e+00 , 9.7155899999999995e-01 , 1.6120200000000001e-01 , 1.7345800000000000e-01 --1.4498424379802928e+00 , 2.2303006312032556e+00 , 6.3075136000000001e+00 , 2.4912500000000001e-01 , -1.3254500000000000e-01 , -9.5935800000000004e-01 --5.8642662335877835e+00 , 2.0757061732911550e+00 , 1.0200587200000001e+01 , 2.5011499999999998e-01 , -9.5421900000000004e-01 , -1.6403899999999999e-01 --4.8639998440725565e+00 , 2.1545806660751587e+00 , 9.5617048000000011e+00 , 2.6336100000000001e-01 , -2.4922900000000001e-01 , 9.3194699999999997e-01 --5.4826896009364710e+00 , 2.1769633495887688e+00 , 1.0352396000000001e+01 , 4.5329000000000003e-01 , 6.1480500000000005e-01 , -6.4540100000000000e-01 --5.1712917490238777e+00 , 2.2287749346367383e+00 , 1.0307104000000001e+01 , -6.9594199999999995e-01 , -4.9865500000000001e-01 , 5.1672799999999997e-01 --5.4272647897889339e+00 , 2.2692493352402199e+00 , 1.0806491200000000e+01 , -6.9594100000000003e-01 , -4.9865500000000001e-01 , 5.1672899999999999e-01 -2.8941625425202133e-01 , 2.3813349423531509e+00 , 5.2727344000000009e+00 , -1.9754700000000000e-01 , 3.0229299999999998e-01 , 9.3252100000000004e-01 -3.7652847618489593e-01 , 2.3944634043641875e+00 , 5.2563440000000003e+00 , 4.2302000000000001e-01 , -4.6397600000000000e-01 , -7.7831899999999998e-01 -4.2067237065881824e-01 , 2.4085976665531241e+00 , 5.2832176000000004e+00 , -6.0451900000000003e-01 , 1.9788100000000000e-01 , 7.7162200000000003e-01 -4.3079026464114523e-01 , 2.4212930849133039e+00 , 5.3483839999999994e+00 , 4.1302499999999998e-01 , 5.1222299999999998e-02 , -9.0927800000000003e-01 -5.2986507789344950e-01 , 2.4339336209009392e+00 , 5.3110584000000003e+00 , -3.7820999999999999e-01 , 3.5432300000000000e-01 , 8.5522600000000004e-01 --2.6374867060154665e+00 , 2.5193802452340850e+00 , 9.1964776000000015e+00 , -2.9347200000000001e-01 , -9.4128000000000001e-01 , 1.6692899999999999e-01 --2.5256561532621964e+00 , 2.5544224575229499e+00 , 9.2730840000000008e+00 , 2.9347200000000001e-01 , 9.4128000000000001e-01 , -1.6692899999999999e-01 -5.1192222308596191e-01 , 2.4787900276357528e+00 , 5.5772984000000001e+00 , -8.3754899999999999e-01 , 4.6052700000000002e-01 , 2.9398299999999999e-01 -1.6189046312919220e-01 , 2.5103561938451087e+00 , 6.1336152000000004e+00 , -4.3126999999999999e-01 , -3.1504399999999999e-01 , -8.4543100000000004e-01 -3.3620888540154481e-01 , 2.5211255482305499e+00 , 6.0029184000000004e+00 , -3.3588499999999999e-01 , -3.7980199999999997e-01 , -8.6193500000000001e-01 -4.2122085803455067e-01 , 2.5343546002212070e+00 , 5.9865800000000000e+00 , 3.2225399999999998e-01 , 3.4946899999999997e-01 , 8.7978599999999996e-01 -4.9494640212378060e-01 , 2.5479815566021973e+00 , 5.9856232000000000e+00 , -2.4372700000000000e-01 , -4.6807500000000002e-01 , -8.4941299999999997e-01 -5.7308373684068403e-01 , 2.5614119625520768e+00 , 5.9741000000000000e+00 , -2.0781400000000000e-01 , 9.5149399999999995e-01 , 2.2687399999999999e-01 --1.3983228989133178e+00 , 2.7652972571510914e+00 , 9.2374536000000003e+00 , 5.0390100000000004e-01 , 8.4590799999999999e-01 , 1.7471000000000000e-01 -3.9419119052660223e-01 , 2.6203732809421396e+00 , 6.4973551999999994e+00 , -3.5683500000000001e-01 , 7.4017299999999997e-01 , 5.6992299999999996e-01 -4.4699514007859342e-01 , 2.6383237811618097e+00 , 6.5397456000000007e+00 , 3.5683500000000001e-01 , -7.4017299999999997e-01 , -5.6992299999999996e-01 -5.1150941596100519e-01 , 2.6551462791318987e+00 , 6.5632184000000002e+00 , -2.4669500000000000e-01 , 7.2913499999999998e-01 , 6.3836000000000004e-01 -7.2338889883355928e-01 , 2.6504389612487937e+00 , 6.3110184000000000e+00 , -8.3595200000000003e-01 , 4.5560099999999998e-01 , -3.0596099999999998e-01 -6.4099588756015868e-01 , 2.6879980377650079e+00 , 6.6063368000000002e+00 , 5.0862600000000001e-02 , 4.2485299999999998e-01 , 9.0383199999999997e-01 --8.8076434209776888e-01 , 2.9758811264474021e+00 , 9.8555360000000007e+00 , 4.2660700000000001e-01 , 6.7720300000000000e-01 , 5.9950199999999998e-01 -6.3554251820875862e-01 , 2.7460475866902390e+00 , 6.9354655999999997e+00 , -3.1140000000000001e-01 , -2.3061900000000000e-02 , 9.4999900000000004e-01 -6.9724269721356169e-01 , 2.7649217465596272e+00 , 6.9737999999999998e+00 , 4.4679500000000000e-01 , -1.1362700000000001e-01 , -8.8739100000000004e-01 -7.5258213229593984e-01 , 2.7855976567401650e+00 , 7.0302512000000004e+00 , -5.0382199999999999e-01 , -1.4616999999999999e-01 , 8.5135099999999997e-01 -8.2413172104848864e-01 , 2.8019234750854598e+00 , 7.0474944000000006e+00 , 1.5477600000000000e-01 , 4.5370599999999997e-02 , -9.8690699999999998e-01 -7.6858523782467936e-01 , 2.8533841191786373e+00 , 7.3912144000000000e+00 , 9.9828099999999997e-01 , 4.5092899999999998e-02 , 3.7444699999999997e-02 -7.8489753133999263e-01 , 2.8892257173216875e+00 , 7.5726008000000000e+00 , -6.9070100000000001e-01 , -8.2817000000000002e-02 , 7.1838199999999997e-01 -1.1613560891529966e+00 , 2.8144624390874551e+00 , 6.7495240000000001e+00 , -9.2245500000000002e-01 , 1.9089400000000001e-01 , -3.3561299999999999e-01 -1.2928342700854047e+00 , 2.8063467886205999e+00 , 6.5633848000000006e+00 , -1.1550500000000000e-02 , -3.6707099999999998e-01 , 9.3012099999999998e-01 -2.7732359623398239e-01 , 3.2285175914675461e+00 , 1.0012669600000001e+01 , 6.3245200000000001e-01 , 7.7098299999999997e-01 , -7.4772199999999997e-02 -5.5240117880181794e-01 , 3.1929451910380600e+00 , 9.5206143999999995e+00 , -8.3062899999999995e-01 , 3.3735100000000001e-01 , -4.4300099999999998e-01 -8.7236555046949182e-01 , 3.1248852307142974e+00 , 8.7925520000000006e+00 , 5.4323399999999999e-01 , -2.4445800000000001e-01 , 8.0320400000000003e-01 -9.5601198006214050e-01 , 3.1551162179354195e+00 , 8.8761368000000012e+00 , 3.8667899999999999e-01 , -6.3993699999999998e-01 , 6.6404799999999997e-01 -1.2150310477661073e+00 , 3.0904176999064088e+00 , 8.2360791999999989e+00 , -7.7512099999999995e-01 , -6.7511500000000002e-02 , -6.2819499999999995e-01 -1.2796913447246578e+00 , 3.1262760984278390e+00 , 8.3645816000000011e+00 , 9.5838300000000004e-04 , -4.1149599999999997e-01 , 9.1141099999999997e-01 -1.3996632210592712e+00 , 3.1267833419119708e+00 , 8.2398647999999994e+00 , 5.7830099999999995e-01 , -6.9547199999999998e-01 , -4.2648300000000000e-01 -1.3477074647466702e+00 , 3.2562492246705785e+00 , 9.0136664000000000e+00 , -1.5913099999999999e-01 , -7.9412899999999997e-01 , 5.8654600000000001e-01 -1.5007425157272412e+00 , 3.2348288137432482e+00 , 8.7344575999999989e+00 , -6.3963899999999996e-01 , -1.5021000000000001e-01 , -7.5385599999999997e-01 -1.5629851776941237e+00 , 3.2913140661245732e+00 , 8.9806983999999996e+00 , -2.7603100000000003e-01 , 2.6524900000000001e-02 , 9.6078300000000005e-01 -1.6801659589136835e+00 , 3.2967098499483418e+00 , 8.8796624000000008e+00 , 6.7754199999999998e-01 , 7.0386199999999999e-01 , -2.1334100000000000e-01 --7.6998249402426033e-01 , 1.4707752022884986e+00 , 7.4327439999999978e-01 , -3.6792800000000001e-02 , 1.9286500000000001e-01 , 9.8053500000000005e-01 --8.9499518629301722e-01 , 1.4505605144684512e+00 , 7.4275439999999993e-01 , -3.6851000000000002e-02 , 1.9286000000000000e-01 , 9.8053400000000002e-01 --1.0379869179722458e+00 , 1.4263827369809940e+00 , 7.3452799999999985e-01 , -6.6654699999999997e-02 , 1.8185299999999999e-01 , 9.8106400000000005e-01 --1.1991530389389453e+00 , 1.3974257191202266e+00 , 7.1980159999999982e-01 , -8.9309899999999998e-02 , 1.7576000000000000e-01 , 9.8037300000000005e-01 --1.3707795233594373e+00 , 1.3667283854015353e+00 , 7.0473199999999991e-01 , -8.3198300000000003e-02 , 1.6714100000000001e-01 , 9.8241599999999996e-01 --1.5617688413619972e+00 , 1.3315656721984370e+00 , 6.8446239999999992e-01 , -8.8319400000000006e-02 , 1.7488000000000001e-01 , 9.8062099999999996e-01 --1.7633461888152162e+00 , 1.2959729670591487e+00 , 6.6505599999999987e-01 , -8.2172999999999996e-02 , 1.8622700000000000e-01 , 9.7906400000000005e-01 --1.9756416258948652e+00 , 1.2579744624090989e+00 , 6.4724080000000006e-01 , -9.5588400000000004e-02 , 1.7908199999999999e-01 , 9.7917900000000002e-01 --2.2264095081970803e+00 , 1.2117329025125252e+00 , 6.1717440000000012e-01 , -9.3178499999999997e-02 , 1.7517300000000000e-01 , 9.8011800000000004e-01 --2.4791603658417340e+00 , 1.1671596819438126e+00 , 5.9498079999999987e-01 , -8.0033999999999994e-02 , 1.7556900000000000e-01 , 9.8120799999999997e-01 --2.7529049313895371e+00 , 1.1181048006396623e+00 , 5.7242319999999980e-01 , -7.8318600000000002e-02 , 1.7843300000000001e-01 , 9.8082999999999998e-01 --3.0666277345286383e+00 , 1.0616392863511419e+00 , 5.4143119999999989e-01 , -8.8184700000000005e-02 , 1.7259600000000000e-01 , 9.8103700000000005e-01 --3.4285528425454430e+00 , 9.9566987930326478e-01 , 5.0042399999999998e-01 , -1.0506100000000000e-01 , 1.6338900000000001e-01 , 9.8095200000000005e-01 --3.8130602125145865e+00 , 9.2619776851308533e-01 , 4.6356639999999993e-01 , -8.9768000000000001e-02 , 1.6516600000000001e-01 , 9.8217200000000005e-01 --4.2392602282993259e+00 , 8.5054840183015301e-01 , 4.2402560000000000e-01 , -8.5382600000000003e-02 , 1.6795599999999999e-01 , 9.8209000000000002e-01 --4.7346369317407095e+00 , 7.6087049611301683e-01 , 3.7389759999999983e-01 , -9.0170100000000003e-02 , 1.7024000000000000e-01 , 9.8126800000000003e-01 --5.2734255021525200e+00 , 6.6512079211796515e-01 , 3.2651519999999978e-01 , -8.6398500000000003e-02 , 1.6914299999999999e-01 , 9.8179700000000003e-01 --5.9033842699404602e+00 , 5.5191929200224221e-01 , 2.6794239999999991e-01 , -9.3012999999999998e-02 , 1.6350200000000001e-01 , 9.8214900000000005e-01 --6.6827881701045921e+00 , 4.1041236339118026e-01 , 1.8455519999999992e-01 , -9.2822900000000000e-02 , 1.6360200000000000e-01 , 9.8214999999999997e-01 --7.5953326956568237e+00 , 2.4575680441108450e-01 , 8.9613599999999849e-02 , -8.7644299999999994e-02 , 1.5443999999999999e-01 , 9.8410699999999995e-01 --8.6032654276429668e+00 , 6.6345032470619847e-02 , 1.2239999999998918e-03 , -8.3318799999999998e-02 , 1.6147200000000000e-01 , 9.8335399999999995e-01 --9.8549580836111552e+00 , -1.5791636700125977e-01 , -1.1412240000000029e-01 , -7.0566900000000002e-02 , 1.6972300000000001e-01 , 9.8296200000000000e-01 --1.1114938966420382e+01 , -3.7636401499049654e-01 , -1.8653760000000030e-01 , 8.8489799999999993e-02 , -1.6044700000000001e-01 , -9.8307000000000000e-01 --1.3288260776989302e+01 , -7.7014361979868617e-01 , -4.1763600000000034e-01 , -4.9415600000000002e-03 , 2.6615800000000001e-01 , 9.6391700000000002e-01 --1.4955605430045892e+01 , -1.0504245850291656e+00 , -4.6745200000000020e-01 , 8.7286500000000000e-01 , 4.7583999999999999e-01 , 1.0808800000000000e-01 --1.4792010483206660e+01 , -9.6283149640543453e-01 , -1.1905199999999994e-01 , 8.7286500000000000e-01 , 4.7583999999999999e-01 , 1.0808800000000000e-01 --1.4783105623837983e+01 , -9.0625182752850852e-01 , 1.9528799999999991e-01 , 8.7286500000000000e-01 , 4.7583999999999999e-01 , 1.0808800000000000e-01 --8.9918031495534656e+00 , 8.7746587749567717e-01 , 4.9877327999999999e+00 , 6.1904599999999999e-01 , 6.0199400000000003e-01 , -5.0436599999999998e-01 --8.9724186818827700e+00 , 9.1585092201257012e-01 , 5.1876519999999999e+00 , 6.1904599999999999e-01 , 6.0199400000000003e-01 , -5.0436599999999998e-01 --8.9596333002795578e+00 , 9.5381085662131460e-01 , 5.3893496000000001e+00 , 6.1904599999999999e-01 , 6.0199400000000003e-01 , -5.0436599999999998e-01 --9.6495001470056891e+00 , 9.0361407827066231e-01 , 5.7466311999999995e+00 , -1.9494100000000000e-01 , -3.8596999999999998e-01 , 9.0167900000000001e-01 --8.6724827702429934e+00 , 1.0605880960516374e+00 , 5.7328512000000007e+00 , -6.2460099999999996e-01 , -5.0400699999999998e-01 , 5.9653199999999995e-01 --8.3591897737951459e+00 , 1.1334126485471265e+00 , 5.8555504000000003e+00 , -4.9831799999999998e-01 , -5.2985800000000005e-01 , 6.8624300000000005e-01 --7.9555285707689425e+00 , 1.2144535725709749e+00 , 5.9433784000000003e+00 , 5.0535799999999997e-01 , 3.0865599999999999e-01 , -8.0581999999999998e-01 --8.0773669557531722e+00 , 1.2340163757758993e+00 , 6.1725528000000001e+00 , -5.2660300000000004e-01 , -3.2783200000000001e-01 , 7.8435699999999997e-01 --7.6017998212784761e+00 , 1.3200193129843820e+00 , 6.2213288000000002e+00 , 6.6900199999999999e-01 , -6.2466200000000000e-02 , -7.4063100000000004e-01 --7.5508744398035326e+00 , 1.3590677943053207e+00 , 6.3943744000000002e+00 , 6.6900199999999999e-01 , -6.2466200000000000e-02 , -7.4063100000000004e-01 --9.2151946078514140e+00 , 1.2246281786773507e+00 , 7.1691224000000000e+00 , 7.6825399999999999e-01 , 5.4458899999999999e-01 , 3.3646500000000001e-01 --1.1692506501872515e+01 , 1.0217714537865419e+00 , 8.3109383999999995e+00 , -1.6592699999999999e-01 , -9.7001599999999999e-01 , -1.7758699999999999e-01 --9.2507890372729502e+00 , 1.3002357753469671e+00 , 7.6368831999999998e+00 , -7.3094099999999995e-01 , -5.2343499999999998e-01 , -4.3788199999999999e-01 --9.0787634043567156e+00 , 1.3572321250175237e+00 , 7.7984783999999996e+00 , -7.3094099999999995e-01 , -5.2343499999999998e-01 , -4.3788199999999999e-01 --1.1352640195844888e+01 , 1.1982878410296964e+00 , 9.0066151999999988e+00 , -2.9117100000000001e-01 , 5.6109699999999996e-01 , -7.7484900000000001e-01 --5.1445330660010562e+00 , 1.7687034654676927e+00 , 6.4956183999999997e+00 , 7.8082799999999997e-01 , -3.8499299999999997e-01 , -4.9202499999999999e-01 --5.8378215141257295e+00 , 1.7408825473246277e+00 , 6.9790416000000004e+00 , -1.6862099999999999e-01 , 9.8292199999999996e-01 , 7.3700600000000005e-02 --4.5617003236865257e+00 , 1.8687144168634415e+00 , 6.5261320000000005e+00 , 1.9744900000000001e-01 , -7.5593399999999999e-01 , -6.2416099999999997e-01 --4.5873200015770923e+00 , 1.8930210877334639e+00 , 6.6887048000000000e+00 , -2.1034800000000001e-01 , 5.1773599999999997e-01 , 8.2927899999999999e-01 --5.0758259559102230e+00 , 1.8859236606871428e+00 , 7.1026248000000001e+00 , -8.2368200000000003e-01 , -5.7971399999999999e-02 , -5.6408100000000005e-01 --4.1730479129344573e+00 , 1.9737510711923236e+00 , 6.7667256000000000e+00 , -3.2612099999999999e-01 , -5.9566500000000000e-03 , 9.4530899999999995e-01 --3.9673864998363566e+00 , 2.0133290102707129e+00 , 6.7962616000000002e+00 , 5.0872499999999998e-01 , 2.0576800000000001e-01 , -8.3597699999999997e-01 --5.6219542229559396e+00 , 1.9442701689251001e+00 , 7.9397624000000002e+00 , 3.6692999999999998e-01 , -8.3302299999999996e-01 , 4.1404800000000003e-01 --5.5565863100719781e+00 , 1.9809617573550771e+00 , 8.0883783999999999e+00 , 2.5359799999999999e-01 , 9.6703300000000003e-01 , -2.3145900000000001e-02 --3.5984052672165756e+00 , 2.1101865674068829e+00 , 7.0079016000000003e+00 , -4.6179300000000000e-02 , -3.1929700000000000e-01 , 9.4652899999999995e-01 --3.6518329855720353e+00 , 2.1336845128211017e+00 , 7.1921688000000001e+00 , -2.4240200000000001e-01 , -3.8544800000000001e-01 , 8.9032100000000003e-01 --3.2669868295078359e+00 , 2.1754158902693712e+00 , 7.0756160000000001e+00 , -4.8320500000000000e-01 , -4.3392500000000001e-01 , 7.6040900000000000e-01 --3.3585158431264253e+00 , 2.1978437463079668e+00 , 7.2886392000000004e+00 , -8.9997800000000003e-02 , -4.9972200000000000e-01 , 8.6149799999999999e-01 --5.8649744412178402e+00 , 2.1471479533162410e+00 , 9.3217768000000003e+00 , 7.5169100000000000e-01 , 5.9131200000000002e-02 , 6.5686000000000000e-01 --6.0540617912181869e+00 , 2.1811249743334948e+00 , 9.6924848000000008e+00 , -9.3239499999999997e-01 , 2.3844299999999999e-01 , -2.7163399999999999e-01 --1.5268608843910987e+00 , 2.3198685838070934e+00 , 6.2823975999999995e+00 , -2.4912599999999999e-01 , 1.3254600000000000e-01 , 9.5935800000000004e-01 --1.4158152826514110e+00 , 2.3415604931793998e+00 , 6.3030831999999997e+00 , -2.4912500000000001e-01 , 1.3254600000000000e-01 , 9.5935800000000004e-01 --4.7786452391254262e+00 , 2.3234260751387139e+00 , 9.3164727999999997e+00 , 7.9005199999999998e-01 , 3.3191199999999997e-02 , -6.1214100000000005e-01 --4.5324158826085759e+00 , 2.3622183596027395e+00 , 9.3138624000000014e+00 , -6.7342999999999997e-01 , -1.7567800000000000e-01 , 7.1807399999999999e-01 --4.5246946283719174e+00 , 2.4008708116591464e+00 , 9.5231519999999996e+00 , -6.7343100000000000e-01 , -1.7567800000000000e-01 , 7.1807299999999996e-01 --2.8958588127436409e+00 , 2.4316055822828382e+00 , 8.1892272000000013e+00 , -2.2861400000000001e-01 , 2.7629300000000001e-01 , 9.3348699999999996e-01 --2.7266949340722100e+00 , 2.4612595621526201e+00 , 8.1985560000000000e+00 , -2.7988600000000002e-01 , -1.5379900000000000e-02 , 9.5991000000000004e-01 -3.1221953862582463e-01 , 2.4407022491892159e+00 , 5.2665775999999997e+00 , -2.5912400000000002e-01 , 3.0266500000000002e-01 , 9.1719600000000001e-01 -4.0761004327872574e-01 , 2.4518350925799455e+00 , 5.2420648000000005e+00 , -3.3257599999999998e-01 , 7.8380200000000000e-01 , 5.2444999999999997e-01 -4.0228977041192215e-01 , 2.4650460980796174e+00 , 5.3223111999999997e+00 , 6.0186300000000004e-01 , -4.0468199999999999e-01 , -6.8847100000000006e-01 -4.4131032489942390e-01 , 2.4777046130497031e+00 , 5.3565792000000005e+00 , -3.9245000000000002e-01 , -3.1487900000000002e-01 , 8.6419599999999996e-01 -5.1349686084913637e-01 , 2.4882446835133818e+00 , 5.3505056000000000e+00 , -9.6741800000000000e-01 , 2.1280700000000000e-01 , 1.3716900000000001e-01 -5.5276121680855317e-01 , 2.5004857124330515e+00 , 5.3827560000000005e+00 , 5.5147599999999997e-01 , 6.3514499999999996e-01 , -5.4079999999999995e-01 -5.5995599685682951e-01 , 2.5147236248901264e+00 , 5.4549631999999999e+00 , 6.1477499999999996e-01 , 4.1033900000000001e-01 , -6.7355299999999996e-01 -6.0762459179474337e-01 , 2.5258657739064816e+00 , 5.4782696000000000e+00 , 6.8981499999999996e-01 , 3.8021800000000000e-01 , -6.1610799999999999e-01 -2.6508164872562623e-01 , 2.5670784258273907e+00 , 6.0260895999999997e+00 , -4.3126999999999999e-01 , -3.1504399999999999e-01 , -8.4543100000000004e-01 -3.3420574077152643e-01 , 2.5801100681640854e+00 , 6.0369992000000003e+00 , -3.3588499999999999e-01 , -3.7980199999999997e-01 , -8.6193500000000001e-01 -3.9720677366111556e-01 , 2.5927239592232034e+00 , 6.0550743999999996e+00 , -3.1612699999999999e-01 , -3.1104700000000002e-01 , -8.9627800000000002e-01 -5.1169691663866557e-01 , 2.6009307487106050e+00 , 5.9937560000000003e+00 , 3.6027599999999999e-01 , 4.2550399999999999e-01 , 8.3014900000000003e-01 -7.6390455889685804e-01 , 2.5925898495553956e+00 , 5.7110319999999994e+00 , -3.9959900000000000e-02 , -5.6544700000000003e-01 , 8.2381599999999999e-01 -8.7409004891047859e-01 , 2.5965071319636870e+00 , 5.6327720000000010e+00 , 1.1545600000000000e-01 , -5.7756399999999997e-01 , 8.0813999999999997e-01 -3.8880131418544672e-01 , 2.6791042265489375e+00 , 6.5505408000000003e+00 , -3.9624900000000002e-01 , 7.7510800000000002e-01 , 4.9213200000000001e-01 -4.5840328605044700e-01 , 2.6930763560777282e+00 , 6.5662343999999999e+00 , 2.8200500000000001e-01 , -7.6866599999999996e-01 , -5.7413000000000003e-01 -7.3325815952953088e-01 , 2.6748829326682451e+00 , 6.2078192000000003e+00 , -8.3595200000000003e-01 , 4.5560099999999998e-01 , -3.0596099999999998e-01 -5.8008077966680460e-01 , 2.7240904799309607e+00 , 6.6301839999999999e+00 , 5.0862600000000001e-02 , 4.2485299999999998e-01 , 9.0383199999999997e-01 --9.9372768221954910e-01 , 3.0413869300990708e+00 , 9.8982799999999997e+00 , 5.6199200000000005e-01 , 4.4419199999999998e-01 , 6.9775200000000004e-01 -5.8193581499884472e-01 , 2.7782807358062316e+00 , 6.9417264000000003e+00 , -2.6105000000000000e-01 , -2.5869500000000000e-02 , 9.6497900000000003e-01 -6.4882368222507947e-01 , 2.7952246538987375e+00 , 6.9715536000000000e+00 , -2.9560599999999998e-01 , 1.0041000000000000e-01 , 9.5001899999999995e-01 -7.1580659839000349e-01 , 2.8109144564864943e+00 , 7.0004760000000008e+00 , 7.2661399999999998e-01 , -8.4975700000000001e-02 , -6.8177100000000002e-01 -7.5604834783934050e-01 , 2.8335672047130731e+00 , 7.0951472000000004e+00 , -2.5199199999999999e-01 , -1.3427600000000001e-01 , 9.5836900000000003e-01 -8.5657871296508281e-01 , 2.8414771779122305e+00 , 7.0451855999999999e+00 , -3.7980000000000000e-02 , -7.1361300000000003e-02 , 9.9672700000000003e-01 -7.7394642238641720e-01 , 2.9023076352266628e+00 , 7.4665207999999996e+00 , -9.3965100000000001e-01 , -1.1234600000000000e-01 , 3.2316200000000000e-01 --4.1575602430708347e-02 , 3.2055449782810141e+00 , 9.9518191999999992e+00 , -3.9620200000000000e-01 , 2.7672900000000000e-01 , 8.7546800000000002e-01 -1.2351648801900335e+00 , 2.8284691845805598e+00 , 6.6187128000000000e+00 , -8.1564300000000001e-01 , -5.1099199999999997e-02 , -5.7629500000000000e-01 -2.8690587071714924e-01 , 3.2245387842833200e+00 , 9.7525031999999996e+00 , -5.8854899999999999e-01 , -5.7132099999999997e-01 , -5.7201599999999997e-01 -8.0694525437458253e-01 , 3.0824634122525669e+00 , 8.4626432000000005e+00 , 5.4284500000000002e-01 , -8.2771799999999995e-01 , 1.4213400000000001e-01 -7.7626039904912014e-01 , 3.1587691061898839e+00 , 8.9244240000000001e+00 , 6.1459200000000003e-01 , -3.7308300000000000e-01 , 6.9504400000000000e-01 -8.9936095401046834e-01 , 3.1691001440026145e+00 , 8.8701983999999996e+00 , -1.9523900000000000e-01 , -1.5941400000000000e-01 , 9.6771300000000005e-01 -1.1119088242247472e+00 , 3.1281318488169401e+00 , 8.4434135999999995e+00 , -5.7198099999999996e-01 , 5.5372100000000002e-01 , -6.0517100000000001e-01 -1.2242196132163954e+00 , 3.1365834269824573e+00 , 8.3828543999999994e+00 , 2.1246200000000001e-01 , -3.3640700000000001e-01 , 9.1743699999999995e-01 -1.4362486838414075e+00 , 3.0747538249942887e+00 , 7.8366151999999998e+00 , -3.7796200000000002e-01 , 9.2384100000000002e-01 , -6.0518500000000003e-02 -1.3501655391953999e+00 , 3.2161796448255782e+00 , 8.7204487999999998e+00 , 8.0438599999999999e-03 , -9.8936999999999997e-01 , 1.4519699999999999e-01 -1.4538623788090921e+00 , 3.2299735870303952e+00 , 8.7056703999999989e+00 , -5.0621000000000005e-01 , -1.7796400000000001e-01 , -8.4384899999999996e-01 -1.5125852361576291e+00 , 3.2846735757698253e+00 , 8.9633096000000005e+00 , -7.7612899999999996e-01 , 5.3961300000000001e-01 , -3.2625399999999999e-01 -1.6340462673516416e+00 , 3.2839546264341997e+00 , 8.8433975999999994e+00 , -3.7795299999999998e-01 , -8.5937300000000005e-01 , 3.4442600000000001e-01 --8.3999109598248545e-01 , 1.5667512186385824e+00 , 7.3037839999999998e-01 , -4.3790200000000001e-02 , 1.8670400000000001e-01 , 9.8143999999999998e-01 --9.8259243155043929e-01 , 1.5462488238400300e+00 , 7.1940639999999978e-01 , -3.6332099999999999e-02 , 1.8358900000000000e-01 , 9.8233199999999998e-01 --1.1355372848592129e+00 , 1.5237961332239773e+00 , 7.0708240000000000e-01 , -8.2893200000000000e-02 , 1.9233400000000000e-01 , 9.7782199999999997e-01 --1.3066619072173333e+00 , 1.4976900555503545e+00 , 6.8856000000000006e-01 , -8.2717200000000005e-02 , 1.8007899999999999e-01 , 9.8016800000000004e-01 --1.4794474666581947e+00 , 1.4727106184195722e+00 , 6.7526880000000000e-01 , -8.9531399999999997e-02 , 1.6850499999999999e-01 , 9.8162600000000000e-01 --1.6814545858003416e+00 , 1.4426406825171334e+00 , 6.5157759999999998e-01 , -9.9329000000000001e-02 , 1.8680800000000000e-01 , 9.7736199999999995e-01 --1.8931218946349913e+00 , 1.4101286437252822e+00 , 6.2948799999999983e-01 , -8.6713700000000005e-02 , 1.8071300000000001e-01 , 9.7970599999999997e-01 --2.1264293402343100e+00 , 1.3757480466836594e+00 , 6.0407039999999990e-01 , -9.4141500000000003e-02 , 1.7741100000000001e-01 , 9.7962400000000005e-01 --2.3784609684060740e+00 , 1.3375729310803044e+00 , 5.7689519999999983e-01 , -8.7679000000000007e-02 , 1.7510400000000001e-01 , 9.8063800000000001e-01 --2.6434816113492134e+00 , 1.2985104075273464e+00 , 5.5307919999999999e-01 , -8.3067500000000002e-02 , 1.7800800000000000e-01 , 9.8051699999999997e-01 --2.9384339988169756e+00 , 1.2545105462836226e+00 , 5.2472879999999988e-01 , -7.4115399999999998e-02 , 1.7571600000000001e-01 , 9.8164700000000005e-01 --3.2265975172813208e+00 , 1.2140303847620975e+00 , 5.1002319999999979e-01 , -1.0016899999999999e-01 , 1.7581300000000000e-01 , 9.7931400000000002e-01 --3.6477968205670397e+00 , 1.1474240284277077e+00 , 4.4793519999999987e-01 , -1.0127300000000000e-01 , 1.6578300000000001e-01 , 9.8094899999999996e-01 --4.0547614991280865e+00 , 1.0867104792747346e+00 , 4.0758319999999992e-01 , -8.6050100000000004e-02 , 1.6098499999999999e-01 , 9.8319900000000005e-01 --4.4934989556112290e+00 , 1.0224988447826673e+00 , 3.6944639999999995e-01 , -9.1097399999999995e-02 , 1.5951899999999999e-01 , 9.8298300000000005e-01 --5.0326582164099039e+00 , 9.4135079695308810e-01 , 3.1014560000000002e-01 , -9.2667899999999997e-02 , 1.6200899999999999e-01 , 9.8242799999999997e-01 --5.6335597330496858e+00 , 8.5074946007233354e-01 , 2.4872319999999992e-01 , -9.2582399999999995e-02 , 1.6537800000000000e-01 , 9.8187500000000005e-01 --6.3258396045336802e+00 , 7.4743992878147325e-01 , 1.7851279999999980e-01 , -9.0368199999999996e-02 , 1.6627700000000001e-01 , 9.8192900000000005e-01 --7.1132135473214397e+00 , 6.3038354006979080e-01 , 1.0409039999999981e-01 , -9.1431999999999999e-02 , 1.6154700000000000e-01 , 9.8262000000000005e-01 --8.0915643150670817e+00 , 4.8401816494718553e-01 , 1.5671999999999908e-03 , -7.9566499999999998e-02 , 1.7291999999999999e-01 , 9.8171699999999995e-01 --9.2357497011287908e+00 , 3.1309020072320304e-01 , -1.1073200000000005e-01 , -8.7526599999999996e-02 , 1.7322499999999999e-01 , 9.8098500000000000e-01 --1.0655944488950155e+01 , 1.0134863868340482e-01 , -2.5247360000000008e-01 , -7.8138799999999994e-02 , 1.6315499999999999e-01 , 9.8350099999999996e-01 --1.2354686945122241e+01 , -1.5020148304802161e-01 , -4.0900399999999992e-01 , 8.7217199999999995e-02 , -1.4739400000000000e-01 , -9.8522500000000002e-01 --1.4574551590737393e+01 , -4.7927519180602074e-01 , -6.1864719999999984e-01 , 2.2047199999999999e-02 , 3.0902800000000002e-01 , 9.5079700000000000e-01 --1.7079616820389287e+01 , -8.4255870827605550e-01 , -8.0599279999999984e-01 , -3.8380400000000002e-02 , 2.7320299999999997e-01 , 9.6119100000000002e-01 --1.7667891133999170e+01 , -8.7777303451582878e-01 , -5.5816080000000001e-01 , -3.8380400000000002e-02 , 2.7320299999999997e-01 , 9.6118999999999999e-01 --1.7837860274561191e+01 , -8.4335869435638289e-01 , -2.2344719999999985e-01 , -3.8380400000000002e-02 , 2.7320299999999997e-01 , 9.6118999999999999e-01 --1.0484228258321089e+01 , 1.0733490008670032e+00 , 5.2779448000000002e+00 , 3.3908100000000002e-01 , 7.0582999999999996e-01 , -6.2195500000000004e-01 --9.9201135697053591e+00 , 1.1696398956007261e+00 , 5.4018400000000000e+00 , -2.5025799999999998e-01 , -3.6085600000000001e-01 , 8.9841700000000002e-01 --9.2225075363611069e+00 , 1.2743145433466658e+00 , 5.4799856000000009e+00 , 3.8417000000000001e-01 , 7.1259600000000001e-01 , -5.8704400000000001e-01 --8.8401906267322303e+00 , 1.3466355939672554e+00 , 5.6042968000000002e+00 , 5.9502900000000003e-01 , 5.9039200000000003e-01 , -5.4532400000000003e-01 --6.6536427197227948e+00 , 1.5802613645156685e+00 , 5.2804719999999996e+00 , -1.2669000000000000e-02 , 6.6236099999999998e-01 , 7.4907699999999999e-01 --6.5667465642697227e+00 , 1.6161279085314364e+00 , 5.4243144000000001e+00 , -2.1321699999999999e-01 , 8.1111699999999998e-01 , 5.4463499999999998e-01 --6.5176304823289914e+00 , 1.6489732884864852e+00 , 5.5767160000000002e+00 , -2.1321699999999999e-01 , 8.1111699999999998e-01 , 5.4463600000000001e-01 --6.8440768699728611e+00 , 1.6512967169941111e+00 , 5.8400752000000002e+00 , -3.7048799999999998e-01 , 5.3404700000000005e-01 , 7.5995599999999996e-01 --7.7768873528392017e+00 , 1.6085501981994861e+00 , 6.3090320000000002e+00 , 6.6900199999999999e-01 , -6.2466500000000001e-02 , -7.4063100000000004e-01 --7.4957338932263138e+00 , 1.6623063111648473e+00 , 6.4092152000000002e+00 , -7.3243700000000000e-01 , -1.8702500000000000e-01 , 6.5464299999999997e-01 --7.5220587295200954e+00 , 1.7944741304935539e+00 , 7.1966096000000004e+00 , -6.9611999999999996e-01 , -4.3623299999999998e-01 , 5.7019100000000000e-01 --5.0977915457500851e+00 , 1.9685279579832697e+00 , 6.3484688000000000e+00 , -6.7499699999999996e-01 , 1.1822600000000000e-01 , 7.2828700000000002e-01 --4.5509278699664071e+00 , 2.0248607028725805e+00 , 6.2546295999999995e+00 , 5.3039000000000003e-01 , -5.9265599999999996e-01 , -6.0617299999999996e-01 --4.9944304742300076e+00 , 2.0274483172881950e+00 , 6.6102783999999994e+00 , -8.2223999999999997e-01 , -5.5002200000000001e-01 , 1.4627499999999999e-01 --4.6269458267621291e+00 , 2.0724304950163730e+00 , 6.5851936000000002e+00 , 2.4901200000000001e-01 , -8.9965200000000001e-01 , -3.5863600000000001e-01 --4.9819924508802469e+00 , 2.0820934352691345e+00 , 6.9210512000000000e+00 , -7.0164000000000004e-01 , -3.1594899999999998e-01 , -6.3865300000000003e-01 --4.2574303642251339e+00 , 2.1388033222623912e+00 , 6.6930832000000002e+00 , -5.7723500000000005e-01 , -2.5713199999999998e-04 , 8.1657800000000003e-01 --4.2774915829943749e+00 , 2.1644808136299805e+00 , 6.8531392000000002e+00 , -5.9796400000000005e-01 , -2.3652999999999999e-01 , 7.6582799999999995e-01 --6.5384862706271338e+00 , 2.1175632852060731e+00 , 8.3249783999999991e+00 , 6.1886699999999994e-01 , 5.8329299999999995e-01 , -5.2609200000000000e-01 --4.8388307997768090e+00 , 2.2014920884483793e+00 , 7.5020784000000003e+00 , -3.6690000000000000e-01 , 8.6389499999999997e-01 , 3.4506700000000001e-01 --3.9457008553031567e+00 , 2.2520061346376279e+00 , 7.1106328000000003e+00 , -5.5810400000000004e-01 , -4.6589199999999997e-01 , 6.8663300000000005e-01 --3.4587167116177957e+00 , 2.2881783853145801e+00 , 6.9461256000000002e+00 , -1.3117300000000000e-02 , -6.5023600000000004e-01 , 7.5961900000000004e-01 --3.4433046924120703e+00 , 2.3137565410323471e+00 , 7.0816376000000005e+00 , 2.5834099999999999e-01 , 4.2585699999999999e-01 , -8.6712500000000003e-01 --3.3571736075527943e+00 , 2.3395249995846967e+00 , 7.1699544000000008e+00 , -3.7216900000000003e-01 , -6.7340000000000000e-01 , 6.3876599999999994e-01 --3.3708751331788074e+00 , 2.3659186422798553e+00 , 7.3296568000000004e+00 , 4.3155600000000000e-01 , 6.0136299999999998e-01 , -6.7240000000000000e-01 --5.5538482965150617e+00 , 2.3870786154544206e+00 , 9.1349720000000012e+00 , -5.8059899999999996e-03 , 4.3856800000000001e-01 , 8.9867900000000001e-01 --1.5527968291178906e+00 , 2.4150969339291493e+00 , 6.2172312000000005e+00 , -2.4912599999999999e-01 , 1.3254600000000000e-01 , 9.5935800000000004e-01 --1.4826193463864152e+00 , 2.4337157848763344e+00 , 6.2719040000000001e+00 , -2.4912599999999999e-01 , 1.3254600000000000e-01 , 9.5935800000000004e-01 --1.3633744411892428e+00 , 2.4513936711627999e+00 , 6.2849767999999999e+00 , -2.4912599999999999e-01 , 1.3254600000000000e-01 , 9.5935800000000004e-01 --4.8153940182616255e+00 , 2.5297883256370040e+00 , 9.4000368000000005e+00 , -5.1557699999999995e-01 , 8.8513999999999995e-02 , 8.5225899999999999e-01 --3.0685650038680148e+00 , 2.5294101383736027e+00 , 8.0475376000000001e+00 , -2.2861400000000001e-01 , 2.7629300000000001e-01 , 9.3348699999999996e-01 --2.8838285584038390e+00 , 2.5535406071892188e+00 , 8.0486192000000010e+00 , -2.2861400000000001e-01 , 2.7629300000000001e-01 , 9.3348699999999996e-01 --2.8726311098162700e+00 , 2.5825302597902553e+00 , 8.2107136000000001e+00 , -2.2861400000000001e-01 , 2.7629300000000001e-01 , 9.3348699999999996e-01 -3.6711947676113210e-01 , 2.4865795140471501e+00 , 5.1581783999999997e+00 , -3.2297599999999999e-01 , 7.8161800000000003e-01 , 5.3362799999999999e-01 -3.6692834461800450e-01 , 2.4990390225959760e+00 , 5.2305207999999999e+00 , -5.5855800000000000e-01 , 6.6833900000000002e-01 , 4.9125999999999997e-01 -3.8932804737581295e-01 , 2.5102999452786081e+00 , 5.2806487999999998e+00 , -4.5152199999999998e-01 , 7.0528100000000005e-01 , 5.4654100000000005e-01 -4.9114645503428656e-01 , 2.5180433732086205e+00 , 5.2459336000000008e+00 , 3.6527500000000002e-01 , -5.1395700000000000e-01 , -7.7615900000000004e-01 -4.9417538612199285e-01 , 2.5313169160539171e+00 , 5.3177456000000003e+00 , 5.0175400000000002e-02 , 9.5451200000000003e-01 , 2.9391899999999999e-01 -4.8578634602947290e-01 , 2.5452184971575358e+00 , 5.4060312000000001e+00 , 8.8921899999999998e-01 , 5.1492999999999997e-02 , -4.5457500000000001e-01 -5.1356985985906567e-01 , 2.5570890091846739e+00 , 5.4550672000000002e+00 , 6.1477499999999996e-01 , 4.1033900000000001e-01 , -6.7355299999999996e-01 -5.5490107066215000e-01 , 2.5681901774493476e+00 , 5.4873592000000002e+00 , -7.1281799999999995e-01 , 8.0815599999999998e-03 , 7.0130199999999998e-01 -6.0255121600666484e-01 , 2.5782716787588256e+00 , 5.5106760000000001e+00 , 8.6813799999999997e-01 , 1.4321400000000001e-01 , -4.7521200000000002e-01 -6.1388320272970143e-01 , 2.5924112469597613e+00 , 5.5832784000000002e+00 , 9.4131399999999998e-01 , 1.2583600000000000e-01 , -3.1319799999999998e-01 -4.3541567806756754e-01 , 2.6279701131578985e+00 , 5.9272272000000008e+00 , 3.6027599999999999e-01 , 4.2550399999999999e-01 , 8.3014900000000003e-01 -5.0903753405759589e-01 , 2.6373972327743846e+00 , 5.9264784000000006e+00 , 3.6027599999999999e-01 , 4.2550399999999999e-01 , 8.3014900000000003e-01 -5.6401072064391644e-01 , 2.6482585828412581e+00 , 5.9499616000000000e+00 , 1.5082599999999999e-01 , 1.3778899999999999e-01 , -9.7891099999999998e-01 -8.1316205733760993e-01 , 2.6333174849572520e+00 , 5.6654592000000008e+00 , 5.3718299999999997e-02 , -5.7163699999999995e-01 , 8.1874599999999997e-01 -8.5298867481697394e-01 , 2.6441720204377783e+00 , 5.7014744000000004e+00 , 1.1545600000000000e-01 , -5.7756399999999997e-01 , 8.0813999999999997e-01 -6.9495146897509219e-01 , 2.6872849834037664e+00 , 6.0767376000000004e+00 , -4.8827700000000002e-01 , -3.1922000000000000e-01 , 8.1220899999999996e-01 -7.7255599606807701e-01 , 2.6954915681869620e+00 , 6.0602432000000004e+00 , -8.8791100000000001e-01 , 4.2788999999999999e-01 , 1.6889199999999999e-01 -7.9004944931325971e-01 , 2.7131573605330814e+00 , 6.1516696000000000e+00 , -8.1381899999999996e-01 , 5.6749099999999997e-01 , -1.2510900000000000e-01 -6.2418010890371378e-01 , 2.7684925085399366e+00 , 6.6017295999999996e+00 , -1.4953700000000000e-02 , 1.7775800000000000e-01 , 9.8396099999999997e-01 --9.3196336989244521e-01 , 3.1264793885938165e+00 , 9.8858519999999999e+00 , 4.7266999999999998e-01 , 4.4161000000000000e-01 , 7.6260300000000003e-01 -6.0055505721231262e-01 , 2.8285547411692038e+00 , 6.9686000000000003e+00 , 1.3732000000000000e-01 , 2.1341700000000002e-02 , -9.9029699999999998e-01 -6.8977589256521488e-01 , 2.8371964435229282e+00 , 6.9514712000000003e+00 , 3.6494100000000002e-01 , -4.0733199999999997e-02 , -9.3013900000000005e-01 -7.4071367669535859e-01 , 2.8558202553108210e+00 , 7.0178752000000006e+00 , 7.3124299999999998e-01 , 1.3440299999999999e-01 , -6.6874500000000003e-01 -8.0989256012416155e-01 , 2.8690370334040827e+00 , 7.0455288000000005e+00 , -1.5018500000000001e-01 , -4.3665700000000002e-02 , 9.8769300000000004e-01 -8.7822704112968331e-01 , 2.8830376798110020e+00 , 7.0716536000000003e+00 , -8.3326399999999995e-02 , 5.5938200000000002e-03 , 9.9650700000000003e-01 -7.7160214690454088e-01 , 2.9542851901301503e+00 , 7.5711656000000005e+00 , -9.3965100000000001e-01 , -1.1234600000000000e-01 , 3.2316200000000000e-01 -8.4604152306935543e-01 , 2.9701176053948806e+00 , 7.6076696000000004e+00 , -6.9070100000000001e-01 , -8.2816799999999996e-02 , 7.1838299999999999e-01 -1.2795915508228823e+00 , 2.8507934403186481e+00 , 6.5756255999999995e+00 , 3.5670199999999999e-02 , -3.1891399999999998e-01 , 9.4711199999999995e-01 -7.6812837673268652e-01 , 3.0969320996008949e+00 , 8.4049440000000004e+00 , 5.4284500000000002e-01 , -8.2771799999999995e-01 , 1.4213400000000001e-01 -7.9467230750966666e-01 , 3.1437720449699631e+00 , 8.6589120000000008e+00 , -4.8907200000000001e-01 , 5.8701199999999998e-01 , 6.4515599999999995e-01 -8.4733411219823873e-01 , 3.1829390631744716e+00 , 8.8434704000000011e+00 , 1.3744300000000001e-01 , 6.6275700000000004e-01 , 7.3611300000000002e-01 -9.4614048413511243e-01 , 3.2016204427918806e+00 , 8.8781959999999991e+00 , -1.1471400000000000e-02 , -1.3062399999999999e-01 , 9.9136599999999997e-01 -1.1801210177784944e+00 , 3.1424897211937139e+00 , 8.3500320000000006e+00 , 1.5038399999999999e-01 , -8.8139299999999998e-01 , 4.4780799999999998e-01 -1.2701321430577268e+00 , 3.1593776045248569e+00 , 8.3792767999999995e+00 , 9.5834900000000005e-04 , -4.1149599999999997e-01 , 9.1141099999999997e-01 -1.3749915021205243e+00 , 3.1653636659060416e+00 , 8.3365223999999998e+00 , -5.8344700000000005e-01 , 4.4339600000000001e-01 , -6.8043299999999995e-01 -1.3843060754870868e+00 , 3.2461591157741458e+00 , 8.7975023999999991e+00 , 6.6377300000000000e-02 , 9.9084099999999997e-01 , 1.1759400000000000e-01 -1.5051437174810163e+00 , 3.2439449125972630e+00 , 8.6910792000000008e+00 , -6.3963899999999996e-01 , -1.5021100000000001e-01 , -7.5385599999999997e-01 -1.5740558034841334e+00 , 3.2879446968822408e+00 , 8.8978208000000016e+00 , 4.1656399999999999e-01 , -7.9193499999999994e-01 , 4.4644499999999998e-01 -1.6802406403953352e+00 , 3.2987730127637054e+00 , 8.8793503999999999e+00 , 6.7754199999999998e-01 , 7.0386199999999999e-01 , -2.1334100000000000e-01 --9.2333443348344657e-01 , 1.6621319172829143e+00 , 7.0640639999999988e-01 , -5.6575599999999997e-02 , 1.7434800000000000e-01 , 9.8305799999999999e-01 --1.0583410696671582e+00 , 1.6470369447596225e+00 , 7.0280799999999988e-01 , -7.0197800000000005e-02 , 1.7650299999999999e-01 , 9.8179399999999994e-01 --1.2299820400494164e+00 , 1.6255196752193135e+00 , 6.8060399999999999e-01 , -8.7436799999999995e-02 , 1.8302900000000000e-01 , 9.7921199999999997e-01 --1.4022508338883255e+00 , 1.6051103209559456e+00 , 6.6376639999999987e-01 , -7.5494599999999995e-02 , 1.7872399999999999e-01 , 9.8099899999999995e-01 --1.5948492405784194e+00 , 1.5823350962171507e+00 , 6.4137519999999992e-01 , -9.3175700000000000e-02 , 1.7889400000000000e-01 , 9.7944600000000004e-01 --1.8069130092922361e+00 , 1.5563855050452207e+00 , 6.1489679999999991e-01 , -9.1105300000000000e-02 , 1.7731200000000000e-01 , 9.7992900000000005e-01 --2.0208323352909483e+00 , 1.5307951524025074e+00 , 5.9507440000000011e-01 , -8.9203099999999994e-02 , 1.8018700000000001e-01 , 9.7957899999999998e-01 --2.2642891988803102e+00 , 1.5006784513190181e+00 , 5.6756640000000003e-01 , -9.5796199999999998e-02 , 1.7491599999999999e-01 , 9.7991200000000001e-01 --2.5285086642160799e+00 , 1.4689708254659506e+00 , 5.3826960000000001e-01 , -8.2055400000000001e-02 , 1.7612200000000000e-01 , 9.8094199999999998e-01 --2.8047577219306241e+00 , 1.4364588552086848e+00 , 5.1295599999999997e-01 , -8.0711000000000005e-02 , 1.7358699999999999e-01 , 9.8150599999999999e-01 --3.1198705004209346e+00 , 1.3985763218511842e+00 , 4.7903120000000010e-01 , -8.3158499999999996e-02 , 1.7504700000000001e-01 , 9.8104199999999997e-01 --3.4672447569363332e+00 , 1.3573555599246505e+00 , 4.4274559999999985e-01 , -1.0242100000000000e-01 , 1.5497500000000000e-01 , 9.8259500000000000e-01 --3.8359895272623223e+00 , 1.3145065966967207e+00 , 4.0963200000000000e-01 , 8.7123699999999998e-02 , -1.5959699999999999e-01 , -9.8333000000000004e-01 --4.2744072979069614e+00 , 1.2610720991975963e+00 , 3.6182319999999990e-01 , 8.5722800000000002e-02 , -1.6043099999999999e-01 , -9.8331800000000003e-01 --4.7637430452690035e+00 , 1.2026313291953401e+00 , 3.0989599999999995e-01 , 9.1573900000000000e-02 , -1.4953200000000000e-01 , -9.8450700000000002e-01 --5.2964336424060994e+00 , 1.1390938452509227e+00 , 2.6032959999999994e-01 , 9.1203599999999996e-02 , -1.5599199999999999e-01 , -9.8353900000000005e-01 --5.9694176335652687e+00 , 1.0575931789030077e+00 , 1.8126880000000001e-01 , -9.8446900000000004e-02 , 1.5455400000000000e-01 , 9.8306700000000002e-01 --6.7361734182263024e+00 , 9.6508830150830538e-01 , 9.6082400000000012e-02 , -8.7350499999999998e-02 , 1.5135000000000001e-01 , 9.8461299999999996e-01 --7.5770184907956537e+00 , 8.6509578050474567e-01 , 1.5908799999999834e-02 , 9.1160900000000003e-02 , -1.5039500000000000e-01 , -9.8441400000000001e-01 --8.6121985827550454e+00 , 7.4173406319340618e-01 , -8.9942399999999978e-02 , -8.3729899999999996e-02 , 1.4784300000000000e-01 , 9.8546000000000000e-01 --9.8530514882808475e+00 , 5.9382225839007985e-01 , -2.1400400000000008e-01 , -8.9255100000000004e-02 , 1.4031199999999999e-01 , 9.8607599999999995e-01 --1.1391527404877566e+01 , 4.1121141863590549e-01 , -3.6833999999999989e-01 , -8.5939199999999993e-02 , 1.5048500000000001e-01 , 9.8487000000000002e-01 --1.3302387703924063e+01 , 1.8423282158547893e-01 , -5.5334560000000010e-01 , 8.7562100000000004e-02 , -1.3823299999999999e-01 , -9.8652099999999998e-01 --1.5676588121996549e+01 , -9.4891897506950595e-02 , -7.6947840000000012e-01 , -8.9340100000000006e-02 , 3.0473200000000000e-01 , 9.4823900000000005e-01 --2.6676083024957599e+01 , -1.2595742948694091e+00 , -1.0130255999999997e+00 , -2.6286199999999999e-02 , 2.7377200000000002e-01 , 9.6143500000000004e-01 --1.0430267241442710e+01 , 1.4253842675651163e+00 , 5.0866160000000002e+00 , -2.6123700000000000e-01 , 2.7267900000000000e-01 , 9.2596000000000001e-01 --1.0417167825484725e+01 , 1.4649359195432523e+00 , 5.3120776000000003e+00 , -2.6123700000000000e-01 , 2.7267900000000000e-01 , 9.2596000000000001e-01 --1.0237680810190747e+01 , 1.5154861233100037e+00 , 5.5064536000000004e+00 , -1.9045699999999999e-01 , -2.3463999999999998e-03 , 9.8169300000000004e-01 --9.6279887652623621e+00 , 1.5952830598908396e+00 , 5.6057736000000000e+00 , -3.0392599999999997e-01 , -4.5853699999999997e-01 , 8.3508800000000005e-01 --6.8525421978674963e+00 , 1.8090613040824572e+00 , 5.1930911999999996e+00 , 9.8886700000000005e-01 , 1.1812599999999999e-01 , 9.0494099999999994e-02 --6.8461730635931435e+00 , 1.8382606996042021e+00 , 5.3604584000000006e+00 , 9.8886700000000005e-01 , 1.1812599999999999e-01 , 9.0494099999999994e-02 --6.7370066596552629e+00 , 1.8726779700001996e+00 , 5.5018776000000003e+00 , -1.2669000000000000e-02 , 6.6236099999999998e-01 , 7.4907699999999999e-01 --6.1365160193257182e+00 , 1.9339495968678755e+00 , 5.5019608000000000e+00 , 2.3821400000000001e-01 , -2.1901200000000001e-01 , -9.4619699999999995e-01 --6.1540424287483546e+00 , 1.9605759920116055e+00 , 5.6672479999999998e+00 , 2.3821400000000001e-01 , -2.1901200000000001e-01 , -9.4619699999999995e-01 --9.7915914908241657e+00 , 1.8103014685999308e+00 , 6.9912200000000002e+00 , -9.8082499999999995e-01 , 2.4034099999999999e-02 , 1.9340099999999999e-01 --2.2755541450417436e+00 , 2.2057877737967075e+00 , 4.7711319999999997e+00 , 9.5458600000000005e-01 , -2.2533300000000001e-01 , -1.9491000000000000e-01 --7.7416603227244636e+00 , 2.0091876032252469e+00 , 6.9242232000000001e+00 , -5.5867100000000003e-01 , 7.1018199999999998e-01 , -4.2840299999999998e-01 --5.3372682589539435e+00 , 2.1288502515899812e+00 , 6.1708160000000003e+00 , 9.4609299999999996e-01 , 3.2308799999999999e-01 , -2.2871800000000001e-02 --5.0342226636993317e+00 , 2.1642293435757520e+00 , 6.2003000000000004e+00 , 2.1332899999999999e-01 , 7.4248999999999998e-01 , 6.3497999999999999e-01 --4.6180577337178335e+00 , 2.2018569996693071e+00 , 6.1701712000000004e+00 , 6.1790900000000004e-01 , -3.8593899999999998e-01 , -6.8501100000000004e-01 --4.5086113925341174e+00 , 2.2290302876510255e+00 , 6.2651231999999997e+00 , -8.0567299999999997e-01 , 3.9541100000000001e-01 , 4.4106899999999999e-01 --4.5280858270987583e+00 , 2.2525983060282138e+00 , 6.4201248000000000e+00 , -8.8296900000000000e-01 , 4.2954399999999998e-01 , 1.8935900000000000e-01 --5.2331797778599078e+00 , 2.2647985554041021e+00 , 6.9205208000000002e+00 , -9.2198199999999997e-01 , -2.6119500000000000e-02 , 3.8635000000000003e-01 --4.3454651251671041e+00 , 2.3059591019419758e+00 , 6.6238087999999999e+00 , -8.6416700000000002e-01 , -1.9643600000000000e-01 , 4.6328000000000003e-01 --4.2846892273037707e+00 , 2.3320102983956046e+00 , 6.7397584000000004e+00 , -8.0631200000000003e-01 , -1.4951000000000000e-01 , 5.7228199999999996e-01 --4.1126004270641543e+00 , 2.3577048454297436e+00 , 6.7933288000000003e+00 , -7.3528400000000005e-01 , -2.6992300000000002e-01 , 6.2168999999999996e-01 --4.1103277717563893e+00 , 2.3833466818899520e+00 , 6.9421320000000000e+00 , -6.5389100000000000e-01 , -3.0044199999999999e-01 , 6.9437899999999997e-01 --4.2476186210291180e+00 , 2.4093062640509335e+00 , 7.1787424000000000e+00 , -3.8408999999999999e-01 , -7.7105400000000002e-01 , 5.0788900000000003e-01 --4.3169194386635237e+00 , 2.4362506100107648e+00 , 7.3820208000000003e+00 , 9.1803300000000004e-02 , 9.1840400000000000e-01 , 3.8484499999999999e-01 --3.7650821761911306e+00 , 2.4593057168310981e+00 , 7.1820080000000006e+00 , -1.9954300000000000e-01 , -3.1732700000000003e-01 , 9.2708500000000005e-01 --2.7497021557311259e+00 , 2.4723644920784444e+00 , 6.6413536000000004e+00 , -7.1668699999999996e-01 , 9.6918000000000004e-02 , -6.9062699999999999e-01 --2.6786701552524246e+00 , 2.4933637593378899e+00 , 6.7238568000000001e+00 , 7.6461199999999996e-01 , 6.3497499999999996e-01 , -1.1034099999999999e-01 --2.4486637143277905e+00 , 2.5101593792163968e+00 , 6.6876336000000007e+00 , 2.6004800000000000e-01 , -9.1505999999999998e-01 , 3.0828699999999998e-01 --5.6500337977551061e+00 , 2.6154872724759990e+00 , 9.2625696000000008e+00 , -6.2405699999999997e-01 , 5.1321700000000003e-01 , -5.8920300000000003e-01 --1.5948794627909382e+00 , 2.5291506868652984e+00 , 6.2789343999999998e+00 , -6.4532900000000004e-02 , 3.1879999999999999e-02 , 9.9740600000000001e-01 --1.3784700514172967e+00 , 2.5400490413004437e+00 , 6.2158168000000007e+00 , 3.5938100000000001e-02 , 2.1148400000000001e-01 , 9.7672000000000003e-01 --1.3710233091536113e+00 , 2.5588022971686462e+00 , 6.3210128000000001e+00 , 2.0227899999999999e-01 , -7.9446399999999995e-01 , 5.7263399999999998e-01 --1.2759463936234865e+00 , 2.5735760559211598e+00 , 6.3514016000000009e+00 , 6.6084500000000002e-01 , -6.3650099999999998e-01 , 3.9768300000000001e-01 --3.0647956148663775e+00 , 2.6836168682096062e+00 , 8.0917063999999996e+00 , -2.2861400000000001e-01 , 2.7629300000000001e-01 , 9.3348699999999996e-01 --2.9015697445956388e+00 , 2.7033550929919872e+00 , 8.1138271999999994e+00 , -2.2861400000000001e-01 , 2.7629300000000001e-01 , 9.3348699999999996e-01 --2.8883552422824774e+00 , 2.7323928308097907e+00 , 8.2765768000000008e+00 , -2.2861400000000001e-01 , 2.7629300000000001e-01 , 9.3348699999999996e-01 --2.6659458044919173e+00 , 2.7481896496365872e+00 , 8.2337912000000006e+00 , -1.4312900000000001e-01 , 2.5322699999999998e-01 , 9.5676000000000005e-01 --2.4748053869867128e+00 , 2.7638662773076268e+00 , 8.2153519999999993e+00 , 4.3267499999999998e-01 , -4.9084000000000000e-01 , 7.5622000000000000e-01 --1.0084771405455206e+00 , 2.6784011156059275e+00 , 6.8128288000000001e+00 , 7.1757099999999996e-01 , 5.1636899999999997e-01 , -4.6739100000000000e-01 -4.6969137621497259e-01 , 2.5741013748699233e+00 , 5.2929727999999994e+00 , -2.2711899999999999e-01 , 9.0989299999999995e-01 , 3.4714699999999998e-01 --8.9070671202438856e-01 , 2.7124614263812110e+00 , 6.9437856000000000e+00 , -6.4548799999999995e-01 , -6.7108199999999996e-01 , 3.6468400000000001e-01 --1.9145068753727670e+00 , 2.8366855448567874e+00 , 8.3063415999999997e+00 , -1.1651000000000000e-01 , 6.2451500000000004e-01 , 7.7227299999999999e-01 -5.2819692331028989e-01 , 2.6091015867583676e+00 , 5.4633664000000000e+00 , -5.8357300000000001e-01 , -2.2510200000000000e-01 , 7.8023900000000002e-01 -5.8921592449653337e-01 , 2.6165215358678164e+00 , 5.4710520000000002e+00 , 8.6813799999999997e-01 , 1.4321400000000001e-01 , -4.7521200000000002e-01 -5.5584631997979317e-01 , 2.6347207923316489e+00 , 5.6016968000000000e+00 , -9.5471499999999998e-01 , -2.6214199999999999e-01 , 1.4071700000000001e-01 -3.4431587436316713e-01 , 2.6777003499238958e+00 , 5.9859664000000006e+00 , -3.1612600000000002e-01 , -3.1104700000000002e-01 , -8.9627800000000002e-01 -6.2101777531907443e-01 , 2.6577240146931884e+00 , 5.6981672000000003e+00 , -3.5942200000000002e-01 , -5.4598700000000000e-01 , 7.5677799999999995e-01 -6.9077151726060348e-01 , 2.6645609473908980e+00 , 5.6942880000000002e+00 , 4.0509899999999999e-01 , -3.2695800000000003e-01 , -8.5381099999999999e-01 -7.3559277888851127e-01 , 2.6738355520540100e+00 , 5.7235224000000002e+00 , -3.6612400000000000e-01 , -5.0368700000000000e-01 , 7.8246499999999997e-01 -7.7108920969886996e-01 , 2.6858189544271189e+00 , 5.7694904000000005e+00 , -1.2726699999999999e-01 , -5.9171700000000005e-01 , 7.9603599999999997e-01 -8.7698734174115844e-01 , 2.6842097484707383e+00 , 5.6997792000000000e+00 , 1.3626400000000000e-01 , -5.9784199999999998e-01 , 7.8994699999999995e-01 -9.2851772301262292e-01 , 2.6928536371149936e+00 , 5.7167832000000001e+00 , 8.3070600000000006e-01 , -5.3554999999999997e-01 , 1.5203100000000000e-01 -7.6905674328075668e-01 , 2.7424354053003555e+00 , 6.1133144000000001e+00 , 3.2298800000000001e-03 , -5.1789300000000005e-01 , 8.5543899999999995e-01 -8.1719911610366713e-01 , 2.7541351951420530e+00 , 6.1500367999999996e+00 , 3.2300699999999998e-03 , -5.1789399999999997e-01 , 8.5543899999999995e-01 --1.1178343485720186e+00 , 3.2160973176583592e+00 , 1.0074944800000001e+01 , -5.6199200000000005e-01 , -4.4419199999999998e-01 , -6.9775200000000004e-01 -5.5770935889980100e-01 , 2.8628249372438290e+00 , 6.9556208000000002e+00 , -9.7980700000000004e-02 , -6.8505899999999995e-02 , 9.9282800000000004e-01 -6.3820840402099388e-01 , 2.8716193310317020e+00 , 6.9584807999999994e+00 , -1.7767100000000000e-01 , 1.1420600000000000e-01 , 9.7744100000000000e-01 -7.1462030653707598e-01 , 2.8811026679271605e+00 , 6.9691615999999996e+00 , -6.3495999999999997e-01 , -1.8769000000000001e-02 , 7.7231700000000003e-01 -7.6332873338762175e-01 , 2.8985742060385760e+00 , 7.0451648000000002e+00 , 4.6449699999999999e-01 , 1.3681399999999999e-01 , -8.7494300000000003e-01 -7.8633772810486136e-01 , 2.9251617687326710e+00 , 7.1873431999999999e+00 , -9.7178600000000004e-01 , -2.1283400000000000e-01 , -1.0165500000000000e-01 -7.2837879420751728e-01 , 2.9808491461241489e+00 , 7.5514992000000003e+00 , -9.3965100000000001e-01 , -1.1234600000000000e-01 , 3.2316200000000000e-01 --1.4625831514265109e-02 , 3.2868591407622891e+00 , 9.8288392000000009e+00 , -5.6938500000000003e-02 , 1.5737799999999999e-01 , 9.8589599999999999e-01 -1.2393790814115535e+00 , 2.8696811934886508e+00 , 6.5817303999999996e+00 , -3.7723899999999999e-01 , 6.3017500000000004e-02 , -9.2396999999999996e-01 -7.3802921224553564e-01 , 3.1112472690506587e+00 , 8.3272456000000012e+00 , 4.8196800000000001e-01 , -8.4843900000000005e-01 , 2.1876499999999999e-01 -8.0301772225917811e-01 , 3.1381630157868479e+00 , 8.4430912000000014e+00 , 5.4284500000000002e-01 , -8.2771799999999995e-01 , 1.4213400000000001e-01 -7.8549359136554342e-01 , 3.2050287717714498e+00 , 8.8555656000000003e+00 , -3.9809200000000000e-01 , 3.8557999999999998e-01 , -8.3237700000000003e-01 -9.0839107976905131e-01 , 3.2091427389943705e+00 , 8.8020680000000002e+00 , -5.6230999999999998e-01 , 7.2214800000000001e-01 , 4.0287800000000001e-01 -1.0216715639637797e+00 , 3.2160824287469669e+00 , 8.7763591999999999e+00 , 9.9961400000000000e-01 , -2.3078999999999999e-02 , 1.5492700000000000e-02 -1.2337007035977501e+00 , 3.1600997904646579e+00 , 8.3171055999999997e+00 , 4.6974300000000002e-01 , 7.5482000000000005e-01 , -4.5780799999999999e-01 -1.5107385901514643e+00 , 3.0465162125829441e+00 , 7.4699216000000002e+00 , -2.6493600000000000e-01 , 7.6862899999999998e-02 , 9.6119800000000000e-01 -1.5957554288268478e+00 , 3.0513769420003714e+00 , 7.4436615999999995e+00 , 1.6386600000000001e-01 , -5.4265100000000001e-04 , -9.8648300000000000e-01 -1.4456950846818049e+00 , 3.2517694625599711e+00 , 8.7330223999999994e+00 , 5.8454899999999999e-01 , 2.3820900000000000e-01 , 7.7560300000000004e-01 -1.5144366903231905e+00 , 3.2938776720669756e+00 , 8.9408872000000006e+00 , -7.7612899999999996e-01 , 5.3961300000000001e-01 , -3.2625399999999999e-01 -1.6367008098803466e+00 , 3.2869758254575014e+00 , 8.8220255999999999e+00 , 3.3865299999999998e-01 , -6.7034700000000003e-01 , 6.6026399999999996e-01 --1.1670067035667264e+00 , 1.7468306867808860e+00 , 6.6371439999999993e-01 , -7.5998800000000005e-02 , 1.7946599999999999e-01 , 9.8082400000000003e-01 --1.3387929604674706e+00 , 1.7310555741019966e+00 , 6.4362159999999990e-01 , 8.3863999999999994e-02 , -1.7931500000000000e-01 , -9.8021100000000005e-01 --1.4956630501060126e+00 , 1.7199573936557164e+00 , 6.3939919999999995e-01 , -8.2712700000000000e-02 , 1.8500600000000000e-01 , 9.7924999999999995e-01 --1.7159192332302355e+00 , 1.6977260993769585e+00 , 6.0326959999999996e-01 , -9.5240500000000006e-02 , 1.6058300000000000e-01 , 9.8241699999999998e-01 --1.9125695594969883e+00 , 1.6810673242598553e+00 , 5.8930239999999978e-01 , -8.8625899999999994e-02 , 1.6011600000000001e-01 , 9.8311199999999999e-01 --2.1552592675266666e+00 , 1.6583686603240786e+00 , 5.5661519999999998e-01 , -9.9251599999999995e-02 , 1.4921599999999999e-01 , 9.8381099999999999e-01 --2.3999256761691772e+00 , 1.6362604156773068e+00 , 5.3169679999999997e-01 , -8.6067000000000005e-02 , 1.4835899999999999e-01 , 9.8518099999999997e-01 --2.6752914015257678e+00 , 1.6120591165852236e+00 , 5.0039279999999997e-01 , -8.2022700000000004e-02 , 1.4492099999999999e-01 , 9.8603799999999997e-01 --2.9538507487827141e+00 , 1.5876985683877376e+00 , 4.7814719999999999e-01 , -8.8887700000000000e-02 , 1.4010300000000001e-01 , 9.8613899999999999e-01 --3.2901782515140710e+00 , 1.5570513852527177e+00 , 4.3873119999999988e-01 , -1.0014800000000000e-01 , 1.5545900000000001e-01 , 9.8275299999999999e-01 --3.6667492904698431e+00 , 1.5227626980696842e+00 , 3.9373039999999992e-01 , -1.0415000000000001e-01 , 1.6399800000000000e-01 , 9.8094700000000001e-01 --4.0669074836936190e+00 , 1.4871541371321220e+00 , 3.5295199999999993e-01 , -8.0427799999999994e-02 , 1.6231999999999999e-01 , 9.8345499999999997e-01 --4.4987669060135227e+00 , 1.4490032366981986e+00 , 3.1387919999999991e-01 , -8.2742499999999997e-02 , 1.5275400000000000e-01 , 9.8479399999999995e-01 --5.0307573465170048e+00 , 1.4010665496746697e+00 , 2.5230079999999999e-01 , -9.2129900000000001e-02 , 1.5537400000000001e-01 , 9.8355000000000004e-01 --5.6253115484912053e+00 , 1.3477291881020017e+00 , 1.8745679999999987e-01 , -9.3455200000000002e-02 , 1.5148400000000001e-01 , 9.8403200000000002e-01 --6.3413326328204018e+00 , 1.2818122890673109e+00 , 1.0275919999999994e-01 , -9.4781599999999994e-02 , 1.5111100000000000e-01 , 9.8396200000000000e-01 --7.1421954249179418e+00 , 1.2097309870803694e+00 , 1.6823999999999950e-02 , -8.7649099999999994e-02 , 1.5399800000000000e-01 , 9.8417600000000005e-01 --8.1165214452777619e+00 , 1.1212481223426356e+00 , -9.2687999999999882e-02 , -8.1078999999999998e-02 , 1.4814300000000000e-01 , 9.8563699999999999e-01 --9.1283617391863849e+00 , 1.0349763975700759e+00 , -1.7811360000000009e-01 , -8.1411499999999998e-02 , 1.4270099999999999e-01 , 9.8641199999999996e-01 --1.0545228366656380e+01 , 9.0627825852818833e-01 , -3.3394720000000033e-01 , -8.1054000000000001e-02 , 1.4632999999999999e-01 , 9.8590999999999995e-01 --1.2294179387854431e+01 , 7.4955775356710941e-01 , -5.2057520000000013e-01 , -8.7996800000000000e-02 , 1.4532999999999999e-01 , 9.8546199999999995e-01 --1.4436479822986538e+01 , 5.5976024591268980e-01 , -7.3402480000000025e-01 , 2.6174800000000002e-02 , 2.5365100000000002e-01 , 9.6694199999999997e-01 --1.7340299644199515e+01 , 3.0208964848647701e-01 , -1.0302792000000003e+00 , 5.3612899999999998e-02 , 2.1429899999999999e-01 , 9.7529600000000005e-01 --7.6581134577737355e+00 , 1.9699672062447879e+00 , 4.8711903999999997e+00 , -1.4444299999999999e-01 , 3.5722999999999999e-01 , 9.2278000000000004e-01 --7.5661473742168521e+00 , 2.0029139886431970e+00 , 5.0332328000000004e+00 , -2.9407599999999999e-02 , 5.6413400000000002e-01 , 8.2515899999999998e-01 --8.0401424924644740e+00 , 2.0150042969197215e+00 , 5.3136272000000000e+00 , -5.1794899999999999e-01 , -4.4266499999999998e-01 , -7.3196799999999995e-01 --6.9282941299909915e+00 , 2.0841854848626231e+00 , 5.2459959999999999e+00 , 5.0910000000000000e-01 , -1.8795799999999999e-01 , -8.3993399999999996e-01 --6.6788725050475186e+00 , 2.1197410563933783e+00 , 5.3544368000000002e+00 , -5.6378300000000003e-01 , 1.9674000000000000e-01 , 8.0214799999999997e-01 --6.0763330118652483e+00 , 2.1641524452441132e+00 , 5.3609160000000005e+00 , -2.4906700000000001e-01 , 2.3066400000000001e-01 , 9.4061700000000004e-01 --6.1271910778928422e+00 , 2.1893173295635973e+00 , 5.5329528000000003e+00 , 1.7828700000000000e-01 , -2.9947800000000002e-01 , -9.3729700000000005e-01 --2.3540902994075719e+00 , 2.2992831309904580e+00 , 4.5438296000000005e+00 , -8.7142600000000003e-01 , -2.6679100000000000e-01 , -4.1163000000000000e-01 --2.2692690500310917e+00 , 2.3158087234522484e+00 , 4.6070720000000005e+00 , -8.7142600000000003e-01 , -2.6679100000000000e-01 , -4.1163000000000000e-01 --2.3307861254496176e+00 , 2.3292201019150096e+00 , 4.7184872000000002e+00 , -7.5947399999999998e-01 , -3.9091700000000001e-01 , -5.1998400000000000e-01 --5.3145032768607825e+00 , 2.3070800858761018e+00 , 5.8902760000000001e+00 , -9.2293000000000003e-01 , 3.7081900000000001e-01 , -1.0341100000000000e-01 --5.3719129017210916e+00 , 2.3308001767081072e+00 , 6.0642991999999998e+00 , -9.2293000000000003e-01 , 3.7081799999999998e-01 , -1.0341100000000000e-01 --5.3967532612769595e+00 , 2.3566018752478399e+00 , 6.2292224000000003e+00 , -9.2293000000000003e-01 , 3.7081900000000001e-01 , -1.0341100000000000e-01 --5.4849951454205614e+00 , 2.3816591973566994e+00 , 6.4243471999999997e+00 , -9.1573800000000005e-01 , 4.0004600000000001e-01 , 3.7247200000000001e-02 --5.4365495381891726e+00 , 2.4088082267902182e+00 , 6.5641648000000004e+00 , -9.3933100000000003e-01 , -2.0352899999999999e-01 , 2.7610299999999999e-01 --5.2050634277689012e+00 , 2.4346370747663477e+00 , 6.6205432000000002e+00 , -7.3291700000000004e-01 , 3.9047300000000001e-01 , 5.5710300000000001e-01 --4.4784147502838829e+00 , 2.4552981267161726e+00 , 6.4301920000000008e+00 , -8.3942600000000001e-01 , 4.3520100000000000e-01 , 3.2552199999999998e-01 --4.4100732339171094e+00 , 2.4795190968612766e+00 , 6.5438847999999998e+00 , -9.2159400000000002e-01 , 1.0685900000000000e-01 , 3.7315700000000002e-01 --4.4323249147648625e+00 , 2.5043811562435918e+00 , 6.7047104000000006e+00 , -8.3121199999999995e-01 , 1.6027300000000000e-01 , 5.3235299999999997e-01 --4.4416246943873130e+00 , 2.5291096997464719e+00 , 6.8623848000000001e+00 , 8.6414999999999997e-01 , 3.4264200000000000e-01 , -3.6856699999999998e-01 --6.3525529028944181e+00 , 2.5960353281695583e+00 , 8.1096360000000001e+00 , -8.5082300000000000e-01 , 5.0528899999999999e-01 , -1.4416300000000001e-01 --4.1905144580500631e+00 , 2.5749187331570411e+00 , 7.0273704000000006e+00 , -8.6092100000000005e-02 , -9.8486399999999996e-01 , 1.5043400000000001e-01 --4.0689219520767104e+00 , 2.5965106354521197e+00 , 7.1078039999999998e+00 , -3.4521900000000000e-01 , -9.1876999999999998e-01 , 1.9153500000000001e-01 --3.9630085858775894e+00 , 2.6183411294907577e+00 , 7.1965992000000005e+00 , -6.1134100000000002e-01 , -7.6408799999999999e-01 , 2.0599000000000001e-01 --2.7230595802161570e+00 , 2.5980149993322121e+00 , 6.5275775999999999e+00 , 1.6068900000000000e-01 , 8.6091099999999998e-01 , 4.8271300000000000e-01 --2.2094328265658110e+00 , 2.5985001535420427e+00 , 6.3022720000000003e+00 , 1.3397500000000001e-01 , 7.4837299999999995e-01 , 6.4960700000000005e-01 --1.8740607009759453e+00 , 2.6022943404292707e+00 , 6.1818504000000010e+00 , 4.9136900000000000e-01 , 5.7729799999999998e-01 , 6.5213800000000000e-01 --1.8865626101834763e+00 , 2.6222989549190991e+00 , 6.3048512000000008e+00 , -4.9136900000000000e-01 , -5.7729799999999998e-01 , -6.5213800000000000e-01 --5.2942493460294369e+00 , 2.8268633806052414e+00 , 9.0489744000000005e+00 , -6.4093999999999998e-02 , 2.8682200000000002e-01 , 9.5583799999999997e-01 --5.0350344881630242e+00 , 2.8471391892020694e+00 , 9.0573879999999996e+00 , 1.3604400000000000e-01 , -3.2025799999999999e-01 , -9.3751099999999998e-01 --4.9701442119785373e+00 , 2.8777066102548980e+00 , 9.2176831999999997e+00 , 1.3604400000000000e-01 , -3.2025799999999999e-01 , -9.3751099999999998e-01 --1.1313424513390844e+00 , 2.6505769149956486e+00 , 6.1478320000000002e+00 , -4.1375500000000003e-02 , 6.8100600000000000e-01 , 7.3110799999999998e-01 --1.1164307744809285e+00 , 2.6670020163371304e+00 , 6.2430440000000003e+00 , -4.1375500000000003e-02 , 6.8100600000000000e-01 , 7.3110799999999998e-01 --1.3361798702494410e+00 , 2.7034119858306829e+00 , 6.5560840000000002e+00 , -6.3554999999999995e-01 , 6.8274199999999996e-01 , -3.6047099999999999e-01 --1.9747299257461775e+00 , 2.7769168776656779e+00 , 7.2853424000000002e+00 , 5.3677000000000002e-02 , 9.2201599999999995e-01 , 3.8341199999999998e-01 --2.6030187298965179e+00 , 2.8574892443995372e+00 , 8.0518640000000001e+00 , -6.0225000000000001e-03 , 9.4262299999999999e-01 , 3.3380399999999999e-01 --2.2028897608809261e+00 , 2.8475419145809560e+00 , 7.8190911999999999e+00 , 1.2008300000000000e-01 , 9.8038800000000004e-01 , 1.5626999999999999e-01 --1.0343926500309020e+00 , 2.7567772023025290e+00 , 6.7536008000000010e+00 , 7.1757099999999996e-01 , 5.1636899999999997e-01 , -4.6739199999999997e-01 --9.8444533040743032e-01 , 2.7727489749540166e+00 , 6.8277112000000004e+00 , -7.1213199999999999e-01 , -6.6897700000000004e-01 , 2.1292500000000000e-01 --9.3849507098004903e-01 , 2.7892793899855977e+00 , 6.9090288000000006e+00 , -7.7712199999999998e-01 , -6.0447099999999998e-01 , 1.7520600000000000e-01 --9.1823638505230765e-01 , 2.8099506178736826e+00 , 7.0212136000000003e+00 , -6.4548799999999995e-01 , -6.7108199999999996e-01 , 3.6468400000000001e-01 --1.8386725540723861e+00 , 2.9496839435043372e+00 , 8.2772943999999988e+00 , -4.9026100000000003e-02 , 5.5319600000000002e-01 , 8.3160699999999999e-01 --1.6896059411344817e+00 , 2.9601213611936452e+00 , 8.2765664000000001e+00 , 2.7793400000000001e-01 , 7.7932699999999999e-01 , 5.6160600000000005e-01 -5.8724209620283463e-01 , 2.6688702456532218e+00 , 5.5038432000000004e+00 , -8.5388299999999995e-01 , -2.1575000000000000e-01 , 4.7364099999999998e-01 -4.9979040701329724e-01 , 2.6961018154620846e+00 , 5.7099399999999996e+00 , 1.5927000000000000e-02 , -2.6213999999999998e-01 , 9.6489800000000003e-01 -6.1290480618320053e-01 , 2.6950767850852273e+00 , 5.6499424000000005e+00 , -5.4494100000000001e-01 , -5.2388200000000003e-02 , 8.3683600000000002e-01 -6.5753186084116355e-01 , 2.7035819491962334e+00 , 5.6805912000000003e+00 , -4.2204300000000000e-01 , 2.9020899999999999e-01 , 8.5887000000000002e-01 -6.9805248909302953e-01 , 2.7128188381003873e+00 , 5.7192791999999999e+00 , 4.7945800000000000e-01 , -4.0899300000000000e-01 , -7.7643099999999998e-01 -7.5536659410361628e-01 , 2.7180997802369626e+00 , 5.7313536000000003e+00 , 5.2809099999999998e-01 , 5.4647000000000001e-01 , -6.4999300000000004e-01 -7.8561226687001273e-01 , 2.7299165361898652e+00 , 5.7859328000000003e+00 , 1.6502900000000001e-01 , 4.5980599999999999e-01 , -8.7255000000000005e-01 -8.8626876678956212e-01 , 2.7270644028919753e+00 , 5.7247287999999994e+00 , -4.1877500000000001e-01 , 5.7565699999999997e-01 , -7.0231500000000002e-01 -8.8718032758478249e-01 , 2.7443496563188194e+00 , 5.8318072000000001e+00 , -2.5165199999999999e-01 , 6.3178299999999998e-01 , -7.3315799999999998e-01 -6.9278225643386504e-01 , 2.8082315462966432e+00 , 6.3023968000000004e+00 , -9.8479200000000000e-01 , 1.3000900000000001e-01 , -1.1525199999999999e-01 -8.3584394066194889e-01 , 2.7959962643238558e+00 , 6.1667808000000006e+00 , -6.7298100000000005e-01 , 3.7910400000000000e-01 , -6.3511899999999999e-01 --8.4964682775354117e-01 , 3.2487504414482586e+00 , 9.6670775999999989e+00 , -2.5629099999999999e-01 , -5.3185899999999997e-01 , -8.0711900000000003e-01 -5.9639601820750721e-01 , 2.9069691348866620e+00 , 6.9458240000000009e+00 , -3.0603799999999998e-01 , -1.5510599999999999e-01 , 9.3929900000000000e-01 -6.6940411390996712e-01 , 2.9155502555023185e+00 , 6.9670920000000001e+00 , -5.1097700000000001e-01 , -1.6520899999999999e-01 , 8.4356900000000001e-01 -7.1265991713947785e-01 , 2.9321287225656469e+00 , 7.0533288000000001e+00 , -7.3929599999999995e-01 , -1.4600099999999999e-01 , 6.5736300000000003e-01 -7.9450926752525719e-01 , 2.9381513293972712e+00 , 7.0532871999999998e+00 , -1.7188999999999999e-01 , -1.9597700000000001e-01 , 9.6542600000000001e-01 -6.8201471661964619e-01 , 3.0104374214396499e+00 , 7.5408911999999999e+00 , -9.3965100000000001e-01 , -1.1234600000000000e-01 , 3.2316200000000000e-01 --7.0951130794095985e-02 , 3.3241801670193132e+00 , 9.7807080000000006e+00 , -5.6938500000000003e-02 , 1.5737799999999999e-01 , 9.8589599999999999e-01 -1.1970889379630192e+00 , 2.8926099271174928e+00 , 6.5969144000000002e+00 , 4.0134199999999998e-01 , -3.2064200000000001e-02 , 9.1536700000000004e-01 -1.1826691345780895e+00 , 2.9319748725034471e+00 , 6.8419384000000001e+00 , 9.0236399999999994e-02 , 8.1528000000000000e-01 , -5.7199400000000000e-01 -6.9660365675214941e-01 , 3.1852377654637110e+00 , 8.6013687999999995e+00 , -5.5201500000000003e-01 , 7.9997700000000005e-01 , -2.3519499999999999e-01 -8.4434730535390501e-01 , 3.1730697470120095e+00 , 8.4618111999999996e+00 , 3.7060599999999999e-01 , -8.7060599999999999e-01 , 3.2356800000000002e-01 -8.5078935444332049e-01 , 3.2302665118532481e+00 , 8.8050215999999999e+00 , -3.9444600000000002e-01 , 9.1809799999999997e-01 , 3.8844200000000002e-02 -9.7489204452131051e-01 , 3.2289794547891075e+00 , 8.7408120000000018e+00 , 5.8101000000000003e-01 , -7.4506399999999995e-01 , -3.2757700000000001e-01 -1.1350674771093037e+00 , 3.2029791252461264e+00 , 8.5141647999999996e+00 , -1.4098200000000000e-01 , -8.0759000000000003e-01 , 5.7264499999999996e-01 -1.4106362044085234e+00 , 3.0939472005020021e+00 , 7.7313983999999998e+00 , -3.7796099999999999e-01 , 9.2384100000000002e-01 , -6.0518400000000000e-02 -1.3332648010719437e+00 , 3.2187173720813615e+00 , 8.5239095999999996e+00 , 2.4517100000000000e-01 , 9.2266700000000001e-01 , -2.9761900000000002e-01 -1.3911451786411109e+00 , 3.2593667083392956e+00 , 8.7432976000000000e+00 , 8.0438599999999999e-03 , -9.8936999999999997e-01 , 1.4519699999999999e-01 -1.5070580762868415e+00 , 3.2552310074738160e+00 , 8.6684488000000002e+00 , -6.3963899999999996e-01 , -1.5021000000000001e-01 , -7.5385599999999997e-01 -1.5757867573995834e+00 , 3.2940788591850323e+00 , 8.8759183999999998e+00 , 3.6932100000000001e-01 , -3.2302900000000001e-01 , 8.7135200000000002e-01 -1.6757064633645107e+00 , 3.3071177500177740e+00 , 8.9092711999999992e+00 , -7.8362600000000004e-01 , -6.0945700000000003e-01 , 1.2038400000000000e-01 diff --git a/thirdparty/libpointmatcher/examples/data/car_cloud401.csv b/thirdparty/libpointmatcher/examples/data/car_cloud401.csv deleted file mode 100644 index a2b2caf..0000000 --- a/thirdparty/libpointmatcher/examples/data/car_cloud401.csv +++ /dev/null @@ -1,25193 +0,0 @@ - 2.6247663e+00 5.2711742e-02 -1.0169336e+00 - 2.6960227e+00 5.4603520e-02 -1.0133617e+00 - 2.7682294e+00 5.5536428e-02 -1.0077459e+00 - 2.8635275e+00 5.8209555e-02 -1.0197800e+00 - 2.9448251e+00 6.0488862e-02 -1.0163893e+00 - 3.0270743e+00 6.1819152e-02 -1.0107550e+00 - 3.1093978e+00 6.4259712e-02 -1.0028730e+00 - 3.2076937e+00 6.6261988e-02 -1.0045798e+00 - 3.3160738e+00 6.9510798e-02 -1.0093139e+00 - 3.4244134e+00 7.1920310e-02 -1.0108024e+00 - 3.5427813e+00 7.4613888e-02 -1.0145695e+00 - 3.6611702e+00 7.7474976e-02 -1.0149408e+00 - 3.7895917e+00 8.0654617e-02 -1.0168916e+00 - 3.9190354e+00 8.3965952e-02 -1.0149504e+00 - 4.0755443e+00 8.8108841e-02 -1.0239305e+00 - 4.2340195e+00 9.1375286e-02 -1.0279735e+00 - 4.4016011e+00 9.6111298e-02 -1.0317446e+00 - 4.5791694e+00 1.0028222e-01 -1.0347486e+00 - 4.7677862e+00 1.0485413e-01 -1.0364388e+00 - 4.9664573e+00 1.0991703e-01 -1.0362128e+00 - 5.1931636e+00 1.1501026e-01 -1.0416681e+00 - 5.4229702e+00 1.2128368e-01 -1.0397917e+00 - 5.6617832e+00 1.2719534e-01 -1.0342485e+00 - 5.9496898e+00 1.3367458e-01 -1.0383478e+00 - 6.2386531e+00 1.4056142e-01 -1.0329619e+00 - 6.5667673e+00 1.4893072e-01 -1.0308946e+00 - 6.9259581e+00 1.5752345e-01 -1.0269276e+00 - 7.3534000e+00 1.6861968e-01 -1.0309145e+00 - 7.7918343e+00 1.7863537e-01 -1.0231013e+00 - 8.3587125e+00 1.9304125e-01 -1.0332185e+00 - 8.9376730e+00 2.0755435e-01 -1.0264946e+00 - 9.6249563e+00 2.2434395e-01 -1.0239559e+00 - 1.0550929e+01 2.4657399e-01 -1.0456868e+00 - 1.1597349e+01 2.7204182e-01 -1.0577078e+00 - 1.3130276e+01 3.1003254e-01 -1.1145004e+00 - 1.4766615e+01 3.4969022e-01 -1.1331657e+00 - 1.6823383e+01 4.0014623e-01 -1.1501529e+00 - 2.0017729e+01 4.7832164e-01 -1.2248905e+00 - 2.4228834e+01 5.8170285e-01 -8.6860687e-01 - 2.4786881e+01 5.9507519e-01 -4.8643481e-01 - 2.5198560e+01 6.0549030e-01 -7.9283859e-02 - 2.4914004e+01 5.9836873e-01 3.5996312e-01 - 2.8210236e+01 6.7981565e-01 7.5741861e-01 - 2.5351202e+01 6.0951004e-01 1.2163751e+00 - 2.3384864e+01 5.6072455e-01 1.5988733e+00 - 2.1013970e+01 5.0301375e-01 1.8953995e+00 - 2.1993541e+01 5.2686427e-01 2.3145020e+00 - 2.0381983e+01 4.8719163e-01 2.5648010e+00 - 2.0083025e+01 4.8007773e-01 2.8857905e+00 - 1.9987813e+01 4.7838959e-01 3.2204735e+00 - 1.9847331e+01 4.7403293e-01 3.5473574e+00 - 2.1005853e+01 5.0300673e-01 4.0650259e+00 - 2.1668545e+01 5.1883440e-01 4.5430500e+00 - 2.1594495e+01 5.1748292e-01 4.9102260e+00 - 2.1052524e+01 5.0355299e-01 5.1821891e+00 - 2.0839877e+01 4.9858859e-01 5.5100491e+00 - 1.8784686e+01 4.4827523e-01 5.3905513e+00 - 1.8453430e+01 4.4075728e-01 5.6439765e+00 - 1.7898168e+01 4.2716204e-01 5.8257939e+00 - 1.7551712e+01 4.1821382e-01 6.0521499e+00 - 1.8433570e+01 4.4008568e-01 6.6557800e+00 - 2.1764223e+01 5.2114571e-01 8.1165538e+00 - 2.0845476e+01 4.9885183e-01 8.2063272e+00 - 1.9621233e+01 4.6872567e-01 8.1506906e+00 - 1.9902775e+01 4.7626717e-01 8.6445924e+00 - 2.1382862e+01 5.1215638e-01 9.6518415e+00 - 2.0999400e+01 5.0227800e-01 9.9154174e+00 - 2.0995773e+01 5.0265179e-01 1.0342348e+01 - 2.2264300e+01 5.3393528e-01 1.1383270e+01 - 2.0567482e+01 4.9237541e-01 1.1007615e+01 - 2.0682463e+01 4.9529288e-01 1.1508781e+01 - 2.0777372e+01 4.9752397e-01 1.2012107e+01 - 2.0929583e+01 5.0058933e-01 1.2561495e+01 - 4.4968824e+00 9.8735760e-02 3.3548491e+00 - 4.4458869e+00 9.6981397e-02 3.4190291e+00 - 4.3526747e+00 9.4387611e-02 3.4553763e+00 - 4.2766048e+00 9.3183785e-02 3.5001599e+00 - 4.2809092e+00 9.2854382e-02 3.5996723e+00 - 4.1947463e+00 9.0849182e-02 3.6362474e+00 - 4.2765221e+00 9.2823772e-02 3.7955425e+00 - 4.2195080e+00 9.1195626e-02 3.8549474e+00 - 4.1454407e+00 8.9920166e-02 3.9007234e+00 - 4.1719345e+00 9.0612671e-02 4.0275824e+00 - 4.1028279e+00 8.8279417e-02 4.0782859e+00 - 4.1836828e+00 9.0416163e-02 4.2599062e+00 - 4.0603192e+00 8.7985421e-02 4.2628902e+00 - 4.2418360e+00 9.2379053e-02 4.5517109e+00 - 4.2150172e+00 9.0937662e-02 4.6515704e+00 - 4.1500480e+00 9.0034525e-02 4.7158948e+00 - 4.0296315e+00 8.6528939e-02 4.7210162e+00 - 4.2213928e+00 9.1902724e-02 5.0621900e+00 - 3.9117161e+00 8.4356918e-02 4.8569178e+00 - 3.8244923e+00 8.1395505e-02 4.8931462e+00 - 3.8571876e+00 8.2391836e-02 5.0740186e+00 - 3.8294508e+00 8.1651369e-02 5.1868652e+00 - 3.6345122e+00 7.7362257e-02 5.0856536e+00 - 3.5563932e+00 7.5341496e-02 5.1316915e+00 - 3.4551061e+00 7.3031069e-02 5.1437447e+00 - 3.2408695e+00 6.7230071e-02 4.9886600e+00 - 3.4238371e+00 7.1570675e-02 5.4194495e+00 - 3.5293057e+00 7.4932916e-02 5.7565494e+00 - 3.5187798e+00 7.4067810e-02 5.9281686e+00 - 3.4477837e+00 7.2193645e-02 6.0059946e+00 - 3.4090989e+00 7.1341121e-02 6.1436449e+00 - 3.0898946e+00 6.4116921e-02 5.7718101e+00 - 2.7897131e+00 5.6721419e-02 5.3994659e+00 - 2.8105292e+00 5.7169959e-02 5.6356068e+00 - 2.7506164e+00 5.5972671e-02 5.7203396e+00 - 2.6431677e+00 5.2645459e-02 5.7044464e+00 - 2.5609980e+00 5.0403385e-02 5.7411087e+00 - 2.3443678e+00 4.5159270e-02 5.4530473e+00 - 2.3168115e+00 4.4829139e-02 5.6147329e+00 - 2.3095055e+00 4.4552669e-02 5.8424725e+00 - 2.5452875e+00 5.0741372e-02 6.7782681e+00 - 2.4379746e+00 4.7983906e-02 6.7941852e+00 - 1.9880638e+00 3.6856382e-02 5.7207833e+00 - 1.8714175e+00 3.4425110e-02 5.6310115e+00 - 1.7689066e+00 3.1919281e-02 5.5771005e+00 - 1.7466082e+00 3.1358708e-02 5.8212667e+00 - 1.6715092e+00 2.8844459e-02 5.8812276e+00 - 1.7553083e+00 3.1515263e-02 6.6624429e+00 - 1.3593724e+00 2.1023280e-02 5.2234260e+00 - 1.2719520e+00 1.9584904e-02 5.1689686e+00 - 1.1997383e+00 1.7564605e-02 5.1818292e+00 - 1.1357471e+00 1.5924301e-02 5.2526920e+00 - 1.0882765e+00 1.4616779e-02 5.4714188e+00 - 1.0534000e+00 1.3896863e-02 5.8585468e+00 - 9.7124326e-01 1.1758251e-02 5.8973065e+00 - 8.9020022e-01 9.9663522e-03 5.9645774e+00 - 7.8906056e-01 6.9859130e-03 5.7211475e+00 - 7.0362907e-01 5.3675163e-03 5.6654853e+00 - 6.2586678e-01 3.6188044e-03 5.8183394e+00 - 5.5392976e-01 1.4024845e-03 7.1797713e+00 - 2.5639589e+00 -9.6581526e-03 -9.9355705e-01 - 2.6640460e+00 -9.9315130e-03 -1.0186916e+00 - 2.7291796e+00 -1.0293468e-02 -1.0073614e+00 - 2.8093364e+00 -1.0124982e-02 -1.0074640e+00 - 2.8974521e+00 -1.0651946e-02 -1.0118868e+00 - 2.9865820e+00 -1.1111265e-02 -1.0137159e+00 - 3.0687168e+00 -1.1725617e-02 -1.0069837e+00 - 3.1588745e+00 -1.2008902e-02 -1.0040219e+00 - 3.2670038e+00 -1.2826738e-02 -1.0101559e+00 - 3.3672021e+00 -1.2727422e-02 -1.0074752e+00 - 3.4763678e+00 -1.3300250e-02 -1.0074199e+00 - 3.6025158e+00 -1.4278204e-02 -1.0150589e+00 - 3.7306835e+00 -1.5189842e-02 -1.0189089e+00 - 3.8599336e+00 -1.4972833e-02 -1.0189165e+00 - 3.9811328e+00 -1.5827655e-02 -1.0099105e+00 - 4.1553203e+00 -1.7140041e-02 -1.0264401e+00 - 4.3055517e+00 -1.8034826e-02 -1.0233184e+00 - 4.4648273e+00 -1.8471778e-02 -1.0201750e+00 - 4.6611400e+00 -1.8760502e-02 -1.0295827e+00 - 4.8594276e+00 -1.9856697e-02 -1.0326549e+00 - 5.0767294e+00 -2.1193166e-02 -1.0376349e+00 - 5.2950726e+00 -2.2245215e-02 -1.0356268e+00 - 5.5254750e+00 -2.2858199e-02 -1.0303105e+00 - 5.7928893e+00 -2.4039087e-02 -1.0318028e+00 - 6.0912983e+00 -2.6165941e-02 -1.0348416e+00 - 6.3898279e+00 -2.6813022e-02 -1.0281419e+00 - 6.7293284e+00 -2.9054910e-02 -1.0239194e+00 - 7.1359529e+00 -3.0795723e-02 -1.0289467e+00 - 7.5455961e+00 -3.3039878e-02 -1.0202510e+00 - 8.0623777e+00 -3.5468163e-02 -1.0263249e+00 - 8.6112845e+00 -3.7329484e-02 -1.0223124e+00 - 9.2692586e+00 -4.1066045e-02 -1.0243875e+00 - 9.9773976e+00 -4.4228251e-02 -1.0144853e+00 - 1.1012914e+01 -4.9031531e-02 -1.0433685e+00 - 1.2189669e+01 -5.4783435e-02 -1.0609618e+00 - 1.3902118e+01 -6.2978687e-02 -1.1224916e+00 - 1.5650841e+01 -7.0635508e-02 -1.1291038e+00 - 1.8127552e+01 -8.2546709e-02 -1.1640296e+00 - 2.0688648e+01 -9.4705753e-02 -1.1215679e+00 - 2.3591521e+01 -1.0751484e-01 -1.0199084e+00 - 2.3562760e+01 -1.0758747e-01 -6.1232479e-01 - 2.3548016e+01 -1.0764248e-01 -2.0753191e-01 - 2.3545301e+01 -1.0750475e-01 1.9557524e-01 - 2.3565600e+01 -1.0779983e-01 5.9776069e-01 - 2.5859409e+01 -1.1901024e-01 1.0004678e+00 - 2.3576196e+01 -1.0752911e-01 1.4031754e+00 - 2.2925396e+01 -1.0448420e-01 1.7835068e+00 - 2.2998742e+01 -1.0528294e-01 2.1794824e+00 - 2.3313561e+01 -1.0662060e-01 2.5957207e+00 - 2.0463611e+01 -9.3467805e-02 2.7469299e+00 - 2.0091038e+01 -9.1537479e-02 3.0595173e+00 - 2.0678286e+01 -9.4175993e-02 3.4779429e+00 - 2.1403845e+01 -9.8073037e-02 3.9382293e+00 - 2.2633607e+01 -1.0301038e-01 4.5059911e+00 - 2.1013419e+01 -9.5904465e-02 4.6173672e+00 - 2.2467727e+01 -1.0313243e-01 5.2706629e+00 - 2.1040819e+01 -9.6439352e-02 5.3664486e+00 - 1.7570130e+01 -7.9448891e-02 4.9413849e+00 - 1.8925312e+01 -8.5721429e-02 5.5943442e+00 - 1.9093800e+01 -8.6635911e-02 5.9825293e+00 - 1.7859833e+01 -8.1522959e-02 5.9782799e+00 - 2.3326701e+01 -1.0666334e-01 7.9791818e+00 - 2.2068865e+01 -1.0043319e-01 8.0087662e+00 - 1.2450744e+01 -5.5476512e-02 5.1152805e+00 - 1.9443385e+01 -8.8915062e-02 7.8953456e+00 - 1.9301243e+01 -8.7376017e-02 8.2177437e+00 - 2.0479785e+01 -9.2985280e-02 9.0730090e+00 - 2.0731787e+01 -9.4624508e-02 9.5884719e+00 - 2.1876544e+01 -9.9527318e-02 1.0517802e+01 - 2.0537902e+01 -9.3497371e-02 1.0344244e+01 - 2.1845339e+01 -9.9365786e-02 1.1411489e+01 - 2.0644976e+01 -9.4326571e-02 1.1264960e+01 - 2.0718636e+01 -9.4674146e-02 1.1751123e+01 - 4.4702496e+00 -1.8635791e-02 3.2011062e+00 - 4.4143516e+00 -1.8350185e-02 3.2600094e+00 - 4.4681296e+00 -1.8685934e-02 3.4800658e+00 - 4.2737566e+00 -1.7424037e-02 3.4508660e+00 - 4.2389562e+00 -1.6804937e-02 3.5219377e+00 - 4.2512805e+00 -1.7342042e-02 3.6270178e+00 - 4.2696977e+00 -1.6895094e-02 3.7391205e+00 - 4.2529175e+00 -1.7454529e-02 3.8285618e+00 - 4.2110703e+00 -1.7404307e-02 3.8998052e+00 - 4.2917407e+00 -1.7773850e-02 4.0711374e+00 - 4.2077763e+00 -1.6736651e-02 4.1110532e+00 - 4.2131247e+00 -1.7276060e-02 4.2277908e+00 - 4.1632910e+00 -1.6752092e-02 4.2988599e+00 - 4.3244127e+00 -1.7178701e-02 4.5668180e+00 - 4.2836009e+00 -1.7407460e-02 4.6538883e+00 - 4.1835446e+00 -1.6887763e-02 4.6840167e+00 - 4.0975373e+00 -1.6618231e-02 4.7261857e+00 - 4.1622996e+00 -1.6551245e-02 4.9273312e+00 - 4.2532051e+00 -1.7047733e-02 5.1690934e+00 - 3.9631686e+00 -1.5705323e-02 4.9848882e+00 - 4.0088834e+00 -1.5664106e-02 5.1825481e+00 - 3.8223085e+00 -1.5350338e-02 5.1033853e+00 - 3.7071674e+00 -1.4306422e-02 5.1055464e+00 - 3.6110624e+00 -1.4358616e-02 5.1289704e+00 - 3.1568467e+00 -1.2396638e-02 4.6567917e+00 - 3.1442448e+00 -1.1714927e-02 4.7762832e+00 - 3.1617787e+00 -1.2352624e-02 4.9462161e+00 - 3.3968119e+00 -1.2964203e-02 5.4617330e+00 - 3.3722046e+00 -1.2807065e-02 5.5964432e+00 - 3.4865284e+00 -1.4108297e-02 5.9715651e+00 - 3.4700798e+00 -1.3564482e-02 6.1441526e+00 - 3.1131308e+00 -1.2366644e-02 5.7142640e+00 - 2.7953769e+00 -1.0878944e-02 5.3176606e+00 - 2.7193948e+00 -1.0349978e-02 5.3570516e+00 - 2.6252760e+00 -9.5736291e-03 5.3591962e+00 - 2.5411778e+00 -9.6055308e-03 5.3774388e+00 - 2.4520837e+00 -8.8604616e-03 5.3850608e+00 - 2.4224815e+00 -8.9496962e-03 5.5289251e+00 - 2.3576070e+00 -8.5799814e-03 5.5987930e+00 - 2.2382038e+00 -7.8999154e-03 5.5279083e+00 - 2.1308743e+00 -7.6957403e-03 5.4823037e+00 - 1.9871384e+00 -7.0277768e-03 5.3210580e+00 - 1.9455320e+00 -6.0843998e-03 5.4509283e+00 - 1.8178502e+00 -6.2326616e-03 5.3129526e+00 - 1.7316647e+00 -5.8396228e-03 5.2968447e+00 - 1.6485230e+00 -5.2337954e-03 5.2887174e+00 - 1.7094369e+00 -5.0193178e-03 5.8514253e+00 - 1.7706101e+00 -5.3112149e-03 6.5051689e+00 - 1.3959249e+00 -3.6305186e-03 5.2158058e+00 - 1.3106264e+00 -3.6706064e-03 5.1718795e+00 - 1.2375399e+00 -3.5971324e-03 5.1854432e+00 - 1.1706177e+00 -3.0013014e-03 5.2371903e+00 - 1.1180334e+00 -2.9255266e-03 5.3968076e+00 - 1.0759215e+00 -2.6272368e-03 5.6947200e+00 - 1.0155310e+00 -1.6673806e-03 5.9030019e+00 - 9.2631648e-01 -1.3688890e-03 5.8813105e+00 - 8.3490834e-01 -9.7871971e-04 5.7982524e+00 - 7.4330169e-01 -6.2762608e-04 5.6536215e+00 - 6.6435261e-01 -7.2880429e-04 5.7170915e+00 - 6.1532046e-01 -3.0973812e-05 7.6089929e+00 - 2.6162457e+00 -7.1807723e-02 -1.0099377e+00 - 2.6881973e+00 -7.4975948e-02 -1.0064208e+00 - 2.7681655e+00 -7.7862375e-02 -1.0076732e+00 - 2.8551552e+00 -8.0381919e-02 -1.0131922e+00 - 2.9371475e+00 -8.3167542e-02 -1.0099565e+00 - 3.0181557e+00 -8.5779400e-02 -1.0044204e+00 - 3.1081241e+00 -8.9122524e-02 -1.0027082e+00 - 3.2071152e+00 -9.2180252e-02 -1.0044701e+00 - 3.3070621e+00 -9.6152508e-02 -1.0032891e+00 - 3.4150373e+00 -9.9749359e-02 -1.0049797e+00 - 3.5329806e+00 -1.0405910e-01 -1.0088993e+00 - 3.6609541e+00 -1.0806999e-01 -1.0147980e+00 - 3.7809381e+00 -1.1214590e-01 -1.0115329e+00 - 3.9189092e+00 -1.1663319e-01 -1.0148666e+00 - 4.0488910e+00 -1.2118551e-01 -1.0090364e+00 - 4.2148352e+00 -1.2665420e-01 -1.0183015e+00 - 4.3737925e+00 -1.3221387e-01 -1.0177069e+00 - 4.5607069e+00 -1.3888304e-01 -1.0256405e+00 - 4.7486565e+00 -1.4531705e-01 -1.0275847e+00 - 4.9465988e+00 -1.5226687e-01 -1.0277628e+00 - 5.1645554e+00 -1.5950265e-01 -1.0295523e+00 - 5.4024722e+00 -1.6797205e-01 -1.0319048e+00 - 5.6604151e+00 -1.7663379e-01 -1.0339709e+00 - 5.9293686e+00 -1.8571415e-01 -1.0310781e+00 - 6.2182990e+00 -1.9589511e-01 -1.0260516e+00 - 6.5562217e+00 -2.0734967e-01 -1.0274724e+00 - 6.8952123e+00 -2.1830796e-01 -1.0176103e+00 - 7.2941186e+00 -2.3217219e-01 -1.0135817e+00 - 7.7709554e+00 -2.4913204e-01 -1.0174907e+00 - 8.3178377e+00 -2.6738671e-01 -1.0228697e+00 - 8.9057021e+00 -2.8766164e-01 -1.0190904e+00 - 9.5735588e+00 -3.1063086e-01 -1.0126684e+00 - 1.0508284e+01 -3.4223578e-01 -1.0373045e+00 - 1.1574943e+01 -3.7938771e-01 -1.0535704e+00 - 1.2988508e+01 -4.2750505e-01 -1.0908607e+00 - 1.4694003e+01 -4.8594036e-01 -1.1222353e+00 - 1.6670516e+01 -5.5354913e-01 -1.1298995e+00 - 1.9743570e+01 -6.5907851e-01 -1.1935249e+00 - 2.4052657e+01 -8.0620703e-01 -8.5432450e-01 - 2.4520761e+01 -8.2238387e-01 -4.6963901e-01 - 2.4702013e+01 -8.2886873e-01 -5.6927946e-02 - 2.6805710e+01 -9.0052893e-01 3.1118680e-01 - 4.6211008e+01 -1.5657282e+00 6.0157921e-01 - 2.5633851e+01 -8.6081491e-01 1.2198758e+00 - 2.5866212e+01 -8.6877168e-01 1.6650843e+00 - 2.3923836e+01 -8.0183099e-01 2.0237039e+00 - 2.3703114e+01 -7.9486148e-01 2.4204106e+00 - 2.1064413e+01 -7.0380834e-01 2.6197387e+00 - 2.0395468e+01 -6.8171687e-01 2.9172415e+00 - 1.9962545e+01 -6.6664686e-01 3.2190404e+00 - 2.1267915e+01 -7.1076867e-01 3.7361039e+00 - 2.2709401e+01 -7.6071411e-01 4.3215997e+00 - 2.1101206e+01 -7.0535249e-01 4.4497451e+00 - 2.2265781e+01 -7.4551227e-01 5.0368680e+00 - 1.9900086e+01 -6.6412262e-01 4.9497357e+00 - 2.2960609e+01 -7.6955976e-01 5.9827356e+00 - 1.8409581e+01 -6.1272414e-01 5.3026280e+00 - 1.8815820e+01 -6.2756611e-01 5.7398940e+00 - 1.9635493e+01 -6.5474601e-01 6.3102831e+00 - 1.9750701e+01 -6.5908553e-01 6.7060748e+00 - 1.9410594e+01 -6.4767936e-01 6.9662306e+00 - 2.0857975e+01 -6.9688886e-01 7.8158795e+00 - 1.8936534e+01 -6.3100646e-01 7.5328307e+00 - 1.9212956e+01 -6.4048988e-01 8.0008710e+00 - 1.9515432e+01 -6.5124622e-01 8.4951457e+00 - 2.1912243e+01 -7.3347699e-01 9.8746215e+00 - 2.1808549e+01 -7.2957260e-01 1.0271158e+01 - 2.0688608e+01 -6.9122342e-01 1.0206393e+01 - 2.0805119e+01 -6.9524120e-01 1.0690970e+01 - 4.5695851e+00 -1.3945217e-01 3.0302353e+00 - 4.4923596e+00 -1.3639557e-01 3.2602445e+00 - 4.3313992e+00 -1.3076919e-01 3.2585576e+00 - 4.3516970e+00 -1.3188350e-01 3.3617146e+00 - 4.3179630e+00 -1.3026385e-01 3.4340320e+00 - 4.2501508e+00 -1.2771219e-01 3.4836856e+00 - 4.2394099e+00 -1.2771620e-01 3.5714603e+00 - 4.3158476e+00 -1.3079364e-01 3.7235282e+00 - 4.1949634e+00 -1.2587392e-01 3.7361467e+00 - 4.2734560e+00 -1.2860422e-01 3.8976965e+00 - 4.2386981e+00 -1.2764518e-01 3.9756597e+00 - 4.2089681e+00 -1.2669278e-01 4.0595996e+00 - 4.0408865e+00 -1.2119822e-01 4.0264243e+00 - 4.4222223e+00 -1.3411509e-01 4.4721594e+00 - 4.2571759e+00 -1.2847671e-01 4.4455663e+00 - 4.2836167e+00 -1.2975523e-01 4.5932485e+00 - 4.2208933e+00 -1.2672248e-01 4.6587666e+00 - 4.2403611e+00 -1.2746454e-01 4.8087681e+00 - 4.1665477e+00 -1.2516285e-01 4.8662807e+00 - 4.0987598e+00 -1.2293319e-01 4.9296670e+00 - 4.0891550e+00 -1.2292726e-01 5.0593859e+00 - 4.5883746e+00 -1.3981253e-01 5.7905418e+00 - 4.1041705e+00 -1.2318897e-01 5.3750956e+00 - 3.7724173e+00 -1.1198694e-01 5.1165702e+00 - 3.5420310e+00 -1.0350920e-01 4.9667882e+00 - 3.4601625e+00 -1.0076650e-01 5.0032027e+00 - 3.1462981e+00 -9.0245071e-02 4.7123607e+00 - 3.1145800e+00 -8.9621860e-02 4.8074428e+00 - 3.2687923e+00 -9.4160681e-02 5.1860827e+00 - 3.7003263e+00 -1.0954578e-01 6.0266169e+00 - 3.2206150e+00 -9.2563275e-02 5.4422169e+00 - 3.4825431e+00 -1.0143973e-01 6.0663091e+00 - 3.1372959e+00 -9.0495649e-02 5.6651036e+00 - 2.8362300e+00 -8.0117499e-02 5.3062058e+00 - 3.0148973e+00 -8.5730192e-02 5.8342321e+00 - 2.6895554e+00 -7.4910886e-02 5.3941621e+00 - 2.6076984e+00 -7.1560444e-02 5.4226368e+00 - 2.4935624e+00 -6.7942255e-02 5.3769058e+00 - 2.4005946e+00 -6.4457195e-02 5.3744042e+00 - 2.3085524e+00 -6.2128075e-02 5.3699514e+00 - 2.2135678e+00 -5.8170562e-02 5.3543227e+00 - 2.1165171e+00 -5.4648871e-02 5.3274144e+00 - 2.0214499e+00 -5.1351540e-02 5.2984023e+00 - 1.9303613e+00 -4.8923459e-02 5.2769177e+00 - 1.8433731e+00 -4.5360865e-02 5.2630614e+00 - 1.7512652e+00 -4.2525708e-02 5.2283468e+00 - 1.6692458e+00 -3.9956861e-02 5.2207165e+00 - 1.5953204e+00 -3.7518644e-02 5.2404765e+00 - 1.5771230e+00 -3.6939777e-02 5.4923709e+00 - 1.4667721e+00 -3.2643168e-02 5.3639812e+00 - 1.3502364e+00 -2.8517363e-02 5.1842747e+00 - 1.2742196e+00 -2.6202827e-02 5.1788226e+00 - 1.2043664e+00 -2.3370862e-02 5.2114540e+00 - 1.1589557e+00 -2.2744499e-02 5.4110493e+00 - 1.0882149e+00 -1.9484333e-02 5.4713993e+00 - 1.0585760e+00 -1.9049941e-02 5.9082995e+00 - 9.6948665e-01 -1.6203991e-02 5.8774705e+00 - 8.9498543e-01 -1.3425177e-02 6.0244742e+00 - 7.8484938e-01 -9.7757010e-03 5.6613255e+00 - 7.0396400e-01 -6.6975580e-03 5.6855024e+00 - 6.2538113e-01 -3.8722580e-03 5.8082991e+00 - 5.5380952e-01 -1.1055598e-03 7.1897079e+00 - 2.5745769e+00 -1.3136123e-01 -1.0075438e+00 - 2.6534068e+00 -1.3633877e-01 -1.0118899e+00 - 2.7242460e+00 -1.4139118e-01 -1.0072720e+00 - 2.8120445e+00 -1.4703102e-01 -1.0140438e+00 - 2.8929108e+00 -1.5180922e-01 -1.0119043e+00 - 2.9737912e+00 -1.5647411e-01 -1.0074677e+00 - 3.0556231e+00 -1.6208801e-01 -1.0007874e+00 - 3.1534255e+00 -1.6815498e-01 -1.0039954e+00 - 3.2531819e+00 -1.7519693e-01 -1.0042638e+00 - 3.3530164e+00 -1.8109905e-01 -1.0016854e+00 - 3.4618178e+00 -1.8767824e-01 -1.0018322e+00 - 3.5885393e+00 -1.9571996e-01 -1.0096269e+00 - 3.7162221e+00 -2.0463187e-01 -1.0135799e+00 - 3.8360354e+00 -2.1161982e-01 -1.0085681e+00 - 3.9737165e+00 -2.2100320e-01 -1.0098562e+00 - 4.1224340e+00 -2.3008415e-01 -1.0118282e+00 - 4.2890889e+00 -2.4048967e-01 -1.0186514e+00 - 4.4567145e+00 -2.5169148e-01 -1.0201348e+00 - 4.6433444e+00 -2.6321240e-01 -1.0251240e+00 - 4.8319468e+00 -2.7556049e-01 -1.0241772e+00 - 5.0395617e+00 -2.8816363e-01 -1.0254378e+00 - 5.2670729e+00 -3.0302693e-01 -1.0278112e+00 - 5.4966267e+00 -3.1764162e-01 -1.0227001e+00 - 5.7641284e+00 -3.3389640e-01 -1.0246509e+00 - 6.0515456e+00 -3.5225859e-01 -1.0246182e+00 - 6.3599428e+00 -3.7174244e-01 -1.0216559e+00 - 6.6972327e+00 -3.9392701e-01 -1.0177376e+00 - 7.0755058e+00 -4.1760786e-01 -1.0142988e+00 - 7.5026227e+00 -4.4529698e-01 -1.0119650e+00 - 7.9607842e+00 -4.7353301e-01 -1.0030877e+00 - 8.5664884e+00 -5.1271763e-01 -1.0150062e+00 - 9.2221594e+00 -5.5445671e-01 -1.0175953e+00 - 9.8998427e+00 -5.9762105e-01 -1.0019275e+00 - 1.0903747e+01 -6.6147206e-01 -1.0262010e+00 - 1.2077374e+01 -7.3531874e-01 -1.0453220e+00 - 1.3747804e+01 -8.4205484e-01 -1.1022322e+00 - 1.5501252e+01 -9.5348664e-01 -1.1123652e+00 - 2.0856417e+01 -1.2935445e+00 -1.1434657e+00 - 2.4022320e+01 -1.4947509e+00 -1.0616705e+00 - 2.4860779e+01 -1.5478043e+00 -7.0648792e-01 - 2.7696954e+01 -1.7283328e+00 -4.2773565e-01 - 2.6323820e+01 -1.6409949e+00 5.4873151e-01 - 2.4690491e+01 -1.5379400e+00 1.0004813e+00 - 2.4557122e+01 -1.5290359e+00 1.4211838e+00 - 2.4616358e+01 -1.5326528e+00 1.8442186e+00 - 2.3651501e+01 -1.4709366e+00 2.2160852e+00 - 2.4263652e+01 -1.5106510e+00 2.6655221e+00 - 2.0632293e+01 -1.2793299e+00 2.7652367e+00 - 2.0508605e+01 -1.2718922e+00 3.1076552e+00 - 2.0925083e+01 -1.2979532e+00 3.5132718e+00 - 1.9553386e+01 -1.2106489e+00 3.6835373e+00 - 1.9671303e+01 -1.2179650e+00 4.0429141e+00 - 2.0814726e+01 -1.2909529e+00 4.5896348e+00 - 1.8622949e+01 -1.1514869e+00 4.5302033e+00 - 1.9759481e+01 -1.2237973e+00 5.1023645e+00 - 2.2203507e+01 -1.3789192e+00 6.0211722e+00 - 2.1019191e+01 -1.3041486e+00 6.1266201e+00 - 1.9200512e+01 -1.1884962e+00 6.0213049e+00 - 1.7844109e+01 -1.1024125e+00 5.9837801e+00 - 1.8956992e+01 -1.1733991e+00 6.6547438e+00 - 2.1152978e+01 -1.3130576e+00 7.7245050e+00 - 1.8786412e+01 -1.1626378e+00 7.3097731e+00 - 1.8936430e+01 -1.1721596e+00 7.7243287e+00 - 1.9105464e+01 -1.1829400e+00 8.1568511e+00 - 1.9051721e+01 -1.1791426e+00 8.5110322e+00 - 1.9469652e+01 -1.2057560e+00 9.0687547e+00 - 2.1377764e+01 -1.3273032e+00 1.0314516e+01 - 2.0714538e+01 -1.2847363e+00 1.0445669e+01 - 4.6612270e+00 -2.6415807e-01 3.0341191e+00 - 4.4745975e+00 -2.5211810e-01 3.0293706e+00 - 2.1709439e+01 -1.3479424e+00 1.2300337e+01 - 4.4101719e+00 -2.4816172e-01 3.1719488e+00 - 4.3544502e+00 -2.4491974e-01 3.2300042e+00 - 4.3667307e+00 -2.4580664e-01 3.3279930e+00 - 4.3760235e+00 -2.4645800e-01 3.4270901e+00 - 4.2743285e+00 -2.3986523e-01 3.4563283e+00 - 4.2476702e+00 -2.3744515e-01 3.5331682e+00 - 4.2769752e+00 -2.3943043e-01 3.6499293e+00 - 4.1972592e+00 -2.3452897e-01 3.6920312e+00 - 4.2215838e+00 -2.3612825e-01 3.8105062e+00 - 4.1798552e+00 -2.3409890e-01 3.8813509e+00 - 4.1291608e+00 -2.3086848e-01 3.9452831e+00 - 4.1465131e+00 -2.3192637e-01 4.0661774e+00 - 4.0317881e+00 -2.2446225e-01 4.0769302e+00 - 4.2153092e+00 -2.3589895e-01 4.3524020e+00 - 4.2296789e+00 -2.3719602e-01 4.4850409e+00 - 4.2681256e+00 -2.3949237e-01 4.6470168e+00 - 4.2675602e+00 -2.3906802e-01 4.7759584e+00 - 4.1458296e+00 -2.3132855e-01 4.7837372e+00 - 4.0861918e+00 -2.2723385e-01 4.8541900e+00 - 4.0856124e+00 -2.2743695e-01 4.9906719e+00 - 4.0810471e+00 -2.2734406e-01 5.1282652e+00 - 3.7910138e+00 -2.0865620e-01 4.9297878e+00 - 3.7022619e+00 -2.0362946e-01 4.9634288e+00 - 3.8180070e+00 -2.1016237e-01 5.2551970e+00 - 3.4967698e+00 -1.9013723e-01 4.9851578e+00 - 3.3158323e+00 -1.7825411e-01 4.8832622e+00 - 3.3333159e+00 -1.7980993e-01 5.0548427e+00 - 3.3067131e+00 -1.7849377e-01 5.1700840e+00 - 3.6251674e+00 -1.9840899e-01 5.8224064e+00 - 3.1864214e+00 -1.7038680e-01 5.3080964e+00 - 3.1257953e+00 -1.6615283e-01 5.3801505e+00 - 2.9346754e+00 -1.5423813e-01 5.2261519e+00 - 2.9282188e+00 -1.5370092e-01 5.3905680e+00 - 3.0442322e+00 -1.6169950e-01 5.7944449e+00 - 2.8239773e+00 -1.4747293e-01 5.5708261e+00 - 2.7050619e+00 -1.4031530e-01 5.5299562e+00 - 2.8152838e+00 -1.4688875e-01 5.9756503e+00 - 2.5175273e+00 -1.2747093e-01 5.5402924e+00 - 2.3673536e+00 -1.1889544e-01 5.4092341e+00 - 2.3127524e+00 -1.1525255e-01 5.4968994e+00 - 2.1766915e+00 -1.0590070e-01 5.3784314e+00 - 2.1008856e+00 -1.0190123e-01 5.4071371e+00 - 1.9808763e+00 -9.3385314e-02 5.3115395e+00 - 1.8879092e+00 -8.8347996e-02 5.2797253e+00 - 1.8101373e+00 -8.2953012e-02 5.2937563e+00 - 1.7131580e+00 -7.6798353e-02 5.2391836e+00 - 1.6282612e+00 -7.1564745e-02 5.2211269e+00 - 1.5504006e+00 -6.6879210e-02 5.2207757e+00 - 1.4715933e+00 -6.1205245e-02 5.2189798e+00 - 1.3876662e+00 -5.5744582e-02 5.1864881e+00 - 1.3087801e+00 -5.0701239e-02 5.1719080e+00 - 1.2399890e+00 -4.6903208e-02 5.2050859e+00 - 1.1753671e+00 -4.2452067e-02 5.2766533e+00 - 1.1260827e+00 -3.9085713e-02 5.4661250e+00 - 1.0595161e+00 -3.5133023e-02 5.5656634e+00 - 1.0105972e+00 -3.1939782e-02 5.8731870e+00 - 9.2680076e-01 -2.6981984e-02 5.8912817e+00 - 8.3575722e-01 -2.1099588e-02 5.8182631e+00 - 7.4239266e-01 -1.5112151e-02 5.6436284e+00 - 6.6262280e-01 -1.0125182e-02 5.6672035e+00 - 6.4907175e-01 -8.9907283e-03 9.5686432e+00 - 2.6086802e+00 -1.9673251e-01 -1.0099363e+00 - 2.6873958e+00 -2.0365469e-01 -1.0131846e+00 - 2.7521711e+00 -2.0997374e-01 -1.0010577e+00 - 2.8468025e+00 -2.1830160e-01 -1.0132458e+00 - 2.9195484e+00 -2.2522249e-01 -1.0035414e+00 - 3.0161467e+00 -2.3442187e-01 -1.0106925e+00 - 3.0909154e+00 -2.4125181e-01 -9.9669974e-01 - 3.1974917e+00 -2.5108525e-01 -1.0044819e+00 - 3.2960773e+00 -2.6099356e-01 -1.0033001e+00 - 3.3967367e+00 -2.6988788e-01 -9.9937768e-01 - 3.5053058e+00 -2.8038591e-01 -9.9792804e-01 - 3.6407458e+00 -2.9315164e-01 -1.0094483e+00 - 3.7682585e+00 -3.0497066e-01 -1.0115548e+00 - 3.8888395e+00 -3.1592312e-01 -1.0046501e+00 - 4.0441969e+00 -3.3078149e-01 -1.0138873e+00 - 4.1837325e+00 -3.4296626e-01 -1.0087409e+00 - 4.3410846e+00 -3.5847444e-01 -1.0084466e+00 - 4.5363476e+00 -3.7591832e-01 -1.0212067e+00 - 4.7236304e+00 -3.9335331e-01 -1.0233050e+00 - 4.9118876e+00 -4.1155504e-01 -1.0194642e+00 - 5.1380146e+00 -4.3253668e-01 -1.0255321e+00 - 5.3661830e+00 -4.5327957e-01 -1.0243153e+00 - 5.6231562e+00 -4.7794185e-01 -1.0265874e+00 - 5.8901406e+00 -5.0297215e-01 -1.0240972e+00 - 6.1781007e+00 -5.2915859e-01 -1.0193766e+00 - 6.4958848e+00 -5.5915736e-01 -1.0147521e+00 - 6.8525285e+00 -5.9257960e-01 -1.0116004e+00 - 7.2490429e+00 -6.2938231e-01 -1.0078272e+00 - 7.7242427e+00 -6.7334861e-01 -1.0121962e+00 - 8.2113839e+00 -7.1936419e-01 -1.0029210e+00 - 8.8260258e+00 -7.7677825e-01 -1.0074874e+00 - 9.5203638e+00 -8.4183196e-01 -1.0083643e+00 - 1.0305391e+01 -9.1508188e-01 -1.0033892e+00 - 1.1416076e+01 -1.0186826e+00 -1.0316676e+00 - 1.2735978e+01 -1.1417593e+00 -1.0562718e+00 - 1.4581813e+01 -1.3132698e+00 -1.1134725e+00 - 1.6481544e+01 -1.4911835e+00 -1.1129188e+00 - 2.1282634e+01 -1.9385396e+00 -1.0095511e+00 - 2.3905157e+01 -2.1832876e+00 -8.4966432e-01 - 2.3764984e+01 -2.1709498e+00 -4.2868874e-01 - 2.3915743e+01 -2.1841338e+00 -2.6372449e-02 - 2.7393516e+01 -2.5087160e+00 2.9317166e-01 - 2.5071869e+01 -2.2928793e+00 7.8505817e-01 - 2.5937975e+01 -2.3735594e+00 1.2234340e+00 - 2.3830252e+01 -2.1766826e+00 1.6140108e+00 - 2.3567524e+01 -2.1520707e+00 2.0119088e+00 - 2.3397426e+01 -2.1362095e+00 2.4068631e+00 - 2.0779008e+01 -1.8920587e+00 2.6032199e+00 - 2.0727317e+01 -1.8874247e+00 2.9565460e+00 - 2.0443484e+01 -1.8601009e+00 3.2824517e+00 - 2.0588079e+01 -1.8743165e+00 3.6565220e+00 - 1.9722100e+01 -1.7935734e+00 3.8855655e+00 - 1.9580679e+01 -1.7800808e+00 4.2071693e+00 - 2.1656123e+01 -1.9734179e+00 4.9384008e+00 - 1.9105450e+01 -1.7359646e+00 5.1428798e+00 - 2.2225098e+01 -2.0264075e+00 6.2388075e+00 - 2.0800628e+01 -1.8935197e+00 6.2731851e+00 - 2.1127835e+01 -1.9248965e+00 6.7458967e+00 - 1.8705021e+01 -1.6986361e+00 6.4163802e+00 - 2.0365470e+01 -1.8537633e+00 7.2909646e+00 - 1.2670795e+01 -1.1352592e+00 5.0901909e+00 - 2.0237272e+01 -1.8418754e+00 8.0201687e+00 - 2.0187698e+01 -1.8363965e+00 8.3930643e+00 - 1.9434827e+01 -1.7669704e+00 8.4915069e+00 - 1.9697412e+01 -1.7913155e+00 8.9867983e+00 - 1.9235825e+01 -1.7476878e+00 9.1825361e+00 - 4.6852974e+00 -3.8984719e-01 2.9159172e+00 - 4.6067592e+00 -3.8253930e-01 2.9675050e+00 - 4.5181980e+00 -3.7495701e-01 3.0124329e+00 - 2.4424805e+01 -2.2322647e+00 1.3508955e+01 - 2.1534492e+01 -1.9628176e+00 1.2471119e+01 - 4.3564161e+00 -3.5930525e-01 3.1912798e+00 - 4.2828404e+00 -3.5252624e-01 3.2382573e+00 - 4.3370204e+00 -3.5768659e-01 3.3617298e+00 - 4.2704552e+00 -3.5114352e-01 3.4124805e+00 - 4.2108410e+00 -3.4582841e-01 3.4671536e+00 - 4.1841778e+00 -3.4344773e-01 3.5431945e+00 - 4.2204437e+00 -3.4658215e-01 3.6654761e+00 - 4.2057753e+00 -3.4530799e-01 3.7540130e+00 - 4.2041006e+00 -3.4519586e-01 3.8551425e+00 - 4.1624918e+00 -3.4117753e-01 3.9257882e+00 - 4.1178854e+00 -3.3700248e-01 3.9959440e+00 - 4.1491748e+00 -3.4023547e-01 4.1303762e+00 - 4.1015734e+00 -3.3588399e-01 4.2004417e+00 - 4.2508288e+00 -3.4943375e-01 4.4522997e+00 - 4.3421111e+00 -3.5856563e-01 4.6620456e+00 - 4.2846116e+00 -3.5242549e-01 4.7358886e+00 - 4.2819959e+00 -3.5282793e-01 4.8658849e+00 - 4.1934887e+00 -3.4429795e-01 4.9097645e+00 - 4.1729388e+00 -3.4231797e-01 5.0255364e+00 - 4.0494293e+00 -3.3065700e-01 5.0293280e+00 - 3.7138873e+00 -2.9974747e-01 4.7792655e+00 - 3.8943701e+00 -3.1599462e-01 5.1358931e+00 - 3.7908021e+00 -3.0674828e-01 5.1557005e+00 - 3.7542727e+00 -3.0335594e-01 5.2602876e+00 - 3.6087142e+00 -2.8953211e-01 5.2202545e+00 - 3.3960742e+00 -2.6968009e-01 5.0787129e+00 - 3.7538184e+00 -3.0380608e-01 5.7552230e+00 - 3.5992620e+00 -2.8903738e-01 5.7030840e+00 - 3.1533435e+00 -2.4681564e-01 5.1832118e+00 - 3.0486828e+00 -2.3774850e-01 5.1779038e+00 - 3.0872693e+00 -2.4150702e-01 5.4115392e+00 - 3.0588321e+00 -2.3826010e-01 5.5432170e+00 - 3.1035275e+00 -2.4245380e-01 5.8158844e+00 - 2.8716236e+00 -2.2126216e-01 5.5769754e+00 - 2.7740142e+00 -2.1210579e-01 5.5820323e+00 - 2.8699759e+00 -2.2063309e-01 5.9912655e+00 - 2.5065442e+00 -1.8682990e-01 5.4224392e+00 - 2.4771275e+00 -1.8388885e-01 5.5669539e+00 - 2.4356809e+00 -1.8012212e-01 5.6932797e+00 - 2.4193454e+00 -1.7919085e-01 5.8939820e+00 - 2.3056562e+00 -1.6839198e-01 5.8519991e+00 - 2.7830103e+00 -2.1280684e-01 7.4759473e+00 - 2.5186754e+00 -1.8843649e-01 7.0597630e+00 - 1.9754193e+00 -1.3785260e-01 5.7018453e+00 - 1.8716526e+00 -1.2813120e-01 5.6502425e+00 - 1.7346433e+00 -1.1471104e-01 5.4712052e+00 - 1.5863971e+00 -1.0113305e-01 5.2211418e+00 - 1.5056591e+00 -9.3782755e-02 5.2103641e+00 - 1.4239141e+00 -8.5926849e-02 5.1883539e+00 - 1.3472101e+00 -7.8488263e-02 5.1842553e+00 - 1.2765478e+00 -7.2021874e-02 5.2083020e+00 - 1.2262098e+00 -6.7491145e-02 5.3593755e+00 - 1.2665571e+00 -7.1619039e-02 6.1528087e+00 - 1.0912113e+00 -5.4806673e-02 5.5110699e+00 - 1.0381743e+00 -4.9796156e-02 5.7492438e+00 - 9.6785355e-01 -4.3695022e-02 5.8874473e+00 - 8.8529532e-01 -3.5847979e-02 5.9248157e+00 - 7.8494302e-01 -2.6347656e-02 5.6912783e+00 - 7.0536018e-01 -1.8834691e-02 5.7255411e+00 - 6.2489753e-01 -1.1862675e-02 5.8083959e+00 - 5.5225505e-01 -4.9748862e-03 7.0897849e+00 - 2.5701446e+00 -2.5381152e-01 -1.0144922e+00 - 2.6268997e+00 -2.6044192e-01 -9.9819537e-01 - 2.7054389e+00 -2.7032048e-01 -1.0005959e+00 - 2.7770440e+00 -2.7935220e-01 -9.9438469e-01 - 2.8724991e+00 -2.9068210e-01 -1.0054286e+00 - 2.9599640e+00 -3.0208196e-01 -1.0074087e+00 - 3.0415533e+00 -3.1169846e-01 -1.0008298e+00 - 3.1310448e+00 -3.2297781e-01 -9.9792223e-01 - 3.2294995e+00 -3.3496379e-01 -9.9833923e-01 - 3.3289696e+00 -3.4687227e-01 -9.9596286e-01 - 3.4373463e+00 -3.6045477e-01 -9.9626222e-01 - 3.5626450e+00 -3.7543936e-01 -1.0042063e+00 - 3.6899032e+00 -3.9135459e-01 -1.0083118e+00 - 3.8092316e+00 -4.0634281e-01 -1.0034030e+00 - 3.9464876e+00 -4.2273444e-01 -1.0049436e+00 - 4.0936612e+00 -4.4075708e-01 -1.0070656e+00 - 4.2597103e+00 -4.6116171e-01 -1.0139926e+00 - 4.4088792e+00 -4.7982924e-01 -1.0064833e+00 - 4.6037964e+00 -5.0313168e-01 -1.0164493e+00 - 4.7907333e+00 -5.2642523e-01 -1.0157533e+00 - 5.0065180e+00 -5.5277918e-01 -1.0213922e+00 - 5.2322432e+00 -5.8058185e-01 -1.0239172e+00 - 5.4689109e+00 -6.0986413e-01 -1.0227322e+00 - 5.7254847e+00 -6.4132773e-01 -1.0210619e+00 - 6.0118720e+00 -6.7668742e-01 -1.0211856e+00 - 6.3092172e+00 -7.1340356e-01 -1.0151024e+00 - 6.6354526e+00 -7.5284014e-01 -1.0084626e+00 - 7.0302012e+00 -8.0190551e-01 -1.0113826e+00 - 7.4548661e+00 -8.5353007e-01 -1.0092547e+00 - 7.9302051e+00 -9.1215641e-01 -1.0056926e+00 - 8.4741718e+00 -9.7898104e-01 -1.0029506e+00 - 9.0976945e+00 -1.0555969e+00 -9.9961599e-01 - 9.8107670e+00 -1.1425099e+00 -9.9372301e-01 - 1.0818012e+01 -1.2668674e+00 -1.0204391e+00 - 1.1935728e+01 -1.4041400e+00 -1.0314807e+00 - 1.3547605e+01 -1.6013022e+00 -1.0818668e+00 - 1.5341495e+01 -1.8219569e+00 -1.1011793e+00 - 1.7661475e+01 -2.1065956e+00 -1.1226857e+00 - 2.0903224e+01 -2.5048811e+00 -1.1601956e+00 - 2.4437653e+01 -2.9385315e+00 -1.1095590e+00 - 2.5293040e+01 -3.0433577e+00 -7.4622002e-01 - 2.5764123e+01 -3.1013981e+00 1.1159316e-01 - 2.5786434e+01 -3.1037426e+00 5.5571889e-01 - 2.2401964e+01 -2.6885517e+00 1.3855531e+00 - 2.2759229e+01 -2.7324811e+00 1.7835056e+00 - 2.2721680e+01 -2.7278723e+00 2.1736913e+00 - 2.3005409e+01 -2.7626410e+00 2.5858634e+00 - 2.1678683e+01 -2.6003132e+00 2.8671925e+00 - 2.1880832e+01 -2.6248774e+00 3.2644464e+00 - 2.0931975e+01 -2.5083304e+00 3.5278793e+00 - 2.4963430e+01 -3.0032043e+00 4.4643606e+00 - 2.5027520e+01 -3.0107928e+00 4.9142943e+00 - 2.2815039e+01 -2.7392345e+00 4.9647180e+00 - 1.9645082e+01 -2.3498163e+00 4.7496106e+00 - 2.6650309e+01 -3.2106646e+00 7.0830114e+00 - 2.5230665e+01 -3.0362067e+00 7.2129290e+00 - 1.9357929e+01 -2.3149420e+00 6.0912176e+00 - 1.8675220e+01 -2.2316533e+00 6.2511205e+00 - 2.3061169e+01 -2.7692298e+00 7.9499603e+00 - 1.9983506e+01 -2.3920715e+00 7.3783482e+00 - 1.8950344e+01 -2.2653522e+00 7.4009026e+00 - 1.9097849e+01 -2.2835188e+00 7.8201053e+00 - 1.9449506e+01 -2.3266164e+00 8.3288881e+00 - 1.8941927e+01 -2.2640171e+00 8.5073535e+00 - 2.0764416e+01 -2.4880028e+00 9.6666825e+00 - 2.0774710e+01 -2.4894131e+00 1.0094817e+01 - 2.3303754e+01 -2.7994432e+00 1.1713595e+01 - 2.1580272e+01 -2.5875898e+00 1.1358846e+01 - 2.2211261e+01 -2.6648374e+00 1.2145632e+01 - 2.1857157e+01 -2.6217394e+00 1.2441156e+01 - 2.2237270e+01 -2.6681550e+00 1.3139761e+01 - 4.4203662e+00 -4.8099713e-01 3.5652422e+00 - 4.2931001e+00 -4.6566009e-01 3.5778868e+00 - 4.1987721e+00 -4.5336094e-01 3.6098018e+00 - 4.2180032e+00 -4.5599487e-01 3.7214507e+00 - 4.3200170e+00 -4.6829131e-01 3.9007487e+00 - 4.2465703e+00 -4.5944942e-01 3.9490254e+00 - 4.1401990e+00 -4.4694711e-01 3.9703916e+00 - 4.1874169e+00 -4.5251551e-01 4.1175564e+00 - 4.1329142e+00 -4.4602287e-01 4.1819520e+00 - 4.1362668e+00 -4.4643645e-01 4.2987958e+00 - 4.4847803e+00 -4.8848351e-01 4.7441680e+00 - 4.3694826e+00 -4.7446482e-01 4.7650139e+00 - 4.1494293e+00 -4.4749573e-01 4.6769332e+00 - 4.1398323e+00 -4.4691161e-01 4.7981131e+00 - 4.1073281e+00 -4.4298582e-01 4.8981434e+00 - 3.9002195e+00 -4.1705384e-01 4.8049277e+00 - 4.2050843e+00 -4.5427826e-01 5.2942857e+00 - 3.6964606e+00 -3.9207421e-01 4.8378939e+00 - 3.6230115e+00 -3.8325203e-01 4.8857712e+00 - 3.6713971e+00 -3.8907336e-01 5.0898113e+00 - 3.6479333e+00 -3.8575249e-01 5.2088392e+00 - 3.3996773e+00 -3.5602595e-01 5.0208734e+00 - 3.2952988e+00 -3.4264090e-01 5.0220589e+00 - 3.2248478e+00 -3.3397051e-01 5.0705258e+00 - 3.3482672e+00 -3.4914528e-01 5.4197433e+00 - 3.3977718e+00 -3.5560875e-01 5.6727686e+00 - 3.1174651e+00 -3.2069691e-01 5.3887264e+00 - 3.2940334e+00 -3.4226589e-01 5.8757011e+00 - 3.1706094e+00 -3.2785863e-01 5.8541256e+00 - 2.8951583e+00 -2.9381386e-01 5.5383571e+00 - 3.0228975e+00 -3.0919486e-01 5.9895839e+00 - 2.8844798e+00 -2.9198690e-01 5.9254103e+00 - 2.6388700e+00 -2.6213064e-01 5.6221796e+00 - 2.4863287e+00 -2.4320718e-01 5.4946304e+00 - 2.3537728e+00 -2.2686269e-01 5.4000257e+00 - 2.4446873e+00 -2.3811660e-01 5.8491736e+00 - 2.2429323e+00 -2.1349892e-01 5.5745660e+00 - 2.6590247e+00 -2.6524875e-01 6.9764794e+00 - 2.5286291e+00 -2.4926198e-01 6.9378480e+00 - 2.3339497e+00 -2.2487706e-01 6.6873379e+00 - 1.9220527e+00 -1.7454262e-01 5.6858623e+00 - 1.9904681e+00 -1.8228803e-01 6.2388041e+00 - 1.9583909e+00 -1.7907587e-01 6.4864490e+00 - 1.5416581e+00 -1.2801689e-01 5.2111298e+00 - 1.4620946e+00 -1.1777067e-01 5.1995011e+00 - 1.3824623e+00 -1.0859037e-01 5.1865238e+00 - 1.3099283e+00 -9.9460553e-02 5.2013395e+00 - 1.2444965e+00 -9.0865780e-02 5.2543848e+00 - 1.3444735e+00 -1.0349425e-01 6.3730704e+00 - 1.1411228e+00 -7.8734152e-02 5.5948444e+00 - 1.0565208e+00 -6.8050904e-02 5.5657037e+00 - 1.1318140e+00 -7.7738314e-02 7.0566557e+00 - 9.2534893e-01 -5.1477224e-02 5.9012097e+00 - 8.3872737e-01 -4.1374426e-02 5.8781175e+00 - 7.4260736e-01 -2.9685270e-02 5.6735820e+00 - 6.6426498e-01 -2.0296550e-02 5.7470931e+00 - 6.4865430e-01 -1.8515452e-02 9.6186768e+00 - 2.5227320e+00 -3.0898001e-01 -1.0115783e+00 - 2.5931895e+00 -3.2017674e-01 -1.0099591e+00 - 2.6646569e+00 -3.3134031e-01 -1.0064454e+00 - 2.7351378e+00 -3.4234982e-01 -1.0010308e+00 - 2.8225192e+00 -3.5493385e-01 -1.0067566e+00 - 2.9019092e+00 -3.6759768e-01 -1.0036183e+00 - 2.9902587e+00 -3.8099770e-01 -1.0044038e+00 - 3.0716734e+00 -3.9355580e-01 -9.9667747e-01 - 3.1699376e+00 -4.0861147e-01 -9.9854384e-01 - 3.2682196e+00 -4.2352427e-01 -9.9751379e-01 - 3.3754070e+00 -4.4012094e-01 -9.9935923e-01 - 3.4915644e+00 -4.5737005e-01 -1.0034306e+00 - 3.6096788e+00 -4.7556951e-01 -1.0040629e+00 - 3.7278155e+00 -4.9359161e-01 -1.0010997e+00 - 3.8637580e+00 -5.1502087e-01 -1.0046865e+00 - 4.0017829e+00 -5.3536716e-01 -1.0041344e+00 - 4.1486678e+00 -5.5827604e-01 -1.0040111e+00 - 4.3055344e+00 -5.8178943e-01 -1.0039197e+00 - 4.4802229e+00 -6.0858189e-01 -1.0077815e+00 - 4.6658383e+00 -6.3697713e-01 -1.0104301e+00 - 4.8712825e+00 -6.6868859e-01 -1.0153405e+00 - 5.0955634e+00 -7.0360656e-01 -1.0215105e+00 - 5.3308451e+00 -7.3902197e-01 -1.0243197e+00 - 5.5671128e+00 -7.7511050e-01 -1.0192922e+00 - 5.8420286e+00 -8.1785971e-01 -1.0205826e+00 - 6.1279601e+00 -8.6098812e-01 -1.0161151e+00 - 6.4336939e+00 -9.0815873e-01 -1.0083665e+00 - 6.7880662e+00 -9.6252555e-01 -1.0055693e+00 - 7.1910936e+00 -1.0239555e+00 -1.0050269e+00 - 7.6437300e+00 -1.0933780e+00 -1.0040961e+00 - 8.1648644e+00 -1.1730666e+00 -1.0053846e+00 - 8.7465491e+00 -1.2622371e+00 -1.0027744e+00 - 9.4364672e+00 -1.3671664e+00 -1.0040599e+00 - 1.0147227e+01 -1.4763823e+00 -9.8553828e-01 - 1.1240005e+01 -1.6440816e+00 -1.0134478e+00 - 1.2481745e+01 -1.8341653e+00 -1.0281567e+00 - 1.4342777e+01 -2.1182982e+00 -1.0927116e+00 - 1.5836823e+01 -2.3474762e+00 -1.0424698e+00 - 1.8865125e+01 -2.8109212e+00 -1.1165987e+00 - 2.4218457e+01 -3.6306117e+00 -4.6721842e-01 - 2.4438169e+01 -3.6636139e+00 -5.6941033e-02 - 2.6013660e+01 -3.9053225e+00 3.2452452e-01 - 2.6030959e+01 -3.9080513e+00 7.7500793e-01 - 2.7573024e+01 -4.1436154e+00 1.2394792e+00 - 2.6903453e+01 -4.0411726e+00 1.6998280e+00 - 2.1860655e+01 -3.2690627e+00 1.9437792e+00 - 2.2334433e+01 -3.3416197e+00 2.3513356e+00 - 2.2031837e+01 -3.2952537e+00 2.7146650e+00 - 2.1753029e+01 -3.2527019e+00 3.0705264e+00 - 2.1301390e+01 -3.1840728e+00 3.3979335e+00 - 2.7019602e+01 -4.0588691e+00 4.5323774e+00 - 2.6583153e+01 -3.9919931e+00 4.9438810e+00 - 3.3266661e+01 -5.0151146e+00 6.5476601e+00 - 2.2397683e+01 -3.3519648e+00 5.1060530e+00 - 1.9940570e+01 -2.9760337e+00 5.0015517e+00 - 2.4056157e+01 -3.6052623e+00 6.2835597e+00 - 2.5672774e+01 -3.8532084e+00 7.1142331e+00 - 2.0070191e+01 -2.9954555e+00 6.1204895e+00 - 2.0360486e+01 -3.0396924e+00 6.5721362e+00 - 1.9852939e+01 -2.9626108e+00 6.7998486e+00 - 1.9844217e+01 -2.9607059e+00 7.1706659e+00 - 1.9557200e+01 -2.9173974e+00 7.4510476e+00 - 1.8939314e+01 -2.8222086e+00 7.6062587e+00 - 1.8943443e+01 -2.8231229e+00 7.9763348e+00 - 2.1450186e+01 -3.2072256e+00 9.3490970e+00 - 2.0508334e+01 -3.0622976e+00 9.3848076e+00 - 2.3463421e+01 -3.5144944e+00 1.1587284e+01 - 2.3473908e+01 -3.5164290e+00 1.2085829e+01 - 2.0908409e+01 -3.1239809e+00 1.1293935e+01 - 2.1235990e+01 -3.1738109e+00 1.1920543e+01 - 2.1114155e+01 -3.1554675e+00 1.2323187e+01 - 2.2094176e+01 -3.3055655e+00 1.3360019e+01 - 4.4598770e+00 -6.0540094e-01 3.5522116e+00 - 4.3905128e+00 -5.9556741e-01 3.6052201e+00 - 4.3042803e+00 -5.8235585e-01 3.6451501e+00 - 4.5075573e+00 -6.1346362e-01 3.8919338e+00 - 4.4173966e+00 -5.9897881e-01 3.9325261e+00 - 4.2714231e+00 -5.7733918e-01 3.9281546e+00 - 4.1971546e+00 -5.6548047e-01 3.9755867e+00 - 4.1835350e+00 -5.6386276e-01 4.0723103e+00 - 4.0624599e+00 -5.4521099e-01 4.0784454e+00 - 4.0827337e+00 -5.4806477e-01 4.2071197e+00 - 4.1000229e+00 -5.5065838e-01 4.3374016e+00 - 4.0416406e+00 -5.4198916e-01 4.4005123e+00 - 4.2860181e+00 -5.7881325e-01 4.7638680e+00 - 4.1439892e+00 -5.5779971e-01 4.7516933e+00 - 3.8267258e+00 -5.0868360e-01 4.5470771e+00 - 3.6786717e+00 -4.8656484e-01 4.5094538e+00 - 3.6760736e+00 -4.8631026e-01 4.6325091e+00 - 3.6326973e+00 -4.7879588e-01 4.7108028e+00 - 3.6370676e+00 -4.8014545e-01 4.8504146e+00 - 3.6076292e+00 -4.7531538e-01 4.9521836e+00 - 3.5263174e+00 -4.6348185e-01 4.9905492e+00 - 3.7570925e+00 -4.9855029e-01 5.4534251e+00 - 3.3578060e+00 -4.3709676e-01 5.0542668e+00 - 3.5009113e+00 -4.5879223e-01 5.4173012e+00 - 3.3039138e+00 -4.2933546e-01 5.2862028e+00 - 3.2346363e+00 -4.1829313e-01 5.3434565e+00 - 3.2112582e+00 -4.1428745e-01 5.4763672e+00 - 3.1688788e+00 -4.0839071e-01 5.5838706e+00 - 3.0896132e+00 -3.9627901e-01 5.6303198e+00 - 2.9614296e+00 -3.7662732e-01 5.5873890e+00 - 3.0919188e+00 -3.9620705e-01 6.0382052e+00 - 3.0486474e+00 -3.8991659e-01 6.1727279e+00 - 2.9464849e+00 -3.7386533e-01 6.1898882e+00 - 2.3774429e+00 -2.8698505e-01 5.1676553e+00 - 2.2460626e+00 -2.6722064e-01 5.0625619e+00 - 2.3227620e+00 -2.7852141e-01 5.4531275e+00 - 2.6947760e+00 -3.3537203e-01 6.6382966e+00 - 2.2301723e+00 -2.6449357e-01 5.6833912e+00 - 2.5324763e+00 -3.1117990e-01 6.8067131e+00 - 2.2720244e+00 -2.7060750e-01 6.3579664e+00 - 2.1847927e+00 -2.5785948e-01 6.4075373e+00 - 2.0855791e+00 -2.4235414e-01 6.4172971e+00 - 1.9842982e+00 -2.2729449e-01 6.4155775e+00 - 1.8508922e+00 -2.0661247e-01 6.2861213e+00 - 1.4940430e+00 -1.5222611e-01 5.1908911e+00 - 1.4176505e+00 -1.3971900e-01 5.1882426e+00 - 1.3451823e+00 -1.2954788e-01 5.2039076e+00 - 1.3121827e+00 -1.2412196e-01 5.4344281e+00 - 1.5059765e+00 -1.5408082e-01 7.0853455e+00 - 1.2882236e+00 -1.2076209e-01 6.3407281e+00 - 1.0972657e+00 -9.1350241e-02 5.5904309e+00 - 1.0240099e+00 -8.0466931e-02 5.6598320e+00 - 9.6933927e-01 -7.1405400e-02 5.9371646e+00 - 8.8084511e-01 -5.8129963e-02 5.8949041e+00 - 7.8709771e-01 -4.4070535e-02 5.7611244e+00 - 7.0357404e-01 -3.1259930e-02 5.7155519e+00 - 6.2459827e-01 -1.8380000e-02 5.8383558e+00 - 5.5200926e-01 -7.4547868e-03 7.0597715e+00 - 2.4755043e+00 -3.6112316e-01 -1.0081139e+00 - 2.5448365e+00 -3.7430754e-01 -1.0074910e+00 - 2.6072953e+00 -3.8564319e-01 -9.9820619e-01 - 2.6924781e+00 -4.0126962e-01 -1.0072727e+00 - 2.7569554e+00 -4.1254881e-01 -9.9439862e-01 - 2.8510491e+00 -4.2981477e-01 -1.0054417e+00 - 2.9303249e+00 -4.4442325e-01 -1.0012055e+00 - 3.0184999e+00 -4.6076486e-01 -1.0008436e+00 - 3.1076885e+00 -4.7704376e-01 -9.9798790e-01 - 3.2057800e+00 -4.9502625e-01 -9.9840723e-01 - 3.2959994e+00 -5.1110448e-01 -9.9026128e-01 - 3.4029540e+00 -5.3162493e-01 -9.9061012e-01 - 3.5278274e+00 -5.5361776e-01 -9.9880658e-01 - 3.6447121e+00 -5.7567068e-01 -9.9773939e-01 - 3.7715685e+00 -5.9840694e-01 -9.9830203e-01 - 3.9161737e+00 -6.2552268e-01 -1.0048657e+00 - 4.0529713e+00 -6.4970273e-01 -1.0022146e+00 - 4.2085220e+00 -6.7827346e-01 -1.0045689e+00 - 4.3650408e+00 -7.0766018e-01 -1.0019829e+00 - 4.5493367e+00 -7.4114233e-01 -1.0076765e+00 - 4.7435651e+00 -7.7613725e-01 -1.0115547e+00 - 4.9476677e+00 -8.1362712e-01 -1.0132681e+00 - 5.1715461e+00 -8.5537104e-01 -1.0159951e+00 - 5.4153258e+00 -8.9933570e-01 -1.0190358e+00 - 5.6699927e+00 -9.4573751e-01 -1.0175179e+00 - 5.9444515e+00 -9.9626529e-01 -1.0144168e+00 - 6.2476727e+00 -1.0515665e+00 -1.0118586e+00 - 6.5617959e+00 -1.1091867e+00 -1.0023447e+00 - 6.9343462e+00 -1.1776970e+00 -9.9966294e-01 - 7.3455927e+00 -1.2524836e+00 -9.9550871e-01 - 7.8251448e+00 -1.3406208e+00 -9.9532275e-01 - 8.3641758e+00 -1.4392800e+00 -9.9328282e-01 - 9.0111841e+00 -1.5578088e+00 -9.9743731e-01 - 9.6879355e+00 -1.6823427e+00 -9.8535930e-01 - 1.0570814e+01 -1.8432275e+00 -9.8998180e-01 - 1.1775580e+01 -2.0639897e+00 -1.0210715e+00 - 1.3120125e+01 -2.3102402e+00 -1.0318421e+00 - 1.5052134e+01 -2.6639964e+00 -1.0789829e+00 - 1.6140513e+01 -2.8628528e+00 -9.5203934e-01 - 2.5511526e+01 -4.5787484e+00 -7.7766126e-01 - 2.7532934e+01 -4.9488599e+00 -4.3977258e-01 - 2.7435377e+01 -4.9309478e+00 4.4243390e-02 - 2.7595419e+01 -4.9601164e+00 5.1968016e-01 - 2.8779992e+01 -5.1772883e+00 1.0004695e+00 - 2.7457721e+01 -4.9352252e+00 1.4787857e+00 - 2.8674187e+01 -5.1572963e+00 2.0006705e+00 - 2.2198457e+01 -3.9720106e+00 2.1563911e+00 - 2.3049035e+01 -4.1275578e+00 2.6033618e+00 - 2.5810590e+01 -4.6332727e+00 3.2516510e+00 - 2.1659935e+01 -3.8735376e+00 3.2612224e+00 - 2.1764238e+01 -3.8923846e+00 3.6545931e+00 - 1.9932541e+01 -3.5570048e+00 3.7768135e+00 - 2.0143819e+01 -3.5956906e+00 4.1633936e+00 - 2.3651565e+01 -4.2379664e+00 5.1505283e+00 - 2.1684855e+01 -3.8776467e+00 5.1866461e+00 - 2.5054278e+01 -4.4949521e+00 6.3062667e+00 - 2.7172775e+01 -4.8824149e+00 7.2606721e+00 - 1.9569405e+01 -3.4910114e+00 5.8338381e+00 - 2.0300446e+01 -3.6246847e+00 6.3940077e+00 - 2.0460298e+01 -3.6543425e+00 6.8190075e+00 - 1.9444911e+01 -3.4681828e+00 6.8885819e+00 - 1.2932391e+01 -2.2756531e+00 5.1069829e+00 - 2.4160005e+01 -4.3311210e+00 9.2826797e+00 - 2.3641153e+01 -4.2365023e+00 1.0031140e+01 - 2.1203030e+01 -3.7894499e+00 9.5037962e+00 - 2.1370046e+01 -3.8206925e+00 1.0006526e+01 - 2.3396656e+01 -4.1916056e+00 1.1363879e+01 - 2.1253766e+01 -3.7993905e+00 1.0838720e+01 - 2.1276014e+01 -3.8037897e+00 1.1301971e+01 - 2.1192139e+01 -3.7880309e+00 1.1718926e+01 - 2.1595607e+01 -3.8616255e+00 1.2403608e+01 - 2.1741057e+01 -3.8883950e+00 1.2970129e+01 - 4.3003143e+00 -6.9540634e-01 3.6058958e+00 - 4.7862145e+00 -7.8486166e-01 4.0514569e+00 - 4.6932149e+00 -7.6792077e-01 4.0976526e+00 - 4.3102007e+00 -6.9750258e-01 3.9188241e+00 - 4.2509283e+00 -6.8687753e-01 3.9798413e+00 - 4.2681706e+00 -6.8984557e-01 4.1025326e+00 - 4.2297913e+00 -6.8258417e-01 4.1818092e+00 - 4.2341501e+00 -6.8299416e-01 4.2999483e+00 - 4.0009887e+00 -6.4052005e-01 4.2051763e+00 - 4.0749029e+00 -6.5387827e-01 4.3895061e+00 - 4.2640876e+00 -6.8920860e-01 4.6956579e+00 - 4.2903504e+00 -6.9397242e-01 4.8537257e+00 - 4.1893909e+00 -6.7531274e-01 4.8844667e+00 - 3.8876073e+00 -6.1943988e-01 4.6933389e+00 - 3.6264965e+00 -5.7166930e-01 4.5298936e+00 - 3.5135172e+00 -5.5107191e-01 4.5244686e+00 - 3.6481889e+00 -5.7586550e-01 4.8149181e+00 - 3.9540381e+00 -6.3161277e-01 5.3364222e+00 - 4.0669600e+00 -6.5236818e-01 5.6413246e+00 - 3.8505451e+00 -6.1321441e-01 5.5202806e+00 - 3.4828344e+00 -5.4599948e-01 5.1745097e+00 - 3.2304819e+00 -5.0005707e-01 4.9647433e+00 - 3.7616095e+00 -5.9719098e-01 5.9162278e+00 - 3.1518399e+00 -4.8502591e-01 5.1514178e+00 - 3.1214804e+00 -4.7951955e-01 5.2656746e+00 - 3.2156447e+00 -4.9695197e-01 5.5944585e+00 - 3.1216151e+00 -4.7917362e-01 5.6158887e+00 - 3.1650733e+00 -4.8727991e-01 5.8890571e+00 - 3.1138972e+00 -4.7779898e-01 5.9974392e+00 - 3.0318082e+00 -4.6310803e-01 6.0519888e+00 - 2.5178795e+00 -3.6877290e-01 5.2063666e+00 - 2.4247135e+00 -3.5161489e-01 5.1961831e+00 - 2.3205074e+00 -3.3324156e-01 5.1566717e+00 - 2.2063756e+00 -3.1175394e-01 5.0870308e+00 - 2.1101212e+00 -2.9464931e-01 5.0518381e+00 - 2.3326190e+00 -3.3539219e-01 5.8546639e+00 - 2.2594865e+00 -3.2197620e-01 5.9146277e+00 - 2.3954303e+00 -3.4640408e-01 6.5974353e+00 - 2.2263482e+00 -3.1581129e-01 6.4020295e+00 - 2.1763885e+00 -3.0619408e-01 6.5751772e+00 - 2.0752996e+00 -2.8856902e-01 6.5849442e+00 - 1.8850284e+00 -2.5336862e-01 6.2546757e+00 - 1.5299807e+00 -1.8798119e-01 5.2013440e+00 - 1.4516581e+00 -1.7379282e-01 5.1898136e+00 - 1.3793749e+00 -1.6059635e-01 5.2060291e+00 - 1.3121352e+00 -1.4831163e-01 5.2503931e+00 - 1.4921466e+00 -1.8134828e-01 6.7217257e+00 - 1.3212974e+00 -1.5013522e-01 6.2742893e+00 - 1.1824927e+00 -1.2518992e-01 5.9415057e+00 - 1.0576427e+00 -1.0176272e-01 5.6153189e+00 - 1.0039711e+00 -9.1723512e-02 5.8731732e+00 - 9.2589793e-01 -7.8120344e-02 5.9510805e+00 - 8.3558153e-01 -6.0754140e-02 5.8880039e+00 - 7.4076325e-01 -4.4120953e-02 5.6836169e+00 - 6.6047432e-01 -2.9056138e-02 5.6671494e+00 - 6.4817008e-01 -2.6510796e-02 9.6186737e+00 - 2.4946112e+00 -4.2629397e-01 -1.0045165e+00 - 2.5638279e+00 -4.4143285e-01 -1.0029955e+00 - 2.6409990e+00 -4.5730166e-01 -1.0064938e+00 - 2.7112378e+00 -4.7230884e-01 -1.0010808e+00 - 2.7972585e+00 -4.9082400e-01 -1.0067059e+00 - 2.8764064e+00 -5.0748550e-01 -1.0035691e+00 - 2.9565058e+00 -5.2509602e-01 -9.9818867e-01 - 3.0445666e+00 -5.4338228e-01 -9.9672887e-01 - 3.1335813e+00 -5.6259785e-01 -9.9262591e-01 - 3.2305013e+00 -5.8345163e-01 -9.9169488e-01 - 3.3363268e+00 -6.0598929e-01 -9.9363935e-01 - 3.4519987e+00 -6.3124360e-01 -9.9791356e-01 - 3.5598612e+00 -6.5357700e-01 -9.9327252e-01 - 3.6844669e+00 -6.8028856e-01 -9.9582789e-01 - 3.8110321e+00 -7.0793075e-01 -9.9454476e-01 - 3.9465747e+00 -7.3616627e-01 -9.9428901e-01 - 4.1008088e+00 -7.6979927e-01 -9.9918893e-01 - 4.2472366e+00 -8.0048672e-01 -9.9467424e-01 - 4.4291545e+00 -8.3999227e-01 -1.0033602e+00 - 4.6042090e+00 -8.7757027e-01 -1.0017861e+00 - 4.7980915e+00 -9.1842375e-01 -1.0028701e+00 - 5.0195858e+00 -9.6624035e-01 -1.0095881e+00 - 5.2609205e+00 -1.0172796e+00 -1.0166702e+00 - 5.5042413e+00 -1.0690376e+00 -1.0156190e+00 - 5.7573902e+00 -1.1241742e+00 -1.0100565e+00 - 6.0402936e+00 -1.1841940e+00 -1.0060387e+00 - 6.3607450e+00 -1.2526601e+00 -1.0052402e+00 - 6.6831998e+00 -1.3217070e+00 -9.9351198e-01 - 7.0817757e+00 -1.4069762e+00 -9.9366851e-01 - 7.5110282e+00 -1.4988282e+00 -9.8808277e-01 - 8.0263479e+00 -1.6083068e+00 -9.9036894e-01 - 8.5920686e+00 -1.7295502e+00 -9.8647861e-01 - 9.2636011e+00 -1.8734397e+00 -9.8673003e-01 - 9.9866380e+00 -2.0277979e+00 -9.7356668e-01 - 1.1047790e+01 -2.2546484e+00 -9.9896395e-01 - 1.2227683e+01 -2.5068525e+00 -1.0067224e+00 - 1.4030477e+01 -2.8926061e+00 -1.0676071e+00 - 1.5643688e+01 -3.2373608e+00 -1.0385320e+00 - 1.7114705e+01 -3.5517951e+00 -9.3548272e-01 - 2.6590594e+01 -5.5775243e+00 -6.3142660e-01 - 2.8040772e+01 -5.8878662e+00 -2.2918146e-01 - 2.8917558e+01 -6.0750114e+00 2.3951117e-01 - 2.9483904e+01 -6.1955960e+00 7.4177989e-01 - 2.9963195e+01 -6.2989240e+00 1.2634591e+00 - 2.4777355e+01 -5.1895891e+00 2.0842895e+00 - 2.5321775e+01 -5.3065114e+00 2.5528714e+00 - 2.5154990e+01 -5.2709686e+00 2.9845810e+00 - 2.5555095e+01 -5.3563981e+00 3.4674187e+00 - 2.1320949e+01 -4.4507048e+00 3.4262514e+00 - 2.1645656e+01 -4.5206177e+00 3.8471130e+00 - 2.1816098e+01 -4.5566297e+00 4.2580433e+00 - 2.0137064e+01 -4.1973436e+00 4.3606204e+00 - 2.0220306e+01 -4.2157193e+00 4.7378778e+00 - 2.3085576e+01 -4.8284858e+00 5.6993880e+00 - 1.9555542e+01 -4.0733917e+00 5.3203826e+00 - 1.9450728e+01 -4.0515441e+00 5.6527624e+00 - 2.0192265e+01 -4.2101603e+00 6.2081903e+00 - 2.0618171e+01 -4.3004301e+00 6.7057255e+00 - 2.0874768e+01 -4.3559545e+00 7.1718540e+00 - 2.0057299e+01 -4.1805457e+00 7.3060174e+00 - 2.0159473e+01 -4.2029017e+00 7.7271083e+00 - 2.2014310e+01 -4.5990736e+00 8.7913036e+00 - 2.0660052e+01 -4.3097537e+00 8.7082966e+00 - 2.1053533e+01 -4.3934056e+00 9.2793964e+00 - 2.1505471e+01 -4.4902867e+00 9.8975456e+00 - 2.1691046e+01 -4.5305665e+00 1.0422634e+01 - 2.1500373e+01 -4.4889080e+00 1.0786906e+01 - 2.1179872e+01 -4.4205309e+00 1.1086983e+01 - 2.1975757e+01 -4.5912231e+00 1.1949850e+01 - 2.1915866e+01 -4.5782358e+00 1.2400736e+01 - 5.6069044e+00 -1.0910161e+00 3.9545611e+00 - 5.5378916e+00 -1.0768270e+00 4.0350868e+00 - 5.6873256e+00 -1.1088493e+00 4.3796682e+00 - 5.5311637e+00 -1.0750627e+00 4.4054982e+00 - 5.5047827e+00 -1.0699114e+00 4.5174452e+00 - 5.3644404e+00 -1.0398464e+00 4.5481671e+00 - 4.8314955e+00 -9.2581728e-01 4.2775011e+00 - 4.8438019e+00 -9.2804459e-01 4.4090972e+00 - 4.4941497e+00 -8.5366591e-01 4.2495918e+00 - 4.3626454e+00 -8.2530762e-01 4.2567142e+00 - 4.0843408e+00 -7.6562882e-01 4.1303339e+00 - 4.4476797e+00 -8.4388268e-01 4.5715934e+00 - 4.3142098e+00 -8.1464302e-01 4.5738785e+00 - 4.3582161e+00 -8.2485894e-01 4.7447213e+00 - 4.3496973e+00 -8.2318067e-01 4.8690444e+00 - 4.2767522e+00 -8.0671962e-01 4.9299583e+00 - 4.3297851e+00 -8.1816792e-01 5.1273388e+00 - 3.6841119e+00 -6.8028906e-01 4.5537191e+00 - 3.5713249e+00 -6.5660720e-01 4.5500432e+00 - 3.5101961e+00 -6.4319555e-01 4.6043263e+00 - 4.0328454e+00 -7.5543287e-01 5.3828939e+00 - 3.6103336e+00 -6.6472756e-01 4.9991567e+00 - 3.4111389e+00 -6.2252986e-01 4.8795583e+00 - 3.3261887e+00 -6.0401286e-01 4.9067033e+00 - 3.3335926e+00 -6.0574753e-01 5.0624352e+00 - 3.5566805e+00 -6.5320719e-01 5.5491983e+00 - 3.1338177e+00 -5.6324372e-01 5.0693813e+00 - 3.0955475e+00 -5.5511029e-01 5.1663362e+00 - 2.9320578e+00 -5.1949713e-01 5.0585566e+00 - 3.2935406e+00 -5.9723983e-01 5.8509355e+00 - 3.2255542e+00 -5.8237042e-01 5.9262149e+00 - 3.1545670e+00 -5.6736893e-01 6.0005051e+00 - 3.0557193e+00 -5.4636151e-01 6.0205042e+00 - 2.5457706e+00 -4.3711229e-01 5.1972503e+00 - 2.5204705e+00 -4.3187544e-01 5.3324150e+00 - 2.3039632e+00 -3.8572402e-01 5.0493269e+00 - 2.3713231e+00 -4.0035665e-01 5.4018674e+00 - 2.1726694e+00 -3.5774717e-01 5.1297573e+00 - 2.6031194e+00 -4.4995734e-01 6.4615891e+00 - 2.2808414e+00 -3.8061581e-01 5.8707309e+00 - 2.2068275e+00 -3.6517502e-01 5.9299996e+00 - 2.3675325e+00 -3.9935968e-01 6.7089538e+00 - 2.1908265e+00 -3.6075423e-01 6.4838636e+00 - 2.0939129e+00 -3.4087946e-01 6.5036063e+00 - 1.9290182e+00 -3.0536283e-01 6.2710863e+00 - 1.5767106e+00 -2.3002680e-01 5.2597994e+00 - 1.4885353e+00 -2.1110958e-01 5.2103501e+00 - 1.4163780e+00 -1.9587486e-01 5.2273653e+00 - 1.3442127e+00 -1.8070419e-01 5.2430822e+00 - 1.4461950e+00 -2.0244968e-01 6.2211312e+00 - 1.3794511e+00 -1.8775120e-01 6.3752085e+00 - 1.3036572e+00 -1.7200757e-01 6.4989528e+00 - 1.0982668e+00 -1.2757502e-01 5.6498828e+00 - 1.0211976e+00 -1.1140744e-01 5.6796982e+00 - 9.6259121e-01 -9.9070319e-02 5.9172446e+00 - 8.8063887e-01 -8.1224169e-02 5.9547169e+00 - 7.8407129e-01 -6.0432996e-02 5.7511368e+00 - 6.9872806e-01 -4.2478721e-02 5.6655729e+00 - 6.1974124e-01 -2.5045477e-02 5.6983414e+00 - 5.5182881e-01 -1.0959786e-02 7.0697576e+00 - 2.4573386e+00 -4.7873933e-01 -1.0152161e+00 - 2.5117237e+00 -4.9132910e-01 -1.0006131e+00 - 2.5887074e+00 -5.1024297e-01 -1.0050613e+00 - 2.6509352e+00 -5.2548762e-01 -9.9398027e-01 - 2.7278839e+00 -5.4519644e-01 -9.9428405e-01 - 2.8216741e+00 -5.6746689e-01 -1.0054789e+00 - 2.9006475e+00 -5.8706999e-01 -1.0011947e+00 - 2.9796351e+00 -6.0655977e-01 -9.9461336e-01 - 3.0596339e+00 -6.2600654e-01 -9.8593778e-01 - 3.1642509e+00 -6.5171110e-01 -9.9252450e-01 - 3.2610580e+00 -6.7449967e-01 -9.9029585e-01 - 3.3666512e+00 -7.0095617e-01 -9.9064385e-01 - 3.4811536e+00 -7.2906699e-01 -9.9326808e-01 - 3.6055656e+00 -7.5887288e-01 -9.9777221e-01 - 3.7220485e+00 -7.8774683e-01 -9.9316212e-01 - 3.8562782e+00 -8.2101506e-01 -9.9485273e-01 - 3.9915313e+00 -8.5414174e-01 -9.9245158e-01 - 4.1534331e+00 -8.9337613e-01 -9.9982586e-01 - 4.3074701e+00 -9.3064715e-01 -9.9743635e-01 - 4.4812050e+00 -9.7331205e-01 -9.9890729e-01 - 4.6816056e+00 -1.0219467e+00 -1.0073571e+00 - 4.8651889e+00 -1.0678276e+00 -1.0010207e+00 - 5.1050768e+00 -1.1260019e+00 -1.0121473e+00 - 5.3361142e+00 -1.1820537e+00 -1.0115094e+00 - 5.5967149e+00 -1.2460634e+00 -1.0139655e+00 - 5.8573705e+00 -1.3096346e+00 -1.0075326e+00 - 6.1486005e+00 -1.3811206e+00 -1.0020995e+00 - 6.4773227e+00 -1.4620154e+00 -9.9913703e-01 - 6.8258596e+00 -1.5468539e+00 -9.9089591e-01 - 7.2227517e+00 -1.6437304e+00 -9.8446206e-01 - 7.6966121e+00 -1.7596440e+00 -9.8497341e-01 - 8.2287111e+00 -1.8900168e+00 -9.8362915e-01 - 8.8378253e+00 -2.0390521e+00 -9.8163946e-01 - 9.5358238e+00 -2.2093758e+00 -9.7704574e-01 - 1.0330528e+01 -2.4043292e+00 -9.6702809e-01 - 1.1481540e+01 -2.6858001e+00 -9.9328944e-01 - 1.2789607e+01 -3.0050602e+00 -1.0037378e+00 - 1.4823054e+01 -3.5024115e+00 -1.0720556e+00 - 1.6080096e+01 -3.8099455e+00 -9.6912722e-01 - 2.6410638e+01 -6.3365631e+00 -8.6480918e-01 - 2.7389296e+01 -6.5756886e+00 -4.5035058e-01 - 2.8040291e+01 -6.7355485e+00 1.0380008e-02 - 2.8801003e+01 -6.9210622e+00 4.9192373e-01 - 2.9000026e+01 -6.9699996e+00 1.0004349e+00 - 2.9277112e+01 -7.0372660e+00 1.5175785e+00 - 2.5079605e+01 -6.0112138e+00 1.8840583e+00 - 2.5284399e+01 -6.0612297e+00 2.3375192e+00 - 2.5073484e+01 -6.0099717e+00 2.7694269e+00 - 2.5242744e+01 -6.0515193e+00 3.2289971e+00 - 3.0862338e+01 -7.4257469e+00 4.2857589e+00 - 2.0640397e+01 -4.9252259e+00 3.5461735e+00 - 2.1286468e+01 -5.0837373e+00 4.0078692e+00 - 1.9601625e+01 -4.6717206e+00 4.1148897e+00 - 1.9651135e+01 -4.6838100e+00 4.4767263e+00 - 2.0218307e+01 -4.8221222e+00 4.9462229e+00 - 1.9939900e+01 -4.7538960e+00 5.2540577e+00 - 1.9617948e+01 -4.6758916e+00 5.5442575e+00 - 2.0650616e+01 -4.9277166e+00 6.1724724e+00 - 2.0457178e+01 -4.8804303e+00 6.5053459e+00 - 2.0650051e+01 -4.9282344e+00 6.9484585e+00 - 2.1651337e+01 -5.1731423e+00 7.6575259e+00 - 2.0112997e+01 -4.7961591e+00 7.5606177e+00 - 1.9741616e+01 -4.7056240e+00 7.8208679e+00 - 1.9960252e+01 -4.7596070e+00 8.2920607e+00 - 2.4367997e+01 -5.8372586e+00 1.0432519e+01 - 2.3295074e+01 -5.5744189e+00 1.0481545e+01 - 2.2469102e+01 -5.3731745e+00 1.0600469e+01 - 2.1610471e+01 -5.1630614e+00 1.0676505e+01 - 2.2508665e+01 -5.3827598e+00 1.1565688e+01 - 2.1531323e+01 -5.1434330e+00 1.1560516e+01 - 2.3253413e+01 -5.5642852e+00 1.2935529e+01 - 5.6655686e+00 -1.2634145e+00 3.9476845e+00 - 5.5808978e+00 -1.2426657e+00 4.0200736e+00 - 5.4200960e+00 -1.2026788e+00 4.0439243e+00 - 5.4669170e+00 -1.2150288e+00 4.1954310e+00 - 5.3308317e+00 -1.1810306e+00 4.2297373e+00 - 5.4519050e+00 -1.2110426e+00 4.4390276e+00 - 5.3296639e+00 -1.1804775e+00 4.4816279e+00 - 5.3092947e+00 -1.1755066e+00 4.5972512e+00 - 5.0147618e+00 -1.1042412e+00 4.5026393e+00 - 4.7558933e+00 -1.0403996e+00 4.4230919e+00 - 4.8928826e+00 -1.0738787e+00 4.6626923e+00 - 4.5032381e+00 -9.7925521e-01 4.4582806e+00 - 4.5679782e+00 -9.9513907e-01 4.6411896e+00 - 4.5060243e+00 -9.7976843e-01 4.7137037e+00 - 4.5351729e+00 -9.8661390e-01 4.8737587e+00 - 4.3494081e+00 -9.4157597e-01 4.8276282e+00 - 4.4013891e+00 -9.5339244e-01 5.0163226e+00 - 4.2651377e+00 -9.2020531e-01 5.0139246e+00 - 4.3150630e+00 -9.3340705e-01 5.2126123e+00 - 3.6061510e+00 -7.5991108e-01 4.5522207e+00 - 3.7621284e+00 -7.9796530e-01 4.8641186e+00 - 3.7090425e+00 -7.8509320e-01 4.9375022e+00 - 3.8680949e+00 -8.2371656e-01 5.2820494e+00 - 3.8725450e+00 -8.2494472e-01 5.4443827e+00 - 3.3287743e+00 -6.9148419e-01 4.8653458e+00 - 3.4402513e+00 -7.1935983e-01 5.1665033e+00 - 3.6312119e+00 -7.6533976e-01 5.6036305e+00 - 3.1288066e+00 -6.4299975e-01 5.0125715e+00 - 3.0440027e+00 -6.2176779e-01 5.0339747e+00 - 3.0325762e+00 -6.1921349e-01 5.1723900e+00 - 2.8762981e+00 -5.8068282e-01 5.0715308e+00 - 3.2341937e+00 -6.6865395e-01 5.8757503e+00 - 3.1653258e+00 -6.5175974e-01 5.9503346e+00 - 3.0855447e+00 -6.3212116e-01 6.0063280e+00 - 3.0663851e+00 -6.2706823e-01 6.1856183e+00 - 2.4628597e+00 -4.7991793e-01 5.1434040e+00 - 2.3918699e+00 -4.6287468e-01 5.1780447e+00 - 2.3288498e+00 -4.4747139e-01 5.2297381e+00 - 2.3325136e+00 -4.4797750e-01 5.4460072e+00 - 2.7233385e+00 -5.4339733e-01 6.6651024e+00 - 2.3170922e+00 -4.4386775e-01 5.8732268e+00 - 2.2273070e+00 -4.2174057e-01 5.8864064e+00 - 2.1564027e+00 -4.0504570e-01 5.9545051e+00 - 2.0306855e+00 -3.7453821e-01 5.8504488e+00 - 1.9877570e+00 -3.6396116e-01 6.0110905e+00 - 1.9269268e+00 -3.4867911e-01 6.1235513e+00 - 1.6032987e+00 -2.6971164e-01 5.2403667e+00 - 1.5193007e+00 -2.4904406e-01 5.2110302e+00 - 1.4462710e+00 -2.3119651e-01 5.2190109e+00 - 1.3742311e+00 -2.1399252e-01 5.2354277e+00 - 1.4879436e+00 -2.4153862e-01 6.2321131e+00 - 1.4072266e+00 -2.2134199e-01 6.2981972e+00 - 1.2307397e+00 -1.7870720e-01 5.7508097e+00 - 1.1498121e+00 -1.5916232e-01 5.7631609e+00 - 1.0587663e+00 -1.3649295e-01 5.6848087e+00 - 9.8593289e-01 -1.1914016e-01 5.7638003e+00 - 9.4192307e-01 -1.0783440e-01 6.2001528e+00 - 8.3131546e-01 -8.1048897e-02 5.8781179e+00 - 7.3473640e-01 -5.7770804e-02 5.6236526e+00 - 6.5787046e-01 -3.7915928e-02 5.6471773e+00 - 6.4556767e-01 -3.5874868e-02 9.6087388e+00 - 2.4733907e+00 -5.4472575e-01 -1.0115595e+00 - 2.5345435e+00 -5.6103992e-01 -1.0031224e+00 - 2.6035298e+00 -5.8008286e-01 -9.9970530e-01 - 2.6803513e+00 -6.0183979e-01 -1.0010086e+00 - 2.7571858e+00 -6.2349326e-01 -1.0002145e+00 - 2.8429176e+00 -6.4689466e-01 -1.0035943e+00 - 2.9217768e+00 -6.6844240e-01 -9.9821229e-01 - 3.0084768e+00 -6.9265979e-01 -9.9665177e-01 - 3.0951922e+00 -7.1675401e-01 -9.9259433e-01 - 3.1918094e+00 -7.4260735e-01 -9.9171519e-01 - 3.2883836e+00 -7.6931969e-01 -9.8798995e-01 - 3.4095251e+00 -8.0321286e-01 -9.9797931e-01 - 3.5159661e+00 -8.3247927e-01 -9.9328788e-01 - 3.6391496e+00 -8.6612877e-01 -9.9589273e-01 - 3.7642932e+00 -9.0070398e-01 -9.9455920e-01 - 3.8972950e+00 -9.3781089e-01 -9.9425065e-01 - 4.0490480e+00 -9.7932326e-01 -9.9924721e-01 - 4.1938730e+00 -1.0199395e+00 -9.9463334e-01 - 4.3554584e+00 -1.0647960e+00 -9.9441933e-01 - 4.5544780e+00 -1.1195244e+00 -1.0060644e+00 - 4.7279648e+00 -1.1667503e+00 -9.9869819e-01 - 4.9368384e+00 -1.2246504e+00 -1.0016370e+00 - 5.1664284e+00 -1.2878422e+00 -1.0051435e+00 - 5.4235835e+00 -1.3588857e+00 -1.0120373e+00 - 5.6728899e+00 -1.4278377e+00 -1.0065705e+00 - 5.9517689e+00 -1.5046736e+00 -1.0026996e+00 - 6.2493298e+00 -1.5875000e+00 -9.9574492e-01 - 6.5952275e+00 -1.6825123e+00 -9.9359381e-01 - 6.9696702e+00 -1.7860986e+00 -9.8799201e-01 - 7.4012623e+00 -1.9053270e+00 -9.8547572e-01 - 7.9097140e+00 -2.0454927e+00 -9.8790786e-01 - 8.4388460e+00 -2.1922690e+00 -9.7712551e-01 - 9.0724820e+00 -2.3666848e+00 -9.7163226e-01 - 9.8223218e+00 -2.5742677e+00 -9.6752308e-01 - 1.0792876e+01 -2.8420889e+00 -9.7882589e-01 - 1.2041265e+01 -3.1865360e+00 -1.0034829e+00 - 1.3636424e+01 -3.6275751e+00 -1.0365294e+00 - 1.5627793e+01 -4.1766247e+00 -1.0659928e+00 - 1.6934780e+01 -4.5373007e+00 -9.4232867e-01 - 2.6428639e+01 -7.1592520e+00 -6.4481716e-01 - 2.6703003e+01 -7.2352958e+00 -1.8649691e-01 - 2.6931122e+01 -7.2979919e+00 2.8236384e-01 - 2.6958213e+01 -7.3059372e+00 7.6087846e-01 - 2.7083922e+01 -7.3398174e+00 1.2410649e+00 - 2.9320409e+01 -7.9575055e+00 1.7833771e+00 - 2.4158353e+01 -6.5327317e+00 2.5014934e+00 - 2.5176884e+01 -6.8134683e+00 3.0151786e+00 - 2.1541143e+01 -5.8101628e+00 3.1021710e+00 - 2.0353610e+01 -5.4815189e+00 3.3470030e+00 - 1.9613439e+01 -5.2772572e+00 3.6107282e+00 - 1.9786077e+01 -5.3249868e+00 3.9903836e+00 - 1.9647183e+01 -5.2869626e+00 4.3242784e+00 - 1.9806080e+01 -5.3304363e+00 4.7123192e+00 - 2.2272256e+01 -6.0112510e+00 5.5956460e+00 - 2.0441418e+01 -5.5059083e+00 5.5866256e+00 - 2.0660526e+01 -5.5667347e+00 6.0216080e+00 - 2.0722912e+01 -5.5835077e+00 6.4259484e+00 - 2.0386809e+01 -5.4913257e+00 6.7218440e+00 - 2.0361428e+01 -5.4838536e+00 7.1037033e+00 - 2.0550078e+01 -5.5358341e+00 7.5585622e+00 - 2.1652189e+01 -5.8402784e+00 8.3426336e+00 - 2.0771594e+01 -5.5973180e+00 8.4474220e+00 - 2.3558918e+01 -6.3673314e+00 9.9445204e+00 - 2.1548739e+01 -5.8115647e+00 9.6019100e+00 - 2.1053825e+01 -5.6749191e+00 9.8325135e+00 - 2.3739134e+01 -6.4170864e+00 1.1483359e+01 - 2.3384496e+01 -6.3187746e+00 1.1819516e+01 - 2.3642661e+01 -6.3902080e+00 1.2451824e+01 - 5.5080451e+00 -1.3826814e+00 3.9398219e+00 - 5.4580579e+00 -1.3691581e+00 4.0300752e+00 - 5.3073760e+00 -1.3276389e+00 4.0566915e+00 - 5.4183733e+00 -1.3578002e+00 4.2507324e+00 - 5.3782438e+00 -1.3474190e+00 4.3502912e+00 - 5.1623892e+00 -1.2874992e+00 4.3248385e+00 - 5.1765992e+00 -1.2916196e+00 4.4610219e+00 - 5.3577777e+00 -1.3413741e+00 4.7295874e+00 - 5.0727464e+00 -1.2623864e+00 4.6404432e+00 - 5.0405280e+00 -1.2541132e+00 4.7475664e+00 - 5.1852038e+00 -1.2940742e+00 5.0073636e+00 - 4.6926266e+00 -1.1574918e+00 4.7148106e+00 - 4.5715013e+00 -1.1239846e+00 4.7372342e+00 - 4.4651693e+00 -1.0948794e+00 4.7697960e+00 - 4.4497541e+00 -1.0910205e+00 4.8892482e+00 - 4.5560215e+00 -1.1193097e+00 5.1353904e+00 - 4.3913366e+00 -1.0745953e+00 5.1083694e+00 - 4.4214769e+00 -1.0825837e+00 5.2869975e+00 - 4.3418600e+00 -1.0606014e+00 5.3499830e+00 - 3.6421149e+00 -8.6783224e-01 4.6848796e+00 - 3.5298072e+00 -8.3619445e-01 4.6804078e+00 - 3.5222828e+00 -8.3460618e-01 4.8041285e+00 - 3.3980570e+00 -8.0021776e-01 4.7799704e+00 - 3.3341610e+00 -7.8274533e-01 4.8318675e+00 - 3.3950028e+00 -7.9918094e-01 5.0594828e+00 - 3.3598710e+00 -7.8904773e-01 5.1601243e+00 - 3.3771827e+00 -7.9403958e-01 5.3430892e+00 - 3.0855856e+00 -7.1362540e-01 5.0526670e+00 - 2.9751706e+00 -6.8293619e-01 5.0314095e+00 - 2.9172006e+00 -6.6736219e-01 5.0926752e+00 - 3.4101795e+00 -8.0322670e-01 6.1267049e+00 - 3.1482291e+00 -7.3061935e-01 5.8565095e+00 - 3.0665793e+00 -7.0829271e-01 5.9037712e+00 - 3.0543376e+00 -7.0524792e-01 6.0914281e+00 - 3.0114318e+00 -6.9294125e-01 6.2263527e+00 - 2.9437167e+00 -6.7435675e-01 6.3161654e+00 - 2.8620954e+00 -6.5231761e-01 6.3778589e+00 - 2.7170076e+00 -6.1173868e-01 6.2914476e+00 - 2.7208230e+00 -6.1258014e-01 6.5616988e+00 - 2.6869248e+00 -6.0372004e-01 6.7593151e+00 - 2.3191113e+00 -5.0247227e-01 6.0487181e+00 - 2.6810232e+00 -6.0205741e-01 7.3910487e+00 - 2.0165000e+00 -4.1908851e-01 5.7037502e+00 - 2.1000874e+00 -4.4140376e-01 6.2645259e+00 - 1.9477214e+00 -3.9963243e-01 6.0721701e+00 - 1.6277681e+00 -3.1128426e-01 5.2207398e+00 - 1.5518783e+00 -2.9063400e-01 5.2210907e+00 - 1.4810308e+00 -2.7039121e-01 5.2395530e+00 - 1.4071203e+00 -2.5051393e-01 5.2469385e+00 - 1.5295074e+00 -2.8416703e-01 6.2523820e+00 - 1.4218422e+00 -2.5406776e-01 6.1620515e+00 - 1.3411803e+00 -2.3239946e-01 6.2174496e+00 - 1.1850739e+00 -1.8867146e-01 5.7571900e+00 - 1.3164165e+00 -2.2558464e-01 7.4344676e+00 - 1.0194467e+00 -1.4293414e-01 5.7294235e+00 - 1.0528272e+00 -1.5287959e-01 6.9624285e+00 - 9.4722047e-01 -1.2343681e-01 6.9017542e+00 - 1.0132126e+00 -1.4113436e-01 9.7136875e+00 - 6.9494333e-01 -5.3769570e-02 5.6356156e+00 - 6.1719536e-01 -3.1894823e-02 5.6583452e+00 - 5.5071184e-01 -1.3911662e-02 7.0897346e+00 - 2.4126559e+00 -5.8867934e-01 -1.0010066e+00 - 2.4863901e+00 -6.1151299e-01 -1.0075443e+00 - 2.5474273e+00 -6.2978165e-01 -9.9820905e-01 - 2.6231229e+00 -6.5353117e-01 -1.0006086e+00 - 2.6930035e+00 -6.7449544e-01 -9.9439893e-01 - 2.7844347e+00 -7.0263657e-01 -1.0054899e+00 - 2.8542816e+00 -7.2438595e-01 -9.9493594e-01 - 2.9398544e+00 -7.5060578e-01 -9.9467141e-01 - 3.0263799e+00 -7.7776477e-01 -9.9196347e-01 - 3.1129817e+00 -8.0379871e-01 -9.8670829e-01 - 3.2240851e+00 -8.3805478e-01 -9.9601704e-01 - 3.3125973e+00 -8.6592763e-01 -9.8507603e-01 - 3.4335680e+00 -9.0273284e-01 -9.9331871e-01 - 3.5476686e+00 -9.3766469e-01 -9.9240004e-01 - 3.6617305e+00 -9.7342106e-01 -9.8793613e-01 - 3.8102037e+00 -1.0190946e+00 -9.9991607e-01 - 3.9351429e+00 -1.0573670e+00 -9.9249162e-01 - 4.0866077e+00 -1.1037607e+00 -9.9514301e-01 - 4.2380419e+00 -1.1509148e+00 -9.9295078e-01 - 4.4170725e+00 -1.2051552e+00 -9.9888959e-01 - 4.5970172e+00 -1.2611594e+00 -9.9883976e-01 - 4.7868342e+00 -1.3196732e+00 -9.9692484e-01 - 5.0042034e+00 -1.3861422e+00 -1.0004946e+00 - 5.2402355e+00 -1.4587544e+00 -1.0040768e+00 - 5.4870938e+00 -1.5348056e+00 -1.0031508e+00 - 5.7359395e+00 -1.6115658e+00 -9.9389180e-01 - 6.0299884e+00 -1.7024722e+00 -9.9232404e-01 - 6.3535645e+00 -1.8021412e+00 -9.8990556e-01 - 6.6968349e+00 -1.9077478e+00 -9.8210933e-01 - 7.0961864e+00 -2.0300118e+00 -9.7894391e-01 - 7.5525160e+00 -2.1708347e+00 -9.7721720e-01 - 8.0482071e+00 -2.3237495e+00 -9.6912957e-01 - 8.7041752e+00 -2.5254858e+00 -9.8165021e-01 - 9.3336778e+00 -2.7191370e+00 -9.6456951e-01 - 1.0125398e+01 -2.9632073e+00 -9.5751727e-01 - 1.1238675e+01 -3.3054606e+00 -9.8114814e-01 - 1.2534835e+01 -3.7053809e+00 -9.9425244e-01 - 1.4430860e+01 -4.2890152e+00 -1.0483545e+00 - 1.6038070e+01 -4.7837081e+00 -9.9592651e-01 - 2.6594287e+01 -8.0329691e+00 -9.0881835e-01 - 2.6717705e+01 -8.0711497e+00 -4.3721652e-01 - 2.6547112e+01 -8.0186375e+00 4.8747484e-02 - 2.6424656e+01 -7.9814548e+00 5.2696039e-01 - 2.6514691e+01 -8.0084992e+00 1.0004217e+00 - 2.6941080e+01 -8.1396512e+00 1.4832499e+00 - 3.1227156e+01 -9.4600667e+00 2.1231678e+00 - 2.6517143e+01 -8.0099630e+00 2.4270383e+00 - 3.3621133e+01 -1.0197026e+01 3.4238206e+00 - 2.1921982e+01 -6.5944655e+00 2.9612897e+00 - 2.1904474e+01 -6.5899259e+00 3.3542587e+00 - 2.1208154e+01 -6.3751588e+00 3.6606486e+00 - 2.0526490e+01 -6.1653733e+00 3.9451666e+00 - 1.9737524e+01 -5.9220725e+00 4.1883439e+00 - 1.9757349e+01 -5.9282127e+00 4.5530740e+00 - 2.0520196e+01 -6.1631490e+00 5.0720857e+00 - 2.3020244e+01 -6.9326264e+00 6.0088378e+00 - 2.0595382e+01 -6.1869729e+00 5.8546612e+00 - 2.0493288e+01 -6.1548201e+00 6.2160523e+00 - 2.0735644e+01 -6.2299758e+00 6.6735250e+00 - 2.0793985e+01 -6.2479540e+00 7.0890636e+00 - 2.2864674e+01 -6.8847913e+00 8.1545868e+00 - 2.0678419e+01 -6.2116678e+00 7.8603397e+00 - 2.0651094e+01 -6.2041750e+00 8.2604325e+00 - 2.2916157e+01 -6.9014395e+00 9.5370948e+00 - 2.1200275e+01 -6.3725379e+00 9.3143413e+00 - 2.1022411e+01 -6.3177361e+00 9.6760841e+00 - 2.4402876e+01 -7.3583302e+00 1.1616403e+01 - 2.7042145e+01 -8.1710949e+00 1.3365031e+01 - 5.9083462e+00 -1.6648863e+00 4.1368004e+00 - 5.7136321e+00 -1.6053213e+00 4.1500827e+00 - 5.6440686e+00 -1.5838861e+00 4.2344595e+00 - 5.6297155e+00 -1.5790612e+00 4.3544583e+00 - 5.3886538e+00 -1.5049099e+00 4.3223517e+00 - 5.3880816e+00 -1.5045397e+00 4.4501947e+00 - 5.2751037e+00 -1.4702204e+00 4.4988604e+00 - 5.3090440e+00 -1.4805068e+00 4.6560518e+00 - 5.3085187e+00 -1.4797622e+00 4.7914854e+00 - 5.2369385e+00 -1.4583688e+00 4.8725727e+00 - 5.2610440e+00 -1.4658449e+00 5.0339916e+00 - 4.8196896e+00 -1.3298180e+00 4.7925131e+00 - 4.6041090e+00 -1.2635829e+00 4.7330056e+00 - 4.5265971e+00 -1.2398212e+00 4.7939880e+00 - 4.5191564e+00 -1.2370488e+00 4.9214545e+00 - 4.3775139e+00 -1.1935639e+00 4.9178810e+00 - 4.6759461e+00 -1.2854162e+00 5.3699239e+00 - 4.4899057e+00 -1.2283544e+00 5.3232020e+00 - 4.4686923e+00 -1.2215773e+00 5.4539602e+00 - 4.2796841e+00 -1.1630891e+00 5.3919674e+00 - 4.1054054e+00 -1.1100292e+00 5.3395632e+00 - 3.4295818e+00 -9.0166595e-01 4.6540187e+00 - 3.4171346e+00 -8.9820030e-01 4.7691667e+00 - 3.3356147e+00 -8.7277265e-01 4.7982525e+00 - 3.3469461e+00 -8.7578549e-01 4.9532222e+00 - 3.3760307e+00 -8.8520481e-01 5.1421399e+00 - 3.3281264e+00 -8.7007940e-01 5.2267945e+00 - 3.7328407e+00 -9.9474470e-01 6.0156142e+00 - 3.0918831e+00 -7.9812390e-01 5.1765440e+00 - 3.1379001e+00 -8.1195620e-01 5.4183400e+00 - 3.3352633e+00 -8.7231382e-01 5.9372368e+00 - 3.3665344e+00 -8.8239807e-01 6.1961602e+00 - 3.2286914e+00 -8.4018291e-01 6.1514751e+00 - 3.0839131e+00 -7.9558343e-01 6.0857894e+00 - 2.9945205e+00 -7.6825645e-01 6.1233405e+00 - 2.9299202e+00 -7.4785939e-01 6.2130445e+00 - 2.8791500e+00 -7.3255614e-01 6.3381579e+00 - 2.7392978e+00 -6.8877622e-01 6.2619692e+00 - 2.7331427e+00 -6.8737717e-01 6.5046376e+00 - 2.6695700e+00 -6.6783727e-01 6.6187075e+00 - 2.5851676e+00 -6.4236481e-01 6.6855554e+00 - 2.1475498e+00 -5.0664906e-01 5.7359958e+00 - 2.0987083e+00 -4.9252279e-01 5.8599539e+00 - 2.1443297e+00 -5.0663736e-01 6.2974076e+00 - 1.8382450e+00 -4.1142700e-01 5.5807199e+00 - 1.6531713e+00 -3.5446292e-01 5.2102976e+00 - 1.5784057e+00 -3.3183486e-01 5.2114452e+00 - 1.5146080e+00 -3.1254588e-01 5.2596476e+00 - 1.4438778e+00 -2.9033381e-01 5.2775114e+00 - 1.4040810e+00 -2.7832531e-01 5.4505786e+00 - 1.3763835e+00 -2.7019950e-01 5.7216834e+00 - 1.3328359e+00 -2.5653206e-01 5.9437524e+00 - 1.2020581e+00 -2.1648092e-01 5.6421134e+00 - 1.3267878e+00 -2.5492259e-01 7.1595099e+00 - 1.0588925e+00 -1.7167193e-01 5.7642391e+00 - 9.8124609e-01 -1.4847014e-01 5.7936109e+00 - 9.9259552e-01 -1.5146787e-01 6.8974501e+00 - 9.2936303e-01 -1.3200291e-01 7.4342431e+00 - 7.2983245e-01 -7.1000039e-02 5.5936977e+00 - 6.5526886e-01 -4.7789208e-02 5.6471798e+00 - 6.4302546e-01 -4.4241985e-02 9.5987544e+00 - 2.5660186e+00 -7.0319907e-01 -9.9970844e-01 - 2.6337763e+00 -7.2608563e-01 -9.9439206e-01 - 2.7024830e+00 -7.4994090e-01 -9.8723154e-01 - 2.7859143e+00 -7.7823081e-01 -9.9085662e-01 - 2.8781853e+00 -8.0924589e-01 -9.9820653e-01 - 2.9557575e+00 -8.3561942e-01 -9.9057601e-01 - 3.0411712e+00 -8.6465767e-01 -9.8666715e-01 - 3.1353674e+00 -8.9739342e-01 -9.8593419e-01 - 3.2306399e+00 -9.2904979e-01 -9.8235753e-01 - 3.3493611e+00 -9.6982045e-01 -9.9239319e-01 - 3.4533805e+00 -1.0059742e+00 -9.8794781e-01 - 3.5751412e+00 -1.0465666e+00 -9.9070202e-01 - 3.6968658e+00 -1.0879637e+00 -9.8951148e-01 - 3.8362186e+00 -1.1357343e+00 -9.9422291e-01 - 3.9775956e+00 -1.1834041e+00 -9.9444625e-01 - 4.1267765e+00 -1.2345533e+00 -9.9464625e-01 - 4.2779238e+00 -1.2865789e+00 -9.8990910e-01 - 4.4556097e+00 -1.3466224e+00 -9.9315040e-01 - 4.6342700e+00 -1.4074326e+00 -9.9045260e-01 - 4.8404191e+00 -1.4772195e+00 -9.9368933e-01 - 5.0651672e+00 -1.5541761e+00 -9.9748820e-01 - 5.2997403e+00 -1.6345360e+00 -9.9727502e-01 - 5.5628214e+00 -1.7237655e+00 -9.9960375e-01 - 5.8268972e+00 -1.8135992e+00 -9.9269746e-01 - 6.1194337e+00 -1.9131961e+00 -9.8618612e-01 - 6.4404403e+00 -2.0224822e+00 -9.7857158e-01 - 6.8075574e+00 -2.1477325e+00 -9.7375826e-01 - 7.2316421e+00 -2.2916254e+00 -9.7208156e-01 - 7.7125931e+00 -2.4560023e+00 -9.7034619e-01 - 8.2407040e+00 -2.6359948e+00 -9.6312547e-01 - 8.8728980e+00 -2.8506004e+00 -9.6074712e-01 - 9.5630217e+00 -3.0852281e+00 -9.4772637e-01 - 1.0430732e+01 -3.3812116e+00 -9.4428946e-01 - 1.1647803e+01 -3.7960635e+00 -9.7048667e-01 - 1.3054407e+01 -4.2747902e+00 -9.8188721e-01 - 1.5356957e+01 -5.0590004e+00 -1.0659507e+00 - 1.7316367e+01 -5.7259371e+00 -1.0238208e+00 - 2.7249095e+01 -9.1077085e+00 -7.2788271e-01 - 2.6961094e+01 -9.0099070e+00 -2.2009923e-01 - 2.6749597e+01 -8.9384564e+00 2.7429430e-01 - 2.6871845e+01 -8.9800126e+00 7.5728370e-01 - 2.7325897e+01 -9.1345255e+00 1.2477017e+00 - 2.5201562e+01 -8.4112016e+00 2.1396626e+00 - 2.5377771e+01 -8.4707987e+00 2.6077898e+00 - 2.1875002e+01 -7.2778282e+00 2.7774200e+00 - 2.1973431e+01 -7.3116838e+00 3.1845834e+00 - 2.1897109e+01 -7.2856311e+00 3.5756527e+00 - 2.2283333e+01 -7.4167859e+00 4.0297933e+00 - 2.1377121e+01 -7.1090652e+00 4.2964487e+00 - 2.1534506e+01 -7.1627766e+00 4.7188455e+00 - 2.1991544e+01 -7.3175300e+00 5.2080555e+00 - 2.0582303e+01 -6.8378309e+00 5.3165441e+00 - 2.0803522e+01 -6.9136353e+00 5.7554563e+00 - 2.0492342e+01 -6.8079565e+00 6.0706570e+00 - 2.0597718e+01 -6.8435788e+00 6.4910809e+00 - 2.3377467e+01 -7.7898252e+00 7.7025563e+00 - 2.1956135e+01 -7.3061793e+00 7.7143058e+00 - 2.0722370e+01 -6.8855268e+00 7.7360146e+00 - 2.0823863e+01 -6.9205494e+00 8.1839668e+00 - 2.2415231e+01 -7.4627600e+00 9.1985203e+00 - 2.1788674e+01 -7.2489637e+00 9.4087092e+00 - 2.1708519e+01 -7.2213981e+00 9.8255595e+00 - 2.6097741e+01 -8.7165431e+00 1.2201391e+01 - 2.6499560e+01 -8.8534219e+00 1.2942772e+01 - 2.8046772e+01 -9.3798241e+00 1.4262094e+01 - 2.8532373e+01 -9.5458032e+00 1.5125243e+01 - 5.8961838e+00 -1.8372899e+00 4.2253785e+00 - 5.6703673e+00 -1.7608344e+00 4.2177946e+00 - 5.5842544e+00 -1.7308936e+00 4.2917416e+00 - 5.4970696e+00 -1.7019977e+00 4.3635441e+00 - 5.5279851e+00 -1.7123441e+00 4.5158511e+00 - 5.4772887e+00 -1.6943882e+00 4.6136997e+00 - 5.2858642e+00 -1.6290359e+00 4.6061508e+00 - 5.2174039e+00 -1.6057904e+00 4.6879285e+00 - 5.1558380e+00 -1.5847403e+00 4.7742775e+00 - 5.1523164e+00 -1.5838292e+00 4.9094210e+00 - 5.2039237e+00 -1.6017259e+00 5.0964152e+00 - 4.9917975e+00 -1.5289021e+00 5.0525811e+00 - 4.8455461e+00 -1.4794848e+00 5.0618596e+00 - 4.3517243e+00 -1.3117183e+00 4.7292284e+00 - 4.2625469e+00 -1.2811246e+00 4.7722240e+00 - 4.2944904e+00 -1.2918092e+00 4.9391594e+00 - 4.6337172e+00 -1.4075950e+00 5.4435946e+00 - 4.4549443e+00 -1.3466532e+00 5.4030443e+00 - 4.0426667e+00 -1.2061837e+00 5.0844726e+00 - 4.0440888e+00 -1.2069824e+00 5.2315846e+00 - 3.9549046e+00 -1.1764428e+00 5.2734815e+00 - 3.9918734e+00 -1.1887011e+00 5.4754066e+00 - 3.2925362e+00 -9.5081118e-01 4.7095534e+00 - 3.9396424e+00 -1.1715761e+00 5.7363067e+00 - 3.4107470e+00 -9.9093298e-01 5.1559519e+00 - 3.7701633e+00 -1.1138564e+00 5.8440408e+00 - 3.6849689e+00 -1.0840974e+00 5.8952631e+00 - 3.3787306e+00 -9.8022945e-01 5.5947632e+00 - 3.1346274e+00 -8.9647304e-01 5.3687629e+00 - 3.3877592e+00 -9.8372248e-01 5.9794541e+00 - 3.3005830e+00 -9.5321023e-01 6.0232423e+00 - 3.1471589e+00 -9.0175805e-01 5.9436551e+00 - 3.1419046e+00 -8.9965055e-01 6.1411272e+00 - 3.0171769e+00 -8.5659367e-01 6.1091354e+00 - 2.9239733e+00 -8.2551004e-01 6.1369129e+00 - 2.8466489e+00 -7.9870330e-01 6.1988453e+00 - 2.7683189e+00 -7.7189522e-01 6.2595824e+00 - 2.6810653e+00 -7.4251788e-01 6.3006236e+00 - 2.6156193e+00 -7.1981026e-01 6.3954253e+00 - 2.5956788e+00 -7.1347681e-01 6.6197128e+00 - 2.2074364e+00 -5.8113129e-01 5.8238045e+00 - 2.1141399e+00 -5.4975840e-01 5.8169255e+00 - 1.9920851e+00 -5.0842143e-01 5.7132135e+00 - 1.7896922e+00 -4.3848779e-01 5.3203313e+00 - 1.6823212e+00 -4.0294380e-01 5.2188169e+00 - 1.6077418e+00 -3.7728053e-01 5.2207147e+00 - 1.5570411e+00 -3.5935910e-01 5.3178642e+00 - 1.4893715e+00 -3.3731536e-01 5.3562427e+00 - 1.4138308e+00 -3.1078190e-01 5.3542988e+00 - 1.6375492e+00 -3.8745678e-01 6.9089145e+00 - 1.3176277e+00 -2.7770884e-01 5.6606403e+00 - 1.2731385e+00 -2.6301355e-01 5.8820637e+00 - 1.1696148e+00 -2.2784087e-01 5.7373906e+00 - 1.2924844e+00 -2.6971483e-01 7.3651038e+00 - 1.0156386e+00 -1.7534182e-01 5.7791049e+00 - 1.0337303e+00 -1.8175181e-01 6.8628459e+00 - 9.3965777e-01 -1.4905898e-01 6.9017632e+00 - 1.0002275e+00 -1.6990299e-01 9.6437987e+00 - 6.9016044e-01 -6.4999970e-02 5.6056614e+00 - 6.1577524e-01 -3.9332117e-02 5.6684328e+00 - 5.5059447e-01 -1.7428269e-02 7.1197456e+00 - 2.5071036e+00 -7.4971580e-01 -9.9815154e-01 - 2.5747334e+00 -7.7465539e-01 -9.9393458e-01 - 2.6423749e+00 -7.9950136e-01 -9.8781997e-01 - 2.7246195e+00 -8.3078573e-01 -9.9259162e-01 - 2.8000521e+00 -8.5921456e-01 -9.8855108e-01 - 2.8911511e+00 -8.9310585e-01 -9.9465052e-01 - 2.9686090e+00 -9.2142403e-01 -9.8592214e-01 - 3.0616768e+00 -9.5617206e-01 -9.8668493e-01 - 3.1547021e+00 -9.9177418e-01 -9.8450174e-01 - 3.2644633e+00 -1.0318136e+00 -9.9071347e-01 - 3.3672934e+00 -1.0709815e+00 -9.8781417e-01 - 3.4789724e+00 -1.1128007e+00 -9.8714155e-01 - 3.5995045e+00 -1.1572367e+00 -9.8799647e-01 - 3.7209987e+00 -1.2025379e+00 -9.8490983e-01 - 3.8591236e+00 -1.2541472e+00 -9.8762210e-01 - 3.9982142e+00 -1.3065921e+00 -9.8579355e-01 - 4.1559405e+00 -1.3653971e+00 -9.8837199e-01 - 4.3224739e+00 -1.4277024e+00 -9.9013126e-01 - 4.5066548e+00 -1.4962284e+00 -9.9469632e-01 - 4.6761940e+00 -1.5591406e+00 -9.8482989e-01 - 4.8887213e+00 -1.6393744e+00 -9.8869203e-01 - 5.1121290e+00 -1.7220996e+00 -9.8909424e-01 - 5.3707049e+00 -1.8193093e+00 -9.9600769e-01 - 5.6147086e+00 -1.9098343e+00 -9.8704105e-01 - 5.9115175e+00 -2.0211482e+00 -9.8908934e-01 - 6.2015435e+00 -2.1293751e+00 -9.7763124e-01 - 6.5650214e+00 -2.2647535e+00 -9.7920438e-01 - 6.9295162e+00 -2.4005587e+00 -9.6794694e-01 - 7.3674361e+00 -2.5642463e+00 -9.6427784e-01 - 7.8807411e+00 -2.7567422e+00 -9.6425871e-01 - 8.4225821e+00 -2.9584001e+00 -9.5244958e-01 - 9.0946424e+00 -3.2095150e+00 -9.5001824e-01 - 9.8793847e+00 -3.5024701e+00 -9.4611845e-01 - 1.0795370e+01 -3.8452547e+00 -9.3766722e-01 - 1.2149187e+01 -4.3508842e+00 -9.6924177e-01 - 1.3830231e+01 -4.9785362e+00 -9.9972068e-01 - 1.6083369e+01 -5.8198850e+00 -1.0422132e+00 - 2.1880247e+01 -7.9852856e+00 -9.9631230e-01 - 2.6880617e+01 -9.8527256e+00 -9.6880312e-01 - 2.7386600e+01 -1.0041722e+01 -5.0363755e-01 - 2.7622278e+01 -1.0129750e+01 -1.0545489e-02 - 2.9320592e+01 -1.0763467e+01 4.6339008e-01 - 2.9381014e+01 -1.0786566e+01 1.0004180e+00 - 2.9545332e+01 -1.0847833e+01 1.5415908e+00 - 3.0814896e+01 -1.1321550e+01 2.1304287e+00 - 3.3018376e+01 -1.2144597e+01 2.8196431e+00 - 3.3235838e+01 -1.2226004e+01 3.4439832e+00 - 2.3728174e+01 -8.6752459e+00 3.1696255e+00 - 2.6400120e+01 -9.6726876e+00 3.9062021e+00 - 2.3688747e+01 -8.6607142e+00 4.0397259e+00 - 2.1288773e+01 -7.7645253e+00 4.1191674e+00 - 2.2150669e+01 -8.0855656e+00 4.6608385e+00 - 2.1810791e+01 -7.9593367e+00 5.0115476e+00 - 2.1576790e+01 -7.8720383e+00 5.3736359e+00 - 2.1959430e+01 -8.0149442e+00 5.8695290e+00 - 2.1110733e+01 -7.6974621e+00 6.0795790e+00 - 2.1278670e+01 -7.7604187e+00 6.5306017e+00 - 2.1637838e+01 -7.8949068e+00 7.0462492e+00 - 2.0400652e+01 -7.4327423e+00 7.0917633e+00 - 2.0334253e+01 -7.4077622e+00 7.4733125e+00 - 2.2051797e+01 -8.0494929e+00 8.4753757e+00 - 2.1385261e+01 -7.8006030e+00 8.6770717e+00 - 2.1582809e+01 -7.8742278e+00 9.1916157e+00 - 2.1647016e+01 -7.8976819e+00 9.6655600e+00 - 2.9805382e+01 -1.0945342e+01 1.3639513e+01 - 2.8128821e+01 -1.0318433e+01 1.3519215e+01 - 2.7765718e+01 -1.0183373e+01 1.3958842e+01 - 2.7778407e+01 -1.0188425e+01 1.4578977e+01 - 2.7181797e+01 -9.9653004e+00 1.4892149e+01 - 6.0543319e+00 -2.0744791e+00 4.2870653e+00 - 5.9438331e+00 -2.0333285e+00 4.3551030e+00 - 5.9040173e+00 -2.0183780e+00 4.4662490e+00 - 5.8062877e+00 -1.9817301e+00 4.5399369e+00 - 5.7399524e+00 -1.9570617e+00 4.6327450e+00 - 5.5008007e+00 -1.8679475e+00 4.6012902e+00 - 5.3804907e+00 -1.8222520e+00 4.6479382e+00 - 5.2816847e+00 -1.7861693e+00 4.7089449e+00 - 5.1455935e+00 -1.7354136e+00 4.7373183e+00 - 5.0910506e+00 -1.7145009e+00 4.8294379e+00 - 5.2682937e+00 -1.7808763e+00 5.1220762e+00 - 4.8846696e+00 -1.6369823e+00 4.9274120e+00 - 4.9754732e+00 -1.6713860e+00 5.1528252e+00 - 5.0731936e+00 -1.7083218e+00 5.3962427e+00 - 4.9528226e+00 -1.6631141e+00 5.4330029e+00 - 4.2869499e+00 -1.4144705e+00 4.9040057e+00 - 4.2422012e+00 -1.3972074e+00 4.9951435e+00 - 4.7360972e+00 -1.5824315e+00 5.6829723e+00 - 4.4475544e+00 -1.4748158e+00 5.5197480e+00 - 4.0292116e+00 -1.3177879e+00 5.1838766e+00 - 3.9844280e+00 -1.3013197e+00 5.2791589e+00 - 3.9682208e+00 -1.2947217e+00 5.4123981e+00 - 4.0897070e+00 -1.3403009e+00 5.7327898e+00 - 3.3434944e+00 -1.0615281e+00 4.8849102e+00 - 3.8546179e+00 -1.2529333e+00 5.7518583e+00 - 3.7597199e+00 -1.2172532e+00 5.7893318e+00 - 3.6805687e+00 -1.1874233e+00 5.8493241e+00 - 3.2764610e+00 -1.0371945e+00 5.3939525e+00 - 3.2444924e+00 -1.0253786e+00 5.5121132e+00 - 3.1406789e+00 -9.8603196e-01 5.5116141e+00 - 3.3077178e+00 -1.0486392e+00 5.9887573e+00 - 3.1418301e+00 -9.8663188e-01 5.8843964e+00 - 3.1158862e+00 -9.7644024e-01 6.0377433e+00 - 3.1382401e+00 -9.8493422e-01 6.2976446e+00 - 3.0087703e+00 -9.3700909e-01 6.2569314e+00 - 2.8565947e+00 -8.8052244e-01 6.1590660e+00 - 2.7527707e+00 -8.4125959e-01 6.1568690e+00 - 2.7249232e+00 -8.3072218e-01 6.3350413e+00 - 2.6121645e+00 -7.8897873e-01 6.3113507e+00 - 2.6722764e+00 -8.1146155e-01 6.7393156e+00 - 2.2383930e+00 -6.4959959e-01 5.8360019e+00 - 2.1532040e+00 -6.1773481e-01 5.8488731e+00 - 1.9790168e+00 -5.5208132e-01 5.5857880e+00 - 1.7819211e+00 -4.7845401e-01 5.2131160e+00 - 1.7074770e+00 -4.5067860e-01 5.2173117e+00 - 1.6488657e+00 -4.2909690e-01 5.2775842e+00 - 1.6151334e+00 -4.1581684e-01 5.4432422e+00 - 1.5327440e+00 -3.8569026e-01 5.4245428e+00 - 1.4523405e+00 -3.5576833e-01 5.4041392e+00 - 1.6804942e+00 -4.4027910e-01 6.9275752e+00 - 1.3682450e+00 -3.2444752e-01 5.7706666e+00 - 1.2969267e+00 -2.9735139e-01 5.8255391e+00 - 1.2055713e+00 -2.6396228e-01 5.7606773e+00 - 1.3149002e+00 -3.0388808e-01 7.1891321e+00 - 1.1787900e+00 -2.5358528e-01 6.9056434e+00 - 9.7662176e-01 -1.7781665e-01 5.8433466e+00 - 9.8179458e-01 -1.7988794e-01 6.8775924e+00 - 9.2286240e-01 -1.5820635e-01 7.4642111e+00 - 7.2605223e-01 -8.4317868e-02 5.6036894e+00 - 6.5172849e-01 -5.6095875e-02 5.6371985e+00 - 6.4167089e-01 -5.3218512e-02 9.6586789e+00 - 2.4541381e+00 -7.9691054e-01 -1.0030058e+00 - 2.5206431e+00 -8.2383285e-01 -9.9968536e-01 - 2.5871599e+00 -8.5066156e-01 -9.9446723e-01 - 2.6614530e+00 -8.8119135e-01 -9.9372023e-01 - 2.7435845e+00 -9.1441050e-01 -9.9719425e-01 - 2.8257308e+00 -9.4751142e-01 -9.9827124e-01 - 2.9098292e+00 -9.8160209e-01 -9.9670824e-01 - 2.9861157e+00 -1.0127916e+00 -9.8662952e-01 - 3.0780126e+00 -1.0504060e+00 -9.8594207e-01 - 3.1786945e+00 -1.0916981e+00 -9.8803102e-01 - 3.2715658e+00 -1.1300793e+00 -9.8140449e-01 - 3.3977162e+00 -1.1804194e+00 -9.9331680e-01 - 3.5081672e+00 -1.2260773e+00 -9.9064503e-01 - 3.6196386e+00 -1.2716183e+00 -9.8438087e-01 - 3.7643437e+00 -1.3299970e+00 -9.9420897e-01 - 3.8934084e+00 -1.3827063e+00 -9.8970228e-01 - 4.0400474e+00 -1.4427368e+00 -9.9004923e-01 - 4.1877148e+00 -1.5025862e+00 -9.8550541e-01 - 4.3529035e+00 -1.5706946e+00 -9.8456717e-01 - 4.5357409e+00 -1.6450138e+00 -9.8623495e-01 - 4.7283321e+00 -1.7238219e+00 -9.8563893e-01 - 4.9482978e+00 -1.8135513e+00 -9.8987957e-01 - 5.1693098e+00 -1.9029569e+00 -9.8633302e-01 - 5.4264292e+00 -2.0078946e+00 -9.8905157e-01 - 5.6933239e+00 -2.1171487e+00 -9.8601064e-01 - 5.9798385e+00 -2.2334506e+00 -9.7983957e-01 - 6.2937045e+00 -2.3613753e+00 -9.7246303e-01 - 6.6799125e+00 -2.5183161e+00 -9.7661717e-01 - 7.0582983e+00 -2.6729535e+00 -9.6411602e-01 - 7.5285679e+00 -2.8647946e+00 -9.6286231e-01 - 8.0546036e+00 -3.0789053e+00 -9.5845134e-01 - 8.6451524e+00 -3.3197829e+00 -9.5001442e-01 - 9.3471816e+00 -3.6056134e+00 -9.4365265e-01 - 1.0178189e+01 -3.9453572e+00 -9.3692946e-01 - 1.1350416e+01 -4.4225721e+00 -9.6057459e-01 - 1.2771938e+01 -5.0019220e+00 -9.8042008e-01 - 1.4730128e+01 -5.8003785e+00 -1.0229074e+00 - 1.7079519e+01 -6.7576007e+00 -1.0396528e+00 - 2.0336185e+01 -8.0848756e+00 -1.0622676e+00 - 2.7415617e+01 -1.0970858e+01 -7.7727793e-01 - 2.7800370e+01 -1.1128203e+01 -2.8679309e-01 - 2.9039681e+01 -1.1632575e+01 1.9340759e-01 - 2.8872202e+01 -1.1564543e+01 7.3305399e-01 - 2.8964768e+01 -1.1602696e+01 1.2686236e+00 - 2.9187415e+01 -1.1693476e+01 1.8115931e+00 - 3.1741265e+01 -1.2734641e+01 2.4734597e+00 - 3.3487709e+01 -1.3446006e+01 3.1792100e+00 - 3.2644670e+01 -1.3102785e+01 3.7323802e+00 - 2.3442465e+01 -9.3513853e+00 3.3858653e+00 - 2.1799677e+01 -8.6817740e+00 3.6208934e+00 - 2.1845911e+01 -8.7010995e+00 4.0349712e+00 - 2.2186620e+01 -8.8399784e+00 4.5003869e+00 - 2.2392427e+01 -8.9230308e+00 4.9563722e+00 - 2.3271238e+01 -9.2822355e+00 5.5579932e+00 - 2.3203145e+01 -9.2547203e+00 5.9884884e+00 - 2.2460015e+01 -8.9507135e+00 6.2575242e+00 - 2.2568990e+01 -8.9954010e+00 6.7219268e+00 - 2.3486296e+01 -9.3691916e+00 7.4199480e+00 - 2.3887994e+01 -9.5329127e+00 8.0045585e+00 - 2.1747137e+01 -8.6606346e+00 7.7967263e+00 - 2.1439214e+01 -8.5351985e+00 8.1299558e+00 - 2.5035707e+01 -1.0001231e+01 9.8657510e+00 - 2.6791424e+01 -1.0717238e+01 1.1054468e+01 - 2.6417309e+01 -1.0563929e+01 1.1464428e+01 - 2.7237110e+01 -1.0898415e+01 1.4772232e+01 - 5.8767822e+00 -2.1917062e+00 4.5582699e+00 - 5.6695166e+00 -2.1070313e+00 4.5569744e+00 - 5.5572635e+00 -2.0612479e+00 4.6151826e+00 - 5.4146338e+00 -2.0028736e+00 4.6476261e+00 - 5.2798180e+00 -1.9478998e+00 4.6816908e+00 - 5.3155115e+00 -1.9628288e+00 4.8485120e+00 - 5.5325874e+00 -2.0512392e+00 5.1700260e+00 - 5.4566034e+00 -2.0202112e+00 5.2579743e+00 - 5.6090570e+00 -2.0822126e+00 5.5479467e+00 - 5.1683049e+00 -1.9031218e+00 5.3058421e+00 - 5.1256323e+00 -1.8858582e+00 5.4196951e+00 - 5.1085321e+00 -1.8778431e+00 5.5601789e+00 - 4.7519899e+00 -1.7329845e+00 5.3572900e+00 - 4.5091919e+00 -1.6341562e+00 5.2544911e+00 - 4.3546373e+00 -1.5715381e+00 5.2367371e+00 - 4.0313337e+00 -1.4394779e+00 5.0185549e+00 - 3.9346297e+00 -1.4000931e+00 5.0476466e+00 - 3.9115738e+00 -1.3899019e+00 5.1641304e+00 - 4.0661220e+00 -1.4533023e+00 5.5092267e+00 - 4.2285989e+00 -1.5197010e+00 5.8843590e+00 - 3.9414785e+00 -1.4025668e+00 5.6721966e+00 - 3.8428588e+00 -1.3619015e+00 5.7045411e+00 - 3.8817016e+00 -1.3778367e+00 5.9356717e+00 - 3.6239008e+00 -1.2731869e+00 5.7299516e+00 - 3.4947748e+00 -1.2204512e+00 5.7057197e+00 - 3.4540401e+00 -1.2042906e+00 5.8199155e+00 - 3.1371526e+00 -1.0751542e+00 5.4699753e+00 - 3.3982220e+00 -1.1816206e+00 6.1072972e+00 - 3.3388997e+00 -1.1571685e+00 6.2042778e+00 - 3.0258038e+00 -1.0298800e+00 5.8217652e+00 - 3.1071134e+00 -1.0628768e+00 6.1850376e+00 - 3.0143504e+00 -1.0246618e+00 6.2155644e+00 - 2.9048102e+00 -9.8027807e-01 6.2085444e+00 - 2.7844696e+00 -9.3070108e-01 6.1717985e+00 - 2.7389220e+00 -9.1230030e-01 6.3050371e+00 - 2.6490430e+00 -8.7618170e-01 6.3372515e+00 - 2.6262373e+00 -8.6657081e-01 6.5432727e+00 - 2.2514536e+00 -7.1331856e-01 5.8009174e+00 - 2.1890873e+00 -6.8856508e-01 5.8800800e+00 - 2.0981522e+00 -6.5130180e-01 5.8734966e+00 - 1.8047715e+00 -5.3111673e-01 5.2105666e+00 - 1.7304527e+00 -5.0130800e-01 5.2154622e+00 - 1.6888059e+00 -4.8388310e-01 5.3338064e+00 - 1.7391618e+00 -5.0550557e-01 5.8277705e+00 - 1.5708813e+00 -4.3674710e-01 5.4728827e+00 - 1.4837401e+00 -4.0079789e-01 5.4242889e+00 - 1.6397794e+00 -4.6435898e-01 6.5550531e+00 - 1.5468954e+00 -4.2659545e-01 6.5561666e+00 - 1.3076754e+00 -3.2883031e-01 5.7097809e+00 - 1.2823387e+00 -3.1842784e-01 6.0497439e+00 - 1.1432322e+00 -2.6176914e-01 5.6483150e+00 - 1.2405273e+00 -3.0193201e-01 7.0775567e+00 - 1.0108341e+00 -2.0870747e-01 5.8486642e+00 - 1.0228099e+00 -2.1318913e-01 6.8628620e+00 - 9.3315877e-01 -1.7628083e-01 6.9516058e+00 - 9.8942823e-01 -1.9934148e-01 9.6438156e+00 - 6.8550167e-01 -7.5754232e-02 5.6056199e+00 - 6.1235531e-01 -4.5644875e-02 5.6583525e+00 - 5.4947811e-01 -2.0375218e-02 7.1398224e+00 - 2.3945936e+00 -8.3732597e-01 -1.0005445e+00 - 2.4599733e+00 -8.6623594e-01 -9.9822042e-01 - 2.5253647e+00 -8.9505229e-01 -9.9399866e-01 - 2.5917666e+00 -9.2383056e-01 -9.8778255e-01 - 2.6717118e+00 -9.5999358e-01 -9.9259972e-01 - 2.7459042e+00 -9.9235963e-01 -9.8855756e-01 - 2.8346436e+00 -1.0321265e+00 -9.9465297e-01 - 2.9098029e+00 -1.0653184e+00 -9.8587023e-01 - 3.0005714e+00 -1.1049451e+00 -9.8667854e-01 - 3.0922957e+00 -1.1454863e+00 -9.8454405e-01 - 3.1840378e+00 -1.1858847e+00 -9.7951314e-01 - 3.2991089e+00 -1.2373863e+00 -9.8789558e-01 - 3.4084290e+00 -1.2850762e+00 -9.8711905e-01 - 3.5177105e+00 -1.3335906e+00 -9.8279729e-01 - 3.6445563e+00 -1.3895049e+00 -9.8492721e-01 - 3.7713678e+00 -1.4462092e+00 -9.8281275e-01 - 3.9079772e+00 -1.5065336e+00 -9.8108083e-01 - 4.0523907e+00 -1.5703373e+00 -9.7932557e-01 - 4.2153225e+00 -1.6424703e+00 -9.8137882e-01 - 4.3958415e+00 -1.7218208e+00 -9.8618831e-01 - 4.5685598e+00 -1.7981815e+00 -9.8068428e-01 - 4.7685863e+00 -1.8865098e+00 -9.8096614e-01 - 4.9861545e+00 -1.9829345e+00 -9.8155765e-01 - 5.2212694e+00 -2.0874160e+00 -9.8165979e-01 - 5.4759944e+00 -2.1990243e+00 -9.8022983e-01 - 5.7491573e+00 -2.3206354e+00 -9.7601729e-01 - 6.0672932e+00 -2.4602969e+00 -9.7759989e-01 - 6.3951018e+00 -2.6061258e+00 -9.7042746e-01 - 6.7776303e+00 -2.7745481e+00 -9.6788499e-01 - 7.1874199e+00 -2.9563457e+00 -9.5914398e-01 - 7.6704134e+00 -3.1698558e+00 -9.5459708e-01 - 8.2168492e+00 -3.4111680e+00 -9.4796901e-01 - 8.8374154e+00 -3.6858579e+00 -9.3754886e-01 - 9.6307049e+00 -4.0358359e+00 -9.4040073e-01 - 1.0498139e+01 -4.4195925e+00 -9.2732589e-01 - 1.1791844e+01 -4.9916236e+00 -9.5525390e-01 - 1.3324674e+01 -5.6687444e+00 -9.7046301e-01 - 1.5714951e+01 -6.7254578e+00 -1.0422267e+00 - 1.7800232e+01 -7.6471461e+00 -9.8790689e-01 - 2.0663123e+01 -8.9134534e+00 -9.2839635e-01 - 2.7690415e+01 -1.2019716e+01 -5.5762678e-01 - 2.7939842e+01 -1.2129781e+01 -4.7212427e-02 - 2.8501504e+01 -1.2377930e+01 4.6598343e-01 - 2.8477760e+01 -1.2367990e+01 1.0003992e+00 - 2.8437464e+01 -1.2350088e+01 1.5336234e+00 - 2.8817793e+01 -1.2517348e+01 2.0815949e+00 - 4.0943872e+01 -1.7878629e+01 3.3179955e+00 - 4.1849041e+01 -1.8278537e+01 4.1619583e+00 - 2.2403637e+01 -9.6822229e+00 3.0955113e+00 - 2.7733288e+01 -1.2038089e+01 4.1298957e+00 - 2.2540969e+01 -9.7428812e+00 3.9592183e+00 - 2.2753125e+01 -9.8371262e+00 4.4197215e+00 - 2.3200592e+01 -1.0035319e+01 4.9314584e+00 - 2.2288168e+01 -9.6317979e+00 5.2008356e+00 - 2.2684956e+01 -9.8067409e+00 5.7151426e+00 - 2.9753643e+01 -1.2931671e+01 7.7989895e+00 - 2.9650018e+01 -1.2885569e+01 8.3584471e+00 - 2.7744625e+01 -1.2043854e+01 8.4273102e+00 - 2.7638906e+01 -1.1997386e+01 8.9512189e+00 - 2.7474204e+01 -1.1924399e+01 1.0582851e+01 - 6.2510690e+00 -2.5419013e+00 4.4858261e+00 - 6.1869822e+00 -2.5137915e+00 4.5900649e+00 - 6.0583858e+00 -2.4568237e+00 4.6516270e+00 - 5.9287684e+00 -2.3999778e+00 4.7094969e+00 - 5.5850303e+00 -2.2476954e+00 4.6109920e+00 - 5.6098709e+00 -2.2593972e+00 4.7690103e+00 - 5.7893673e+00 -2.3375510e+00 5.0493999e+00 - 5.7457825e+00 -2.3190231e+00 5.1674014e+00 - 5.5692231e+00 -2.2406944e+00 5.1766423e+00 - 5.4083131e+00 -2.1689945e+00 5.1926215e+00 - 5.3970385e+00 -2.1641951e+00 5.3360315e+00 - 5.3975235e+00 -2.1644456e+00 5.4930345e+00 - 5.1239666e+00 -2.0444353e+00 5.3955883e+00 - 5.0471827e+00 -2.0096990e+00 5.4764500e+00 - 4.9879379e+00 -1.9841120e+00 5.5761777e+00 - 4.5851133e+00 -1.8063098e+00 5.3138778e+00 - 4.3085461e+00 -1.6836657e+00 5.1648568e+00 - 4.1719040e+00 -1.6236025e+00 5.1578314e+00 - 3.9363612e+00 -1.5194454e+00 5.0297941e+00 - 4.3060462e+00 -1.6828417e+00 5.6223959e+00 - 4.2135202e+00 -1.6417016e+00 5.6717003e+00 - 4.0269405e+00 -1.5589511e+00 5.5962807e+00 - 4.0108017e+00 -1.5518062e+00 5.7406062e+00 - 3.8388794e+00 -1.4755745e+00 5.6729270e+00 - 3.7580642e+00 -1.4398736e+00 5.7279342e+00 - 3.5694052e+00 -1.3566341e+00 5.6194625e+00 - 3.3532456e+00 -1.2614167e+00 5.4562027e+00 - 3.2566801e+00 -1.2188619e+00 5.4685167e+00 - 3.2297596e+00 -1.2068901e+00 5.5959500e+00 - 3.3107586e+00 -1.2428841e+00 5.9187221e+00 - 3.2083712e+00 -1.1970841e+00 5.9287092e+00 - 3.0058229e+00 -1.1076764e+00 5.7458275e+00 - 2.9210398e+00 -1.0699893e+00 5.7754300e+00 - 2.8480237e+00 -1.0378072e+00 5.8296615e+00 - 2.9164331e+00 -1.0683790e+00 6.1856851e+00 - 2.8935887e+00 -1.0580453e+00 6.3658390e+00 - 2.7145149e+00 -9.7857809e-01 6.1931149e+00 - 3.0180905e+00 -1.1131363e+00 7.1846956e+00 - 2.6335018e+00 -9.4261117e-01 6.4954152e+00 - 2.2742398e+00 -7.8381448e-01 5.8027523e+00 - 2.2366305e+00 -7.6730493e-01 5.9479499e+00 - 2.1231872e+00 -7.1783719e-01 5.8770247e+00 - 1.8274954e+00 -5.8633677e-01 5.2169549e+00 - 1.7543008e+00 -5.5455023e-01 5.2226471e+00 - 1.7137167e+00 -5.3615434e-01 5.3416378e+00 - 1.8863969e+00 -6.1294826e-01 6.2869225e+00 - 1.6118856e+00 -4.9106658e-01 5.5397886e+00 - 1.5199443e+00 -4.5071224e-01 5.4730851e+00 - 1.6151596e+00 -4.9253872e-01 6.2810553e+00 - 1.5927775e+00 -4.8315197e-01 6.6243542e+00 - 1.3422000e+00 -3.7248262e-01 5.7412575e+00 - 1.2572064e+00 -3.3441407e-01 5.6975521e+00 - 1.3366499e+00 -3.6977305e-01 6.7779369e+00 - 1.2719964e+00 -3.4124872e-01 7.0109175e+00 - 1.0851192e+00 -2.5838343e-01 6.2109004e+00 - 9.7093924e-01 -2.0861381e-01 5.9029725e+00 - 9.6805874e-01 -2.0713464e-01 6.8575948e+00 - 9.1336359e-01 -1.8271066e-01 7.4641769e+00 - 9.2474901e-01 -1.8731170e-01 9.8677980e+00 - 6.4819038e-01 -6.5416033e-02 5.6471919e+00 - 6.3937898e-01 -6.1132709e-02 9.7186569e+00 - 2.4041952e+00 -9.1024861e-01 -1.0030141e+00 - 2.4616978e+00 -9.3729373e-01 -9.9292369e-01 - 2.5337383e+00 -9.7181362e-01 -9.9446904e-01 - 2.6057930e+00 -1.0062202e+00 -9.9371723e-01 - 2.6720321e+00 -1.0378464e+00 -9.8445605e-01 - 2.7518778e+00 -1.0758359e+00 -9.8577831e-01 - 2.8336758e+00 -1.1148150e+00 -9.8446059e-01 - 2.9222580e+00 -1.1573856e+00 -9.8661204e-01 - 3.0196239e+00 -1.2036438e+00 -9.9173963e-01 - 3.1101780e+00 -1.2470465e+00 -9.8805504e-01 - 3.2085201e+00 -1.2940566e+00 -9.8694391e-01 - 3.3156509e+00 -1.3447150e+00 -9.8800991e-01 - 3.4305150e+00 -1.3999334e+00 -9.9070093e-01 - 3.5395667e+00 -1.4523470e+00 -9.8438319e-01 - 3.6641870e+00 -1.5120346e+00 -9.8441089e-01 - 3.8063189e+00 -1.5800600e+00 -9.8964219e-01 - 3.9329296e+00 -1.6404319e+00 -9.8083756e-01 - 4.0926088e+00 -1.7165093e+00 -9.8547962e-01 - 4.2620356e+00 -1.7971248e+00 -9.8885663e-01 - 4.4324367e+00 -1.8785070e+00 -9.8629455e-01 - 4.6125902e+00 -1.9643879e+00 -9.8166841e-01 - 4.8092204e+00 -2.0593559e+00 -9.7839783e-01 - 5.0331705e+00 -2.1661979e+00 -9.7901549e-01 - 5.2833909e+00 -2.2857814e+00 -9.8207036e-01 - 5.5346053e+00 -2.4059739e+00 -9.7599010e-01 - 5.8306051e+00 -2.5472619e+00 -9.7665495e-01 - 6.1363926e+00 -2.6927677e+00 -9.6956278e-01 - 6.4946554e+00 -2.8647930e+00 -9.6809452e-01 - 6.8900177e+00 -3.0529741e+00 -9.6405586e-01 - 7.3223113e+00 -3.2602036e+00 -9.5530062e-01 - 7.8257614e+00 -3.4999478e+00 -9.4918542e-01 - 8.3924229e+00 -3.7714030e+00 -9.3919283e-01 - 9.0759338e+00 -4.0982862e+00 -9.3369540e-01 - 9.9211054e+00 -4.5014860e+00 -9.3524343e-01 - 1.0867512e+01 -4.9542326e+00 -9.2265713e-01 - 1.2314291e+01 -5.6451506e+00 -9.5677928e-01 - 1.4150474e+01 -6.5231217e+00 -9.9158745e-01 - 1.6519312e+01 -7.6547568e+00 -1.0226776e+00 - 1.9297214e+01 -8.9822440e+00 -1.0057815e+00 - 2.2438524e+01 -1.0483398e+01 -9.1327654e-01 - 2.8517099e+01 -1.3388572e+01 -8.9880445e-01 - 3.0092954e+01 -1.4141609e+01 -4.3154357e-01 - 2.8947888e+01 -1.3593943e+01 1.7478188e-01 - 2.8613711e+01 -1.3433898e+01 7.2844007e-01 - 2.8784771e+01 -1.3516417e+01 1.2740238e+00 - 2.9155573e+01 -1.3692635e+01 1.8320078e+00 - 4.2037873e+01 -1.9849811e+01 4.6237761e+00 - 2.7047894e+01 -1.2686476e+01 3.8335000e+00 - 2.7725485e+01 -1.3010297e+01 4.4383223e+00 - 2.7657974e+01 -1.2978131e+01 4.9631010e+00 - 4.7262561e+01 -2.2346088e+01 1.1545086e+01 - 4.8542949e+01 -2.2957622e+01 1.2805075e+01 - 4.8998260e+01 -2.3175822e+01 1.4901604e+01 - 6.0270806e+00 -2.6406292e+00 4.6086226e+00 - 5.9621578e+00 -2.6096158e+00 4.7097196e+00 - 6.0396578e+00 -2.6473971e+00 4.9115521e+00 - 5.6985870e+00 -2.4842002e+00 4.8138942e+00 - 5.6746666e+00 -2.4723653e+00 4.9422168e+00 - 5.7297555e+00 -2.4992301e+00 5.1346381e+00 - 5.5984980e+00 -2.4358068e+00 5.1815805e+00 - 5.4242218e+00 -2.3527277e+00 5.1882701e+00 - 4.8564461e+00 -2.0819243e+00 4.8409004e+00 - 4.8578908e+00 -2.0820266e+00 4.9818704e+00 - 5.1239096e+00 -2.2098410e+00 5.3773152e+00 - 5.0277132e+00 -2.1638210e+00 5.4396178e+00 - 4.8631480e+00 -2.0850565e+00 5.4318423e+00 - 4.7474284e+00 -2.0291536e+00 5.4674454e+00 - 4.3932492e+00 -1.8605549e+00 5.2405428e+00 - 4.2686327e+00 -1.8013518e+00 5.2510072e+00 - 4.1449929e+00 -1.7423817e+00 5.2579728e+00 - 4.0780626e+00 -1.7097888e+00 5.3278658e+00 - 4.0091274e+00 -1.6771440e+00 5.3963670e+00 - 4.0154762e+00 -1.6803046e+00 5.5624885e+00 - 4.0580713e+00 -1.6999504e+00 5.7840671e+00 - 3.9255840e+00 -1.6372859e+00 5.7738840e+00 - 3.6855632e+00 -1.5220240e+00 5.6014725e+00 - 3.5960757e+00 -1.4796823e+00 5.6382836e+00 - 3.5017157e+00 -1.4345450e+00 5.6648743e+00 - 3.3056004e+00 -1.3404054e+00 5.5244722e+00 - 3.1690870e+00 -1.2757037e+00 5.4696586e+00 - 3.3791329e+00 -1.3758954e+00 6.0097659e+00 - 3.1633986e+00 -1.2721224e+00 5.8173460e+00 - 3.1101070e+00 -1.2471839e+00 5.9112618e+00 - 2.9921764e+00 -1.1913273e+00 5.8827017e+00 - 2.9497097e+00 -1.1708708e+00 6.0005010e+00 - 2.9700040e+00 -1.1802654e+00 6.2599587e+00 - 2.8834582e+00 -1.1390429e+00 6.2980083e+00 - 2.7253308e+00 -1.0635439e+00 6.1718079e+00 - 2.6927465e+00 -1.0475798e+00 6.3323203e+00 - 3.6366746e+00 -1.4987761e+00 8.9967162e+00 - 2.2621661e+00 -8.4251864e-01 5.9591118e+00 - 2.2031005e+00 -8.1343645e-01 6.0486536e+00 - 1.8431138e+00 -6.4207958e-01 5.2041891e+00 - 1.7740349e+00 -6.0903536e-01 5.2200065e+00 - 1.9894370e+00 -7.1198277e-01 6.2359035e+00 - 1.8703316e+00 -6.5489918e-01 6.1296944e+00 - 1.6712993e+00 -5.5974346e-01 5.6832829e+00 - 1.5500356e+00 -5.0125417e-01 5.5018251e+00 - 1.5362604e+00 -4.9542170e-01 5.7840707e+00 - 1.5662206e+00 -5.0919051e-01 6.3305384e+00 - 1.4300773e+00 -4.4389440e-01 6.0661347e+00 - 1.2858047e+00 -3.7513969e-01 5.6999852e+00 - 1.2336922e+00 -3.5087948e-01 5.8624116e+00 - 1.2903618e+00 -3.7770476e-01 6.8648202e+00 - 1.2178983e+00 -3.4316978e-01 7.0477912e+00 - 1.0040925e+00 -2.4044605e-01 5.9082429e+00 - 1.0038987e+00 -2.4109254e-01 6.8031797e+00 - 9.2971981e-01 -2.0522327e-01 7.0512759e+00 - 9.7875448e-01 -2.2880812e-01 9.6837825e+00 - 6.7978083e-01 -8.5927226e-02 5.5756194e+00 - 6.0993560e-01 -5.2517438e-02 5.6584061e+00 - 5.4848670e-01 -2.3355237e-02 7.1997493e+00 - 2.3360729e+00 -9.4378354e-01 -9.9363032e-01 - 2.4050396e+00 -9.7927175e-01 -9.9821276e-01 - 2.4691907e+00 -1.0120253e+00 -9.9398938e-01 - 2.5401187e+00 -1.0484294e+00 -9.9443368e-01 - 2.6052324e+00 -1.0820433e+00 -9.8616886e-01 - 2.6838920e+00 -1.1230223e+00 -9.8853782e-01 - 2.7703924e+00 -1.1666709e+00 -9.9472830e-01 - 2.8364841e+00 -1.2010220e+00 -9.7992513e-01 - 2.9171254e+00 -1.2427542e+00 -9.7486002e-01 - 3.0200894e+00 -1.2955933e+00 -9.8450347e-01 - 3.1094721e+00 -1.3418673e+00 -9.7946853e-01 - 3.2221837e+00 -1.3992445e+00 -9.8784694e-01 - 3.3203139e+00 -1.4500109e+00 -9.8184340e-01 - 3.4349464e+00 -1.5091433e+00 -9.8283808e-01 - 3.5496030e+00 -1.5680835e+00 -9.7993756e-01 - 3.6807692e+00 -1.6353306e+00 -9.8283672e-01 - 3.8051267e+00 -1.6996976e+00 -9.7642432e-01 - 3.9547738e+00 -1.7760886e+00 -9.7938700e-01 - 4.1043935e+00 -1.8532154e+00 -9.7700668e-01 - 4.2802525e+00 -1.9433301e+00 -9.8205741e-01 - 4.4483716e+00 -2.0294530e+00 -9.7674431e-01 - 4.6504001e+00 -2.1341455e+00 -9.8093712e-01 - 4.8369725e+00 -2.2301482e+00 -9.7034452e-01 - 5.0740280e+00 -2.3520007e+00 -9.7450781e-01 - 5.3217937e+00 -2.4792517e+00 -9.7336462e-01 - 5.5957805e+00 -2.6201526e+00 -9.7281133e-01 - 5.8872747e+00 -2.7699397e+00 -9.6832332e-01 - 6.1982192e+00 -2.9296770e+00 -9.5875874e-01 - 6.5693693e+00 -3.1205183e+00 -9.5694249e-01 - 6.9852324e+00 -3.3340647e+00 -9.5398188e-01 - 7.4293083e+00 -3.5619353e+00 -9.4257908e-01 - 7.9520375e+00 -3.8308342e+00 -9.3454400e-01 - 8.5641136e+00 -4.1462927e+00 -9.2726683e-01 - 9.2821510e+00 -4.5152662e+00 -9.1940567e-01 - 1.0169239e+01 -4.9709551e+00 -9.1702128e-01 - 1.1233114e+01 -5.5184140e+00 -9.1150169e-01 - 1.2926449e+01 -6.3886177e+00 -9.6363321e-01 - 1.4993829e+01 -7.4521994e+00 -1.0009253e+00 - 1.7030455e+01 -8.4986778e+00 -9.5346587e-01 - 2.0876766e+01 -1.0476845e+01 -1.0043831e+00 - 3.4504325e+01 -1.7483648e+01 -3.3496831e-01 - 3.1995018e+01 -1.6193080e+01 3.8210378e-01 - 3.0683301e+01 -1.5519409e+01 1.0002633e+00 - 3.5036191e+01 -1.7756762e+01 1.6780911e+00 - 1.9606462e+01 -9.8241497e+00 7.9807744e+00 - 5.6757460e+00 -2.6610524e+00 4.7798060e+00 - 5.4619751e+00 -2.5506578e+00 4.7633648e+00 - 5.4165764e+00 -2.5284892e+00 4.8716861e+00 - 5.8602643e+00 -2.7557637e+00 5.3789735e+00 - 5.1301804e+00 -2.3802084e+00 4.9238107e+00 - 5.2095062e+00 -2.4215368e+00 5.1372210e+00 - 4.9371629e+00 -2.2815135e+00 5.0402819e+00 - 5.1666527e+00 -2.3987131e+00 5.4030886e+00 - 5.0238480e+00 -2.3259644e+00 5.4218080e+00 - 4.8615950e+00 -2.2422178e+00 5.4161754e+00 - 4.7928825e+00 -2.2067613e+00 5.5011570e+00 - 4.4024812e+00 -2.0057119e+00 5.2373334e+00 - 4.3170973e+00 -1.9627251e+00 5.2921095e+00 - 4.2122695e+00 -1.9087059e+00 5.3232328e+00 - 4.1210654e+00 -1.8619450e+00 5.3661443e+00 - 4.0289097e+00 -1.8142352e+00 5.4068120e+00 - 3.9650128e+00 -1.7815133e+00 5.4829878e+00 - 3.9128183e+00 -1.7548136e+00 5.5733056e+00 - 3.8352613e+00 -1.7151240e+00 5.6318005e+00 - 3.7079829e+00 -1.6489562e+00 5.6177079e+00 - 3.7163056e+00 -1.6534484e+00 5.7998025e+00 - 3.5313729e+00 -1.5583528e+00 5.6922249e+00 - 4.5298173e+00 -2.0718910e+00 7.4712641e+00 - 3.4192005e+00 -1.5007925e+00 5.8663954e+00 - 3.3621350e+00 -1.4718017e+00 5.9565301e+00 - 3.2709115e+00 -1.4246794e+00 5.9865079e+00 - 3.0917381e+00 -1.3322984e+00 5.8514947e+00 - 2.9545500e+00 -1.2613409e+00 5.7804570e+00 - 2.8583549e+00 -1.2122163e+00 5.7841343e+00 - 2.8374450e+00 -1.2019820e+00 5.9444568e+00 - 2.7246471e+00 -1.1437472e+00 5.9094399e+00 - 2.6832757e+00 -1.1220586e+00 6.0331791e+00 - 2.6340442e+00 -1.0973389e+00 6.1478061e+00 - 2.5721487e+00 -1.0652126e+00 6.2346120e+00 - 2.5112418e+00 -1.0337397e+00 6.3296542e+00 - 2.4581247e+00 -1.0074069e+00 6.4518350e+00 - 1.9590398e+00 -7.4984177e-01 5.2757719e+00 - 1.8381456e+00 -6.8736817e-01 5.1345651e+00 - 1.7907721e+00 -6.6335885e-01 5.2169760e+00 - 1.7503157e+00 -6.4239580e-01 5.3272286e+00 - 1.9172068e+00 -7.2887638e-01 6.2118514e+00 - 1.8111250e+00 -6.7374661e-01 6.1427041e+00 - 1.5818783e+00 -5.5645343e-01 5.5398952e+00 - 1.5327249e+00 -5.3059393e-01 5.6573691e+00 - 1.5881453e+00 -5.5914997e-01 6.3005276e+00 - 1.5481003e+00 -5.3850958e-01 6.5460604e+00 - 1.4329768e+00 -4.7969007e-01 6.3988908e+00 - 1.2414466e+00 -3.8114385e-01 5.7270879e+00 - 1.3216480e+00 -4.2209351e-01 6.8371801e+00 - 1.2373240e+00 -3.7867453e-01 6.9019407e+00 - 1.0640320e+00 -2.9018014e-01 6.1711479e+00 - 9.7337333e-01 -2.4348716e-01 6.0720842e+00 - 9.5138617e-01 -2.3167541e-01 6.8077452e+00 - 8.9887006e-01 -2.0488082e-01 7.4243093e+00 - 9.0906949e-01 -2.0989087e-01 9.7778962e+00 - 6.4471391e-01 -7.4243517e-02 5.6671729e+00 - 6.3721550e-01 -7.0083611e-02 9.8386592e+00 - 2.2854293e+00 -9.8540320e-01 -1.0045811e+00 - 2.3416812e+00 -1.0164693e+00 -9.9618702e-01 - 2.4037690e+00 -1.0501531e+00 -9.9300637e-01 - 2.4735717e+00 -1.0885449e+00 -9.9444704e-01 - 2.5297954e+00 -1.1203517e+00 -9.8080981e-01 - 2.6073879e+00 -1.1623362e+00 -9.8452431e-01 - 2.6858730e+00 -1.2062567e+00 -9.8574585e-01 - 2.7644337e+00 -1.2490571e+00 -9.8452002e-01 - 2.8429495e+00 -1.2927313e+00 -9.8074773e-01 - 2.9301871e+00 -1.3411049e+00 -9.8020166e-01 - 3.0252114e+00 -1.3930959e+00 -9.8242880e-01 - 3.1134239e+00 -1.4422313e+00 -9.7584376e-01 - 3.2171951e+00 -1.4987196e+00 -9.7720218e-01 - 3.3286389e+00 -1.5607699e+00 -9.8023595e-01 - 3.4421031e+00 -1.6227489e+00 -9.7938089e-01 - 3.5555311e+00 -1.6855328e+00 -9.7458109e-01 - 3.6854091e+00 -1.7576155e+00 -9.7543154e-01 - 3.8163144e+00 -1.8295272e+00 -9.7159098e-01 - 3.9703950e+00 -1.9153162e+00 -9.7662053e-01 - 4.1187295e+00 -1.9972540e+00 -9.7169211e-01 - 4.3000251e+00 -2.0967878e+00 -9.7801388e-01 - 4.4580840e+00 -2.1839651e+00 -9.6577827e-01 - 4.6655515e+00 -2.2980569e+00 -9.7084260e-01 - 4.8662238e+00 -2.4091602e+00 -9.6439809e-01 - 5.1008228e+00 -2.5386950e+00 -9.6466294e-01 - 5.3529182e+00 -2.6772049e+00 -9.6279085e-01 - 5.6388413e+00 -2.8359679e+00 -9.6403334e-01 - 5.9355503e+00 -2.9990092e+00 -9.5752199e-01 - 6.2748297e+00 -3.1868355e+00 -9.5395563e-01 - 6.6587522e+00 -3.3984426e+00 -9.5079340e-01 - 7.0862754e+00 -3.6346388e+00 -9.4538576e-01 - 7.5487482e+00 -3.8896442e+00 -9.3285813e-01 - 8.1071600e+00 -4.1978851e+00 -9.2630659e-01 - 8.7189588e+00 -4.5349430e+00 -9.0995238e-01 - 9.4954806e+00 -4.9637303e+00 -9.0430766e-01 - 1.0464915e+01 -5.4987535e+00 -9.0462570e-01 - 1.1799745e+01 -6.2355811e+00 -9.2888365e-01 - 1.3415764e+01 -7.1272677e+00 -9.4213214e-01 - 1.5862446e+01 -8.4775367e+00 -9.9906262e-01 - 1.8086532e+01 -9.7049885e+00 -9.3412129e-01 - 3.9026832e+01 -2.1261437e+01 -1.5220376e-01 - 3.8898341e+01 -2.1190352e+01 6.1733543e-01 - 4.1288510e+01 -2.2509191e+01 1.4066487e+00 - 4.3818043e+01 -2.3905967e+01 4.0262999e+00 - 4.5589451e+01 -2.4883729e+01 5.0533172e+00 - 4.5526897e+01 -2.4849000e+01 1.5262384e+01 - 1.8969935e+01 -1.0193255e+01 7.6515775e+00 - 5.5505646e+00 -2.7870881e+00 4.6750580e+00 - 5.4421736e+00 -2.7273317e+00 4.7365581e+00 - 5.3337629e+00 -2.6677329e+00 4.7948621e+00 - 5.0397394e+00 -2.5052798e+00 4.6990530e+00 - 5.2851241e+00 -2.6403401e+00 5.0447205e+00 - 4.9589382e+00 -2.4609146e+00 4.9082234e+00 - 4.7824861e+00 -2.3628606e+00 4.8906587e+00 - 4.9248388e+00 -2.4420150e+00 5.1663208e+00 - 4.8475623e+00 -2.3985363e+00 5.2408471e+00 - 4.8606525e+00 -2.4061474e+00 5.4063455e+00 - 4.7920691e+00 -2.3686279e+00 5.4926263e+00 - 4.4881515e+00 -2.2002287e+00 5.3227939e+00 - 4.2337444e+00 -2.0599925e+00 5.1913913e+00 - 4.1018361e+00 -1.9880598e+00 5.1867549e+00 - 4.0731427e+00 -1.9716031e+00 5.3013624e+00 - 4.3685157e+00 -2.1341029e+00 5.8216890e+00 - 3.9689753e+00 -1.9143688e+00 5.4787035e+00 - 3.8769849e+00 -1.8637912e+00 5.5167258e+00 - 3.8463328e+00 -1.8469130e+00 5.6374321e+00 - 3.7699534e+00 -1.8043028e+00 5.6955754e+00 - 3.5805596e+00 -1.7000309e+00 5.5855702e+00 - 3.5674449e+00 -1.6928309e+00 5.7346802e+00 - 3.4287212e+00 -1.6154917e+00 5.6892692e+00 - 4.4319032e+00 -2.1701216e+00 7.5352863e+00 - 3.3118577e+00 -1.5521401e+00 5.8531707e+00 - 3.2237504e+00 -1.5031955e+00 5.8832396e+00 - 2.8694536e+00 -1.3073856e+00 5.4166013e+00 - 2.7793071e+00 -1.2576317e+00 5.4201102e+00 - 2.6511257e+00 -1.1865169e+00 5.3430017e+00 - 2.7599845e+00 -1.2468758e+00 5.7543116e+00 - 2.7274125e+00 -1.2292658e+00 5.8874090e+00 - 2.6714557e+00 -1.1984203e+00 5.9758434e+00 - 2.6252795e+00 -1.1728801e+00 6.0905112e+00 - 2.5615153e+00 -1.1380658e+00 6.1685854e+00 - 2.1645138e+00 -9.1884517e-01 5.3743530e+00 - 2.0948455e+00 -8.7937942e-01 5.3975668e+00 - 1.9468409e+00 -7.9820060e-01 5.1961314e+00 - 1.8614330e+00 -7.5076399e-01 5.1587748e+00 - 1.8033954e+00 -7.1892525e-01 5.2041199e+00 - 1.7522122e+00 -6.9114942e-01 5.2769569e+00 - 1.9716921e+00 -8.1149370e-01 6.3312331e+00 - 1.7402207e+00 -6.8425688e-01 5.7845172e+00 - 1.6067309e+00 -6.1022098e-01 5.5579132e+00 - 1.5585806e+00 -5.8438252e-01 5.6761829e+00 - 1.6138175e+00 -6.1492085e-01 6.2994156e+00 - 1.5137417e+00 -5.5950169e-01 6.2232083e+00 - 1.4648898e+00 -5.3278036e-01 6.4189344e+00 - 1.3529327e+00 -4.7070617e-01 6.2603708e+00 - 1.3468205e+00 -4.6660062e-01 6.7795466e+00 - 1.2675534e+00 -4.2347087e-01 6.8648156e+00 - 1.1983876e+00 -3.8463182e-01 7.0576664e+00 - 9.9429549e-01 -2.7249103e-01 5.9579434e+00 - 9.9016592e-01 -2.6986193e-01 6.8130940e+00 - 9.2328554e-01 -2.3347514e-01 7.1410181e+00 - 9.6095983e-01 -2.5427871e-01 9.6138608e+00 - 6.7518515e-01 -9.6693096e-02 5.5956027e+00 - 6.0657876e-01 -5.8841804e-02 5.6683506e+00 - 5.4762003e-01 -2.5854192e-02 7.2896887e+00 - 2.2833345e+00 -1.0532875e+00 -1.0006188e+00 - 2.3452963e+00 -1.0890095e+00 -9.9823797e-01 - 2.4062108e+00 -1.1255794e+00 -9.9400661e-01 - 2.4691334e+00 -1.1621766e+00 -9.8788394e-01 - 2.5310099e+00 -1.1996118e+00 -9.7971102e-01 - 2.6074291e+00 -1.2444823e+00 -9.8237479e-01 - 2.6848023e+00 -1.2902821e+00 -9.8239541e-01 - 2.7621910e+00 -1.3359588e+00 -9.7991911e-01 - 2.8473025e+00 -1.3862793e+00 -9.8076573e-01 - 2.9334294e+00 -1.4365223e+00 -9.7881899e-01 - 3.0195140e+00 -1.4876193e+00 -9.7392627e-01 - 3.1133265e+00 -1.5433209e+00 -9.7155746e-01 - 3.2235785e+00 -1.6084050e+00 -9.7653681e-01 - 3.3415657e+00 -1.6780345e+00 -9.8284155e-01 - 3.4450914e+00 -1.7390642e+00 -9.7496332e-01 - 3.5650044e+00 -1.8104094e+00 -9.7308531e-01 - 3.6927178e+00 -1.8852636e+00 -9.7178323e-01 - 3.8290534e+00 -1.9666436e+00 -9.7021246e-01 - 3.9741937e+00 -2.0515437e+00 -9.6822203e-01 - 4.1356784e+00 -2.1476183e+00 -9.6938572e-01 - 4.3146336e+00 -2.2528749e+00 -9.7260728e-01 - 4.5022866e+00 -2.3635372e+00 -9.7311280e-01 - 4.6909201e+00 -2.4749169e+00 -9.6668046e-01 - 4.9124188e+00 -2.6056894e+00 -9.6740413e-01 - 5.1522872e+00 -2.7475258e+00 -9.6659408e-01 - 5.4008732e+00 -2.8946102e+00 -9.5987193e-01 - 5.6910733e+00 -3.0655699e+00 -9.5913746e-01 - 6.0083297e+00 -3.2530878e+00 -9.5595098e-01 - 6.3517152e+00 -3.4560229e+00 -9.4866098e-01 - 6.7540838e+00 -3.6938564e+00 -9.4622125e-01 - 7.1912743e+00 -3.9525521e+00 -9.3776096e-01 - 7.6894837e+00 -4.2459518e+00 -9.2776520e-01 - 8.2562827e+00 -4.5814638e+00 -9.1481391e-01 - 8.9682081e+00 -5.0014701e+00 -9.1190693e-01 - 9.8019963e+00 -5.4938310e+00 -9.0488147e-01 - 1.0840837e+01 -6.1071219e+00 -9.0216764e-01 - 1.2240336e+01 -6.9346205e+00 -9.1634474e-01 - 1.4078994e+01 -8.0206432e+00 -9.3639983e-01 - 1.6683645e+01 -9.5591151e+00 -9.7551000e-01 - 1.9739234e+01 -1.1363589e+01 -9.5482136e-01 - 2.3664496e+01 -1.3682376e+01 -8.8119030e-01 - 4.3569645e+01 -2.5438732e+01 3.6215474e+00 - 4.2734749e+01 -2.4945424e+01 7.0227858e+00 - 5.0328913e+00 -2.6767324e+00 4.5508594e+00 - 4.9576689e+00 -2.6323974e+00 4.6249303e+00 - 4.9580902e+00 -2.6326413e+00 4.7618085e+00 - 4.9488013e+00 -2.6275323e+00 4.8936768e+00 - 4.8017964e+00 -2.5409429e+00 4.9032288e+00 - 4.7557066e+00 -2.5131656e+00 5.0024669e+00 - 4.6552724e+00 -2.4536053e+00 5.0495097e+00 - 4.7429860e+00 -2.5064262e+00 5.2840606e+00 - 4.5950343e+00 -2.4183342e+00 5.2823306e+00 - 4.5741201e+00 -2.4065871e+00 5.4125413e+00 - 4.1912284e+00 -2.1803393e+00 5.1401193e+00 - 4.1159800e+00 -2.1356970e+00 5.2001579e+00 - 4.0047927e+00 -2.0700499e+00 5.2153279e+00 - 4.3809904e+00 -2.2927152e+00 5.8342420e+00 - 4.3135809e+00 -2.2523047e+00 5.9195719e+00 - 4.0071873e+00 -2.0718441e+00 5.6866829e+00 - 4.0145450e+00 -2.0754956e+00 5.8643365e+00 - 3.8217621e+00 -1.9615167e+00 5.7638857e+00 - 3.5852178e+00 -1.8216539e+00 5.5861342e+00 - 3.4943569e+00 -1.7685400e+00 5.6160144e+00 - 3.4200567e+00 -1.7243573e+00 5.6679598e+00 - 3.1911568e+00 -1.5892499e+00 5.4643636e+00 - 3.1381949e+00 -1.5580668e+00 5.5430508e+00 - 3.0794300e+00 -1.5229715e+00 5.6126699e+00 - 3.0361731e+00 -1.4982137e+00 5.7151433e+00 - 2.7789436e+00 -1.3455903e+00 5.4057282e+00 - 2.6393589e+00 -1.2629691e+00 5.3040929e+00 - 2.5873354e+00 -1.2323242e+00 5.3730889e+00 - 2.7719421e+00 -1.3415855e+00 5.9621603e+00 - 2.6615645e+00 -1.2764732e+00 5.9271898e+00 - 2.6398305e+00 -1.2637559e+00 6.0961056e+00 - 2.5518747e+00 -1.2115378e+00 6.1114942e+00 - 2.2542658e+00 -1.0355742e+00 5.5768003e+00 - 2.0744786e+00 -9.2974615e-01 5.3079633e+00 - 1.9414392e+00 -8.5159468e-01 5.1445316e+00 - 1.8513523e+00 -7.9775409e-01 5.0890660e+00 - 1.8364139e+00 -7.8905368e-01 5.2661479e+00 - 1.7579745e+00 -7.4322122e-01 5.2453478e+00 - 1.6727231e+00 -6.9247176e-01 5.1941099e+00 - 1.7205317e+00 -7.2043929e-01 5.6380406e+00 - 1.6411335e+00 -6.7423107e-01 5.6236358e+00 - 1.5872438e+00 -6.4242578e-01 5.7137121e+00 - 1.5246089e+00 -6.0456100e-01 5.7738069e+00 - 1.5454050e+00 -6.1768197e-01 6.2616268e+00 - 1.5006104e+00 -5.9068512e-01 6.4678273e+00 - 1.4086258e+00 -5.3593536e-01 6.4283483e+00 - 1.3609500e+00 -5.0888385e-01 6.6725106e+00 - 1.2877965e+00 -4.6512159e-01 6.7779356e+00 - 1.2256228e+00 -4.2821361e-01 7.0009757e+00 - 1.0340764e+00 -3.1535537e-01 6.0520259e+00 - 9.7874517e-01 -2.8208979e-01 6.2908227e+00 - 9.3877406e-01 -2.5901070e-01 6.8276943e+00 - 1.0321569e+00 -3.1462047e-01 9.8384718e+00 - 9.0494779e-01 -2.3883089e-01 9.9776938e+00 - 7.6729079e-01 -1.5791063e-01 9.8845409e+00 - 6.3524147e-01 -7.9583475e-02 1.0028574e+01 - 2.2182889e+00 -1.0853153e+00 -9.9753608e-01 - 2.2781272e+00 -1.1229646e+00 -9.9614841e-01 - 2.3389747e+00 -1.1605856e+00 -9.9296614e-01 - 2.4055401e+00 -1.2027986e+00 -9.9449870e-01 - 2.4672900e+00 -1.2422769e+00 -9.8722544e-01 - 2.5415857e+00 -1.2890746e+00 -9.9088240e-01 - 2.6111261e+00 -1.3321408e+00 -9.8578309e-01 - 2.6863291e+00 -1.3807563e+00 -9.8455006e-01 - 2.7568358e+00 -1.4246532e+00 -9.7481006e-01 - 2.8397778e+00 -1.4777846e+00 -9.7430315e-01 - 2.9314432e+00 -1.5356005e+00 -9.7672284e-01 - 3.0241265e+00 -1.5933193e+00 -9.7594965e-01 - 3.1244799e+00 -1.6566197e+00 -9.7725132e-01 - 3.2325660e+00 -1.7244851e+00 -9.8027788e-01 - 3.3338415e+00 -1.7894852e+00 -9.7429251e-01 - 3.4506255e+00 -1.8627563e+00 -9.7460302e-01 - 3.5683733e+00 -1.9368779e+00 -9.7067235e-01 - 3.7025152e+00 -2.0212608e+00 -9.7164324e-01 - 3.8366272e+00 -2.1063993e+00 -9.6767063e-01 - 3.9948574e+00 -2.2064331e+00 -9.7172276e-01 - 4.1540626e+00 -2.3072288e+00 -9.6973591e-01 - 4.3229588e+00 -2.4135300e+00 -9.6583522e-01 - 4.5149937e+00 -2.5345182e+00 -9.6695978e-01 - 4.7166698e+00 -2.6619252e+00 -9.6442303e-01 - 4.9424361e+00 -2.8049683e+00 -9.6466789e-01 - 5.1789138e+00 -2.9534000e+00 -9.5940651e-01 - 5.4471591e+00 -3.1229904e+00 -9.5780306e-01 - 5.7414578e+00 -3.3091180e+00 -9.5454346e-01 - 6.0936590e+00 -3.5312580e+00 -9.5967696e-01 - 6.4478218e+00 -3.7548280e+00 -9.5083486e-01 - 6.8607951e+00 -4.0162233e+00 -9.4539599e-01 - 7.3075989e+00 -4.2983660e+00 -9.3283473e-01 - 7.8383765e+00 -4.6329155e+00 -9.2411400e-01 - 8.4376379e+00 -5.0114528e+00 -9.0994159e-01 - 9.1960889e+00 -5.4903948e+00 -9.0611673e-01 - 1.0048173e+01 -6.0285335e+00 -8.8973718e-01 - 1.1270723e+01 -6.8001994e+00 -9.0377391e-01 - 1.2939942e+01 -7.8545729e+00 -9.3695983e-01 - 1.5160149e+01 -9.2564413e+00 -9.7532898e-01 - 1.7695092e+01 -1.0857112e+01 -9.5807549e-01 - 3.4047879e+01 -2.1181753e+01 -3.8893346e-02 - 3.5149011e+01 -2.1877421e+01 6.4243194e-01 - 4.2940060e+01 -2.6796263e+01 3.1914804e+00 - 5.0567472e+00 -2.8772421e+00 4.8442528e+00 - 4.8231000e+00 -2.7287549e+00 4.7830022e+00 - 4.6793317e+00 -2.6383491e+00 4.7925463e+00 - 4.6352314e+00 -2.6107470e+00 4.8906793e+00 - 4.5776186e+00 -2.5739664e+00 4.9754270e+00 - 4.4599292e+00 -2.5004099e+00 5.0005596e+00 - 4.6094480e+00 -2.5948464e+00 5.3003602e+00 - 4.4337206e+00 -2.4837809e+00 5.2629255e+00 - 4.4370747e+00 -2.4862461e+00 5.4192191e+00 - 4.3959728e+00 -2.4593099e+00 5.5277793e+00 - 4.3635173e+00 -2.4392214e+00 5.6503409e+00 - 4.4579671e+00 -2.4991126e+00 5.9324572e+00 - 4.4246360e+00 -2.4774691e+00 6.0650599e+00 - 4.3040435e+00 -2.4019690e+00 6.0854088e+00 - 3.8443488e+00 -2.1109240e+00 5.6308433e+00 - 4.1675700e+00 -2.3157173e+00 6.2624192e+00 - 4.1109668e+00 -2.2799367e+00 6.3686363e+00 - 3.5162749e+00 -1.9046387e+00 5.6490252e+00 - 3.4470247e+00 -1.8602853e+00 5.7105429e+00 - 4.0789202e+00 -2.2598905e+00 6.9348446e+00 - 3.1289722e+00 -1.6597455e+00 5.5243941e+00 - 3.0247186e+00 -1.5939169e+00 5.5112775e+00 - 2.7710001e+00 -1.4337374e+00 5.2168870e+00 - 2.5589435e+00 -1.2996295e+00 4.9732868e+00 - 2.5468107e+00 -1.2921039e+00 5.1099594e+00 - 2.4444146e+00 -1.2269906e+00 5.0645267e+00 - 2.5488466e+00 -1.2936708e+00 5.4643612e+00 - 2.6825951e+00 -1.3775020e+00 5.9583760e+00 - 2.6462768e+00 -1.3556180e+00 6.0921868e+00 - 2.2648907e+00 -1.1143307e+00 5.3774690e+00 - 2.1614407e+00 -1.0490862e+00 5.3132132e+00 - 2.0132000e+00 -9.5556817e-01 5.1175784e+00 - 1.9496300e+00 -9.1455989e-01 5.1388763e+00 - 1.8665307e+00 -8.6217072e-01 5.1030633e+00 - 1.8496615e+00 -8.5179398e-01 5.2711634e+00 - 1.7694757e+00 -8.0126477e-01 5.2418322e+00 - 1.7263354e+00 -7.7402849e-01 5.3337697e+00 - 1.6490624e+00 -7.2536415e-01 5.3108202e+00 - 1.6928829e+00 -7.5356954e-01 5.7653002e+00 - 1.5433411e+00 -6.5880128e-01 5.4519668e+00 - 1.5472864e+00 -6.6118374e-01 5.7922795e+00 - 1.5474283e+00 -6.6181189e-01 6.1632672e+00 - 1.5154284e+00 -6.4117721e-01 6.4184626e+00 - 1.4354267e+00 -5.9020810e-01 6.4385695e+00 - 1.4056013e+00 -5.7136516e-01 6.7814480e+00 - 1.3059212e+00 -5.0917424e-01 6.7006990e+00 - 1.2516768e+00 -4.7525966e-01 6.9538748e+00 - 1.1738858e+00 -4.2527748e-01 7.0577200e+00 - 9.8649742e-01 -3.0669867e-01 6.0472869e+00 - 9.7337844e-01 -2.9944693e-01 6.8230674e+00 - 1.1242816e+00 -3.9403744e-01 1.0390898e+01 - 9.4529075e-01 -2.8141611e-01 9.6138944e+00 - 8.3580845e-01 -2.1245882e-01 1.0101373e+01 - 6.9612929e-01 -1.2388792e-01 9.8569694e+00 - 5.4481341e-01 -2.8598218e-02 7.0897946e+00 - 2.1602500e+00 -1.1170945e+00 -1.0011170e+00 - 2.2190244e+00 -1.1557246e+00 -1.0005755e+00 - 2.2652204e+00 -1.1878106e+00 -9.8455975e-01 - 2.3306592e+00 -1.2320211e+00 -9.8728843e-01 - 2.3971097e+00 -1.2761836e+00 -9.8782301e-01 - 2.4635130e+00 -1.3212397e+00 -9.8621062e-01 - 2.5376348e+00 -1.3709740e+00 -9.8862029e-01 - 2.6050646e+00 -1.4158639e+00 -9.8241676e-01 - 2.6791558e+00 -1.4663588e+00 -9.7998280e-01 - 2.7552594e+00 -1.5168464e+00 -9.7495841e-01 - 2.8447380e+00 -1.5776111e+00 -9.7882112e-01 - 2.9275258e+00 -1.6335215e+00 -9.7387086e-01 - 3.0257500e+00 -1.6987935e+00 -9.7706460e-01 - 3.1171637e+00 -1.7612000e+00 -9.7124641e-01 - 3.2307336e+00 -1.8375911e+00 -9.7769097e-01 - 3.3309004e+00 -1.9044457e+00 -9.7000529e-01 - 3.4454582e+00 -1.9814951e+00 -9.6831347e-01 - 3.5763482e+00 -2.0698175e+00 -9.7177329e-01 - 3.7005516e+00 -2.1532511e+00 -9.6572102e-01 - 3.8478113e+00 -2.2525461e+00 -9.6824002e-01 - 4.0037608e+00 -2.3573108e+00 -9.6934137e-01 - 4.1606846e+00 -2.4628422e+00 -9.6450363e-01 - 4.3406824e+00 -2.5840922e+00 -9.6534073e-01 - 4.5379793e+00 -2.7174411e+00 -9.6658891e-01 - 4.7363213e+00 -2.8504760e+00 -9.6024965e-01 - 4.9673552e+00 -3.0058354e+00 -9.5971923e-01 - 5.2137705e+00 -3.1720281e+00 -9.5664679e-01 - 5.4862324e+00 -3.3548122e+00 -9.5301682e-01 - 5.8000202e+00 -3.5663530e+00 -9.5302937e-01 - 6.1302159e+00 -3.7885608e+00 -9.4590874e-01 - 6.5258214e+00 -4.0552107e+00 -9.4621100e-01 - 6.9397957e+00 -4.3334485e+00 -9.3534181e-01 - 7.4192192e+00 -4.6558130e+00 -9.2550341e-01 - 7.9660522e+00 -5.0232299e+00 -9.1275740e-01 - 8.6110057e+00 -5.4577797e+00 -9.0040937e-01 - 9.3887988e+00 -5.9816614e+00 -8.8928068e-01 - 1.0406283e+01 -6.6661143e+00 -8.9123498e-01 - 1.1698120e+01 -7.5348337e+00 -8.9690699e-01 - 1.3510588e+01 -8.7551109e+00 -9.2549677e-01 - 1.5830471e+01 -1.0315383e+01 -9.4204941e-01 - 1.8450815e+01 -1.2079115e+01 -8.9294957e-01 - 3.3076356e+01 -2.1920961e+01 -3.7109463e-01 - 3.3182387e+01 -2.1992696e+01 3.1242892e-01 - 4.1623051e+01 -2.7672648e+01 7.0860807e+00 - 4.0373475e+01 -2.6831228e+01 8.6120123e+00 - 5.6448685e+00 -3.4620461e+00 4.0247278e+00 - 5.3415028e+00 -3.2576905e+00 3.9735670e+00 - 5.3274533e+00 -3.2478611e+00 4.0937175e+00 - 5.6237928e+00 -3.4483228e+00 5.3246850e+00 - 5.6339876e+00 -3.4544451e+00 5.4964356e+00 - 4.6209474e+00 -2.7726843e+00 4.7432638e+00 - 4.5595544e+00 -2.7319008e+00 4.8232316e+00 - 4.3871794e+00 -2.6155786e+00 4.7947283e+00 - 4.4078479e+00 -2.6300196e+00 4.9531077e+00 - 4.3001648e+00 -2.5568706e+00 4.9822036e+00 - 4.2049757e+00 -2.4930022e+00 5.0213922e+00 - 4.1281351e+00 -2.4413983e+00 5.0782937e+00 - 4.0271848e+00 -2.3727687e+00 5.1053683e+00 - 3.9551090e+00 -2.3253367e+00 5.1648492e+00 - 3.8947257e+00 -2.2840058e+00 5.2368741e+00 - 3.8101674e+00 -2.2266855e+00 5.2783225e+00 - 3.5477246e+00 -2.0501807e+00 5.0797997e+00 - 3.6515989e+00 -2.1202864e+00 5.3696708e+00 - 3.4219280e+00 -1.9664988e+00 5.1978982e+00 - 3.5800622e+00 -2.0721572e+00 5.5851063e+00 - 3.2169050e+00 -1.8280166e+00 5.1921324e+00 - 3.2609077e+00 -1.8576443e+00 5.4163974e+00 - 3.1230385e+00 -1.7652259e+00 5.3525154e+00 - 3.1264721e+00 -1.7670555e+00 5.5216931e+00 - 2.7175548e+00 -1.4922879e+00 4.9627877e+00 - 2.6550841e+00 -1.4505320e+00 5.0004621e+00 - 2.5568266e+00 -1.3839788e+00 4.9688500e+00 - 2.5418294e+00 -1.3736849e+00 5.0971936e+00 - 2.5530110e+00 -1.3809896e+00 5.2867184e+00 - 2.3655180e+00 -1.2556395e+00 5.0582168e+00 - 2.6888467e+00 -1.4729824e+00 5.9621462e+00 - 2.3230163e+00 -1.2263938e+00 5.3124515e+00 - 2.2925325e+00 -1.2066233e+00 5.4310117e+00 - 2.0807062e+00 -1.0634552e+00 5.0874404e+00 - 1.9269717e+00 -9.5994311e-01 4.8642131e+00 - 1.8712564e+00 -9.2201022e-01 4.8937241e+00 - 1.8951202e+00 -9.3915428e-01 5.1630538e+00 - 1.8559855e+00 -9.1205635e-01 5.2570760e+00 - 1.7905833e+00 -8.6806932e-01 5.2755349e+00 - 1.6911116e+00 -8.0111851e-01 5.1697192e+00 - 1.6227568e+00 -7.5506778e-01 5.1655667e+00 - 1.8778449e+00 -9.2720986e-01 6.4318368e+00 - 1.5308229e+00 -6.9393867e-01 5.3352311e+00 - 1.4634424e+00 -6.4865467e-01 5.3370177e+00 - 1.4410467e+00 -6.3267285e-01 5.5506318e+00 - 1.3697815e+00 -5.8473754e-01 5.5404971e+00 - 1.4552373e+00 -6.4253499e-01 6.4189012e+00 - 1.3959513e+00 -6.0305188e-01 6.5559905e+00 - 1.3427109e+00 -5.6657288e-01 6.7610745e+00 - 1.2589991e+00 -5.1052500e-01 6.7779501e+00 - 1.1693446e+00 -4.5065025e-01 6.7435105e+00 - 1.0181679e+00 -3.4853221e-01 6.0917075e+00 - 1.0129161e+00 -3.4477146e-01 6.8875362e+00 - 9.2422583e-01 -2.8522813e-01 6.8476002e+00 - 1.0123119e+00 -3.4401252e-01 9.8284298e+00 - 8.9670726e-01 -2.6750590e-01 1.0137454e+01 - 7.5633844e-01 -1.7228332e-01 9.8645919e+00 - 6.3201674e-01 -8.8462319e-02 1.0128554e+01 - 2.1464600e+00 -1.1799305e+00 -9.9052315e-01 - 2.2031206e+00 -1.2204090e+00 -9.8937680e-01 - 2.2674347e+00 -1.2666022e+00 -9.9300197e-01 - 2.3259952e+00 -1.3090034e+00 -9.8786768e-01 - 2.3846284e+00 -1.3503090e+00 -9.8078541e-01 - 2.4499186e+00 -1.3972542e+00 -9.7817186e-01 - 2.5228671e+00 -1.4498747e+00 -9.7953081e-01 - 2.5948931e+00 -1.5013145e+00 -9.7843922e-01 - 2.6688105e+00 -1.5547461e+00 -9.7475797e-01 - 2.7495133e+00 -1.6117591e+00 -9.7434614e-01 - 2.8311112e+00 -1.6706886e+00 -9.7104183e-01 - 2.9127269e+00 -1.7294751e+00 -9.6484111e-01 - 3.0087829e+00 -1.7975481e+00 -9.6648157e-01 - 3.1124505e+00 -1.8721849e+00 -9.6984770e-01 - 3.2170807e+00 -1.9476821e+00 -9.6917240e-01 - 3.3150797e+00 -2.0173328e+00 -9.5983356e-01 - 3.4350636e+00 -2.1038850e+00 -9.6111068e-01 - 3.5704448e+00 -2.2006282e+00 -9.6708643e-01 - 3.6923631e+00 -2.2888271e+00 -9.5878252e-01 - 3.8373998e+00 -2.3918757e+00 -9.5879980e-01 - 3.9977249e+00 -2.5070156e+00 -9.6151896e-01 - 4.1590275e+00 -2.6228977e+00 -9.5779964e-01 - 4.3443446e+00 -2.7555360e+00 -9.5930930e-01 - 4.5373072e+00 -2.8944671e+00 -9.5705141e-01 - 4.7552973e+00 -3.0500968e+00 -9.5762863e-01 - 4.9665568e+00 -3.2017064e+00 -9.4604741e-01 - 5.2402332e+00 -3.3970478e+00 -9.5141737e-01 - 5.5147956e+00 -3.5948937e+00 -9.4555555e-01 - 5.8220851e+00 -3.8147832e+00 -9.3980961e-01 - 6.1783244e+00 -4.0698947e+00 -9.3743433e-01 - 6.5738689e+00 -4.3543531e+00 -9.3285280e-01 - 7.0041203e+00 -4.6616233e+00 -9.2125272e-01 - 7.4985912e+00 -5.0168737e+00 -9.0898389e-01 - 8.0660968e+00 -5.4235406e+00 -8.9392875e-01 - 8.7468984e+00 -5.9113665e+00 -8.8067583e-01 - 9.5582631e+00 -6.4932207e+00 -8.6499236e-01 - 1.0692155e+01 -7.3064315e+00 -8.7412964e-01 - 1.2280179e+01 -8.4442188e+00 -9.0830663e-01 - 1.4009427e+01 -9.6844123e+00 -8.9384902e-01 - 1.7059617e+01 -1.1871122e+01 -9.6190480e-01 - 1.8997780e+01 -1.3259608e+01 -7.9123659e-01 - 3.0266701e+01 -2.1338288e+01 -5.9906032e-01 - 3.0796730e+01 -2.1717497e+01 2.3822785e-02 - 3.0537551e+01 -2.1531936e+01 6.7748481e-01 - 4.0172786e+01 -2.8438875e+01 2.2782419e+00 - 3.9977505e+01 -2.8299947e+01 3.1207404e+00 - 4.0038707e+01 -2.8343413e+01 3.9754588e+00 - 3.9511545e+01 -2.7964975e+01 6.4687394e+00 - 3.9825632e+01 -2.8190202e+01 9.9677150e+00 - 3.8656993e+01 -2.7352347e+01 1.0551561e+01 - 5.3290887e+00 -3.4621039e+00 3.9627010e+00 - 5.2573508e+00 -3.4104247e+00 4.0475018e+00 - 5.2279412e+00 -3.3890754e+00 4.1587685e+00 - 5.3024312e+00 -3.4425720e+00 4.3434727e+00 - 5.7031869e+00 -3.7293966e+00 4.7709603e+00 - 5.2118620e+00 -3.3775437e+00 4.5528856e+00 - 4.8725308e+00 -3.1345600e+00 4.4279524e+00 - 4.8710466e+00 -3.1329255e+00 4.5599439e+00 - 4.9475124e+00 -3.1877388e+00 4.7609208e+00 - 5.2896557e+00 -3.4341234e+00 5.2042970e+00 - 5.0465826e+00 -3.2591440e+00 5.1398954e+00 - 4.5356983e+00 -2.8935711e+00 4.8108285e+00 - 4.3791449e+00 -2.7814699e+00 4.7973541e+00 - 4.3565001e+00 -2.7643838e+00 4.9117931e+00 - 4.3068370e+00 -2.7288867e+00 5.0005599e+00 - 4.2186291e+00 -2.6660048e+00 5.0485649e+00 - 4.1487698e+00 -2.6153875e+00 5.1142829e+00 - 4.2436372e+00 -2.6835890e+00 5.3709747e+00 - 4.1631782e+00 -2.6256582e+00 5.4296891e+00 - 3.8089106e+00 -2.3727122e+00 5.1439589e+00 - 3.8065562e+00 -2.3694783e+00 5.2868903e+00 - 3.5688477e+00 -2.1998525e+00 5.1212946e+00 - 3.6020986e+00 -2.2233836e+00 5.3138865e+00 - 3.9728926e+00 -2.4893594e+00 6.0033547e+00 - 3.3426268e+00 -2.0376632e+00 5.2438498e+00 - 4.4920604e+00 -2.8617151e+00 7.1747437e+00 - 3.0676232e+00 -1.8407644e+00 5.1174888e+00 - 3.1202190e+00 -1.8781827e+00 5.3569033e+00 - 3.0483210e+00 -1.8267512e+00 5.3961611e+00 - 3.0044546e+00 -1.7947013e+00 5.4831598e+00 - 2.7152212e+00 -1.5886836e+00 5.1193444e+00 - 2.5525284e+00 -1.4712325e+00 4.9638691e+00 - 2.4824948e+00 -1.4209762e+00 4.9817470e+00 - 2.4095242e+00 -1.3690473e+00 4.9893478e+00 - 2.4370958e+00 -1.3887093e+00 5.2125218e+00 - 2.3071248e+00 -1.2954077e+00 5.0952818e+00 - 2.3231551e+00 -1.3067283e+00 5.3108065e+00 - 2.1350447e+00 -1.1726027e+00 5.0361195e+00 - 2.0746764e+00 -1.1285731e+00 5.0615538e+00 - 1.9523105e+00 -1.0408563e+00 4.9219144e+00 - 1.9257854e+00 -1.0215986e+00 5.0349686e+00 - 1.8217296e+00 -9.4748505e-01 4.9264249e+00 - 1.7622562e+00 -9.0485768e-01 4.9449142e+00 - 1.7919819e+00 -9.2647401e-01 5.2524753e+00 - 1.7228288e+00 -8.7721924e-01 5.2512735e+00 - 1.6294568e+00 -8.0923018e-01 5.1535790e+00 - 1.9100721e+00 -1.0108818e+00 6.5029481e+00 - 1.7458769e+00 -8.9275834e-01 6.1775394e+00 - 1.4705176e+00 -6.9569376e-01 5.3073550e+00 - 1.5825554e+00 -7.7590449e-01 6.1505560e+00 - 1.3681847e+00 -6.2306939e-01 5.4534881e+00 - 1.4738656e+00 -6.9833598e-01 6.4086228e+00 - 1.4157029e+00 -6.5636587e-01 6.5365714e+00 - 1.3693931e+00 -6.2282475e-01 6.7716945e+00 - 1.2848696e+00 -5.6264802e-01 6.7697484e+00 - 1.1954626e+00 -4.9821712e-01 6.7263718e+00 - 1.0654532e+00 -4.0500698e-01 6.2843359e+00 - 9.8064098e-01 -3.4507449e-01 6.1963976e+00 - 9.5871079e-01 -3.2868162e-01 6.8628472e+00 - 1.0809051e+00 -4.1630874e-01 1.0091894e+01 - 9.3280726e-01 -3.1030224e-01 9.7037053e+00 - 8.2474262e-01 -2.3238003e-01 1.0151285e+01 - 6.8841437e-01 -1.3495350e-01 9.8469498e+00 - 5.7097024e-01 -5.1013036e-02 1.1009672e+01 - 2.0856085e+00 -1.2085276e+00 -9.9404343e-01 - 2.1364394e+00 -1.2463391e+00 -9.8668487e-01 - 2.1986895e+00 -1.2934675e+00 -9.9145264e-01 - 2.2494210e+00 -1.3331054e+00 -9.8059918e-01 - 2.3126343e+00 -1.3810892e+00 -9.8122564e-01 - 2.3767985e+00 -1.4300269e+00 -9.7970833e-01 - 2.4409763e+00 -1.4788563e+00 -9.7599373e-01 - 2.5118744e+00 -1.5323035e+00 -9.7629800e-01 - 2.5770185e+00 -1.5819637e+00 -9.6794271e-01 - 2.6488252e+00 -1.6372189e+00 -9.6315723e-01 - 2.7350045e+00 -1.7028166e+00 -9.6736191e-01 - 2.8144930e+00 -1.7635600e+00 -9.6275363e-01 - 2.9083602e+00 -1.8345965e+00 -9.6613674e-01 - 2.9888243e+00 -1.8960967e+00 -9.5538961e-01 - 3.0969769e+00 -1.9792036e+00 -9.6227044e-01 - 3.2004376e+00 -2.0575572e+00 -9.5994515e-01 - 3.3105769e+00 -2.1413779e+00 -9.5859290e-01 - 3.4350520e+00 -2.2363509e+00 -9.6238594e-01 - 3.5537786e+00 -2.3274923e+00 -9.5662051e-01 - 3.6812471e+00 -2.4231705e+00 -9.5078538e-01 - 3.8305986e+00 -2.5375963e+00 -9.5247080e-01 - 3.9876442e+00 -2.6574116e+00 -9.5233588e-01 - 4.1609845e+00 -2.7893146e+00 -9.5360762e-01 - 4.3343071e+00 -2.9218747e+00 -9.4793833e-01 - 4.5392541e+00 -3.0777696e+00 -9.4952331e-01 - 4.7528528e+00 -3.2399538e+00 -9.4604553e-01 - 4.9817101e+00 -3.4149850e+00 -9.4032612e-01 - 5.2355531e+00 -3.6075637e+00 -9.3439597e-01 - 5.5199388e+00 -3.8251152e+00 -9.2962522e-01 - 5.8446031e+00 -4.0722711e+00 -9.2664647e-01 - 6.2238363e+00 -4.3610625e+00 -9.2815843e-01 - 6.6127123e+00 -4.6567768e+00 -9.1597186e-01 - 7.0560682e+00 -4.9958692e+00 -9.0308319e-01 - 7.5723223e+00 -5.3885001e+00 -8.8990590e-01 - 8.1823386e+00 -5.8540383e+00 -8.7751570e-01 - 8.8652558e+00 -6.3736095e+00 -8.5459991e-01 - 9.7931819e+00 -7.0814426e+00 -8.5054276e-01 - 1.0959599e+01 -7.9702706e+00 -8.4814087e-01 - 1.2586592e+01 -9.2098922e+00 -8.6572054e-01 - 1.4675223e+01 -1.0800879e+01 -8.7312295e-01 - 1.7726211e+01 -1.3125756e+01 -8.9471924e-01 - 2.9800151e+01 -2.2325706e+01 -2.8635083e-01 - 2.9599131e+01 -2.2172036e+01 3.6141656e-01 - 3.0176594e+01 -2.2612508e+01 1.0000449e+00 - 3.9142756e+01 -2.9444228e+01 1.8479927e+00 - 3.7845639e+01 -2.8455885e+01 2.6395731e+00 - 3.8667086e+01 -2.9081894e+01 3.5147299e+00 - 3.8999187e+01 -2.9334565e+01 4.3845036e+00 - 3.8773144e+01 -2.9163385e+01 6.9081763e+00 - 5.4901443e+00 -3.8020276e+00 4.0597749e+00 - 5.4109146e+00 -3.7417956e+00 4.1461024e+00 - 5.2117293e+00 -3.5901428e+00 4.1500638e+00 - 5.1468797e+00 -3.5407082e+00 4.2384371e+00 - 5.1837502e+00 -3.5690092e+00 4.4000034e+00 - 5.0613479e+00 -3.4750936e+00 4.4455873e+00 - 4.9993748e+00 -3.4278145e+00 4.5344496e+00 - 4.8692112e+00 -3.3290464e+00 4.5673266e+00 - 4.9377819e+00 -3.3816236e+00 4.7633360e+00 - 4.5983528e+00 -3.1221025e+00 4.6077508e+00 - 4.5410957e+00 -3.0793845e+00 4.6913023e+00 - 4.4886760e+00 -3.0397428e+00 4.7793811e+00 - 4.8061485e+00 -3.2802884e+00 5.2295300e+00 - 4.3445325e+00 -2.9290413e+00 4.9142822e+00 - 4.3324721e+00 -2.9199060e+00 5.0430653e+00 - 4.2099191e+00 -2.8266784e+00 5.0544418e+00 - 4.0873396e+00 -2.7336627e+00 5.0615237e+00 - 4.2107818e+00 -2.8280367e+00 5.3510693e+00 - 4.2987512e+00 -2.8945866e+00 5.6124280e+00 - 3.8465011e+00 -2.5493798e+00 5.2072090e+00 - 3.7267727e+00 -2.4582075e+00 5.2008475e+00 - 3.7002544e+00 -2.4388955e+00 5.3150004e+00 - 3.5651680e+00 -2.3351554e+00 5.2804796e+00 - 3.7137185e+00 -2.4491913e+00 5.6489365e+00 - 3.2505795e+00 -2.0953728e+00 5.1212093e+00 - 3.8081074e+00 -2.5209157e+00 6.1368901e+00 - 3.2957446e+00 -2.1304540e+00 5.4995258e+00 - 3.1807571e+00 -2.0426124e+00 5.4722734e+00 - 3.0618867e+00 -1.9521048e+00 5.4333992e+00 - 3.3599557e+00 -2.1789311e+00 6.1360033e+00 - 2.9550871e+00 -1.8703484e+00 5.5762059e+00 - 2.5616226e+00 -1.5706868e+00 4.9920477e+00 - 2.4724612e+00 -1.5032618e+00 4.9688469e+00 - 2.3842813e+00 -1.4360304e+00 4.9429463e+00 - 2.4687064e+00 -1.4992708e+00 5.2867656e+00 - 2.3081919e+00 -1.3773926e+00 5.1019226e+00 - 2.1910480e+00 -1.2881305e+00 4.9997210e+00 - 2.1317517e+00 -1.2430560e+00 5.0272999e+00 - 2.0753155e+00 -1.2007841e+00 5.0625087e+00 - 1.9387953e+00 -1.0963389e+00 4.8789783e+00 - 1.8524592e+00 -1.0299311e+00 4.8185643e+00 - 1.8761999e+00 -1.0485746e+00 5.0777561e+00 - 1.7695136e+00 -9.6724513e-01 4.9497491e+00 - 1.7827701e+00 -9.7662064e-01 5.2010392e+00 - 1.7350784e+00 -9.4041323e-01 5.2661297e+00 - 1.6699119e+00 -8.9196366e-01 5.2737539e+00 - 1.5767173e+00 -8.2049423e-01 5.1655739e+00 - 1.5552090e+00 -8.0442648e-01 5.3416321e+00 - 1.5143517e+00 -7.7347284e-01 5.4505933e+00 - 1.4201271e+00 -7.0116596e-01 5.3176479e+00 - 1.3929237e+00 -6.8032398e-01 5.5021163e+00 - 1.3316986e+00 -6.3407247e-01 5.5308506e+00 - 1.2705252e+00 -5.8689297e-01 5.5581369e+00 - 1.3998231e+00 -6.8540219e-01 6.8210508e+00 - 1.3164864e+00 -6.2223099e-01 6.8202513e+00 - 1.2263293e+00 -5.5317857e-01 6.7680407e+00 - 1.1370361e+00 -4.8577476e-01 6.7038913e+00 - 1.0022602e+00 -3.8221825e-01 6.1413264e+00 - 9.8707853e-01 -3.7124984e-01 6.8279265e+00 - 1.1510653e+00 -4.9628272e-01 1.0364237e+01 - 9.8740960e-01 -3.7105386e-01 9.7586295e+00 - 8.8028069e-01 -2.9008090e-01 1.0127456e+01 - 7.4638651e-01 -1.8772996e-01 9.8646143e+00 - 6.2772993e-01 -9.6759897e-02 1.0198576e+01 - 2.0248812e+00 -1.2351013e+00 -9.9706354e-01 - 2.0678854e+00 -1.2701298e+00 -9.8358629e-01 - 2.1176014e+00 -1.3098452e+00 -9.7552619e-01 - 2.1844428e+00 -1.3635630e+00 -9.8620492e-01 - 2.2398264e+00 -1.4087885e+00 -9.8121208e-01 - 2.3019266e+00 -1.4586614e+00 -9.8083737e-01 - 2.3649784e+00 -1.5094833e+00 -9.7821901e-01 - 2.4336922e+00 -1.5658597e+00 -9.7956680e-01 - 2.4977103e+00 -1.6175124e+00 -9.7230775e-01 - 2.5674518e+00 -1.6737127e+00 -9.6886464e-01 - 2.6381473e+00 -1.7308423e+00 -9.6277836e-01 - 2.7221583e+00 -1.7992410e+00 -9.6542976e-01 - 2.8071871e+00 -1.8675425e+00 -9.6488828e-01 - 2.8921754e+00 -1.9366833e+00 -9.6110121e-01 - 2.9781214e+00 -2.0067238e+00 -9.5407170e-01 - 3.0907610e+00 -2.0982859e+00 -9.6416759e-01 - 3.1854017e+00 -2.1737567e+00 -9.5492142e-01 - 3.2999702e+00 -2.2670100e+00 -9.5633517e-01 - 3.4221608e+00 -2.3667433e+00 -9.5777669e-01 - 3.5463780e+00 -2.4663561e+00 -9.5433062e-01 - 3.6705651e+00 -2.5667244e+00 -9.4594103e-01 - 3.8232954e+00 -2.6914551e+00 -9.4904133e-01 - 3.9780608e+00 -2.8159963e+00 -9.4585576e-01 - 4.1537258e+00 -2.9591063e+00 -9.4779052e-01 - 4.3466923e+00 -3.1142956e+00 -9.4973685e-01 - 4.5472485e+00 -3.2767402e+00 -9.4716694e-01 - 4.7553987e+00 -3.4464057e+00 -9.3938168e-01 - 4.9951334e+00 -3.6402404e+00 -9.3550520e-01 - 5.2654064e+00 -3.8590824e+00 -9.3348726e-01 - 5.5595633e+00 -4.0972724e+00 -9.2845962e-01 - 5.8985563e+00 -4.3724414e+00 -9.2679070e-01 - 6.2777315e+00 -4.6790167e+00 -9.2291949e-01 - 6.6884385e+00 -5.0112132e+00 -9.1187155e-01 - 7.1688557e+00 -5.3998612e+00 -9.0247420e-01 - 7.6807802e+00 -5.8148417e+00 -8.8005772e-01 - 8.3092485e+00 -6.3233638e+00 -8.6245715e-01 - 9.0531896e+00 -6.9269816e+00 -8.4187972e-01 - 1.0007306e+01 -7.6991210e+00 -8.2840423e-01 - 1.1170568e+01 -8.6410160e+00 -8.0774590e-01 - 1.3255107e+01 -1.0329775e+01 -8.7007383e-01 - 1.6071229e+01 -1.2610241e+01 -9.2935661e-01 - 1.8164098e+01 -1.4304467e+01 -7.8881637e-01 - 2.8636279e+01 -2.2785608e+01 -5.8078027e-01 - 2.8653489e+01 -2.2799364e+01 5.1371011e-02 - 2.8645838e+01 -2.2793543e+01 6.8391159e-01 - 2.8645868e+01 -2.2793220e+01 1.3160752e+00 - 2.8629652e+01 -2.2779902e+01 1.9477982e+00 - 2.8643996e+01 -2.2791418e+01 2.5811583e+00 - 2.8595283e+01 -2.2752151e+01 3.2111010e+00 - 2.8599138e+01 -2.2754953e+01 3.8455979e+00 - 2.8580060e+01 -2.2739365e+01 4.4791290e+00 - 2.8574311e+01 -2.2735453e+01 5.1159571e+00 - 2.8629740e+01 -2.2780746e+01 5.7654479e+00 - 3.6898894e+01 -2.9476855e+01 8.8379555e+00 - 3.9581905e+01 -3.1650170e+01 1.3073512e+01 - 3.8946131e+01 -3.1134744e+01 1.4719768e+01 - 3.9084777e+01 -3.1246573e+01 1.6654409e+01 - 5.1246011e+00 -3.7454285e+00 3.9672260e+00 - 5.1316998e+00 -3.7511492e+00 4.1029314e+00 - 5.2192543e+00 -3.8210148e+00 4.2970732e+00 - 4.9774987e+00 -3.6257089e+00 4.2597955e+00 - 5.1463261e+00 -3.7632896e+00 4.5222566e+00 - 4.9457456e+00 -3.6005230e+00 4.5059540e+00 - 4.9365759e+00 -3.5934300e+00 4.6375234e+00 - 4.7053248e+00 -3.4056822e+00 4.5820308e+00 - 4.6310536e+00 -3.3454945e+00 4.6533113e+00 - 4.4667942e+00 -3.2118097e+00 4.6409225e+00 - 4.4480450e+00 -3.1967721e+00 4.7592431e+00 - 4.3842978e+00 -3.1450180e+00 4.8350799e+00 - 4.3377762e+00 -3.1074965e+00 4.9280328e+00 - 4.2356635e+00 -3.0253767e+00 4.9627593e+00 - 4.3405540e+00 -3.1101402e+00 5.2213076e+00 - 4.1311005e+00 -2.9413057e+00 5.1346741e+00 - 4.0002986e+00 -2.8344438e+00 5.1278072e+00 - 4.0678349e+00 -2.8893126e+00 5.3571770e+00 - 4.0970870e+00 -2.9126512e+00 5.5487828e+00 - 4.0726029e+00 -2.8936738e+00 5.6788592e+00 - 3.8756084e+00 -2.7333674e+00 5.5770503e+00 - 3.7447208e+00 -2.6271903e+00 5.5563006e+00 - 3.7030047e+00 -2.5935155e+00 5.6584247e+00 - 3.7955806e+00 -2.6691121e+00 5.9653570e+00 - 3.2779778e+00 -2.2498247e+00 5.3365153e+00 - 3.2084203e+00 -2.1931845e+00 5.3825104e+00 - 3.1541839e+00 -2.1494078e+00 5.4506721e+00 - 3.1758270e+00 -2.1666769e+00 5.6542405e+00 - 2.9727648e+00 -2.0025107e+00 5.4612664e+00 - 2.9166223e+00 -1.9568605e+00 5.5244414e+00 - 2.6615873e+00 -1.7508140e+00 5.2027657e+00 - 2.4660974e+00 -1.5919796e+00 4.9722613e+00 - 2.4329644e+00 -1.5646268e+00 5.0585243e+00 - 2.3334321e+00 -1.4849658e+00 5.0065492e+00 - 2.2560781e+00 -1.4216925e+00 4.9948944e+00 - 2.1834526e+00 -1.3633957e+00 4.9897637e+00 - 2.1436118e+00 -1.3302933e+00 5.0624681e+00 - 2.1604518e+00 -1.3452434e+00 5.2866774e+00 - 1.9280826e+00 -1.1561155e+00 4.8539585e+00 - 1.8794837e+00 -1.1170570e+00 4.8945839e+00 - 1.8974273e+00 -1.1312251e+00 5.1358689e+00 - 1.7611743e+00 -1.0205187e+00 4.9171850e+00 - 1.8331383e+00 -1.0793736e+00 5.3542801e+00 - 1.7711030e+00 -1.0294976e+00 5.3742299e+00 - 1.6694992e+00 -9.4722210e-01 5.2512511e+00 - 1.5678802e+00 -8.6403661e-01 5.1062004e+00 - 1.5493049e+00 -8.4915702e-01 5.2820988e+00 - 1.4794910e+00 -7.9301902e-01 5.2571326e+00 - 1.4280779e+00 -7.5130738e-01 5.3073565e+00 - 1.3892669e+00 -7.2007558e-01 5.4244015e+00 - 1.3272283e+00 -6.6970999e-01 5.4340144e+00 - 1.2768538e+00 -6.2876684e-01 5.5104021e+00 - 1.4173332e+00 -7.4261758e-01 6.8011371e+00 - 1.3342434e+00 -6.7489516e-01 6.7913007e+00 - 1.2598859e+00 -6.1539717e-01 6.8485985e+00 - 1.0943408e+00 -4.8197257e-01 6.1230508e+00 - 1.0197644e+00 -4.2112890e-01 6.0860673e+00 - 1.0113889e+00 -4.1409356e-01 6.7825314e+00 - 9.4004885e-01 -3.5665609e-01 6.8827651e+00 - 8.5988814e-01 -2.9118459e-01 6.8917447e+00 - 9.2045157e-01 -3.4023001e-01 9.8534406e+00 - 8.1061839e-01 -2.5159908e-01 1.0171243e+01 - 6.7969903e-01 -1.4494515e-01 9.8169588e+00 - 5.6767137e-01 -5.5326958e-02 1.0999593e+01 - 1.9701003e+00 -1.2623775e+00 -1.0069942e+00 - 2.0062791e+00 -1.2946589e+00 -9.8690208e-01 - 2.0596368e+00 -1.3400000e+00 -9.8669695e-01 - 2.1195882e+00 -1.3920021e+00 -9.9141038e-01 - 2.1739078e+00 -1.4382084e+00 -9.8726370e-01 - 2.2281783e+00 -1.4853230e+00 -9.8126969e-01 - 2.2891662e+00 -1.5370801e+00 -9.7979394e-01 - 2.3443993e+00 -1.5850550e+00 -9.6975849e-01 - 2.4177093e+00 -1.6479814e+00 -9.7621822e-01 - 2.4862640e+00 -1.7071761e+00 -9.7392168e-01 - 2.5548347e+00 -1.7662428e+00 -9.6902834e-01 - 2.6310687e+00 -1.8309453e+00 -9.6730850e-01 - 2.7062616e+00 -1.8964464e+00 -9.6273938e-01 - 2.7891221e+00 -1.9675489e+00 -9.6064463e-01 - 2.8729396e+00 -2.0395561e+00 -9.5540732e-01 - 2.9833892e+00 -2.1340916e+00 -9.6744561e-01 - 3.0681891e+00 -2.2068014e+00 -9.5497082e-01 - 3.1729129e+00 -2.2973232e+00 -9.5375520e-01 - 3.2919726e+00 -2.3989972e+00 -9.5768488e-01 - 3.4052831e+00 -2.4968446e+00 -9.5215596e-01 - 3.5328753e+00 -2.6067919e+00 -9.5072402e-01 - 3.6824119e+00 -2.7344799e+00 -9.5666243e-01 - 3.8252670e+00 -2.8572397e+00 -9.5228973e-01 - 3.9899559e+00 -2.9996552e+00 -9.5359026e-01 - 4.1566842e+00 -3.1418467e+00 -9.4790577e-01 - 4.3442606e+00 -3.3035350e+00 -9.4589379e-01 - 4.5546904e+00 -3.4847671e+00 -9.4606254e-01 - 4.7737770e+00 -3.6722491e+00 -9.4036950e-01 - 5.0289424e+00 -3.8922965e+00 -9.4060180e-01 - 5.2860521e+00 -4.1139118e+00 -9.2965505e-01 - 5.5879862e+00 -4.3725997e+00 -9.2396467e-01 - 5.9574618e+00 -4.6900261e+00 -9.2820907e-01 - 6.3203090e+00 -5.0021004e+00 -9.1355297e-01 - 6.7660108e+00 -5.3848075e+00 -9.0753847e-01 - 7.2650415e+00 -5.8136013e+00 -8.9617558e-01 - 7.8107520e+00 -6.2827783e+00 -8.7369720e-01 - 8.5440304e+00 -6.9126794e+00 -8.7018017e-01 - 8.9937372e+00 -7.3001717e+00 -7.7394332e-01 - 9.7824364e+00 -7.9770642e+00 -7.2019087e-01 - 1.2032207e+01 -9.9107043e+00 -8.6697704e-01 - 1.4090922e+01 -1.1680891e+01 -8.8357766e-01 - 2.8960526e+01 -2.4459838e+01 -3.1046110e-01 - 2.8995811e+01 -2.4490621e+01 3.4414534e-01 - 2.9037789e+01 -2.4526763e+01 9.9997605e-01 - 3.8064650e+01 -3.2284356e+01 3.5957206e+00 - 3.6754127e+01 -3.1158472e+01 8.5712679e+00 - 3.1535635e+01 -2.6673582e+01 1.0447797e+01 - 3.2563098e+01 -2.7556966e+01 1.2328304e+01 - 3.3150538e+01 -2.8061003e+01 1.4162277e+01 - 4.9801547e+00 -3.8499330e+00 4.0099178e+00 - 4.8969043e+00 -3.7795826e+00 4.2142171e+00 - 4.9197033e+00 -3.7987456e+00 4.5021758e+00 - 4.5707648e+00 -3.4981430e+00 4.3543349e+00 - 4.4308203e+00 -3.3777820e+00 4.3657819e+00 - 4.5801133e+00 -3.5071159e+00 4.6291583e+00 - 4.4946344e+00 -3.4328267e+00 4.6879978e+00 - 4.5303399e+00 -3.4644638e+00 4.8617507e+00 - 4.4305230e+00 -3.3780090e+00 4.9057609e+00 - 4.3421337e+00 -3.3018353e+00 4.9586182e+00 - 4.3310906e+00 -3.2926077e+00 5.0904943e+00 - 4.2292894e+00 -3.2054193e+00 5.1266710e+00 - 4.1399190e+00 -3.1285331e+00 5.1724906e+00 - 3.9377899e+00 -2.9543321e+00 5.0816423e+00 - 3.8827405e+00 -2.9079837e+00 5.1601951e+00 - 3.8497836e+00 -2.8787077e+00 5.2651854e+00 - 4.1408650e+00 -3.1294402e+00 5.8012049e+00 - 3.9606408e+00 -2.9748426e+00 5.7260066e+00 - 3.8406701e+00 -2.8713803e+00 5.7244471e+00 - 3.6260062e+00 -2.6861625e+00 5.5776643e+00 - 3.7585073e+00 -2.8003760e+00 5.9432253e+00 - 3.6097685e+00 -2.6728023e+00 5.8872881e+00 - 3.1719919e+00 -2.2968181e+00 5.3520031e+00 - 3.1609962e+00 -2.2872112e+00 5.4915697e+00 - 3.1012082e+00 -2.2354508e+00 5.5521630e+00 - 3.0098166e+00 -2.1565793e+00 5.5547438e+00 - 2.9662698e+00 -2.1193968e+00 5.6444911e+00 - 2.8911163e+00 -2.0551277e+00 5.6757266e+00 - 2.4700798e+00 -1.6931305e+00 5.0004549e+00 - 2.3929409e+00 -1.6265903e+00 4.9942446e+00 - 2.3435930e+00 -1.5839337e+00 5.0458108e+00 - 2.2971045e+00 -1.5440847e+00 5.1049071e+00 - 2.1911277e+00 -1.4534757e+00 5.0231956e+00 - 2.1906995e+00 -1.4529859e+00 5.1939848e+00 - 2.1317769e+00 -1.4018311e+00 5.2232639e+00 - 2.1352117e+00 -1.4051982e+00 5.4220538e+00 - 1.9072534e+00 -1.2088439e+00 4.9786385e+00 - 1.8050074e+00 -1.1210848e+00 4.8643042e+00 - 1.8593801e+00 -1.1686287e+00 5.2250562e+00 - 1.8263618e+00 -1.1403595e+00 5.3298964e+00 - 1.7962701e+00 -1.1143609e+00 5.4531530e+00 - 1.6978509e+00 -1.0297162e+00 5.3413517e+00 - 1.6157655e+00 -9.5891028e-01 5.2736859e+00 - 1.5471464e+00 -8.9971377e-01 5.2511647e+00 - 1.4891270e+00 -8.4937813e-01 5.2650597e+00 - 1.6164713e+00 -9.5937230e-01 6.1330643e+00 - 1.3846109e+00 -7.6029071e-01 5.3563275e+00 - 1.3439839e+00 -7.2543301e-01 5.4633927e+00 - 1.2879294e+00 -6.7701687e-01 5.5016001e+00 - 1.4618796e+00 -8.2635192e-01 6.9666920e+00 - 1.3576255e+00 -7.3701814e-01 6.8210539e+00 - 1.2795822e+00 -6.6966870e-01 6.8300280e+00 - 1.1975941e+00 -5.9963171e-01 6.8075552e+00 - 1.0450162e+00 -4.6912833e-01 6.1197180e+00 - 9.8635491e-01 -4.1743192e-01 6.2207573e+00 - 9.6929697e-01 -4.0332043e-01 6.8875897e+00 - 8.9026022e-01 -3.3535699e-01 6.8875285e+00 - 9.6369292e-01 -3.9820527e-01 9.7486010e+00 - 8.5779365e-01 -3.0822271e-01 1.0017653e+01 - 7.3449847e-01 -2.0205875e-01 9.8645935e+00 - 6.2357237e-01 -1.0660339e-01 1.0338559e+01 - 1.9237318e+00 -1.2988879e+00 -1.0310392e+00 - 1.9390324e+00 -1.3134613e+00 -9.8275603e-01 - 1.9856211e+00 -1.3550878e+00 -9.7658482e-01 - 2.0425104e+00 -1.4079646e+00 -9.8243768e-01 - 2.1004109e+00 -1.4607984e+00 -9.8619630e-01 - 2.1536162e+00 -1.5089037e+00 -9.8124821e-01 - 2.2124805e+00 -1.5625880e+00 -9.8076564e-01 - 2.2722956e+00 -1.6172263e+00 -9.7813930e-01 - 2.3321244e+00 -1.6717561e+00 -9.7331567e-01 - 2.4099120e+00 -1.7432116e+00 -9.8448861e-01 - 2.4594089e+00 -1.7872565e+00 -9.6289716e-01 - 2.5324573e+00 -1.8548524e+00 -9.6271704e-01 - 2.6122328e+00 -1.9270119e+00 -9.6545715e-01 - 2.6862555e+00 -1.9953744e+00 -9.5933793e-01 - 2.7669476e+00 -2.0692779e+00 -9.5568989e-01 - 2.8553098e+00 -2.1487630e+00 -9.5411671e-01 - 2.9625351e+00 -2.2470164e+00 -9.6414947e-01 - 3.0584157e+00 -2.3348425e+00 -9.5980829e-01 - 3.1543203e+00 -2.4224765e+00 -9.5157191e-01 - 3.2644998e+00 -2.5222646e+00 -9.4853115e-01 - 3.3822419e+00 -2.6295249e+00 -9.4536874e-01 - 3.5132098e+00 -2.7498018e+00 -9.4585106e-01 - 3.6660650e+00 -2.8887917e+00 -9.5315480e-01 - 3.8056411e+00 -3.0162218e+00 -9.4582814e-01 - 3.9737130e+00 -3.1689078e+00 -9.4784441e-01 - 4.1493095e+00 -3.3298855e+00 -9.4609390e-01 - 4.3467577e+00 -3.5103761e+00 -9.4712020e-01 - 4.5451975e+00 -3.6914954e+00 -9.3941086e-01 - 4.7655019e+00 -3.8920242e+00 -9.3238090e-01 - 5.0294328e+00 -4.1327088e+00 -9.3355166e-01 - 5.3019197e+00 -4.3814795e+00 -9.2556550e-01 - 5.6180603e+00 -4.6701892e+00 -9.2138547e-01 - 5.9778736e+00 -4.9986852e+00 -9.1791542e-01 - 6.3680995e+00 -5.3547407e+00 -9.0726622e-01 - 6.8247995e+00 -5.7710592e+00 -8.9815976e-01 - 7.3469430e+00 -6.2483555e+00 -8.8604886e-01 - 7.9081688e+00 -6.7593578e+00 -8.5879963e-01 - 8.5718297e+00 -7.3656768e+00 -8.2868241e-01 - 8.9889304e+00 -7.7464474e+00 -7.1755733e-01 - 1.0379647e+01 -9.0152000e+00 -7.6077672e-01 - 1.2756468e+01 -1.1184364e+01 -8.9052155e-01 - 1.4682844e+01 -1.2942656e+01 -8.4882036e-01 - 2.8277601e+01 -2.5346835e+01 -6.4185950e-01 - 3.0243582e+01 -2.7141583e+01 -5.4433315e-02 - 2.8634675e+01 -2.5673452e+01 6.6754560e-01 - 9.1709991e+00 -7.9127367e+00 1.1024576e+00 - 9.1687849e+00 -7.9104460e+00 1.3073111e+00 - 3.6387022e+01 -3.2748260e+01 3.1211335e+00 - 3.5292854e+01 -3.1748691e+01 3.8806701e+00 - 3.5691686e+01 -3.2112603e+01 6.4278819e+00 - 3.5154636e+01 -3.1623689e+01 7.1763285e+00 - 3.0121089e+01 -2.7029606e+01 1.0626979e+01 - 3.0792312e+01 -2.7642024e+01 1.3147022e+01 - 3.1969605e+01 -2.8716511e+01 1.4432186e+01 - 3.2036752e+01 -2.8777498e+01 1.5284728e+01 - 3.1367064e+01 -2.8166912e+01 1.5797307e+01 - 3.6629580e+01 -3.2969989e+01 2.0266609e+01 - 4.4108298e+00 -3.5691613e+00 4.2446845e+00 - 4.3493812e+00 -3.5125335e+00 4.3204670e+00 - 4.3621335e+00 -3.5243918e+00 4.4606455e+00 - 4.3292189e+00 -3.4942617e+00 4.5626898e+00 - 4.3000876e+00 -3.4681099e+00 4.6700134e+00 - 4.7157120e+00 -3.8468819e+00 5.2231943e+00 - 4.4014015e+00 -3.5601375e+00 5.2018787e+00 - 4.2904155e+00 -3.4587567e+00 5.2299028e+00 - 4.1680117e+00 -3.3465019e+00 5.2408404e+00 - 3.9073260e+00 -3.1099688e+00 5.0816980e+00 - 3.8163012e+00 -3.0266185e+00 5.1142929e+00 - 3.8053245e+00 -3.0163448e+00 5.2471182e+00 - 3.8820183e+00 -3.0866560e+00 5.4998211e+00 - 3.8129406e+00 -3.0230881e+00 5.5646952e+00 - 3.7791013e+00 -2.9923113e+00 5.6786281e+00 - 3.7481183e+00 -2.9643668e+00 5.7995915e+00 - 3.8040207e+00 -3.0142138e+00 6.0553181e+00 - 3.4496642e+00 -2.6916657e+00 5.6764444e+00 - 3.3614518e+00 -2.6109833e+00 5.6991413e+00 - 3.1119772e+00 -2.3828518e+00 5.4451266e+00 - 3.0398559e+00 -2.3184636e+00 5.4824451e+00 - 3.0308463e+00 -2.3095755e+00 5.6301449e+00 - 2.7086135e+00 -2.0159558e+00 5.1926260e+00 - 2.5458162e+00 -1.8667621e+00 5.0298786e+00 - 2.5176245e+00 -1.8411388e+00 5.1277107e+00 - 2.4168086e+00 -1.7494723e+00 5.0735493e+00 - 2.3447112e+00 -1.6828305e+00 5.0755130e+00 - 2.3212347e+00 -1.6628064e+00 5.1875093e+00 - 2.2022924e+00 -1.5529738e+00 5.0731904e+00 - 2.1559133e+00 -1.5112196e+00 5.1303898e+00 - 2.1507467e+00 -1.5058319e+00 5.2930569e+00 - 2.0718631e+00 -1.4340661e+00 5.2687776e+00 - 2.1251304e+00 -1.4824068e+00 5.6121543e+00 - 1.9695727e+00 -1.3417195e+00 5.3677806e+00 - 2.0900239e+00 -1.4513560e+00 5.9520602e+00 - 1.8309392e+00 -1.2147933e+00 5.3514619e+00 - 1.7634785e+00 -1.1538621e+00 5.3450680e+00 - 1.6970042e+00 -1.0930850e+00 5.3367733e+00 - 1.6065557e+00 -1.0095563e+00 5.2323869e+00 - 1.5525402e+00 -9.5988788e-01 5.2579044e+00 - 1.4946468e+00 -9.0751400e-01 5.2725991e+00 - 1.4454205e+00 -8.6285357e-01 5.3242661e+00 - 1.4039266e+00 -8.2482456e-01 5.4133582e+00 - 1.3373929e+00 -7.6400630e-01 5.3856378e+00 - 1.3017531e+00 -7.3102775e-01 5.5215004e+00 - 1.4489265e+00 -8.6599585e-01 6.7991183e+00 - 1.3807615e+00 -8.0368740e-01 6.8599438e+00 - 1.3029062e+00 -7.3328798e-01 6.8699678e+00 - 1.2260386e+00 -6.6303276e-01 6.8782907e+00 - 1.0574034e+00 -5.0926084e-01 6.0538376e+00 - 9.9487056e-01 -4.5222913e-01 6.0960654e+00 - 9.9442685e-01 -4.5126215e-01 6.8818897e+00 - 9.1851120e-01 -3.8143689e-01 6.8827187e+00 - 8.4258671e-01 -3.1271380e-01 6.9017244e+00 - 9.0091313e-01 -3.6614027e-01 9.8734623e+00 - 7.9336879e-01 -2.6807244e-01 1.0101375e+01 - 6.6892428e-01 -1.5480428e-01 9.7669493e+00 - 5.5408325e-01 -4.9288571e-02 9.4496675e+00 - 1.8777936e+00 -1.3319594e+00 -9.8537035e-01 - 1.9232588e+00 -1.3755588e+00 -9.7989588e-01 - 1.9686736e+00 -1.4200763e+00 -9.7277383e-01 - 2.0188045e+00 -1.4691548e+00 -9.7096270e-01 - 2.0812962e+00 -1.5285781e+00 -9.8063227e-01 - 2.1380363e+00 -1.5841945e+00 -9.8124277e-01 - 2.1901403e+00 -1.6340953e+00 -9.7339585e-01 - 2.2478443e+00 -1.6905622e+00 -9.6976516e-01 - 2.3065599e+00 -1.7469812e+00 -9.6394036e-01 - 2.3765879e+00 -1.8146026e+00 -9.6794551e-01 - 2.4362103e+00 -1.8728444e+00 -9.5733059e-01 - 2.5015586e+00 -1.9356140e+00 -9.5013211e-01 - 2.5857540e+00 -2.0172799e+00 -9.5713637e-01 - 2.6643183e+00 -2.0931451e+00 -9.5518065e-01 - 2.7429016e+00 -2.1688576e+00 -9.5012876e-01 - 2.8290359e+00 -2.2521357e+00 -9.4685287e-01 - 2.9274413e+00 -2.3475062e+00 -9.4996475e-01 - 3.0268099e+00 -2.4437321e+00 -9.4893532e-01 - 3.1271430e+00 -2.5408036e+00 -9.4356483e-01 - 3.2473510e+00 -2.6565952e+00 -9.4760618e-01 - 3.3684688e+00 -2.7741850e+00 -9.4635803e-01 - 3.5028757e+00 -2.9037699e+00 -9.4830478e-01 - 3.6381973e+00 -3.0351136e+00 -9.4416301e-01 - 3.7886913e+00 -3.1805080e+00 -9.4192489e-01 - 3.9524290e+00 -3.3387763e+00 -9.4043508e-01 - 4.1237521e+00 -3.5043344e+00 -9.3512819e-01 - 4.3158691e+00 -3.6903369e+00 -9.3244548e-01 - 4.5297291e+00 -3.8977527e+00 -9.3054281e-01 - 4.7587947e+00 -4.1189532e+00 -9.2515045e-01 - 5.0162255e+00 -4.3680013e+00 -9.2086236e-01 - 5.2954872e+00 -4.6372439e+00 -9.1290940e-01 - 5.6172913e+00 -4.9482999e+00 -9.0746179e-01 - 5.9815962e+00 -5.3020184e+00 -9.0147368e-01 - 6.4036983e+00 -5.7104267e+00 -8.9634854e-01 - 6.8694033e+00 -6.1602111e+00 -8.8364438e-01 - 7.3937693e+00 -6.6673671e+00 -8.6416699e-01 - 8.0033364e+00 -7.2567045e+00 -8.4066106e-01 - 8.4152643e+00 -7.6559471e+00 -7.4421212e-01 - 8.8283106e+00 -8.0542895e+00 -6.2829042e-01 - 8.8261038e+00 -8.0519396e+00 -4.2223844e-01 - 8.8569818e+00 -8.0819689e+00 -2.2200238e-01 - 8.8566429e+00 -8.0817979e+00 -1.7156057e-02 - 8.8458704e+00 -8.0719549e+00 1.8797843e-01 - 8.8408368e+00 -8.0665362e+00 3.9179389e-01 - 2.7416574e+01 -2.6033520e+01 -3.0770783e-01 - 2.7328702e+01 -2.5947456e+01 3.4840304e-01 - 8.8095333e+00 -8.0364254e+00 9.9995351e-01 - 8.8082379e+00 -8.0353448e+00 1.2017572e+00 - 9.0265428e+00 -8.2466087e+00 1.4141817e+00 - 9.6235395e+00 -8.8238816e+00 1.6651513e+00 - 9.6204331e+00 -8.8206830e+00 1.8871867e+00 - 9.6153925e+00 -8.8163518e+00 2.1094786e+00 - 9.6141689e+00 -8.8152138e+00 2.3327054e+00 - 2.8998693e+01 -2.7562799e+01 8.7064996e+00 - 2.9094632e+01 -2.7655746e+01 9.4555112e+00 - 2.9733409e+01 -2.8273832e+01 1.0389176e+01 - 3.0580292e+01 -2.9092621e+01 1.3793894e+01 - 3.0764272e+01 -2.9270843e+01 1.5497241e+01 - 3.1274550e+01 -2.9764089e+01 1.7434385e+01 - 3.6261723e+01 -3.4588425e+01 2.1100942e+01 - 4.9190334e+00 -4.2743239e+00 4.8418293e+00 - 4.8397922e+00 -4.1973787e+00 4.9213250e+00 - 4.6950325e+00 -4.0574764e+00 4.9366438e+00 - 4.5977056e+00 -3.9635874e+00 4.9919864e+00 - 4.3200481e+00 -3.6945043e+00 4.8616805e+00 - 4.2482986e+00 -3.6255979e+00 4.9298121e+00 - 4.4253867e+00 -3.7961016e+00 5.2664358e+00 - 4.1694071e+00 -3.5494682e+00 5.1346004e+00 - 3.9352861e+00 -3.3228075e+00 5.0109243e+00 - 3.9879565e+00 -3.3738559e+00 5.2183704e+00 - 3.9666124e+00 -3.3523497e+00 5.3425957e+00 - 3.9271458e+00 -3.3147094e+00 5.4465127e+00 - 3.7470791e+00 -3.1405015e+00 5.3624364e+00 - 3.7522889e+00 -3.1457582e+00 5.5253643e+00 - 3.7499035e+00 -3.1438039e+00 5.6828770e+00 - 3.6809990e+00 -3.0773043e+00 5.7464039e+00 - 3.6454043e+00 -3.0424188e+00 5.8601449e+00 - 3.4234214e+00 -2.8273673e+00 5.6790952e+00 - 3.3554626e+00 -2.7613469e+00 5.7341294e+00 - 3.2817568e+00 -2.6904520e+00 5.7793468e+00 - 2.9511412e+00 -2.3710741e+00 5.3655398e+00 - 2.9611965e+00 -2.3798573e+00 5.5441308e+00 - 2.7179914e+00 -2.1452049e+00 5.2473034e+00 - 2.5032867e+00 -1.9378353e+00 4.9810822e+00 - 2.4133275e+00 -1.8498806e+00 4.9461605e+00 - 2.2966112e+00 -1.7373029e+00 4.8494143e+00 - 2.2866018e+00 -1.7273360e+00 4.9772427e+00 - 2.2689215e+00 -1.7112781e+00 5.0972085e+00 - 2.2389534e+00 -1.6817137e+00 5.1914530e+00 - 2.4578436e+00 -1.8936722e+00 5.9153389e+00 - 2.0988093e+00 -1.5471754e+00 5.1851809e+00 - 2.1051163e+00 -1.5527326e+00 5.3837607e+00 - 1.9615464e+00 -1.4142392e+00 5.1703595e+00 - 2.3680493e+00 -1.8063773e+00 6.5737038e+00 - 1.9618511e+00 -1.4135667e+00 5.5677146e+00 - 2.0446986e+00 -1.4942706e+00 6.0627905e+00 - 1.8379953e+00 -1.2937460e+00 5.6080246e+00 - 1.6970894e+00 -1.1580747e+00 5.3410799e+00 - 1.6135707e+00 -1.0769746e+00 5.2567953e+00 - 1.5481982e+00 -1.0138829e+00 5.2358642e+00 - 1.5039108e+00 -9.7097179e-01 5.2987006e+00 - 1.4241013e+00 -8.9444126e-01 5.2077100e+00 - 1.3913457e+00 -8.6252594e-01 5.3256850e+00 - 1.3278698e+00 -8.0086745e-01 5.2984050e+00 - 1.2874835e+00 -7.6150780e-01 5.3954345e+00 - 1.2287975e+00 -7.0485233e-01 5.3944038e+00 - 1.3844155e+00 -8.5550177e-01 6.7905885e+00 - 1.3251681e+00 -7.9787333e-01 6.9093611e+00 - 1.2484878e+00 -7.2405892e-01 6.9087965e+00 - 1.1747310e+00 -6.5253976e-01 6.9261491e+00 - 1.0151290e+00 -4.9839869e-01 6.0999199e+00 - 9.5476967e-01 -4.3904071e-01 6.1512309e+00 - 9.4658234e-01 -4.3256419e-01 6.9174073e+00 - 8.7084221e-01 -3.5927334e-01 6.9074511e+00 - 9.4504079e-01 -4.3074291e-01 9.8583544e+00 - 8.3749178e-01 -3.2703931e-01 9.9776554e+00 - 7.2486218e-01 -2.1807756e-01 9.9745778e+00 - 6.1841214e-01 -1.1435945e-01 1.0438596e+01 - 1.8165578e+00 -1.3504329e+00 -9.8748528e-01 - 1.8599609e+00 -1.3949527e+00 -9.8285379e-01 - 1.8986689e+00 -1.4347439e+00 -9.6951558e-01 - 1.9477353e+00 -1.4848082e+00 -9.6865048e-01 - 1.9967525e+00 -1.5357808e+00 -9.6593806e-01 - 2.0524250e+00 -1.5924076e+00 -9.6799398e-01 - 2.1080508e+00 -1.6499231e+00 -9.6780306e-01 - 2.1636902e+00 -1.7073301e+00 -9.6541485e-01 - 2.2203407e+00 -1.7646941e+00 -9.6093242e-01 - 2.2882426e+00 -1.8342624e+00 -9.6633027e-01 - 2.3458004e+00 -1.8934443e+00 -9.5695783e-01 - 2.4146730e+00 -1.9638089e+00 -9.5701584e-01 - 2.4844412e+00 -2.0360849e+00 -9.5408152e-01 - 2.5655316e+00 -2.1194846e+00 -9.5937912e-01 - 2.6306821e+00 -2.1858972e+00 -9.4499107e-01 - 2.7136885e+00 -2.2710914e+00 -9.4370395e-01 - 2.8089046e+00 -2.3693847e+00 -9.4895480e-01 - 2.8872995e+00 -2.4486662e+00 -9.3521520e-01 - 2.9966916e+00 -2.5609350e+00 -9.4206689e-01 - 3.1060538e+00 -2.6739594e+00 -9.4397508e-01 - 3.2107860e+00 -2.7812189e+00 -9.3642708e-01 - 3.3287410e+00 -2.9015197e+00 -9.3302321e-01 - 3.4654664e+00 -3.0423609e+00 -9.3663174e-01 - 3.6041059e+00 -3.1850114e+00 -9.3395518e-01 - 3.7559861e+00 -3.3405603e+00 -9.3252632e-01 - 3.9153883e+00 -3.5044207e+00 -9.2773020e-01 - 4.0955807e+00 -3.6887551e+00 -9.2615753e-01 - 4.2899100e+00 -3.8878944e+00 -9.2274034e-01 - 4.4973841e+00 -4.1017291e+00 -9.1647668e-01 - 4.7398214e+00 -4.3500380e+00 -9.1553669e-01 - 5.0039655e+00 -4.6205649e+00 -9.1143201e-01 - 5.2822798e+00 -4.9056307e+00 -9.0008947e-01 - 5.6152400e+00 -5.2474896e+00 -8.9539399e-01 - 5.9698831e+00 -5.6122727e+00 -8.8159154e-01 - 6.3943704e+00 -6.0476928e+00 -8.7214498e-01 - 6.8877341e+00 -6.5534478e+00 -8.6215718e-01 - 7.4583757e+00 -7.1398889e+00 -8.4786532e-01 - 8.1065104e+00 -7.8037493e+00 -8.2382496e-01 - 8.4794128e+00 -8.1866675e+00 -7.0871667e-01 - 9.8836858e+00 -9.6276538e+00 -7.6995637e-01 - 1.1318366e+01 -1.1099334e+01 -7.6599091e-01 - 1.3484849e+01 -1.3322824e+01 -7.9133369e-01 - 2.9692552e+01 -2.9951991e+01 -9.5425423e-02 - 3.0567234e+01 -3.0848754e+01 6.2385022e-01 - 3.0504388e+01 -3.0784555e+01 1.3750012e+00 - 9.2162308e+00 -8.9426609e+00 1.5451664e+00 - 9.2149782e+00 -8.9417545e+00 1.7636990e+00 - 9.2184792e+00 -8.9451086e+00 1.9830131e+00 - 9.2257394e+00 -8.9526332e+00 2.2037113e+00 - 2.8946712e+01 -2.9186392e+01 5.6433321e+00 - 2.8600234e+01 -2.8830708e+01 7.7369268e+00 - 2.7978386e+01 -2.8193596e+01 8.2964620e+00 - 2.9759144e+01 -3.0020337e+01 9.5287016e+00 - 2.8667728e+01 -2.8900486e+01 1.2953883e+01 - 2.9014299e+01 -2.9256452e+01 1.4669099e+01 - 3.0198428e+01 -3.0472165e+01 1.6067619e+01 - 3.0200024e+01 -3.0473550e+01 1.6909516e+01 - 3.1144573e+01 -3.1442743e+01 1.8294750e+01 - 4.5295253e+00 -4.1344719e+00 4.1348686e+00 - 4.4240049e+00 -4.0265052e+00 4.1809568e+00 - 4.4329341e+00 -4.0352194e+00 4.3192016e+00 - 4.4569715e+00 -4.0600442e+00 4.4745681e+00 - 4.4611711e+00 -4.0643058e+00 4.6159265e+00 - 4.6498580e+00 -4.2574330e+00 4.9352719e+00 - 4.2784625e+00 -3.8775142e+00 4.7212802e+00 - 4.1700905e+00 -3.7661617e+00 4.7512993e+00 - 4.2084078e+00 -3.8046484e+00 4.9316817e+00 - 4.2097684e+00 -3.8064539e+00 5.0786435e+00 - 4.2575486e+00 -3.8553637e+00 5.2828104e+00 - 4.0384018e+00 -3.6306283e+00 5.1789613e+00 - 3.8220692e+00 -3.4085460e+00 5.0655137e+00 - 3.7931899e+00 -3.3783177e+00 5.1744368e+00 - 3.7775012e+00 -3.3629343e+00 5.3034348e+00 - 3.6283190e+00 -3.2099365e+00 5.2539557e+00 - 3.6259334e+00 -3.2074681e+00 5.4016309e+00 - 3.5231609e+00 -3.1016534e+00 5.4077589e+00 - 3.4061061e+00 -2.9821964e+00 5.3884715e+00 - 3.4189537e+00 -2.9943242e+00 5.5637059e+00 - 3.3625346e+00 -2.9371741e+00 5.6359272e+00 - 3.3099651e+00 -2.8829562e+00 5.7143769e+00 - 3.3057334e+00 -2.8786506e+00 5.8765909e+00 - 3.1801228e+00 -2.7500743e+00 5.8285715e+00 - 3.1341892e+00 -2.7026965e+00 5.9187317e+00 - 2.9288979e+00 -2.4914038e+00 5.7025209e+00 - 2.5953707e+00 -2.1497357e+00 5.2089353e+00 - 2.5075458e+00 -2.0602842e+00 5.1865421e+00 - 2.3030159e+00 -1.8493965e+00 4.9025630e+00 - 2.2626510e+00 -1.8078029e+00 4.9638382e+00 - 2.2212837e+00 -1.7661834e+00 5.0244175e+00 - 2.1647561e+00 -1.7083531e+00 5.0496480e+00 - 2.1804876e+00 -1.7241247e+00 5.2559825e+00 - 2.1420924e+00 -1.6838971e+00 5.3325317e+00 - 2.0503685e+00 -1.5903602e+00 5.2665075e+00 - 1.9538857e+00 -1.4915740e+00 5.1792277e+00 - 2.5102921e+00 -2.0627065e+00 7.0382284e+00 - 2.1731599e+00 -1.7159364e+00 6.2594619e+00 - 2.0299998e+00 -1.5705580e+00 6.0438162e+00 - 1.9898227e+00 -1.5284949e+00 6.1551288e+00 - 1.6863829e+00 -1.2178021e+00 5.3170589e+00 - 1.5993062e+00 -1.1283448e+00 5.2149625e+00 - 1.5532802e+00 -1.0801588e+00 5.2607288e+00 - 1.4785358e+00 -1.0038534e+00 5.1915449e+00 - 1.4276863e+00 -9.5144942e-01 5.2154060e+00 - 1.3902489e+00 -9.1263569e-01 5.3050351e+00 - 1.3393847e+00 -8.6086407e-01 5.3363367e+00 - 1.6060022e+00 -1.1349627e+00 7.1283072e+00 - 1.4998878e+00 -1.0260701e+00 6.9703017e+00 - 1.4061827e+00 -9.2971354e-01 6.8576933e+00 - 1.3413159e+00 -8.6309610e-01 6.9284985e+00 - 1.2696937e+00 -7.8956106e-01 6.9486420e+00 - 1.2164878e+00 -7.3497121e-01 7.1347101e+00 - 1.1089859e+00 -6.2551815e-01 6.8450231e+00 - 9.6809998e-01 -4.8070535e-01 6.0960333e+00 - 9.7353137e-01 -4.8616864e-01 6.9614364e+00 - 9.0585154e-01 -4.1688819e-01 7.0420398e+00 - 8.2134813e-01 -3.3046313e-01 6.8618807e+00 - 8.7849920e-01 -3.8937099e-01 9.8833572e+00 - 7.7836826e-01 -2.8574141e-01 1.0131275e+01 - 6.6046067e-01 -1.6484729e-01 9.8169579e+00 - 5.5078131e-01 -5.2079795e-02 9.4096760e+00 - 1.7602095e+00 -1.3705505e+00 -9.9655793e-01 - 1.7968474e+00 -1.4113262e+00 -9.8536110e-01 - 1.8391971e+00 -1.4567430e+00 -9.7987786e-01 - 1.8871393e+00 -1.5087851e+00 -9.7980938e-01 - 1.9303870e+00 -1.5560938e+00 -9.7093430e-01 - 1.9783514e+00 -1.6079585e+00 -9.6727025e-01 - 2.0319139e+00 -1.6664042e+00 -9.6812207e-01 - 2.0864266e+00 -1.7258087e+00 -9.6692998e-01 - 2.1353057e+00 -1.7794322e+00 -9.5717742e-01 - 2.2011425e+00 -1.8499455e+00 -9.6391763e-01 - 2.2668749e+00 -1.9223247e+00 -9.6796195e-01 - 2.3177314e+00 -1.9767359e+00 -9.5147446e-01 - 2.3844344e+00 -2.0499114e+00 -9.5017894e-01 - 2.4577448e+00 -2.1296395e+00 -9.5160469e-01 - 2.5264202e+00 -2.2036421e+00 -9.4437326e-01 - 2.6006465e+00 -2.2851191e+00 -9.3951073e-01 - 2.6861422e+00 -2.3786575e+00 -9.4163207e-01 - 2.7735968e+00 -2.4731315e+00 -9.4001477e-01 - 2.8676096e+00 -2.5750664e+00 -9.3927141e-01 - 2.9671855e+00 -2.6843772e+00 -9.3889941e-01 - 3.0743836e+00 -2.8001681e+00 -9.3855518e-01 - 3.1758928e+00 -2.9111355e+00 -9.2880191e-01 - 3.3027638e+00 -3.0493241e+00 -9.3137910e-01 - 3.4296718e+00 -3.1872170e+00 -9.2796370e-01 - 3.5828359e+00 -3.3542524e+00 -9.3408616e-01 - 3.7369824e+00 -3.5219905e+00 -9.3297113e-01 - 3.8987142e+00 -3.6970184e+00 -9.2803900e-01 - 4.0669761e+00 -3.8802480e+00 -9.1873768e-01 - 4.2746703e+00 -4.1065500e+00 -9.2087150e-01 - 4.4899099e+00 -4.3409762e+00 -9.1584276e-01 - 4.7259092e+00 -4.5966369e+00 -9.0919383e-01 - 4.9815599e+00 -4.8753818e+00 -8.9912455e-01 - 5.2841810e+00 -5.2053824e+00 -8.9452637e-01 - 5.6150862e+00 -5.5649092e+00 -8.8454124e-01 - 5.9986116e+00 -5.9818588e+00 -8.7615344e-01 - 6.4375976e+00 -6.4591915e+00 -8.6492916e-01 - 6.9630122e+00 -7.0311594e+00 -8.5657884e-01 - 7.5636680e+00 -7.6845317e+00 -8.4067252e-01 - 8.2395392e+00 -8.4200295e+00 -8.1156753e-01 - 8.7492662e+00 -8.9745427e+00 -7.1326950e-01 - 1.0191867e+01 -1.0544440e+01 -7.5857475e-01 - 1.1631937e+01 -1.2110461e+01 -7.2896296e-01 - 2.8404566e+01 -3.0357745e+01 -4.4011940e-01 - 2.9290151e+01 -3.1321454e+01 2.5726023e-01 - 2.9031100e+01 -3.1039199e+01 9.9986732e-01 - 3.2838946e+01 -3.5181967e+01 5.1805505e+00 - 2.7192014e+01 -2.9039393e+01 5.8428540e+00 - 2.7676895e+01 -2.9566002e+01 7.3603810e+00 - 2.9336866e+01 -3.1372214e+01 9.2827050e+00 - 2.8548200e+01 -3.0515237e+01 1.2105628e+01 - 2.8198624e+01 -3.0133776e+01 1.2736268e+01 - 2.8978858e+01 -3.0983354e+01 1.4673603e+01 - 2.9472382e+01 -3.1520144e+01 1.6582061e+01 - 3.0193300e+01 -3.2304476e+01 1.7842813e+01 - 4.3651037e+00 -4.2042526e+00 4.1657583e+00 - 4.3324442e+00 -4.1700214e+00 4.2699017e+00 - 4.2814578e+00 -4.1137690e+00 4.4921187e+00 - 4.1998208e+00 -4.0256693e+00 4.5509541e+00 - 4.1804907e+00 -4.0036271e+00 4.6682320e+00 - 4.1365793e+00 -3.9561633e+00 4.7625807e+00 - 4.0803988e+00 -3.8955593e+00 4.8440417e+00 - 4.0449845e+00 -3.8571687e+00 4.9477966e+00 - 3.9284790e+00 -3.7302273e+00 4.9586743e+00 - 4.0704027e+00 -3.8846696e+00 5.2729959e+00 - 3.6935242e+00 -3.4742576e+00 4.9595129e+00 - 3.7024893e+00 -3.4832002e+00 5.1133880e+00 - 3.6830684e+00 -3.4629154e+00 5.2355591e+00 - 3.6033142e+00 -3.3758432e+00 5.2760108e+00 - 3.4593459e+00 -3.2193027e+00 5.2234212e+00 - 3.4522206e+00 -3.2119463e+00 5.3627746e+00 - 3.3299428e+00 -3.0787851e+00 5.3303280e+00 - 3.3237931e+00 -3.0721855e+00 5.4758202e+00 - 3.3157736e+00 -3.0634220e+00 5.6222185e+00 - 3.1943795e+00 -2.9317517e+00 5.5810290e+00 - 3.2619755e+00 -3.0050108e+00 5.8642709e+00 - 3.1443505e+00 -2.8774322e+00 5.8260635e+00 - 3.1032807e+00 -2.8329189e+00 5.9250458e+00 - 2.9469160e+00 -2.6621916e+00 5.7997440e+00 - 2.7630409e+00 -2.4622445e+00 5.6032844e+00 - 2.5062682e+00 -2.1831822e+00 5.2349646e+00 - 2.3837757e+00 -2.0496740e+00 5.1285109e+00 - 2.2905615e+00 -1.9483626e+00 5.0758292e+00 - 2.2569943e+00 -1.9112852e+00 5.1554076e+00 - 2.1552089e+00 -1.8009777e+00 5.0714971e+00 - 2.1576014e+00 -1.8036059e+00 5.2435240e+00 - 2.0880291e+00 -1.7277016e+00 5.2331005e+00 - 2.3103202e+00 -1.9702032e+00 6.0327637e+00 - 2.2636377e+00 -1.9181941e+00 6.1142898e+00 - 2.2168240e+00 -1.8687817e+00 6.2039545e+00 - 2.2356274e+00 -1.8882417e+00 6.5012641e+00 - 2.0408160e+00 -1.6769675e+00 6.1157808e+00 - 1.7690364e+00 -1.3802538e+00 5.4183779e+00 - 1.7516145e+00 -1.3621316e+00 5.5801920e+00 - 1.6220481e+00 -1.2216724e+00 5.3224529e+00 - 1.5438822e+00 -1.1348879e+00 5.2379550e+00 - 1.4979133e+00 -1.0857295e+00 5.2831722e+00 - 1.4196002e+00 -1.0006367e+00 5.1846412e+00 - 1.4508968e+00 -1.0350573e+00 5.5997561e+00 - 1.6895401e+00 -1.2942584e+00 7.1327457e+00 - 1.6612393e+00 -1.2630177e+00 7.4040157e+00 - 1.5373320e+00 -1.1286517e+00 7.1516484e+00 - 1.4621766e+00 -1.0465624e+00 7.1579753e+00 - 1.3668361e+00 -9.4307497e-01 7.0254010e+00 - 1.2839691e+00 -8.5212533e-01 6.9584485e+00 - 1.2173337e+00 -7.8098849e-01 7.0171270e+00 - 1.0386650e+00 -5.8568082e-01 6.0272853e+00 - 1.0037359e+00 -5.4805494e-01 6.2978807e+00 - 9.9148647e-01 -5.3467081e-01 6.9155587e+00 - 9.2393018e-01 -4.6182448e-01 6.9671499e+00 - 8.5054648e-01 -3.8113533e-01 6.9272778e+00 - 9.2651586e-01 -4.6432711e-01 1.0027932e+01 - 8.2031590e-01 -3.4859665e-01 1.0027585e+01 - 7.1316278e-01 -2.3244610e-01 1.0034532e+01 - 6.1594934e-01 -1.2643285e-01 1.0838500e+01 - 1.6982823e+00 -1.3839345e+00 -9.9801855e-01 - 1.7302115e+00 -1.4200900e+00 -9.8031228e-01 - 1.7751432e+00 -1.4720788e+00 -9.8283105e-01 - 1.8116730e+00 -1.5147499e+00 -9.6953758e-01 - 1.8668549e+00 -1.5789072e+00 -9.8243283e-01 - 1.9090491e+00 -1.6271129e+00 -9.7270601e-01 - 1.9559011e+00 -1.6808618e+00 -9.6794092e-01 - 2.0027039e+00 -1.7355191e+00 -9.6132850e-01 - 2.0551663e+00 -1.7957504e+00 -9.5908174e-01 - 2.1234671e+00 -1.8748099e+00 -9.7332535e-01 - 2.1768362e+00 -1.9368640e+00 -9.6628846e-01 - 2.2255679e+00 -1.9932123e+00 -9.5099391e-01 - 2.2902051e+00 -2.0673377e+00 -9.5114063e-01 - 2.3613888e+00 -2.1490177e+00 -9.5405895e-01 - 2.4269395e+00 -2.2249117e+00 -9.4831691e-01 - 2.4981012e+00 -2.3072831e+00 -9.4499332e-01 - 2.5758144e+00 -2.3971697e+00 -9.4364230e-01 - 2.6656765e+00 -2.5011572e+00 -9.4887960e-01 - 2.7443726e+00 -2.5917416e+00 -9.4019121e-01 - 2.8474139e+00 -2.7096344e+00 -9.4682641e-01 - 2.9381712e+00 -2.8160525e+00 -9.3933378e-01 - 3.0365494e+00 -2.9289606e+00 -9.3206866e-01 - 3.1470932e+00 -3.0558366e+00 -9.2869519e-01 - 3.2818857e+00 -3.2118229e+00 -9.3665101e-01 - 3.4110575e+00 -3.3619247e+00 -9.3394894e-01 - 3.5543471e+00 -3.5269842e+00 -9.3249853e-01 - 3.7032220e+00 -3.6992422e+00 -9.2782392e-01 - 3.8717691e+00 -3.8939028e+00 -9.2617061e-01 - 4.0412457e+00 -4.0902039e+00 -9.1603174e-01 - 4.2436155e+00 -4.3219637e+00 -9.1335792e-01 - 4.4767168e+00 -4.5919289e+00 -9.1549723e-01 - 4.7173753e+00 -4.8699247e+00 -9.0857630e-01 - 4.9852355e+00 -5.1785754e+00 -9.0011090e-01 - 5.2914114e+00 -5.5327312e+00 -8.9284127e-01 - 5.6369792e+00 -5.9313129e+00 -8.8392374e-01 - 6.0404914e+00 -6.3986661e+00 -8.7647706e-01 - 6.4974808e+00 -6.9261781e+00 -8.6409014e-01 - 7.0462899e+00 -7.5586231e+00 -8.5340163e-01 - 7.7055058e+00 -8.3200711e+00 -8.4193722e-01 - 8.4761795e+00 -9.2101588e+00 -8.2111070e-01 - 9.3199719e+00 -1.0184601e+01 -7.7394654e-01 - 1.0627141e+01 -1.1694354e+01 -7.6261015e-01 - 1.2854594e+01 -1.4266030e+01 -8.1731082e-01 - 1.5712269e+01 -1.7566743e+01 -8.2892615e-01 - 2.9326037e+01 -3.3287946e+01 -1.5328361e-01 - 3.2709557e+01 -3.7195017e+01 3.1480189e+00 - 2.7322703e+01 -3.0974811e+01 5.6681857e+00 - 2.9069999e+01 -3.2992232e+01 1.2286669e+01 - 2.8129796e+01 -3.1906089e+01 1.3501954e+01 - 2.9080787e+01 -3.3005338e+01 1.5608245e+01 - 4.4711875e+00 -4.5861729e+00 4.1583113e+00 - 4.3599335e+00 -4.4569357e+00 4.2015834e+00 - 4.2316811e+00 -4.3095864e+00 4.2253439e+00 - 4.1776322e+00 -4.2469911e+00 4.3090966e+00 - 4.1216962e+00 -4.1823697e+00 4.3909587e+00 - 4.1709125e+00 -4.2394876e+00 4.5729938e+00 - 4.1028328e+00 -4.1596926e+00 4.6426682e+00 - 4.1201400e+00 -4.1799783e+00 4.8004555e+00 - 4.0228573e+00 -4.0678995e+00 4.8383802e+00 - 3.8146793e+00 -3.8281442e+00 4.7473393e+00 - 3.6986063e+00 -3.6936214e+00 4.7498304e+00 - 3.6294297e+00 -3.6145542e+00 4.8035277e+00 - 3.6110812e+00 -3.5927054e+00 4.9181057e+00 - 3.5513384e+00 -3.5237787e+00 4.9810559e+00 - 3.6128976e+00 -3.5944789e+00 5.2075389e+00 - 3.6415376e+00 -3.6278658e+00 5.3980422e+00 - 3.5959660e+00 -3.5745014e+00 5.4880050e+00 - 3.4364975e+00 -3.3912718e+00 5.4086630e+00 - 3.3118051e+00 -3.2481371e+00 5.3721349e+00 - 3.2483687e+00 -3.1734844e+00 5.4247129e+00 - 3.2017373e+00 -3.1205522e+00 5.5046912e+00 - 3.1806322e+00 -3.0950731e+00 5.6284187e+00 - 3.1311782e+00 -3.0390377e+00 5.7068596e+00 - 3.1100586e+00 -3.0141909e+00 5.8380274e+00 - 3.0135427e+00 -2.9035060e+00 5.8286578e+00 - 2.9104632e+00 -2.7843713e+00 5.7996881e+00 - 2.8393950e+00 -2.7022842e+00 5.8311208e+00 - 2.7354049e+00 -2.5808421e+00 5.7869243e+00 - 2.4427760e+00 -2.2434117e+00 5.3183262e+00 - 2.3527519e+00 -2.1396866e+00 5.2777209e+00 - 2.1910175e+00 -1.9533330e+00 5.0566642e+00 - 2.3368238e+00 -2.1207585e+00 5.5786577e+00 - 2.0816474e+00 -1.8261465e+00 5.1013274e+00 - 2.0632707e+00 -1.8050385e+00 5.2211486e+00 - 2.0147054e+00 -1.7489072e+00 5.2622332e+00 - 2.2259128e+00 -1.9926047e+00 6.0647272e+00 - 2.1613229e+00 -1.9191332e+00 6.0921395e+00 - 2.1119413e+00 -1.8614882e+00 6.1626909e+00 - 1.7456740e+00 -1.4390000e+00 5.1767181e+00 - 1.7680617e+00 -1.4645438e+00 5.4568841e+00 - 1.6750132e+00 -1.3567510e+00 5.3329943e+00 - 1.6605165e+00 -1.3403952e+00 5.5031878e+00 - 1.5816094e+00 -1.2494343e+00 5.4210916e+00 - 1.5045596e+00 -1.1607360e+00 5.3360919e+00 - 1.4550253e+00 -1.1032796e+00 5.3622989e+00 - 1.3855655e+00 -1.0223509e+00 5.2916529e+00 - 1.3198409e+00 -9.4629889e-01 5.2283331e+00 - 1.6328776e+00 -1.3093659e+00 7.2442769e+00 - 1.5580467e+00 -1.2221047e+00 7.2541513e+00 - 1.4898258e+00 -1.1434379e+00 7.3009540e+00 - 1.3040428e+00 -9.2903951e-01 6.5453045e+00 - 1.3084338e+00 -9.3404927e-01 7.0754782e+00 - 1.2487944e+00 -8.6532808e-01 7.1747826e+00 - 1.0660599e+00 -6.5355820e-01 6.1681343e+00 - 1.0119479e+00 -5.9095129e-01 6.2318621e+00 - 9.5689076e-01 -5.2786024e-01 6.3041824e+00 - 9.4970079e-01 -5.1938762e-01 7.0310057e+00 - 8.8338127e-01 -4.4314777e-01 7.0918335e+00 - 8.0517061e-01 -3.5259507e-01 6.9216445e+00 - 8.5821083e-01 -4.1426852e-01 9.9632074e+00 - 7.6036936e-01 -3.0119712e-01 1.0121335e+01 - 6.5199931e-01 -1.7590378e-01 9.8869411e+00 - 5.4760779e-01 -5.5907725e-02 9.4297089e+00 - 1.6730476e+00 -1.4371415e+00 -9.8923076e-01 - 1.7075675e+00 -1.4798000e+00 -9.7812822e-01 - 1.7513849e+00 -1.5336878e+00 -9.7984558e-01 - 1.7915661e+00 -1.5819057e+00 -9.7280906e-01 - 1.8363430e+00 -1.6366785e+00 -9.7098436e-01 - 1.8857186e+00 -1.6979816e+00 -9.7387210e-01 - 1.9314569e+00 -1.7536246e+00 -9.6820572e-01 - 1.9864448e+00 -1.8213953e+00 -9.7331215e-01 - 2.0331463e+00 -1.8778937e+00 -9.6350445e-01 - 2.0890402e+00 -1.9474921e+00 -9.6392064e-01 - 2.1459478e+00 -2.0170278e+00 -9.6184309e-01 - 2.1982186e+00 -2.0808528e+00 -9.5140799e-01 - 2.2663377e+00 -2.1634272e+00 -9.5586524e-01 - 2.3241705e+00 -2.2346379e+00 -9.4600127e-01 - 2.3932043e+00 -2.3189710e+00 -9.4437000e-01 - 2.4733840e+00 -2.4173841e+00 -9.5012288e-01 - 2.5433369e+00 -2.5034415e+00 -9.4170395e-01 - 2.6300951e+00 -2.6091530e+00 -9.4503483e-01 - 2.7177570e+00 -2.7167118e+00 -9.4407496e-01 - 2.8053846e+00 -2.8250608e+00 -9.3887073e-01 - 2.9107696e+00 -2.9540078e+00 -9.4307276e-01 - 3.0171247e+00 -3.0837561e+00 -9.4203484e-01 - 3.1243902e+00 -3.2152976e+00 -9.3560753e-01 - 3.2493683e+00 -3.3683110e+00 -9.3604003e-01 - 3.3753227e+00 -3.5220764e+00 -9.3023380e-01 - 3.5133388e+00 -3.6916706e+00 -9.2552344e-01 - 3.6634837e+00 -3.8760426e+00 -9.2085986e-01 - 3.8387877e+00 -4.0913180e+00 -9.2213618e-01 - 4.0095399e+00 -4.2996887e+00 -9.1110945e-01 - 4.2277123e+00 -4.5678832e+00 -9.1594728e-01 - 4.4422843e+00 -4.8301220e+00 -9.0623839e-01 - 4.6931498e+00 -5.1379520e+00 -9.0191375e-01 - 4.9822646e+00 -5.4923333e+00 -8.9973411e-01 - 5.2854488e+00 -5.8630899e+00 -8.8702145e-01 - 5.6501164e+00 -6.3100947e+00 -8.8063912e-01 - 6.0474778e+00 -6.7967301e+00 -8.6499443e-01 - 6.5390136e+00 -7.3987499e+00 -8.5665469e-01 - 7.1191579e+00 -8.1093170e+00 -8.4591043e-01 - 7.8754758e+00 -9.0367639e+00 -8.4748245e-01 - 8.5452682e+00 -9.8576701e+00 -7.8839516e-01 - 9.5805370e+00 -1.1126640e+01 -7.6342831e-01 - 1.1045799e+01 -1.2920821e+01 -7.5295460e-01 - 1.6054126e+01 -1.9057489e+01 -7.2035480e-01 - 3.0780871e+01 -3.7101035e+01 9.9972976e-01 - 3.1280154e+01 -3.7713732e+01 2.6997343e+00 - 2.8222026e+01 -3.3966307e+01 1.2747356e+01 - 4.2287328e+00 -4.5686240e+00 4.1360140e+00 - 4.1113160e+00 -4.4246399e+00 4.1657809e+00 - 4.0976837e+00 -4.4078663e+00 4.2848855e+00 - 4.1691628e+00 -4.4954371e+00 4.4867081e+00 - 4.0816526e+00 -4.3882136e+00 4.5397304e+00 - 4.0315589e+00 -4.3266748e+00 4.6272153e+00 - 4.0267456e+00 -4.3215588e+00 4.9059367e+00 - 3.7679631e+00 -4.0044475e+00 4.7558238e+00 - 3.6560825e+00 -3.8670229e+00 4.7612497e+00 - 3.5834331e+00 -3.7789187e+00 4.8109182e+00 - 3.5024911e+00 -3.6780441e+00 4.8450896e+00 - 3.4054691e+00 -3.5602725e+00 4.8565996e+00 - 3.4059015e+00 -3.5604277e+00 4.9952757e+00 - 3.3801223e+00 -3.5285051e+00 5.1016931e+00 - 3.3711456e+00 -3.5183227e+00 5.2351114e+00 - 3.3238102e+00 -3.4603995e+00 5.3137465e+00 - 3.2624520e+00 -3.3846984e+00 5.3697642e+00 - 3.2357067e+00 -3.3524592e+00 5.4813785e+00 - 3.1602504e+00 -3.2600954e+00 5.5124315e+00 - 3.1101257e+00 -3.1982888e+00 5.5850851e+00 - 3.0637904e+00 -3.1404112e+00 5.6640166e+00 - 3.0069782e+00 -3.0726924e+00 5.7264075e+00 - 2.9512747e+00 -3.0031189e+00 5.7870981e+00 - 2.9367487e+00 -2.9859664e+00 5.9329224e+00 - 2.8632002e+00 -2.8949471e+00 5.9594243e+00 - 2.7219524e+00 -2.7229404e+00 5.8378709e+00 - 2.4549541e+00 -2.3948095e+00 5.4151295e+00 - 2.7522416e+00 -2.7589219e+00 6.2809033e+00 - 2.2934246e+00 -2.1977501e+00 5.3693603e+00 - 2.1680256e+00 -2.0439738e+00 5.2231770e+00 - 2.0688546e+00 -1.9231753e+00 5.1315239e+00 - 2.0017165e+00 -1.8397662e+00 5.1136064e+00 - 1.9767873e+00 -1.8101197e+00 5.2156253e+00 - 2.1684113e+00 -2.0433840e+00 5.9620569e+00 - 2.1614593e+00 -2.0361905e+00 6.1588881e+00 - 2.0735923e+00 -1.9292390e+00 6.1050942e+00 - 1.9989961e+00 -1.8364919e+00 6.0843592e+00 - 1.6594505e+00 -1.4205584e+00 5.1200713e+00 - 1.6166893e+00 -1.3678152e+00 5.1605864e+00 - 1.6436944e+00 -1.4018030e+00 5.4782862e+00 - 1.5896876e+00 -1.3347448e+00 5.4904304e+00 - 1.4788725e+00 -1.2002384e+00 5.2567986e+00 - 1.4275891e+00 -1.1375909e+00 5.2642375e+00 - 1.3631215e+00 -1.0574686e+00 5.2036128e+00 - 1.3127551e+00 -9.9604594e-01 5.2077022e+00 - 1.2861085e+00 -9.6301847e-01 5.3352967e+00 - 1.5404821e+00 -1.2747040e+00 7.1432142e+00 - 1.4525215e+00 -1.1669541e+00 7.0448266e+00 - 1.2987735e+00 -9.7931287e-01 6.4759283e+00 - 1.3059757e+00 -9.8700042e-01 6.9960041e+00 - 1.2274035e+00 -8.9078381e-01 6.9191534e+00 - 1.1353224e+00 -7.7865577e-01 6.7020290e+00 - 1.0296619e+00 -6.4911647e-01 6.2939951e+00 - 9.5647801e-01 -5.5909440e-01 6.1394205e+00 - 9.6166300e-01 -5.6549518e-01 6.9452979e+00 - 8.9446579e-01 -4.8410631e-01 6.9472047e+00 - 8.3319341e-01 -4.0823451e-01 7.0269428e+00 - 9.0599234e-01 -4.9677692e-01 1.0177542e+01 - 8.0639770e-01 -3.7596830e-01 1.0267215e+01 - 7.0165284e-01 -2.4736359e-01 1.0164398e+01 - 6.0853961e-01 -1.3351237e-01 1.0848507e+01 - 1.6103649e+00 -1.4464624e+00 -9.9058677e-01 - 1.6448196e+00 -1.4901573e+00 -9.8023369e-01 - 1.6865749e+00 -1.5449655e+00 -9.8279403e-01 - 1.7209873e+00 -1.5895145e+00 -9.6949497e-01 - 1.7637009e+00 -1.6452175e+00 -9.6871301e-01 - 1.8064268e+00 -1.7008220e+00 -9.6593351e-01 - 1.8546887e+00 -1.7640192e+00 -9.6791996e-01 - 1.8983760e+00 -1.8204939e+00 -9.6129877e-01 - 1.9568390e+00 -1.8967678e+00 -9.7181437e-01 - 2.0014299e+00 -1.9550899e+00 -9.6090245e-01 - 2.0506834e+00 -2.0189158e+00 -9.5415326e-01 - 2.1110692e+00 -2.0969301e+00 -9.5698549e-01 - 2.1612300e+00 -2.1625739e+00 -9.4534629e-01 - 2.2261814e+00 -2.2478987e+00 -9.4844684e-01 - 2.2930886e+00 -2.3341837e+00 -9.4830814e-01 - 2.3599547e+00 -2.4213128e+00 -9.4502371e-01 - 2.4268412e+00 -2.5082795e+00 -9.3844335e-01 - 2.5206013e+00 -2.6300693e+00 -9.5404039e-01 - 2.5884099e+00 -2.7187355e+00 -9.4017299e-01 - 2.6673115e+00 -2.8224196e+00 -9.3244167e-01 - 2.7695035e+00 -2.9543190e+00 -9.3938194e-01 - 2.8605320e+00 -3.0727955e+00 -9.3199703e-01 - 2.9682050e+00 -3.2137593e+00 -9.3301721e-01 - 3.0879913e+00 -3.3696239e+00 -9.3658108e-01 - 3.1976117e+00 -3.5121310e+00 -9.2592283e-01 - 3.3359745e+00 -3.6921494e+00 -9.2871029e-01 - 3.4697172e+00 -3.8663240e+00 -9.2044354e-01 - 3.6211327e+00 -4.0628049e+00 -9.1569110e-01 - 3.7901111e+00 -4.2835023e+00 -9.1265598e-01 - 3.9711740e+00 -4.5198462e+00 -9.0702130e-01 - 4.1829667e+00 -4.7944104e+00 -9.0649937e-01 - 4.3956472e+00 -5.0714642e+00 -8.9444603e-01 - 4.6380199e+00 -5.3875073e+00 -8.8405691e-01 - 4.9286858e+00 -5.7659821e+00 -8.8039799e-01 - 5.2500195e+00 -6.1842031e+00 -8.7226444e-01 - 5.6085264e+00 -6.6505689e+00 -8.5928212e-01 - 6.0394207e+00 -7.2117748e+00 -8.5017835e-01 - 6.5427405e+00 -7.8675153e+00 -8.3876079e-01 - 7.1501112e+00 -8.6579221e+00 -8.2714983e-01 - 7.9338905e+00 -9.6780719e+00 -8.2401812e-01 - 8.6769248e+00 -1.0645956e+01 -7.6734417e-01 - 9.8804696e+00 -1.2212579e+01 -7.5476547e-01 - 1.0965383e+01 -1.3625237e+01 -6.5433250e-01 - 2.9192606e+01 -3.7356286e+01 -2.3372400e-01 - 3.0053678e+01 -3.8477461e+01 1.4230480e+00 - 3.0075699e+01 -3.8505855e+01 2.2710571e+00 - 4.1264808e+00 -4.7215482e+00 4.5070362e+00 - 4.0365690e+00 -4.6042477e+00 4.5580744e+00 - 3.6340372e+00 -4.0799791e+00 4.4053384e+00 - 3.5421624e+00 -3.9607444e+00 4.4323638e+00 - 3.4801181e+00 -3.8799093e+00 4.4899348e+00 - 3.4870516e+00 -3.8884978e+00 4.6282858e+00 - 3.4957861e+00 -3.9008303e+00 4.7742196e+00 - 3.5073819e+00 -3.9159558e+00 4.9279829e+00 - 3.3856805e+00 -3.7572584e+00 4.9054869e+00 - 3.2322051e+00 -3.5580694e+00 4.8316285e+00 - 3.2503662e+00 -3.5811157e+00 4.9954540e+00 - 3.3515144e+00 -3.7130191e+00 5.2898921e+00 - 3.2698869e+00 -3.6064916e+00 5.3158791e+00 - 3.2451515e+00 -3.5742649e+00 5.4296842e+00 - 3.1812422e+00 -3.4907122e+00 5.4791228e+00 - 3.1033008e+00 -3.3894556e+00 5.5044459e+00 - 3.1578876e+00 -3.4611617e+00 5.7627608e+00 - 3.1397883e+00 -3.4362893e+00 5.8981139e+00 - 2.9954676e+00 -3.2499867e+00 5.7981017e+00 - 2.9250096e+00 -3.1578660e+00 5.8303373e+00 - 2.8545349e+00 -3.0658784e+00 5.8598763e+00 - 2.7803064e+00 -2.9691617e+00 5.8790926e+00 - 2.7967408e+00 -2.9904483e+00 6.0964081e+00 - 2.4130213e+00 -2.4911133e+00 5.4043193e+00 - 2.3761226e+00 -2.4428375e+00 5.4831656e+00 - 2.3887797e+00 -2.4595823e+00 5.6863632e+00 - 2.3425811e+00 -2.3985496e+00 5.7482174e+00 - 2.8354285e+00 -3.0413612e+00 7.2583110e+00 - 1.9682215e+00 -1.9120077e+00 5.0926462e+00 - 1.9425453e+00 -1.8777151e+00 5.1863305e+00 - 1.8746399e+00 -1.7898223e+00 5.1567825e+00 - 1.8751499e+00 -1.7909040e+00 5.3374555e+00 - 2.0623161e+00 -2.0348638e+00 6.1458178e+00 - 1.9476686e+00 -1.8846085e+00 5.9822202e+00 - 1.9727691e+00 -1.9172272e+00 6.3049706e+00 - 1.6072893e+00 -1.4414273e+00 5.1816970e+00 - 1.5646485e+00 -1.3866902e+00 5.2221130e+00 - 1.5399118e+00 -1.3544734e+00 5.3357184e+00 - 1.5858300e+00 -1.4130196e+00 5.7675523e+00 - 1.4453508e+00 -1.2310466e+00 5.3832792e+00 - 1.3679614e+00 -1.1292895e+00 5.2578883e+00 - 1.3036109e+00 -1.0466838e+00 5.1868277e+00 - 1.2525459e+00 -9.7919751e-01 5.1707978e+00 - 1.2240815e+00 -9.4255892e-01 5.2881129e+00 - 1.3830534e+00 -1.1494835e+00 6.6055524e+00 - 1.3397938e+00 -1.0937175e+00 6.7466457e+00 - 1.2634149e+00 -9.9346965e-01 6.6526617e+00 - 1.2487535e+00 -9.7503445e-01 7.0461292e+00 - 1.1246760e+00 -8.1336193e-01 6.5356994e+00 - 1.0365706e+00 -6.9903310e-01 6.2667782e+00 - 9.7613363e-01 -6.1988042e-01 6.2319082e+00 - 9.1368681e-01 -5.3916789e-01 6.1654347e+00 - 9.1036844e-01 -5.3448324e-01 6.9216571e+00 - 8.5215633e-01 -4.5775150e-01 7.0022350e+00 - 7.8906007e-01 -3.7677051e-01 7.0412824e+00 - 8.3698595e-01 -4.3861293e-01 1.0053048e+01 - 7.4456074e-01 -3.1934967e-01 1.0221250e+01 - 6.4372659e-01 -1.8700003e-01 1.0016899e+01 - 5.4449305e-01 -5.8234420e-02 9.4396550e+00 - 1.5786108e+00 -1.4918980e+00 -9.7463283e-01 - 1.6146574e+00 -1.5420404e+00 -9.7098018e-01 - 1.6516512e+00 -1.5931663e+00 -9.6578301e-01 - 1.6923027e+00 -1.6497898e+00 -9.6584402e-01 - 1.7339628e+00 -1.7063899e+00 -9.6421032e-01 - 1.7791632e+00 -1.7704569e+00 -9.6723631e-01 - 1.8299623e+00 -1.8410998e+00 -9.7467829e-01 - 1.8679490e+00 -1.8928446e+00 -9.6054573e-01 - 1.9197132e+00 -1.9643282e+00 -9.6354677e-01 - 1.9631910e+00 -2.0245394e+00 -9.5163368e-01 - 2.0205128e+00 -2.1034432e+00 -9.5590497e-01 - 2.0732004e+00 -2.1766166e+00 -9.5141922e-01 - 2.1259034e+00 -2.2496668e+00 -9.4443654e-01 - 2.1850914e+00 -2.3312783e+00 -9.4037566e-01 - 2.2488911e+00 -2.4193167e+00 -9.3892981e-01 - 2.3126503e+00 -2.5081944e+00 -9.3423834e-01 - 2.3930913e+00 -2.6187447e+00 -9.4169697e-01 - 2.4633658e+00 -2.7159424e+00 -9.3503334e-01 - 2.5391985e+00 -2.8205553e+00 -9.2954009e-01 - 2.6362030e+00 -2.9552715e+00 -9.3891261e-01 - 2.7175043e+00 -3.0690473e+00 -9.2949681e-01 - 2.8165065e+00 -3.2043886e+00 -9.2883846e-01 - 2.9154198e+00 -3.3414726e+00 -9.2298731e-01 - 3.0364675e+00 -3.5095201e+00 -9.2796049e-01 - 3.1474716e+00 -3.6622014e+00 -9.1851100e-01 - 3.2750187e+00 -3.8392111e+00 -9.1427134e-01 - 3.4090904e+00 -4.0244669e+00 -9.0656136e-01 - 3.5597200e+00 -4.2339328e+00 -9.0166416e-01 - 3.7234280e+00 -4.4591403e+00 -8.9486972e-01 - 3.9091969e+00 -4.7169308e+00 -8.9120987e-01 - 4.1180974e+00 -5.0062693e+00 -8.8873982e-01 - 4.3344948e+00 -5.3046353e+00 -8.7715998e-01 - 4.5960600e+00 -5.6673294e+00 -8.7389961e-01 - 4.8817348e+00 -6.0623087e+00 -8.6529068e-01 - 5.2025145e+00 -6.5064025e+00 -8.5367473e-01 - 5.5815062e+00 -7.0313559e+00 -8.4423662e-01 - 6.0141860e+00 -7.6295234e+00 -8.2991643e-01 - 6.5226806e+00 -8.3324467e+00 -8.1299942e-01 - 7.1531123e+00 -9.2053783e+00 -7.9906200e-01 - 7.9250916e+00 -1.0272247e+01 -7.8153809e-01 - 8.8079130e+00 -1.1495153e+01 -7.4158229e-01 - 1.0088243e+01 -1.3266612e+01 -7.2067504e-01 - 1.1131309e+01 -1.4710252e+01 -5.8811802e-01 - 3.2485596e+01 -4.4255698e+01 3.8611400e+00 - 1.2399643e+01 -1.6464239e+01 7.6002762e+00 - 3.5753754e+00 -4.2547818e+00 4.4093171e+00 - 3.5052208e+00 -4.1586898e+00 4.4612795e+00 - 3.3831776e+00 -3.9895290e+00 4.4470803e+00 - 3.3288428e+00 -3.9139603e+00 4.5089685e+00 - 3.2549575e+00 -3.8124380e+00 4.5445662e+00 - 3.3203595e+00 -3.9018980e+00 4.7615381e+00 - 3.2947370e+00 -3.8671767e+00 4.8639117e+00 - 3.7797251e+00 -4.5380665e+00 5.6986041e+00 - 3.3020349e+00 -3.8780096e+00 5.1593648e+00 - 3.8169480e+00 -4.5896400e+00 6.0987090e+00 - 3.1943435e+00 -3.7276095e+00 5.2896797e+00 - 3.1752801e+00 -3.7013725e+00 5.4109542e+00 - 3.1088249e+00 -3.6099289e+00 5.4546125e+00 - 3.0470262e+00 -3.5245525e+00 5.5029469e+00 - 3.0168497e+00 -3.4824271e+00 5.6074865e+00 - 3.0982192e+00 -3.5948418e+00 5.9269172e+00 - 2.9555350e+00 -3.3978252e+00 5.8224615e+00 - 2.8751168e+00 -3.2870927e+00 5.8336156e+00 - 2.7556766e+00 -3.1212416e+00 5.7559852e+00 - 2.7683171e+00 -3.1381195e+00 5.9564861e+00 - 2.6646062e+00 -2.9950633e+00 5.9035122e+00 - 2.7442384e+00 -3.1058019e+00 6.2747349e+00 - 2.3445353e+00 -2.5515793e+00 5.4970349e+00 - 2.2881858e+00 -2.4744902e+00 5.5265207e+00 - 2.2160475e+00 -2.3745651e+00 5.5119244e+00 - 2.1420252e+00 -2.2720750e+00 5.4860995e+00 - 2.1556003e+00 -2.2910681e+00 5.7057224e+00 - 1.8997562e+00 -1.9366363e+00 5.1395395e+00 - 1.8824987e+00 -1.9135899e+00 5.2593583e+00 - 1.8830764e+00 -1.9136155e+00 5.4411802e+00 - 1.8164641e+00 -1.8208477e+00 5.4103825e+00 - 1.7862130e+00 -1.7793185e+00 5.5028370e+00 - 2.1484437e+00 -2.2806959e+00 7.0358962e+00 - 1.6388268e+00 -1.5755662e+00 5.3667395e+00 - 1.5318459e+00 -1.4283416e+00 5.1514802e+00 - 1.4894439e+00 -1.3691174e+00 5.1815609e+00 - 1.5266252e+00 -1.4205068e+00 5.5651366e+00 - 1.4917691e+00 -1.3719824e+00 5.6514673e+00 - 1.3593176e+00 -1.1896389e+00 5.2642227e+00 - 1.3065786e+00 -1.1163603e+00 5.2416097e+00 - 1.2735037e+00 -1.0712235e+00 5.3224896e+00 - 1.2245543e+00 -1.0023882e+00 5.3159920e+00 - 1.3460590e+00 -1.1700074e+00 6.3898255e+00 - 1.3161026e+00 -1.1292179e+00 6.5888461e+00 - 1.2437196e+00 -1.0297013e+00 6.5051863e+00 - 1.2678588e+00 -1.0632111e+00 7.1721110e+00 - 1.1405892e+00 -8.8613205e-01 6.6246962e+00 - 1.0642932e+00 -7.8109615e-01 6.4656957e+00 - 9.8222767e-01 -6.6620697e-01 6.1952077e+00 - 9.3628121e-01 -6.0315919e-01 6.2979115e+00 - 9.3090385e-01 -5.9627564e-01 6.9949652e+00 - 8.6606204e-01 -5.0646512e-01 6.9471813e+00 - 8.0508647e-01 -4.2254837e-01 6.9671475e+00 - 8.9642791e-01 -5.4965544e-01 1.0696346e+01 - 7.9142030e-01 -4.0376724e-01 1.0496960e+01 - 6.8795486e-01 -2.6059774e-01 1.0204384e+01 - 6.0019050e-01 -1.3903020e-01 1.0848430e+01 - 1.5547392e+00 -1.5549277e+00 -9.8018720e-01 - 1.5897330e+00 -1.6059622e+00 -9.7558293e-01 - 1.6210292e+00 -1.6523336e+00 -9.6237500e-01 - 1.6688595e+00 -1.7220742e+00 -9.7545008e-01 - 1.7084097e+00 -1.7804931e+00 -9.7261227e-01 - 1.7534964e+00 -1.8464998e+00 -9.7444053e-01 - 1.7975980e+00 -1.9123425e+00 -9.7416819e-01 - 1.8298834e+00 -1.9593624e+00 -9.5262412e-01 - 1.8795363e+00 -2.0326747e+00 -9.5462081e-01 - 1.9255532e+00 -2.1003169e+00 -9.4786363e-01 - 1.9761744e+00 -2.1744451e+00 -9.4491999e-01 - 2.0267507e+00 -2.2494472e+00 -9.3942989e-01 - 2.0828742e+00 -2.3319531e+00 -9.3690794e-01 - 2.1481416e+00 -2.4284625e+00 -9.4266267e-01 - 2.2052400e+00 -2.5117303e+00 -9.3410176e-01 - 2.2714264e+00 -2.6099639e+00 -9.3306884e-01 - 2.3578356e+00 -2.7373321e+00 -9.4874582e-01 - 2.4249473e+00 -2.8372407e+00 -9.3992647e-01 - 2.4930787e+00 -2.9370374e+00 -9.2761462e-01 - 2.5869222e+00 -3.0744497e+00 -9.3453178e-01 - 2.6705985e+00 -3.1985144e+00 -9.2742657e-01 - 2.7709206e+00 -3.3450564e+00 -9.2852671e-01 - 2.8756982e+00 -3.5008191e+00 -9.2809815e-01 - 2.9814502e+00 -3.6573485e+00 -9.2173050e-01 - 3.0992603e+00 -3.8297364e+00 -9.1705798e-01 - 3.2215961e+00 -4.0102691e+00 -9.0930829e-01 - 3.3614240e+00 -4.2160989e+00 -9.0492427e-01 - 3.5113329e+00 -4.4375136e+00 -8.9913285e-01 - 3.6787499e+00 -4.6840973e+00 -8.9411030e-01 - 3.8526522e+00 -4.9397565e+00 -8.8217209e-01 - 4.0586647e+00 -5.2438348e+00 -8.7705477e-01 - 4.2877044e+00 -5.5813269e+00 -8.7043136e-01 - 4.5498269e+00 -5.9680195e+00 -8.6498939e-01 - 4.8404967e+00 -6.3963608e+00 -8.5556659e-01 - 5.1818176e+00 -6.8980749e+00 -8.4814366e-01 - 5.5681456e+00 -7.4674643e+00 -8.3585803e-01 - 6.0106136e+00 -8.1192267e+00 -8.1835378e-01 - 6.5587677e+00 -8.9280457e+00 -8.0516869e-01 - 7.1585870e+00 -9.8112029e+00 -7.7181480e-01 - 8.0598807e+00 -1.1140539e+01 -7.7207900e-01 - 9.0644726e+00 -1.2618808e+01 -7.3719920e-01 - 1.0499283e+01 -1.4734508e+01 -7.1408179e-01 - 1.1836094e+01 -1.6703766e+01 -5.8814817e-01 - 3.1743323e+01 -4.6039217e+01 1.2321621e+01 - 3.3220738e+00 -4.1584888e+00 4.2023794e+00 - 3.2338226e+00 -4.0287349e+00 4.2234568e+00 - 3.2064911e+00 -3.9885022e+00 4.3135543e+00 - 3.1690114e+00 -3.9332217e+00 4.3913578e+00 - 3.1490632e+00 -3.9039563e+00 4.4917628e+00 - 3.1725299e+00 -3.9384993e+00 4.6527185e+00 - 3.1849856e+00 -3.9558220e+00 4.8036814e+00 - 3.6841139e+00 -4.6929355e+00 5.6752948e+00 - 3.6375053e+00 -4.6240475e+00 5.7736095e+00 - 3.2712156e+00 -4.0835044e+00 5.3667348e+00 - 3.0249126e+00 -3.7207348e+00 5.1211777e+00 - 3.0123818e+00 -3.7026799e+00 5.2472209e+00 - 3.0867676e+00 -3.8125803e+00 5.5280232e+00 - 3.0891181e+00 -3.8155435e+00 5.6932585e+00 - 2.9073796e+00 -3.5484103e+00 5.5192033e+00 - 2.5443498e+00 -3.0129337e+00 4.9739875e+00 - 2.5234642e+00 -2.9826059e+00 5.0744460e+00 - 2.8366758e+00 -3.4442432e+00 5.8742451e+00 - 2.7955047e+00 -3.3842503e+00 5.9616510e+00 - 2.5719981e+00 -3.0546757e+00 5.6409963e+00 - 2.5910459e+00 -3.0822830e+00 5.8554034e+00 - 2.7972013e+00 -3.3861653e+00 6.5306367e+00 - 2.2604582e+00 -2.5946363e+00 5.3963503e+00 - 2.1691971e+00 -2.4601822e+00 5.3267029e+00 - 2.1390793e+00 -2.4160414e+00 5.4113182e+00 - 2.1349544e+00 -2.4098503e+00 5.5712359e+00 - 2.1661224e+00 -2.4553990e+00 5.8430230e+00 - 1.9067962e+00 -2.0746832e+00 5.2565416e+00 - 1.8377736e+00 -1.9713933e+00 5.2125241e+00 - 1.8252541e+00 -1.9537637e+00 5.3502025e+00 - 1.7570833e+00 -1.8527351e+00 5.3020860e+00 - 1.6972567e+00 -1.7640629e+00 5.2778563e+00 - 2.2417585e+00 -2.5678144e+00 7.5076483e+00 - 1.6658108e+00 -1.7191027e+00 5.5589819e+00 - 1.6096995e+00 -1.6359840e+00 5.5486200e+00 - 1.5330429e+00 -1.5232129e+00 5.4439075e+00 - 1.4787177e+00 -1.4434425e+00 5.4288939e+00 - 1.4057741e+00 -1.3352114e+00 5.3180746e+00 - 1.3803343e+00 -1.2979986e+00 5.4304367e+00 - 1.3063675e+00 -1.1888758e+00 5.2959507e+00 - 1.2697933e+00 -1.1338807e+00 5.3489320e+00 - 1.2172250e+00 -1.0571760e+00 5.3147349e+00 - 1.1730782e+00 -9.9272606e-01 5.3267466e+00 - 1.3204652e+00 -1.2094940e+00 6.6540546e+00 - 1.2456425e+00 -1.0986586e+00 6.5328058e+00 - 1.1933018e+00 -1.0221973e+00 6.5747132e+00 - 1.2004458e+00 -1.0329285e+00 7.1343881e+00 - 1.0735859e+00 -8.4535558e-01 6.5160664e+00 - 1.0222122e+00 -7.6972020e-01 6.5627143e+00 - 9.4413398e-01 -6.5563130e-01 6.3011522e+00 - 8.9848656e-01 -5.8709939e-01 6.3934711e+00 - 8.8178750e-01 -5.6238388e-01 6.9713692e+00 - 8.1805712e-01 -4.6966582e-01 6.9027095e+00 - 7.6895216e-01 -3.9816305e-01 7.1111465e+00 - 8.1783338e-01 -4.6917571e-01 1.0282656e+01 - 7.2781336e-01 -3.3593561e-01 1.0311181e+01 - 6.3564845e-01 -2.0066729e-01 1.0256818e+01 - 5.4031768e-01 -6.0484129e-02 9.4296793e+00 - 1.4924178e+00 -1.5582668e+00 -9.8184050e-01 - 1.5216439e+00 -1.6056227e+00 -9.7077394e-01 - 1.5555824e+00 -1.6575691e+00 -9.6561756e-01 - 1.5967047e+00 -1.7225932e+00 -9.7267623e-01 - 1.6269567e+00 -1.7697878e+00 -9.5711841e-01 - 1.6736267e+00 -1.8423109e+00 -9.6704536e-01 - 1.7156637e+00 -1.9090938e+00 -9.6801551e-01 - 1.7550621e+00 -1.9702721e+00 -9.6033485e-01 - 1.7980034e+00 -2.0388974e+00 -9.5691439e-01 - 1.8374265e+00 -2.0998786e+00 -9.4523866e-01 - 1.8941048e+00 -2.1890820e+00 -9.5570620e-01 - 1.9426178e+00 -2.2650143e+00 -9.5125883e-01 - 1.9910866e+00 -2.3418154e+00 -9.4416511e-01 - 2.0532298e+00 -2.4402113e+00 -9.5130936e-01 - 2.1082022e+00 -2.5254260e+00 -9.4414113e-01 - 2.1667297e+00 -2.6179892e+00 -9.3923558e-01 - 2.2308105e+00 -2.7180072e+00 -9.3629941e-01 - 2.3039258e+00 -2.8339338e+00 -9.3974304e-01 - 2.3790032e+00 -2.9507713e+00 -9.3894866e-01 - 2.4530481e+00 -3.0683384e+00 -9.3390673e-01 - 2.5381338e+00 -3.2018562e+00 -9.3365293e-01 - 2.6232497e+00 -3.3351326e+00 -9.2850517e-01 - 2.7148127e+00 -3.4777899e+00 -9.2263410e-01 - 2.8254547e+00 -3.6522313e+00 -9.2762813e-01 - 2.9269911e+00 -3.8123639e+00 -9.1815314e-01 - 3.0441325e+00 -3.9957675e+00 -9.1393434e-01 - 3.1722234e+00 -4.1968841e+00 -9.0971037e-01 - 3.3103312e+00 -4.4146121e+00 -9.0462870e-01 - 3.4549131e+00 -4.6415042e+00 -8.9442913e-01 - 3.6204957e+00 -4.9019306e+00 -8.8761107e-01 - 3.8016633e+00 -5.1863048e+00 -8.7950767e-01 - 4.0102798e+00 -5.5135844e+00 -8.7386269e-01 - 4.2454226e+00 -5.8825889e+00 -8.6822559e-01 - 4.5170903e+00 -6.3100772e+00 -8.6473498e-01 - 4.8272410e+00 -6.7969901e+00 -8.5975211e-01 - 5.1593595e+00 -7.3187772e+00 -8.4357269e-01 - 5.5655178e+00 -7.9576566e+00 -8.3298783e-01 - 6.0212224e+00 -8.6722480e+00 -8.1226580e-01 - 6.6103754e+00 -9.5980057e+00 -8.0137505e-01 - 7.2380539e+00 -1.0583881e+01 -7.6252550e-01 - 8.1063163e+00 -1.1947112e+01 -7.3818579e-01 - 9.3870235e+00 -1.3959371e+01 -7.3834329e-01 - 1.3367500e+01 -2.0212931e+01 -6.7410854e-01 - 2.9586660e+01 -4.5689588e+01 7.6534339e+00 - 3.7261117e+00 -5.0683572e+00 4.6107188e+00 - 3.2271916e+00 -4.2845384e+00 4.1745401e+00 - 3.1430646e+00 -4.1529437e+00 4.1973036e+00 - 3.1085924e+00 -4.0977411e+00 4.2771949e+00 - 3.1961808e+00 -4.2355857e+00 4.5163411e+00 - 3.1450931e+00 -4.1561170e+00 4.5799193e+00 - 3.1372833e+00 -4.1425837e+00 4.7014506e+00 - 3.6346204e+00 -4.9252561e+00 5.5624065e+00 - 3.5790812e+00 -4.8375655e+00 5.6447301e+00 - 4.0775903e+00 -5.6220037e+00 6.5926731e+00 - 3.6682835e+00 -4.9782854e+00 6.1307125e+00 - 3.0372916e+00 -3.9866112e+00 5.2559667e+00 - 2.9889847e+00 -3.9110949e+00 5.3241281e+00 - 2.9250996e+00 -3.8100293e+00 5.3626903e+00 - 2.9935720e+00 -3.9184469e+00 5.6459590e+00 - 2.9682779e+00 -3.8790382e+00 5.7623169e+00 - 2.8142450e+00 -3.6359542e+00 5.6224179e+00 - 2.7162288e+00 -3.4824179e+00 5.5854122e+00 - 2.4230843e+00 -3.0213758e+00 5.1209323e+00 - 2.4077966e+00 -2.9986622e+00 5.2364500e+00 - 2.3677658e+00 -2.9350161e+00 5.2978369e+00 - 2.6113892e+00 -3.3182967e+00 6.0356280e+00 - 2.2572008e+00 -2.7615062e+00 5.3447280e+00 - 2.1692060e+00 -2.6229993e+00 5.2798666e+00 - 2.1134785e+00 -2.5347498e+00 5.2924779e+00 - 2.0788752e+00 -2.4811108e+00 5.3609331e+00 - 2.0581656e+00 -2.4483457e+00 5.4702814e+00 - 2.0900213e+00 -2.4990135e+00 5.7408149e+00 - 2.0896999e+00 -2.4976713e+00 5.9288827e+00 - 1.8307812e+00 -2.0912220e+00 5.2955732e+00 - 1.7906351e+00 -2.0284972e+00 5.3382831e+00 - 1.7116732e+00 -1.9048805e+00 5.2471673e+00 - 1.6909672e+00 -1.8720859e+00 5.3571149e+00 - 1.6647666e+00 -1.8298212e+00 5.4491076e+00 - 2.0373459e+00 -2.4170182e+00 7.1449318e+00 - 1.5974317e+00 -1.7252066e+00 5.5952489e+00 - 1.9678376e+00 -2.3066930e+00 7.4436934e+00 - 1.4189451e+00 -1.4443357e+00 5.2373702e+00 - 1.3732196e+00 -1.3723017e+00 5.2386047e+00 - 1.3218653e+00 -1.2923857e+00 5.2099487e+00 - 1.2872359e+00 -1.2384394e+00 5.2643715e+00 - 1.5773098e+00 -1.6942774e+00 7.1820063e+00 - 1.2022145e+00 -1.1049234e+00 5.2843424e+00 - 1.1769929e+00 -1.0644192e+00 5.4026483e+00 - 1.2824108e+00 -1.2314834e+00 6.4479184e+00 - 1.2340763e+00 -1.1551555e+00 6.4920103e+00 - 1.1932309e+00 -1.0910140e+00 6.6027386e+00 - 1.1290009e+00 -9.8909363e-01 6.5168072e+00 - 1.0881994e+00 -9.2511642e-01 6.6444643e+00 - 1.0682680e+00 -8.9283729e-01 7.0073444e+00 - 9.3573405e-01 -6.8639663e-01 6.1361162e+00 - 9.1109357e-01 -6.4692174e-01 6.4564183e+00 - 8.9527307e-01 -6.2322246e-01 7.0149371e+00 - 8.3666463e-01 -5.3079046e-01 6.9871103e+00 - 7.7510098e-01 -4.3270566e-01 6.8676101e+00 - 7.2817095e-01 -3.5938090e-01 7.0951676e+00 - 7.6537359e-01 -4.1872281e-01 1.0467121e+01 - 6.8315794e-01 -2.8969021e-01 1.0824111e+01 - 5.9071972e-01 -1.4495880e-01 1.0818543e+01 - 1.4547368e+00 -1.6023281e+00 -9.6561740e-01 - 1.4938448e+00 -1.6673742e+00 -9.7556614e-01 - 1.5220255e+00 -1.7155630e+00 -9.6234944e-01 - 1.5584472e+00 -1.7759029e+00 -9.6160028e-01 - 1.5984681e+00 -1.8427226e+00 -9.6576013e-01 - 1.6384417e+00 -1.9104357e+00 -9.6777301e-01 - 1.6757769e+00 -1.9725442e+00 -9.6113509e-01 - 1.7121255e+00 -2.0344986e+00 -9.5259632e-01 - 1.7576046e+00 -2.1105649e+00 -9.5453152e-01 - 1.7994469e+00 -2.1809660e+00 -9.4781273e-01 - 1.8494866e+00 -2.2643822e+00 -9.5081525e-01 - 1.8958896e+00 -2.3421333e+00 -9.4516378e-01 - 1.9513733e+00 -2.4349093e+00 -9.4823881e-01 - 1.9976898e+00 -2.5143833e+00 -9.3699503e-01 - 2.0668129e+00 -2.6295491e+00 -9.5016352e-01 - 2.1232341e+00 -2.7239016e+00 -9.4345460e-01 - 2.1977589e+00 -2.8492813e+00 -9.5374964e-01 - 2.2596382e+00 -2.9528804e+00 -9.4481607e-01 - 2.3260173e+00 -3.0648314e+00 -9.3700016e-01 - 2.3934193e+00 -3.1766457e+00 -9.2519235e-01 - 2.4788831e+00 -3.3203363e+00 -9.2734266e-01 - 2.5743386e+00 -3.4808403e+00 -9.3273021e-01 - 2.6606871e+00 -3.6270452e+00 -9.2384849e-01 - 2.7626321e+00 -3.7965902e+00 -9.2162123e-01 - 2.8689782e+00 -3.9763084e+00 -9.1691685e-01 - 2.9808481e+00 -4.1642320e+00 -9.0913847e-01 - 3.1082138e+00 -4.3773318e+00 -9.0471941e-01 - 3.2455990e+00 -4.6070232e+00 -8.9904314e-01 - 3.3928911e+00 -4.8552360e+00 -8.9071218e-01 - 3.5657372e+00 -5.1443922e+00 -8.8802856e-01 - 3.7539956e+00 -5.4604230e+00 -8.8261255e-01 - 3.9522477e+00 -5.7937664e+00 -8.7029670e-01 - 4.1913812e+00 -6.1961217e+00 -8.6484132e-01 - 4.4570658e+00 -6.6400048e+00 -8.5539876e-01 - 4.7726020e+00 -7.1703540e+00 -8.5000859e-01 - 5.1245987e+00 -7.7607327e+00 -8.3757703e-01 - 5.5484182e+00 -8.4719082e+00 -8.2723953e-01 - 6.0331779e+00 -9.2856352e+00 -8.0821458e-01 - 6.6461859e+00 -1.0313963e+01 -7.9371310e-01 - 7.4628083e+00 -1.1685130e+01 -7.8998946e-01 - 8.2814650e+00 -1.3058693e+01 -7.3109227e-01 - 2.9004483e+01 -4.7838439e+01 5.3856943e+00 - 3.4990783e+00 -5.0354495e+00 4.7345500e+00 - 3.4740041e+00 -4.9922205e+00 4.8473139e+00 - 3.4305779e+00 -4.9199498e+00 4.9368314e+00 - 3.1160091e+00 -4.3917549e+00 4.6470907e+00 - 3.4533903e+00 -4.9578726e+00 5.2711715e+00 - 3.5159241e+00 -5.0634621e+00 5.5233992e+00 - 3.4397455e+00 -4.9341939e+00 5.5695571e+00 - 3.5050886e+00 -5.0440233e+00 5.8407998e+00 - 3.6864968e+00 -5.3491670e+00 6.3193052e+00 - 2.8955983e+00 -4.0208504e+00 5.1415861e+00 - 2.9142670e+00 -4.0530350e+00 5.3239816e+00 - 2.9275254e+00 -4.0750746e+00 5.5021054e+00 - 2.9270859e+00 -4.0741593e+00 5.6612593e+00 - 2.8131965e+00 -3.8837215e+00 5.6007044e+00 - 2.3776424e+00 -3.1523398e+00 5.2964812e+00 - 2.3093991e+00 -3.0381805e+00 5.2904702e+00 - 2.2805811e+00 -2.9891105e+00 5.3749345e+00 - 2.1756634e+00 -2.8135366e+00 5.2683999e+00 - 2.1458840e+00 -2.7635964e+00 5.3490225e+00 - 2.1014518e+00 -2.6887487e+00 5.3882573e+00 - 2.0469051e+00 -2.5975540e+00 5.4010164e+00 - 2.4427024e+00 -3.2621967e+00 6.7373697e+00 - 2.0369238e+00 -2.5803568e+00 5.7147176e+00 - 1.9832837e+00 -2.4909850e+00 5.7322669e+00 - 1.9930641e+00 -2.5066074e+00 5.9545504e+00 - 1.9688499e+00 -2.4660898e+00 6.0743513e+00 - 1.7204109e+00 -2.0495608e+00 5.3942228e+00 - 1.7026456e+00 -2.0184093e+00 5.5150466e+00 - 1.6323971e+00 -1.9005893e+00 5.4389812e+00 - 1.5767992e+00 -1.8082105e+00 5.4137416e+00 - 1.6003936e+00 -1.8484372e+00 5.7228593e+00 - 1.5439659e+00 -1.7531056e+00 5.6954767e+00 - 1.3888851e+00 -1.4917923e+00 5.1945407e+00 - 1.3451590e+00 -1.4198545e+00 5.1962683e+00 - 1.2950521e+00 -1.3354280e+00 5.1589717e+00 - 1.2541148e+00 -1.2673786e+00 5.1665809e+00 - 1.5397090e+00 -1.7472823e+00 7.0789224e+00 - 1.1890139e+00 -1.1568601e+00 5.2727683e+00 - 1.1434888e+00 -1.0801302e+00 5.2476377e+00 - 1.3929998e+00 -1.5016313e+00 7.3022998e+00 - 1.2298824e+00 -1.2258031e+00 6.5185495e+00 - 1.1799119e+00 -1.1423493e+00 6.5425756e+00 - 1.1327440e+00 -1.0631896e+00 6.5845182e+00 - 1.1136948e+00 -1.0303498e+00 6.8992058e+00 - 1.0628232e+00 -9.4657624e-01 6.9487533e+00 - 9.8473766e-01 -8.1522564e-01 6.6712211e+00 - 9.1782609e-01 -7.0185622e-01 6.4692992e+00 - 8.9912726e-01 -6.7137417e-01 6.9387918e+00 - 8.4833434e-01 -5.8645581e-01 6.9912860e+00 - 7.9377486e-01 -4.9433141e-01 6.9823726e+00 - 7.4308366e-01 -4.0860014e-01 7.0513465e+00 - 7.9167626e-01 -4.9120250e-01 1.0352588e+01 - 7.0907415e-01 -3.5442763e-01 1.0441068e+01 - 6.2895600e-01 -2.1851861e-01 1.0696782e+01 - 5.2581858e-01 -4.5006970e-02 7.0998325e+00 - 1.3392251e+00 -1.5070286e+00 -9.8472396e-01 - 1.3654382e+00 -1.5543509e+00 -9.7664416e-01 - 1.3962426e+00 -1.6082626e+00 -9.7447532e-01 - 1.4260581e+00 -1.6620400e+00 -9.7080514e-01 - 1.4594090e+00 -1.7233236e+00 -9.7259369e-01 - 1.4937685e+00 -1.7845839e+00 -9.7268751e-01 - 1.5244926e+00 -1.8401693e+00 -9.6392758e-01 - 1.5624029e+00 -1.9088126e+00 -9.6698320e-01 - 1.6013237e+00 -1.9774179e+00 -9.6804447e-01 - 1.6330184e+00 -2.0337996e+00 -9.5394471e-01 - 1.6718447e+00 -2.1041918e+00 -9.5071206e-01 - 1.7070926e+00 -2.1679369e+00 -9.3917460e-01 - 1.7550057e+00 -2.2533049e+00 -9.4366969e-01 - 1.8028758e+00 -2.3395318e+00 -9.4531868e-01 - 1.8507632e+00 -2.4256209e+00 -9.4417113e-01 - 1.9031406e+00 -2.5201405e+00 -9.4573925e-01 - 1.9529396e+00 -2.6080586e+00 -9.3870611e-01 - 2.0098298e+00 -2.7108266e+00 -9.3929448e-01 - 2.0721546e+00 -2.8230284e+00 -9.4145351e-01 - 2.1435761e+00 -2.9501270e+00 -9.4974225e-01 - 2.2022908e+00 -3.0564519e+00 -9.3895259e-01 - 2.2565500e+00 -3.1540703e+00 -9.1985416e-01 - 2.3378834e+00 -3.2996510e+00 -9.2468920e-01 - 2.4191291e+00 -3.4469645e+00 -9.2413167e-01 - 2.4968640e+00 -3.5865748e+00 -9.1412035e-01 - 2.5845913e+00 -3.7429933e+00 -9.0724641e-01 - 2.6813188e+00 -3.9161106e+00 -9.0250790e-01 - 2.7915360e+00 -4.1143620e+00 -9.0272036e-01 - 2.9117061e+00 -4.3302512e+00 -9.0262484e-01 - 3.0283177e+00 -4.5393355e+00 -8.9102845e-01 - 3.1684088e+00 -4.7903821e+00 -8.8791992e-01 - 3.3129248e+00 -5.0514099e+00 -8.7843907e-01 - 3.4818811e+00 -5.3552750e+00 -8.7370427e-01 - 3.6618243e+00 -5.6765526e+00 -8.6287182e-01 - 3.8741558e+00 -6.0582535e+00 -8.5786935e-01 - 4.1108521e+00 -6.4844260e+00 -8.5022283e-01 - 4.3874040e+00 -6.9802858e+00 -8.4409060e-01 - 4.6973469e+00 -7.5371090e+00 -8.3325493e-01 - 5.0661124e+00 -8.1978476e+00 -8.2356369e-01 - 5.4826290e+00 -8.9473113e+00 -8.0538513e-01 - 5.9489263e+00 -9.7853551e+00 -7.7333227e-01 - 6.5318817e+00 -1.0831081e+01 -7.4176732e-01 - 7.4101124e+00 -1.2408840e+01 -7.4315157e-01 - 8.4647437e+00 -1.4300944e+01 -7.1960571e-01 - 1.4419906e+01 -2.4995137e+01 -4.9787310e-01 - 3.6525749e+00 -5.6618877e+00 4.4462109e+00 - 3.6139800e+00 -5.5932568e+00 4.5490945e+00 - 3.3814056e+00 -5.1753614e+00 4.4202809e+00 - 3.4733041e+00 -5.3411242e+00 4.9707600e+00 - 2.9430306e+00 -4.3891182e+00 4.3890090e+00 - 3.2891958e+00 -5.0088196e+00 5.0152782e+00 - 2.9002665e+00 -4.3115561e+00 4.5857940e+00 - 3.0912872e+00 -4.6538639e+00 5.0144096e+00 - 2.9528156e+00 -4.4054343e+00 4.9404326e+00 - 2.9831432e+00 -4.4607927e+00 5.1349129e+00 - 3.2796435e+00 -4.9925352e+00 5.7954972e+00 - 2.8968339e+00 -4.3057215e+00 5.2842893e+00 - 2.8237211e+00 -4.1740017e+00 5.3027734e+00 - 2.8441417e+00 -4.2108387e+00 5.4945989e+00 - 2.7982631e+00 -4.1283808e+00 5.5641050e+00 - 2.8005621e+00 -4.1322720e+00 5.7307881e+00 - 2.6582717e+00 -3.8775693e+00 5.5967516e+00 - 2.5459619e+00 -3.6763567e+00 5.5127271e+00 - 2.5147129e+00 -3.6179604e+00 5.6002507e+00 - 2.5605725e+00 -3.7023323e+00 5.8756644e+00 - 2.1507771e+00 -2.9645713e+00 5.0449188e+00 - 2.0610784e+00 -2.8037069e+00 4.9636462e+00 - 2.0322989e+00 -2.7532983e+00 5.0347278e+00 - 2.1065358e+00 -2.8858347e+00 5.3846314e+00 - 2.1087967e+00 -2.8905455e+00 5.5549596e+00 - 2.0537660e+00 -2.7905395e+00 5.5627815e+00 - 1.9685462e+00 -2.6381944e+00 5.4769955e+00 - 2.0201103e+00 -2.7308754e+00 5.8141596e+00 - 1.9631741e+00 -2.6289911e+00 5.8170947e+00 - 1.9929830e+00 -2.6814893e+00 6.1088572e+00 - 1.8903672e+00 -2.4984364e+00 5.9537801e+00 - 1.8627143e+00 -2.4475776e+00 6.0554703e+00 - 1.6796294e+00 -2.1198597e+00 5.5649483e+00 - 1.6281676e+00 -2.0260606e+00 5.5531297e+00 - 1.5527915e+00 -1.8917112e+00 5.4401361e+00 - 1.5662151e+00 -1.9155251e+00 5.7038518e+00 - 1.5219625e+00 -1.8366632e+00 5.7231631e+00 - 1.4245684e+00 -1.6621683e+00 5.4829704e+00 - 1.7268946e+00 -2.2055050e+00 7.2493539e+00 - 1.2644900e+00 -1.3737019e+00 5.0984712e+00 - 1.2247375e+00 -1.3021587e+00 5.0970898e+00 - 1.5131610e+00 -1.8202672e+00 7.0514479e+00 - 1.4718684e+00 -1.7465046e+00 7.1533942e+00 - 1.4388773e+00 -1.6880190e+00 7.3213232e+00 - 1.0913793e+00 -1.0638822e+00 5.2488599e+00 - 1.2382557e+00 -1.3271078e+00 6.6700758e+00 - 1.1710344e+00 -1.2061133e+00 6.5404693e+00 - 1.2241970e+00 -1.3030399e+00 7.4601512e+00 - 1.1283239e+00 -1.1293698e+00 7.0841222e+00 - 1.0796399e+00 -1.0431566e+00 7.1450500e+00 - 1.0086167e+00 -9.1472276e-01 6.9385055e+00 - 9.0361436e-01 -7.2671702e-01 6.2545467e+00 - 9.0655520e-01 -7.3188279e-01 6.9614550e+00 - 8.5888420e-01 -6.4561181e-01 7.0247767e+00 - 8.0257094e-01 -5.4575511e-01 6.9473087e+00 - 7.5199796e-01 -4.5392178e-01 6.9373838e+00 - 7.0930556e-01 -3.7784970e-01 7.1850046e+00 - 7.4251861e-01 -4.3847251e-01 1.0586882e+01 - 6.6339232e-01 -2.9596975e-01 1.0714106e+01 - 5.5098073e-01 -9.3206638e-02 7.1091636e+00 - 1.2776283e+00 -1.4989037e+00 -9.7683476e-01 - 1.3054235e+00 -1.5527523e+00 -9.7705342e-01 - 1.3332278e+00 -1.6065270e+00 -9.7577393e-01 - 1.3619800e+00 -1.6612803e+00 -9.7285004e-01 - 1.3906813e+00 -1.7169566e+00 -9.6837845e-01 - 1.4256271e+00 -1.7846631e+00 -9.7636804e-01 - 1.4516996e+00 -1.8346560e+00 -9.6164761e-01 - 1.4911342e+00 -1.9108029e+00 -9.7255263e-01 - 1.5208159e+00 -1.9671967e+00 -9.6114318e-01 - 1.5540361e+00 -2.0310721e+00 -9.5469306e-01 - 1.5907984e+00 -2.1023996e+00 -9.5260302e-01 - 1.6203923e+00 -2.1605262e+00 -9.3580101e-01 - 1.6653017e+00 -2.2457867e+00 -9.4178471e-01 - 1.7101078e+00 -2.3329032e+00 -9.4487277e-01 - 1.7478046e+00 -2.4058317e+00 -9.3349816e-01 - 1.8016478e+00 -2.5088371e+00 -9.4256650e-01 - 1.8438488e+00 -2.5900829e+00 -9.3161040e-01 - 1.9021458e+00 -2.7023238e+00 -9.3944968e-01 - 1.9487974e+00 -2.7928297e+00 -9.2776390e-01 - 2.0116140e+00 -2.9132646e+00 -9.3352478e-01 - 2.0788125e+00 -3.0440256e+00 -9.3990471e-01 - 2.1309426e+00 -3.1436155e+00 -9.2269835e-01 - 2.2071499e+00 -3.2910061e+00 -9.2981543e-01 - 2.2763063e+00 -3.4232266e+00 -9.2281902e-01 - 2.3453699e+00 -3.5572193e+00 -9.1122905e-01 - 2.4234855e+00 -3.7069827e+00 -9.0322234e-01 - 2.5095398e+00 -3.8744058e+00 -8.9779771e-01 - 2.6100789e+00 -4.0670483e+00 -8.9782662e-01 - 2.7230547e+00 -4.2857171e+00 -9.0185489e-01 - 2.8245001e+00 -4.4807014e+00 -8.8735609e-01 - 2.9438740e+00 -4.7101735e+00 -8.7897624e-01 - 3.0801294e+00 -4.9749814e+00 -8.7486485e-01 - 3.2273568e+00 -5.2573200e+00 -8.6705284e-01 - 3.3914879e+00 -5.5748169e+00 -8.5991373e-01 - 3.5745305e+00 -5.9274994e+00 -8.5155620e-01 - 3.7899110e+00 -6.3415233e+00 -8.4738108e-01 - 4.0186235e+00 -6.7840041e+00 -8.3447539e-01 - 4.2896350e+00 -7.3054001e+00 -8.2414572e-01 - 4.5964230e+00 -7.8979646e+00 -8.0972530e-01 - 4.9588694e+00 -8.5971652e+00 -7.9449335e-01 - 5.3959376e+00 -9.4372597e+00 -7.7867928e-01 - 5.8821364e+00 -1.0376802e+01 -7.4644833e-01 - 6.4941069e+00 -1.1555592e+01 -7.1310435e-01 - 7.3123874e+00 -1.3132269e+01 -6.8483576e-01 - 8.4929336e+00 -1.5409589e+01 -6.7059908e-01 - 3.4740855e+00 -5.7354800e+00 4.2218603e+00 - 3.4403616e+00 -5.6691402e+00 4.3249270e+00 - 3.4209607e+00 -5.6318910e+00 4.4453600e+00 - 3.3169553e+00 -5.4311906e+00 4.4620338e+00 - 3.2921139e+00 -5.3840378e+00 4.5733011e+00 - 3.3141139e+00 -5.4269067e+00 4.7465912e+00 - 2.8326955e+00 -4.4987167e+00 4.2293919e+00 - 2.7799177e+00 -4.3967820e+00 4.2787562e+00 - 2.8028313e+00 -4.4403864e+00 4.4383600e+00 - 2.7671203e+00 -4.3723045e+00 4.5135187e+00 - 2.7351256e+00 -4.3092521e+00 4.5929074e+00 - 2.7165516e+00 -4.2739471e+00 4.6954090e+00 - 2.6862153e+00 -4.2168102e+00 4.7788840e+00 - 2.7236743e+00 -4.2872124e+00 4.9820722e+00 - 3.2759857e+00 -5.3528264e+00 6.1504080e+00 - 3.2160237e+00 -5.2383332e+00 6.2217249e+00 - 2.9567697e+00 -4.7375615e+00 5.8914442e+00 - 2.7271935e+00 -4.2942464e+00 5.5915488e+00 - 2.5552556e+00 -3.9629775e+00 5.3878368e+00 - 2.5095962e+00 -3.8761901e+00 5.4438116e+00 - 2.4261216e+00 -3.7143255e+00 5.4104104e+00 - 2.3903940e+00 -3.6463766e+00 5.4828724e+00 - 2.3574557e+00 -3.5823112e+00 5.5613159e+00 - 2.3146003e+00 -3.4987748e+00 5.6158317e+00 - 2.2626376e+00 -3.3988780e+00 5.6453669e+00 - 1.9294436e+00 -2.7575249e+00 4.9054107e+00 - 1.9118104e+00 -2.7227386e+00 4.9986205e+00 - 1.9891028e+00 -2.8722895e+00 5.3731740e+00 - 1.9298931e+00 -2.7572420e+00 5.3556493e+00 - 1.9149324e+00 -2.7293366e+00 5.4751141e+00 - 1.8990964e+00 -2.6993572e+00 5.5948824e+00 - 1.9041453e+00 -2.7089945e+00 5.7905674e+00 - 1.8150147e+00 -2.5363701e+00 5.6640562e+00 - 1.7965370e+00 -2.5002966e+00 5.7821385e+00 - 1.8115543e+00 -2.5305431e+00 6.0394534e+00 - 1.7422806e+00 -2.3971972e+00 5.9742305e+00 - 1.5894922e+00 -2.1020930e+00 5.5505109e+00 - 1.5346510e+00 -1.9964466e+00 5.5105948e+00 - 1.5080057e+00 -1.9445411e+00 5.5942050e+00 - 1.4886594e+00 -1.9063394e+00 5.7136895e+00 - 1.4756142e+00 -1.8822950e+00 5.8788891e+00 - 1.4472038e+00 -1.8268738e+00 5.9705469e+00 - 1.6511083e+00 -2.2217634e+00 7.3548523e+00 - 1.1960515e+00 -1.3430615e+00 5.0465195e+00 - 1.5518964e+00 -2.0291310e+00 7.4571997e+00 - 1.4487626e+00 -1.8308344e+00 7.1642046e+00 - 1.3894654e+00 -1.7164864e+00 7.1324975e+00 - 1.3842086e+00 -1.7063618e+00 7.4912736e+00 - 1.2928261e+00 -1.5299858e+00 7.2155073e+00 - 1.2426754e+00 -1.4332304e+00 7.2445855e+00 - 1.1243688e+00 -1.2054145e+00 6.6592691e+00 - 1.1164550e+00 -1.1913804e+00 7.0531122e+00 - 1.0662638e+00 -1.0939169e+00 7.0560235e+00 - 1.0030515e+00 -9.7200295e-01 6.9094260e+00 - 9.2762453e-01 -8.2619795e-01 6.5626799e+00 - 8.8658739e-01 -7.4626780e-01 6.6275750e+00 - 8.6056241e-01 -6.9765683e-01 6.9685611e+00 - 8.1312449e-01 -6.0488155e-01 6.9813986e+00 - 7.6561710e-01 -5.1472445e-01 7.0222001e+00 - 7.0845148e-01 -4.0332741e-01 6.7722560e+00 - 7.6063667e-01 -5.0535648e-01 1.0312628e+01 - 6.8838532e-01 -3.6572086e-01 1.0451064e+01 - 6.1436760e-01 -2.2412667e-01 1.0626761e+01 - 5.2370263e-01 -4.7389188e-02 7.1098753e+00 - 1.2440055e+00 -1.5416513e+00 -9.6961250e-01 - 1.2697478e+00 -1.5963464e+00 -9.6917599e-01 - 1.2964373e+00 -1.6520250e+00 -9.6719496e-01 - 1.3231366e+00 -1.7076248e+00 -9.6361590e-01 - 1.3570173e+00 -1.7763219e+00 -9.7265140e-01 - 1.3810278e+00 -1.8272353e+00 -9.5877396e-01 - 1.4148716e+00 -1.8967422e+00 -9.6396459e-01 - 1.4460776e+00 -1.9606395e+00 -9.6040454e-01 - 1.4762369e+00 -2.0253798e+00 -9.5489411e-01 - 1.5084042e+00 -2.0901474e+00 -9.4749237e-01 - 1.5431155e+00 -2.1623065e+00 -9.4444754e-01 - 1.5777802e+00 -2.2353542e+00 -9.3915586e-01 - 1.6205205e+00 -2.3234207e+00 -9.4368616e-01 - 1.6596850e+00 -2.4048202e+00 -9.3951213e-01 - 1.6988656e+00 -2.4860916e+00 -9.3274131e-01 - 1.7460684e+00 -2.5833245e+00 -9.3464427e-01 - 1.7932307e+00 -2.6813967e+00 -9.3330163e-01 - 1.8403525e+00 -2.7803082e+00 -9.2871339e-01 - 1.8955064e+00 -2.8951023e+00 -9.3120089e-01 - 1.9551602e+00 -3.0182482e+00 -9.3480605e-01 - 2.0077015e+00 -3.1272309e+00 -9.2444792e-01 - 2.0647426e+00 -3.2445653e+00 -9.1520745e-01 - 2.1367890e+00 -3.3946064e+00 -9.2016562e-01 - 2.2017843e+00 -3.5294774e+00 -9.1101031e-01 - 2.2712279e+00 -3.6736282e+00 -9.0152483e-01 - 2.3566934e+00 -3.8503984e+00 -9.0324487e-01 - 2.4510419e+00 -4.0458365e+00 -9.0650186e-01 - 2.5418876e+00 -4.2335073e+00 -8.9900667e-01 - 2.6406255e+00 -4.4397264e+00 -8.9184672e-01 - 2.7368589e+00 -4.6382386e+00 -8.7393777e-01 - 2.8773774e+00 -4.9311251e+00 -8.8468763e-01 - 2.9949688e+00 -5.1740261e+00 -8.6612263e-01 - 3.1453484e+00 -5.4868318e+00 -8.6203362e-01 - 3.3135770e+00 -5.8357940e+00 -8.5737261e-01 - 3.4952364e+00 -6.2113917e+00 -8.4757581e-01 - 3.6981414e+00 -6.6333081e+00 -8.3572547e-01 - 3.9402783e+00 -7.1350538e+00 -8.2838959e-01 - 4.2002655e+00 -7.6734604e+00 -8.1044450e-01 - 4.5242028e+00 -8.3465378e+00 -8.0076900e-01 - 4.8838430e+00 -9.0924032e+00 -7.7931303e-01 - 5.3343146e+00 -1.0025539e+01 -7.6249648e-01 - 5.8630698e+00 -1.1122352e+01 -7.3488530e-01 - 6.5778056e+00 -1.2605057e+01 -7.1772175e-01 - 7.3639304e+00 -1.4234504e+01 -6.6011885e-01 - 2.8944330e+01 -5.8989940e+01 1.0029640e+00 - 8.4608209e+00 -1.6511330e+01 3.9042213e+00 - 8.5401176e+00 -1.6676711e+01 4.2654258e+00 - 9.1466406e+00 -1.7933845e+01 5.9651184e+00 - 9.2459794e+00 -1.8139302e+01 6.7754277e+00 - 3.2607872e+00 -5.7257456e+00 4.3804914e+00 - 3.1852523e+00 -5.5693712e+00 4.4279115e+00 - 3.1694926e+00 -5.5382667e+00 4.5502271e+00 - 2.7848171e+00 -4.7398781e+00 4.1625861e+00 - 2.6903910e+00 -4.5450608e+00 4.1532586e+00 - 2.6192945e+00 -4.3964976e+00 4.1699983e+00 - 2.6348665e+00 -4.4282854e+00 4.3162488e+00 - 2.6343397e+00 -4.4270366e+00 4.4416452e+00 - 2.6247940e+00 -4.4087227e+00 4.5563432e+00 - 2.6046126e+00 -4.3665793e+00 4.6532108e+00 - 2.6041345e+00 -4.3649412e+00 4.7864975e+00 - 2.5821970e+00 -4.3186941e+00 4.8830734e+00 - 2.5914734e+00 -4.3393749e+00 5.0433327e+00 - 2.5247894e+00 -4.2003772e+00 5.0546097e+00 - 2.5036953e+00 -4.1569744e+00 5.1555259e+00 - 2.4619892e+00 -4.0712582e+00 5.2149333e+00 - 2.8673017e+00 -4.9111578e+00 6.2657101e+00 - 2.4709812e+00 -4.0887539e+00 5.5398406e+00 - 2.3576440e+00 -3.8535899e+00 5.4313196e+00 - 2.3176921e+00 -3.7719924e+00 5.4907190e+00 - 2.2365565e+00 -3.6039006e+00 5.4441804e+00 - 2.2684519e+00 -3.6689933e+00 5.6868901e+00 - 2.0706623e+00 -3.2593630e+00 5.3129669e+00 - 2.0899561e+00 -3.2992307e+00 5.5231714e+00 - 2.0339109e+00 -3.1824905e+00 5.5233657e+00 - 1.9499918e+00 -3.0084046e+00 5.4325944e+00 - 1.8292072e+00 -2.7581437e+00 5.2151412e+00 - 1.8116885e+00 -2.7219269e+00 5.3170906e+00 - 1.7987174e+00 -2.6941966e+00 5.4354504e+00 - 1.8305798e+00 -2.7621310e+00 5.7218541e+00 - 1.7834903e+00 -2.6634775e+00 5.7322969e+00 - 1.7020791e+00 -2.4960406e+00 5.6117009e+00 - 1.6630671e+00 -2.4139383e+00 5.6420339e+00 - 1.9959181e+00 -3.1049648e+00 7.2186715e+00 - 1.9201167e+00 -2.9471098e+00 7.1542823e+00 - 1.5088923e+00 -2.0936391e+00 5.5621056e+00 - 1.4571599e+00 -1.9862294e+00 5.5210821e+00 - 1.4649708e+00 -2.0025474e+00 5.7673417e+00 - 1.4249561e+00 -1.9199050e+00 5.7871412e+00 - 1.4120928e+00 -1.8928599e+00 5.9523919e+00 - 1.6587940e+00 -2.4060954e+00 7.6110024e+00 - 1.5864336e+00 -2.2565005e+00 7.5258734e+00 - 1.4733206e+00 -2.0208765e+00 7.1645165e+00 - 1.4316567e+00 -1.9353395e+00 7.2405530e+00 - 1.3782948e+00 -1.8233302e+00 7.2295500e+00 - 1.3621066e+00 -1.7907077e+00 7.5029798e+00 - 1.2886580e+00 -1.6386769e+00 7.3444470e+00 - 1.2352561e+00 -1.5269879e+00 7.3269520e+00 - 1.1041209e+00 -1.2548304e+00 6.5889417e+00 - 1.1081504e+00 -1.2637604e+00 7.0801627e+00 - 1.0509506e+00 -1.1440834e+00 6.9765915e+00 - 9.9548804e-01 -1.0291770e+00 6.8800532e+00 - 9.2981170e-01 -8.9252750e-01 6.6233091e+00 - 8.8808285e-01 -8.0544632e-01 6.6496086e+00 - 8.6775109e-01 -7.6471901e-01 7.0407098e+00 - 8.1962085e-01 -6.6479763e-01 7.0148517e+00 - 7.7141725e-01 -5.6546252e-01 6.9771084e+00 - 7.2796005e-01 -4.7560318e-01 7.0370231e+00 - 6.7478031e-01 -3.6450213e-01 6.7859677e+00 - 7.1866014e-01 -4.5562558e-01 1.0656761e+01 - 6.4468938e-01 -3.0282563e-01 1.0634161e+01 - 5.4474676e-01 -9.5833048e-02 7.0891066e+00 - 1.2177913e+00 -1.6093903e+00 -9.9204123e-01 - 1.2382473e+00 -1.6529501e+00 -9.7580124e-01 - 1.2628858e+00 -1.7094604e+00 -9.7286541e-01 - 1.2885317e+00 -1.7659573e+00 -9.6843461e-01 - 1.3167154e+00 -1.8298950e+00 -9.6935947e-01 - 1.3423208e+00 -1.8872312e+00 -9.6168307e-01 - 1.3740540e+00 -1.9585619e+00 -9.6576948e-01 - 1.4031488e+00 -2.0242879e+00 -9.6120508e-01 - 1.4322558e+00 -2.0899154e+00 -9.5464315e-01 - 1.4623722e+00 -2.1555147e+00 -9.4628662e-01 - 1.4949735e+00 -2.2294927e+00 -9.4203767e-01 - 1.5347113e+00 -2.3174418e+00 -9.4785683e-01 - 1.5646865e+00 -2.3857166e+00 -9.3295954e-01 - 1.6043353e+00 -2.4754084e+00 -9.3358588e-01 - 1.6484741e+00 -2.5735308e+00 -9.3692791e-01 - 1.6925719e+00 -2.6724974e+00 -9.3712420e-01 - 1.7376273e+00 -2.7723638e+00 -9.3407808e-01 - 1.7816440e+00 -2.8730090e+00 -9.2778317e-01 - 1.8311544e+00 -2.9821010e+00 -9.2330822e-01 - 1.8867049e+00 -3.1069202e+00 -9.2520354e-01 - 1.9431597e+00 -3.2335819e+00 -9.2270823e-01 - 2.0040584e+00 -3.3695579e+00 -9.2058190e-01 - 2.0684662e+00 -3.5137661e+00 -9.1837151e-01 - 2.1328439e+00 -3.6587298e+00 -9.1121762e-01 - 2.2060941e+00 -3.8224453e+00 -9.0729857e-01 - 2.2933146e+00 -4.0196167e+00 -9.1373013e-01 - 2.3790294e+00 -4.2091368e+00 -9.0931599e-01 - 2.4795461e+00 -4.4350509e+00 -9.1280983e-01 - 2.5571940e+00 -4.6099974e+00 -8.8733799e-01 - 2.6780569e+00 -4.8803483e+00 -8.9236989e-01 - 2.7998574e+00 -5.1522756e+00 -8.8761783e-01 - 2.9091913e+00 -5.3994462e+00 -8.6408544e-01 - 3.0706484e+00 -5.7604872e+00 -8.6849879e-01 - 3.2057468e+00 -6.0621755e+00 -8.4093433e-01 - 3.4042430e+00 -6.5065580e+00 -8.4246647e-01 - 3.6230039e+00 -6.9970607e+00 -8.3914534e-01 - 3.8621051e+00 -7.5325635e+00 -8.2852357e-01 - 4.1303102e+00 -8.1337185e+00 -8.1183925e-01 - 4.4549361e+00 -8.8618062e+00 -7.9815284e-01 - 4.8527729e+00 -9.7539247e+00 -7.8693950e-01 - 5.2516336e+00 -1.0647444e+01 -7.4212200e-01 - 5.8453735e+00 -1.1977461e+01 -7.2623657e-01 - 6.6147027e+00 -1.3700166e+01 -7.0868500e-01 - 7.6071153e+00 -1.5925206e+01 -6.7844445e-01 - 8.4711291e+00 -1.7862323e+01 3.5761128e+00 - 8.4359634e+00 -1.7782363e+01 3.9111034e+00 - 8.5463734e+00 -1.8031249e+01 4.3050705e+00 - 8.4423538e+00 -1.7798514e+01 4.9662612e+00 - 8.4769655e+00 -1.7875294e+01 5.3403920e+00 - 8.0122822e+00 -1.6834862e+01 5.4268041e+00 - 8.5956167e+00 -1.8141701e+01 6.1385701e+00 - 8.1962886e+00 -1.7246974e+01 6.2385746e+00 - 8.1265548e+00 -1.7091132e+01 6.5447042e+00 - 7.6386509e+00 -1.5998417e+01 6.5246523e+00 - 7.6025023e+00 -1.5916726e+01 6.8327305e+00 - 8.8156720e+00 -1.8636172e+01 9.4541641e+00 - 8.8663896e+00 -1.8750058e+01 9.9287476e+00 - 3.1594108e+00 -5.9614539e+00 4.3987517e+00 - 3.0633088e+00 -5.7461188e+00 4.4167574e+00 - 3.0354609e+00 -5.6820766e+00 4.5211026e+00 - 2.9889067e+00 -5.5781134e+00 4.5986633e+00 - 2.6712944e+00 -4.8663107e+00 4.2658423e+00 - 2.6406150e+00 -4.7982059e+00 4.3475770e+00 - 3.0548330e+00 -5.7261745e+00 5.1508325e+00 - 2.6387448e+00 -4.7931660e+00 4.6081616e+00 - 2.5300994e+00 -4.5495622e+00 4.5540630e+00 - 2.5135328e+00 -4.5142895e+00 4.6583560e+00 - 2.5068466e+00 -4.4987833e+00 4.7805840e+00 - 2.4797592e+00 -4.4377315e+00 4.8660486e+00 - 2.4269132e+00 -4.3195370e+00 4.8993924e+00 - 2.4424673e+00 -4.3530151e+00 5.0721589e+00 - 2.4312756e+00 -4.3292014e+00 5.1946057e+00 - 2.9536387e+00 -5.5005603e+00 6.5198295e+00 - 2.9142667e+00 -5.4117511e+00 6.6241255e+00 - 2.1129011e+00 -3.6149372e+00 4.8902033e+00 - 2.2758215e+00 -3.9807885e+00 5.4365973e+00 - 2.2549303e+00 -3.9342175e+00 5.5409603e+00 - 2.1816635e+00 -3.7690878e+00 5.5049321e+00 - 2.1837935e+00 -3.7758763e+00 5.6736615e+00 - 1.9228640e+00 -3.1902457e+00 5.0910993e+00 - 2.0104921e+00 -3.3859219e+00 5.4987022e+00 - 1.9326484e+00 -3.2115089e+00 5.4218945e+00 - 1.8414417e+00 -3.0068238e+00 5.2921125e+00 - 1.7839912e+00 -2.8785346e+00 5.2606074e+00 - 1.7416701e+00 -2.7840233e+00 5.2742288e+00 - 1.7385519e+00 -2.7773096e+00 5.4257040e+00 - 1.7631186e+00 -2.8320298e+00 5.6865703e+00 - 1.7314995e+00 -2.7618491e+00 5.7483838e+00 - 1.6508438e+00 -2.5811545e+00 5.6129117e+00 - 1.6219417e+00 -2.5159528e+00 5.6787587e+00 - 1.9894273e+00 -3.3409957e+00 7.4668462e+00 - 1.8794422e+00 -3.0938716e+00 7.2397690e+00 - 1.6281807e+00 -2.5294883e+00 6.3221807e+00 - 1.4973228e+00 -2.2369787e+00 5.9132720e+00 - 1.4362243e+00 -2.0995044e+00 5.8199606e+00 - 1.3965855e+00 -2.0102479e+00 5.8320224e+00 - 1.6570725e+00 -2.5961487e+00 7.5387874e+00 - 1.6060246e+00 -2.4806899e+00 7.5596394e+00 - 1.5728918e+00 -2.4060166e+00 7.6898253e+00 - 1.4795830e+00 -2.1963829e+00 7.4350583e+00 - 1.3861235e+00 -1.9874371e+00 7.1460839e+00 - 1.3573828e+00 -1.9240393e+00 7.2969237e+00 - 1.3061936e+00 -1.8091945e+00 7.2850665e+00 - 1.2649294e+00 -1.7163371e+00 7.3474230e+00 - 1.1612560e+00 -1.4835867e+00 6.8589928e+00 - 1.0999486e+00 -1.3462352e+00 6.7024107e+00 - 1.1348169e+00 -1.4242743e+00 7.4955187e+00 - 1.0607924e+00 -1.2590102e+00 7.2190920e+00 - 9.8029959e-01 -1.0773151e+00 6.8012213e+00 - 9.2694311e-01 -9.5855798e-01 6.6636297e+00 - 8.9290626e-01 -8.8100898e-01 6.7698499e+00 - 8.6625002e-01 -8.2166950e-01 7.0232032e+00 - 8.2211963e-01 -7.2296399e-01 7.0181061e+00 - 7.7603876e-01 -6.2119247e-01 6.9714186e+00 - 7.3470225e-01 -5.2839736e-01 7.0122520e+00 - 6.9053283e-01 -4.2794077e-01 6.9616126e+00 - 7.3166325e-01 -5.2268343e-01 1.0352609e+01 - 6.6876388e-01 -3.8013154e-01 1.0540906e+01 - 6.0103053e-01 -2.3035082e-01 1.0646775e+01 - 5.2052113e-01 -4.8186503e-02 7.0697848e+00 - 1.1565541e+00 -1.5952985e+00 -9.8474896e-01 - 1.1775951e+00 -1.6453143e+00 -9.7660449e-01 - 1.2038162e+00 -1.7083460e+00 -9.8186724e-01 - 1.2248143e+00 -1.7592208e+00 -9.7087668e-01 - 1.2483477e+00 -1.8175562e+00 -9.6564128e-01 - 1.2744798e+00 -1.8823306e+00 -9.6571122e-01 - 1.3016212e+00 -1.9470767e+00 -9.6398656e-01 - 1.3287134e+00 -2.0127311e+00 -9.6041456e-01 - 1.3557571e+00 -2.0792889e+00 -9.5489537e-01 - 1.3863418e+00 -2.1533085e+00 -9.5393600e-01 - 1.4144083e+00 -2.2197297e+00 -9.4442491e-01 - 1.4449587e+00 -2.2945394e+00 -9.3922117e-01 - 1.4815288e+00 -2.3852389e+00 -9.4368362e-01 - 1.5165795e+00 -2.4683954e+00 -9.3949765e-01 - 1.5505873e+00 -2.5523653e+00 -9.3276204e-01 - 1.5951540e+00 -2.6597474e+00 -9.4025562e-01 - 1.6361466e+00 -2.7604477e+00 -9.3874525e-01 - 1.6780970e+00 -2.8620479e+00 -9.3399246e-01 - 1.7270806e+00 -2.9794751e+00 -9.3641212e-01 - 1.7759679e+00 -3.0987041e+00 -9.3483748e-01 - 1.8248190e+00 -3.2187379e+00 -9.2931811e-01 - 1.8816513e+00 -3.3555774e+00 -9.2932679e-01 - 1.9384517e+00 -3.4931873e+00 -9.2469160e-01 - 1.9952202e+00 -3.6315674e+00 -9.1541252e-01 - 2.0589214e+00 -3.7876110e+00 -9.1001075e-01 - 2.1305601e+00 -3.9613242e+00 -9.0739080e-01 - 2.2135668e+00 -4.1620840e+00 -9.1041540e-01 - 2.2965558e+00 -4.3635008e+00 -9.0649895e-01 - 2.3794675e+00 -4.5665667e+00 -8.9549203e-01 - 2.4852226e+00 -4.8218353e+00 -8.9797070e-01 - 2.5908531e+00 -5.0796465e+00 -8.9121194e-01 - 2.6826420e+00 -5.3024578e+00 -8.6306581e-01 - 2.8293472e+00 -5.6587668e+00 -8.7092559e-01 - 2.9586754e+00 -5.9725696e+00 -8.5193929e-01 - 3.1324336e+00 -6.3953624e+00 -8.5278173e-01 - 3.2889395e+00 -6.7736207e+00 -8.2617804e-01 - 3.5195071e+00 -7.3334354e+00 -8.3072459e-01 - 3.7544532e+00 -7.9046338e+00 -8.1681453e-01 - 4.0347579e+00 -8.5869867e+00 -8.0460993e-01 - 4.3570811e+00 -9.3698786e+00 -7.8640369e-01 - 4.7188378e+00 -1.0246762e+01 -7.5469319e-01 - 5.1703895e+00 -1.1344769e+01 -7.2384321e-01 - 5.7635282e+00 -1.2784544e+01 -6.9703318e-01 - 6.5914595e+00 -1.4796743e+01 -6.8118237e-01 - 7.6369892e+00 -1.7336370e+01 -6.3945626e-01 - 9.5511129e+00 -2.1988440e+01 3.0813269e+00 - 9.5400677e+00 -2.1961092e+01 3.4970604e+00 - 8.1217663e+00 -1.8515445e+01 3.8148387e+00 - 8.0117479e+00 -1.8247571e+01 4.1263038e+00 - 8.0889044e+00 -1.8435642e+01 4.8760185e+00 - 8.0242275e+00 -1.8280089e+01 5.2026564e+00 - 7.8353568e+00 -1.7822051e+01 5.4502600e+00 - 7.2694205e+00 -1.6446536e+01 5.4350624e+00 - 7.2353838e+00 -1.6363011e+01 5.7422361e+00 - 7.3929381e+00 -1.6746301e+01 6.1936051e+00 - 7.6739912e+00 -1.7429076e+01 6.7633136e+00 - 7.1347933e+00 -1.6120495e+01 6.6649463e+00 - 7.0674829e+00 -1.5956203e+01 6.9422090e+00 - 7.3021922e+00 -1.6527146e+01 7.5058860e+00 - 8.3418824e+00 -1.9052881e+01 8.9098439e+00 - 8.3448268e+00 -1.9059350e+01 9.3281604e+00 - 8.4774308e+00 -1.9381100e+01 9.8975970e+00 - 8.1807150e+00 -1.8660686e+01 9.9854417e+00 - 8.0855294e+00 -1.8428960e+01 1.0293993e+01 - 8.1901357e+00 -1.8683222e+01 1.0855267e+01 - 2.9957459e+00 -6.0637401e+00 4.3416296e+00 - 2.8987522e+00 -5.8296573e+00 4.3523082e+00 - 2.9395576e+00 -5.9274273e+00 4.5538220e+00 - 2.8926031e+00 -5.8134687e+00 4.6301912e+00 - 2.8710175e+00 -5.7623469e+00 4.7445467e+00 - 2.8750041e+00 -5.7708887e+00 4.9004353e+00 - 2.8394880e+00 -5.6839292e+00 4.9923834e+00 - 2.8127133e+00 -5.6188321e+00 5.0990729e+00 - 2.4453137e+00 -4.7267433e+00 4.5793461e+00 - 2.7994523e+00 -5.5884753e+00 5.3910191e+00 - 2.8121726e+00 -5.6199720e+00 5.5800256e+00 - 2.7485553e+00 -5.4648058e+00 5.6176195e+00 - 2.2987997e+00 -4.3706684e+00 4.9661837e+00 - 2.3290296e+00 -4.4451593e+00 5.1792301e+00 - 2.2696258e+00 -4.3016640e+00 5.1889387e+00 - 2.7765975e+00 -5.5320659e+00 6.5789461e+00 - 2.0137182e+00 -3.6785671e+00 4.8415897e+00 - 1.9419599e+00 -3.5042623e+00 4.7901811e+00 - 1.9748883e+00 -3.5843940e+00 5.0141022e+00 - 1.8854766e+00 -3.3677289e+00 4.9055450e+00 - 2.3199390e+00 -4.4233373e+00 6.3136102e+00 - 1.8078970e+00 -3.1790426e+00 4.9547880e+00 - 1.7836298e+00 -3.1200805e+00 5.0218154e+00 - 2.1038997e+00 -3.8990095e+00 6.2070785e+00 - 1.7765734e+00 -3.1020740e+00 5.2948085e+00 - 2.1296631e+00 -3.9620019e+00 6.6864143e+00 - 2.1188320e+00 -3.9347919e+00 6.8574515e+00 - 1.5925289e+00 -2.6570863e+00 5.1040845e+00 - 1.7227764e+00 -2.9730413e+00 5.7670655e+00 - 1.6685901e+00 -2.8402000e+00 5.7302094e+00 - 1.9350535e+00 -3.4884088e+00 7.0382154e+00 - 1.5572943e+00 -2.5717029e+00 5.6288424e+00 - 1.5349372e+00 -2.5150988e+00 5.7112932e+00 - 1.7947653e+00 -3.1468784e+00 7.1399795e+00 - 1.5572968e+00 -2.5700496e+00 6.2271989e+00 - 1.5446645e+00 -2.5390956e+00 6.3906534e+00 - 1.4220854e+00 -2.2416298e+00 5.9704355e+00 - 1.3890110e+00 -2.1613323e+00 6.0120347e+00 - 1.3132697e+00 -1.9784561e+00 5.8053369e+00 - 1.5458845e+00 -2.5431854e+00 7.4803915e+00 - 1.4970079e+00 -2.4243867e+00 7.4903522e+00 - 1.4783592e+00 -2.3795796e+00 7.7032222e+00 - 1.3582143e+00 -2.0872877e+00 7.2020443e+00 - 1.3146596e+00 -1.9803718e+00 7.2215695e+00 - 1.3085396e+00 -1.9660132e+00 7.5433967e+00 - 1.2300775e+00 -1.7756120e+00 7.2829787e+00 - 1.2079344e+00 -1.7224545e+00 7.4981617e+00 - 1.0772731e+00 -1.4046491e+00 6.6700885e+00 - 1.0524092e+00 -1.3439666e+00 6.8315513e+00 - 1.0609485e+00 -1.3647784e+00 7.3919151e+00 - 9.6755890e-01 -1.1382553e+00 6.7906892e+00 - 9.2107570e-01 -1.0244416e+00 6.7032606e+00 - 8.8716506e-01 -9.4382115e-01 6.7907056e+00 - 8.6438515e-01 -8.8771608e-01 7.0644195e+00 - 8.2243874e-01 -7.8505322e-01 7.0406909e+00 - 7.8041998e-01 -6.8399998e-01 7.0248518e+00 - 7.4026662e-01 -5.8669264e-01 7.0368201e+00 - 6.9822076e-01 -4.8430884e-01 6.9871739e+00 - 6.5315435e-01 -3.7524716e-01 6.8058549e+00 - 6.9086228e-01 -4.6798528e-01 1.0656841e+01 - 6.2611344e-01 -3.1021394e-01 1.0604202e+01 - 5.3963712e-01 -9.8543124e-02 7.1090963e+00 - 1.1180640e+00 -1.6357253e+00 -9.7711052e-01 - 1.1396373e+00 -1.6931349e+00 -9.7581350e-01 - 1.1611602e+00 -1.7514627e+00 -9.7286891e-01 - 1.1811029e+00 -1.8032495e+00 -9.6132623e-01 - 1.2078207e+00 -1.8744749e+00 -9.6939182e-01 - 1.2328994e+00 -1.9401464e+00 -9.6861001e-01 - 1.2579301e+00 -2.0067163e+00 -9.6578112e-01 - 1.2829713e+00 -2.0732024e+00 -9.6125433e-01 - 1.3104957e+00 -2.1480820e+00 -9.6113476e-01 - 1.3339071e+00 -2.2089402e+00 -9.4626244e-01 - 1.3624543e+00 -2.2836832e+00 -9.4215098e-01 - 1.3908953e+00 -2.3603067e+00 -9.3564326e-01 - 1.4254758e+00 -2.4508312e+00 -9.3900071e-01 - 1.4574184e+00 -2.5357461e+00 -9.3360746e-01 - 1.4953864e+00 -2.6365065e+00 -9.3698151e-01 - 1.5333138e+00 -2.7381062e+00 -9.3710995e-01 - 1.5697213e+00 -2.8321679e+00 -9.2868986e-01 - 1.6075659e+00 -2.9354610e+00 -9.2262673e-01 - 1.6534445e+00 -3.0546219e+00 -9.2333973e-01 - 1.7017658e+00 -3.1830157e+00 -9.2521434e-01 - 1.7475118e+00 -3.3047832e+00 -9.1798830e-01 - 1.8027240e+00 -3.4516895e+00 -9.2069436e-01 - 1.8529405e+00 -3.5825594e+00 -9.0954259e-01 - 1.9125107e+00 -3.7404980e+00 -9.0692542e-01 - 1.9780202e+00 -3.9160000e+00 -9.0738335e-01 - 2.0479886e+00 -4.1006981e+00 -9.0581321e-01 - 2.1213603e+00 -4.2955041e+00 -9.0166288e-01 - 2.1991963e+00 -4.4994617e+00 -8.9458558e-01 - 2.2863573e+00 -4.7312336e+00 -8.9089963e-01 - 2.3779334e+00 -4.9730655e+00 -8.8243937e-01 - 2.4822777e+00 -5.2519852e+00 -8.7813575e-01 - 2.5979687e+00 -5.5586380e+00 -8.7313489e-01 - 2.7146647e+00 -5.8658112e+00 -8.5720109e-01 - 2.8485257e+00 -6.2202800e+00 -8.4364594e-01 - 3.0169111e+00 -6.6657215e+00 -8.4253700e-01 - 3.1817810e+00 -7.1040133e+00 -8.2293583e-01 - 3.3958325e+00 -7.6723770e+00 -8.1774736e-01 - 3.6143842e+00 -8.2501208e+00 -7.9400161e-01 - 3.8958662e+00 -8.9957417e+00 -7.8188734e-01 - 4.2092738e+00 -9.8269296e+00 -7.5733890e-01 - 4.6290308e+00 -1.0936056e+01 -7.4666998e-01 - 5.1539940e+00 -1.2326284e+01 -7.3419831e-01 - 5.6789114e+00 -1.3719972e+01 -6.7029249e-01 - 6.2369401e+00 -1.5197789e+01 -5.6359318e-01 - 7.2316979e+00 -1.7832537e+01 -4.9944003e-01 - 7.4338664e+00 -1.8367484e+01 4.8658508e-01 - 7.5167554e+00 -1.8588267e+01 8.2727164e-01 - 8.1000490e+00 -2.0131943e+01 1.9403011e+00 - 8.2124376e+00 -2.0430988e+01 2.3365300e+00 - 8.3129046e+00 -2.0695766e+01 2.7417553e+00 - 8.8807093e+00 -2.2200586e+01 3.2857641e+00 - 6.6334286e+00 -1.6248311e+01 2.9793887e+00 - 6.4267599e+00 -1.5701965e+01 3.5088989e+00 - 6.3826914e+00 -1.5584112e+01 3.7882088e+00 - 5.7082679e+00 -1.3797746e+01 3.7339905e+00 - 6.2511607e+00 -1.5236078e+01 4.3140216e+00 - 6.1508274e+00 -1.4969631e+01 4.5480016e+00 - 5.9120620e+00 -1.4336807e+01 4.6795584e+00 - 5.8193354e+00 -1.4092737e+01 4.8963728e+00 - 6.2163162e+00 -1.5145428e+01 5.4901209e+00 - 6.2353897e+00 -1.5194792e+01 5.8117320e+00 - 5.8580271e+00 -1.4195364e+01 5.7846861e+00 - 5.7471263e+00 -1.3902479e+01 5.9726720e+00 - 5.8259234e+00 -1.4109587e+01 6.3413446e+00 - 5.7850949e+00 -1.4003148e+01 6.5967674e+00 - 5.6577656e+00 -1.3665636e+01 6.7545187e+00 - 5.5988274e+00 -1.3509351e+01 6.9817626e+00 - 6.7170672e+00 -1.6472731e+01 8.6565318e+00 - 6.5380048e+00 -1.5995753e+01 8.7926041e+00 - 7.5371948e+00 -1.8644078e+01 1.0506233e+01 - 7.4967902e+00 -1.8536830e+01 1.0879359e+01 - 7.6097282e+00 -1.8837675e+01 1.1482228e+01 - 7.5467672e+00 -1.8671806e+01 1.1836882e+01 - 2.7089594e+00 -5.8538554e+00 4.9869532e+00 - 2.6435192e+00 -5.6788299e+00 5.0182723e+00 - 2.7614669e+00 -5.9935366e+00 5.5703308e+00 - 2.7532752e+00 -5.9714073e+00 5.7230794e+00 - 6.2028706e+00 -1.5112334e+01 1.3849083e+01 - 2.2160730e+00 -4.5466536e+00 5.3005765e+00 - 2.4025142e+00 -5.0417695e+00 5.9387071e+00 - 2.1281121e+00 -4.3158154e+00 5.3780416e+00 - 2.0712236e+00 -4.1631366e+00 5.3737649e+00 - 1.8436492e+00 -3.5604068e+00 4.8730555e+00 - 1.8997335e+00 -3.7091116e+00 5.1783126e+00 - 2.0263807e+00 -4.0449827e+00 5.7187458e+00 - 1.7254946e+00 -3.2477833e+00 4.9246455e+00 - 1.6875343e+00 -3.1474779e+00 4.9390555e+00 - 1.6896738e+00 -3.1531593e+00 5.0897081e+00 - 1.6996680e+00 -3.1797510e+00 5.2731829e+00 - 1.6818060e+00 -3.1320522e+00 5.3635545e+00 - 1.9570722e+00 -3.8616303e+00 6.5789007e+00 - 1.9227893e+00 -3.7697594e+00 6.6500736e+00 - 1.9328864e+00 -3.7986230e+00 6.9090528e+00 - 1.6294969e+00 -2.9950403e+00 5.8367103e+00 - 1.8520487e+00 -3.5839258e+00 7.0135025e+00 - 1.5431097e+00 -2.7666695e+00 5.8260786e+00 - 1.4886294e+00 -2.6204047e+00 5.7562223e+00 - 1.6308950e+00 -2.9990396e+00 6.6661217e+00 - 1.5274157e+00 -2.7230921e+00 6.3608881e+00 - 1.5034928e+00 -2.6603477e+00 6.4640716e+00 - 1.4979828e+00 -2.6465727e+00 6.6739858e+00 - 1.5250046e+00 -2.7186780e+00 7.0925879e+00 - 1.4739629e+00 -2.5837875e+00 7.0604172e+00 - 1.3992897e+00 -2.3836084e+00 6.8600682e+00 - 1.3771385e+00 -2.3269061e+00 7.0052903e+00 - 1.3393543e+00 -2.2246775e+00 7.0384276e+00 - 1.3648746e+00 -2.2937389e+00 7.5568121e+00 - 1.2715049e+00 -2.0453093e+00 7.1743766e+00 - 1.2335016e+00 -1.9474102e+00 7.2210453e+00 - 1.2328764e+00 -1.9440689e+00 7.5902399e+00 - 1.1515737e+00 -1.7297778e+00 7.2419540e+00 - 1.0941996e+00 -1.5768534e+00 7.0805745e+00 - 1.0224801e+00 -1.3862508e+00 6.7314956e+00 - 1.0085574e+00 -1.3495348e+00 7.0093152e+00 - 9.5269753e-01 -1.2021313e+00 6.7992383e+00 - 9.1290633e-01 -1.0962568e+00 6.7620216e+00 - 8.8931779e-01 -1.0329035e+00 6.9585882e+00 - 8.5758597e-01 -9.5094569e-01 7.0755903e+00 - 8.1325161e-01 -8.3345545e-01 6.9638374e+00 - 7.8168215e-01 -7.4916866e-01 7.0875320e+00 - 7.3907469e-01 -6.3549964e-01 6.9615391e+00 - 6.9538873e-01 -5.2034917e-01 6.7833155e+00 - 6.6479377e-01 -4.4043791e-01 6.9816117e+00 - 5.9786686e-01 -2.6195005e-01 7.4238762e+00 - 5.8762750e-01 -2.3555480e-01 1.0626689e+01 - 5.1753031e-01 -4.9522924e-02 7.0998061e+00 - 1.0595943e+00 -1.6251751e+00 -9.7716989e-01 - 1.0775794e+00 -1.6760164e+00 -9.6916609e-01 - 1.0955117e+00 -1.7277955e+00 -9.5991421e-01 - 1.1176283e+00 -1.7925104e+00 -9.6366687e-01 - 1.1381058e+00 -1.8516712e+00 -9.5857214e-01 - 1.1627117e+00 -1.9247303e+00 -9.6573325e-01 - 1.1806213e+00 -1.9772058e+00 -9.5033935e-01 - 1.2087179e+00 -2.0586449e+00 -9.6041271e-01 - 1.2327063e+00 -2.1260232e+00 -9.5493430e-01 - 1.2556480e+00 -2.1942444e+00 -9.4750551e-01 - 1.2821319e+00 -2.2699176e+00 -9.4443679e-01 - 1.3111014e+00 -2.3539646e+00 -9.4537578e-01 - 1.3374926e+00 -2.4314100e+00 -9.3771351e-01 - 1.3664327e+00 -2.5162076e+00 -9.3360912e-01 - 1.3988609e+00 -2.6094049e+00 -9.3281649e-01 - 1.4287108e+00 -2.6960007e+00 -9.2342259e-01 - 1.4696020e+00 -2.8143157e+00 -9.3335789e-01 - 1.4994275e+00 -2.9016227e+00 -9.1812160e-01 - 1.5411794e+00 -3.0226442e+00 -9.2092006e-01 - 1.5804157e+00 -3.1360474e+00 -9.1476730e-01 - 1.6281132e+00 -3.2745832e+00 -9.1964209e-01 - 1.6673361e+00 -3.3886089e+00 -9.0584916e-01 - 1.7218668e+00 -3.5466344e+00 -9.1110634e-01 - 1.7729482e+00 -3.6959498e+00 -9.0675954e-01 - 1.8284201e+00 -3.8555222e+00 -9.0163352e-01 - 1.8887748e+00 -4.0335799e+00 -8.9923023e-01 - 1.9570727e+00 -4.2292628e+00 -8.9870989e-01 - 2.0242927e+00 -4.4265541e+00 -8.9149541e-01 - 2.0994035e+00 -4.6424036e+00 -8.8481593e-01 - 2.1769289e+00 -4.8682265e+00 -8.7405492e-01 - 2.2647861e+00 -5.1218553e+00 -8.6529017e-01 - 2.3609277e+00 -5.4040920e+00 -8.5696760e-01 - 2.4708505e+00 -5.7233586e+00 -8.5040780e-01 - 2.5969990e+00 -6.0888733e+00 -8.4647276e-01 - 2.7334026e+00 -6.4838378e+00 -8.3734362e-01 - 2.8884347e+00 -6.9351174e+00 -8.2865538e-01 - 3.0292090e+00 -7.3420439e+00 -7.9253056e-01 - 3.1979343e+00 -7.8331196e+00 -7.6063748e-01 - 3.3318430e+00 -8.2228789e+00 -6.9017375e-01 - 3.6428501e+00 -9.1249089e+00 -7.0136440e-01 - 4.0092757e+00 -1.0187454e+01 -7.0628082e-01 - 4.3824565e+00 -1.1272690e+01 -6.7517654e-01 - 4.8479198e+00 -1.2621017e+01 -6.3867277e-01 - 5.4104015e+00 -1.4254159e+01 -5.8411279e-01 - 6.0214735e+00 -1.6030349e+01 -4.8284722e-01 - 7.0850358e+00 -1.9117352e+01 -4.1333027e-01 - 6.7665413e+00 -1.8194269e+01 -7.8443226e-03 - 6.7453428e+00 -1.8132017e+01 3.3093720e-01 - 6.7743490e+00 -1.8216501e+01 6.6433190e-01 - 6.9541479e+00 -1.8739254e+01 1.0006929e+00 - 7.2374095e+00 -1.9559017e+01 1.7230249e+00 - 7.5213300e+00 -2.0384430e+01 2.1306432e+00 - 6.6434080e+00 -1.7835432e+01 2.3197067e+00 - 6.0866787e+00 -1.6218985e+01 2.5013251e+00 - 6.1675860e+00 -1.6455302e+01 2.8297741e+00 - 6.0523493e+00 -1.6122241e+01 3.0943018e+00 - 6.0660782e+00 -1.6159904e+01 3.4026530e+00 - 5.4791002e+00 -1.4455407e+01 3.4220197e+00 - 5.3330695e+00 -1.4031647e+01 3.6172834e+00 - 5.3141774e+00 -1.3976621e+01 3.8740055e+00 - 5.4427841e+00 -1.4353007e+01 4.2272919e+00 - 5.4461161e+00 -1.4362353e+01 4.5074774e+00 - 5.3786857e+00 -1.4164380e+01 4.7357210e+00 - 5.3938858e+00 -1.4209970e+01 5.0276335e+00 - 5.4049431e+00 -1.4241261e+01 5.3196671e+00 - 5.4509231e+00 -1.4376116e+01 5.6491339e+00 - 5.4304246e+00 -1.4315275e+01 5.9199969e+00 - 5.5064118e+00 -1.4535983e+01 6.2941636e+00 - 5.8053881e+00 -1.5406078e+01 6.9310732e+00 - 5.8225450e+00 -1.5455199e+01 7.2754122e+00 - 5.5387913e+00 -1.4630730e+01 7.2526141e+00 - 5.4899665e+00 -1.4490802e+01 7.5061339e+00 - 5.8544080e+00 -1.5546552e+01 8.3217070e+00 - 5.9707290e+00 -1.5886120e+01 8.8357534e+00 - 5.7731971e+00 -1.5313306e+01 8.8998293e+00 - 5.7948148e+00 -1.5373669e+01 9.2857459e+00 - 5.9128994e+00 -1.5719344e+01 9.8405326e+00 - 6.4942965e+00 -1.7406851e+01 1.1205671e+01 - 7.0356182e+00 -1.8979625e+01 1.2590428e+01 - 5.9071346e+00 -1.5703049e+01 1.3067546e+01 - 2.5800632e+00 -6.0406492e+00 5.8146716e+00 - 2.5136367e+00 -5.8481487e+00 5.8331199e+00 - 2.4909353e+00 -5.7826481e+00 5.9528806e+00 - 2.4321646e+00 -5.6131635e+00 5.9817284e+00 - 2.1185695e+00 -4.7021164e+00 5.3235652e+00 - 2.0967608e+00 -4.6370046e+00 5.4164063e+00 - 2.2071162e+00 -4.9571545e+00 5.8900831e+00 - 1.8784703e+00 -4.0060287e+00 5.0916651e+00 - 1.8463251e+00 -3.9105700e+00 5.1367158e+00 - 1.8062596e+00 -3.7957564e+00 5.1579325e+00 - 1.8609252e+00 -3.9524028e+00 5.4833143e+00 - 1.6369190e+00 -3.3018610e+00 4.8792999e+00 - 1.6381364e+00 -3.3058427e+00 5.0226654e+00 - 1.6376076e+00 -3.3056418e+00 5.1673372e+00 - 1.8335079e+00 -3.8729709e+00 6.0592804e+00 - 1.6539956e+00 -3.3523553e+00 5.5389960e+00 - 1.8137617e+00 -3.8177651e+00 6.3589519e+00 - 1.7738666e+00 -3.7005585e+00 6.3881594e+00 - 1.5691743e+00 -3.1068287e+00 5.6938135e+00 - 1.5351417e+00 -3.0083156e+00 5.7172988e+00 - 1.5114474e+00 -2.9401345e+00 5.7888741e+00 - 1.4653502e+00 -2.8059159e+00 5.7491967e+00 - 1.4416958e+00 -2.7369005e+00 5.8174265e+00 - 1.4206515e+00 -2.6752637e+00 5.9018237e+00 - 1.3718868e+00 -2.5341246e+00 5.8366905e+00 - 1.4831704e+00 -2.8587194e+00 6.6862441e+00 - 1.4466982e+00 -2.7509489e+00 6.7113904e+00 - 1.4022831e+00 -2.6229726e+00 6.6894321e+00 - 1.3770267e+00 -2.5486217e+00 6.7823394e+00 - 1.3412670e+00 -2.4457733e+00 6.8102272e+00 - 1.3108032e+00 -2.3565619e+00 6.8728971e+00 - 1.2828306e+00 -2.2772272e+00 6.9618707e+00 - 1.2672832e+00 -2.2291686e+00 7.1430222e+00 - 1.2629245e+00 -2.2178411e+00 7.4463652e+00 - 1.1992855e+00 -2.0341810e+00 7.2499668e+00 - 1.1951001e+00 -2.0214690e+00 7.5813751e+00 - 1.1542565e+00 -1.9017415e+00 7.5794259e+00 - 1.0843697e+00 -1.6993724e+00 7.2675018e+00 - 1.0345454e+00 -1.5560851e+00 7.1433966e+00 - 9.7587716e-01 -1.3860827e+00 6.8800579e+00 - 9.3746867e-01 -1.2735856e+00 6.8364986e+00 - 9.0430823e-01 -1.1771712e+00 6.8591809e+00 - 8.7031939e-01 -1.0767610e+00 6.8603449e+00 - 8.5317475e-01 -1.0290027e+00 7.1747855e+00 - 8.1559815e-01 -9.1995765e-01 7.1435063e+00 - 7.7531194e-01 -8.0226581e-01 7.0407295e+00 - 7.4128116e-01 -7.0373793e-01 7.0645145e+00 - 7.0453976e-01 -5.9553988e-01 6.9970271e+00 - 6.6578132e-01 -4.8326058e-01 6.8477503e+00 - 6.3447699e-01 -3.9376064e-01 6.9555668e+00 - 6.0849505e-01 -3.1738569e-01 7.4112262e+00 - 5.7183521e-01 -2.1059877e-01 7.3961726e+00 - 5.3346542e-01 -1.0067193e-01 7.0991270e+00 - 9.6877606e-01 -1.5034713e+00 -9.7990937e-01 - 9.8216060e-01 -1.5477970e+00 -9.6749277e-01 - 1.0007196e+00 -1.6051830e+00 -9.6938227e-01 - 1.0208153e+00 -1.6699740e+00 -9.7712363e-01 - 1.0367481e+00 -1.7216569e+00 -9.6836478e-01 - 1.0552145e+00 -1.7808151e+00 -9.6566073e-01 - 1.0752801e+00 -1.8463616e+00 -9.6845859e-01 - 1.0937066e+00 -1.9063542e+00 -9.6240906e-01 - 1.1131411e+00 -1.9663284e+00 -9.5476468e-01 - 1.1356475e+00 -2.0411225e+00 -9.5902378e-01 - 1.1550428e+00 -2.1019261e+00 -9.4793405e-01 - 1.1785118e+00 -2.1775806e+00 -9.4815172e-01 - 1.2029317e+00 -2.2541890e+00 -9.4622561e-01 - 1.2263671e+00 -2.3306286e+00 -9.4209903e-01 - 1.2507539e+00 -2.4080171e+00 -9.3572880e-01 - 1.2776282e+00 -2.4937647e+00 -9.3306665e-01 - 1.3044583e+00 -2.5803811e+00 -9.2775816e-01 - 1.3338398e+00 -2.6743300e+00 -9.2560804e-01 - 1.3656548e+00 -2.7775856e+00 -9.2611770e-01 - 1.3984274e+00 -2.8817409e+00 -9.2338492e-01 - 1.4336377e+00 -2.9951684e+00 -9.2261278e-01 - 1.4713485e+00 -3.1168514e+00 -9.2345132e-01 - 1.5074809e+00 -3.2319785e+00 -9.1539214e-01 - 1.5485976e+00 -3.3637497e+00 -9.1325098e-01 - 1.5980636e+00 -3.5225783e+00 -9.2064001e-01 - 1.6366316e+00 -3.6475114e+00 -9.0510351e-01 - 1.6870351e+00 -3.8079165e+00 -9.0270858e-01 - 1.7398353e+00 -3.9784380e+00 -8.9912855e-01 - 1.8020034e+00 -4.1759147e+00 -9.0178596e-01 - 1.8606664e+00 -4.3656438e+00 -8.9409070e-01 - 1.9227340e+00 -4.5654710e+00 -8.8361550e-01 - 1.9941246e+00 -4.7931272e+00 -8.7683126e-01 - 2.0679913e+00 -5.0297501e+00 -8.6581530e-01 - 2.1535057e+00 -5.3054090e+00 -8.5915333e-01 - 2.2483685e+00 -5.6086951e+00 -8.5208738e-01 - 2.3691796e+00 -5.9955444e+00 -8.6008304e-01 - 2.4874605e+00 -6.3754080e+00 -8.5168706e-01 - 2.5572702e+00 -6.5991085e+00 -7.8741706e-01 - 2.6554739e+00 -6.9155805e+00 -7.3887091e-01 - 2.8040893e+00 -7.3908463e+00 -7.1604394e-01 - 2.9609979e+00 -7.8951650e+00 -6.8242342e-01 - 3.1623402e+00 -8.5420527e+00 -6.5806429e-01 - 3.5019615e+00 -9.6323118e+00 -6.8808103e-01 - 3.8342009e+00 -1.0697882e+01 -6.7431462e-01 - 4.2143671e+00 -1.1915928e+01 -6.4290983e-01 - 4.6691856e+00 -1.3374419e+01 -5.9569974e-01 - 5.1651086e+00 -1.4966841e+01 -5.0909605e-01 - 5.8339904e+00 -1.7111749e+01 -4.1012399e-01 - 6.2020799e+00 -1.8293069e+01 1.6391513e-01 - 6.2289024e+00 -1.8380477e+01 4.9636620e-01 - 6.2994697e+00 -1.8605859e+01 8.3044716e-01 - 6.8326426e+00 -2.0314707e+01 1.9296061e+00 - 6.9837893e+00 -2.0801291e+01 2.3332447e+00 - 6.0119005e+00 -1.7683074e+01 2.4582647e+00 - 5.3075449e+00 -1.5422934e+01 2.5559767e+00 - 5.1033956e+00 -1.4768392e+01 2.7629431e+00 - 5.1318109e+00 -1.4860177e+01 3.0496435e+00 - 4.8998823e+00 -1.4115988e+01 3.2102073e+00 - 4.9400365e+00 -1.4245566e+01 3.4974980e+00 - 4.9877899e+00 -1.4399127e+01 3.7958371e+00 - 4.9229654e+00 -1.4191246e+01 4.0247774e+00 - 4.9791578e+00 -1.4371664e+01 4.3379059e+00 - 5.0976554e+00 -1.4750526e+01 4.7097995e+00 - 4.9621705e+00 -1.4316674e+01 4.8787685e+00 - 5.0124355e+00 -1.4479949e+01 5.2067072e+00 - 4.9678913e+00 -1.4334867e+01 5.4480317e+00 - 5.0855157e+00 -1.4713702e+01 5.8597785e+00 - 5.0712192e+00 -1.4666778e+01 6.1407014e+00 - 5.1502633e+00 -1.4920779e+01 6.5349142e+00 - 5.1039633e+00 -1.4772107e+01 6.7857844e+00 - 5.1585891e+00 -1.4948970e+01 7.1685333e+00 - 5.0432379e+00 -1.4579090e+01 7.3261158e+00 - 5.3699656e+00 -1.5627719e+01 8.1180413e+00 - 5.3490706e+00 -1.5558914e+01 8.4275621e+00 - 3.8857471e+00 -1.0865530e+01 6.4289884e+00 - 5.4494252e+00 -1.5882954e+01 9.2951781e+00 - 5.4478846e+00 -1.5877859e+01 9.6581843e+00 - 5.3578861e+00 -1.5588264e+01 9.8659278e+00 - 1.8103212e+00 -4.2046002e+00 4.1416966e+00 - 5.3977383e+00 -1.5716730e+01 1.3182302e+01 - 2.3738970e+00 -6.0144067e+00 6.0113924e+00 - 2.1453351e+00 -5.2817360e+00 5.5608492e+00 - 1.7755803e+00 -4.0943409e+00 4.6630216e+00 - 1.7961918e+00 -4.1611975e+00 4.8565271e+00 - 1.8135174e+00 -4.2159771e+00 5.0468539e+00 - 1.7597572e+00 -4.0435424e+00 5.0200569e+00 - 1.7490839e+00 -4.0104292e+00 5.1284249e+00 - 1.6361116e+00 -3.6464658e+00 4.8872925e+00 - 1.6237231e+00 -3.6078904e+00 4.9823857e+00 - 1.5546802e+00 -3.3855837e+00 4.8708213e+00 - 1.5380318e+00 -3.3336454e+00 4.9470591e+00 - 1.5198802e+00 -3.2730029e+00 5.0149671e+00 - 1.5499320e+00 -3.3698472e+00 5.2825831e+00 - 1.5841680e+00 -3.4822078e+00 5.5861822e+00 - 1.5549206e+00 -3.3882181e+00 5.6253803e+00 - 1.4782269e+00 -3.1397615e+00 5.4453903e+00 - 1.4785548e+00 -3.1433298e+00 5.6161747e+00 - 1.4179005e+00 -2.9472510e+00 5.4916348e+00 - 1.3740576e+00 -2.8085134e+00 5.4447120e+00 - 1.4009964e+00 -2.8929293e+00 5.7567898e+00 - 1.3623730e+00 -2.7684396e+00 5.7322644e+00 - 1.3670408e+00 -2.7857636e+00 5.9544632e+00 - 1.4648360e+00 -3.0978931e+00 6.7357016e+00 - 1.2982821e+00 -2.5642803e+00 5.9477669e+00 - 1.3782437e+00 -2.8207478e+00 6.6769087e+00 - 1.3737991e+00 -2.8064963e+00 6.8977063e+00 - 1.3095098e+00 -2.6011289e+00 6.7134576e+00 - 1.2718097e+00 -2.4783290e+00 6.6964189e+00 - 1.2690906e+00 -2.4704891e+00 6.9517644e+00 - 1.2279283e+00 -2.3375351e+00 6.9128199e+00 - 1.1977568e+00 -2.2428938e+00 6.9640063e+00 - 1.1728243e+00 -2.1633758e+00 7.0603612e+00 - 1.1712085e+00 -2.1573344e+00 7.3817700e+00 - 1.1809145e+00 -2.1869600e+00 7.8469434e+00 - 1.1802424e+00 -2.1870878e+00 8.2673724e+00 - 1.1097900e+00 -1.9597559e+00 7.9322935e+00 - 9.9843641e-01 -1.6015953e+00 7.0516482e+00 - 9.5878670e-01 -1.4746912e+00 6.9735441e+00 - 9.2694813e-01 -1.3726561e+00 6.9898335e+00 - 9.0818927e-01 -1.3134715e+00 7.2093040e+00 - 8.8428635e-01 -1.2368574e+00 7.3695744e+00 - 8.4201295e-01 -1.0995885e+00 7.2142806e+00 - 8.1276559e-01 -1.0086935e+00 7.3123037e+00 - 7.7660439e-01 -8.9121736e-01 7.2505628e+00 - 7.4118649e-01 -7.7841698e-01 7.1965571e+00 - 7.0211328e-01 -6.5184856e-01 6.9913092e+00 - 6.6465658e-01 -5.3153057e-01 6.7833559e+00 - 6.3823412e-01 -4.4836104e-01 6.9715534e+00 - 5.8146545e-01 -2.6494077e-01 7.3639507e+00 - 5.4640377e-01 -1.5217343e-01 7.1078953e+00 - 5.1441394e-01 -5.0831202e-02 7.0898775e+00 - 9.1661191e-01 -1.4881759e+00 -9.7773865e-01 - 9.3222435e-01 -1.5444821e+00 -9.8166570e-01 - 9.4713806e-01 -1.5962720e+00 -9.7629948e-01 - 9.6100079e-01 -1.6489393e+00 -9.6968200e-01 - 9.7751747e-01 -1.7070880e+00 -9.6921843e-01 - 9.9398317e-01 -1.7661598e+00 -9.6720716e-01 - 1.0113961e+00 -1.8262151e+00 -9.6365136e-01 - 1.0278201e+00 -1.8861360e+00 -9.5859424e-01 - 1.0483725e+00 -1.9599551e+00 -9.6579296e-01 - 1.0657560e+00 -2.0207610e+00 -9.5719378e-01 - 1.0872102e+00 -2.0964424e+00 -9.6040139e-01 - 1.1060867e+00 -2.1655173e+00 -9.5490786e-01 - 1.1259731e+00 -2.2345590e+00 -9.4751986e-01 - 1.1473451e+00 -2.3119288e+00 -9.4443601e-01 - 1.1686698e+00 -2.3901921e+00 -9.3920521e-01 - 1.1925423e+00 -2.4758174e+00 -9.3773204e-01 - 1.2173680e+00 -2.5623770e+00 -9.3371559e-01 - 1.2486365e+00 -2.6741255e+00 -9.4431589e-01 - 1.2749142e+00 -2.7697983e+00 -9.4025936e-01 - 1.2996098e+00 -2.8589447e+00 -9.2790437e-01 - 1.3318158e+00 -2.9722697e+00 -9.2872072e-01 - 1.3639825e+00 -3.0864241e+00 -9.2609171e-01 - 1.3985305e+00 -3.2108181e+00 -9.2477452e-01 - 1.4306211e+00 -3.3266117e+00 -9.1485530e-01 - 1.4735978e+00 -3.4769134e+00 -9.2002167e-01 - 1.5154860e+00 -3.6289072e+00 -9.2019181e-01 - 1.5583419e+00 -3.7817219e+00 -9.1552149e-01 - 1.6035918e+00 -3.9446727e+00 -9.1006559e-01 - 1.6547824e+00 -4.1251771e+00 -9.0748504e-01 - 1.7083156e+00 -4.3167457e+00 -9.0267108e-01 - 1.7643142e+00 -4.5173648e+00 -8.9532330e-01 - 1.8237200e+00 -4.7280621e+00 -8.8479608e-01 - 1.8854770e+00 -4.9497546e+00 -8.7063717e-01 - 1.9629169e+00 -5.2261585e+00 -8.6859441e-01 - 2.0452164e+00 -5.5217489e+00 -8.6323225e-01 - 2.1499073e+00 -5.8935690e+00 -8.7096866e-01 - 2.1969809e+00 -6.0626621e+00 -8.0524705e-01 - 2.2777260e+00 -6.3525378e+00 -7.6751694e-01 - 2.3882507e+00 -6.7453443e+00 -7.4641981e-01 - 2.5035503e+00 -7.1590456e+00 -7.1611132e-01 - 2.6486197e+00 -7.6762708e+00 -6.9419639e-01 - 2.8101845e+00 -8.2523312e+00 -6.6547610e-01 - 3.0457355e+00 -9.0940585e+00 -6.6505818e-01 - 3.3594974e+00 -1.0215096e+01 -6.7978024e-01 - 3.6684424e+00 -1.1318669e+01 -6.5168024e-01 - 4.0415101e+00 -1.2654297e+01 -6.1323007e-01 - 4.4511450e+00 -1.4115805e+01 -5.4036113e-01 - 4.9380728e+00 -1.5857470e+01 -4.4023252e-01 - 5.6196137e+00 -1.8290341e+01 -3.2763448e-01 - 5.7307851e+00 -1.8689025e+01 3.2272435e-01 - 5.7926166e+00 -1.8909821e+01 6.5773438e-01 - 5.9014664e+00 -1.9297573e+01 1.0004896e+00 - 5.0215302e+00 -1.6154294e+01 2.4680638e+00 - 4.8664626e+00 -1.5600623e+01 2.7031318e+00 - 4.7212246e+00 -1.5082381e+01 2.9234666e+00 - 4.7589648e+00 -1.5219301e+01 3.2215473e+00 - 4.9800256e+00 -1.6007615e+01 3.6332303e+00 - 4.7645651e+00 -1.5239488e+01 3.7909096e+00 - 4.8329895e+00 -1.5483757e+01 4.1258353e+00 - 4.7462376e+00 -1.5174493e+01 4.3498098e+00 - 4.7776101e+00 -1.5285108e+01 4.6648547e+00 - 4.7411932e+00 -1.5155665e+01 4.9243219e+00 - 4.5710433e+00 -1.4547425e+01 5.0482574e+00 - 4.6734254e+00 -1.4912252e+01 5.4407844e+00 - 4.7079393e+00 -1.5038164e+01 5.7747869e+00 - 4.6931295e+00 -1.4983180e+01 6.0558159e+00 - 4.6144711e+00 -1.4704566e+01 6.2582240e+00 - 4.6228274e+00 -1.4731783e+01 6.5683959e+00 - 4.5375812e+00 -1.4428623e+01 6.7521122e+00 - 4.8194030e+00 -1.5437735e+01 7.4772854e+00 - 4.8187511e+00 -1.5432544e+01 7.8029353e+00 - 4.8104686e+00 -1.5404135e+01 8.1222806e+00 - 5.0107665e+00 -1.6119496e+01 8.8060330e+00 - 4.9736673e+00 -1.5986436e+01 9.0970652e+00 - 4.8718858e+00 -1.5624761e+01 9.2674841e+00 - 4.9755952e+00 -1.5993207e+01 9.8309921e+00 - 5.1595708e+00 -1.6650928e+01 1.0584992e+01 - 5.1788013e+00 -1.6720484e+01 1.1025243e+01 - 6.3608340e+00 -2.0946765e+01 1.4592773e+01 - 5.3535123e+00 -1.7347974e+01 1.2699145e+01 - 5.3116721e+00 -1.7196844e+01 1.3045285e+01 - 1.7049035e+00 -4.3070504e+00 4.1318819e+00 - 1.6637530e+00 -4.1597767e+00 4.1388885e+00 - 5.0290666e+00 -1.6188879e+01 1.3668436e+01 - 4.9348342e+00 -1.5852620e+01 1.3861388e+01 - 1.6514070e+00 -4.1159192e+00 4.4614016e+00 - 1.6715718e+00 -4.1899566e+00 4.6511590e+00 - 1.6503609e+00 -4.1133624e+00 4.7133929e+00 - 1.6789879e+00 -4.2151029e+00 4.9413100e+00 - 1.6818239e+00 -4.2258344e+00 5.0921072e+00 - 1.6373353e+00 -4.0663832e+00 5.0777080e+00 - 1.6576360e+00 -4.1398508e+00 5.2992757e+00 - 1.6447226e+00 -4.0938225e+00 5.4024148e+00 - 1.4646496e+00 -3.4478936e+00 4.8397078e+00 - 1.4241039e+00 -3.3053709e+00 4.8124024e+00 - 1.4012230e+00 -3.2219217e+00 4.8490774e+00 - 1.4623995e+00 -3.4409465e+00 5.2592969e+00 - 1.4485450e+00 -3.3933713e+00 5.3520529e+00 - 1.4598559e+00 -3.4327356e+00 5.5626823e+00 - 1.4061094e+00 -3.2397771e+00 5.4644860e+00 - 1.4040724e+00 -3.2319445e+00 5.6196040e+00 - 1.2641216e+00 -2.7339844e+00 5.0548371e+00 - 1.2470842e+00 -2.6709287e+00 5.1121062e+00 - 1.2759442e+00 -2.7739016e+00 5.4366017e+00 - 1.2972072e+00 -2.8523574e+00 5.7406108e+00 - 1.2818473e+00 -2.7966117e+00 5.8344749e+00 - 1.3602942e+00 -3.0765297e+00 6.5339448e+00 - 1.3760307e+00 -3.1320596e+00 6.8686964e+00 - 1.3003561e+00 -2.8615331e+00 6.5890900e+00 - 1.3554995e+00 -3.0603484e+00 7.2371444e+00 - 1.2234974e+00 -2.5880060e+00 6.5096900e+00 - 1.2132224e+00 -2.5517102e+00 6.6825784e+00 - 1.1936936e+00 -2.4829056e+00 6.7919439e+00 - 1.1919722e+00 -2.4756452e+00 7.0570237e+00 - 1.1472304e+00 -2.3156384e+00 6.9525876e+00 - 1.1175440e+00 -2.2119636e+00 6.9843020e+00 - 1.1023559e+00 -2.1574239e+00 7.1550192e+00 - 1.1507951e+00 -2.3297443e+00 8.0252837e+00 - 1.1324158e+00 -2.2639161e+00 8.2376157e+00 - 1.0808549e+00 -2.0806974e+00 8.0671967e+00 - 9.7222743e-01 -1.6907387e+00 7.1232900e+00 - 9.3996165e-01 -1.5778916e+00 7.1144183e+00 - 9.4394283e-01 -1.5882391e+00 7.6174240e+00 - 8.9806015e-01 -1.4251870e+00 7.4114196e+00 - 8.6763531e-01 -1.3167970e+00 7.4361977e+00 - 8.1118427e-01 -1.1154524e+00 6.9585368e+00 - 8.3108247e-01 -1.1891702e+00 8.0020331e+00 - 7.7114196e-01 -9.7118493e-01 7.3705843e+00 - 7.3878925e-01 -8.5903252e-01 7.3476300e+00 - 6.9674943e-01 -7.0700357e-01 6.9850519e+00 - 6.6793579e-01 -6.0232784e-01 6.9572381e+00 - 6.3616696e-01 -4.9199931e-01 6.8377510e+00 - 5.8910139e-01 -3.2120855e-01 7.3712849e+00 - 5.5849077e-01 -2.1378738e-01 7.3561626e+00 - 5.2735680e-01 -1.0281235e-01 7.1091825e+00 - 8.7911978e-01 -1.5281490e+00 -9.7994085e-01 - 8.9203285e-01 -1.5798525e+00 -9.7526741e-01 - 9.0653963e-01 -1.6379887e+00 -9.7699476e-01 - 9.1940851e-01 -1.6905610e+00 -9.6967498e-01 - 9.3481089e-01 -1.7506087e+00 -9.6840999e-01 - 9.4769642e-01 -1.8030481e+00 -9.5839353e-01 - 9.6623464e-01 -1.8768892e+00 -9.6848231e-01 - 9.7901823e-01 -1.9311746e+00 -9.5537046e-01 - 9.9592842e-01 -1.9993731e+00 -9.5481407e-01 - 1.0153795e+00 -2.0749877e+00 -9.5911397e-01 - 1.0322535e+00 -2.1439910e+00 -9.5461284e-01 - 1.0490790e+00 -2.2138976e+00 -9.4816451e-01 - 1.0684473e+00 -2.2912056e+00 -9.4627283e-01 - 1.0877689e+00 -2.3694022e+00 -9.4213431e-01 - 1.1095774e+00 -2.4559627e+00 -9.4180376e-01 - 1.1288671e+00 -2.5349296e+00 -9.3302136e-01 - 1.1531195e+00 -2.6307130e+00 -9.3365267e-01 - 1.1748544e+00 -2.7188930e+00 -9.2563239e-01 - 1.2030356e+00 -2.8322324e+00 -9.3162961e-01 - 1.2272218e+00 -2.9295762e+00 -9.2337267e-01 - 1.2538433e+00 -3.0362118e+00 -9.1747587e-01 - 1.2843850e+00 -3.1604724e+00 -9.1834325e-01 - 1.3198494e+00 -3.3023839e+00 -9.2527886e-01 - 1.3528007e+00 -3.4366574e+00 -9.2286374e-01 - 1.3891375e+00 -3.5811817e+00 -9.2076485e-01 - 1.4245045e+00 -3.7254189e+00 -9.1406846e-01 - 1.4632614e+00 -3.8798724e+00 -9.0698916e-01 - 1.5034143e+00 -4.0444015e+00 -8.9912110e-01 - 1.5582727e+00 -4.2628999e+00 -9.0980767e-01 - 1.6032895e+00 -4.4465812e+00 -8.9792107e-01 - 1.6589903e+00 -4.6684480e+00 -8.9462964e-01 - 1.7088214e+00 -4.8721946e+00 -8.7697704e-01 - 1.7742683e+00 -5.1317037e+00 -8.7248969e-01 - 1.8449426e+00 -5.4206560e+00 -8.6878494e-01 - 1.9039637e+00 -5.6553572e+00 -8.3714669e-01 - 1.9546780e+00 -5.8626612e+00 -7.8908678e-01 - 2.0385033e+00 -6.1998679e+00 -7.7156870e-01 - 2.1305198e+00 -6.5674597e+00 -7.4999914e-01 - 2.2336728e+00 -6.9828138e+00 -7.2734379e-01 - 2.3551670e+00 -7.4756470e+00 -7.0748777e-01 - 2.4873339e+00 -8.0077877e+00 -6.7844965e-01 - 2.6534530e+00 -8.6737235e+00 -6.5633768e-01 - 2.8901241e+00 -9.6290731e+00 -6.6013399e-01 - 3.1654502e+00 -1.0740722e+01 -6.5375562e-01 - 3.4611291e+00 -1.1931396e+01 -6.1827351e-01 - 3.8052008e+00 -1.3316594e+01 -5.6298161e-01 - 4.1783587e+00 -1.4819031e+01 -4.6994645e-01 - 4.6787400e+00 -1.6835091e+01 -3.6477581e-01 - 5.0560873e+00 -1.8357128e+01 -1.5645867e-01 - 6.8996321e+00 -2.5781897e+01 -1.5932969e-01 - 5.4125369e+00 -1.9796114e+01 2.6056455e+00 - 4.5929757e+00 -1.6490171e+01 2.6363613e+00 - 5.0782524e+00 -1.8447113e+01 3.1659359e+00 - 4.9275097e+00 -1.7839584e+01 3.4202476e+00 - 4.5282268e+00 -1.6231702e+01 3.4997913e+00 - 4.4765308e+00 -1.6023905e+01 3.7631973e+00 - 4.3652330e+00 -1.5573368e+01 3.9743472e+00 - 5.3851494e+00 -1.9686187e+01 5.1272086e+00 - 4.1841037e+00 -1.4847560e+01 4.3919203e+00 - 4.1793030e+00 -1.4825538e+01 4.6677051e+00 - 4.6732933e+00 -1.6819005e+01 5.4820767e+00 - 4.2809232e+00 -1.5234919e+01 5.3535937e+00 - 4.1644334e+00 -1.4767851e+01 5.5075906e+00 - 4.1126076e+00 -1.4560060e+01 5.7303476e+00 - 3.9672116e+00 -1.3971221e+01 5.8169403e+00 - 4.0478058e+00 -1.4299220e+01 6.2175972e+00 - 4.0802418e+00 -1.4426695e+01 6.5579974e+00 - 4.0420208e+00 -1.4276211e+01 6.7946110e+00 - 4.1804567e+00 -1.4830716e+01 7.3298366e+00 - 4.1222000e+00 -1.4596095e+01 7.5396954e+00 - 4.0630261e+00 -1.4359735e+01 7.7430663e+00 - 4.2272747e+00 -1.5022911e+01 8.3835165e+00 - 4.4240279e+00 -1.5816410e+01 9.1255122e+00 - 4.3528550e+00 -1.5530110e+01 9.3301982e+00 - 4.7816007e+00 -1.7254629e+01 1.0653149e+01 - 4.6813054e+00 -1.6851895e+01 1.0824037e+01 - 5.0396559e+00 -1.8297394e+01 1.2105223e+01 - 4.6573635e+00 -1.6757670e+01 1.1580775e+01 - 4.9480462e+00 -1.7925951e+01 1.2767104e+01 - 4.8494293e+00 -1.7529489e+01 1.2955112e+01 - 1.6211395e+00 -4.5192605e+00 4.2003378e+00 - 1.5637174e+00 -4.2904335e+00 4.1533602e+00 - 1.5502472e+00 -4.2356611e+00 4.2299392e+00 - 1.5733858e+00 -4.3268490e+00 4.4213252e+00 - 1.5394835e+00 -4.1926547e+00 4.4363413e+00 - 1.5341232e+00 -4.1709792e+00 4.5430381e+00 - 1.5409312e+00 -4.1989217e+00 4.6954607e+00 - 1.5364973e+00 -4.1789113e+00 4.8101437e+00 - 1.6034592e+00 -4.4503397e+00 5.2022871e+00 - 1.5828137e+00 -4.3645857e+00 5.2678704e+00 - 1.5569894e+00 -4.2642585e+00 5.3176481e+00 - 1.5649240e+00 -4.2917509e+00 5.5006794e+00 - 1.3876603e+00 -3.5802645e+00 4.8880637e+00 - 1.3539213e+00 -3.4416700e+00 4.8707221e+00 - 1.3387096e+00 -3.3821614e+00 4.9395690e+00 - 1.3505717e+00 -3.4282528e+00 5.1366097e+00 - 1.3385875e+00 -3.3828367e+00 5.2285595e+00 - 1.3766159e+00 -3.5342575e+00 5.5783165e+00 - 1.3558442e+00 -3.4500276e+00 5.6332625e+00 - 1.3169250e+00 -3.2963557e+00 5.5900782e+00 - 1.2626487e+00 -3.0766013e+00 5.4451073e+00 - 1.1731159e+00 -2.7156368e+00 5.0712144e+00 - 1.1554482e+00 -2.6459706e+00 5.1194506e+00 - 1.1838121e+00 -2.7580656e+00 5.4616203e+00 - 1.1801780e+00 -2.7433108e+00 5.6128023e+00 - 1.2543771e+00 -3.0444089e+00 6.3249575e+00 - 1.2664903e+00 -3.0921039e+00 6.6313105e+00 - 1.2251541e+00 -2.9269309e+00 6.5542326e+00 - 1.1772993e+00 -2.7335661e+00 6.4108242e+00 - 1.1730318e+00 -2.7153201e+00 6.6112989e+00 - 1.1324532e+00 -2.5531621e+00 6.5148410e+00 - 1.1191083e+00 -2.4994510e+00 6.6509449e+00 - 1.1578395e+00 -2.6545394e+00 7.2910364e+00 - 1.0975862e+00 -2.4097853e+00 6.9959856e+00 - 1.0742781e+00 -2.3186188e+00 7.0663245e+00 - 1.0493942e+00 -2.2193294e+00 7.1165482e+00 - 1.0262483e+00 -2.1253198e+00 7.1837421e+00 - 9.9645568e-01 -2.0046574e+00 7.1736687e+00 - 9.7241107e-01 -1.9087610e+00 7.2373709e+00 - 9.3256937e-01 -1.7477193e+00 7.0789871e+00 - 9.0937432e-01 -1.6546180e+00 7.1480284e+00 - 9.1399071e-01 -1.6715366e+00 7.6608660e+00 - 8.7993791e-01 -1.5354498e+00 7.5926873e+00 - 8.4592933e-01 -1.3969467e+00 7.4924496e+00 - 8.0839342e-01 -1.2462315e+00 7.3107316e+00 - 8.0408933e-01 -1.2290092e+00 7.8336546e+00 - 7.7600157e-01 -1.1159541e+00 7.8744081e+00 - 7.3057630e-01 -9.3325896e-01 7.4385497e+00 - 6.8920714e-01 -7.6607160e-01 6.9983249e+00 - 6.6245622e-01 -6.6047054e-01 6.9714540e+00 - 6.3486974e-01 -5.4835224e-01 6.8728787e+00 - 6.8900971e-01 -7.6786396e-01 1.1058923e+01 - 6.5113273e-01 -6.1617816e-01 1.1380680e+01 - 5.6619145e-01 -2.6953785e-01 7.3739838e+00 - 5.3723981e-01 -1.5513438e-01 7.1179101e+00 - 5.1129409e-01 -5.1135844e-02 7.0597746e+00 - 8.3845995e-01 -1.5550990e+00 -9.6614541e-01 - 8.5255117e-01 -1.6196505e+00 -9.7636461e-01 - 8.6335918e-01 -1.6731334e+00 -9.6968805e-01 - 8.7682052e-01 -1.7321027e+00 -9.6926526e-01 - 8.8864334e-01 -1.7855130e+00 -9.5989521e-01 - 9.0100396e-01 -1.8462728e+00 -9.5647373e-01 - 9.1596201e-01 -1.9134815e+00 -9.5855732e-01 - 9.2928030e-01 -1.9751411e+00 -9.5189341e-01 - 9.4419971e-01 -2.0431743e+00 -9.5043178e-01 - 9.5900977e-01 -2.1131127e+00 -9.4707327e-01 - 9.7642220e-01 -2.1894605e+00 -9.4842083e-01 - 9.9272897e-01 -2.2676384e+00 -9.4756870e-01 - 1.0085140e+00 -2.3383386e+00 -9.3817122e-01 - 1.0257846e+00 -2.4173669e+00 -9.3307790e-01 - 1.0445445e+00 -2.5046937e+00 -9.3168949e-01 - 1.0632596e+00 -2.5928944e+00 -9.2775461e-01 - 1.0860018e+00 -2.6968344e+00 -9.3288030e-01 - 1.1071658e+00 -2.7942185e+00 -9.2910828e-01 - 1.1292849e+00 -2.8925221e+00 -9.2249333e-01 - 1.1519039e+00 -2.9989948e+00 -9.1818184e-01 - 1.1793785e+00 -3.1241695e+00 -9.2098767e-01 - 1.2043978e+00 -3.2407291e+00 -9.1489183e-01 - 1.2318591e+00 -3.3665263e+00 -9.1005748e-01 - 1.2631884e+00 -3.5108814e+00 -9.1063936e-01 - 1.2969076e+00 -3.6654070e+00 -9.1113480e-01 - 1.3266882e+00 -3.8029697e+00 -8.9802489e-01 - 1.3643156e+00 -3.9757330e+00 -8.9744457e-01 - 1.4042818e+00 -4.1595899e+00 -8.9523011e-01 - 1.4481376e+00 -4.3618322e+00 -8.9493619e-01 - 1.4865699e+00 -4.5387784e+00 -8.7663290e-01 - 1.5390975e+00 -4.7797276e+00 -8.7768712e-01 - 1.5915540e+00 -5.0222765e+00 -8.7065212e-01 - 1.6512887e+00 -5.2934370e+00 -8.6535452e-01 - 1.6843501e+00 -5.4451826e+00 -8.1071486e-01 - 1.7391403e+00 -5.6998978e+00 -7.8326967e-01 - 1.8050879e+00 -6.0016937e+00 -7.6118034e-01 - 1.8825269e+00 -6.3616119e+00 -7.4420463e-01 - 1.9672246e+00 -6.7508134e+00 -7.2232491e-01 - 2.0693150e+00 -7.2165204e+00 -7.0498881e-01 - 2.1765781e+00 -7.7131374e+00 -6.7764941e-01 - 2.3060291e+00 -8.3064779e+00 -6.5218381e-01 - 2.4729781e+00 -9.0741304e+00 -6.3727453e-01 - 2.6860037e+00 -1.0056579e+01 -6.2977604e-01 - 2.9259965e+00 -1.1157125e+01 -6.0440339e-01 - 3.1986511e+00 -1.2414157e+01 -5.5969865e-01 - 3.5021279e+00 -1.3808982e+01 -4.8505836e-01 - 3.8503463e+00 -1.5409586e+01 -3.7931732e-01 - 4.1219465e+00 -1.6658455e+01 -1.9183215e-01 - 4.2511631e+00 -1.7251820e+01 7.5033858e-02 - 4.9198477e+00 -2.0331618e+01 2.7378977e-01 - 5.4200171e+00 -2.2634489e+01 2.6201564e+00 - 5.4430301e+00 -2.2739575e+01 3.0363051e+00 - 5.3247669e+00 -2.2196382e+01 3.3878061e+00 - 5.4082632e+00 -2.2578293e+01 3.8374616e+00 - 5.4955335e+00 -2.2981577e+01 4.3056698e+00 - 5.4809959e+00 -2.2912255e+01 4.7140478e+00 - 5.3972103e+00 -2.2527627e+01 5.0654482e+00 - 3.9861237e+00 -1.6038241e+01 4.1905542e+00 - 3.6930906e+00 -1.4690227e+01 4.1958544e+00 - 3.6953482e+00 -1.4700638e+01 4.4734958e+00 - 3.7071249e+00 -1.4753084e+01 4.7645661e+00 - 3.6958644e+00 -1.4704979e+01 5.0325961e+00 - 3.8342812e+00 -1.5339018e+01 5.5013583e+00 - 3.8066615e+00 -1.5213154e+01 5.7600466e+00 - 4.3051965e+00 -1.7508542e+01 6.8220705e+00 - 3.5808832e+00 -1.4172779e+01 5.9943711e+00 - 3.5712043e+00 -1.4131719e+01 6.2638402e+00 - 3.5372769e+00 -1.3975977e+01 6.4903558e+00 - 3.6482115e+00 -1.4486448e+01 6.9901379e+00 - 3.6410433e+00 -1.4454593e+01 7.2792693e+00 - 3.8230049e+00 -1.5290996e+01 7.9675036e+00 - 3.8490999e+00 -1.5409790e+01 8.3537718e+00 - 3.8340433e+00 -1.5343583e+01 8.6584786e+00 - 3.8397403e+00 -1.5367425e+01 9.0131556e+00 - 3.7775414e+00 -1.5081229e+01 9.2064774e+00 - 4.0773147e+00 -1.6460436e+01 1.0337574e+01 - 4.5003917e+00 -1.8405648e+01 1.1875198e+01 - 4.2662818e+00 -1.7330122e+01 1.1656283e+01 - 4.1647234e+00 -1.6863258e+01 1.1783965e+01 - 4.1238369e+00 -1.6677386e+01 1.2083529e+01 - 4.5822006e+00 -1.8786044e+01 1.3967815e+01 - 1.4480899e+00 -4.3620410e+00 4.1260673e+00 - 1.4381092e+00 -4.3161725e+00 4.2093718e+00 - 1.4509340e+00 -4.3778646e+00 4.3762379e+00 - 1.4931032e+00 -4.5730847e+00 4.6570422e+00 - 1.4847984e+00 -4.5335079e+00 4.7570670e+00 - 1.4385604e+00 -4.3184553e+00 4.7088976e+00 - 1.4278029e+00 -4.2692104e+00 4.7986484e+00 - 1.5445377e+00 -4.8066091e+00 5.4296832e+00 - 1.4449630e+00 -4.3519151e+00 5.1534549e+00 - 1.3915004e+00 -4.1047278e+00 5.0568871e+00 - 1.4329848e+00 -4.2978988e+00 5.3982694e+00 - 1.4303456e+00 -4.2827150e+00 5.5391114e+00 - 1.4203624e+00 -4.2384136e+00 5.6514288e+00 - 1.4414801e+00 -4.3343198e+00 5.9270636e+00 - 1.2799476e+00 -3.5900422e+00 5.2264268e+00 - 1.2461232e+00 -3.4353258e+00 5.1902683e+00 - 1.4071340e+00 -4.1754344e+00 6.2768790e+00 - 1.2826926e+00 -3.6037783e+00 5.7202958e+00 - 1.2376817e+00 -3.3986040e+00 5.6161364e+00 - 1.1983807e+00 -3.2159207e+00 5.5305729e+00 - 1.1367350e+00 -2.9305476e+00 5.2841895e+00 - 1.1178978e+00 -2.8464171e+00 5.3193040e+00 - 1.0976766e+00 -2.7510842e+00 5.3359524e+00 - 1.0931677e+00 -2.7337363e+00 5.4777004e+00 - 1.0832875e+00 -2.6870648e+00 5.5772847e+00 - 1.0846393e+00 -2.6915198e+00 5.7718359e+00 - 1.1402020e+00 -2.9511071e+00 6.4489176e+00 - 1.1152076e+00 -2.8348646e+00 6.4566543e+00 - 1.0668907e+00 -2.6126147e+00 6.2480452e+00 - 1.0361736e+00 -2.4714042e+00 6.1861011e+00 - 1.0505171e+00 -2.5357020e+00 6.5647475e+00 - 9.9163341e-01 -2.2650465e+00 6.2072351e+00 - 9.7369406e-01 -2.1838410e+00 6.2653166e+00 - 1.0293320e+00 -2.4378850e+00 7.1751117e+00 - 9.4279109e-01 -2.0417518e+00 6.4428257e+00 - 9.7522238e-01 -2.1888622e+00 7.1550519e+00 - 9.5418953e-01 -2.0930092e+00 7.2215412e+00 - 9.2575536e-01 -1.9654022e+00 7.1913924e+00 - 9.0074906e-01 -1.8487392e+00 7.1873940e+00 - 8.7898688e-01 -1.7475830e+00 7.2386076e+00 - 8.7433471e-01 -1.7274692e+00 7.5972878e+00 - 8.4277152e-01 -1.5813725e+00 7.4913539e+00 - 8.1445287e-01 -1.4502637e+00 7.4308946e+00 - 7.8348750e-01 -1.3100055e+00 7.3091251e+00 - 7.5338035e-01 -1.1709261e+00 7.1646805e+00 - 7.6011890e-01 -1.2014007e+00 7.9724367e+00 - 7.2923821e-01 -1.0594343e+00 7.8447753e+00 - 6.9054792e-01 -8.8227194e-01 7.4268701e+00 - 6.5503664e-01 -7.1701081e-01 6.9751899e+00 - 6.3051329e-01 -6.0504114e-01 6.8975289e+00 - 6.1485169e-01 -5.3511687e-01 7.2561228e+00 - 6.5157095e-01 -7.0473564e-01 1.1314859e+01 - 5.6977307e-01 -3.2605651e-01 7.3713430e+00 - 5.4627067e-01 -2.1705965e-01 7.3561992e+00 - 5.2124614e-01 -1.0445341e-01 7.1091009e+00 - 7.9862601e-01 -1.6002907e+00 -9.7528462e-01 - 8.0849176e-01 -1.6527507e+00 -9.6935357e-01 - 8.1989162e-01 -1.7126354e+00 -9.6967388e-01 - 8.2812563e-01 -1.7594823e+00 -9.5369692e-01 - 8.4265948e-01 -1.8331752e+00 -9.6567065e-01 - 8.5396726e-01 -1.8948272e+00 -9.6129754e-01 - 8.6534450e-01 -1.9554084e+00 -9.5547583e-01 - 8.7661118e-01 -2.0179046e+00 -9.4795700e-01 - 8.8947897e-01 -2.0867744e+00 -9.4564044e-01 - 9.0382989e-01 -2.1639921e+00 -9.4802756e-01 - 9.1606657e-01 -2.2272895e+00 -9.3526877e-01 - 9.3038194e-01 -2.3053070e+00 -9.3361127e-01 - 9.4465066e-01 -2.3842131e+00 -9.2970693e-01 - 9.5987088e-01 -2.4640682e+00 -9.2355894e-01 - 9.7811575e-01 -2.5596367e+00 -9.2716747e-01 - 9.9631829e-01 -2.6560594e+00 -9.2783003e-01 - 1.0144170e+00 -2.7543428e+00 -9.2569682e-01 - 1.0325336e+00 -2.8524835e+00 -9.2066718e-01 - 1.0536264e+00 -2.9672409e+00 -9.2344687e-01 - 1.0726584e+00 -3.0671353e+00 -9.1222883e-01 - 1.0960906e+00 -3.1929814e+00 -9.1327449e-01 - 1.1209680e+00 -3.3279949e+00 -9.1537871e-01 - 1.1468092e+00 -3.4638589e+00 -9.1324174e-01 - 1.1701342e+00 -3.5921096e+00 -9.0225342e-01 - 1.1983284e+00 -3.7389540e+00 -8.9618513e-01 - 1.2284633e+00 -3.9031693e+00 -8.9417800e-01 - 1.2595085e+00 -4.0691779e+00 -8.8678148e-01 - 1.2958061e+00 -4.2639135e+00 -8.8591009e-01 - 1.3335698e+00 -4.4676491e+00 -8.8270145e-01 - 1.3761088e+00 -4.6917603e+00 -8.8001905e-01 - 1.4162047e+00 -4.9071578e+00 -8.6643744e-01 - 1.4615144e+00 -5.1521070e+00 -8.5583573e-01 - 1.4814006e+00 -5.2573376e+00 -7.8949207e-01 - 1.5320329e+00 -5.5304522e+00 -7.7402954e-01 - 1.5912711e+00 -5.8433150e+00 -7.6076449e-01 - 1.6509510e+00 -6.1658432e+00 -7.3961625e-01 - 1.7259393e+00 -6.5659746e+00 -7.2745016e-01 - 1.8022673e+00 -6.9776632e+00 -7.0400904e-01 - 1.8939996e+00 -7.4656724e+00 -6.8380678e-01 - 1.9922896e+00 -7.9947558e+00 -6.5461023e-01 - 2.1125446e+00 -8.6406954e+00 -6.2899633e-01 - 2.2662042e+00 -9.4625414e+00 -6.1063089e-01 - 2.4623529e+00 -1.0508898e+01 -5.9767305e-01 - 2.6689027e+00 -1.1616631e+01 -5.5571972e-01 - 2.9050081e+00 -1.2882593e+01 -4.9292737e-01 - 3.1798240e+00 -1.4354307e+01 -4.0580683e-01 - 3.4366807e+00 -1.5728685e+01 -2.5899739e-01 - 3.5551494e+00 -1.6365820e+01 -1.8040657e-02 - 3.6534311e+00 -1.6891059e+01 2.4996106e-01 - 4.2786567e+00 -2.0242460e+01 4.6098115e-01 - 4.8528006e+00 -2.3317503e+01 3.2843228e+00 - 4.7500747e+00 -2.2766062e+01 3.6390257e+00 - 4.6728181e+00 -2.2356551e+01 3.9944648e+00 - 4.8548798e+00 -2.3333079e+01 4.5476356e+00 - 4.7831209e+00 -2.2948786e+01 4.9068880e+00 - 4.8167419e+00 -2.3128853e+01 5.3611124e+00 - 3.5119036e+00 -1.6134592e+01 4.3396087e+00 - 3.2227719e+00 -1.4586927e+01 4.2899807e+00 - 3.2530369e+00 -1.4748769e+01 4.6022528e+00 - 3.2658134e+00 -1.4818068e+01 4.8985537e+00 - 3.2769788e+00 -1.4881072e+01 5.1984588e+00 - 3.3741594e+00 -1.5400583e+01 5.6409003e+00 - 3.2594969e+00 -1.4784779e+01 5.7422933e+00 - 3.3648868e+00 -1.5352882e+01 6.2261292e+00 - 3.2182175e+00 -1.4566590e+01 6.2476214e+00 - 3.1771946e+00 -1.4345104e+01 6.4563198e+00 - 3.1900557e+00 -1.4414242e+01 6.7761412e+00 - 3.3778465e+00 -1.5420845e+01 7.4980664e+00 - 3.2744979e+00 -1.4865096e+01 7.5754188e+00 - 3.3655971e+00 -1.5358079e+01 8.1204172e+00 - 3.4091640e+00 -1.5588418e+01 8.5641441e+00 - 3.4320172e+00 -1.5712100e+01 8.9691963e+00 - 3.4336408e+00 -1.5720572e+01 9.3254431e+00 - 3.8495920e+00 -1.7951630e+01 1.0915458e+01 - 3.6273068e+00 -1.6760938e+01 1.0646635e+01 - 3.5773138e+00 -1.6490451e+01 1.0881807e+01 - 3.6574648e+00 -1.6922518e+01 1.1549323e+01 - 3.6310454e+00 -1.6780358e+01 1.1874983e+01 - 1.4912247e+00 -5.3112043e+00 4.5766198e+00 - 1.4685128e+00 -5.1927967e+00 4.6306929e+00 - 1.3504292e+00 -4.5616525e+00 4.3100306e+00 - 1.3386104e+00 -4.4960480e+00 4.3845633e+00 - 1.3258461e+00 -4.4294451e+00 4.4578510e+00 - 1.3131335e+00 -4.3619143e+00 4.5296909e+00 - 1.2973705e+00 -4.2778437e+00 4.5875175e+00 - 1.3053529e+00 -4.3202112e+00 4.7538608e+00 - 1.3364263e+00 -4.4836315e+00 5.0353677e+00 - 1.2807293e+00 -4.1888431e+00 4.9049268e+00 - 1.2728140e+00 -4.1425437e+00 4.9994111e+00 - 1.2455694e+00 -3.9966632e+00 4.9952868e+00 - 1.2450823e+00 -3.9956132e+00 5.1369127e+00 - 1.3136607e+00 -4.3640190e+00 5.6787086e+00 - 1.3348397e+00 -4.4762391e+00 5.9692651e+00 - 1.3114886e+00 -4.3507759e+00 6.0030696e+00 - 1.2580635e+00 -4.0665849e+00 5.8438012e+00 - 1.3414870e+00 -4.5139324e+00 6.5711235e+00 - 1.2758925e+00 -4.1612649e+00 6.3217454e+00 - 1.2716687e+00 -4.1406077e+00 6.4900613e+00 - 1.2344784e+00 -3.9403271e+00 6.4180345e+00 - 1.1232108e+00 -3.3448843e+00 5.7707863e+00 - 9.9259877e-01 -2.6443082e+00 4.9146200e+00 - 1.0008095e+00 -2.6853669e+00 5.1277551e+00 - 1.0444028e+00 -2.9201356e+00 5.6640142e+00 - 1.0107530e+00 -2.7420621e+00 5.5531117e+00 - 1.0126718e+00 -2.7541492e+00 5.7562459e+00 - 1.0017216e+00 -2.6911871e+00 5.8392138e+00 - 1.0393737e+00 -2.8941808e+00 6.4223018e+00 - 1.0244261e+00 -2.8142095e+00 6.4995492e+00 - 9.7601998e-01 -2.5564850e+00 6.2175024e+00 - 9.6804670e-01 -2.5137435e+00 6.3614233e+00 - 9.3841929e-01 -2.3519630e+00 6.2504987e+00 - 9.2892507e-01 -2.3006600e+00 6.3831933e+00 - 9.0759554e-01 -2.1893419e+00 6.3770329e+00 - 8.9495542e-01 -2.1222629e+00 6.4802333e+00 - 8.7071473e-01 -1.9896827e+00 6.4139691e+00 - 9.5467969e-01 -2.4408691e+00 8.0132528e+00 - 9.5088305e-01 -2.4229869e+00 8.3684332e+00 - 9.2589181e-01 -2.2909463e+00 8.3913103e+00 - 8.4881853e-01 -1.8760163e+00 7.4432736e+00 - 8.4115737e-01 -1.8359380e+00 7.7358071e+00 - 8.2012070e-01 -1.7222796e+00 7.7770881e+00 - 7.8475231e-01 -1.5300037e+00 7.4856738e+00 - 7.5313520e-01 -1.3613446e+00 7.2483667e+00 - 7.2633187e-01 -1.2163646e+00 7.0853881e+00 - 7.3591129e-01 -1.2702100e+00 7.9712745e+00 - 7.1493585e-01 -1.1565780e+00 8.0322807e+00 - 6.8891876e-01 -1.0185094e+00 7.9330164e+00 - 6.4613853e-01 -7.8661255e-01 7.0776002e+00 - 6.2386000e-01 -6.6968364e-01 6.9813581e+00 - 6.0502657e-01 -5.6820278e-01 7.0023003e+00 - 5.8801263e-01 -4.7805493e-01 7.1808841e+00 - 5.8474609e-01 -4.6173874e-01 8.6757442e+00 - 5.4991785e-01 -2.7357021e-01 7.3739828e+00 - 5.2813608e-01 -1.5709838e-01 7.1278752e+00 - 5.0830246e-01 -5.1963057e-02 7.0798586e+00 - 7.4682070e-01 -1.5790333e+00 -9.7381070e-01 - 7.5568335e-01 -1.6314723e+00 -9.6867548e-01 - 7.6508256e-01 -1.6912706e+00 -9.6968858e-01 - 7.7290347e-01 -1.7445130e+00 -9.6180396e-01 - 7.8167035e-01 -1.7987488e+00 -9.5257458e-01 - 7.9256380e-01 -1.8668062e+00 -9.5649357e-01 - 8.0193916e-01 -1.9273108e+00 -9.5156439e-01 - 8.1120396e-01 -1.9897305e+00 -9.4493809e-01 - 8.2206925e-01 -2.0585287e+00 -9.4361394e-01 - 8.3441706e-01 -2.1356796e+00 -9.4709334e-01 - 8.4671760e-01 -2.2137240e+00 -9.4842578e-01 - 8.5743799e-01 -2.2852273e+00 -9.4116013e-01 - 8.6970420e-01 -2.3640618e+00 -9.3824821e-01 - 8.8138720e-01 -2.4364254e+00 -9.2694113e-01 - 8.9663018e-01 -2.5318717e+00 -9.3173864e-01 - 9.1029362e-01 -2.6207720e+00 -9.2783819e-01 - 9.2391226e-01 -2.7105460e+00 -9.2139127e-01 - 9.4150028e-01 -2.8170367e+00 -9.2355587e-01 - 9.5657081e-01 -2.9159240e+00 -9.1706887e-01 - 9.7455789e-01 -3.0324200e+00 -9.1824177e-01 - 9.9350449e-01 -3.1498010e+00 -9.1587261e-01 - 1.0128956e+00 -3.2763087e+00 -9.1495834e-01 - 1.0346710e+00 -3.4130313e+00 -9.1485651e-01 - 1.0525072e+00 -3.5327959e+00 -9.0124921e-01 - 1.0786037e+00 -3.6971340e+00 -9.0662023e-01 - 1.0988526e+00 -3.8268869e+00 -8.8923105e-01 - 1.1248885e+00 -3.9927410e+00 -8.8481493e-01 - 1.1522639e+00 -4.1696382e+00 -8.7896124e-01 - 1.1878696e+00 -4.3918644e+00 -8.8714236e-01 - 1.2194846e+00 -4.5980606e+00 -8.8037019e-01 - 1.2577964e+00 -4.8421562e+00 -8.8128158e-01 - 1.2803613e+00 -4.9847324e+00 -8.3654117e-01 - 1.3086200e+00 -5.1651869e+00 -8.0028016e-01 - 1.3496865e+00 -5.4307627e+00 -7.8603157e-01 - 1.3931793e+00 -5.7062183e+00 -7.6580380e-01 - 1.4423463e+00 -6.0202242e+00 -7.4741402e-01 - 1.5009487e+00 -6.3932235e+00 -7.3398208e-01 - 1.5637582e+00 -6.7962971e+00 -7.1508766e-01 - 1.6360351e+00 -7.2581080e+00 -6.9595749e-01 - 1.7149809e+00 -7.7590732e+00 -6.6943028e-01 - 1.8089467e+00 -8.3593297e+00 -6.4460596e-01 - 1.9180235e+00 -9.0576341e+00 -6.1654025e-01 - 2.0582373e+00 -9.9527600e+00 -5.9547828e-01 - 2.2243851e+00 -1.1015586e+01 -5.6690480e-01 - 2.4065940e+00 -1.2178452e+01 -5.1347097e-01 - 2.6133264e+00 -1.3500089e+01 -4.3603651e-01 - 2.8433083e+00 -1.4968932e+01 -3.2545206e-01 - 2.9406084e+00 -1.5590680e+01 -1.0334617e-01 - 2.9839897e+00 -1.5864147e+01 1.5858240e-01 - 3.3210065e+00 -1.8018859e+01 3.6331400e-01 - 3.6084740e+00 -1.9854583e+01 6.4943579e-01 - 7.3586075e+00 -4.3805963e+01 1.0003682e+00 - 7.2759540e+00 -4.3275489e+01 1.7648857e+00 - 7.2211421e+00 -4.2929833e+01 2.5177227e+00 - 4.2071085e+00 -2.3679999e+01 3.0971320e+00 - 4.1764626e+00 -2.3484840e+01 3.9189196e+00 - 3.9914414e+00 -2.2306541e+01 4.5762194e+00 - 4.1279358e+00 -2.3175646e+01 5.1364874e+00 - 3.0196438e+00 -1.6098364e+01 4.1675465e+00 - 3.0181024e+00 -1.6089665e+01 4.4617904e+00 - 2.9738677e+00 -1.5806643e+01 4.6938055e+00 - 2.9651685e+00 -1.5750018e+01 4.9749161e+00 - 2.9797036e+00 -1.5841236e+01 5.2965172e+00 - 2.8793817e+00 -1.5204483e+01 5.4130083e+00 - 2.8795159e+00 -1.5201048e+01 5.7042975e+00 - 2.8938397e+00 -1.5296017e+01 6.0308909e+00 - 2.8930821e+00 -1.5291154e+01 6.3296244e+00 - 2.9105412e+00 -1.5401469e+01 6.6741767e+00 - 2.8827927e+00 -1.5227252e+01 6.9166637e+00 - 2.8980205e+00 -1.5325097e+01 7.2672227e+00 - 2.8683786e+00 -1.5132102e+01 7.5017864e+00 - 2.9098468e+00 -1.5396746e+01 7.9389082e+00 - 2.9111541e+00 -1.5409292e+01 8.2733307e+00 - 3.0843427e+00 -1.6516467e+01 9.1537964e+00 - 2.9906845e+00 -1.5915299e+01 9.2082231e+00 - 3.0337824e+00 -1.6189699e+01 9.7133994e+00 - 2.9530512e+00 -1.5674249e+01 9.7945023e+00 - 2.9757304e+00 -1.5819736e+01 1.0244986e+01 - 1.3389978e+00 -5.3598658e+00 4.2601654e+00 - 1.3150557e+00 -5.2111891e+00 4.2961325e+00 - 1.3722550e+00 -5.5764473e+00 4.6654306e+00 - 1.3267415e+00 -5.2827138e+00 4.6068675e+00 - 1.3291492e+00 -5.3004782e+00 4.7569130e+00 - 1.2322893e+00 -4.6832499e+00 4.4444155e+00 - 1.1982735e+00 -4.4654244e+00 4.4063466e+00 - 1.1870074e+00 -4.3902444e+00 4.4723936e+00 - 1.1674233e+00 -4.2683735e+00 4.4990430e+00 - 1.1757687e+00 -4.3215512e+00 4.6703227e+00 - 1.1840515e+00 -4.3762596e+00 4.8510899e+00 - 1.2817649e+00 -5.0000762e+00 5.5567917e+00 - 1.1431339e+00 -4.1105248e+00 4.8805865e+00 - 1.1411694e+00 -4.1000494e+00 5.0082400e+00 - 1.2293548e+00 -4.6666447e+00 5.7234931e+00 - 1.2260549e+00 -4.6461250e+00 5.8699832e+00 - 1.2016240e+00 -4.4871291e+00 5.8708015e+00 - 1.1771076e+00 -4.3293321e+00 5.8675745e+00 - 1.1443611e+00 -4.1220781e+00 5.7999821e+00 - 1.2168561e+00 -4.5846393e+00 6.5308258e+00 - 1.2012142e+00 -4.4827964e+00 6.6032940e+00 - 1.2001885e+00 -4.4769823e+00 6.7997562e+00 - 1.0974367e+00 -3.8227290e+00 6.1352368e+00 - 1.0883905e+00 -3.7626882e+00 6.2424668e+00 - 9.1612564e-01 -2.6629603e+00 4.8500308e+00 - 9.1042878e-01 -2.6297485e+00 4.9462483e+00 - 9.1820115e-01 -2.6789522e+00 5.1766087e+00 - 9.3946205e-01 -2.8109325e+00 5.5540454e+00 - 9.3601360e-01 -2.7931475e+00 5.7058777e+00 - 9.2843886e-01 -2.7415481e+00 5.8065064e+00 - 9.1192032e-01 -2.6340322e+00 5.8104160e+00 - 9.5102558e-01 -2.8843797e+00 6.4919495e+00 - 9.3437982e-01 -2.7804593e+00 6.5242721e+00 - 9.0132983e-01 -2.5720205e+00 6.3388780e+00 - 8.7138114e-01 -2.3791984e+00 6.1659495e+00 - 8.6238286e-01 -2.3182591e+00 6.2711324e+00 - 8.4718036e-01 -2.2235209e+00 6.3020968e+00 - 8.4619035e-01 -2.2205157e+00 6.5631769e+00 - 8.1849176e-01 -2.0394966e+00 6.3775003e+00 - 8.8383389e-01 -2.4601953e+00 7.8410293e+00 - 8.6447218e-01 -2.3344843e+00 7.8644841e+00 - 8.6989059e-01 -2.3718982e+00 8.3897419e+00 - 8.5283483e-01 -2.2616699e+00 8.4879375e+00 - 7.9462848e-01 -1.8895028e+00 7.6711532e+00 - 7.9801649e-01 -1.9123265e+00 8.2251401e+00 - 7.5407443e-01 -1.6299312e+00 7.6174486e+00 - 7.2594879e-01 -1.4528406e+00 7.3723950e+00 - 7.0257527e-01 -1.2999216e+00 7.1916823e+00 - 7.0153647e-01 -1.2970054e+00 7.7536382e+00 - 6.8437365e-01 -1.1866012e+00 7.8148802e+00 - 6.6795803e-01 -1.0829045e+00 7.9237068e+00 - 6.4037129e-01 -9.0490272e-01 7.5160043e+00 - 6.1648772e-01 -7.5399669e-01 7.2134437e+00 - 5.9996239e-01 -6.4808235e-01 7.2456672e+00 - 5.8348311e-01 -5.3973703e-01 7.2461315e+00 - 5.6599375e-01 -4.3091073e-01 7.2348638e+00 - 5.5050354e-01 -3.2940323e-01 7.3613143e+00 - 5.3311262e-01 -2.1927452e-01 7.3561894e+00 - 5.1519630e-01 -1.0509260e-01 7.1090696e+00 - 6.9613647e-01 -1.5558227e+00 -9.7203956e-01 - 7.0358600e-01 -1.6146116e+00 -9.7529313e-01 - 7.1039641e-01 -1.6678921e+00 -9.6940287e-01 - 7.1715462e-01 -1.7221055e+00 -9.6216466e-01 - 7.2550840e-01 -1.7827369e+00 -9.6102762e-01 - 7.3287325e-01 -1.8432339e+00 -9.5838924e-01 - 7.4018714e-01 -1.9046539e+00 -9.5420317e-01 - 7.4844883e-01 -1.9670526e+00 -9.4837270e-01 - 7.5671978e-01 -2.0293773e+00 -9.4104408e-01 - 7.6659917e-01 -2.1137900e+00 -9.5236016e-01 - 7.7483209e-01 -2.1769343e+00 -9.4138643e-01 - 7.8360958e-01 -2.2473740e+00 -9.3526262e-01 - 7.9534473e-01 -2.3345782e+00 -9.3994443e-01 - 8.0456301e-01 -2.4141741e+00 -9.3587477e-01 - 8.1473218e-01 -2.4947239e+00 -9.2966133e-01 - 8.2786640e-01 -2.5919791e+00 -9.3305499e-01 - 8.3800495e-01 -2.6732894e+00 -9.2199792e-01 - 8.5159106e-01 -2.7796122e+00 -9.2564794e-01 - 8.6365784e-01 -2.8783920e+00 -9.2064956e-01 - 8.7864056e-01 -2.9947855e+00 -9.2341094e-01 - 8.9210458e-01 -3.1036311e+00 -9.1742403e-01 - 9.0842923e-01 -3.2310480e+00 -9.1834833e-01 - 9.2477793e-01 -3.3582728e+00 -9.1537744e-01 - 9.4102962e-01 -3.4873042e+00 -9.0851214e-01 - 9.5730597e-01 -3.6161386e+00 -8.9765177e-01 - 9.7830482e-01 -3.7820599e+00 -9.0071050e-01 - 9.9927612e-01 -3.9487171e+00 -8.9842623e-01 - 1.0202193e+00 -4.1161151e+00 -8.9089881e-01 - 1.0458450e+00 -4.3214345e+00 -8.9394503e-01 - 1.0728797e+00 -4.5367260e+00 -8.9410506e-01 - 1.1026941e+00 -4.7722675e+00 -8.9468510e-01 - 1.1164682e+00 -4.8786349e+00 -8.3846023e-01 - 1.1448126e+00 -5.1062393e+00 -8.2240172e-01 - 1.1727686e+00 -5.3242686e+00 -7.9579955e-01 - 1.2053219e+00 -5.5819324e+00 -7.7397893e-01 - 1.2453523e+00 -5.8976492e+00 -7.6075490e-01 - 1.2886346e+00 -6.2425208e+00 -7.4491131e-01 - 1.3389275e+00 -6.6370103e+00 -7.2996751e-01 - 1.3924348e+00 -7.0614692e+00 -7.0865916e-01 - 1.4562365e+00 -7.5639305e+00 -6.9027492e-01 - 1.5246014e+00 -8.1073305e+00 -6.6259041e-01 - 1.6063847e+00 -8.7599406e+00 -6.3630986e-01 - 1.7041220e+00 -9.5297356e+00 -6.0735099e-01 - 1.8300587e+00 -1.0528293e+01 -5.8580462e-01 - 1.9588551e+00 -1.1547492e+01 -5.3211924e-01 - 2.1187826e+00 -1.2813973e+01 -4.7143429e-01 - 2.2963799e+00 -1.4220417e+01 -3.7992466e-01 - 2.4004437e+00 -1.5042932e+01 -1.9311273e-01 - 2.4402500e+00 -1.5358075e+01 5.3372148e-02 - 2.5377904e+00 -1.6125533e+01 2.9057393e-01 - 2.8645781e+00 -1.8714408e+01 5.0627215e-01 - 2.8712947e+00 -1.8769684e+01 8.3515972e-01 - 2.8741497e+00 -1.8789547e+01 1.1655282e+00 - 2.8735280e+00 -1.8784115e+01 1.4960721e+00 - 2.8726654e+00 -1.8782670e+01 1.8268142e+00 - 2.8735619e+00 -1.8785305e+01 2.1583473e+00 - 2.8728271e+00 -1.8781808e+01 2.4901889e+00 - 2.8686039e+00 -1.8753109e+01 2.8203081e+00 - 2.8675371e+00 -1.8738554e+01 3.1522070e+00 - 2.8648370e+00 -1.8717883e+01 3.4841146e+00 - 2.8614412e+00 -1.8692157e+01 3.8159774e+00 - 2.8606758e+00 -1.8689419e+01 4.1526626e+00 - 2.8621448e+00 -1.8699642e+01 4.4936777e+00 - 2.8572523e+00 -1.8665676e+01 4.8280469e+00 - 2.8635476e+00 -1.8712672e+01 5.1817597e+00 - 2.5169852e+00 -1.5965198e+01 4.8636433e+00 - 2.5019137e+00 -1.5847666e+01 5.1313760e+00 - 3.4489986e+00 -2.3345875e+01 7.5261073e+00 - 2.4847185e+00 -1.5714441e+01 5.6921100e+00 - 2.4750978e+00 -1.5639823e+01 5.9708369e+00 - 2.4819531e+00 -1.5692444e+01 6.2927842e+00 - 2.4819518e+00 -1.5692154e+01 6.6013505e+00 - 2.4668833e+00 -1.5574598e+01 6.8695825e+00 - 2.4130405e+00 -1.5147877e+01 7.0144698e+00 - 2.4027134e+00 -1.5068288e+01 7.2914540e+00 - 2.4353208e+00 -1.5329860e+01 7.7190673e+00 - 2.5031135e+00 -1.5861458e+01 8.2862393e+00 - 2.5072722e+00 -1.5894197e+01 8.6416650e+00 - 2.5865077e+00 -1.6523071e+01 9.3038762e+00 - 2.9855194e+00 -1.9685365e+01 1.1329412e+01 - 1.2146888e+00 -5.6671740e+00 4.1015764e+00 - 1.2043534e+00 -5.5773370e+00 4.1811122e+00 - 1.1819879e+00 -5.4021367e+00 4.2077513e+00 - 1.1540459e+00 -5.1850273e+00 4.2030214e+00 - 1.1613873e+00 -5.2376746e+00 4.3635679e+00 - 1.1573105e+00 -5.2117170e+00 4.4772544e+00 - 1.1836425e+00 -5.4201602e+00 4.7553045e+00 - 1.1490329e+00 -5.1450184e+00 4.6991931e+00 - 1.0684385e+00 -4.5059868e+00 4.3607893e+00 - 1.0549699e+00 -4.3997562e+00 4.4030908e+00 - 1.0731963e+00 -4.5414596e+00 4.6417541e+00 - 1.0370748e+00 -4.2556211e+00 4.5366647e+00 - 1.0612441e+00 -4.4510475e+00 4.8318079e+00 - 1.0438352e+00 -4.3090005e+00 4.8432310e+00 - 1.0976367e+00 -4.7390600e+00 5.3778466e+00 - 1.1034662e+00 -4.7856527e+00 5.5776526e+00 - 1.0728358e+00 -4.5429222e+00 5.4998868e+00 - 1.0725081e+00 -4.5400820e+00 5.6575434e+00 - 1.1701315e+00 -5.3124636e+00 6.6434106e+00 - 1.0373206e+00 -4.2625530e+00 5.6891262e+00 - 1.0370331e+00 -4.2593925e+00 5.8532747e+00 - 1.0443295e+00 -4.3170416e+00 6.0947678e+00 - 1.0835377e+00 -4.6255324e+00 6.6560168e+00 - 1.0016236e+00 -3.9771476e+00 6.0400179e+00 - 9.6862398e-01 -3.7199561e+00 5.8870615e+00 - 9.5795521e-01 -3.6348460e+00 5.9518140e+00 - 8.6900065e-01 -2.9267675e+00 5.1357708e+00 - 8.5951618e-01 -2.8544562e+00 5.1866294e+00 - 8.5008393e-01 -2.7812119e+00 5.2361401e+00 - 8.8526733e-01 -3.0592033e+00 5.8410652e+00 - 8.7446621e-01 -2.9756666e+00 5.8941817e+00 - 8.4984580e-01 -2.7794186e+00 5.7562948e+00 - 8.4607620e-01 -2.7499742e+00 5.9001448e+00 - 8.6206206e-01 -2.8727921e+00 6.3344328e+00 - 8.5278969e-01 -2.7987859e+00 6.4196490e+00 - 8.3631110e-01 -2.6731148e+00 6.4054416e+00 - 8.1155055e-01 -2.4774710e+00 6.2350452e+00 - 7.9960603e-01 -2.3782299e+00 6.2596599e+00 - 8.0495437e-01 -2.4247564e+00 6.6216656e+00 - 7.8716613e-01 -2.2852253e+00 6.5618272e+00 - 7.6527936e-01 -2.1085634e+00 6.3964545e+00 - 7.8280004e-01 -2.2516939e+00 7.0697286e+00 - 8.0554747e-01 -2.4340706e+00 7.9284326e+00 - 7.9739714e-01 -2.3637766e+00 8.1219584e+00 - 7.8742763e-01 -2.2909145e+00 8.3245800e+00 - 7.4045821e-01 -1.9158106e+00 7.5199969e+00 - 7.3057525e-01 -1.8396782e+00 7.6876137e+00 - 7.0418489e-01 -1.6291226e+00 7.3510878e+00 - 6.8784855e-01 -1.4987046e+00 7.2912895e+00 - 6.7300664e-01 -1.3786073e+00 7.2678352e+00 - 6.6395678e-01 -1.3074645e+00 7.4773444e+00 - 6.5653779e-01 -1.2476151e+00 7.7845203e+00 - 6.4091000e-01 -1.1247293e+00 7.7758518e+00 - 6.2444973e-01 -9.9684893e-01 7.7253907e+00 - 6.0481467e-01 -8.4414011e-01 7.4642661e+00 - 5.8913289e-01 -7.1601268e-01 7.3389958e+00 - 5.7319258e-01 -5.9098275e-01 7.1914522e+00 - 5.5964530e-01 -4.8589691e-01 7.2308070e+00 - 5.5648937e-01 -4.6302364e-01 8.6357323e+00 - 5.3376612e-01 -2.7611293e-01 7.3839199e+00 - 5.1903153e-01 -1.5855317e-01 7.1279031e+00 - 5.0518322e-01 -5.2262772e-02 7.0498556e+00 - 6.5337138e-01 -1.5840380e+00 -9.6607846e-01 - 6.5876868e-01 -1.6436684e+00 -9.6857699e-01 - 6.6511256e-01 -1.7042873e+00 -9.6963087e-01 - 6.6987875e-01 -1.7583453e+00 -9.6168716e-01 - 6.7624051e-01 -1.8188213e+00 -9.5984463e-01 - 6.8155313e-01 -1.8801599e+00 -9.5645121e-01 - 6.8781356e-01 -1.9424770e+00 -9.5141339e-01 - 6.9461487e-01 -2.0121190e+00 -9.5182476e-01 - 7.0089564e-01 -2.0742736e+00 -9.4349101e-01 - 7.0819179e-01 -2.1521242e+00 -9.4700484e-01 - 7.1490719e-01 -2.2234842e+00 -9.4172401e-01 - 7.2364167e-01 -2.3105564e+00 -9.4739505e-01 - 7.2984578e-01 -2.3743550e+00 -9.3187096e-01 - 7.3754962e-01 -2.4621420e+00 -9.3299481e-01 - 7.4614598e-01 -2.5518651e+00 -9.3162571e-01 - 7.5428018e-01 -2.6331185e+00 -9.2186068e-01 - 7.6486254e-01 -2.7393338e+00 -9.2699931e-01 - 7.7540379e-01 -2.8463934e+00 -9.2899222e-01 - 7.8436489e-01 -2.9469118e+00 -9.2238705e-01 - 7.9482393e-01 -3.0556599e+00 -9.1808851e-01 - 8.0720504e-01 -3.1819267e+00 -9.2084742e-01 - 8.1906624e-01 -3.3007011e+00 -9.1476134e-01 - 8.3179667e-01 -3.4378865e+00 -9.1478110e-01 - 8.4500598e-01 -3.5676350e+00 -9.0585918e-01 - 8.5909130e-01 -3.7157402e+00 -9.0194444e-01 - 8.7314415e-01 -3.8646207e+00 -8.9348570e-01 - 8.9241741e-01 -4.0587721e+00 -9.0154915e-01 - 9.0969317e-01 -4.2370390e+00 -8.9516506e-01 - 9.3114699e-01 -4.4613852e+00 -9.0265363e-01 - 9.4645792e-01 -4.6235065e+00 -8.7652853e-01 - 9.6366091e-01 -4.8039020e+00 -8.5251737e-01 - 9.8556317e-01 -5.0220860e+00 -8.3638316e-01 - 1.0041519e+00 -5.2131551e+00 -8.0344368e-01 - 1.0290678e+00 -5.4807496e+00 -7.8889569e-01 - 1.0567836e+00 -5.7684313e+00 -7.7147177e-01 - 1.0873671e+00 -6.0751443e+00 -7.5002294e-01 - 1.1241459e+00 -6.4609843e+00 -7.3892671e-01 - 1.1623804e+00 -6.8564220e+00 -7.1735367e-01 - 1.2074045e+00 -7.3215954e+00 -6.9808965e-01 - 1.2574215e+00 -7.8369523e+00 -6.7337729e-01 - 1.3168519e+00 -8.4613762e+00 -6.5205371e-01 - 1.3841410e+00 -9.1550296e+00 -6.2155651e-01 - 1.4668154e+00 -1.0008147e+01 -5.9209911e-01 - 1.5599484e+00 -1.0970531e+01 -5.4860558e-01 - 1.6707133e+00 -1.2122046e+01 -4.9489015e-01 - 1.7929629e+00 -1.3383181e+01 -4.1280987e-01 - 1.8917234e+00 -1.4406967e+01 -2.6589839e-01 - 1.9291087e+00 -1.4794148e+01 -3.8873479e-02 - 1.9861027e+00 -1.5387027e+01 1.9036743e-01 - 2.0814193e+00 -1.6373092e+01 4.2605123e-01 - 3.6746245e+00 -3.2861314e+01 4.2465739e-01 - 3.6991659e+00 -3.3115011e+01 1.0009158e+00 - 4.4049913e+00 -4.0426500e+01 2.4193310e+00 - 4.5627346e+00 -4.2065521e+01 3.2158912e+00 - 2.8428712e+00 -2.4262556e+01 3.5626180e+00 - 2.8367465e+00 -2.4204011e+01 3.9863941e+00 - 2.6874443e+00 -2.2660724e+01 4.2002448e+00 - 2.6685291e+00 -2.2463410e+01 4.5751026e+00 - 2.6631046e+00 -2.2408338e+01 4.9702101e+00 - 2.7361664e+00 -2.3166572e+01 5.5246997e+00 - 2.7228973e+00 -2.3025870e+01 5.9177343e+00 - 2.6276734e+00 -2.2044436e+01 6.1137105e+00 - 2.0420347e+00 -1.5973779e+01 5.0017647e+00 - 2.0301321e+00 -1.5853487e+01 5.2683404e+00 - 2.0472709e+00 -1.6035642e+01 5.6201429e+00 - 2.0503667e+00 -1.6067291e+01 5.9356722e+00 - 2.0083036e+00 -1.5629170e+01 6.1022520e+00 - 2.0180009e+00 -1.5735151e+01 6.4438349e+00 - 2.4191438e+00 -1.9894228e+01 8.2752272e+00 - 2.0328692e+00 -1.5889592e+01 7.1284966e+00 - 1.9546575e+00 -1.5079764e+01 7.1214721e+00 - 1.9732564e+00 -1.5273030e+01 7.5138631e+00 - 2.0067542e+00 -1.5621609e+01 7.9881151e+00 - 2.0260078e+00 -1.5822322e+01 8.4131091e+00 - 2.0448643e+00 -1.6013528e+01 8.8472486e+00 - 2.0272140e+00 -1.5838985e+01 9.1085804e+00 - 1.0480200e+00 -5.6863623e+00 4.0376705e+00 - 1.0346655e+00 -5.5456119e+00 4.0884811e+00 - 1.0178362e+00 -5.3785183e+00 4.1201918e+00 - 1.0094583e+00 -5.2891127e+00 4.1934290e+00 - 1.0152326e+00 -5.3514031e+00 4.3598675e+00 - 1.0029600e+00 -5.2258165e+00 4.4096173e+00 - 1.0076296e+00 -5.2731254e+00 4.5734213e+00 - 1.0006871e+00 -5.1934801e+00 4.6538394e+00 - 9.3218078e-01 -4.4850136e+00 4.2740891e+00 - 9.2854109e-01 -4.4509209e+00 4.3703506e+00 - 9.3396612e-01 -4.5022928e+00 4.5340500e+00 - 9.7971446e-01 -4.9817926e+00 5.0530318e+00 - 9.7992032e-01 -4.9863364e+00 5.2040406e+00 - 9.7093000e-01 -4.8901774e+00 5.2711413e+00 - 9.6599542e-01 -4.8452010e+00 5.3829938e+00 - 9.3570382e-01 -4.5273878e+00 5.2421490e+00 - 9.1576311e-01 -4.3248600e+00 5.1959370e+00 - 9.1604152e-01 -4.3283083e+00 5.3488938e+00 - 9.3912611e-01 -4.5636476e+00 5.7478381e+00 - 8.9402768e-01 -4.0998846e+00 5.4175604e+00 - 8.9813438e-01 -4.1421074e+00 5.6224680e+00 - 9.8668333e-01 -5.0604533e+00 6.8491796e+00 - 9.6115667e-01 -4.7982554e+00 6.7454913e+00 - 8.6336052e-01 -3.7767349e+00 5.6863603e+00 - 8.5158891e-01 -3.6577602e+00 5.7045938e+00 - 8.6196319e-01 -3.7679162e+00 6.0235503e+00 - 8.0931471e-01 -3.2175012e+00 5.4497497e+00 - 7.7168016e-01 -2.8256067e+00 5.0548871e+00 - 7.7110489e-01 -2.8268085e+00 5.2116432e+00 - 8.0915900e-01 -3.2145336e+00 5.9734504e+00 - 7.9080948e-01 -3.0326844e+00 5.8763846e+00 - 8.4229368e-01 -3.5628343e+00 6.9574196e+00 - 8.2750349e-01 -3.4087147e+00 6.9323868e+00 - 7.6808584e-01 -2.7887016e+00 6.0554251e+00 - 7.5880307e-01 -2.6959110e+00 6.0947594e+00 - 7.5464427e-01 -2.6563824e+00 6.2392157e+00 - 7.4678256e-01 -2.5744987e+00 6.3030087e+00 - 7.4392847e-01 -2.5488696e+00 6.4922970e+00 - 7.3485533e-01 -2.4528566e+00 6.5361768e+00 - 7.2915962e-01 -2.3875739e+00 6.6520385e+00 - 7.0869922e-01 -2.1845574e+00 6.4333929e+00 - 6.9971057e-01 -2.0863221e+00 6.4615433e+00 - 7.2122907e-01 -2.3082173e+00 7.3712648e+00 - 7.2427485e-01 -2.3495488e+00 7.8551792e+00 - 7.2321929e-01 -2.3369675e+00 8.2281258e+00 - 6.9052201e-01 -1.9985807e+00 7.5699442e+00 - 6.7815837e-01 -1.8711427e+00 7.5559246e+00 - 6.5022123e-01 -1.5774930e+00 7.3555824e+00 - 6.3970996e-01 -1.4727726e+00 7.4114569e+00 - 6.2804053e-01 -1.3493713e+00 7.3776074e+00 - 6.1914000e-01 -1.2535261e+00 7.4788651e+00 - 6.1423002e-01 -1.2065052e+00 7.8740663e+00 - 5.9846460e-01 -1.0382168e+00 7.5880195e+00 - 5.8598447e-01 -9.0861535e-01 7.4962982e+00 - 5.7324764e-01 -7.8364394e-01 7.4120158e+00 - 5.6148947e-01 -6.5631010e-01 7.2755466e+00 - 5.5017965e-01 -5.4322948e-01 7.2362967e+00 - 5.6563529e-01 -7.1708757e-01 1.1304985e+01 - 5.3031161e-01 -3.3827284e-01 7.4812236e+00 - 5.1895477e-01 -2.2041052e-01 7.3363082e+00 - 5.0815036e-01 -1.0617068e-01 7.1191787e+00 - 6.0439390e-01 -1.5653254e+00 -9.7200574e-01 - 6.0820118e-01 -1.6184935e+00 -9.6750421e-01 - 6.1142833e-01 -1.6651662e+00 -9.5410814e-01 - 6.1478141e-01 -1.7255741e+00 -9.5455323e-01 - 6.1914129e-01 -1.7859736e+00 -9.5360322e-01 - 6.2292041e-01 -1.8398825e+00 -9.4385855e-01 - 6.2776896e-01 -1.9085397e+00 -9.4700977e-01 - 6.3256839e-01 -1.9781051e+00 -9.4831367e-01 - 6.3638013e-01 -2.0475264e+00 -9.4791648e-01 - 6.4060867e-01 -2.1105225e+00 -9.3882769e-01 - 6.4532095e-01 -2.1818159e+00 -9.3463914e-01 - 6.5057843e-01 -2.2603996e+00 -9.3520064e-01 - 6.5625208e-01 -2.3325631e+00 -9.2717041e-01 - 6.6195157e-01 -2.4202932e+00 -9.2958631e-01 - 6.6706847e-01 -2.5015476e+00 -9.2350717e-01 - 6.7321429e-01 -2.5983896e+00 -9.2707832e-01 - 6.7977692e-01 -2.6888064e+00 -9.2195787e-01 - 6.8583621e-01 -2.7873713e+00 -9.1993671e-01 - 6.9381080e-01 -2.9035092e+00 -9.2607164e-01 - 7.0126548e-01 -3.0121547e+00 -9.2336159e-01 - 7.0916155e-01 -3.1299515e+00 -9.2260581e-01 - 7.1695877e-01 -3.2495697e+00 -9.1825524e-01 - 7.2477756e-01 -3.3690155e+00 -9.1040899e-01 - 7.3398064e-01 -3.4986306e+00 -9.0367164e-01 - 7.4221021e-01 -3.6279882e+00 -8.9293603e-01 - 7.5316594e-01 -3.7943119e+00 -8.9611318e-01 - 7.6545806e-01 -3.9717032e+00 -8.9835213e-01 - 7.7821317e-01 -4.1580735e+00 -8.9904967e-01 - 7.9308855e-01 -4.3914089e+00 -9.1376371e-01 - 8.0210294e-01 -4.5256262e+00 -8.7876359e-01 - 8.1423515e-01 -4.7068742e+00 -8.5788304e-01 - 8.2726620e-01 -4.9062966e+00 -8.3831424e-01 - 8.4164720e-01 -5.1166783e+00 -8.1560996e-01 - 8.5687669e-01 -5.3461526e+00 -7.9256985e-01 - 8.7433522e-01 -5.6049183e+00 -7.7090207e-01 - 8.9527818e-01 -5.9214953e+00 -7.5781816e-01 - 9.1572896e-01 -6.2303581e+00 -7.3139481e-01 - 9.4331428e-01 -6.6356832e+00 -7.1988140e-01 - 9.7162106e-01 -7.0626630e+00 -6.9919426e-01 - 1.0043510e+00 -7.5490207e+00 -6.7710727e-01 - 1.0404649e+00 -8.0955400e+00 -6.5047153e-01 - 1.0836263e+00 -8.7407635e+00 -6.2341584e-01 - 1.1345721e+00 -9.5057087e+00 -5.9410699e-01 - 1.1925134e+00 -1.0370805e+01 -5.5319277e-01 - 1.2574215e+00 -1.1336798e+01 -4.9552993e-01 - 1.3391875e+00 -1.2570484e+01 -4.3507911e-01 - 1.4194270e+00 -1.3765653e+01 -3.2805906e-01 - 1.4478413e+00 -1.4184253e+01 -1.1845242e-01 - 1.4733008e+00 -1.4569776e+01 1.0726270e-01 - 1.5695151e+00 -1.6018462e+01 2.9937936e-01 - 1.7526976e+00 -1.8761507e+01 5.0804982e-01 - 2.7686893e+00 -3.3972326e+01 7.0352319e-01 - 2.7703307e+00 -3.3993033e+01 1.2979665e+00 - 2.7724928e+00 -3.4021742e+01 1.8935021e+00 - 3.0418498e+00 -3.8067981e+01 2.6665422e+00 - 4.7419619e+00 -6.3521133e+01 6.0114946e+00 - 2.1687246e+00 -2.4997617e+01 3.4129041e+00 - 2.1483199e+00 -2.4694273e+01 3.8203876e+00 - 1.9988421e+00 -2.2455368e+01 3.9633807e+00 - 2.0824385e+00 -2.3703093e+01 4.5508619e+00 - 2.0141714e+00 -2.2693242e+01 4.8064454e+00 - 2.0039675e+00 -2.2534320e+01 5.1863472e+00 - 1.9553023e+00 -2.1813212e+01 5.4483433e+00 - 1.9841973e+00 -2.2238800e+01 5.9417413e+00 - 1.9670413e+00 -2.1994636e+01 6.2926506e+00 - 1.5672762e+00 -1.5996083e+01 5.1465691e+00 - 1.8468630e+00 -2.0191066e+01 6.6123288e+00 - 1.5717070e+00 -1.6071603e+01 5.7717335e+00 - 1.8090719e+00 -1.9621892e+01 7.2009461e+00 - 1.5856153e+00 -1.6275060e+01 6.4579179e+00 - 1.5536769e+00 -1.5801244e+01 6.6082566e+00 - 1.8246506e+00 -1.9860051e+01 8.4422145e+00 - 1.5356210e+00 -1.5531393e+01 7.1318189e+00 - 1.5443988e+00 -1.5670811e+01 7.5058949e+00 - 1.5424043e+00 -1.5637281e+01 7.8148363e+00 - 1.5453880e+00 -1.5689208e+01 8.1662096e+00 - 1.8652533e+00 -2.0487858e+01 1.0794396e+01 - 1.6089719e+00 -1.6635098e+01 9.3129334e+00 - 1.5072325e+00 -1.5116455e+01 8.8869158e+00 - 1.5053698e+00 -1.5081357e+01 9.2073933e+00 - 8.6243068e-01 -5.4449731e+00 4.0876838e+00 - 8.5953889e-01 -5.3987149e+00 4.1874457e+00 - 8.6326100e-01 -5.4618470e+00 4.3546393e+00 - 8.8156013e-01 -5.7384360e+00 4.6645355e+00 - 1.5404223e+00 -1.5625184e+01 1.1365632e+01 - 8.8817260e-01 -5.8297009e+00 5.0159245e+00 - 8.1360766e-01 -4.7108998e+00 4.3681650e+00 - 7.9764433e-01 -4.4756427e+00 4.3193126e+00 - 8.4285711e-01 -5.1525235e+00 4.9631761e+00 - 8.4503511e-01 -5.1920219e+00 5.1398266e+00 - 8.4857806e-01 -5.2428756e+00 5.3318470e+00 - 8.3951615e-01 -5.1136796e+00 5.3773939e+00 - 8.2565164e-01 -4.8940132e+00 5.3403113e+00 - 8.0269441e-01 -4.5534340e+00 5.1820782e+00 - 7.9060145e-01 -4.3713566e+00 5.1577523e+00 - 7.7341932e-01 -4.1204820e+00 5.0583757e+00 - 7.8757660e-01 -4.3359607e+00 5.4222533e+00 - 7.9088779e-01 -4.3744407e+00 5.6207736e+00 - 8.2698436e-01 -4.9272010e+00 6.3896324e+00 - 7.7893266e-01 -4.1984822e+00 5.7560451e+00 - 7.9518351e-01 -4.4510397e+00 6.2240650e+00 - 7.4868273e-01 -3.7443530e+00 5.5527071e+00 - 7.3376131e-01 -3.5214853e+00 5.4374769e+00 - 7.2962808e-01 -3.4618534e+00 5.5222690e+00 - 6.9823152e-01 -2.9964724e+00 5.0595638e+00 - 6.9125593e-01 -2.8793568e+00 5.0462204e+00 - 6.9024748e-01 -2.8703101e+00 5.1866541e+00 - 6.8405890e-01 -2.7748413e+00 5.2029088e+00 - 7.0565044e-01 -3.0988279e+00 5.8749666e+00 - 7.0509014e-01 -3.1019729e+00 6.0733697e+00 - 7.3311662e-01 -3.5140014e+00 6.9798145e+00 - 6.8492605e-01 -2.8004033e+00 5.9610980e+00 - 6.8854334e-01 -2.8563360e+00 6.2730161e+00 - 6.8074797e-01 -2.7367030e+00 6.2689652e+00 - 6.7293658e-01 -2.6171981e+00 6.2623174e+00 - 6.6876162e-01 -2.5599626e+00 6.3795680e+00 - 6.6425974e-01 -2.4905981e+00 6.4780998e+00 - 6.6258221e-01 -2.4625724e+00 6.6766743e+00 - 6.5151063e-01 -2.2909856e+00 6.5434246e+00 - 6.4219556e-01 -2.1612340e+00 6.4989347e+00 - 6.4503997e-01 -2.2015960e+00 6.9012018e+00 - 6.6224558e-01 -2.4712793e+00 7.9945308e+00 - 6.5512012e-01 -2.3615503e+00 8.0745674e+00 - 6.3886674e-01 -2.1152018e+00 7.7237981e+00 - 6.2732748e-01 -1.9320951e+00 7.5392204e+00 - 6.1731842e-01 -1.7972736e+00 7.4949852e+00 - 6.0910613e-01 -1.6662307e+00 7.4576337e+00 - 5.9942964e-01 -1.5230786e+00 7.3594195e+00 - 5.9030799e-01 -1.3881712e+00 7.2776283e+00 - 5.8473769e-01 -1.3066290e+00 7.4382434e+00 - 5.7813111e-01 -1.2049163e+00 7.5190727e+00 - 5.6948414e-01 -1.0804415e+00 7.4701331e+00 - 5.6227854e-01 -9.6980558e-01 7.5077732e+00 - 5.5564275e-01 -8.7090500e-01 7.6328959e+00 - 5.4572917e-01 -7.2242709e-01 7.3590041e+00 - 5.3771805e-01 -6.0142375e-01 7.2611713e+00 - 5.3033839e-01 -4.9166306e-01 7.2608087e+00 - 5.2924188e-01 -4.6892231e-01 8.6857526e+00 - 5.1661745e-01 -2.7858536e-01 7.3940599e+00 - 5.0892800e-01 -1.5943829e-01 7.1179968e+00 - 5.0119199e-01 -5.2525254e-02 7.0599055e+00 - 5.6805772e-01 -1.8189462e+00 -9.5256252e-01 - 5.7031501e-01 -1.8811053e+00 -9.4920989e-01 - 5.7317277e-01 -1.9495973e+00 -9.5145586e-01 - 5.7485794e-01 -2.0051969e+00 -9.3791030e-01 - 5.7814847e-01 -2.0829091e+00 -9.4350882e-01 - 5.8038561e-01 -2.1457449e+00 -9.3361466e-01 - 5.8363997e-01 -2.2242620e+00 -9.3526844e-01 - 5.8631297e-01 -2.2962934e+00 -9.2822744e-01 - 5.8901056e-01 -2.3839013e+00 -9.3183231e-01 - 5.9164861e-01 -2.4567277e+00 -9.2064682e-01 - 5.9578948e-01 -2.5535177e+00 -9.2560988e-01 - 5.9940919e-01 -2.6428252e+00 -9.2192772e-01 - 6.0294355e-01 -2.7496193e+00 -9.2709442e-01 - 6.0641590e-01 -2.8416516e+00 -9.1787027e-01 - 6.1082751e-01 -2.9667926e+00 -9.2784441e-01 - 6.1475667e-01 -3.0678530e+00 -9.1807761e-01 - 6.1960728e-01 -3.1863915e+00 -9.1576459e-01 - 6.2399695e-01 -3.2964505e+00 -9.0485589e-01 - 6.2819564e-01 -3.4258717e+00 -9.0029992e-01 - 6.3341653e-01 -3.5551613e+00 -8.9185194e-01 - 6.3979139e-01 -3.7305852e+00 -9.0206117e-01 - 6.4579869e-01 -3.8799791e+00 -8.9352745e-01 - 6.5254507e-01 -4.0661443e+00 -8.9740196e-01 - 6.5963645e-01 -4.2632625e+00 -8.9923646e-01 - 6.6598650e-01 -4.4241433e+00 -8.7922476e-01 - 6.7273745e-01 -4.5950146e+00 -8.5792174e-01 - 6.7969770e-01 -4.7952437e+00 -8.4177999e-01 - 6.8769496e-01 -4.9952229e+00 -8.1934920e-01 - 6.9591324e-01 -5.2244662e+00 -8.0018202e-01 - 7.0492532e-01 -5.4737547e+00 -7.7973059e-01 - 7.1617139e-01 -5.7522952e+00 -7.5985246e-01 - 7.2760353e-01 -6.0608948e+00 -7.3909346e-01 - 7.4148205e-01 -6.4280796e+00 -7.2356968e-01 - 7.5613238e-01 -6.8160011e+00 -7.0051972e-01 - 7.7257900e-01 -7.2733756e+00 -6.8016240e-01 - 7.9246050e-01 -7.7899888e+00 -6.5680402e-01 - 8.1412000e-01 -8.3767169e+00 -6.2929711e-01 - 8.3972573e-01 -9.0638534e+00 -5.9906432e-01 - 8.6981321e-01 -9.8592816e+00 -5.6261626e-01 - 9.0263966e-01 -1.0726214e+01 -5.0844039e-01 - 9.4325243e-01 -1.1812132e+01 -4.5121997e-01 - 9.9022019e-01 -1.3058890e+01 -3.7318884e-01 - 1.0163681e+00 -1.3777366e+01 -2.0594640e-01 - 1.0304318e+00 -1.4135550e+01 1.1081338e-02 - 1.0538498e+00 -1.4769255e+01 2.2572262e-01 - 1.1800014e+00 -1.8136130e+01 3.6649536e-01 - 1.7870856e+00 -3.4315548e+01 1.0004509e+00 - 1.7863376e+00 -3.4309792e+01 1.5997110e+00 - 1.6303379e+00 -3.0160231e+01 2.0543959e+00 - 1.7794464e+00 -3.4138838e+01 2.7908002e+00 - 1.9244482e+00 -3.8010281e+01 3.6602141e+00 - 1.9231048e+00 -3.7968153e+01 4.3245663e+00 - 1.3323653e+00 -2.2211553e+01 3.3365044e+00 - 1.3355478e+00 -2.2296017e+01 3.7398435e+00 - 1.3361110e+00 -2.2324308e+01 4.1400274e+00 - 1.2387079e+00 -1.9730168e+01 4.1274061e+00 - 1.2928432e+00 -2.1167677e+01 4.7354445e+00 - 1.2285815e+00 -1.9452178e+01 4.7839825e+00 - 1.3280390e+00 -2.2109712e+01 5.7032327e+00 - 1.3231498e+00 -2.1995307e+01 6.0818934e+00 - 1.2584717e+00 -2.0269640e+01 6.4354093e+00 - 1.2424943e+00 -1.9835635e+01 6.6921422e+00 - 1.1861202e+00 -1.8332337e+01 6.9610580e+00 - 1.1135574e+00 -1.6421135e+01 6.6585725e+00 - 1.1255186e+00 -1.6743043e+01 7.0984007e+00 - 1.0871267e+00 -1.5719575e+01 7.0386402e+00 - 1.0822616e+00 -1.5565180e+01 7.2935780e+00 - 1.1387633e+00 -1.7081511e+01 8.2560223e+00 - 1.1991822e+00 -1.8704672e+01 9.3341484e+00 - 1.1686122e+00 -1.7886711e+01 9.3468537e+00 - 1.1422873e+00 -1.7182027e+01 9.3862468e+00 - 1.1437123e+00 -1.7246109e+01 9.7938979e+00 - 1.1603473e+00 -1.7681994e+01 1.0408328e+01 - 1.1072202e+00 -1.6255811e+01 1.0017610e+01 - 1.1247537e+00 -1.6728224e+01 1.0665075e+01 - 7.1554547e-01 -5.7731127e+00 4.4714293e+00 - 7.1204615e-01 -5.6864533e+00 4.5558855e+00 - 7.0398030e-01 -5.4722807e+00 4.5565844e+00 - 7.0153971e-01 -5.4014866e+00 4.6460220e+00 - 7.1072572e-01 -5.6638259e+00 4.9691887e+00 - 7.0713748e-01 -5.5615883e+00 5.0440662e+00 - 7.0085606e-01 -5.4022221e+00 5.0743908e+00 - 7.0381771e-01 -5.4801987e+00 5.2850740e+00 - 6.9686197e-01 -5.2804492e+00 5.2794689e+00 - 6.8305354e-01 -4.9217728e+00 5.1332026e+00 - 6.7820894e-01 -4.7884448e+00 5.1661043e+00 - 6.7747878e-01 -4.7745956e+00 5.3025949e+00 - 6.9396028e-01 -5.2101594e+00 5.8627432e+00 - 6.5553117e-01 -4.1976909e+00 5.0569046e+00 - 6.5561290e-01 -4.2042582e+00 5.2074133e+00 - 6.6508420e-01 -4.4495761e+00 5.6110389e+00 - 6.6960198e-01 -4.5725363e+00 5.9074345e+00 - 6.7426137e-01 -4.6938493e+00 6.2169643e+00 - 6.6475676e-01 -4.4311764e+00 6.1019399e+00 - 6.6694033e-01 -4.5088810e+00 6.3776948e+00 - 6.5317943e-01 -4.1436359e+00 6.1214690e+00 - 6.2964995e-01 -3.5064811e+00 5.4917465e+00 - 6.1807541e-01 -3.2055091e+00 5.2568000e+00 - 6.0901183e-01 -2.9478646e+00 5.0613213e+00 - 6.1317884e-01 -3.0609493e+00 5.3743531e+00 - 5.9995735e-01 -2.7152036e+00 5.0291749e+00 - 6.4578181e-01 -3.9348678e+00 7.0636913e+00 - 6.1786809e-01 -3.1873958e+00 6.1053555e+00 - 6.1342360e-01 -3.0620018e+00 6.1001987e+00 - 6.2898909e-01 -3.4828377e+00 7.0362907e+00 - 6.0612809e-01 -2.8727036e+00 6.1866240e+00 - 6.0517510e-01 -2.8663082e+00 6.3948717e+00 - 5.9638709e-01 -2.6175929e+00 6.1411594e+00 - 5.9572780e-01 -2.6062718e+00 6.3479608e+00 - 5.9196221e-01 -2.5044199e+00 6.3744987e+00 - 5.9344675e-01 -2.5481276e+00 6.7279789e+00 - 5.8584770e-01 -2.3305256e+00 6.4955184e+00 - 5.8218397e-01 -2.2456958e+00 6.5631451e+00 - 5.7722371e-01 -2.1091661e+00 6.4988699e+00 - 5.8246425e-01 -2.2586273e+00 7.2114801e+00 - 5.8817327e-01 -2.4232123e+00 8.0441806e+00 - 5.8409820e-01 -2.3127021e+00 8.1234590e+00 - 5.7058732e-01 -1.9512182e+00 7.3882261e+00 - 5.6716208e-01 -1.8450994e+00 7.4404835e+00 - 5.6180627e-01 -1.6964734e+00 7.3365659e+00 - 5.5690654e-01 -1.5788432e+00 7.3361002e+00 - 5.5241891e-01 -1.4522467e+00 7.2945396e+00 - 5.4876039e-01 -1.3505708e+00 7.3580311e+00 - 5.4406333e-01 -1.2277109e+00 7.3217624e+00 - 5.3974638e-01 -1.1186179e+00 7.3520516e+00 - 5.3651359e-01 -1.0318916e+00 7.5189046e+00 - 5.3253701e-01 -9.1543700e-01 7.5160882e+00 - 5.2813186e-01 -8.1169051e-01 7.6203327e+00 - 5.2231663e-01 -6.5693673e-01 7.2556945e+00 - 5.1793784e-01 -5.4782226e-01 7.2661586e+00 - 5.2346283e-01 -7.1551080e-01 1.1245094e+01 - 5.1021455e-01 -3.3349095e-01 7.3713765e+00 - 5.0592371e-01 -2.2315782e-01 7.3862855e+00 - 5.0209971e-01 -1.0630066e-01 7.1092101e+00 - 5.1498029e-01 -1.8517783e+00 -9.5111595e-01 - 5.1530640e-01 -1.9127801e+00 -9.4700750e-01 - 5.1611254e-01 -1.9821087e+00 -9.4839855e-01 - 5.1587140e-01 -2.0522851e+00 -9.4793909e-01 - 5.1704522e-01 -2.1160969e+00 -9.3879121e-01 - 5.1683485e-01 -2.2018005e+00 -9.4797886e-01 - 5.1756741e-01 -2.2727485e+00 -9.4168019e-01 - 5.1819064e-01 -2.3456018e+00 -9.3348464e-01 - 5.1936152e-01 -2.4257258e+00 -9.2963962e-01 - 5.1948758e-01 -2.5066779e+00 -9.2354459e-01 - 5.2010478e-01 -2.5958681e+00 -9.2115128e-01 - 5.2115537e-01 -2.6942737e+00 -9.2201064e-01 - 5.2212306e-01 -2.8101461e+00 -9.3131937e-01 - 5.2309020e-01 -2.9102499e+00 -9.2608703e-01 - 5.2355710e-01 -3.0184772e+00 -9.2345459e-01 - 5.2444018e-01 -3.1202842e+00 -9.1223043e-01 - 5.2573089e-01 -3.2478012e+00 -9.1325724e-01 - 5.2650107e-01 -3.3678306e+00 -9.0553894e-01 - 5.2714355e-01 -3.5062008e+00 -9.0372354e-01 - 5.2883770e-01 -3.6279151e+00 -8.8841857e-01 - 5.3023653e-01 -3.8029186e+00 -8.9621486e-01 - 5.3097788e-01 -3.9888492e+00 -9.0266709e-01 - 5.3255044e-01 -4.1940103e+00 -9.1158004e-01 - 5.3368685e-01 -4.3095660e+00 -8.7394751e-01 - 5.3571814e-01 -4.5079669e+00 -8.6737725e-01 - 5.3643591e-01 -4.6793444e+00 -8.4340880e-01 - 5.3822790e-01 -4.8985251e+00 -8.3140661e-01 - 5.4000283e-01 -5.1183579e+00 -8.1236349e-01 - 5.4200370e-01 -5.3674154e+00 -7.9578499e-01 - 5.4399491e-01 -5.6170659e+00 -7.7096705e-01 - 5.4660003e-01 -5.9060351e+00 -7.4941979e-01 - 5.4883507e-01 -6.2341493e+00 -7.2884289e-01 - 5.5246426e-01 -6.6217360e+00 -7.1244969e-01 - 5.5569214e-01 -7.0492330e+00 -6.9228309e-01 - 5.5928969e-01 -7.5368679e+00 -6.7075426e-01 - 5.6351368e-01 -8.0642372e+00 -6.4066112e-01 - 5.6849655e-01 -8.7112105e+00 -6.1448492e-01 - 5.7429872e-01 -9.4279231e+00 -5.7776490e-01 - 5.8042165e-01 -1.0255578e+01 -5.3267070e-01 - 5.8779130e-01 -1.1212133e+01 -4.7611951e-01 - 5.9648811e-01 -1.2329522e+01 -4.0473430e-01 - 6.0398083e-01 -1.3238290e+01 -2.7454737e-01 - 6.0653879e-01 -1.3587333e+01 -6.9213484e-02 - 6.1064732e-01 -1.4092846e+01 1.3812220e-01 - 6.2752745e-01 -1.6253895e+01 2.9047510e-01 - 6.5038512e-01 -1.9162832e+01 4.9830603e-01 - 7.3343125e-01 -2.9748064e+01 7.4059875e-01 - 7.3333727e-01 -2.9727283e+01 1.2595155e+00 - 7.3235473e-01 -2.9638347e+01 1.7762774e+00 - 7.3323679e-01 -2.9700794e+01 2.2968906e+00 - 7.3313980e-01 -2.9763028e+01 2.8206033e+00 - 7.3275459e-01 -2.9747153e+01 3.3413658e+00 - 7.3257333e-01 -2.9761194e+01 3.8659057e+00 - 6.7335210e-01 -2.2185304e+01 3.5279102e+00 - 6.4207275e-01 -1.8161936e+01 3.3913140e+00 - 6.4283015e-01 -1.8266510e+01 3.7301794e+00 - 6.4461923e-01 -1.8521085e+01 4.0996663e+00 - 6.4886282e-01 -1.9152949e+01 4.5500259e+00 - 6.5156310e-01 -1.9460756e+01 4.9595792e+00 - 6.5250135e-01 -1.9564400e+01 5.3375459e+00 - 6.5600502e-01 -2.0010838e+01 5.8043949e+00 - 6.3451973e-01 -1.7270927e+01 5.4668229e+00 - 6.4681841e-01 -1.8827996e+01 6.2218910e+00 - 6.4857045e-01 -1.9136891e+01 6.6689500e+00 - 6.6442429e-01 -2.1228436e+01 7.6937611e+00 - 6.4252379e-01 -1.8368538e+01 7.1462213e+00 - 6.3171193e-01 -1.6985168e+01 7.0151714e+00 - 6.2968524e-01 -1.6699828e+01 7.2442084e+00 - 6.2915112e-01 -1.6625446e+01 7.5494236e+00 - 6.3324845e-01 -1.7183225e+01 8.1178797e+00 - 6.4588130e-01 -1.8817219e+01 9.1823172e+00 - 6.3639065e-01 -1.7643081e+01 9.0408546e+00 - 6.6900856e-01 -2.1895915e+01 1.1444143e+01 - 6.1728145e-01 -1.5221905e+01 8.5898313e+00 - 6.1434391e-01 -1.4847659e+01 8.7296838e+00 - 6.1458440e-01 -1.4912654e+01 9.0973379e+00 - 6.1449230e-01 -1.4847418e+01 9.4006987e+00 - 5.4454299e-01 -5.8151993e+00 4.4259009e+00 - 5.4401008e-01 -5.7121412e+00 4.5008192e+00 - 5.4301022e-01 -5.6169404e+00 4.5785309e+00 - 5.4271688e-01 -5.5781544e+00 4.6925625e+00 - 5.4146620e-01 -5.5043412e+00 4.7836460e+00 - 5.4126590e-01 -5.4296555e+00 4.8733783e+00 - 5.4129554e-01 -5.5059198e+00 5.0745836e+00 - 5.4165035e-01 -5.4736015e+00 5.2005446e+00 - 5.3780018e-01 -4.9613817e+00 4.9468197e+00 - 5.3694941e-01 -4.8456064e+00 4.9946800e+00 - 5.3608332e-01 -4.8511951e+00 5.1435443e+00 - 5.3539163e-01 -4.7326014e+00 5.1877603e+00 - 5.4332855e-01 -5.8023833e+00 6.3170095e+00 - 5.3514714e-01 -4.6492004e+00 5.4124300e+00 - 5.3128703e-01 -4.1145825e+00 5.0442605e+00 - 5.3021029e-01 -4.0714410e+00 5.1440648e+00 - 5.3143645e-01 -4.2332977e+00 5.4611225e+00 - 5.3173785e-01 -4.2895544e+00 5.6817644e+00 - 5.3220459e-01 -4.2731461e+00 5.8308370e+00 - 5.2981098e-01 -4.0781561e+00 5.7753767e+00 - 5.3608600e-01 -4.8783359e+00 6.9183705e+00 - 5.2455710e-01 -3.3051874e+00 5.1557628e+00 - 5.2578007e-01 -3.4874842e+00 5.5459177e+00 - 5.2446974e-01 -3.2887802e+00 5.4454122e+00 - 5.2153350e-01 -2.8861580e+00 5.0462018e+00 - 5.1984408e-01 -2.7638901e+00 5.0218584e+00 - 5.2901799e-01 -3.9739100e+00 7.0040611e+00 - 5.2768850e-01 -3.8309300e+00 7.0134367e+00 - 5.2741349e-01 -3.7772559e+00 7.1646805e+00 - 5.2635669e-01 -3.5928146e+00 7.1004209e+00 - 5.2213610e-01 -3.0823086e+00 6.4484915e+00 - 5.2380329e-01 -3.2300253e+00 6.9496770e+00 - 5.1957373e-01 -2.7521685e+00 6.2866426e+00 - 5.1939234e-01 -2.6768159e+00 6.3696336e+00 - 5.1861907e-01 -2.5568111e+00 6.3614160e+00 - 5.1763677e-01 -2.5338454e+00 6.5599354e+00 - 5.1756483e-01 -2.4759699e+00 6.6950511e+00 - 5.1639895e-01 -2.2877586e+00 6.5248758e+00 - 5.1532768e-01 -2.1727139e+00 6.5174052e+00 - 5.1507082e-01 -2.2341624e+00 6.9759998e+00 - 5.1749595e-01 -2.5768744e+00 8.2772744e+00 - 5.1652334e-01 -2.3672198e+00 8.0746013e+00 - 5.1359674e-01 -2.0356495e+00 7.4567216e+00 - 5.1294997e-01 -1.8942192e+00 7.3953821e+00 - 5.1145425e-01 -1.7897866e+00 7.4564215e+00 - 5.1104437e-01 -1.6627521e+00 7.4286311e+00 - 5.0947406e-01 -1.5175705e+00 7.3205548e+00 - 5.0917999e-01 -1.4084779e+00 7.3557252e+00 - 5.0790843e-01 -1.2761662e+00 7.2716107e+00 - 5.0746885e-01 -1.1697836e+00 7.3126228e+00 - 5.0571868e-01 -1.0709946e+00 7.4010756e+00 - 5.0507931e-01 -9.7085027e-01 7.4979652e+00 - 5.0465495e-01 -8.9404400e-01 7.7915459e+00 - 5.0368063e-01 -7.1986005e-01 7.3191877e+00 - 5.0248256e-01 -6.0634439e-01 7.3009801e+00 - 5.0294057e-01 -8.0536951e-01 1.1228527e+01 - 5.0121889e-01 -4.6215065e-01 8.5659440e+00 - 4.9959311e-01 -2.8109578e-01 7.4439501e+00 - 4.9888694e-01 -1.6033996e-01 7.1280155e+00 - 4.9826139e-01 -5.2864721e-02 7.0898773e+00 - 4.6076788e-01 -1.8204882e+00 -9.5252503e-01 - 4.5962250e-01 -1.8888221e+00 -9.5645619e-01 - 4.5889515e-01 -1.9507210e+00 -9.5149600e-01 - 4.5711928e-01 -2.0134776e+00 -9.4488504e-01 - 4.5588552e-01 -2.0835493e+00 -9.4352352e-01 - 4.5360447e-01 -2.1544687e+00 -9.4031148e-01 - 4.5286678e-01 -2.2327390e+00 -9.4185267e-01 - 4.5102406e-01 -2.3128344e+00 -9.4109429e-01 - 4.4871917e-01 -2.3844602e+00 -9.3193998e-01 - 4.4784028e-01 -2.4654060e+00 -9.2694041e-01 - 4.4493437e-01 -2.5627649e+00 -9.3173179e-01 - 4.4350427e-01 -2.6527573e+00 -9.2778442e-01 - 4.4105025e-01 -2.7591837e+00 -9.3283218e-01 - 4.3901364e-01 -2.8591801e+00 -9.2908845e-01 - 4.3699492e-01 -2.9590336e+00 -9.2244830e-01 - 4.3435612e-01 -3.0689995e+00 -9.1820908e-01 - 4.3173767e-01 -3.1788029e+00 -9.1067392e-01 - 4.2898660e-01 -3.3069863e+00 -9.0984068e-01 - 4.2671316e-01 -3.4277427e+00 -9.0026551e-01 - 4.2379945e-01 -3.5750617e+00 -9.0119068e-01 - 4.2028047e-01 -3.7323749e+00 -9.0211973e-01 - 4.1607518e-01 -3.9171344e+00 -9.1120241e-01 - 4.1272316e-01 -4.1046594e+00 -9.1434676e-01 - 4.0991294e-01 -4.2190897e+00 -8.7904823e-01 - 4.0593735e-01 -4.4172708e+00 -8.7535532e-01 - 4.0164703e-01 -4.5884840e+00 -8.5416752e-01 - 3.9805653e-01 -4.7972980e+00 -8.4194260e-01 - 3.9344956e-01 -5.0067134e+00 -8.2287334e-01 - 3.8857185e-01 -5.2371598e+00 -8.0346586e-01 - 3.8298584e-01 -5.4957440e+00 -7.8597009e-01 - 3.7720410e-01 -5.7742440e+00 -7.6578861e-01 - 3.7017441e-01 -6.0735470e+00 -7.4186991e-01 - 3.6259352e-01 -6.4312784e+00 -7.2367627e-01 - 3.5398322e-01 -6.8390967e+00 -7.0540854e-01 - 3.4441793e-01 -7.2958916e+00 -6.8481912e-01 - 3.3317624e-01 -7.8136167e+00 -6.6111365e-01 - 3.2133503e-01 -8.3911877e+00 -6.3134857e-01 - 3.0651126e-01 -9.0677618e+00 -5.9918452e-01 - 2.8961348e-01 -9.8451469e+00 -5.5953176e-01 - 2.7258983e-01 -1.0642405e+01 -4.9606976e-01 - 2.4967944e-01 -1.1718487e+01 -4.3924277e-01 - 2.2781836e-01 -1.2746385e+01 -3.4004384e-01 - 2.1776500e-01 -1.3236263e+01 -1.5822267e-01 - 2.1147038e-01 -1.3533302e+01 5.3411488e-02 - 1.9056796e-01 -1.4516836e+01 2.3912551e-01 - 1.1728314e-01 -1.7934172e+01 3.7350600e-01 - -2.2913215e-01 -3.4191785e+01 9.9988316e-01 - -2.3399282e-01 -3.4386337e+01 1.6002387e+00 - -2.3394270e-01 -3.4400592e+01 2.2014823e+00 - -2.3246001e-01 -3.4324835e+01 2.7991780e+00 - -2.5394586e-01 -3.5326570e+01 4.0912569e+00 - -2.5264006e-01 -3.5238001e+01 4.7043414e+00 - 7.4011892e-02 -1.9935307e+01 3.4482557e+00 - 1.1421362e-01 -1.8018698e+01 3.5328861e+00 - 1.0873088e-01 -1.8277188e+01 3.8955022e+00 - 1.0915732e-01 -1.8254096e+01 4.2193614e+00 - 1.0527404e-01 -1.8470106e+01 4.5909859e+00 - 1.0370462e-01 -1.8530912e+01 4.9398216e+00 - 1.3185295e-01 -1.7174186e+01 4.9658379e+00 - 1.3773361e-01 -1.6908305e+01 5.2166117e+00 - 9.3611993e-02 -1.8956077e+01 6.0805375e+00 - 1.3482217e-01 -1.7058099e+01 5.8924432e+00 - 1.4738646e-01 -1.6444235e+01 6.0286903e+00 - 1.4346309e-01 -1.6611183e+01 6.3984957e+00 - 1.3711883e-01 -1.6920481e+01 6.8276024e+00 - 1.3789610e-01 -1.6891491e+01 7.1494663e+00 - 1.3782777e-01 -1.6893799e+01 7.4863960e+00 - 1.3247440e-01 -1.7120740e+01 7.9188432e+00 - 9.1583469e-02 -1.9031554e+01 9.0801683e+00 - 9.2421201e-02 -1.8987855e+01 9.4558736e+00 - 8.7726990e-02 -1.9190662e+01 9.9509049e+00 - 1.1319244e-01 -1.8034250e+01 9.7979860e+00 - 1.7861512e-01 -1.4973671e+01 8.6314573e+00 - 1.8393994e-01 -1.4696974e+01 8.8166207e+00 - 1.7313565e-01 -1.5205445e+01 9.4306957e+00 - 1.7546698e-01 -1.5082378e+01 9.7098625e+00 - 1.7560162e-01 -1.5099352e+01 1.0074848e+01 - 1.5024922e-01 -1.6236122e+01 1.1147833e+01 - 3.7651044e-01 -5.7097324e+00 4.7089899e+00 - 3.8013463e-01 -5.5526099e+00 4.7465730e+00 - 3.8234486e-01 -5.4538047e+00 4.8199820e+00 - 3.8287512e-01 -5.4353416e+00 4.9499294e+00 - 3.7187330e-01 -5.9081716e+00 5.4534133e+00 - 3.8503350e-01 -5.2937577e+00 5.1372717e+00 - 3.9451996e-01 -4.8792386e+00 4.9521626e+00 - 3.9665259e-01 -4.7637334e+00 4.9982157e+00 - 3.9849515e-01 -4.6704451e+00 5.0610858e+00 - 3.9868937e-01 -4.6577617e+00 5.1954254e+00 - 4.0036969e-01 -4.5846372e+00 5.2762120e+00 - 4.0416079e-01 -4.4225708e+00 5.2721991e+00 - 4.0742410e-01 -4.2693636e+00 5.2709294e+00 - 4.0978309e-01 -4.1316348e+00 5.2800405e+00 - 4.0972128e-01 -4.1587323e+00 5.4612995e+00 - 4.0911230e-01 -4.1607192e+00 5.6223998e+00 - 4.0905816e-01 -4.1709509e+00 5.7999232e+00 - 4.1409252e-01 -3.9330637e+00 5.6882344e+00 - 4.2630117e-01 -3.3908930e+00 5.1888318e+00 - 4.2683438e-01 -3.3545703e+00 5.2946696e+00 - 4.2439869e-01 -3.4778696e+00 5.6161557e+00 - 4.2907513e-01 -3.2260382e+00 5.4415044e+00 - 4.3221417e-01 -3.1079488e+00 5.4398651e+00 - 4.2784676e-01 -3.3035020e+00 5.8995934e+00 - 4.3147079e-01 -3.1412234e+00 5.8391014e+00 - 4.3383158e-01 -3.0192532e+00 5.8338713e+00 - 4.2101207e-01 -3.5886971e+00 6.9745122e+00 - 4.2351333e-01 -3.4844718e+00 7.0362380e+00 - 4.2587586e-01 -3.3829024e+00 7.1049041e+00 - 4.3730488e-01 -2.8397415e+00 6.3419325e+00 - 4.4592407e-01 -2.4549315e+00 5.8203775e+00 - 4.4521117e-01 -2.4807421e+00 6.0872827e+00 - 4.4250080e-01 -2.6196456e+00 6.6191989e+00 - 4.4835499e-01 -2.3382889e+00 6.2529494e+00 - 4.4872518e-01 -2.3089420e+00 6.4402322e+00 - 4.5086382e-01 -2.2280291e+00 6.5168272e+00 - 4.5314858e-01 -2.1061508e+00 6.4894747e+00 - 4.4176741e-01 -2.5955504e+00 8.1323827e+00 - 4.5302960e-01 -2.1085628e+00 7.1269806e+00 - 4.5318259e-01 -2.0693045e+00 7.3721479e+00 - 4.5659590e-01 -1.9265458e+00 7.3021071e+00 - 4.5875198e-01 -1.8491038e+00 7.4501611e+00 - 4.6079439e-01 -1.7338037e+00 7.4717946e+00 - 4.6359061e-01 -1.5817505e+00 7.3458308e+00 - 4.6556920e-01 -1.4884066e+00 7.4503487e+00 - 4.6908798e-01 -1.3401634e+00 7.3091493e+00 - 4.7195182e-01 -1.2268519e+00 7.3119526e+00 - 4.7374473e-01 -1.1156086e+00 7.3323860e+00 - 4.7538149e-01 -1.0322166e+00 7.5187974e+00 - 4.7797421e-01 -9.2777627e-01 7.6051424e+00 - 4.8038108e-01 -8.3049412e-01 7.7692371e+00 - 4.8420463e-01 -6.5815449e-01 7.2656017e+00 - 4.7736804e-01 -8.9952679e-01 1.1280788e+01 - 4.8831233e-01 -4.5294366e-01 7.4842358e+00 - 4.9019120e-01 -3.3379304e-01 7.3813271e+00 - 4.9295287e-01 -2.2490816e-01 7.4362133e+00 - 4.9511479e-01 -1.0689100e-01 7.1292069e+00 - 4.0593561e-01 -1.8492066e+00 -9.5117043e-01 - 4.0220883e-01 -1.9109636e+00 -9.4699971e-01 - 3.9902231e-01 -1.9800504e+00 -9.4837804e-01 - 3.9578667e-01 -2.0500455e+00 -9.4790905e-01 - 3.9156396e-01 -2.1198914e+00 -9.4563909e-01 - 3.8776600e-01 -2.1990217e+00 -9.4802008e-01 - 3.8496936e-01 -2.2624142e+00 -9.3526392e-01 - 3.8113585e-01 -2.3423444e+00 -9.3360029e-01 - 3.7579529e-01 -2.4304065e+00 -9.3593166e-01 - 3.7140810e-01 -2.5194028e+00 -9.3571974e-01 - 3.6697548e-01 -2.6092779e+00 -9.3306123e-01 - 3.6255889e-01 -2.6990248e+00 -9.2780593e-01 - 3.5654004e-01 -2.8144691e+00 -9.3699252e-01 - 3.5203693e-01 -2.9059390e+00 -9.2614490e-01 - 3.4697211e-01 -3.0065392e+00 -9.1804739e-01 - 3.4083180e-01 -3.1245014e+00 -9.1749717e-01 - 3.3459323e-01 -3.2442801e+00 -9.1325230e-01 - 3.2895089e-01 -3.3546528e+00 -9.0066422e-01 - 3.2203096e-01 -3.5018384e+00 -9.0377396e-01 - 3.1356780e-01 -3.6579608e+00 -9.0693395e-01 - 3.0486761e-01 -3.8343290e+00 -9.1409996e-01 - 2.9505944e-01 -4.0288346e+00 -9.2426926e-01 - 2.8975250e-01 -4.1349798e+00 -8.8676080e-01 - 2.7997090e-01 -4.3135000e+00 -8.7799446e-01 - 2.7116177e-01 -4.4928018e+00 -8.6358867e-01 - 2.6283459e-01 -4.6646420e+00 -8.3974181e-01 - 2.5051593e-01 -4.9013860e+00 -8.3499627e-01 - 2.3925448e-01 -5.1214299e+00 -8.1586227e-01 - 2.2684825e-01 -5.3604209e+00 -7.9588670e-01 - 2.1367721e-01 -5.6285170e+00 -7.7717405e-01 - 1.9807029e-01 -5.9367080e+00 -7.6087398e-01 - 1.8184473e-01 -6.2555158e+00 -7.3693762e-01 - 1.6208087e-01 -6.6325115e+00 -7.1751825e-01 - 1.4029498e-01 -7.0594893e+00 -6.9712274e-01 - 1.1588490e-01 -7.5464187e+00 -6.7525557e-01 - 8.8489150e-02 -8.0829939e+00 -6.4681597e-01 - 5.6040105e-02 -8.7195615e+00 -6.1821867e-01 - 2.0354386e-02 -9.4266481e+00 -5.7951467e-01 - -2.1264626e-02 -1.0232207e+01 -5.3131092e-01 - -6.6357144e-02 -1.1129044e+01 -4.6716903e-01 - -1.2244489e-01 -1.2224415e+01 -3.9476796e-01 - -1.4999601e-01 -1.2754195e+01 -2.2979380e-01 - -1.5996933e-01 -1.2962914e+01 -2.1592501e-02 - -1.8023086e-01 -1.3357811e+01 1.8193899e-01 - -3.6358534e-01 -1.6951905e+01 2.5883559e-01 - -5.0493301e-01 -1.9727757e+01 4.8264185e-01 - -1.0922623e+00 -3.1258419e+01 7.2654838e-01 - -1.0957558e+00 -3.1328325e+01 1.2733885e+00 - -1.2335761e+00 -3.4033613e+01 1.8919834e+00 - -1.1025450e+00 -3.1448722e+01 2.3745201e+00 - -1.2318574e+00 -3.4001656e+01 3.0819661e+00 - -1.2262574e+00 -3.3890504e+01 3.6702811e+00 - -1.2304603e+00 -3.3958559e+01 4.2737041e+00 - -1.2260032e+00 -3.3866339e+01 4.8631603e+00 - -4.5107627e-01 -1.8664225e+01 3.4601850e+00 - -5.6353392e-01 -2.0870330e+01 4.1229846e+00 - -9.7023257e-01 -2.8850368e+01 5.8338572e+00 - -4.6672372e-01 -1.8961738e+01 4.5187447e+00 - -3.6045402e-01 -1.6871827e+01 4.4369243e+00 - -3.6448945e-01 -1.6955648e+01 4.7636819e+00 - -3.6387872e-01 -1.6945310e+01 5.0733507e+00 - -3.6106921e-01 -1.6881513e+01 5.3714580e+00 - -3.6267157e-01 -1.6908458e+01 5.6951946e+00 - -3.2655145e-01 -1.6202026e+01 5.8053038e+00 - -3.3814679e-01 -1.6430110e+01 6.1869831e+00 - -3.2669590e-01 -1.6204126e+01 6.4288772e+00 - -3.5271782e-01 -1.6709523e+01 6.9248489e+00 - -3.5305169e-01 -1.6716016e+01 7.2579818e+00 - -5.9320434e-01 -2.1408536e+01 9.4438462e+00 - -4.8114775e-01 -1.9219045e+01 8.9710019e+00 - -4.5861771e-01 -1.8774989e+01 9.1740359e+00 - -4.6652838e-01 -1.8930006e+01 9.6377940e+00 - -4.4953012e-01 -1.8595955e+01 9.8811315e+00 - -3.2078660e-01 -1.6060761e+01 9.0178709e+00 - -2.9705734e-01 -1.5608970e+01 9.1358115e+00 - -2.8941710e-01 -1.5446960e+01 9.3977056e+00 - -2.9946502e-01 -1.5637107e+01 9.8584038e+00 - -2.6531444e-01 -1.4972501e+01 9.8309160e+00 - -2.7250473e-01 -1.5114541e+01 1.0274105e+01 - -3.7148435e-01 -1.7048163e+01 1.1874654e+01 - 2.0969738e-01 -5.6711076e+00 4.7586767e+00 - 2.3857542e-01 -5.1056679e+00 4.6468030e+00 - 2.4596510e-01 -4.9689543e+00 4.6819653e+00 - 2.4823740e-01 -4.9200666e+00 4.7803641e+00 - 2.5202524e-01 -4.8451430e+00 4.8595471e+00 - 2.5624922e-01 -4.7626084e+00 4.9309429e+00 - 2.5448683e-01 -4.7836114e+00 5.0914865e+00 - 2.4916095e-01 -4.8839339e+00 5.3268523e+00 - 2.5513518e-01 -4.7714248e+00 5.3778353e+00 - 2.6768222e-01 -4.5271827e+00 5.3022316e+00 - 2.6266812e-01 -4.6229508e+00 5.5488849e+00 - 2.8723853e-01 -4.1508141e+00 5.2295787e+00 - 2.9255755e-01 -4.0486983e+00 5.2724678e+00 - 2.8936120e-01 -4.0956009e+00 5.4752484e+00 - 2.9264530e-01 -4.0293445e+00 5.5610698e+00 - 2.9547614e-01 -3.9886720e+00 5.6764908e+00 - 3.1137316e-01 -3.6647536e+00 5.4522577e+00 - 3.2446652e-01 -3.4068624e+00 5.2886696e+00 - 3.0587719e-01 -3.7808760e+00 5.9346075e+00 - 3.2570247e-01 -3.3853387e+00 5.5819633e+00 - 3.2028797e-01 -3.4915268e+00 5.9010218e+00 - 3.2536982e-01 -3.3933692e+00 5.9447084e+00 - 3.3530643e-01 -3.2079371e+00 5.8531985e+00 - 3.4042104e-01 -3.0906503e+00 5.8579945e+00 - 3.4259932e-01 -3.0624128e+00 6.0049712e+00 - 3.4396502e-01 -3.0310847e+00 6.1526014e+00 - 3.2143013e-01 -3.4719129e+00 7.1446824e+00 - 3.5461788e-01 -2.8251875e+00 6.2113642e+00 - 3.6177832e-01 -2.6698911e+00 6.1357758e+00 - 3.6614205e-01 -2.5841766e+00 6.1905936e+00 - 3.6599333e-01 -2.6008373e+00 6.4606484e+00 - 3.6423230e-01 -2.6300812e+00 6.7782918e+00 - 3.6420140e-01 -2.6284800e+00 7.0526515e+00 - 3.7684598e-01 -2.3695335e+00 6.7281157e+00 - 3.8781131e-01 -2.1593772e+00 6.4894999e+00 - 3.7816983e-01 -2.3433963e+00 7.2757953e+00 - 3.9272886e-01 -2.0632631e+00 6.8349604e+00 - 3.9512010e-01 -2.0180666e+00 7.0408729e+00 - 3.9787512e-01 -1.9668686e+00 7.2468876e+00 - 3.9932264e-01 -1.9232396e+00 7.5008425e+00 - 4.0805019e-01 -1.7536581e+00 7.3311245e+00 - 4.1377101e-01 -1.6447213e+00 7.3704707e+00 - 4.1869005e-01 -1.5525064e+00 7.4760274e+00 - 4.2651328e-01 -1.3984033e+00 7.3166904e+00 - 4.3322644e-01 -1.2665802e+00 7.2324506e+00 - 4.4291340e-01 -1.0880856e+00 6.8799621e+00 - 4.4407144e-01 -1.0601790e+00 7.3419499e+00 - 4.4788149e-01 -9.7394659e-01 7.5276070e+00 - 4.5151063e-01 -8.9638023e-01 7.8212253e+00 - 4.6063782e-01 -7.1926447e-01 7.3192238e+00 - 4.6754306e-01 -6.0271087e-01 7.2710796e+00 - 4.7186054e-01 -5.0932910e-01 7.4801101e+00 - 4.7420225e-01 -4.5898420e-01 8.5160931e+00 - 4.8363002e-01 -2.8367826e-01 7.5138620e+00 - 4.8990426e-01 -1.6030512e-01 7.1379814e+00 - 4.9533080e-01 -5.3204187e-02 7.1198490e+00 - 3.4876275e-01 -1.8831338e+00 -9.5655308e-01 - 3.4445029e-01 -1.9384397e+00 -9.4438672e-01 - 3.3780767e-01 -2.0146440e+00 -9.5190065e-01 - 3.3258186e-01 -2.0844689e+00 -9.5042653e-01 - 3.2823692e-01 -2.1405501e+00 -9.3371616e-01 - 3.2098533e-01 -2.2267782e+00 -9.4183324e-01 - 3.1521016e-01 -2.3056348e+00 -9.4111169e-01 - 3.0838954e-01 -2.3853245e+00 -9.3824000e-01 - 3.0152228e-01 -2.4659027e+00 -9.3312148e-01 - 2.9514553e-01 -2.5547240e+00 -9.3180455e-01 - 2.8720584e-01 -2.6526396e+00 -9.3373394e-01 - 2.7922258e-01 -2.7514192e+00 -9.3291711e-01 - 2.7171572e-01 -2.8427817e+00 -9.2355810e-01 - 2.6267113e-01 -2.9588100e+00 -9.2799140e-01 - 2.5513857e-01 -3.0508935e+00 -9.1298975e-01 - 2.4595401e-01 -3.1695876e+00 -9.1068255e-01 - 2.3630730e-01 -3.2798120e+00 -8.9997941e-01 - 2.2595639e-01 -3.4176256e+00 -9.0032632e-01 - 2.1354538e-01 -3.5726324e+00 -9.0602006e-01 - 1.9947317e-01 -3.7385502e+00 -9.1126545e-01 - 1.8465567e-01 -3.9329013e+00 -9.2441515e-01 - 1.7540334e-01 -4.0379112e+00 -8.8904093e-01 - 1.6218153e-01 -4.2071333e+00 -8.7900992e-01 - 1.4742512e-01 -4.3852232e+00 -8.6763090e-01 - 1.3414884e-01 -4.5559120e+00 -8.4681399e-01 - 1.1701369e-01 -4.7731246e+00 -8.3839649e-01 - 9.8802486e-02 -4.9919307e+00 -8.2298522e-01 - 8.0383221e-02 -5.2307510e+00 -8.0688576e-01 - 6.0389497e-02 -5.4792736e+00 -7.8609281e-01 - 3.7638317e-02 -5.7567509e+00 -7.6595715e-01 - 1.2455576e-02 -6.0742886e+00 -7.4753494e-01 - -1.4962797e-02 -6.4124852e+00 -7.2367444e-01 - -4.6910247e-02 -6.8087501e+00 -7.0312923e-01 - -8.3487482e-02 -7.2649196e+00 -6.8260416e-01 - -1.2461579e-01 -7.7798491e+00 -6.5915248e-01 - -1.7145488e-01 -8.3563161e+00 -6.2952618e-01 - -2.2180803e-01 -8.9912930e+00 -5.9068423e-01 - -2.8184550e-01 -9.7367949e+00 -5.4723162e-01 - -3.4924536e-01 -1.0571473e+01 -4.9062391e-01 - -4.2643053e-01 -1.1535319e+01 -4.2117628e-01 - -4.8165391e-01 -1.2222538e+01 -2.8901538e-01 - -5.1199424e-01 -1.2600803e+01 -1.0616671e-01 - -5.4335315e-01 -1.2996491e+01 8.8160777e-02 - -7.2914908e-01 -1.5309057e+01 1.9487181e-01 - -9.3022183e-01 -1.7811609e+01 3.7572852e-01 - -1.8221021e+00 -2.8921923e+01 4.9304716e-01 - -1.8256019e+00 -2.8956723e+01 9.9950792e-01 - -1.8395489e+00 -2.9131139e+01 1.5096161e+00 - -1.8375226e+00 -2.9107941e+01 2.0191892e+00 - -1.8285390e+00 -2.8986125e+01 2.5234542e+00 - -1.8460573e+00 -2.9203735e+01 3.0481304e+00 - -1.8430534e+00 -2.9164473e+01 3.5592079e+00 - -1.8406473e+00 -2.9135145e+01 4.0714800e+00 - -1.8388931e+00 -2.9116701e+01 4.5859951e+00 - -1.1611298e+00 -2.0669091e+01 3.9138966e+00 - -1.1567196e+00 -2.0615282e+01 4.2753642e+00 - -8.9820405e-01 -1.7394883e+01 4.0767650e+00 - -8.8710188e-01 -1.7259833e+01 4.3654992e+00 - -8.7637213e-01 -1.7130854e+01 4.6527328e+00 - -8.7922649e-01 -1.7161830e+01 4.9745735e+00 - -8.5447931e-01 -1.6848503e+01 5.2139794e+00 - -8.2737380e-01 -1.6511990e+01 5.4384100e+00 - -7.9633276e-01 -1.6125762e+01 5.6386372e+00 - -8.3706552e-01 -1.6624036e+01 6.0986042e+00 - -8.3342275e-01 -1.6579969e+01 6.4043879e+00 - -8.3006257e-01 -1.6540740e+01 6.7134156e+00 - -8.3498102e-01 -1.6607292e+01 7.0636568e+00 - -8.9854478e-01 -1.7392448e+01 7.6975130e+00 - -9.9735509e-01 -1.8622109e+01 8.5478530e+00 - -9.9517439e-01 -1.8588909e+01 8.9157577e+00 - -1.0021365e+00 -1.8676650e+01 9.3417488e+00 - -7.9600202e-01 -1.6107217e+01 8.5348937e+00 - -8.0427911e-01 -1.6215264e+01 8.9341604e+00 - -7.5715288e-01 -1.5621761e+01 8.9852926e+00 - -7.5091296e-01 -1.5551568e+01 9.2951782e+00 - -7.4219030e-01 -1.5439359e+01 9.5856544e+00 - -7.4581088e-01 -1.5486256e+01 9.9696609e+00 - -8.5407933e-01 -1.6822786e+01 1.1140620e+01 - -1.8102697e+00 -2.8707201e+01 1.8995316e+01 - 6.6499893e-02 -5.3753033e+00 4.5019695e+00 - 7.1075782e-02 -5.3215025e+00 4.6011129e+00 - 7.9580224e-02 -5.2175266e+00 4.6651168e+00 - 8.4322588e-02 -5.1608482e+00 4.7618145e+00 - 9.3428400e-02 -5.0463936e+00 4.8153855e+00 - 1.1372550e-01 -4.7908051e+00 4.7554944e+00 - 1.1392376e-01 -4.7948939e+00 4.8954672e+00 - 1.2386422e-01 -4.6655176e+00 4.9273713e+00 - 1.1616844e-01 -4.7544787e+00 5.1462716e+00 - 1.2329360e-01 -4.6739026e+00 5.2221515e+00 - 1.2864782e-01 -4.6066617e+00 5.3101142e+00 - 1.3141412e-01 -4.5670207e+00 5.4248857e+00 - 1.3656014e-01 -4.5035065e+00 5.5183400e+00 - 1.3245666e-01 -4.5491054e+00 5.7260681e+00 - 1.5052855e-01 -4.3298654e+00 5.6586722e+00 - 1.7234157e-01 -4.0619481e+00 5.5257742e+00 - 1.7912810e-01 -3.9693365e+00 5.5810378e+00 - 1.7987798e-01 -3.9654070e+00 5.7417378e+00 - 2.0806178e-01 -3.6188161e+00 5.4840706e+00 - 1.8832672e-01 -3.8533236e+00 5.9486188e+00 - 1.7893571e-01 -3.9769768e+00 6.2948959e+00 - 1.9374105e-01 -3.7959171e+00 6.2424196e+00 - 2.2088951e-01 -3.4474998e+00 5.9395130e+00 - 2.3757186e-01 -3.2491628e+00 5.8333076e+00 - 2.5067677e-01 -3.0782963e+00 5.7553125e+00 - 2.5572249e-01 -3.0160993e+00 5.8423244e+00 - 2.6119571e-01 -2.9463602e+00 5.9201508e+00 - 2.5602592e-01 -3.0154366e+00 6.2394798e+00 - 2.7417022e-01 -2.7883977e+00 6.0465443e+00 - 2.7582933e-01 -2.7704979e+00 6.2270749e+00 - 2.8474485e-01 -2.6565324e+00 6.2302090e+00 - 2.8620726e-01 -2.6432989e+00 6.4377039e+00 - 2.8332516e-01 -2.6744959e+00 6.7550501e+00 - 2.8397683e-01 -2.6597042e+00 6.9929107e+00 - 2.8636327e-01 -2.6323821e+00 7.2226333e+00 - 3.1286127e-01 -2.3002939e+00 6.7114784e+00 - 3.0330002e-01 -2.4250067e+00 7.3389555e+00 - 3.1801518e-01 -2.2395102e+00 7.1738222e+00 - 3.3282923e-01 -2.0506449e+00 6.9756816e+00 - 3.3566657e-01 -2.0171408e+00 7.2294264e+00 - 3.4361773e-01 -1.9232594e+00 7.3116535e+00 - 3.5320739e-01 -1.7966865e+00 7.2867277e+00 - 3.6359688e-01 -1.6738219e+00 7.2688885e+00 - 3.6468540e-01 -1.6612123e+00 7.6853742e+00 - 3.7669695e-01 -1.5047560e+00 7.5381104e+00 - 3.9165340e-01 -1.3258841e+00 7.2601628e+00 - 4.1136246e-01 -1.0802381e+00 6.5756947e+00 - 4.1743845e-01 -1.0036192e+00 6.7119505e+00 - 4.1744998e-01 -1.0044726e+00 7.3607928e+00 - 4.2437127e-01 -9.1645717e-01 7.5457419e+00 - 4.3023270e-01 -8.3351598e-01 7.8089442e+00 - 4.4527410e-01 -6.5529759e-01 7.2555886e+00 - 4.2446400e-01 -8.9633280e-01 1.1280757e+01 - 4.6136040e-01 -4.5080723e-01 7.4742844e+00 - 4.6519266e-01 -3.9761952e-01 8.6096407e+00 - 4.7911085e-01 -2.2713047e-01 7.5361313e+00 - 4.8912580e-01 -1.0652830e-01 7.1292260e+00 - 2.9725470e-01 -1.8406335e+00 -9.5112270e-01 - 2.9012525e-01 -1.9085653e+00 -9.5423577e-01 - 2.8382016e-01 -1.9637207e+00 -9.4146378e-01 - 2.7565329e-01 -2.0324215e+00 -9.4112831e-01 - 2.6837525e-01 -2.1030880e+00 -9.3889915e-01 - 2.5964606e-01 -2.1809240e+00 -9.4141366e-01 - 2.5040554e-01 -2.2669721e+00 -9.4832586e-01 - 2.4204588e-01 -2.3392764e+00 -9.4000181e-01 - 2.3469672e-01 -2.4115427e+00 -9.2968341e-01 - 2.2437952e-01 -2.4991892e+00 -9.2970172e-01 - 2.1449447e-01 -2.5960609e+00 -9.3317245e-01 - 2.0350869e-01 -2.6947232e+00 -9.3364447e-01 - 1.9305892e-01 -2.7849763e+00 -9.2572375e-01 - 1.8204683e-01 -2.8843646e+00 -9.2065301e-01 - 1.7047428e-01 -2.9928733e+00 -9.1813262e-01 - 1.5943835e-01 -3.0929679e+00 -9.0711961e-01 - 1.4627099e-01 -3.2113413e+00 -9.0320166e-01 - 1.3254995e-01 -3.3387809e+00 -9.0073541e-01 - 1.1513454e-01 -3.4935939e+00 -9.0861054e-01 - 9.7115713e-02 -3.6583862e+00 -9.1618992e-01 - 7.9007888e-02 -3.8249212e+00 -9.1857650e-01 - 6.6235538e-02 -3.9380751e+00 -8.8988758e-01 - 4.8065846e-02 -4.1061360e+00 -8.8268677e-01 - 2.8870445e-02 -4.2748722e+00 -8.7013977e-01 - 9.0796380e-03 -4.4535238e+00 -8.5599863e-01 - -9.7386960e-03 -4.6329569e+00 -8.3621803e-01 - -3.5466288e-02 -4.8596948e+00 -8.2807860e-01 - -5.9645530e-02 -5.0779707e+00 -8.0925245e-01 - -8.5030380e-02 -5.3161955e+00 -7.8963505e-01 - -1.1573565e-01 -5.5924238e+00 -7.7421771e-01 - -1.4931079e-01 -5.8995366e+00 -7.5806016e-01 - -1.8662430e-01 -6.2354057e+00 -7.3976017e-01 - -2.2616789e-01 -6.5918893e+00 -7.1512300e-01 - -2.6911470e-01 -6.9881611e+00 -6.8790140e-01 - -3.1738665e-01 -7.4229898e+00 -6.5584141e-01 - -3.8014131e-01 -7.9970179e+00 -6.3685027e-01 - -4.5040640e-01 -8.6293438e+00 -6.0923001e-01 - -5.2356316e-01 -9.2937598e+00 -5.6479018e-01 - -6.0826719e-01 -1.0066482e+01 -5.1373502e-01 - -7.0715319e-01 -1.0958165e+01 -4.5161793e-01 - -8.0658241e-01 -1.1860378e+01 -3.5984214e-01 - -8.4135640e-01 -1.2179349e+01 -1.8009122e-01 - -8.6208319e-01 -1.2366726e+01 2.0615709e-02 - -9.8089856e-01 -1.3443325e+01 1.7247668e-01 - -1.2359398e+00 -1.5759334e+01 3.0741902e-01 - -1.5508697e+00 -1.8621096e+01 5.0900059e-01 - -2.5816911e+00 -2.7979400e+01 7.5361603e-01 - -2.6743725e+00 -2.8824681e+01 1.2523473e+00 - -2.6836392e+00 -2.8905180e+01 1.7606974e+00 - -2.6803285e+00 -2.8877176e+01 2.2676225e+00 - -2.6803383e+00 -2.8870979e+01 2.7757440e+00 - -2.6903398e+00 -2.8964054e+01 3.2925286e+00 - -2.6888487e+00 -2.8949774e+01 3.8036463e+00 - -2.6874104e+00 -2.8936433e+01 4.3160121e+00 - -2.6838292e+00 -2.8904205e+01 4.8275331e+00 - -2.6797048e+00 -2.8862994e+01 5.3388080e+00 - -1.7091470e+00 -2.0048369e+01 4.3746622e+00 - -1.6783303e+00 -1.9770949e+01 4.6860886e+00 - -2.6702902e+00 -2.8772503e+01 6.8884030e+00 - -1.5586410e+00 -1.8680060e+01 5.1658973e+00 - -1.5975270e+00 -1.9030472e+01 5.5960315e+00 - -1.5734171e+00 -1.8813481e+01 5.8943602e+00 - -1.6515529e+00 -1.9520608e+01 6.4457603e+00 - -2.6884230e+00 -2.8934468e+01 9.6217656e+00 - -1.4286463e+00 -1.7499684e+01 6.5505498e+00 - -1.4431675e+00 -1.7627243e+01 6.9330956e+00 - -1.3162838e+00 -1.6471600e+01 6.8677974e+00 - -1.4148579e+00 -1.7373383e+01 7.5343556e+00 - -1.4396086e+00 -1.7589950e+01 7.9703156e+00 - -1.3685963e+00 -1.6951653e+01 8.0637459e+00 - -1.4113455e+00 -1.7337492e+01 8.5836600e+00 - -1.3889526e+00 -1.7130827e+01 8.8537732e+00 - -1.3132058e+00 -1.6444467e+01 8.8907367e+00 - -1.3173847e+00 -1.6483663e+01 9.2675583e+00 - -1.2954757e+00 -1.6284475e+01 9.5279309e+00 - -2.6624978e+00 -2.8678300e+01 1.6664171e+01 - -2.6018623e+00 -2.8125247e+01 1.7007674e+01 - -2.6631527e+00 -2.8679365e+01 1.8680314e+01 - -1.8646228e-01 -6.2196270e+00 4.9866244e+00 - -2.2565577e-01 -6.5730121e+00 5.3767575e+00 - -7.9829563e-02 -5.2507389e+00 4.6305933e+00 - -9.3985538e-02 -5.3808376e+00 4.8615751e+00 - -4.8094656e-02 -4.9616410e+00 4.6937325e+00 - -4.7562209e-02 -4.9599649e+00 4.8290135e+00 - -5.0621389e-02 -4.9858724e+00 4.9902075e+00 - -5.5758572e-02 -5.0306634e+00 5.1725709e+00 - -4.6220480e-02 -4.9432689e+00 5.2472985e+00 - -4.0724939e-02 -4.8911875e+00 5.3533295e+00 - -3.4053042e-02 -4.8361953e+00 5.4588092e+00 - -7.0801400e-03 -4.5850653e+00 5.3778705e+00 - 3.8398738e-06 -4.5226542e+00 5.4716677e+00 - 1.7373010e-02 -4.3682107e+00 5.4720521e+00 - 3.1143772e-02 -4.2414052e+00 5.4972509e+00 - 6.0883132e-02 -3.9749586e+00 5.3645768e+00 - 7.4737139e-02 -3.8459407e+00 5.3738465e+00 - 2.2319270e-02 -4.3188854e+00 6.0870500e+00 - 8.9057610e-02 -3.7173210e+00 5.5371228e+00 - 8.8480687e-02 -3.7190518e+00 5.7034168e+00 - 6.0893397e-02 -3.9693324e+00 6.2043353e+00 - 7.0323998e-02 -3.8838283e+00 6.2812595e+00 - 7.5499318e-02 -3.8384317e+00 6.4138546e+00 - 7.2491065e-02 -3.8680582e+00 6.6617385e+00 - 6.9983058e-02 -3.8895612e+00 6.9122223e+00 - 1.4802193e-01 -3.1829942e+00 6.0265381e+00 - 1.7357451e-01 -2.9499188e+00 5.8429712e+00 - 1.7711453e-01 -2.9152263e+00 5.9802094e+00 - 1.7641941e-01 -2.9215117e+00 6.1959895e+00 - 1.8754534e-01 -2.8222452e+00 6.2289710e+00 - 2.1127416e-01 -2.6018956e+00 6.0293224e+00 - 2.1459960e-01 -2.5720122e+00 6.1906286e+00 - 1.8457313e-01 -2.8458245e+00 7.0022047e+00 - 1.8809565e-01 -2.8153978e+00 7.2150465e+00 - 1.9204586e-01 -2.7779431e+00 7.4285401e+00 - 2.0355898e-01 -2.6740352e+00 7.4948317e+00 - 2.5000617e-01 -2.2479004e+00 6.7407207e+00 - 2.3657782e-01 -2.3708522e+00 7.3787479e+00 - 2.6853914e-01 -2.0836412e+00 6.9198347e+00 - 2.7219338e-01 -2.0531933e+00 7.1736251e+00 - 2.8059641e-01 -1.9699267e+00 7.2850084e+00 - 2.8992792e-01 -1.8888246e+00 7.4145149e+00 - 3.0666084e-01 -1.7394656e+00 7.3118266e+00 - 3.1312270e-01 -1.6770834e+00 7.5253767e+00 - 3.2142992e-01 -1.5987083e+00 7.6996791e+00 - 3.3491008e-01 -1.4752565e+00 7.6974111e+00 - 3.7149366e-01 -1.1487017e+00 6.6835466e+00 - 3.8413757e-01 -1.0360584e+00 6.6242459e+00 - 3.7964556e-01 -1.0699346e+00 7.4306371e+00 - 3.9134510e-01 -9.6195839e-01 7.4781039e+00 - 4.0586582e-01 -8.3152362e-01 7.3552366e+00 - 4.1883384e-01 -7.1422738e-01 7.3092210e+00 - 4.3166704e-01 -5.9852423e-01 7.2511699e+00 - 4.4197291e-01 -5.0551008e-01 7.4600815e+00 - 4.5374189e-01 -3.9955763e-01 7.5678219e+00 - 4.6666120e-01 -2.8265061e-01 7.5139160e+00 - 4.8005409e-01 -1.6226002e-01 7.2279494e+00 - 4.9227240e-01 -5.2502021e-02 7.0898963e+00 - 2.8731665e-01 -1.5240054e+00 -9.6998411e-01 - 2.3832700e-01 -1.8704470e+00 -9.5659732e-01 - 2.2914717e-01 -1.9392056e+00 -9.5865571e-01 - 2.1892005e-01 -2.0088120e+00 -9.5886359e-01 - 2.1016812e-01 -2.0710568e+00 -9.5043260e-01 - 2.0136521e-01 -2.1342246e+00 -9.4045391e-01 - 1.9064648e-01 -2.2118855e+00 -9.4186343e-01 - 1.8034331e-01 -2.2831311e+00 -9.3478109e-01 - 1.6952942e-01 -2.3625839e+00 -9.3199656e-01 - 1.5720910e-01 -2.4501637e+00 -9.3310715e-01 - 1.4484336e-01 -2.5386223e+00 -9.3177115e-01 - 1.3243281e-01 -2.6279546e+00 -9.2788868e-01 - 1.1852015e-01 -2.7253795e+00 -9.2720220e-01 - 1.0608206e-01 -2.8154476e+00 -9.1797672e-01 - 8.9988854e-02 -2.9320596e+00 -9.2253797e-01 - 7.5949793e-02 -3.0320418e+00 -9.1291369e-01 - 6.0353335e-02 -3.1410741e+00 -9.0563683e-01 - 4.4201962e-02 -3.2591824e+00 -9.0001144e-01 - 2.2840543e-02 -3.4128650e+00 -9.1012068e-01 - 1.9616910e-03 -3.5590812e+00 -9.1068898e-01 - -2.1605968e-02 -3.7326719e+00 -9.2040331e-01 - -3.7324928e-02 -3.8447461e+00 -8.9375194e-01 - -5.9870317e-02 -4.0024317e+00 -8.8493332e-01 - -8.2505317e-02 -4.1618649e+00 -8.7102177e-01 - -1.0567797e-01 -4.3302361e+00 -8.5596513e-01 - -1.3357625e-01 -4.5267005e+00 -8.4680256e-01 - -1.6212338e-01 -4.7340229e+00 -8.3489766e-01 - -1.9006256e-01 -4.9318455e+00 -8.1275190e-01 - -2.2396197e-01 -5.1779417e+00 -8.0040318e-01 - -2.6049298e-01 -5.4346668e+00 -7.8310847e-01 - -2.9977836e-01 -5.7203218e+00 -7.6597167e-01 - -3.4168426e-01 -6.0165171e+00 -7.4209112e-01 - -3.9112792e-01 -6.3707126e+00 -7.2381348e-01 - -4.4597297e-01 -6.7645903e+00 -7.0324469e-01 - -5.0564786e-01 -7.1889409e+00 -6.7603660e-01 - -5.7449025e-01 -7.6819515e+00 -6.4888938e-01 - -6.5570825e-01 -8.2634996e+00 -6.2200419e-01 - -7.4387559e-01 -8.8942200e+00 -5.8383964e-01 - -8.4226246e-01 -9.5950018e+00 -5.3484700e-01 - -9.5523713e-01 -1.0404793e+01 -4.7688278e-01 - -1.0923699e+00 -1.1382277e+01 -4.1159879e-01 - -1.1431817e+00 -1.1750199e+01 -2.4735640e-01 - -1.1651223e+00 -1.1907694e+01 -5.2321241e-02 - -1.2343435e+00 -1.2398273e+01 1.2419276e-01 - -1.5112808e+00 -1.4379964e+01 2.3857379e-01 - -1.9082668e+00 -1.7221099e+01 3.9218584e-01 - -3.0716330e+00 -2.5537595e+01 5.4908319e-01 - -3.2051506e+00 -2.6492164e+01 9.9909044e-01 - -3.5785534e+00 -2.9161346e+01 1.5129298e+00 - -3.5803085e+00 -2.9167763e+01 2.0274914e+00 - -3.5725179e+00 -2.9115694e+01 2.5397098e+00 - -3.6433025e+00 -2.9618681e+01 3.0903062e+00 - -3.6435707e+00 -2.9617643e+01 3.6154043e+00 - -3.6390384e+00 -2.9586883e+01 4.1389066e+00 - -3.6356185e+00 -2.9558007e+01 4.6635099e+00 - -3.6343820e+00 -2.9548857e+01 5.1922036e+00 - -3.6300039e+00 -2.9520876e+01 5.7201492e+00 - -3.6250794e+00 -2.9483888e+01 6.2483481e+00 - -2.2194895e+00 -1.9433017e+01 4.8135332e+00 - -2.1368087e+00 -1.8840811e+01 5.0432303e+00 - -2.1667187e+00 -1.9057907e+01 5.4421024e+00 - -3.6144199e+00 -2.9404594e+01 8.4016316e+00 - -2.1953531e+00 -1.9256773e+01 6.2093229e+00 - -3.6081875e+00 -2.9359432e+01 9.4995223e+00 - -3.6062917e+00 -2.9340887e+01 1.0056584e+01 - -3.6011369e+00 -2.9301542e+01 1.0612299e+01 - -3.5981205e+00 -2.9281564e+01 1.1179396e+01 - -3.5949491e+00 -2.9259315e+01 1.1751986e+01 - -3.5910981e+00 -2.9225962e+01 1.2326828e+01 - -1.9719325e+00 -1.7657570e+01 8.2030160e+00 - -3.5846053e+00 -2.9180782e+01 1.3506117e+01 - -1.9624783e+00 -1.7588080e+01 8.9063016e+00 - -3.5774594e+00 -2.9126257e+01 1.4712775e+01 - -3.5737759e+00 -2.9097853e+01 1.5329113e+01 - -3.5612547e+00 -2.9004972e+01 1.5921491e+01 - -2.7897911e-01 -5.5606447e+00 3.9856939e+00 - -2.7153964e-01 -5.5091029e+00 4.0832290e+00 - -4.4706380e-01 -6.7569752e+00 5.0995440e+00 - -3.8460168e-01 -6.3150791e+00 4.9847463e+00 - -3.4540076e-01 -6.0300990e+00 4.9539264e+00 - -3.3286715e-01 -5.9439091e+00 5.0484193e+00 - -2.2204291e-01 -5.1513028e+00 4.6420853e+00 - -2.2501988e-01 -5.1755219e+00 4.7969879e+00 - -2.7029081e-01 -5.4966735e+00 5.1824648e+00 - -2.2309651e-01 -5.1580890e+00 5.0693532e+00 - -2.3966042e-01 -5.2791932e+00 5.3169271e+00 - -1.9762151e-01 -4.9767776e+00 5.2165449e+00 - -1.9018554e-01 -4.9257795e+00 5.3233182e+00 - -1.5468349e-01 -4.6661457e+00 5.2422078e+00 - -1.6429044e-01 -4.7369852e+00 5.4601259e+00 - -1.3305168e-01 -4.5159755e+00 5.4039755e+00 - -1.2998928e-01 -4.4887099e+00 5.5324718e+00 - -6.9778735e-02 -4.0583167e+00 5.2440405e+00 - -5.7299983e-02 -3.9710180e+00 5.3002319e+00 - -7.1758582e-02 -4.0750834e+00 5.5702812e+00 - -3.2253485e-02 -3.7946781e+00 5.4074219e+00 - -7.5507474e-03 -3.6154120e+00 5.3510682e+00 - -6.9104475e-02 -4.0569685e+00 6.0590752e+00 - -8.9661388e-02 -4.2008269e+00 6.4292461e+00 - -6.0285211e-02 -3.9928534e+00 6.3507218e+00 - -5.2415795e-02 -3.9352971e+00 6.4688834e+00 - -7.6391722e-02 -4.1069070e+00 6.9223453e+00 - -3.2150471e-02 -3.7936829e+00 6.6788404e+00 - 6.5435530e-02 -3.0962924e+00 5.8139135e+00 - 7.9899190e-02 -2.9908542e+00 5.8338542e+00 - 7.7776353e-02 -3.0041220e+00 6.0486859e+00 - 8.8424143e-02 -2.9316697e+00 6.1268472e+00 - 3.0570502e-03 -3.5334372e+00 7.4371371e+00 - 2.5302378e-02 -3.3802124e+00 7.4189285e+00 - 4.8456965e-02 -3.2099225e+00 7.3617254e+00 - 9.3605812e-02 -2.8912937e+00 6.9858855e+00 - 1.0975162e-01 -2.7747770e+00 7.0087738e+00 - 1.0613010e-01 -2.8033303e+00 7.3582339e+00 - 1.1635332e-01 -2.7236551e+00 7.4802960e+00 - 1.4339648e-01 -2.5340242e+00 7.3326045e+00 - 1.8660735e-01 -2.2254238e+00 6.8535433e+00 - 1.7880231e-01 -2.2798010e+00 7.3241509e+00 - 2.0925054e-01 -2.0599512e+00 7.0418836e+00 - 2.0293423e-01 -2.1084057e+00 7.5527399e+00 - 2.1005658e-01 -2.0523926e+00 7.7802169e+00 - 2.4269210e-01 -1.8259804e+00 7.4308301e+00 - 2.6192481e-01 -1.6864291e+00 7.3558437e+00 - 2.6555885e-01 -1.6628472e+00 7.7338257e+00 - 2.7740707e-01 -1.5746133e+00 7.8887967e+00 - 3.2886858e-01 -1.2109544e+00 6.7515603e+00 - 3.4327450e-01 -1.1049461e+00 6.7425376e+00 - 3.6020767e-01 -9.8553288e-01 6.6430273e+00 - 3.5879885e-01 -9.9640409e-01 7.3509447e+00 - 3.7619897e-01 -8.6913343e-01 7.2486410e+00 - 3.8521138e-01 -8.0708501e-01 7.6402114e+00 - 4.0640747e-01 -6.5296150e-01 7.2755377e+00 - 4.0055575e-01 -6.8876386e-01 8.9497026e+00 - 4.3546830e-01 -4.4823858e-01 7.4743176e+00 - 4.4830751e-01 -3.4950681e-01 7.7408028e+00 - 4.6606342e-01 -2.2278826e-01 7.4461869e+00 - 4.8326461e-01 -1.0720723e-01 7.1891695e+00 - 2.3687946e-01 -1.5461396e+00 -9.7208525e-01 - 1.8852817e-01 -1.8324250e+00 -9.5846584e-01 - 1.7928016e-01 -1.8864711e+00 -9.4713214e-01 - 1.6670383e-01 -1.9613552e+00 -9.5547556e-01 - 1.5594940e-01 -2.0235284e+00 -9.4803698e-01 - 1.4374197e-01 -2.0928858e+00 -9.4564171e-01 - 1.3294828e-01 -2.1558884e+00 -9.3475777e-01 - 1.1877653e-01 -2.2406422e+00 -9.4180349e-01 - 1.0648320e-01 -2.3117176e+00 -9.3371603e-01 - 9.2159146e-02 -2.3992357e+00 -9.3601878e-01 - 7.8311497e-02 -2.4793366e+00 -9.2977936e-01 - 6.1500117e-02 -2.5747832e+00 -9.3317750e-01 - 4.7101868e-02 -2.6639257e+00 -9.2789040e-01 - 2.8625600e-02 -2.7703129e+00 -9.3143946e-01 - 1.1685351e-02 -2.8683366e+00 -9.2629931e-01 - -5.3574556e-03 -2.9682114e+00 -9.1816364e-01 - -2.1384217e-02 -3.0680037e+00 -9.0713473e-01 - -4.2992342e-02 -3.1931432e+00 -9.0833771e-01 - -6.7784112e-02 -3.3374488e+00 -9.1558425e-01 - -9.2607740e-02 -3.4825247e+00 -9.1818692e-01 - -1.1903542e-01 -3.6375393e+00 -9.2089017e-01 - -1.4084230e-01 -3.7668457e+00 -9.0526587e-01 - -1.6268535e-01 -3.8969569e+00 -8.8569684e-01 - -1.8920860e-01 -4.0542825e+00 -8.7446846e-01 - -2.1989456e-01 -4.2305610e+00 -8.6618429e-01 - -2.4960804e-01 -4.4076210e+00 -8.5226066e-01 - -2.8040499e-01 -4.5863336e+00 -8.3254177e-01 - -3.2118056e-01 -4.8295725e+00 -8.3160550e-01 - -3.5827513e-01 -5.0460606e+00 -8.1268768e-01 - -4.0013335e-01 -5.2914614e+00 -7.9601882e-01 - -4.4518549e-01 -5.5566261e+00 -7.7725397e-01 - -4.9816706e-01 -5.8697267e+00 -7.6388521e-01 - -5.5058241e-01 -6.1741767e+00 -7.3722975e-01 - -6.1420536e-01 -6.5475157e+00 -7.1772003e-01 - -6.8098649e-01 -6.9403329e+00 -6.9032146e-01 - -7.6049809e-01 -7.4108133e+00 -6.6682297e-01 - -8.4898620e-01 -7.9305914e+00 -6.3703260e-01 - -9.4811077e-01 -8.5105686e+00 -6.0030226e-01 - -1.0631264e+00 -9.1877068e+00 -5.5998265e-01 - -1.1903438e+00 -9.9346722e+00 -5.0653143e-01 - -1.3425106e+00 -1.0829266e+01 -4.4664519e-01 - -1.4372193e+00 -1.1390846e+01 -3.1693377e-01 - -1.4918768e+00 -1.1706939e+01 -1.4381022e-01 - -1.5240537e+00 -1.1901019e+01 4.9388277e-02 - -1.6878724e+00 -1.2860531e+01 2.0165865e-01 - -2.0854157e+00 -1.5196527e+01 3.2635163e-01 - -3.4948507e+00 -2.3484471e+01 3.7522611e-01 - -3.6468963e+00 -2.4378827e+01 7.8312914e-01 - -4.5422530e+00 -2.9643259e+01 1.2611031e+00 - -4.5644038e+00 -2.9772133e+01 1.7895408e+00 - -4.5631760e+00 -2.9763052e+01 2.3168362e+00 - -4.5498692e+00 -2.9686672e+01 2.8405370e+00 - -4.5811298e+00 -2.9867456e+01 3.3831057e+00 - -4.5768585e+00 -2.9841360e+01 3.9133477e+00 - -4.5726419e+00 -2.9816217e+01 4.4445382e+00 - -4.5652264e+00 -2.9771271e+01 4.9744316e+00 - -4.5594598e+00 -2.9737137e+01 5.5067710e+00 - -4.5611141e+00 -2.9743266e+01 6.0474500e+00 - -2.8071729e+00 -1.9434590e+01 4.6529358e+00 - -2.7603366e+00 -1.9156714e+01 4.9526265e+00 - -4.5160821e+00 -2.9479852e+01 7.6281443e+00 - -4.5455011e+00 -2.9649315e+01 8.2191035e+00 - -4.5334625e+00 -2.9578127e+01 8.7578866e+00 - -4.5370368e+00 -2.9600844e+01 9.3257282e+00 - -4.5337637e+00 -2.9576236e+01 9.8853859e+00 - -4.5325123e+00 -2.9569029e+01 1.0455727e+01 - -4.5265348e+00 -2.9533210e+01 1.1022224e+01 - -4.5235114e+00 -2.9513691e+01 1.1600256e+01 - -4.5188698e+00 -2.9484121e+01 1.2180687e+01 - -4.5115528e+00 -2.9443571e+01 1.2763263e+01 - -4.5086979e+00 -2.9427978e+01 1.3363016e+01 - -4.5035797e+00 -2.9391505e+01 1.3961827e+01 - -4.5008547e+00 -2.9379012e+01 1.4579756e+01 - -4.4973825e+00 -2.9354360e+01 1.5201087e+01 - -4.4850458e+00 -2.9281820e+01 1.5807785e+01 - -4.4770913e+00 -2.9233082e+01 1.6434808e+01 - -4.5618441e-01 -5.6138762e+00 4.0918399e+00 - -4.4655871e-01 -5.5593906e+00 4.1907182e+00 - -4.3636472e-01 -5.4952063e+00 4.2836077e+00 - -4.4950093e-01 -5.5727164e+00 4.4639298e+00 - -4.0923382e-01 -5.3371509e+00 4.4492578e+00 - -5.1232479e-01 -5.9429790e+00 4.9903082e+00 - -3.8630713e-01 -5.1994117e+00 4.6248470e+00 - -4.8473743e-01 -5.7786972e+00 5.1808795e+00 - -4.7194842e-01 -5.7052080e+00 5.2825054e+00 - -4.3735804e-01 -5.4978148e+00 5.2793705e+00 - -4.3515249e-01 -5.4856481e+00 5.4259383e+00 - -3.6948011e-01 -5.1042697e+00 5.2679491e+00 - -3.7622149e-01 -5.1427118e+00 5.4550153e+00 - -3.5090214e-01 -4.9905801e+00 5.4790938e+00 - -3.1676268e-01 -4.7893688e+00 5.4519367e+00 - -2.7387995e-01 -4.5402078e+00 5.3708968e+00 - -2.1241669e-01 -4.1760904e+00 5.1632227e+00 - -2.0299816e-01 -4.1248074e+00 5.2579549e+00 - -1.9583759e-01 -4.0780731e+00 5.3593333e+00 - -2.3281348e-01 -4.2958907e+00 5.7552809e+00 - -2.5312120e-01 -4.4157958e+00 6.0627928e+00 - -1.6815532e-01 -3.9176746e+00 5.6535231e+00 - -1.9597569e-01 -4.0821851e+00 6.0231555e+00 - -1.8277973e-01 -4.0008023e+00 6.1024624e+00 - -1.8633645e-01 -4.0211016e+00 6.3153470e+00 - -1.7977891e-01 -3.9869222e+00 6.4661086e+00 - -1.6978903e-01 -3.9274633e+00 6.5847640e+00 - -1.6118350e-01 -3.8751561e+00 6.7192998e+00 - -1.3199840e-01 -3.7054129e+00 6.6786069e+00 - -1.1867565e-01 -3.6225011e+00 6.7686510e+00 - -9.7008135e-02 -3.4974027e+00 6.7892796e+00 - -1.4723578e-02 -3.0173130e+00 6.1955873e+00 - 1.3179747e-02 -2.8497757e+00 6.1089543e+00 - -5.6330057e-02 -3.2546421e+00 7.0813289e+00 - -6.5469656e-02 -3.3090683e+00 7.4484194e+00 - -3.4963295e-02 -3.1321620e+00 7.3718212e+00 - 5.7841640e-03 -2.8946060e+00 7.1555995e+00 - -2.6130970e-02 -3.0777415e+00 7.8518777e+00 - 8.6184821e-03 -2.8771140e+00 7.7128075e+00 - 6.8196826e-02 -2.5275434e+00 7.1899729e+00 - 1.0866316e-01 -2.2906867e+00 6.8987950e+00 - 9.4640078e-02 -2.3679776e+00 7.4255391e+00 - 1.2321665e-01 -2.2046445e+00 7.3156804e+00 - 1.2365924e-01 -2.1992596e+00 7.6667454e+00 - 1.4698920e-01 -2.0601458e+00 7.6283004e+00 - 1.7979614e-01 -1.8706144e+00 7.4048848e+00 - 1.8598661e-01 -1.8339101e+00 7.7069109e+00 - 2.1069519e-01 -1.6856276e+00 7.6124365e+00 - 2.1581716e-01 -1.6540665e+00 7.9913173e+00 - 2.8521256e-01 -1.2524781e+00 6.7308497e+00 - 3.0119717e-01 -1.1556014e+00 6.7620167e+00 - 3.2113182e-01 -1.0368294e+00 6.6734330e+00 - 3.2349836e-01 -1.0266855e+00 7.2234970e+00 - 3.3828518e-01 -9.3959538e-01 7.3792072e+00 - 3.5961077e-01 -8.1310353e-01 7.2660042e+00 - 3.6609443e-01 -7.7014516e-01 7.8556751e+00 - 3.9697128e-01 -5.9191146e-01 7.2411457e+00 - 4.1109693e-01 -5.0619378e-01 7.5298917e+00 - 4.3096165e-01 -3.9365372e-01 7.5378344e+00 - 4.4981875e-01 -2.8216031e-01 7.5638573e+00 - 4.6945973e-01 -1.6521933e-01 7.4178948e+00 - 4.8921338e-01 -5.1804781e-02 7.0598438e+00 - 1.9808512e-01 -1.5085855e+00 -9.6999368e-01 - 1.8691559e-01 -1.5608814e+00 -9.6614360e-01 - 1.2919236e-01 -1.8528212e+00 -9.5659285e-01 - 1.1654786e-01 -1.9129928e+00 -9.5154417e-01 - 1.0338522e-01 -1.9814308e+00 -9.5199182e-01 - 8.9175921e-02 -2.0507116e+00 -9.5048908e-01 - 7.4977715e-02 -2.1199038e+00 -9.4718856e-01 - 6.0731005e-02 -2.1899993e+00 -9.4194083e-01 - 4.7433956e-02 -2.2610587e+00 -9.3474908e-01 - 3.0228446e-02 -2.3464606e+00 -9.3833991e-01 - 1.4438519e-02 -2.4254929e+00 -9.3314245e-01 - -3.9162204e-03 -2.5135887e+00 -9.3178737e-01 - -2.1257380e-02 -2.6016218e+00 -9.2793855e-01 - -4.1159036e-02 -2.6986840e+00 -9.2723299e-01 - -6.0044646e-02 -2.7956638e+00 -9.2363419e-01 - -8.1547888e-02 -2.9026449e+00 -9.2262970e-01 - -1.0151573e-01 -3.0012674e+00 -9.1303590e-01 - -1.2152590e-01 -3.1007440e+00 -9.0049612e-01 - -1.4769209e-01 -3.2348015e+00 -9.0503574e-01 - -1.7897434e-01 -3.3868777e+00 -9.1506286e-01 - -2.1086062e-01 -3.5489382e+00 -9.2489412e-01 - -2.4075236e-01 -3.6953610e+00 -9.2039042e-01 - -2.6089120e-01 -3.7979287e+00 -8.8947489e-01 - -2.9392898e-01 -3.9632170e+00 -8.8492228e-01 - -3.2542704e-01 -4.1201122e+00 -8.7108121e-01 - -3.5852114e-01 -4.2868820e+00 -8.5604233e-01 - -3.9833719e-01 -4.4816240e+00 -8.4689115e-01 - -4.3874126e-01 -4.6862222e+00 -8.3494732e-01 - -4.8178680e-01 -4.9015280e+00 -8.1965553e-01 - -5.2897346e-01 -5.1356143e+00 -8.0381227e-01 - -5.7935651e-01 -5.3894844e+00 -7.8627252e-01 - -6.3654805e-01 -5.6730495e+00 -7.6902816e-01 - -6.9686097e-01 -5.9752831e+00 -7.4773982e-01 - -7.6558458e-01 -6.3171357e+00 -7.2654783e-01 - -8.4164693e-01 -6.6975623e+00 -7.0330763e-01 - -9.2765210e-01 -7.1264559e+00 -6.7841625e-01 - -1.0294295e+00 -7.6337249e+00 -6.5526844e-01 - -1.1411711e+00 -8.1901475e+00 -6.2412767e-01 - -1.2587547e+00 -8.7776100e+00 -5.7880414e-01 - -1.3993804e+00 -9.4809560e+00 -5.3182724e-01 - -1.5641293e+00 -1.0301818e+01 -4.7700223e-01 - -1.7461939e+00 -1.1211026e+01 -4.0439599e-01 - -1.8014286e+00 -1.1486990e+01 -2.3184661e-01 - -1.8365240e+00 -1.1662963e+01 -4.1125317e-02 - -1.9344647e+00 -1.2147910e+01 1.3308541e-01 - -2.1448453e+00 -1.3198470e+01 2.9393913e-01 - -3.8510184e+00 -2.1715050e+01 2.2556278e-01 - -4.0259152e+00 -2.2587782e+01 5.9679606e-01 - -4.6057627e+00 -2.5483767e+01 9.9874413e-01 - -5.4476329e+00 -2.9685692e+01 1.5270036e+00 - -5.4392968e+00 -2.9641941e+01 2.0541468e+00 - -5.4226888e+00 -2.9560713e+01 2.5784893e+00 - -5.4186819e+00 -2.9538792e+01 3.1051342e+00 - -5.4074019e+00 -2.9479339e+01 3.6288815e+00 - -5.3935302e+00 -2.9410091e+01 4.1510284e+00 - -5.3813172e+00 -2.9351735e+01 4.6740231e+00 - -5.3701614e+00 -2.9294305e+01 5.1972702e+00 - -5.3605954e+00 -2.9246700e+01 5.7227140e+00 - -5.3463636e+00 -2.9171481e+01 6.2443638e+00 - -5.3295383e+00 -2.9086452e+01 6.7647127e+00 - -5.3127694e+00 -2.9002390e+01 7.2857104e+00 - -5.2887590e+00 -2.8881047e+01 7.7987169e+00 - -5.2990283e+00 -2.8931006e+01 8.3552280e+00 - -5.2839322e+00 -2.8858463e+01 8.8846139e+00 - -5.2728713e+00 -2.8803340e+01 9.4218925e+00 - -5.2602648e+00 -2.8739259e+01 9.9596210e+00 - -5.2445294e+00 -2.8656452e+01 1.0494504e+01 - -5.2251956e+00 -2.8563841e+01 1.1029182e+01 - -5.2180898e+00 -2.8525495e+01 1.1587337e+01 - -5.2053300e+00 -2.8459674e+01 1.2140097e+01 - -5.1842248e+00 -2.8354756e+01 1.2682367e+01 - -5.1671935e+00 -2.8268082e+01 1.3236075e+01 - -5.0182210e+00 -2.7525843e+01 1.3497411e+01 - -5.1972747e+00 -2.8418425e+01 1.4513643e+01 - -5.4283363e+00 -2.9566947e+01 1.5705622e+01 - -5.4013246e+00 -2.9433052e+01 1.6293184e+01 - -6.2542795e-01 -5.6101459e+00 4.0419380e+00 - -6.0932464e-01 -5.5306723e+00 4.1267279e+00 - -6.1273786e-01 -5.5446675e+00 4.2648087e+00 - -6.2490707e-01 -5.6056826e+00 4.4350999e+00 - -6.0304173e-01 -5.4963236e+00 4.5025604e+00 - -5.5737177e-01 -5.2709622e+00 4.4909616e+00 - -5.7351399e-01 -5.3488987e+00 4.6792331e+00 - -5.8582544e-01 -5.4131134e+00 4.8657026e+00 - -6.1451333e-01 -5.5524947e+00 5.1142530e+00 - -6.2372663e-01 -5.5987423e+00 5.3027208e+00 - -5.8222472e-01 -5.3928923e+00 5.2971163e+00 - -5.5775859e-01 -5.2731508e+00 5.3546371e+00 - -5.4717193e-01 -5.2200544e+00 5.4670946e+00 - -5.4217446e-01 -5.1944306e+00 5.6052718e+00 - -4.3733601e-01 -4.6708235e+00 5.2889386e+00 - -4.3952870e-01 -4.6825865e+00 5.4532343e+00 - -4.7804807e-01 -4.8736710e+00 5.7999136e+00 - -3.5919263e-01 -4.2776781e+00 5.3626785e+00 - -3.4476654e-01 -4.2092436e+00 5.4453199e+00 - -4.1538638e-01 -4.5601892e+00 5.9876143e+00 - -3.2213424e-01 -4.0937558e+00 5.6370271e+00 - -3.3137571e-01 -4.1422914e+00 5.8601505e+00 - -3.1641690e-01 -4.0649581e+00 5.9408478e+00 - -3.7708859e-01 -4.3684256e+00 6.5019649e+00 - -3.6344077e-01 -4.2976576e+00 6.6104280e+00 - -3.0396343e-01 -4.0000383e+00 6.4145568e+00 - -2.7948557e-01 -3.8786558e+00 6.4445628e+00 - -2.4547613e-01 -3.7120925e+00 6.4062998e+00 - -2.3894428e-01 -3.6786342e+00 6.5627040e+00 - -2.2542923e-01 -3.6099587e+00 6.6692687e+00 - -2.0787067e-01 -3.5227669e+00 6.7496639e+00 - -1.9718084e-01 -3.4693619e+00 6.8886382e+00 - -1.7528158e-01 -3.3581846e+00 6.9321795e+00 - -1.5364456e-01 -3.2516817e+00 6.9822608e+00 - -1.8003982e-01 -3.3833579e+00 7.4895365e+00 - -1.5113227e-01 -3.2362473e+00 7.4774957e+00 - -1.0338265e-01 -2.9995103e+00 7.2734863e+00 - -1.2528988e-01 -3.1075708e+00 7.7971911e+00 - -2.5572323e-03 -2.4965396e+00 6.7187004e+00 - 1.4759223e-02 -2.4133456e+00 6.7990941e+00 - 1.7515114e-02 -2.3978126e+00 7.0544267e+00 - 5.0041190e-02 -2.2350661e+00 6.9375640e+00 - 3.8059531e-02 -2.2932502e+00 7.4274086e+00 - 4.7763892e-02 -2.2438091e+00 7.6468836e+00 - 9.4844798e-02 -2.0113845e+00 7.3149330e+00 - 1.1669207e-01 -1.9001069e+00 7.3402472e+00 - 1.1687752e-01 -1.9029658e+00 7.7673136e+00 - 1.3882980e-01 -1.7913648e+00 7.8194443e+00 - 1.8545696e-01 -1.5610189e+00 7.3845719e+00 - 2.0725265e-01 -1.4506693e+00 7.4113339e+00 - 2.5878410e-01 -1.1921350e+00 6.7221289e+00 - 2.7503538e-01 -1.1114790e+00 6.8308891e+00 - 2.8880133e-01 -1.0438929e+00 7.0369286e+00 - 3.0286631e-01 -9.7237010e-01 7.2619958e+00 - 3.2571363e-01 -8.5804353e-01 7.2287814e+00 - 3.4471940e-01 -7.6629239e-01 7.3623086e+00 - 3.8812296e-01 -5.4606266e-01 7.3657951e+00 - 4.0764541e-01 -4.4708826e-01 7.5241939e+00 - 4.3043374e-01 -3.3374879e-01 7.4912289e+00 - 4.5413828e-01 -2.1803036e-01 7.3861520e+00 - 4.7646752e-01 -1.0732811e-01 7.2592037e+00 - 1.4683103e-01 -1.5276635e+00 -9.7214042e-01 - 6.6985580e-02 -1.8710175e+00 -9.5431003e-01 - 5.3347222e-02 -1.9310942e+00 -9.4855904e-01 - 3.5731553e-02 -2.0065794e+00 -9.5493935e-01 - 1.9532083e-02 -2.0756901e+00 -9.5243148e-01 - 3.3437108e-03 -2.1447121e+00 -9.4812584e-01 - -1.4354787e-02 -2.2218907e+00 -9.4831457e-01 - -3.0639553e-02 -2.2927145e+00 -9.4001464e-01 - -4.8372992e-02 -2.3706880e+00 -9.3605888e-01 - -6.7151253e-02 -2.4494897e+00 -9.2985311e-01 - -9.0472222e-02 -2.5528597e+00 -9.3912801e-01 - -1.1079863e-01 -2.6406376e+00 -9.3377150e-01 - -1.3368492e-01 -2.7374396e+00 -9.3145837e-01 - -1.5561600e-01 -2.8351611e+00 -9.2630233e-01 - -1.7852737e-01 -2.9326792e+00 -9.1824669e-01 - -2.0154129e-01 -3.0320484e+00 -9.0719552e-01 - -2.3007636e-01 -3.1557678e+00 -9.0842579e-01 - -2.6279263e-01 -3.2985879e+00 -9.1559657e-01 - -2.9647931e-01 -3.4411258e+00 -9.1826971e-01 - -3.3591076e-01 -3.6118639e+00 -9.3022956e-01 - -3.5748362e-01 -3.7051756e+00 -8.9645768e-01 - -3.9546681e-01 -3.8692829e+00 -8.9433577e-01 - -4.2934299e-01 -4.0159139e+00 -8.7868349e-01 - -4.6581585e-01 -4.1723788e+00 -8.6222973e-01 - -5.0795599e-01 -4.3559088e+00 -8.5231566e-01 - -5.5117774e-01 -4.5410767e+00 -8.3630672e-01 - -6.0424179e-01 -4.7723613e+00 -8.3177922e-01 - -6.5419084e-01 -4.9860598e+00 -8.1271941e-01 - -7.1252428e-01 -5.2386513e+00 -7.9929871e-01 - -7.7498713e-01 -5.5099297e+00 -7.8342889e-01 - -8.4681033e-01 -5.8198632e+00 -7.6959943e-01 - -9.1607160e-01 -6.1212719e+00 -7.4258951e-01 - -9.9879447e-01 -6.4792819e+00 -7.2041396e-01 - -1.0909667e+00 -6.8776897e+00 -6.9508597e-01 - -1.2007982e+00 -7.3524467e+00 -6.7339208e-01 - -1.3199855e+00 -7.8663385e+00 -6.4320196e-01 - -1.4459626e+00 -8.4102917e+00 -6.0047347e-01 - -1.5896614e+00 -9.0321248e+00 -5.5189157e-01 - -1.7765382e+00 -9.8372287e+00 -5.0962199e-01 - -1.9895644e+00 -1.0760484e+01 -4.5455442e-01 - -2.0908346e+00 -1.1199576e+01 -3.1031928e-01 - -2.1590679e+00 -1.1491738e+01 -1.3639002e-01 - -2.2370946e+00 -1.1830143e+01 4.3785534e-02 - -2.4791987e+00 -1.2874449e+01 1.9100991e-01 - -4.1341344e+00 -2.0031036e+01 1.0118799e-01 - -4.3427701e+00 -2.0929606e+01 4.3625768e-01 - -5.0267613e+00 -2.3888163e+01 7.8466454e-01 - -5.5212216e+00 -2.6021741e+01 1.2315798e+00 - -5.5572823e+00 -2.6178737e+01 1.7020172e+00 - -5.5470752e+00 -2.6134046e+01 2.1696292e+00 - -5.4812130e+00 -2.5847766e+01 2.6211759e+00 - -5.9751017e+00 -2.7981932e+01 3.2587518e+00 - -5.9243192e+00 -2.7764367e+01 3.7423163e+00 - -6.1455689e+00 -2.8720501e+01 4.3569446e+00 - -6.1405491e+00 -2.8698009e+01 4.8761459e+00 - -6.1490171e+00 -2.8733358e+01 5.4058930e+00 - -5.5107956e+00 -2.5972721e+01 5.4596154e+00 - -5.4966218e+00 -2.5912191e+01 5.9278233e+00 - -5.4902687e+00 -2.5881923e+01 6.4032793e+00 - -5.4720785e+00 -2.5804640e+01 6.8703358e+00 - -5.3997866e+00 -2.5492724e+01 7.2804286e+00 - -5.7700866e+00 -2.7089258e+01 8.1891894e+00 - -5.4669302e+00 -2.5780218e+01 8.3367094e+00 - -5.9194310e+00 -2.7734717e+01 9.4306414e+00 - -5.9089682e+00 -2.7689014e+01 9.9592772e+00 - -5.8984807e+00 -2.7643114e+01 1.0491908e+01 - -5.6981399e+00 -2.6774814e+01 1.1273358e+01 - -5.6771149e+00 -2.6686310e+01 1.1788003e+01 - -5.6677760e+00 -2.6643099e+01 1.2325679e+01 - -5.3963459e+00 -2.5471847e+01 1.2366652e+01 - -5.4638901e+00 -2.5762843e+01 1.3049247e+01 - -5.3040245e+00 -2.5070313e+01 1.3272217e+01 - -5.6604758e+00 -2.6609947e+01 1.4616126e+01 - -8.7521032e-01 -5.9366579e+00 4.1719247e+00 - -7.8882415e-01 -5.5652329e+00 4.1012058e+00 - -7.8821072e-01 -5.5618781e+00 4.2299956e+00 - -7.7552783e-01 -5.5065571e+00 4.3292142e+00 - -7.7913939e-01 -5.5242002e+00 4.4743848e+00 - -8.1176938e-01 -5.6613885e+00 4.7017252e+00 - -8.0199989e-01 -5.6220425e+00 4.8190713e+00 - -8.2946840e-01 -5.7403333e+00 5.0494526e+00 - -8.1392269e-01 -5.6709886e+00 5.1517666e+00 - -7.9726639e-01 -5.5997746e+00 5.2526798e+00 - -7.6193497e-01 -5.4485201e+00 5.2914579e+00 - -7.7571826e-01 -5.5048124e+00 5.4942664e+00 - -7.0700571e-01 -5.2093358e+00 5.4077788e+00 - -6.9442456e-01 -5.1563751e+00 5.5199303e+00 - -6.6299647e-01 -5.0199379e+00 5.5585623e+00 - -6.4354968e-01 -4.9347625e+00 5.6410478e+00 - -5.4015301e-01 -4.4870152e+00 5.3708177e+00 - -4.6110737e-01 -4.1479897e+00 5.1841973e+00 - -4.3654985e-01 -4.0422594e+00 5.2222838e+00 - -5.2236483e-01 -4.4129449e+00 5.7727545e+00 - -4.4714894e-01 -4.0871173e+00 5.5782983e+00 - -6.2964178e-01 -4.8742079e+00 6.6543284e+00 - -4.8137073e-01 -4.2322981e+00 6.0868893e+00 - -6.2369922e-01 -4.8456735e+00 7.0338541e+00 - -5.8702969e-01 -4.6876370e+00 7.0492610e+00 - -4.7231056e-01 -4.1928614e+00 6.6088342e+00 - -3.6296379e-01 -3.7202156e+00 6.1606213e+00 - -3.4237969e-01 -3.6319257e+00 6.2264257e+00 - -3.3222771e-01 -3.5869446e+00 6.3567077e+00 - -3.6045319e-01 -3.7099521e+00 6.7536316e+00 - -3.3309018e-01 -3.5906562e+00 6.7855248e+00 - -3.2426256e-01 -3.5528629e+00 6.9512128e+00 - -2.9835768e-01 -3.4418240e+00 6.9968388e+00 - -2.7234654e-01 -3.3289044e+00 7.0400685e+00 - -2.3182974e-01 -3.1518570e+00 6.9582952e+00 - -2.7417784e-01 -3.3379943e+00 7.5814954e+00 - -2.2596184e-01 -3.1301080e+00 7.4433858e+00 - -2.2203638e-01 -3.1117185e+00 7.6970685e+00 - -9.4258299e-02 -2.5571556e+00 6.7600031e+00 - -8.6882048e-02 -2.5291123e+00 6.9699349e+00 - -4.5176935e-02 -2.3449327e+00 6.8111079e+00 - -4.0120119e-02 -2.3239921e+00 7.0569482e+00 - 3.7305543e-03 -2.1356464e+00 6.8634599e+00 - -2.9640890e-02 -2.2791894e+00 7.6078558e+00 - -1.2721550e-02 -2.2069049e+00 7.7709914e+00 - 2.3508213e-02 -2.0503197e+00 7.6759363e+00 - 4.6987198e-02 -1.9477499e+00 7.7500296e+00 - 1.0100084e-01 -1.7125731e+00 7.3406051e+00 - 1.2296147e-01 -1.6192572e+00 7.4284806e+00 - 1.4757737e-01 -1.5125447e+00 7.4662180e+00 - 1.9836259e-01 -1.2943132e+00 6.9944714e+00 - 2.3758614e-01 -1.1265688e+00 6.6835818e+00 - 2.3989249e-01 -1.1143272e+00 7.1748704e+00 - 2.6197501e-01 -1.0179743e+00 7.2432716e+00 - 2.8293088e-01 -9.2671360e-01 7.3693016e+00 - 3.1212074e-01 -8.0270419e-01 7.2560724e+00 - 3.3658845e-01 -6.9820729e-01 7.2894144e+00 - 3.8356020e-01 -4.9192614e-01 7.4202232e+00 - 4.0718694e-01 -3.8920713e-01 7.5378620e+00 - 4.3296729e-01 -2.7761605e-01 7.5339004e+00 - 4.5960506e-01 -1.6514725e-01 7.4679137e+00 - 4.8628053e-01 -5.1130758e-02 7.0698410e+00 - 9.4641471e-02 -1.5456644e+00 -9.7393401e-01 - 4.9023172e-03 -1.8871952e+00 -9.5162693e-01 - -1.3250529e-02 -1.9553260e+00 -9.5195880e-01 - -2.8930025e-02 -2.0161556e+00 -9.4365498e-01 - -4.8524763e-02 -2.0913820e+00 -9.4723239e-01 - -6.6703303e-02 -2.1602338e+00 -9.4192162e-01 - -8.7390751e-02 -2.2371867e+00 -9.4120192e-01 - -1.0958648e-01 -2.3222815e+00 -9.4467698e-01 - -1.2784784e-01 -2.3928267e+00 -9.3317463e-01 - -1.5013503e-01 -2.4796838e+00 -9.3185638e-01 - -1.7340435e-01 -2.5663523e+00 -9.2793816e-01 - -2.0075231e-01 -2.6702706e+00 -9.3295597e-01 - -2.2410939e-01 -2.7586719e+00 -9.2364519e-01 - -2.5148058e-01 -2.8632915e+00 -9.2262085e-01 - -2.7486397e-01 -2.9524188e+00 -9.0776731e-01 - -3.0640525e-01 -3.0760504e+00 -9.1088569e-01 - -3.4143203e-01 -3.2075503e+00 -9.1509630e-01 - -3.8063754e-01 -3.3581311e+00 -9.2484790e-01 - -4.1427997e-01 -3.4840267e+00 -9.1552645e-01 - -4.4696104e-01 -3.6107926e+00 -9.0236332e-01 - -4.8475323e-01 -3.7555376e+00 -8.9388866e-01 - -5.2508433e-01 -3.9091394e+00 -8.8506158e-01 - -5.6393717e-01 -4.0553548e+00 -8.6709625e-01 - -6.1359061e-01 -4.2467921e+00 -8.6395465e-01 - -6.6013337e-01 -4.4206778e+00 -8.4697988e-01 - -7.1501817e-01 -4.6326023e+00 -8.3859020e-01 - -7.7085798e-01 -4.8441216e+00 -8.2320598e-01 - -8.3189668e-01 -5.0753530e+00 -8.0711767e-01 - -8.9713055e-01 -5.3263125e+00 -7.8942957e-01 - -9.7266951e-01 -5.6149239e+00 -7.7492685e-01 - -1.0492064e+00 -5.9039891e+00 -7.5058350e-01 - -1.1418269e+00 -6.2596914e+00 -7.3436798e-01 - -1.2354908e+00 -6.6167261e+00 -7.0586522e-01 - -1.3513775e+00 -7.0590723e+00 -6.8523210e-01 - -1.4776268e+00 -7.5405618e+00 -6.5749784e-01 - -1.6167777e+00 -8.0700512e+00 -6.2231002e-01 - -1.7689358e+00 -8.6494163e+00 -5.7717250e-01 - -1.9484521e+00 -9.3332975e+00 -5.2891322e-01 - -2.1657921e+00 -1.0162175e+01 -4.7727301e-01 - -2.4141986e+00 -1.1107796e+01 -4.1067118e-01 - -2.4929808e+00 -1.1408529e+01 -2.4035911e-01 - -2.5741850e+00 -1.1716668e+01 -6.0555508e-02 - -2.6791427e+00 -1.2119471e+01 1.2316320e-01 - -4.3039685e+00 -1.8314270e+01 6.5378943e-03 - -4.6297340e+00 -1.9556257e+01 2.9268859e-01 - -4.8052651e+00 -2.0222818e+01 6.3373109e-01 - -5.8769986e+00 -2.4307648e+01 9.9843702e-01 - -5.9623781e+00 -2.4632477e+01 1.4428150e+00 - -5.9567027e+00 -2.4611751e+01 1.8869066e+00 - -5.9184900e+00 -2.4466955e+01 2.3239763e+00 - -5.9854920e+00 -2.4720826e+01 2.7854662e+00 - -6.0095944e+00 -2.4812003e+01 3.2425706e+00 - -5.9986353e+00 -2.4770371e+01 3.6899037e+00 - -5.9955768e+00 -2.4760156e+01 4.1413384e+00 - -5.9909732e+00 -2.4740989e+01 4.5931229e+00 - -5.9823538e+00 -2.4705075e+01 5.0436561e+00 - -5.9754386e+00 -2.4680931e+01 5.4974837e+00 - -5.9696284e+00 -2.4658612e+01 5.9536108e+00 - -5.9622726e+00 -2.4627336e+01 6.4101878e+00 - -5.9540832e+00 -2.4598984e+01 6.8695070e+00 - -5.8806934e+00 -2.4317877e+01 7.2664948e+00 - -5.9669661e+00 -2.4646964e+01 7.8259299e+00 - -5.9388603e+00 -2.4537205e+01 8.2722996e+00 - -5.9523091e+00 -2.4586913e+01 8.7694447e+00 - -5.9386066e+00 -2.4534274e+01 9.2397469e+00 - -5.9275240e+00 -2.4492171e+01 9.7168928e+00 - -5.9138932e+00 -2.4441137e+01 1.0195184e+01 - -5.9038141e+00 -2.4399532e+01 1.0681272e+01 - -5.8876688e+00 -2.4340353e+01 1.1165054e+01 - -5.8608459e+00 -2.4236418e+01 1.1633946e+01 - -5.8496786e+00 -2.4194154e+01 1.2134612e+01 - -5.7839816e+00 -2.3941256e+01 1.2539948e+01 - -1.0631899e+00 -5.9547897e+00 4.0024679e+00 - -1.0185728e+00 -5.7827970e+00 4.0459729e+00 - -1.0205725e+00 -5.7899233e+00 4.1827050e+00 - -5.7660867e+00 -2.3874112e+01 1.4679568e+01 - -1.0106381e+00 -5.7549322e+00 4.4346305e+00 - -9.7132549e-01 -5.6045273e+00 4.4813357e+00 - -9.7077824e-01 -5.6027328e+00 4.6190137e+00 - -9.4820542e-01 -5.5156561e+00 4.7031884e+00 - -9.3995387e-01 -5.4850450e+00 4.8245791e+00 - -9.5065440e-01 -5.5219460e+00 4.9974763e+00 - -9.4887531e-01 -5.5167974e+00 5.1435919e+00 - -9.6490752e-01 -5.5770503e+00 5.3447073e+00 - -8.8327505e-01 -5.2665202e+00 5.2538930e+00 - -8.6842669e-01 -5.2089370e+00 5.3608965e+00 - -8.7420230e-01 -5.2308940e+00 5.5377320e+00 - -8.2097889e-01 -5.0293662e+00 5.5199532e+00 - -8.5369290e-01 -5.1540315e+00 5.7973389e+00 - -6.5408680e-01 -4.3926013e+00 5.2349010e+00 - -5.9702375e-01 -4.1747022e+00 5.1677310e+00 - -6.0156175e-01 -4.1922275e+00 5.3343279e+00 - -6.4062451e-01 -4.3408511e+00 5.6466763e+00 - -5.9762377e-01 -4.1758009e+00 5.6292581e+00 - -7.5177291e-01 -4.7636844e+00 6.4693080e+00 - -7.0508505e-01 -4.5876077e+00 6.4562292e+00 - -6.5685561e-01 -4.4015759e+00 6.4233260e+00 - -6.9955128e-01 -4.5654344e+00 6.8283617e+00 - -6.6921536e-01 -4.4480397e+00 6.8861622e+00 - -4.7729421e-01 -3.7191825e+00 6.1030042e+00 - -4.5214813e-01 -3.6209118e+00 6.1531695e+00 - -4.8711790e-01 -3.7557812e+00 6.5454135e+00 - -4.8238866e-01 -3.7369426e+00 6.7283819e+00 - -4.1802305e-01 -3.4924057e+00 6.5602300e+00 - -3.9790982e-01 -3.4130360e+00 6.6478037e+00 - -4.4153012e-01 -3.5814039e+00 7.1628029e+00 - -4.1524839e-01 -3.4820950e+00 7.2352375e+00 - -3.4709987e-01 -3.2216402e+00 7.0085058e+00 - -3.3094918e-01 -3.1606553e+00 7.1451702e+00 - -3.4626543e-01 -3.2187971e+00 7.5309049e+00 - -3.3230510e-01 -3.1628521e+00 7.7047770e+00 - -1.7763104e-01 -2.5746849e+00 6.7096186e+00 - -1.4759187e-01 -2.4591458e+00 6.7095410e+00 - -1.3032524e-01 -2.3957331e+00 6.8358662e+00 - -1.0516703e-01 -2.2968497e+00 6.8781915e+00 - -7.1556440e-02 -2.1701771e+00 6.8441015e+00 - -2.6767492e-02 -2.0012379e+00 6.6851060e+00 - -6.5071813e-02 -2.1440156e+00 7.4389062e+00 - -6.7421789e-02 -2.1551874e+00 7.8570869e+00 - -2.6551539e-03 -1.9082625e+00 7.4549262e+00 - 3.2260464e-02 -1.7755880e+00 7.4019091e+00 - 6.4675790e-02 -1.6524929e+00 7.3751116e+00 - 5.1986348e-02 -1.6987119e+00 8.0442923e+00 - 1.1853277e-01 -1.4469337e+00 7.4795811e+00 - 1.7517382e-01 -1.2301291e+00 6.9862420e+00 - 2.0262229e-01 -1.1238605e+00 6.9781272e+00 - 2.1095166e-01 -1.0912951e+00 7.4012934e+00 - 2.4321965e-01 -9.6783024e-01 7.3212129e+00 - 2.7752654e-01 -8.4105163e-01 7.1891925e+00 - 3.0493184e-01 -7.3667521e-01 7.2034988e+00 - 3.1447204e-01 -6.9598111e-01 7.8522353e+00 - 3.5648417e-01 -5.3964777e-01 7.3756864e+00 - 3.8409848e-01 -4.3205385e-01 7.3944384e+00 - 4.0873522e-01 -3.3755248e-01 7.6708716e+00 - 4.3763376e-01 -2.2773301e-01 7.7359632e+00 - 4.6973290e-01 -1.0746553e-01 7.3491630e+00 - 4.2934919e-02 -1.5525851e+00 -1.0347493e+00 - 4.1927677e-02 -1.5562074e+00 -9.6758176e-01 - -4.2481737e-02 -1.8423400e+00 -9.5434805e-01 - -6.1517244e-02 -1.9084559e+00 -9.5557485e-01 - -8.1660257e-02 -1.9764165e+00 -9.5490160e-01 - -9.6868900e-02 -2.0298733e+00 -9.3895449e-01 - -1.2191299e-01 -2.1120717e+00 -9.4816175e-01 - -1.4354394e-01 -2.1880115e+00 -9.4838732e-01 - -1.6229953e-01 -2.2503433e+00 -9.3368263e-01 - -1.8642458e-01 -2.3342660e+00 -9.3610223e-01 - -2.1165283e-01 -2.4199990e+00 -9.3592264e-01 - -2.3686566e-01 -2.5056088e+00 -9.3324613e-01 - -2.6318169e-01 -2.5930289e+00 -9.2797042e-01 - -2.9345468e-01 -2.6956949e+00 -9.3153009e-01 - -3.1879946e-01 -2.7839064e+00 -9.2081468e-01 - -3.5015406e-01 -2.8882103e+00 -9.1827947e-01 - -3.7803776e-01 -2.9852783e+00 -9.0721163e-01 - -4.1700993e-01 -3.1156429e+00 -9.1355647e-01 - -4.5507848e-01 -3.2478549e+00 -9.1561057e-01 - -4.9920042e-01 -3.3970232e+00 -9.2309866e-01 - -5.4190185e-01 -3.5397825e+00 -9.2099944e-01 - -5.7091546e-01 -3.6399059e+00 -8.9205205e-01 - -6.2126755e-01 -3.8095061e+00 -8.9438876e-01 - -6.6306885e-01 -3.9546565e+00 -8.7876060e-01 - -7.0840477e-01 -4.1085834e+00 -8.6237732e-01 - -7.6496604e-01 -4.2984478e+00 -8.5616683e-01 - -8.1548420e-01 -4.4719538e+00 -8.3638280e-01 - -8.8234130e-01 -4.6993963e+00 -8.3185956e-01 - -9.4770781e-01 -4.9193539e+00 -8.1620052e-01 - -1.0172117e+00 -5.1580625e+00 -7.9939075e-01 - -1.0903442e+00 -5.4073297e+00 -7.7743206e-01 - -1.1783349e+00 -5.7031273e+00 -7.6119640e-01 - -1.2678822e+00 -6.0084843e+00 -7.3737082e-01 - -1.3687701e+00 -6.3522474e+00 -7.1298246e-01 - -1.4974979e+00 -6.7911814e+00 -6.9984752e-01 - -1.6246349e+00 -7.2213135e+00 -6.6913436e-01 - -1.7734065e+00 -7.7274150e+00 -6.3924602e-01 - -1.9360698e+00 -8.2813919e+00 -6.0060255e-01 - -2.1136659e+00 -8.8840428e+00 -5.5035466e-01 - -2.3304331e+00 -9.6207111e+00 -4.9946180e-01 - -2.5863252e+00 -1.0491027e+01 -4.4043323e-01 - -2.8483002e+00 -1.1380598e+01 -3.5238275e-01 - -2.9637790e+00 -1.1774428e+01 -1.8255835e-01 - -3.0511713e+00 -1.2069570e+01 9.0576152e-03 - -4.3962696e+00 -1.6642029e+01 -6.2264758e-02 - -4.8380255e+00 -1.8142340e+01 1.7296522e-01 - -5.0108151e+00 -1.8729145e+01 4.8732856e-01 - -6.2257625e+00 -2.2859550e+01 7.9028659e-01 - -6.2996561e+00 -2.3109140e+01 1.2084546e+00 - -6.2943106e+00 -2.3092597e+01 1.6285247e+00 - -6.2788113e+00 -2.3040643e+01 2.0468855e+00 - -6.2026583e+00 -2.2780433e+01 2.4505941e+00 - -6.4932055e+00 -2.3766299e+01 2.9478697e+00 - -6.4738580e+00 -2.3700999e+01 3.3770626e+00 - -6.6017462e+00 -2.4134470e+01 3.8644081e+00 - -6.5774639e+00 -2.4054146e+01 4.2991373e+00 - -6.5692030e+00 -2.4023675e+01 4.7406297e+00 - -6.5523413e+00 -2.3966808e+01 5.1787644e+00 - -6.5443040e+00 -2.3940187e+01 5.6232515e+00 - -6.5348427e+00 -2.3906613e+01 6.0680878e+00 - -6.3769513e+00 -2.3368120e+01 6.3982915e+00 - -6.3299040e+00 -2.3208253e+01 6.8062284e+00 - -6.2488532e+00 -2.2931768e+01 7.1800681e+00 - -6.3200755e+00 -2.3175570e+01 7.6977572e+00 - -6.3030351e+00 -2.3115727e+01 8.1354437e+00 - -6.9591429e+00 -2.5343935e+01 9.3275369e+00 - -6.9509987e+00 -2.5318523e+01 9.8285526e+00 - -6.9413021e+00 -2.5284100e+01 1.0331117e+01 - -6.9417731e+00 -2.5286230e+01 1.0852768e+01 - -6.9218748e+00 -2.5215497e+01 1.1351576e+01 - -6.2099538e+00 -2.2796311e+01 1.0840770e+01 - -6.2244249e+00 -2.2847184e+01 1.1353598e+01 - -6.2111094e+00 -2.2801249e+01 1.1829840e+01 - -6.1600400e+00 -2.2625100e+01 1.2247362e+01 - -6.1291313e+00 -2.2519115e+01 1.2701910e+01 - -6.0657148e+00 -2.2303523e+01 1.3100589e+01 - -5.9109077e+00 -2.1777213e+01 1.3323180e+01 - -6.1954159e+00 -2.2744089e+01 1.4411712e+01 - -6.0605260e+00 -2.2284451e+01 1.4681368e+01 - -1.1666293e+00 -5.6603006e+00 4.6152528e+00 - -1.1142942e+00 -5.4820737e+00 5.0761178e+00 - -1.3846002e+00 -6.4009571e+00 5.9366166e+00 - -1.0780328e+00 -5.3575123e+00 5.2853155e+00 - -1.0013461e+00 -5.0972496e+00 5.2265477e+00 - -1.0107558e+00 -5.1298094e+00 5.4076332e+00 - -1.0835937e+00 -5.3764214e+00 5.7860990e+00 - -1.1363674e+00 -5.5541560e+00 6.1216948e+00 - -1.2042062e+00 -5.7857468e+00 6.5259215e+00 - -7.3037976e-01 -4.1745508e+00 5.1297989e+00 - -7.1132723e-01 -4.1124248e+00 5.2122224e+00 - -8.3876687e-01 -4.5448897e+00 5.8212656e+00 - -8.0325678e-01 -4.4237535e+00 5.8597261e+00 - -8.1133908e-01 -4.4521955e+00 6.0647300e+00 - -7.9572891e-01 -4.3991402e+00 6.1824651e+00 - -7.6638341e-01 -4.2984277e+00 6.2465013e+00 - -7.5554157e-01 -4.2590651e+00 6.3856669e+00 - -7.2509535e-01 -4.1565620e+00 6.4467044e+00 - -6.2403699e-01 -3.8138007e+00 6.1803659e+00 - -6.0343858e-01 -3.7432325e+00 6.2730765e+00 - -5.8403667e-01 -3.6762516e+00 6.3728801e+00 - -6.7229247e-01 -3.9771762e+00 7.0323633e+00 - -5.8487837e-01 -3.6792816e+00 6.7952555e+00 - -5.2725682e-01 -3.4838239e+00 6.7010544e+00 - -5.1786778e-01 -3.4537070e+00 6.8744265e+00 - -4.8859545e-01 -3.3540949e+00 6.9364149e+00 - -5.4168535e-01 -3.5330236e+00 7.5099650e+00 - -4.1276007e-01 -3.0946607e+00 6.9406710e+00 - -4.1923507e-01 -3.1182956e+00 7.2443499e+00 - -3.8739402e-01 -3.0085571e+00 7.2912049e+00 - -2.6749243e-01 -2.6015174e+00 6.6861656e+00 - -2.2984108e-01 -2.4747022e+00 6.6598532e+00 - -3.8010942e-01 -2.9832232e+00 8.1528746e+00 - -3.1418982e-01 -2.7606938e+00 7.9474514e+00 - -1.6658856e-01 -2.2573260e+00 6.9731401e+00 - -1.0099220e-01 -2.0353167e+00 6.6761316e+00 - -7.0571647e-02 -1.9304400e+00 6.6839867e+00 - -9.8313090e-02 -2.0242223e+00 7.3062456e+00 - -1.2106653e-01 -2.1030722e+00 7.9524677e+00 - -3.3838320e-02 -1.8059324e+00 7.3568560e+00 - -1.3023941e-02 -1.7357012e+00 7.5237734e+00 - 3.1706765e-02 -1.5855792e+00 7.3897362e+00 - 4.6720084e-02 -1.5338981e+00 7.6607317e+00 - 9.4023043e-02 -1.3700114e+00 7.4434979e+00 - 1.3857990e-01 -1.2197314e+00 7.2518830e+00 - 1.5958807e-01 -1.1484673e+00 7.4599992e+00 - 1.9809458e-01 -1.0197610e+00 7.3516871e+00 - 2.3316860e-01 -9.0004652e-01 7.2802848e+00 - 2.5904685e-01 -8.1118224e-01 7.4246252e+00 - 2.9626523e-01 -6.8421689e-01 7.2595369e+00 - 3.2442035e-01 -5.9013718e-01 7.3904898e+00 - 3.5597184e-01 -4.8322847e-01 7.4002402e+00 - 3.8757184e-01 -3.7541641e-01 7.4080434e+00 - 4.1625039e-01 -2.7715390e-01 7.6237915e+00 - 4.4980835e-01 -1.6306473e-01 7.4979085e+00 - 4.8322213e-01 -5.0428592e-02 7.0398883e+00 - 2.6270877e-04 -1.5317078e+00 -9.8945890e-01 - -1.2012412e-02 -1.5700602e+00 -9.6876818e-01 - -1.0538128e-01 -1.8554566e+00 -9.5161066e-01 - -1.2640818e-01 -1.9214121e+00 -9.5203209e-01 - -1.4602013e-01 -1.9810030e+00 -9.4376510e-01 - -1.6814344e-01 -2.0487146e+00 -9.4048870e-01 - -1.9271606e-01 -2.1235353e+00 -9.4195279e-01 - -2.1733596e-01 -2.1992494e+00 -9.4126993e-01 - -2.4194229e-01 -2.2748552e+00 -9.3838978e-01 - -2.6765366e-01 -2.3522860e+00 -9.3321007e-01 - -2.9235330e-01 -2.4296690e+00 -9.2583624e-01 - -3.2301055e-01 -2.5222114e+00 -9.2799058e-01 - -3.5622707e-01 -2.6237730e+00 -9.3308841e-01 - -3.8451415e-01 -2.7108702e+00 -9.2371140e-01 - -4.1781411e-01 -2.8141302e+00 -9.2271753e-01 - -4.4963889e-01 -2.9100285e+00 -9.1308479e-01 - -4.8904383e-01 -3.0311727e+00 -9.1607709e-01 - -5.2597357e-01 -3.1450011e+00 -9.1013406e-01 - -5.8006120e-01 -3.3092103e+00 -9.2963451e-01 - -6.2307928e-01 -3.4407899e+00 -9.2498097e-01 - -6.5509849e-01 -3.5408207e+00 -8.9782182e-01 - -7.0169413e-01 -3.6820358e+00 -8.8956708e-01 - -7.5094914e-01 -3.8341014e+00 -8.8086081e-01 - -8.0017331e-01 -3.9859207e+00 -8.6716070e-01 - -8.5555528e-01 -4.1565622e+00 -8.5619869e-01 - -9.1452531e-01 -4.3369229e+00 -8.4333338e-01 - -9.8214539e-01 -4.5440738e+00 -8.3510056e-01 - -1.0508409e+00 -4.7528133e+00 -8.1977410e-01 - -1.1220544e+00 -4.9702419e+00 -8.0069940e-01 - -1.2081397e+00 -5.2343094e+00 -7.8954501e-01 - -1.2942893e+00 -5.4999226e+00 -7.6920274e-01 - -1.3875554e+00 -5.7839821e+00 -7.4520328e-01 - -1.4982801e+00 -6.1244356e+00 -7.2672462e-01 - -1.6213331e+00 -6.5031510e+00 -7.0598209e-01 - -1.7576395e+00 -6.9189676e+00 -6.8092466e-01 - -1.9088622e+00 -7.3828110e+00 -6.5140361e-01 - -2.0811499e+00 -7.9134294e+00 -6.1865888e-01 - -2.2554378e+00 -8.4449898e+00 -5.6693201e-01 - -2.4805028e+00 -9.1363518e+00 -5.2272836e-01 - -2.7373243e+00 -9.9225512e+00 -4.6764312e-01 - -3.0495550e+00 -1.0879609e+01 -4.0599045e-01 - -3.4109832e+00 -1.1988274e+01 -3.2634298e-01 - -3.9273760e+00 -1.3571214e+01 -2.4997789e-01 - -4.4877602e+00 -1.5287538e+01 -1.2571106e-01 - -5.0443357e+00 -1.6993926e+01 6.1820818e-02 - -5.2339957e+00 -1.7576854e+01 3.5296851e-01 - -5.3853665e+00 -1.8041580e+01 6.6728520e-01 - -6.5526964e+00 -2.1618780e+01 9.9822931e-01 - -6.8524387e+00 -2.2537028e+01 1.4119271e+00 - -6.8125520e+00 -2.2412764e+01 1.8213641e+00 - -6.5871733e+00 -2.1721689e+01 2.1955887e+00 - -6.7799746e+00 -2.2314892e+01 2.6394504e+00 - -6.8076944e+00 -2.2397670e+01 3.0593174e+00 - -6.7556614e+00 -2.2237631e+01 3.4566019e+00 - -6.9505939e+00 -2.2835401e+01 3.9472594e+00 - -6.9514668e+00 -2.2839196e+01 4.3743786e+00 - -6.9545020e+00 -2.2845743e+01 4.8040498e+00 - -6.9417510e+00 -2.2806382e+01 5.2280549e+00 - -6.9572888e+00 -2.2854647e+01 5.6709749e+00 - -6.9248724e+00 -2.2754752e+01 6.0855649e+00 - -6.6963644e+00 -2.2056076e+01 6.3541654e+00 - -6.6394025e+00 -2.1880030e+01 6.7364124e+00 - -6.5714763e+00 -2.1671163e+01 7.1061594e+00 - -6.4422751e+00 -2.1274432e+01 7.4149979e+00 - -6.6257576e+00 -2.1838080e+01 8.0208458e+00 - -6.5222182e+00 -2.1518900e+01 8.3526916e+00 - -6.8977912e+00 -2.2670371e+01 9.2087929e+00 - -6.8994605e+00 -2.2673009e+01 9.6784123e+00 - -6.8855017e+00 -2.2632033e+01 1.0136372e+01 - -6.8614416e+00 -2.2556064e+01 1.0584134e+01 - -6.8425119e+00 -2.2499260e+01 1.1043685e+01 - -6.7732134e+00 -2.2285402e+01 1.1434804e+01 - -6.5719801e+00 -2.1669128e+01 1.1626838e+01 - -6.5052724e+00 -2.1464541e+01 1.2009920e+01 - -6.4226082e+00 -2.1210105e+01 1.2365914e+01 - -6.4401271e+00 -2.1262253e+01 1.2889737e+01 - -6.3013795e+00 -2.0837544e+01 1.3147475e+01 - -6.5386385e+00 -2.1562613e+01 1.4093027e+01 - -6.4718615e+00 -2.1357988e+01 1.4497132e+01 - -1.5193832e+00 -6.1836505e+00 5.7252807e+00 - -1.5283919e+00 -6.2104274e+00 5.9222985e+00 - -1.5399718e+00 -6.2473503e+00 6.1340502e+00 - -1.1142704e+00 -4.9428082e+00 5.2098144e+00 - -1.3072492e+00 -5.5345495e+00 5.8846900e+00 - -1.1959441e+00 -5.1949163e+00 5.7495043e+00 - -1.2693631e+00 -5.4182360e+00 6.1317307e+00 - -1.3319276e+00 -5.6106455e+00 6.5032542e+00 - -1.0259680e+00 -4.6708223e+00 5.7441290e+00 - -9.8887617e-01 -4.5572456e+00 5.7938660e+00 - -9.4942624e-01 -4.4372890e+00 5.8335618e+00 - -9.5956509e-01 -4.4666071e+00 6.0386217e+00 - -9.3826448e-01 -4.4015588e+00 6.1422134e+00 - -8.9760510e-01 -4.2779113e+00 6.1769137e+00 - -8.7382783e-01 -4.2045039e+00 6.2700655e+00 - -9.0340829e-01 -4.2956619e+00 6.5796207e+00 - -7.5249863e-01 -3.8330741e+00 6.1611838e+00 - -6.9486689e-01 -3.6558867e+00 6.1030272e+00 - -7.2553062e-01 -3.7492114e+00 6.4282152e+00 - -7.9494252e-01 -3.9635896e+00 6.9548545e+00 - -7.8064622e-01 -3.9176383e+00 7.1096935e+00 - -7.3160682e-01 -3.7693585e+00 7.1052803e+00 - -6.7267109e-01 -3.5866932e+00 7.0378344e+00 - -6.2966186e-01 -3.4562157e+00 7.0513576e+00 - -5.5524314e-01 -3.2274854e+00 6.8801187e+00 - -6.3134249e-01 -3.4615230e+00 7.5681669e+00 - -4.8359645e-01 -3.0076265e+00 6.9508323e+00 - -6.4954029e-01 -3.5172484e+00 8.2613795e+00 - -4.5150643e-01 -2.9082763e+00 7.2733375e+00 - -3.2362390e-01 -2.5190754e+00 6.6823453e+00 - -4.5400503e-01 -2.9156933e+00 7.8879764e+00 - -3.9068241e-01 -2.7228991e+00 7.7471139e+00 - -3.6909594e-01 -2.6565979e+00 7.9166234e+00 - -1.8437520e-01 -2.0916943e+00 6.7320922e+00 - -1.4622223e-01 -1.9730335e+00 6.7037760e+00 - -1.4858533e-01 -1.9807000e+00 7.0511968e+00 - -2.1713587e-01 -2.1915042e+00 8.0947923e+00 - -1.8235377e-01 -2.0844372e+00 8.1721985e+00 - -6.3946343e-02 -1.7219150e+00 7.3154512e+00 - -3.6479098e-02 -1.6384897e+00 7.4330168e+00 - -4.1656337e-02 -1.6533011e+00 7.9763485e+00 - 3.3898557e-02 -1.4217664e+00 7.4794628e+00 - 6.6179564e-02 -1.3222223e+00 7.5437388e+00 - 1.1118396e-01 -1.1841389e+00 7.4099933e+00 - 1.4915422e-01 -1.0679696e+00 7.3716887e+00 - 1.5413714e-01 -1.0509289e+00 7.9829723e+00 - 2.2498933e-01 -8.3492624e-01 7.2485879e+00 - 2.6049979e-01 -7.2749709e-01 7.2332573e+00 - 2.7303430e-01 -6.8647022e-01 7.8721467e+00 - 3.2291376e-01 -5.3414200e-01 7.4254835e+00 - 3.5845237e-01 -4.2751943e-01 7.4343223e+00 - 3.9000849e-01 -3.3088849e-01 7.6409218e+00 - 4.2576352e-01 -2.1944197e-01 7.6259923e+00 - 4.6286617e-01 -1.0504847e-01 7.3490861e+00 - -5.0800177e-02 -1.5319377e+00 -9.7541543e-01 - -6.8883698e-02 -1.5827100e+00 -9.6949523e-01 - -1.7255690e-01 -1.8726591e+00 -9.5555385e-01 - -1.9410988e-01 -1.9311715e+00 -9.4812906e-01 - -2.1817486e-01 -1.9978097e+00 -9.4579474e-01 - -2.4228835e-01 -2.0653511e+00 -9.4151320e-01 - -2.7125070e-01 -2.1461975e+00 -9.4846013e-01 - -2.9539974e-01 -2.2145388e+00 -9.4013398e-01 - -3.2551256e-01 -2.2980889e+00 -9.4233475e-01 - -3.5315203e-01 -2.3743379e+00 -9.3589983e-01 - -3.8329548e-01 -2.4586485e+00 -9.3325697e-01 - -4.1693798e-01 -2.5509357e+00 -9.3390362e-01 - -4.4962466e-01 -2.6441374e+00 -9.3160746e-01 - -4.8435063e-01 -2.7380772e+00 -9.2645886e-01 - -5.2063399e-01 -2.8410671e+00 -9.2365767e-01 - -5.5795663e-01 -2.9448408e+00 -9.1770758e-01 - -5.9777091e-01 -3.0565776e+00 -9.1355202e-01 - -6.5072282e-01 -3.2024278e+00 -9.2555471e-01 - -7.0621549e-01 -3.3571494e+00 -9.3750461e-01 - -7.3860849e-01 -3.4469728e+00 -9.0724222e-01 - -7.8313416e-01 -3.5709158e+00 -8.9204262e-01 - -8.3621596e-01 -3.7198670e+00 -8.8586932e-01 - -8.9395037e-01 -3.8795232e+00 -8.7873874e-01 - -9.4808851e-01 -4.0299103e+00 -8.6237562e-01 - -1.0144508e+00 -4.2161794e+00 -8.5628199e-01 - -1.0758277e+00 -4.3870215e+00 -8.3646221e-01 - -1.1564170e+00 -4.6096200e+00 -8.3189289e-01 - -1.2310185e+00 -4.8168176e+00 -8.1290146e-01 - -1.3178152e+00 -5.0596656e+00 -7.9948532e-01 - -1.4092361e+00 -5.3129920e+00 -7.8051759e-01 - -1.5129547e+00 -5.6038198e+00 -7.6412962e-01 - -1.6211642e+00 -5.9030287e+00 -7.4019174e-01 - -1.7488820e+00 -6.2594534e+00 -7.2062010e-01 - -1.8934125e+00 -6.6619527e+00 -6.9997352e-01 - -2.0548010e+00 -7.1114053e+00 -6.7580539e-01 - -2.2233138e+00 -7.5798825e+00 -6.3944100e-01 - -2.4087184e+00 -8.0960981e+00 -5.9521083e-01 - -2.6278692e+00 -8.7064619e+00 -5.4883153e-01 - -2.8939904e+00 -9.4473241e+00 -5.0103158e-01 - -3.2106445e+00 -1.0328202e+01 -4.4581273e-01 - -3.5743577e+00 -1.1341835e+01 -3.7414297e-01 - -4.0499935e+00 -1.2665397e+01 -2.9690698e-01 - -4.5761016e+00 -1.4129520e+01 -1.8278926e-01 - -5.2032691e+00 -1.5874653e+01 -3.3160043e-02 - -5.4250843e+00 -1.6490964e+01 2.3340029e-01 - -5.5903777e+00 -1.6952883e+01 5.2673863e-01 - -6.8266977e+00 -2.0392924e+01 8.0899054e-01 - -6.9215736e+00 -2.0656152e+01 1.1896135e+00 - -6.9056637e+00 -2.0612048e+01 1.5716137e+00 - -6.8848652e+00 -2.0553290e+01 1.9516594e+00 - -6.8002890e+00 -2.0317485e+01 2.3185730e+00 - -6.9361827e+00 -2.0697125e+01 2.7289208e+00 - -6.9515562e+00 -2.0739952e+01 3.1200079e+00 - -6.9415840e+00 -2.0711363e+01 3.5055134e+00 - -6.9327869e+00 -2.0685676e+01 3.8917700e+00 - -6.9215707e+00 -2.0653121e+01 4.2778732e+00 - -6.9141171e+00 -2.0633227e+01 4.6670271e+00 - -6.9017122e+00 -2.0597663e+01 5.0545765e+00 - -6.8930650e+00 -2.0574720e+01 5.4459756e+00 - -6.8855221e+00 -2.0553597e+01 5.8397741e+00 - -6.8755553e+00 -2.0525567e+01 6.2342182e+00 - -6.8500082e+00 -2.0454822e+01 6.6190499e+00 - -6.8230458e+00 -2.0377193e+01 7.0028325e+00 - -6.8576022e+00 -2.0474634e+01 7.4422882e+00 - -6.8834803e+00 -2.0544544e+01 7.8811333e+00 - -6.8386230e+00 -2.0419197e+01 8.2578459e+00 - -6.8863645e+00 -2.0554226e+01 8.7322779e+00 - -6.8785268e+00 -2.0529715e+01 9.1542424e+00 - -6.8697798e+00 -2.0507007e+01 9.5813966e+00 - -6.8560245e+00 -2.0467657e+01 1.0006397e+01 - -6.8482700e+00 -2.0445359e+01 1.0444291e+01 - -6.8310556e+00 -2.0398866e+01 1.0875927e+01 - -6.8243457e+00 -2.0377910e+01 1.1325908e+01 - -6.8105715e+00 -2.0339440e+01 1.1773580e+01 - -6.7907951e+00 -2.0284423e+01 1.2218396e+01 - -6.7206615e+00 -2.0088733e+01 1.2588078e+01 - -6.6720884e+00 -1.9953162e+01 1.2993400e+01 - -6.4954301e+00 -1.9461110e+01 1.3178897e+01 - -6.7915010e+00 -2.0284864e+01 1.4206674e+01 - -6.6866988e+00 -1.9994144e+01 1.4532507e+01 - -1.6731765e+00 -6.0446364e+00 5.7521132e+00 - -1.6640281e+00 -6.0174742e+00 5.9061085e+00 - -1.6108123e+00 -5.8695153e+00 5.9608584e+00 - -1.4454451e+00 -5.4101006e+00 5.7383303e+00 - -1.3790316e+00 -5.2234226e+00 5.7405264e+00 - -1.3702158e+00 -5.2014965e+00 5.8896758e+00 - -1.2870811e+00 -4.9674115e+00 5.8367652e+00 - -1.3068123e+00 -5.0240443e+00 6.0658596e+00 - -1.1798918e+00 -4.6719284e+00 5.8778975e+00 - -1.1302378e+00 -4.5314155e+00 5.8995954e+00 - -1.1261155e+00 -4.5215526e+00 6.0626852e+00 - -1.2978678e+00 -4.9973934e+00 6.7945902e+00 - -1.0295214e+00 -4.2523299e+00 6.1074811e+00 - -1.0632828e+00 -4.3457819e+00 6.4061617e+00 - -1.0659917e+00 -4.3515703e+00 6.6093142e+00 - -9.8339078e-01 -4.1238134e+00 6.5091604e+00 - -9.6950573e-01 -4.0842429e+00 6.6562067e+00 - -9.7460437e-01 -4.0976956e+00 6.8838817e+00 - -1.0746453e+00 -4.3769705e+00 7.5206430e+00 - -9.1727817e-01 -3.9394534e+00 7.0899863e+00 - -9.5421208e-01 -4.0408514e+00 7.4872997e+00 - -8.0291704e-01 -3.6199243e+00 7.0383752e+00 - -8.7304119e-01 -3.8156684e+00 7.6161640e+00 - -7.6553365e-01 -3.5148486e+00 7.3412415e+00 - -6.3941934e-01 -3.1650490e+00 6.9442406e+00 - -5.8653914e-01 -3.0177089e+00 6.9054077e+00 - -6.2923116e-01 -3.1367979e+00 7.4039530e+00 - -5.9282472e-01 -3.0354032e+00 7.4701147e+00 - -5.2944997e-01 -2.8605442e+00 7.3720882e+00 - -4.9644149e-01 -2.7663181e+00 7.4513402e+00 - -4.9059738e-01 -2.7502176e+00 7.7218446e+00 - -4.6476545e-01 -2.6790436e+00 7.8734658e+00 - -2.9722899e-01 -2.2143287e+00 6.9731272e+00 - -2.1640938e-01 -1.9876122e+00 6.6480582e+00 - -1.8260947e-01 -1.8945828e+00 6.6840109e+00 - -2.0221802e-01 -1.9468403e+00 7.1829217e+00 - -2.6941496e-01 -2.1334184e+00 8.1908714e+00 - -2.1204448e-01 -1.9746075e+00 8.0855636e+00 - -2.1023651e-01 -1.9689273e+00 8.5451395e+00 - -1.3200246e-01 -1.7504086e+00 8.1932573e+00 - -4.7202651e-02 -1.5157816e+00 7.7092781e+00 - -2.2234709e-02 -1.4460537e+00 7.9316632e+00 - 4.9588362e-02 -1.2473489e+00 7.5164185e+00 - 1.5563882e-02 -1.3414850e+00 8.6890124e+00 - 1.0661262e-01 -1.0870927e+00 7.9039496e+00 - 1.6781456e-01 -9.1640259e-01 7.5175863e+00 - 2.1856468e-01 -7.7650012e-01 7.2659704e+00 - 2.5812022e-01 -6.6734668e-01 7.2297041e+00 - 2.7928938e-01 -6.0768956e-01 7.7090257e+00 - 3.2534022e-01 -4.8092799e-01 7.4900264e+00 - 3.6293065e-01 -3.7398291e-01 7.5078478e+00 - 3.9958840e-01 -2.7315860e-01 7.6637467e+00 - 4.4001165e-01 -1.6098222e-01 7.5279033e+00 - 4.8028785e-01 -4.9250287e-02 7.0398483e+00 - -1.0320918e-01 -1.5374664e+00 -9.6871167e-01 - -2.4160471e-01 -1.8877173e+00 -9.5899051e-01 - -2.6174828e-01 -1.9399094e+00 -9.4377620e-01 - -2.9020485e-01 -2.0125879e+00 -9.4722433e-01 - -3.1870930e-01 -2.0861649e+00 -9.4862538e-01 - -3.4825795e-01 -2.1605651e+00 -9.4767654e-01 - -3.7433694e-01 -2.2277393e+00 -9.3839481e-01 - -4.0737664e-01 -2.3100520e+00 -9.3943708e-01 - -4.3946298e-01 -2.3932990e+00 -9.3793605e-01 - -4.7259291e-01 -2.4773642e+00 -9.3398526e-01 - -5.0822250e-01 -2.5694566e+00 -9.3312739e-01 - -5.4489260e-01 -2.6623426e+00 -9.2932037e-01 - -5.8757190e-01 -2.7713161e+00 -9.3359368e-01 - -6.2777722e-01 -2.8729835e+00 -9.2913142e-01 - -6.6802243e-01 -2.9754853e+00 -9.2132369e-01 - -7.2134812e-01 -3.1111281e+00 -9.3022314e-01 - -7.7476712e-01 -3.2485481e+00 -9.3462892e-01 - -8.2564823e-01 -3.3776354e+00 -9.2974942e-01 - -8.6704123e-01 -3.4833354e+00 -9.0695856e-01 - -9.2506598e-01 -3.6310859e+00 -9.0281644e-01 - -9.7704761e-01 -3.7624780e+00 -8.8510078e-01 - -1.0386376e+00 -3.9197655e+00 -8.7535992e-01 - -1.0977499e+00 -4.0697173e+00 -8.5628423e-01 - -1.1770864e+00 -4.2714733e+00 -8.5465311e-01 - -1.2529992e+00 -4.4668871e+00 -8.4234239e-01 - -1.3334294e+00 -4.6708937e+00 -8.2677647e-01 - -1.4174353e+00 -4.8845209e+00 -8.0730970e-01 - -1.5227451e+00 -5.1515755e+00 -7.9889300e-01 - -1.6246208e+00 -5.4122041e+00 -7.7809879e-01 - -1.7371083e+00 -5.6992261e+00 -7.5633764e-01 - -1.8719832e+00 -6.0413280e+00 -7.3983130e-01 - -2.0140716e+00 -6.4036831e+00 -7.1577336e-01 - -2.1810125e+00 -6.8288694e+00 -6.9447007e-01 - -2.3562025e+00 -7.2750630e+00 -6.6186701e-01 - -2.5598219e+00 -7.7937184e+00 -6.2831751e-01 - -2.7635055e+00 -8.3144336e+00 -5.7574267e-01 - -1.6653321e+00 -5.5164968e+00 6.0925274e-02 - -1.6637382e+00 -5.5123121e+00 1.6724041e-01 - -1.6513246e+00 -5.4785264e+00 2.7683452e-01 - -1.6628029e+00 -5.5079329e+00 3.7757832e-01 - -1.6257753e+00 -5.4152841e+00 4.9052479e-01 - -1.6396205e+00 -5.4506253e+00 5.9007410e-01 - -5.5825553e+00 -1.5495772e+01 1.2600823e-01 - -5.8172436e+00 -1.6093154e+01 3.9451773e-01 - -7.0849667e+00 -1.9321696e+01 6.3569256e-01 - -7.1629242e+00 -1.9519653e+01 9.9797285e-01 - -7.3261773e+00 -1.9935569e+01 1.3717314e+00 - -7.2348051e+00 -1.9703262e+01 1.7370735e+00 - -7.1375297e+00 -1.9455714e+01 2.0933172e+00 - -7.3338132e+00 -1.9955416e+01 2.4969441e+00 - -7.3560203e+00 -2.0011333e+01 2.8787068e+00 - -7.3427557e+00 -1.9977452e+01 3.2536182e+00 - -7.3388505e+00 -1.9965928e+01 3.6314924e+00 - -7.3315255e+00 -1.9947578e+01 4.0096096e+00 - -7.3182505e+00 -1.9913613e+01 4.3862189e+00 - -7.3097356e+00 -1.9892244e+01 4.7659820e+00 - -7.3033853e+00 -1.9873645e+01 5.1478976e+00 - -7.2936743e+00 -1.9849208e+01 5.5303054e+00 - -7.2815411e+00 -1.9817878e+01 5.9130591e+00 - -7.2376126e+00 -1.9707173e+01 6.2765826e+00 - -7.1923997e+00 -1.9591663e+01 6.6374580e+00 - -7.1306939e+00 -1.9434696e+01 6.9846726e+00 - -7.1752379e+00 -1.9547870e+01 7.4183578e+00 - -7.1784216e+00 -1.9555604e+01 7.8239588e+00 - -7.1342983e+00 -1.9441796e+01 8.1896307e+00 - -7.2555310e+00 -1.9751124e+01 8.7206729e+00 - -7.2466959e+00 -1.9726165e+01 9.1326970e+00 - -7.2370112e+00 -1.9704000e+01 9.5500600e+00 - -7.2292890e+00 -1.9681444e+01 9.9729227e+00 - -7.2171396e+00 -1.9652047e+01 1.0397523e+01 - -7.2129793e+00 -1.9639517e+01 1.0836321e+01 - -7.1523658e+00 -1.9485305e+01 1.1207508e+01 - -7.0634379e+00 -1.9258520e+01 1.1539496e+01 - -7.0404855e+00 -1.9199655e+01 1.1964679e+01 - -6.9622547e+00 -1.9001491e+01 1.2313263e+01 - -6.9721502e+00 -1.9024954e+01 1.2797878e+01 - -6.8113686e+00 -1.8614690e+01 1.3013741e+01 - -7.0991584e+00 -1.9348416e+01 1.3986063e+01 - -7.0183981e+00 -1.9142502e+01 1.4352372e+01 - -1.8664703e+00 -6.0244355e+00 5.7016474e+00 - -1.8339608e+00 -5.9398703e+00 5.8079117e+00 - -1.4831434e+00 -5.0466518e+00 5.2352360e+00 - -1.6283605e+00 -5.4183643e+00 5.7130339e+00 - -1.6570035e+00 -5.4901691e+00 5.9489391e+00 - -1.7055957e+00 -5.6131282e+00 6.2413572e+00 - -1.5834010e+00 -5.3030313e+00 6.3122136e+00 - -1.3339592e+00 -4.6664458e+00 5.8413321e+00 - -1.2712989e+00 -4.5086423e+00 5.8432736e+00 - -1.4920842e+00 -5.0696197e+00 6.6391543e+00 - -1.4878612e+00 -5.0594679e+00 6.8283615e+00 - -1.4342104e+00 -4.9201955e+00 6.8703209e+00 - -1.5833220e+00 -5.3006810e+00 7.5503244e+00 - -1.5484804e+00 -5.2114901e+00 7.6717652e+00 - -1.1277382e+00 -4.1409255e+00 6.4939747e+00 - -1.0906795e+00 -4.0454498e+00 6.5629274e+00 - -1.0783607e+00 -4.0160316e+00 6.7258030e+00 - -1.1943288e+00 -4.3107961e+00 7.3746405e+00 - -1.0112946e+00 -3.8440376e+00 6.8975277e+00 - -9.6498908e-01 -3.7265867e+00 6.9355025e+00 - -9.6068817e-01 -3.7163283e+00 7.1471316e+00 - -9.0255552e-01 -3.5661683e+00 7.1310554e+00 - -9.7037250e-01 -3.7391347e+00 7.6855791e+00 - -1.0170892e+00 -3.8582381e+00 8.1789435e+00 - -7.0320908e-01 -3.0596110e+00 6.9296212e+00 - -6.4173149e-01 -2.9011587e+00 6.8624529e+00 - -6.9315408e-01 -3.0339714e+00 7.3971727e+00 - -6.6416671e-01 -2.9585982e+00 7.5160272e+00 - -6.1562372e-01 -2.8362473e+00 7.5342224e+00 - -5.3563636e-01 -2.6306219e+00 7.3488701e+00 - -5.5072750e-01 -2.6696446e+00 7.7562882e+00 - -5.0565112e-01 -2.5560423e+00 7.7960624e+00 - -3.1400502e-01 -2.0680412e+00 6.7880952e+00 - -2.8411093e-01 -1.9929435e+00 6.8823272e+00 - -2.5634491e-01 -1.9208407e+00 6.9944420e+00 - -3.5835575e-01 -2.1803144e+00 8.2088524e+00 - -3.1315996e-01 -2.0652421e+00 8.2581652e+00 - -2.6107145e-01 -1.9319645e+00 8.2381532e+00 - -2.5117754e-01 -1.9055494e+00 8.6403869e+00 - -1.4904421e-01 -1.6460423e+00 8.0927966e+00 - -8.9231054e-02 -1.4949169e+00 7.9569147e+00 - -3.2796937e-02 -1.3502931e+00 7.8273818e+00 - -3.8358113e-02 -1.3637459e+00 8.5388564e+00 - 1.3639770e-02 -1.2311925e+00 8.5041625e+00 - 8.4392238e-02 -1.0529050e+00 8.1409946e+00 - 1.3293382e-01 -9.2695512e-01 8.0903276e+00 - 2.1612960e-01 -7.1834044e-01 7.2828409e+00 - 2.2197188e-01 -7.0216852e-01 8.1804152e+00 - 2.8940665e-01 -5.2916198e-01 7.5051430e+00 - 3.3398018e-01 -4.1699935e-01 7.4144303e+00 - 3.7537133e-01 -3.1131415e-01 7.3913398e+00 - 4.1389839e-01 -2.1317298e-01 7.5560703e+00 - 4.5700110e-01 -1.0369550e-01 7.3691804e+00 - -1.6083714e-01 -1.5460630e+00 -9.6953386e-01 - -3.0912452e-01 -1.8944760e+00 -9.5503638e-01 - -3.3706049e-01 -1.9588686e+00 -9.5258868e-01 - -3.6504559e-01 -2.0241694e+00 -9.4829365e-01 - -3.9553897e-01 -2.0975663e+00 -9.4848982e-01 - -4.2455841e-01 -2.1636115e+00 -9.4024688e-01 - -4.5608428e-01 -2.2377381e+00 -9.3619550e-01 - -4.9111292e-01 -2.3198708e+00 -9.3603288e-01 - -5.2964123e-01 -2.4099850e+00 -9.3925964e-01 - -5.6815290e-01 -2.4999661e+00 -9.3978973e-01 - -6.1022014e-01 -2.5988913e+00 -9.4296051e-01 - -6.4987487e-01 -2.6915171e+00 -9.3754593e-01 - -6.8951110e-01 -2.7839951e+00 -9.2913504e-01 - -7.3866423e-01 -2.9006062e+00 -9.3349226e-01 - -7.8289100e-01 -3.0027775e+00 -9.2387402e-01 - -8.4364450e-01 -3.1451286e+00 -9.3550055e-01 - -9.0098114e-01 -3.2811916e+00 -9.3754612e-01 - -9.4274978e-01 -3.3766990e+00 -9.1195165e-01 - -1.0011539e+00 -3.5142865e+00 -9.0560518e-01 - -1.0560237e+00 -3.6436166e+00 -8.9027624e-01 - -1.1224995e+00 -3.7987311e+00 -8.8311549e-01 - -1.1854989e+00 -3.9465654e+00 -8.6652322e-01 - -1.2636566e+00 -4.1291035e+00 -8.6024045e-01 - -1.3347725e+00 -4.2953385e+00 -8.4028744e-01 - -1.4316564e+00 -4.5221369e+00 -8.3911494e-01 - -1.5214916e+00 -4.7325781e+00 -8.2317355e-01 - -1.6194569e+00 -4.9615285e+00 -8.0606870e-01 - -1.7291042e+00 -5.2179024e+00 -7.8984183e-01 - -1.8504235e+00 -5.5016210e+00 -7.7289492e-01 - -1.8547052e+00 -5.5119406e+00 -6.6282434e-01 - -1.8157723e+00 -5.4222033e+00 -5.2541600e-01 - -1.8000009e+00 -5.3831166e+00 -4.0599164e-01 - -1.7973325e+00 -5.3778673e+00 -2.9713244e-01 - -1.7945468e+00 -5.3706488e+00 -1.8887172e-01 - -1.7987457e+00 -5.3792751e+00 -8.4992718e-02 - -1.8018855e+00 -5.3869599e+00 1.8933433e-02 - -1.7968092e+00 -5.3749317e+00 1.2584140e-01 - -1.7824657e+00 -5.3423131e+00 2.3447993e-01 - -1.7878588e+00 -5.3539929e+00 3.3601385e-01 - -1.6193247e+00 -4.9608159e+00 4.7988147e-01 - -1.8151222e+00 -5.4176524e+00 5.3566451e-01 - -1.8217512e+00 -5.4332350e+00 6.3789919e-01 - -1.8273182e+00 -5.4478515e+00 7.4068040e-01 - -1.8291606e+00 -5.4506268e+00 8.4405599e-01 - -1.8137275e+00 -5.4163063e+00 9.4789804e-01 - -7.4195286e+00 -1.8538529e+01 1.1732337e+00 - -7.4053531e+00 -1.8504889e+01 1.5242218e+00 - -7.3970176e+00 -1.8484953e+01 1.8749208e+00 - -7.2954209e+00 -1.8247700e+01 2.2109201e+00 - -7.6194842e+00 -1.9005041e+01 2.6236392e+00 - -7.6344606e+00 -1.9040053e+01 2.9908093e+00 - -7.5643584e+00 -1.8876675e+01 3.3359537e+00 - -7.7541137e+00 -1.9319438e+01 3.7629640e+00 - -7.7457157e+00 -1.9299519e+01 4.1335880e+00 - -7.7303696e+00 -1.9264046e+01 4.5027009e+00 - -7.7172532e+00 -1.9232380e+01 4.8732170e+00 - -7.7053046e+00 -1.9203557e+01 5.2456827e+00 - -7.6934641e+00 -1.9176628e+01 5.6202449e+00 - -7.6535287e+00 -1.9081975e+01 5.9788777e+00 - -7.4809714e+00 -1.8678695e+01 6.2501800e+00 - -7.4480679e+00 -1.8600779e+01 6.6065780e+00 - -7.3744806e+00 -1.8428505e+01 6.9331397e+00 - -7.3474484e+00 -1.8365060e+01 7.2939923e+00 - -7.4343395e+00 -1.8566716e+01 7.7526287e+00 - -7.3899519e+00 -1.8464506e+01 8.1072569e+00 - -7.6198961e+00 -1.9001800e+01 8.7227046e+00 - -7.6030830e+00 -1.8960062e+01 9.1187331e+00 - -7.5969091e+00 -1.8945968e+01 9.5309091e+00 - -7.5837901e+00 -1.8916344e+01 9.9410746e+00 - -7.5786627e+00 -1.8903607e+01 1.0365038e+01 - -7.5350975e+00 -1.8799932e+01 1.0748135e+01 - -7.3158231e+00 -1.8287775e+01 1.1349592e+01 - -7.2955831e+00 -1.8240185e+01 1.1766637e+01 - -7.2148066e+00 -1.8048883e+01 1.2101327e+01 - -7.2213276e+00 -1.8065364e+01 1.2569056e+01 - -7.1486446e+00 -1.7892795e+01 1.2920639e+01 - -6.9659333e+00 -1.7465749e+01 1.3097191e+01 - -7.3016982e+00 -1.8250585e+01 1.4133206e+01 - -7.1815485e+00 -1.7969423e+01 1.4426675e+01 - -1.9889476e+00 -5.8217398e+00 5.8571080e+00 - -1.6637660e+00 -5.0588559e+00 5.3756240e+00 - -1.5660311e+00 -4.8322623e+00 5.3310028e+00 - -1.8177389e+00 -5.4191364e+00 6.0324335e+00 - -1.7412183e+00 -5.2408277e+00 6.2216102e+00 - -1.6965712e+00 -5.1363296e+00 6.2996829e+00 - -1.9826123e+00 -5.8044210e+00 7.2021746e+00 - -1.9228816e+00 -5.6653012e+00 7.2686343e+00 - -1.8884209e+00 -5.5827638e+00 7.3970138e+00 - -1.8148561e+00 -5.4114861e+00 7.4209514e+00 - -1.7909291e+00 -5.3557497e+00 7.5825572e+00 - -1.7715070e+00 -5.3090218e+00 7.7592532e+00 - -1.6945062e+00 -5.1297558e+00 7.7664555e+00 - -1.2586987e+00 -4.1097692e+00 6.6186008e+00 - -1.2291982e+00 -4.0419426e+00 6.7275117e+00 - -1.1972118e+00 -3.9656831e+00 6.8274807e+00 - -1.1953238e+00 -3.9622431e+00 7.0402620e+00 - -1.1092466e+00 -3.7603003e+00 6.9496704e+00 - -1.0244448e+00 -3.5625756e+00 6.8533874e+00 - -1.0143498e+00 -3.5379492e+00 7.0382399e+00 - -1.0112470e+00 -3.5318071e+00 7.2664997e+00 - -1.2341828e+00 -4.0509166e+00 8.4783440e+00 - -1.1068229e+00 -3.7537400e+00 8.2147926e+00 - -7.4325017e-01 -2.9042884e+00 6.8173773e+00 - -6.9418357e-01 -2.7894002e+00 6.8273269e+00 - -6.9437703e-01 -2.7896139e+00 7.0851566e+00 - -8.0083188e-01 -3.0364646e+00 7.9225074e+00 - -7.8368581e-01 -2.9970086e+00 8.1519408e+00 - -6.0305524e-01 -2.5739978e+00 7.4375053e+00 - -6.0986603e-01 -2.5897004e+00 7.7994674e+00 - -4.2620288e-01 -2.1598619e+00 6.9637273e+00 - -3.7387294e-01 -2.0383651e+00 6.9289760e+00 - -3.2261987e-01 -1.9179525e+00 6.8912811e+00 - -4.6438015e-01 -2.2490619e+00 8.3113194e+00 - -3.8343414e-01 -2.0595858e+00 8.1049308e+00 - -3.4788313e-01 -1.9768890e+00 8.2580262e+00 - -3.6753939e-01 -2.0225222e+00 8.9305251e+00 - -2.3145515e-01 -1.7037205e+00 8.1641343e+00 - -1.6440018e-01 -1.5478888e+00 8.0106542e+00 - -1.1528056e-01 -1.4325770e+00 8.0291931e+00 - -5.8399725e-02 -1.2996407e+00 7.9475924e+00 - -6.1477887e-02 -1.3051993e+00 8.6594633e+00 - 1.7575600e-02 -1.1217783e+00 8.2885818e+00 - 7.7767687e-02 -9.7978757e-01 8.1308206e+00 - 1.6379760e-01 -7.8037185e-01 7.4444189e+00 - 2.0711250e-01 -6.7899770e-01 7.4781991e+00 - 2.4947876e-01 -5.7768310e-01 7.5298101e+00 - 2.9594131e-01 -4.7114061e-01 7.5099501e+00 - 3.3835029e-01 -3.7154753e-01 7.6077025e+00 - 3.8093232e-01 -2.7005590e-01 7.7236828e+00 - 4.3021044e-01 -1.5687272e-01 7.5179490e+00 - 4.7635602e-01 -4.8006606e-02 7.0399113e+00 - -3.7405856e-01 -1.8920037e+00 -9.4384405e-01 - -4.0398593e-01 -1.9562359e+00 -9.4059097e-01 - -4.3982118e-01 -2.0347145e+00 -9.4861351e-01 - -4.7078289e-01 -2.0996910e+00 -9.4141252e-01 - -5.0770839e-01 -2.1798764e+00 -9.4473845e-01 - -5.3770687e-01 -2.2457084e+00 -9.3339614e-01 - -5.7911788e-01 -2.3337163e+00 -9.3811074e-01 - -6.1611880e-01 -2.4155360e+00 -9.3404657e-01 - -6.5761633e-01 -2.5052668e+00 -9.3316885e-01 - -7.0366823e-01 -2.6038861e+00 -9.3502852e-01 - -7.5215463e-01 -2.7094962e+00 -9.3923164e-01 - -7.9126411e-01 -2.7936390e+00 -9.2392616e-01 - -8.4088865e-01 -2.9018543e+00 -9.2138560e-01 - -8.9499931e-01 -3.0178971e+00 -9.2033358e-01 - -9.6073069e-01 -3.1598425e+00 -9.2984680e-01 - -1.0219266e+00 -3.2935663e+00 -9.2988134e-01 - -1.0701863e+00 -3.3968492e+00 -9.0716732e-01 - -1.1289426e+00 -3.5240569e+00 -8.9422192e-01 - -1.1958008e+00 -3.6690330e+00 -8.8535621e-01 - -1.2671906e+00 -3.8227153e+00 -8.7553245e-01 - -1.3421113e+00 -3.9851445e+00 -8.6435431e-01 - -1.4181148e+00 -4.1492213e+00 -8.4728104e-01 - -1.5127684e+00 -4.3559193e+00 -8.4260826e-01 - -1.6048743e+00 -4.5542059e+00 -8.2705218e-01 - -1.7051735e+00 -4.7720232e+00 -8.1078247e-01 - -1.8180361e+00 -5.0152392e+00 -7.9608592e-01 - -1.9112423e+00 -5.2163446e+00 -7.5785620e-01 - -1.9999106e+00 -5.4092087e+00 -7.0974831e-01 - -2.2271398e+00 -5.9006535e+00 -7.4267584e-01 - -2.3941978e+00 -6.2616205e+00 -7.2103532e-01 - -2.5820536e+00 -6.6683611e+00 -6.9710862e-01 - -2.7871407e+00 -7.1118428e+00 -6.6645725e-01 - -3.0002864e+00 -7.5732622e+00 -6.2305673e-01 - -3.2433477e+00 -8.0988202e+00 -5.7450549e-01 - -3.5567831e+00 -8.7769497e+00 -5.3291217e-01 - -3.8124039e+00 -9.3299383e+00 -4.4608485e-01 - -3.8059714e+00 -9.3161414e+00 -2.6157667e-01 - -3.6806940e+00 -9.0453191e+00 -4.8829321e-02 - -3.4711289e+00 -8.5906792e+00 1.7065048e-01 - -3.4843952e+00 -8.6198469e+00 3.3457146e-01 - -3.4767676e+00 -8.6019582e+00 5.0194955e-01 - -3.8188047e+00 -9.3438258e+00 6.3907725e-01 - -3.7880422e+00 -9.2754984e+00 8.2014461e-01 - -7.6439119e+00 -1.7618949e+01 9.9699446e-01 - -7.6426681e+00 -1.7616229e+01 1.3357707e+00 - -7.6309930e+00 -1.7590107e+01 1.6737285e+00 - -7.6124299e+00 -1.7549428e+01 2.0102250e+00 - -7.5743204e+00 -1.7467001e+01 2.3426391e+00 - -7.6929007e+00 -1.7723674e+01 2.7052630e+00 - -7.6754390e+00 -1.7684790e+01 3.0446582e+00 - -7.6672775e+00 -1.7667277e+01 3.3867670e+00 - -7.6487568e+00 -1.7627451e+01 3.7262094e+00 - -7.6404682e+00 -1.7607890e+01 4.0693178e+00 - -7.6208258e+00 -1.7566107e+01 4.4091573e+00 - -7.6114074e+00 -1.7544523e+01 4.7539612e+00 - -7.5951632e+00 -1.7509394e+01 5.0970535e+00 - -7.5846108e+00 -1.7485754e+01 5.4442520e+00 - -7.5706984e+00 -1.7456279e+01 5.7918428e+00 - -7.5590064e+00 -1.7430538e+01 6.1423348e+00 - -7.5242864e+00 -1.7354697e+01 6.4793999e+00 - -7.5068779e+00 -1.7317270e+01 6.8297808e+00 - -7.3996817e+00 -1.7084007e+01 7.1124764e+00 - -7.5719145e+00 -1.7456671e+01 7.6190232e+00 - -7.5383048e+00 -1.7383213e+01 7.9673265e+00 - -7.6071040e+00 -1.7533514e+01 8.4116036e+00 - -7.6067338e+00 -1.7531286e+01 8.7999705e+00 - -7.5984184e+00 -1.7513574e+01 9.1866235e+00 - -7.5796462e+00 -1.7471739e+01 9.5668156e+00 - -7.5689878e+00 -1.7448799e+01 9.9606054e+00 - -7.5478762e+00 -1.7401764e+01 1.0347335e+01 - -7.5303027e+00 -1.7364050e+01 1.0744058e+01 - -7.5172606e+00 -1.7335557e+01 1.1151576e+01 - -7.5076865e+00 -1.7315307e+01 1.1570637e+01 - -7.4406025e+00 -1.7168742e+01 1.1916929e+01 - -7.4310122e+00 -1.7148878e+01 1.2348424e+01 - -7.4188657e+00 -1.7120021e+01 1.2782362e+01 - -7.2499121e+00 -1.6756069e+01 1.2984539e+01 - -7.5679659e+00 -1.7443727e+01 1.3958981e+01 - -7.4446471e+00 -1.7176092e+01 1.4246489e+01 - -7.2721128e+00 -1.6802480e+01 1.4445564e+01 - -2.1606719e+00 -5.7506302e+00 5.9489766e+00 - -2.0066333e+00 -5.4176745e+00 5.8322792e+00 - -2.1844389e+00 -5.8007041e+00 7.6169474e+00 - -1.9723106e+00 -5.3422577e+00 7.3106754e+00 - -1.8698399e+00 -5.1200675e+00 7.2639393e+00 - -1.8428068e+00 -5.0620733e+00 7.4142008e+00 - -1.8225304e+00 -5.0175870e+00 7.5871974e+00 - -1.4590826e+00 -4.2331715e+00 6.7579879e+00 - -1.3760553e+00 -4.0508731e+00 6.7124385e+00 - -1.3491179e+00 -3.9931285e+00 6.8373816e+00 - -1.4019087e+00 -4.1079072e+00 7.2287446e+00 - -1.2906552e+00 -3.8679657e+00 7.0856609e+00 - -1.1452356e+00 -3.5527841e+00 6.8026872e+00 - -1.0636310e+00 -3.3758813e+00 6.7275759e+00 - -1.1377725e+00 -3.5348775e+00 7.2325892e+00 - -1.1005445e+00 -3.4548536e+00 7.3339421e+00 - -9.0434573e-01 -3.0315991e+00 6.7846024e+00 - -7.3551754e-01 -2.6666720e+00 6.2998847e+00 - -7.8915196e-01 -2.7827341e+00 6.7653075e+00 - -7.3497984e-01 -2.6656845e+00 6.7644056e+00 - -7.2264872e-01 -2.6377151e+00 6.9586913e+00 - -8.4170433e-01 -2.8965531e+00 7.8422673e+00 - -7.8287324e-01 -2.7692634e+00 7.8512445e+00 - -6.6193674e-01 -2.5077726e+00 7.5076922e+00 - -6.3928251e-01 -2.4582960e+00 7.7032562e+00 - -5.8492892e-01 -2.3387647e+00 7.7121430e+00 - -3.9798901e-01 -1.9368509e+00 6.8634425e+00 - -5.2377770e-01 -2.2076760e+00 8.0627401e+00 - -4.9075658e-01 -2.1347951e+00 8.2372611e+00 - -4.1404009e-01 -1.9689319e+00 8.0955417e+00 - -4.4596403e-01 -2.0386322e+00 8.8339832e+00 - -3.0672427e-01 -1.7381083e+00 8.1476723e+00 - -2.5246645e-01 -1.6203739e+00 8.1606533e+00 - -1.9262484e-01 -1.4899514e+00 8.1127998e+00 - -1.0194082e-01 -1.2947751e+00 7.7100281e+00 - -7.6592772e-02 -1.2403614e+00 8.0283837e+00 - -6.6302703e-02 -1.2164536e+00 8.6026507e+00 - 1.7486775e-02 -1.0364027e+00 8.2100793e+00 - 6.8485156e-02 -9.2421423e-01 8.2487854e+00 - 1.6777083e-01 -7.1148803e-01 7.3821239e+00 - 1.7890097e-01 -6.8654021e-01 8.2003353e+00 - 2.6018329e-01 -5.1281436e-01 7.4554564e+00 - 3.0851289e-01 -4.0794151e-01 7.4244534e+00 - 3.5285121e-01 -3.0952048e-01 7.5211504e+00 - 4.0116127e-01 -2.0686676e-01 7.5262013e+00 - 4.4932547e-01 -1.0125282e-01 7.4291814e+00 - -3.9077849e-01 -1.7866130e+00 -9.6275661e-01 - -4.1925658e-01 -1.8436905e+00 -9.5505948e-01 - -4.5112500e-01 -1.9068443e+00 -9.5264861e-01 - -4.7612355e-01 -1.9566170e+00 -9.3502058e-01 - -5.1488691e-01 -2.0338680e+00 -9.4208436e-01 - -5.4684062e-01 -2.0987349e+00 -9.3388142e-01 - -5.8569606e-01 -2.1777531e+00 -9.3625178e-01 - -6.2559448e-01 -2.2575847e+00 -9.3607248e-01 - -6.6202260e-01 -2.3301855e+00 -9.2746043e-01 - -7.0991792e-01 -2.4259147e+00 -9.3395684e-01 - -7.5434110e-01 -2.5143983e+00 -9.3172085e-01 - -8.0231924e-01 -2.6118209e+00 -9.3202568e-01 - -8.5127644e-01 -2.7090303e+00 -9.2923115e-01 - -9.0033435e-01 -2.8080760e+00 -9.2314147e-01 - -9.5282185e-01 -2.9140274e+00 -9.1889270e-01 - -1.0223788e+00 -3.0528485e+00 -9.3073913e-01 - -1.0919664e+00 -3.1924301e+00 -9.3774193e-01 - -1.1386048e+00 -3.2856364e+00 -9.1213078e-01 - -1.1932954e+00 -3.3956979e+00 -8.9234677e-01 - -1.2684844e+00 -3.5455299e+00 -8.9039899e-01 - -1.3356948e+00 -3.6801262e+00 -8.7493435e-01 - -1.4110016e+00 -3.8324465e+00 -8.6265050e-01 - -1.4953378e+00 -4.0013941e+00 -8.5279480e-01 - -1.5796966e+00 -4.1710380e+00 -8.3679707e-01 - -1.6857547e+00 -4.3840744e+00 -8.3224185e-01 - -1.7882656e+00 -4.5887499e+00 -8.1660675e-01 - -1.8953479e+00 -4.8029660e+00 -7.9666812e-01 - -2.0196082e+00 -5.0524662e+00 -7.8099048e-01 - -2.1574761e+00 -5.3281883e+00 -7.6453611e-01 - -2.3080056e+00 -5.6311258e+00 -7.4596024e-01 - -2.4812299e+00 -5.9778896e+00 -7.2858672e-01 - -2.6716436e+00 -6.3605453e+00 -7.0753439e-01 - -2.8848430e+00 -6.7887849e+00 -6.8279124e-01 - -3.0990021e+00 -7.2171726e+00 -6.4201509e-01 - -3.3303180e+00 -7.6811912e+00 -5.9226666e-01 - -3.6369590e+00 -8.2966446e+00 -5.5280574e-01 - -3.7413600e+00 -8.5055080e+00 -4.2191050e-01 - -3.7520720e+00 -8.5256959e+00 -2.5584503e-01 - -3.8451330e+00 -8.7134789e+00 -1.1084088e-01 - -3.8045421e+00 -8.6317233e+00 6.9803804e-02 - -3.7263341e+00 -8.4748720e+00 2.5312009e-01 - -3.7142266e+00 -8.4492051e+00 4.2098796e-01 - -3.6863283e+00 -8.3943971e+00 5.8892284e-01 - -3.6800806e+00 -8.3825923e+00 7.5330548e-01 - -3.6634606e+00 -8.3483720e+00 9.1711912e-01 - -7.9524025e+00 -1.6948146e+01 1.1621514e+00 - -7.9454939e+00 -1.6934154e+01 1.4924269e+00 - -7.8291488e+00 -1.6700629e+01 1.8116982e+00 - -7.7458916e+00 -1.6533514e+01 2.1269404e+00 - -7.9942421e+00 -1.7030854e+01 2.4946277e+00 - -8.0123894e+00 -1.7067094e+01 2.8332426e+00 - -7.9918615e+00 -1.7026786e+01 3.1646390e+00 - -7.9917479e+00 -1.7026094e+01 3.5016198e+00 - -7.9892712e+00 -1.7019496e+01 3.8391958e+00 - -7.9834939e+00 -1.7008056e+01 4.1773136e+00 - -7.9708287e+00 -1.6982058e+01 4.5139699e+00 - -7.9593914e+00 -1.6959899e+01 4.8526254e+00 - -7.9455940e+00 -1.6931859e+01 5.1913767e+00 - -7.9375443e+00 -1.6916271e+01 5.5349829e+00 - -7.9271315e+00 -1.6894778e+01 5.8791843e+00 - -7.8882279e+00 -1.6815589e+01 6.2079485e+00 - -7.8766780e+00 -1.6792014e+01 6.5550440e+00 - -7.8151137e+00 -1.6668756e+01 6.8696799e+00 - -7.7422339e+00 -1.6523581e+01 7.1748546e+00 - -7.8533594e+00 -1.6744363e+01 7.6228696e+00 - -7.8213250e+00 -1.6680098e+01 7.9659291e+00 - -7.8904583e+00 -1.6818843e+01 8.4001264e+00 - -7.8811095e+00 -1.6799878e+01 8.7728942e+00 - -7.8773583e+00 -1.6791133e+01 9.1552118e+00 - -7.8646670e+00 -1.6766990e+01 9.5353129e+00 - -7.8575089e+00 -1.6752036e+01 9.9256134e+00 - -7.8434690e+00 -1.6722575e+01 1.0313454e+01 - -7.8214926e+00 -1.6677698e+01 1.0698182e+01 - -7.7677726e+00 -1.6570149e+01 1.1050487e+01 - -7.7117600e+00 -1.6457775e+01 1.1401738e+01 - -7.6874786e+00 -1.6408490e+01 1.1797248e+01 - -7.5940724e+00 -1.6222290e+01 1.2105178e+01 - -7.6230766e+00 -1.6279875e+01 1.2586388e+01 - -7.5249109e+00 -1.6081085e+01 1.2891064e+01 - -7.3498486e+00 -1.5731280e+01 1.3078382e+01 - -7.7165474e+00 -1.6464787e+01 1.4120667e+01 - -7.5878456e+00 -1.6206999e+01 1.4398215e+01 - -2.6963734e+00 -6.4012929e+00 8.0289011e+00 - -2.6378455e+00 -6.2846779e+00 8.1456390e+00 - -2.5782138e+00 -6.1662477e+00 8.2598775e+00 - -2.5422216e+00 -6.0937354e+00 8.4305936e+00 - -1.9875199e+00 -4.9802485e+00 7.2903089e+00 - -2.4893236e+00 -5.9857499e+00 8.8310413e+00 - -2.3313867e+00 -5.6695633e+00 8.6844090e+00 - -1.5584551e+00 -4.1222349e+00 6.7905752e+00 - -1.6299107e+00 -4.2655268e+00 7.2111941e+00 - -1.5262944e+00 -4.0554125e+00 7.1246968e+00 - -1.4804472e+00 -3.9646182e+00 7.2110475e+00 - -1.3105373e+00 -3.6236248e+00 6.8919065e+00 - -1.2027057e+00 -3.4073318e+00 6.7532145e+00 - -1.1310297e+00 -3.2645565e+00 6.7261050e+00 - -1.0694820e+00 -3.1417315e+00 6.7292782e+00 - -1.0000286e+00 -3.0021908e+00 6.6949328e+00 - -8.2824667e-01 -2.6566383e+00 6.2477978e+00 - -8.1060675e-01 -2.6212728e+00 6.3955289e+00 - -7.7838117e-01 -2.5573279e+00 6.4901966e+00 - -7.9323468e-01 -2.5872312e+00 6.7988421e+00 - -7.4749398e-01 -2.4962561e+00 6.8483390e+00 - -9.0221378e-01 -2.8058171e+00 7.8789153e+00 - -7.6448573e-01 -2.5299662e+00 7.5016103e+00 - -5.6198988e-01 -2.1232651e+00 6.7277704e+00 - -7.0053812e-01 -2.4001261e+00 7.8103000e+00 - -6.6468095e-01 -2.3286927e+00 7.9591431e+00 - -6.4652481e-01 -2.2912651e+00 8.2297210e+00 - -5.3707141e-01 -2.0724131e+00 7.9224850e+00 - -5.0330575e-01 -2.0041981e+00 8.1049411e+00 - -4.2739493e-01 -1.8530249e+00 7.9895829e+00 - -3.9240729e-01 -1.7815346e+00 8.1788785e+00 - -3.3084949e-01 -1.6575976e+00 8.1640747e+00 - -2.7938548e-01 -1.5564298e+00 8.2439717e+00 - -1.6950517e-01 -1.3365302e+00 7.7363343e+00 - -1.0376824e-01 -1.2041246e+00 7.6144554e+00 - -1.2551399e-01 -1.2469860e+00 8.5218203e+00 - -8.6852636e-02 -1.1697336e+00 8.8113330e+00 - -9.7641734e-02 -1.1901510e+00 9.9010495e+00 - 7.1894685e-02 -8.4973515e-01 8.2176566e+00 - 1.2886008e-01 -7.3705355e-01 8.2331730e+00 - 1.9743025e-01 -5.9889760e-01 7.9478918e+00 - 2.6871529e-01 -4.5593722e-01 7.4800320e+00 - 3.1892077e-01 -3.5627385e-01 7.5079467e+00 - 3.5091881e-01 -2.9066588e-01 8.4430705e+00 - 4.2047171e-01 -1.5277975e-01 7.5279197e+00 - 4.7336071e-01 -4.7316048e-02 7.0299835e+00 - -4.2517482e-01 -1.7261624e+00 -9.5881792e-01 - -4.5453679e-01 -1.7812348e+00 -9.5221548e-01 - -4.8734871e-01 -1.8433756e+00 -9.5074988e-01 - -5.2120729e-01 -1.9063592e+00 -9.4733388e-01 - -5.5505478e-01 -1.9692541e+00 -9.4212011e-01 - -5.9574624e-01 -2.0453232e+00 -9.4792868e-01 - -6.3408417e-01 -2.1160801e+00 -9.4490259e-01 - -6.7147060e-01 -2.1877860e+00 -9.3963283e-01 - -7.1429466e-01 -2.2663703e+00 -9.3809528e-01 - -7.5616597e-01 -2.3458938e+00 -9.3411431e-01 - -8.0353145e-01 -2.4332631e+00 -9.3321674e-01 - -8.5439290e-01 -2.5285844e+00 -9.3510928e-01 - -9.0178284e-01 -2.6166649e+00 -9.2836930e-01 - -9.5717584e-01 -2.7206923e+00 -9.2930379e-01 - -1.0136050e+00 -2.8254788e+00 -9.2659000e-01 - -1.0700735e+00 -2.9310948e+00 -9.2043084e-01 - -1.1515033e+00 -3.0836074e+00 -9.3963861e-01 - -1.2135462e+00 -3.1987429e+00 -9.2997176e-01 - -1.2631084e+00 -3.2906872e+00 -9.0270272e-01 - -1.3376793e+00 -3.4304215e+00 -8.9865364e-01 - -1.4087748e+00 -3.5628856e+00 -8.8537279e-01 - -1.4844045e+00 -3.7040755e+00 -8.7153340e-01 - -1.5690659e+00 -3.8619123e+00 -8.6052167e-01 - -1.6583124e+00 -4.0293981e+00 -8.4740369e-01 - -1.7655790e+00 -4.2293138e+00 -8.4268724e-01 - -1.8694207e+00 -4.4228772e+00 -8.2709144e-01 - -1.9823336e+00 -4.6339171e+00 -8.1087794e-01 - -2.1088080e+00 -4.8702953e+00 -7.9623442e-01 - -2.2453971e+00 -5.1249680e+00 -7.7852343e-01 - -2.4001451e+00 -5.4147266e+00 -7.6227370e-01 - -2.5739770e+00 -5.7384100e+00 -7.4543421e-01 - -2.7670015e+00 -6.0979186e+00 -7.2600818e-01 - -2.9827581e+00 -6.5020682e+00 -7.0403953e-01 - -3.2176188e+00 -6.9408195e+00 -6.7493957e-01 - -3.4443962e+00 -7.3629834e+00 -6.2518118e-01 - -3.7176129e+00 -7.8736676e+00 -5.7637650e-01 - -4.0754908e+00 -8.5411554e+00 -5.3613514e-01 - -4.4706364e+00 -9.2788842e+00 -4.8118528e-01 - -4.9459838e+00 -1.0166834e+01 -4.1802985e-01 - -5.4358079e+00 -1.1080430e+01 -3.2338281e-01 - -6.0476990e+00 -1.2223721e+01 -2.1555047e-01 - -6.2174133e+00 -1.2539643e+01 2.8298145e-03 - -6.4368187e+00 -1.2948538e+01 2.2760492e-01 - -6.8992345e+00 -1.3813304e+01 4.5003487e-01 - -7.9510822e+00 -1.5776323e+01 6.8452161e-01 - -8.1746664e+00 -1.6192654e+01 9.9679672e-01 - -8.3949130e+00 -1.6604360e+01 1.3254436e+00 - -8.1271692e+00 -1.6103630e+01 1.6348048e+00 - -8.0210599e+00 -1.5906172e+01 1.9425019e+00 - -7.9938754e+00 -1.5854188e+01 2.2545581e+00 - -8.2592114e+00 -1.6350634e+01 2.6196028e+00 - -8.2636327e+00 -1.6358158e+01 2.9472048e+00 - -8.1902155e+00 -1.6220852e+01 3.2561686e+00 - -8.6798564e+00 -1.7134746e+01 3.7284950e+00 - -8.6797433e+00 -1.7134573e+01 4.0752134e+00 - -8.6716807e+00 -1.7118881e+01 4.4209170e+00 - -8.6703684e+00 -1.7115614e+01 4.7707795e+00 - -8.4571539e+00 -1.6718498e+01 5.0280174e+00 - -8.6396209e+00 -1.7057936e+01 5.4641034e+00 - -8.6473137e+00 -1.7071619e+01 5.8252704e+00 - -8.2278098e+00 -1.6288417e+01 5.9479491e+00 - -8.0992500e+00 -1.6049084e+01 6.2172974e+00 - -8.0821816e+00 -1.6016438e+01 6.5517964e+00 - -8.0042547e+00 -1.5870084e+01 6.8464689e+00 - -7.9500394e+00 -1.5768677e+01 7.1565211e+00 - -8.0445536e+00 -1.5945509e+01 7.5806389e+00 - -8.0196181e+00 -1.5899033e+01 7.9204145e+00 - -8.3121288e+00 -1.6443689e+01 8.5337081e+00 - -8.3006718e+00 -1.6422920e+01 8.9049721e+00 - -8.2733690e+00 -1.6371538e+01 9.2656171e+00 - -8.2595726e+00 -1.6345569e+01 9.6434187e+00 - -8.2378988e+00 -1.6305173e+01 1.0018357e+01 - -8.2048405e+00 -1.6241795e+01 1.0385183e+01 - -8.8851084e+00 -1.7511511e+01 1.1559481e+01 - -8.2221869e+00 -1.6274943e+01 1.1230967e+01 - -7.9900592e+00 -1.5840625e+01 1.1371711e+01 - -7.8872870e+00 -1.5647787e+01 1.1663137e+01 - -7.8183087e+00 -1.5518962e+01 1.1997877e+01 - -7.8055257e+00 -1.5495118e+01 1.2412435e+01 - -7.7568260e+00 -1.5405338e+01 1.2784571e+01 - -7.5742044e+00 -1.5062516e+01 1.2961673e+01 - -7.9252838e+00 -1.5717322e+01 1.3951519e+01 - -7.8325684e+00 -1.5543862e+01 1.4284813e+01 - -2.9171826e+00 -6.3723271e+00 7.9800752e+00 - -2.8457099e+00 -6.2394285e+00 8.0769064e+00 - -2.9034759e+00 -6.3458726e+00 9.5784588e+00 - -2.4245877e+00 -5.4525779e+00 8.6382364e+00 - -2.4370024e+00 -5.4754560e+00 8.9499245e+00 - -2.2626744e+00 -5.1506872e+00 8.7537073e+00 - -2.3622580e+00 -5.3366126e+00 9.3317943e+00 - -2.3643827e+00 -5.3387637e+00 9.6492048e+00 - -1.4095073e+00 -3.5588530e+00 6.9850404e+00 - -1.2545670e+00 -3.2688907e+00 6.7107612e+00 - -1.1946310e+00 -3.1570967e+00 6.7322104e+00 - -1.1157440e+00 -3.0098615e+00 6.6825088e+00 - -1.0113044e+00 -2.8159471e+00 6.5334274e+00 - -8.8792964e-01 -2.5856864e+00 6.2910235e+00 - -8.9935435e-01 -2.6066274e+00 6.5621600e+00 - -8.4729703e-01 -2.5092710e+00 6.5862723e+00 - -8.4419777e-01 -2.5036727e+00 6.8237703e+00 - -7.9210037e-01 -2.4059960e+00 6.8543746e+00 - -9.6322287e-01 -2.7247469e+00 7.9424757e+00 - -7.0240306e-01 -2.2385176e+00 6.9829290e+00 - -6.1039961e-01 -2.0664065e+00 6.8038614e+00 - -7.8316235e-01 -2.3878641e+00 8.0575102e+00 - -5.2190209e-01 -1.9020261e+00 6.9291718e+00 - -6.0244059e-01 -2.0514563e+00 7.7601553e+00 - -5.7564307e-01 -2.0015335e+00 7.9899139e+00 - -4.9697535e-01 -1.8550190e+00 7.8850812e+00 - -5.7667582e-01 -2.0013626e+00 8.9204596e+00 - -4.0787283e-01 -1.6878668e+00 8.1476206e+00 - -3.7202083e-01 -1.6206007e+00 8.3740648e+00 - -2.3440890e-01 -1.3643302e+00 7.7035636e+00 - -1.6914964e-01 -1.2424463e+00 7.6317679e+00 - -1.6694260e-01 -1.2371873e+00 8.2246264e+00 - -1.4059006e-01 -1.1879409e+00 8.6420525e+00 - -1.4509926e-01 -1.1950501e+00 9.5631667e+00 - -7.2847256e-02 -1.0608662e+00 9.5657135e+00 - 7.6998607e-02 -7.8294720e-01 8.2356568e+00 - 1.3900500e-01 -6.6758825e-01 8.2102598e+00 - 2.3108281e-01 -4.9600044e-01 7.4354828e+00 - 2.8932097e-01 -3.8664319e-01 7.2847501e+00 - 3.4027592e-01 -2.9160627e-01 7.3213990e+00 - 3.8855359e-01 -2.0262059e-01 7.5761314e+00 - 4.4265025e-01 -9.9884075e-02 7.5091538e+00 - -5.2597075e-01 -1.7860928e+00 -9.5513934e-01 - -5.5731303e-01 -1.8409163e+00 -9.4593375e-01 - -5.9310218e-01 -1.9027377e+00 -9.4166206e-01 - -6.3233819e-01 -1.9716028e+00 -9.4202781e-01 - -6.7156125e-01 -2.0403644e+00 -9.4029616e-01 - -7.1182913e-01 -2.1099542e+00 -9.3631448e-01 - -7.6005342e-01 -2.1946023e+00 -9.4225411e-01 - -8.0480558e-01 -2.2720047e+00 -9.3946135e-01 - -8.5405435e-01 -2.3573183e+00 -9.3985503e-01 - -9.0334669e-01 -2.4434959e+00 -9.3750250e-01 - -9.5713133e-01 -2.5375501e+00 -9.3763727e-01 - -1.0119559e+00 -2.6323931e+00 -9.3472301e-01 - -1.0668202e+00 -2.7280705e+00 -9.2846327e-01 - -1.1430867e+00 -2.8616709e+00 -9.4433051e-01 - -1.2079191e+00 -2.9729229e+00 -9.4064516e-01 - -1.2853082e+00 -3.1090054e+00 -9.4727180e-01 - -1.3288022e+00 -3.1838751e+00 -9.1217173e-01 - -1.4027536e+00 -3.3135019e+00 -9.0582160e-01 - -1.4777350e+00 -3.4438387e+00 -8.9482442e-01 - -1.5571902e+00 -3.5819043e+00 -8.8331824e-01 - -1.6422353e+00 -3.7296126e+00 -8.7080129e-01 - -1.7407486e+00 -3.9008821e+00 -8.6434798e-01 - -1.8403424e+00 -4.0737796e+00 -8.5160005e-01 - -1.9445156e+00 -4.2562816e+00 -8.3584698e-01 - -2.0676960e+00 -4.4710644e+00 -8.2669448e-01 - -2.1919457e+00 -4.6873866e+00 -8.0944957e-01 - -2.3307507e+00 -4.9289521e+00 -7.9307233e-01 - -2.4896551e+00 -5.2045200e+00 -7.7889867e-01 - -2.6576625e+00 -5.4983346e+00 -7.5946344e-01 - -2.8557912e+00 -5.8426739e+00 -7.4375788e-01 - -3.0741014e+00 -6.2227041e+00 -7.2396447e-01 - -3.1857600e+00 -6.4165005e+00 -6.4182693e-01 - -3.0137347e+00 -6.1177836e+00 -4.3665143e-01 - -2.9919315e+00 -6.0792337e+00 -3.0051719e-01 - -2.9488348e+00 -6.0036279e+00 -1.5983427e-01 - -2.9337944e+00 -5.9770877e+00 -3.1376115e-02 - -2.9267349e+00 -5.9663171e+00 9.3003130e-02 - -2.9094721e+00 -5.9360283e+00 2.1885968e-01 - -2.9212932e+00 -5.9554952e+00 3.3753802e-01 - -2.9557016e+00 -6.0168981e+00 4.5281750e-01 - -2.9607317e+00 -6.0236147e+00 5.7392880e-01 - -2.9838605e+00 -6.0644200e+00 6.9352928e-01 - -2.9262487e+00 -5.9633769e+00 8.1875041e-01 - -2.9269900e+00 -5.9653899e+00 9.3880223e-01 - -8.2358540e+00 -1.5209392e+01 1.1498201e+00 - -8.2235022e+00 -1.5186931e+01 1.4553141e+00 - -8.2134508e+00 -1.5169357e+01 1.7605628e+00 - -8.1205805e+00 -1.5007854e+01 2.0552969e+00 - -8.3936825e+00 -1.5482680e+01 2.4019016e+00 - -8.4048900e+00 -1.5502401e+01 2.7180322e+00 - -8.3881435e+00 -1.5473874e+01 3.0298081e+00 - -8.3645729e+00 -1.5431817e+01 3.3395727e+00 - -8.3824594e+00 -1.5462878e+01 3.6616105e+00 - -8.3824562e+00 -1.5463067e+01 3.9807134e+00 - -8.3700986e+00 -1.5441075e+01 4.2969438e+00 - -8.3453934e+00 -1.5396956e+01 4.6092030e+00 - -8.3364905e+00 -1.5382586e+01 4.9293349e+00 - -8.3252853e+00 -1.5363313e+01 5.2500118e+00 - -8.3207620e+00 -1.5355404e+01 5.5760965e+00 - -8.3038937e+00 -1.5325387e+01 5.8978105e+00 - -8.2792074e+00 -1.5281935e+01 6.2168109e+00 - -8.2756951e+00 -1.5274583e+01 6.5506388e+00 - -8.1839861e+00 -1.5114839e+01 6.8287463e+00 - -8.1783385e+00 -1.5105466e+01 7.1654650e+00 - -8.2452080e+00 -1.5221264e+01 7.5595684e+00 - -8.2104198e+00 -1.5160135e+01 7.8832415e+00 - -8.2594309e+00 -1.5245828e+01 8.2791538e+00 - -8.2681316e+00 -1.5260043e+01 8.6485634e+00 - -8.2411775e+00 -1.5213511e+01 8.9919282e+00 - -8.2242150e+00 -1.5183774e+01 9.3484984e+00 - -8.1949874e+00 -1.5133084e+01 9.6975514e+00 - -8.1623394e+00 -1.5075562e+01 1.0046947e+01 - -8.1352873e+00 -1.5028247e+01 1.0406192e+01 - -8.1215990e+00 -1.5004174e+01 1.0786090e+01 - -8.1089272e+00 -1.4980703e+01 1.1172833e+01 - -8.0863835e+00 -1.4942939e+01 1.1556407e+01 - -8.0401897e+00 -1.4860721e+01 1.1914613e+01 - -8.0019107e+00 -1.4794260e+01 1.2289265e+01 - -7.9891855e+00 -1.4771394e+01 1.2704272e+01 - -7.8048862e+00 -1.4450622e+01 1.2883753e+01 - -8.1173902e+00 -1.4993490e+01 1.3791245e+01 - -8.0600805e+00 -1.4894561e+01 1.4176292e+01 - -2.7248169e+00 -5.6092316e+00 8.5725243e+00 - -2.5738323e+00 -5.3443035e+00 8.4759220e+00 - -2.5640175e+00 -5.3275890e+00 8.7232430e+00 - -2.4842742e+00 -5.1892840e+00 8.7976292e+00 - -2.5675001e+00 -5.3332848e+00 9.3107698e+00 - -1.7271499e+00 -3.8720661e+00 7.2597688e+00 - -1.6220793e+00 -3.6883661e+00 7.1884827e+00 - -1.1880821e+00 -2.9335816e+00 6.1111920e+00 - -1.1220434e+00 -2.8186633e+00 6.1020118e+00 - -1.3372280e+00 -3.1938303e+00 7.0105426e+00 - -1.1991339e+00 -2.9527892e+00 6.7809325e+00 - -1.0524018e+00 -2.6987635e+00 6.5001664e+00 - -1.2405116e+00 -3.0246714e+00 7.4236218e+00 - -9.1476889e-01 -2.4580127e+00 6.4457897e+00 - -8.5430037e-01 -2.3525794e+00 6.4408163e+00 - -8.6224494e-01 -2.3662108e+00 6.7219837e+00 - -8.3271780e-01 -2.3160073e+00 6.8597982e+00 - -8.2171473e-01 -2.2952552e+00 7.0888906e+00 - -7.2052636e-01 -2.1200157e+00 6.9032041e+00 - -6.7108545e-01 -2.0341981e+00 6.9543343e+00 - -5.8090762e-01 -1.8763749e+00 6.7882981e+00 - -7.1036856e-01 -2.1009898e+00 7.8432636e+00 - -6.4101226e-01 -1.9805766e+00 7.8275842e+00 - -5.8481349e-01 -1.8827888e+00 7.8855915e+00 - -5.4170793e-01 -1.8076281e+00 8.0375102e+00 - -5.5752145e-01 -1.8353180e+00 8.6317048e+00 - -5.1523756e-01 -1.7607494e+00 8.8514413e+00 - -3.0330921e-01 -1.3929512e+00 7.6897815e+00 - -2.4388327e-01 -1.2893595e+00 7.7070327e+00 - -1.8341147e-01 -1.1844156e+00 7.7123962e+00 - -2.1126461e-01 -1.2309550e+00 8.6594289e+00 - -2.5248213e-01 -1.3025032e+00 9.9750306e+00 - -1.3235858e-01 -1.0943121e+00 9.4460806e+00 - 2.3377573e-02 -8.2373343e-01 8.2176747e+00 - 8.8324214e-02 -7.0898939e-01 8.1834790e+00 - 1.4474367e-01 -6.1253245e-01 8.3360671e+00 - 2.3944275e-01 -4.4668719e-01 7.5498428e+00 - 3.0154861e-01 -3.4063333e-01 7.4180724e+00 - 3.5654906e-01 -2.4335305e-01 7.4240480e+00 - 4.1166580e-01 -1.4772214e-01 7.4978877e+00 - 4.7185172e-01 -4.4117335e-02 6.8099639e+00 - -6.3940791e-01 -1.8557552e+00 -9.6081490e-01 - -6.7272864e-01 -1.9103148e+00 -9.4870653e-01 - -7.1389336e-01 -1.9780030e+00 -9.4791695e-01 - -7.5610290e-01 -2.0465192e+00 -9.4487736e-01 - -7.9829888e-01 -2.1149270e+00 -9.3964048e-01 - -8.4944883e-01 -2.1983279e+00 -9.4422185e-01 - -8.9612847e-01 -2.2745434e+00 -9.4007400e-01 - -9.4836310e-01 -2.3596067e+00 -9.3905987e-01 - -1.0050310e+00 -2.4515597e+00 -9.4078235e-01 - -1.0572895e+00 -2.5373292e+00 -9.3382595e-01 - -1.1150385e+00 -2.6309151e+00 -9.2935368e-01 - -1.1817235e+00 -2.7393510e+00 -9.3180322e-01 - -1.2528934e+00 -2.8556045e+00 -9.3554156e-01 - -1.3351069e+00 -2.9885072e+00 -9.4459810e-01 - -1.4119079e+00 -3.1152476e+00 -9.4417993e-01 - -1.4628297e+00 -3.1968255e+00 -9.1180693e-01 - -1.5406385e+00 -3.3240984e+00 -9.0314615e-01 - -1.6194767e+00 -3.4520762e+00 -8.8973843e-01 - -1.7128508e+00 -3.6046257e+00 -8.8383978e-01 - -1.8017496e+00 -3.7499505e+00 -8.6841291e-01 - -1.9106115e+00 -3.9266415e+00 -8.6252940e-01 - -2.0250504e+00 -4.1128718e+00 -8.5353770e-01 - -2.1350085e+00 -4.2918330e+00 -8.3411889e-01 - -2.2650297e+00 -4.5039919e+00 -8.2084842e-01 - -2.4106058e+00 -4.7413435e+00 -8.0864218e-01 - -2.5672332e+00 -4.9959224e+00 -7.9321508e-01 - -2.7338463e+00 -5.2667332e+00 -7.7342134e-01 - -2.9316465e+00 -5.5890643e+00 -7.5850307e-01 - -3.1450223e+00 -5.9372699e+00 -7.3820737e-01 - -3.3894929e+00 -6.3357427e+00 -7.1764310e-01 - -3.6450239e+00 -6.7520309e+00 -6.8551867e-01 - -3.2026566e+00 -6.0311865e+00 -3.7697948e-01 - -3.1431494e+00 -5.9331338e+00 -2.2889451e-01 - -3.1226781e+00 -5.8997694e+00 -9.7802801e-02 - -3.1212184e+00 -5.8987202e+00 2.5989196e-02 - -3.1140975e+00 -5.8869428e+00 1.5051865e-01 - -3.1013177e+00 -5.8644567e+00 2.7538604e-01 - -3.1432651e+00 -5.9344879e+00 3.8953570e-01 - -3.1016086e+00 -5.8654488e+00 5.1743525e-01 - -3.1468417e+00 -5.9402046e+00 6.3344022e-01 - -7.5522725e+00 -1.3116381e+01 4.5963731e-01 - -8.3305173e+00 -1.4383358e+01 7.0215504e-01 - -8.6974116e+00 -1.4981498e+01 9.9654891e-01 - -8.9429692e+00 -1.5380320e+01 1.3115002e+00 - -8.4463450e+00 -1.4572779e+01 1.5938012e+00 - -8.3774190e+00 -1.4459113e+01 1.8858364e+00 - -8.3318810e+00 -1.4384199e+01 2.1770240e+00 - -8.6319050e+00 -1.4873454e+01 2.5235053e+00 - -8.6375024e+00 -1.4882856e+01 2.8320836e+00 - -8.5785718e+00 -1.4785500e+01 3.1268875e+00 - -8.7962548e+00 -1.5140319e+01 3.4932624e+00 - -8.7973807e+00 -1.5142525e+01 3.8107697e+00 - -8.7917360e+00 -1.5132144e+01 4.1274139e+00 - -8.7817938e+00 -1.5116990e+01 4.4443970e+00 - -8.7694897e+00 -1.5095941e+01 4.7617756e+00 - -8.7284560e+00 -1.5030030e+01 5.0681533e+00 - -8.7671131e+00 -1.5090874e+01 5.4115127e+00 - -8.7504285e+00 -1.5063873e+01 5.7328759e+00 - -8.5551091e+00 -1.4745508e+01 5.9580645e+00 - -8.4630270e+00 -1.4595976e+01 6.2329688e+00 - -8.4440726e+00 -1.4564333e+01 6.5495835e+00 - -8.3530102e+00 -1.4414913e+01 6.8209953e+00 - -8.3574437e+00 -1.4423050e+01 7.1564373e+00 - -8.4171981e+00 -1.4519897e+01 7.5368463e+00 - -8.3904331e+00 -1.4475392e+01 7.8593864e+00 - -8.7206787e+00 -1.5014641e+01 8.4750492e+00 - -8.7093210e+00 -1.4994665e+01 8.8302331e+00 - -8.6980497e+00 -1.4976412e+01 9.1910093e+00 - -8.6823520e+00 -1.4951323e+01 9.5534235e+00 - -8.6732434e+00 -1.4936341e+01 9.9264893e+00 - -8.6551989e+00 -1.4905994e+01 1.0296639e+01 - -8.6238948e+00 -1.4854785e+01 1.0658670e+01 - -8.5748917e+00 -1.4775260e+01 1.1006479e+01 - -8.4107091e+00 -1.4507497e+01 1.1225144e+01 - -8.2321227e+00 -1.4215702e+01 1.1420108e+01 - -8.2185349e+00 -1.4193979e+01 1.1813139e+01 - -8.1539491e+00 -1.4088007e+01 1.2146931e+01 - -8.1711829e+00 -1.4114883e+01 1.2594313e+01 - -8.0082880e+00 -1.3851436e+01 1.2805290e+01 - -7.8408169e+00 -1.3577895e+01 1.3002925e+01 - -8.2538781e+00 -1.4250647e+01 1.4060921e+01 - -8.1007588e+00 -1.4001238e+01 1.4300485e+01 - -2.8113935e+00 -5.3886488e+00 8.0215109e+00 - -2.6815005e+00 -5.1775147e+00 7.9874661e+00 - -2.7962903e+00 -5.3628533e+00 8.4983350e+00 - -2.7633601e+00 -5.3090506e+00 8.6925208e+00 - -2.6830437e+00 -5.1783285e+00 8.7764888e+00 - -2.5576079e+00 -4.9747903e+00 8.7456497e+00 - -1.9014359e+00 -3.9072119e+00 7.3095362e+00 - -1.7992212e+00 -3.7390287e+00 7.2656660e+00 - -1.6708161e+00 -3.5312319e+00 7.1424848e+00 - -1.6347428e+00 -3.4717812e+00 7.2724938e+00 - -1.2161071e+00 -2.7910576e+00 6.2404024e+00 - -1.4625470e+00 -3.1903537e+00 7.2309157e+00 - -1.4232672e+00 -3.1273282e+00 7.3560227e+00 - -1.0325602e+00 -2.4915557e+00 6.2735560e+00 - -9.8673120e-01 -2.4161637e+00 6.3325319e+00 - -9.5194911e-01 -2.3600260e+00 6.4346777e+00 - -9.2041802e-01 -2.3088511e+00 6.5541093e+00 - -8.8446923e-01 -2.2503956e+00 6.6639432e+00 - -8.2876391e-01 -2.1591297e+00 6.6910368e+00 - -8.2343875e-01 -2.1507863e+00 6.9461075e+00 - -6.2564578e-01 -1.8291146e+00 6.3124586e+00 - -6.6727181e-01 -1.8967929e+00 6.7972475e+00 - -6.6284022e-01 -1.8885847e+00 7.0888755e+00 - -7.3679113e-01 -2.0080222e+00 7.8451485e+00 - -6.7553165e-01 -1.9089467e+00 7.8948510e+00 - -5.9896394e-01 -1.7835545e+00 7.8468420e+00 - -7.3306105e-01 -2.0006062e+00 9.1896185e+00 - -5.2191813e-01 -1.6581668e+00 8.2635034e+00 - -3.9345724e-01 -1.4491935e+00 7.8209700e+00 - -3.1172149e-01 -1.3170144e+00 7.6937971e+00 - -2.4183539e-01 -1.2024674e+00 7.6414583e+00 - -2.4286436e-01 -1.2025670e+00 8.2638372e+00 - -2.2540071e-01 -1.1750139e+00 8.8192571e+00 - -1.8715705e-01 -1.1114141e+00 9.2372034e+00 - -1.2533389e-01 -1.0114444e+00 9.4468556e+00 - 3.2533360e-02 -7.5516699e-01 8.2158379e+00 - 9.9230913e-02 -6.4714667e-01 8.2301224e+00 - 2.0098806e-01 -4.8115799e-01 7.4553617e+00 - 2.7311967e-01 -3.6349431e-01 7.1051881e+00 - 3.2186052e-01 -2.8400161e-01 7.3712994e+00 - 3.7507249e-01 -1.9783291e-01 7.6560773e+00 - 4.3690704e-01 -9.7041475e-02 7.5391862e+00 - -7.4631137e-01 -1.9015285e+00 -9.4207757e-01 - -7.8940604e-01 -1.9680496e+00 -9.4033242e-01 - -8.3800042e-01 -2.0424607e+00 -9.4256955e-01 - -8.8657938e-01 -2.1167487e+00 -9.4230975e-01 - -9.3620132e-01 -2.1918501e+00 -9.3950032e-01 - -9.8580723e-01 -2.2668233e+00 -9.3409409e-01 - -1.0443609e+00 -2.3567402e+00 -9.3750733e-01 - -1.1039539e+00 -2.4474409e+00 -9.3777168e-01 - -1.1635874e+00 -2.5389809e+00 -9.3479041e-01 - -1.2287076e+00 -2.6383076e+00 -9.3369402e-01 - -1.3037608e+00 -2.7524141e+00 -9.3931651e-01 - -1.3799068e+00 -2.8682471e+00 -9.4064191e-01 - -1.4604731e+00 -2.9908663e+00 -9.4260651e-01 - -1.5277368e+00 -3.0933110e+00 -9.2612430e-01 - -1.5895352e+00 -3.1886557e+00 -9.0141545e-01 - -1.6811473e+00 -3.3284579e+00 -8.9926030e-01 - -1.7694035e+00 -3.4629738e+00 -8.8757453e-01 - -1.8621298e+00 -3.6051891e+00 -8.7478051e-01 - -1.9713200e+00 -3.7707941e+00 -8.6824034e-01 - -2.0805317e+00 -3.9370856e+00 -8.5535840e-01 - -2.1953209e+00 -4.1129213e+00 -8.3946815e-01 - -2.3310535e+00 -4.3199199e+00 -8.3022166e-01 - -2.4678547e+00 -4.5284529e+00 -8.1278288e-01 - -2.6257030e+00 -4.7700096e+00 -7.9919209e-01 - -2.7955377e+00 -5.0277118e+00 -7.8192743e-01 - -2.9754145e+00 -5.3026130e+00 -7.5964732e-01 - -3.1983917e+00 -5.6435655e+00 -7.4635841e-01 - -3.2951620e+00 -5.7900757e+00 -6.6344136e-01 - -3.2992277e+00 -5.7976378e+00 -5.3798900e-01 - -3.3938295e+00 -5.9418612e+00 -4.4678777e-01 - -4.2642211e+00 -7.2697074e+00 -6.1260671e-01 - -4.6515731e+00 -7.8613062e+00 -5.7472539e-01 - -5.0785267e+00 -8.5120128e+00 -5.2297072e-01 - -5.5806285e+00 -9.2791320e+00 -4.6280704e-01 - -6.1553455e+00 -1.0154370e+01 -3.8574808e-01 - -6.5113834e+00 -1.0698076e+01 -2.3417917e-01 - -6.6254682e+00 -1.0872408e+01 -2.5729826e-02 - -6.8532364e+00 -1.1219713e+01 1.7683503e-01 - -7.3967573e+00 -1.2049032e+01 3.6808018e-01 - -8.4590587e+00 -1.3670061e+01 5.6864061e-01 - -8.5937663e+00 -1.3874541e+01 8.5179457e-01 - -8.5662699e+00 -1.3832744e+01 1.1409224e+00 - -8.5520892e+00 -1.3812257e+01 1.4290811e+00 - -8.5366136e+00 -1.3786881e+01 1.7162897e+00 - -8.4738326e+00 -1.3691419e+01 1.9978468e+00 - -8.7244217e+00 -1.4074491e+01 2.3208630e+00 - -8.8148496e+00 -1.4211018e+01 2.6325313e+00 - -8.8028500e+00 -1.4193950e+01 2.9299833e+00 - -8.7179347e+00 -1.4063783e+01 3.2101924e+00 - -9.2163931e+00 -1.4823534e+01 3.6450327e+00 - -9.1998856e+00 -1.4798980e+01 3.9573064e+00 - -9.0090792e+00 -1.4507007e+01 4.2110583e+00 - -9.0002483e+00 -1.4493428e+01 4.8381082e+00 - -8.8933039e+00 -1.4329911e+01 5.1097279e+00 - -8.8887771e+00 -1.4321672e+01 5.7451778e+00 - -8.7157822e+00 -1.4057884e+01 5.9752990e+00 - -8.6244049e+00 -1.3919659e+01 6.2438569e+00 - -8.5945279e+00 -1.3872332e+01 6.5462139e+00 - -8.4469217e+00 -1.3647209e+01 6.7747946e+00 - -8.3026991e+00 -1.3428108e+01 6.9991877e+00 - -8.5757131e+00 -1.3844297e+01 7.5166136e+00 - -8.5579639e+00 -1.3816310e+01 7.8389229e+00 - -8.3399499e+00 -1.3484118e+01 8.0066194e+00 - -8.9000560e+00 -1.4338225e+01 8.8091420e+00 - -8.8888268e+00 -1.4320307e+01 9.1631266e+00 - -8.8776809e+00 -1.4304087e+01 9.5232029e+00 - -8.8586576e+00 -1.4273440e+01 9.8804162e+00 - -8.8298851e+00 -1.4230514e+01 1.0234160e+01 - -8.7690738e+00 -1.4136781e+01 1.0559268e+01 - -8.9645444e+00 -1.4435038e+01 1.1162312e+01 - -8.6090373e+00 -1.3892180e+01 1.1174690e+01 - -8.4272652e+00 -1.3613779e+01 1.1366390e+01 - -8.4039495e+00 -1.3579432e+01 1.1742718e+01 - -8.2914165e+00 -1.3406282e+01 1.2013127e+01 - -8.3229522e+00 -1.3454830e+01 1.2471278e+01 - -8.2291860e+00 -1.3312040e+01 1.2774039e+01 - -8.0331779e+00 -1.3011981e+01 1.2934445e+01 - -8.4116264e+00 -1.3589119e+01 1.3919928e+01 - -8.3155985e+00 -1.3443298e+01 1.4246054e+01 - -2.9462127e+00 -5.2532899e+00 8.0987686e+00 - -2.7929708e+00 -5.0184598e+00 8.0249633e+00 - -2.8195102e+00 -5.0595286e+00 8.3369351e+00 - -2.8098288e+00 -5.0449114e+00 8.5822578e+00 - -2.7540688e+00 -4.9588822e+00 8.7260530e+00 - -1.4191952e+00 -2.9247232e+00 5.7260054e+00 - -1.3616705e+00 -2.8365395e+00 5.7538405e+00 - -1.3369961e+00 -2.7991563e+00 5.8699898e+00 - -1.6992805e+00 -3.3513897e+00 7.0532900e+00 - -1.6120453e+00 -3.2169955e+00 7.0379119e+00 - -1.2639393e+00 -2.6877234e+00 6.2432098e+00 - -1.1966125e+00 -2.5852903e+00 6.2467524e+00 - -1.1793958e+00 -2.5574324e+00 6.4043682e+00 - -1.1218875e+00 -2.4698959e+00 6.4393441e+00 - -1.0491114e+00 -2.3589433e+00 6.4191041e+00 - -1.0264909e+00 -2.3244780e+00 6.5749589e+00 - -9.7768629e-01 -2.2499342e+00 6.6406665e+00 - -9.1910198e-01 -2.1608041e+00 6.6686486e+00 - -8.5392462e-01 -2.0605051e+00 6.6670033e+00 - -8.3557367e-01 -2.0326520e+00 6.8662637e+00 - -6.0542923e-01 -1.6830337e+00 6.1076844e+00 - -7.2378721e-01 -1.8623743e+00 6.9568971e+00 - -6.4999559e-01 -1.7497969e+00 6.9100380e+00 - -6.7697393e-01 -1.7909787e+00 7.4008386e+00 - -8.0107666e-01 -1.9793511e+00 8.5053466e+00 - -7.6592244e-01 -1.9259128e+00 8.7756305e+00 - -6.8424512e-01 -1.8009052e+00 8.7664568e+00 - -5.2292470e-01 -1.5552836e+00 8.1930539e+00 - -4.0062328e-01 -1.3687561e+00 7.8161453e+00 - -3.3320851e-01 -1.2651043e+00 7.8241329e+00 - -2.5410069e-01 -1.1450717e+00 7.7319177e+00 - -2.9671210e-01 -1.2104385e+00 8.8069268e+00 - -2.1090191e-01 -1.0788791e+00 8.7125998e+00 - -2.0035257e-01 -1.0616669e+00 9.4955525e+00 - -1.8071428e-01 -1.0314775e+00 1.0369021e+01 - 4.5677496e-02 -6.8687683e-01 8.2132892e+00 - 1.1418476e-01 -5.8253168e-01 8.2365548e+00 - 2.2049355e-01 -4.2138627e-01 7.4102410e+00 - 2.8728443e-01 -3.1962565e-01 7.2583283e+00 - 3.4498401e-01 -2.3107595e-01 7.3341035e+00 - 4.0398198e-01 -1.4173471e-01 7.4879278e+00 - 4.6897909e-01 -4.2446357e-02 6.8199115e+00 - -7.8252788e-01 -1.8374866e+00 -9.4881778e-01 - -8.2416648e-01 -1.8967987e+00 -9.4152993e-01 - -8.7018803e-01 -1.9620823e+00 -9.3862627e-01 - -9.2071113e-01 -2.0353164e+00 -9.3970806e-01 - -9.7667001e-01 -2.1154143e+00 -9.4422243e-01 - -1.0282194e+00 -2.1893288e+00 -9.4005791e-01 - -1.0797534e+00 -2.2631201e+00 -9.3339647e-01 - -1.1466809e+00 -2.3587520e+00 -9.4088156e-01 - -1.2037489e+00 -2.4412235e+00 -9.3395803e-01 - -1.2663068e+00 -2.5315064e+00 -9.2941875e-01 - -1.3342906e+00 -2.6285741e+00 -9.2671401e-01 - -1.4177121e+00 -2.7483511e+00 -9.3550946e-01 - -1.4976577e+00 -2.8608529e+00 -9.3497325e-01 - -1.5920926e+00 -2.9970377e+00 -9.4419295e-01 - -1.6523292e+00 -3.0832978e+00 -9.1643754e-01 - -1.7224325e+00 -3.1832914e+00 -8.9445180e-01 - -1.8135191e+00 -3.3147681e+00 -8.8560181e-01 - -1.9155148e+00 -3.4607869e+00 -8.7987196e-01 - -2.0185343e+00 -3.6074662e+00 -8.6849630e-01 - -2.1270773e+00 -3.7627420e+00 -8.5516064e-01 - -2.2521347e+00 -3.9423255e+00 -8.4643126e-01 - -2.3826456e+00 -4.1294297e+00 -8.3419341e-01 - -2.5252196e+00 -4.3338093e+00 -8.2092882e-01 - -2.6842864e+00 -4.5623242e+00 -8.0877483e-01 - -2.8498483e+00 -4.7991632e+00 -7.9036297e-01 - -3.0318889e+00 -5.0600243e+00 -7.7076455e-01 - -3.2424989e+00 -5.3624044e+00 -7.5344728e-01 - -3.4815419e+00 -5.7041816e+00 -7.3591345e-01 - -3.7546724e+00 -6.0960299e+00 -7.1780188e-01 - -4.0397989e+00 -6.5046165e+00 -6.8777701e-01 - -4.3369132e+00 -6.9298774e+00 -6.4454044e-01 - -4.6690732e+00 -7.4048287e+00 -5.9423097e-01 - -5.0967724e+00 -8.0177850e+00 -5.5074176e-01 - -5.5640000e+00 -8.6887487e+00 -4.9133133e-01 - -6.1242523e+00 -9.4900861e+00 -4.2341373e-01 - -6.6318466e+00 -1.0218235e+01 -3.1237340e-01 - -6.7187801e+00 -1.0341150e+01 -1.0602724e-01 - -6.8596620e+00 -1.0544170e+01 9.8095360e-02 - -7.2791268e+00 -1.1144488e+01 2.8478778e-01 - -8.2175600e+00 -1.2489150e+01 4.6484341e-01 - -8.6510467e+00 -1.3109417e+01 7.1748643e-01 - -8.7213483e+00 -1.3209663e+01 9.9650288e-01 - -8.7258731e+00 -1.3216468e+01 1.2779131e+00 - -8.7160933e+00 -1.3202096e+01 1.5587912e+00 - -8.6920758e+00 -1.3167598e+01 1.8380880e+00 - -8.5672275e+00 -1.2989384e+01 2.1042664e+00 - -8.7263476e+00 -1.3217509e+01 2.4067596e+00 - -8.7570797e+00 -1.3260451e+01 2.6961216e+00 - -8.7550446e+00 -1.3258414e+01 2.9817610e+00 - -8.7452414e+00 -1.3243854e+01 3.2664344e+00 - -8.7331997e+00 -1.3225418e+01 3.5511030e+00 - -8.7233866e+00 -1.3210780e+01 3.8373744e+00 - -8.7048723e+00 -1.3184716e+01 4.1219271e+00 - -8.6940474e+00 -1.3170030e+01 4.4103926e+00 - -8.6874413e+00 -1.3158971e+01 4.7014661e+00 - -8.6656160e+00 -1.3127981e+01 4.9882584e+00 - -8.6569938e+00 -1.3116886e+01 5.2825216e+00 - -8.6460072e+00 -1.3099875e+01 5.5775797e+00 - -8.6318405e+00 -1.3080016e+01 5.8732787e+00 - -8.6143733e+00 -1.3055314e+01 6.1695194e+00 - -8.6109703e+00 -1.3048320e+01 6.4758316e+00 - -8.5442073e+00 -1.2952670e+01 6.7458406e+00 - -8.4260824e+00 -1.2784604e+01 6.9813226e+00 - -8.6306426e+00 -1.3076460e+01 7.4397282e+00 - -8.6175278e+00 -1.3058517e+01 7.7561536e+00 - -8.5485440e+00 -1.2959647e+01 8.0330988e+00 - -8.6489871e+00 -1.3101511e+01 8.4472181e+00 - -8.6292797e+00 -1.3074465e+01 8.7731661e+00 - -8.6224888e+00 -1.3062962e+01 9.1137776e+00 - -8.6049464e+00 -1.3039206e+01 9.4516158e+00 - -8.5850352e+00 -1.3009501e+01 9.7909481e+00 - -8.5750370e+00 -1.2995446e+01 1.0146432e+01 - -8.5562245e+00 -1.2968031e+01 1.0498901e+01 - -8.5374297e+00 -1.2941272e+01 1.0858310e+01 - -8.5294740e+00 -1.2929013e+01 1.1235722e+01 - -8.5018845e+00 -1.2889567e+01 1.1598756e+01 - -8.4556674e+00 -1.2822935e+01 1.1946117e+01 - -8.4421909e+00 -1.2803133e+01 1.2340745e+01 - -8.4145254e+00 -1.2763594e+01 1.2725902e+01 - -8.2056251e+00 -1.2464991e+01 1.2872683e+01 - -8.4594898e+00 -1.2827564e+01 1.3664688e+01 - -8.4152884e+00 -1.2763545e+01 1.4057947e+01 - -8.2794483e+00 -1.2569096e+01 1.4321054e+01 - -3.2164279e+00 -5.3205644e+00 7.2644199e+00 - -3.1654504e+00 -5.2467939e+00 7.3979358e+00 - -3.0415009e+00 -5.0695742e+00 7.4008441e+00 - -2.9731273e+00 -4.9714543e+00 7.5005114e+00 - -3.1531593e+00 -5.2286427e+00 8.0808080e+00 - -3.0934137e+00 -5.1423954e+00 8.2136543e+00 - -3.0315594e+00 -5.0543391e+00 8.3450968e+00 - -2.2151856e+00 -3.8859760e+00 6.8509587e+00 - -2.9218855e+00 -4.8967311e+00 8.6424225e+00 - -1.5041205e+00 -2.8667255e+00 5.6393647e+00 - -1.4774339e+00 -2.8288210e+00 5.7482670e+00 - -1.4365823e+00 -2.7703391e+00 5.8242276e+00 - -1.3848204e+00 -2.6957581e+00 5.8740956e+00 - -1.3570354e+00 -2.6565969e+00 5.9894372e+00 - -1.3226405e+00 -2.6066478e+00 6.0876855e+00 - -1.2687232e+00 -2.5293692e+00 6.1339028e+00 - -1.2886279e+00 -2.5579058e+00 6.4033637e+00 - -2.3761136e+00 -4.1144073e+00 1.0051252e+01 - -2.3476178e+00 -4.0726602e+00 1.0340577e+01 - -2.1446129e+00 -3.7823162e+00 1.0051664e+01 - -1.9535640e+00 -3.5078762e+00 9.7713198e+00 - -9.4204021e-01 -2.0618256e+00 6.3920725e+00 - -8.9462819e-01 -1.9939832e+00 6.4625247e+00 - -9.0988221e-01 -2.0149242e+00 6.7895538e+00 - -8.7108423e-01 -1.9598743e+00 6.9150572e+00 - -6.2485464e-01 -1.6066979e+00 6.1063416e+00 - -7.6197914e-01 -1.8026859e+00 7.0417966e+00 - -7.2956418e-01 -1.7566107e+00 7.2211480e+00 - -7.5735141e-01 -1.7962196e+00 7.7426139e+00 - -8.4295279e-01 -1.9174717e+00 8.6500346e+00 - -7.8536896e-01 -1.8350043e+00 8.8051079e+00 - -5.9262042e-01 -1.5597463e+00 8.0992878e+00 - -4.9340346e-01 -1.4183113e+00 7.9374083e+00 - -4.2198555e-01 -1.3148176e+00 7.9470811e+00 - -3.2504894e-01 -1.1760471e+00 7.7490023e+00 - -2.6660915e-01 -1.0937451e+00 7.8614259e+00 - -2.7585783e-01 -1.1060647e+00 8.6517646e+00 - -2.4015578e-01 -1.0539217e+00 9.1186514e+00 - -1.8833622e-01 -9.7961060e-01 9.5062489e+00 - 1.1770009e-01 -5.4365278e-01 6.3994517e+00 - 6.4744877e-02 -6.1844333e-01 8.1804596e+00 - 2.0791054e-01 -4.1393457e-01 6.7779716e+00 - 2.6202349e-01 -3.3560837e-01 6.8656872e+00 - 3.1134240e-01 -2.6520642e-01 7.1715919e+00 - 3.6631473e-01 -1.8620169e-01 7.5161857e+00 - 4.3680779e-01 -8.5242059e-02 6.9692024e+00 - -7.7081243e-01 -1.7099999e+00 -9.5277581e-01 - -8.1334602e-01 -1.7673956e+00 -9.4838043e-01 - -8.6466031e-01 -1.8368525e+00 -9.5515046e-01 - -9.0283479e-01 -1.8889830e+00 -9.4042862e-01 - -9.5623811e-01 -1.9600912e+00 -9.4259874e-01 - -1.0086285e+00 -2.0311416e+00 -9.4237500e-01 - -1.0630600e+00 -2.1029449e+00 -9.3959844e-01 - -1.1209899e+00 -2.1827198e+00 -9.4001150e-01 - -1.1853501e+00 -2.2692684e+00 -9.4325469e-01 - -1.2453002e+00 -2.3496287e+00 -9.3771912e-01 - -1.3106812e+00 -2.4368133e+00 -9.3481710e-01 - -1.3761020e+00 -2.5248322e+00 -9.2856960e-01 - -1.4623490e+00 -2.6415307e+00 -9.3940181e-01 - -1.5342898e+00 -2.7380708e+00 -9.3089151e-01 - -1.6271076e+00 -2.8642135e+00 -9.3791322e-01 - -1.7218916e+00 -2.9899939e+00 -9.4003461e-01 - -1.7785498e+00 -3.0671277e+00 -9.0594307e-01 - -1.8789022e+00 -3.2023783e+00 -9.0355800e-01 - -1.9747799e+00 -3.3304092e+00 -8.9174458e-01 - -2.0751885e+00 -3.4671414e+00 -8.7887324e-01 - -2.1830593e+00 -3.6113718e+00 -8.6448459e-01 - -2.3073879e+00 -3.7789427e+00 -8.5535105e-01 - -2.4382309e+00 -3.9549904e+00 -8.4305581e-01 - -2.5855168e+00 -4.1542602e+00 -8.3361862e-01 - -2.7403041e+00 -4.3618578e+00 -8.1921879e-01 - -2.9005934e+00 -4.5778795e+00 -7.9936327e-01 - -3.0903478e+00 -4.8335086e+00 -7.8478124e-01 - -3.3095525e+00 -5.1286272e+00 -7.7307566e-01 - -3.3965291e+00 -5.2456976e+00 -6.9137091e-01 - -3.3272140e+00 -5.1511861e+00 -5.4207043e-01 - -3.1334428e+00 -4.8896312e+00 -3.5181653e-01 - -3.0993221e+00 -4.8454833e+00 -2.2935089e-01 - -3.0825517e+00 -4.8227397e+00 -1.1463330e-01 - -3.0821255e+00 -4.8213968e+00 -6.3685575e-03 - -3.0621327e+00 -4.7949502e+00 1.0604388e-01 - -3.0540532e+00 -4.7830344e+00 2.1434058e-01 - -3.0548256e+00 -4.7847796e+00 3.1956110e-01 - -3.0380965e+00 -4.7623661e+00 4.2758695e-01 - -7.1572285e+00 -1.0307053e+01 -1.3389700e-02 - -7.2142863e+00 -1.0383985e+01 2.0592278e-01 - -3.1231142e+00 -4.8754299e+00 7.3355884e-01 - -3.1250009e+00 -4.8790741e+00 8.3958078e-01 - -8.8928101e+00 -1.2642422e+01 8.5904397e-01 - -8.8744177e+00 -1.2617847e+01 1.1336586e+00 - -8.8483806e+00 -1.2582769e+01 1.4069069e+00 - -8.8365315e+00 -1.2566903e+01 1.6799890e+00 - -8.7984448e+00 -1.2514658e+01 1.9500132e+00 - -8.8465986e+00 -1.2580090e+01 2.2298790e+00 - -8.9273678e+00 -1.2688257e+01 2.5184619e+00 - -8.9220231e+00 -1.2680789e+01 2.7963037e+00 - -8.9015078e+00 -1.2654292e+01 3.0718117e+00 - -8.8971526e+00 -1.2646695e+01 3.3510549e+00 - -8.8766330e+00 -1.2620164e+01 3.6272620e+00 - -8.8712673e+00 -1.2612529e+01 3.9084996e+00 - -8.8571987e+00 -1.2593453e+01 4.1883182e+00 - -8.8518152e+00 -1.2585675e+01 4.4724522e+00 - -8.8322696e+00 -1.2558891e+01 4.7525576e+00 - -8.8258670e+00 -1.2551006e+01 5.0400843e+00 - -8.8172210e+00 -1.2539204e+01 5.3284052e+00 - -8.7823849e+00 -1.2491403e+01 5.6059777e+00 - -8.7845689e+00 -1.2493513e+01 5.9039627e+00 - -8.7661424e+00 -1.2469181e+01 6.1939080e+00 - -8.7553254e+00 -1.2455073e+01 6.4909125e+00 - -8.6693115e+00 -1.2338390e+01 6.7433449e+00 - -8.5855944e+00 -1.2226565e+01 6.9961312e+00 - -8.7922792e+00 -1.2503552e+01 7.4484098e+00 - -8.7672397e+00 -1.2469956e+01 7.7511736e+00 - -8.7063233e+00 -1.2388579e+01 8.0296323e+00 - -8.7932575e+00 -1.2505009e+01 8.4269946e+00 - -8.7844226e+00 -1.2492214e+01 8.7557152e+00 - -8.7712810e+00 -1.2474573e+01 9.0862727e+00 - -8.7537750e+00 -1.2451108e+01 9.4182181e+00 - -8.7427327e+00 -1.2435715e+01 9.7615151e+00 - -8.7219395e+00 -1.2408030e+01 1.0101642e+01 - -8.7129892e+00 -1.2394828e+01 1.0458877e+01 - -8.6834652e+00 -1.2355480e+01 1.0802080e+01 - -8.6745447e+00 -1.2343548e+01 1.1174096e+01 - -8.6503731e+00 -1.2310913e+01 1.1537187e+01 - -8.6033146e+00 -1.2246627e+01 1.1878751e+01 - -8.5943094e+00 -1.2234534e+01 1.2274288e+01 - -8.5700568e+00 -1.2201768e+01 1.2660300e+01 - -8.3730900e+00 -1.1935693e+01 1.2824279e+01 - -8.2295147e+00 -1.1744242e+01 1.3056648e+01 - -3.2669231e+00 -5.0661248e+00 6.3890159e+00 - -3.3617766e+00 -5.1942232e+00 6.7236245e+00 - -3.3502205e+00 -5.1786360e+00 6.9100152e+00 - -2.9242851e+00 -4.6056469e+00 6.4436844e+00 - -3.1827632e+00 -4.9525240e+00 7.0615297e+00 - -3.2774715e+00 -5.0804929e+00 7.4392842e+00 - -2.7790247e+00 -4.4087680e+00 6.7873130e+00 - -2.6862094e+00 -4.2841923e+00 6.8233477e+00 - -2.6205292e+00 -4.1966798e+00 6.9081358e+00 - -3.3260764e+00 -5.1450173e+00 8.5037758e+00 - -2.3818541e+00 -3.8756788e+00 6.8555847e+00 - -2.8520396e+00 -4.5067145e+00 8.0578558e+00 - -1.5900530e+00 -2.8092554e+00 5.5610665e+00 - -1.5559955e+00 -2.7645817e+00 5.6536698e+00 - -1.5012202e+00 -2.6895152e+00 5.6967870e+00 - -1.4681823e+00 -2.6454677e+00 5.7957352e+00 - -2.0308488e+00 -3.4022315e+00 7.4033708e+00 - -2.0158627e+00 -3.3807669e+00 7.6112773e+00 - -1.3408392e+00 -2.4740067e+00 6.0299916e+00 - -1.7645774e+00 -3.0435769e+00 7.4355990e+00 - -1.6297725e+00 -2.8618280e+00 7.3006471e+00 - -1.6029837e+00 -2.8262003e+00 7.4849540e+00 - -1.5405808e+00 -2.7428293e+00 7.5631583e+00 - -2.1680265e+00 -3.5849776e+00 9.9573700e+00 - -1.0406842e+00 -2.0702203e+00 6.4060114e+00 - -9.3427071e-01 -1.9270193e+00 6.2682303e+00 - -1.0226700e+00 -2.0447571e+00 6.8595052e+00 - -8.9482936e-01 -1.8740484e+00 6.6352301e+00 - -7.2287918e-01 -1.6416882e+00 6.1913747e+00 - -7.9176060e-01 -1.7347115e+00 6.7789071e+00 - -8.9472276e-01 -1.8728097e+00 7.5886443e+00 - -8.3014083e-01 -1.7855207e+00 7.6474181e+00 - -9.6155477e-01 -1.9623493e+00 8.7533042e+00 - -8.7535688e-01 -1.8465591e+00 8.7659837e+00 - -7.8375605e-01 -1.7221050e+00 8.7375524e+00 - -6.2937469e-01 -1.5154737e+00 8.2995803e+00 - -5.3058833e-01 -1.3831529e+00 8.1757995e+00 - -4.0734555e-01 -1.2160072e+00 7.8338831e+00 - -3.5337527e-01 -1.1444943e+00 8.0063398e+00 - -3.4468742e-01 -1.1320576e+00 8.6102184e+00 - -2.6601537e-01 -1.0253064e+00 8.6337029e+00 - -2.5035804e-01 -1.0043657e+00 9.3767912e+00 - -1.8185089e-01 -9.1239920e-01 9.6353569e+00 - 1.3080183e-01 -4.9199018e-01 6.3852081e+00 - 7.1248390e-02 -5.7253281e-01 8.4057355e+00 - 2.2288669e-01 -3.6852450e-01 6.8420210e+00 - 2.7800107e-01 -2.9384291e-01 6.9988953e+00 - 3.3441630e-01 -2.1835009e-01 7.2342184e+00 - 3.9710256e-01 -1.3374592e-01 7.3779410e+00 - 4.6772182e-01 -3.9299004e-02 6.6798915e+00 - -7.5666232e-01 -1.5918101e+00 -9.5919386e-01 - -7.9569253e-01 -1.6411947e+00 -9.5080984e-01 - -8.4016840e-01 -1.6975218e+00 -9.4745642e-01 - -8.8896885e-01 -1.7588382e+00 -9.4883636e-01 - -9.4227208e-01 -1.8281151e+00 -9.5440151e-01 - -9.8776934e-01 -1.8850831e+00 -9.4500276e-01 - -1.0430399e+00 -1.9540075e+00 -9.4586735e-01 - -1.0929649e+00 -2.0178208e+00 -9.3830631e-01 - -1.1537770e+00 -2.0954845e+00 -9.4010733e-01 - -1.2199615e+00 -2.1789903e+00 -9.4489108e-01 - -1.2818569e+00 -2.2583067e+00 -9.4089685e-01 - -1.3501206e+00 -2.3433850e+00 -9.3948267e-01 - -1.4174260e+00 -2.4293581e+00 -9.3472618e-01 - -1.4912169e+00 -2.5230623e+00 -9.3195126e-01 - -1.5867676e+00 -2.6443542e+00 -9.4560328e-01 - -1.6615694e+00 -2.7386156e+00 -9.3508513e-01 - -1.7537978e+00 -2.8554064e+00 -9.3486228e-01 - -1.8514417e+00 -2.9788982e+00 -9.3477607e-01 - -1.9273478e+00 -3.0754939e+00 -9.1202101e-01 - -2.0206128e+00 -3.1935629e+00 -8.9841229e-01 - -2.1312865e+00 -3.3340183e+00 -8.9220244e-01 - -2.2320461e+00 -3.4603608e+00 -8.7253241e-01 - -2.3601444e+00 -3.6238449e+00 -8.6648077e-01 - -2.4957558e+00 -3.7957503e+00 -8.5736413e-01 - -2.6378176e+00 -3.9751061e+00 -8.4453608e-01 - -2.7983758e+00 -4.1785355e+00 -8.3401080e-01 - -2.9588823e+00 -4.3815510e+00 -8.1509588e-01 - -3.1552897e+00 -4.6309921e+00 -8.0518347e-01 - -3.2939580e+00 -4.8057943e+00 -7.5715727e-01 - -3.2881807e+00 -4.7992959e+00 -6.3956802e-01 - -3.2748017e+00 -4.7831526e+00 -5.2049898e-01 - -3.3091541e+00 -4.8262722e+00 -4.2073976e-01 - -3.6759163e+00 -5.2902531e+00 -4.3393577e-01 - -4.8095860e+00 -6.7269408e+00 -6.6765295e-01 - -3.3438376e+00 -4.8701900e+00 -9.5260769e-02 - -3.2141759e+00 -4.7053432e+00 4.9096327e-02 - -3.1877049e+00 -4.6712246e+00 1.6229181e-01 - -3.1710914e+00 -4.6507656e+00 2.7121577e-01 - -3.1848274e+00 -4.6679140e+00 3.7367168e-01 - -3.1725243e+00 -4.6523310e+00 4.8015944e-01 - -3.1526299e+00 -4.6271868e+00 5.8642907e-01 - -3.2499296e+00 -4.7499909e+00 6.8149643e-01 - -3.2528162e+00 -4.7535894e+00 7.8722192e-01 - -9.1331901e+00 -1.2204255e+01 7.2497332e-01 - -9.1593744e+00 -1.2237330e+01 9.9639904e-01 - -9.1823141e+00 -1.2266525e+01 1.2691152e+00 - -9.1845915e+00 -1.2268864e+01 1.5421813e+00 - -9.1716889e+00 -1.2252101e+01 1.8144116e+00 - -8.9939836e+00 -1.2027560e+01 2.0678661e+00 - -9.2034018e+00 -1.2291965e+01 2.3663519e+00 - -9.2675148e+00 -1.2373143e+01 2.6531002e+00 - -9.2665223e+00 -1.2371400e+01 2.9315517e+00 - -9.2688155e+00 -1.2374382e+01 3.2118585e+00 - -9.2558778e+00 -1.2357338e+01 3.4897818e+00 - -9.2397637e+00 -1.2337475e+01 3.7677467e+00 - -9.2387409e+00 -1.2335491e+01 4.0510921e+00 - -9.2226138e+00 -1.2315524e+01 4.3311544e+00 - -9.2270310e+00 -1.2320952e+01 4.6202056e+00 - -9.2043662e+00 -1.2292321e+01 4.9009015e+00 - -9.2032972e+00 -1.2289968e+01 5.1917377e+00 - -9.1860723e+00 -1.2268749e+01 5.4781394e+00 - -9.1839159e+00 -1.2265228e+01 5.7736170e+00 - -9.1720609e+00 -1.2250346e+01 6.0672729e+00 - -9.1396014e+00 -1.2209072e+01 6.3518904e+00 - -9.1385069e+00 -1.2207031e+01 6.6566590e+00 - -8.9306963e+00 -1.1944771e+01 6.8377804e+00 - -9.2111114e+00 -1.2299721e+01 7.3271001e+00 - -9.1926359e+00 -1.2275514e+01 7.6347731e+00 - -9.0973159e+00 -1.2154218e+01 7.8904248e+00 - -9.2845754e+00 -1.2392489e+01 8.3581952e+00 - -9.2703970e+00 -1.2374083e+01 8.6852044e+00 - -9.2529126e+00 -1.2350791e+01 9.0136541e+00 - -9.2409582e+00 -1.2336663e+01 9.3528027e+00 - -9.2310204e+00 -1.2323091e+01 9.6984991e+00 - -9.2157162e+00 -1.2303726e+01 1.0046180e+01 - -9.2014881e+00 -1.2285955e+01 1.0400854e+01 - -9.1882144e+00 -1.2267773e+01 1.0762622e+01 - -9.1847792e+00 -1.2264132e+01 1.1142791e+01 - -9.1769100e+00 -1.2253596e+01 1.1525795e+01 - -9.0869148e+00 -1.2139823e+01 1.1825405e+01 - -9.0735778e+00 -1.2122167e+01 1.2217036e+01 - -9.0646276e+00 -1.2111546e+01 1.2623258e+01 - -8.8546300e+00 -1.1845305e+01 1.2786248e+01 - -8.6489404e+00 -1.1583920e+01 1.2947200e+01 - -3.4083743e+00 -4.9482205e+00 6.2886554e+00 - -3.3742532e+00 -4.9051009e+00 6.4307960e+00 - -3.3476450e+00 -4.8709168e+00 6.5858390e+00 - -3.1644748e+00 -4.6380332e+00 6.5092417e+00 - -3.1174034e+00 -4.5785856e+00 6.6323745e+00 - -3.0649068e+00 -4.5118439e+00 6.7474045e+00 - -3.0146111e+00 -4.4486785e+00 6.8685319e+00 - -2.8413065e+00 -4.2290045e+00 6.7765272e+00 - -2.7737456e+00 -4.1435673e+00 6.8622071e+00 - -2.7342441e+00 -4.0940275e+00 6.9987913e+00 - -2.6450996e+00 -3.9808644e+00 7.0429209e+00 - -2.8328890e+00 -4.2179114e+00 7.6355883e+00 - -2.7760395e+00 -4.1459538e+00 7.7599461e+00 - -1.6948809e+00 -2.7771989e+00 5.6951989e+00 - -1.6146217e+00 -2.6759014e+00 5.6916090e+00 - -1.5881931e+00 -2.6426368e+00 5.8077505e+00 - -1.5638915e+00 -2.6118432e+00 5.9321370e+00 - -1.4835495e+00 -2.5088523e+00 5.9223555e+00 - -1.4431019e+00 -2.4577253e+00 6.0112969e+00 - -1.8423518e+00 -2.9632481e+00 7.2822317e+00 - -1.6749008e+00 -2.7511975e+00 7.0700905e+00 - -1.7019555e+00 -2.7852536e+00 7.4014439e+00 - -1.6472815e+00 -2.7151229e+00 7.5065813e+00 - -1.5647963e+00 -2.6115945e+00 7.5304016e+00 - -1.1293605e+00 -2.0609788e+00 6.3832748e+00 - -1.0319747e+00 -1.9369707e+00 6.2923527e+00 - -9.6684719e-01 -1.8549057e+00 6.3072264e+00 - -1.0376672e+00 -1.9437362e+00 6.8354910e+00 - -7.6486710e-01 -1.5993547e+00 6.0435656e+00 - -8.7515488e-01 -1.7381871e+00 6.7690803e+00 - -7.1057813e-01 -1.5299367e+00 6.3558961e+00 - -7.3944384e-01 -1.5665168e+00 6.7957188e+00 - -8.6515762e-01 -1.7245701e+00 7.7615720e+00 - -9.5320515e-01 -1.8355858e+00 8.6499800e+00 - -8.3018216e-01 -1.6805112e+00 8.4685577e+00 - -7.3808464e-01 -1.5642508e+00 8.4373235e+00 - -6.7142523e-01 -1.4790129e+00 8.5582622e+00 - -4.9987418e-01 -1.2620050e+00 7.9664833e+00 - -4.1013778e-01 -1.1490545e+00 7.8859660e+00 - -4.3321104e-01 -1.1766514e+00 8.7153909e+00 - -3.3801685e-01 -1.0561456e+00 8.6320642e+00 - -2.5653796e-01 -9.5365403e-01 8.6741643e+00 - -2.3347273e-01 -9.2410129e-01 9.3775336e+00 - -2.2839896e-01 -9.1634843e-01 1.0508415e+01 - 1.4571717e-01 -4.4448733e-01 6.3903822e+00 - 1.8392420e-01 -3.9643756e-01 6.7779574e+00 - 2.4583507e-01 -3.1854536e-01 6.8058726e+00 - 3.0288001e-01 -2.4502597e-01 6.9618912e+00 - 3.5762312e-01 -1.7610477e-01 7.4262309e+00 - 4.3461012e-01 -7.9509676e-02 6.7993240e+00 - -8.2830790e-01 -1.5836177e+00 -9.6215942e-01 - -8.6932828e-01 -1.6328322e+00 -9.5277028e-01 - -9.1467510e-01 -1.6870507e+00 -9.4841413e-01 - -9.6546510e-01 -1.7481920e+00 -9.4868907e-01 - -1.0172397e+00 -1.8091645e+00 -9.4676354e-01 - -1.0734556e+00 -1.8770906e+00 -9.4887302e-01 - -1.1306543e+00 -1.9448331e+00 -9.4848240e-01 - -1.1888960e+00 -2.0133890e+00 -9.4554214e-01 - -1.2471824e+00 -2.0828186e+00 -9.4005541e-01 - -1.3163516e+00 -2.1660642e+00 -9.4323160e-01 - -1.3855016e+00 -2.2491571e+00 -9.4331161e-01 - -1.4556909e+00 -2.3330338e+00 -9.4024271e-01 - -1.5323049e+00 -2.4236398e+00 -9.3910505e-01 - -1.6197886e+00 -2.5279582e+00 -9.4453290e-01 - -1.7029206e+00 -2.6270706e+00 -9.4083280e-01 - -1.7925308e+00 -2.7338551e+00 -9.3791576e-01 - -1.9048860e+00 -2.8680632e+00 -9.4932506e-01 - -1.9836766e+00 -2.9625674e+00 -9.2835746e-01 - -2.0688833e+00 -3.0637319e+00 -9.0792284e-01 - -2.1714452e+00 -3.1863402e+00 -8.9603528e-01 - -2.2750341e+00 -3.3096336e+00 -8.7900128e-01 - -2.4088990e+00 -3.4689150e+00 -8.7612506e-01 - -2.5372849e+00 -3.6209878e+00 -8.6282490e-01 - -2.6831201e+00 -3.7962865e+00 -8.5367802e-01 - -2.8428949e+00 -3.9867505e+00 -8.4369701e-01 - -3.0036787e+00 -4.1777569e+00 -8.2567314e-01 - -3.1893813e+00 -4.3995465e+00 -8.1148376e-01 - -3.3998693e+00 -4.6500219e+00 -7.9913057e-01 - -3.5801400e+00 -4.8660106e+00 -7.6253283e-01 - -3.5926884e+00 -4.8806737e+00 -6.4899301e-01 - -3.5793443e+00 -4.8653253e+00 -5.2577948e-01 - -3.8913079e+00 -5.2362175e+00 -5.1667206e-01 - -4.8648612e+00 -6.3972355e+00 -7.0049636e-01 - -5.2427166e+00 -6.8487792e+00 -6.5856874e-01 - -5.6658327e+00 -7.3533375e+00 -6.0813970e-01 - -6.1536346e+00 -7.9338528e+00 -5.5006022e-01 - -6.7236576e+00 -8.6152687e+00 -4.8279139e-01 - -6.9757688e+00 -8.9153489e+00 -3.2836245e-01 - -7.2257413e+00 -9.2138977e+00 -1.6070583e-01 - -7.8655677e+00 -9.9761062e+00 -2.7845310e-02 - -8.9147246e+00 -1.1227392e+01 1.0022844e-01 - -9.7778441e+00 -1.2255760e+01 2.9775835e-01 - -9.7769658e+00 -1.2255962e+01 5.7730768e-01 - -9.9605951e+00 -1.2473862e+01 8.5391631e-01 - -9.9218498e+00 -1.2428001e+01 1.1375678e+00 - -9.9251829e+00 -1.2431771e+01 1.4209236e+00 - -9.9068647e+00 -1.2408821e+01 1.7031281e+00 - -9.8649087e+00 -1.2359351e+01 1.9825768e+00 - -9.9232842e+00 -1.2428675e+01 2.2726099e+00 - -1.0047548e+01 -1.2577589e+01 2.5764874e+00 - -1.0034673e+01 -1.2562081e+01 2.8637983e+00 - -1.0025028e+01 -1.2550330e+01 3.1523158e+00 - -1.0005682e+01 -1.2527204e+01 3.4393111e+00 - -1.0008954e+01 -1.2530492e+01 3.7324548e+00 - -9.9959997e+00 -1.2513829e+01 4.0229123e+00 - -9.9917924e+00 -1.2509476e+01 4.3174351e+00 - -9.9778236e+00 -1.2492745e+01 4.6104862e+00 - -9.9606164e+00 -1.2472184e+01 4.9038289e+00 - -9.9401713e+00 -1.2447796e+01 5.1973634e+00 - -9.9477147e+00 -1.2456159e+01 5.5043005e+00 - -9.9261885e+00 -1.2430652e+01 5.8014777e+00 - -9.9197295e+00 -1.2422833e+01 6.1079306e+00 - -9.8798151e+00 -1.2374634e+01 6.3996697e+00 - -9.8722688e+00 -1.2365646e+01 6.7107641e+00 - -9.6502484e+00 -1.2100804e+01 6.9005814e+00 - -9.9713243e+00 -1.2483227e+01 7.4133343e+00 - -9.9572394e+00 -1.2466085e+01 7.7349996e+00 - -9.8332416e+00 -1.2317661e+01 7.9860323e+00 - -1.0080940e+01 -1.2613295e+01 8.4976555e+00 - -1.0064639e+01 -1.2593481e+01 8.8353954e+00 - -1.0055865e+01 -1.2582726e+01 9.1835409e+00 - -1.0036341e+01 -1.2559719e+01 9.5289130e+00 - -1.0012511e+01 -1.2531880e+01 9.8758224e+00 - -1.0012298e+01 -1.2531423e+01 1.0248558e+01 - -9.9850605e+00 -1.2497369e+01 1.0603550e+01 - -9.9794938e+00 -1.2491737e+01 1.0986010e+01 - -9.9587312e+00 -1.2466359e+01 1.1360394e+01 - -9.9154030e+00 -1.2414991e+01 1.1720040e+01 - -9.7783774e+00 -1.2250652e+01 1.1984224e+01 - -9.8156650e+00 -1.2294879e+01 1.2441597e+01 - -9.7271111e+00 -1.2189744e+01 1.2767473e+01 - -9.4610396e+00 -1.1871969e+01 1.2885122e+01 - -9.9756192e+00 -1.2484757e+01 1.3956607e+01 - -3.6473767e+00 -4.9424517e+00 6.3160785e+00 - -3.5628552e+00 -4.8413045e+00 6.3953720e+00 - -3.5159876e+00 -4.7855491e+00 6.5246956e+00 - -3.5110079e+00 -4.7794505e+00 6.7139979e+00 - -3.4834124e+00 -4.7459297e+00 6.8770774e+00 - -3.3527704e+00 -4.5908704e+00 6.8862440e+00 - -3.3133296e+00 -4.5428465e+00 7.0326153e+00 - -3.0367194e+00 -4.2143051e+00 6.7944298e+00 - -3.0369926e+00 -4.2130928e+00 7.0001255e+00 - -2.9686778e+00 -4.1322476e+00 7.0952386e+00 - -2.9497229e+00 -4.1101838e+00 7.2796622e+00 - -2.7729471e+00 -3.8985284e+00 7.1718116e+00 - -2.7110537e+00 -3.8249020e+00 7.2753303e+00 - -2.7457107e+00 -3.8670606e+00 7.5756915e+00 - -1.6888858e+00 -2.6068896e+00 5.5973506e+00 - -1.6518425e+00 -2.5624663e+00 5.6885461e+00 - -2.2512379e+00 -3.2766031e+00 7.2212155e+00 - -2.1240158e+00 -3.1247619e+00 7.1614766e+00 - -2.0921855e+00 -3.0874851e+00 7.3245450e+00 - -1.9039672e+00 -2.8624825e+00 7.0955168e+00 - -1.7993417e+00 -2.7379108e+00 7.0650970e+00 - -1.8476731e+00 -2.7951778e+00 7.4484892e+00 - -1.7537420e+00 -2.6834336e+00 7.4497063e+00 - -1.6961375e+00 -2.6145108e+00 7.5542845e+00 - -2.4749869e+00 -3.5418498e+00 1.0270424e+01 - -1.1623749e+00 -1.9791702e+00 6.4149870e+00 - -1.0643663e+00 -1.8618318e+00 6.3318993e+00 - -1.0069730e+00 -1.7935656e+00 6.3826447e+00 - -8.5786497e-01 -1.6154934e+00 6.0901916e+00 - -7.8878030e-01 -1.5329227e+00 6.0796847e+00 - -9.0069303e-01 -1.6660878e+00 6.8163439e+00 - -1.0761699e+00 -1.8750130e+00 7.9090667e+00 - -1.4797513e+00 -2.3562265e+00 1.0188575e+01 - -1.0414696e+00 -1.8341847e+00 8.5910825e+00 - -1.2200610e+00 -2.0456506e+00 1.0012355e+01 - -8.2606534e-01 -1.5768710e+00 8.4195658e+00 - -7.1209930e-01 -1.4407068e+00 8.2704708e+00 - -5.4332683e-01 -1.2396282e+00 7.7382673e+00 - -4.7818576e-01 -1.1620968e+00 7.8435758e+00 - -4.5821630e-01 -1.1375988e+00 8.3002089e+00 - -4.0760251e-01 -1.0780805e+00 8.5905226e+00 - -3.2741672e-01 -9.8201123e-01 8.6632849e+00 - -2.6287352e-01 -9.0483073e-01 8.9020791e+00 - -3.0705040e-01 -9.5674846e-01 1.0487965e+01 - 1.0106962e-01 -4.7115614e-01 6.4049894e+00 - 1.4003538e-01 -4.2611160e-01 6.7733843e+00 - 2.0288995e-01 -3.4974659e-01 6.8120822e+00 - 2.6971832e-01 -2.6964825e-01 6.7692712e+00 - 3.2776631e-01 -2.0079189e-01 7.0143232e+00 - 3.8941731e-01 -1.2725420e-01 7.3579439e+00 - 4.6565934e-01 -3.7643798e-02 6.6299611e+00 - -8.9009529e-01 -1.5622749e+00 -9.5091613e-01 - -9.4178090e-01 -1.6215047e+00 -9.5418341e-01 - -9.9005583e-01 -1.6744957e+00 -9.4886850e-01 - -1.0427745e+00 -1.7344600e+00 -9.4798811e-01 - -1.0954803e+00 -1.7943209e+00 -9.4501031e-01 - -1.1545623e+00 -1.8600077e+00 -9.4591096e-01 - -1.2147481e+00 -1.9275097e+00 -9.4431228e-01 - -1.2739203e+00 -1.9949491e+00 -9.4021987e-01 - -1.3458517e+00 -2.0740945e+00 -9.4498299e-01 - -1.4114977e+00 -2.1491714e+00 -9.4097448e-01 - -1.4845703e+00 -2.2309467e+00 -9.3949330e-01 - -1.5630098e+00 -2.3185197e+00 -9.4009595e-01 - -1.6533794e+00 -2.4207565e+00 -9.4751102e-01 - -1.7328925e+00 -2.5099034e+00 -9.4072040e-01 - -1.8307733e+00 -2.6205468e+00 -9.4477083e-01 - -1.9113582e+00 -2.7112526e+00 -9.3028731e-01 - -2.0166850e+00 -2.8292662e+00 -9.3022365e-01 - -2.1220425e+00 -2.9480403e+00 -9.2531637e-01 - -2.2219887e+00 -3.0606619e+00 -9.1113412e-01 - -2.3294025e+00 -3.1808261e+00 -8.9633346e-01 - -2.4422238e+00 -3.3076274e+00 -8.8037105e-01 - -2.5808766e+00 -3.4634383e+00 -8.7403202e-01 - -2.7205472e+00 -3.6198606e+00 -8.6104840e-01 - -2.8850339e+00 -3.8052150e+00 -8.5489479e-01 - -3.0505297e+00 -3.9911117e+00 -8.4069833e-01 - -3.2289596e+00 -4.1921752e+00 -8.2447240e-01 - -3.4342382e+00 -4.4228548e+00 -8.1112538e-01 - -3.6588645e+00 -4.6753417e+00 -7.9588235e-01 - -3.7822538e+00 -4.8139604e+00 -7.2780829e-01 - -3.7947923e+00 -4.8285447e+00 -6.1267045e-01 - -3.9815773e+00 -5.0372368e+00 -5.5827008e-01 - -4.1092933e+00 -5.1818929e+00 -4.7565397e-01 - -5.2871818e+00 -6.5058393e+00 -6.9453469e-01 - -5.6912456e+00 -6.9604364e+00 -6.4498565e-01 - -6.1629443e+00 -7.4899303e+00 -5.9022323e-01 - -6.6937691e+00 -8.0864941e+00 -5.2387764e-01 - -7.1524386e+00 -8.6021240e+00 -4.1651371e-01 - -7.1873035e+00 -8.6423341e+00 -2.1847345e-01 - -7.7695416e+00 -9.2969833e+00 -9.1674619e-02 - -8.5828769e+00 -1.0211218e+01 4.0945257e-02 - -9.8337179e+00 -1.1617226e+01 1.8120022e-01 - -1.0572536e+01 -1.2447727e+01 4.1405895e-01 - -1.0597364e+01 -1.2475933e+01 7.0435973e-01 - -1.0752225e+01 -1.2649699e+01 9.9573486e-01 - -1.0751188e+01 -1.2648116e+01 1.2912149e+00 - -1.0732914e+01 -1.2626554e+01 1.5858033e+00 - -1.0717940e+01 -1.2609820e+01 1.8801496e+00 - -1.0553602e+01 -1.2425358e+01 2.1585919e+00 - -1.1133956e+01 -1.3078149e+01 2.5268854e+00 - -1.1154358e+01 -1.3100553e+01 2.8383992e+00 - -1.1071652e+01 -1.3007645e+01 3.1331755e+00 - -1.1387463e+01 -1.3362092e+01 3.5088486e+00 - -1.1376708e+01 -1.3350024e+01 3.8252780e+00 - -1.1355193e+01 -1.3325639e+01 4.1402325e+00 - -1.1356230e+01 -1.3326617e+01 4.4623844e+00 - -1.1340104e+01 -1.3308722e+01 4.7814969e+00 - -1.1333598e+01 -1.3301047e+01 5.1052780e+00 - -1.1322793e+01 -1.3288580e+01 5.4297974e+00 - -1.1308746e+01 -1.3272257e+01 5.7551079e+00 - -1.1104711e+01 -1.3042659e+01 6.0010416e+00 - -1.0930770e+01 -1.2847081e+01 6.2524437e+00 - -1.0924305e+01 -1.2840245e+01 6.5794704e+00 - -1.0814701e+01 -1.2715774e+01 6.8558032e+00 - -1.0432699e+01 -1.2287265e+01 6.9810911e+00 - -1.0919735e+01 -1.2834456e+01 7.5895028e+00 - -1.0867040e+01 -1.2774898e+01 7.9033307e+00 - -1.1213379e+01 -1.3163948e+01 8.4740374e+00 - -1.1191762e+01 -1.3139779e+01 8.8251464e+00 - -1.1183007e+01 -1.3130200e+01 9.1899705e+00 - -1.1164496e+01 -1.3108289e+01 9.5524239e+00 - -1.1152453e+01 -1.3094489e+01 9.9254299e+00 - -1.1135106e+01 -1.3075899e+01 1.0300369e+01 - -1.1101503e+01 -1.3036618e+01 1.0667380e+01 - -1.1125874e+01 -1.3064273e+01 1.1090414e+01 - -1.0853312e+01 -1.2757596e+01 1.1255028e+01 - -1.0721174e+01 -1.2608934e+01 1.1540941e+01 - -1.0669411e+01 -1.2550849e+01 1.1904709e+01 - -1.0602590e+01 -1.2475152e+01 1.2257703e+01 - -1.0606482e+01 -1.2479472e+01 1.2690774e+01 - -1.0372579e+01 -1.2216638e+01 1.2874810e+01 - -1.0121540e+01 -1.1934105e+01 1.3032037e+01 - -1.0745340e+01 -1.2635423e+01 1.4207685e+01 - -3.7492231e+00 -4.7736658e+00 6.3592440e+00 - -3.6511487e+00 -4.6630228e+00 6.4240682e+00 - -3.6269804e+00 -4.6363879e+00 6.5857064e+00 - -3.6059434e+00 -4.6122128e+00 6.7545939e+00 - -3.6576628e+00 -4.6703802e+00 7.0350244e+00 - -3.7136234e+00 -4.7333860e+00 7.3340424e+00 - -3.3674285e+00 -4.3436360e+00 7.0194180e+00 - -3.0930274e+00 -4.0355416e+00 6.7909655e+00 - -3.0345832e+00 -3.9694927e+00 6.8992847e+00 - -2.9216832e+00 -3.8430940e+00 6.9156816e+00 - -2.8525302e+00 -3.7646185e+00 7.0044985e+00 - -3.0623078e+00 -4.0015954e+00 7.6122166e+00 - -2.8221731e+00 -3.7302606e+00 7.3895936e+00 - -2.9153406e+00 -3.8350862e+00 7.8110523e+00 - -2.9027222e+00 -3.8205945e+00 8.0372395e+00 - -2.2359624e+00 -3.0721881e+00 6.8723200e+00 - -2.2575587e+00 -3.0955894e+00 7.1421389e+00 - -2.1714172e+00 -2.9986016e+00 7.1800762e+00 - -1.9680804e+00 -2.7712766e+00 6.9354212e+00 - -1.8958371e+00 -2.6896382e+00 6.9907219e+00 - -2.0058210e+00 -2.8131490e+00 7.5203382e+00 - -1.8781202e+00 -2.6691302e+00 7.4450627e+00 - -1.8154519e+00 -2.5988951e+00 7.5418354e+00 - -1.7878562e+00 -2.5674357e+00 7.7441649e+00 - -2.4846815e+00 -3.3504917e+00 1.0193561e+01 - -2.4789871e+00 -3.3438392e+00 1.0596695e+01 - -1.1055527e+00 -1.8019621e+00 6.4168083e+00 - -1.0376836e+00 -1.7246789e+00 6.4397106e+00 - -9.9645163e-01 -1.6789307e+00 6.5626541e+00 - -9.5404327e-01 -1.6302718e+00 6.6850463e+00 - -1.1353395e+00 -1.8343848e+00 7.7464293e+00 - -1.1542042e+00 -1.8561573e+00 8.2137947e+00 - -1.4680355e+00 -2.2072912e+00 1.0091445e+01 - -1.0020086e+00 -1.6839258e+00 8.3726670e+00 - -9.1480518e-01 -1.5854578e+00 8.4013134e+00 - -8.2979626e-01 -1.4910309e+00 8.4468934e+00 - -6.5937462e-01 -1.2990362e+00 7.9761029e+00 - -5.6705170e-01 -1.1946847e+00 7.9275327e+00 - -5.3884984e-01 -1.1635384e+00 8.3261160e+00 - -4.3708365e-01 -1.0493521e+00 8.2245376e+00 - -3.9699929e-01 -1.0039214e+00 8.6222428e+00 - -3.1189070e-01 -9.0818223e-01 8.6741653e+00 - -2.9928381e-01 -8.9266467e-01 9.5062493e+00 - -2.3237257e-01 -8.1882358e-01 9.9229128e+00 - 1.1586861e-01 -4.2819324e-01 6.4599493e+00 - 1.5900298e-01 -3.7940584e-01 6.8078088e+00 - 2.2671913e-01 -3.0334451e-01 6.8059416e+00 - 2.9349011e-01 -2.2834635e-01 6.8420796e+00 - 3.4998765e-01 -1.6405786e-01 7.3162488e+00 - 4.2973523e-01 -7.5186538e-02 6.7592917e+00 - -9.6782584e-01 -1.5550025e+00 -9.5960591e-01 - -1.0063139e+00 -1.5959286e+00 -9.4183038e-01 - -1.0705854e+00 -1.6639328e+00 -9.5530036e-01 - -1.1262304e+00 -1.7226548e+00 -9.5316158e-01 - -1.1754721e+00 -1.7753340e+00 -9.4274979e-01 - -1.2374809e+00 -1.8397834e+00 -9.4249192e-01 - -1.2985364e+00 -1.9051671e+00 -9.3969077e-01 - -1.3660246e+00 -1.9773441e+00 -9.4011925e-01 - -1.4344931e+00 -2.0493177e+00 -9.3764813e-01 - -1.5093913e+00 -2.1280601e+00 -9.3790726e-01 - -1.5897172e+00 -2.2136021e+00 -9.4030056e-01 - -1.9548078e+00 -2.6009187e+00 -9.4277069e-01 - -2.0446952e+00 -2.6962081e+00 -9.3090722e-01 - -2.1720806e+00 -2.8304868e+00 -9.4181977e-01 - -2.2565922e+00 -2.9204237e+00 -9.1663673e-01 - -2.3603964e+00 -3.0306963e+00 -9.0024369e-01 - -2.4834834e+00 -3.1612257e+00 -8.9104265e-01 - -2.6139698e+00 -3.2982368e+00 -8.7997435e-01 - -2.7509755e+00 -3.4437642e+00 -8.6654337e-01 - -2.9201741e+00 -3.6240089e+00 -8.6421718e-01 - -3.0710210e+00 -3.7833993e+00 -8.4380926e-01 - -3.2625962e+00 -3.9860601e+00 -8.3533315e-01 - -3.4606064e+00 -4.1960481e+00 -8.2064872e-01 - -3.6789680e+00 -4.4278273e+00 -8.0496398e-01 - -3.9111819e+00 -4.6735582e+00 -7.8410009e-01 - -4.1315880e+00 -4.9071481e+00 -7.4678686e-01 - -4.1257502e+00 -4.9001669e+00 -6.1940969e-01 - -4.1371393e+00 -4.9125715e+00 -4.9938029e-01 - -4.3425093e+00 -5.1307872e+00 -4.3718653e-01 - -4.3462628e+00 -5.1332758e+00 -3.1018413e-01 - -4.3469628e+00 -5.1349587e+00 -1.8344058e-01 - -4.3197391e+00 -5.1059560e+00 -5.1174169e-02 - -4.3246912e+00 -5.1115327e+00 7.2784000e-02 - -4.3221036e+00 -5.1084762e+00 1.9797187e-01 - -4.3173421e+00 -5.1025744e+00 3.2250534e-01 - -4.3041080e+00 -5.0891361e+00 4.4751588e-01 - -4.3026545e+00 -5.0881363e+00 5.7030911e-01 - -4.2871912e+00 -5.0708952e+00 6.9381668e-01 - -4.2964537e+00 -5.0813479e+00 8.1533865e-01 - -4.2917076e+00 -5.0755692e+00 9.3737521e-01 - -4.2848460e+00 -5.0679274e+00 1.0591066e+00 - -4.2694583e+00 -5.0518064e+00 1.1801668e+00 - -4.2530160e+00 -5.0347785e+00 1.3005750e+00 - -4.2558059e+00 -5.0376035e+00 1.4219811e+00 - -4.2500088e+00 -5.0309474e+00 1.5427664e+00 - -4.3041731e+00 -5.0884528e+00 1.6720930e+00 - -1.2049952e+01 -1.3294336e+01 3.0780635e+00 - -1.1996382e+01 -1.3236852e+01 3.3915879e+00 - -1.2067036e+01 -1.3313007e+01 3.7310942e+00 - -1.2053057e+01 -1.3297745e+01 4.0551558e+00 - -1.2034783e+01 -1.3277726e+01 4.3792565e+00 - -1.2026194e+01 -1.3268958e+01 4.7073763e+00 - -1.2006846e+01 -1.3247879e+01 5.0339213e+00 - -1.1997118e+01 -1.3237015e+01 5.3652347e+00 - -1.1982152e+01 -1.3222416e+01 5.6973328e+00 - -1.1957429e+01 -1.3195475e+01 6.0272600e+00 - -1.1830061e+01 -1.3059487e+01 6.3147296e+00 - -1.1829972e+01 -1.3059511e+01 6.6574529e+00 - -1.1674935e+01 -1.2895905e+01 6.9287713e+00 - -1.1712246e+01 -1.2935672e+01 7.2942112e+00 - -1.1796429e+01 -1.3023202e+01 7.6911322e+00 - -1.1720495e+01 -1.2943914e+01 8.0063465e+00 - -1.1907291e+01 -1.3141777e+01 8.4804311e+00 - -1.1892079e+01 -1.3124699e+01 8.8425425e+00 - -1.1876954e+01 -1.3109343e+01 9.2102463e+00 - -1.1857463e+01 -1.3088154e+01 9.5795377e+00 - -1.1838994e+01 -1.3067611e+01 9.9547745e+00 - -1.1821606e+01 -1.3048696e+01 1.0336306e+01 - -1.1804238e+01 -1.3030457e+01 1.0724379e+01 - -1.1716348e+01 -1.2936823e+01 1.1060238e+01 - -1.1611410e+01 -1.2825736e+01 1.1384518e+01 - -1.1590790e+01 -1.2804077e+01 1.1784818e+01 - -1.1424971e+01 -1.2627977e+01 1.2058257e+01 - -1.1473656e+01 -1.2679521e+01 1.2536186e+01 - -1.1362263e+01 -1.2561468e+01 1.2867191e+01 - -1.1067391e+01 -1.2249190e+01 1.3010165e+01 - -1.1672746e+01 -1.2890141e+01 1.4111032e+01 - -1.1481232e+01 -1.2686634e+01 1.4381859e+01 - -3.9129863e+00 -4.6722040e+00 6.4862115e+00 - -3.8895849e+00 -4.6469698e+00 7.0627351e+00 - -3.8356120e+00 -4.5901775e+00 7.2013753e+00 - -3.7655929e+00 -4.5153973e+00 7.3178030e+00 - -3.3303258e+00 -4.0541918e+00 6.8740498e+00 - -3.1198661e+00 -3.8313621e+00 6.7494204e+00 - -3.1649434e+00 -3.8789997e+00 7.0277886e+00 - -2.9620381e+00 -3.6649215e+00 6.8995324e+00 - -3.1049383e+00 -3.8157356e+00 7.3645171e+00 - -2.9562234e+00 -3.6573082e+00 7.3221427e+00 - -2.8799136e+00 -3.5763537e+00 7.4089909e+00 - -2.7122053e+00 -3.3994659e+00 7.3171289e+00 - -2.4328927e+00 -3.1039549e+00 6.9827354e+00 - -2.2557056e+00 -2.9164325e+00 6.8338206e+00 - -2.2687571e+00 -2.9301737e+00 7.0863896e+00 - -2.0512343e+00 -2.6994245e+00 6.8269601e+00 - -3.1844922e+00 -3.8981594e+00 9.7467066e+00 - -2.5485470e+00 -3.2257168e+00 8.5295551e+00 - -1.9404837e+00 -2.5815633e+00 7.2744225e+00 - -1.8483610e+00 -2.4839690e+00 7.2914674e+00 - -1.8262569e+00 -2.4608499e+00 7.5009504e+00 - -1.6684057e+00 -2.2934939e+00 7.3264168e+00 - -1.6758889e+00 -2.3008595e+00 7.6333043e+00 - -1.1824404e+00 -1.7786708e+00 6.3681749e+00 - -1.1011510e+00 -1.6929511e+00 6.3551344e+00 - -1.0812419e+00 -1.6723306e+00 6.5520386e+00 - -1.0020342e+00 -1.5882031e+00 6.5447966e+00 - -9.7671271e-01 -1.5609062e+00 6.7413381e+00 - -1.1646237e+00 -1.7600730e+00 7.8336563e+00 - -1.2613588e+00 -1.8619904e+00 8.6523837e+00 - -1.1016834e+00 -1.6925211e+00 8.3813156e+00 - -1.0200752e+00 -1.6063157e+00 8.4591614e+00 - -8.9952643e-01 -1.4784486e+00 8.3327626e+00 - -7.5699860e-01 -1.3272153e+00 8.0573934e+00 - -6.5132380e-01 -1.2149740e+00 7.9617941e+00 - -5.4784633e-01 -1.1057653e+00 7.8630540e+00 - -5.1759162e-01 -1.0737726e+00 8.2609821e+00 - -4.2971726e-01 -9.8004255e-01 8.2758408e+00 - -3.8975500e-01 -9.3868203e-01 8.7125954e+00 - -3.1099903e-01 -8.5373772e-01 8.8625098e+00 - -2.8692889e-01 -8.2883323e-01 9.6552121e+00 - -7.1195596e-02 -6.0060808e-01 8.2530085e+00 - 1.2550265e-01 -3.9353995e-01 6.6239849e+00 - 1.8090301e-01 -3.3389318e-01 6.8419736e+00 - 2.5254401e-01 -2.5861558e-01 6.8291073e+00 - 3.1446566e-01 -1.9249921e-01 7.0842829e+00 - 3.8272797e-01 -1.1980945e-01 7.3179691e+00 - 4.6284980e-01 -3.5984429e-02 6.6599336e+00 - -1.1422587e+00 -1.6401886e+00 -9.4811943e-01 - -1.1880498e+00 -1.6857946e+00 -9.3247093e-01 - -1.9868800e+00 -2.4849773e+00 -9.4969361e-01 - -2.0732106e+00 -2.5713129e+00 -9.3498970e-01 - -2.1723402e+00 -2.6701890e+00 -9.2579585e-01 - -2.3099605e+00 -2.8079495e+00 -9.3847593e-01 - -2.4037112e+00 -2.9014484e+00 -9.1546311e-01 - -2.5113102e+00 -3.0083504e+00 -8.9640947e-01 - -2.6446277e+00 -3.1423272e+00 -8.8827682e-01 - -2.7863404e+00 -3.2827055e+00 -8.7787424e-01 - -2.9409442e+00 -3.4373916e+00 -8.6828828e-01 - -3.1029965e+00 -3.5994676e+00 -8.5498774e-01 - -3.2789277e+00 -3.7757071e+00 -8.4080274e-01 - -3.4761606e+00 -3.9727789e+00 -8.2766134e-01 - -3.6936884e+00 -4.1906747e+00 -8.1416845e-01 - -3.9270679e+00 -4.4224259e+00 -7.9598943e-01 - -4.2075586e+00 -4.7038417e+00 -7.8488183e-01 - -4.4484029e+00 -4.9441441e+00 -7.4600997e-01 - -4.4351760e+00 -4.9312792e+00 -6.1236050e-01 - -4.4262048e+00 -4.9223376e+00 -4.8209567e-01 - -4.4161802e+00 -4.9124989e+00 -3.5268258e-01 - -4.4114660e+00 -4.9074906e+00 -2.2600214e-01 - -4.4120585e+00 -4.9072830e+00 -1.0145510e-01 - -4.4041753e+00 -4.8995144e+00 2.4068383e-02 - -4.3941797e+00 -4.8899073e+00 1.4878727e-01 - -4.3894883e+00 -4.8850813e+00 2.7177227e-01 - -4.3911577e+00 -4.8859580e+00 3.9337574e-01 - -4.3768782e+00 -4.8716867e+00 5.1623613e-01 - -4.3743780e+00 -4.8698440e+00 6.3707898e-01 - -4.3782330e+00 -4.8736596e+00 7.5743919e-01 - -4.3596702e+00 -4.8547292e+00 8.7834121e-01 - -4.3464675e+00 -4.8415422e+00 9.9825803e-01 - -4.3460325e+00 -4.8406445e+00 1.1177585e+00 - -4.3360707e+00 -4.8313083e+00 1.2369842e+00 - -4.3324612e+00 -4.8276060e+00 1.3562266e+00 - -4.3277932e+00 -4.8229672e+00 1.4754163e+00 - -4.3135433e+00 -4.8089324e+00 1.5934826e+00 - -4.3056418e+00 -4.8005019e+00 1.7121649e+00 - -1.2961132e+01 -1.3448403e+01 3.3309836e+00 - -1.3609998e+01 -1.4096188e+01 3.7974740e+00 - -1.3691901e+01 -1.4177964e+01 4.1716693e+00 - -1.3671502e+01 -1.4157549e+01 4.5264754e+00 - -1.3716111e+01 -1.4202476e+01 4.9003250e+00 - -1.3376063e+01 -1.3861892e+01 5.1631730e+00 - -1.3680593e+01 -1.4166760e+01 5.6217362e+00 - -1.3669713e+01 -1.4155244e+01 5.9877532e+00 - -1.3011366e+01 -1.3497752e+01 6.1115541e+00 - -1.2823740e+01 -1.3309459e+01 6.3944696e+00 - -1.2809715e+01 -1.3294856e+01 6.7456969e+00 - -1.2615805e+01 -1.3101471e+01 7.0176092e+00 - -1.2779612e+01 -1.3265318e+01 7.4573338e+00 - -1.2771919e+01 -1.3256710e+01 7.8215114e+00 - -1.2625938e+01 -1.3111485e+01 8.1156194e+00 - -1.3546309e+01 -1.4030307e+01 9.0147706e+00 - -1.3540348e+01 -1.4024316e+01 9.8287426e+00 - -1.3513378e+01 -1.3997038e+01 1.0228726e+01 - -1.3492759e+01 -1.3975903e+01 1.0638663e+01 - -1.3233504e+01 -1.3717287e+01 1.1313556e+01 - -1.2812973e+01 -1.3296908e+01 1.1422987e+01 - -1.2572212e+01 -1.3055937e+01 1.1659823e+01 - -1.2517609e+01 -1.3001847e+01 1.2047600e+01 - -1.2439507e+01 -1.2922863e+01 1.2419886e+01 - -1.2427372e+01 -1.2910895e+01 1.2857061e+01 - -1.2109043e+01 -1.2592417e+01 1.3011999e+01 - -1.1848211e+01 -1.2332411e+01 1.3212228e+01 - -1.2554355e+01 -1.3037366e+01 1.4396273e+01 - -3.9116842e+00 -4.4036714e+00 7.4507633e+00 - -3.2181495e+00 -3.7109919e+00 6.6300488e+00 - -3.2185653e+00 -3.7119509e+00 6.8322480e+00 - -3.3271116e+00 -3.8206638e+00 7.2173481e+00 - -3.2182110e+00 -3.7119125e+00 7.2572681e+00 - -3.0287659e+00 -3.5228787e+00 7.1536592e+00 - -2.8742651e+00 -3.3674681e+00 7.0979813e+00 - -2.6361791e+00 -3.1300396e+00 6.8768432e+00 - -2.4764970e+00 -2.9698001e+00 6.7833488e+00 - -2.3878944e+00 -2.8818972e+00 6.8231209e+00 - -2.2844480e+00 -2.7786100e+00 6.8271995e+00 - -2.1153552e+00 -2.6093110e+00 6.6852410e+00 - -2.0744339e+00 -2.5691405e+00 6.8166717e+00 - -1.4885953e+00 -1.9834083e+00 5.6708892e+00 - -1.4129115e+00 -1.9084876e+00 5.6759377e+00 - -1.9482235e+00 -2.4426187e+00 7.2351764e+00 - -1.4887118e+00 -1.9842533e+00 6.2793821e+00 - -1.7646276e+00 -2.2582932e+00 7.2719086e+00 - -1.8228913e+00 -2.3176562e+00 7.7221477e+00 - -1.3416128e+00 -1.8371053e+00 6.5731880e+00 - -1.2004259e+00 -1.6962875e+00 6.3893531e+00 - -1.1699712e+00 -1.6650601e+00 6.5501251e+00 - -1.1384610e+00 -1.6334351e+00 6.7201825e+00 - -1.0826972e+00 -1.5778901e+00 6.8157200e+00 - -1.0343003e+00 -1.5301129e+00 6.9478307e+00 - -1.2245233e+00 -1.7190025e+00 8.0624844e+00 - -8.8684667e-01 -1.3819796e+00 7.0197122e+00 - -7.4808488e-01 -1.2439508e+00 6.7566319e+00 - -9.5024982e-01 -1.4452362e+00 8.1320915e+00 - -8.6373618e-01 -1.3589846e+00 8.1764635e+00 - -7.4994184e-01 -1.2440914e+00 8.0633620e+00 - -6.5304984e-01 -1.1480540e+00 8.0346977e+00 - -6.0826831e-01 -1.1032092e+00 8.3455957e+00 - -5.2797656e-01 -1.0236134e+00 8.4503084e+00 - -4.2159667e-01 -9.1635325e-01 8.3562521e+00 - -2.0048732e-01 -6.9618247e-01 7.2223431e+00 - -3.5563166e-01 -8.5020245e-01 9.5655779e+00 - -2.8179531e-01 -7.7624892e-01 9.9525565e+00 - 7.2877126e-02 -4.2276071e-01 6.6986411e+00 - 1.4628612e-01 -3.5046010e-01 6.6683891e+00 - 2.1370423e-01 -2.8245356e-01 6.7260942e+00 - 2.8018128e-01 -2.1650892e-01 6.8420784e+00 - 3.4988425e-01 -1.4631757e-01 6.9465194e+00 - 4.2511431e-01 -7.1928249e-02 6.8192336e+00 - -2.0021284e+00 -2.3564810e+00 -9.4592562e-01 - -2.1041089e+00 -2.4524805e+00 -9.4286347e-01 - -2.2114458e+00 -2.5541940e+00 -9.4018727e-01 - -2.3271914e+00 -2.6624173e+00 -9.3743840e-01 - -2.4504040e+00 -2.7781783e+00 -9.3397126e-01 - -2.5470141e+00 -2.8693837e+00 -9.0865096e-01 - -2.6840982e+00 -2.9992492e+00 -9.0310083e-01 - -2.8221434e+00 -3.1287586e+00 -8.9155493e-01 - -2.9676459e+00 -3.2657269e+00 -8.7769272e-01 - -3.1408423e+00 -3.4294816e+00 -8.7134934e-01 - -3.3149894e+00 -3.5927965e+00 -8.5731228e-01 - -3.5040700e+00 -3.7711819e+00 -8.4173878e-01 - -3.7143288e+00 -3.9683811e+00 -8.2680859e-01 - -3.9459366e+00 -4.1873062e+00 -8.1077505e-01 - -4.2136180e+00 -4.4392961e+00 -7.9749348e-01 - -4.5249053e+00 -4.7329248e+00 -7.8699508e-01 - -4.6105901e+00 -4.8130690e+00 -6.8729535e-01 - -4.5953067e+00 -4.7993279e+00 -5.5370179e-01 - -4.5863349e+00 -4.7903814e+00 -4.2333708e-01 - -4.5816754e+00 -4.7863257e+00 -2.9570820e-01 - -4.5759009e+00 -4.7803661e+00 -1.6878087e-01 - -4.5542310e+00 -4.7602012e+00 -3.9448415e-02 - -4.5591308e+00 -4.7648450e+00 8.3161808e-02 - -4.5490738e+00 -4.7542311e+00 2.0803090e-01 - -4.5433836e+00 -4.7494606e+00 3.3111259e-01 - -4.5440536e+00 -4.7503879e+00 4.5291264e-01 - -4.5361305e+00 -4.7417849e+00 5.7509064e-01 - -4.5336278e+00 -4.7399225e+00 6.9633299e-01 - -4.5290096e+00 -4.7361968e+00 8.1727013e-01 - -4.5158623e+00 -4.7239674e+00 9.3803552e-01 - -4.5090105e+00 -4.7164044e+00 1.0581688e+00 - -4.5001041e+00 -4.7079802e+00 1.1779466e+00 - -4.4965510e+00 -4.7052452e+00 1.2978378e+00 - -4.4929384e+00 -4.7015183e+00 1.4175796e+00 - -4.4787443e+00 -4.6884460e+00 1.5363946e+00 - -4.5006410e+00 -4.7090905e+00 1.6594986e+00 - -1.4025176e+01 -1.3678179e+01 3.2673857e+00 - -1.4015503e+01 -1.3669301e+01 3.6192226e+00 - -1.4037666e+01 -1.3690227e+01 3.9785333e+00 - -1.4033319e+01 -1.3686821e+01 4.3348783e+00 - -1.4003411e+01 -1.3658116e+01 4.6864133e+00 - -1.3983070e+01 -1.3638689e+01 5.0414687e+00 - -1.3964833e+01 -1.3621027e+01 5.3988268e+00 - -1.3928563e+01 -1.3586609e+01 5.7519431e+00 - -1.3915647e+01 -1.3574380e+01 6.1146082e+00 - -1.3883581e+01 -1.3543472e+01 6.4727295e+00 - -1.3888707e+01 -1.3548590e+01 6.8478760e+00 - -1.3596769e+01 -1.3273903e+01 7.0987525e+00 - -1.3869198e+01 -1.3530567e+01 7.5974923e+00 - -1.3838178e+01 -1.3501006e+01 7.9676012e+00 - -1.3727565e+01 -1.3395894e+01 8.2996502e+00 - -1.3807973e+01 -1.3472721e+01 8.7348678e+00 - -1.3802327e+01 -1.3466453e+01 9.1302118e+00 - -1.3783988e+01 -1.3449011e+01 9.5236246e+00 - -1.3773060e+01 -1.3438658e+01 9.9268445e+00 - -1.3749381e+01 -1.3416149e+01 1.0327784e+01 - -1.3680150e+01 -1.3351498e+01 1.0703636e+01 - -1.3664903e+01 -1.3336714e+01 1.1120527e+01 - -1.3643290e+01 -1.3316188e+01 1.1539600e+01 - -1.3615253e+01 -1.3288933e+01 1.1960603e+01 - -1.3398632e+01 -1.3084688e+01 1.2236446e+01 - -1.3526388e+01 -1.3205553e+01 1.2797680e+01 - -1.3246155e+01 -1.2940642e+01 1.3019274e+01 - -1.2926895e+01 -1.2641101e+01 1.3197969e+01 - -1.3694153e+01 -1.3363040e+01 1.4389837e+01 - -3.3242320e+00 -3.5984483e+00 6.7271779e+00 - -3.4369395e+00 -3.7043555e+00 7.3251280e+00 - -3.3326660e+00 -3.6066213e+00 7.3799376e+00 - -2.9833410e+00 -3.2780295e+00 7.0091378e+00 - -2.9149761e+00 -3.2130728e+00 7.1075374e+00 - -3.3660916e+00 -3.6376078e+00 8.1689435e+00 - -2.4880023e+00 -2.8104466e+00 6.7465234e+00 - -2.5379473e+00 -2.8578298e+00 7.0644579e+00 - -1.6161281e+00 -1.9898870e+00 5.3855427e+00 - -2.3507309e+00 -2.6818780e+00 7.1389269e+00 - -1.5791359e+00 -1.9556708e+00 5.6547610e+00 - -1.5753432e+00 -1.9520525e+00 5.8330793e+00 - -1.6821389e+00 -2.0522348e+00 6.2910382e+00 - -1.5834257e+00 -1.9592648e+00 6.2634152e+00 - -1.5700262e+00 -1.9465677e+00 6.4544426e+00 - -1.2660699e+00 -1.6605073e+00 5.8589408e+00 - -1.3989340e+00 -1.7851016e+00 6.4600397e+00 - -1.2897970e+00 -1.6830142e+00 6.3863464e+00 - -1.2500410e+00 -1.6456658e+00 6.5201263e+00 - -1.3888613e+00 -1.7763397e+00 7.2540253e+00 - -1.2050380e+00 -1.6026611e+00 6.9355424e+00 - -1.0685770e+00 -1.4736488e+00 6.7506170e+00 - -9.5845165e-01 -1.3701534e+00 6.6459099e+00 - -1.2318646e+00 -1.6267713e+00 8.0929232e+00 - -8.4723414e-01 -1.2651504e+00 6.8554094e+00 - -7.4556831e-01 -1.1696020e+00 6.7621602e+00 - -9.6058182e-01 -1.3721763e+00 8.2171607e+00 - -6.5304623e-01 -1.0827412e+00 7.1086377e+00 - -7.9323885e-01 -1.2147117e+00 8.3798718e+00 - -6.2991121e-01 -1.0608825e+00 7.9801932e+00 - -4.5227908e-01 -8.9339938e-01 7.4084414e+00 - -4.8546289e-01 -9.2451612e-01 8.2758488e+00 - -4.3845467e-01 -8.8053018e-01 8.6730819e+00 - -4.2509314e-01 -8.6701913e-01 9.4657115e+00 - -3.2695108e-01 -7.7470229e-01 9.5857062e+00 - -2.2259412e-01 -6.7681710e-01 9.6638367e+00 - 1.0182088e-01 -3.7206180e-01 6.6438973e+00 - 1.7105755e-01 -3.0662826e-01 6.6924066e+00 - 2.3443298e-01 -2.4651565e-01 6.8890968e+00 - 3.0309375e-01 -1.8228884e-01 7.0942623e+00 - 3.8431366e-01 -1.0567677e-01 6.9180698e+00 - 4.6097452e-01 -3.3864693e-02 6.6599408e+00 - -1.9353183e+00 -2.1625073e+00 -9.5790886e-01 - -2.0061756e+00 -2.2253337e+00 -9.3574939e-01 - -2.1290120e+00 -2.3339615e+00 -9.4975755e-01 - -2.2264128e+00 -2.4208706e+00 -9.3986307e-01 - -2.3513663e+00 -2.5318905e+00 -9.4402819e-01 - -2.4699687e+00 -2.6378006e+00 -9.3857234e-01 - -2.6033542e+00 -2.7560318e+00 -9.3662265e-01 - -2.7101972e+00 -2.8507043e+00 -9.1277026e-01 - -2.8520103e+00 -2.9761121e+00 -9.0400663e-01 - -2.9939069e+00 -3.1032183e+00 -8.8915130e-01 - -3.1643192e+00 -3.2540941e+00 -8.8265942e-01 - -3.3358051e+00 -3.4065437e+00 -8.6877426e-01 - -3.5221065e+00 -3.5720896e+00 -8.5385126e-01 - -3.7306482e+00 -3.7574154e+00 -8.4011811e-01 - -3.9614203e+00 -3.9624423e+00 -8.2597678e-01 - -4.2218407e+00 -4.1937997e+00 -8.1255631e-01 - -4.5266913e+00 -4.4637988e+00 -8.0316312e-01 - -4.8538558e+00 -4.7551973e+00 -7.8727005e-01 - -4.9498067e+00 -4.8395887e+00 -6.8459411e-01 - -4.9334992e+00 -4.8257012e+00 -5.4680891e-01 - -4.8874468e+00 -4.7841956e+00 -4.0245966e-01 - -4.8679224e+00 -4.7666494e+00 -2.6787849e-01 - -4.8537692e+00 -4.7549355e+00 -1.3608031e-01 - -4.8681214e+00 -4.7669074e+00 -1.0947659e-02 - -4.8507409e+00 -4.7514510e+00 1.1934440e-01 - -4.7645529e+00 -4.6755374e+00 2.5804404e-01 - -4.7736248e+00 -4.6829204e+00 3.8101538e-01 - -4.7964674e+00 -4.7025716e+00 5.0277455e-01 - -4.8162492e+00 -4.7213579e+00 6.2547340e-01 - -4.7988399e+00 -4.7051558e+00 7.5062219e-01 - -4.7931448e+00 -4.7003459e+00 8.7450290e-01 - -4.7863932e+00 -4.6946142e+00 9.9803125e-01 - -4.7785242e+00 -4.6869590e+00 1.1212576e+00 - -4.7611918e+00 -4.6718869e+00 1.2437592e+00 - -4.7723762e+00 -4.6811084e+00 1.3675352e+00 - -4.7592798e+00 -4.6698020e+00 1.4898483e+00 - -4.7524728e+00 -4.6631128e+00 1.6125281e+00 - -4.7658237e+00 -4.6751206e+00 1.7381569e+00 - -1.5338930e+01 -1.4065034e+01 3.5945481e+00 - -1.5553547e+01 -1.4256057e+01 4.0109961e+00 - -1.5541640e+01 -1.4244889e+01 4.3914417e+00 - -1.5524498e+01 -1.4230006e+01 4.7722725e+00 - -1.5509460e+01 -1.4216892e+01 5.1553061e+00 - -1.5482726e+01 -1.4192534e+01 5.5366116e+00 - -1.5471892e+01 -1.4182930e+01 5.9246502e+00 - -1.5289642e+01 -1.4019891e+01 6.2580053e+00 - -1.5073681e+01 -1.3828654e+01 6.5740419e+00 - -1.5063849e+01 -1.3819024e+01 6.9613846e+00 - -1.4697744e+01 -1.3493915e+01 7.2069130e+00 - -1.5062248e+01 -1.3817789e+01 7.7550928e+00 - -1.5014337e+01 -1.3774627e+01 8.1368418e+00 - -1.5382959e+01 -1.4102364e+01 8.7233846e+00 - -1.5377284e+01 -1.4096897e+01 9.1429978e+00 - -1.5351587e+01 -1.4074851e+01 9.5572642e+00 - -1.5340572e+01 -1.4064318e+01 9.9844042e+00 - -1.5310537e+01 -1.4037173e+01 1.0405601e+01 - -1.5273144e+01 -1.4004392e+01 1.0828077e+01 - -1.5196585e+01 -1.3935892e+01 1.1229725e+01 - -1.4927766e+01 -1.3696775e+01 1.1503725e+01 - -1.4688626e+01 -1.3485258e+01 1.1791785e+01 - -1.4624714e+01 -1.3427568e+01 1.2202756e+01 - -1.4644250e+01 -1.3444602e+01 1.2683909e+01 - -1.4476894e+01 -1.3296313e+01 1.3025293e+01 - -1.4115197e+01 -1.2974283e+01 1.3203517e+01 - -1.4894777e+01 -1.3666179e+01 1.4359236e+01 - -1.4618645e+01 -1.3421789e+01 1.4627124e+01 - -7.4302242e+00 -7.0383996e+00 1.1596375e+01 - -7.0832472e+00 -6.7295158e+00 1.1492190e+01 - -3.5897854e+00 -3.6288997e+00 7.2852036e+00 - -3.5216057e+00 -3.5680017e+00 7.4026278e+00 - -3.3713067e+00 -3.4344349e+00 7.3867010e+00 - -3.0242430e+00 -3.1272230e+00 7.0269821e+00 - -2.9729297e+00 -3.0807670e+00 7.1562364e+00 - -4.6157690e+00 -4.5392082e+00 1.0406928e+01 - -1.8141979e+00 -2.0527212e+00 5.4143951e+00 - -1.7389655e+00 -1.9860489e+00 5.4345714e+00 - -1.6563781e+00 -1.9127354e+00 5.4358519e+00 - -1.6505213e+00 -1.9071488e+00 5.5957377e+00 - -1.5511057e+00 -1.8186655e+00 5.5594207e+00 - -1.6860008e+00 -1.9382587e+00 6.0568579e+00 - -1.6705973e+00 -1.9245902e+00 6.2295025e+00 - -2.0309851e+00 -2.2440259e+00 7.3563520e+00 - -1.4277092e+00 -1.7093870e+00 6.0513828e+00 - -1.3577383e+00 -1.6476699e+00 6.0865542e+00 - -1.4492371e+00 -1.7288466e+00 6.5822290e+00 - -1.3581903e+00 -1.6475862e+00 6.5720517e+00 - -1.6537139e+00 -1.9090234e+00 7.7741366e+00 - -1.5594205e+00 -1.8259292e+00 7.8047993e+00 - -1.1532429e+00 -1.4655394e+00 6.7503391e+00 - -1.0988549e+00 -1.4170769e+00 6.8631553e+00 - -9.6815006e-01 -1.3010989e+00 6.6915238e+00 - -1.1716751e+00 -1.4811915e+00 7.8661000e+00 - -8.5200872e-01 -1.1974493e+00 6.8999583e+00 - -8.5071349e-01 -1.1963822e+00 7.2862743e+00 - -7.7635837e-01 -1.1302311e+00 7.3554421e+00 - -6.9571932e-01 -1.0579598e+00 7.3939318e+00 - -5.9022195e-01 -9.6497236e-01 7.2941771e+00 - -6.3088779e-01 -1.0001362e+00 8.0912433e+00 - -3.3590752e-01 -7.3943067e-01 6.7325046e+00 - -3.0193572e-01 -7.0833466e-01 7.0563626e+00 - -2.3793430e-01 -6.5177238e-01 7.2025616e+00 - -9.0712584e-02 -5.2135116e-01 6.5948790e+00 - -1.6644553e-02 -4.5646270e-01 6.5979292e+00 - 5.5477901e-02 -3.9156348e-01 6.6190131e+00 - 1.2858866e-01 -3.2680353e-01 6.6384959e+00 - 1.8973241e-01 -2.7206083e-01 6.8657021e+00 - 2.6506557e-01 -2.0509954e-01 6.9119958e+00 - 3.4517937e-01 -1.3393119e-01 6.8065655e+00 - 4.2223268e-01 -6.6203313e-02 6.7492831e+00 - -1.6867462e+00 -1.8295928e+00 -9.6054642e-01 - -1.7574280e+00 -1.8889536e+00 -9.4917208e-01 - -1.8608373e+00 -1.9746244e+00 -9.6202962e-01 - -1.9389247e+00 -2.0405162e+00 -9.4978679e-01 - -2.0306994e+00 -2.1169777e+00 -9.4484783e-01 - -2.1362750e+00 -2.2059489e+00 -9.4601500e-01 - -2.2502035e+00 -2.3004674e+00 -9.4785820e-01 - -2.3567851e+00 -2.3899563e+00 -9.4048313e-01 - -2.4855340e+00 -2.4976106e+00 -9.4208750e-01 - -2.6079324e+00 -2.6001599e+00 -9.3417079e-01 - -2.7451126e+00 -2.7150205e+00 -9.2956049e-01 - -2.8621290e+00 -2.8121680e+00 -9.0732543e-01 - -3.0214856e+00 -2.9457819e+00 -9.0335526e-01 - -3.1818592e+00 -3.0800023e+00 -8.9264063e-01 - -3.3570564e+00 -3.2273829e+00 -8.8218655e-01 - -3.5342645e+00 -3.3752751e+00 -8.6428569e-01 - -3.7325993e+00 -3.5410531e+00 -8.4847597e-01 - -3.9615971e+00 -3.7332342e+00 -8.3608061e-01 - -4.2284942e+00 -3.9554472e+00 -8.2817755e-01 - -4.5176622e+00 -4.1982005e+00 -8.1662070e-01 - -4.8532468e+00 -4.4793958e+00 -8.0748674e-01 - -5.2278029e+00 -4.7921868e+00 -7.9525205e-01 - -5.6847419e+00 -5.1745941e+00 -7.9038873e-01 - -6.0686840e+00 -5.4952144e+00 -7.4526989e-01 - -5.9329764e+00 -5.3817204e+00 -5.5716609e-01 - -7.1628055e+00 -6.4106455e+00 -6.7523716e-01 - -5.8717884e+00 -5.3307509e+00 -2.4436866e-01 - -8.3812595e+00 -7.4311022e+00 -5.2836879e-01 - -8.6519070e+00 -7.6573264e+00 -3.6355144e-01 - -8.8211917e+00 -7.7991912e+00 -1.7438514e-01 - -9.6005759e+00 -8.4506284e+00 -4.0920878e-02 - -1.0600518e+01 -9.2874906e+00 1.0985993e-01 - -1.2234634e+01 -1.0654345e+01 2.6937263e-01 - -1.4757193e+01 -1.2764819e+01 4.7215231e-01 - -1.5912696e+01 -1.3731647e+01 8.0582084e-01 - -1.6111956e+01 -1.3898540e+01 1.1815351e+00 - -1.6091659e+01 -1.3881010e+01 1.5589117e+00 - -1.6097763e+01 -1.3885910e+01 1.9372575e+00 - -1.6043787e+01 -1.3841467e+01 2.3117970e+00 - -1.6161677e+01 -1.3939325e+01 2.7021265e+00 - -1.6266895e+01 -1.4026681e+01 3.0971662e+00 - -1.6250856e+01 -1.4013608e+01 3.4805962e+00 - -1.6246326e+01 -1.4008740e+01 3.8666045e+00 - -1.6228160e+01 -1.3993710e+01 4.2516269e+00 - -1.6212101e+01 -1.3980475e+01 4.6383528e+00 - -1.6198147e+01 -1.3969019e+01 5.0270819e+00 - -1.6172555e+01 -1.3947301e+01 5.4144318e+00 - -1.6148010e+01 -1.3926421e+01 5.8038321e+00 - -1.6141357e+01 -1.3920144e+01 6.2005712e+00 - -1.6098883e+01 -1.3884375e+01 6.5884254e+00 - -1.6102819e+01 -1.3888021e+01 6.9946304e+00 - -1.5902251e+01 -1.3720167e+01 7.3260329e+00 - -1.6122230e+01 -1.3904789e+01 7.8243996e+00 - -1.6072295e+01 -1.3862035e+01 8.2205740e+00 - -1.6168846e+01 -1.3942374e+01 8.6866022e+00 - -1.6149526e+01 -1.3926673e+01 9.1067277e+00 - -1.6117455e+01 -1.3898820e+01 9.5244730e+00 - -1.6100189e+01 -1.3884494e+01 9.9547915e+00 - -1.6082887e+01 -1.3869882e+01 1.0390903e+01 - -1.6059282e+01 -1.3850540e+01 1.0828945e+01 - -1.6022928e+01 -1.3819056e+01 1.1264406e+01 - -8.8798953e+00 -7.8438029e+00 7.0908356e+00 - -8.7084717e+00 -7.7011349e+00 7.2433380e+00 - -8.7580796e+00 -7.7422143e+00 7.5472425e+00 - -8.5087485e+00 -7.5340600e+00 7.6387630e+00 - -8.4319873e+00 -7.4688813e+00 7.8527425e+00 - -1.5927823e+01 -1.3738423e+01 1.4112360e+01 - -1.5878737e+01 -1.3697516e+01 1.4591433e+01 - -6.8236455e+00 -6.1233558e+00 7.5556698e+00 - -6.9090998e+00 -6.1951679e+00 7.8838394e+00 - -6.5327022e+00 -5.8801256e+00 7.7778669e+00 - -6.5623991e+00 -5.9055119e+00 8.0584467e+00 - -6.2028708e+00 -5.6039032e+00 7.9442298e+00 - -6.1263175e+00 -5.5398707e+00 8.1147134e+00 - -7.7213245e+00 -6.8742049e+00 1.0812614e+01 - -7.3994536e+00 -6.6040053e+00 1.1110485e+01 - -7.3594182e+00 -6.5711286e+00 1.1416996e+01 - -7.2772794e+00 -6.5021299e+00 1.1674007e+01 - -4.7651218e+00 -4.4007680e+00 1.0266154e+01 - -2.8844349e+00 -2.8282598e+00 7.1777771e+00 - -1.8664993e+00 -1.9769779e+00 5.4822696e+00 - -1.7464407e+00 -1.8770518e+00 5.4187280e+00 - -1.6619873e+00 -1.8059320e+00 5.4185031e+00 - -1.6865968e+00 -1.8272384e+00 5.6460853e+00 - -1.6125867e+00 -1.7643603e+00 5.6691596e+00 - -1.5197995e+00 -1.6868127e+00 5.6469396e+00 - -1.5013559e+00 -1.6714136e+00 5.7975530e+00 - -1.4724308e+00 -1.6474673e+00 5.9310595e+00 - -1.6421887e+00 -1.7889018e+00 6.5924900e+00 - -1.4510365e+00 -1.6292045e+00 6.3245132e+00 - -1.3509380e+00 -1.5458798e+00 6.2861435e+00 - -1.3782436e+00 -1.5677149e+00 6.6209005e+00 - -1.3501521e+00 -1.5439400e+00 6.8104898e+00 - -1.3220638e+00 -1.5212230e+00 7.0191548e+00 - -1.1154810e+00 -1.3479406e+00 6.6194510e+00 - -1.0268613e+00 -1.2736119e+00 6.6081287e+00 - -9.5390553e-01 -1.2126691e+00 6.6515300e+00 - -9.4549691e-01 -1.2058590e+00 6.9602234e+00 - -8.7143630e-01 -1.1441244e+00 7.0209001e+00 - -8.0773493e-01 -1.0904755e+00 7.1282967e+00 - -7.1181465e-01 -1.0099393e+00 7.0892894e+00 - -6.3155232e-01 -9.4377289e-01 7.1255795e+00 - -5.2637166e-01 -8.5537924e-01 7.0137382e+00 - -3.9341010e-01 -7.4444665e-01 6.7029698e+00 - -3.0702226e-01 -6.7187898e-01 6.6535010e+00 - -2.4027336e-01 -6.1644047e-01 6.7400649e+00 - -1.6724380e-01 -5.5439233e-01 6.7856139e+00 - -6.4628923e-02 -4.6939688e-01 6.5619178e+00 - 9.3127059e-03 -4.0706573e-01 6.5739059e+00 - 8.2247322e-02 -3.4577630e-01 6.6040739e+00 - 1.5822372e-01 -2.8222739e-01 6.6026728e+00 - 2.2036665e-01 -2.3011581e-01 6.8790632e+00 - 2.9663670e-01 -1.6628325e-01 6.9644534e+00 - 3.7949141e-01 -9.6806995e-02 6.8081269e+00 - 4.5909699e-01 -3.0731467e-02 6.6399734e+00 - -1.6873198e+00 -1.7237652e+00 -9.5104501e-01 - -1.7588283e+00 -1.7801486e+00 -9.4131428e-01 - -1.8450893e+00 -1.8480926e+00 -9.3993334e-01 - -1.9376546e+00 -1.9207719e+00 -9.4058274e-01 - -2.0312567e+00 -1.9942153e+00 -9.3768373e-01 - -2.1322779e+00 -2.0742980e+00 -9.3611351e-01 - -2.2543584e+00 -2.1706964e+00 -9.4532293e-01 - -2.3710859e+00 -2.2619245e+00 -9.4490820e-01 - -2.4879060e+00 -2.3549248e+00 -9.3989992e-01 - -2.6203901e+00 -2.4582164e+00 -9.3899311e-01 - -2.7455863e+00 -2.5574655e+00 -9.2861871e-01 - -2.9076296e+00 -2.6853449e+00 -9.3362558e-01 - -3.0348754e+00 -2.7859300e+00 -9.1225917e-01 - -3.1915854e+00 -2.9093110e+00 -9.0100048e-01 - -3.3640593e+00 -3.0448146e+00 -8.9044822e-01 - -3.5439216e+00 -3.1867112e+00 -8.7623092e-01 - -3.7405957e+00 -3.3415832e+00 -8.6096943e-01 - -3.9667591e+00 -3.5199672e+00 -8.5007314e-01 - -4.2013508e+00 -3.7055330e+00 -8.3246278e-01 - -4.4832024e+00 -3.9266963e+00 -8.2161560e-01 - -4.8103589e+00 -4.1844223e+00 -8.1439222e-01 - -5.1849173e+00 -4.4804263e+00 -8.0749114e-01 - -5.6067392e+00 -4.8125717e+00 -7.9811504e-01 - -5.9305475e+00 -5.0671370e+00 -7.4340946e-01 - -5.9531980e+00 -5.0847369e+00 -6.0032624e-01 - -5.9043007e+00 -5.0466712e+00 -4.4100659e-01 - -7.6998143e+00 -6.4615935e+00 -6.5769466e-01 - -5.8001430e+00 -4.9643034e+00 -1.3042371e-01 - -8.9638088e+00 -7.4579199e+00 -4.8430164e-01 - -9.0609737e+00 -7.5343911e+00 -2.8428837e-01 - -9.5233205e+00 -7.8985968e+00 -1.2159379e-01 - -1.0351817e+01 -8.5512685e+00 2.8254293e-02 - -1.1633737e+01 -9.5614312e+00 1.8401776e-01 - -1.3644656e+01 -1.1146259e+01 3.6371738e-01 - -1.6533785e+01 -1.3422885e+01 6.1249966e-01 - -1.6536713e+01 -1.3424961e+01 9.9098682e-01 - -1.6817346e+01 -1.3645673e+01 1.3756653e+00 - -1.6801362e+01 -1.3633553e+01 1.7600438e+00 - -1.6765333e+01 -1.3604671e+01 2.1427707e+00 - -1.6527358e+01 -1.3416392e+01 2.5067765e+00 - -1.7004639e+01 -1.3793311e+01 2.9404237e+00 - -1.6975924e+01 -1.3769711e+01 3.3290634e+00 - -1.6940982e+01 -1.3742511e+01 3.7169863e+00 - -1.6932298e+01 -1.3735560e+01 4.1095746e+00 - -1.6902576e+01 -1.3711952e+01 4.4996093e+00 - -1.6890702e+01 -1.3702079e+01 4.8943365e+00 - -1.6866192e+01 -1.3681998e+01 5.2877813e+00 - -1.6835451e+01 -1.3658278e+01 5.6813086e+00 - -1.6799417e+01 -1.3629871e+01 6.0746720e+00 - -1.6788552e+01 -1.3620534e+01 6.4775420e+00 - -1.6740931e+01 -1.3582783e+01 6.8711739e+00 - -1.6431663e+01 -1.3338821e+01 7.1707174e+00 - -1.6832693e+01 -1.3654637e+01 7.7357461e+00 - -1.6805015e+01 -1.3632829e+01 8.1476090e+00 - -1.6934910e+01 -1.3735330e+01 8.6317570e+00 - -1.6931323e+01 -1.3732029e+01 9.0658076e+00 - -1.6913046e+01 -1.3717655e+01 9.4983202e+00 - -1.6895793e+01 -1.3703951e+01 9.9362789e+00 - -1.6864851e+01 -1.3679144e+01 1.0372103e+01 - -1.6834934e+01 -1.3655007e+01 1.0813374e+01 - -1.6811368e+01 -1.3637014e+01 1.1264599e+01 - -1.6781379e+01 -1.3612296e+01 1.1717655e+01 - -9.1827544e+00 -7.6268465e+00 7.2736394e+00 - -6.6668812e+00 -5.6450564e+00 5.8459300e+00 - -6.7238960e+00 -5.6895819e+00 6.0916783e+00 - -6.7000692e+00 -5.6703185e+00 6.2862223e+00 - -6.4852899e+00 -5.5012048e+00 6.3373294e+00 - -7.1907250e+00 -6.0570713e+00 7.1112191e+00 - -7.2045989e+00 -6.0678006e+00 7.3628436e+00 - -6.8229683e+00 -5.7668978e+00 7.2814657e+00 - -6.9679773e+00 -5.8812705e+00 7.6496487e+00 - -6.9514306e+00 -5.8685661e+00 7.8850111e+00 - -6.7617965e+00 -5.7188508e+00 7.9592574e+00 - -6.5291813e+00 -5.5350680e+00 7.9840995e+00 - -6.4507921e+00 -5.4739847e+00 8.1580213e+00 - -5.9068500e+00 -5.0443927e+00 7.8359056e+00 - -6.3630242e+00 -5.4037980e+00 8.5870514e+00 - -8.0577681e+00 -6.7382413e+00 1.0798272e+01 - -7.9906112e+00 -6.6857306e+00 1.1068604e+01 - -7.7159168e+00 -6.4685986e+00 1.1089038e+01 - -7.5544440e+00 -6.3413674e+00 1.1241763e+01 - -7.0463287e+00 -5.9418362e+00 1.0937271e+01 - -2.9574845e+00 -2.7208760e+00 7.0497790e+00 - -2.8877162e+00 -2.6659359e+00 7.1501660e+00 - -2.8074708e+00 -2.6024831e+00 7.2327469e+00 - -1.7187112e+00 -1.7460596e+00 5.3433104e+00 - -1.7181019e+00 -1.7448008e+00 5.5106510e+00 - -1.6558226e+00 -1.6949953e+00 5.5591731e+00 - -1.8129483e+00 -1.8195492e+00 6.0912345e+00 - -1.6096802e+00 -1.6589597e+00 5.8357544e+00 - -1.5756324e+00 -1.6327140e+00 5.9612061e+00 - -1.5216831e+00 -1.5898209e+00 6.0421601e+00 - -1.9766643e+00 -1.9476435e+00 7.4522334e+00 - -1.5555670e+00 -1.6162172e+00 6.6000576e+00 - -1.5619622e+00 -1.6208625e+00 6.8822740e+00 - -1.2527528e+00 -1.3782645e+00 6.2461309e+00 - -1.6078731e+00 -1.6572398e+00 7.6283695e+00 - -1.2321527e+00 -1.3614052e+00 6.7314719e+00 - -1.1021662e+00 -1.2589035e+00 6.5905467e+00 - -1.3078509e+00 -1.4197653e+00 7.6650653e+00 - -1.0407449e+00 -1.2101946e+00 7.0195974e+00 - -9.1603919e-01 -1.1122867e+00 6.8807337e+00 - -8.8568952e-01 -1.0875720e+00 7.1323393e+00 - -7.8900681e-01 -1.0115588e+00 7.1041635e+00 - -7.0686242e-01 -9.4745794e-01 7.1415451e+00 - -6.0814946e-01 -8.6974726e-01 7.0894436e+00 - -4.6613163e-01 -7.5723004e-01 6.7610195e+00 - -3.7380740e-01 -6.8492971e-01 6.6932047e+00 - -3.0511745e-01 -6.3056964e-01 6.7806108e+00 - -2.2615397e-01 -5.6880853e-01 6.8074142e+00 - -1.2165499e-01 -4.8637799e-01 6.5949468e+00 - -4.4834363e-02 -4.2618268e-01 6.6078234e+00 - 3.4090712e-02 -3.6266556e-01 6.5891845e+00 - 1.0989384e-01 -3.0359573e-01 6.6185431e+00 - 1.7478734e-01 -2.5258329e-01 6.8357978e+00 - 2.5187922e-01 -1.9176755e-01 6.9220326e+00 - 3.3667784e-01 -1.2437831e-01 6.7866227e+00 - 4.1748396e-01 -6.1903391e-02 6.7493005e+00 - -1.6912800e+00 -1.6239843e+00 -9.4623059e-01 - -1.7710001e+00 -1.6832395e+00 -9.4371665e-01 - -1.8580264e+00 -1.7471993e+00 -9.4382913e-01 - -1.9461516e+00 -1.8129348e+00 -9.4064327e-01 - -2.0342577e+00 -1.8785176e+00 -9.3436124e-01 - -2.1370461e+00 -1.9545852e+00 -9.3488052e-01 - -2.2481898e+00 -2.0362199e+00 -9.3647534e-01 - -2.3804486e+00 -2.1351328e+00 -9.4810110e-01 - -2.4926561e+00 -2.2182624e+00 -9.4070462e-01 - -2.6205907e+00 -2.3127050e+00 -9.3785943e-01 - -2.7484957e+00 -2.4069111e+00 -9.3022016e-01 - -2.8921801e+00 -2.5133630e+00 -9.2578424e-01 - -3.0506395e+00 -2.6320719e+00 -9.2355608e-01 - -3.1963090e+00 -2.7388283e+00 -9.0747856e-01 - -3.3641229e+00 -2.8635679e+00 -8.9668506e-01 - -3.5486952e+00 -3.0003400e+00 -8.8599554e-01 - -3.7332226e+00 -3.1367525e+00 -8.6801504e-01 - -3.9493007e+00 -3.2975926e+00 -8.5514283e-01 - -4.1967974e+00 -3.4807727e+00 -8.4558037e-01 - -4.4610844e+00 -3.6767557e+00 -8.3147802e-01 - -4.7641955e+00 -3.9016097e+00 -8.1981693e-01 - -5.1239017e+00 -4.1674201e+00 -8.1299508e-01 - -5.5077878e+00 -4.4524363e+00 -7.9816806e-01 - -6.0018368e+00 -4.8187714e+00 -7.9757305e-01 - -6.5618875e+00 -5.2330266e+00 -7.9190398e-01 - -7.0516038e+00 -5.5963698e+00 -7.4602723e-01 - -7.5664494e+00 -5.9784691e+00 -6.8425188e-01 - -5.7856927e+00 -4.6573180e+00 -1.7238890e-01 - -5.8167472e+00 -4.6808742e+00 -3.8271475e-02 - -9.4703627e+00 -7.3889750e+00 -4.1909492e-01 - -9.4968594e+00 -7.4077410e+00 -2.0324078e-01 - -1.0224402e+01 -7.9482869e+00 -5.6142634e-02 - -1.1216129e+01 -8.6829696e+00 1.0196246e-01 - -1.2800457e+01 -9.8567986e+00 2.7026921e-01 - -1.5314037e+01 -1.1719904e+01 4.7621021e-01 - -1.8147148e+01 -1.3819262e+01 7.8759081e-01 - -1.8243344e+01 -1.3890569e+01 1.1935977e+00 - -1.9154404e+01 -1.4565132e+01 1.6300869e+00 - -1.8684186e+01 -1.4216456e+01 2.0323057e+00 - -1.8338808e+01 -1.3960064e+01 2.4240278e+00 - -1.9109147e+01 -1.4530324e+01 2.9101719e+00 - -1.9150721e+01 -1.4561399e+01 3.3443948e+00 - -1.9059146e+01 -1.4493965e+01 3.7630242e+00 - -1.9177179e+01 -1.4580802e+01 4.2134857e+00 - -1.9168419e+01 -1.4574792e+01 4.6477713e+00 - -1.9146960e+01 -1.4557565e+01 5.0810246e+00 - -1.9118271e+01 -1.4536752e+01 5.5144570e+00 - -1.9098966e+01 -1.4522202e+01 5.9517605e+00 - -1.9057693e+01 -1.4492112e+01 6.3853583e+00 - -1.8760674e+01 -1.4271550e+01 6.7441031e+00 - -1.8708852e+01 -1.4232370e+01 7.1715806e+00 - -1.8038899e+01 -1.3735490e+01 7.3877369e+00 - -1.8763409e+01 -1.4271698e+01 8.0899873e+00 - -1.8683371e+01 -1.4213214e+01 8.5163384e+00 - -1.9055717e+01 -1.4488146e+01 9.1315379e+00 - -1.9021691e+01 -1.4463320e+01 9.5916725e+00 - -1.9004351e+01 -1.4449950e+01 1.0063389e+01 - -1.8971324e+01 -1.4425588e+01 1.0533164e+01 - -1.8953917e+01 -1.4411681e+01 1.1015767e+01 - -8.2863251e+00 -6.5079907e+00 5.7485086e+00 - -1.8529711e+01 -1.4097401e+01 1.1780011e+01 - -8.4376792e+00 -6.6209345e+00 6.2991854e+00 - -9.5411652e+00 -7.4381687e+00 7.2235917e+00 - -6.6086181e+00 -5.2655964e+00 5.5999725e+00 - -6.6068909e+00 -5.2639564e+00 5.7965235e+00 - -6.9086659e+00 -5.4879323e+00 6.2109298e+00 - -6.6620240e+00 -5.3045770e+00 6.2442168e+00 - -6.5117223e+00 -5.1934675e+00 6.3415362e+00 - -6.5852271e+00 -5.2468493e+00 6.6110517e+00 - -6.4182061e+00 -5.1235034e+00 6.6923454e+00 - -6.4833352e+00 -5.1711555e+00 6.9662324e+00 - -6.3790918e+00 -5.0945923e+00 7.0995821e+00 - -6.9251983e+00 -5.4987175e+00 7.8305607e+00 - -6.6943210e+00 -5.3274897e+00 7.8630415e+00 - -6.3203011e+00 -5.0510461e+00 7.7444697e+00 - -6.1009654e+00 -4.8877695e+00 7.7643978e+00 - -6.5182685e+00 -5.1975139e+00 8.4519789e+00 - -6.4191063e+00 -5.1234342e+00 8.6099126e+00 - -6.1862669e+00 -4.9515701e+00 8.6172188e+00 - -6.0035304e+00 -4.8154575e+00 8.6717536e+00 - -7.2425950e+00 -5.7331191e+00 1.0458207e+01 - -5.9985412e+00 -4.8115605e+00 9.2204075e+00 - -5.8983587e+00 -4.7373638e+00 9.3819336e+00 - -7.0678516e+00 -5.6032043e+00 1.1266326e+01 - -4.6542103e+00 -3.8152207e+00 1.0678731e+01 - -4.4924337e+00 -3.6946307e+00 1.0738566e+01 - -2.0346081e+00 -1.8759447e+00 6.1402400e+00 - -1.8724327e+00 -1.7550477e+00 6.0049169e+00 - -1.6916162e+00 -1.6210841e+00 5.8120643e+00 - -1.6232977e+00 -1.5707231e+00 5.8589197e+00 - -2.2094669e+00 -2.0041606e+00 7.4650689e+00 - -2.0961904e+00 -1.9205248e+00 7.4691551e+00 - -1.9672689e+00 -1.8241699e+00 7.4252589e+00 - -1.8966424e+00 -1.7719559e+00 7.5323832e+00 - -1.2909686e+00 -1.3242246e+00 6.1164441e+00 - -1.2288248e+00 -1.2775644e+00 6.1822433e+00 - -1.6576264e+00 -1.5945287e+00 7.8003988e+00 - -1.1834683e+00 -1.2449297e+00 6.5912604e+00 - -1.1212220e+00 -1.1979658e+00 6.6834766e+00 - -1.3200514e+00 -1.3445315e+00 7.7512403e+00 - -1.0361031e+00 -1.1349370e+00 7.0459936e+00 - -9.2312026e-01 -1.0515848e+00 6.9632885e+00 - -8.6384050e-01 -1.0062793e+00 7.0992587e+00 - -7.7364191e-01 -9.4004885e-01 7.1085511e+00 - -6.7516531e-01 -8.6680563e-01 7.0671844e+00 - -6.0350820e-01 -8.1387689e-01 7.1697615e+00 - -4.3312464e-01 -6.8785727e-01 6.6833024e+00 - -3.4722041e-01 -6.2482735e-01 6.6633428e+00 - -2.8482552e-01 -5.7822343e-01 6.8090418e+00 - -2.0498985e-01 -5.1856103e-01 6.8350423e+00 - -9.5690543e-02 -4.3795509e-01 6.5916970e+00 - -1.7997540e-02 -3.8037262e-01 6.6136081e+00 - 6.2737046e-02 -3.2001653e-01 6.5941127e+00 - 1.4240379e-01 -2.6170405e-01 6.5927470e+00 - 2.0829645e-01 -2.1332274e-01 6.8591858e+00 - 2.9018128e-01 -1.5129607e-01 6.8545193e+00 - 3.7386620e-01 -9.0442861e-02 6.8082482e+00 - 4.5628950e-01 -2.9571453e-02 6.6800830e+00 - -1.7165546e+00 -1.5441061e+00 -9.6413224e-01 - -1.7782370e+00 -1.5875952e+00 -9.4538623e-01 - -1.8598232e+00 -1.6446568e+00 -9.4136701e-01 - -1.9497137e+00 -1.7063625e+00 -9.3997102e-01 - -2.0397050e+00 -1.7699044e+00 -9.3527987e-01 - -2.1505833e+00 -1.8468400e+00 -9.4291529e-01 - -2.2562316e+00 -1.9206191e+00 -9.4122696e-01 - -2.3702346e+00 -1.9999603e+00 -9.4051430e-01 - -2.4842117e+00 -2.0790945e+00 -9.3560682e-01 - -2.6212952e+00 -2.1753466e+00 -9.3992491e-01 - -2.7446508e+00 -2.2607037e+00 -9.3034727e-01 - -2.8900465e+00 -2.3621780e+00 -9.2874953e-01 - -3.0375244e+00 -2.4652494e+00 -9.2145324e-01 - -3.2226571e+00 -2.5938212e+00 -9.2808565e-01 - -3.3721772e+00 -2.6981695e+00 -9.0859883e-01 - -3.5520293e+00 -2.8231805e+00 -8.9771762e-01 - -3.7402680e+00 -2.9545241e+00 -8.8316819e-01 - -3.9525687e+00 -3.1025851e+00 -8.7094967e-01 - -4.1732449e+00 -3.2568899e+00 -8.5326515e-01 - -4.4430085e+00 -3.4437742e+00 -8.4438376e-01 - -4.7369245e+00 -3.6491283e+00 -8.3284021e-01 - -5.0632263e+00 -3.8765157e+00 -8.1960939e-01 - -5.4544195e+00 -4.1494396e+00 -8.1254265e-01 - -5.9031129e+00 -4.4620013e+00 -8.0506805e-01 - -6.5213543e+00 -4.8929600e+00 -8.2274608e-01 - -5.8058690e+00 -4.3943975e+00 -4.9721854e-01 - -5.8022547e+00 -4.3916890e+00 -3.5760207e-01 - -5.7965274e+00 -4.3871370e+00 -2.1869031e-01 - -5.7887466e+00 -4.3817336e+00 -8.0333841e-02 - -9.5892154e+00 -7.0304852e+00 -5.1514246e-01 - -9.8951102e+00 -7.2438888e+00 -3.3702303e-01 - -1.0149685e+01 -7.4213946e+00 -1.4116672e-01 - -1.1031946e+01 -8.0355906e+00 1.1120254e-02 - -1.2322136e+01 -8.9345558e+00 1.7416529e-01 - -1.4497180e+01 -1.0450294e+01 3.5377282e-01 - -1.8121731e+01 -1.2975819e+01 5.9394110e-01 - -1.9962376e+01 -1.4258305e+01 9.8906111e-01 - -2.0369900e+01 -1.4542637e+01 1.4329293e+00 - -2.1040896e+01 -1.5010250e+01 1.9052868e+00 - -2.0246643e+01 -1.4456135e+01 2.3140945e+00 - -1.9889582e+01 -1.4206432e+01 2.7266998e+00 - -2.1063400e+01 -1.5024443e+01 3.2876298e+00 - -2.0888323e+01 -1.4902780e+01 3.7282999e+00 - -2.1049824e+01 -1.5014374e+01 4.2130915e+00 - -2.1025253e+01 -1.4996905e+01 4.6751493e+00 - -2.1009134e+01 -1.4986801e+01 5.1402257e+00 - -2.0979320e+01 -1.4965548e+01 5.6040669e+00 - -2.0966229e+01 -1.4956047e+01 6.0734971e+00 - -2.0874752e+01 -1.4891978e+01 6.5252338e+00 - -2.0608774e+01 -1.4706505e+01 6.9273522e+00 - -2.0353291e+01 -1.4528659e+01 7.3247052e+00 - -2.0672453e+01 -1.4750525e+01 7.9017153e+00 - -2.0601856e+01 -1.4700823e+01 8.3618990e+00 - -2.0909458e+01 -1.4915098e+01 8.9643953e+00 - -2.0885827e+01 -1.4898135e+01 9.4555196e+00 - -2.0853899e+01 -1.4876581e+01 9.9481685e+00 - -8.5769883e+00 -6.3229822e+00 5.0207882e+00 - -8.4957986e+00 -6.2656937e+00 5.2024893e+00 - -8.5096964e+00 -6.2755819e+00 5.4306435e+00 - -8.6113177e+00 -6.3469652e+00 5.7074283e+00 - -7.4630461e+00 -5.5460981e+00 5.3154088e+00 - -7.7129426e+00 -5.7204336e+00 5.6614654e+00 - -7.3051181e+00 -5.4364921e+00 5.6339280e+00 - -7.1791531e+00 -5.3484202e+00 5.7628714e+00 - -7.0740571e+00 -5.2746275e+00 5.9020596e+00 - -7.0953354e+00 -5.2903305e+00 6.1253398e+00 - -7.0278257e+00 -5.2430386e+00 6.2910981e+00 - -7.0991056e+00 -5.2926520e+00 6.5584116e+00 - -6.9136930e+00 -5.1633909e+00 6.6398005e+00 - -6.8180233e+00 -5.0967194e+00 6.7857059e+00 - -6.6461878e+00 -4.9766321e+00 6.8678314e+00 - -6.6485767e+00 -4.9783161e+00 7.0934073e+00 - -6.6863699e+00 -5.0041057e+00 7.3560348e+00 - -6.5416852e+00 -4.9033698e+00 7.4598078e+00 - -6.4939482e+00 -4.8696341e+00 7.6516881e+00 - -6.4357854e+00 -4.8288278e+00 7.8370477e+00 - -6.3234940e+00 -4.7517315e+00 7.9707220e+00 - -6.4894105e+00 -4.8669818e+00 8.3967484e+00 - -6.2727538e+00 -4.7152275e+00 8.4237695e+00 - -6.0635075e+00 -4.5700436e+00 8.4508600e+00 - -5.9084255e+00 -4.4619495e+00 8.5336806e+00 - -6.3856832e+00 -4.7941559e+00 9.3826370e+00 - -6.5846661e+00 -4.9324505e+00 9.9304528e+00 - -7.0095657e+00 -5.2285042e+00 1.0803535e+01 - -5.7375547e+00 -4.3414049e+00 1.1449284e+01 - -3.6472832e+00 -2.8864855e+00 8.7724157e+00 - -3.5402187e+00 -2.8109740e+00 8.8678530e+00 - -2.5895898e+00 -2.1490809e+00 7.2557942e+00 - -2.4412960e+00 -2.0464950e+00 7.1993562e+00 - -3.3240481e+00 -2.6604402e+00 9.3944534e+00 - -3.6664201e+00 -2.8980986e+00 1.0533678e+01 - -2.2195989e+00 -1.8917682e+00 7.4941299e+00 - -2.0619552e+00 -1.7811247e+00 7.3891775e+00 - -2.0049843e+00 -1.7412908e+00 7.5333415e+00 - -1.3820963e+00 -1.3083998e+00 6.1424584e+00 - -1.3087736e+00 -1.2577186e+00 6.1816578e+00 - -1.7604439e+00 -1.5720640e+00 7.8045310e+00 - -1.2241093e+00 -1.1978066e+00 6.4607283e+00 - -1.1879903e+00 -1.1731472e+00 6.6375088e+00 - -1.1062847e+00 -1.1161630e+00 6.6724406e+00 - -1.1857473e+00 -1.1712112e+00 7.3048226e+00 - -1.0254738e+00 -1.0595378e+00 7.0623335e+00 - -9.3855621e-01 -9.9902569e-01 7.0938553e+00 - -8.8457539e-01 -9.6103745e-01 7.2779780e+00 - -7.6675399e-01 -8.7920445e-01 7.1705875e+00 - -6.7263981e-01 -8.1383161e-01 7.1673825e+00 - -5.1183560e-01 -7.0234435e-01 6.7805213e+00 - -4.0553640e-01 -6.2779073e-01 6.6539368e+00 - -3.4232111e-01 -5.8369936e-01 6.7904431e+00 - -2.7082493e-01 -5.3360382e-01 6.8963649e+00 - -1.5353330e-01 -4.5239409e-01 6.6345178e+00 - -7.0905970e-02 -3.9453393e-01 6.6276493e+00 - 1.1710261e-02 -3.3676245e-01 6.6189830e+00 - 8.8273132e-02 -2.8326851e-01 6.6783487e+00 - 1.6389351e-01 -2.3133218e-01 6.7859565e+00 - 2.4274063e-01 -1.7565836e-01 6.8919582e+00 - 3.3023430e-01 -1.1445365e-01 6.7766612e+00 - 4.1373115e-01 -5.6650430e-02 6.7293402e+00 - -1.8658850e+00 -1.5461116e+00 -9.4378768e-01 - -1.9566619e+00 -1.6058319e+00 -9.4388588e-01 - -2.0484172e+00 -1.6653340e+00 -9.4078485e-01 - -2.1548573e+00 -1.7353407e+00 -9.4488464e-01 - -2.2550108e+00 -1.8012690e+00 -9.4001305e-01 - -2.3624625e+00 -1.8718377e+00 -9.3646948e-01 - -2.4708889e+00 -1.9421587e+00 -9.2912742e-01 - -2.6033628e+00 -2.0285648e+00 -9.3155669e-01 - -2.7578190e+00 -2.1301110e+00 -9.4241492e-01 - -2.8913486e+00 -2.2179480e+00 -9.3455449e-01 - -3.0414745e+00 -2.3149746e+00 -9.2994300e-01 - -3.1990017e+00 -2.4184976e+00 -9.2376388e-01 - -3.3888610e+00 -2.5425920e+00 -9.2678328e-01 - -3.5567371e+00 -2.6520557e+00 -9.1143638e-01 - -3.7486858e+00 -2.7783205e+00 -9.0011828e-01 - -3.9415877e+00 -2.9041652e+00 -8.8150601e-01 - -4.1668572e+00 -3.0513812e+00 -8.6804763e-01 - -4.4088064e+00 -3.2094851e+00 -8.5174649e-01 - -4.6998351e+00 -3.4001044e+00 -8.4295008e-01 - -4.9918512e+00 -3.5910936e+00 -8.2261513e-01 - -5.3986545e+00 -3.8565593e+00 -8.2573215e-01 - -5.7417485e+00 -4.0809909e+00 -7.9362014e-01 - -5.7914387e+00 -4.1139607e+00 -6.6973666e-01 - -5.8066168e+00 -4.1234644e+00 -5.3631030e-01 - -5.7549753e+00 -4.0891277e+00 -3.8813760e-01 - -5.8484555e+00 -4.1499500e+00 -2.7242199e-01 - -5.8323858e+00 -4.1400257e+00 -1.3393921e-01 - -5.8319167e+00 -4.1393711e+00 8.9195144e-04 - -5.8283344e+00 -4.1369188e+00 1.3531484e-01 - -5.8320509e+00 -4.1391118e+00 2.6830984e-01 - -1.0981197e+01 -7.5068270e+00 -8.5562637e-02 - -1.1972652e+01 -8.1547944e+00 8.1980182e-02 - -1.3765281e+01 -9.3271740e+00 2.4829729e-01 - -1.6485026e+01 -1.1104337e+01 4.5958184e-01 - -2.2098280e+01 -1.4774989e+01 7.5229307e-01 - -2.2115455e+01 -1.4785629e+01 1.2237046e+00 - -2.2460157e+01 -1.5010659e+01 1.7060112e+00 - -2.2446072e+01 -1.5001767e+01 2.1845766e+00 - -2.2225419e+01 -1.4856633e+01 2.6483379e+00 - -2.2598226e+01 -1.5100604e+01 3.1593864e+00 - -2.2596624e+01 -1.5099664e+01 3.6444285e+00 - -2.2562643e+01 -1.5076745e+01 4.1266846e+00 - -2.2497412e+01 -1.5033869e+01 4.6044594e+00 - -2.2490560e+01 -1.5029095e+01 5.0922836e+00 - -2.2460795e+01 -1.5009779e+01 5.5776471e+00 - -2.2422681e+01 -1.4984955e+01 6.0628876e+00 - -2.2403286e+01 -1.4971748e+01 6.5540231e+00 - -2.2334920e+01 -1.4926896e+01 7.0349851e+00 - -2.1901789e+01 -1.4643419e+01 7.4123140e+00 - -2.3912338e+01 -1.5957055e+01 8.5282052e+00 - -2.2265262e+01 -1.4880917e+01 8.5291333e+00 - -2.4110830e+01 -1.6086705e+01 9.6945550e+00 - -7.0780928e+00 -4.9520928e+00 3.8497627e+00 - -8.4724304e+00 -5.8636775e+00 4.5808722e+00 - -7.0373727e+00 -4.9259071e+00 4.1839338e+00 - -8.4012728e+00 -5.8175339e+00 4.9701403e+00 - -8.2245739e+00 -5.7023775e+00 5.1002379e+00 - -6.7866682e+00 -4.7618332e+00 4.6011192e+00 - -7.8388707e+00 -5.4496436e+00 5.3260870e+00 - -7.0811594e+00 -4.9538628e+00 5.1222383e+00 - -7.3376690e+00 -5.1211758e+00 5.4602798e+00 - -6.8664525e+00 -4.8134778e+00 5.3823190e+00 - -7.3727952e+00 -5.1448207e+00 5.8903917e+00 - -6.9838422e+00 -4.8905287e+00 5.8488142e+00 - -6.8322471e+00 -4.7913459e+00 5.9499178e+00 - -7.2780359e+00 -5.0827592e+00 6.4671613e+00 - -7.0181613e+00 -4.9123665e+00 6.4979022e+00 - -7.0216407e+00 -4.9152432e+00 6.7183373e+00 - -6.9657018e+00 -4.8776813e+00 6.8962613e+00 - -7.1261968e+00 -4.9825724e+00 7.2547607e+00 - -6.1341328e+00 -4.3344656e+00 6.6467640e+00 - -6.0502217e+00 -4.2795409e+00 6.7842102e+00 - -6.0453042e+00 -4.2754873e+00 6.9928375e+00 - -6.3887950e+00 -4.5004250e+00 7.5390109e+00 - -6.3048344e+00 -4.4456203e+00 7.6942847e+00 - -6.2322663e+00 -4.3975746e+00 7.8611761e+00 - -6.2055379e+00 -4.3812979e+00 8.0798791e+00 - -6.3730272e+00 -4.4899479e+00 8.5157022e+00 - -6.3659225e+00 -4.4855211e+00 8.7748599e+00 - -7.1536044e+00 -4.9992054e+00 9.9746038e+00 - -6.9094786e+00 -4.8402979e+00 9.9972977e+00 - -7.2958340e+00 -5.0918825e+00 1.0802868e+01 - -7.3102939e+00 -5.1018359e+00 1.1170301e+01 - -5.9389015e+00 -4.2051777e+00 1.1382432e+01 - -5.7716241e+00 -4.0955558e+00 1.1490633e+01 - -5.5462977e+00 -3.9484006e+00 1.1496201e+01 - -5.6144170e+00 -3.9924421e+00 1.2020737e+01 - -3.7594821e+00 -2.7813025e+00 8.9763769e+00 - -4.0672760e+00 -2.9820749e+00 9.8906937e+00 - -2.5336026e+00 -1.9795767e+00 7.1419576e+00 - -2.4385634e+00 -1.9184594e+00 7.1955266e+00 - -3.9350872e+00 -2.8954971e+00 1.0743866e+01 - -3.7225004e+00 -2.7562816e+00 1.0675111e+01 - -2.1967207e+00 -1.7598745e+00 7.4511378e+00 - -2.1130283e+00 -1.7056656e+00 7.5335528e+00 - -2.0282271e+00 -1.6496021e+00 7.6142674e+00 - -1.3697659e+00 -1.2197080e+00 6.1255920e+00 - -1.2842187e+00 -1.1641726e+00 6.1360414e+00 - -1.2925776e+00 -1.1684359e+00 6.4235576e+00 - -1.2245755e+00 -1.1247302e+00 6.4975763e+00 - -1.1492868e+00 -1.0754445e+00 6.5514504e+00 - -1.1378788e+00 -1.0672290e+00 6.8315208e+00 - -1.0800684e+00 -1.0297550e+00 6.9695884e+00 - -1.0190854e+00 -9.8949110e-01 7.1070984e+00 - -9.1801140e-01 -9.2424405e-01 7.0896391e+00 - -8.4152232e-01 -8.7340278e-01 7.1762696e+00 - -7.1989980e-01 -7.9385794e-01 7.0476422e+00 - -6.1992629e-01 -7.2936827e-01 7.0136066e+00 - -5.4041537e-01 -6.7745838e-01 7.0850470e+00 - -3.9652213e-01 -5.8334851e-01 6.7518123e+00 - -3.3131257e-01 -5.4042602e-01 6.9075878e+00 - -2.3550867e-01 -4.7710852e-01 6.8449003e+00 - -1.2158169e-01 -4.0280134e-01 6.6015369e+00 - -4.2192435e-02 -3.5134788e-01 6.6434641e+00 - 4.4227188e-02 -2.9533071e-01 6.6041230e+00 - 1.2465305e-01 -2.4259905e-01 6.6326644e+00 - 1.8750471e-01 -2.0162841e-01 7.0288471e+00 - 2.8572282e-01 -1.3642486e-01 6.7446786e+00 - 3.6829915e-01 -8.2582417e-02 6.7981828e+00 - 4.5528396e-01 -2.6475460e-02 6.6200626e+00 - -1.9805881e+00 -1.5201210e+00 -9.6388578e-01 - -2.0523149e+00 -1.5640223e+00 -9.4545794e-01 - -2.1459350e+00 -1.6213210e+00 -9.4065187e-01 - -2.2551766e+00 -1.6880569e+00 -9.4289323e-01 - -2.3571341e+00 -1.7507798e+00 -9.3626628e-01 - -2.4830255e+00 -1.8276480e+00 -9.4060839e-01 - -2.5933130e+00 -1.8957361e+00 -9.3096203e-01 - -2.7285847e+00 -1.9788418e+00 -9.3093362e-01 - -2.8794582e+00 -2.0712272e+00 -9.3475658e-01 - -3.0313562e+00 -2.1642781e+00 -9.3303360e-01 - -3.1842774e+00 -2.2579847e+00 -9.2556492e-01 - -3.3611632e+00 -2.3665971e+00 -9.2422168e-01 - -3.5473770e+00 -2.4805141e+00 -9.1985586e-01 - -3.7585394e+00 -2.6091632e+00 -9.1931513e-01 - -3.9384714e+00 -2.7195554e+00 -8.9693948e-01 - -4.1517152e+00 -2.8503107e+00 -8.8076287e-01 - -4.3815840e+00 -2.9910014e+00 -8.6269193e-01 - -4.6531100e+00 -3.1575435e+00 -8.5029754e-01 - -4.9579734e+00 -3.3451698e+00 -8.3845954e-01 - -5.3054632e+00 -3.5583556e+00 -8.2760070e-01 - -5.7049247e+00 -3.8025434e+00 -8.1749498e-01 - -5.7804800e+00 -3.8485012e+00 -7.0382474e-01 - -7.0223309e+00 -4.6097256e+00 -8.7918124e-01 - -6.9405830e+00 -4.5596240e+00 -7.0013277e-01 - -5.7635507e+00 -3.8384125e+00 -2.9862639e-01 - -8.7801787e+00 -5.6866937e+00 -7.2869876e-01 - -5.8917642e+00 -3.9169469e+00 -5.6768437e-02 - -5.8725950e+00 -3.9053332e+00 7.9108796e-02 - -5.8856729e+00 -3.9130969e+00 2.0973303e-01 - -1.0966477e+01 -7.0270610e+00 -1.8260987e-01 - -1.1832658e+01 -7.5583569e+00 -1.7890967e-02 - -1.3208569e+01 -8.4007427e+00 1.5010114e-01 - -1.5851816e+01 -1.0021005e+01 3.2163491e-01 - -1.4955846e+01 -9.4717578e+00 6.7538744e-01 - -1.5257560e+01 -9.6564814e+00 9.9163848e-01 - -2.5962027e+01 -1.6216298e+01 1.5274795e+00 - -2.6282747e+01 -1.6413086e+01 2.0824366e+00 - -2.6160224e+01 -1.6337389e+01 2.6242200e+00 - -2.7034219e+01 -1.6872721e+01 3.2431461e+00 - -2.7081235e+01 -1.6901639e+01 3.8150661e+00 - -2.7756380e+01 -1.7314909e+01 4.4675941e+00 - -2.7726324e+01 -1.7295848e+01 5.0490869e+00 - -2.7703603e+01 -1.7282237e+01 5.6330966e+00 - -2.7655852e+01 -1.7252221e+01 6.2143403e+00 - -2.6563370e+01 -1.6582401e+01 7.1541638e+00 - -2.6192405e+01 -1.6355040e+01 7.6386729e+00 - -2.6595946e+01 -1.6602685e+01 8.3210031e+00 - -2.6334112e+01 -1.6441692e+01 8.8309862e+00 - -2.7531590e+01 -1.7175178e+01 9.7923916e+00 - -7.5262696e+00 -4.9167000e+00 3.6942904e+00 - -7.3791798e+00 -4.8270447e+00 3.8202218e+00 - -7.4492471e+00 -4.8698479e+00 4.0242142e+00 - -7.3790062e+00 -4.8263884e+00 4.1767281e+00 - -7.1217816e+00 -4.6688337e+00 4.2486687e+00 - -6.9768316e+00 -4.5807195e+00 4.3611726e+00 - -6.9263430e+00 -4.5491063e+00 4.5136920e+00 - -6.9433713e+00 -4.5588688e+00 4.7002080e+00 - -7.1204213e+00 -4.6679774e+00 4.9739126e+00 - -7.2153134e+00 -4.7255556e+00 5.2137302e+00 - -7.0443612e+00 -4.6207791e+00 5.3096324e+00 - -7.0925701e+00 -4.6509799e+00 5.5313911e+00 - -7.1749464e+00 -4.7008595e+00 5.7798629e+00 - -6.8410522e+00 -4.4969954e+00 5.7667443e+00 - -6.9317097e+00 -4.5518509e+00 6.0261257e+00 - -6.8780783e+00 -4.5187176e+00 6.1928684e+00 - -6.8140782e+00 -4.4794860e+00 6.3536392e+00 - -6.3473599e+00 -4.1929069e+00 6.2085639e+00 - -6.1557590e+00 -4.0756100e+00 6.2585654e+00 - -5.8666870e+00 -3.8992949e+00 6.2219515e+00 - -6.1326530e+00 -4.0618058e+00 6.6451196e+00 - -6.1091625e+00 -4.0478080e+00 6.8342184e+00 - -6.1893579e+00 -4.0968495e+00 7.1223844e+00 - -6.5080791e+00 -4.2921964e+00 7.6482222e+00 - -6.3952387e+00 -4.2223609e+00 7.7777456e+00 - -6.1973970e+00 -4.1008362e+00 7.8194902e+00 - -6.1385545e+00 -4.0652131e+00 8.0022978e+00 - -6.2828667e+00 -4.1536031e+00 8.4097448e+00 - -6.8106018e+00 -4.4762028e+00 9.2695525e+00 - -7.2407700e+00 -4.7395347e+00 1.0068063e+01 - -6.9267882e+00 -4.5477646e+00 1.0009407e+01 - -7.1121893e+00 -4.6605583e+00 1.0562089e+01 - -6.9173626e+00 -4.5415954e+00 1.0649535e+01 - -7.2538775e+00 -4.7473625e+00 1.1448632e+01 - -6.2304393e+00 -4.1202489e+00 1.0395828e+01 - -5.7507764e+00 -3.8263699e+00 1.0716087e+01 - -5.8116531e+00 -3.8631197e+00 1.1174138e+01 - -5.6831758e+00 -3.7852712e+00 1.1342618e+01 - -5.5711436e+00 -3.7159193e+00 1.1542157e+01 - -5.4187894e+00 -3.6223173e+00 1.1673168e+01 - -4.2324464e+00 -2.8959838e+00 9.8681427e+00 - -2.6527642e+00 -1.9291308e+00 7.1443098e+00 - -2.5144507e+00 -1.8437655e+00 7.1127124e+00 - -2.4103037e+00 -1.7801356e+00 7.1471779e+00 - -3.9256952e+00 -2.7074118e+00 1.0745443e+01 - -3.7993692e+00 -2.6301648e+00 1.0879023e+01 - -3.6441035e+00 -2.5348288e+00 1.0947554e+01 - -3.4950994e+00 -2.4444023e+00 1.1030783e+01 - -2.0082904e+00 -1.5344242e+00 7.5946458e+00 - -1.3360357e+00 -1.1225933e+00 6.0620210e+00 - -1.3856357e+00 -1.1519631e+00 6.4602650e+00 - -1.3033989e+00 -1.1028967e+00 6.4979871e+00 - -1.2272270e+00 -1.0556210e+00 6.5528560e+00 - -1.1860600e+00 -1.0302914e+00 6.7290717e+00 - -1.0430388e+00 -9.4233367e-01 6.5535400e+00 - -1.0850301e+00 -9.6767455e-01 7.0622748e+00 - -9.8213544e-01 -9.0549985e-01 7.0457569e+00 - -9.1916883e-01 -8.6597448e-01 7.1910005e+00 - -8.5932500e-01 -8.3038718e-01 7.3743044e+00 - -7.0315537e-01 -7.3461817e-01 7.0893718e+00 - -5.7880571e-01 -6.5790701e-01 6.9272258e+00 - -5.3414734e-01 -6.3033521e-01 7.2133450e+00 - -3.9978659e-01 -5.4883594e-01 6.9578863e+00 - -2.8078207e-01 -4.7516953e-01 6.7481646e+00 - -1.8934141e-01 -4.1921320e-01 6.7137015e+00 - -8.9872829e-02 -3.5875852e-01 6.5978670e+00 - -8.6146570e-03 -3.0895994e-01 6.6289509e+00 - 7.0701422e-02 -2.6015423e-01 6.6982428e+00 - 1.4813911e-01 -2.1234808e-01 6.8258675e+00 - 2.3453979e-01 -1.6009243e-01 6.8520927e+00 - 3.2285874e-01 -1.0600285e-01 6.8166396e+00 - 4.1184707e-01 -5.0990869e-02 6.6592866e+00 - -2.1559816e+00 -1.5219558e+00 -9.5159889e-01 - -2.2441431e+00 -1.5722086e+00 -9.3966481e-01 - -2.3635078e+00 -1.6405014e+00 -9.4517109e-01 - -2.4755865e+00 -1.7047664e+00 -9.4150941e-01 - -2.5876412e+00 -1.7688393e+00 -9.3395255e-01 - -2.7173628e+00 -1.8431368e+00 -9.3158943e-01 - -2.8543740e+00 -1.9220058e+00 -9.2915606e-01 - -3.0079839e+00 -2.0100841e+00 -9.3037114e-01 - -3.1791845e+00 -2.1072619e+00 -9.3423272e-01 - -3.3431525e+00 -2.2013546e+00 -9.2777816e-01 - -3.5403310e+00 -2.3139694e+00 -9.3071791e-01 - -3.7302721e+00 -2.4234598e+00 -9.2254249e-01 - -3.9617179e+00 -2.5560373e+00 -9.2478660e-01 - -4.1286972e+00 -2.6516291e+00 -8.9160666e-01 - -4.3715269e+00 -2.7908966e+00 -8.8083494e-01 - -4.6143000e+00 -2.9297108e+00 -8.6087456e-01 - -4.9162749e+00 -3.1025924e+00 -8.5158394e-01 - -5.2359073e+00 -3.2861388e+00 -8.3615146e-01 - -5.6074022e+00 -3.4987821e+00 -8.2336897e-01 - -6.0806768e+00 -3.7701488e+00 -8.2418262e-01 - -7.0140061e+00 -4.3044996e+00 -9.2362505e-01 - -6.9230910e+00 -4.2519265e+00 -7.4425446e-01 - -6.9142587e+00 -4.2466740e+00 -5.8747432e-01 - -5.8416322e+00 -3.6330209e+00 -9.5513570e-02 - -5.8235398e+00 -3.6224915e+00 3.7420092e-02 - -5.8282822e+00 -3.6248458e+00 1.6592382e-01 - -1.1530885e+01 -6.8925340e+00 -3.4145386e-01 - -1.1765723e+01 -7.0267796e+00 -1.1901775e-01 - -1.2872533e+01 -7.6606675e+00 5.0344840e-02 - -1.5060797e+01 -8.9138593e+00 2.0877282e-01 - -1.4992334e+01 -8.8752334e+00 5.2423682e-01 - -1.4971564e+01 -8.8629896e+00 8.3619031e-01 - -1.5170815e+01 -8.9768275e+00 1.1492133e+00 - -1.5330640e+01 -9.0686216e+00 1.4693159e+00 - -2.9269720e+01 -1.7054377e+01 2.4818393e+00 - -2.9587359e+01 -1.7235826e+01 3.7124549e+00 - -2.9541762e+01 -1.7209525e+01 4.3172240e+00 - -2.9496105e+01 -1.7182223e+01 4.9220433e+00 - -2.9423548e+01 -1.7140669e+01 5.5233905e+00 - -2.9350991e+01 -1.7099120e+01 6.1246377e+00 - -2.9293993e+01 -1.7066501e+01 6.7291248e+00 - -2.9194424e+01 -1.7008766e+01 7.3256022e+00 - -2.8617857e+01 -1.6678455e+01 7.8104720e+00 - -2.9306476e+01 -1.7073161e+01 8.5981351e+00 - -3.2064598e+01 -1.8652871e+01 9.9908855e+00 - -3.1990719e+01 -1.8609814e+01 1.0664439e+01 - -7.8135199e+00 -4.7610216e+00 3.6520394e+00 - -7.6055778e+00 -4.6417310e+00 3.7620159e+00 - -7.3478826e+00 -4.4936102e+00 3.8465339e+00 - -7.2623131e+00 -4.4446009e+00 3.9880663e+00 - -7.3954759e+00 -4.5214697e+00 4.2170569e+00 - -7.3617264e+00 -4.5022506e+00 4.3824058e+00 - -7.2367564e+00 -4.4303812e+00 4.5070483e+00 - -7.1822598e+00 -4.3988867e+00 4.6620518e+00 - -7.3246784e+00 -4.4809978e+00 4.9155880e+00 - -7.1147554e+00 -4.3604040e+00 4.9936487e+00 - -7.0840944e+00 -4.3427855e+00 5.1634010e+00 - -7.0430560e+00 -4.3189998e+00 5.3285799e+00 - -6.9305563e+00 -4.2544645e+00 5.4519590e+00 - -6.8843588e+00 -4.2280887e+00 5.6149758e+00 - -6.9645102e+00 -4.2741999e+00 5.8612455e+00 - -7.1895637e+00 -4.4025847e+00 6.2134926e+00 - -7.1164093e+00 -4.3609851e+00 6.3724882e+00 - -6.3754544e+00 -3.9367024e+00 6.0417088e+00 - -6.5083160e+00 -4.0121952e+00 6.3391141e+00 - -6.2043243e+00 -3.8377246e+00 6.3037005e+00 - -6.0173405e+00 -3.7303329e+00 6.3506147e+00 - -6.1026204e+00 -3.7798211e+00 6.6236153e+00 - -6.1950849e+00 -3.8330432e+00 6.9136652e+00 - -6.1995600e+00 -3.8358398e+00 7.1345030e+00 - -6.1398259e+00 -3.8011295e+00 7.3000288e+00 - -6.4587222e+00 -3.9836494e+00 7.8415550e+00 - -6.3802960e+00 -3.9380439e+00 8.0068285e+00 - -6.4074006e+00 -3.9536309e+00 8.2859078e+00 - -6.2711149e+00 -3.8761327e+00 8.3962855e+00 - -6.7964797e+00 -4.1759664e+00 9.2528530e+00 - -6.9743594e+00 -4.2776942e+00 9.7547806e+00 - -6.7510885e+00 -4.1497592e+00 9.7949506e+00 - -6.5754061e+00 -4.0494305e+00 9.8878392e+00 - -6.7107826e+00 -4.1270983e+00 1.0380608e+01 - -6.1723957e+00 -3.8188298e+00 9.9921221e+00 - -6.1238086e+00 -3.7909790e+00 1.0248266e+01 - -6.3282272e+00 -3.9076849e+00 1.0880756e+01 - -5.9294706e+00 -3.6797457e+00 1.0643776e+01 - -5.7310189e+00 -3.5649940e+00 1.0691257e+01 - -5.6792396e+00 -3.5352289e+00 1.0969615e+01 - -5.3746076e+00 -3.3616148e+00 1.0837020e+01 - -5.0906287e+00 -3.1990081e+00 1.0720214e+01 - -5.4277332e+00 -3.3913501e+00 1.1707987e+01 - -4.8786861e+00 -3.0775337e+00 1.1100992e+01 - -2.6397311e+00 -1.7960579e+00 7.1332597e+00 - -2.4955548e+00 -1.7125794e+00 7.0910059e+00 - -4.5827391e+00 -2.9076082e+00 1.1771623e+01 - -2.5216681e+00 -1.7279809e+00 7.6777494e+00 - -3.8153296e+00 -2.4677752e+00 1.0958419e+01 - -3.6347256e+00 -2.3646916e+00 1.0971443e+01 - -2.2324140e+00 -1.5620719e+00 7.8961616e+00 - -2.0512600e+00 -1.4579886e+00 7.7483345e+00 - -1.4599231e+00 -1.1203557e+00 6.4408418e+00 - -1.3839188e+00 -1.0759674e+00 6.4979568e+00 - -1.3121029e+00 -1.0354796e+00 6.5724111e+00 - -1.2361175e+00 -9.9175812e-01 6.6362674e+00 - -1.1590824e+00 -9.4716913e-01 6.6986726e+00 - -1.3394827e+00 -1.0508161e+00 7.7038310e+00 - -1.0614237e+00 -8.9202311e-01 7.0590982e+00 - -1.0283207e+00 -8.7251086e-01 7.3304675e+00 - -9.2967727e-01 -8.1628651e-01 7.3505140e+00 - -8.0036681e-01 -7.4218048e-01 7.2227082e+00 - -6.7419183e-01 -6.6953545e-01 7.0818776e+00 - -5.7565303e-01 -6.1311546e-01 7.0653700e+00 - -4.8018211e-01 -5.5864772e-01 7.0663992e+00 - -3.5529917e-01 -4.8725910e-01 6.8583555e+00 - -2.5486903e-01 -4.2973608e-01 6.7856126e+00 - -1.4541568e-01 -3.6676661e-01 6.6114207e+00 - -6.1279330e-02 -3.1859466e-01 6.6334558e+00 - 2.6835933e-02 -2.6871143e-01 6.6140310e+00 - 1.0509196e-01 -2.2291847e-01 6.7223260e+00 - 1.7268989e-01 -1.8472013e-01 7.0886792e+00 - 2.7939746e-01 -1.2349281e-01 6.7146434e+00 - 3.6653305e-01 -7.3401323e-02 6.6982181e+00 - 4.5340725e-01 -2.3851443e-02 6.6100325e+00 - -2.2739233e+00 -1.4835088e+00 -9.6718516e-01 - -2.3421042e+00 -1.5190591e+00 -9.3787719e-01 - -2.4550127e+00 -1.5803713e+00 -9.3635852e-01 - -2.5771530e+00 -1.6451865e+00 -9.3581155e-01 - -2.7003259e+00 -1.7107312e+00 -9.3101703e-01 - -2.8317882e+00 -1.7808017e+00 -9.2644871e-01 - -2.9871093e+00 -1.8639024e+00 -9.3050197e-01 - -3.1527667e+00 -1.9523261e+00 -9.3312750e-01 - -3.3184472e+00 -2.0414512e+00 -9.2971087e-01 - -3.5017142e+00 -2.1396413e+00 -9.2824161e-01 - -3.7108713e+00 -2.2515356e+00 -9.3124308e-01 - -3.9044197e+00 -2.3546103e+00 -9.1945706e-01 - -4.1653354e+00 -2.4937405e+00 -9.2790429e-01 - -4.3526565e+00 -2.5942430e+00 -8.9716001e-01 - -4.5824100e+00 -2.7166915e+00 -8.7518371e-01 - -4.8380873e+00 -2.8536293e+00 -8.5333389e-01 - -5.1372281e+00 -3.0132329e+00 -8.3580475e-01 - -5.4457222e+00 -3.1788573e+00 -8.0951051e-01 - -5.8826233e+00 -3.4121844e+00 -8.0801968e-01 - -6.7868154e+00 -3.8953224e+00 -9.1126955e-01 - -7.3583108e+00 -4.2011847e+00 -8.9806084e-01 - -6.9702672e+00 -3.9936572e+00 -6.5057229e-01 - -5.6840114e+00 -3.3056497e+00 -2.3949162e-01 - -5.6318156e+00 -3.2780154e+00 -1.0440828e-01 - -5.7090766e+00 -3.3189513e+00 7.3226657e-03 - -5.7936185e+00 -3.3643897e+00 1.2052213e-01 - -1.1989178e+01 -6.6768897e+00 -4.9504202e-01 - -1.2229684e+01 -6.8056301e+00 -2.6963853e-01 - -1.2687609e+01 -7.0500449e+00 -5.2605969e-02 - -1.4181097e+01 -7.8490006e+00 1.1977676e-01 - -1.5285007e+01 -8.4390936e+00 3.6655931e-01 - -1.5124495e+01 -8.3528465e+00 6.8241012e-01 - -1.5039614e+01 -8.3074929e+00 9.9173388e-01 - -1.5328492e+01 -8.4620547e+00 1.3048159e+00 - -3.9434753e+01 -2.1349483e+01 2.5595133e+00 - -3.6608902e+01 -1.9838534e+01 3.9221315e+00 - -3.2718922e+01 -1.7758850e+01 4.2773265e+00 - -3.5891932e+01 -1.9454419e+01 5.3171074e+00 - -3.5916448e+01 -1.9467672e+01 6.0499154e+00 - -3.3748689e+01 -1.8307561e+01 7.8282885e+00 - -3.4244032e+01 -1.8572409e+01 8.6381897e+00 - -3.1516694e+01 -1.7114236e+01 8.6981086e+00 - -3.1204137e+01 -1.6946658e+01 9.2811446e+00 - -3.1123352e+01 -1.6903652e+01 9.9217178e+00 - -2.9797191e+01 -1.6194205e+01 1.0187016e+01 - -3.1227540e+01 -1.6959402e+01 1.1297003e+01 - -9.5220557e+00 -5.3565128e+00 4.4681177e+00 - -9.4923448e+00 -5.3399970e+00 4.6750761e+00 - -9.5423198e+00 -5.3672060e+00 4.9145201e+00 - -7.7817456e+00 -4.4252349e+00 4.4124381e+00 - -7.6695171e+00 -4.3659620e+00 4.5506965e+00 - -7.3194989e+00 -4.1791591e+00 4.5771679e+00 - -8.0269734e+00 -4.5568902e+00 5.0981820e+00 - -7.0763788e+00 -4.0484025e+00 4.8193256e+00 - -7.2235725e+00 -4.1269397e+00 5.0784220e+00 - -7.1919735e+00 -4.1103786e+00 5.2482207e+00 - -7.0859137e+00 -4.0532099e+00 5.3770091e+00 - -7.4148881e+00 -4.2286763e+00 5.7656614e+00 - -7.0391930e+00 -4.0283265e+00 5.7326338e+00 - -7.3929086e+00 -4.2173836e+00 6.1608570e+00 - -7.3726090e+00 -4.2068376e+00 6.3573546e+00 - -6.6984208e+00 -3.8463870e+00 6.0940149e+00 - -6.7514500e+00 -3.8744067e+00 6.3336178e+00 - -6.0691743e+00 -3.5100131e+00 6.0181696e+00 - -6.1139351e+00 -3.5331605e+00 6.2447655e+00 - -6.0823275e+00 -3.5165304e+00 6.4159625e+00 - -6.4554088e+00 -3.7158922e+00 6.9362263e+00 - -6.3628209e+00 -3.6665407e+00 7.0729927e+00 - -6.1112435e+00 -3.5317657e+00 7.0631896e+00 - -6.0847277e+00 -3.5177028e+00 7.2572727e+00 - -6.7330990e+00 -3.8639161e+00 8.1209924e+00 - -6.5104459e+00 -3.7455597e+00 8.1493235e+00 - -6.2835805e+00 -3.6231107e+00 8.1642104e+00 - -6.1403817e+00 -3.5466268e+00 8.2625808e+00 - -6.1591396e+00 -3.5567157e+00 8.5413373e+00 - -6.0726599e+00 -3.5105329e+00 8.7078342e+00 - -6.0490613e+00 -3.4977343e+00 8.9536613e+00 - -6.3275219e+00 -3.6460275e+00 9.5871655e+00 - -6.4080062e+00 -3.6898570e+00 1.0000030e+01 - -6.2172726e+00 -3.5877429e+00 1.0066405e+01 - -6.0770455e+00 -3.5124427e+00 1.0197893e+01 - -5.9996833e+00 -3.4709128e+00 1.0421145e+01 - -6.0932953e+00 -3.5203246e+00 1.0907557e+01 - -5.8459344e+00 -3.3886435e+00 1.0890924e+01 - -5.5615110e+00 -3.2367108e+00 1.0802075e+01 - -5.3306511e+00 -3.1129415e+00 1.0787837e+01 - -5.5394408e+00 -3.2249079e+00 1.1530556e+01 - -2.7191685e+00 -1.7189182e+00 6.8329786e+00 - -2.6885406e+00 -1.7020799e+00 7.0071750e+00 - -2.6126547e+00 -1.6617322e+00 7.1039387e+00 - -2.5315970e+00 -1.6181768e+00 7.1908003e+00 - -2.3857556e+00 -1.5400454e+00 7.1438939e+00 - -2.5195131e+00 -1.6112651e+00 7.7078229e+00 - -2.2729526e+00 -1.4792754e+00 7.4340624e+00 - -3.5918355e+00 -2.1837216e+00 1.0931113e+01 - -2.1847076e+00 -1.4321804e+00 7.8228777e+00 - -2.0512327e+00 -1.3610694e+00 7.8013247e+00 - -1.4530287e+00 -1.0411081e+00 6.4695304e+00 - -1.3588046e+00 -9.9114587e-01 6.4793000e+00 - -1.3413966e+00 -9.8114300e-01 6.7218991e+00 - -1.1918557e+00 -9.0198483e-01 6.5588762e+00 - -1.1692815e+00 -8.8985181e-01 6.8102493e+00 - -1.1210117e+00 -8.6350506e-01 6.9953820e+00 - -1.0727458e+00 -8.3822107e-01 7.1994905e+00 - -9.9679499e-01 -7.9787017e-01 7.3165787e+00 - -9.0239460e-01 -7.4649894e-01 7.3549130e+00 - -7.5200607e-01 -6.6654188e-01 7.1282670e+00 - -6.2414715e-01 -5.9857707e-01 6.9760425e+00 - -5.3901676e-01 -5.5256153e-01 7.0366254e+00 - -4.6000468e-01 -5.1082669e-01 7.1449156e+00 - -3.1816436e-01 -4.3488413e-01 6.8271077e+00 - -2.3612282e-01 -3.9098836e-01 6.9018314e+00 - -1.0877783e-01 -3.2300458e-01 6.5879097e+00 - -2.3830142e-02 -2.7793321e-01 6.6090916e+00 - 8.2042180e-02 -2.2050091e-01 6.3595015e+00 - 1.3930265e-01 -1.9073012e-01 6.7859077e+00 - 2.2646164e-01 -1.4354609e-01 6.8321027e+00 - 3.1460689e-01 -9.6001973e-02 6.8665593e+00 - 4.0990195e-01 -4.5819056e-02 6.5793452e+00 - -2.4781169e+00 -1.4808706e+00 -9.6044792e-01 - -2.5699864e+00 -1.5265439e+00 -9.4160808e-01 - -2.6866681e+00 -1.5843131e+00 -9.3393311e-01 - -2.8198988e+00 -1.6503784e+00 -9.3165404e-01 - -2.9696718e+00 -1.7246856e+00 -9.3367223e-01 - -3.1122165e+00 -1.7959422e+00 -9.2607341e-01 - -3.2806096e+00 -1.8800539e+00 -9.2599117e-01 - -3.4655301e+00 -1.9722892e+00 -9.2780915e-01 - -3.6524671e+00 -2.0650803e+00 -9.2307924e-01 - -3.8817934e+00 -2.1789584e+00 -9.2996340e-01 - -4.0707590e+00 -2.2729180e+00 -9.1084567e-01 - -4.3610820e+00 -2.4175843e+00 -9.2514608e-01 - -4.5520085e+00 -2.5116563e+00 -8.9049155e-01 - -4.8029755e+00 -2.6369119e+00 -8.7004806e-01 - -5.0797402e+00 -2.7746185e+00 -8.4893126e-01 - -5.3502539e+00 -2.9090466e+00 -8.1479847e-01 - -5.6114048e+00 -3.0384083e+00 -7.6825770e-01 - -5.7857201e+00 -3.1252340e+00 -6.8870722e-01 - -5.5495899e+00 -3.0077859e+00 -5.0081763e-01 - -6.8703085e+00 -3.6650553e+00 -6.7841223e-01 - -5.6986303e+00 -3.0813963e+00 -2.8610735e-01 - -5.6641556e+00 -3.0649342e+00 -1.5516944e-01 - -5.6461648e+00 -3.0557319e+00 -2.8877963e-02 - -5.7150146e+00 -3.0901382e+00 8.3179831e-02 - -5.7363245e+00 -3.1009363e+00 2.0329135e-01 - -1.1300320e+01 -5.8680189e+00 -2.7526882e-01 - -1.3050841e+01 -6.7374361e+00 -1.9824759e-01 - -1.1261571e+01 -5.8482187e+00 1.9039113e-01 - -1.1254644e+01 -5.8452157e+00 4.2068452e-01 - -1.1279701e+01 -5.8574151e+00 6.4932203e-01 - -1.1319213e+01 -5.8767389e+00 8.7850033e-01 - -1.5304473e+01 -7.8585553e+00 1.1455385e+00 - -1.5567864e+01 -7.9894469e+00 1.4613006e+00 - -3.9747308e+01 -2.0012716e+01 2.9404511e+00 - -3.3866473e+01 -1.7087713e+01 3.3285661e+00 - -3.3851861e+01 -1.7080284e+01 4.0003386e+00 - -3.3674127e+01 -1.6992226e+01 4.6561132e+00 - -3.3727643e+01 -1.7018381e+01 5.3362707e+00 - -3.3921539e+01 -1.7114045e+01 6.0416492e+00 - -3.3483640e+01 -1.6896466e+01 6.6528838e+00 - -3.3327630e+01 -1.6819421e+01 7.3028278e+00 - -3.1437338e+01 -1.5878050e+01 7.5921517e+00 - -3.0855147e+01 -1.5588754e+01 8.1062436e+00 - -3.0914940e+01 -1.5617876e+01 8.7594527e+00 - -3.0187316e+01 -1.5256277e+01 9.2098072e+00 - -3.0384411e+01 -1.5354428e+01 9.9016112e+00 - -3.0810508e+01 -1.5565933e+01 1.0678216e+01 - -3.1350019e+01 -1.5833714e+01 1.1516670e+01 - -9.5740992e+00 -5.0069570e+00 4.7578743e+00 - -9.6652326e+00 -5.0529371e+00 5.0136169e+00 - -9.0559086e+00 -4.7501849e+00 4.9838077e+00 - -9.3759614e+00 -4.9088530e+00 5.3378347e+00 - -9.3804038e+00 -4.9113885e+00 5.5639659e+00 - -9.3002051e+00 -4.8707870e+00 5.7518029e+00 - -9.1261952e+00 -4.7840385e+00 5.8923295e+00 - -9.0481195e+00 -4.7453593e+00 6.0792731e+00 - -7.6286788e+00 -4.0403912e+00 5.5202005e+00 - -7.5094535e+00 -3.9809484e+00 5.6501972e+00 - -7.6634216e+00 -4.0573628e+00 5.9437732e+00 - -7.4452318e+00 -3.9487131e+00 6.0135612e+00 - -7.4043474e+00 -3.9282205e+00 6.1930209e+00 - -7.1232912e+00 -3.7878521e+00 6.2104941e+00 - -7.0175164e+00 -3.7355400e+00 6.3421271e+00 - -6.8962471e+00 -3.6748056e+00 6.4602329e+00 - -6.1454992e+00 -3.3020169e+00 6.0941865e+00 - -6.3560709e+00 -3.4067779e+00 6.4549911e+00 - -6.2554746e+00 -3.3566945e+00 6.5758525e+00 - -6.2383208e+00 -3.3482073e+00 6.7674649e+00 - -6.2664459e+00 -3.3618497e+00 7.0037018e+00 - -6.5242279e+00 -3.4901635e+00 7.4588742e+00 - -6.7355855e+00 -3.5952307e+00 7.8932894e+00 - -6.8346361e+00 -3.6443082e+00 8.2385439e+00 - -6.6278677e+00 -3.5411016e+00 8.2858427e+00 - -6.4355693e+00 -3.4456518e+00 8.3411228e+00 - -6.1979923e+00 -3.3275582e+00 8.3419409e+00 - -6.1199470e+00 -3.2886063e+00 8.5141531e+00 - -5.3288618e+00 -2.8958723e+00 7.8517098e+00 - -6.5409892e+00 -3.4975342e+00 9.5707454e+00 - -6.4947500e+00 -3.4749512e+00 9.8189539e+00 - -5.3499866e+00 -2.9056203e+00 8.6389914e+00 - -6.2437361e+00 -3.3495352e+00 1.0124705e+01 - -5.9496468e+00 -3.2038241e+00 1.0043512e+01 - -5.7912800e+00 -3.1251379e+00 1.0144083e+01 - -6.0306441e+00 -3.2434157e+00 1.0843749e+01 - -5.8187714e+00 -3.1380575e+00 1.0879997e+01 - -5.6377818e+00 -3.0486965e+00 1.0960478e+01 - -2.7263680e+00 -1.6018297e+00 6.4353639e+00 - -2.8961285e+00 -1.6856512e+00 6.9441678e+00 - -2.5165023e+00 -1.4974676e+00 6.4894952e+00 - -2.5311582e+00 -1.5043457e+00 6.7369296e+00 - -2.4226333e+00 -1.4505571e+00 6.7603394e+00 - -2.4013350e+00 -1.4400666e+00 6.9569337e+00 - -2.3779191e+00 -1.4282122e+00 7.1633599e+00 - -2.3411482e+00 -1.4099908e+00 7.3526690e+00 - -3.8090623e+00 -2.1385915e+00 1.1070601e+01 - -2.2930864e+00 -1.3860374e+00 7.8324843e+00 - -2.1936706e+00 -1.3363187e+00 7.9042104e+00 - -2.0031579e+00 -1.2419437e+00 7.7338761e+00 - -1.4402045e+00 -9.6269604e-01 6.4886117e+00 - -1.4044472e+00 -9.4453737e-01 6.6754270e+00 - -1.3247076e+00 -9.0502582e-01 6.7398683e+00 - -1.3511634e+00 -9.1749135e-01 7.1632678e+00 - -1.1733081e+00 -8.2936757e-01 6.9123201e+00 - -1.0710788e+00 -7.7869813e-01 6.9056853e+00 - -1.0911806e+00 -7.8860974e-01 7.3881927e+00 - -9.6439590e-01 -7.2531833e-01 7.3020866e+00 - -9.2007624e-01 -7.0303183e-01 7.5823611e+00 - -7.0594975e-01 -5.9685455e-01 7.0525564e+00 - -5.9361848e-01 -5.4118690e-01 6.9771282e+00 - -5.0767655e-01 -4.9878607e-01 7.0466952e+00 - -4.0852844e-01 -4.4914409e-01 7.0358248e+00 - -2.8925620e-01 -3.8962711e-01 6.8646461e+00 - -1.7617068e-01 -3.3339037e-01 6.7006760e+00 - -8.0303755e-02 -2.8585797e-01 6.6433725e+00 - 1.0564716e-02 -2.4066297e-01 6.6338739e+00 - 1.0921224e-01 -1.9192683e-01 6.4830786e+00 - 1.7744025e-01 -1.5827753e-01 6.8192148e+00 - 2.7120419e-01 -1.1147656e-01 6.7446389e+00 - 3.6383413e-01 -6.5184877e-02 6.6382560e+00 - 4.5159363e-01 -2.1239034e-02 6.6200273e+00 - -2.5507439e+00 -1.4073293e+00 -9.4139984e-01 - -2.6681953e+00 -1.4611488e+00 -9.3591742e-01 - -2.8031932e+00 -1.5231990e+00 -9.3572785e-01 - -2.9382241e+00 -1.5860293e+00 -9.3109415e-01 - -3.0907334e+00 -1.6560294e+00 -9.3050446e-01 - -3.2442691e+00 -1.7267097e+00 -9.2466844e-01 - -3.4319021e+00 -1.8139316e+00 -9.2982081e-01 - -3.6204920e+00 -1.9007630e+00 -9.2827825e-01 - -3.8359105e+00 -2.0002460e+00 -9.3135268e-01 - -4.0347818e+00 -2.0919620e+00 -9.1949336e-01 - -4.2779686e+00 -2.2035682e+00 -9.1769330e-01 - -4.5820716e+00 -2.3442890e+00 -9.2990055e-01 - -4.7849676e+00 -2.4375666e+00 -8.9380960e-01 - -5.0394711e+00 -2.5553258e+00 -8.6810714e-01 - -5.2959745e+00 -2.6735078e+00 -8.3316012e-01 - -5.6133018e+00 -2.8195510e+00 -8.0707639e-01 - -6.1255953e+00 -3.0561902e+00 -8.2257853e-01 - -7.0380403e+00 -3.4773747e+00 -9.2042314e-01 - -6.9158109e+00 -3.4206150e+00 -7.3985039e-01 - -6.8266322e+00 -3.3795540e+00 -5.7221640e-01 - -6.7879665e+00 -3.3612332e+00 -4.1896839e-01 - -5.7335935e+00 -2.8749660e+00 -9.0420701e-02 - -5.7321399e+00 -2.8739661e+00 3.2372529e-02 - -5.7101055e+00 -2.8640825e+00 1.5710359e-01 - -1.2675326e+01 -6.0775811e+00 -5.3208376e-01 - -1.4081719e+01 -6.7259501e+00 -4.1272239e-01 - -1.4066359e+01 -6.7188157e+00 -1.2941916e-01 - -1.1252347e+01 -5.4212722e+00 3.1555413e-01 - -1.1297938e+01 -5.4414667e+00 5.4000698e-01 - -1.1430161e+01 -5.5025764e+00 7.6430953e-01 - -1.5963163e+01 -7.5937327e+00 9.9116202e-01 - -1.5834302e+01 -7.5337494e+00 1.3051997e+00 - -3.5057293e+01 -1.6401501e+01 2.3479905e+00 - -3.4984974e+01 -1.6368033e+01 3.0285352e+00 - -3.4168720e+01 -1.5991211e+01 3.6507051e+00 - -3.4564233e+01 -1.6173854e+01 4.3590155e+00 - -3.4894743e+01 -1.6325831e+01 5.0771264e+00 - -3.4156972e+01 -1.5985998e+01 5.6669627e+00 - -3.4437979e+01 -1.6114755e+01 6.3877277e+00 - -3.5145426e+01 -1.6441039e+01 7.1971628e+00 - -3.1264206e+01 -1.4650373e+01 7.7811331e+00 - -3.0462956e+01 -1.4280332e+01 8.8540856e+00 - -3.4009213e+01 -1.5915451e+01 1.0454681e+01 - -2.9932670e+01 -1.4035636e+01 9.9617270e+00 - -1.0474950e+01 -5.0606863e+00 4.4589066e+00 - -3.0281581e+01 -1.4195583e+01 1.1344764e+01 - -1.0470388e+01 -5.0591752e+00 4.9186711e+00 - -9.7367061e+00 -4.7204738e+00 4.8753074e+00 - -9.2048858e+00 -4.4753388e+00 4.8836618e+00 - -9.0065693e+00 -4.3836289e+00 5.0122794e+00 - -8.9410469e+00 -4.3534630e+00 5.1943138e+00 - -8.8734150e+00 -4.3214832e+00 5.3750442e+00 - -9.0599780e+00 -4.4073748e+00 5.6805028e+00 - -9.1734664e+00 -4.4598251e+00 5.9605319e+00 - -1.0701692e+01 -5.1647032e+00 7.2772052e+00 - -6.4380726e+00 -3.1984600e+00 5.0573095e+00 - -9.1457076e+00 -4.4468753e+00 6.8804574e+00 - -8.7993319e+00 -4.2870318e+00 6.9049771e+00 - -8.9456188e+00 -4.3547130e+00 7.2423296e+00 - -7.1740721e+00 -3.5378877e+00 6.2739704e+00 - -7.3019025e+00 -3.5965558e+00 6.5729177e+00 - -6.8817429e+00 -3.4030616e+00 6.4761750e+00 - -6.9046924e+00 -3.4134668e+00 6.7031090e+00 - -6.4753226e+00 -3.2150948e+00 6.5744299e+00 - -6.0892347e+00 -3.0374210e+00 6.4610562e+00 - -7.3618751e+00 -3.6234162e+00 7.7557697e+00 - -6.5893587e+00 -3.2677108e+00 7.3146382e+00 - -6.5998986e+00 -3.2722981e+00 7.5526227e+00 - -7.4549656e+00 -3.6668125e+00 8.6060303e+00 - -6.7123821e+00 -3.3244544e+00 8.1425134e+00 - -6.7906234e+00 -3.3602448e+00 8.4776724e+00 - -6.6182667e+00 -3.2812485e+00 8.5611208e+00 - -6.8833289e+00 -3.4029284e+00 9.1207400e+00 - -5.2826721e+00 -2.6651105e+00 7.5861285e+00 - -5.1094067e+00 -2.5848275e+00 7.6158416e+00 - -6.4995193e+00 -3.2252376e+00 9.5498487e+00 - -5.4147335e+00 -2.7258714e+00 8.4836432e+00 - -6.3579638e+00 -3.1607690e+00 9.9897423e+00 - -6.2204181e+00 -3.0970108e+00 1.0127924e+01 - -6.2152082e+00 -3.0942307e+00 1.0452555e+01 - -6.1299805e+00 -3.0551734e+00 1.0675981e+01 - -6.0231570e+00 -3.0056125e+00 1.0874625e+01 - -2.9880210e+00 -1.6069574e+00 6.4783828e+00 - -2.8397060e+00 -1.5383266e+00 6.4451461e+00 - -2.7283199e+00 -1.4868168e+00 6.4665480e+00 - -2.6025877e+00 -1.4285405e+00 6.4598936e+00 - -2.7688514e+00 -1.5049192e+00 6.9814248e+00 - -2.5233143e+00 -1.3924533e+00 6.7575941e+00 - -2.4672354e+00 -1.3664519e+00 6.8847241e+00 - -2.4582376e+00 -1.3624546e+00 7.1173586e+00 - -2.3856925e+00 -1.3283032e+00 7.2266637e+00 - -2.2906831e+00 -1.2847431e+00 7.2902102e+00 - -2.4063454e+00 -1.3381912e+00 7.8502473e+00 - -2.2713421e+00 -1.2755826e+00 7.8411191e+00 - -2.1302403e+00 -1.2103982e+00 7.8105000e+00 - -1.8890590e+00 -1.0990451e+00 7.4984421e+00 - -1.7041937e+00 -1.0142568e+00 7.3099926e+00 - -1.3856992e+00 -8.6752443e-01 6.6937398e+00 - -1.4233845e+00 -8.8441500e-01 7.1355492e+00 - -1.1816865e+00 -7.7387544e-01 6.6866595e+00 - -1.1397764e+00 -7.5425482e-01 6.8901855e+00 - -1.1761595e+00 -7.7083843e-01 7.4204809e+00 - -1.0506079e+00 -7.1245832e-01 7.3551500e+00 - -9.6274363e-01 -6.7231693e-01 7.4421379e+00 - -7.6013486e-01 -5.7854065e-01 6.9919134e+00 - -7.2000641e-01 -5.6069343e-01 7.2988653e+00 - -5.5217347e-01 -4.8342180e-01 6.9384791e+00 - -4.6130831e-01 -4.4083196e-01 6.9774687e+00 - -3.5835804e-01 -3.9295414e-01 6.9357237e+00 - -2.4743926e-01 -3.4208415e-01 6.8225941e+00 - -1.2762119e-01 -2.8675797e-01 6.5879402e+00 - -4.5904998e-02 -2.4907230e-01 6.6785915e+00 - 8.2361501e-02 -1.9082992e-01 6.2101535e+00 - 1.2466972e-01 -1.7082112e-01 6.8457909e+00 - 2.2131327e-01 -1.2615106e-01 6.7722035e+00 - 3.0461493e-01 -8.7958536e-02 7.0364342e+00 - 4.0808014e-01 -3.9661896e-02 6.5193791e+00 - -2.5594798e+00 -1.3024321e+00 -9.6053759e-01 - -2.6550390e+00 -1.3428640e+00 -9.4163316e-01 - -2.7908059e+00 -1.4009596e+00 -9.4353626e-01 - -2.9193476e+00 -1.4560292e+00 -9.3632174e-01 - -3.0735657e+00 -1.5210319e+00 -9.3817072e-01 - -3.2196183e+00 -1.5840465e+00 -9.3045619e-01 - -3.3923957e+00 -1.6578519e+00 -9.3015441e-01 - -3.5661349e+00 -1.7313061e+00 -9.2395673e-01 - -3.7666469e+00 -1.8164496e+00 -9.2312471e-01 - -3.9939236e+00 -1.9132183e+00 -9.2635995e-01 - -4.2397056e+00 -2.0178419e+00 -9.2849275e-01 - -4.4782440e+00 -2.1192918e+00 -9.1851163e-01 - -4.7693291e+00 -2.2441757e+00 -9.1916513e-01 - -5.0098738e+00 -2.3466168e+00 -8.9120063e-01 - -5.2689127e+00 -2.4568241e+00 -8.6033591e-01 - -5.5371372e+00 -2.5701647e+00 -8.2295214e-01 - -5.9484739e+00 -2.7455875e+00 -8.1606505e-01 - -6.8362605e+00 -3.1233277e+00 -9.1800712e-01 - -7.0899732e+00 -3.2311571e+00 -8.3282539e-01 - -6.9557074e+00 -3.1741407e+00 -6.5263998e-01 - -6.9542245e+00 -3.1739375e+00 -5.0547762e-01 - -5.6345779e+00 -2.6115347e+00 -1.1884476e-01 - -5.6063781e+00 -2.5990574e+00 5.0194306e-03 - -5.6121877e+00 -2.6019031e+00 1.2234015e-01 - -1.2563268e+01 -5.5623428e+00 -6.2457311e-01 - -1.3786612e+01 -6.0832279e+00 -5.0281812e-01 - -1.5505586e+01 -6.8147429e+00 -3.7772616e-01 - -1.5470627e+01 -6.7995646e+00 -7.0210196e-02 - -1.6615448e+01 -7.2877829e+00 1.7860799e-01 - -1.6249275e+01 -7.1317209e+00 5.1437583e-01 - -1.6217366e+01 -7.1178379e+00 8.3248748e-01 - -1.6493982e+01 -7.2357079e+00 1.1519941e+00 - -1.7896460e+01 -7.8321528e+00 1.5135719e+00 - -4.0368615e+01 -1.7400515e+01 2.9168565e+00 - -3.8963703e+01 -1.6802368e+01 3.6015703e+00 - -3.8943735e+01 -1.6793353e+01 4.3521288e+00 - -3.8929927e+01 -1.6786888e+01 5.1044530e+00 - -3.8053742e+01 -1.6414401e+01 5.7525991e+00 - -3.8500469e+01 -1.6604140e+01 6.5585954e+00 - -3.3343443e+01 -1.4408391e+01 7.1360346e+00 - -3.3158339e+01 -1.4329347e+01 7.7606695e+00 - -3.2747182e+01 -1.4154243e+01 8.3324129e+00 - -3.2750158e+01 -1.4155375e+01 8.9922008e+00 - -3.1551960e+01 -1.3644523e+01 9.3443797e+00 - -1.0030802e+01 -4.4826965e+00 3.9538694e+00 - -1.0177034e+01 -4.5452973e+00 4.2118734e+00 - -1.0141390e+01 -4.5301066e+00 4.4195614e+00 - -1.0059470e+01 -4.4944039e+00 4.6118345e+00 - -1.0121395e+01 -4.5206609e+00 4.8559109e+00 - -9.4859320e+00 -4.2500536e+00 4.8367374e+00 - -9.3537815e+00 -4.1938671e+00 4.9976530e+00 - -9.3561719e+00 -4.1950469e+00 5.2131917e+00 - -8.8112051e+00 -3.9625310e+00 5.1854422e+00 - -9.0128144e+00 -4.0486212e+00 5.4888007e+00 - -8.7800643e+00 -3.9493303e+00 5.5897985e+00 - -8.6130890e+00 -3.8788256e+00 5.7178535e+00 - -7.1526225e+00 -3.2564568e+00 5.1410755e+00 - -6.5136050e+00 -2.9849473e+00 4.9627393e+00 - -6.3354900e+00 -2.9091895e+00 5.0283898e+00 - -8.8657277e+00 -3.9857231e+00 6.7514524e+00 - -8.5180835e+00 -3.8374893e+00 6.7659239e+00 - -8.6671561e+00 -3.9012575e+00 7.0978941e+00 - -7.2401552e+00 -3.2932611e+00 6.3527229e+00 - -7.2066500e+00 -3.2790876e+00 6.5373457e+00 - -7.1475057e+00 -3.2542482e+00 6.7053645e+00 - -7.2114128e+00 -3.2813042e+00 6.9713196e+00 - -7.1152634e+00 -3.2397662e+00 7.1166596e+00 - -7.3729777e+00 -3.3497031e+00 7.5582093e+00 - -6.7989594e+00 -3.1052099e+00 7.3022091e+00 - -6.9376745e+00 -3.1645159e+00 7.6558223e+00 - -7.0394218e+00 -3.2079378e+00 7.9905017e+00 - -7.1267142e+00 -3.2442402e+00 8.3245404e+00 - -5.9625075e+00 -2.7492546e+00 7.4281706e+00 - -6.6064060e+00 -3.0231076e+00 8.3203328e+00 - -6.4354469e+00 -2.9503380e+00 8.3978892e+00 - -5.3403017e+00 -2.4847451e+00 7.4518320e+00 - -5.2104607e+00 -2.4293932e+00 7.5326041e+00 - -5.6021605e+00 -2.5950519e+00 8.4863570e+00 - -5.2418306e+00 -2.4416737e+00 8.2968452e+00 - -5.3280367e+00 -2.4788793e+00 8.6745756e+00 - -4.8828113e+00 -2.2893995e+00 8.3458901e+00 - -6.1716771e+00 -2.8378254e+00 1.0437335e+01 - -5.8655140e+00 -2.7068164e+00 1.0337370e+01 - -5.9605931e+00 -2.7477523e+00 1.0831082e+01 - -2.9536845e+00 -1.4688108e+00 6.4540349e+00 - -2.7944453e+00 -1.4007742e+00 6.4019370e+00 - -2.7078563e+00 -1.3638177e+00 6.4636585e+00 - -2.6284028e+00 -1.3296868e+00 6.5405820e+00 - -2.5438978e+00 -1.2943421e+00 6.6077024e+00 - -2.6125701e+00 -1.3223874e+00 6.9690532e+00 - -2.4196926e+00 -1.2404465e+00 6.8339605e+00 - -2.5506686e+00 -1.2967455e+00 7.3583885e+00 - -2.3781745e+00 -1.2226259e+00 7.2631559e+00 - -2.3282989e+00 -1.2020992e+00 7.4340479e+00 - -2.3660664e+00 -1.2175835e+00 7.8233237e+00 - -2.2527861e+00 -1.1690739e+00 7.8673897e+00 - -2.1171142e+00 -1.1117371e+00 7.8539118e+00 - -1.7704648e+00 -9.6401861e-01 7.2513538e+00 - -1.4821437e+00 -8.4183894e-01 6.7502387e+00 - -1.3741903e+00 -7.9571217e-01 6.7398878e+00 - -1.3670164e+00 -7.9279502e-01 7.0494817e+00 - -1.2499122e+00 -7.4329662e-01 7.0171812e+00 - -1.5250424e+00 -8.6003341e-01 8.4107476e+00 - -1.1101332e+00 -6.8292362e-01 7.2917837e+00 - -1.0508284e+00 -6.5731747e-01 7.4956080e+00 - -9.9757849e-01 -6.3548459e-01 7.7574269e+00 - -8.8240485e-01 -5.8637133e-01 7.7553947e+00 - -7.0562727e-01 -5.1150147e-01 7.4181001e+00 - -5.2700437e-01 -4.3486489e-01 6.9975045e+00 - -4.2123409e-01 -3.9011002e-01 6.9568973e+00 - -3.2252334e-01 -3.4808895e-01 6.9536144e+00 - -2.0281361e-01 -2.9723868e-01 6.7700447e+00 - -9.4278148e-02 -2.5140323e-01 6.6334489e+00 - 3.8924310e-02 -1.9390158e-01 6.1561060e+00 - 1.2224740e-01 -1.5841731e-01 6.1640539e+00 - 1.6954256e-01 -1.3822619e-01 6.7892386e+00 - 2.6406849e-01 -9.8014595e-02 6.7646444e+00 - 3.5932976e-01 -5.7900773e-02 6.6582495e+00 - 4.5071508e-01 -1.8675466e-02 6.6099941e+00 - -2.7654067e+00 -1.2792202e+00 -9.4559316e-01 - -2.8947175e+00 -1.3303352e+00 -9.4047131e-01 - -3.0424494e+00 -1.3876018e+00 -9.4023885e-01 - -3.1902108e+00 -1.4456191e+00 -9.3496300e-01 - -3.3564455e+00 -1.5107210e+00 -9.3322859e-01 - -3.5401487e+00 -1.5829137e+00 -9.3394015e-01 - -3.7340615e+00 -1.6583863e+00 -9.3232431e-01 - -3.9198025e+00 -1.7318214e+00 -9.2014620e-01 - -4.1588747e+00 -1.8248591e+00 -9.2319230e-01 - -4.4082603e+00 -1.9230375e+00 -9.2111523e-01 - -4.6853302e+00 -2.0316359e+00 -9.2015550e-01 - -4.9808290e+00 -2.1469641e+00 -9.1554608e-01 - -5.2876239e+00 -2.2672495e+00 -9.0331339e-01 - -5.4608212e+00 -2.3348258e+00 -8.3873663e-01 - -5.7593741e+00 -2.4525121e+00 -8.0455574e-01 - -6.5826623e+00 -2.7746612e+00 -9.0032667e-01 - -7.1655772e+00 -3.0034756e+00 -9.0476527e-01 - -7.8695222e+00 -3.2784339e+00 -9.1509155e-01 - -8.4841076e+00 -3.5194387e+00 -8.8038603e-01 - -8.0183841e+00 -3.3369084e+00 -6.1762601e-01 - -7.9880887e+00 -3.3253062e+00 -4.4827552e-01 - -8.0193894e+00 -3.3376352e+00 -2.9038038e-01 - -9.5269892e+00 -3.9284891e+00 -3.2752169e-01 - -1.3510417e+01 -5.4883204e+00 -5.8903676e-01 - -1.5490726e+01 -6.2645753e+00 -5.1118767e-01 - -1.7807460e+01 -7.1725630e+00 -3.8471434e-01 - -1.7733469e+01 -7.1436601e+00 -3.6164579e-02 - -1.8036089e+01 -7.2613956e+00 2.9480988e-01 - -1.8026743e+01 -7.2577094e+00 6.4269973e-01 - -4.0732615e+01 -1.6153599e+01 1.7503296e+00 - -4.0723912e+01 -1.6149804e+01 2.5234426e+00 - -4.0637251e+01 -1.6115799e+01 3.2927818e+00 - -3.9683627e+01 -1.5741259e+01 3.9956168e+00 - -3.8849202e+01 -1.5414824e+01 4.6755284e+00 - -3.8320497e+01 -1.5207090e+01 5.3604791e+00 - -3.9788010e+01 -1.5782407e+01 6.2901176e+00 - -3.8321845e+01 -1.5207808e+01 6.8378450e+00 - -3.2362611e+01 -1.2872760e+01 6.5713346e+00 - -3.2321605e+01 -1.2857186e+01 7.1968861e+00 - -3.3102953e+01 -1.3162486e+01 7.9956298e+00 - -3.3485337e+01 -1.3312108e+01 8.7384749e+00 - -3.2964337e+01 -1.3108138e+01 9.2777790e+00 - -3.3312790e+01 -1.3244095e+01 1.0034058e+01 - -1.0052431e+01 -4.1325383e+00 4.0303457e+00 - -1.0090730e+01 -4.1481416e+00 4.2551278e+00 - -9.6799388e+00 -3.9863630e+00 4.3363250e+00 - -9.7397698e+00 -4.0104152e+00 4.5667630e+00 - -9.4858808e+00 -3.9104607e+00 4.6866211e+00 - -9.3202191e+00 -3.8460268e+00 4.8322048e+00 - -9.4035281e+00 -3.8780029e+00 5.0764951e+00 - -8.8351757e+00 -3.6561370e+00 5.0445209e+00 - -7.2339731e+00 -3.0286240e+00 4.5202867e+00 - -7.1411663e+00 -2.9917497e+00 4.6484559e+00 - -6.5402515e+00 -2.7565398e+00 4.5209056e+00 - -7.0683480e+00 -2.9636665e+00 4.9589063e+00 - -6.6877425e+00 -2.8146746e+00 4.9277809e+00 - -6.5488496e+00 -2.7593198e+00 5.0196107e+00 - -6.5145539e+00 -2.7468671e+00 5.1705719e+00 - -8.5918720e+00 -3.5599288e+00 6.6301367e+00 - -7.6521047e+00 -3.1920298e+00 6.2541537e+00 - -7.2889657e+00 -3.0501140e+00 6.2208820e+00 - -5.6019800e+00 -2.3887750e+00 5.2504019e+00 - -5.4396810e+00 -2.3250396e+00 5.2971189e+00 - -7.2458992e+00 -3.0320821e+00 6.8176641e+00 - -5.3106932e+00 -2.2751729e+00 5.5288526e+00 - -5.0951805e+00 -2.1901953e+00 5.5227298e+00 - -4.9841394e+00 -2.1471148e+00 5.5961132e+00 - -7.0730821e+00 -2.9645787e+00 7.5786115e+00 - -6.9300911e+00 -2.9086233e+00 7.6875075e+00 - -5.9972692e+00 -2.5428468e+00 7.0585599e+00 - -6.0293154e+00 -2.5556760e+00 7.3063952e+00 - -5.7421601e+00 -2.4427265e+00 7.2437828e+00 - -5.8406741e+00 -2.4818426e+00 7.5681174e+00 - -5.9104882e+00 -2.5094280e+00 7.8767876e+00 - -5.3840923e+00 -2.3023961e+00 7.5357216e+00 - -5.2198167e+00 -2.2389392e+00 7.5792362e+00 - -6.8698685e+00 -2.8844926e+00 9.7800283e+00 - -5.2407208e+00 -2.2467095e+00 8.0836700e+00 - -5.1427941e+00 -2.2080745e+00 8.2131225e+00 - -5.1122998e+00 -2.1959142e+00 8.4343082e+00 - -4.8703278e+00 -2.1012361e+00 8.3729762e+00 - -5.7989280e+00 -2.4645210e+00 9.9653634e+00 - -5.8928373e+00 -2.5015672e+00 1.0437850e+01 - -6.1928673e+00 -2.6185069e+00 1.1252166e+01 - -2.9095454e+00 -1.3337306e+00 6.4202661e+00 - -2.7700474e+00 -1.2789991e+00 6.3993839e+00 - -2.6765310e+00 -1.2429436e+00 6.4513951e+00 - -4.5601159e+00 -1.9793461e+00 1.0031905e+01 - -2.8331034e+00 -1.3030790e+00 7.1904346e+00 - -2.6008009e+00 -1.2123071e+00 6.9983935e+00 - -2.7131704e+00 -1.2568485e+00 7.4792738e+00 - -2.6409187e+00 -1.2286510e+00 7.6097000e+00 - -2.3413796e+00 -1.1103906e+00 7.2451773e+00 - -2.2712196e+00 -1.0833500e+00 7.3699665e+00 - -2.3374560e+00 -1.1095507e+00 7.8319355e+00 - -2.2447739e+00 -1.0731574e+00 7.9300921e+00 - -1.9811603e+00 -9.6997278e-01 7.5818537e+00 - -1.7939056e+00 -8.9587419e-01 7.4032283e+00 - -1.4340024e+00 -7.5527543e-01 6.6937074e+00 - -1.3689814e+00 -7.3014814e-01 6.8141171e+00 - -1.3485818e+00 -7.2241271e-01 7.0954572e+00 - -1.1788835e+00 -6.5507631e-01 6.8805284e+00 - -1.1928718e+00 -6.6126075e-01 7.3243668e+00 - -1.0880818e+00 -6.1939722e-01 7.3454842e+00 - -1.0248477e+00 -5.9505446e-01 7.5488459e+00 - -9.5238964e-01 -5.6623967e-01 7.7323058e+00 - -8.5767243e-01 -5.2965692e-01 7.8367484e+00 - -6.1266710e-01 -4.3338865e-01 7.1249170e+00 - -4.8592891e-01 -3.8417877e-01 6.9774293e+00 - -3.9138389e-01 -3.4690911e-01 7.0147563e+00 - -2.6579901e-01 -2.9784711e-01 6.8225277e+00 - -1.5637741e-01 -2.5503025e-01 6.7070012e+00 - -1.1373068e-02 -1.9862984e-01 6.1814803e+00 - 7.6760014e-02 -1.6437722e-01 6.1503110e+00 - 1.1502087e-01 -1.4817390e-01 6.8457345e+00 - 2.1429494e-01 -1.0917250e-01 6.7621979e+00 - 3.0302847e-01 -7.4763235e-02 6.9165460e+00 - 4.0632448e-01 -3.5039042e-02 6.5093498e+00 - -2.7278715e+00 -1.1559119e+00 -9.4169483e-01 - -2.8671469e+00 -1.2057702e+00 -9.4358211e-01 - -2.9991971e+00 -1.2526027e+00 -9.3635176e-01 - -3.1559254e+00 -1.3094288e+00 -9.3818809e-01 - -3.2981704e+00 -1.3594229e+00 -9.2623329e-01 - -3.4743365e+00 -1.4230021e+00 -9.2611466e-01 - -3.6699040e+00 -1.4925297e+00 -9.2798581e-01 - -3.8747407e+00 -1.5663749e+00 -9.2708368e-01 - -4.0805318e+00 -1.6398098e+00 -9.1908712e-01 - -4.3407051e+00 -1.7337247e+00 -9.2506353e-01 - -4.5761379e+00 -1.8171483e+00 -9.1188572e-01 - -4.8659343e+00 -1.9209040e+00 -9.0968457e-01 - -5.2008313e+00 -2.0412377e+00 -9.1239468e-01 - -5.6104779e+00 -2.1876830e+00 -9.2587076e-01 - -5.7146296e+00 -2.2249615e+00 -8.3377844e-01 - -6.4091273e+00 -2.4732489e+00 -9.0144771e-01 - -6.9242608e+00 -2.6585740e+00 -8.9703588e-01 - -7.5971022e+00 -2.8994837e+00 -9.1103594e-01 - -8.0976866e+00 -3.0784828e+00 -8.6257114e-01 - -8.0161959e+00 -3.0493038e+00 -6.8098715e-01 - -7.8568467e+00 -2.9922499e+00 -4.8974460e-01 - -7.9639285e+00 -3.0308961e+00 -3.4800559e-01 - -7.9009071e+00 -3.0082531e+00 -1.7910137e-01 - -9.6214499e+00 -3.6240523e+00 -2.3021808e-01 - -9.4620088e+00 -3.5662643e+00 -2.4093904e-02 - -9.7021559e+00 -3.6528488e+00 1.4175701e-01 - -2.2591487e+01 -8.2678799e+00 -8.3384687e-02 - -2.8289732e+01 -1.0308276e+01 7.1735883e-01 - -3.6141196e+01 -1.3120196e+01 1.3195435e+00 - -4.1024235e+01 -1.4868209e+01 2.1320706e+00 - -4.0980773e+01 -1.4852689e+01 2.9007862e+00 - -3.9299166e+01 -1.4250279e+01 3.5635570e+00 - -3.5721727e+01 -1.2968792e+01 4.0078138e+00 - -3.5731822e+01 -1.2972622e+01 4.6854004e+00 - -3.4964944e+01 -1.2697897e+01 5.2720611e+00 - -3.3572713e+01 -1.2198763e+01 5.7453704e+00 - -3.3433482e+01 -1.2149173e+01 6.3674361e+00 - -3.5346220e+01 -1.2833336e+01 7.3510487e+00 - -3.6680562e+01 -1.3311519e+01 8.2980020e+00 - -3.2348493e+01 -1.1759498e+01 8.0793601e+00 - -3.2401718e+01 -1.1779200e+01 8.7282593e+00 - -3.3148558e+01 -1.2045799e+01 9.5605249e+00 - -1.0157754e+01 -3.8146360e+00 3.9211983e+00 - -1.0189844e+01 -3.8267817e+00 4.1423673e+00 - -1.0045906e+01 -3.7749044e+00 4.3116328e+00 - -9.6575129e+00 -3.6357143e+00 4.3954841e+00 - -9.8327382e+00 -3.6979647e+00 4.6656646e+00 - -8.9452888e+00 -3.3803382e+00 4.5465978e+00 - -9.0357087e+00 -3.4133955e+00 4.7806726e+00 - -9.3050312e+00 -3.5098529e+00 5.0958740e+00 - -7.4350275e+00 -2.8396464e+00 4.4858734e+00 - -7.2902959e+00 -2.7879180e+00 4.5925641e+00 - -6.5709498e+00 -2.5301247e+00 4.4175125e+00 - -7.0826799e+00 -2.7141261e+00 4.8361490e+00 - -6.7406148e+00 -2.5907056e+00 4.8289506e+00 - -6.8433655e+00 -2.6284362e+00 5.0549217e+00 - -6.6352536e+00 -2.5530448e+00 5.1092914e+00 - -6.7716751e+00 -2.6023604e+00 5.3639762e+00 - -6.1384862e+00 -2.3754944e+00 5.1481292e+00 - -7.4909076e+00 -2.8596750e+00 6.1946122e+00 - -6.1251398e+00 -2.3709577e+00 5.4776298e+00 - -5.7363294e+00 -2.2318270e+00 5.3791566e+00 - -5.6948877e+00 -2.2164648e+00 5.5166138e+00 - -5.4890120e+00 -2.1428690e+00 5.5321378e+00 - -5.2555835e+00 -2.0593885e+00 5.5176680e+00 - -5.1579754e+00 -2.0238148e+00 5.6053217e+00 - -5.0512537e+00 -1.9861983e+00 5.6846082e+00 - -5.3294968e+00 -2.0862511e+00 6.0982632e+00 - -5.0950385e+00 -2.0015466e+00 6.0693088e+00 - -6.4287651e+00 -2.4786351e+00 7.5032050e+00 - -6.1126183e+00 -2.3660508e+00 7.4281166e+00 - -5.8893567e+00 -2.2860244e+00 7.4327031e+00 - -5.8028988e+00 -2.2552734e+00 7.5712259e+00 - -5.6082590e+00 -2.1856378e+00 7.5943236e+00 - -5.3952127e+00 -2.1084214e+00 7.5905012e+00 - -5.2985658e+00 -2.0740390e+00 7.7135632e+00 - -6.6983310e+00 -2.5752326e+00 9.6316513e+00 - -5.3255298e+00 -2.0835605e+00 8.2359428e+00 - -5.1696786e+00 -2.0277698e+00 8.2966081e+00 - -5.0607723e+00 -1.9892857e+00 8.4161882e+00 - -6.3382353e+00 -2.4458171e+00 1.0453169e+01 - -6.1760461e+00 -2.3876006e+00 1.0570345e+01 - -5.9517233e+00 -2.3076462e+00 1.0594953e+01 - -3.0874428e+00 -1.2831137e+00 6.5363123e+00 - -2.9644770e+00 -1.2386066e+00 6.5519807e+00 - -2.8120469e+00 -1.1844966e+00 6.5141284e+00 - -2.7654946e+00 -1.1674477e+00 6.6513707e+00 - -2.7393059e+00 -1.1580624e+00 6.8316693e+00 - -2.6662280e+00 -1.1312999e+00 6.9342267e+00 - -2.6084556e+00 -1.1109330e+00 7.0711360e+00 - -2.6299862e+00 -1.1185528e+00 7.3760202e+00 - -2.5039861e+00 -1.0733927e+00 7.3883336e+00 - -2.4878133e+00 -1.0678017e+00 7.6415708e+00 - -2.1910464e+00 -9.6129355e-01 7.2592222e+00 - -2.2418735e+00 -9.7923770e-01 7.6840436e+00 - -2.2032510e+00 -9.6590379e-01 7.9185378e+00 - -1.9787694e+00 -8.8549754e-01 7.6698857e+00 - -1.5017495e+00 -7.1498431e-01 6.6753173e+00 - -1.4023370e+00 -6.7900225e-01 6.6926531e+00 - -1.4256137e+00 -6.8759551e-01 7.0969186e+00 - -1.2907137e+00 -6.3952164e-01 7.0172201e+00 - -1.1082873e+00 -5.7443750e-01 6.7522621e+00 - -1.1949662e+00 -6.0450445e-01 7.4748691e+00 - -1.1287893e+00 -5.8075689e-01 7.6698316e+00 - -1.0565056e+00 -5.5539783e-01 7.8642764e+00 - -4.3856891e-01 -3.3402947e-01 5.4809208e+00 - -7.7156772e-01 -4.5264716e-01 7.6139487e+00 - -5.5437696e-01 -3.7506094e-01 7.0171511e+00 - -4.4597472e-01 -3.3647900e-01 6.9766319e+00 - -3.4363467e-01 -3.0018211e-01 6.9634965e+00 - -2.0732641e-01 -2.5073992e-01 6.6708593e+00 - -1.0519884e-01 -2.1510955e-01 6.6036914e+00 - 3.1511449e-02 -1.6584996e-01 6.1262328e+00 - 1.1552977e-01 -1.3542570e-01 6.1341256e+00 - 1.6270693e-01 -1.1875611e-01 6.7892215e+00 - 2.5793095e-01 -8.4613084e-02 6.7846466e+00 - 3.5588297e-01 -4.9170957e-02 6.6682530e+00 - 4.4996127e-01 -1.5630834e-02 6.6299734e+00 - -2.7111713e+00 -1.0450644e+00 -9.5147101e-01 - -2.8348208e+00 -1.0854510e+00 -9.4561171e-01 - -2.9584462e+00 -1.1256455e+00 -9.3585722e-01 - -3.1086890e+00 -1.1747404e+00 -9.3571199e-01 - -3.2690917e+00 -1.2262020e+00 -9.3498680e-01 - -3.4387145e+00 -1.2810728e+00 -9.3333566e-01 - -3.6175524e+00 -1.3393135e+00 -9.2995956e-01 - -3.8147929e+00 -1.4035581e+00 -9.2847653e-01 - -4.0222990e+00 -1.4720450e+00 -9.2391742e-01 - -4.2491352e+00 -1.5453946e+00 -9.1959986e-01 - -4.4861687e+00 -1.6219256e+00 -9.1095735e-01 - -4.7682622e+00 -1.7141952e+00 -9.1047170e-01 - -5.0523518e+00 -1.8068581e+00 -9.0014223e-01 - -5.4192724e+00 -1.9264317e+00 -9.0629660e-01 - -5.8065956e+00 -2.0524320e+00 -9.0509949e-01 - -6.2327370e+00 -2.1909663e+00 -9.0054138e-01 - -6.7427086e+00 -2.3568750e+00 -9.0282623e-01 - -7.3201187e+00 -2.5446654e+00 -9.0261417e-01 - -8.0570296e+00 -2.7847465e+00 -9.1726085e-01 - -7.8171774e+00 -2.7064061e+00 -7.0443672e-01 - -9.6327669e+00 -3.2967827e+00 -8.8427873e-01 - -9.9440409e+00 -3.3984505e+00 -7.4507906e-01 - -7.8248344e+00 -2.7086716e+00 -2.3459840e-01 - -7.8621703e+00 -2.7210074e+00 -8.4174931e-02 - -7.8319999e+00 -2.7109195e+00 7.4738057e-02 - -1.6305224e+01 -5.4682856e+00 -5.5525149e-01 - -1.8898656e+01 -6.3128255e+00 -4.3700831e-01 - -4.1354597e+01 -1.3619681e+01 1.7452186e+00 - -4.1316316e+01 -1.3606929e+01 2.5125007e+00 - -3.7286898e+01 -1.2295372e+01 3.0616188e+00 - -3.6270071e+01 -1.1964782e+01 3.6835296e+00 - -3.6361838e+01 -1.1994287e+01 4.3708968e+00 - -3.4371535e+01 -1.1346182e+01 4.8347679e+00 - -3.4255042e+01 -1.1308703e+01 5.4680843e+00 - -3.3968899e+01 -1.1214588e+01 6.0747316e+00 - -3.3992320e+01 -1.1221967e+01 6.7252419e+00 - -3.3975920e+01 -1.1216844e+01 7.3729873e+00 - -3.3883915e+01 -1.1186802e+01 8.0085239e+00 - -3.3650958e+01 -1.1110618e+01 8.6135805e+00 - -1.0620407e+01 -3.6174597e+00 3.6934554e+00 - -1.0519602e+01 -3.5840552e+00 3.8826215e+00 - -1.0497468e+01 -3.5769872e+00 4.0920951e+00 - -1.0243601e+01 -3.4950451e+00 4.2329667e+00 - -1.0142839e+01 -3.4619904e+00 4.4150415e+00 - -1.0128868e+01 -3.4574051e+00 4.6251887e+00 - -9.6984488e+00 -3.3178646e+00 4.6864358e+00 - -9.5823891e+00 -3.2795066e+00 4.8525353e+00 - -9.0733959e+00 -3.1133799e+00 4.8580194e+00 - -7.7909131e+00 -2.6962443e+00 4.5168406e+00 - -7.7046278e+00 -2.6684201e+00 4.6568105e+00 - -7.2172965e+00 -2.5097154e+00 4.6077265e+00 - -6.6127363e+00 -2.3137100e+00 4.4828886e+00 - -6.5285295e+00 -2.2859060e+00 4.5997437e+00 - -6.6371305e+00 -2.3206181e+00 4.8187936e+00 - -6.5978233e+00 -2.3077859e+00 4.9632973e+00 - -6.7227441e+00 -2.3484471e+00 5.2042680e+00 - -6.7507196e+00 -2.3572836e+00 5.3961124e+00 - -6.0647989e+00 -2.1344721e+00 5.1425935e+00 - -6.1478920e+00 -2.1616292e+00 5.3630156e+00 - -6.0586129e+00 -2.1324439e+00 5.4734636e+00 - -5.7072926e+00 -2.0180122e+00 5.3975662e+00 - -5.6567895e+00 -2.0015401e+00 5.5280042e+00 - -5.2658357e+00 -1.8750648e+00 5.3995043e+00 - -5.2978801e+00 -1.8847845e+00 5.5888142e+00 - -5.4084698e+00 -1.9213780e+00 5.8483190e+00 - -5.3487651e+00 -1.9016444e+00 5.9748347e+00 - -5.2218462e+00 -1.8607891e+00 6.0429234e+00 - -6.6090527e+00 -2.3118661e+00 7.4911855e+00 - -5.9561913e+00 -2.0986329e+00 7.1056795e+00 - -5.9656817e+00 -2.1018385e+00 7.3323755e+00 - -5.9823033e+00 -2.1078352e+00 7.5749727e+00 - -5.8389003e+00 -2.0602344e+00 7.6575452e+00 - -5.3900532e+00 -1.9142741e+00 7.4061769e+00 - -5.5817835e+00 -1.9769480e+00 7.8495936e+00 - -5.4221946e+00 -1.9255003e+00 7.9081473e+00 - -5.8061351e+00 -2.0495251e+00 8.6192017e+00 - -5.4826469e+00 -1.9451484e+00 8.4888042e+00 - -5.3097331e+00 -1.8880892e+00 8.5351842e+00 - -5.7993249e+00 -2.0478812e+00 9.4678254e+00 - -6.1960805e+00 -2.1765377e+00 1.0332477e+01 - -5.8949008e+00 -2.0787758e+00 1.0243694e+01 - -3.1804072e+00 -1.1960946e+00 6.5192772e+00 - -3.0241348e+00 -1.1449758e+00 6.4864548e+00 - -2.9116057e+00 -1.1081421e+00 6.5166836e+00 - -2.8956481e+00 -1.1027233e+00 6.7056513e+00 - -2.8786932e+00 -1.0978889e+00 6.9042536e+00 - -2.7133034e+00 -1.0436645e+00 6.8440882e+00 - -2.7125377e+00 -1.0437348e+00 7.0857851e+00 - -2.6030017e+00 -1.0072241e+00 7.1260606e+00 - -2.3798429e+00 -9.3502406e-01 6.9326892e+00 - -2.2308211e+00 -8.8661901e-01 6.8768167e+00 - -2.5271889e+00 -9.8263088e-01 7.8139300e+00 - -2.0687966e+00 -8.3435993e-01 7.0555636e+00 - -2.0535936e+00 -8.2848192e-01 7.3133983e+00 - -2.0870743e+00 -8.4031069e-01 7.7208901e+00 - -1.6341038e+00 -6.9208661e-01 6.8339008e+00 - -1.4650265e+00 -6.3744809e-01 6.6654588e+00 - -1.4984129e+00 -6.4852307e-01 7.0882317e+00 - -1.3849656e+00 -6.1135716e-01 7.0858983e+00 - -1.1725056e+00 -5.4222094e-01 6.7371521e+00 - -1.3318759e+00 -5.9411386e-01 7.6991779e+00 - -1.1981806e+00 -5.5072466e-01 7.6448489e+00 - -1.1270123e+00 -5.2727442e-01 7.8398954e+00 - -4.9385788e-01 -3.2217280e-01 5.5110146e+00 - -4.1313740e-01 -2.9553847e-01 5.4991902e+00 - -7.5125775e-01 -4.0531421e-01 7.7433511e+00 - -5.1142539e-01 -3.2700376e-01 7.0070061e+00 - -4.0925963e-01 -2.9416260e-01 7.0048556e+00 - -2.8509446e-01 -2.5356617e-01 6.8423896e+00 - -1.8201910e-01 -2.2046170e-01 6.8062786e+00 - -2.4527916e-02 -1.6927310e-01 6.2112518e+00 - 6.9227532e-02 -1.3882872e-01 6.1304742e+00 - 1.1123301e-01 -1.2433362e-01 6.7758972e+00 - 2.0827559e-01 -9.2763585e-02 6.7621265e+00 - 2.9969986e-01 -6.3026019e-02 6.9064758e+00 - 4.0375562e-01 -2.8877720e-02 6.5292867e+00 - -2.7985560e+00 -9.6632131e-01 -9.4660572e-01 - -2.9240089e+00 -1.0034977e+00 -9.3889118e-01 - -3.0667661e+00 -1.0449070e+00 -9.3646793e-01 - -3.2187478e+00 -1.0897602e+00 -9.3381786e-01 - -3.3798911e+00 -1.1370404e+00 -9.3059102e-01 - -3.5511906e+00 -1.1866578e+00 -9.2618497e-01 - -3.7500853e+00 -1.2449525e+00 -9.2808907e-01 - -3.9683747e+00 -1.3091413e+00 -9.3088429e-01 - -4.1876179e+00 -1.3729150e+00 -9.2648522e-01 - -4.4344962e+00 -1.4462004e+00 -9.2505081e-01 - -4.6925054e+00 -1.5215753e+00 -9.1863870e-01 - -4.9688901e+00 -1.6027373e+00 -9.0972510e-01 - -5.3023767e+00 -1.6999390e+00 -9.0947990e-01 - -5.6736416e+00 -1.8088861e+00 -9.0892275e-01 - -6.0928527e+00 -1.9320092e+00 -9.0877208e-01 - -6.5232111e+00 -2.0578689e+00 -8.9650291e-01 - -7.0862263e+00 -2.2227302e+00 -9.0181607e-01 - -7.7726763e+00 -2.4236831e+00 -9.1550041e-01 - -8.4427371e+00 -2.6201964e+00 -9.0066935e-01 - -9.1994749e+00 -2.8422062e+00 -8.7853876e-01 - -9.8356452e+00 -3.0279563e+00 -8.0777793e-01 - -9.6360466e+00 -2.9697105e+00 -5.8400211e-01 - -9.5660418e+00 -2.9490675e+00 -3.8630689e-01 - -9.5307484e+00 -2.9387416e+00 -1.9619874e-01 - -1.5394668e+01 -4.6570380e+00 -6.0349278e-01 - -1.8098299e+01 -5.4492629e+00 -5.3530935e-01 - -3.9473122e+01 -1.1711056e+01 5.7232927e+00 - -3.4792232e+01 -1.0339461e+01 6.4759874e+00 - -3.4095827e+01 -1.0135029e+01 7.6615844e+00 - -3.5521683e+01 -1.0553155e+01 8.6158521e+00 - -1.0587757e+01 -3.2476394e+00 3.7673251e+00 - -1.0586045e+01 -3.2471508e+00 3.9810541e+00 - -1.0849250e+01 -3.3240780e+00 4.2728267e+00 - -9.6890435e+00 -2.9841056e+00 4.7532168e+00 - -1.0154936e+01 -3.1210933e+00 5.1442204e+00 - -9.5573085e+00 -2.9456799e+00 5.1213655e+00 - -9.3529055e+00 -2.8856154e+00 5.2463002e+00 - -7.8459631e+00 -2.4443363e+00 4.7756885e+00 - -7.6854489e+00 -2.3966250e+00 4.8812785e+00 - -7.5321658e+00 -2.3525030e+00 4.9865896e+00 - -6.8544184e+00 -2.1531875e+00 4.8154803e+00 - -6.9170539e+00 -2.1724463e+00 5.0178649e+00 - -6.9164740e+00 -2.1719381e+00 5.1902489e+00 - -6.9708470e+00 -2.1874019e+00 5.3983026e+00 - -6.8959349e+00 -2.1651507e+00 5.5334112e+00 - -9.2577360e+00 -2.8573225e+00 7.2228574e+00 - -5.9299599e+00 -1.8828688e+00 5.2628147e+00 - -5.5131883e+00 -1.7605865e+00 5.1418715e+00 - -5.2928522e+00 -1.6956004e+00 5.1430128e+00 - -5.4256683e+00 -1.7350588e+00 5.3985909e+00 - -5.9755507e+00 -1.8962736e+00 5.9871496e+00 - -5.7083951e+00 -1.8175617e+00 5.9580887e+00 - -5.5643606e+00 -1.7750141e+00 6.0204815e+00 - -5.3237317e+00 -1.7044783e+00 5.9964932e+00 - -5.5316764e+00 -1.7660696e+00 6.3612596e+00 - -5.8727179e+00 -1.8657522e+00 6.8674977e+00 - -5.7520480e+00 -1.8302221e+00 6.9621200e+00 - -6.0065098e+00 -1.9041535e+00 7.4257030e+00 - -5.7608212e+00 -1.8328540e+00 7.4030476e+00 - -5.4571633e+00 -1.7435250e+00 7.3090585e+00 - -5.7471037e+00 -1.8284460e+00 7.8514989e+00 - -5.5278666e+00 -1.7647216e+00 7.8461011e+00 - -5.3675365e+00 -1.7174502e+00 7.9022529e+00 - -5.6440593e+00 -1.7980822e+00 8.4867512e+00 - -5.7254562e+00 -1.8217842e+00 8.8594805e+00 - -5.7479197e+00 -1.8288212e+00 9.1749548e+00 - -5.5052737e+00 -1.7577247e+00 9.1445186e+00 - -5.4362860e+00 -1.7376881e+00 9.3489582e+00 - -5.3185168e+00 -1.7027751e+00 9.4881838e+00 - -3.0592523e+00 -1.0414217e+00 6.3880481e+00 - -2.9996868e+00 -1.0233157e+00 6.5018292e+00 - -2.8965286e+00 -9.9315985e-01 6.5477641e+00 - -2.8633974e+00 -9.8403833e-01 6.7110118e+00 - -2.7865568e+00 -9.6090260e-01 6.8057150e+00 - -2.7127843e+00 -9.3920501e-01 6.9081175e+00 - -2.7099596e+00 -9.3837957e-01 7.1501580e+00 - -2.6108502e+00 -9.0997759e-01 7.2164294e+00 - -2.1591070e+00 -7.7693273e-01 6.5472642e+00 - -2.1603761e+00 -7.7822081e-01 6.8023501e+00 - -2.2141510e+00 -7.9354771e-01 7.1955217e+00 - -2.0755216e+00 -7.5246135e-01 7.1614007e+00 - -9.3846152e-01 -4.2025485e-01 4.6117788e+00 - -2.0441775e+00 -7.4382420e-01 7.7163664e+00 - -1.5234808e+00 -5.9161899e-01 6.6285157e+00 - -1.4779823e+00 -5.7753357e-01 6.8057599e+00 - -1.4405395e+00 -5.6662086e-01 7.0304685e+00 - -1.3192924e+00 -5.3142149e-01 6.9980469e+00 - -1.2353744e+00 -5.0695642e-01 7.0877348e+00 - -1.3206825e+00 -5.3152754e-01 7.8216765e+00 - -1.1771284e+00 -4.8920913e-01 7.7376029e+00 - -5.3880241e-01 -3.0234851e-01 5.4919916e+00 - -4.6331119e-01 -2.8092737e-01 5.5101932e+00 - -3.8377488e-01 -2.5778193e-01 5.5074592e+00 - -1.1288685e-01 -1.7816840e-01 4.4314396e+00 - -4.8163192e-01 -2.8580344e-01 7.0850889e+00 - -3.3668463e-01 -2.4326814e-01 6.8052545e+00 - -2.1987864e-01 -2.0934724e-01 6.6609852e+00 - -1.2198156e-01 -1.8053292e-01 6.6533527e+00 - 2.2165541e-02 -1.3820319e-01 6.1262283e+00 - 1.0594482e-01 -1.1329930e-01 6.1640315e+00 - 1.5587131e-01 -9.9286032e-02 6.7892044e+00 - 2.5185589e-01 -7.1228107e-02 6.8245739e+00 - 3.5156581e-01 -4.1422323e-02 6.7381842e+00 - 4.4821073e-01 -1.3030034e-02 6.6599931e+00 - -2.7677302e+00 -8.5407987e-01 -9.5153168e-01 - -2.8756210e+00 -8.8290236e-01 -9.3602738e-01 - -3.0272845e+00 -9.2211864e-01 -9.4066597e-01 - -3.1636465e+00 -9.5754934e-01 -9.3126810e-01 - -3.3255017e+00 -9.9990261e-01 -9.3068287e-01 - -3.5067056e+00 -1.0472664e+00 -9.3333549e-01 - -3.6716091e+00 -1.0909002e+00 -9.2185494e-01 - -3.8813073e+00 -1.1455735e+00 -9.2457185e-01 - -4.0920208e+00 -1.2008385e+00 -9.2024465e-01 - -4.3495656e+00 -1.2678615e+00 -9.2686294e-01 - -4.5999873e+00 -1.3337048e+00 -9.2126822e-01 - -4.8788511e+00 -1.4059246e+00 -9.1708572e-01 - -5.1862675e+00 -1.4864362e+00 -9.1261832e-01 - -5.5415319e+00 -1.5793074e+00 -9.1225207e-01 - -5.9263250e+00 -1.6802324e+00 -9.0800218e-01 - -6.3497568e+00 -1.7907105e+00 -9.0073970e-01 - -6.8404139e+00 -1.9193043e+00 -8.9567296e-01 - -7.4746420e+00 -2.0851934e+00 -9.0730423e-01 - -8.2055644e+00 -2.2762601e+00 -9.1739702e-01 - -8.9395036e+00 -2.4688702e+00 -9.0166332e-01 - -9.8280841e+00 -2.7003822e+00 -8.8786201e-01 - -9.5902098e+00 -2.6390940e+00 -6.5726365e-01 - -1.2328182e+01 -3.3549566e+00 -8.7037762e-01 - -9.4769392e+00 -2.6087121e+00 -2.7158313e-01 - -1.5144359e+01 -4.0915736e+00 -7.0812395e-01 - -1.7281753e+01 -4.6500838e+00 -6.1771860e-01 - -4.2371793e+01 -1.1211517e+01 2.0284378e-01 - -4.2881334e+01 -1.1344929e+01 9.7601171e-01 - -1.0419564e+01 -2.8550391e+00 4.4440805e+00 - -9.8168678e+00 -2.6971372e+00 4.4585032e+00 - -9.5559072e+00 -2.6289921e+00 4.5725777e+00 - -1.0112407e+01 -2.7744540e+00 4.9856847e+00 - -7.6310768e+00 -2.1257917e+00 4.2209856e+00 - -7.5308943e+00 -2.0994297e+00 4.3484264e+00 - -7.6421304e+00 -2.1279934e+00 4.5668889e+00 - -7.6608749e+00 -2.1328178e+00 4.7497677e+00 - -7.5525971e+00 -2.1050291e+00 4.8753860e+00 - -7.4686364e+00 -2.0822856e+00 5.0112154e+00 - -7.3562769e+00 -2.0529961e+00 5.1316282e+00 - -7.0376401e+00 -1.9696807e+00 5.1366652e+00 - -6.7637446e+00 -1.8980095e+00 5.1557691e+00 - -6.3233057e+00 -1.7836116e+00 5.0664074e+00 - -6.9332916e+00 -1.9423900e+00 5.6107621e+00 - -9.2843743e+00 -2.5574200e+00 7.3113554e+00 - -5.7995266e+00 -1.6459702e+00 5.2230902e+00 - -5.3257153e+00 -1.5223719e+00 5.0566744e+00 - -5.5344216e+00 -1.5768549e+00 5.3617216e+00 - -5.5227258e+00 -1.5738613e+00 5.5168934e+00 - -5.5384322e+00 -1.5780031e+00 5.6970164e+00 - -5.4880962e+00 -1.5644135e+00 5.8298004e+00 - -5.3535245e+00 -1.5292778e+00 5.8930176e+00 - -5.1509388e+00 -1.4762146e+00 5.8950569e+00 - -5.4914070e+00 -1.5651260e+00 6.3765302e+00 - -5.3487461e+00 -1.5286131e+00 6.4369263e+00 - -5.9356287e+00 -1.6811296e+00 7.1958947e+00 - -6.0049602e+00 -1.6997012e+00 7.4846934e+00 - -5.4695248e+00 -1.5594678e+00 7.1627863e+00 - -5.2842179e+00 -1.5114639e+00 7.1833041e+00 - -5.3899721e+00 -1.5384697e+00 7.5205025e+00 - -5.3831441e+00 -1.5367691e+00 7.7446531e+00 - -5.8143701e+00 -1.6497921e+00 8.4985099e+00 - -5.9726342e+00 -1.6903521e+00 8.9633572e+00 - -5.7760583e+00 -1.6391552e+00 9.0012697e+00 - -5.6464301e+00 -1.6059185e+00 9.1211809e+00 - -5.5663737e+00 -1.5842901e+00 9.3105554e+00 - -5.3860478e+00 -1.5374524e+00 9.3620996e+00 - -5.6991062e+00 -1.6193834e+00 1.0138424e+01 - -4.8562424e+00 -1.3991450e+00 9.1964149e+00 - -4.7063009e+00 -1.3591628e+00 9.2749175e+00 - -4.5300805e+00 -1.3129849e+00 9.3081970e+00 - -3.1320723e+00 -9.4862061e-01 7.2383738e+00 - -2.8569230e+00 -8.7578448e-01 6.9998948e+00 - -2.8389776e+00 -8.7210285e-01 7.2168704e+00 - -3.0343527e+00 -9.2268632e-01 7.8587588e+00 - -2.2314328e+00 -7.1314695e-01 6.5318485e+00 - -2.1416647e+00 -6.8963895e-01 6.5892077e+00 - -2.4975700e+00 -7.8178626e-01 7.6326287e+00 - -2.2197519e+00 -7.0967133e-01 7.3021554e+00 - -1.0037493e+00 -3.9215813e-01 4.6537489e+00 - -9.2743690e-01 -3.7221142e-01 4.6432828e+00 - -8.5818870e-01 -3.5400473e-01 4.6497668e+00 - -1.4960551e+00 -5.2068842e-01 6.6560861e+00 - -1.6966477e+00 -5.7299664e-01 7.5798392e+00 - -1.3820366e+00 -4.9081995e-01 6.9718010e+00 - -1.2438809e+00 -4.5455052e-01 6.8805498e+00 - -1.4649799e+00 -5.1175148e-01 8.0643912e+00 - -1.2422249e+00 -4.5390994e-01 7.7027221e+00 - -1.1452163e+00 -4.2880020e-01 7.8011083e+00 - -5.1530291e-01 -2.6373835e-01 5.5304920e+00 - -2.2546147e-01 -1.8846165e-01 4.5113393e+00 - -1.5436119e-01 -1.6998138e-01 4.4650334e+00 - -5.4384762e-01 -2.7149346e-01 7.0955804e+00 - -4.0505953e-01 -2.3459723e-01 6.8764367e+00 - -2.7844779e-01 -2.0217082e-01 6.6938333e+00 - -1.6881539e-01 -1.7344250e-01 6.5978236e+00 - -4.1549673e-02 -1.4021685e-01 6.2908234e+00 - 5.6892029e-02 -1.1405585e-01 6.1901033e+00 - 1.3761984e-01 -9.3551728e-02 6.2971275e+00 - 2.0425094e-01 -7.5457157e-02 6.7421741e+00 - 2.9637187e-01 -5.1283876e-02 6.8965056e+00 - 4.0119105e-01 -2.4229242e-02 6.5793352e+00 - -2.8589572e+00 -7.7234554e-01 -9.5169628e-01 - -2.9595166e+00 -7.9626153e-01 -9.2947061e-01 - -3.1047854e+00 -8.2950407e-01 -9.2723447e-01 - -3.2846201e+00 -8.7035364e-01 -9.3842700e-01 - -3.4400788e+00 -9.0671837e-01 -9.3066740e-01 - -3.6229588e+00 -9.4882378e-01 -9.3046523e-01 - -3.8078577e+00 -9.9150472e-01 -9.2411467e-01 - -4.0191681e+00 -1.0398932e+00 -9.2342708e-01 - -4.2599945e+00 -1.0957179e+00 -9.2659590e-01 - -4.4925827e+00 -1.1484590e+00 -9.1825323e-01 - -4.7729881e+00 -1.2127991e+00 -9.1885534e-01 - -5.0727028e+00 -1.2818345e+00 -9.1630320e-01 - -5.4202095e+00 -1.3622668e+00 -9.1860088e-01 - -5.7880051e+00 -1.4471862e+00 -9.1474483e-01 - -6.1862022e+00 -1.5380657e+00 -9.0630205e-01 - -6.6606948e+00 -1.6477257e+00 -9.0427153e-01 - -7.2225722e+00 -1.7774065e+00 -9.0672142e-01 - -7.8433336e+00 -1.9202634e+00 -9.0275120e-01 - -8.5910731e+00 -2.0917697e+00 -9.0299185e-01 - -9.2828356e+00 -2.2507663e+00 -8.6604807e-01 - -1.0264262e+01 -2.4767845e+00 -8.5454784e-01 - -1.1557656e+01 -2.7748672e+00 -8.5578955e-01 - -1.3200489e+01 -3.1522250e+00 -8.5857312e-01 - -1.4991586e+01 -3.5647104e+00 -8.1996091e-01 - -1.6417602e+01 -3.8929580e+00 -6.8112606e-01 - -1.9280459e+01 -4.5519746e+00 -6.0861845e-01 - -5.8284511e+01 -1.3527241e+01 2.5456286e+00 - -1.0182728e+01 -2.4571884e+00 4.2402680e+00 - -9.8938073e+00 -2.3906471e+00 4.3560512e+00 - -9.8069060e+00 -2.3710941e+00 4.5321693e+00 - -9.8924655e+00 -2.3902388e+00 4.7695328e+00 - -1.0027750e+01 -2.4211854e+00 5.0319152e+00 - -9.9936198e+00 -2.4141809e+00 5.2345095e+00 - -7.6055518e+00 -1.8646997e+00 4.4396346e+00 - -7.5105948e+00 -1.8419740e+00 4.5682883e+00 - -9.5065229e+00 -2.3014879e+00 5.6720941e+00 - -9.5311467e+00 -2.3066199e+00 5.9021825e+00 - -9.3681596e+00 -2.2694473e+00 6.0409174e+00 - -7.7416058e+00 -1.8952192e+00 5.3958565e+00 - -8.0513559e+00 -1.9668732e+00 5.7573422e+00 - -7.0943996e+00 -1.7463888e+00 5.4029425e+00 - -6.1872772e+00 -1.5375451e+00 5.0363085e+00 - -6.2333991e+00 -1.5482745e+00 5.2285586e+00 - -6.0371772e+00 -1.5030002e+00 5.2679669e+00 - -7.2319167e+00 -1.7785011e+00 6.2446106e+00 - -6.7558188e+00 -1.6684768e+00 6.1105894e+00 - -7.2153502e+00 -1.7738899e+00 6.6400690e+00 - -5.8647030e+00 -1.4635936e+00 5.8264510e+00 - -5.5884728e+00 -1.3999559e+00 5.7876648e+00 - -5.5291289e+00 -1.3861991e+00 5.9145778e+00 - -5.5275218e+00 -1.3855198e+00 6.0916528e+00 - -5.7214681e+00 -1.4304445e+00 6.4454983e+00 - -5.4088214e+00 -1.3584219e+00 6.3573136e+00 - -5.9561635e+00 -1.4838653e+00 7.0632390e+00 - -6.6239133e+00 -1.6372838e+00 7.9277807e+00 - -6.7345320e+00 -1.6629773e+00 8.2854697e+00 - -6.5888917e+00 -1.6293445e+00 8.3924468e+00 - -5.5290496e+00 -1.3861242e+00 7.5105420e+00 - -5.4108294e+00 -1.3582222e+00 7.6101614e+00 - -5.4525708e+00 -1.3676418e+00 7.8946337e+00 - -6.1379834e+00 -1.5257940e+00 8.9653718e+00 - -5.8527047e+00 -1.4601166e+00 8.8978940e+00 - -5.7060676e+00 -1.4260400e+00 8.9948307e+00 - -5.5746373e+00 -1.3960234e+00 9.1126869e+00 - -5.3723702e+00 -1.3491161e+00 9.1317524e+00 - -1.1431905e+00 -3.7681145e-01 3.3601569e+00 - -4.9649182e+00 -1.2555797e+00 9.1476517e+00 - -4.7657940e+00 -1.2101926e+00 9.1524939e+00 - -4.6475271e+00 -1.1829493e+00 9.2792789e+00 - -5.9641780e+00 -1.4852902e+00 1.1807911e+01 - -4.6897973e+00 -1.1923820e+00 1.0027027e+01 - -2.8351148e+00 -7.6585049e-01 7.0384918e+00 - -2.7454175e+00 -7.4497053e-01 7.1236151e+00 - -2.9970045e+00 -8.0345129e-01 7.8813820e+00 - -2.8274433e+00 -7.6381343e-01 7.8355272e+00 - -2.5126668e+00 -6.9166183e-01 7.4699810e+00 - -2.3493358e+00 -6.5462082e-01 7.4046685e+00 - -2.2485195e+00 -6.3123090e-01 7.4730790e+00 - -9.8354989e-01 -3.4055094e-01 4.6671984e+00 - -9.1341903e-01 -3.2435919e-01 4.6745774e+00 - -8.3018867e-01 -3.0487328e-01 4.6430654e+00 - -1.9870681e+00 -5.7020935e-01 8.1911464e+00 - -1.4585870e+00 -4.4906030e-01 6.9924410e+00 - -1.3568629e+00 -4.2542187e-01 7.0265914e+00 - -6.4626189e-01 -2.6213894e-01 4.9595163e+00 - -5.7311762e-01 -2.4546168e-01 4.9601445e+00 - -1.2252877e+00 -3.9570863e-01 7.8247007e+00 - -5.5213981e-01 -2.4084164e-01 5.4822315e+00 - -2.5166567e-01 -1.7209830e-01 4.4656383e+00 - -2.1368520e-01 -1.6337898e-01 4.5863234e+00 - -1.3572208e-01 -1.4528386e-01 4.5002451e+00 - -5.5690514e-01 -2.4105813e-01 7.4498984e+00 - -3.3284811e-01 -1.9021835e-01 6.6865708e+00 - -2.2831797e-01 -1.6568832e-01 6.6411619e+00 - -1.0608916e-01 -1.3768605e-01 6.4247618e+00 - 1.5813315e-02 -1.1022856e-01 6.1162770e+00 - 1.0028843e-01 -9.0379742e-02 6.1541250e+00 - 1.5009468e-01 -7.8874522e-02 6.7892344e+00 - 2.4964200e-01 -5.5525526e-02 6.7745522e+00 - 3.4812188e-01 -3.3701070e-02 6.7682621e+00 - 4.4733362e-01 -1.0970748e-02 6.6599970e+00 - -2.8284061e+00 -6.6436288e-01 -9.6191725e-01 - -2.9307296e+00 -6.8423914e-01 -9.4128170e-01 - -3.0584991e+00 -7.1014447e-01 -9.3160575e-01 - -3.2045098e+00 -7.3921557e-01 -9.2706771e-01 - -3.3870803e+00 -7.7575309e-01 -9.3555248e-01 - -3.5614809e+00 -8.1026793e-01 -9.3377461e-01 - -3.7277761e+00 -8.4379152e-01 -9.2238369e-01 - -3.9316121e+00 -8.8458314e-01 -9.2121586e-01 - -4.1638490e+00 -9.3090718e-01 -9.2460598e-01 - -4.4163491e+00 -9.8099714e-01 -9.2748501e-01 - -4.6698559e+00 -1.0316098e+00 -9.2192167e-01 - -4.9517439e+00 -1.0875971e+00 -9.1772024e-01 - -5.2823686e+00 -1.1539784e+00 -9.1951364e-01 - -5.6423494e+00 -1.2254867e+00 -9.1887046e-01 - -6.0226160e+00 -1.3014573e+00 -9.1157415e-01 - -6.4617004e+00 -1.3890437e+00 -9.0674599e-01 - -6.9595849e+00 -1.4881030e+00 -9.0148955e-01 - -7.5447244e+00 -1.6051152e+00 -8.9931446e-01 - -8.2190863e+00 -1.7397279e+00 -8.9552017e-01 - -9.0202284e+00 -1.8998613e+00 -8.9328885e-01 - -9.9105270e+00 -2.0770680e+00 -8.7875151e-01 - -1.1113287e+01 -2.3175967e+00 -8.8329160e-01 - -1.2308790e+01 -2.5563908e+00 -8.4410797e-01 - -1.4090518e+01 -2.9118030e+00 -8.3650361e-01 - -1.5738130e+01 -3.2403623e+00 -7.5125330e-01 - -1.5678340e+01 -3.2281997e+00 -4.5405458e-01 - -1.5983768e+01 -3.2897328e+00 -1.8640985e-01 - -5.5369437e+01 -1.1149012e+01 9.6193422e-01 - -2.3405442e+01 -4.7701536e+00 1.8350762e+00 - -2.3358392e+01 -4.7599601e+00 2.2588066e+00 - -9.5282900e+00 -2.0002214e+00 4.1188699e+00 - -9.5671411e+00 -2.0075602e+00 4.3276285e+00 - -9.5918415e+00 -2.0127890e+00 4.5354948e+00 - -9.0594109e+00 -1.9062804e+00 4.5404710e+00 - -9.1256301e+00 -1.9194504e+00 4.7600990e+00 - -9.1148795e+00 -1.9175200e+00 4.9532759e+00 - -9.1355165e+00 -1.9219099e+00 5.1627778e+00 - -1.1357496e+01 -2.3644782e+00 6.3731739e+00 - -9.8500429e+00 -2.0641710e+00 5.9124164e+00 - -9.3582866e+00 -1.9663766e+00 5.8944444e+00 - -8.1366373e+00 -1.7227464e+00 5.4797982e+00 - -8.0934720e+00 -1.7138106e+00 5.6515036e+00 - -7.4378750e+00 -1.5824235e+00 5.4792762e+00 - -6.9271414e+00 -1.4805230e+00 5.3651663e+00 - -6.6401586e+00 -1.4234911e+00 5.3679906e+00 - -6.3238682e+00 -1.3606881e+00 5.3409131e+00 - -6.2726894e+00 -1.3499478e+00 5.4779374e+00 - -6.5534357e+00 -1.4060949e+00 5.8435855e+00 - -6.3484754e+00 -1.3653870e+00 5.8824643e+00 - -7.0338129e+00 -1.5023087e+00 6.5731872e+00 - -6.7185104e+00 -1.4388474e+00 6.5379733e+00 - -5.8803439e+00 -1.2717469e+00 6.0751023e+00 - -5.8908503e+00 -1.2734876e+00 6.2694926e+00 - -4.4774869e+00 -9.9215501e-01 5.2520635e+00 - -5.9290574e+00 -1.2813532e+00 6.6904349e+00 - -5.5533036e+00 -1.2067184e+00 6.5498678e+00 - -5.8670371e+00 -1.2684725e+00 7.0451554e+00 - -6.6518469e+00 -1.4257805e+00 8.0322616e+00 - -6.5934163e+00 -1.4138640e+00 8.2219482e+00 - -6.4824215e+00 -1.3915684e+00 8.3614375e+00 - -5.5246034e+00 -1.2004716e+00 7.5782515e+00 - -6.5473939e+00 -1.4045746e+00 8.9693286e+00 - -6.3070500e+00 -1.3567304e+00 8.9727940e+00 - -6.0556154e+00 -1.3066029e+00 8.9549522e+00 - -5.8758964e+00 -1.2702883e+00 9.0160304e+00 - -1.2832519e+00 -3.5511717e-01 3.3237067e+00 - -1.2375234e+00 -3.4568357e-01 3.3470888e+00 - -1.1968630e+00 -3.3759676e-01 3.3775773e+00 - -1.1340249e+00 -3.2548699e-01 3.3746897e+00 - -4.9251335e+00 -1.0804713e+00 9.1874283e+00 - -5.5426432e+00 -1.2039619e+00 1.0473005e+01 - -6.1032934e+00 -1.3148962e+00 1.1757411e+01 - -5.9889518e+00 -1.2920303e+00 1.1993171e+01 - -2.6328147e+00 -6.2412739e-01 6.5233269e+00 - -2.5191393e+00 -6.0091207e-01 6.5433069e+00 - -2.4236521e+00 -5.8198614e-01 6.5961510e+00 - -2.4661881e+00 -5.9023358e-01 6.9234232e+00 - -2.4240448e+00 -5.8194361e-01 7.1010741e+00 - -2.3566804e+00 -5.6838962e-01 7.2336545e+00 - -2.3536969e+00 -5.6732628e-01 7.5210382e+00 - -2.2953346e+00 -5.5595657e-01 7.6996385e+00 - -9.6547378e-01 -2.9138508e-01 4.6894922e+00 - -8.6331791e-01 -2.7130156e-01 4.6122776e+00 - -1.5480676e+00 -4.0696453e-01 6.7215847e+00 - -1.9518504e+00 -4.8759735e-01 8.2412210e+00 - -1.3872246e+00 -3.7446225e-01 6.9050180e+00 - -1.7281806e+00 -4.4255985e-01 8.4101314e+00 - -6.2575401e-01 -2.2280867e-01 4.9886882e+00 - -5.5978436e-01 -2.1030065e-01 5.0178011e+00 - -5.9984003e-01 -2.1789616e-01 5.4822952e+00 - -5.1472433e-01 -2.0096530e-01 5.4622115e+00 - -2.3389936e-01 -1.4530701e-01 4.5015531e+00 - -1.6803265e-01 -1.3207442e-01 4.4845742e+00 - -7.3036023e-01 -2.4339074e-01 8.0801601e+00 - -4.3478734e-01 -1.8527640e-01 6.9850240e+00 - -2.9163462e-01 -1.5574945e-01 6.7036396e+00 - -1.8142662e-01 -1.3458425e-01 6.6176113e+00 - -3.7808788e-02 -1.0525151e-01 6.1714304e+00 - 4.5555108e-02 -8.8824368e-02 6.2399917e+00 - 1.4549476e-01 -6.9345601e-02 6.1075525e+00 - 1.9742125e-01 -5.8518340e-02 6.7921433e+00 - 3.0239182e-01 -3.7474254e-02 6.6367677e+00 - 3.9787780e-01 -1.8558185e-02 6.6894120e+00 - -2.8899277e+00 -5.7264653e-01 -9.4713835e-01 - -3.0001973e+00 -5.9120974e-01 -9.2992271e-01 - -3.1469788e+00 -6.1634096e-01 -9.2777698e-01 - -3.3028041e+00 -6.4192508e-01 -9.2555307e-01 - -3.4779196e+00 -6.7153757e-01 -9.2691620e-01 - -3.6540590e+00 -7.0181066e-01 -9.2263350e-01 - -3.8493602e+00 -7.3405417e-01 -9.2073853e-01 - -4.0639984e+00 -7.7121461e-01 -9.2018376e-01 - -4.2977855e+00 -8.1024200e-01 -9.1991930e-01 - -4.5518346e+00 -8.5302545e-01 -9.1894400e-01 - -4.8251406e+00 -8.9957123e-01 -9.1616239e-01 - -5.1003875e+00 -9.4555271e-01 -9.0438551e-01 - -5.4709237e+00 -1.0088786e+00 -9.1339228e-01 - -5.8525016e+00 -1.0730655e+00 -9.1277669e-01 - -6.2644791e+00 -1.1431977e+00 -9.0727474e-01 - -6.7168434e+00 -1.2187151e+00 -8.9775352e-01 - -7.2654764e+00 -1.3118828e+00 -8.9617900e-01 - -7.8748117e+00 -1.4151346e+00 -8.8872617e-01 - -8.6207609e+00 -1.5405727e+00 -8.8824662e-01 - -9.4659380e+00 -1.6837131e+00 -8.8017380e-01 - -1.0527736e+01 -1.8632706e+00 -8.7918002e-01 - -1.1621760e+01 -2.0472878e+00 -8.4562769e-01 - -1.3205853e+01 -2.3154058e+00 -8.3944429e-01 - -1.5037785e+01 -2.6243872e+00 -8.0628641e-01 - -1.7372802e+01 -3.0195795e+00 -7.5786068e-01 - -1.6161845e+01 -2.8142474e+00 -3.4152918e-01 - -1.5961522e+01 -2.7804213e+00 2.5961071e-01 - -1.0154711e+01 -1.7993534e+00 3.9883748e+00 - -9.7141254e+00 -1.7240948e+00 4.0602393e+00 - -9.5841214e+00 -1.7031121e+00 4.2165969e+00 - -9.5460512e+00 -1.6962540e+00 4.4008516e+00 - -9.3927418e+00 -1.6702742e+00 4.5448040e+00 - -9.0534400e+00 -1.6130750e+00 4.6145801e+00 - -8.9719243e+00 -1.5989533e+00 4.7757806e+00 - -8.7226639e+00 -1.5573463e+00 4.8664058e+00 - -8.7361402e+00 -1.5587085e+00 5.0648007e+00 - -8.7365340e+00 -1.5589760e+00 5.2607580e+00 - -9.4635761e+00 -1.6823308e+00 5.8104958e+00 - -9.4234256e+00 -1.6749236e+00 6.0083273e+00 - -1.0464509e+01 -1.8506264e+00 6.7780516e+00 - -1.0354574e+01 -1.8318577e+00 6.9663815e+00 - -7.7946323e+00 -1.3999145e+00 5.7511192e+00 - -7.7545844e+00 -1.3928110e+00 5.9225338e+00 - -6.4316435e+00 -1.1696130e+00 5.3006141e+00 - -6.1735107e+00 -1.1258280e+00 5.3045704e+00 - -5.8851325e+00 -1.0773294e+00 5.2786711e+00 - -5.8916824e+00 -1.0785693e+00 5.4475809e+00 - -6.2799307e+00 -1.1441425e+00 5.8965589e+00 - -6.7256224e+00 -1.2189007e+00 6.4138279e+00 - -6.0525350e+00 -1.1050889e+00 6.0908726e+00 - -6.2649990e+00 -1.1416794e+00 6.4486264e+00 - -6.1169892e+00 -1.1168324e+00 6.5229815e+00 - -4.5497597e+00 -8.5165863e-01 5.3674295e+00 - -4.3928247e+00 -8.2524322e-01 5.3832801e+00 - -6.5499377e+00 -1.1895106e+00 7.5415877e+00 - -6.6581427e+00 -1.2073476e+00 7.8786493e+00 - -6.8975122e+00 -1.2481357e+00 8.3614301e+00 - -2.9591832e+00 -5.8343306e-01 4.5640175e+00 - -5.5330005e+00 -1.0173970e+00 7.4372097e+00 - -5.7743433e+00 -1.0583960e+00 7.9335298e+00 - -6.3342608e+00 -1.1529462e+00 8.8219358e+00 - -5.9682995e+00 -1.0904205e+00 8.6680092e+00 - -5.8918233e+00 -1.0779331e+00 8.8507479e+00 - -1.3254490e+00 -3.0745021e-01 3.3233179e+00 - -1.2858384e+00 -3.0023093e-01 3.3552574e+00 - -1.2331733e+00 -2.9162448e-01 3.3704274e+00 - -1.1744555e+00 -2.8184007e-01 3.3762906e+00 - -1.1056839e+00 -2.7053641e-01 3.3643951e+00 - -3.7070489e+00 -7.0953123e-01 7.4348817e+00 - -3.5742863e+00 -6.8648897e-01 7.4745769e+00 - -1.4097990e+00 -3.2127053e-01 4.1536430e+00 - -1.3449685e+00 -3.1034442e-01 4.1697248e+00 - -1.2218059e+00 -2.9013751e-01 4.0801595e+00 - -1.1217695e+00 -2.7297991e-01 4.0222260e+00 - -1.0509124e+00 -2.6056863e-01 4.0149687e+00 - -9.7712485e-01 -2.4885108e-01 3.9973147e+00 - -2.4092376e+00 -4.9004887e-01 7.1718427e+00 - -1.0817252e+00 -2.6611990e-01 4.5116448e+00 - -1.0168811e+00 -2.5508540e-01 4.5299239e+00 - -9.5604122e-01 -2.4441684e-01 4.5561555e+00 - -8.4807063e-01 -2.2660443e-01 4.4604943e+00 - -8.3643998e-01 -2.2464728e-01 4.6149167e+00 - -1.7374402e+00 -3.7635928e-01 7.3897685e+00 - -7.9295886e-01 -2.1679779e-01 4.9064214e+00 - -7.2509563e-01 -2.0574757e-01 4.9286861e+00 - -6.6323148e-01 -1.9544668e-01 4.9689468e+00 - -6.0031511e-01 -1.8425854e-01 5.0081561e+00 - -5.6043080e-01 -1.7794646e-01 5.1432658e+00 - -5.7440319e-01 -1.8039401e-01 5.5210385e+00 - -2.8294368e-01 -1.3125430e-01 4.5632393e+00 - -2.1120326e-01 -1.1930571e-01 4.5275643e+00 - -1.4546069e-01 -1.0809659e-01 4.5100852e+00 - -5.8010175e-01 -1.8054688e-01 7.5090332e+00 - -3.6568820e-01 -1.4475183e-01 6.8349163e+00 - -2.3875180e-01 -1.2344105e-01 6.6510570e+00 - -1.0902616e-01 -1.0085755e-01 6.3751042e+00 - 8.5856112e-03 -8.1213059e-02 6.1262043e+00 - 9.9556722e-02 -6.6228131e-02 6.0942658e+00 - 1.6844557e-01 -5.4202354e-02 6.4199503e+00 - 2.5216844e-01 -4.0063980e-02 6.6447148e+00 - 3.4479921e-01 -2.4495115e-02 6.8081782e+00 - 4.4651734e-01 -7.9095804e-03 6.6600513e+00 - -2.9564660e+00 -4.8083485e-01 -9.3653836e-01 - -3.0847507e+00 -4.9869425e-01 -9.2705588e-01 - -3.2322145e+00 -5.1866200e-01 -9.2275767e-01 - -3.4080425e+00 -5.4335243e-01 -9.2686228e-01 - -3.5747062e+00 -5.6611019e-01 -9.2130669e-01 - -3.7707224e+00 -5.9345135e-01 -9.2255271e-01 - -3.9849569e+00 -6.2377598e-01 -9.2524121e-01 - -4.1829501e+00 -6.5135764e-01 -9.1354723e-01 - -4.4466664e+00 -6.8792930e-01 -9.2042806e-01 - -4.7022625e+00 -7.2339148e-01 -9.1529880e-01 - -4.9972394e+00 -7.6372112e-01 -9.1469251e-01 - -5.2932751e+00 -8.0550633e-01 -9.0429591e-01 - -5.6752264e+00 -8.5896674e-01 -9.1031466e-01 - -6.0692150e+00 -9.1320792e-01 -9.0630837e-01 - -6.5127172e+00 -9.7446646e-01 -9.0185053e-01 - -7.0340750e+00 -1.0472877e+00 -9.0174840e-01 - -7.5867316e+00 -1.1246864e+00 -8.9051406e-01 - -8.2484885e+00 -1.2167636e+00 -8.8338898e-01 - -9.0668288e+00 -1.3298675e+00 -8.8417236e-01 - -9.9660238e+00 -1.4554203e+00 -8.7042600e-01 - -1.1101619e+01 -1.6131657e+00 -8.6334435e-01 - -1.2377595e+01 -1.7905285e+00 -8.3630612e-01 - -1.4176991e+01 -2.0406095e+00 -8.2978354e-01 - -1.6157091e+01 -2.3157048e+00 -7.7926023e-01 - -1.6451253e+01 -2.3567389e+00 -5.0929204e-01 - -1.6356342e+01 -2.3441808e+00 -2.0181665e-01 - -1.0410217e+01 -1.5163560e+00 3.9429515e+00 - -1.0023963e+01 -1.4627207e+00 4.0384455e+00 - -1.0073803e+01 -1.4699827e+00 4.2555783e+00 - -1.0232595e+01 -1.4917689e+00 4.5122473e+00 - -9.7303434e+00 -1.4220220e+00 4.5481588e+00 - -9.2947150e+00 -1.3609355e+00 4.5912166e+00 - -9.1114524e+00 -1.3356719e+00 4.7167970e+00 - -9.1370404e+00 -1.3389252e+00 4.9229693e+00 - -9.0950587e+00 -1.3334733e+00 5.1038650e+00 - -8.7786324e+00 -1.2894829e+00 5.1626193e+00 - -8.6871769e+00 -1.2763008e+00 5.3169964e+00 - -1.0329829e+01 -1.5052302e+00 6.3230434e+00 - -1.0448071e+01 -1.5213540e+00 6.6218353e+00 - -1.0069073e+01 -1.4689344e+00 6.6638679e+00 - -9.8917606e+00 -1.4435119e+00 6.8055971e+00 - -8.5971196e+00 -1.2632887e+00 6.2937048e+00 - -7.1453981e+00 -1.0619770e+00 5.6301180e+00 - -5.9973518e+00 -9.0229758e-01 5.0918091e+00 - -5.8092778e+00 -8.7567529e-01 5.1294845e+00 - -5.8601963e+00 -8.8300314e-01 5.3237991e+00 - -6.1983611e+00 -9.2978413e-01 5.7273865e+00 - -5.2331659e+00 -7.9569098e-01 5.1987775e+00 - -6.4421511e+00 -9.6416539e-01 6.2731566e+00 - -6.4435468e+00 -9.6440199e-01 6.4685178e+00 - -4.8003742e+00 -7.3625652e-01 5.3262382e+00 - -4.8915202e+00 -7.4821261e-01 5.5601777e+00 - -4.5202214e+00 -6.9641331e-01 5.3987375e+00 - -4.5096892e+00 -6.9571290e-01 5.5467205e+00 - -4.5031022e+00 -6.9439134e-01 5.7024068e+00 - -6.8523070e+00 -1.0202997e+00 8.1568742e+00 - -2.9773304e+00 -4.8295825e-01 4.5050065e+00 - -2.8751947e+00 -4.6819345e-01 4.5225710e+00 - -5.7412536e+00 -8.6608904e-01 7.7461202e+00 - -5.5240560e+00 -8.3619702e-01 7.7437054e+00 - -6.0044279e+00 -9.0288590e-01 8.5426380e+00 - -5.9501961e+00 -8.9495358e-01 8.7479661e+00 - -3.8743172e+00 -6.0719766e-01 6.4449503e+00 - -3.3886909e+00 -5.3943542e-01 6.0170901e+00 - -1.2553671e+00 -2.4329895e-01 3.3470546e+00 - -1.1907078e+00 -2.3425660e-01 3.3452082e+00 - -1.1672953e+00 -2.3098275e-01 3.3991691e+00 - -1.0925890e+00 -2.2047534e-01 3.3784653e+00 - -1.0400107e+00 -2.1307769e-01 3.3893902e+00 - -1.0507867e+00 -2.1490985e-01 3.5008844e+00 - -9.9721694e-01 -2.0762684e-01 3.5107074e+00 - -1.3354437e+00 -2.5408621e-01 4.2032357e+00 - -1.1934162e+00 -2.3479771e-01 4.0777551e+00 - -1.1126177e+00 -2.2279703e-01 4.0541365e+00 - -1.0138413e+00 -2.0973431e-01 3.9930086e+00 - -8.4881649e-01 -1.8687885e-01 3.7856093e+00 - -7.2096846e-01 -1.6889878e-01 3.6367517e+00 - -1.0706408e+00 -2.1759858e-01 4.5528367e+00 - -1.0049214e+00 -2.0863814e-01 4.5708123e+00 - -8.9506878e-01 -1.9289127e-01 4.4762425e+00 - -6.9613732e-01 -1.6563398e-01 4.1362538e+00 - -8.1174501e-01 -1.8142636e-01 4.6265494e+00 - -8.4512522e-01 -1.8626275e-01 4.9326710e+00 - -7.7432113e-01 -1.7582251e-01 4.9462369e+00 - -7.0258711e-01 -1.6650371e-01 4.9585507e+00 - -6.3978809e-01 -1.5728486e-01 4.9983584e+00 - -5.6501373e-01 -1.4674964e-01 4.9984785e+00 - -5.0123073e-01 -1.3770454e-01 5.0359859e+00 - -5.4010328e-01 -1.4388249e-01 5.5304398e+00 - -4.5823365e-01 -1.3187504e-01 5.5284410e+00 - -1.7665204e-01 -9.2948768e-02 4.4944118e+00 - -4.5928778e-01 -1.3239069e-01 6.4653285e+00 - -5.1573926e-01 -1.3975171e-01 7.4393405e+00 - -2.9789491e-01 -1.0971992e-01 6.6937983e+00 - -2.1655637e-01 -9.8045425e-02 6.8459093e+00 - -4.0985444e-02 -7.3948309e-02 6.1515833e+00 - 3.8208601e-02 -6.2821194e-02 6.2698927e+00 - 1.4171365e-01 -4.8545783e-02 6.0976388e+00 - 1.9638885e-01 -4.0379773e-02 6.7522068e+00 - 3.0280477e-01 -2.5922550e-02 6.5467851e+00 - 3.9456392e-01 -1.2892054e-02 6.7993889e+00 - -2.9259482e+00 -3.7311824e-01 -9.5215268e-01 - -3.0378497e+00 -3.8555419e-01 -9.3472860e-01 - -3.1850838e+00 -4.0162280e-01 -9.3242637e-01 - -3.3343460e+00 -4.1834084e-01 -9.2547390e-01 - -3.5189259e+00 -4.3857331e-01 -9.3124625e-01 - -3.6882632e+00 -4.5600729e-01 -9.2273281e-01 - -3.8940245e+00 -4.7879061e-01 -9.2484438e-01 - -4.1007427e+00 -5.0118340e-01 -9.2026102e-01 - -4.3458645e+00 -5.2867162e-01 -9.2359964e-01 - -4.5929333e+00 -5.5564480e-01 -9.1894176e-01 - -4.8500156e+00 -5.8278380e-01 -9.0960821e-01 - -5.1747871e+00 -6.1855049e-01 -9.1394914e-01 - -5.5106113e+00 -6.5526678e-01 -9.1046549e-01 - -5.8857893e+00 -6.9663377e-01 -9.0711025e-01 - -6.3204270e+00 -7.4361373e-01 -9.0731628e-01 - -6.7943887e+00 -7.9500789e-01 -9.0285664e-01 - -7.3197749e+00 -8.5209956e-01 -8.9389370e-01 - -7.9531540e+00 -9.2202488e-01 -8.9094009e-01 - -8.6761963e+00 -1.0003945e+00 -8.8431313e-01 - -9.5283318e+00 -1.0929842e+00 -8.7668846e-01 - -1.0539857e+01 -1.2038833e+00 -8.6607537e-01 - -1.1779267e+01 -1.3390936e+00 -8.5465858e-01 - -1.3287930e+01 -1.5038070e+00 -8.3571896e-01 - -1.4878086e+01 -1.6764844e+00 -7.7333096e-01 - -1.7529404e+01 -1.9659972e+00 -7.5900376e-01 - -1.9181708e+01 -2.1457855e+00 -5.7212873e-01 - -1.9096864e+01 -2.1363974e+00 -2.1957951e-01 - -1.1793568e+01 -1.3398736e+00 4.4200739e+00 - -1.1541923e+01 -1.3120854e+00 4.5786490e+00 - -1.0985078e+01 -1.2517158e+00 4.6335093e+00 - -1.0411114e+01 -1.1885960e+00 4.6635980e+00 - -9.8775368e+00 -1.1303424e+00 4.6879685e+00 - -9.5414982e+00 -1.0944922e+00 4.7682295e+00 - -7.8738632e+00 -9.1201517e-01 4.3109940e+00 - -8.8996141e+00 -1.0239919e+00 4.9082715e+00 - -8.9765186e+00 -1.0320805e+00 5.1364255e+00 - -8.7130848e+00 -1.0039546e+00 5.2152129e+00 - -8.5130659e+00 -9.8193252e-01 5.3161192e+00 - -1.2018487e+01 -1.3636428e+00 7.5433839e+00 - -8.7017526e+00 -1.0024483e+00 6.2280180e+00 - -5.9017680e+00 -6.9753532e-01 4.7869557e+00 - -6.2002087e+00 -7.3000120e-01 5.1232099e+00 - -5.9259308e+00 -7.0001534e-01 5.1113270e+00 - -6.4597509e+00 -7.5754334e-01 5.6259871e+00 - -5.6159644e+00 -6.6612969e-01 5.2212821e+00 - -5.4524202e+00 -6.4779951e-01 5.2641236e+00 - -7.2568434e+00 -8.4440075e-01 6.7643847e+00 - -7.1082896e+00 -8.2840136e-01 6.8632025e+00 - -5.1219510e+00 -6.1235930e-01 5.4908197e+00 - -4.8739929e+00 -5.8528541e-01 5.4489055e+00 - -4.7055039e+00 -5.6659379e-01 5.4646652e+00 - -4.6114679e+00 -5.5638469e-01 5.5421781e+00 - -4.5837969e+00 -5.5329069e-01 5.6784231e+00 - -6.4784961e+00 -7.6005253e-01 7.6516247e+00 - -6.3198984e+00 -7.4261271e-01 7.7310857e+00 - -2.9104774e+00 -3.7060174e-01 4.4856349e+00 - -2.8155979e+00 -3.6014237e-01 4.5086631e+00 - -2.7207320e+00 -3.4979139e-01 4.5294939e+00 - -5.2766541e+00 -6.2871816e-01 7.5569278e+00 - -4.0953518e+00 -4.9962033e-01 6.4033617e+00 - -3.9822361e+00 -4.8758195e-01 6.4601412e+00 - -3.9112660e+00 -4.7942521e-01 6.5692364e+00 - -1.2332580e+00 -1.8837946e-01 3.2680151e+00 - -1.2239615e+00 -1.8745393e-01 3.3382988e+00 - -1.2116085e+00 -1.8569801e-01 3.4088231e+00 - -1.1129615e+00 -1.7521723e-01 3.3561336e+00 - -1.1216732e+00 -1.7559516e-01 3.4590329e+00 - -1.0782746e+00 -1.7180068e-01 3.4872131e+00 - -1.0408182e+00 -1.6726908e-01 3.5230031e+00 - -9.6126137e-01 -1.5870135e-01 3.4893490e+00 - -9.5692511e-01 -1.5826043e-01 3.5842175e+00 - -1.1630928e+00 -1.8059547e-01 4.0749943e+00 - -1.0684293e+00 -1.6979899e-01 4.0238156e+00 - -9.6278351e-01 -1.5810042e-01 3.9435890e+00 - -7.9507415e-01 -1.3996592e-01 3.7251922e+00 - -7.1056514e-01 -1.3097763e-01 3.6656549e+00 - -6.9613049e-01 -1.2917686e-01 3.7597933e+00 - -8.1981555e-01 -1.4315825e-01 4.1959827e+00 - -7.0222973e-01 -1.2991001e-01 4.0605380e+00 - -8.5768046e-01 -1.4674221e-01 4.6429440e+00 - -7.8811253e-01 -1.3969056e-01 4.6473732e+00 - -8.1937289e-01 -1.4262931e-01 4.9538887e+00 - -7.5075175e-01 -1.3562244e-01 4.9764483e+00 - -6.7808410e-01 -1.2739553e-01 4.9881093e+00 - -6.7326597e-01 -1.2722977e-01 5.2394815e+00 - -5.3183324e-01 -1.1166236e-01 4.9980448e+00 - -5.5772877e-01 -1.1449337e-01 5.4141571e+00 - -9.8599294e-01 -1.6078349e-01 7.7161173e+00 - -2.2063995e-01 -7.7642880e-02 4.5470939e+00 - -7.3403317e-01 -1.3336336e-01 7.6658510e+00 - -3.8743337e-01 -9.5506375e-02 6.3058716e+00 - -3.7950800e-01 -9.4320198e-02 6.8842777e+00 - -2.5792150e-01 -8.1249711e-02 6.7501187e+00 - -1.1588989e-01 -6.6354749e-02 6.3949712e+00 - -1.8160775e-02 -5.5687181e-02 6.3651062e+00 - 1.4347674e-01 -3.7422233e-02 5.4961381e+00 - 1.5693720e-01 -3.6529828e-02 6.5597229e+00 - 2.5282780e-01 -2.6027449e-02 6.5848453e+00 - 3.4334793e-01 -1.5376990e-02 6.8082380e+00 - 4.4570107e-01 -4.8484131e-03 6.6601056e+00 - -3.0043424e+00 -2.7805834e-01 -9.5115147e-01 - -3.1079752e+00 -2.8665012e-01 -9.2705954e-01 - -3.2740977e+00 -2.9992608e-01 -9.3188724e-01 - -3.4502566e+00 -3.1355015e-01 -9.3573470e-01 - -3.6102970e+00 -3.2644487e-01 -9.2550010e-01 - -3.8066447e+00 -3.4272459e-01 -9.2658885e-01 - -4.0049498e+00 -3.5857302e-01 -9.2137902e-01 - -4.2314157e+00 -3.7597099e-01 -9.2102522e-01 - -4.4780864e+00 -3.9615270e-01 -9.2050950e-01 - -4.7357688e+00 -4.1643979e-01 -9.1531493e-01 - -5.0226487e+00 -4.3904047e-01 -9.1142797e-01 - -5.3488394e+00 -4.6543285e-01 -9.1051552e-01 - -5.7051440e+00 -4.9290898e-01 -9.0746138e-01 - -6.1017943e+00 -5.2492609e-01 -9.0353369e-01 - -6.5285985e+00 -5.5886133e-01 -8.9411883e-01 - -7.0540723e+00 -6.0036498e-01 -8.9453490e-01 - -7.6298992e+00 -6.4652616e-01 -8.8840298e-01 - -8.3235152e+00 -7.0188621e-01 -8.8759824e-01 - -9.0985987e+00 -7.6294681e-01 -8.7850015e-01 - -1.0023739e+01 -8.3697771e-01 -8.6873709e-01 - -1.1107884e+01 -9.2314419e-01 -8.5238772e-01 - -1.2500113e+01 -1.0341254e+00 -8.4192364e-01 - -1.4182223e+01 -1.1680944e+00 -8.1882425e-01 - -1.6313268e+01 -1.3375856e+00 -7.8459325e-01 - -1.8665573e+01 -1.5240957e+00 -6.9569222e-01 - -1.1703494e+01 -9.6957202e-01 4.2706905e+00 - -1.1538813e+01 -9.5638803e-01 4.4535512e+00 - -1.1524994e+01 -9.5507610e-01 4.6783787e+00 - -1.1278928e+01 -9.3633761e-01 4.8297251e+00 - -8.1458367e+00 -6.8737885e-01 3.9794947e+00 - -8.0275997e+00 -6.7717877e-01 4.1064197e+00 - -8.0743210e+00 -6.8105128e-01 4.2946307e+00 - -7.9048898e+00 -6.6802457e-01 4.3993735e+00 - -7.4589867e+00 -6.3262145e-01 4.3821590e+00 - -8.7109704e+00 -7.3168151e-01 5.1056505e+00 - -3.8570332e+00 -3.4581729e-01 3.1275746e+00 - -8.7284888e+00 -7.3259574e-01 5.9136001e+00 - -6.3743948e+00 -5.4619172e-01 4.8156487e+00 - -6.2291659e+00 -5.3419904e-01 4.8903546e+00 - -5.7674989e+00 -4.9780477e-01 4.7709680e+00 - -5.6916308e+00 -4.9120835e-01 4.8748034e+00 - -6.4436078e+00 -5.5135256e-01 5.5156931e+00 - -5.6113302e+00 -4.8546391e-01 5.1283380e+00 - -5.5625947e+00 -4.8126926e-01 5.2517831e+00 - -5.3832854e+00 -4.6658008e-01 5.2808898e+00 - -5.3235648e+00 -4.6249190e-01 5.3953614e+00 - -5.3491257e+00 -4.6398105e-01 5.5765158e+00 - -5.4389938e+00 -4.7169939e-01 5.8165462e+00 - -5.8279761e+00 -5.0252331e-01 6.3179814e+00 - -4.1388302e+00 -3.6824167e-01 5.0382734e+00 - -4.9714764e+00 -4.3389564e-01 5.9344468e+00 - -3.8277084e+00 -3.4274431e-01 5.0414029e+00 - -6.2819898e+00 -5.3775642e-01 7.5598481e+00 - -3.0139892e+00 -2.7843083e-01 4.5190733e+00 - -2.9242859e+00 -2.7121363e-01 4.5513045e+00 - -2.7734458e+00 -2.6002321e-01 4.5157794e+00 - -2.7188455e+00 -2.5512006e-01 4.5798802e+00 - -4.1808021e+00 -3.7159477e-01 6.3930683e+00 - -4.0347323e+00 -3.5937153e-01 6.4128900e+00 - -3.9659367e+00 -3.5406505e-01 6.5225397e+00 - -3.8259621e+00 -3.4335970e-01 6.5447767e+00 - -3.5846976e+00 -3.2361582e-01 6.4279725e+00 - -2.4214686e+00 -2.3179962e-01 5.0270494e+00 - -1.1382749e+00 -1.2925781e-01 3.3419078e+00 - -3.0727284e+00 -2.8348707e-01 6.3035856e+00 - -2.1534375e+00 -2.0969976e-01 5.0910871e+00 - -3.2346174e+00 -2.9602547e-01 6.9847416e+00 - -1.0119225e+00 -1.2004912e-01 3.5192939e+00 - -9.8852903e-01 -1.1744214e-01 3.5799961e+00 - -1.1903991e+00 -1.3397145e-01 4.0515367e+00 - -9.9084849e-01 -1.1805535e-01 3.8070207e+00 - -9.0643506e-01 -1.1137802e-01 3.7614150e+00 - -8.4501790e-01 -1.0619634e-01 3.7586777e+00 - -7.7561458e-01 -1.0046013e-01 3.7364398e+00 - -7.0322190e-01 -9.4430553e-02 3.7035558e+00 - -6.5587753e-01 -9.1252313e-02 3.7241327e+00 - -7.4335131e-01 -9.8489411e-02 4.0776646e+00 - -6.9688550e-01 -9.4294936e-02 4.1176208e+00 - -6.5242322e-01 -9.0552816e-02 4.1662223e+00 - -1.9335038e+00 -1.9223974e-01 8.0709464e+00 - -7.8581506e-01 -1.0143222e-01 4.9557545e+00 - -7.1032883e-01 -9.5823981e-02 4.9585162e+00 - -6.4976928e-01 -9.1005884e-02 5.0079664e+00 - -5.7723378e-01 -8.4866499e-02 5.0178289e+00 - -5.2461519e-01 -8.0757410e-02 5.1039082e+00 - -5.5432008e-01 -8.2397510e-02 5.5595341e+00 - -9.6068804e-01 -1.1475150e-01 7.8657780e+00 - -1.5439655e+00 -1.6058256e-01 1.1502217e+01 - -4.4809745e-01 -7.4771174e-02 6.3667992e+00 - -3.5837384e-01 -6.7391388e-02 6.4023263e+00 - -3.0896191e-01 -6.2948243e-02 6.7334111e+00 - -2.0141308e-01 -5.4695040e-02 6.6870843e+00 - -6.3624864e-02 -4.3624925e-02 6.3305496e+00 - 4.0653279e-02 -3.5850216e-02 6.2100751e+00 - 1.2938859e-01 -2.8331152e-02 6.2472034e+00 - 2.0203003e-01 -2.2591533e-02 6.6124232e+00 - 3.0240819e-01 -1.4350149e-02 6.5167804e+00 - 3.9467679e-01 -7.3484670e-03 6.7294288e+00 - -3.2029543e+00 -1.8388442e-01 -9.3244360e-01 - -3.3698157e+00 -1.9296431e-01 -9.3447002e-01 - -3.5466531e+00 -2.0139535e-01 -9.3556575e-01 - -3.7164429e+00 -2.0976672e-01 -9.2689582e-01 - -3.9053356e+00 -2.1912141e-01 -9.2086293e-01 - -4.1314606e+00 -2.3070023e-01 -9.2410236e-01 - -4.3595362e+00 -2.4179357e-01 -9.1994455e-01 - -4.6168211e+00 -2.5529412e-01 -9.1899202e-01 - -4.8850544e+00 -2.6787845e-01 -9.1291080e-01 - -5.1915456e+00 -2.8336231e-01 -9.1075570e-01 - -5.5291556e+00 -2.9992367e-01 -9.0755437e-01 - -5.9059977e+00 -3.1913197e-01 -9.0438079e-01 - -6.3229975e+00 -3.3983126e-01 -8.9928380e-01 - -6.7902614e+00 -3.6344544e-01 -8.9283164e-01 - -7.3368837e+00 -3.9043214e-01 -8.8922758e-01 - -7.9830121e+00 -4.2260280e-01 -8.8885862e-01 - -8.6893928e+00 -4.5765218e-01 -8.7836388e-01 - -9.5455530e+00 -5.0087430e-01 -8.7124723e-01 - -1.0542328e+01 -5.5033649e-01 -8.5784848e-01 - -1.1758151e+01 -6.1056229e-01 -8.4286700e-01 - -1.3263424e+01 -6.8620903e-01 -8.2393637e-01 - -1.5148439e+01 -7.7960986e-01 -7.9627907e-01 - -1.7344911e+01 -8.8954257e-01 -7.3304321e-01 - -1.1531832e+01 -5.9850815e-01 4.5587061e+00 - -8.9522039e+00 -4.7031433e-01 3.9763681e+00 - -9.1262787e+00 -4.7893167e-01 4.2170627e+00 - -8.6077370e+00 -4.5285402e-01 4.2215866e+00 - -8.0912977e+00 -4.2750286e-01 4.2089380e+00 - -7.5136872e+00 -3.9893579e-01 4.1537014e+00 - -7.3004012e+00 -3.8805299e-01 4.2282422e+00 - -3.9723857e+00 -2.2264192e-01 2.9429896e+00 - -3.8375825e+00 -2.1513932e-01 2.9752286e+00 - -3.8292936e+00 -2.1526043e-01 3.0635925e+00 - -6.7344338e+00 -3.5939393e-01 4.6047052e+00 - -6.6707707e+00 -3.5697982e-01 4.7306491e+00 - -6.5779533e+00 -3.5208284e-01 4.8410718e+00 - -6.6837864e+00 -3.5775644e-01 5.0624769e+00 - -6.6982803e+00 -3.5818268e-01 5.2381039e+00 - -5.7800343e+00 -3.1174209e-01 4.8464716e+00 - -5.8217011e+00 -3.1437620e-01 5.0253790e+00 - -5.8091695e+00 -3.1377206e-01 5.1738551e+00 - -5.5699893e+00 -3.0131527e-01 5.1702623e+00 - -5.6677404e+00 -3.0618484e-01 5.3974851e+00 - -5.5820278e+00 -3.0231985e-01 5.4986911e+00 - -5.4231307e+00 -2.9465033e-01 5.5433887e+00 - -5.3514051e+00 -2.9055664e-01 5.6523793e+00 - -5.2686852e+00 -2.8649552e-01 5.7538944e+00 - -4.0375094e+00 -2.2503719e-01 4.8741910e+00 - -3.8947820e+00 -2.1799180e-01 4.8866794e+00 - -3.3913839e+00 -1.9319133e-01 4.5645566e+00 - -3.2637331e+00 -1.8658595e-01 4.5700510e+00 - -6.3877296e+00 -3.4257786e-01 7.7660384e+00 - -6.2617195e+00 -3.3558937e-01 7.8781555e+00 - -2.8788910e+00 -1.6722888e-01 4.5594116e+00 - -5.6192896e+00 -3.0422170e-01 7.6754994e+00 - -2.5216542e+00 -1.4992451e-01 4.4133764e+00 - -2.7795313e+00 -1.6239825e-01 4.8379045e+00 - -3.2716071e+00 -1.8740477e-01 5.5732773e+00 - -3.7144295e+00 -2.0902034e-01 6.2954630e+00 - -3.7368556e+00 -2.1060075e-01 6.5189548e+00 - -3.4260280e+00 -1.9497613e-01 6.3029022e+00 - -2.3339705e+00 -1.4056079e-01 4.9711460e+00 - -2.2924890e+00 -1.3859040e-01 5.0612042e+00 - -2.2379536e+00 -1.3523776e-01 5.1343931e+00 - -2.1225006e+00 -1.3017995e-01 5.1141071e+00 - -2.8706821e+00 -1.6669866e-01 6.4973250e+00 - -2.7140946e+00 -1.5934955e-01 6.4520417e+00 - -9.5876121e-01 -7.2320881e-02 3.5754840e+00 - -9.7035740e-01 -7.2154634e-02 3.7060083e+00 - -9.1910648e-01 -7.0422072e-02 3.7224273e+00 - -8.7080135e-01 -6.8118947e-02 3.7467460e+00 - -8.0151477e-01 -6.4347088e-02 3.7252064e+00 - -8.0805848e-01 -6.3990418e-02 3.8657025e+00 - -6.8994638e-01 -5.8699437e-02 3.7322490e+00 - -6.6458450e-01 -5.7468251e-02 3.8080254e+00 - -7.4787633e-01 -6.1887311e-02 4.1627942e+00 - -7.0346934e-01 -5.9102732e-02 4.2122443e+00 - -1.9795978e+00 -1.2211866e-01 7.9928796e+00 - -8.1276868e-01 -6.4668932e-02 4.9159603e+00 - -7.5331972e-01 -6.1720247e-02 4.9668113e+00 - -6.7795825e-01 -5.8140407e-02 4.9689729e+00 - -6.1746324e-01 -5.4353751e-02 5.0177736e+00 - -6.8012080e-01 -5.8230325e-02 5.5498071e+00 - -6.0065753e-01 -5.4020253e-02 5.5696342e+00 - -1.0412597e+00 -7.5557214e-02 7.9308240e+00 - -2.2015477e-01 -3.5515109e-02 4.5274912e+00 - -1.6475582e-01 -3.2782810e-02 4.5690664e+00 - -4.1691827e-01 -4.4244409e-02 6.4538103e+00 - -3.5389656e-01 -4.1497795e-02 6.6865736e+00 - -2.4945671e-01 -3.6041081e-02 6.6609292e+00 - -1.4702410e-01 -3.1066283e-02 6.6433309e+00 - -8.7753222e-04 -2.3988591e-02 6.1560802e+00 - 1.5329371e-01 -1.6865221e-02 5.3565926e+00 - 2.1919567e-01 -1.3149936e-02 5.5316192e+00 - 2.5074233e-01 -1.1361574e-02 6.5948480e+00 - 3.4463880e-01 -6.3937804e-03 6.7281888e+00 - 4.4581925e-01 -1.8410140e-03 6.6400319e+00 - -3.6769630e+00 -8.5959915e-02 -9.5096855e-01 - -3.8293493e+00 -8.8790929e-02 -9.3076465e-01 - -4.0088503e+00 -9.2333502e-02 -9.1746705e-01 - -4.2455944e+00 -9.7270572e-02 -9.2106867e-01 - -4.4842873e+00 -1.0170738e-01 -9.1697343e-01 - -4.7420609e+00 -1.0695014e-01 -9.1191967e-01 - -5.0389738e+00 -1.1306763e-01 -9.1148720e-01 - -5.3569477e+00 -1.1974206e-01 -9.0749306e-01 - -5.6859147e+00 -1.2637407e-01 -8.9582376e-01 - -6.1112346e+00 -1.3503882e-01 -9.0088091e-01 - -6.5395209e+00 -1.4381465e-01 -8.9159661e-01 - -7.0561174e+00 -1.5464864e-01 -8.8977566e-01 - -7.6238249e+00 -1.6609682e-01 -8.8170163e-01 - -8.3009015e+00 -1.8014532e-01 -8.7722964e-01 - -9.0883117e+00 -1.9646273e-01 -8.7086330e-01 - -1.0025172e+01 -2.1574640e-01 -8.6362835e-01 - -1.1073345e+01 -2.3759502e-01 -8.4146235e-01 - -1.2370271e+01 -2.6442562e-01 -8.1821595e-01 - -1.4047337e+01 -2.9848097e-01 -7.9687229e-01 - -1.6203850e+01 -3.4231556e-01 -7.6788150e-01 - -3.8785980e+01 -8.0665202e-01 2.8581902e-01 - -4.6071185e+01 -9.5568174e-01 9.6631568e-01 - -9.2098994e+00 -1.9884136e-01 3.7771363e+00 - -1.1215518e+01 -2.3974055e-01 4.5732984e+00 - -1.0133625e+01 -2.1806772e-01 4.4473052e+00 - -8.2942921e+00 -1.7980427e-01 4.0216551e+00 - -8.0432747e+00 -1.7487137e-01 4.1030649e+00 - -7.6519838e+00 -1.6642781e-01 4.1228609e+00 - -7.3919969e+00 -1.6111907e-01 4.1823699e+00 - -3.9014487e+00 -8.9382567e-02 2.8647904e+00 - -3.8320806e+00 -8.8569178e-02 2.9250971e+00 - -7.8581955e+00 -1.7097753e-01 4.8907035e+00 - -7.9687672e+00 -1.7278651e-01 5.1235615e+00 - -7.1740250e+00 -1.5649985e-01 4.9034879e+00 - -6.6096967e+00 -1.4484994e-01 4.7742753e+00 - -6.6132320e+00 -1.4559450e-01 4.9366341e+00 - -6.6467640e+00 -1.4648674e-01 5.1201111e+00 - -6.4199507e+00 -1.4156945e-01 5.1516093e+00 - -6.2952668e+00 -1.3868887e-01 5.2400077e+00 - -6.5389989e+00 -1.4394074e-01 5.5646695e+00 - -5.5544920e+00 -1.2327879e-01 5.0779816e+00 - -5.4579424e+00 -1.2173589e-01 5.1658186e+00 - -5.7886757e+00 -1.2817063e-01 5.5627643e+00 - -5.9802687e+00 -1.3211321e-01 5.8762264e+00 - -5.8075785e+00 -1.2828577e-01 5.9209283e+00 - -3.9951554e+00 -9.2060185e-02 4.6344828e+00 - -3.9456843e+00 -9.0538907e-02 4.7252148e+00 - -3.5931455e+00 -8.3270919e-02 4.5531710e+00 - -2.8465926e+00 -6.8147185e-02 4.0089520e+00 - -3.2693044e+00 -7.6901479e-02 4.5098072e+00 - -2.8118794e+00 -6.7099319e-02 4.1933137e+00 - -2.7195475e+00 -6.5565544e-02 4.2152960e+00 - -2.6982013e+00 -6.5308044e-02 4.3069648e+00 - -2.6667968e+00 -6.4010933e-02 4.3914115e+00 - -2.5944388e+00 -6.2385110e-02 4.4313345e+00 - -2.6320677e+00 -6.3868168e-02 4.5979450e+00 - -2.6716313e+00 -6.4737653e-02 4.7745496e+00 - -2.6182330e+00 -6.3466273e-02 4.8448445e+00 - -2.4709518e+00 -6.0730319e-02 4.7963418e+00 - -3.3015317e+00 -7.7294645e-02 6.0369088e+00 - -2.4720217e+00 -6.0427066e-02 5.0836879e+00 - -2.3197205e+00 -5.6728609e-02 5.0202885e+00 - -2.2942988e+00 -5.6566862e-02 5.1351655e+00 - -2.2209524e+00 -5.5594453e-02 5.1833248e+00 - -1.0607250e+00 -3.1173070e-02 3.4923829e+00 - -1.0065209e+00 -2.9951948e-02 3.5021006e+00 - -1.3284451e+00 -3.6991634e-02 4.1599435e+00 - -1.2821659e+00 -3.6351425e-02 4.2088870e+00 - -9.6264298e-01 -2.9547004e-02 3.7452100e+00 - -8.8253359e-01 -2.8210545e-02 3.7080043e+00 - -9.0606155e-01 -2.8496726e-02 3.8754700e+00 - -9.2253227e-01 -2.8130273e-02 4.0444620e+00 - -8.0858692e-01 -2.6567360e-02 3.9318436e+00 - -7.0258929e-01 -2.4220316e-02 3.8253431e+00 - -7.4691848e-01 -2.5050761e-02 4.0776685e+00 - -2.0605687e+00 -5.1775423e-02 7.6548963e+00 - -6.8620095e-01 -2.4127551e-02 4.2507622e+00 - -6.7170630e-01 -2.3910353e-02 4.3938386e+00 - -7.9819001e-01 -2.6045400e-02 4.9842518e+00 - -7.1401705e-01 -2.4384167e-02 4.9585193e+00 - -6.2785721e-01 -2.2403600e-02 4.9214448e+00 - -5.9626385e-01 -2.1660375e-02 5.0757036e+00 - -6.3589430e-01 -2.2247643e-02 5.5404501e+00 - -1.1166627e+00 -3.2665749e-02 7.9756310e+00 - -2.5990955e-01 -1.5434933e-02 4.5602875e+00 - -2.0949836e-01 -1.3923082e-02 4.6317904e+00 - -1.8074477e-01 -1.3309230e-02 4.8405404e+00 - -3.6033832e-01 -1.7118238e-02 6.4023616e+00 - -3.1210563e-01 -1.6124570e-02 6.7433358e+00 - -1.9999261e-01 -1.3130246e-02 6.6572910e+00 - -8.6080760e-02 -1.1319241e-02 6.5294418e+00 - 1.0803098e-01 -7.3197843e-03 5.4330958e+00 - 1.6801605e-01 -5.7600350e-03 5.6786520e+00 - 2.0106153e-01 -4.9737820e-03 6.6024489e+00 - 3.0307286e-01 -2.8498063e-03 6.5067974e+00 - 3.9497687e-01 -1.3403506e-03 6.7094063e+00 - -3.7304664e+00 3.8628257e-02 -9.3105225e-01 - -3.9196906e+00 4.0335012e-02 -9.2486209e-01 - -4.1279506e+00 4.2109607e-02 -9.2025987e-01 - -4.3652453e+00 4.4418592e-02 -9.2001034e-01 - -4.6135543e+00 4.6602495e-02 -9.1548146e-01 - -4.8909440e+00 4.8437149e-02 -9.1295856e-01 - -5.1892786e+00 5.1674273e-02 -9.0767222e-01 - -5.5267372e+00 5.4159839e-02 -9.0451027e-01 - -5.9041851e+00 5.8046741e-02 -9.0157108e-01 - -6.3116712e+00 6.1970009e-02 -8.9404283e-01 - -6.7892958e+00 6.5930030e-02 -8.9028863e-01 - -7.3269811e+00 7.0605012e-02 -8.8459698e-01 - -7.9437600e+00 7.6087427e-02 -8.7805642e-01 - -8.6716456e+00 8.3221111e-02 -8.7241333e-01 - -9.5087282e+00 9.0162225e-02 -8.6208174e-01 - -1.0466900e+01 9.8835119e-02 -8.4297811e-01 - -1.1664382e+01 1.0979010e-01 -8.2661488e-01 - -1.3052083e+01 1.2201785e-01 -7.9382135e-01 - -1.4849307e+01 1.3797446e-01 -7.5988532e-01 - -1.7098048e+01 1.5807014e-01 -7.0704618e-01 - -3.8235188e+01 3.4844000e-01 -4.2289713e-02 - -4.2147192e+01 3.8379892e-01 5.9697516e-01 - -1.3463439e+01 1.2609166e-01 4.6005675e+00 - -9.4860011e+00 8.9894333e-02 3.7615942e+00 - -8.8701390e+00 8.5122697e-02 3.7682405e+00 - -8.5825107e+00 8.2157462e-02 3.8563220e+00 - -8.4929557e+00 8.0969727e-02 4.0018078e+00 - -8.1472852e+00 7.8780402e-02 4.0549501e+00 - -8.0267855e+00 7.6761770e-02 4.1809620e+00 - -8.5752508e+00 8.1936664e-02 4.5670647e+00 - -8.4836337e+00 8.1669324e-02 4.7133935e+00 - -3.8304847e+00 3.9451565e-02 2.8792234e+00 - -4.8260458e+00 4.8343933e-02 3.4223931e+00 - -4.7016963e+00 4.7521028e-02 3.4762334e+00 - -4.6210047e+00 4.6804859e-02 3.6607989e+00 - -4.4677230e+00 4.5143861e-02 3.6925749e+00 - -4.3763860e+00 4.4701252e-02 3.7543097e+00 - -6.4488138e+00 6.3537467e-02 5.0859011e+00 - -6.2054879e+00 6.0686664e-02 5.1022616e+00 - -4.2593961e+00 4.3173251e-02 4.0272003e+00 - -6.1834342e+00 6.0924859e-02 5.4164013e+00 - -6.0390172e+00 5.9725573e-02 5.4870572e+00 - -5.4880330e+00 5.4479787e-02 5.2640436e+00 - -6.3536112e+00 6.2224524e-02 6.0631842e+00 - -4.0336563e+00 4.1660773e-02 4.4729329e+00 - -3.9014530e+00 3.9819009e-02 4.4956365e+00 - -3.2688863e+00 3.4186516e-02 4.1016281e+00 - -3.0158945e+00 3.1817526e-02 3.9981575e+00 - -3.4208917e+00 3.6247722e-02 4.4629093e+00 - -2.8065061e+00 3.0507887e-02 4.0244635e+00 - -3.3332477e+00 3.5346641e-02 4.6320220e+00 - -2.7629177e+00 2.9630464e-02 4.2010558e+00 - -2.7276220e+00 2.9358730e-02 4.2788476e+00 - -2.6424289e+00 2.8556347e-02 4.3056950e+00 - -2.6719923e+00 2.8777496e-02 4.4558515e+00 - -5.3504357e+00 5.3021969e-02 7.6017505e+00 - -3.4203632e+00 3.5700172e-02 5.5827142e+00 - -2.6458210e+00 2.8740821e-02 4.8098286e+00 - -2.6224321e+00 2.8732791e-02 4.9188192e+00 - -2.5661634e+00 2.7799352e-02 4.9886044e+00 - -2.5856015e+00 2.8563930e-02 5.1620004e+00 - -2.4774677e+00 2.7266447e-02 5.1664031e+00 - -2.4659749e+00 2.7605874e-02 5.3082905e+00 - -2.3359258e+00 2.6171099e-02 5.2760196e+00 - -2.5406630e+00 2.7644726e-02 5.7632102e+00 - -2.9853315e+00 3.1676625e-02 6.6762792e+00 - -2.7126906e+00 2.9713864e-02 6.4434078e+00 - -1.0242741e+00 1.4490993e-02 3.6885504e+00 - -9.8213407e-01 1.3686304e-02 3.7235735e+00 - -8.8821065e-01 1.2895514e-02 3.6603554e+00 - -8.5002262e-01 1.2657790e-02 3.7019830e+00 - -9.3220816e-01 1.3168318e-02 3.9958270e+00 - -8.7209622e-01 1.2862277e-02 4.0021793e+00 - -7.8319857e-01 1.1578777e-02 3.9431216e+00 - -6.4359928e-01 1.0732786e-02 3.7526677e+00 - -7.9310182e-01 1.2595005e-02 4.2744412e+00 - -7.2607917e-01 1.1254900e-02 4.2683866e+00 - -6.8479411e-01 1.1139528e-02 4.3364216e+00 - -8.4587764e-01 1.2257966e-02 5.0107914e+00 - -7.8161439e-01 1.2462160e-02 5.0526368e+00 - -6.9363147e-01 1.1390084e-02 5.0169031e+00 - -6.1059191e-01 1.0999616e-02 4.9888758e+00 - -5.5827319e-01 1.0133786e-02 5.0754026e+00 - -3.9129384e-01 8.2088806e-03 4.6946984e+00 - -3.2414131e-01 8.4224503e-03 4.6998803e+00 - -2.4719555e-01 7.5571376e-03 4.6548930e+00 - -1.7425151e-01 6.3455887e-03 4.6182578e+00 - -1.0425080e-01 5.7243083e-03 4.5899219e+00 - -3.0881191e-01 7.7461892e-03 6.3799913e+00 - -2.4492152e-01 7.8504080e-03 6.6211898e+00 - -1.4971409e-01 6.7046421e-03 6.6532989e+00 - 6.3822533e-02 4.1608670e-03 5.4892720e+00 - 1.5643586e-01 4.0322638e-03 5.3166945e+00 - 2.4392457e-01 3.1368097e-03 5.1224596e+00 - 2.4878180e-01 3.2712303e-03 6.6447006e+00 - 3.4692845e-01 2.5339055e-03 6.6482362e+00 - 4.4593949e-01 6.6703024e-04 6.6300954e+00 - -3.8179435e+00 1.6550011e-01 -9.2665814e-01 - -4.0248625e+00 1.7304818e-01 -9.2535270e-01 - -4.2437416e+00 1.8146453e-01 -9.2111268e-01 - -4.4995985e+00 1.9175294e-01 -9.2414588e-01 - -4.7674634e+00 2.0201121e-01 -9.2219743e-01 - -5.0173272e+00 2.1093822e-01 -9.0497552e-01 - -5.3441540e+00 2.2368725e-01 -9.0438794e-01 - -5.7209734e+00 2.3826968e-01 -9.0748702e-01 - -6.0987741e+00 2.5253145e-01 -8.9804879e-01 - -6.5365447e+00 2.6926561e-01 -8.9156628e-01 - -7.0332673e+00 2.8856936e-01 -8.8484662e-01 - -7.6299653e+00 3.1161873e-01 -8.8390225e-01 - -8.2866273e+00 3.3667070e-01 -8.7517725e-01 - -9.0732508e+00 3.6643756e-01 -8.6898642e-01 - -9.9997852e+00 4.0178002e-01 -8.6010439e-01 - -1.1017227e+01 4.4047995e-01 -8.3360557e-01 - -1.2284518e+01 4.8925833e-01 -8.0706286e-01 - -1.3871625e+01 5.5055473e-01 -7.7605963e-01 - -1.5857533e+01 6.2654798e-01 -7.3220592e-01 - -1.8413139e+01 7.2384831e-01 -6.6946634e-01 - -3.9176388e+01 1.5181988e+00 -4.1527790e-01 - -3.7746779e+01 1.4635974e+00 3.0428579e-01 - -1.2873890e+01 5.1218921e-01 4.3265728e+00 - -1.1964294e+01 4.7760168e-01 4.3324763e+00 - -1.2154315e+01 4.8436983e-01 4.6211704e+00 - -9.4704360e+00 3.8176293e-01 4.0424651e+00 - -9.3110439e+00 3.7606780e-01 4.1821352e+00 - -9.4242685e+00 3.8026424e-01 4.4115094e+00 - -4.1033826e+00 1.7607399e-01 2.6728203e+00 - -3.9143644e+00 1.6962705e-01 2.6920964e+00 - -3.8571837e+00 1.6742928e-01 2.7577331e+00 - -3.8439330e+00 1.6677436e-01 2.8413868e+00 - -4.1031614e+00 1.7659553e-01 3.0468546e+00 - -4.0669142e+00 1.7537478e-01 3.1268900e+00 - -7.3629094e+00 3.0164285e-01 4.8302907e+00 - -8.0160313e+00 3.2601766e-01 5.3342380e+00 - -4.6377611e+00 1.9664481e-01 3.7289040e+00 - -4.4757111e+00 1.9117300e-01 3.7552069e+00 - -3.6482768e+00 1.5926340e-01 3.3922300e+00 - -4.2744549e+00 1.8349920e-01 3.8655803e+00 - -3.9010160e+00 1.6910865e-01 3.7473411e+00 - -4.2467891e+00 1.8242593e-01 4.0794264e+00 - -6.4217351e+00 2.6518597e-01 5.6644130e+00 - -3.8172108e+00 1.6555319e-01 4.0198357e+00 - -6.5382303e+00 2.7023728e-01 6.1088305e+00 - -6.5595829e+00 2.7074482e-01 6.3150916e+00 - -3.9367675e+00 1.6973470e-01 4.4632137e+00 - -3.2384453e+00 1.4386781e-01 4.0245417e+00 - -3.2002166e+00 1.4240792e-01 4.1021737e+00 - -2.9347701e+00 1.3147627e-01 3.9828285e+00 - -3.5582954e+00 1.5619615e-01 4.6507787e+00 - -3.1573153e+00 1.3995109e-01 4.4076069e+00 - -5.2982958e+00 2.2251107e-01 6.5949369e+00 - -5.3275627e+00 2.2355464e-01 6.8225467e+00 - -2.7177545e+00 1.2351197e-01 4.3285093e+00 - -2.6795264e+00 1.2204715e-01 4.4060414e+00 - -3.5297001e+00 1.5511590e-01 5.4710673e+00 - -3.5162521e+00 1.5449020e-01 5.6160941e+00 - -3.5187479e+00 1.5401528e-01 5.7851414e+00 - -2.4150726e+00 1.1152046e-01 4.5963643e+00 - -2.6844003e+00 1.2233849e-01 5.0719785e+00 - -2.6789518e+00 1.2208307e-01 5.2147335e+00 - -2.6645028e+00 1.2193569e-01 5.3504191e+00 - -2.5764262e+00 1.1851782e-01 5.3886916e+00 - -2.3590466e+00 1.0976529e-01 5.2345926e+00 - -2.4868650e+00 1.1428469e-01 5.5940013e+00 - -2.3212013e+00 1.0812167e-01 5.5098798e+00 - -2.2987231e+00 1.0784049e-01 5.6526311e+00 - -2.1977618e+00 1.0342174e-01 5.6662432e+00 - -2.1981016e+00 1.0410194e-01 5.8611521e+00 - -9.6242911e-01 5.6700267e-02 3.7451594e+00 - -9.1436115e-01 5.5045133e-02 3.7702756e+00 - -9.1796215e-01 5.4806608e-02 3.9023725e+00 - -9.1756432e-01 5.4375551e-02 4.0354554e+00 - -9.0123878e-01 5.3665621e-02 4.1419210e+00 - -6.6661863e-01 4.4724766e-02 3.7426225e+00 - -8.0201753e-01 5.0384097e-02 4.2166632e+00 - -8.9268288e-01 5.3916483e-02 4.6215475e+00 - -8.4057746e-01 5.1346004e-02 4.6735170e+00 - -6.8738323e-01 4.5590577e-02 4.4411695e+00 - -1.6924219e+00 8.4300905e-02 7.7322178e+00 - -6.5533411e-01 4.4818526e-02 4.7673122e+00 - -6.6050710e-01 4.4481694e-02 5.0367931e+00 - -5.2821065e-01 3.9989035e-02 4.8246371e+00 - -4.5922826e-01 3.7204155e-02 4.8322584e+00 - -3.6066604e-01 3.3297952e-02 4.7119949e+00 - -2.8876704e-01 3.0225089e-02 4.6971847e+00 - -1.9422254e-01 2.7391886e-02 4.5532639e+00 - -1.7345472e-01 2.6422944e-02 4.8011894e+00 - -9.4714032e-02 2.3311556e-02 4.7333736e+00 - -2.8973060e-01 3.0820044e-02 6.5848896e+00 - -2.1416863e-01 2.7750278e-02 6.7764112e+00 - 4.3062548e-02 1.8386814e-02 5.3062734e+00 - 1.1709639e-01 1.5268369e-02 5.3335042e+00 - 1.9492747e-01 1.1893683e-02 5.2996488e+00 - 2.8690518e-01 8.2329521e-03 4.9946860e+00 - 3.0274080e-01 8.2067049e-03 6.5068548e+00 - 3.9521529e-01 4.1750927e-03 6.6793961e+00 - -3.5608189e+00 2.7648356e-01 -9.4423291e-01 - -3.7124359e+00 2.8650457e-01 -9.2687045e-01 - -3.9099431e+00 3.0054146e-01 -9.2484183e-01 - -4.1264844e+00 3.1466098e-01 -9.2410152e-01 - -4.3549224e+00 3.3067036e-01 -9.1997679e-01 - -4.6023846e+00 3.4684119e-01 -9.1554235e-01 - -4.8787451e+00 3.6566841e-01 -9.1296291e-01 - -5.1860518e+00 3.8634495e-01 -9.1078428e-01 - -5.5222390e+00 4.0982076e-01 -9.0756422e-01 - -5.9093517e+00 4.3622678e-01 -9.0727818e-01 - -6.3064435e+00 4.6274288e-01 -8.9672337e-01 - -6.7733731e+00 4.9427558e-01 -8.9029023e-01 - -7.3091216e+00 5.3093194e-01 -8.8458614e-01 - -7.9346547e+00 5.7394692e-01 -8.8024345e-01 - -8.6599975e+00 6.2306108e-01 -8.7448416e-01 - -9.4960495e+00 6.8009892e-01 -8.6402690e-01 - -1.0471813e+01 7.4585594e-01 -8.4793090e-01 - -1.1617096e+01 8.2426272e-01 -8.2370296e-01 - -1.3001833e+01 9.1854395e-01 -7.9127071e-01 - -1.4735765e+01 1.0363214e+00 -7.5083331e-01 - -1.6998497e+01 1.1895027e+00 -7.0126871e-01 - -3.9565455e+01 2.7240872e+00 2.0224166e+00 - -3.9541289e+01 2.7223411e+00 2.7230177e+00 - -1.1891249e+01 8.4246784e-01 3.9723057e+00 - -1.1847642e+01 8.3967182e-01 4.1910444e+00 - -1.1810012e+01 8.3734197e-01 4.4118996e+00 - -1.0092836e+01 7.1993515e-01 4.1365575e+00 - -1.0094185e+01 7.2006806e-01 4.3394095e+00 - -9.6938392e+00 6.9338330e-01 4.4101432e+00 - -9.1899270e+00 6.5898475e-01 4.4313573e+00 - -9.4843138e+00 6.7872728e-01 4.7331719e+00 - -3.8744225e+00 2.9815717e-01 2.7232562e+00 - -3.8064113e+00 2.9306899e-01 2.7842628e+00 - -3.7931643e+00 2.9238451e-01 2.8673173e+00 - -4.0599177e+00 3.0997834e-01 3.0787559e+00 - -4.1133670e+00 3.1427341e-01 3.2011248e+00 - -4.7615411e+00 3.5841658e-01 3.6244682e+00 - -4.7064060e+00 3.5439824e-01 3.7115337e+00 - -3.7548823e+00 2.8907289e-01 3.3113922e+00 - -3.9657051e+00 3.0354757e-01 3.5280460e+00 - -3.7492448e+00 2.8929678e-01 3.5043844e+00 - -3.9261724e+00 3.0137622e-01 3.7140387e+00 - -3.8193045e+00 2.9387313e-01 3.7534982e+00 - -3.6297646e+00 2.8149590e-01 3.7348163e+00 - -3.8444772e+00 2.9600195e-01 3.9877374e+00 - -3.7754501e+00 2.9099619e-01 4.0516372e+00 - -3.8497523e+00 2.9588047e-01 4.2210637e+00 - -3.9598411e+00 3.0360431e-01 4.4243126e+00 - -3.6260721e+00 2.8048832e-01 4.2841207e+00 - -3.1908001e+00 2.5130881e-01 4.0443791e+00 - -3.0611012e+00 2.4243366e-01 4.0436158e+00 - -3.0229493e+00 2.3984379e-01 4.1186006e+00 - -4.1746026e+00 3.1832148e-01 5.2868754e+00 - -4.1791103e+00 3.1835843e-01 5.4435947e+00 - -4.1298882e+00 3.1479464e-01 5.5528015e+00 - -4.0497801e+00 3.0993192e-01 5.6330462e+00 - -3.8175796e+00 2.9390454e-01 5.5524047e+00 - -3.7106753e+00 2.8669212e-01 5.5977569e+00 - -3.8016433e+00 2.9244748e-01 5.8653643e+00 - -2.8080214e+00 2.2538208e-01 4.8759221e+00 - -2.6008506e+00 2.1129315e-01 4.7635003e+00 - -2.4414126e+00 2.0050630e-01 4.6998703e+00 - -2.4370400e+00 1.9969057e-01 4.8300441e+00 - -2.6610969e+00 2.1525336e-01 5.2745069e+00 - -2.7202218e+00 2.1880510e-01 5.5162947e+00 - -2.6292668e+00 2.1324646e-01 5.5553560e+00 - -2.4886945e+00 2.0388722e-01 5.5177040e+00 - -1.0843469e+00 1.0841497e-01 3.4871450e+00 - -1.1873034e+00 1.1481197e-01 3.7530926e+00 - -1.1333357e+00 1.1156562e-01 3.7735450e+00 - -1.0903075e+00 1.0879033e-01 3.8103619e+00 - -2.3993099e+00 1.9729806e-01 6.3413935e+00 - -1.0003309e+00 1.0190246e-01 3.8820349e+00 - -1.0256701e+00 1.0424839e-01 4.0598949e+00 - -9.7272554e-01 1.0034637e-01 4.0860931e+00 - -8.4738999e-01 9.2360846e-02 3.9566541e+00 - -7.2812400e-01 8.3578488e-02 3.8239879e+00 - -6.2967257e-01 7.6724006e-02 3.7249965e+00 - -8.0142697e-01 8.8712344e-02 4.3023769e+00 - -7.6131518e-01 8.5710899e-02 4.3714627e+00 - -7.9234082e-01 8.8258031e-02 4.6473688e+00 - -7.1657637e-01 8.2895266e-02 4.6315464e+00 - -6.8921510e-01 8.0935522e-02 4.7666409e+00 - -6.2626673e-01 7.6606359e-02 4.7964028e+00 - -5.7612458e-01 7.3389627e-02 4.8733470e+00 - -5.0526136e-01 6.8529352e-02 4.8818601e+00 - -4.1667671e-01 6.2681606e-02 4.8113150e+00 - -3.7435796e-01 6.0211007e-02 4.9341273e+00 - -2.1806520e-01 4.9131487e-02 4.5176960e+00 - -1.7482535e-01 4.5984597e-02 4.6280205e+00 - -1.5892567e-01 4.4750992e-02 4.9252499e+00 - -3.0696561e-01 5.4776822e-02 6.3799629e+00 - -2.4331671e-01 5.0888295e-02 6.6212596e+00 - -1.5908217e-01 4.5305542e-02 6.7525773e+00 - 1.0301757e-01 2.7141643e-02 5.0911070e+00 - 1.5565150e-01 2.3637242e-02 5.3267458e+00 - 2.4764007e-01 1.7484664e-02 5.0725683e+00 - 2.5237318e-01 1.7142946e-02 6.5648966e+00 - 3.4566663e-01 1.1103070e-02 6.7182081e+00 - 4.4518425e-01 4.2159439e-03 6.6400374e+00 - -2.9899270e+00 3.4019708e-01 -9.4629413e-01 - -3.1203867e+00 3.5257680e-01 -9.3648764e-01 - -3.2777363e+00 3.6810469e-01 -9.3638243e-01 - -3.4360538e+00 3.8393445e-01 -9.3138008e-01 - -3.6223072e+00 4.0207439e-01 -9.3402876e-01 - -3.8185312e+00 4.2090752e-01 -9.3484786e-01 - -4.0167121e+00 4.4017685e-01 -9.2926849e-01 - -4.2338053e+00 4.6153257e-01 -9.2487678e-01 - -4.4898117e+00 4.8588314e-01 -9.2770161e-01 - -4.7467652e+00 5.1070308e-01 -9.2223350e-01 - -5.0335512e+00 5.3926638e-01 -9.1806749e-01 - -5.3492834e+00 5.6958765e-01 -9.1370940e-01 - -5.7058268e+00 6.0432709e-01 -9.1041868e-01 - -6.0822351e+00 6.4157794e-01 -9.0092157e-01 - -6.4985558e+00 6.8136010e-01 -8.8900011e-01 - -7.0323925e+00 7.3350821e-01 -8.9218200e-01 - -7.5970419e+00 7.8908888e-01 -8.8392893e-01 - -8.2424075e+00 8.5167814e-01 -8.7312037e-01 - -9.0252492e+00 9.2735286e-01 -8.6701472e-01 - -9.9385242e+00 1.0161333e+00 -8.5664534e-01 - -1.0971262e+01 1.1167664e+00 -8.3370790e-01 - -1.2224084e+01 1.2389662e+00 -8.0576995e-01 - -1.3794634e+01 1.3916033e+00 -7.7356742e-01 - -1.5723643e+01 1.5797559e+00 -7.2478422e-01 - -1.8407640e+01 1.8406128e+00 -6.7562783e-01 - -3.9217473e+01 3.8674706e+00 -4.2247578e-01 - -3.9601494e+01 3.9047444e+00 9.7077385e-01 - -4.5337755e+01 4.4624968e+00 1.7704466e+00 - -4.6371864e+01 4.5636907e+00 2.6102725e+00 - -4.7985741e+01 4.7205859e+00 4.3707640e+00 - -5.2470637e+01 5.1567475e+00 5.6171632e+00 - -4.6719846e+01 4.5973040e+00 5.9514829e+00 - -4.9640227e+01 4.8813260e+00 7.1481707e+00 - -4.9515941e+01 4.8692555e+00 8.0250807e+00 - -4.5594295e+01 4.4877431e+00 9.1311632e+00 - -1.3209848e+01 1.3352541e+00 3.6671806e+00 - -1.3006031e+01 1.3151705e+00 3.8740687e+00 - -1.2808167e+01 1.2962446e+00 4.0768313e+00 - -1.2840262e+01 1.2987998e+00 4.3314173e+00 - -1.2723037e+01 1.2875032e+00 4.5493199e+00 - -1.2591874e+01 1.2750746e+00 4.7613851e+00 - -1.1372222e+01 1.1561218e+00 4.6373732e+00 - -1.0171591e+01 1.0394214e+00 4.4750203e+00 - -9.9490925e+00 1.0174654e+00 4.6063923e+00 - -7.2843121e+00 7.5824116e-01 3.8401895e+00 - -3.9434358e+00 4.3306800e-01 2.7100187e+00 - -3.8208338e+00 4.2064438e-01 2.7503246e+00 - -4.0920785e+00 4.4717311e-01 2.9544416e+00 - -4.4030631e+00 4.7761264e-01 3.1889485e+00 - -4.2475796e+00 4.6273105e-01 3.2197611e+00 - -3.9937236e+00 4.3726970e-01 3.1976231e+00 - -4.1316093e+00 4.5099277e-01 3.3667057e+00 - -3.7911991e+00 4.1850040e-01 3.2881108e+00 - -4.5345688e+00 4.9078793e-01 3.7987623e+00 - -4.5541068e+00 4.9230171e-01 3.9265658e+00 - -3.5298376e+00 3.9263142e-01 3.4283469e+00 - -3.6806191e+00 4.0726668e-01 3.6202922e+00 - -3.7101149e+00 4.1009124e-01 3.7421853e+00 - -3.8181119e+00 4.2051929e-01 3.9216587e+00 - -3.9797343e+00 4.3641388e-01 4.1459487e+00 - -3.8114296e+00 4.2002397e-01 4.1418134e+00 - -4.0107774e+00 4.3933720e-01 4.4092208e+00 - -3.6914906e+00 4.0785174e-01 4.2848501e+00 - -3.6960236e+00 4.0923403e-01 4.4080619e+00 - -3.6360443e+00 4.0322674e-01 4.4811783e+00 - -3.4926697e+00 3.8854022e-01 4.4810177e+00 - -3.4455465e+00 3.8479364e-01 4.5638139e+00 - -4.6149658e+00 4.9802665e-01 5.7841501e+00 - -4.2013845e+00 4.5758481e-01 5.5538086e+00 - -4.1631112e+00 4.5441818e-01 5.6778817e+00 - -4.0126921e+00 4.3976669e-01 5.6869874e+00 - -3.0334674e+00 3.4459624e-01 4.8007460e+00 - -3.0132277e+00 3.4198562e-01 4.9140896e+00 - -3.5853311e+00 3.9825507e-01 5.7142314e+00 - -2.8049260e+00 3.2219203e-01 4.9506256e+00 - -2.7300589e+00 3.1511717e-01 5.0001737e+00 - -2.7514281e+00 3.1703902e-01 5.1743256e+00 - -2.9007092e+00 3.3150126e-01 5.5260672e+00 - -2.8099735e+00 3.2212722e-01 5.5688224e+00 - -2.6953741e+00 3.1159658e-01 5.5769447e+00 - -2.5490944e+00 2.9756167e-01 5.5328800e+00 - -1.4493904e+00 1.9053964e-01 4.0096940e+00 - -1.1270168e+00 1.5827849e-01 3.6111043e+00 - -1.1791660e+00 1.6389400e-01 3.8019846e+00 - -1.1352552e+00 1.5910376e-01 3.8396964e+00 - -8.7838710e-01 1.3433204e-01 3.4920043e+00 - -9.7009740e-01 1.4373977e-01 3.7716512e+00 - -9.1333573e-01 1.3767769e-01 3.7792092e+00 - -8.6839361e-01 1.3360718e-01 3.8124737e+00 - -9.0854411e-01 1.3763160e-01 4.0262867e+00 - -7.7064857e-01 1.2398736e-01 3.8588022e+00 - -6.6937713e-01 1.1400993e-01 3.7609487e+00 - -6.5512663e-01 1.1227614e-01 3.8644739e+00 - -6.7635698e-01 1.1479237e-01 4.0709355e+00 - -8.1799786e-01 1.2889274e-01 4.6264993e+00 - -7.7101503e-01 1.2350872e-01 4.6963610e+00 - -7.0911641e-01 1.1831203e-01 4.7275739e+00 - -6.4728479e-01 1.1206418e-01 4.7577378e+00 - -5.8739649e-01 1.0636094e-01 4.7964973e+00 - -5.2951110e-01 1.0021027e-01 4.8440021e+00 - -5.2270445e-01 9.9676952e-02 5.1039069e+00 - -4.3717515e-01 9.1461343e-02 5.0627336e+00 - -3.1538609e-01 7.9761883e-02 4.8340771e+00 - -2.2900514e-01 7.1346459e-02 4.7495549e+00 - -1.9162956e-01 6.7496001e-02 4.9193236e+00 - -1.1899484e-01 6.0202435e-02 4.9012128e+00 - -2.7814842e-01 7.6313608e-02 6.5254035e+00 - -1.9028415e-01 6.7073076e-02 6.6077186e+00 - 9.7859378e-02 3.9515672e-02 4.8090814e+00 - 1.1842798e-01 3.7255565e-02 5.3335127e+00 - 2.0175546e-01 2.9581721e-02 5.2198369e+00 - 2.8295343e-01 2.0964604e-02 5.0845940e+00 - 3.0346794e-01 1.9690513e-02 6.5167968e+00 - 3.9564011e-01 1.0664274e-02 6.6893861e+00 - -3.0303547e+00 4.4953818e-01 -9.3471755e-01 - -3.1685153e+00 4.6725326e-01 -9.2783004e-01 - -3.3345602e+00 4.8820651e-01 -9.3004137e-01 - -3.5105204e+00 5.1081048e-01 -9.3127168e-01 - -3.6884424e+00 5.3381125e-01 -9.2690255e-01 - -3.8932935e+00 5.5913074e-01 -9.2878934e-01 - -4.1000400e+00 5.8589325e-01 -9.2412747e-01 - -4.3356388e+00 6.1619579e-01 -9.2366730e-01 - -4.6100851e+00 6.5053448e-01 -9.2957434e-01 - -4.8675254e+00 6.8362699e-01 -9.1970536e-01 - -5.1537982e+00 7.2041719e-01 -9.1084204e-01 - -5.4978370e+00 7.6328065e-01 -9.1053234e-01 - -5.8726199e+00 8.1115673e-01 -9.0727643e-01 - -6.2583209e+00 8.6019042e-01 -8.9399787e-01 - -6.7215613e+00 9.1957114e-01 -8.8785984e-01 - -7.2544362e+00 9.8714162e-01 -8.8229669e-01 - -7.8767325e+00 1.0670672e+00 -8.7809262e-01 - -8.5686742e+00 1.1545798e+00 -8.6642374e-01 - -9.3997680e+00 1.2604362e+00 -8.5660300e-01 - -1.0340175e+01 1.3804331e+00 -8.3639216e-01 - -1.1488406e+01 1.5260935e+00 -8.1476266e-01 - -1.2885111e+01 1.7041693e+00 -7.8598946e-01 - -1.4598953e+01 1.9220639e+00 -7.4510787e-01 - -1.6799891e+01 2.2021022e+00 -6.9166938e-01 - -2.0197858e+01 2.6347543e+00 -6.5709306e-01 - -4.3757353e+01 5.6332273e+00 -2.0060676e-01 - -4.6291077e+01 5.9561856e+00 5.5413387e-01 - -4.6659269e+01 6.0034375e+00 1.3802949e+00 - -4.7616970e+01 6.1248228e+00 2.2348730e+00 - -4.5734537e+01 5.8856978e+00 3.0009934e+00 - -4.6178308e+01 5.9413428e+00 3.8436271e+00 - -4.7338592e+01 6.0890711e+00 4.7600327e+00 - -4.5537970e+01 5.8603646e+00 5.4345311e+00 - -4.5405213e+01 5.8431418e+00 6.2382525e+00 - -4.3959651e+01 5.6596951e+00 6.8671538e+00 - -5.0062446e+01 6.4364054e+00 8.5794245e+00 - -5.1245036e+01 6.5860896e+00 9.6897104e+00 - -4.8374547e+01 6.2211579e+00 1.0094091e+01 - -4.6946011e+01 6.0393189e+00 1.0694283e+01 - -4.4000578e+01 5.6645235e+00 1.0910555e+01 - -1.3238813e+01 1.7493267e+00 4.3143572e+00 - -1.2930103e+01 1.7093496e+00 4.4906409e+00 - -1.1328092e+01 1.5056763e+00 4.2972600e+00 - -1.1687898e+01 1.5519471e+00 4.6295085e+00 - -1.1026736e+01 1.4671049e+00 4.6543428e+00 - -3.8576714e+00 5.5519280e-01 2.4661724e+00 - -5.8892140e+00 8.1341668e-01 3.2754735e+00 - -4.7518373e+00 6.6860215e-01 2.9751255e+00 - -3.9968905e+00 5.7227154e-01 2.7818787e+00 - -3.9658234e+00 5.6829320e-01 2.8606803e+00 - -3.8781318e+00 5.5767319e-01 2.9150300e+00 - -3.8530408e+00 5.5416101e-01 2.9959481e+00 - -3.9341368e+00 5.6462423e-01 3.1280956e+00 - -3.8702799e+00 5.5693972e-01 3.1923597e+00 - -4.3772077e+00 6.2061872e-01 3.5547948e+00 - -4.4284440e+00 6.2755536e-01 3.6926390e+00 - -4.5541345e+00 6.4332044e-01 3.8772649e+00 - -3.8104792e+00 5.4928972e-01 3.5551154e+00 - -3.4529484e+00 5.0378872e-01 3.4374076e+00 - -3.6024853e+00 5.2239569e-01 3.6300505e+00 - -3.7301542e+00 5.3842454e-01 3.8175792e+00 - -4.2615189e+00 6.0620099e-01 4.2933028e+00 - -4.0984340e+00 5.8570499e-01 4.3011167e+00 - -3.9294260e+00 5.6431912e-01 4.2982248e+00 - -3.9261138e+00 5.6306624e-01 4.4183142e+00 - -3.7729824e+00 5.4391550e-01 4.4209168e+00 - -3.7676192e+00 5.4349433e-01 4.5400515e+00 - -3.6750327e+00 5.3128936e-01 4.5886419e+00 - -3.5972901e+00 5.2153496e-01 4.6483168e+00 - -3.5334490e+00 5.1320821e-01 4.7198216e+00 - -4.0157229e+00 5.7482415e-01 5.3128908e+00 - -4.0826118e+00 5.8372285e-01 5.5317347e+00 - -4.2882399e+00 6.0962432e-01 5.9038853e+00 - -3.9636705e+00 5.6852134e-01 5.7336994e+00 - -3.8937711e+00 5.5986955e-01 5.8262088e+00 - -3.6456335e+00 5.2734958e-01 5.7156448e+00 - -3.0349387e+00 4.5004020e-01 5.1647090e+00 - -2.8483014e+00 4.2589959e-01 5.0874524e+00 - -2.8696012e+00 4.2889229e-01 5.2630529e+00 - -1.4176637e+00 2.4422329e-01 3.5138420e+00 - -2.7498242e+00 4.1336287e-01 5.4190719e+00 - -2.7997624e+00 4.2005785e-01 5.6545404e+00 - -1.2613964e+00 2.2395795e-01 3.5785568e+00 - -1.2333464e+00 2.2101187e-01 3.6340975e+00 - -1.3636276e+00 2.3718199e-01 3.9423843e+00 - -1.1100652e+00 2.0494748e-01 3.6423391e+00 - -1.0533453e+00 1.9803625e-01 3.6529430e+00 - -8.8495073e-01 1.7639028e-01 3.4624362e+00 - -8.5199627e-01 1.7245221e-01 3.5039783e+00 - -8.4472943e-01 1.7168527e-01 3.5982876e+00 - -8.2659004e-01 1.6939612e-01 3.6751834e+00 - -8.2226202e-01 1.6873980e-01 3.7883286e+00 - -9.0183897e-01 1.7866367e-01 4.0931062e+00 - -7.2570628e-01 1.5610582e-01 3.8331110e+00 - -6.7197282e-01 1.4943998e-01 3.8450228e+00 - -9.0327193e-01 1.7894578e-01 4.5814034e+00 - -5.6945850e-01 1.3671602e-01 3.8750547e+00 - -7.7887380e-01 1.6273860e-01 4.6284930e+00 - -7.0628861e-01 1.5401770e-01 4.6219671e+00 - -6.7311633e-01 1.4975729e-01 4.7380157e+00 - -6.2221277e-01 1.4304091e-01 4.8060166e+00 - -5.4571445e-01 1.3344266e-01 4.7865939e+00 - -4.4274961e-01 1.1989211e-01 4.6592696e+00 - -4.8108798e-01 1.2520324e-01 5.1029916e+00 - -3.9474692e-01 1.1440612e-01 5.0512274e+00 - -2.7326717e-01 9.8171971e-02 4.8116828e+00 - -2.6722237e-01 9.7524576e-02 5.1490936e+00 - -1.5556726e-01 8.3665381e-02 4.9252119e+00 - -3.3227125e-01 1.0625659e-01 6.5777265e+00 - -2.2124423e-01 9.1805086e-02 6.4824365e+00 - 7.6413991e-02 5.4238455e-02 4.7159734e+00 - 1.2562432e-01 4.7486399e-02 4.8821076e+00 - 1.5692308e-01 4.4113348e-02 5.3366414e+00 - 2.5048153e-01 3.2369106e-02 5.0525928e+00 - 2.5515380e-01 3.1025507e-02 6.5448708e+00 - 3.4527742e-01 1.9639929e-02 6.7482269e+00 - 4.4543004e-01 6.6958446e-03 6.6700508e+00 - -2.9555897e+00 5.4298986e-01 -9.4139084e-01 - -3.0845682e+00 5.6329463e-01 -9.3178417e-01 - -3.2403758e+00 5.8774944e-01 -9.3182845e-01 - -3.4150515e+00 6.1515950e-01 -9.3570674e-01 - -3.5827399e+00 6.4163227e-01 -9.2976982e-01 - -3.7772400e+00 6.7239303e-01 -9.3068731e-01 - -3.9826449e+00 7.0493394e-01 -9.2922234e-01 - -4.1890675e+00 7.3686351e-01 -9.2111277e-01 - -4.4431086e+00 7.7713447e-01 -9.2413432e-01 - -4.6792703e+00 8.1407040e-01 -9.1198307e-01 - -4.9918604e+00 8.6374182e-01 -9.1811061e-01 - -5.2866214e+00 9.0916010e-01 -9.0741779e-01 - -5.6498395e+00 9.6620282e-01 -9.0748889e-01 - -6.0328591e+00 1.0267785e+00 -9.0090376e-01 - -6.4466682e+00 1.0914882e+00 -8.8892582e-01 - -6.9190109e+00 1.1657214e+00 -8.7755697e-01 - -7.4886104e+00 1.2555379e+00 -8.7266423e-01 - -8.1386209e+00 1.3573823e+00 -8.6476462e-01 - -8.8967597e+00 1.4768561e+00 -8.5556532e-01 - -9.7729834e+00 1.6147659e+00 -8.4093959e-01 - -1.0807977e+01 1.7775729e+00 -8.2105515e-01 - -1.2011678e+01 1.9662266e+00 -7.8888883e-01 - -1.3569626e+01 2.2112755e+00 -7.5891963e-01 - -1.5386540e+01 2.4963965e+00 -7.0159436e-01 - -1.8011249e+01 2.9091285e+00 -6.5278639e-01 - -3.0905806e+01 4.9345440e+00 -1.3303405e-01 - -4.3000038e+01 6.8351132e+00 1.9960414e-01 - -4.3205005e+01 6.8676295e+00 9.6801358e-01 - -4.4008880e+01 6.9933426e+00 2.5406158e+00 - -4.4519796e+01 7.0742720e+00 4.1534678e+00 - -4.5257788e+01 7.1903497e+00 5.8342720e+00 - -4.3814819e+01 6.9635002e+00 6.4747419e+00 - -4.8556033e+01 7.7078752e+00 8.8279017e+00 - -4.8714881e+01 7.7330522e+00 9.7468741e+00 - -1.3629972e+01 2.2202021e+00 4.0295187e+00 - -1.3344526e+01 2.1755531e+00 4.2247994e+00 - -1.3239616e+01 2.1586831e+00 4.4568700e+00 - -1.3655231e+01 2.2243030e+00 4.8280573e+00 - -1.1316433e+01 1.8571473e+00 4.4204240e+00 - -1.0528574e+01 1.7325144e+00 4.4040869e+00 - -4.0215359e+00 7.1038467e-01 2.4833580e+00 - -3.9013117e+00 6.9142350e-01 2.5305091e+00 - -4.4779265e+00 7.8225577e-01 2.8298582e+00 - -4.2982170e+00 7.5385514e-01 2.8602870e+00 - -4.1918613e+00 7.3710180e-01 2.9148240e+00 - -4.2312074e+00 7.4312758e-01 3.0286100e+00 - -3.7978287e+00 6.7509397e-01 2.9331722e+00 - -3.6746343e+00 6.5627345e-01 2.9665812e+00 - -4.1370654e+00 7.2912660e-01 3.2851358e+00 - -4.1238649e+00 7.2703941e-01 3.3802746e+00 - -4.5535596e+00 7.9369629e-01 3.7148524e+00 - -4.2896335e+00 7.5308054e-01 3.6825865e+00 - -4.7300972e+00 8.2208731e-01 4.0513571e+00 - -4.7792392e+00 8.2968640e-01 4.2050753e+00 - -3.5408069e+00 6.3513362e-01 3.5515190e+00 - -3.5711921e+00 6.3991893e-01 3.6714185e+00 - -3.5817917e+00 6.4104314e-01 3.7820649e+00 - -3.5893293e+00 6.4304208e-01 3.8938508e+00 - -3.6187118e+00 6.4728729e-01 4.0242837e+00 - -3.8035098e+00 6.7602605e-01 4.2770188e+00 - -3.7150229e+00 6.6217736e-01 4.3279184e+00 - -3.7492797e+00 6.6765597e-01 4.4772438e+00 - -3.6201992e+00 6.4764998e-01 4.4939543e+00 - -3.5297455e+00 6.3344390e-01 4.5400534e+00 - -3.6589991e+00 6.5339885e-01 4.7844686e+00 - -3.3468825e+00 6.0458569e-01 4.6256533e+00 - -4.3229991e+00 7.5738592e-01 5.7064763e+00 - -4.2759501e+00 7.5046760e-01 5.8262749e+00 - -4.0677028e+00 7.1756163e-01 5.7805558e+00 - -4.0385061e+00 7.1264778e-01 5.9189886e+00 - -3.9330723e+00 6.9707994e-01 5.9760760e+00 - -3.8079492e+00 6.7708244e-01 6.0083296e+00 - -3.6769017e+00 6.5620493e-01 6.0300770e+00 - -2.9665454e+00 5.4522311e-01 5.3263974e+00 - -1.4429875e+00 3.0587245e-01 3.5125592e+00 - -1.3992205e+00 2.9890108e-01 3.5465748e+00 - -1.3554591e+00 2.9188538e-01 3.5796915e+00 - -1.3047653e+00 2.8400805e-01 3.6038969e+00 - -1.2540784e+00 2.7607652e-01 3.6270037e+00 - -1.1599509e+00 2.6114299e-01 3.5822039e+00 - -1.0787109e+00 2.4770476e-01 3.5518276e+00 - -8.9672692e-01 2.1955769e-01 3.3479409e+00 - -8.6582900e-01 2.1474356e-01 3.3895389e+00 - -9.0599325e-01 2.2072106e-01 3.5619046e+00 - -8.1979360e-01 2.0776252e-01 3.5068437e+00 - -7.8103037e-01 2.0098994e-01 3.5387777e+00 - -8.5462282e-01 2.1257809e-01 3.8035871e+00 - -7.7237884e-01 2.0015695e-01 3.7545315e+00 - -7.4043817e-01 1.9512296e-01 3.8131549e+00 - -7.0750180e-01 1.9000881e-01 3.8713756e+00 - -6.6469967e-01 1.8336394e-01 3.9107877e+00 - -6.0815688e-01 1.7400554e-01 3.9123021e+00 - -5.2301724e-01 1.6112891e-01 3.8374192e+00 - -7.2900706e-01 1.9350858e-01 4.6018368e+00 - -7.0675872e-01 1.8932826e-01 4.7465841e+00 - -6.4217244e-01 1.7943524e-01 4.7672988e+00 - -5.7953010e-01 1.7008189e-01 4.7965095e+00 - -5.6204037e-01 1.6702800e-01 4.9985012e+00 - -4.1711142e-01 1.4374596e-01 4.7061942e+00 - -4.3278789e-01 1.4684924e-01 5.0724898e+00 - -3.5056590e-01 1.3373660e-01 5.0296761e+00 - -2.5761664e-01 1.1897225e-01 4.9263029e+00 - -2.2616513e-01 1.1394033e-01 5.1458277e+00 - -4.9519804e-01 1.5603822e-01 7.3207949e+00 - -3.8402576e-01 1.3862156e-01 7.3274758e+00 - 3.9612806e-02 7.2778920e-02 4.7617433e+00 - 1.1185520e-01 6.1318757e-02 4.6996860e+00 - 1.1988226e-01 6.0223181e-02 5.3533967e+00 - 2.0191150e-01 4.6601670e-02 5.2597466e+00 - 2.8660892e-01 3.3801368e-02 5.0445897e+00 - 3.0326143e-01 3.0718880e-02 6.5568040e+00 - 3.9606635e-01 1.6649173e-02 6.7094133e+00 - -3.3167626e+00 7.1638556e-01 -9.3900392e-01 - -3.4742161e+00 7.4634019e-01 -9.3129946e-01 - -3.6495365e+00 7.7921424e-01 -9.2693280e-01 - -3.8347679e+00 8.1377350e-01 -9.2088598e-01 - -4.0487378e+00 8.5381250e-01 -9.2023862e-01 - -4.2825525e+00 8.9703964e-01 -9.1992640e-01 - -4.5350872e+00 9.4543763e-01 -9.1905282e-01 - -4.7985697e+00 9.9475676e-01 -9.1295068e-01 - -5.1017011e+00 1.0512914e+00 -9.1076442e-01 - -5.4236519e+00 1.1111706e+00 -9.0452190e-01 - -5.7851694e+00 1.1794396e+00 -8.9864925e-01 - -6.1863627e+00 1.2541933e+00 -8.9124958e-01 - -6.6270986e+00 1.3375289e+00 -8.8032458e-01 - -7.1262967e+00 1.4314739e+00 -8.6826044e-01 - -7.7325528e+00 1.5445974e+00 -8.6278927e-01 - -8.4279014e+00 1.6752826e+00 -8.5443048e-01 - -9.2312402e+00 1.8257340e+00 -8.4197467e-01 - -1.0162337e+01 2.0002697e+00 -8.2310988e-01 - -1.1290542e+01 2.2119313e+00 -8.0135539e-01 - -1.2605921e+01 2.4586967e+00 -7.6495833e-01 - -1.4274898e+01 2.7722161e+00 -7.2336365e-01 - -1.6562034e+01 3.2012089e+00 -6.8384948e-01 - -2.8142711e+01 5.3735499e+00 -2.9329551e-01 - -3.1098226e+01 5.9284398e+00 1.3501630e-01 - -3.9865372e+01 7.5730255e+00 6.1193178e-01 - -3.9834115e+01 7.5671282e+00 2.0448970e+00 - -4.3001874e+01 8.1604600e+00 3.6749056e+00 - -4.3027138e+01 8.1655546e+00 4.4530702e+00 - -4.3470341e+01 8.2482190e+00 5.2749437e+00 - -4.8136761e+01 9.1236272e+00 6.6016206e+00 - -4.3754476e+01 8.3017435e+00 6.8945561e+00 - -4.6096522e+01 8.7413722e+00 8.0500612e+00 - -4.6076065e+01 8.7369683e+00 8.8944936e+00 - -4.6048602e+01 8.7322988e+00 9.7420998e+00 - -1.2929448e+01 2.5190465e+00 3.7695559e+00 - -1.2840526e+01 2.5030058e+00 3.9988808e+00 - -1.2787313e+01 2.4924820e+00 4.2352628e+00 - -1.2663766e+01 2.4697761e+00 4.4532886e+00 - -1.1967212e+01 2.3391385e+00 4.5078977e+00 - -5.2507476e+00 1.0786742e+00 2.7284941e+00 - -4.0856656e+00 8.5990948e-01 2.4673669e+00 - -3.9755102e+00 8.3982495e-01 2.5200423e+00 - -4.0603159e+00 8.5588601e-01 2.6392208e+00 - -4.1975716e+00 8.8134766e-01 2.7828898e+00 - -4.1844001e+00 8.7902892e-01 2.8733344e+00 - -4.4967244e+00 9.3731326e-01 3.1013697e+00 - -4.3064581e+00 9.0177328e-01 3.1220732e+00 - -4.5197972e+00 9.4169621e-01 3.3229693e+00 - -4.4175901e+00 9.2239087e-01 3.3816627e+00 - -9.3118677e+00 1.8400705e+00 5.9681157e+00 - -4.1499087e+00 8.7189987e-01 3.4579941e+00 - -4.2187715e+00 8.8522469e-01 3.6020399e+00 - -4.3103601e+00 9.0282552e-01 3.7641373e+00 - -4.4573610e+00 9.2975034e-01 3.9657658e+00 - -4.3719530e+00 9.1386070e-01 4.0324043e+00 - -4.4684662e+00 9.3177679e-01 4.2150419e+00 - -3.7978831e+00 8.0587175e-01 3.8893088e+00 - -3.8607499e+00 8.1837393e-01 4.0442716e+00 - -3.5915510e+00 7.6806182e-01 3.9645924e+00 - -3.6278161e+00 7.7408186e-01 4.1021891e+00 - -3.6046818e+00 7.7049176e-01 4.1993431e+00 - -3.3642317e+00 7.2506150e-01 4.1224040e+00 - -3.3105143e+00 7.1517291e-01 4.1905441e+00 - -3.9206896e+00 8.2921076e-01 4.8352828e+00 - -4.5544381e+00 9.4775891e-01 5.5421213e+00 - -3.8150929e+00 8.0978745e-01 5.0168127e+00 - -4.4022778e+00 9.1960140e-01 5.7255968e+00 - -4.6081690e+00 9.5762531e-01 6.0991535e+00 - -4.3133511e+00 9.0256201e-01 5.9751959e+00 - -3.9760999e+00 8.3996911e-01 5.7916740e+00 - -3.9667353e+00 8.3731365e-01 5.9514442e+00 - -3.9661338e+00 8.3799428e-01 6.1273239e+00 - -3.9794183e+00 8.3971159e-01 6.3273679e+00 - -4.8569735e+00 1.0051885e+00 7.6013970e+00 - -1.4603151e+00 3.6764082e-01 3.5032114e+00 - -1.4235443e+00 3.6050457e-01 3.5455885e+00 - -1.3916585e+00 3.5503210e-01 3.5953229e+00 - -1.3351418e+00 3.4443358e-01 3.6122175e+00 - -1.2845704e+00 3.3454756e-01 3.6362223e+00 - -1.0052533e+00 2.8235812e-01 3.3090680e+00 - -1.1133736e+00 3.0293231e-01 3.5714446e+00 - -1.0175063e+00 2.8428103e-01 3.5145022e+00 - -9.8959711e-01 2.7917845e-01 3.5668461e+00 - -8.8681439e-01 2.6004666e-01 3.4884583e+00 - -8.5397913e-01 2.5412453e-01 3.5302992e+00 - -8.4183532e-01 2.5162976e-01 3.6159529e+00 - -7.8338724e-01 2.4090717e-01 3.6125166e+00 - -8.2730001e-01 2.4907746e-01 3.8244462e+00 - -7.5411290e-01 2.3506675e-01 3.7929464e+00 - -7.2223307e-01 2.2903088e-01 3.8515195e+00 - -9.0658931e-01 2.6366374e-01 4.4453823e+00 - -6.5936428e-01 2.1787684e-01 3.9860473e+00 - -5.6365154e-01 1.9902215e-01 3.8844609e+00 - -4.9044264e-01 1.8621708e-01 3.8368817e+00 - -7.0780644e-01 2.2621181e-01 4.6599666e+00 - -6.7375581e-01 2.1990198e-01 4.7762109e+00 - -6.0342305e-01 2.0667685e-01 4.7772301e+00 - -5.3896831e-01 1.9470124e-01 4.7962462e+00 - -4.2656334e-01 1.7363999e-01 4.6301860e+00 - -3.6412405e-01 1.6163255e-01 4.6461122e+00 - -2.7821704e-01 1.4581967e-01 4.5534474e+00 - -3.1137880e-01 1.5179737e-01 5.0370538e+00 - -2.6537547e-01 1.4301280e-01 5.1785775e+00 - -5.2251128e-01 1.9199068e-01 7.1835227e+00 - -4.8242366e-01 1.8445527e-01 7.6457169e+00 - -2.9110513e-01 1.4816899e-01 7.0674118e+00 - 7.6054847e-02 7.9304344e-02 4.7556897e+00 - 1.3569097e-01 6.8491405e-02 4.8124247e+00 - 1.5726039e-01 6.4129088e-02 5.3765024e+00 - 2.4764696e-01 4.7538498e-02 5.1323614e+00 - 3.1712499e-01 3.4488556e-02 5.1762300e+00 - 3.4414034e-01 2.8690159e-02 6.8482114e+00 - 4.4579914e-01 1.0161091e-02 6.7200394e+00 - -3.2079418e+00 8.0924201e-01 -9.3644646e-01 - -3.3631729e+00 8.4294531e-01 -9.3134360e-01 - -3.5193719e+00 8.7695047e-01 -9.2134360e-01 - -3.7033219e+00 9.1629118e-01 -9.1844414e-01 - -3.9070054e+00 9.6074002e-01 -9.1747706e-01 - -4.1373654e+00 1.0115890e+00 -9.2106646e-01 - -4.3707327e+00 1.0620018e+00 -9.1690626e-01 - -4.6228187e+00 1.1175952e+00 -9.1198496e-01 - -4.9036175e+00 1.1788753e+00 -9.0826829e-01 - -5.2051761e+00 1.2445833e+00 -9.0123769e-01 - -5.5354314e+00 1.3161060e+00 -8.9281493e-01 - -5.9240077e+00 1.4009135e+00 -8.8979378e-01 - -6.3323156e+00 1.4903298e+00 -8.7856792e-01 - -6.7900973e+00 1.5898508e+00 -8.6543251e-01 - -7.3437765e+00 1.7108763e+00 -8.5907370e-01 - -7.9578188e+00 1.8439098e+00 -8.4592597e-01 - -8.7072545e+00 2.0079183e+00 -8.3827634e-01 - -9.2182378e+00 2.1188710e+00 -7.6069666e-01 - -9.8547974e+00 2.2573316e+00 -6.8590144e-01 - -1.1013583e+01 2.5099481e+00 -6.6437643e-01 - -1.2474891e+01 2.8291328e+00 -6.3986226e-01 - -1.4269401e+01 3.2203911e+00 -5.9942504e-01 - -1.8012147e+01 4.0367062e+00 -6.7115624e-01 - -2.7092606e+01 6.0160146e+00 -5.0027745e-01 - -4.0110585e+01 8.8534906e+00 2.4460546e-01 - -4.0107288e+01 8.8532389e+00 9.7009234e-01 - -4.0345283e+01 8.9048755e+00 1.6996154e+00 - -4.0278753e+01 8.8898870e+00 2.4274414e+00 - -4.2785521e+01 9.4372326e+00 3.2896935e+00 - -4.2681292e+01 9.4139716e+00 4.0583450e+00 - -4.3673293e+01 9.6301894e+00 4.9225744e+00 - -4.3824027e+01 9.6626110e+00 5.7348081e+00 - -4.5559113e+01 1.0040725e+01 6.7535332e+00 - -4.5802583e+01 1.0093738e+01 7.6251975e+00 - -4.5730710e+01 1.0078680e+01 8.4590247e+00 - -1.3011912e+01 2.9453986e+00 3.4282381e+00 - -1.2815453e+01 2.9028709e+00 3.6387818e+00 - -1.2729707e+01 2.8840059e+00 3.8679652e+00 - -1.2735822e+01 2.8857302e+00 4.1172254e+00 - -1.2700488e+01 2.8775082e+00 4.3580097e+00 - -1.2621664e+01 2.8601125e+00 4.5881646e+00 - -1.2643571e+01 2.8652560e+00 4.8466651e+00 - -5.3704902e+00 1.2796286e+00 2.8320596e+00 - -5.2170076e+00 1.2464794e+00 2.8965260e+00 - -3.9454778e+00 9.6953600e-01 2.5629195e+00 - -4.1753420e+00 1.0191900e+00 2.7377059e+00 - -4.1454272e+00 1.0124930e+00 2.8209541e+00 - -4.2221356e+00 1.0294813e+00 2.9484473e+00 - -4.1971219e+00 1.0243201e+00 3.0364559e+00 - -4.3133606e+00 1.0489557e+00 3.1890471e+00 - -4.2577125e+00 1.0373908e+00 3.2661689e+00 - -4.4025086e+00 1.0689546e+00 3.4427243e+00 - -4.3172948e+00 1.0499657e+00 3.5073141e+00 - -4.2991961e+00 1.0458041e+00 3.6070305e+00 - -4.2800987e+00 1.0415869e+00 3.7068437e+00 - -4.3685550e+00 1.0611382e+00 3.8716290e+00 - -4.3099467e+00 1.0486019e+00 3.9529857e+00 - -4.2256721e+00 1.0306606e+00 4.0173294e+00 - -4.6328613e+00 1.1187017e+00 4.4058815e+00 - -3.4968090e+00 8.7124421e-01 3.7541652e+00 - -3.4323467e+00 8.5726625e-01 3.8136298e+00 - -3.7161159e+00 9.1922004e-01 4.1300172e+00 - -3.6624783e+00 9.0766270e-01 4.2048482e+00 - -3.4451552e+00 8.5969234e-01 4.1496036e+00 - -3.4517030e+00 8.6104772e-01 4.2698255e+00 - -3.2008198e+00 8.0697371e-01 4.1729233e+00 - -3.3749925e+00 8.4489348e-01 4.4416604e+00 - -5.0743769e+00 1.2149319e+00 6.1283871e+00 - -3.4343517e+00 8.5770455e-01 4.7483735e+00 - -4.3043553e+00 1.0468674e+00 5.7412423e+00 - -4.1125747e+00 1.0058065e+00 5.7132484e+00 - -5.7430814e+00 1.3608770e+00 7.6063424e+00 - -4.1824715e+00 1.0207535e+00 6.1308580e+00 - -4.0350956e+00 9.8857338e-01 6.1468545e+00 - -3.9596737e+00 9.7170642e-01 6.2422382e+00 - -3.7059402e+00 9.1629821e-01 6.1219553e+00 - -5.1137317e+00 1.2232087e+00 8.0836335e+00 - -1.4398136e+00 4.2320944e-01 3.5361879e+00 - -1.3902863e+00 4.1250023e-01 3.5625427e+00 - -1.3230691e+00 3.9745762e-01 3.5635707e+00 - -1.2567997e+00 3.8339359e-01 3.5629542e+00 - -1.0429797e+00 3.3618202e-01 3.3370834e+00 - -9.7679724e-01 3.2142332e-01 3.3223844e+00 - -1.0305953e+00 3.3354721e-01 3.5009390e+00 - -1.0381279e+00 3.3558556e-01 3.6135238e+00 - -9.2964204e-01 3.1174360e-01 3.5280242e+00 - -8.4773471e-01 2.9353780e-01 3.4832609e+00 - -7.9627606e-01 2.8270451e-01 3.4892848e+00 - -7.8907191e-01 2.8092091e-01 3.5832442e+00 - -7.4943342e-01 2.7207427e-01 3.6148747e+00 - -7.0880109e-01 2.6313269e-01 3.6458028e+00 - -7.1528766e-01 2.6446168e-01 3.7857499e+00 - -7.7076186e-01 2.7720198e-01 4.0553969e+00 - -6.9277341e-01 2.6034332e-01 4.0127941e+00 - -5.8149508e-01 2.3573723e-01 3.8749503e+00 - -5.4569636e-01 2.2835422e-01 3.9313629e+00 - -8.0480659e-01 2.8446159e-01 4.8664494e+00 - -7.0228528e-01 2.6169352e-01 4.7751265e+00 - -6.4674705e-01 2.4976578e-01 4.8246328e+00 - -5.6186125e-01 2.3125053e-01 4.7772632e+00 - -4.6237061e-01 2.0940634e-01 4.6604820e+00 - -3.7557149e-01 1.9113828e-01 4.5800476e+00 - -4.6056022e-01 2.0891697e-01 5.2381074e+00 - -2.2853697e-01 1.5880924e-01 4.4917250e+00 - -2.6838319e-01 1.6762911e-01 5.0243931e+00 - -2.2344050e-01 1.5737420e-01 5.1754075e+00 - -5.4375680e-01 2.2726408e-01 7.7059602e+00 - -3.5266662e-01 1.8502705e-01 7.1691009e+00 - 4.5179172e-02 9.8521989e-02 4.7617407e+00 - 1.1430765e-01 8.4225922e-02 4.7195668e+00 - 1.4130834e-01 7.7622743e-02 5.1442495e+00 - 1.9551439e-01 6.5965856e-02 5.3994043e+00 - 2.8739833e-01 4.5782776e-02 5.0646192e+00 - 3.5843394e-01 3.0137298e-02 5.0177943e+00 - 3.9568246e-01 2.2649844e-02 6.7893186e+00 - -2.8359555e+00 8.3137884e-01 -9.4714366e-01 - -2.9612255e+00 8.6339674e-01 -9.3953939e-01 - -3.0974183e+00 8.9705191e-01 -9.3244909e-01 - -3.2513649e+00 9.3556129e-01 -9.2999419e-01 - -3.4053415e+00 9.7331513e-01 -9.2259580e-01 - -3.5878884e+00 1.0194410e+00 -9.2274303e-01 - -3.7793457e+00 1.0672114e+00 -9.2081379e-01 - -3.9817071e+00 1.1167669e+00 -9.1640221e-01 - -4.2126192e+00 1.1748521e+00 -9.1634020e-01 - -4.4623101e+00 1.2371210e+00 -9.1546755e-01 - -4.7129481e+00 1.2998593e+00 -9.0630194e-01 - -5.0021170e+00 1.3717417e+00 -9.0125438e-01 - -5.3209237e+00 1.4504717e+00 -8.9536040e-01 - -5.6683011e+00 1.5370546e+00 -8.8727447e-01 - -6.0640534e+00 1.6355180e+00 -8.8057733e-01 - -6.4132736e+00 1.7234486e+00 -8.4761575e-01 - -6.7744120e+00 1.8125825e+00 -8.0492798e-01 - -7.0406033e+00 1.8796234e+00 -7.2809501e-01 - -7.6100066e+00 2.0214218e+00 -7.0634369e-01 - -8.3442985e+00 2.2037282e+00 -6.9558508e-01 - -9.1465899e+00 2.4038952e+00 -6.7046948e-01 - -1.0180838e+01 2.6618384e+00 -6.5277944e-01 - -1.1525037e+01 2.9964285e+00 -6.4016092e-01 - -1.3122813e+01 3.3943817e+00 -6.0937836e-01 - -1.4538696e+01 3.7479804e+00 -5.0323904e-01 - -2.6985822e+01 6.8496146e+00 -7.5271639e-01 - -4.0424110e+01 1.0197677e+01 -1.3455369e-01 - -4.0447456e+01 1.0203572e+01 6.0150765e-01 - -4.0525090e+01 1.0222831e+01 1.3386466e+00 - -4.0677709e+01 1.0260907e+01 2.0807269e+00 - -1.3867814e+01 3.5800697e+00 1.6360359e+00 - -1.3855150e+01 3.5770961e+00 1.8943229e+00 - -1.3827700e+01 3.5701706e+00 2.1516122e+00 - -1.3825887e+01 3.5699149e+00 2.4110336e+00 - -1.3799435e+01 3.5630548e+00 2.6684260e+00 - -4.2161251e+01 1.0630024e+01 6.7559544e+00 - -4.2345268e+01 1.0675404e+01 7.5664528e+00 - -4.2269278e+01 1.0656543e+01 9.1360495e+00 - -1.2900717e+01 3.3392933e+00 3.7994042e+00 - -1.2907804e+01 3.3412848e+00 4.0528624e+00 - -1.2873501e+01 3.3323480e+00 4.2981938e+00 - -1.2655767e+01 3.2778608e+00 4.4957796e+00 - -1.1312922e+01 2.9435830e+00 4.3667104e+00 - -1.2109911e+01 3.1415939e+00 4.8392514e+00 - -5.2213460e+00 1.4251974e+00 2.8543958e+00 - -4.0665082e+00 1.1377215e+00 2.5706892e+00 - -4.1026707e+00 1.1471399e+00 2.6758779e+00 - -4.0008521e+00 1.1216360e+00 2.7304740e+00 - -4.1158730e+00 1.1505456e+00 2.8696305e+00 - -4.2900458e+00 1.1936215e+00 3.0402925e+00 - -4.5036187e+00 1.2464175e+00 3.2375515e+00 - -4.3239227e+00 1.2016209e+00 3.2609795e+00 - -5.0025485e+00 1.3707439e+00 3.6997723e+00 - -4.9134512e+00 1.3490939e+00 3.7760838e+00 - -8.8779166e+00 2.3361027e+00 6.0216681e+00 - -4.1846459e+00 1.1667374e+00 3.6163778e+00 - -4.2157969e+00 1.1749879e+00 3.7445214e+00 - -4.2854069e+00 1.1919257e+00 3.8998076e+00 - -4.2771550e+00 1.1899616e+00 4.0115914e+00 - -4.0945516e+00 1.1448031e+00 4.0110898e+00 - -4.1394921e+00 1.1558920e+00 4.1594035e+00 - -4.0859255e+00 1.1427349e+00 4.2423237e+00 - -3.9348822e+00 1.1051361e+00 4.2546601e+00 - -3.6450525e+00 1.0325598e+00 4.1557269e+00 - -3.4674594e+00 9.8857902e-01 4.1324701e+00 - -3.5960763e+00 1.0203267e+00 4.3525704e+00 - -3.3673083e+00 9.6376056e-01 4.2795568e+00 - -3.4210605e+00 9.7728223e-01 4.4459272e+00 - -3.2750219e+00 9.4090548e-01 4.4364073e+00 - -3.3809673e+00 9.6639632e-01 4.6590792e+00 - -3.3815191e+00 9.6692906e-01 4.7902181e+00 - -3.3102945e+00 9.4866823e-01 4.8524554e+00 - -3.8233149e+00 1.0773378e+00 5.5262101e+00 - -5.7506685e+00 1.5574290e+00 7.7778171e+00 - -5.9702260e+00 1.6119555e+00 8.2649852e+00 - -5.7943862e+00 1.5679754e+00 8.3203362e+00 - -8.0471465e+00 2.1288525e+00 1.1297364e+01 - -5.3385100e+00 1.4545592e+00 8.2876730e+00 - -3.4730433e+00 9.8934253e-01 6.1390418e+00 - -4.6508473e+00 1.2827402e+00 7.9065283e+00 - -3.2104335e+00 9.2428222e-01 6.1582518e+00 - -1.2271506e+00 4.3014451e-01 3.4901784e+00 - -1.2013397e+00 4.2331673e-01 3.5456240e+00 - -1.0831807e+00 3.9382638e-01 3.4591418e+00 - -9.5716216e-01 3.6284737e-01 3.3522593e+00 - -1.0540398e+00 3.8743592e-01 3.6081608e+00 - -8.8689870e-01 3.4494259e-01 3.4204924e+00 - -7.8842083e-01 3.2097914e-01 3.3405673e+00 - -8.6853985e-01 3.4131270e-01 3.5917693e+00 - -1.4214244e+00 4.7865928e-01 4.7952957e+00 - -7.7568171e-01 3.1756840e-01 3.6305144e+00 - -7.2235765e-01 3.0453655e-01 3.6349331e+00 - -6.2985542e-01 2.8155832e-01 3.5473869e+00 - -9.2341780e-01 3.5396118e-01 4.3648380e+00 - -6.7314265e-01 2.9214871e-01 3.9096789e+00 - -5.9828146e-01 2.7337896e-01 3.8651872e+00 - -5.8015935e-01 2.6940454e-01 3.9686990e+00 - -5.2392752e-01 2.5498254e-01 3.9688630e+00 - -5.0674850e-01 2.5099291e-01 4.0911044e+00 - -6.8595877e-01 2.9511602e-01 4.8619863e+00 - -6.0318584e-01 2.7424319e-01 4.8251589e+00 - -4.6283758e-01 2.3979938e-01 4.5650698e+00 - -4.0937933e-01 2.2680836e-01 4.6108367e+00 - -3.1701910e-01 2.0321112e-01 4.4904814e+00 - -2.5583076e-01 1.8769684e-01 4.4948739e+00 - -3.3838975e-01 2.0881812e-01 5.2231406e+00 - -2.6240915e-01 1.8992528e-01 5.2178965e+00 - -1.7969376e-01 1.6910840e-01 5.1619431e+00 - -3.8590106e-01 2.2033683e-01 7.0722467e+00 - 1.3545790e-02 1.2126884e-01 4.7773343e+00 - 7.8628350e-02 1.0421035e-01 4.7755713e+00 - 1.3802236e-01 8.9399734e-02 4.8323047e+00 - 1.6714514e-01 8.2133376e-02 5.3067684e+00 - 2.4768338e-01 6.2055329e-02 5.1823075e+00 - 3.2153572e-01 4.3776407e-02 5.1262837e+00 - 3.4312656e-01 3.8725734e-02 6.9681712e+00 - 4.4542323e-01 1.3131146e-02 6.8600681e+00 - -2.8592386e+00 9.4264374e-01 -9.3656879e-01 - -2.9942052e+00 9.8012282e-01 -9.3177727e-01 - -3.1370380e+00 1.0200696e+00 -9.2725917e-01 - -3.2986198e+00 1.0649556e+00 -9.2687392e-01 - -3.4611068e+00 1.1111601e+00 -9.2124157e-01 - -3.6423949e+00 1.1613711e+00 -9.1839413e-01 - -3.8423576e+00 1.2176316e+00 -9.1743193e-01 - -4.0620464e+00 1.2790593e+00 -9.1720360e-01 - -4.2905749e+00 1.3432123e+00 -9.1325043e-01 - -4.5397576e+00 1.4136687e+00 -9.0847947e-01 - -4.7978309e+00 1.4859273e+00 -8.9843599e-01 - -5.0943105e+00 1.5693583e+00 -8.9191049e-01 - -5.4016646e+00 1.6548109e+00 -8.7810858e-01 - -5.7010719e+00 1.7384412e+00 -8.5094940e-01 - -6.0004163e+00 1.8225741e+00 -8.1360281e-01 - -6.3381410e+00 1.9180864e+00 -7.7557939e-01 - -6.7331062e+00 2.0279973e+00 -7.3941474e-01 - -7.2137333e+00 2.1628996e+00 -7.0815928e-01 - -7.8362360e+00 2.3378771e+00 -6.8881822e-01 - -8.5937485e+00 2.5499889e+00 -6.7167701e-01 - -9.5049090e+00 2.8055751e+00 -6.5272816e-01 - -1.0598337e+01 3.1115854e+00 -6.2783251e-01 - -1.2067043e+01 3.5240905e+00 -6.1158056e-01 - -1.3528731e+01 3.9338333e+00 -5.4146935e-01 - -1.4971542e+01 4.3381192e+00 -4.1693855e-01 - -1.4983448e+01 4.3417876e+00 -1.3559888e-01 - -1.4981618e+01 4.3406366e+00 1.4619411e-01 - -1.4935408e+01 4.3278323e+00 4.2908897e-01 - -4.0772570e+01 1.1571489e+01 2.2154982e-01 - -4.0798836e+01 1.1578162e+01 9.6970578e-01 - -1.5000727e+01 4.3464799e+00 1.2698099e+00 - -1.4291680e+01 4.1468578e+00 1.5257890e+00 - -1.4020967e+01 4.0709094e+00 1.7797751e+00 - -1.3996480e+01 4.0644165e+00 2.0421676e+00 - -1.3985840e+01 4.0608181e+00 2.3056042e+00 - -1.3971208e+01 4.0569778e+00 2.5690281e+00 - -4.2367765e+01 1.2017747e+01 6.4342614e+00 - -4.7457995e+01 1.3444399e+01 7.9636430e+00 - -4.7580246e+01 1.3478885e+01 8.8722183e+00 - -4.7536112e+01 1.3466167e+01 9.7597675e+00 - -4.1568274e+01 1.1792839e+01 9.4599449e+00 - -1.2896075e+01 3.7555873e+00 3.9468478e+00 - -4.8079833e+01 1.3618587e+01 1.2609725e+01 - -4.0980989e+01 1.1628378e+01 1.1708300e+01 - -1.1138775e+01 3.2622662e+00 4.2294668e+00 - -1.1508079e+01 3.3665138e+00 4.5663231e+00 - -1.1363647e+01 3.3261492e+00 4.7571567e+00 - -5.5922993e+00 1.7081234e+00 3.0506859e+00 - -5.4659888e+00 1.6722572e+00 3.1283701e+00 - -3.8725553e+00 1.2261931e+00 2.6490313e+00 - -3.9785726e+00 1.2552354e+00 2.7816176e+00 - -4.0549891e+00 1.2771345e+00 2.9073649e+00 - -8.6950961e+00 2.5774520e+00 5.0453462e+00 - -1.1018912e+01 3.2293262e+00 6.3158240e+00 - -8.7371536e+00 2.5888012e+00 5.4647636e+00 - -1.0072186e+01 2.9629474e+00 6.3449469e+00 - -5.3368669e+00 1.6366800e+00 4.0831043e+00 - -4.2045984e+00 1.3182424e+00 3.5930077e+00 - -4.2278525e+00 1.3247856e+00 3.7165811e+00 - -4.1557015e+00 1.3048597e+00 3.7868046e+00 - -4.2821929e+00 1.3400967e+00 3.9787852e+00 - -4.3290001e+00 1.3533743e+00 4.1285043e+00 - -4.4455736e+00 1.3864662e+00 4.3297409e+00 - -3.7177963e+00 1.1821849e+00 3.9496495e+00 - -3.9995369e+00 1.2610807e+00 4.2662901e+00 - -5.4478120e+00 1.6666995e+00 5.4806331e+00 - -4.0714569e+00 1.2816070e+00 4.5716989e+00 - -3.7674170e+00 1.1963593e+00 4.4570830e+00 - -3.8809925e+00 1.2282662e+00 4.6784843e+00 - -3.8334216e+00 1.2149035e+00 4.7701625e+00 - -3.4135394e+00 1.0972103e+00 4.5269723e+00 - -3.3099959e+00 1.0683846e+00 4.5571913e+00 - -3.3911571e+00 1.0904903e+00 4.7620553e+00 - -4.0762343e+00 1.2819388e+00 5.5816577e+00 - -3.7801189e+00 1.1997239e+00 5.4377050e+00 - -4.2607144e+00 1.3344495e+00 6.1112612e+00 - -5.8102600e+00 1.7684909e+00 8.0165805e+00 - -5.6141352e+00 1.7137088e+00 8.0407001e+00 - -7.9041200e+00 2.3543830e+00 1.1024034e+01 - -7.4240665e+00 2.2205691e+00 1.0791981e+01 - -4.9660641e+00 1.5320288e+00 7.9983031e+00 - -3.2033126e+00 1.0381321e+00 5.9146984e+00 - -3.0742900e+00 1.0013754e+00 5.9172170e+00 - -2.8491004e+00 9.3877764e-01 5.7790422e+00 - -2.8406932e+00 9.3650779e-01 5.9454074e+00 - -2.6705141e+00 8.8850772e-01 5.8726333e+00 - -9.4962383e-01 4.0662648e-01 3.3139086e+00 - -9.3664935e-01 4.0221705e-01 3.3822302e+00 - -1.6711905e+00 6.0857724e-01 4.7444722e+00 - -1.5688381e+00 5.7981726e-01 4.7140205e+00 - -1.5154479e+00 5.6525110e-01 4.7683760e+00 - -1.4836287e+00 5.5615189e-01 4.8661487e+00 - -7.7931045e-01 3.5845327e-01 3.6010862e+00 - -1.8897068e+00 6.6893070e-01 6.0766891e+00 - -1.6737512e+00 6.0848552e-01 5.8293305e+00 - -1.0940434e+00 4.4652907e-01 4.7081528e+00 - -7.2194020e-01 3.4281375e-01 3.9817725e+00 - -6.2475830e-01 3.1498381e-01 3.8830227e+00 - -9.1829622e-01 3.9768203e-01 4.8269223e+00 - -5.5738988e-01 2.9599212e-01 4.0065954e+00 - -8.1740841e-01 3.6916686e-01 4.9610706e+00 - -7.3280192e-01 3.4532514e-01 4.9272820e+00 - -6.6675758e-01 3.2636819e-01 4.9490356e+00 - -5.2857851e-01 2.8808526e-01 4.7099749e+00 - -4.3045105e-01 2.6029023e-01 4.5928949e+00 - -3.6056611e-01 2.4090777e-01 4.5703912e+00 - -2.8294492e-01 2.1905131e-01 4.5075119e+00 - -2.2475520e-01 2.0316976e-01 4.5210523e+00 - -2.9451435e-01 2.2209614e-01 5.2207129e+00 - -2.1678425e-01 2.0007852e-01 5.1950868e+00 - -4.5472733e-01 2.6704663e-01 7.2220545e+00 - -3.2136730e-01 2.2940732e-01 7.0304504e+00 - 4.8932113e-02 1.2636333e-01 4.7815703e+00 - 1.1869478e-01 1.0651951e-01 4.7294536e+00 - 1.7034964e-01 9.2096801e-02 4.8653133e+00 - 2.0147059e-01 8.3176992e-02 5.3694827e+00 - 2.9018264e-01 5.8147565e-02 5.0746052e+00 - 3.6097614e-01 3.8504415e-02 5.0277787e+00 - 3.9716996e-01 2.8562685e-02 6.8293675e+00 - -2.7722194e+00 1.0233510e+00 -9.4258894e-01 - -2.8960679e+00 1.0623020e+00 -9.3503508e-01 - -3.0208899e+00 1.1015104e+00 -9.2348296e-01 - -3.1811878e+00 1.1511976e+00 -9.2584556e-01 - -3.3414530e+00 1.2011459e+00 -9.2291469e-01 - -3.5115118e+00 1.2547487e+00 -9.1890215e-01 - -3.6835318e+00 1.3087532e+00 -9.0919028e-01 - -3.9087133e+00 1.3791516e+00 -9.1677969e-01 - -4.1349064e+00 1.4489881e+00 -9.1672574e-01 - -4.3275109e+00 1.5098528e+00 -8.9491002e-01 - -4.5378416e+00 1.5757934e+00 -8.7323526e-01 - -4.7855933e+00 1.6527426e+00 -8.5717909e-01 - -5.0883952e+00 1.7475830e+00 -8.5077688e-01 - -5.4207057e+00 1.8513338e+00 -8.4222909e-01 - -5.7716414e+00 1.9615283e+00 -8.2757640e-01 - -6.0782914e+00 2.0572493e+00 -7.8795287e-01 - -6.4046263e+00 2.1584675e+00 -7.4237146e-01 - -6.8144653e+00 2.2873943e+00 -7.0495043e-01 - -7.3463344e+00 2.4532132e+00 -6.7900878e-01 - -8.0493113e+00 2.6728054e+00 -6.6707876e-01 - -8.8289233e+00 2.9166757e+00 -6.4325772e-01 - -9.8828847e+00 3.2465873e+00 -6.3440273e-01 - -1.1176800e+01 3.6504337e+00 -6.2030447e-01 - -1.2586542e+01 4.0920098e+00 -5.7311012e-01 - -1.4520401e+01 4.6965447e+00 -5.2791549e-01 - -2.1774674e+01 6.9640611e+00 -8.5550963e-01 - -2.3658777e+01 7.5533975e+00 3.1671712e-01 - -2.3694769e+01 7.5644808e+00 7.5833767e-01 - -3.2705373e+01 1.0381284e+01 1.2753516e+00 - -4.1330554e+01 1.3077344e+01 2.1119321e+00 - -4.2278341e+01 1.3373234e+01 3.7045621e+00 - -4.2216897e+01 1.3354175e+01 4.4855856e+00 - -4.0509083e+01 1.2820236e+01 5.1017222e+00 - -4.1600665e+01 1.3160980e+01 5.9891591e+00 - -4.2041475e+01 1.3298649e+01 6.8308323e+00 - -4.7555332e+01 1.5021387e+01 9.3828996e+00 - -4.2424105e+01 1.3418249e+01 9.2969406e+00 - -4.3280385e+01 1.3684980e+01 1.0293007e+01 - -4.7377785e+01 1.4966041e+01 1.2077455e+01 - -4.7148978e+01 1.4893879e+01 1.2941966e+01 - -1.2366342e+01 4.0216439e+00 4.4745248e+00 - -1.1828214e+01 3.8534924e+00 4.5707101e+00 - -1.0750855e+01 3.5171522e+00 4.4811280e+00 - -1.1301189e+01 3.6889393e+00 4.8872584e+00 - -5.3594305e+00 1.8313562e+00 3.0482759e+00 - -5.2971579e+00 1.8123434e+00 3.1450481e+00 - -4.0889330e+00 1.4339898e+00 2.7930053e+00 - -4.1917381e+00 1.4661372e+00 2.9314261e+00 - -1.1074502e+01 3.6177604e+00 6.0111538e+00 - -1.0665280e+01 3.4898773e+00 6.0747097e+00 - -1.0161867e+01 3.3323137e+00 6.0793745e+00 - -5.1976721e+00 1.7807479e+00 3.8411499e+00 - -5.1579847e+00 1.7686816e+00 3.9493331e+00 - -5.1340337e+00 1.7610021e+00 4.0661079e+00 - -5.1738818e+00 1.7731158e+00 4.2210478e+00 - -4.8868607e+00 1.6838547e+00 4.1866335e+00 - -4.9237826e+00 1.6947261e+00 4.3403151e+00 - -4.6799960e+00 1.6187545e+00 4.3189286e+00 - -4.5353455e+00 1.5736493e+00 4.3541024e+00 - -3.7775254e+00 1.3367909e+00 3.9605142e+00 - -4.2627805e+00 1.4883904e+00 4.4230074e+00 - -4.1348623e+00 1.4482662e+00 4.4573379e+00 - -4.1540607e+00 1.4545561e+00 4.6009235e+00 - -3.9182872e+00 1.3803937e+00 4.5456555e+00 - -3.9482753e+00 1.3898992e+00 4.7004630e+00 - -3.8497887e+00 1.3593012e+00 4.7494237e+00 - -3.6052043e+00 1.2832153e+00 4.6661616e+00 - -3.4146162e+00 1.2233421e+00 4.6214813e+00 - -3.4867675e+00 1.2456298e+00 4.8207739e+00 - -3.3324578e+00 1.1973434e+00 4.8036804e+00 - -4.0935523e+00 1.4353273e+00 5.7204787e+00 - -3.8999880e+00 1.3746108e+00 5.6826299e+00 - -5.1439153e+00 1.7628357e+00 7.2191674e+00 - -9.0278356e+00 2.9770751e+00 1.1874232e+01 - -8.2880089e+00 2.7457349e+00 1.1388169e+01 - -5.2034144e+00 1.7823513e+00 7.9835155e+00 - -4.9950233e+00 1.7169848e+00 7.9710358e+00 - -4.8601029e+00 1.6744942e+00 8.0469910e+00 - -3.0324019e+00 1.1029947e+00 5.8129236e+00 - -2.9515489e+00 1.0782117e+00 5.8767248e+00 - -2.8697666e+00 1.0523023e+00 5.9391741e+00 - -1.8181824e+00 7.2393642e-01 4.5256250e+00 - -1.7854532e+00 7.1407223e-01 4.6091122e+00 - -1.6421728e+00 6.6966548e-01 4.5154011e+00 - -1.6681727e+00 6.7734731e-01 4.6989092e+00 - -1.6158893e+00 6.6094131e-01 4.7552647e+00 - -2.1325502e+00 8.2245154e-01 5.8633596e+00 - -1.5445406e+00 6.3851462e-01 4.9356522e+00 - -8.1707473e-01 4.1094344e-01 3.6425841e+00 - -7.6392454e-01 3.9497493e-01 3.6482502e+00 - -7.5284261e-01 3.9099995e-01 3.7431948e+00 - -7.0264007e-01 3.7558722e-01 3.7564610e+00 - -9.2374195e-01 4.4497744e-01 4.4197235e+00 - -6.8717731e-01 3.7034643e-01 3.9927153e+00 - -8.4757565e-01 4.2086409e-01 4.5720298e+00 - -1.3373114e+00 5.7310368e-01 6.1317725e+00 - -4.8195333e-01 3.0687648e-01 3.8934546e+00 - -4.0941628e-01 2.8354514e-01 3.8350848e+00 - -6.2395443e-01 3.5046091e-01 4.7189009e+00 - -5.3180241e-01 3.2158964e-01 4.6334497e+00 - -5.1449621e-01 3.1655345e-01 4.8155157e+00 - -3.8351229e-01 2.7600017e-01 4.5623939e+00 - -3.2155864e-01 2.5650166e-01 4.5682799e+00 - -2.4799568e-01 2.3333157e-01 4.5144014e+00 - -7.6476884e-01 3.9471788e-01 7.4765899e+00 - -6.5658744e-01 3.6019132e-01 7.4986512e+00 - -5.0202815e-01 3.1256692e-01 7.2328167e+00 - -7.4458944e-02 1.7855404e-01 4.9955237e+00 - 4.9349796e-03 1.5427414e-01 4.9062202e+00 - 8.0326374e-02 1.3015722e-01 4.8153315e+00 - 1.4809126e-01 1.0939125e-01 4.7825964e+00 - 1.8739055e-01 9.6587744e-02 5.0974733e+00 - 2.5439338e-01 7.6221834e-02 5.1324067e+00 - 3.2594419e-01 5.4077747e-02 5.0563627e+00 - 3.4466977e-01 4.7662510e-02 6.9682214e+00 - 4.4168142e-01 1.7225626e-02 7.1800842e+00 - -2.6844982e+00 1.0990525e+00 -9.4756551e-01 - -2.7904521e+00 1.1353057e+00 -9.3217940e-01 - -2.9219413e+00 1.1805889e+00 -9.2759406e-01 - -3.0533437e+00 1.2270810e+00 -9.1876358e-01 - -3.2212153e+00 1.2841516e+00 -9.2304561e-01 - -3.3722738e+00 1.3368867e+00 -9.1340052e-01 - -3.5499038e+00 1.3978926e+00 -9.1090791e-01 - -3.7461481e+00 1.4659451e+00 -9.1035009e-01 - -3.8991615e+00 1.5186170e+00 -8.8416944e-01 - -4.0708512e+00 1.5773237e+00 -8.6017365e-01 - -4.3142105e+00 1.6613515e+00 -8.5781019e-01 - -4.5585155e+00 1.7458585e+00 -8.4695404e-01 - -4.8126485e+00 1.8332300e+00 -8.3077184e-01 - -5.1040648e+00 1.9337419e+00 -8.1751079e-01 - -5.4150523e+00 2.0416908e+00 -7.9948960e-01 - -5.7545441e+00 2.1585390e+00 -7.7832725e-01 - -6.0488173e+00 2.2598168e+00 -7.3294669e-01 - -6.4353618e+00 2.3931379e+00 -6.9989116e-01 - -6.9524604e+00 2.5716934e+00 -6.8227834e-01 - -7.5726281e+00 2.7854438e+00 -6.6706701e-01 - -8.2780839e+00 3.0297516e+00 -6.4522715e-01 - -9.2280064e+00 3.3572756e+00 -6.3869883e-01 - -1.0358459e+01 3.7472598e+00 -6.2412481e-01 - -1.1631146e+01 4.1860926e+00 -5.8665228e-01 - -1.3479892e+01 4.8243404e+00 -5.6697480e-01 - -2.0480970e+01 7.2397735e+00 -9.6089922e-01 - -2.1259794e+01 7.5088944e+00 -2.2625033e-01 - -3.0534212e+01 1.0708674e+01 -1.7495259e-01 - -3.0596228e+01 1.0729828e+01 3.9729338e-01 - -3.0677833e+01 1.0758271e+01 9.7130318e-01 - -3.1750532e+01 1.1128452e+01 1.5658120e+00 - -4.9818871e+01 1.7362248e+01 2.8122227e+00 - -4.3844048e+01 1.5299865e+01 4.2389542e+00 - -4.1269115e+01 1.4412227e+01 4.8267357e+00 - -4.1303037e+01 1.4423048e+01 5.6086762e+00 - -4.1634124e+01 1.4537178e+01 6.4330112e+00 - -4.7834940e+01 1.6676316e+01 9.9692127e+00 - -4.0681739e+01 1.4208228e+01 9.4280401e+00 - -4.2533719e+01 1.4846465e+01 1.0634302e+01 - -1.2150515e+01 4.3639992e+00 4.0771371e+00 - -1.2188915e+01 4.3780967e+00 4.3342965e+00 - -1.0716479e+01 3.8696483e+00 4.1681635e+00 - -1.1417784e+01 4.1111527e+00 4.6028251e+00 - -1.1401337e+01 4.1057431e+00 4.8368789e+00 - -1.0680054e+01 3.8572587e+00 4.8309669e+00 - -1.0355894e+01 3.7449295e+00 4.9426402e+00 - -1.0955074e+01 3.9512190e+00 5.3983330e+00 - -5.3628565e+00 2.0223079e+00 3.3744917e+00 - -5.2791553e+00 1.9935954e+00 3.4636002e+00 - -5.1337194e+00 1.9436354e+00 3.5231384e+00 - -5.1078637e+00 1.9345867e+00 3.6348626e+00 - -5.0555599e+00 1.9162819e+00 3.7337639e+00 - -5.0855090e+00 1.9271309e+00 3.8752886e+00 - -5.1135711e+00 1.9359538e+00 4.0187038e+00 - -5.2884683e+00 1.9970511e+00 4.2483553e+00 - -4.8864681e+00 1.8576158e+00 4.1514269e+00 - -5.6118120e+00 2.1084618e+00 4.7246473e+00 - -4.9659499e+00 1.8851050e+00 4.4666514e+00 - -4.8675518e+00 1.8517362e+00 4.5404798e+00 - -4.6419392e+00 1.7731359e+00 4.5248420e+00 - -4.5749064e+00 1.7504308e+00 4.6136569e+00 - -4.2592277e+00 1.6413326e+00 4.5176672e+00 - -4.1922405e+00 1.6182629e+00 4.5990912e+00 - -4.1478058e+00 1.6024011e+00 4.6972198e+00 - -4.1454036e+00 1.6019132e+00 4.8315947e+00 - -4.0304799e+00 1.5619129e+00 4.8728078e+00 - -3.7413318e+00 1.4624439e+00 4.7566824e+00 - -3.5138954e+00 1.3838905e+00 4.6836603e+00 - -3.4459398e+00 1.3610381e+00 4.7504496e+00 - -3.4181814e+00 1.3506055e+00 4.8568236e+00 - -3.2514132e+00 1.2937861e+00 4.8244549e+00 - -4.0374005e+00 1.5648018e+00 5.7903398e+00 - -4.0369005e+00 1.5641554e+00 5.9595773e+00 - -3.8642445e+00 1.5046179e+00 5.9402222e+00 - -3.3826134e+00 1.3388856e+00 5.5522395e+00 - -5.3501224e+00 2.0168807e+00 8.1042142e+00 - -4.9583064e+00 1.8821041e+00 7.8666457e+00 - -3.3194585e+00 1.3171248e+00 5.9782476e+00 - -3.1430373e+00 1.2555275e+00 5.9220253e+00 - -2.9587596e+00 1.1924170e+00 5.8449034e+00 - -2.8839716e+00 1.1663575e+00 5.9160139e+00 - -1.8577853e+00 8.1296451e-01 4.5533172e+00 - -1.7929017e+00 7.9070588e-01 4.5879565e+00 - -1.7290242e+00 7.6844366e-01 4.6213006e+00 - -1.6436457e+00 7.3912458e-01 4.6195165e+00 - -1.6325011e+00 7.3461894e-01 4.7442236e+00 - -1.7647349e+00 7.8022620e-01 5.1378774e+00 - -8.6469464e-01 4.7071837e-01 3.5966762e+00 - -1.4622296e+00 6.7652655e-01 4.8923185e+00 - -8.2501079e-01 4.5656111e-01 3.7435101e+00 - -7.6710468e-01 4.3686593e-01 3.7405197e+00 - -7.1801704e-01 4.1954929e-01 3.7544875e+00 - -6.7668824e-01 4.0555757e-01 3.7855603e+00 - -8.6323779e-01 4.6976761e-01 4.3865883e+00 - -8.0721807e-01 4.5055615e-01 4.4112198e+00 - -1.3622491e+00 6.4196483e-01 6.1146125e+00 - -5.1235974e-01 3.4871152e-01 3.9313276e+00 - -4.4281391e-01 3.2507202e-01 3.8833043e+00 - -3.5971752e-01 2.9616837e-01 3.7861962e+00 - -5.5433672e-01 3.6306775e-01 4.6333450e+00 - -5.1578419e-01 3.4945410e-01 4.7291963e+00 - -3.9765499e-01 3.0910991e-01 4.5252040e+00 - -3.2519934e-01 2.8358091e-01 4.4830631e+00 - -2.8273429e-01 2.6908498e-01 4.5659176e+00 - -2.0448713e-01 2.4213086e-01 4.4819596e+00 - -7.6805326e-01 4.3607643e-01 7.8607464e+00 - -2.2930155e-01 2.5030298e-01 5.3427717e+00 - -1.5762665e-01 2.2554037e-01 5.3554655e+00 - -2.3586951e-02 1.7983719e-01 4.9015309e+00 - 2.8775679e-02 1.6148620e-01 5.0197580e+00 - 1.1933605e-01 1.3051146e-01 4.7891412e+00 - 1.8310620e-01 1.0893932e-01 4.7756943e+00 - 2.1497809e-01 9.7983442e-02 5.2398100e+00 - 2.9109535e-01 7.1114319e-02 5.1146101e+00 - 2.8691815e-01 7.2503269e-02 7.2363844e+00 - 3.9828243e-01 3.3541541e-02 6.7694414e+00 - -2.6987419e+00 1.2107359e+00 -9.3776795e-01 - -2.8112793e+00 1.2542480e+00 -9.2560285e-01 - -2.9503465e+00 1.3068802e+00 -9.2363609e-01 - -3.0904443e+00 1.3587976e+00 -9.1712215e-01 - -3.2559403e+00 1.4218719e+00 -9.1881141e-01 - -3.3802575e+00 1.4687241e+00 -8.9412280e-01 - -3.5045501e+00 1.5157734e+00 -8.6543912e-01 - -3.6905976e+00 1.5864882e+00 -8.5946865e-01 - -3.8943160e+00 1.6632363e+00 -8.5448771e-01 - -4.1077523e+00 1.7447591e+00 -8.4597774e-01 - -4.2957330e+00 1.8155832e+00 -8.1997603e-01 - -4.5199590e+00 1.9003215e+00 -8.0024411e-01 - -4.7705985e+00 1.9956252e+00 -7.8167131e-01 - -5.0320598e+00 2.0938883e+00 -7.5707015e-01 - -5.3394935e+00 2.2107665e+00 -7.3670791e-01 - -5.7106401e+00 2.3512223e+00 -7.2302270e-01 - -6.0836997e+00 2.4924641e+00 -6.9584778e-01 - -6.5126250e+00 2.6541491e+00 -6.6833521e-01 - -7.0786626e+00 2.8685294e+00 -6.5539142e-01 - -7.7298827e+00 3.1153428e+00 -6.3831527e-01 - -8.6044899e+00 3.4460771e+00 -6.3711601e-01 - -9.5544401e+00 3.8054405e+00 -6.1563772e-01 - -1.0756025e+01 4.2612260e+00 -5.9465911e-01 - -1.2397499e+01 4.8815459e+00 -5.8288600e-01 - -2.0757230e+01 8.0464248e+00 -8.0834940e-01 - -2.8857470e+01 1.1111902e+01 -3.9753060e-01 - -2.8969409e+01 1.1153790e+01 1.4776841e-01 - -2.9249757e+01 1.1260108e+01 6.9493370e-01 - -2.9138351e+01 1.1217735e+01 1.2492181e+00 - -3.0747631e+01 1.1826067e+01 1.8460049e+00 - -3.0523495e+01 1.1741729e+01 2.4194855e+00 - -3.0505069e+01 1.1734299e+01 2.9987524e+00 - -4.3111569e+01 1.6505756e+01 4.6290085e+00 - -4.0485231e+01 1.5510538e+01 9.8756193e+00 - -4.0416214e+01 1.5484091e+01 1.0658462e+01 - -1.2181785e+01 4.7984104e+00 4.2427319e+00 - -1.0532085e+01 4.1751052e+00 4.0396191e+00 - -1.0580363e+01 4.1926963e+00 4.2743396e+00 - -1.1072818e+01 4.3786990e+00 4.6533793e+00 - -1.0975223e+01 4.3417864e+00 4.8567471e+00 - -5.1437581e+00 2.1355529e+00 3.0131159e+00 - -5.0837344e+00 2.1125796e+00 3.1081950e+00 - -5.0481277e+00 2.0995365e+00 3.2119460e+00 - -5.0292058e+00 2.0918537e+00 3.3225443e+00 - -5.0249084e+00 2.0904369e+00 3.4405331e+00 - -5.0264506e+00 2.0916083e+00 3.5631361e+00 - -5.0437260e+00 2.0971910e+00 3.6948300e+00 - -5.0833875e+00 2.1128590e+00 3.8407827e+00 - -6.0245956e+00 2.4688050e+00 4.4701252e+00 - -5.8344677e+00 2.3964866e+00 4.5175744e+00 - -5.0518831e+00 2.1005141e+00 4.2159594e+00 - -4.8109910e+00 2.0092344e+00 4.2059590e+00 - -4.8389559e+00 2.0193499e+00 4.3553172e+00 - -4.7270766e+00 1.9775845e+00 4.4178623e+00 - -4.6553111e+00 1.9504515e+00 4.5040629e+00 - -4.3392399e+00 1.8307795e+00 4.4178038e+00 - -4.3603571e+00 1.8383252e+00 4.5641427e+00 - -4.0121013e+00 1.7065002e+00 4.4339297e+00 - -4.2256598e+00 1.7873477e+00 4.7314301e+00 - -4.6843762e+00 1.9609290e+00 5.2446393e+00 - -3.8887386e+00 1.6603584e+00 4.7251016e+00 - -3.9137186e+00 1.6696996e+00 4.8826897e+00 - -3.9572290e+00 1.6862431e+00 5.0617638e+00 - -4.1071764e+00 1.7427000e+00 5.3494616e+00 - -4.1526144e+00 1.7593972e+00 5.5494658e+00 - -5.9856343e+00 2.4529135e+00 7.5680889e+00 - -3.9816974e+00 1.6953317e+00 5.6992532e+00 - -3.9567871e+00 1.6857340e+00 5.8391450e+00 - -3.5229283e+00 1.5214411e+00 5.5229744e+00 - -3.3536131e+00 1.4572546e+00 5.4867482e+00 - -3.3101721e+00 1.4409736e+00 5.5954165e+00 - -5.4608878e+00 2.2542450e+00 8.4467253e+00 - -3.2116072e+00 1.4032647e+00 5.8041241e+00 - -3.1154439e+00 1.3675959e+00 5.8491440e+00 - -3.1207716e+00 1.3691172e+00 6.0347308e+00 - -2.8881245e+00 1.2814030e+00 5.8846328e+00 - -2.4761657e+00 1.1256214e+00 5.4507328e+00 - -2.3977174e+00 1.0951172e+00 5.4974095e+00 - -1.7812574e+00 8.6256883e-01 4.6756524e+00 - -1.6853558e+00 8.2583943e-01 4.6586497e+00 - -1.6011002e+00 7.9455241e-01 4.6562687e+00 - -9.2284038e-01 5.3736484e-01 3.5753248e+00 - -8.7572749e-01 5.2034154e-01 3.5927946e+00 - -1.5266619e+00 7.6599962e-01 4.9795152e+00 - -8.5948194e-01 5.1383501e-01 3.7843513e+00 - -7.6374214e-01 4.7787627e-01 3.7019309e+00 - -7.4784346e-01 4.7117651e-01 3.7882695e+00 - -6.9394399e-01 4.5109568e-01 3.7928321e+00 - -1.2543615e+00 6.6315379e-01 5.2996983e+00 - -1.4675052e+00 7.4297513e-01 6.0614193e+00 - -5.6634229e-01 4.0276887e-01 3.8837385e+00 - -5.2215424e-01 3.8648365e-01 3.9125039e+00 - -4.6540865e-01 3.6451999e-01 3.9028242e+00 - -1.7663720e+00 8.5602340e-01 8.2149485e+00 - -6.4360818e-01 4.3197736e-01 4.8618823e+00 - -8.1815966e-01 4.9798622e-01 5.7356841e+00 - -3.9906013e-01 3.3952715e-01 4.4493205e+00 - -3.4027856e-01 3.1724377e-01 4.4558640e+00 - -2.9693352e-01 3.0122733e-01 4.5293765e+00 - -2.1692802e-01 2.7070326e-01 4.4362723e+00 - -1.6972267e-01 2.5287164e-01 4.4981361e+00 - -2.6684969e-01 2.8926309e-01 5.3948480e+00 - -1.5213649e-01 2.4521622e-01 5.1323871e+00 - -5.3802902e-02 2.0896843e-01 4.9262124e+00 - 1.5613030e-02 1.8222793e-01 4.8963650e+00 - 6.2168938e-02 1.6466476e-01 5.0637498e+00 - 1.5622649e-01 1.2897300e-01 4.7626569e+00 - 1.9159784e-01 1.1538126e-01 5.1174461e+00 - 2.6204133e-01 8.9330933e-02 5.0825522e+00 - 3.2860888e-01 6.3939419e-02 5.0763851e+00 - 3.4284647e-01 5.7718783e-02 7.1481592e+00 - 4.4367100e-01 2.0145196e-02 7.1201542e+00 - -2.7010942e+00 1.3199708e+00 -9.2241622e-01 - -2.8301046e+00 1.3731137e+00 -9.1813377e-01 - -2.9590886e+00 1.4264685e+00 -9.0955662e-01 - -3.0812131e+00 1.4768329e+00 -8.9226368e-01 - -3.1944847e+00 1.5240614e+00 -8.6676070e-01 - -3.3596986e+00 1.5914537e+00 -8.6195643e-01 - -3.5414714e+00 1.6667587e+00 -8.5934260e-01 - -3.6909588e+00 1.7281381e+00 -8.3531534e-01 - -3.8668271e+00 1.8008580e+00 -8.1699119e-01 - -4.0514810e+00 1.8772509e+00 -7.9599052e-01 - -4.2723827e+00 1.9675384e+00 -7.8165915e-01 - -4.4765309e+00 2.0524983e+00 -7.5325124e-01 - -4.7159766e+00 2.1503939e+00 -7.2946872e-01 - -5.0003420e+00 2.2677968e+00 -7.1087673e-01 - -5.3042171e+00 2.3936436e+00 -6.8737441e-01 - -5.6354730e+00 2.5303624e+00 -6.6003419e-01 - -6.0753208e+00 2.7110055e+00 -6.4780714e-01 - -6.5805858e+00 2.9197438e+00 -6.3415920e-01 - -7.2413795e+00 3.1913528e+00 -6.3436695e-01 - -7.9401476e+00 3.4801636e+00 -6.1716659e-01 - -8.8501085e+00 3.8554465e+00 -6.1023709e-01 - -9.8264651e+00 4.2580096e+00 -5.7911243e-01 - -1.1511673e+01 4.9522697e+00 -6.0606028e-01 - -1.5359464e+01 6.5393308e+00 -8.1758885e-01 - -1.8527345e+01 7.8450482e+00 -8.1808791e-01 - -1.9015055e+01 8.0460938e+00 -4.9388616e-01 - -2.7335316e+01 1.1476138e+01 -6.0361414e-01 - -2.7357117e+01 1.1485524e+01 -7.7993840e-02 - -2.7712318e+01 1.1631091e+01 4.4136494e-01 - -2.7736073e+01 1.1640937e+01 9.7388309e-01 - -4.2682964e+01 1.7801093e+01 9.1941789e+00 - -4.0937746e+01 1.7081471e+01 9.6717621e+00 - -4.1894396e+01 1.7475491e+01 1.0705323e+01 - -5.0875270e+00 2.3027940e+00 2.3898610e+00 - -5.0910676e+00 2.3045857e+00 2.5023333e+00 - -5.0750966e+00 2.2979482e+00 2.6101949e+00 - -5.0308352e+00 2.2791546e+00 2.7096706e+00 - -5.0021529e+00 2.2675513e+00 2.8137939e+00 - -4.9803213e+00 2.2584932e+00 2.9204371e+00 - -4.9838397e+00 2.2604622e+00 3.0365049e+00 - -4.9766966e+00 2.2566435e+00 3.1499890e+00 - -4.9753372e+00 2.2563754e+00 3.2673385e+00 - -4.9983756e+00 2.2661904e+00 3.3964563e+00 - -5.0350888e+00 2.2813075e+00 3.5349086e+00 - -1.1296643e+01 4.8614396e+00 6.6673600e+00 - -8.3114216e+00 3.6318070e+00 5.4338146e+00 - -8.1390978e+00 3.5598159e+00 5.5469385e+00 - -6.0200371e+00 2.6869013e+00 4.5852941e+00 - -5.8390450e+00 2.6123627e+00 4.6375149e+00 - -4.5819442e+00 2.0944899e+00 4.0402421e+00 - -4.7883529e+00 2.1798237e+00 4.2954253e+00 - -6.7720632e+00 2.9971801e+00 5.7164391e+00 - -4.6314929e+00 2.1143969e+00 4.4612862e+00 - -4.5520832e+00 2.0814752e+00 4.5412171e+00 - -4.3331676e+00 1.9919065e+00 4.5187526e+00 - -4.1923450e+00 1.9336183e+00 4.5463902e+00 - -4.2016995e+00 1.9371718e+00 4.6872465e+00 - -4.0306607e+00 1.8665590e+00 4.6852685e+00 - -3.8898413e+00 1.8087603e+00 4.7025692e+00 - -3.8582051e+00 1.7961364e+00 4.8099285e+00 - -3.8743554e+00 1.8026735e+00 4.9621938e+00 - -3.9002136e+00 1.8135500e+00 5.1294237e+00 - -3.7370355e+00 1.7459633e+00 5.1182336e+00 - -3.9879854e+00 1.8491873e+00 5.5177880e+00 - -3.9680076e+00 1.8408740e+00 5.6573466e+00 - -5.2270976e+00 2.3598274e+00 7.1821224e+00 - -3.8530171e+00 1.7931550e+00 5.8662463e+00 - -3.2691047e+00 1.5523230e+00 5.3629907e+00 - -3.2228427e+00 1.5334430e+00 5.4631592e+00 - -3.2720266e+00 1.5533859e+00 5.6835518e+00 - -8.2473783e+00 3.6027483e+00 1.2252962e+01 - -3.2583094e+00 1.5476907e+00 6.0094498e+00 - -2.9034674e+00 1.4016228e+00 5.7015787e+00 - -2.6041710e+00 1.2785550e+00 5.4458813e+00 - -2.4888480e+00 1.2311299e+00 5.4390985e+00 - -2.4008165e+00 1.1942581e+00 5.4702107e+00 - -2.0121661e+00 1.0350020e+00 5.0188039e+00 - -1.7248337e+00 9.1638178e-01 4.6967794e+00 - -1.6602629e+00 8.8904478e-01 4.7297688e+00 - -1.5995194e+00 8.6430313e-01 4.7699628e+00 - -1.5387832e+00 8.3950236e-01 4.8089583e+00 - -1.8404382e+00 9.6400816e-01 5.5549041e+00 - -1.8408468e+00 9.6362243e-01 5.7484643e+00 - -7.8370342e-01 5.2796784e-01 3.7168045e+00 - -7.3185311e-01 5.0707007e-01 3.7226216e+00 - -6.9169944e-01 4.9017749e-01 3.7544455e+00 - -1.2908139e+00 7.3747351e-01 5.3380087e+00 - -1.4676598e+00 8.0998859e-01 5.9968390e+00 - -2.3132257e+00 1.1573893e+00 8.5079338e+00 - -5.2414014e-01 4.2184407e-01 3.8748275e+00 - -4.8107439e-01 4.0359582e-01 3.9030959e+00 - -9.0746256e-01 5.7923719e-01 5.4052241e+00 - -5.7580343e-01 4.4225937e-01 4.5658926e+00 - -5.3930561e-01 4.2778445e-01 4.6620994e+00 - -4.6806968e-01 3.9796668e-01 4.6330935e+00 - -3.6110776e-01 3.5369504e-01 4.4575987e+00 - -3.0919786e-01 3.3224197e-01 4.4926789e+00 - -4.6830935e-01 3.9746975e-01 5.5108020e+00 - -1.8896884e-01 2.8332057e-01 4.4819346e+00 - -3.0621577e-01 3.3080112e-01 5.4562199e+00 - -2.0310758e-01 2.8891300e-01 5.2836351e+00 - -6.5725907e-02 2.3209512e-01 4.8321305e+00 - -1.4601071e-02 2.1137395e-01 4.9213462e+00 - 6.0371258e-02 1.8029805e-01 4.8312038e+00 - 1.1816533e-01 1.5609741e-01 4.8786984e+00 - 1.7607531e-01 1.3282299e-01 4.9449697e+00 - 2.2187387e-01 1.1311876e-01 5.2298095e+00 - 2.9581434e-01 8.2865535e-02 5.1146020e+00 - 2.9874972e-01 8.0922495e-02 7.0165255e+00 - 4.0132814e-01 3.8411105e-02 6.6894841e+00 - -2.6056931e+00 1.3901695e+00 -9.2786962e-01 - -2.7158728e+00 1.4395425e+00 -9.1600818e-01 - -2.7948211e+00 1.4740878e+00 -8.8198143e-01 - -2.9225580e+00 1.5314340e+00 -8.7230726e-01 - -3.0756963e+00 1.5999125e+00 -8.7133568e-01 - -3.2210327e+00 1.6643777e+00 -8.6090281e-01 - -3.3751043e+00 1.7334339e+00 -8.4944100e-01 - -3.5389063e+00 1.8071662e+00 -8.3644768e-01 - -3.7036713e+00 1.8812398e+00 -8.1775822e-01 - -3.8684607e+00 1.9546022e+00 -7.9322636e-01 - -4.0342132e+00 2.0283058e+00 -7.6299836e-01 - -4.2350954e+00 2.1178326e+00 -7.3964181e-01 - -4.4358737e+00 2.2087062e+00 -7.0924356e-01 - -4.6728836e+00 2.3136025e+00 -6.8291783e-01 - -4.9536928e+00 2.4399543e+00 -6.6158527e-01 - -5.2882208e+00 2.5893778e+00 -6.4496402e-01 - -5.5709533e+00 2.7159177e+00 -6.0200220e-01 - -6.0947865e+00 2.9499070e+00 -6.0740733e-01 - -6.7278415e+00 3.2334028e+00 -6.1728365e-01 - -7.4165032e+00 3.5409582e+00 -6.1428662e-01 - -8.2416371e+00 3.9109649e+00 -6.1042394e-01 - -9.2053718e+00 4.3409422e+00 -5.9765035e-01 - -1.0586552e+01 4.9594402e+00 -6.0892067e-01 - -1.2042753e+01 5.6106963e+00 -5.7698910e-01 - -1.7471959e+01 8.0394186e+00 -9.1228690e-01 - -1.9065158e+01 8.7518041e+00 -7.0490599e-01 - -1.9116700e+01 8.7744322e+00 -3.3244365e-01 - -2.5947368e+01 1.1830204e+01 -2.8942752e-01 - -2.6155562e+01 1.1922805e+01 2.1071072e-01 - -2.6465167e+01 1.2060968e+01 7.1723735e-01 - -2.6986393e+01 1.2293834e+01 1.2373196e+00 - -2.0919187e+01 9.5799111e+00 1.5945621e+00 - -2.0897396e+01 9.5708330e+00 2.0034794e+00 - -5.5782141e+01 2.5173137e+01 5.7991503e+00 - -5.6068454e+01 2.5300081e+01 1.1315165e+01 - -4.9857744e+00 2.4535751e+00 2.2172923e+00 - -4.9299185e+00 2.4278970e+00 2.3134316e+00 - -4.9168935e+00 2.4223442e+00 2.4193555e+00 - -4.9204446e+00 2.4240521e+00 2.5301299e+00 - -4.9210582e+00 2.4246063e+00 2.6414436e+00 - -4.9119459e+00 2.4204499e+00 2.7505268e+00 - -4.9174662e+00 2.4224955e+00 2.8657021e+00 - -4.9307664e+00 2.4282126e+00 2.9847493e+00 - -4.9499069e+00 2.4365129e+00 3.1083107e+00 - -1.1518427e+01 5.3748020e+00 5.9094005e+00 - -1.1251723e+01 5.2547366e+00 6.0579547e+00 - -1.1456465e+01 5.3458695e+00 6.4116634e+00 - -9.8689996e+00 4.6361053e+00 5.9271469e+00 - -1.0013339e+01 4.7013145e+00 6.2363054e+00 - -1.0110007e+01 4.7438658e+00 6.5309684e+00 - -1.0110183e+01 4.7443141e+00 6.7819570e+00 - -8.8903380e+00 4.1984534e+00 6.3431883e+00 - -4.4537341e+00 2.2151590e+00 3.9397827e+00 - -4.4134672e+00 2.1965924e+00 4.0389716e+00 - -4.3887498e+00 2.1854527e+00 4.1476020e+00 - -4.4779166e+00 2.2252002e+00 4.3344239e+00 - -4.1777296e+00 2.0908975e+00 4.2573949e+00 - -4.3301330e+00 2.1590593e+00 4.4950695e+00 - -4.3043817e+00 2.1481449e+00 4.6094896e+00 - -4.3205505e+00 2.1545342e+00 4.7587586e+00 - -4.1352503e+00 2.0716590e+00 4.7493876e+00 - -3.8283339e+00 1.9348738e+00 4.6305879e+00 - -4.0701631e+00 2.0427754e+00 4.9738863e+00 - -3.8926407e+00 1.9641055e+00 4.9589492e+00 - -3.8222330e+00 1.9315801e+00 5.0359125e+00 - -4.1339661e+00 2.0708761e+00 5.4819218e+00 - -3.6443294e+00 1.8523461e+00 5.1513617e+00 - -5.4533211e+00 2.6610726e+00 7.1761682e+00 - -5.2815353e+00 2.5842663e+00 7.2119373e+00 - -5.1311822e+00 2.5166111e+00 7.2645084e+00 - -5.0050840e+00 2.4606960e+00 7.3421815e+00 - -3.2483125e+00 1.6748534e+00 5.4721605e+00 - -3.2254546e+00 1.6649283e+00 5.6029699e+00 - -3.0383751e+00 1.5817453e+00 5.5290235e+00 - -2.7163875e+00 1.4368048e+00 5.2644529e+00 - -2.6362551e+00 1.4011063e+00 5.3095732e+00 - -2.5667734e+00 1.3707651e+00 5.3688128e+00 - -2.5022407e+00 1.3410612e+00 5.4348598e+00 - -2.4366569e+00 1.3122346e+00 5.4996556e+00 - -2.3332329e+00 1.2661655e+00 5.5056951e+00 - -1.6611720e+00 9.6528727e-01 4.5674179e+00 - -1.6083589e+00 9.4146770e-01 4.6165264e+00 - -1.5797586e+00 9.2920917e-01 4.7073660e+00 - -1.4784234e+00 8.8406929e-01 4.6690179e+00 - -1.4557135e+00 8.7296174e-01 4.7758569e+00 - -1.7702702e+00 1.0135898e+00 5.5681450e+00 - -2.8715726e+00 1.5056452e+00 8.0754852e+00 - -1.5413066e+00 9.1178401e-01 5.4731319e+00 - -1.6433377e+00 9.5763714e-01 5.9084388e+00 - -1.5691082e+00 9.2350523e-01 5.9577236e+00 - -1.4899525e+00 8.8855376e-01 5.9965054e+00 - -2.3483653e+00 1.2718975e+00 8.5088100e+00 - -5.2412909e-01 4.5708852e-01 3.8372447e+00 - -5.1399869e-01 4.5251524e-01 3.9593582e+00 - -4.0918027e-01 4.0512554e-01 3.7992492e+00 - -8.5190424e-01 6.0314193e-01 5.4088082e+00 - -5.4804211e-01 4.6752136e-01 4.6235480e+00 - -4.7111376e-01 4.3342379e-01 4.5758948e+00 - -3.8463305e-01 3.9425953e-01 4.4782707e+00 - -3.5495839e-01 3.8151827e-01 4.6010670e+00 - -2.6462456e-01 3.4151289e-01 4.4710206e+00 - -2.5513662e-01 3.3674812e-01 4.7095911e+00 - -1.8312181e-01 3.0460184e-01 4.6548634e+00 - -2.5871025e-01 3.3784577e-01 5.4538771e+00 - -1.3011667e-01 2.8003905e-01 5.0928870e+00 - -2.8458756e-02 2.3511422e-01 4.8372583e+00 - 2.2603595e-02 2.1286225e-01 4.9359615e+00 - 9.3580579e-02 1.8097525e-01 4.8650074e+00 - 1.6348768e-01 1.4909133e-01 4.7726333e+00 - 2.0248321e-01 1.3179748e-01 5.0775209e+00 - 2.6688137e-01 1.0308099e-01 5.0825449e+00 - 3.3220865e-01 7.3752249e-02 5.0763795e+00 - 3.4202052e-01 6.8223815e-02 7.3181564e+00 - 4.4541110e-01 2.2102636e-02 7.0001990e+00 - -2.5018767e+00 1.4501255e+00 -9.2736292e-01 - -2.5630693e+00 1.4798314e+00 -8.8840113e-01 - -2.6642919e+00 1.5279344e+00 -8.7102554e-01 - -2.7888088e+00 1.5889638e+00 -8.6405602e-01 - -2.9231262e+00 1.6535936e+00 -8.5710348e-01 - -3.0661831e+00 1.7227798e+00 -8.4982114e-01 - -3.2092085e+00 1.7922173e+00 -8.3744509e-01 - -3.3707936e+00 1.8696539e+00 -8.2795226e-01 - -3.5069865e+00 1.9353702e+00 -8.0141754e-01 - -3.6606781e+00 2.0100418e+00 -7.7741926e-01 - -3.8066319e+00 2.0796737e+00 -7.4450940e-01 - -4.0119502e+00 2.1790930e+00 -7.2932296e-01 - -4.1928763e+00 2.2668375e+00 -6.9739106e-01 - -4.4254433e+00 2.3792164e+00 -6.7656815e-01 - -4.7193895e+00 2.5208417e+00 -6.6662112e-01 - -4.9539002e+00 2.6332461e+00 -6.2746488e-01 - -5.3275865e+00 2.8147364e+00 -6.1869173e-01 - -5.6243827e+00 2.9571817e+00 -5.7552657e-01 - -6.2376328e+00 3.2539758e+00 -5.9649384e-01 - -7.0135323e+00 3.6282539e+00 -6.2848937e-01 - -7.7113559e+00 3.9659575e+00 -6.1530861e-01 - -8.6341490e+00 4.4109101e+00 -6.1474029e-01 - -9.7905218e+00 4.9692171e+00 -6.1531796e-01 - -1.1333361e+01 5.7139474e+00 -6.2430794e-01 - -1.6443717e+01 8.1819216e+00 -9.9324686e-01 - -1.6965544e+01 8.4339990e+00 -7.1300319e-01 - -1.7017066e+01 8.4588561e+00 -3.7639502e-01 - -2.4643824e+01 1.2140882e+01 -4.8661365e-01 - -2.4771785e+01 1.2202715e+01 -3.4751990e-03 - -2.5026290e+01 1.2325447e+01 4.8154542e-01 - -2.5013074e+01 1.2319146e+01 9.7628458e-01 - -4.4628772e+01 2.1790645e+01 1.8324408e+00 - -5.2840105e+01 2.5755271e+01 4.0539792e+00 - -5.2963174e+01 2.5813392e+01 6.1434517e+00 - -4.8765028e+00 2.5960201e+00 2.0475914e+00 - -4.8061796e+00 2.5612724e+00 2.1402841e+00 - -4.7960963e+00 2.5568388e+00 2.2449695e+00 - -4.8113193e+00 2.5642962e+00 2.3563333e+00 - -4.8411767e+00 2.5779408e+00 2.4734896e+00 - -4.8602418e+00 2.5878754e+00 2.5896610e+00 - -4.9046567e+00 2.6088371e+00 2.7152570e+00 - -1.1991823e+01 6.0305367e+00 5.2278722e+00 - -1.1640994e+01 5.8608190e+00 5.3676432e+00 - -1.1502140e+01 5.7935894e+00 5.5762567e+00 - -1.1512961e+01 5.7994394e+00 5.8422632e+00 - -1.1157361e+01 5.6271514e+00 5.9562997e+00 - -1.1437463e+01 5.7625489e+00 6.3421318e+00 - -1.0613418e+01 5.3639403e+00 6.2256461e+00 - -1.0150971e+01 5.1407891e+00 6.2534233e+00 - -9.8470209e+00 4.9935806e+00 6.3451150e+00 - -8.5139373e+00 4.3508483e+00 5.8708770e+00 - -9.1099023e+00 4.6380968e+00 6.4255835e+00 - -5.8814431e+00 3.0803839e+00 4.7594686e+00 - -5.8372788e+00 3.0582363e+00 4.8922513e+00 - -5.8610796e+00 3.0694796e+00 5.0693625e+00 - -4.1897509e+00 2.2634481e+00 4.1222011e+00 - -4.5594132e+00 2.4421534e+00 4.5036463e+00 - -4.3531328e+00 2.3418689e+00 4.4924015e+00 - -4.1924538e+00 2.2647126e+00 4.5076309e+00 - -3.9667589e+00 2.1557397e+00 4.4662572e+00 - -3.8750612e+00 2.1118919e+00 4.5229220e+00 - -3.8193395e+00 2.0846257e+00 4.6071257e+00 - -3.9257560e+00 2.1353189e+00 4.8317613e+00 - -3.9136463e+00 2.1299727e+00 4.9609093e+00 - -3.8025724e+00 2.0760978e+00 5.0008280e+00 - -4.4601382e+00 2.3931857e+00 5.7783190e+00 - -3.7677389e+00 2.0587241e+00 5.2586873e+00 - -6.0474574e+00 3.1586140e+00 7.7664467e+00 - -3.3592824e+00 1.8621471e+00 5.1298950e+00 - -3.2996468e+00 1.8334943e+00 5.2111392e+00 - -3.2400782e+00 1.8037903e+00 5.2913343e+00 - -2.9437577e+00 1.6616695e+00 5.0926643e+00 - -2.8308319e+00 1.6070350e+00 5.0993680e+00 - -2.7606121e+00 1.5724928e+00 5.1557064e+00 - -2.6942256e+00 1.5404967e+00 5.2182506e+00 - -2.6443092e+00 1.5166086e+00 5.3028241e+00 - -2.5992790e+00 1.4943745e+00 5.3945550e+00 - -3.3051403e+00 1.8354100e+00 6.5951858e+00 - -7.7378805e+00 3.9731857e+00 1.3564588e+01 - -1.4614359e+00 9.4619719e-01 4.1031543e+00 - -2.0780112e+00 1.2432799e+00 5.2343144e+00 - -1.7308714e+00 1.0756325e+00 4.8058052e+00 - -1.9201428e+00 1.1672590e+00 5.2891541e+00 - -1.5131347e+00 9.7045460e-01 4.7100265e+00 - -1.4226794e+00 9.2677780e-01 4.6878934e+00 - -1.7753032e+00 1.0970615e+00 5.5462366e+00 - -2.8134459e+00 1.5978230e+00 7.9018713e+00 - -1.6513029e+00 1.0368457e+00 5.6760990e+00 - -1.4399257e+00 9.3525878e-01 5.4026634e+00 - -1.5794226e+00 1.0023782e+00 5.9377767e+00 - -1.4985646e+00 9.6289430e-01 5.9681609e+00 - -1.4022147e+00 9.1655368e-01 5.9601401e+00 - -1.1012641e+00 7.7146238e-01 5.3844228e+00 - -1.0282072e+00 7.3599665e-01 5.4054456e+00 - -9.4353438e-01 6.9588033e-01 5.3873778e+00 - -8.7149536e-01 6.6031740e-01 5.4052077e+00 - -5.4797372e-01 5.0477133e-01 4.5658412e+00 - -4.9147026e-01 4.7726266e-01 4.5855724e+00 - -4.2822481e-01 4.4685588e-01 4.5753680e+00 - -3.6211290e-01 4.1472884e-01 4.5542171e+00 - -2.8157804e-01 3.7627215e-01 4.4636035e+00 - -2.5390671e-01 3.6256440e-01 4.6048825e+00 - -3.5930650e-01 4.1343121e-01 5.4598808e+00 - -2.9589872e-01 3.8225869e-01 5.5151939e+00 - -1.5979600e-01 3.1758441e-01 5.1260611e+00 - -7.0739831e-02 2.7437448e-01 4.9703489e+00 - 1.0669932e-03 2.3953470e-01 4.9015377e+00 - 7.8546336e-02 2.0231894e-01 4.7716334e+00 - 1.1155741e-01 1.8645547e-01 5.0576642e+00 - 1.7291420e-01 1.5599857e-01 5.0845196e+00 - 2.3163921e-01 1.2810579e-01 5.1799494e+00 - 3.0146841e-01 9.4567909e-02 5.0945659e+00 - 3.0446687e-01 9.2613261e-02 7.0165142e+00 - 4.0549471e-01 4.4200638e-02 6.6293991e+00 - -2.4417725e+00 1.5301702e+00 -8.7851681e-01 - -2.5486038e+00 1.5852844e+00 -8.6816073e-01 - -2.6787283e+00 1.6533350e+00 -8.6801097e-01 - -2.7952795e+00 1.7132090e+00 -8.5442548e-01 - -2.9351158e+00 1.7860835e+00 -8.4974791e-01 - -3.0759194e+00 1.8592648e+00 -8.4007333e-01 - -3.2176296e+00 1.9337547e+00 -8.2535142e-01 - -3.3526006e+00 2.0032604e+00 -8.0181462e-01 - -3.4953088e+00 2.0772966e+00 -7.7725206e-01 - -3.6545132e+00 2.1602622e+00 -7.5452999e-01 - -3.7981541e+00 2.2348811e+00 -7.1937733e-01 - -3.9923346e+00 2.3359299e+00 -6.9823248e-01 - -4.2049892e+00 2.4461767e+00 -6.7592546e-01 - -4.4341161e+00 2.5655451e+00 -6.5156375e-01 - -4.7410148e+00 2.7249501e+00 -6.4271419e-01 - -5.0575969e+00 2.8894056e+00 -6.2474249e-01 - -5.3926161e+00 3.0633547e+00 -5.9961604e-01 - -5.7713312e+00 3.2601012e+00 -5.7254094e-01 - -6.5338901e+00 3.6569207e+00 -6.1914729e-01 - -7.2818156e+00 4.0454817e+00 -6.3249597e-01 - -8.1190166e+00 4.4811739e+00 -6.3350105e-01 - -9.0475167e+00 4.9633824e+00 -6.1681315e-01 - -1.0671587e+01 5.8082240e+00 -6.6788644e-01 - -1.3965752e+01 7.5207455e+00 -8.7099897e-01 - -1.6032437e+01 8.5945168e+00 -8.0948330e-01 - -1.5987710e+01 8.5711920e+00 -4.7770069e-01 - -1.5954620e+01 8.5544119e+00 -1.4947315e-01 - -2.3442228e+01 1.2446634e+01 -2.0043242e-01 - -2.3811857e+01 1.2638284e+01 2.5987208e-01 - -2.3775388e+01 1.2619755e+01 7.3865065e-01 - -2.4485854e+01 1.2988634e+01 1.2224539e+00 - -3.4626370e+01 1.8259043e+01 2.0036773e+00 - -2.5076183e+01 1.3295265e+01 2.2345348e+00 - -3.4724044e+01 1.8310014e+01 3.3948842e+00 - -3.4787952e+01 1.8342733e+01 4.0966318e+00 - -3.4805222e+01 1.8351541e+01 4.7977691e+00 - -3.4820539e+01 1.8359369e+01 5.5017461e+00 - -3.4877569e+01 1.8389246e+01 6.2152058e+00 - -4.7847298e+00 2.7469063e+00 1.8851915e+00 - -4.7087224e+00 2.7067815e+00 1.9775136e+00 - -4.6666553e+00 2.6849800e+00 2.0743478e+00 - -4.6837659e+00 2.6944587e+00 2.1837212e+00 - -4.7174495e+00 2.7112226e+00 2.2984445e+00 - -4.7743706e+00 2.7408522e+00 2.4217878e+00 - -1.2784611e+01 6.9046440e+00 4.8586396e+00 - -1.2706145e+01 6.8634465e+00 5.1140005e+00 - -1.2554905e+01 6.7845318e+00 5.3447406e+00 - -1.2359018e+01 6.6828891e+00 5.5559010e+00 - -1.1958471e+01 6.4745139e+00 5.6846564e+00 - -1.1816990e+01 6.4005529e+00 5.9022965e+00 - -1.0999401e+01 5.9755813e+00 5.8328073e+00 - -1.0988877e+01 5.9705474e+00 6.0874045e+00 - -1.0383830e+01 5.6562053e+00 6.0682374e+00 - -1.3860789e+01 7.4628227e+00 8.0205745e+00 - -1.1246344e+01 6.1036066e+00 7.0187851e+00 - -8.5149053e+00 4.6841448e+00 5.8350181e+00 - -5.7218001e+00 3.2327904e+00 4.4881411e+00 - -5.6427617e+00 3.1922608e+00 4.5961838e+00 - -4.2365970e+00 2.4614782e+00 3.8922499e+00 - -5.7135739e+00 3.2283440e+00 4.9535835e+00 - -7.9918816e+00 4.4120119e+00 6.6259764e+00 - -4.5049040e+00 2.6006625e+00 4.4493340e+00 - -6.0676966e+00 3.4125226e+00 5.7062211e+00 - -4.0912487e+00 2.3855471e+00 4.4180433e+00 - -4.0676277e+00 2.3726513e+00 4.5303715e+00 - -3.9896896e+00 2.3323975e+00 4.6022629e+00 - -3.9195308e+00 2.2958203e+00 4.6781260e+00 - -3.8755176e+00 2.2729797e+00 4.7766014e+00 - -3.5525263e+00 2.1055462e+00 4.6257730e+00 - -3.4340014e+00 2.0433075e+00 4.6477357e+00 - -3.3638564e+00 2.0071360e+00 4.7115640e+00 - -3.2927839e+00 1.9698233e+00 4.7737408e+00 - -3.2333143e+00 1.9388120e+00 4.8476933e+00 - -3.1283238e+00 1.8845460e+00 4.8723499e+00 - -3.0359386e+00 1.8366075e+00 4.9080862e+00 - -2.9561545e+00 1.7950307e+00 4.9556013e+00 - -2.8879684e+00 1.7597947e+00 5.0156910e+00 - -2.8197910e+00 1.7244898e+00 5.0743825e+00 - -2.7680903e+00 1.6972387e+00 5.1540045e+00 - -2.7260410e+00 1.6752943e+00 5.2479423e+00 - -7.0451760e+00 3.9178136e+00 1.1294346e+01 - -3.4281710e+00 2.0393567e+00 6.5531445e+00 - -1.6000415e+00 1.0906660e+00 4.0765585e+00 - -1.5407542e+00 1.0592296e+00 4.1013724e+00 - -3.1130179e+00 1.8759459e+00 6.6957282e+00 - -1.4085653e+00 9.9108588e-01 4.1220401e+00 - -3.0082771e+00 1.8215322e+00 6.9592883e+00 - -1.6590022e+00 1.1206719e+00 4.8104489e+00 - -1.5677638e+00 1.0731538e+00 4.7927056e+00 - -1.4407598e+00 1.0078883e+00 4.7035280e+00 - -1.6150848e+00 1.0973679e+00 5.2022094e+00 - -1.3887038e+00 9.7986618e-01 4.9093415e+00 - -2.6328296e+00 1.6262655e+00 7.7652880e+00 - -1.4686260e+00 1.0219729e+00 5.4374111e+00 - -1.4689926e+00 1.0219222e+00 5.6377630e+00 - -1.4558511e+00 1.0142059e+00 5.8213886e+00 - -1.3307924e+00 9.4998436e-01 5.7306697e+00 - -1.2203137e+00 8.9186936e-01 5.6643700e+00 - -1.0433344e+00 8.0082220e-01 5.3997381e+00 - -9.5602180e-01 7.5511114e-01 5.3732191e+00 - -8.9472298e-01 7.2264378e-01 5.4200986e+00 - -5.6609733e-01 5.5244263e-01 4.5746151e+00 - -5.3177526e-01 5.3510760e-01 4.6711766e+00 - -4.3408356e-01 4.8444708e-01 4.5375054e+00 - -3.7677389e-01 4.5431256e-01 4.5457469e+00 - -3.3578094e-01 4.3247963e-01 4.6204619e+00 - -2.3343462e-01 3.7934594e-01 4.4225045e+00 - -2.2107426e-01 3.7342432e-01 4.6412899e+00 - -2.4394955e-01 3.8535918e-01 5.0958036e+00 - -1.4169097e-01 3.3204002e-01 4.8738262e+00 - -1.1378128e-01 3.1765838e-01 5.1027450e+00 - -1.2668821e-02 2.6476459e-01 4.8273880e+00 - 3.8150606e-02 2.3902416e-01 4.9161523e+00 - 9.8335571e-02 2.0672423e-01 4.9246831e+00 - 1.6144455e-01 1.7419544e-01 4.9119810e+00 - 2.1705422e-01 1.4551838e-01 4.9878445e+00 - 2.7272102e-01 1.1626631e-01 5.0925717e+00 - 2.6472778e-01 1.2003913e-01 6.9145823e+00 - 3.6976188e-01 6.5003599e-02 6.3385357e+00 - 4.5306331e-01 2.2481197e-02 6.2502082e+00 - -2.2619147e+00 1.5401741e+00 -9.0264831e-01 - -2.3354409e+00 1.5819889e+00 -8.7722375e-01 - -2.4478798e+00 1.6441243e+00 -8.7368742e-01 - -2.5534598e+00 1.7032644e+00 -8.6153518e-01 - -2.6746209e+00 1.7700942e+00 -8.5487250e-01 - -2.7889225e+00 1.8339337e+00 -8.3949403e-01 - -2.9274454e+00 1.9118458e+00 -8.3277023e-01 - -3.0737668e+00 1.9932817e+00 -8.2517088e-01 - -3.2055179e+00 2.0664707e+00 -8.0433873e-01 - -3.3217073e+00 2.1312982e+00 -7.7137562e-01 - -3.4708693e+00 2.2146612e+00 -7.4863502e-01 - -3.6200581e+00 2.2972933e+00 -7.2045153e-01 - -3.8021426e+00 2.3995908e+00 -6.9984345e-01 - -4.0182303e+00 2.5197091e+00 -6.8491070e-01 - -4.2352053e+00 2.6412887e+00 -6.6183443e-01 - -4.5036227e+00 2.7906364e+00 -6.4711939e-01 - -4.8399204e+00 2.9776637e+00 -6.4295523e-01 - -5.0926867e+00 3.1193643e+00 -6.0162709e-01 - -5.2523795e+00 3.2080121e+00 -5.2571636e-01 - -5.9667678e+00 3.6065748e+00 -5.7961457e-01 - -6.9419812e+00 4.1498301e+00 -6.6286956e-01 - -7.6794837e+00 4.5606964e+00 -6.5875989e-01 - -8.5148248e+00 5.0262068e+00 -6.4282460e-01 - -9.8609625e+00 5.7778801e+00 -6.7670004e-01 - -1.2710753e+01 7.3667790e+00 -8.6944891e-01 - -1.5264489e+01 8.7907992e+00 -9.1181441e-01 - -1.5917885e+01 9.1547412e+00 -6.5980568e-01 - -2.2282186e+01 1.2703253e+01 -3.8825893e-01 - -2.2413612e+01 1.2775725e+01 6.2536868e-02 - -2.2432535e+01 1.2786578e+01 5.2028338e-01 - -2.2340991e+01 1.2735620e+01 9.7859487e-01 - -3.3428525e+01 1.8917198e+01 1.6461258e+00 - -3.3387688e+01 1.8894205e+01 2.3229416e+00 - -3.3222826e+01 1.8802128e+01 2.9915863e+00 - -3.3074474e+01 1.8718867e+01 3.6560933e+00 - -3.3132461e+01 1.8751191e+01 4.3368980e+00 - -3.3381296e+01 1.8889667e+01 5.0446827e+00 - -5.0156787e+00 3.0751156e+00 1.7702036e+00 - -4.6395010e+00 2.8653994e+00 1.8221806e+00 - -4.5917502e+00 2.8382160e+00 1.9185443e+00 - -4.5594755e+00 2.8200788e+00 2.0166599e+00 - -4.5687993e+00 2.8259401e+00 2.1232601e+00 - -4.6362861e+00 2.8631542e+00 2.2450930e+00 - -1.2491114e+01 7.2413007e+00 4.4208039e+00 - -1.2428249e+01 7.2071211e+00 4.6773167e+00 - -1.2445783e+01 7.2171290e+00 4.9582783e+00 - -1.2409143e+01 7.1960555e+00 5.2246191e+00 - -1.2342462e+01 7.1586727e+00 5.4818670e+00 - -1.2148007e+01 7.0500232e+00 5.6915797e+00 - -1.1132719e+01 6.4842976e+00 5.5732460e+00 - -6.4386410e+00 3.8679481e+00 3.8838227e+00 - -6.4836733e+00 3.8925291e+00 4.0613082e+00 - -6.5248167e+00 3.9150074e+00 4.2415767e+00 - -6.5871674e+00 3.9505014e+00 4.4359522e+00 - -6.6456851e+00 3.9829303e+00 4.6338594e+00 - -5.5354295e+00 3.3634321e+00 4.2150188e+00 - -5.4778805e+00 3.3316004e+00 4.3306749e+00 - -4.0563473e+00 2.5389517e+00 3.6519253e+00 - -3.9611946e+00 2.4859241e+00 3.7097225e+00 - -3.9347263e+00 2.4711553e+00 3.8080082e+00 - -6.7816596e+00 4.0582997e+00 5.8034270e+00 - -5.6660461e+00 3.4359744e+00 5.2333061e+00 - -5.7196975e+00 3.4655584e+00 5.4404348e+00 - -3.7302067e+00 2.3568862e+00 4.1388851e+00 - -3.6534507e+00 2.3141915e+00 4.2005914e+00 - -3.5824801e+00 2.2750328e+00 4.2658636e+00 - -3.5251205e+00 2.2422026e+00 4.3410201e+00 - -3.4590038e+00 2.2054730e+00 4.4089058e+00 - -3.4131402e+00 2.1808298e+00 4.4935415e+00 - -3.3461027e+00 2.1429048e+00 4.5586770e+00 - -3.2916098e+00 2.1123091e+00 4.6349425e+00 - -3.2351876e+00 2.0805413e+00 4.7101525e+00 - -3.1787727e+00 2.0487144e+00 4.7841640e+00 - -3.1068410e+00 2.0091995e+00 4.8434405e+00 - -3.0291552e+00 1.9658976e+00 4.8940573e+00 - -2.9814201e+00 1.9391051e+00 4.9780867e+00 - -3.0176709e+00 1.9594646e+00 5.1620340e+00 - -3.0847905e+00 1.9970344e+00 5.3923809e+00 - -4.8779827e+00 2.9955817e+00 7.8247407e+00 - -5.0548375e+00 3.0941136e+00 8.3006637e+00 - -7.7022530e+00 4.5687083e+00 1.2169108e+01 - -7.6903952e+00 4.5621662e+00 1.2556435e+01 - -6.8565286e+00 4.0969495e+00 1.1757528e+01 - -6.6334301e+00 3.9729866e+00 1.1815031e+01 - -4.2306448e+00 2.6349267e+00 8.4387756e+00 - -4.1873775e+00 2.6105529e+00 8.6467662e+00 - -1.4040652e+00 1.0600542e+00 4.2235397e+00 - -1.6783826e+00 1.2131408e+00 4.8310381e+00 - -1.6201029e+00 1.1806577e+00 4.8739320e+00 - -1.4789355e+00 1.1023464e+00 4.7614812e+00 - -1.4525200e+00 1.0866397e+00 4.8610149e+00 - -1.3335301e+00 1.0211121e+00 4.7770060e+00 - -1.3253950e+00 1.0156364e+00 4.9189007e+00 - -1.5356798e+00 1.1324429e+00 5.5604337e+00 - -1.3733664e+00 1.0426896e+00 5.3847382e+00 - -1.3285218e+00 1.0174252e+00 5.4758187e+00 - -1.3134505e+00 1.0090560e+00 5.6486513e+00 - -1.2224063e+00 9.5843856e-01 5.6288594e+00 - -3.0540005e+00 1.9768746e+00 1.1038348e+01 - -9.8852431e-01 8.2781591e-01 5.4242004e+00 - -9.1196242e-01 7.8511668e-01 5.4250331e+00 - -8.2484613e-01 7.3680572e-01 5.3863284e+00 - -7.5793050e-01 6.9893846e-01 5.4121133e+00 - -5.3857776e-01 5.7762083e-01 4.8724723e+00 - -3.9518934e-01 4.9707299e-01 4.5562667e+00 - -3.3413137e-01 4.6371248e-01 4.5445193e+00 - -2.4827071e-01 4.1598313e-01 4.4150818e+00 - -2.0928562e-01 3.9366336e-01 4.4977431e+00 - -1.6549445e-01 3.6904919e-01 4.5602629e+00 - -1.5113776e-01 3.6145933e-01 4.8084544e+00 - -1.1291553e-01 3.4004883e-01 4.9488468e+00 - -4.4274831e-02 3.0144024e-01 4.9012670e+00 - -3.0657179e-03 2.7875607e-01 5.0600264e+00 - 8.2546288e-02 2.3110270e-01 4.8510886e+00 - 1.0038755e-01 2.2105893e-01 5.2963226e+00 - 1.8029889e-01 1.7658811e-01 5.1243087e+00 - 2.4234331e-01 1.4152622e-01 5.1400730e+00 - 3.0531479e-01 1.0635143e-01 5.1345109e+00 - 3.1985728e-01 9.8355465e-02 6.7067544e+00 - 4.0779399e-01 4.9079292e-02 6.6294446e+00 - -2.1568682e+00 1.5871818e+00 -8.9880716e-01 - -2.2371200e+00 1.6340892e+00 -8.8000019e-01 - -2.3317847e+00 1.6915330e+00 -8.6853251e-01 - -2.4274874e+00 1.7482028e+00 -8.5371618e-01 - -2.5609103e+00 1.8282320e+00 -8.5874262e-01 - -2.6575649e+00 1.8853318e+00 -8.3643235e-01 - -2.7928678e+00 1.9669272e+00 -8.3241321e-01 - -2.9291983e+00 2.0478324e+00 -8.2334750e-01 - -3.0509603e+00 2.1204760e+00 -8.0134863e-01 - -3.1804619e+00 2.1976305e+00 -7.7872351e-01 - -3.3264045e+00 2.2846719e+00 -7.5878744e-01 - -3.4810159e+00 2.3773504e+00 -7.3687322e-01 - -3.6356524e+00 2.4693129e+00 -7.0921648e-01 - -3.8154179e+00 2.5766468e+00 -6.8536681e-01 - -4.0609883e+00 2.7232032e+00 -6.7886523e-01 - -4.2822788e+00 2.8561550e+00 -6.5422071e-01 - -4.6042587e+00 3.0481749e+00 -6.5329479e-01 - -4.7200595e+00 3.1171394e+00 -5.7698442e-01 - -4.8425937e+00 3.1906184e+00 -4.9875259e-01 - -5.6193118e+00 3.6535089e+00 -5.8537615e-01 - -6.3648762e+00 4.0994037e+00 -6.3300635e-01 - -7.2835882e+00 4.6477107e+00 -6.8722275e-01 - -8.0183656e+00 5.0862424e+00 -6.6807433e-01 - -9.0867991e+00 5.7240563e+00 -6.7752221e-01 - -1.1630244e+01 7.2432528e+00 -8.7112677e-01 - -1.4155035e+01 8.7505570e+00 -9.5842933e-01 - -1.4362058e+01 8.8741714e+00 -6.8050033e-01 - -1.4401762e+01 8.8975363e+00 -3.7973571e-01 - -1.4634891e+01 9.0362458e+00 -9.2177587e-02 - -2.1339328e+01 1.3039245e+01 -1.3100801e-01 - -2.1661900e+01 1.3231778e+01 3.0333087e-01 - -2.1454540e+01 1.3108359e+01 7.5629164e-01 - -3.1372101e+01 1.9029246e+01 1.2937926e+00 - -3.1379775e+01 1.9033846e+01 1.9421129e+00 - -5.0083227e+00 3.2887922e+00 1.2751203e+00 - -4.9606154e+00 3.2602306e+00 1.3840677e+00 - -4.6712551e+00 3.0875028e+00 1.4692987e+00 - -4.5781680e+00 3.0314638e+00 1.5649036e+00 - -4.5353337e+00 3.0056928e+00 1.6635308e+00 - -4.5156552e+00 2.9944710e+00 1.7643868e+00 - -4.4950426e+00 2.9821622e+00 1.8646898e+00 - -4.4724975e+00 2.9687061e+00 1.9644368e+00 - -4.4664185e+00 2.9644207e+00 2.0672372e+00 - -4.6013881e+00 3.0445536e+00 2.2036897e+00 - -4.2136515e+00 2.8129269e+00 2.2123215e+00 - -4.1775495e+00 2.7921943e+00 2.3032325e+00 - -4.1569707e+00 2.7796146e+00 2.3980423e+00 - -4.1527862e+00 2.7772962e+00 2.4977537e+00 - -4.1785656e+00 2.7924121e+00 2.6091053e+00 - -4.1290043e+00 2.7625915e+00 2.6949748e+00 - -4.1035620e+00 2.7476615e+00 2.7887692e+00 - -4.0839703e+00 2.7352308e+00 2.8853800e+00 - -4.0546619e+00 2.7180158e+00 2.9782620e+00 - -4.0320806e+00 2.7053644e+00 3.0740643e+00 - -4.0086229e+00 2.6906488e+00 3.1697627e+00 - -3.9754527e+00 2.6711143e+00 3.2610332e+00 - -3.9490674e+00 2.6551662e+00 3.3556729e+00 - -3.9207479e+00 2.6380855e+00 3.4500563e+00 - -3.8760018e+00 2.6115186e+00 3.5349940e+00 - -3.8370405e+00 2.5884926e+00 3.6235976e+00 - -3.7894332e+00 2.5596470e+00 3.7065275e+00 - -3.7553226e+00 2.5390748e+00 3.7982438e+00 - -3.6980196e+00 2.5052773e+00 3.8740492e+00 - -3.6542716e+00 2.4787709e+00 3.9589901e+00 - -3.6028192e+00 2.4474729e+00 4.0376118e+00 - -3.5560896e+00 2.4206817e+00 4.1204458e+00 - -3.5094867e+00 2.3918473e+00 4.2023802e+00 - -3.4608930e+00 2.3628477e+00 4.2834092e+00 - -3.4180767e+00 2.3374480e+00 4.3693026e+00 - -3.3665611e+00 2.3071716e+00 4.4483741e+00 - -3.3276489e+00 2.2832373e+00 4.5388250e+00 - -3.2945081e+00 2.2629521e+00 4.6351389e+00 - -3.2391369e+00 2.2303069e+00 4.7116001e+00 - -3.1953052e+00 2.2049847e+00 4.8002868e+00 - -3.1380710e+00 2.1701213e+00 4.8747434e+00 - -3.0798454e+00 2.1351432e+00 4.9480982e+00 - -3.0688009e+00 2.1288062e+00 5.0762003e+00 - -3.0259993e+00 2.1027741e+00 5.1695341e+00 - -2.9860304e+00 2.0792474e+00 5.2694700e+00 - -2.9393634e+00 2.0509254e+00 5.3617915e+00 - -2.9128725e+00 2.0353057e+00 5.4833477e+00 - -2.8960256e+00 2.0250517e+00 5.6204181e+00 - -8.0538470e+00 5.1016630e+00 1.3060317e+01 - -7.8821229e+00 4.9993066e+00 1.3247933e+01 - -6.8028965e+00 4.3545205e+00 1.2060582e+01 - -1.5110929e+00 1.1986535e+00 4.1575898e+00 - -1.4635663e+00 1.1707099e+00 4.1980234e+00 - -4.1238914e+00 2.7566041e+00 8.8168891e+00 - -1.6935939e+00 1.3083242e+00 4.8507667e+00 - -1.6085778e+00 1.2567259e+00 4.8442767e+00 - -1.5369701e+00 1.2141055e+00 4.8608555e+00 - -1.3654470e+00 1.1113901e+00 4.6777326e+00 - -1.4034180e+00 1.1340777e+00 4.9064310e+00 - -1.3529845e+00 1.1037058e+00 4.9620851e+00 - -1.2689053e+00 1.0536889e+00 4.9459110e+00 - -1.3903195e+00 1.1258026e+00 5.4016688e+00 - -1.3388365e+00 1.0952650e+00 5.4754469e+00 - -1.2959315e+00 1.0705747e+00 5.5757225e+00 - -1.1591550e+00 9.8777523e-01 5.4281766e+00 - -1.1680453e+00 9.9349124e-01 5.6736525e+00 - -2.0124653e+00 1.4971633e+00 8.4040116e+00 - -8.9163493e-01 8.2867861e-01 5.3171285e+00 - -8.6121491e-01 8.1076227e-01 5.4577972e+00 - -6.8150829e-01 7.0368847e-01 5.0960183e+00 - -6.2241317e-01 6.6865344e-01 5.1289206e+00 - -4.2574471e-01 5.5142778e-01 4.6238605e+00 - -3.5535965e-01 5.0862178e-01 4.5746749e+00 - -3.0398698e-01 4.7874967e-01 4.6011625e+00 - -2.4224323e-01 4.4076940e-01 4.5780245e+00 - -1.6807471e-01 3.9656558e-01 4.4851305e+00 - -1.9851566e-01 4.1440061e-01 4.9684356e+00 - -1.1948804e-01 3.6832608e-01 4.8639895e+00 - -5.5774470e-02 3.3001306e-01 4.8365504e+00 - -1.7618842e-02 3.0652314e-01 4.9955686e+00 - 2.0718246e-02 2.8396754e-01 5.1937880e+00 - 1.2300869e-01 2.2338188e-01 4.8054633e+00 - 1.5958413e-01 2.0179106e-01 5.0613170e+00 - 2.2788019e-01 1.6042843e-01 4.9579063e+00 - 2.7768661e-01 1.2998821e-01 5.1325143e+00 - 3.4321733e-01 9.1153809e-02 5.0564297e+00 - 3.7598418e-01 7.2178396e-02 6.2684574e+00 - 4.5306325e-01 2.5876030e-02 6.5001492e+00 - -1.9751351e+00 1.5777452e+00 -9.0817422e-01 - -2.0454606e+00 1.6230906e+00 -8.8855049e-01 - -2.1303230e+00 1.6769488e+00 -8.7676620e-01 - -2.2093899e+00 1.7268359e+00 -8.5711230e-01 - -2.3241308e+00 1.8008746e+00 -8.5905498e-01 - -2.4254182e+00 1.8647479e+00 -8.4736296e-01 - -2.5421050e+00 1.9393116e+00 -8.4110940e-01 - -2.6452810e+00 2.0046820e+00 -8.2177007e-01 - -2.7783332e+00 2.0902527e+00 -8.1575819e-01 - -2.9124129e+00 2.1751333e+00 -8.0469975e-01 - -3.0396920e+00 2.2560364e+00 -7.8467623e-01 - -3.1823544e+00 2.3477580e+00 -7.6749437e-01 - -3.3337472e+00 2.4441101e+00 -7.4848455e-01 - -3.5015710e+00 2.5504279e+00 -7.3056577e-01 - -3.6374241e+00 2.6377269e+00 -6.9318309e-01 - -3.8544402e+00 2.7757831e+00 -6.8173266e-01 - -4.0724014e+00 2.9143235e+00 -6.6168967e-01 - -4.3395646e+00 3.0845235e+00 -6.4971307e-01 - -4.5419566e+00 3.2142474e+00 -6.0650313e-01 - -4.5396932e+00 3.2126510e+00 -4.9460041e-01 - -4.5615827e+00 3.2261881e+00 -3.9010351e-01 - -4.5815337e+00 3.2386272e+00 -2.8516391e-01 - -4.5830983e+00 3.2401353e+00 -1.7599392e-01 - -4.5740978e+00 3.2340540e+00 -6.5413407e-02 - -4.5727944e+00 3.2333376e+00 4.2847380e-02 - -4.5695575e+00 3.2314837e+00 1.5075185e-01 - -4.5808267e+00 3.2383890e+00 2.5581070e-01 - -4.5824091e+00 3.2397542e+00 3.6208428e-01 - -4.5830549e+00 3.2400522e+00 4.6820446e-01 - -4.5905114e+00 3.2437298e+00 5.7349912e-01 - -4.5872868e+00 3.2417773e+00 6.7940606e-01 - -4.5918091e+00 3.2442765e+00 7.8474073e-01 - -4.5856527e+00 3.2411260e+00 8.9028817e-01 - -4.5863039e+00 3.2413797e+00 9.9550947e-01 - -4.5773374e+00 3.2350275e+00 1.1005968e+00 - -4.5239195e+00 3.2018149e+00 1.2036308e+00 - -4.4445424e+00 3.1507971e+00 1.3028773e+00 - -4.4143118e+00 3.1318824e+00 1.4030464e+00 - -4.3908884e+00 3.1163768e+00 1.5029892e+00 - -4.3741492e+00 3.1062939e+00 1.6030061e+00 - -4.3565353e+00 3.0941320e+00 1.7026195e+00 - -4.3205217e+00 3.0716617e+00 1.7988232e+00 - -4.2662356e+00 3.0368350e+00 1.8906176e+00 - -4.2022929e+00 2.9962269e+00 1.9787327e+00 - -4.1547660e+00 2.9657076e+00 2.0682537e+00 - -4.0966452e+00 2.9283447e+00 2.1540419e+00 - -4.0375386e+00 2.8908227e+00 2.2378295e+00 - -4.0189027e+00 2.8793066e+00 2.3314975e+00 - -3.9983339e+00 2.8666481e+00 2.4247093e+00 - -3.9932200e+00 2.8632033e+00 2.5230688e+00 - -3.9785036e+00 2.8530294e+00 2.6187974e+00 - -3.9695169e+00 2.8473539e+00 2.7173431e+00 - -3.9441452e+00 2.8313431e+00 2.8094892e+00 - -3.9409452e+00 2.8291935e+00 2.9114010e+00 - -3.9194267e+00 2.8155712e+00 3.0065569e+00 - -3.9046322e+00 2.8065371e+00 3.1051323e+00 - -3.8889600e+00 2.7954487e+00 3.2038037e+00 - -3.8558556e+00 2.7748729e+00 3.2942249e+00 - -3.8372522e+00 2.7625816e+00 3.3924369e+00 - -3.8089973e+00 2.7444694e+00 3.4861706e+00 - -3.7788093e+00 2.7252148e+00 3.5794482e+00 - -3.7399113e+00 2.7011671e+00 3.6676018e+00 - -3.7078548e+00 2.6797385e+00 3.7597736e+00 - -3.6593784e+00 2.6487697e+00 3.8414012e+00 - -3.6099113e+00 2.6176812e+00 3.9218270e+00 - -3.5662260e+00 2.5901582e+00 4.0064180e+00 - -3.5283808e+00 2.5652184e+00 4.0955233e+00 - -3.5096741e+00 2.5542689e+00 4.2006771e+00 - -3.4833791e+00 2.5365683e+00 4.3003100e+00 - -3.7340580e+00 2.6970123e+00 4.6405705e+00 - -3.5518634e+00 2.5803372e+00 4.6133619e+00 - -3.4783248e+00 2.5339790e+00 4.6781724e+00 - -4.4926236e+00 3.1798523e+00 5.7846701e+00 - -4.4863314e+00 3.1757242e+00 5.9514404e+00 - -4.4829253e+00 3.1731587e+00 6.1259611e+00 - -4.4631694e+00 3.1599771e+00 6.2883890e+00 - -4.4520053e+00 3.1530486e+00 6.4652797e+00 - -4.4379616e+00 3.1439892e+00 6.6431589e+00 - -4.4498568e+00 3.1513501e+00 6.8575340e+00 - -4.5741292e+00 3.2309233e+00 7.2177240e+00 - -4.4303078e+00 3.1388798e+00 7.2560193e+00 - -2.8683941e+00 2.1441291e+00 5.4262416e+00 - -2.8246790e+00 2.1163284e+00 5.5254641e+00 - -2.7626881e+00 2.0772291e+00 5.6012017e+00 - -2.7218678e+00 2.0509220e+00 5.7067763e+00 - -4.3517618e+00 3.0880967e+00 8.3478837e+00 - -1.4881159e+00 1.2656660e+00 4.1211016e+00 - -1.4714439e+00 1.2550461e+00 4.2102320e+00 - -1.4192800e+00 1.2213967e+00 4.2424079e+00 - -3.2179212e+00 2.3666651e+00 7.5213168e+00 - -3.0992318e+00 2.2899683e+00 7.5553056e+00 - -1.3231715e+00 1.1597178e+00 4.4502104e+00 - -1.4723526e+00 1.2543598e+00 4.8814993e+00 - -1.3223448e+00 1.1585879e+00 4.7312075e+00 - -1.2097150e+00 1.0873625e+00 4.6459170e+00 - -1.2944953e+00 1.1416620e+00 4.9895884e+00 - -1.3581786e+00 1.1815498e+00 5.3111124e+00 - -1.4428109e+00 1.2354844e+00 5.7081667e+00 - -1.3014313e+00 1.1456749e+00 5.5664450e+00 - -1.1926581e+00 1.0762942e+00 5.4934025e+00 - -1.0800851e+00 1.0046155e+00 5.3989233e+00 - -1.0497672e+00 9.8536722e-01 5.5328499e+00 - -9.5254103e-01 9.2325037e-01 5.4708343e+00 - -8.5820436e-01 8.6318561e-01 5.4062322e+00 - -7.2667849e-01 7.7912833e-01 5.2068167e+00 - -6.1999391e-01 7.1171005e-01 5.0698115e+00 - -4.2379857e-01 5.8657772e-01 4.5665461e+00 - -3.6690693e-01 5.5000821e-01 4.5658962e+00 - -3.3184113e-01 5.2851652e-01 4.6604555e+00 - -2.6546210e-01 4.8532980e-01 4.6189227e+00 - -2.1234404e-01 4.5178428e-01 4.6341667e+00 - -3.0152899e-01 5.0827688e-01 5.4404278e+00 - -1.6961527e-01 4.2392368e-01 5.0538936e+00 - -9.0833041e-02 3.7434099e-01 4.9391091e+00 - -1.0310954e-02 3.2258787e-01 4.7827696e+00 - -4.2047476e-03 3.1830529e-01 5.2085681e+00 - 8.0109433e-02 2.6522332e-01 5.0099185e+00 - 1.2687348e-01 2.3561337e-01 5.1571706e+00 - 1.6913682e-01 2.0867509e-01 5.4132531e+00 - 2.5760585e-01 1.5170489e-01 5.0203298e+00 - 3.0747453e-01 1.2021494e-01 5.2344378e+00 - 3.3419013e-01 1.0265196e-01 6.4069846e+00 - 4.1021800e-01 5.4439010e-02 6.6595027e+00 - -1.8717897e+00 1.6130076e+00 -9.0053923e-01 - -1.9477842e+00 1.6643673e+00 -8.8788546e-01 - -2.0314770e+00 1.7210820e+00 -8.7775115e-01 - -2.1151520e+00 1.7779396e+00 -8.6472043e-01 - -2.2055241e+00 1.8401165e+00 -8.5371297e-01 - -2.3190727e+00 1.9171941e+00 -8.5361020e-01 - -2.4268804e+00 1.9893479e+00 -8.4468936e-01 - -2.5191220e+00 2.0531747e+00 -8.2293841e-01 - -2.6500114e+00 2.1415020e+00 -8.1937871e-01 - -2.7808692e+00 2.2300807e+00 -8.1072529e-01 - -2.9049272e+00 2.3146769e+00 -7.9320667e-01 - -3.0376608e+00 2.4048562e+00 -7.7480854e-01 - -3.1780687e+00 2.5005827e+00 -7.5503468e-01 - -3.3416167e+00 2.6115006e+00 -7.4027279e-01 - -3.4916547e+00 2.7132204e+00 -7.1252501e-01 - -3.6483608e+00 2.8204909e+00 -6.8210629e-01 - -3.9004413e+00 2.9922134e+00 -6.8171197e-01 - -4.0986165e+00 3.1260644e+00 -6.5124707e-01 - -4.2253922e+00 3.2130541e+00 -5.8887429e-01 - -4.2876768e+00 3.2552646e+00 -5.0146207e-01 - -4.3249209e+00 3.2803660e+00 -4.0495009e-01 - -4.3284984e+00 3.2818620e+00 -2.9847041e-01 - -4.3300821e+00 3.2832174e+00 -1.9239659e-01 - -4.3307303e+00 3.2834958e+00 -8.6675913e-02 - -4.3371378e+00 3.2880359e+00 1.7067867e-02 - -4.3426079e+00 3.2915137e+00 1.2075814e-01 - -4.3384514e+00 3.2884546e+00 2.2571268e-01 - -4.3650579e+00 3.3070620e+00 3.2558316e-01 - -4.3580299e+00 3.3018079e+00 4.3022776e-01 - -4.3654422e+00 3.3063543e+00 5.3287607e-01 - -4.3708583e+00 3.3107798e+00 6.3551803e-01 - -4.3676497e+00 3.3086992e+00 7.3882818e-01 - -4.3538852e+00 3.2989553e+00 8.4205068e-01 - -4.3391263e+00 3.2891213e+00 9.4467076e-01 - -4.3224959e+00 3.2771381e+00 1.0466844e+00 - -4.3048721e+00 3.2650551e+00 1.1478959e+00 - -4.2939953e+00 3.2573780e+00 1.2488316e+00 - -4.2811253e+00 3.2495554e+00 1.3492615e+00 - -4.2750586e+00 3.2451715e+00 1.4500644e+00 - -4.2603176e+00 3.2351947e+00 1.5497881e+00 - -4.2350300e+00 3.2174807e+00 1.6479259e+00 - -4.2000772e+00 3.1940542e+00 1.7437828e+00 - -4.1641946e+00 3.1695063e+00 1.8383877e+00 - -4.1273819e+00 3.1438369e+00 1.9317405e+00 - -4.0722396e+00 3.1067834e+00 2.0201351e+00 - -4.0401819e+00 3.0853646e+00 2.1125066e+00 - -4.0081912e+00 3.0628948e+00 2.2038291e+00 - -3.9732127e+00 3.0401893e+00 2.2940433e+00 - -3.9623624e+00 3.0323005e+00 2.3906843e+00 - -3.9736341e+00 3.0391860e+00 2.4953436e+00 - -3.9435192e+00 3.0188310e+00 2.5865733e+00 - -3.9595162e+00 3.0302037e+00 2.6950455e+00 - -3.9419183e+00 3.0179137e+00 2.7920621e+00 - -3.9387091e+00 3.0158380e+00 2.8954721e+00 - -3.9653256e+00 3.0333334e+00 3.0133196e+00 - -4.0120400e+00 3.0657041e+00 3.1436736e+00 - -4.1106589e+00 3.1327651e+00 3.3034748e+00 - -4.5244243e+00 3.4129732e+00 3.6352298e+00 - -4.5086325e+00 3.4028406e+00 3.7532773e+00 - -4.4899672e+00 3.3905278e+00 3.8713144e+00 - -4.4780789e+00 3.3818655e+00 3.9940192e+00 - -4.4556004e+00 3.3663299e+00 4.1123921e+00 - -4.4388399e+00 3.3553862e+00 4.2354797e+00 - -4.4279152e+00 3.3470603e+00 4.3637808e+00 - -4.4140531e+00 3.3375806e+00 4.4926213e+00 - -4.3982531e+00 3.3269979e+00 4.6218046e+00 - -4.3872269e+00 3.3199990e+00 4.7567479e+00 - -4.3733838e+00 3.3098525e+00 4.8923296e+00 - -4.3642511e+00 3.3043114e+00 5.0341212e+00 - -3.7323131e+00 2.8745740e+00 4.6431149e+00 - -3.7396024e+00 2.8790725e+00 4.7853136e+00 - -4.3216408e+00 3.2739576e+00 5.4640843e+00 - -4.3009369e+00 3.2608306e+00 5.6085816e+00 - -4.2918266e+00 3.2540790e+00 5.7663526e+00 - -4.2855442e+00 3.2498721e+00 5.9315249e+00 - -4.2811492e+00 3.2471722e+00 6.1045442e+00 - -4.2681672e+00 3.2376658e+00 6.2721393e+00 - -4.2570124e+00 3.2306634e+00 6.4475318e+00 - -4.2488015e+00 3.2242463e+00 6.6311238e+00 - -4.2366513e+00 3.2166447e+00 6.8158512e+00 - -4.2265053e+00 3.2085857e+00 7.0091241e+00 - -4.2114213e+00 3.1992867e+00 7.2036291e+00 - -4.1868179e+00 3.1820794e+00 7.3918574e+00 - -1.8195807e+00 1.5742181e+00 4.2755341e+00 - -2.6775676e+00 2.1567742e+00 5.6502184e+00 - -2.6100088e+00 2.1108526e+00 5.7165461e+00 - -2.5663827e+00 2.0813093e+00 5.8209614e+00 - -3.9992088e+00 3.0541329e+00 8.3351678e+00 - -3.9218026e+00 3.0013766e+00 8.4777656e+00 - -1.4812329e+00 1.3440920e+00 4.4763335e+00 - -1.3525754e+00 1.2570982e+00 4.3758022e+00 - -1.3397316e+00 1.2485496e+00 4.4817749e+00 - -1.2713768e+00 1.2024989e+00 4.4859274e+00 - -1.3847736e+00 1.2790271e+00 4.8586159e+00 - -1.2562203e+00 1.1912007e+00 4.7412054e+00 - -1.1495935e+00 1.1197105e+00 4.6634743e+00 - -1.6440906e+00 1.4550250e+00 5.9655089e+00 - -1.5833062e+00 1.4127736e+00 6.0369038e+00 - -2.5738111e+00 2.0848252e+00 8.7686697e+00 - -1.1751997e+00 1.1362970e+00 5.4302608e+00 - -1.0943871e+00 1.0817082e+00 5.4190381e+00 - -1.0880757e+00 1.0761856e+00 5.6183171e+00 - -9.7582060e-01 9.9990320e-01 5.5115516e+00 - -8.4926276e-01 9.1478313e-01 5.3452598e+00 - -8.4660229e-01 9.1326486e-01 5.5803082e+00 - -6.8017603e-01 8.0042017e-01 5.2477315e+00 - -5.5197471e-01 7.1287524e-01 5.0144665e+00 - -3.6871279e-01 5.8835457e-01 4.5279714e+00 - -3.2432381e-01 5.5790197e-01 4.5746556e+00 - -2.5806356e-01 5.1325026e-01 4.5236841e+00 - -2.4400343e-01 5.0329065e-01 4.7238349e+00 - -1.7394575e-01 4.5632123e-01 4.6510273e+00 - -1.7582853e-01 4.5713468e-01 4.9880144e+00 - -1.0771890e-01 4.1015632e-01 4.9328410e+00 - -4.8994325e-02 3.7061299e-01 4.9351299e+00 - 4.0990549e-03 3.3532307e-01 4.9757914e+00 - 4.9689227e-02 3.0436944e-01 5.0945818e+00 - 1.3350751e-01 2.4629319e-01 4.8352064e+00 - 1.7546013e-01 2.1841916e-01 5.0115386e+00 - 2.3777109e-01 1.7538732e-01 4.9479961e+00 - 2.8371060e-01 1.4464663e-01 5.1724041e+00 - 2.8657804e-01 1.4237561e-01 6.7447377e+00 - 3.8027754e-01 7.7949639e-02 6.2485221e+00 - 4.5629848e-01 2.6801801e-02 6.2401630e+00 - -1.7228367e+00 1.6089033e+00 -9.2318329e-01 - -1.7832376e+00 1.6526719e+00 -9.0304242e-01 - -1.8504045e+00 1.7006937e+00 -8.8627354e-01 - -1.9252128e+00 1.7550429e+00 -8.7257307e-01 - -2.0134977e+00 1.8188563e+00 -8.6646516e-01 - -2.1027605e+00 1.8828927e+00 -8.5705813e-01 - -2.2063704e+00 1.9585068e+00 -8.5414105e-01 - -2.3042405e+00 2.0291872e+00 -8.4260567e-01 - -2.4020885e+00 2.1000450e+00 -8.2747472e-01 - -2.5076232e+00 2.1763515e+00 -8.1296559e-01 - -2.6419731e+00 2.2738144e+00 -8.1143715e-01 - -2.7715765e+00 2.3664436e+00 -8.0048819e-01 - -2.9077978e+00 2.4655417e+00 -7.8851589e-01 - -3.0305698e+00 2.5544398e+00 -7.6360802e-01 - -3.1754297e+00 2.6594165e+00 -7.4476360e-01 - -3.3222508e+00 2.7647949e+00 -7.2021985e-01 - -3.4833832e+00 2.8820367e+00 -6.9637321e-01 - -3.7070292e+00 3.0432700e+00 -6.9083107e-01 - -3.8854119e+00 3.1730000e+00 -6.5868309e-01 - -4.0407705e+00 3.2850650e+00 -6.1088746e-01 - -4.0702173e+00 3.3066328e+00 -5.1545079e-01 - -4.0987218e+00 3.3271777e+00 -4.1926861e-01 - -4.1339800e+00 3.3520744e+00 -3.2446089e-01 - -4.1519047e+00 3.3651481e+00 -2.2447116e-01 - -4.1688895e+00 3.3771791e+00 -1.2413543e-01 - -4.1915696e+00 3.3944985e+00 -2.5226887e-02 - -4.1980428e+00 3.3979973e+00 7.7667553e-02 - -4.2025209e+00 3.4013654e+00 1.8035588e-01 - -4.2127539e+00 3.4090299e+00 2.8176644e-01 - -4.2143592e+00 3.4102128e+00 3.8434458e-01 - -4.2064013e+00 3.4038373e+00 4.8773715e-01 - -4.2051356e+00 3.4028204e+00 5.8990546e-01 - -4.2095614e+00 3.4071214e+00 6.9124584e-01 - -4.1977995e+00 3.3974491e+00 7.9347594e-01 - -4.1917292e+00 3.3930947e+00 8.9487811e-01 - -4.1923461e+00 3.3941384e+00 9.9585504e-01 - -4.1997069e+00 3.3996128e+00 1.0970555e+00 - -4.1898289e+00 3.3919913e+00 1.1978945e+00 - -4.1780172e+00 3.3832322e+00 1.2983772e+00 - -4.1652105e+00 3.3743880e+00 1.3983572e+00 - -4.1505309e+00 3.3634044e+00 1.4979307e+00 - -4.1348569e+00 3.3523308e+00 1.5969017e+00 - -4.1335986e+00 3.3512548e+00 1.6978715e+00 - -4.1237273e+00 3.3435791e+00 1.7976118e+00 - -4.1675109e+00 3.3757751e+00 1.9078315e+00 - -4.2180751e+00 3.4115920e+00 2.0221196e+00 - -4.2426776e+00 3.4296235e+00 2.1330197e+00 - -4.3363019e+00 3.4979591e+00 2.2639917e+00 - -4.3417891e+00 3.5007849e+00 2.3747229e+00 - -4.3606126e+00 3.5147122e+00 2.4907960e+00 - -4.3631569e+00 3.5164286e+00 2.6029654e+00 - -4.3704904e+00 3.5216056e+00 2.7183980e+00 - -4.3768809e+00 3.5257646e+00 2.8346759e+00 - -4.3803323e+00 3.5287848e+00 2.9517928e+00 - -4.3751794e+00 3.5251363e+00 3.0662820e+00 - -4.3604264e+00 3.5147389e+00 3.1777408e+00 - -4.3514584e+00 3.5078824e+00 3.2928653e+00 - -4.3415518e+00 3.4999734e+00 3.4081360e+00 - -4.3363681e+00 3.4965712e+00 3.5276191e+00 - -4.3369637e+00 3.4967541e+00 3.6516667e+00 - -4.3356182e+00 3.4958586e+00 3.7765566e+00 - -4.3246771e+00 3.4881798e+00 3.8977169e+00 - -4.3262302e+00 3.4887484e+00 4.0283596e+00 - -4.3324975e+00 3.4938928e+00 4.1646128e+00 - -4.3368821e+00 3.4969765e+00 4.3020575e+00 - -4.3460982e+00 3.5026668e+00 4.4457111e+00 - -4.3446609e+00 3.5025054e+00 4.5854826e+00 - -4.3490527e+00 3.5050159e+00 4.7315662e+00 - -4.3629276e+00 3.5157255e+00 4.8898193e+00 - -4.3481342e+00 3.5046201e+00 5.0274449e+00 - -4.3304642e+00 3.4913592e+00 5.1655597e+00 - -4.3165662e+00 3.4816512e+00 5.3100305e+00 - -4.2873725e+00 3.4604251e+00 5.4431604e+00 - -4.2687196e+00 3.4464664e+00 5.5886125e+00 - -4.2471902e+00 3.4303522e+00 5.7345537e+00 - -4.2294296e+00 3.4178155e+00 5.8873503e+00 - -4.2202645e+00 3.4115023e+00 6.0540104e+00 - -4.2206900e+00 3.4114977e+00 6.2350365e+00 - -4.2229992e+00 3.4130297e+00 6.4245090e+00 - -4.2042536e+00 3.3992959e+00 6.5947801e+00 - -4.2333251e+00 3.4197362e+00 6.8294417e+00 - -4.2011178e+00 3.3969342e+00 6.9950708e+00 - -4.1928500e+00 3.3904562e+00 7.1976889e+00 - -1.6075538e+00 1.5227779e+00 3.8816754e+00 - -1.8328333e+00 1.6847536e+00 4.3038049e+00 - -1.5562987e+00 1.4852613e+00 4.0165742e+00 - -2.6002165e+00 2.2395605e+00 5.7146423e+00 - -2.5232595e+00 2.1842459e+00 5.7648550e+00 - -1.5714805e+00 1.4964437e+00 4.3845707e+00 - -1.5281166e+00 1.4653207e+00 4.4367010e+00 - -1.4657223e+00 1.4193451e+00 4.4553044e+00 - -1.3345362e+00 1.3248366e+00 4.3479193e+00 - -1.3131148e+00 1.3099216e+00 4.4371321e+00 - -1.2946343e+00 1.2956167e+00 4.5350437e+00 - -1.2274012e+00 1.2476079e+00 4.5387991e+00 - -1.1249373e+00 1.1734524e+00 4.4629272e+00 - -1.1188080e+00 1.1685378e+00 4.5934926e+00 - -1.2279521e+00 1.2474174e+00 4.9984788e+00 - -1.3074818e+00 1.3045221e+00 5.3646074e+00 - -1.5050099e+00 1.4472411e+00 6.0586498e+00 - -1.1282129e+00 1.1748682e+00 5.2947036e+00 - -1.0410061e+00 1.1115079e+00 5.2560398e+00 - -1.0442072e+00 1.1134337e+00 5.4725317e+00 - -9.5314369e-01 1.0482287e+00 5.4216200e+00 - -9.1344447e-01 1.0199685e+00 5.5268974e+00 - -6.9137319e-01 8.5904509e-01 5.0211327e+00 - -6.8972157e-01 8.5801765e-01 5.2446488e+00 - -5.7131861e-01 7.7202633e-01 5.0509165e+00 - -3.7802575e-01 6.3306914e-01 4.5283262e+00 - -3.3093945e-01 5.9851317e-01 4.5562729e+00 - -2.8286114e-01 5.6384749e-01 4.5832176e+00 - -2.3760306e-01 5.3127156e-01 4.6285995e+00 - -3.3399851e-01 6.0114412e-01 5.4329434e+00 - -2.5461192e-01 5.4319666e-01 5.3524096e+00 - -1.2155148e-01 4.4729153e-01 4.9164765e+00 - -6.3005294e-02 4.0529119e-01 4.9094762e+00 - 1.0968748e-03 3.5843638e-01 4.8519184e+00 - 3.7132852e-02 3.3253468e-01 5.0203801e+00 - 9.5658278e-02 2.8985268e-01 5.0198214e+00 - 1.4861416e-01 2.5191677e-01 5.0676229e+00 - 2.0525114e-01 2.1021785e-01 5.0845490e+00 - 2.6656187e-01 1.6619848e-01 5.0402851e+00 - 2.6761186e-01 1.6517695e-01 6.3328232e+00 - 3.4509193e-01 1.0858384e-01 6.2570402e+00 - 4.1750673e-01 5.6124863e-02 6.3995541e+00 - -1.6221321e+00 1.6334630e+00 -9.1210048e-01 - -1.6871449e+00 1.6841725e+00 -8.9918204e-01 - -1.7599200e+00 1.7392105e+00 -8.8933280e-01 - -1.8259013e+00 1.7902170e+00 -8.7161711e-01 - -1.9120192e+00 1.8568215e+00 -8.6726222e-01 - -1.9924588e+00 1.9174856e+00 -8.5443923e-01 - -2.0861901e+00 1.9906392e+00 -8.4865831e-01 - -2.1876715e+00 2.0682199e+00 -8.4394904e-01 - -2.2900668e+00 2.1470501e+00 -8.3539094e-01 - -2.4000873e+00 2.2323358e+00 -8.2730446e-01 - -2.4967195e+00 2.3064197e+00 -8.0633275e-01 - -2.6298137e+00 2.4079430e+00 -8.0230901e-01 - -2.7628156e+00 2.5107194e+00 -7.9314123e-01 - -2.8823671e+00 2.6033057e+00 -7.7083813e-01 - -2.9952428e+00 2.6898862e+00 -7.4016999e-01 - -3.1599054e+00 2.8157069e+00 -7.2964066e-01 - -3.3101176e+00 2.9312918e+00 -7.0567957e-01 - -3.4679341e+00 3.0534996e+00 -6.7879429e-01 - -3.7254668e+00 3.2513197e+00 -6.8465983e-01 - -3.9072283e+00 3.3913546e+00 -6.5109698e-01 - -3.9979128e+00 3.4616510e+00 -5.7801105e-01 - -4.0503251e+00 3.5013517e+00 -4.8873375e-01 - -4.0931539e+00 3.5336565e+00 -3.9534609e-01 - -4.1119476e+00 3.5488535e+00 -2.9405401e-01 - -4.1212285e+00 3.5555739e+00 -1.9029991e-01 - -4.1218773e+00 3.5558472e+00 -8.4679104e-02 - -4.1042695e+00 3.5431219e+00 2.3773046e-02 - -4.1174355e+00 3.5519745e+00 1.2534335e-01 - -4.1132822e+00 3.5488907e+00 2.2979851e-01 - -4.1071964e+00 3.5446595e+00 3.3369760e-01 - -4.1078644e+00 3.5447802e+00 4.3622223e-01 - -4.1075354e+00 3.5448305e+00 5.3854392e-01 - -4.1053323e+00 3.5427513e+00 6.4065873e-01 - -4.0858843e+00 3.5276254e+00 7.4341077e-01 - -4.0884374e+00 3.5297870e+00 8.4434451e-01 - -4.0900519e+00 3.5308960e+00 9.4542449e-01 - -4.0897309e+00 3.5308823e+00 1.0464478e+00 - -4.0970911e+00 3.5363616e+00 1.1477482e+00 - -4.0776579e+00 3.5211175e+00 1.2481032e+00 - -4.0505509e+00 3.5003213e+00 1.3469826e+00 - -4.0215748e+00 3.4773561e+00 1.4448561e+00 - -3.9753169e+00 3.4421539e+00 1.5395220e+00 - -3.9587161e+00 3.4299342e+00 1.6367416e+00 - -3.9804311e+00 3.4464130e+00 1.7400910e+00 - -4.0480615e+00 3.4982526e+00 1.8532936e+00 - -4.1692600e+00 3.5911728e+00 1.9812207e+00 - -4.2559870e+00 3.6578518e+00 2.1074260e+00 - -4.2632904e+00 3.6637844e+00 2.2179150e+00 - -4.2763843e+00 3.6732134e+00 2.3311709e+00 - -4.2884739e+00 3.6826312e+00 2.4454223e+00 - -4.2833475e+00 3.6787709e+00 2.5556168e+00 - -4.2839507e+00 3.6794088e+00 2.6686285e+00 - -4.2750098e+00 3.6723355e+00 2.7793584e+00 - -4.2803992e+00 3.6764587e+00 2.8961326e+00 - -4.2829095e+00 3.6784461e+00 3.0137952e+00 - -4.2691535e+00 3.6681191e+00 3.1254569e+00 - -4.2764456e+00 3.6736262e+00 3.2475812e+00 - -4.2818564e+00 3.6770628e+00 3.3706971e+00 - -4.2853260e+00 3.6794210e+00 3.4946552e+00 - -4.3078936e+00 3.6966088e+00 3.6314162e+00 - -4.3141978e+00 3.7014576e+00 3.7616769e+00 - -4.5116082e+00 3.8530683e+00 4.0091297e+00 - -8.8689055e+00 7.2039663e+00 6.8810460e+00 - -5.2482942e+00 4.4197228e+00 4.7672891e+00 - -6.3100630e+00 5.2361633e+00 5.6556070e+00 - -5.4373621e+00 4.5654517e+00 5.2294451e+00 - -5.6718100e+00 4.7453615e+00 5.5774561e+00 - -5.6283212e+00 4.7111107e+00 5.7282614e+00 - -5.7155988e+00 4.7783324e+00 5.9858053e+00 - -5.9967074e+00 4.9941362e+00 6.4140346e+00 - -5.2866775e+00 4.4485708e+00 6.0074341e+00 - -5.9715312e+00 4.9753165e+00 6.8126982e+00 - -6.2219522e+00 5.1673053e+00 7.2632391e+00 - -5.6180242e+00 4.7030979e+00 6.9115522e+00 - -5.3244076e+00 4.4768797e+00 6.8338914e+00 - -5.1815792e+00 4.3671011e+00 6.8975979e+00 - -1.9568805e+00 1.8880126e+00 3.6412384e+00 - -4.3617010e+00 3.7369368e+00 6.4157954e+00 - -4.6139106e+00 3.9307069e+00 6.9000010e+00 - -4.3986846e+00 3.7649365e+00 6.8534837e+00 - -4.3284601e+00 3.7105324e+00 6.9743802e+00 - -4.2677138e+00 3.6643667e+00 7.1082453e+00 - -4.1545332e+00 3.5776444e+00 7.1760037e+00 - -1.5924161e+00 1.6077292e+00 3.8736869e+00 - -1.5148732e+00 1.5485440e+00 3.8669164e+00 - -1.5060028e+00 1.5414231e+00 3.9564229e+00 - -1.4752093e+00 1.5174224e+00 4.0154884e+00 - -4.3635063e+00 3.7360491e+00 8.6964632e+00 - -1.5545679e+00 1.5779581e+00 4.3701327e+00 - -1.5217785e+00 1.5533174e+00 4.4389293e+00 - -1.4928735e+00 1.5302997e+00 4.5154796e+00 - -1.4524573e+00 1.4997324e+00 4.5752100e+00 - -1.3768554e+00 1.4416256e+00 4.5675973e+00 - -1.3184210e+00 1.3961530e+00 4.5915068e+00 - -1.3055752e+00 1.3871051e+00 4.7076166e+00 - -1.1615195e+00 1.2762181e+00 4.5486956e+00 - -1.1278407e+00 1.2496166e+00 4.6194858e+00 - -1.2176603e+00 1.3190885e+00 4.9797613e+00 - -1.0746454e+00 1.2084361e+00 4.8041144e+00 - -1.2270378e+00 1.3263687e+00 5.3570257e+00 - -1.0783490e+00 1.2112887e+00 5.1597354e+00 - -9.7429834e-01 1.1311604e+00 5.0665266e+00 - -9.3671013e-01 1.1021047e+00 5.1532333e+00 - -1.0707961e+00 1.2048571e+00 5.7660535e+00 - -7.3343370e-01 9.4657035e-01 4.9348735e+00 - -6.9874648e-01 9.1895899e-01 5.0269335e+00 - -6.6681864e-01 8.9443925e-01 5.1374810e+00 - -6.0643973e-01 8.4843190e-01 5.1529946e+00 - -5.4894455e-01 8.0400683e-01 5.1766580e+00 - -4.0541300e-01 6.9408821e-01 4.8347668e+00 - -3.5650651e-01 6.5594084e-01 4.8733923e+00 - -2.5846655e-01 5.8115895e-01 4.6786320e+00 - -2.9722921e-01 6.1049960e-01 5.1613208e+00 - -2.7553356e-01 5.9313508e-01 5.3832162e+00 - -1.6814389e-01 5.1115146e-01 5.1154630e+00 - -7.2207723e-02 4.3769469e-01 4.8640805e+00 - -3.6407057e-02 4.0939684e-01 5.0042268e+00 - 2.9505655e-02 3.5990499e-01 4.9361748e+00 - 8.2167238e-02 3.1858582e-01 4.9559102e+00 - 1.3769262e-01 2.7604084e-01 4.9544621e+00 - 1.9046209e-01 2.3558385e-01 4.9916759e+00 - 2.4684897e-01 1.9137055e-01 4.9778895e+00 - 2.9242287e-01 1.5616097e-01 5.1724833e+00 - 3.0228327e-01 1.4805485e-01 6.5350024e+00 - 3.8563071e-01 8.4153106e-02 6.2385711e+00 - 4.5835278e-01 2.8691346e-02 6.2201325e+00 - -1.5990677e+00 1.7159153e+00 -9.0019019e-01 - -1.6630147e+00 1.7676205e+00 -8.8612597e-01 - -1.7336060e+00 1.8255827e+00 -8.7533308e-01 - -1.8041807e+00 1.8836779e+00 -8.6184353e-01 - -1.8891701e+00 1.9522947e+00 -8.5599290e-01 - -1.9740795e+00 2.0220661e+00 -8.4699577e-01 - -2.0867643e+00 2.1137827e+00 -8.5402834e-01 - -2.1659136e+00 2.1787831e+00 -8.3311697e-01 - -2.2871959e+00 2.2772225e+00 -8.3642316e-01 - -2.3672997e+00 2.3426332e+00 -8.0841736e-01 - -2.4894644e+00 2.4425734e+00 -8.0278102e-01 - -2.6048888e+00 2.5375393e+00 -7.8813005e-01 - -2.7499932e+00 2.6558194e+00 -7.8445826e-01 - -2.8673517e+00 2.7514038e+00 -7.5971338e-01 - -2.9990326e+00 2.8587629e+00 -7.3746338e-01 - -3.1383233e+00 2.9727006e+00 -7.1318809e-01 - -3.2852214e+00 3.0932367e+00 -6.8648798e-01 - -3.4837564e+00 3.2552433e+00 -6.7523171e-01 - -3.7281426e+00 3.4546705e+00 -6.7314769e-01 - -3.9065217e+00 3.6007177e+00 -6.3559697e-01 - -4.0180452e+00 3.6910989e+00 -5.6717785e-01 - -4.0387099e+00 3.7084501e+00 -4.6517949e-01 - -4.0345269e+00 3.7056028e+00 -3.5593025e-01 - -4.0371057e+00 3.7070433e+00 -2.4935387e-01 - -4.0310543e+00 3.7020220e+00 -1.4121042e-01 - -4.0307645e+00 3.7012429e+00 -3.5443364e-02 - -4.0361732e+00 3.7057276e+00 6.8397113e-02 - -4.0330137e+00 3.7027387e+00 1.7355459e-01 - -4.0355514e+00 3.7050234e+00 2.7698524e-01 - -4.0371517e+00 3.7062458e+00 3.8036239e-01 - -4.0520732e+00 3.7192071e+00 4.8174086e-01 - -4.0508001e+00 3.7182493e+00 5.8510769e-01 - -4.0562770e+00 3.7216730e+00 6.8769932e-01 - -4.0597569e+00 3.7249806e+00 7.9038447e-01 - -4.0613610e+00 3.7261734e+00 8.9316235e-01 - -4.0619668e+00 3.7273058e+00 9.9593706e-01 - -4.0616956e+00 3.7263789e+00 1.0987078e+00 - -4.0441874e+00 3.7123413e+00 1.2008174e+00 - -4.0018907e+00 3.6776323e+00 1.3005897e+00 - -3.9281350e+00 3.6167206e+00 1.3957533e+00 - -3.8524027e+00 3.5555304e+00 1.4877145e+00 - -3.7996597e+00 3.5117669e+00 1.5794586e+00 - -3.7755148e+00 3.4919273e+00 1.6738036e+00 - -3.7656651e+00 3.4840791e+00 1.7700482e+00 - -3.7625525e+00 3.4807159e+00 1.8676151e+00 - -3.8261300e+00 3.5333106e+00 1.9807554e+00 - -1.1788922e+01 1.0037237e+01 4.0717960e+00 - -1.1669802e+01 9.9394357e+00 4.3274954e+00 - -1.1388511e+01 9.7099171e+00 4.5317208e+00 - -1.0618040e+01 9.0803775e+00 4.5675306e+00 - -1.0088914e+01 8.6483967e+00 4.6522554e+00 - -9.9193895e+00 8.5093796e+00 4.8462986e+00 - -9.6506858e+00 8.2899449e+00 4.9959375e+00 - -9.3295827e+00 8.0276113e+00 5.1130267e+00 - -9.3679157e+00 8.0590525e+00 5.3761385e+00 - -9.4244069e+00 8.1042807e+00 5.6523993e+00 - -9.3311980e+00 8.0277685e+00 5.8609514e+00 - -9.4076240e+00 8.0902058e+00 6.1565110e+00 - -6.2627591e+00 5.5217286e+00 4.6978650e+00 - -6.2117022e+00 5.4800501e+00 4.8496909e+00 - -6.1720345e+00 5.4484439e+00 5.0086996e+00 - -8.9308607e+00 7.7004676e+00 6.9266229e+00 - -6.3633938e+00 5.6040985e+00 5.5063245e+00 - -8.3338168e+00 7.2132678e+00 7.0525002e+00 - -5.4382474e+00 4.8479650e+00 5.2415468e+00 - -5.5005725e+00 4.8989203e+00 5.4644956e+00 - -5.3200092e+00 4.7516744e+00 5.5063885e+00 - -5.3175797e+00 4.7493418e+00 5.6844080e+00 - -4.9352160e+00 4.4366144e+00 5.5481899e+00 - -5.8944204e+00 5.2198005e+00 6.5580637e+00 - -5.6595796e+00 5.0280747e+00 6.5580617e+00 - -6.3604821e+00 5.6009350e+00 7.4240277e+00 - -5.7782740e+00 5.1242005e+00 7.0966218e+00 - -5.2854958e+00 4.7228461e+00 6.8250224e+00 - -2.0550270e+00 2.0857635e+00 3.6662317e+00 - -1.9653176e+00 2.0121011e+00 3.6655069e+00 - -1.9345684e+00 1.9872315e+00 3.7272187e+00 - -1.8857682e+00 1.9472035e+00 3.7682405e+00 - -4.3775810e+00 3.9806819e+00 6.8607334e+00 - -4.2419493e+00 3.8691372e+00 6.9003415e+00 - -4.1890222e+00 3.8258136e+00 7.0415238e+00 - -5.3825564e+00 4.8002539e+00 8.8498045e+00 - -1.5534150e+00 1.6747172e+00 3.8359997e+00 - -1.5711093e+00 1.6901476e+00 3.9635058e+00 - -1.5005060e+00 1.6317649e+00 3.9644481e+00 - -1.4697679e+00 1.6068066e+00 4.0243621e+00 - -1.4343322e+00 1.5771395e+00 4.0759689e+00 - -1.4586124e+00 1.5982618e+00 4.2292670e+00 - -1.4706075e+00 1.6079193e+00 4.3686371e+00 - -1.4845391e+00 1.6181755e+00 4.5177015e+00 - -2.1970580e+00 2.2004097e+00 5.9617904e+00 - -1.3926029e+00 1.5431401e+00 4.6131492e+00 - -1.3058475e+00 1.4720457e+00 4.5797758e+00 - -1.4457806e+00 1.5871253e+00 5.0096992e+00 - -1.1560503e+00 1.3500505e+00 4.5474228e+00 - -1.1271846e+00 1.3262034e+00 4.6274183e+00 - -1.0774164e+00 1.2858735e+00 4.6635430e+00 - -1.0532573e+00 1.2661472e+00 4.7601851e+00 - -2.4862266e+00 2.4344947e+00 8.5442256e+00 - -1.2199320e+00 1.4011169e+00 5.5376220e+00 - -9.8731056e-01 1.2120704e+00 5.1044674e+00 - -8.9401692e-01 1.1354188e+00 5.0277741e+00 - -8.3947307e-01 1.0915199e+00 5.0584384e+00 - -7.9538417e-01 1.0550592e+00 5.1251452e+00 - -7.0118935e-01 9.7808782e-01 5.0229305e+00 - -6.7031743e-01 9.5265129e-01 5.1339303e+00 - -6.6203358e-01 9.4630143e-01 5.3391452e+00 - -5.1977110e-01 8.3015257e-01 5.0318114e+00 - -5.5577804e-01 8.5946669e-01 5.4365884e+00 - -3.3262190e-01 6.7742868e-01 4.7293087e+00 - -3.7701615e-01 7.1359833e-01 5.2012826e+00 - -3.5349802e-01 6.9472357e-01 5.3950064e+00 - -2.2763134e-01 5.9140181e-01 5.0432870e+00 - -2.3407317e-01 5.9699942e-01 5.4306287e+00 - -9.6292816e-02 4.8336986e-01 4.9263555e+00 - -4.2737059e-02 4.4064349e-01 4.9390460e+00 - 1.4501036e-02 3.9416398e-01 4.9210608e+00 - 3.2611732e-02 3.7823636e-01 5.2482374e+00 - 1.1864291e-01 3.0857553e-01 4.9602839e+00 - 1.7023522e-01 2.6571705e-01 4.9881116e+00 - 2.2650392e-01 2.2004368e-01 4.9649864e+00 - 2.6821093e-01 1.8608095e-01 5.1799677e+00 - 2.7831964e-01 1.7707961e-01 6.3229586e+00 - 3.5168763e-01 1.1771103e-01 6.2670622e+00 - 4.2005568e-01 6.1451511e-02 6.4694621e+00 - -1.6347683e+00 1.8528452e+00 -8.7268232e-01 - -1.7233284e+00 1.9292015e+00 -8.7690341e-01 - -1.7860577e+00 1.9841475e+00 -8.5669878e-01 - -1.8688596e+00 2.0557180e+00 -8.4930526e-01 - -1.9449268e+00 2.1222698e+00 -8.3379599e-01 - -2.0487090e+00 2.2117637e+00 -8.3436597e-01 - -2.1657707e+00 2.3138457e+00 -8.3998049e-01 - -2.2581307e+00 2.3925001e+00 -8.2276492e-01 - -2.3560600e+00 2.4784810e+00 -8.0617675e-01 - -2.4759715e+00 2.5824163e+00 -7.9814818e-01 - -2.5892028e+00 2.6803802e+00 -7.8105542e-01 - -2.7233469e+00 2.7973236e+00 -7.7077720e-01 - -2.8594516e+00 2.9146737e+00 -7.5469977e-01 - -3.0088135e+00 3.0447891e+00 -7.4007131e-01 - -3.1382005e+00 3.1564684e+00 -7.0883722e-01 - -3.2751967e+00 3.2747312e+00 -6.7547796e-01 - -3.5340673e+00 3.5004109e+00 -6.8751543e-01 - -3.7510803e+00 3.6878737e+00 -6.7089278e-01 - -3.9031570e+00 3.8209214e+00 -6.2074825e-01 - -3.9314593e+00 3.8446296e+00 -5.2121903e-01 - -3.9358488e+00 3.8492212e+00 -4.1398593e-01 - -3.9469976e+00 3.8581204e+00 -3.0902618e-01 - -3.9704823e+00 3.8785946e+00 -2.0816569e-01 - -3.9787551e+00 3.8853333e+00 -1.0281675e-01 - -4.0003578e+00 3.9037419e+00 -8.6476042e-04 - -4.0276520e+00 3.9274685e+00 1.0025930e-01 - -4.0463720e+00 3.9437708e+00 2.0369912e-01 - -4.0707823e+00 3.9654009e+00 3.0651077e-01 - -4.0942491e+00 3.9860180e+00 4.1026767e-01 - -4.1015785e+00 3.9917436e+00 5.1656188e-01 - -4.1297897e+00 4.0166951e+00 6.2103537e-01 - -4.1266160e+00 4.0138195e+00 7.2849001e-01 - -4.1530024e+00 4.0357331e+00 8.3460395e-01 - -4.1165231e+00 4.0037896e+00 9.4258600e-01 - -4.0933023e+00 3.9846016e+00 1.0489193e+00 - -4.0778291e+00 3.9698604e+00 1.1545805e+00 - -4.0746057e+00 3.9678981e+00 1.2602877e+00 - -4.0628873e+00 3.9573619e+00 1.3652640e+00 - -4.0654686e+00 3.9587827e+00 1.4714409e+00 - -3.7425377e+00 3.6797238e+00 1.5367790e+00 - -3.6594580e+00 3.6077947e+00 1.6234174e+00 - -3.5906914e+00 3.5477142e+00 1.7090591e+00 - -3.5437852e+00 3.5070777e+00 1.7960793e+00 - -3.5102400e+00 3.4773456e+00 1.8844463e+00 - -3.5127624e+00 3.4802677e+00 1.9805364e+00 - -3.5439080e+00 3.5063974e+00 2.0849699e+00 - -4.5392785e+00 4.3702309e+00 2.4737273e+00 - -4.6074136e+00 4.4286529e+00 2.6178469e+00 - -4.6802002e+00 4.4926673e+00 2.7679269e+00 - -4.7511471e+00 4.5537622e+00 2.9220444e+00 - -4.7973812e+00 4.5930654e+00 3.0713773e+00 - -4.8701423e+00 4.6567678e+00 3.2353897e+00 - -9.3402825e+00 8.5334023e+00 5.3472626e+00 - -2.4348006e+01 2.1547092e+01 1.2619008e+01 - -9.1991164e+00 8.4093942e+00 5.7886463e+00 - -9.0072536e+00 8.2441389e+00 5.9460993e+00 - -8.7803764e+00 8.0463657e+00 6.0771058e+00 - -9.5853823e+00 8.7444036e+00 6.7922605e+00 - -8.6344036e+00 7.9200681e+00 6.4984479e+00 - -8.5064011e+00 7.8077268e+00 6.6742103e+00 - -6.0822006e+00 5.7070100e+00 5.3354099e+00 - -5.2875603e+00 5.0174248e+00 4.9795458e+00 - -5.7315290e+00 5.4026355e+00 5.4700097e+00 - -5.2314799e+00 4.9679684e+00 5.2837118e+00 - -5.3895525e+00 5.1047194e+00 5.5827178e+00 - -4.7157784e+00 4.5205080e+00 5.2223018e+00 - -4.9459399e+00 4.7208752e+00 5.5834948e+00 - -4.6701059e+00 4.4814447e+00 5.5211133e+00 - -5.3454555e+00 5.0668617e+00 6.3075051e+00 - -5.8222841e+00 5.4800603e+00 6.9578898e+00 - -5.6090118e+00 5.2953685e+00 6.9722920e+00 - -2.1048522e+00 2.2569792e+00 3.6398710e+00 - -2.0039405e+00 2.1702042e+00 3.6311133e+00 - -4.2683317e+00 4.1324475e+00 6.1923584e+00 - -1.9331838e+00 2.1084062e+00 3.7451623e+00 - -1.8627296e+00 2.0467697e+00 3.7611844e+00 - -1.8321063e+00 2.0198619e+00 3.8220964e+00 - -1.7777314e+00 1.9730658e+00 3.8548070e+00 - -4.1989651e+00 4.0720908e+00 7.1006246e+00 - -4.8600653e+00 4.6444186e+00 8.2060668e+00 - -1.5208275e+00 1.7508381e+00 3.8128199e+00 - -1.4835498e+00 1.7187852e+00 3.8590262e+00 - -1.4359341e+00 1.6762966e+00 3.8894635e+00 - -4.3452377e+00 4.1972809e+00 8.4931762e+00 - -1.4305360e+00 1.6720284e+00 4.0926912e+00 - -1.3563140e+00 1.6078377e+00 4.0820830e+00 - -1.3616731e+00 1.6122024e+00 4.2037511e+00 - -6.1349922e+00 5.7472909e+00 1.2842610e+01 - -5.8241767e+00 5.4771428e+00 1.2709239e+01 - -2.1158129e+00 2.2648451e+00 6.0249929e+00 - -1.3516688e+00 1.6027963e+00 4.6926558e+00 - -1.2575786e+00 1.5213786e+00 4.6421246e+00 - -1.1663816e+00 1.4419834e+00 4.5884077e+00 - -1.0874162e+00 1.3744816e+00 4.5573082e+00 - -1.0671870e+00 1.3560138e+00 4.6543129e+00 - -1.0978673e+00 1.3832827e+00 4.8831409e+00 - -1.1823797e+00 1.4565271e+00 5.2652246e+00 - -1.2243711e+00 1.4919136e+00 5.5629073e+00 - -1.1803562e+00 1.4533143e+00 5.6470414e+00 - -9.2111091e-01 1.2295107e+00 5.1120093e+00 - -8.0640824e-01 1.1298088e+00 4.9608277e+00 - -7.4735757e-01 1.0786456e+00 4.9718980e+00 - -6.7892761e-01 1.0189698e+00 4.9441820e+00 - -6.4999242e-01 9.9464618e-01 5.0550387e+00 - -6.8042899e-01 1.0202524e+00 5.3919804e+00 - -6.2697334e-01 9.7414733e-01 5.4374784e+00 - -5.1147347e-01 8.7432622e-01 5.2243213e+00 - -4.4021281e-01 8.1264441e-01 5.1798661e+00 - -3.7465259e-01 7.5517834e-01 5.1527596e+00 - -3.4468781e-01 7.2949821e-01 5.2981194e+00 - -2.5100594e-01 6.4842778e-01 5.1128074e+00 - -2.4068613e-01 6.3866353e-01 5.3930705e+00 - -1.8635171e-01 5.9102814e-01 5.4290267e+00 - -6.7575344e-02 4.8936823e-01 5.0214002e+00 - 4.3633267e-03 4.2713046e-01 4.8858557e+00 - 4.8291924e-02 3.8784146e-01 4.9560071e+00 - 9.4272957e-02 3.4887989e-01 5.0352409e+00 - 1.4756051e-01 3.0246307e-01 5.0338975e+00 - 2.0271575e-01 2.5438152e-01 5.0215110e+00 - 2.5692502e-01 2.0729333e-01 5.0077798e+00 - 3.0125782e-01 1.6865573e-01 5.1924378e+00 - 3.5738780e-01 1.2032652e-01 5.1762528e+00 - 3.9004676e-01 9.0904768e-02 6.2385112e+00 - 4.5953509e-01 3.0618123e-02 6.2401550e+00 - -1.7763114e+00 2.0956841e+00 -8.6105936e-01 - -1.8579227e+00 2.1702787e+00 -8.5192001e-01 - -1.9518836e+00 2.2563399e+00 -8.4907721e-01 - -2.0334518e+00 2.3312793e+00 -8.3294649e-01 - -2.1292423e+00 2.4198247e+00 -8.2270569e-01 - -2.2317189e+00 2.5137781e+00 -8.1269037e-01 - -2.3408195e+00 2.6141512e+00 -8.0265047e-01 - -2.4574790e+00 2.7220259e+00 -7.9213296e-01 - -2.5884019e+00 2.8426625e+00 -7.8435964e-01 - -2.7335827e+00 2.9761052e+00 -7.7843162e-01 - -2.8521386e+00 3.0848990e+00 -7.5172773e-01 - -2.9991803e+00 3.2200606e+00 -7.3365795e-01 - -3.1452446e+00 3.3544801e+00 -7.0914969e-01 - -3.2998480e+00 3.4966047e+00 -6.8126422e-01 - -3.5598510e+00 3.7365301e+00 -6.9059323e-01 - -3.7866345e+00 3.9446364e+00 -6.7412758e-01 - -3.8642327e+00 4.0155429e+00 -5.9304253e-01 - -3.9265360e+00 4.0738932e+00 -5.0382314e-01 - -4.2320632e+00 4.3548836e+00 -4.8896480e-01 - -5.3591265e+00 5.3915659e+00 -6.9774824e-01 - -6.1668867e+00 6.1350269e+00 -7.6728229e-01 - -7.1816064e+00 7.0679841e+00 -8.4778989e-01 - -8.3157849e+00 8.1115874e+00 -9.0578447e-01 - -9.9131436e+00 9.5816574e+00 -9.9857721e-01 - -1.1105873e+01 1.0678353e+01 -9.4749199e-01 - -1.1363238e+01 1.0915555e+01 -7.0569332e-01 - -1.1258899e+01 1.0819673e+01 -4.0914702e-01 - -1.5224970e+01 1.4467655e+01 -5.0924492e-01 - -1.5483871e+01 1.4706591e+01 -1.5368194e-01 - -1.5467608e+01 1.4690424e+01 2.2698380e-01 - -1.5680905e+01 1.4887384e+01 6.0065605e-01 - -2.2895711e+01 2.1524726e+01 9.7729763e-01 - -2.2885543e+01 2.1514569e+01 1.5320195e+00 - -2.2830713e+01 2.1464487e+01 2.0844303e+00 - -4.1384384e+00 4.2669102e+00 1.3260308e+00 - -4.0461313e+00 4.1811286e+00 1.4277134e+00 - -4.0031167e+00 4.1415419e+00 1.5311260e+00 - -3.9809654e+00 4.1213287e+00 1.6357143e+00 - -3.6799814e+00 3.8442174e+00 1.6933823e+00 - -3.4586618e+00 3.6411855e+00 1.7521932e+00 - -3.3977160e+00 3.5844514e+00 1.8351149e+00 - -3.3575659e+00 3.5481470e+00 1.9203611e+00 - -3.3089375e+00 3.5031356e+00 2.0021798e+00 - -3.2735441e+00 3.4710671e+00 2.0861451e+00 - -3.2590491e+00 3.4575772e+00 2.1754305e+00 - -3.2370094e+00 3.4364723e+00 2.2619411e+00 - -3.2480753e+00 3.4470649e+00 2.3607093e+00 - -3.2373788e+00 3.4369160e+00 2.4520560e+00 - -4.5915187e+00 4.6818121e+00 3.1091824e+00 - -4.6261454e+00 4.7143344e+00 3.2572763e+00 - -4.6731489e+00 4.7570732e+00 3.4142540e+00 - -4.7106580e+00 4.7911876e+00 3.5706975e+00 - -4.7386163e+00 4.8176448e+00 3.7259579e+00 - -4.7846103e+00 4.8598978e+00 3.8945677e+00 - -4.8287702e+00 4.8991868e+00 4.0663162e+00 - -4.8690412e+00 4.9363730e+00 4.2408477e+00 - -4.9196779e+00 4.9837733e+00 4.4266537e+00 - -5.1399135e+00 5.1856682e+00 4.7297385e+00 - -5.8913177e+00 5.8770191e+00 5.4158564e+00 - -5.9381379e+00 5.9191597e+00 5.6417475e+00 - -5.7292412e+00 5.7270082e+00 5.6823765e+00 - -4.2460104e+00 4.3636400e+00 4.7157092e+00 - -4.2673837e+00 4.3823340e+00 4.8842278e+00 - -4.4722731e+00 4.5715675e+00 5.2135742e+00 - -4.8135242e+00 4.8841334e+00 5.6790530e+00 - -5.2161113e+00 5.2547428e+00 6.2287541e+00 - -5.2268592e+00 5.2647829e+00 6.4378836e+00 - -4.1248805e+00 4.2516912e+00 5.5570155e+00 - -2.1073922e+00 2.3957444e+00 3.6638797e+00 - -2.0550115e+00 2.3485698e+00 3.7067338e+00 - -1.9629855e+00 2.2636364e+00 3.7040476e+00 - -2.3173863e+00 2.5887966e+00 4.2051308e+00 - -1.8971126e+00 2.2035120e+00 3.8256536e+00 - -1.7900143e+00 2.1042438e+00 3.7950462e+00 - -1.7481040e+00 2.0659315e+00 3.8420334e+00 - -4.8804651e+00 4.9446204e+00 8.0458048e+00 - -2.3306661e+00 2.6009518e+00 4.8371934e+00 - -4.5529147e+00 4.6434253e+00 8.0951853e+00 - -1.8177141e+00 2.1294567e+00 4.3695835e+00 - -1.6312644e+00 1.9577341e+00 4.2086958e+00 - -4.3597858e+00 4.4652935e+00 8.5803692e+00 - -1.4199864e+00 1.7630797e+00 4.1009505e+00 - -1.4583058e+00 1.7992713e+00 4.2780221e+00 - -1.8563843e+00 2.1644786e+00 5.0877823e+00 - -1.3868496e+00 1.7324478e+00 4.3927152e+00 - -1.2996609e+00 1.6521380e+00 4.3560891e+00 - -1.1379344e+00 1.5036705e+00 4.1688757e+00 - -1.1045355e+00 1.4732850e+00 4.2237345e+00 - -1.0994527e+00 1.4685607e+00 4.3366752e+00 - -1.1537508e+00 1.5183343e+00 4.5859652e+00 - -1.2174338e+00 1.5765761e+00 4.8731426e+00 - -1.1161522e+00 1.4831730e+00 4.7920199e+00 - -1.4387647e+00 1.7804197e+00 5.7388321e+00 - -2.0221694e+00 2.3147668e+00 7.4257838e+00 - -1.1155683e+00 1.4829826e+00 5.2934441e+00 - -1.1441727e+00 1.5092189e+00 5.5645623e+00 - -9.9210867e-01 1.3690641e+00 5.3310418e+00 - -7.8830950e-01 1.1827658e+00 4.9181545e+00 - -7.3231107e-01 1.1308066e+00 4.9296833e+00 - -6.9891221e-01 1.0988738e+00 5.0139546e+00 - -6.5507301e-01 1.0588704e+00 5.0696239e+00 - -7.2856522e-01 1.1260998e+00 5.5660771e+00 - -9.0034175e-01 1.2842953e+00 6.5018965e+00 - -4.7573295e-01 8.9411317e-01 5.0604240e+00 - -4.5995146e-01 8.8028801e-01 5.2454360e+00 - -3.9181128e-01 8.1674930e-01 5.2001905e+00 - -3.4701420e-01 7.7533204e-01 5.2689396e+00 - -3.0960605e-01 7.4174306e-01 5.3853073e+00 - -2.2379464e-01 6.6155846e-01 5.2284353e+00 - -1.9102814e-01 6.3209345e-01 5.3817741e+00 - -8.0108261e-02 5.3039950e-01 5.0244597e+00 - -4.5541704e-02 4.9821370e-01 5.1656064e+00 - 1.4149136e-02 4.4361344e-01 5.1284826e+00 - 8.9397549e-02 3.7361359e-01 4.9215121e+00 - 1.3975472e-01 3.2789049e-01 4.9305655e+00 - 1.9104183e-01 2.8104594e-01 4.9383668e+00 - 2.4219947e-01 2.3316678e-01 4.9251940e+00 - 2.8178847e-01 1.9732119e-01 5.1400810e+00 - 3.2699756e-01 1.5558619e-01 5.3442102e+00 - 3.5828415e-01 1.2632903e-01 6.2870216e+00 - 4.2572311e-01 6.4192249e-02 6.3094949e+00 - -1.8418677e+00 2.2865853e+00 -8.5355112e-01 - -1.9146754e+00 2.3571357e+00 -8.3435439e-01 - -2.0196693e+00 2.4597257e+00 -8.3526253e-01 - -2.1189216e+00 2.5573969e+00 -8.2725274e-01 - -2.2192052e+00 2.6543483e+00 -8.1479564e-01 - -2.3127522e+00 2.7462959e+00 -7.9392316e-01 - -2.4395184e+00 2.8695485e+00 -7.8900788e-01 - -2.5671868e+00 2.9941442e+00 -7.7834612e-01 - -2.7090517e+00 3.1325529e+00 -7.6937945e-01 - -2.8442315e+00 3.2650297e+00 -7.5054959e-01 - -3.0002459e+00 3.4176259e+00 -7.3568739e-01 - -3.1572141e+00 3.5706372e+00 -7.1363089e-01 - -3.3350046e+00 3.7438663e+00 -6.9354453e-01 - -3.5961350e+00 3.9980769e+00 -6.9936605e-01 - -3.8230489e+00 4.2203981e+00 -6.7959585e-01 - -4.0585339e+00 4.4496539e+00 -6.5180457e-01 - -4.3563905e+00 4.7413551e+00 -6.3411774e-01 - -4.8862660e+00 5.2578630e+00 -6.7394700e-01 - -5.7473491e+00 6.0989034e+00 -7.8240779e-01 - -6.5496369e+00 6.8820989e+00 -8.3290972e-01 - -7.5742902e+00 7.8817145e+00 -8.9611882e-01 - -8.9196416e+00 9.1947350e+00 -9.7671280e-01 - -1.0900807e+01 1.1128376e+01 -1.1089268e+00 - -1.1139433e+01 1.1360549e+01 -8.6479305e-01 - -1.4244296e+01 1.4392104e+01 -9.9897286e-01 - -1.4417370e+01 1.4560049e+01 -6.5565656e-01 - -1.4486292e+01 1.4627225e+01 -2.9599762e-01 - -1.4492744e+01 1.4633772e+01 7.0071114e-02 - -1.4574016e+01 1.4711895e+01 4.3317109e-01 - -1.5659860e+01 1.5771017e+01 7.8652131e-01 - -1.6110803e+01 1.6211288e+01 1.1856028e+00 - -2.1814771e+01 2.1778856e+01 1.7936199e+00 - -2.1623070e+01 2.1591166e+01 2.3269428e+00 - -2.1525048e+01 2.1494360e+01 2.8595648e+00 - -2.1548017e+01 2.1516677e+01 3.4017757e+00 - -3.9676781e+00 4.3593231e+00 1.5967590e+00 - -3.8747146e+00 4.2681712e+00 1.6920943e+00 - -3.8441366e+00 4.2383232e+00 1.7947028e+00 - -3.5431379e+00 3.9455566e+00 1.8401270e+00 - -3.4691806e+00 3.8720298e+00 1.9238968e+00 - -3.3015333e+00 3.7092459e+00 1.9805530e+00 - -3.1907009e+00 3.6004490e+00 2.0453097e+00 - -3.1279912e+00 3.5401893e+00 2.1199840e+00 - -3.0578112e+00 3.4712043e+00 2.1896359e+00 - -2.9876502e+00 3.4020665e+00 2.2561917e+00 - -2.9155121e+00 3.3326552e+00 2.3196449e+00 - -2.8642711e+00 3.2818323e+00 2.3886180e+00 - -2.8063779e+00 3.2253306e+00 2.4523233e+00 - -2.7532278e+00 3.1731731e+00 2.5169450e+00 - -2.7000312e+00 3.1219042e+00 2.5793199e+00 - -2.6601733e+00 3.0817172e+00 2.6466371e+00 - -2.6192664e+00 3.0423927e+00 2.7124034e+00 - -2.5774915e+00 3.0009351e+00 2.7766676e+00 - -2.5214676e+00 2.9471165e+00 2.8315414e+00 - -2.4853143e+00 2.9120526e+00 2.8965261e+00 - -2.4680831e+00 2.8947697e+00 2.9733662e+00 - -4.7814708e+00 5.1520958e+00 4.6715109e+00 - -4.7923411e+00 5.1621887e+00 4.8411899e+00 - -4.8126398e+00 5.1814332e+00 5.0220901e+00 - -4.2695191e+00 4.6512471e+00 4.7624422e+00 - -4.4992731e+00 4.8758005e+00 5.1062195e+00 - -4.2770791e+00 4.6585250e+00 5.0813235e+00 - -4.4963747e+00 4.8730893e+00 5.4386453e+00 - -4.7392920e+00 5.1090955e+00 5.8354049e+00 - -4.6312289e+00 5.0033114e+00 5.9170510e+00 - -4.9475460e+00 5.3121420e+00 6.4184043e+00 - -2.0348545e+00 2.4711818e+00 3.6149556e+00 - -2.4796484e+00 2.9046387e+00 4.1871483e+00 - -2.0068832e+00 2.4446140e+00 3.7803961e+00 - -2.2875692e+00 2.7173024e+00 4.2033136e+00 - -2.2033555e+00 2.6347511e+00 4.2188807e+00 - -1.8411052e+00 2.2814185e+00 3.8870458e+00 - -4.0656709e+00 4.4509425e+00 6.8327073e+00 - -1.9280542e+00 2.3670396e+00 4.2124649e+00 - -2.2716586e+00 2.7006842e+00 4.7964658e+00 - -1.9726358e+00 2.4094482e+00 4.5070137e+00 - -1.8149520e+00 2.2561815e+00 4.3999605e+00 - -1.6997444e+00 2.1431938e+00 4.3453495e+00 - -1.6428722e+00 2.0881176e+00 4.3759501e+00 - -1.5079527e+00 1.9556231e+00 4.2757223e+00 - -1.4435263e+00 1.8940390e+00 4.2854712e+00 - -1.3933352e+00 1.8444100e+00 4.3166453e+00 - -1.8276969e+00 2.2669379e+00 5.2265287e+00 - -1.2966802e+00 1.7495789e+00 4.3828030e+00 - -1.2454566e+00 1.7006796e+00 4.4097296e+00 - -1.0400973e+00 1.5004600e+00 4.1222732e+00 - -1.0529324e+00 1.5124723e+00 4.2676398e+00 - -1.0694656e+00 1.5286288e+00 4.4313477e+00 - -1.2137862e+00 1.6687304e+00 4.8952072e+00 - -1.4960753e+00 1.9434358e+00 5.7200309e+00 - -1.4260087e+00 1.8750916e+00 5.7418930e+00 - -1.3052269e+00 1.7579113e+00 5.6298834e+00 - -1.1009904e+00 1.5588185e+00 5.2830051e+00 - -1.1633444e+00 1.6186123e+00 5.6433882e+00 - -1.0182616e+00 1.4778967e+00 5.4304638e+00 - -7.9926127e-01 1.2640672e+00 4.9664761e+00 - -7.0030628e-01 1.1676301e+00 4.8416633e+00 - -6.6602804e-01 1.1341718e+00 4.9164926e+00 - -7.0379863e-01 1.1711394e+00 5.2511169e+00 - -9.2956656e-01 1.3903269e+00 6.3192275e+00 - -8.7074466e-01 1.3326938e+00 6.3814810e+00 - -5.0632027e-01 9.7821141e-01 5.1815186e+00 - -4.5893048e-01 9.3133911e-01 5.2243886e+00 - -4.0773443e-01 8.8170393e-01 5.2566582e+00 - -3.4065818e-01 8.1718438e-01 5.2105665e+00 - -2.7558937e-01 7.5269704e-01 5.1626834e+00 - -2.1322547e-01 6.9276808e-01 5.1225019e+00 - -1.9464660e-01 6.7357621e-01 5.3442063e+00 - -1.2860694e-01 6.0932578e-01 5.2820880e+00 - -6.6329973e-02 5.4870215e-01 5.2278239e+00 - 5.1896326e-03 4.7950540e-01 5.0930258e+00 - 7.3760377e-02 4.1240192e-01 4.9362156e+00 - 1.2662950e-01 3.6057837e-01 4.9063060e+00 - 1.5573829e-01 3.3196892e-01 5.1531405e+00 - 2.2777890e-01 2.6199309e-01 4.8822097e+00 - 2.6887471e-01 2.2211478e-01 5.0177883e+00 - 3.0927896e-01 1.8268404e-01 5.2422587e+00 - 3.5873945e-01 1.3370644e-01 5.3461949e+00 - 3.9384028e-01 9.8655794e-02 6.3385293e+00 - 4.6152692e-01 3.2524203e-02 6.2001995e+00 - -1.1573784e+00 1.7156690e+00 -9.3344219e-01 - -1.2072485e+00 1.7683788e+00 -9.2241800e-01 - -1.8980275e+00 2.4833379e+00 -8.3797914e-01 - -2.0064832e+00 2.5950536e+00 -8.4111829e-01 - -2.0912980e+00 2.6823855e+00 -8.2177414e-01 - -2.1883320e+00 2.7832568e+00 -8.0722761e-01 - -2.3052266e+00 2.9039947e+00 -8.0054712e-01 - -2.4097899e+00 3.0126041e+00 -7.8072892e-01 - -2.5530889e+00 3.1607830e+00 -7.7874337e-01 - -2.6906980e+00 3.3031152e+00 -7.6639206e-01 - -2.8424360e+00 3.4603163e+00 -7.5458688e-01 - -3.0007739e+00 3.6241292e+00 -7.3886192e-01 - -3.1675851e+00 3.7966885e+00 -7.1891041e-01 - -3.3334097e+00 3.9685796e+00 -6.9102227e-01 - -3.5870336e+00 4.2306432e+00 -6.9116997e-01 - -3.8348801e+00 4.4880738e+00 -6.7660689e-01 - -4.0837111e+00 4.7451591e+00 -6.5000588e-01 - -4.5165351e+00 5.1924806e+00 -6.7230324e-01 - -5.2558794e+00 5.9586287e+00 -7.6730824e-01 - -5.9583577e+00 6.6858241e+00 -8.1416204e-01 - -6.8966726e+00 7.6557546e+00 -8.8535078e-01 - -7.9677611e+00 8.7649261e+00 -9.3996051e-01 - -9.2971508e+00 1.0141547e+01 -9.9295227e-01 - -9.7822404e+00 1.0642421e+01 -8.2873573e-01 - -9.8719962e+00 1.0735396e+01 -5.8075715e-01 - -9.9393036e+00 1.0804344e+01 -6.2399703e-02 - -1.4612752e+01 1.5641801e+01 -1.5733235e-01 - -1.4645562e+01 1.5675644e+01 2.2136965e-01 - -1.4438012e+01 1.5459621e+01 6.0750920e-01 - -1.4912971e+01 1.5951284e+01 9.8217662e-01 - -1.5174813e+01 1.6222368e+01 1.3755205e+00 - -1.5682741e+01 1.6746308e+01 1.7944556e+00 - -2.0478990e+01 2.1711068e+01 2.5576666e+00 - -2.0505716e+01 2.1738090e+01 3.0890555e+00 - -2.0526804e+01 2.1758846e+01 3.6223206e+00 - -2.0546878e+01 2.1779675e+01 4.1582793e+00 - -3.8192793e+00 4.4687219e+00 1.7582535e+00 - -3.4449352e+00 4.0807345e+00 1.7933039e+00 - -3.2561950e+00 3.8856694e+00 1.8517227e+00 - -3.2587082e+00 3.8886653e+00 1.9493109e+00 - -3.2602810e+00 3.8906236e+00 2.0473451e+00 - -3.3014593e+00 3.9327224e+00 2.1581615e+00 - -3.6731824e+00 4.3173288e+00 2.3811798e+00 - -3.4468703e+00 4.0824626e+00 2.4109926e+00 - -3.0595175e+00 3.6817858e+00 2.3679917e+00 - -2.9490744e+00 3.5672997e+00 2.4187137e+00 - -2.7783311e+00 3.3914353e+00 2.4379492e+00 - -2.6811103e+00 3.2905095e+00 2.4830778e+00 - -2.6234206e+00 3.2308346e+00 2.5432363e+00 - -2.5658065e+00 3.1700396e+00 2.6009475e+00 - -2.5128133e+00 3.1155975e+00 2.6597756e+00 - -2.4598336e+00 3.0610470e+00 2.7164063e+00 - -2.4068669e+00 3.0063931e+00 2.7709397e+00 - -2.3529758e+00 2.9505734e+00 2.8233221e+00 - -2.3056958e+00 2.9012768e+00 2.8778266e+00 - -2.2574901e+00 2.8508243e+00 2.9303799e+00 - -2.2270874e+00 2.8200912e+00 2.9947860e+00 - -2.2090038e+00 2.8005519e+00 3.0676270e+00 - -2.1833294e+00 2.7742813e+00 3.1353465e+00 - -2.1633152e+00 2.7535799e+00 3.2073318e+00 - -4.1330715e+00 4.7910686e+00 4.9968014e+00 - -4.8275277e+00 5.5078450e+00 5.7793344e+00 - -4.6520657e+00 5.3269251e+00 5.8034959e+00 - -4.5067841e+00 5.1759364e+00 5.8482942e+00 - -4.4695449e+00 5.1379028e+00 5.9961208e+00 - -4.6729698e+00 5.3476071e+00 6.3960366e+00 - -2.4009683e+00 2.9987751e+00 4.1384653e+00 - -2.3245344e+00 2.9193812e+00 4.1677417e+00 - -2.2697109e+00 2.8624598e+00 4.2192717e+00 - -2.2252544e+00 2.8157424e+00 4.2818764e+00 - -4.0696117e+00 4.7235653e+00 6.7026398e+00 - -1.7915176e+00 2.3684087e+00 3.9619467e+00 - -1.8832756e+00 2.4624889e+00 4.1893578e+00 - -1.9496125e+00 2.5308541e+00 4.3944516e+00 - -1.9022759e+00 2.4825249e+00 4.4483072e+00 - -4.1227701e+00 4.7768594e+00 7.8717839e+00 - -1.7654753e+00 2.3407375e+00 4.4862961e+00 - -1.6206466e+00 2.1902555e+00 4.3792851e+00 - -1.5930507e+00 2.1622346e+00 4.4544882e+00 - -1.4744796e+00 2.0398520e+00 4.3763903e+00 - -1.3981867e+00 1.9603631e+00 4.3632199e+00 - -1.3406509e+00 1.9004897e+00 4.3788343e+00 - -1.2484038e+00 1.8051603e+00 4.3287003e+00 - -1.1711523e+00 1.7258097e+00 4.2992972e+00 - -1.7696031e+00 2.3436815e+00 5.6505125e+00 - -1.0317933e+00 1.5808719e+00 4.2568263e+00 - -1.0032745e+00 1.5521895e+00 4.3198413e+00 - -1.5347900e+00 2.1008048e+00 5.6707557e+00 - -1.5173829e+00 2.0828646e+00 5.8153105e+00 - -1.3679845e+00 1.9287153e+00 5.6400678e+00 - -1.3562902e+00 1.9148923e+00 5.7999739e+00 - -1.2256612e+00 1.7802601e+00 5.6515185e+00 - -1.0520892e+00 1.6010415e+00 5.3645240e+00 - -7.9074807e-01 1.3311088e+00 4.7919053e+00 - -7.8556536e-01 1.3256353e+00 4.9504386e+00 - -7.4394014e-01 1.2824664e+00 5.0002702e+00 - -6.4529076e-01 1.1815242e+00 4.8651686e+00 - -7.7070899e-01 1.3101765e+00 5.5050927e+00 - -6.8890817e-01 1.2254488e+00 5.4335745e+00 - -9.4724924e-01 1.4922361e+00 6.6932770e+00 - -8.5136337e-01 1.3922896e+00 6.6152137e+00 - -8.0011721e-01 1.3394447e+00 6.7242357e+00 - -4.0389734e-01 9.3011666e-01 5.2263119e+00 - -3.1759644e-01 8.4116506e-01 5.0752760e+00 - -2.7041032e-01 7.9163374e-01 5.1047617e+00 - -2.2867844e-01 7.4931712e-01 5.1718720e+00 - -1.6662076e-01 6.8487811e-01 5.1213018e+00 - -1.4898149e-01 6.6621473e-01 5.3524977e+00 - -8.7816762e-02 6.0319278e-01 5.3091721e+00 - -7.3395855e-03 5.2056624e-01 5.0966846e+00 - 4.7177302e-02 4.6325766e-01 5.0593259e+00 - 1.0630976e-01 4.0213232e-01 4.9709638e+00 - 1.5899309e-01 3.4779263e-01 4.9305663e+00 - 2.0353984e-01 3.0282779e-01 4.9881780e+00 - 2.5520755e-01 2.4892474e-01 4.9351497e+00 - 2.9168386e-01 2.1025310e-01 5.1701199e+00 - 3.4002392e-01 1.6087460e-01 5.2444463e+00 - 3.6394620e-01 1.3500078e-01 6.3271089e+00 - 4.2877395e-01 6.7039761e-02 6.2695865e+00 - -1.0734103e+00 1.7288875e+00 -9.2870527e-01 - -1.1222281e+00 1.7824846e+00 -9.1873258e-01 - -1.1663690e+00 1.8301771e+00 -9.0078799e-01 - -1.2368166e+00 1.9081554e+00 -9.1090792e-01 - -1.2752104e+00 1.9509734e+00 -8.8314650e-01 - -1.3466229e+00 2.0292782e+00 -8.8786992e-01 - -1.4199517e+00 2.1088585e+00 -8.8944047e-01 - -1.4866029e+00 2.1824477e+00 -8.8234635e-01 - -1.7889282e+00 2.5153273e+00 -8.4884120e-01 - -1.8763187e+00 2.6103136e+00 -8.4007132e-01 - -1.9513798e+00 2.6931567e+00 -8.1846335e-01 - -2.0519034e+00 2.8029319e+00 -8.1064228e-01 - -2.1523383e+00 2.9139307e+00 -7.9827644e-01 - -2.2593930e+00 3.0313837e+00 -7.8518687e-01 - -2.3796515e+00 3.1625449e+00 -7.7469446e-01 - -2.5186359e+00 3.3156343e+00 -7.6957358e-01 - -2.6651624e+00 3.4763584e+00 -7.6127842e-01 - -2.8313982e+00 3.6591895e+00 -7.5595456e-01 - -2.9919987e+00 3.8352211e+00 -7.3931651e-01 - -3.1534891e+00 4.0126945e+00 -7.1493444e-01 - -3.3468986e+00 4.2258880e+00 -6.9682316e-01 - -3.5478884e+00 4.4458967e+00 -6.7189249e-01 - -3.7629129e+00 4.6820423e+00 -6.4206429e-01 - -4.1151955e+00 5.0689985e+00 -6.5086753e-01 - -4.8040365e+00 5.8257470e+00 -7.5252901e-01 - -5.4307717e+00 6.5132845e+00 -7.9889535e-01 - -6.3582327e+00 7.5314411e+00 -8.9565851e-01 - -7.2225347e+00 8.4807649e+00 -9.2824070e-01 - -8.4353969e+00 9.8136120e+00 -9.9380977e-01 - -9.1584501e+00 1.0607227e+01 -8.9983532e-01 - -1.0009233e+01 1.1540718e+01 -7.9054584e-01 - -1.0001810e+01 1.1532951e+01 -5.1396785e-01 - -9.8769804e+00 1.1395338e+01 -2.2490110e-01 - -1.4096947e+01 1.6029718e+01 -3.4305315e-01 - -1.4567439e+01 1.6546886e+01 5.2977225e-03 - -1.4833141e+01 1.6837625e+01 3.8578123e-01 - -1.4911788e+01 1.6924267e+01 7.8218643e-01 - -1.4731270e+01 1.6724480e+01 1.1796066e+00 - -1.4921705e+01 1.6933506e+01 1.5816784e+00 - -1.5148753e+01 1.7182478e+01 1.9962234e+00 - -1.9509737e+01 2.1971192e+01 2.7937665e+00 - -1.9546754e+01 2.2010571e+01 3.3191026e+00 - -1.9530230e+01 2.1991337e+01 3.8401910e+00 - -1.9560594e+01 2.2024529e+01 4.3701967e+00 - -1.0183854e+01 1.1729394e+01 3.0760042e+00 - -3.0775670e+00 3.9269757e+00 1.7899101e+00 - -3.0547540e+00 3.9019506e+00 1.8792125e+00 - -3.0572795e+00 3.9048480e+00 1.9748032e+00 - -3.0654770e+00 3.9132210e+00 2.0727621e+00 - -3.2884995e+00 4.1588167e+00 2.2426468e+00 - -3.5754295e+00 4.4722065e+00 2.4476287e+00 - -3.5638143e+00 4.4598143e+00 2.5555007e+00 - -3.5578102e+00 4.4538996e+00 2.6657911e+00 - -3.5640797e+00 4.4600574e+00 2.7820698e+00 - -3.5937731e+00 4.4923334e+00 2.9110218e+00 - -3.6281216e+00 4.5301722e+00 3.0453350e+00 - -3.6540379e+00 4.5584205e+00 3.1785674e+00 - -3.6846088e+00 4.5922366e+00 3.3172609e+00 - -2.4660937e+00 3.2547082e+00 2.7304210e+00 - -2.4020856e+00 3.1841085e+00 2.7802662e+00 - -2.3249563e+00 3.0991405e+00 2.8193250e+00 - -2.2421871e+00 3.0084407e+00 2.8508220e+00 - -2.1772376e+00 2.9373273e+00 2.8914753e+00 - -2.1300989e+00 2.8858693e+00 2.9426831e+00 - -2.0829714e+00 2.8343226e+00 2.9920930e+00 - -2.0359158e+00 2.7816853e+00 3.0396549e+00 - -1.9944675e+00 2.7355551e+00 3.0902344e+00 - -1.9576247e+00 2.6959010e+00 3.1444278e+00 - -1.9208508e+00 2.6551809e+00 3.1972724e+00 - -1.9168251e+00 2.6510773e+00 3.2810531e+00 - -1.9072646e+00 2.6393712e+00 3.3598681e+00 - -1.8957673e+00 2.6265521e+00 3.4388262e+00 - -4.6655570e+00 5.6652290e+00 6.4586198e+00 - -4.4860502e+00 5.4692267e+00 6.4667796e+00 - -1.7423120e+00 2.4582334e+00 3.5485080e+00 - -1.8758809e+00 2.6051311e+00 3.7989030e+00 - -2.1236812e+00 2.8759101e+00 4.2031889e+00 - -2.1317675e+00 2.8846558e+00 4.3289630e+00 - -1.7739221e+00 2.4925991e+00 3.9795414e+00 - -3.9105897e+00 4.8364551e+00 6.9876492e+00 - -1.7564673e+00 2.4729768e+00 4.1710367e+00 - -1.8533843e+00 2.5797262e+00 4.4250883e+00 - -2.0681142e+00 2.8154323e+00 4.8702486e+00 - -1.9901340e+00 2.7292264e+00 4.8854337e+00 - -1.4381178e+00 2.1237851e+00 4.1315290e+00 - -1.4368667e+00 2.1221359e+00 4.2411377e+00 - -1.4729974e+00 2.1612910e+00 4.4199520e+00 - -1.3464480e+00 2.0231113e+00 4.3162516e+00 - -1.3872221e+00 2.0674088e+00 4.5121622e+00 - -1.2924937e+00 1.9636711e+00 4.4573214e+00 - -1.2108273e+00 1.8747748e+00 4.4228551e+00 - -1.2132415e+00 1.8775307e+00 4.5560985e+00 - -1.1522165e+00 1.8097816e+00 4.5587634e+00 - -1.6063547e+00 2.3066562e+00 5.7094028e+00 - -1.4854562e+00 2.1741195e+00 5.6114664e+00 - -1.3953520e+00 2.0756769e+00 5.5768181e+00 - -2.0476067e+00 2.7894330e+00 7.3993225e+00 - -1.3336694e+00 2.0075094e+00 5.7938640e+00 - -1.3060639e+00 1.9769869e+00 5.9196527e+00 - -8.3312596e-01 1.4587753e+00 4.7863700e+00 - -5.9516805e-01 1.1979649e+00 4.2477881e+00 - -1.3367071e+00 2.0092796e+00 6.6936052e+00 - -9.4136565e-01 1.5767296e+00 5.6759232e+00 - -6.7659482e-01 1.2862835e+00 4.9974635e+00 - -6.0066379e-01 1.2039025e+00 4.9256655e+00 - -5.4152500e-01 1.1392177e+00 4.9069647e+00 - -1.2067957e+00 1.8659904e+00 7.7424574e+00 - -8.3073535e-01 1.4550575e+00 6.5510149e+00 - -7.6770710e-01 1.3851802e+00 6.5940221e+00 - -6.9348840e-01 1.3041582e+00 6.5878486e+00 - -3.5080381e-01 9.2946837e-01 5.2374302e+00 - -2.6117839e-01 8.3132559e-01 5.0467777e+00 - -2.4471073e-01 8.1185239e-01 5.2400740e+00 - -1.8282816e-01 7.4446686e-01 5.1905513e+00 - -1.6343075e-01 7.2274767e-01 5.4027635e+00 - -1.0619252e-01 6.5998054e-01 5.3799749e+00 - -5.8157858e-02 6.0713010e-01 5.4244374e+00 - 3.6646882e-02 5.0421730e-01 5.0633778e+00 - 7.1719174e-02 4.6442579e-01 5.1933823e+00 - 1.4698852e-01 3.8191462e-01 4.9163417e+00 - 1.8135344e-01 3.4502311e-01 5.0836537e+00 - 2.4909558e-01 2.7129810e-01 4.7926093e+00 - 2.7895219e-01 2.3753328e-01 5.0577158e+00 - 3.1461672e-01 1.9834850e-01 5.3621018e+00 - 3.6795973e-01 1.3969625e-01 5.2962814e+00 - 3.9913181e-01 1.0436659e-01 6.3185907e+00 - 4.6314228e-01 3.4000578e-02 6.0502319e+00 - -1.0851406e+00 1.8481922e+00 -9.0378003e-01 - -1.1375481e+00 1.9088620e+00 -8.9713777e-01 - -1.2012062e+00 1.9827742e+00 -9.0009040e-01 - -1.2601830e+00 2.0508163e+00 -8.9437199e-01 - -1.3190836e+00 2.1199834e+00 -8.8610633e-01 - -1.3789670e+00 2.1893341e+00 -8.7534058e-01 - -1.4434940e+00 2.2648555e+00 -8.6715340e-01 - -1.5145984e+00 2.3476852e+00 -8.6118846e-01 - -1.6035307e+00 2.4510654e+00 -8.6704065e-01 - -1.6755293e+00 2.5353022e+00 -8.5403084e-01 - -1.7541611e+00 2.6258848e+00 -8.4249459e-01 - -1.8383039e+00 2.7247762e+00 -8.3193491e-01 - -1.9234195e+00 2.8239300e+00 -8.1727712e-01 - -2.0263440e+00 2.9437871e+00 -8.1134028e-01 - -2.1058170e+00 3.0362006e+00 -7.8416976e-01 - -2.2218592e+00 3.1709698e+00 -7.7668482e-01 - -2.3378060e+00 3.3070168e+00 -7.6355646e-01 - -2.4912969e+00 3.4856672e+00 -7.6631517e-01 - -2.6457378e+00 3.6647623e+00 -7.6128033e-01 - -2.8188234e+00 3.8669502e+00 -7.5827076e-01 - -2.9938517e+00 4.0696876e+00 -7.4656556e-01 - -3.1687649e+00 4.2738604e+00 -7.2602088e-01 - -3.3502037e+00 4.4857553e+00 -6.9930881e-01 - -3.5766450e+00 4.7490724e+00 -6.8156379e-01 - -3.8798403e+00 5.1024195e+00 -6.8130265e-01 - -4.4378133e+00 5.7523190e+00 -7.5557302e-01 - -4.9600778e+00 6.3610219e+00 -7.8788214e-01 - -5.6827144e+00 7.2029209e+00 -8.5208419e-01 - -6.4398620e+00 8.0854859e+00 -8.8674054e-01 - -7.4123210e+00 9.2181932e+00 -9.3320785e-01 - -8.4717761e+00 1.0451101e+01 -9.4623420e-01 - -9.6630035e+00 1.1838988e+01 -9.2754440e-01 - -9.6575148e+00 1.1832350e+01 -6.5080984e-01 - -1.2743333e+01 1.5427008e+01 -7.9436122e-01 - -1.3203765e+01 1.5963584e+01 -4.8727948e-01 - -1.3681056e+01 1.6518353e+01 -1.5756215e-01 - -1.4200403e+01 1.7121922e+01 1.9473806e-01 - -1.5066787e+01 1.8131495e+01 5.6459674e-01 - -1.5225583e+01 1.8316277e+01 9.8148624e-01 - -1.5035360e+01 1.8093777e+01 1.3978890e+00 - -1.6388995e+01 1.9670247e+01 1.8853674e+00 - -1.6343662e+01 1.9617638e+01 2.3350344e+00 - -1.6632442e+01 1.9952003e+01 2.8185379e+00 - -1.6875211e+01 2.0234965e+01 3.3126032e+00 - -1.9709896e+01 2.3536482e+01 4.2361620e+00 - -1.9696153e+01 2.3519649e+01 4.7819798e+00 - -1.9683338e+01 2.3503951e+01 5.3293493e+00 - -2.8731092e+00 3.9269652e+00 1.8161825e+00 - -2.8765844e+00 3.9308264e+00 1.9098292e+00 - -2.8781216e+00 3.9335845e+00 2.0038187e+00 - -2.8666752e+00 3.9193283e+00 2.0941619e+00 - -3.5778602e+00 4.7467965e+00 2.4397056e+00 - -3.5288669e+00 4.6904756e+00 2.5365978e+00 - -3.4921049e+00 4.6470814e+00 2.6365324e+00 - -3.4730562e+00 4.6251542e+00 2.7432268e+00 - -3.4586819e+00 4.6086372e+00 2.8521863e+00 - -3.4621271e+00 4.6117067e+00 2.9703020e+00 - -3.4636325e+00 4.6136878e+00 3.0890602e+00 - -3.4885512e+00 4.6418707e+00 3.2221895e+00 - -3.5171257e+00 4.6755659e+00 3.3608767e+00 - -3.5382693e+00 4.6997064e+00 3.4979868e+00 - -3.5519246e+00 4.7152645e+00 3.6329710e+00 - -3.5982380e+00 4.7691916e+00 3.7938982e+00 - -3.6370564e+00 4.8145904e+00 3.9537980e+00 - -4.3351557e+00 5.6266764e+00 4.6112035e+00 - -2.0517924e+00 2.9687693e+00 2.9903748e+00 - -1.9880562e+00 2.8944496e+00 3.0255869e+00 - -1.9308708e+00 2.8276500e+00 3.0628713e+00 - -1.8838933e+00 2.7738729e+00 3.1075863e+00 - -1.8379852e+00 2.7190707e+00 3.1505562e+00 - -1.7966845e+00 2.6707297e+00 3.1968403e+00 - -1.7543949e+00 2.6222544e+00 3.2416231e+00 - -1.7177667e+00 2.5793385e+00 3.2904718e+00 - -1.6754956e+00 2.5307154e+00 3.3322583e+00 - -1.6277045e+00 2.4743716e+00 3.3666820e+00 - -1.5901648e+00 2.4301864e+00 3.4112825e+00 - -1.5516356e+00 2.3858717e+00 3.4544815e+00 - -1.5187616e+00 2.3471657e+00 3.5027453e+00 - -1.4848963e+00 2.3083450e+00 3.5499072e+00 - -1.4510973e+00 2.2684781e+00 3.5961200e+00 - -1.4163070e+00 2.2284965e+00 3.6412309e+00 - -1.3815836e+00 2.1874638e+00 3.6852928e+00 - -1.3552204e+00 2.1565981e+00 3.7421210e+00 - -1.3278627e+00 2.1256423e+00 3.7983468e+00 - -1.3052733e+00 2.0983147e+00 3.8612314e+00 - -1.3077322e+00 2.1017442e+00 3.9676088e+00 - -1.3307060e+00 2.1283641e+00 4.1120171e+00 - -1.4579443e+00 2.2760812e+00 4.4471373e+00 - -1.3719396e+00 2.1759949e+00 4.4147981e+00 - -1.6331304e+00 2.4791908e+00 5.0312311e+00 - -1.1488022e+00 1.9165752e+00 4.2292745e+00 - -1.1280700e+00 1.8909960e+00 4.3049002e+00 - -1.1936972e+00 1.9681266e+00 4.5661270e+00 - -1.4453406e+00 2.2600271e+00 5.2494401e+00 - -1.3741888e+00 2.1775768e+00 5.2511656e+00 - -1.3654199e+00 2.1660343e+00 5.3928550e+00 - -1.3490764e+00 2.1476323e+00 5.5268261e+00 - -2.4381685e+00 3.4133956e+00 8.4799222e+00 - -2.3918299e+00 3.3584234e+00 8.6612685e+00 - -7.8763961e-01 1.4944248e+00 4.5498415e+00 - -7.8996479e-01 1.4973760e+00 4.7073046e+00 - -1.2811778e+00 2.0678084e+00 6.3443485e+00 - -1.2832689e+00 2.0700513e+00 6.5887524e+00 - -1.2306101e+00 2.0088110e+00 6.6718473e+00 - -6.6377582e-01 1.3493967e+00 4.9912674e+00 - -5.9283295e-01 1.2668236e+00 4.9297223e+00 - -5.2559934e-01 1.1888201e+00 4.8748832e+00 - -1.0116161e+00 1.7526401e+00 7.0108362e+00 - -1.1355117e+00 1.8955230e+00 7.8582057e+00 - -7.7586963e-01 1.4788858e+00 6.6531287e+00 - -4.0928309e-01 1.0539629e+00 5.2695969e+00 - -3.4954155e-01 9.8347901e-01 5.2358595e+00 - -2.9988974e-01 9.2593041e-01 5.2483040e+00 - -2.5757094e-01 8.7717255e-01 5.3076185e+00 - -1.8227556e-01 7.8816484e-01 5.1622601e+00 - -1.3903628e-01 7.3872576e-01 5.2089869e+00 - -9.4926057e-02 6.8717813e-01 5.2547110e+00 - -8.2792014e-02 6.7325907e-01 5.5544917e+00 - 1.8857628e-02 5.5404475e-01 5.1361223e+00 - 6.7569444e-02 4.9805291e-01 5.1383834e+00 - 1.1802563e-01 4.3941099e-01 5.1096260e+00 - 1.8110470e-01 3.6602872e-01 4.9207194e+00 - 2.2510170e-01 3.1460777e-01 4.9284911e+00 - 2.6827809e-01 2.6466616e-01 4.9650305e+00 - 3.0007348e-01 2.2774173e-01 5.2698296e+00 - 3.4861595e-01 1.6988089e-01 5.2544620e+00 - 3.6973238e-01 1.4414868e-01 6.3971089e+00 - 4.3300934e-01 7.0800559e-02 6.2696753e+00 - -1.2977489e+00 2.2245863e+00 -8.9480210e-01 - -1.3601647e+00 2.3019364e+00 -8.8761926e-01 - -1.4235006e+00 2.3804868e+00 -8.7758637e-01 - -1.4878162e+00 2.4592454e+00 -8.6455400e-01 - -1.5838135e+00 2.5787156e+00 -8.7816492e-01 - -1.6536209e+00 2.6659357e+00 -8.6301295e-01 - -1.7188724e+00 2.7452524e+00 -8.3988986e-01 - -1.8064775e+00 2.8532645e+00 -8.3166107e-01 - -1.8995881e+00 2.9696298e+00 -8.2350997e-01 - -1.9881365e+00 3.0781408e+00 -8.0638898e-01 - -2.0821885e+00 3.1950198e+00 -7.8904605e-01 - -2.2005635e+00 3.3409319e+00 -7.8219649e-01 - -2.2021488e+00 3.3433058e+00 -6.9599735e-01 - -2.4259677e+00 3.6202725e+00 -7.4352147e-01 - -2.6227202e+00 3.8629249e+00 -7.6238654e-01 - -2.8081783e+00 4.0926847e+00 -7.6456548e-01 - -2.9955108e+00 4.3240550e+00 -7.5679995e-01 - -3.1827829e+00 4.5559081e+00 -7.3924650e-01 - -3.3830940e+00 4.8038181e+00 -7.1719820e-01 - -3.6692161e+00 5.1580033e+00 -7.1968701e-01 - -4.0840357e+00 5.6717542e+00 -7.5588531e-01 - -4.5940142e+00 6.3020915e+00 -8.0215326e-01 - -5.1728592e+00 7.0191302e+00 -8.4256095e-01 - -5.8785910e+00 7.8910361e+00 -8.8792236e-01 - -6.6485220e+00 8.8431459e+00 -9.1121216e-01 - -7.8687769e+00 1.0352867e+01 -9.9917739e-01 - -9.1914055e+00 1.1989426e+01 -1.0410035e+00 - -1.0748863e+01 1.3915534e+01 -1.0520091e+00 - -1.2015139e+01 1.5481523e+01 -9.3160578e-01 - -1.2428986e+01 1.5993759e+01 -6.3382354e-01 - -1.2853078e+01 1.6517694e+01 -3.1492845e-01 - -1.3343268e+01 1.7123765e+01 2.2250057e-02 - -1.5363020e+01 1.9621773e+01 3.2039994e-01 - -1.5532331e+01 1.9830307e+01 7.5841012e-01 - -1.5513283e+01 1.9807127e+01 1.2031832e+00 - -1.5716078e+01 2.0057542e+01 1.6560549e+00 - -1.7610139e+01 2.2399461e+01 2.2358673e+00 - -1.5674422e+01 2.0003360e+01 2.5539749e+00 - -1.7648285e+01 2.2444132e+01 3.2497522e+00 - -1.7652408e+01 2.2448572e+01 3.7578856e+00 - -1.7644344e+01 2.2439221e+01 4.2657229e+00 - -1.7643822e+01 2.2437500e+01 4.7766347e+00 - -2.6918170e+00 3.9460671e+00 1.7548480e+00 - -2.6710865e+00 3.9199591e+00 1.8400115e+00 - -2.6801291e+00 3.9311616e+00 1.9333305e+00 - -2.6817389e+00 3.9328243e+00 2.0253720e+00 - -2.6945112e+00 3.9484338e+00 2.1221010e+00 - -2.5526504e+00 3.7743207e+00 2.1616533e+00 - -2.5403626e+00 3.7577194e+00 2.2461997e+00 - -2.5437868e+00 3.7625037e+00 2.3382987e+00 - -2.5649095e+00 3.7888732e+00 2.4395546e+00 - -2.5665088e+00 3.7906196e+00 2.5332941e+00 - -2.5495307e+00 3.7687362e+00 2.6181722e+00 - -3.3913439e+00 4.8097090e+00 3.1854760e+00 - -3.3723885e+00 4.7860046e+00 3.2966641e+00 - -3.3645826e+00 4.7763507e+00 3.4146371e+00 - -3.3670418e+00 4.7787470e+00 3.5405896e+00 - -3.3899050e+00 4.8072820e+00 3.6833007e+00 - -3.4062782e+00 4.8272950e+00 3.8238891e+00 - -3.4198277e+00 4.8442146e+00 3.9662146e+00 - -3.4426889e+00 4.8722503e+00 4.1190628e+00 - -3.4702575e+00 4.9049159e+00 4.2786202e+00 - -3.4828062e+00 4.9212807e+00 4.4311795e+00 - -5.9969717e+00 8.0281353e+00 6.8326756e+00 - -1.8274553e+00 2.8751197e+00 3.1749333e+00 - -1.7602889e+00 2.7919371e+00 3.1974451e+00 - -1.7144547e+00 2.7360295e+00 3.2382673e+00 - -1.6640980e+00 2.6724665e+00 3.2718298e+00 - -1.6229405e+00 2.6219494e+00 3.3145176e+00 - -1.5772010e+00 2.5647689e+00 3.3497962e+00 - -1.5350657e+00 2.5140288e+00 3.3891848e+00 - -1.5042379e+00 2.4745304e+00 3.4392024e+00 - -1.4621807e+00 2.4226504e+00 3.4757442e+00 - -1.4247222e+00 2.3773008e+00 3.5169984e+00 - -1.3873319e+00 2.3308901e+00 3.5570038e+00 - -1.3499503e+00 2.2844104e+00 3.5956108e+00 - -1.3162847e+00 2.2424461e+00 3.6398253e+00 - -1.2826259e+00 2.2004277e+00 3.6829411e+00 - -1.2526211e+00 2.1639363e+00 3.7319143e+00 - -1.2180373e+00 2.1207569e+00 3.7729791e+00 - -1.1834609e+00 2.0775185e+00 3.8128453e+00 - -1.1442478e+00 2.0285693e+00 3.8443540e+00 - -1.1170333e+00 1.9954373e+00 3.8969835e+00 - -1.0806008e+00 1.9499264e+00 3.9337464e+00 - -1.0524589e+00 1.9156533e+00 3.9847243e+00 - -1.0623423e+00 1.9276585e+00 4.1133525e+00 - -1.0814467e+00 1.9515039e+00 4.2671852e+00 - -1.4877481e+00 2.4526125e+00 5.2584244e+00 - -1.4521143e+00 2.4082392e+00 5.3372882e+00 - -1.3359061e+00 2.2646970e+00 5.2342165e+00 - -8.1614128e-01 1.6237702e+00 4.1509527e+00 - -1.2933473e+00 2.2111522e+00 5.4598705e+00 - -1.9847583e+00 3.0648237e+00 7.4263005e+00 - -7.9375498e-01 1.5956360e+00 4.4799065e+00 - -7.5921351e-01 1.5516026e+00 4.5239172e+00 - -1.3040626e+00 2.2236011e+00 6.2624131e+00 - -5.5874266e-01 1.3046685e+00 4.2189710e+00 - -1.1817111e+00 2.0726770e+00 6.3411915e+00 - -6.7972302e-01 1.4539570e+00 4.9162218e+00 - -6.3217997e-01 1.3945994e+00 4.9300701e+00 - -5.7813436e-01 1.3278516e+00 4.9242182e+00 - -5.5172431e-01 1.2958130e+00 5.0180496e+00 - -7.2530623e-01 1.5086473e+00 5.9208475e+00 - -2.7925423e+00 4.0544893e+00 1.4934083e+01 - -4.3112274e-01 1.1459473e+00 5.1563601e+00 - -3.8356858e-01 1.0866784e+00 5.1720062e+00 - -3.2769846e-01 1.0179211e+00 5.1481198e+00 - -2.8110013e-01 9.5956671e-01 5.1608231e+00 - -2.5366973e-01 9.2609765e-01 5.2876594e+00 - -1.9425435e-01 8.5146019e-01 5.2304998e+00 - -1.2922442e-01 7.7243632e-01 5.1322710e+00 - -7.4402182e-02 7.0437351e-01 5.0807227e+00 - -8.6105894e-02 7.1872297e-01 5.5368505e+00 - -1.4842421e-02 6.3067495e-01 5.3655377e+00 - 5.6343586e-02 5.4303935e-01 5.1620654e+00 - 9.3926174e-02 4.9661848e-01 5.2626448e+00 - 1.6934264e-01 4.0312011e-01 4.9261713e+00 - 2.0503473e-01 3.5818168e-01 5.0340983e+00 - 2.5784937e-01 2.9375989e-01 4.9120961e+00 - 2.8921484e-01 2.5391566e-01 5.1374437e+00 - 3.3582489e-01 1.9720224e-01 5.1226322e+00 - 3.7799261e-01 1.4414267e-01 5.2163018e+00 - 4.0617100e-01 1.0848514e-01 6.2485581e+00 - 4.6519802e-01 3.5385841e-02 6.0402386e+00 - -1.5497817e+00 2.6940129e+00 -8.7825523e-01 - -1.6175202e+00 2.7822076e+00 -8.6116164e-01 - -1.7009607e+00 2.8928998e+00 -8.5449249e-01 - -1.7853722e+00 3.0038693e+00 -8.4342559e-01 - -1.8762866e+00 3.1232572e+00 -8.3233332e-01 - -1.9616420e+00 3.2347207e+00 -8.1247410e-01 - -2.0692079e+00 3.3770558e+00 -8.0391284e-01 - -2.1666202e+00 3.5043876e+00 -7.8215873e-01 - -2.1793701e+00 3.5212077e+00 -7.0140921e-01 - -2.3055449e+00 3.6869213e+00 -6.8908037e-01 - -2.3684823e+00 3.7696875e+00 -6.3410220e-01 - -2.8060414e+00 4.3436914e+00 -7.7726074e-01 - -2.9925099e+00 4.5891866e+00 -7.6679309e-01 - -3.1966604e+00 4.8569141e+00 -7.5430928e-01 - -3.4601861e+00 5.2037273e+00 -7.5657392e-01 - -3.7896935e+00 5.6361836e+00 -7.7076589e-01 - -4.2203185e+00 6.2031513e+00 -8.0488604e-01 - -4.7364512e+00 6.8803655e+00 -8.4381650e-01 - -5.4391823e+00 7.8030686e+00 -9.1292833e-01 - -6.1622065e+00 8.7527971e+00 -9.4730369e-01 - -7.0847154e+00 9.9658073e+00 -9.9243361e-01 - -8.2318322e+00 1.1473288e+01 -1.0365853e+00 - -9.7251526e+00 1.3434785e+01 -1.0850761e+00 - -1.1269266e+01 1.5463365e+01 -1.0564637e+00 - -1.1657294e+01 1.5972446e+01 -7.7059990e-01 - -1.2055451e+01 1.6495186e+01 -4.6442149e-01 - -1.2504587e+01 1.7085068e+01 -1.4071512e-01 - -1.2871992e+01 1.7567194e+01 2.1313341e-01 - -1.5948418e+01 2.1608284e+01 5.0626825e-01 - -1.6048182e+01 2.1739169e+01 9.8011939e-01 - -1.6706598e+01 2.2602977e+01 1.4751318e+00 - -1.6705170e+01 2.2600461e+01 1.9711587e+00 - -1.6728741e+01 2.2631682e+01 2.4697809e+00 - -1.6734736e+01 2.2638790e+01 2.9687831e+00 - -1.6766712e+01 2.2679813e+01 3.4727807e+00 - -1.0213096e+01 1.4070881e+01 2.8458418e+00 - -8.4184825e+00 1.1713205e+01 2.7968735e+00 - -8.3620820e+00 1.1638887e+01 3.0451935e+00 - -2.5053808e+00 3.9461922e+00 1.7821261e+00 - -2.4902792e+00 3.9264187e+00 1.8668116e+00 - -2.4872872e+00 3.9215756e+00 1.9546401e+00 - -2.5296533e+00 3.9774768e+00 2.0591761e+00 - -2.6249005e+00 4.1019097e+00 2.1866901e+00 - -2.3826793e+00 3.7841405e+00 2.1823471e+00 - -2.4056702e+00 3.8150505e+00 2.5543248e+00 - -5.3007677e+00 7.6148697e+00 4.2881053e+00 - -3.4251209e+00 5.1530484e+00 3.3521744e+00 - -3.3775405e+00 5.0898635e+00 3.4505153e+00 - -3.3224947e+00 5.0179139e+00 3.5430348e+00 - -3.3008324e+00 4.9891519e+00 3.6566585e+00 - -3.2838363e+00 4.9658641e+00 3.7738455e+00 - -3.2750475e+00 4.9555124e+00 3.8991559e+00 - -3.2719754e+00 4.9497625e+00 4.0293809e+00 - -3.2715640e+00 4.9494398e+00 4.1646611e+00 - -3.2860021e+00 4.9678110e+00 4.3149303e+00 - -3.2975557e+00 4.9840906e+00 4.4669871e+00 - -3.3082820e+00 4.9973978e+00 4.6207873e+00 - -3.3365055e+00 5.0349296e+00 4.7967292e+00 - -3.4046493e+00 5.1222490e+00 5.0177199e+00 - -3.4328591e+00 5.1593750e+00 5.2056966e+00 - -1.6026026e+00 2.7581696e+00 3.3353066e+00 - -1.5579700e+00 2.6991493e+00 3.3725852e+00 - -1.5327739e+00 2.6654467e+00 3.4314629e+00 - -1.5888609e+00 2.7399926e+00 3.5917337e+00 - -1.7041371e+00 2.8914982e+00 3.8359814e+00 - -1.8157383e+00 3.0371300e+00 4.0876049e+00 - -1.6989271e+00 2.8841800e+00 4.0381592e+00 - -1.4426662e+00 2.5469184e+00 3.7797765e+00 - -1.3185728e+00 2.3837405e+00 3.6948461e+00 - -1.2535581e+00 2.2994373e+00 3.6921954e+00 - -1.2163732e+00 2.2498387e+00 3.7283543e+00 - -1.1791360e+00 2.2011730e+00 3.7631653e+00 - -1.1409696e+00 2.1513809e+00 3.7966244e+00 - -1.1028714e+00 2.1005278e+00 3.8288346e+00 - -1.0647209e+00 2.0506076e+00 3.8596969e+00 - -1.0265791e+00 2.0006185e+00 3.8891609e+00 - -9.9115090e-01 1.9551187e+00 3.9249282e+00 - -9.6049091e-01 1.9132471e+00 3.9673545e+00 - -9.2507562e-01 1.8676439e+00 4.0010244e+00 - -8.9713041e-01 1.8302518e+00 4.0495542e+00 - -8.6455157e-01 1.7871244e+00 4.0892270e+00 - -8.4948074e-01 1.7671046e+00 4.1689187e+00 - -7.9471360e-01 1.6960228e+00 4.1574689e+00 - -7.9163140e-01 1.6913849e+00 4.2697169e+00 - -7.2126359e-01 1.5990590e+00 4.2130618e+00 - -7.0621414e-01 1.5783526e+00 4.2990953e+00 - -3.0796182e+00 4.6885764e+00 1.1197804e+01 - -5.9130681e-01 1.4278099e+00 4.2352249e+00 - -6.1389157e-01 1.4575385e+00 4.4426554e+00 - -1.1430642e+00 2.1505442e+00 6.2999661e+00 - -1.0873051e+00 2.0762580e+00 6.3463394e+00 - -6.2628293e-01 1.4733983e+00 4.9686992e+00 - -5.6237985e-01 1.3897964e+00 4.9182619e+00 - -5.3702572e-01 1.3568410e+00 5.0125455e+00 - -6.9517583e-01 1.5628548e+00 5.8574128e+00 - -4.7172852e-01 1.2696381e+00 5.1537133e+00 - -3.8406313e-01 1.1545861e+00 4.9837314e+00 - -3.6142831e-01 1.1250425e+00 5.1029945e+00 - -3.2138761e-01 1.0726067e+00 5.1460842e+00 - -2.7402788e-01 1.0107527e+00 5.1498442e+00 - -2.6687312e-01 1.0008383e+00 5.3828760e+00 - -2.3499057e-01 9.5915223e-01 5.4910666e+00 - -1.1472322e-01 8.0188812e-01 5.0361120e+00 - -7.5721379e-02 7.4918759e-01 5.0726129e+00 - -2.2902256e-02 6.8119150e-01 5.0199724e+00 - -2.3717832e-02 6.8094896e-01 5.3975550e+00 - 6.5194862e-02 5.6443207e-01 5.0179792e+00 - 1.0885316e-01 5.0772581e-01 5.0199062e+00 - 1.5688595e-01 4.4372910e-01 4.9611906e+00 - 2.0052679e-01 3.8739903e-01 4.9504835e+00 - 2.4228597e-01 3.3210623e-01 4.9583599e+00 - 2.7884613e-01 2.8452047e-01 5.0746223e+00 - 3.1890449e-01 2.3119434e-01 5.1401835e+00 - 3.5826780e-01 1.7931942e-01 5.2744621e+00 - 4.1274364e-01 1.0818762e-01 4.8580171e+00 - 4.3955244e-01 7.1986294e-02 6.0996668e+00 - -1.8402756e+00 3.2713900e+00 -8.3535717e-01 - -1.9269699e+00 3.3939014e+00 -8.1683564e-01 - -2.0313396e+00 3.5392136e+00 -8.0503677e-01 - -2.1254968e+00 3.6705095e+00 -7.8029434e-01 - -2.1428246e+00 3.6945415e+00 -7.0127404e-01 - -2.1813745e+00 3.7493060e+00 -6.3515292e-01 - -2.2089246e+00 3.7867614e+00 -5.6083673e-01 - -2.2132543e+00 3.7933783e+00 -4.7332810e-01 - -2.2111854e+00 3.7897109e+00 -3.8314895e-01 - -2.2137044e+00 3.7931767e+00 -2.9629704e-01 - -2.2152873e+00 3.7955702e+00 -2.0969840e-01 - -2.2159949e+00 3.7958897e+00 -1.2340334e-01 - -2.2212853e+00 3.8033817e+00 -3.9636513e-02 - -2.2201207e+00 3.8015568e+00 4.6152026e-02 - -2.2235371e+00 3.8069192e+00 1.2971196e-01 - -2.2205618e+00 3.8019432e+00 2.1484378e-01 - -2.2286778e+00 3.8125138e+00 2.9657383e-01 - -2.2348571e+00 3.8219715e+00 3.7844696e-01 - -2.2300716e+00 3.8138393e+00 4.6282217e-01 - -2.2408847e+00 3.8295465e+00 5.4371476e-01 - -2.2387386e+00 3.8275281e+00 6.2680345e-01 - -2.2422245e+00 3.8318197e+00 7.0891478e-01 - -2.2447712e+00 3.8350637e+00 7.9127224e-01 - -2.2408137e+00 3.8298991e+00 8.7380408e-01 - -2.2535556e+00 3.8467832e+00 9.5585200e-01 - -2.2597908e+00 3.8552785e+00 1.0384738e+00 - -2.2641488e+00 3.8616687e+00 1.1213881e+00 - -2.2509391e+00 3.8438820e+00 1.2033841e+00 - -2.2719810e+00 3.8724442e+00 1.2883114e+00 - -2.2690187e+00 3.8673647e+00 1.3713458e+00 - -2.2816166e+00 3.8864300e+00 1.4570899e+00 - -9.7191683e+00 1.4278821e+01 2.9881275e+00 - -7.9497184e+00 1.1805411e+01 2.9008690e+00 - -8.4012369e+00 1.2436037e+01 3.2745444e+00 - -2.3434774e+00 3.9710948e+00 1.8139403e+00 - -2.3459847e+00 3.9746541e+00 1.9026898e+00 - -2.3419988e+00 3.9697161e+00 1.9898160e+00 - -2.3768171e+00 4.0180269e+00 2.0920766e+00 - -2.3885992e+00 4.0335120e+00 2.1875041e+00 - -5.1516654e+00 7.8922618e+00 4.6216311e+00 - -3.5590076e+00 5.6679209e+00 3.7405125e+00 - -3.5576877e+00 5.6657902e+00 3.8808824e+00 - -3.6291266e+00 5.7661461e+00 4.0776213e+00 - -3.2638063e+00 5.2547752e+00 3.9400932e+00 - -3.2127372e+00 5.1831955e+00 4.0352222e+00 - -3.1865577e+00 5.1462196e+00 4.1505248e+00 - -3.1695812e+00 5.1222600e+00 4.2743532e+00 - -3.1562661e+00 5.1037684e+00 4.4028407e+00 - -3.1568023e+00 5.1039102e+00 4.5463139e+00 - -3.1554571e+00 5.1019815e+00 4.6907789e+00 - -3.1715502e+00 5.1252644e+00 4.8571362e+00 - -3.2254462e+00 5.2002130e+00 5.0685367e+00 - -1.7510361e+00 3.1410670e+00 3.5531261e+00 - -1.7387514e+00 3.1244411e+00 3.6371731e+00 - -1.7164057e+00 3.0925869e+00 3.7095940e+00 - -1.7685797e+00 3.1652222e+00 3.8765431e+00 - -1.5124796e+00 2.8072925e+00 3.6461142e+00 - -1.7137229e+00 3.0876372e+00 4.0169004e+00 - -1.7630023e+00 3.1577457e+00 4.1970724e+00 - -1.7351432e+00 3.1176024e+00 4.2708694e+00 - -1.6970561e+00 3.0651133e+00 4.3306943e+00 - -4.6842843e+00 7.2330721e+00 9.1416010e+00 - -3.9921341e+00 6.2660006e+00 8.3051470e+00 - -3.9545649e+00 6.2143153e+00 8.5016041e+00 - -1.4833669e+00 2.7656059e+00 4.4572890e+00 - -1.1751986e+00 2.3352266e+00 4.0231572e+00 - -1.0691960e+00 2.1879200e+00 3.9328497e+00 - -1.0046567e+00 2.0967236e+00 3.9120191e+00 - -9.6663659e-01 2.0447307e+00 3.9413825e+00 - -9.2597978e-01 1.9871184e+00 3.9617954e+00 - -8.8797754e-01 1.9349826e+00 3.9882623e+00 - -8.5104109e-01 1.8818512e+00 4.0135835e+00 - -8.1945918e-01 1.8387941e+00 4.0534593e+00 - -7.8518037e-01 1.7911145e+00 4.0843350e+00 - -7.5737040e-01 1.7516103e+00 4.1305669e+00 - -7.0566723e-01 1.6796390e+00 4.1176781e+00 - -6.9889119e-01 1.6703084e+00 4.2207231e+00 - -6.9029701e-01 1.6578857e+00 4.3243099e+00 - -1.1608216e+00 2.3124984e+00 5.8235089e+00 - -1.1171897e+00 2.2519715e+00 5.8898036e+00 - -7.0741899e-01 1.6807688e+00 4.8042800e+00 - -6.6396560e-01 1.6198464e+00 4.8220355e+00 - -5.9024656e-01 1.5180270e+00 4.7398961e+00 - -5.5784509e-01 1.4714193e+00 4.7900544e+00 - -4.9424269e-01 1.3833516e+00 4.7301272e+00 - -5.0109444e-01 1.3918623e+00 4.9334009e+00 - -5.1057878e-01 1.4049936e+00 5.1658992e+00 - -4.3791175e-01 1.3033203e+00 5.0652362e+00 - -3.7622346e-01 1.2170620e+00 4.9990239e+00 - -3.1900213e-01 1.1389025e+00 4.9490602e+00 - -3.3482380e-01 1.1591971e+00 5.2574383e+00 - -2.8945342e-01 1.0970040e+00 5.2721408e+00 - -2.4784490e-01 1.0379286e+00 5.3046348e+00 - -2.0436747e-01 9.7719826e-01 5.3262855e+00 - -1.9715313e-01 9.6672856e-01 5.5885803e+00 - -7.3987092e-02 7.9480743e-01 5.0642444e+00 - -4.7755047e-02 7.5773617e-01 5.1978739e+00 - -4.3001493e-02 7.5222849e-01 5.5368340e+00 - 4.2807347e-02 6.3244039e-01 5.1885770e+00 - 1.0319293e-01 5.4690342e-01 5.0142038e+00 - 1.4297633e-01 4.9137997e-01 5.0352200e+00 - 1.8100054e-01 4.3838834e-01 5.0848575e+00 - 2.2614920e-01 3.7545487e-01 5.0440294e+00 - 2.6416005e-01 3.2184073e-01 5.1013071e+00 - 2.9884779e-01 2.7381881e-01 5.2670636e+00 - 3.5347298e-01 1.9872315e-01 4.9728637e+00 - 3.9152411e-01 1.4491510e-01 5.0464709e+00 - 4.1421123e-01 1.1153469e-01 6.1985966e+00 - 4.6818945e-01 3.6727190e-02 6.0103172e+00 - -2.0998956e+00 3.8691184e+00 -6.0782439e-01 - -2.1052216e+00 3.8758106e+00 -5.2001295e-01 - -2.1030901e+00 3.8731598e+00 -4.2948383e-01 - -2.1010231e+00 3.8694776e+00 -3.3960431e-01 - -2.0970237e+00 3.8646480e+00 -2.5028085e-01 - -2.1042490e+00 3.8732678e+00 -1.6635747e-01 - -2.0984407e+00 3.8652722e+00 -7.7990364e-02 - -2.0982147e+00 3.8644998e+00 7.6519282e-03 - -2.0961158e+00 3.8615879e+00 9.2887578e-02 - -2.0940803e+00 3.8576545e+00 1.7767339e-01 - -2.0956264e+00 3.8608578e+00 2.6042718e-01 - -2.0972333e+00 3.8630592e+00 3.4313063e-01 - -2.0979034e+00 3.8641933e+00 4.2568071e-01 - -2.0976978e+00 3.8632583e+00 5.0802707e-01 - -2.0910450e+00 3.8529423e+00 5.9109675e-01 - -2.0944762e+00 3.8581865e+00 6.7225964e-01 - -2.0914616e+00 3.8540399e+00 7.5394610e-01 - -2.0940164e+00 3.8572199e+00 8.3500516e-01 - -2.1001410e+00 3.8676302e+00 9.1592985e-01 - -2.0953740e+00 3.8593502e+00 9.9730876e-01 - -2.1006197e+00 3.8677160e+00 1.0785291e+00 - -2.0994822e+00 3.8656743e+00 1.1599231e+00 - -2.0974080e+00 3.8625654e+00 1.2411637e+00 - -2.0953946e+00 3.8584546e+00 1.3223539e+00 - -2.0969463e+00 3.8616135e+00 1.4042088e+00 - -2.0986165e+00 3.8627933e+00 1.4864624e+00 - -2.0992879e+00 3.8639176e+00 1.5688128e+00 - -2.0980828e+00 3.8629320e+00 1.6513557e+00 - -2.0969373e+00 3.8609544e+00 1.7340481e+00 - -2.1013457e+00 3.8664265e+00 1.8186099e+00 - -2.0983225e+00 3.8623489e+00 1.9016947e+00 - -2.0944215e+00 3.8562169e+00 1.9848753e+00 - -2.0950739e+00 3.8574939e+00 2.0703218e+00 - -2.1233898e+00 3.8974675e+00 2.7998268e+00 - -2.1102193e+00 3.8788513e+00 2.8852681e+00 - -2.1228218e+00 3.8968489e+00 2.9898882e+00 - -2.1280001e+00 3.9052376e+00 3.0918325e+00 - -2.1277535e+00 3.9041136e+00 3.1906082e+00 - -2.1311068e+00 3.9094644e+00 3.2941930e+00 - -2.1335769e+00 3.9128052e+00 3.3987727e+00 - -2.1341667e+00 3.9140657e+00 3.5041442e+00 - -2.1440080e+00 3.9274391e+00 3.6199889e+00 - -2.1372375e+00 3.9180642e+00 3.7221350e+00 - -1.5890340e+00 3.1028497e+00 3.2434282e+00 - -1.5566675e+00 3.0554469e+00 3.2977310e+00 - -1.5344953e+00 3.0211751e+00 3.3616616e+00 - -1.5946439e+00 3.1111845e+00 3.5253999e+00 - -1.5513430e+00 3.0464646e+00 3.5674734e+00 - -1.7607024e+00 3.3583095e+00 3.9365556e+00 - -1.7504113e+00 3.3413101e+00 4.0308460e+00 - -1.6054197e+00 3.1264591e+00 3.9407261e+00 - -1.4549901e+00 2.9032322e+00 3.8299598e+00 - -1.5819501e+00 3.0909075e+00 4.1217562e+00 - -1.5340444e+00 3.0197066e+00 4.1601160e+00 - -1.4449746e+00 2.8874254e+00 4.1295463e+00 - -3.8704697e+00 6.4893843e+00 8.2855673e+00 - -1.4352105e+00 2.8721890e+00 4.3393956e+00 - -1.4303312e+00 2.8642915e+00 4.4487895e+00 - -1.4774262e+00 2.9357818e+00 4.6594175e+00 - -3.3061295e+00 5.6502896e+00 8.2945390e+00 - -3.2762242e+00 5.6042352e+00 8.4940697e+00 - -3.2315156e+00 5.5391174e+00 8.6711206e+00 - -8.6391513e-01 2.0225306e+00 3.9020944e+00 - -9.0928926e-01 2.0896363e+00 4.1073212e+00 - -8.3039449e-01 1.9732192e+00 4.0404879e+00 - -7.8717601e-01 1.9088724e+00 4.0496029e+00 - -7.5401149e-01 1.8592938e+00 4.0812801e+00 - -7.1715436e-01 1.8050127e+00 4.1035546e+00 - -6.8400525e-01 1.7553111e+00 4.1327349e+00 - -6.5362375e-01 1.7091511e+00 4.1692668e+00 - -6.2495084e-01 1.6674743e+00 4.2131976e+00 - -5.9088351e-01 1.6165575e+00 4.2392282e+00 - -5.7049986e-01 1.5856143e+00 4.3074111e+00 - -5.4918071e-01 1.5535939e+00 4.3752409e+00 - -6.2609282e-01 1.6685345e+00 4.7780491e+00 - -5.8200525e-01 1.6020643e+00 4.7858617e+00 - -5.2056072e-01 1.5112794e+00 4.7291857e+00 - -4.7185944e-01 1.4394303e+00 4.7151079e+00 - -4.7689202e-01 1.4453729e+00 4.9092856e+00 - -4.2093358e-01 1.3625798e+00 4.8654656e+00 - -4.3399667e-01 1.3818393e+00 5.1160063e+00 - -3.8532355e-01 1.3092494e+00 5.1071716e+00 - -3.1491447e-01 1.2045748e+00 4.9837423e+00 - -3.1426286e-01 1.2035930e+00 5.2069620e+00 - -2.6655482e-01 1.1318438e+00 5.1936864e+00 - -2.2506448e-01 1.0713083e+00 5.2168415e+00 - -2.1164167e-01 1.0510983e+00 5.4117949e+00 - -2.1262513e-01 1.0515772e+00 5.7229612e+00 - -1.0890120e-01 8.9874016e-01 5.3369755e+00 - -6.2176731e-02 8.2768376e-01 5.3162627e+00 - -1.8050897e-01 1.0025606e+00 6.6728497e+00 - 3.7744977e-02 6.8000573e-01 5.2110926e+00 - 1.0152271e-01 5.8633367e-01 4.9982518e+00 - 1.3919303e-01 5.2896676e-01 5.0199727e+00 - 1.8580182e-01 4.5956467e-01 4.9314955e+00 - 2.1656741e-01 4.1492673e-01 5.0596631e+00 - 2.5959292e-01 3.5058512e-01 5.0081042e+00 - 2.8603454e-01 3.1054695e-01 5.2639292e+00 - 3.3254676e-01 2.4140455e-01 5.1401963e+00 - 3.7379625e-01 1.7997588e-01 5.1047247e+00 - 4.1753471e-01 1.1587327e-01 4.9579321e+00 - 4.4285214e-01 7.5791007e-02 6.1196837e+00 - -2.9260904e+00 5.4388085e+00 -7.8628521e-01 - -3.1893474e+00 5.8565339e+00 -7.9435233e-01 - -3.5110963e+00 6.3676224e+00 -8.1136962e-01 - -3.8968811e+00 6.9796027e+00 -8.3386953e-01 - -4.4984976e+00 7.9347837e+00 -9.1371811e-01 - -5.0651925e+00 8.8352591e+00 -9.4182296e-01 - -5.7874261e+00 9.9802804e+00 -9.8133107e-01 - -6.6064474e+00 1.1279587e+01 -1.0009191e+00 - -7.8706592e+00 1.3287034e+01 -1.0775209e+00 - -9.3449743e+00 1.5628018e+01 -1.1164134e+00 - -9.7875725e+00 1.6329970e+01 -8.7096519e-01 - -2.0574983e+00 4.0579700e+00 6.1982420e-01 - -2.0389391e+00 4.0290363e+00 7.0604160e-01 - -2.0304652e+00 4.0156529e+00 7.9015246e-01 - -2.0220564e+00 4.0012332e+00 8.7351386e-01 - -2.0172211e+00 3.9940142e+00 9.5614162e-01 - -1.9959957e+00 3.9596976e+00 1.0382027e+00 - -2.0002997e+00 3.9670356e+00 1.1200687e+00 - -1.9991598e+00 3.9650136e+00 1.2018621e+00 - -2.0026438e+00 3.9693200e+00 1.2842731e+00 - -1.9996286e+00 3.9651783e+00 1.3660594e+00 - -2.0012355e+00 3.9673797e+00 1.4487629e+00 - -1.9964059e+00 3.9601164e+00 1.5304918e+00 - -2.0016330e+00 3.9686300e+00 1.6147084e+00 - -1.9959865e+00 3.9583104e+00 1.6964829e+00 - -1.9938397e+00 3.9562970e+00 1.7796714e+00 - -1.9918134e+00 3.9522896e+00 1.8629591e+00 - -1.9943416e+00 3.9556814e+00 1.9483129e+00 - -1.9904984e+00 3.9485722e+00 2.0319426e+00 - -1.9806484e+00 3.9320453e+00 2.9222942e+00 - -1.9967949e+00 3.9574802e+00 3.0309747e+00 - -1.9919515e+00 3.9498111e+00 3.1247383e+00 - -1.9861689e+00 3.9410945e+00 3.2187481e+00 - -1.9895849e+00 3.9454286e+00 3.3219829e+00 - -1.9865208e+00 3.9411620e+00 3.4214970e+00 - -1.9826367e+00 3.9338638e+00 3.5215560e+00 - -1.9813513e+00 3.9330045e+00 3.6269204e+00 - -1.9801826e+00 3.9301809e+00 3.7329831e+00 - -1.5079066e+00 3.1821176e+00 3.3021952e+00 - -1.4411409e+00 3.0763504e+00 3.3138087e+00 - -1.5448154e+00 3.2388655e+00 3.5313095e+00 - -1.9870858e+00 3.9406443e+00 4.1974831e+00 - -1.8701878e+00 3.7552946e+00 4.1622506e+00 - -1.5958614e+00 3.3194835e+00 3.9006079e+00 - -1.2968888e+00 2.8471226e+00 3.5793403e+00 - -1.1974356e+00 2.6889968e+00 3.5257515e+00 - -1.1663224e+00 2.6380675e+00 3.5681211e+00 - -1.1413980e+00 2.6001308e+00 3.6222032e+00 - -2.0090529e+00 3.9743626e+00 5.1519345e+00 - -1.0053410e+00 2.3841517e+00 3.5792521e+00 - -9.6604001e-01 2.3206476e+00 3.6005647e+00 - -2.0005098e+00 3.9597697e+00 5.5952476e+00 - -1.2945773e+00 2.8413547e+00 4.4146405e+00 - -2.0096372e+00 3.9726589e+00 5.9443995e+00 - -2.0136719e+00 3.9790552e+00 6.1287366e+00 - -8.6472942e-01 2.1590121e+00 3.8822509e+00 - -1.2922636e+00 2.8363345e+00 4.9218992e+00 - -1.1973776e+00 2.6865376e+00 4.8487040e+00 - -2.0332672e+00 4.0091634e+00 6.9528906e+00 - -2.0389408e+00 4.0190523e+00 7.1853250e+00 - -7.6055424e-01 1.9940941e+00 4.1821036e+00 - -7.1852137e-01 1.9267626e+00 4.1902717e+00 - -6.5459410e-01 1.8270652e+00 4.1389261e+00 - -6.1986484e-01 1.7708225e+00 4.1595083e+00 - -5.8784481e-01 1.7191036e+00 4.1870930e+00 - -5.4667323e-01 1.6544736e+00 4.1880244e+00 - -5.1636982e-01 1.6071738e+00 4.2217095e+00 - -4.8883216e-01 1.5634305e+00 4.2630458e+00 - -4.7403407e-01 1.5386525e+00 4.3475796e+00 - -4.7994744e-01 1.5481722e+00 4.5117495e+00 - -5.0386595e-01 1.5869268e+00 4.7578912e+00 - -4.5105985e-01 1.5015064e+00 4.7179248e+00 - -4.2530047e-01 1.4601422e+00 4.7847864e+00 - -4.3924273e-01 1.4819604e+00 5.0251939e+00 - -5.5683202e-01 1.6688770e+00 5.7571127e+00 - -4.3802992e-01 1.4803058e+00 5.4373763e+00 - -2.9675243e-01 1.2570060e+00 4.9709314e+00 - -2.6732615e-01 1.2102182e+00 5.0340329e+00 - -2.4874710e-01 1.1793807e+00 5.1626963e+00 - -2.1294303e-01 1.1231742e+00 5.2054975e+00 - -1.7175768e-01 1.0581385e+00 5.2184637e+00 - -1.7274523e-01 1.0596161e+00 5.5093558e+00 - -1.3063160e-01 9.9292999e-01 5.5306078e+00 - -5.9962759e-02 8.8023125e-01 5.3267731e+00 - -1.9686996e-02 8.1647957e-01 5.3442873e+00 - 7.2417057e-03 7.7384403e-01 5.4878989e+00 - 1.0085003e-01 6.2569853e-01 4.9821968e+00 - 1.3840156e-01 5.6686664e-01 4.9944789e+00 - 1.6530560e-01 5.2403402e-01 5.1340955e+00 - 2.1336055e-01 4.4753586e-01 5.0055095e+00 - 2.4644983e-01 3.9426161e-01 5.0838268e+00 - 2.8828934e-01 3.2796366e-01 5.0116461e+00 - 2.9753091e-01 3.1276344e-01 5.6857695e+00 - 3.6330979e-01 2.0963969e-01 5.0228269e+00 - 4.0237307e-01 1.4681449e-01 4.9565996e+00 - 4.3898789e-01 8.9049849e-02 4.9690351e+00 - 4.7018353e-01 3.7619780e-02 5.9903363e+00 - -3.2020831e+00 6.2762593e+00 -8.2098540e-01 - -3.5446986e+00 6.8565929e+00 -8.4249110e-01 - -4.0518056e+00 7.7174188e+00 -9.0975820e-01 - -4.5270703e+00 8.5225262e+00 -9.2921756e-01 - -5.0395670e+00 9.3900509e+00 -9.2879798e-01 - -5.9038435e+00 1.0854845e+01 -1.0037284e+00 - -6.8661012e+00 1.2486648e+01 -1.0463430e+00 - -8.1636772e+00 1.4686615e+01 -1.1043010e+00 - -9.1010890e+00 1.6274181e+01 -9.9770528e-01 - -9.4110282e+00 1.6799273e+01 -7.1862006e-01 - -9.7345545e+00 1.7347173e+01 -4.2095187e-01 - -1.0080739e+01 1.7933500e+01 -1.0421364e-01 - -1.3148227e+01 2.3130695e+01 5.1430923e-01 - -1.3668364e+01 2.4012899e+01 9.8242957e-01 - -1.4282116e+01 2.5051134e+01 1.4892876e+00 - -1.5280788e+01 2.6743938e+01 2.0646544e+00 - -1.5929692e+01 2.7841531e+01 2.6736307e+00 - -1.5907191e+01 2.7802968e+01 3.2368866e+00 - -8.0174560e+00 1.4432423e+01 2.4555115e+00 - -8.0284148e+00 1.4450876e+01 2.7529368e+00 - -8.2391791e+00 1.4806850e+01 3.1000264e+00 - -8.2946092e+00 1.4900355e+01 3.4205568e+00 - -7.6447050e+00 1.3798160e+01 3.5274840e+00 - -7.4060654e+00 1.3393706e+01 3.7322917e+00 - -7.2764541e+00 1.3172678e+01 3.9633671e+00 - -1.8794584e+00 4.0282182e+00 2.9823062e+00 - -3.7671719e+00 7.2241670e+00 4.7288428e+00 - -3.7838613e+00 7.2527841e+00 4.9210729e+00 - -1.9385081e+00 4.1264929e+00 3.3338622e+00 - -1.9399714e+00 4.1298422e+00 3.4398369e+00 - -1.9315365e+00 4.1151152e+00 3.5372305e+00 - -1.9222239e+00 4.0983339e+00 3.6347201e+00 - -1.9155105e+00 4.0879866e+00 3.7374152e+00 - -1.9134518e+00 4.0832072e+00 3.8455714e+00 - -1.9095140e+00 4.0763376e+00 3.9543197e+00 - -1.4727464e+00 3.3379777e+00 3.5141610e+00 - -1.9061259e+00 4.0705346e+00 4.1847689e+00 - -1.9020804e+00 4.0650413e+00 4.3011582e+00 - -1.1281037e+00 2.7528274e+00 3.3201257e+00 - -1.1151652e+00 2.7313255e+00 3.3875885e+00 - -1.0778044e+00 2.6683908e+00 3.4179962e+00 - -1.1191372e+00 2.7387385e+00 3.5722755e+00 - -1.1740512e+00 2.8314248e+00 3.7558741e+00 - -1.8990500e+00 4.0569811e+00 5.0912111e+00 - -9.4300935e-01 2.4390180e+00 3.5480262e+00 - -9.2376053e-01 2.4065273e+00 3.6038771e+00 - -1.8896183e+00 4.0409367e+00 5.5265804e+00 - -1.8773656e+00 4.0209599e+00 5.6642588e+00 - -1.8823999e+00 4.0279209e+00 5.8385619e+00 - -1.8836736e+00 4.0307213e+00 6.0144487e+00 - -1.8805368e+00 4.0239414e+00 6.1845732e+00 - -1.8772855e+00 4.0185919e+00 6.3634374e+00 - -1.8785595e+00 4.0203591e+00 6.5588992e+00 - -1.8807731e+00 4.0226548e+00 6.7638526e+00 - -1.8755840e+00 4.0151691e+00 6.9626346e+00 - -1.1823294e+00 2.8411723e+00 5.3748418e+00 - -1.1313635e+00 2.7550578e+00 5.3994005e+00 - -1.0713670e+00 2.6540334e+00 5.3973052e+00 - -5.9591511e-01 1.8507654e+00 4.1825505e+00 - -5.5960631e-01 1.7879766e+00 4.1944347e+00 - -5.2224838e-01 1.7260504e+00 4.2047681e+00 - -4.8319850e-01 1.6595080e+00 4.2050060e+00 - -4.5225597e-01 1.6066999e+00 4.2295472e+00 - -4.2401960e-01 1.5584403e+00 4.2615903e+00 - -3.9760979e-01 1.5126896e+00 4.3015307e+00 - -3.7020676e-01 1.4668391e+00 4.3406690e+00 - -3.6703249e-01 1.4624211e+00 4.4776360e+00 - -4.0977713e-01 1.5329183e+00 4.8148422e+00 - -4.1280845e-01 1.5387794e+00 5.0098126e+00 - -4.9123042e-01 1.6704069e+00 5.5648958e+00 - -4.0098621e-01 1.5172113e+00 5.3571307e+00 - -3.3039756e-01 1.3992301e+00 5.2285496e+00 - -2.7875692e-01 1.3115018e+00 5.1810948e+00 - -2.0750221e-01 1.1902905e+00 5.0085144e+00 - -1.8271841e-01 1.1481359e+00 5.0986496e+00 - -1.4716096e-01 1.0884114e+00 5.1309126e+00 - -1.7672610e-01 1.1377857e+00 5.6040459e+00 - -8.6782514e-02 9.8631371e-01 5.2691410e+00 - -5.3938828e-02 9.3004544e-01 5.3272824e+00 - -1.9285832e-02 8.7113026e-01 5.3747298e+00 - 1.0096446e-02 8.2141210e-01 5.4797277e+00 - 6.2460500e-02 7.3245926e-01 5.3681497e+00 - 1.3679298e-01 6.0678955e-01 4.9885146e+00 - 1.7228365e-01 5.4704711e-01 5.0001535e+00 - 2.0163325e-01 4.9706783e-01 5.0998579e+00 - 2.2064691e-01 4.6506169e-01 5.3871719e+00 - 2.7952794e-01 3.6492297e-01 5.0180872e+00 - 2.9540281e-01 3.3843482e-01 5.4731556e+00 - 3.4881647e-01 2.4746882e-01 5.1003481e+00 - 3.9014017e-01 1.7808039e-01 4.9249956e+00 - 4.2557494e-01 1.1892282e-01 4.9079707e+00 - 4.4858716e-01 7.6493158e-02 6.0196904e+00 - -2.6750728e+00 5.7645762e+00 -8.2883498e-01 - -2.9187872e+00 6.2072132e+00 -8.3664959e-01 - -3.2193422e+00 6.7540455e+00 -8.5546076e-01 - -3.6211919e+00 7.4823238e+00 -8.9861680e-01 - -4.0617104e+00 8.2827699e+00 -9.2927453e-01 - -4.5708525e+00 9.2070143e+00 -9.5410121e-01 - -5.2145029e+00 1.0375601e+01 -9.8904919e-01 - -6.0269358e+00 1.1850990e+01 -1.0299793e+00 - -7.1437081e+00 1.3877179e+01 -1.0951994e+00 - -8.4344275e+00 1.6221762e+01 -1.1210851e+00 - -8.7397005e+00 1.6774988e+01 -8.5553140e-01 - -9.0331256e+00 1.7307581e+01 -5.6690580e-01 - -9.3292401e+00 1.7844342e+01 -2.5824421e-01 - -9.6180840e+00 1.8367686e+01 7.1859971e-02 - -1.2209748e+01 2.3072103e+01 2.9433863e-01 - -1.2672399e+01 2.3911859e+01 7.4517451e-01 - -1.3218014e+01 2.4901796e+01 1.2308659e+00 - -1.6533401e+01 3.0916616e+01 2.5195615e+00 - -7.7524272e+00 1.4976311e+01 2.0355637e+00 - -7.6703842e+00 1.4827117e+01 2.3221617e+00 - -7.6777038e+00 1.4839411e+01 2.6211700e+00 - -7.8211369e+00 1.5100325e+01 2.9538100e+00 - -7.7174959e+00 1.4911239e+01 3.2309286e+00 - -7.6643691e+00 1.4813941e+01 3.5174481e+00 - -7.5273193e+00 1.4565582e+01 3.7727540e+00 - -4.2584576e+00 8.6281822e+00 5.2768756e+00 - -3.5358334e+00 7.3181511e+00 4.8020765e+00 - -3.4687883e+00 7.1952334e+00 4.9129558e+00 - -3.4781881e+00 7.2121343e+00 5.1003121e+00 - -2.6588032e+00 5.7261573e+00 4.6944700e+00 - -2.6404656e+00 5.6913271e+00 4.8232317e+00 - -1.3672229e+00 3.3843707e+00 3.3649407e+00 - -4.7664959e+00 9.5453027e+00 7.9355029e+00 - -2.4664247e+00 5.3765632e+00 5.0588569e+00 - -1.1102774e+00 2.9165967e+00 3.2867061e+00 - -1.0911981e+00 2.8812039e+00 3.3445034e+00 - -1.0432226e+00 2.7958194e+00 3.3599334e+00 - -1.0160972e+00 2.7451713e+00 3.4031147e+00 - -1.3815496e+00 3.4073286e+00 4.0919947e+00 - -1.1232943e+00 2.9411679e+00 3.7652660e+00 - -2.7173643e+00 5.8293256e+00 6.6788958e+00 - -8.7768379e-01 2.4936980e+00 3.5166908e+00 - -9.1954979e-01 2.5709156e+00 3.6874553e+00 - -9.6687229e-01 2.6563614e+00 3.8758697e+00 - -1.0088283e+00 2.7313124e+00 4.0614647e+00 - -9.7886753e-01 2.6776645e+00 4.1082808e+00 - -3.1695082e+00 6.6455195e+00 8.9893213e+00 - -3.0207498e+00 6.3751138e+00 8.9363610e+00 - -2.8988955e+00 6.1540303e+00 8.9349002e+00 - -2.7026796e+00 5.7977104e+00 8.7448109e+00 - -1.8305786e+00 4.2189318e+00 6.8385652e+00 - -1.8201517e+00 4.1994075e+00 7.0234909e+00 - -1.1100080e+00 2.9128190e+00 5.3301109e+00 - -1.0701408e+00 2.8406448e+00 5.3794818e+00 - -1.0356276e+00 2.7785498e+00 5.4435072e+00 - -9.8679627e-01 2.6904194e+00 5.4652750e+00 - -1.0185850e+00 2.7468665e+00 5.7349225e+00 - -5.0551348e-01 1.8177915e+00 4.2546065e+00 - -4.6317238e-01 1.7402445e+00 4.2392471e+00 - -4.3064292e-01 1.6809495e+00 4.2562889e+00 - -3.9360232e-01 1.6144245e+00 4.2544357e+00 - -3.6103052e-01 1.5559836e+00 4.2685315e+00 - -3.3392261e-01 1.5057117e+00 4.2990788e+00 - -3.0758227e-01 1.4588902e+00 4.3375707e+00 - -2.7954937e-01 1.4074574e+00 4.3660670e+00 - -2.6758752e-01 1.3846411e+00 4.4664411e+00 - -3.1342670e-01 1.4677145e+00 4.8511054e+00 - -3.1828008e-01 1.4756049e+00 5.0645098e+00 - -3.5330865e-01 1.5383093e+00 5.4561194e+00 - -2.7435702e-01 1.3964738e+00 5.2613804e+00 - -2.1780986e-01 1.2930280e+00 5.1660106e+00 - -1.7006055e-01 1.2073827e+00 5.1153733e+00 - -1.3128607e-01 1.1365766e+00 5.1102163e+00 - -1.2443219e-01 1.1227106e+00 5.3239207e+00 - -8.9121781e-02 1.0589491e+00 5.3553832e+00 - -4.1471739e-02 9.7251057e-01 5.2886657e+00 - -3.4868207e-03 9.0446334e-01 5.2976952e+00 - 2.2963028e-02 8.5593826e-01 5.4029527e+00 - 7.0521624e-02 7.6928475e-01 5.3116160e+00 - 1.2163555e-01 6.7786319e-01 5.1690291e+00 - 1.7255200e-01 5.8537921e-01 4.9846442e+00 - 1.9377202e-01 5.4586216e-01 5.1638813e+00 - 2.2901194e-01 4.8205308e-01 5.1741204e+00 - 2.6681089e-01 4.1355118e-01 5.1334120e+00 - 3.0541502e-01 3.4344676e-01 5.0614391e+00 - 3.4068969e-01 2.8094677e-01 5.0576962e+00 - 3.7577200e-01 2.1690964e-01 5.0227918e+00 - 4.1072156e-01 1.5232740e-01 4.9565765e+00 - 4.4347357e-01 9.3263570e-02 5.0390862e+00 - 4.7236339e-01 3.9481181e-02 6.0102557e+00 - -7.3001961e+00 1.5190960e+01 2.4841537e+00 - -7.3558213e+00 1.5298162e+01 2.7975016e+00 - -7.3540999e+00 1.5294082e+01 3.1009662e+00 - -7.3997991e+00 1.5382916e+01 3.4200650e+00 - -7.0820752e+00 1.4762732e+01 3.6186058e+00 - -2.5113155e+00 5.8567267e+00 4.7964536e+00 - -1.2653164e+00 3.4319444e+00 3.3158080e+00 - -4.4888103e+00 9.7037767e+00 7.8086268e+00 - -4.3765059e+00 9.4846849e+00 7.9163613e+00 - -4.4347015e+00 9.5970056e+00 8.2690214e+00 - -2.2217849e+00 5.2916367e+00 5.1610588e+00 - -2.1954572e+00 5.2405888e+00 5.2759532e+00 - -3.7615505e+00 8.2857386e+00 8.0119568e+00 - -1.3116029e+00 3.5202970e+00 4.0886938e+00 - -1.0481857e+00 3.0083973e+00 3.7359546e+00 - -1.0015218e+00 2.9179900e+00 3.7496379e+00 - -9.2722050e-01 2.7740201e+00 3.7081216e+00 - -9.3330217e-01 2.7837421e+00 3.8156127e+00 - -8.3315356e-01 2.5900425e+00 3.7131119e+00 - -8.4448230e-01 2.6117292e+00 3.8329611e+00 - -9.0561520e-01 2.7313929e+00 4.0674317e+00 - -8.2697686e-01 2.5777706e+00 3.9984304e+00 - -2.8104439e+00 6.4333116e+00 8.7483653e+00 - -2.8373490e+00 6.4839572e+00 9.0888560e+00 - -2.6585551e+00 6.1361754e+00 8.9282899e+00 - -1.9148418e+00 4.6902552e+00 7.2788069e+00 - -2.4933631e+00 5.8129312e+00 9.0632633e+00 - -2.3947069e+00 5.6213162e+00 9.0816181e+00 - -1.5412899e+00 3.9631563e+00 6.9076683e+00 - -2.3797063e+00 5.5912368e+00 9.6450024e+00 - -9.2345936e-01 2.7620861e+00 5.4302104e+00 - -9.1855328e-01 2.7523391e+00 5.5831490e+00 - -8.9139998e-01 2.6998512e+00 5.6700748e+00 - -8.7141424e-01 2.6600550e+00 5.7816498e+00 - -4.5738459e-01 1.8567220e+00 4.4707584e+00 - -3.7451148e-01 1.6957241e+00 4.2988674e+00 - -3.3519139e-01 1.6181466e+00 4.2792228e+00 - -3.0467984e-01 1.5588001e+00 4.2927752e+00 - -2.7417569e-01 1.4993944e+00 4.3051292e+00 - -2.4543974e-01 1.4434798e+00 4.3250313e+00 - -2.1940748e-01 1.3921334e+00 4.3528348e+00 - -1.9420178e-01 1.3432504e+00 4.3888322e+00 - -1.7961065e-01 1.3147556e+00 4.4790573e+00 - -2.0293316e-01 1.3603358e+00 4.7825298e+00 - -2.5536427e-01 1.4612165e+00 5.2752907e+00 - -2.1328747e-01 1.3794945e+00 5.2563341e+00 - -1.6595065e-01 1.2874586e+00 5.1977044e+00 - -1.1774925e-01 1.1937789e+00 5.1272356e+00 - -9.1573556e-02 1.1425473e+00 5.1978854e+00 - -5.0417843e-02 1.0630490e+00 5.1620041e+00 - -3.3851169e-02 1.0306570e+00 5.3174896e+00 - 8.9218997e-03 9.4594629e-01 5.2594277e+00 - 3.8642634e-02 8.8780141e-01 5.3163794e+00 - 7.4558054e-02 8.1877467e-01 5.3233673e+00 - 1.1122050e-01 7.4664910e-01 5.3092774e+00 - 1.7481483e-01 6.2357562e-01 4.9688289e+00 - 2.0449961e-01 5.6565913e-01 5.0101502e+00 - 2.2384290e-01 5.2721876e-01 5.2087698e+00 - 2.3742038e-01 5.0050874e-01 5.5758548e+00 - 2.9451386e-01 3.8999639e-01 5.1573312e+00 - 3.1177632e-01 3.5594413e-01 5.5628026e+00 - 3.6083252e-01 2.6024183e-01 5.1701308e+00 - 4.0054521e-01 1.8446935e-01 4.9249166e+00 - 4.3274318e-01 1.2200959e-01 4.8980622e+00 - 4.5369679e-01 7.9203234e-02 5.9997007e+00 - -4.8112229e-01 2.0534910e+00 2.0840667e+00 - -4.7298414e-01 2.0369084e+00 2.1235823e+00 - -4.6043042e-01 2.0107849e+00 2.1581345e+00 - -3.1541283e+00 7.6567395e+00 5.6001262e+00 - -3.7799327e+00 8.9656155e+00 6.6133493e+00 - -2.3480642e+00 5.9668385e+00 4.8894369e+00 - -2.3194081e+00 5.9046132e+00 5.0042676e+00 - -2.3251211e+00 5.9172814e+00 5.1714849e+00 - -3.9312221e+00 9.2834864e+00 7.7998849e+00 - -3.7916492e+00 8.9890177e+00 7.8368777e+00 - -2.0308388e+00 5.3002955e+00 5.1838831e+00 - -1.9959774e+00 5.2257247e+00 5.2798605e+00 - -4.6069040e+00 1.0694567e+01 1.0082346e+01 - -9.2847158e-01 2.9889706e+00 3.6318452e+00 - -4.1814978e+00 9.8023685e+00 9.9438083e+00 - -8.5545666e-01 2.8355378e+00 3.6809148e+00 - -8.6400854e-01 2.8537567e+00 3.7949105e+00 - -9.1226708e-01 2.9560482e+00 3.9982192e+00 - -8.4669547e-01 2.8167136e+00 3.9586308e+00 - -7.8103056e-01 2.6791562e+00 3.9145486e+00 - -7.2861585e-01 2.5696777e+00 3.8945946e+00 - -2.9420150e+00 7.2040143e+00 9.4029134e+00 - -2.9050937e+00 7.1246740e+00 9.6072467e+00 - -2.0507167e+00 5.3371708e+00 7.6776647e+00 - -1.9557115e+00 5.1368814e+00 7.6583229e+00 - -2.0591483e+00 5.3530418e+00 8.1885649e+00 - -2.2356914e+00 5.7222060e+00 8.9637217e+00 - -2.1678948e+00 5.5799364e+00 9.0494187e+00 - -1.3756672e+00 3.9209933e+00 6.8660731e+00 - -2.1936044e+00 5.6318841e+00 9.7404702e+00 - -2.0694850e+00 5.3701492e+00 9.6503889e+00 - -6.2889551e-01 2.3579862e+00 4.9432026e+00 - -5.4572982e-01 2.1840691e+00 4.7942746e+00 - -7.5652104e-01 2.6239363e+00 5.7394689e+00 - -3.2026128e-01 1.7120550e+00 4.3502918e+00 - -2.8745976e-01 1.6417397e+00 4.3477507e+00 - -2.5015018e-01 1.5641698e+00 4.3258153e+00 - -2.1900876e-01 1.4992410e+00 4.3287257e+00 - -1.9057350e-01 1.4388607e+00 4.3391380e+00 - -1.6290642e-01 1.3819259e+00 4.3573950e+00 - -1.3794302e-01 1.3295593e+00 4.3835533e+00 - -1.1386578e-01 1.2786639e+00 4.4180549e+00 - -1.0473402e-01 1.2578585e+00 4.5352682e+00 - -1.4257166e-01 1.3385149e+00 4.9617538e+00 - -1.5954929e-01 1.3718349e+00 5.2886200e+00 - -8.9920458e-02 1.2268005e+00 5.0585524e+00 - -6.8314277e-02 1.1818166e+00 5.1484463e+00 - -4.8468701e-02 1.1398688e+00 5.2569244e+00 - -2.4237349e-02 1.0886578e+00 5.3458077e+00 - 1.1278950e-02 1.0138629e+00 5.3371630e+00 - 5.0295698e-02 9.3231422e-01 5.2977916e+00 - 8.0588351e-02 8.6812399e-01 5.3347129e+00 - 1.1011733e-01 8.0689956e-01 5.3900154e+00 - 1.5161500e-01 7.1951818e-01 5.2968497e+00 - 1.9059045e-01 6.3918670e-01 5.2213740e+00 - 2.2172673e-01 5.7318527e-01 5.2430605e+00 - 2.2998540e-01 5.5528796e-01 5.6599055e+00 - 2.6205241e-01 4.8610855e-01 5.7196898e+00 - 3.1852935e-01 3.6912214e-01 5.2307021e+00 - 3.5551590e-01 2.9206534e-01 5.0976063e+00 - 3.8829730e-01 2.2416797e-01 5.0427817e+00 - 4.2013130e-01 1.5776825e-01 4.9765751e+00 - 4.4945663e-01 9.5432131e-02 4.9890808e+00 - 4.7442055e-01 4.0362162e-02 6.0102996e+00 - -4.6080501e-01 2.1727419e+00 2.1064940e+00 - -4.5271660e-01 2.1552461e+00 2.1477570e+00 - -3.4551964e+00 8.9516332e+00 5.9799549e+00 - -3.1026917e+00 8.1517128e+00 5.7325865e+00 - -2.7816429e+00 7.4274014e+00 5.4949989e+00 - -3.4849632e+00 9.0185648e+00 6.6850105e+00 - -2.7929442e+00 7.4516715e+00 5.8888587e+00 - -2.1546373e+00 6.0066679e+00 5.0984399e+00 - -2.1393721e+00 5.9703651e+00 5.2342018e+00 - -3.1614189e+00 8.2844974e+00 7.1017954e+00 - -2.9829323e+00 7.8776576e+00 7.0240429e+00 - -1.8373092e+00 5.2861045e+00 5.1941017e+00 - -1.8070497e+00 5.2180394e+00 5.2942921e+00 - -4.1351562e+00 1.0484755e+01 9.9458057e+00 - -3.5691827e+00 9.2027560e+00 9.1382810e+00 - -8.7716617e-01 3.1131967e+00 3.8525809e+00 - -8.2609101e-01 2.9974405e+00 3.8459608e+00 - -8.1180507e-01 2.9649596e+00 3.9161596e+00 - -7.4416896e-01 2.8107917e+00 3.8631727e+00 - -7.2372699e-01 2.7650571e+00 3.9163655e+00 - -6.7706637e-01 2.6593657e+00 3.9050710e+00 - -6.5146839e-01 2.6004231e+00 3.9409614e+00 - -2.5623297e+00 6.9216288e+00 9.1070199e+00 - -1.7763217e+00 5.1433599e+00 7.2397815e+00 - -1.9820410e+00 5.6081136e+00 8.0460471e+00 - -2.1116031e+00 5.9002341e+00 8.6803362e+00 - -2.2026421e+00 6.1047980e+00 9.2345027e+00 - -1.9974916e+00 5.6397111e+00 8.8850204e+00 - -1.9853313e+00 5.6122918e+00 9.1352049e+00 - -2.0063513e+00 5.6591665e+00 9.5078847e+00 - -1.1624602e+00 3.7531001e+00 6.8551168e+00 - -1.9374837e+00 5.5014303e+00 9.9093265e+00 - -7.3746025e-01 2.7921126e+00 5.6953113e+00 - -6.8901766e-01 2.6825244e+00 5.6885034e+00 - -2.8200706e+00 7.4914381e+00 1.5172717e+01 - -4.8982138e-01 2.2317880e+00 5.3985242e+00 - -3.8667838e-01 1.9983233e+00 5.1050285e+00 - -2.0887795e-01 1.5954980e+00 4.4210348e+00 - -1.6672186e-01 1.5006995e+00 4.3610714e+00 - -1.3589037e-01 1.4312311e+00 4.3529939e+00 - -1.1022332e-01 1.3743876e+00 4.3706579e+00 - -8.5622055e-02 1.3165485e+00 4.3871762e+00 - -6.1787744e-02 1.2621647e+00 4.4117389e+00 - -4.0535864e-02 1.2138338e+00 4.4540412e+00 - -3.9078030e-02 1.2117735e+00 4.6363586e+00 - -9.2996782e-02 1.3326131e+00 5.2261650e+00 - -3.7911067e-02 1.2087211e+00 5.0607252e+00 - -9.7643614e-03 1.1429405e+00 5.0832202e+00 - 9.8960420e-03 1.0984815e+00 5.1813104e+00 - 2.5344113e-02 1.0641560e+00 5.3368982e+00 - 5.5287999e-02 9.9511577e-01 5.3565392e+00 - 9.8204071e-02 8.9886929e-01 5.2481828e+00 - 1.1533278e-01 8.5880576e-01 5.4114524e+00 - 1.4618996e-01 7.8851106e-01 5.4271447e+00 - 1.7960963e-01 7.1251990e-01 5.4120640e+00 - 2.2072607e-01 6.2106061e-01 5.2767495e+00 - 2.3055670e-01 5.9861961e-01 5.6444480e+00 - 2.5975477e-01 5.3114073e-01 5.7147793e+00 - 2.9984510e-01 4.4003432e-01 5.5651361e+00 - 3.3334288e-01 3.6518300e-01 5.5529022e+00 - 3.5856965e-01 3.0666931e-01 5.7786079e+00 - 4.0776194e-01 1.9649630e-01 5.0747644e+00 - 4.4072257e-01 1.2405725e-01 4.8480505e+00 - 4.5712490e-01 8.1971241e-02 6.0797420e+00 - -5.6558951e+00 1.5143133e+01 2.8542289e+00 - -5.6350674e+00 1.5091713e+01 3.1365821e+00 - -3.8314184e-01 2.1669940e+00 2.0650472e+00 - -3.7853906e-01 2.1579176e+00 2.1100215e+00 - -3.5194123e+00 9.8756248e+00 6.3091342e+00 - -3.0322479e+00 8.6789668e+00 5.8716473e+00 - -2.7876195e+00 8.0773504e+00 5.7293035e+00 - -2.8939018e+00 8.3382910e+00 6.0874447e+00 - -2.8247744e+00 8.1675885e+00 6.1879525e+00 - -3.6966875e+00 1.0310153e+01 7.8132744e+00 - -1.9851737e+00 6.1034603e+00 5.1933435e+00 - -1.9604185e+00 6.0427250e+00 5.3132310e+00 - -2.7426264e+00 7.9644800e+00 6.9035353e+00 - -2.6675489e+00 7.7773309e+00 6.9830908e+00 - -1.6451496e+00 5.2659085e+00 5.2029229e+00 - -1.6290869e+00 5.2269108e+00 5.3257967e+00 - -1.8159283e+00 5.6859073e+00 5.8777158e+00 - -7.9690874e-01 3.1824183e+00 3.8292469e+00 - -7.2033633e-01 2.9947517e+00 3.7589340e+00 - -6.8545305e-01 2.9081936e+00 3.7752034e+00 - -6.8341546e-01 2.9037608e+00 3.8701263e+00 - -6.2696382e-01 2.7628483e+00 3.8280688e+00 - -2.2389344e+00 6.7218801e+00 8.1248558e+00 - -2.0253374e+00 6.1963867e+00 7.8013295e+00 - -1.7625492e+00 5.5491509e+00 7.3080886e+00 - -1.7844253e+00 5.6028944e+00 7.5959307e+00 - -1.5355280e+00 4.9918117e+00 7.0866745e+00 - -1.6793690e+00 5.3444054e+00 7.7498078e+00 - -1.6251065e+00 5.2111418e+00 7.8186237e+00 - -1.6504004e+00 5.2722993e+00 8.1505760e+00 - -2.3003478e+00 6.8652186e+00 1.0651689e+01 - -2.0705458e+00 6.3005322e+00 1.0184917e+01 - -1.7699617e+00 5.5640542e+00 9.4152991e+00 - -1.0147950e+00 3.7115849e+00 6.8249145e+00 - -1.7898069e+00 5.6115494e+00 1.0144981e+01 - -1.8191461e+00 5.6810809e+00 1.0620323e+01 - -1.7594699e+00 5.5351213e+00 1.0742997e+01 - -2.0255969e+00 6.1856319e+00 1.2327343e+01 - -2.4850966e+00 7.3111539e+00 1.4939347e+01 - -3.9875860e-01 2.1986392e+00 5.3669570e+00 - -3.0197844e-01 1.9599711e+00 5.0619427e+00 - -2.8342163e-01 1.9147301e+00 5.1429571e+00 - -1.3260589e-01 1.5442938e+00 4.4925755e+00 - -8.5784774e-02 1.4297852e+00 4.3847954e+00 - -5.8721515e-02 1.3638992e+00 4.3836732e+00 - -3.5122114e-02 1.3060910e+00 4.3995954e+00 - -1.1590331e-02 1.2472266e+00 4.4143686e+00 - 8.5994648e-03 1.1979297e+00 4.4561244e+00 - 2.6208680e-02 1.1547005e+00 4.5159194e+00 - 1.0955843e-03 1.2152401e+00 4.9163855e+00 - 2.0520260e-02 1.1678659e+00 4.9958978e+00 - -9.4813076e-03 1.2406570e+00 5.5158379e+00 - 4.2281287e-02 1.1127731e+00 5.3265858e+00 - 8.0463418e-02 1.0193975e+00 5.2500564e+00 - 1.1179386e-01 9.4226916e-01 5.2297381e+00 - 1.3294851e-01 8.8955106e-01 5.3249223e+00 - 1.5579325e-01 8.3220200e-01 5.4097115e+00 - 1.8715946e-01 7.5535942e-01 5.3951860e+00 - 2.1600735e-01 6.8508216e-01 5.4087873e+00 - 2.4904785e-01 6.0451373e-01 5.3616949e+00 - 2.6289638e-01 5.6935411e-01 5.6600097e+00 - 2.9423073e-01 4.9174120e-01 5.6501281e+00 - 3.1822425e-01 4.3192502e-01 5.8279465e+00 - 3.5605684e-01 3.3885058e-01 5.6359620e+00 - 4.0163580e-01 2.2988784e-01 5.0328053e+00 - 4.2935609e-01 1.6173108e-01 4.9666107e+00 - 4.5687829e-01 9.4054298e-02 4.8291057e+00 - 4.7678967e-01 4.2188738e-02 6.0902937e+00 - -3.4840551e+00 1.0695955e+01 -1.0176360e+00 - -3.8683545e+00 1.1726724e+01 -9.8761291e-01 - -4.3913818e+00 1.3131089e+01 -9.7566287e-01 - -5.2757372e+00 1.5504427e+01 -1.0391169e+00 - -6.1555749e+00 1.7864914e+01 -1.0125546e+00 - -7.0644973e+00 2.0303371e+01 -9.0565520e-01 - -1.2780920e+01 3.5643035e+01 -3.4636618e-01 - -1.2773038e+01 3.5622432e+01 3.1832007e-01 - -1.2800701e+01 3.5693190e+01 9.8182294e-01 - -1.2844646e+01 3.5809238e+01 1.6487991e+00 - -1.2853226e+01 3.5830930e+01 2.3170075e+00 - -1.2850585e+01 3.5822851e+01 2.9851133e+00 - -1.2858392e+01 3.5840623e+01 3.6561135e+00 - -1.2860867e+01 3.5847105e+01 4.3284386e+00 - -1.2871270e+01 3.5871326e+01 5.0049438e+00 - -1.2869518e+01 3.5864698e+01 5.6809934e+00 - -5.1396811e+00 1.5126155e+01 3.2610846e+00 - -5.1251204e+00 1.5087102e+01 3.5424660e+00 - -1.2932087e+01 3.6029018e+01 7.7607488e+00 - -3.1299856e+00 9.7253660e+00 5.6158811e+00 - -2.5873677e+00 8.2733186e+00 5.1123532e+00 - -2.4272193e+00 7.8426382e+00 5.0775413e+00 - -2.3769425e+00 7.7076090e+00 5.1867186e+00 - -2.4657875e+00 7.9443614e+00 5.5031925e+00 - -2.5022096e+00 8.0411855e+00 5.7521539e+00 - -2.5119588e+00 8.0674577e+00 5.9661836e+00 - -2.7902913e+00 8.8121586e+00 6.6457483e+00 - -2.7648981e+00 8.7422963e+00 6.8249547e+00 - -1.8020478e+00 6.1622717e+00 5.2672081e+00 - -1.7809491e+00 6.1070438e+00 5.3925535e+00 - -2.4303553e+00 7.8460728e+00 6.8582878e+00 - -2.4229871e+00 7.8246701e+00 7.0622484e+00 - -1.4548204e+00 5.2324183e+00 5.2044012e+00 - -1.4398252e+00 5.1924102e+00 5.3258297e+00 - -2.6318590e+00 8.3832801e+00 8.2394669e+00 - -1.5820533e+00 5.5718183e+00 5.9855278e+00 - -6.2177514e-01 2.9999057e+00 3.7805991e+00 - -6.0949416e-01 2.9674767e+00 3.8494059e+00 - -5.8186106e-01 2.8929501e+00 3.8769413e+00 - -1.6529600e+00 5.7574411e+00 6.9297845e+00 - -1.6035537e+00 5.6265869e+00 7.0008143e+00 - -1.6055599e+00 5.6315711e+00 7.2197511e+00 - -1.6870488e+00 5.8494027e+00 7.6892006e+00 - -1.3531171e+00 4.9549142e+00 6.8686989e+00 - -1.5841897e+00 5.5715936e+00 7.8351333e+00 - -1.5468334e+00 5.4708880e+00 7.9532102e+00 - -1.4795317e+00 5.2910537e+00 7.9686742e+00 - -1.5727753e+00 5.5398465e+00 8.5624241e+00 - -1.3835253e+00 5.0320626e+00 8.1216308e+00 - -1.8383557e+00 6.2477179e+00 1.0171371e+01 - -1.8127818e+00 6.1777518e+00 1.0409254e+01 - -8.7249126e-01 3.6643164e+00 6.7935272e+00 - -1.9565880e+00 6.5601932e+00 1.1773882e+01 - -1.6505770e+00 5.7420583e+00 1.0800802e+01 - -1.8325722e+00 6.2276192e+00 1.2054548e+01 - -2.9824400e-01 2.1277736e+00 4.9310911e+00 - -2.9609155e-01 2.1221957e+00 5.0838410e+00 - -2.5659873e-01 2.0154839e+00 5.0433049e+00 - -2.3827560e-01 1.9668284e+00 5.1158786e+00 - -2.5552525e-01 2.0142632e+00 5.4035027e+00 - -1.9830975e-01 1.8587393e+00 5.2500229e+00 - -3.5801465e-02 1.4263305e+00 4.4163964e+00 - -8.2799434e-03 1.3524595e+00 4.3964416e+00 - 1.4197154e-02 1.2926882e+00 4.4118668e+00 - 3.5668687e-02 1.2329183e+00 4.4260967e+00 - 5.5615558e-02 1.1801329e+00 4.4579135e+00 - 7.4738338e-02 1.1298305e+00 4.4983237e+00 - 7.1042193e-02 1.1389315e+00 4.7374931e+00 - 3.8758471e-02 1.2232696e+00 5.2649877e+00 - 3.8650909e-02 1.2232267e+00 5.5465377e+00 - 8.9684527e-02 1.0853915e+00 5.3176315e+00 - 1.2235385e-01 9.9876253e-01 5.2692384e+00 - 1.5244012e-01 9.1818155e-01 5.2384850e+00 - 1.6581745e-01 8.8131937e-01 5.4212440e+00 - 1.9513203e-01 8.0364015e-01 5.4075735e+00 - 2.2437634e-01 7.2539929e-01 5.3825170e+00 - 7.3975730e-02 1.1199115e+00 8.5359972e+00 - 2.6389371e-01 6.1763746e-01 5.6841545e+00 - 2.2394154e-01 7.1960402e-01 7.2432002e+00 - 3.1768290e-01 4.7388661e-01 5.8037526e+00 - 3.6838661e-01 3.3827161e-01 5.1145714e+00 - 3.7626849e-01 3.1611691e-01 5.8085703e+00 - 4.1985792e-01 1.9929244e-01 5.0448151e+00 - 4.4714007e-01 1.2866596e-01 4.8880331e+00 - 4.6304713e-01 8.3137921e-02 6.0296862e+00 - -2.6411748e+00 9.2610185e+00 -9.9360750e-01 - -1.9988184e+00 7.3657721e+00 -4.4451685e-01 - -1.9966791e+00 7.3606049e+00 -3.0370178e-01 - -3.6900349e+00 1.2353508e+01 -9.5505210e-01 - -2.0002086e+00 7.3705220e+00 -2.7728225e-02 - -2.0023566e+00 7.3774678e+00 1.0941197e-01 - -3.4596166e-01 2.4907952e+00 9.7632235e-01 - -3.8154402e-01 2.5955767e+00 1.0231372e+00 - -3.7214984e-01 2.5662527e+00 1.0701820e+00 - -3.6765640e-01 2.5552711e+00 1.1170531e+00 - -3.2845506e-01 2.4395256e+00 1.1567629e+00 - -3.5985698e-01 2.5303086e+00 1.2095490e+00 - -1.2988928e+01 3.9744757e+01 5.7627704e+00 - -2.2211503e+00 8.0076887e+00 4.6730404e+00 - -2.3003718e+00 8.2394268e+00 4.9608667e+00 - -2.6318656e+00 9.2148560e+00 5.6368875e+00 - -2.2630128e+00 8.1284286e+00 5.2754930e+00 - -2.2363816e+00 8.0477436e+00 5.4200823e+00 - -2.2103061e+00 7.9742652e+00 5.5677237e+00 - -2.2741860e+00 8.1607271e+00 5.8714056e+00 - -2.1577272e+00 7.8180486e+00 5.8588550e+00 - -2.3696607e+00 8.4393107e+00 6.4563907e+00 - -2.1187786e+00 7.7000692e+00 6.1762188e+00 - -1.6352841e+00 6.2794353e+00 5.3852532e+00 - -1.6027999e+00 6.1820443e+00 5.4833721e+00 - -1.6016275e+00 6.1761556e+00 5.6488591e+00 - -1.6137778e+00 6.2130239e+00 5.8511672e+00 - -1.2719262e+00 5.2079343e+00 5.2165950e+00 - -1.2630621e+00 5.1818961e+00 5.3492868e+00 - -5.5746416e-01 3.1064756e+00 3.7022556e+00 - -5.2262082e-01 3.0033097e+00 3.7072296e+00 - -5.1480947e-01 2.9794739e+00 3.7820480e+00 - -5.2041968e-01 2.9965737e+00 3.8972823e+00 - -5.0161382e-01 2.9406442e+00 3.9451809e+00 - -1.4141102e+00 5.6206587e+00 6.8292268e+00 - -1.4733434e+00 5.7963326e+00 7.2242242e+00 - -1.4543504e+00 5.7377730e+00 7.3808854e+00 - -1.2616518e+00 5.1703448e+00 6.9551279e+00 - -1.1978675e+00 4.9834194e+00 6.9447311e+00 - -1.3969535e+00 5.5674961e+00 7.8793354e+00 - -2.0969190e+00 7.6215246e+00 1.0757705e+01 - -1.8265966e+00 6.8282425e+00 1.0059660e+01 - -1.1846533e+00 4.9417290e+00 7.7970549e+00 - -1.1402084e+00 4.8119277e+00 7.8630572e+00 - -1.6810918e+00 6.3972720e+00 1.0465396e+01 - -1.7373292e+00 6.5614289e+00 1.1076309e+01 - -7.3841959e-01 3.6287537e+00 6.7858433e+00 - -1.5606299e+00 6.0418428e+00 1.1008434e+01 - -1.4271129e+00 5.6476217e+00 1.0726285e+01 - -9.5377613e-01 4.2601384e+00 8.6323418e+00 - -2.6225664e-01 2.2302461e+00 5.1597026e+00 - -2.1062815e-01 2.0798445e+00 5.0419490e+00 - -1.8755922e-01 2.0121240e+00 5.0797898e+00 - -1.7621601e-01 1.9786910e+00 5.1878003e+00 - -1.6165721e-01 1.9331334e+00 5.2777660e+00 - -1.4768389e-01 1.8935126e+00 5.3855648e+00 - 1.3519048e-03 1.4548290e+00 4.5304040e+00 - 4.0220783e-02 1.3415841e+00 4.4182052e+00 - 6.1457406e-02 1.2783898e+00 4.4237946e+00 - 8.1866855e-02 1.2176538e+00 4.4374779e+00 - 1.0232974e-01 1.1578605e+00 4.4500131e+00 - 1.1863333e-01 1.1101718e+00 4.4992228e+00 - 1.2423668e-01 1.0948654e+00 4.6622434e+00 - 7.6593225e-02 1.2297930e+00 5.3816769e+00 - 1.0050104e-01 1.1597079e+00 5.4133215e+00 - 1.3678339e-01 1.0535146e+00 5.2985881e+00 - 1.5325671e-01 1.0051193e+00 5.4145139e+00 - -1.6282080e-01 1.9224598e+00 1.0147405e+01 - 2.0597539e-01 8.5023512e-01 5.4097137e+00 - 2.2908562e-01 7.8284480e-01 5.4542462e+00 - 2.4484416e-01 7.3574304e-01 5.6356935e+00 - 1.3543269e-01 1.0496406e+00 8.4077221e+00 - 2.2206611e-01 7.9697746e-01 7.3849746e+00 - 3.2384345e-01 5.0149835e-01 5.6402526e+00 - 3.4077028e-01 4.5105393e-01 5.9375002e+00 - 3.9217293e-01 3.0391899e-01 5.0577471e+00 - 4.1434687e-01 2.3811499e-01 5.0926955e+00 - 4.3933387e-01 1.6315848e-01 4.9267296e+00 - 4.5017100e-01 1.2894770e-01 6.1486554e+00 - 4.7903261e-01 4.4038530e-02 6.1302380e+00 - -2.2296411e+00 8.8927503e+00 -9.8078531e-01 - -2.4898643e+00 9.7408208e+00 -9.8446767e-01 - -2.8239067e+00 1.0826408e+01 -1.0013129e+00 - -3.4724018e-01 2.7571862e+00 5.4247075e-01 - -3.4376628e-01 2.7455785e+00 5.9568685e-01 - -3.4620918e-01 2.7522308e+00 6.4583603e-01 - -3.4771351e-01 2.7578305e+00 6.9613145e-01 - -3.4927806e-01 2.7624334e+00 7.4647643e-01 - -3.4160419e-01 2.7374989e+00 7.9902238e-01 - -3.4229348e-01 2.7400277e+00 8.4906376e-01 - -3.4643285e-01 2.7517757e+00 8.9877180e-01 - -3.4373228e-01 2.7440882e+00 9.4919609e-01 - -3.4115461e-01 2.7343871e+00 9.9931997e-01 - -3.4341684e-01 2.7440302e+00 1.0493205e+00 - -3.4679522e-01 2.7517595e+00 1.0998228e+00 - -3.4334352e-01 2.7399745e+00 1.1494433e+00 - -3.4478455e-01 2.7465958e+00 1.2001886e+00 - -4.1220424e+00 1.5034142e+01 4.6243253e+00 - -2.4555793e+00 9.6086956e+00 5.0567817e+00 - -2.1990573e+00 8.7745427e+00 4.8919934e+00 - -2.8372426e+00 1.0847528e+01 6.0472224e+00 - -2.3898499e+00 9.3928743e+00 5.5773515e+00 - -1.9751992e+00 8.0431368e+00 5.0999041e+00 - -1.9440117e+00 7.9392938e+00 5.2280860e+00 - -2.0076474e+00 8.1465749e+00 5.5271350e+00 - -2.1204448e+00 8.5125378e+00 5.9318996e+00 - -2.2223854e+00 8.8427279e+00 6.3364595e+00 - -2.5148542e+00 9.7935771e+00 7.1506211e+00 - -2.1363608e+00 8.5623785e+00 6.5924570e+00 - -1.9493645e+00 7.9547114e+00 6.3996043e+00 - -1.9339644e+00 7.9021667e+00 6.5720108e+00 - -1.4391645e+00 6.2967729e+00 5.6091661e+00 - -1.4129384e+00 6.2113036e+00 5.7175489e+00 - -1.4100640e+00 6.2003634e+00 5.8843759e+00 - -1.0955121e+00 5.1757635e+00 5.2277060e+00 - -4.4841915e-01 3.0759707e+00 3.6044656e+00 - -4.2157588e-01 2.9889436e+00 3.6217089e+00 - -4.1883154e-01 2.9800585e+00 3.7086370e+00 - -4.0284200e-01 2.9272816e+00 3.7559970e+00 - -1.2852073e+00 5.7902720e+00 6.6447481e+00 - -1.2963280e+00 5.8257837e+00 6.8815592e+00 - -1.4850306e+00 6.4370066e+00 7.7291547e+00 - -1.2569846e+00 5.6993117e+00 7.1698031e+00 - -1.3742938e+00 6.0774419e+00 7.8138913e+00 - -1.0794818e+00 5.1186281e+00 6.9432380e+00 - -1.0481512e+00 5.0190229e+00 7.0357663e+00 - -1.0386328e+00 4.9850189e+00 7.2107987e+00 - -1.1116535e+00 5.2235454e+00 7.7436546e+00 - -1.0556706e+00 5.0396049e+00 7.7434715e+00 - -1.0169165e+00 4.9146123e+00 7.8185832e+00 - -1.5647950e+00 6.6880452e+00 1.0624650e+01 - -1.7399206e+00 7.2562655e+00 1.1834427e+01 - -1.4555946e+00 6.3307293e+00 1.0813313e+01 - -6.1029068e-01 3.5939233e+00 6.7856691e+00 - -1.3083058e+00 5.8523840e+00 1.0792747e+01 - -8.2965989e-01 4.2993124e+00 8.4815606e+00 - -7.8514703e-01 4.1553128e+00 8.5243334e+00 - -1.5053666e-01 2.1003055e+00 4.9615713e+00 - -1.3520494e-01 2.0518559e+00 5.0346539e+00 - -9.0121160e-01 4.5280028e+00 1.0291567e+01 - -8.9919378e-02 1.9039311e+00 5.0801186e+00 - -5.9794122e-02 1.8073729e+00 5.0508540e+00 - -3.2378717e-02 1.7153336e+00 5.0284919e+00 - -2.6037387e-02 1.6963404e+00 5.1787739e+00 - 8.5143995e-02 1.3368467e+00 4.4582110e+00 - 1.0759659e-01 1.2621381e+00 4.4354251e+00 - 1.2694457e-01 1.2004410e+00 4.4486618e+00 - 1.4458826e-01 1.1432615e+00 4.4699965e+00 - 1.6134703e-01 1.0875631e+00 4.4998741e+00 - 1.7413045e-01 1.0464706e+00 4.5766144e+00 - 6.8056327e-02 1.3847165e+00 6.0464168e+00 - 1.3703592e-01 1.1613020e+00 5.5301618e+00 - 1.6786773e-01 1.0623530e+00 5.4536523e+00 - -1.2357344e-01 1.9970888e+00 1.0041756e+01 - -7.2574309e-02 1.8318588e+00 1.0008341e+01 - 2.4552540e-01 8.1119845e-01 5.3585299e+00 - 2.5287942e-01 7.8504044e-01 5.6484309e+00 - 1.4451125e-01 1.1307842e+00 8.4570293e+00 - 1.8135063e-01 1.0091434e+00 8.4963435e+00 - 2.6212513e-01 7.4829825e-01 7.3623981e+00 - 3.4454569e-01 4.8629516e-01 5.8237003e+00 - 3.8726713e-01 3.4964106e-01 5.1644564e+00 - 4.0901750e-01 2.7890506e-01 5.1602020e+00 - 4.3514570e-01 1.9544695e-01 4.8851134e+00 - 4.5362065e-01 1.3326306e-01 4.9480407e+00 - 4.6747198e-01 8.6349760e-02 6.0996871e+00 - -1.8542380e+00 8.5566336e+00 -9.7042742e-01 - -2.0578147e+00 9.2974096e+00 -9.6516187e-01 - -2.3090977e+00 1.0210261e+01 -9.6638788e-01 - -2.6318640e+00 1.1382604e+01 -9.7977267e-01 - -2.8450758e+00 1.2158301e+01 -8.8906275e-01 - -3.2959961e+00 1.3794456e+01 -8.8869122e-01 - -3.9866715e+00 1.6304498e+01 -9.3295067e-01 - -4.7658447e+00 1.9136757e+01 -9.1856691e-01 - -5.5892894e+00 2.2126592e+01 -8.1476329e-01 - -3.2092500e+00 1.3466364e+01 3.3319439e+00 - -3.2301157e+00 1.3537980e+01 3.5971713e+00 - -3.2122076e+00 1.3473630e+01 3.8378281e+00 - -3.2067334e+00 1.3451619e+01 4.0877871e+00 - -3.1765875e+00 1.3341816e+01 4.3167934e+00 - -3.2143671e+00 1.3480054e+01 4.6102776e+00 - -2.5133145e+00 1.0928945e+01 5.2334104e+00 - -2.2950522e+00 1.0137651e+01 5.1377316e+00 - -1.7064439e+00 7.9998085e+00 4.4336601e+00 - -2.4265805e+00 1.0611888e+01 5.7809715e+00 - -1.8380665e+00 8.4763864e+00 5.0027938e+00 - -1.7876547e+00 8.2946017e+00 5.0997587e+00 - -1.7994706e+00 8.3367207e+00 5.3072123e+00 - -1.8481662e+00 8.5102587e+00 5.5913132e+00 - -1.8362745e+00 8.4659511e+00 5.7637354e+00 - -1.9689475e+00 8.9462985e+00 6.2459828e+00 - -1.8980483e+00 8.6912056e+00 6.3055869e+00 - -1.7032087e+00 7.9836721e+00 6.0705541e+00 - -1.6774631e+00 7.8886897e+00 6.2089456e+00 - -1.7798391e+00 8.2585941e+00 6.6653154e+00 - -1.7115642e+00 8.0107665e+00 6.7064550e+00 - -1.7567964e+00 8.1726130e+00 7.0420741e+00 - -1.2382382e+00 6.2945001e+00 5.8278090e+00 - -9.5408143e-01 5.2634751e+00 5.1865620e+00 - -9.2441207e-01 5.1545062e+00 5.2501261e+00 - -8.2865974e-01 4.8076142e+00 5.1074502e+00 - -3.4753208e-01 3.0652856e+00 3.7139050e+00 - -3.1875645e-01 2.9613376e+00 3.7159513e+00 - -2.9499625e-01 2.8732682e+00 3.7286595e+00 - -1.2243769e+00 6.2394148e+00 7.1379533e+00 - -1.3231380e+00 6.5962592e+00 7.7193986e+00 - -1.2567347e+00 6.3536755e+00 7.7023196e+00 - -1.2251810e+00 6.2400802e+00 7.8163623e+00 - -9.3277857e-01 5.1798368e+00 6.8596148e+00 - -9.4029427e-01 5.2083990e+00 7.1022533e+00 - -9.0161852e-01 5.0670072e+00 7.1500397e+00 - -9.6700575e-01 5.3001754e+00 7.6650906e+00 - -9.2575827e-01 5.1516137e+00 7.7130146e+00 - -8.6996985e-01 4.9493147e+00 7.6863044e+00 - -1.5183676e+00 7.2913070e+00 1.1214370e+01 - -1.4071705e+00 6.8883160e+00 1.1011188e+01 - -1.6859224e+00 7.8930364e+00 1.2905743e+01 - -1.2837219e+00 6.4413141e+00 1.1087744e+01 - -1.2941175e+00 6.4774635e+00 1.1540085e+01 - -1.4818022e+00 7.1509306e+00 1.3096382e+01 - -6.9122120e-01 4.2980454e+00 8.5637710e+00 - -6.4854566e-01 4.1412116e+00 8.5882648e+00 - -7.7576062e-02 2.0803588e+00 4.9718168e+00 - -6.2604624e-02 2.0264515e+00 5.0355590e+00 - -5.6718518e-02 2.0012417e+00 5.1611196e+00 - -3.0459740e-02 1.9064494e+00 5.1425049e+00 - -1.0531023e-02 1.8367144e+00 5.1763595e+00 - 1.7984846e-02 1.7312064e+00 5.1265203e+00 - 4.2630182e-02 1.6426892e+00 5.1111103e+00 - 1.2263601e-01 1.3548570e+00 4.5634223e+00 - 1.5437242e-01 1.2403584e+00 4.4375124e+00 - 1.7072159e-01 1.1788082e+00 4.4500595e+00 - 1.8730320e-01 1.1206626e+00 4.4708475e+00 - 2.0206194e-01 1.0650556e+00 4.5001323e+00 - 2.1454159e-01 1.0194727e+00 4.5668834e+00 - 2.1038799e-01 1.0345023e+00 4.8642353e+00 - 1.8886045e-01 1.1112309e+00 5.4535146e+00 - 2.0694430e-01 1.0433430e+00 5.5021077e+00 - -3.5257926e-02 1.9071309e+00 9.9132852e+00 - 8.4599829e-02 1.4778508e+00 8.5256843e+00 - 2.6478363e-01 8.3259162e-01 5.6509178e+00 - 2.8547045e-01 7.5829917e-01 5.6949047e+00 - 1.9061517e-01 1.0922889e+00 8.5659759e+00 - 2.5216807e-01 8.7197415e-01 7.8608811e+00 - 2.9716826e-01 7.1033665e-01 7.4484584e+00 - 3.6437551e-01 4.7061014e-01 6.0569385e+00 - 4.1257833e-01 2.9975296e-01 4.9381791e+00 - 4.3063425e-01 2.3370477e-01 4.9430278e+00 - 4.4874443e-01 1.6809012e-01 4.9566656e+00 - 4.6828580e-01 9.8869967e-02 4.8591351e+00 - 4.8127699e-01 4.5384041e-02 6.1802195e+00 - -1.5250556e+00 8.3017878e+00 -9.7540748e-01 - -1.6951895e+00 8.9993351e+00 -9.7182042e-01 - -1.9054769e+00 9.8614066e+00 -9.7620130e-01 - -2.1583241e+00 1.0897526e+01 -9.8149577e-01 - -2.3507182e+00 1.1687092e+01 -9.0932041e-01 - -2.6515820e+00 1.2920742e+01 -8.7349992e-01 - -3.1228750e+00 1.4849579e+01 -8.8193329e-01 - -3.8421563e+00 1.7797404e+01 -9.3169157e-01 - -4.5618457e+00 2.0749492e+01 -8.7602724e-01 - -1.3513914e+01 5.7427288e+01 2.0103081e+00 - -2.8149558e+00 1.3571697e+01 3.7104904e+00 - -2.7062913e+00 1.3124529e+01 3.8666438e+00 - -3.2742537e+00 1.5449404e+01 4.6656907e+00 - -2.7677589e+00 1.3373462e+01 4.6834660e+00 - -2.4029495e+00 1.1879953e+01 4.5019742e+00 - -2.3345320e+00 1.1596046e+01 4.6448159e+00 - -2.2764495e+00 1.1356208e+01 4.7939579e+00 - -2.2734105e+00 1.1345036e+01 5.0168645e+00 - -2.0786149e+00 1.0545392e+01 4.9466733e+00 - -2.0309094e+00 1.0349802e+01 5.0854866e+00 - -2.1127163e+00 1.0684271e+01 5.4391488e+00 - -1.4560624e+00 7.9955341e+00 4.4904971e+00 - -1.4818319e+00 8.1043365e+00 4.7108674e+00 - -1.4304483e+00 7.8902184e+00 4.7840899e+00 - -1.5529726e+00 8.3922261e+00 5.2099380e+00 - -1.7513761e+00 9.2030085e+00 5.8227720e+00 - -2.0350587e+00 1.0363491e+01 6.6676892e+00 - -1.7831189e+00 9.3309510e+00 6.3200777e+00 - -1.6804001e+00 8.9110953e+00 6.2919949e+00 - -1.5690606e+00 8.4536711e+00 6.2248617e+00 - -1.4967818e+00 8.1573416e+00 6.2435385e+00 - -1.4891452e+00 8.1248890e+00 6.4273170e+00 - -1.8211139e+00 9.4810489e+00 7.5784691e+00 - -1.1955505e+00 6.9247809e+00 5.9878910e+00 - -1.1195314e+00 6.6109352e+00 5.9412271e+00 - -1.0553571e+00 6.3482610e+00 5.9208476e+00 - -7.8481473e-01 5.2446726e+00 5.2157808e+00 - -7.1606423e-01 4.9615787e+00 5.1332024e+00 - -7.0056776e-01 4.8981569e+00 5.2281486e+00 - -2.2825844e-01 2.9699632e+00 3.6563950e+00 - -6.3709865e-01 4.6358219e+00 5.2944636e+00 - -6.0480520e-01 4.5058757e+00 5.3226013e+00 - -6.6258088e-01 4.7391835e+00 5.7084389e+00 - -1.0873681e+00 6.4726854e+00 7.6588585e+00 - -1.0844483e+00 6.4595293e+00 7.8820640e+00 - -1.0251350e+00 6.2160318e+00 7.8581653e+00 - -1.2087756e+00 6.9638052e+00 8.9568118e+00 - -1.3866718e+00 7.6883303e+00 1.0099222e+01 - -8.0045434e-01 5.2966788e+00 7.4944255e+00 - -8.8702395e-01 5.6508937e+00 8.1790524e+00 - -7.6202225e-01 5.1394150e+00 7.7674733e+00 - -7.4728475e-01 5.0764179e+00 7.9305873e+00 - -7.5843711e-01 5.1233240e+00 8.2553457e+00 - -9.7857825e-01 6.0200726e+00 9.8448831e+00 - -1.1289680e+00 6.6297775e+00 1.1112135e+01 - -6.3639302e-01 4.6206593e+00 8.3202382e+00 - -5.9462116e-01 4.4498994e+00 8.3258004e+00 - -1.1663702e+00 6.7773925e+00 1.2603833e+01 - -5.4436602e-01 4.2418058e+00 8.5592307e+00 - -5.0329246e-01 4.0760813e+00 8.5643486e+00 - -3.9996793e-02 2.1906100e+00 5.2377814e+00 - -2.8479765e-02 2.1443402e+00 5.3299036e+00 - 8.1380085e-03 1.9945398e+00 5.2060053e+00 - 2.9817407e-02 1.9059164e+00 5.2050367e+00 - 3.8032321e-02 1.8700483e+00 5.3207959e+00 - 6.0454014e-02 1.7777725e+00 5.3077878e+00 - 9.5430200e-02 1.6350538e+00 5.1629249e+00 - 1.5381562e-01 1.3970344e+00 4.7435743e+00 - 1.9499633e-01 1.2308337e+00 4.4768797e+00 - 2.1104235e-01 1.1647981e+00 4.4795375e+00 - 2.2638287e-01 1.1032245e+00 4.4903898e+00 - 2.4165639e-01 1.0405998e+00 4.5001931e+00 - 2.5289372e-01 9.9157907e-01 4.5568088e+00 - 2.5188891e-01 9.9446602e-01 4.8154918e+00 - 2.3190417e-01 1.0780650e+00 5.4439715e+00 - 2.1409057e-01 1.1461356e+00 6.1057439e+00 - 2.9302150e-02 1.8867138e+00 1.0125855e+01 - 2.8125283e-01 8.7437471e-01 5.6236241e+00 - 2.9970390e-01 7.9725840e-01 5.6484403e+00 - 3.1663687e-01 7.2614759e-01 5.7115171e+00 - 2.4586176e-01 1.0063859e+00 8.3578108e+00 - 3.5072639e-01 5.8468119e-01 5.8935011e+00 - 3.7014663e-01 5.0572554e-01 5.9430324e+00 - 4.0991404e-01 3.4782911e-01 5.0747954e+00 - 4.2962102e-01 2.6776955e-01 4.9208283e+00 - 4.4787074e-01 1.9471739e-01 4.8051723e+00 - 4.5996989e-01 1.4330027e-01 5.1778906e+00 - 4.7183517e-01 8.9068926e-02 6.1597002e+00 - -5.2402447e-01 4.8106736e+00 -2.7311507e-01 - -5.2217986e-01 4.8031514e+00 -1.8004105e-01 - -5.2432826e-01 4.8126728e+00 -9.1988288e-02 - -9.3469606e-01 6.7378176e+00 -4.0338906e-01 - -8.0467206e-01 6.1260629e+00 -1.6245401e-01 - -8.4482855e-01 6.3190148e+00 -8.2814432e-02 - -8.9618005e-01 6.5587468e+00 -3.9114699e-03 - -9.2871780e-01 6.7110665e+00 9.4906636e-02 - -2.1561031e+00 1.2478178e+01 -4.5733742e-01 - -2.1773377e+00 1.2579423e+01 -2.4222929e-01 - -2.9122314e+00 1.6030573e+01 -2.9499245e-01 - -5.3397609e+00 2.7433197e+01 -7.2453257e-01 - -1.4953982e+01 7.2597603e+01 -9.6858836e-01 - -2.1474409e+00 1.2428005e+01 1.3287840e+00 - -2.1476123e+00 1.2430030e+01 1.5509594e+00 - -2.1306946e+00 1.2350545e+01 1.7684393e+00 - -2.1341300e+00 1.2364825e+01 1.9910315e+00 - -2.7367159e+00 1.5185938e+01 3.8726788e+00 - -2.7283208e+00 1.5144805e+01 4.1450895e+00 - -2.7534236e+00 1.5259967e+01 4.4538514e+00 - -2.6617873e+00 1.4828094e+01 4.6346867e+00 - -2.0466884e+00 1.1941420e+01 4.1535196e+00 - -2.1268829e+00 1.2320019e+01 4.4888751e+00 - -1.8784142e+00 1.1151780e+01 4.3734569e+00 - -1.8740606e+00 1.1129882e+01 4.5839685e+00 - -1.7563164e+00 1.0574591e+01 4.6140374e+00 - -1.9826215e+00 1.1636930e+01 5.2089278e+00 - -1.7056286e+00 1.0335314e+01 4.9471243e+00 - -1.7043054e+00 1.0329599e+01 5.1566561e+00 - -1.6876202e+00 1.0248257e+01 5.3364826e+00 - -1.2406348e+00 8.1545713e+00 4.6221960e+00 - -1.2372533e+00 8.1355211e+00 4.7879181e+00 - -1.2476902e+00 8.1842333e+00 4.9884299e+00 - -1.3185364e+00 8.5178843e+00 5.3389609e+00 - -1.4771861e+00 9.2586807e+00 5.9239635e+00 - -1.3767522e+00 8.7857109e+00 5.8738845e+00 - -1.3608184e+00 8.7094946e+00 6.0348398e+00 - -1.2813259e+00 8.3356875e+00 6.0170442e+00 - -1.2551063e+00 8.2160415e+00 6.1441339e+00 - -1.5482720e+00 9.5871928e+00 7.2404406e+00 - -1.4510881e+00 9.1276191e+00 7.1734007e+00 - -9.3260195e-01 6.6992392e+00 5.7049327e+00 - -9.2207777e-01 6.6504936e+00 5.8469445e+00 - -1.3124133e+00 8.4769901e+00 7.4095918e+00 - -8.7799351e-01 6.4413093e+00 6.0509303e+00 - -5.9455716e-01 5.1139086e+00 5.1570778e+00 - -7.7425417e-01 5.9559010e+00 6.0169636e+00 - -5.8457884e-01 5.0662592e+00 5.4213898e+00 - -5.1145878e-01 4.7264535e+00 5.2726970e+00 - -4.9876135e-01 4.6663222e+00 5.3699011e+00 - -5.3164359e-01 4.8187685e+00 5.6726666e+00 - -5.0276186e-01 4.6820594e+00 5.7018598e+00 - -5.3556560e-01 4.8346173e+00 6.0271472e+00 - -8.6605882e-01 6.3774037e+00 7.8674456e+00 - -5.1860992e-01 4.7528575e+00 6.2998070e+00 - -8.1786051e-01 6.1516273e+00 8.1058660e+00 - -7.5796506e-01 5.8711354e+00 8.0245154e+00 - -7.4810427e-01 5.8251255e+00 8.2207635e+00 - -6.7311945e-01 5.4688901e+00 8.0263121e+00 - -6.5636348e-01 5.3901760e+00 8.1783744e+00 - -6.4108552e-01 5.3193350e+00 8.3457768e+00 - -8.9395384e-01 6.4995632e+00 1.0311614e+01 - -8.1420618e-01 6.1233677e+00 1.0104801e+01 - -5.2183598e-01 4.7574203e+00 8.3453251e+00 - -4.8422449e-01 4.5840149e+00 8.3531460e+00 - -2.3767828e-01 3.4307556e+00 6.7204302e+00 - -4.1182541e-01 4.2408114e+00 8.3572134e+00 - -3.9430784e-01 4.1580836e+00 8.5101699e+00 - -3.6678862e-01 4.0296548e+00 8.5832176e+00 - 3.3601893e-02 2.1646310e+00 5.2485208e+00 - 6.2248361e-02 2.0301678e+00 5.1611611e+00 - 7.4914359e-02 1.9713326e+00 5.2238590e+00 - 9.1433628e-02 1.8953686e+00 5.2493311e+00 - 1.0320607e-01 1.8379455e+00 5.3191737e+00 - 1.4173069e-01 1.6588575e+00 5.0926801e+00 - 1.5891580e-01 1.5786302e+00 5.0937280e+00 - 1.2816313e-01 1.7175797e+00 5.6926106e+00 - 2.3777353e-01 1.2087324e+00 4.4878183e+00 - 2.5181953e-01 1.1427881e+00 4.4898832e+00 - 2.6591834e-01 1.0777816e+00 4.4907000e+00 - 2.7779582e-01 1.0237765e+00 4.5285341e+00 - 2.8936707e-01 9.6526145e-01 4.5559795e+00 - 2.9756780e-01 9.2928004e-01 4.6694416e+00 - 2.4867052e-01 1.1494279e+00 5.8911037e+00 - 7.8476430e-02 1.9328807e+00 9.9036034e+00 - 2.9657058e-01 9.2715619e-01 5.6547677e+00 - 3.1460260e-01 8.4462823e-01 5.6509177e+00 - 3.2948272e-01 7.7267093e-01 5.7146497e+00 - 2.5848723e-01 1.0933098e+00 8.4671854e+00 - 3.6015973e-01 6.2649822e-01 5.8583393e+00 - 3.7821969e-01 5.4367783e-01 5.8688212e+00 - 4.1219454e-01 3.8513520e-01 5.0814516e+00 - 4.3135526e-01 2.9916323e-01 4.8684063e+00 - 4.4529603e-01 2.3186228e-01 4.8632297e+00 - 4.5928962e-01 1.6549916e-01 4.8568051e+00 - 4.6600935e-01 1.3104911e-01 6.0487310e+00 - 4.8333559e-01 4.5760741e-02 6.1903007e+00 - -7.5427180e-01 6.8799933e+00 -8.7548832e-01 - -8.5446026e-01 7.4262686e+00 -8.8399464e-01 - -1.0458339e+00 8.4736930e+00 -9.9075023e-01 - -1.1810433e+00 9.2189319e+00 -9.9423685e-01 - -1.3405621e+00 1.0092076e+01 -9.9667385e-01 - -1.5377413e+00 1.1170812e+01 -1.0052151e+00 - -1.6742952e+00 1.1922413e+01 -9.2270082e-01 - -1.9045274e+00 1.3180896e+01 -8.8663901e-01 - -2.2844933e+00 1.5261999e+01 -9.0915455e-01 - -2.9088657e+00 1.8687435e+01 -1.0018815e+00 - -1.7850512e+00 1.2511972e+01 1.2184769e+00 - -1.7837118e+00 1.2505871e+01 1.4404430e+00 - -1.7734982e+00 1.2447939e+01 1.6596045e+00 - -1.7744263e+00 1.2454018e+01 1.8816847e+00 - -2.1597761e+00 1.4552954e+01 3.6039758e+00 - -2.1808197e+00 1.4669953e+01 3.8940991e+00 - -2.1735477e+00 1.4627366e+01 4.1560756e+00 - -2.1631489e+00 1.4570398e+01 4.4150375e+00 - -2.2360269e+00 1.4968525e+01 4.7889333e+00 - -2.1357954e+00 1.4416406e+01 4.9220811e+00 - -1.5378640e+00 1.1140822e+01 4.2439375e+00 - -1.5252942e+00 1.1073481e+01 4.4381171e+00 - -1.7129231e+00 1.2098354e+01 4.9921646e+00 - -2.1880127e+00 1.4697742e+01 6.1397442e+00 - -2.1821996e+00 1.4663181e+01 6.4201569e+00 - -1.2666091e+00 9.6537159e+00 4.7637720e+00 - -1.2661196e+00 9.6514384e+00 4.9607241e+00 - -1.7124983e+00 1.2090789e+01 6.2128402e+00 - -1.2706177e+00 9.6712367e+00 5.3737859e+00 - -1.2814204e+00 9.7286729e+00 5.6081118e+00 - -1.1305363e+00 8.9053624e+00 5.4120019e+00 - -1.1556894e+00 9.0384738e+00 5.6782273e+00 - -1.1161851e+00 8.8258693e+00 5.7674683e+00 - -1.1643828e+00 9.0868926e+00 6.1171368e+00 - -1.1108745e+00 8.7937826e+00 6.1575976e+00 - -1.0381748e+00 8.3914368e+00 6.1224285e+00 - -1.2631575e+00 9.6205268e+00 7.1072763e+00 - -1.1790542e+00 9.1598732e+00 7.0429736e+00 - -7.3670630e-01 6.7455160e+00 5.6228438e+00 - -1.0795053e+00 8.6154925e+00 7.1291864e+00 - -1.0864437e+00 8.6527940e+00 7.3869093e+00 - -1.6219377e+00 1.1574549e+01 9.8614158e+00 - -4.4441505e-01 5.1484884e+00 5.0867618e+00 - -4.3289830e-01 5.0854119e+00 5.1838181e+00 - -4.3784860e-01 5.1103638e+00 5.3569328e+00 - -4.2050882e-01 5.0125050e+00 5.4272339e+00 - -3.7389584e-01 4.7603500e+00 5.3549804e+00 - -3.9901539e-01 4.8932133e+00 5.6364365e+00 - -4.2158705e-01 5.0182005e+00 5.9239726e+00 - -3.8179833e-01 4.8008636e+00 5.8779781e+00 - -3.7711223e-01 4.7715227e+00 6.0198698e+00 - -3.7814002e-01 4.7778362e+00 6.2061949e+00 - -3.5634856e-01 4.6554678e+00 6.2529470e+00 - -3.3798596e-01 4.5577456e+00 6.3272399e+00 - -1.0691203e+00 8.5328424e+00 1.1331578e+01 - -5.7296439e-01 5.8334864e+00 8.3192933e+00 - -4.8584316e-01 5.3552176e+00 7.9647819e+00 - -4.8676925e-01 5.3592493e+00 8.2264117e+00 - -7.1035809e-01 6.5760548e+00 1.0196872e+01 - -4.1377810e-01 4.9612954e+00 8.1992343e+00 - -3.8512026e-01 4.8039298e+00 8.2363564e+00 - -5.9372464e-01 5.9333229e+00 1.0282624e+01 - -4.8663078e-01 5.3502131e+00 9.6996732e+00 - -1.1918346e-01 3.3550825e+00 6.6738705e+00 - -2.7782688e-01 4.2168272e+00 8.4209475e+00 - -2.5734060e-01 4.1031972e+00 8.5208427e+00 - -2.4634299e-01 4.0424619e+00 8.7249189e+00 - 1.2250072e-01 2.0376885e+00 5.0627978e+00 - 1.4211632e-01 1.9333897e+00 5.0264706e+00 - 1.5189716e-01 1.8766410e+00 5.0872811e+00 - 1.4065197e-01 1.9380625e+00 5.4214365e+00 - 1.3373596e-01 1.9734799e+00 5.7220050e+00 - 1.9289054e-01 1.6562521e+00 5.1629797e+00 - 2.1296955e-01 1.5450408e+00 5.0890438e+00 - 2.2067601e-01 1.5014994e+00 5.1910673e+00 - 2.7354332e-01 1.2153440e+00 4.5835902e+00 - 2.9053830e-01 1.1198873e+00 4.4999852e+00 - 3.0257624e-01 1.0539703e+00 4.5001588e+00 - 3.1339226e-01 9.9900408e-01 4.5375462e+00 - 3.2314433e-01 9.4305705e-01 4.5740875e+00 - 3.3092129e-01 9.0111045e-01 4.6679219e+00 - 2.7642813e-01 1.1922814e+00 6.2421543e+00 - 9.9591672e-02 2.1315713e+00 1.1182261e+01 - 3.3231248e-01 8.8932028e-01 5.6432972e+00 - 3.4565227e-01 8.1051230e-01 5.6682284e+00 - 3.5801921e-01 7.4464560e-01 5.7707236e+00 - 3.6609656e-01 6.9839485e-01 6.0406855e+00 - 3.8526993e-01 5.9262500e-01 5.8934967e+00 - 3.9774453e-01 5.2503994e-01 6.0624579e+00 - 4.3363966e-01 3.3598475e-01 4.8854992e+00 - 4.4634079e-01 2.6629883e-01 4.8510116e+00 - 4.5834256e-01 1.9957697e-01 4.8551299e+00 - 4.6248995e-01 1.7383921e-01 6.0174059e+00 - 4.7726131e-01 8.7302784e-02 6.0096687e+00 - -5.1955427e-01 6.7366640e+00 -8.9079284e-01 - -6.2081892e-01 7.3994920e+00 -9.3698124e-01 - -7.3893068e-01 8.1814361e+00 -9.8844080e-01 - -8.4486934e-01 8.8807070e+00 -9.9324479e-01 - -9.7008420e-01 9.7084353e+00 -9.9996104e-01 - -1.1112629e+00 1.0635949e+01 -9.9618207e-01 - -1.2844335e+00 1.1779841e+01 -9.9657141e-01 - -1.5098465e+00 1.3269336e+01 -1.0089804e+00 - -1.7566451e+00 1.4900215e+01 -9.8778172e-01 - -2.0688671e+00 1.6955743e+01 -9.5819061e-01 - -2.4745584e+00 1.9634361e+01 -9.1720720e-01 - -1.6701958e+00 1.4287342e+01 4.4653058e+00 - -1.7173660e+00 1.4598437e+01 4.8146006e+00 - -1.4572746e+00 1.2882400e+01 4.6097890e+00 - -1.7838100e+00 1.5036762e+01 5.5005612e+00 - -1.3244224e+00 1.2004390e+01 4.8249925e+00 - -1.3009757e+00 1.1852571e+01 5.0077531e+00 - -1.3291337e+00 1.2033615e+01 5.3063755e+00 - -1.3237790e+00 1.1994360e+01 5.5321549e+00 - -1.3759343e+00 1.2337349e+01 5.9116464e+00 - -1.0173495e+00 9.9761363e+00 5.1764595e+00 - -1.0119647e+00 9.9391844e+00 5.3678829e+00 - -8.9187652e-01 9.1509865e+00 5.2151866e+00 - -8.9096970e-01 9.1393655e+00 5.4062892e+00 - -8.3999943e-01 8.8048286e+00 5.4375953e+00 - -8.2964118e-01 8.7358896e+00 5.5969244e+00 - -8.0291852e-01 8.5597504e+00 5.6979622e+00 - -9.7958626e-01 9.7164828e+00 6.5571220e+00 - -9.5069162e-01 9.5258533e+00 6.6719773e+00 - -9.5383531e-01 9.5440107e+00 6.9123986e+00 - -9.2422406e-01 9.3490078e+00 7.0208571e+00 - -8.5065330e-01 8.8646577e+00 6.9311555e+00 - -7.9118699e-01 8.4757836e+00 6.8885952e+00 - -7.3201169e-01 8.0830368e+00 6.8283056e+00 - -9.2217115e-01 9.3324057e+00 7.9809466e+00 - -2.9607865e-01 5.2178058e+00 5.0471833e+00 - -2.7745618e-01 5.0926772e+00 5.0950924e+00 - -4.7518954e-01 6.3946836e+00 6.3288868e+00 - -2.8530083e-01 5.1434520e+00 5.4411660e+00 - -2.8346920e-01 5.1327317e+00 5.5909677e+00 - -2.5433738e-01 4.9364763e+00 5.5727346e+00 - -2.5959652e-01 4.9716387e+00 5.7692770e+00 - -2.6261462e-01 4.9944100e+00 5.9614107e+00 - -2.3359542e-01 4.7967388e+00 5.9347377e+00 - -2.0713618e-01 4.6221047e+00 5.9244656e+00 - -2.2211863e-01 4.7235440e+00 6.2116145e+00 - -2.0985924e-01 4.6400133e+00 6.3016653e+00 - -1.9955358e-01 4.5727170e+00 6.4132549e+00 - -9.5295793e-01 9.5044768e+00 1.2656926e+01 - -6.9022466e-01 7.7818735e+00 1.0890296e+01 - -3.6667884e-01 5.6593209e+00 8.4562711e+00 - -3.9216886e-01 5.8241651e+00 8.9569243e+00 - -3.2673356e-01 5.3987957e+00 8.6515010e+00 - -2.5526009e-01 4.9292318e+00 8.2513009e+00 - -3.6719092e-01 5.6548851e+00 9.6378502e+00 - -1.7001223e-01 4.3685599e+00 7.9318041e+00 - -1.4769825e-01 4.2224312e+00 7.9653072e+00 - -6.4430786e-03 3.2984509e+00 6.6603488e+00 - -3.6989459e-01 5.6645679e+00 1.1121019e+01 - -1.1472096e-01 3.9974237e+00 8.4428784e+00 - 1.8486697e-01 2.0465435e+00 4.9736671e+00 - 1.9272156e-01 1.9909915e+00 5.0360325e+00 - 2.0290969e-01 1.9253347e+00 5.0795581e+00 - 2.0386707e-01 1.9156651e+00 5.2494381e+00 - 2.0628541e-01 1.8974703e+00 5.4110189e+00 - 2.0124530e-01 1.9307729e+00 5.7116801e+00 - 2.2452747e-01 1.7773388e+00 5.5590075e+00 - 2.6444457e-01 1.5175339e+00 5.1026985e+00 - 2.7108956e-01 1.4730313e+00 5.2042753e+00 - 3.1705434e-01 1.1747811e+00 4.5468751e+00 - 3.2913479e-01 1.0949778e+00 4.5098867e+00 - 3.3835477e-01 1.0316844e+00 4.5190595e+00 - 3.4774822e-01 9.7080853e-01 4.5367225e+00 - 3.5568112e-01 9.1742957e-01 4.5823597e+00 - 3.6315370e-01 8.7098770e-01 4.6661050e+00 - 3.1899029e-01 1.1506257e+00 6.2428450e+00 - 3.5271166e-01 9.2984491e-01 5.6156408e+00 - 3.6448342e-01 8.5664338e-01 5.6707426e+00 - 3.7669948e-01 7.7637667e-01 5.6851396e+00 - 3.8208609e-01 7.3479762e-01 5.9651002e+00 - 3.9371891e-01 6.5790705e-01 6.0467173e+00 - 4.0995245e-01 5.5327116e-01 5.8985897e+00 - 4.3488502e-01 3.9377134e-01 5.1213354e+00 - 4.4950333e-01 3.0158505e-01 4.8584628e+00 - 4.5869926e-01 2.3655212e-01 4.8931529e+00 - 4.6932925e-01 1.6690511e-01 4.8367492e+00 - 4.7405408e-01 1.3207167e-01 6.0387187e+00 - 4.8651648e-01 4.6553129e-02 6.2302914e+00 - -2.8400520e-01 6.4458599e+00 -9.8633576e-01 - -3.3356334e-01 6.8513781e+00 -9.8030157e-01 - -3.9095116e-01 7.3263575e+00 -9.7874680e-01 - -4.5907925e-01 7.8889701e+00 -9.8285025e-01 - -5.4353897e-01 8.5794595e+00 -9.9696550e-01 - -6.3059976e-01 9.2921417e+00 -9.9153399e-01 - -7.2533384e-01 1.0076051e+01 -9.7505067e-01 - -8.6346117e-01 1.1203944e+01 -9.9238875e-01 - -1.0170863e+00 1.2472051e+01 -9.9251798e-01 - -1.2031426e+00 1.3998282e+01 -9.8485477e-01 - -1.4539634e+00 1.6060411e+01 -9.9001029e-01 - -1.7899819e+00 1.8816716e+01 -9.9654244e-01 - -1.0671822e+00 1.2830337e+01 4.4601644e+00 - -1.0729149e+00 1.2878090e+01 5.2121746e+00 - -8.2645028e-01 1.0850732e+01 4.7612814e+00 - -8.0658732e-01 1.0690776e+01 4.9172319e+00 - -6.4605012e-01 9.3704159e+00 4.6211276e+00 - -5.9964400e-01 8.9933033e+00 4.6580663e+00 - -6.4131028e-01 9.3301582e+00 4.9874335e+00 - -6.0308736e-01 9.0155558e+00 5.0410636e+00 - -5.7822058e-01 8.8091138e+00 5.1355978e+00 - -6.1878614e-01 9.1462120e+00 5.4913788e+00 - -6.6030158e-01 9.4832408e+00 5.8647908e+00 - -6.6725160e-01 9.5377695e+00 6.1058445e+00 - -7.1214577e-01 9.8993294e+00 6.5247248e+00 - -6.8785953e-01 9.6988638e+00 6.6378911e+00 - -6.5297564e-01 9.4116883e+00 6.6943941e+00 - -5.6619077e-01 8.7055688e+00 6.4775802e+00 - -5.4026278e-01 8.4848286e+00 6.5480826e+00 - -5.3656151e-01 8.4530760e+00 6.7411623e+00 - -5.4247740e-01 8.5073159e+00 6.9978431e+00 - -8.6403981e-01 1.1124710e+01 9.1383136e+00 - -5.3397544e-01 8.4282707e+00 7.3955756e+00 - -1.2590396e-01 5.1015212e+00 5.0132213e+00 - -1.2648683e-01 5.1007744e+00 5.1589414e+00 - -1.2477337e-01 5.0885940e+00 5.2994042e+00 - -1.3250903e-01 5.1484916e+00 5.5062560e+00 - -9.8030771e-02 4.8627163e+00 5.4088026e+00 - -1.0412956e-01 4.9165262e+00 5.6162450e+00 - -1.2755590e-01 5.1068439e+00 5.9659443e+00 - -9.5087061e-02 4.8373737e+00 5.8712034e+00 - -1.0270785e-01 4.8976736e+00 6.1064697e+00 - -9.2428758e-02 4.8143920e+00 6.1991237e+00 - -9.0394549e-02 4.7900332e+00 6.3573064e+00 - -3.4785952e-01 6.8856686e+00 8.9758771e+00 - -2.4325522e-01 6.0376025e+00 8.2456134e+00 - -2.2575535e-01 5.8921569e+00 8.3273721e+00 - -2.4443706e-01 6.0393757e+00 8.7843979e+00 - -1.5660501e-01 5.3247338e+00 8.1148390e+00 - -1.4838738e-01 5.2532155e+00 8.2802159e+00 - -1.5846460e-01 5.3311907e+00 8.6663126e+00 - -9.0913781e-02 4.7866576e+00 8.1454814e+00 - -5.5754650e-02 4.4993178e+00 7.9770133e+00 - -3.6549084e-02 4.3361714e+00 7.9872453e+00 - -1.2329981e-02 4.1429054e+00 7.9424624e+00 - 9.7658257e-02 3.2471790e+00 6.6634368e+00 - -3.0647950e-04 4.0394389e+00 8.3374730e+00 - 2.1516814e-02 3.8557801e+00 8.3014424e+00 - 2.5127230e-01 2.0025354e+00 4.9560040e+00 - 2.5526067e-01 1.9640087e+00 5.0534978e+00 - 2.5517596e-01 1.9687900e+00 5.2505058e+00 - 2.6312319e-01 1.8992368e+00 5.2936367e+00 - 2.7468014e-01 1.8090614e+00 5.2895030e+00 - 2.7557278e-01 1.7973272e+00 5.4783085e+00 - 2.8373847e-01 1.7305511e+00 5.5372207e+00 - 3.1617558e-01 1.4646524e+00 5.0501200e+00 - 3.2744420e-01 1.3716572e+00 5.0090816e+00 - 3.5170326e-01 1.1789254e+00 4.6521872e+00 - 3.6467409e-01 1.0692331e+00 4.5194477e+00 - 3.7265175e-01 1.0025017e+00 4.5184850e+00 - 3.8022541e-01 9.4418902e-01 4.5451441e+00 - 3.8709684e-01 8.8984892e-01 4.5903347e+00 - 3.9320584e-01 8.3848448e-01 4.6541063e+00 - 2.6376025e-01 1.8555476e+00 9.7837233e+00 - 3.8557989e-01 8.9315599e-01 5.6237558e+00 - 3.9423097e-01 8.1861169e-01 5.6682299e+00 - 4.0426430e-01 7.3594481e-01 5.6720455e+00 - 4.0382987e-01 7.3204353e-01 6.2388395e+00 - 4.2024236e-01 6.0451195e-01 5.9531691e+00 - 4.3145591e-01 5.1159237e-01 5.8934041e+00 - 4.5069175e-01 3.5788519e-01 5.1046855e+00 - 4.6180200e-01 2.7136045e-01 4.8909161e+00 - 4.7005915e-01 2.0634680e-01 4.9450350e+00 - 4.7819589e-01 1.3284974e-01 4.8081370e+00 - 4.8281132e-01 8.9921748e-02 6.1296535e+00 - -4.1385954e-02 5.9027128e+00 -9.8396925e-01 - -7.4325202e-02 6.2687351e+00 -9.8550100e-01 - -1.0771641e-01 6.6265042e+00 -9.7200481e-01 - -1.4736468e-01 7.0634217e+00 -9.6798115e-01 - -2.0361918e-01 7.6743724e+00 -9.9416653e-01 - -2.5734353e-01 8.2594691e+00 -9.9255946e-01 - -3.2227716e-01 8.9742229e+00 -9.9928142e-01 - -3.9681621e-01 9.7781574e+00 -9.9932962e-01 - -4.8843406e-01 1.0780284e+01 -1.0082479e+00 - -5.8985951e-01 1.1884202e+01 -9.9919847e-01 - -7.1972684e-01 1.3296389e+01 -9.9787082e-01 - -8.8565932e-01 1.5105792e+01 -9.9989468e-01 - -1.1178768e+00 1.7641411e+01 -1.0218132e+00 - -1.3627808e+00 2.0310957e+01 -9.6795823e-01 - -1.6700609e+00 2.3646929e+01 -4.5718815e-01 - -4.6001314e-01 1.0412538e+01 3.8976457e+00 - -4.3682064e-01 1.0160440e+01 4.0200739e+00 - -8.6580880e-01 1.4817103e+01 5.6880548e+00 - -7.2017962e-01 1.3231355e+01 5.4428800e+00 - -4.0952810e-01 9.8578145e+00 4.5032111e+00 - -4.3325339e-01 1.0112446e+01 4.7943715e+00 - -3.5193296e-01 9.2296413e+00 4.6486838e+00 - -4.2192543e-01 9.9830062e+00 5.1503178e+00 - -3.5811337e-01 9.2882571e+00 5.0536336e+00 - -3.3087042e-01 8.9906072e+00 5.1121021e+00 - -3.2099692e-01 8.8816068e+00 5.2518838e+00 - -3.8465335e-01 9.5722274e+00 5.7904155e+00 - -3.5263576e-01 9.2226499e+00 5.8189761e+00 - -4.4257840e-01 1.0196604e+01 6.5570568e+00 - -4.1768578e-01 9.9252133e+00 6.6364720e+00 - -6.5955447e-01 1.2537743e+01 8.4126416e+00 - -3.1677013e-01 8.8234103e+00 6.4271746e+00 - -2.5614270e-01 8.1645423e+00 6.2211073e+00 - -2.9804324e-01 8.6205520e+00 6.7276240e+00 - -3.0632734e-01 8.7009084e+00 7.0023549e+00 - -2.9572163e-01 8.5871436e+00 7.1480742e+00 - -2.5586676e-01 8.1580658e+00 7.0598592e+00 - 2.7299865e-02 5.0886220e+00 4.9196969e+00 - 2.7829430e-02 5.0897594e+00 5.0643160e+00 - 1.4385003e-02 5.2342186e+00 5.3309106e+00 - 2.6237896e-02 5.0970262e+00 5.3700449e+00 - 5.0401899e-04 5.3785845e+00 5.7767335e+00 - -3.0271696e-02 5.7058094e+00 6.2484836e+00 - -4.3654803e-03 5.4264448e+00 6.1686890e+00 - 1.3119851e-02 5.2356268e+00 6.1649777e+00 - 4.1786368e-02 4.9221476e+00 6.0277761e+00 - 5.6910690e-02 4.7580195e+00 6.0334760e+00 - -3.5139049e-01 9.1513294e+00 1.1025304e+01 - -3.3023391e-01 8.9168719e+00 1.1116737e+01 - -1.3658469e-01 6.8313987e+00 9.0287135e+00 - -3.4013977e-01 9.0218746e+00 1.1986297e+01 - -3.1481313e-01 8.7428210e+00 1.2033147e+01 - -1.3516135e-02 5.4996187e+00 8.1949395e+00 - 9.5453308e-03 5.2552411e+00 8.1294564e+00 - 6.6749562e-03 5.2750669e+00 8.4239606e+00 - 4.1399528e-02 4.9028107e+00 8.1609622e+00 - 6.8411170e-02 4.6131114e+00 7.9956645e+00 - 7.5738485e-02 4.5282896e+00 8.1344695e+00 - 9.5678366e-02 4.3151395e+00 8.0678657e+00 - 1.0414499e-01 4.2171593e+00 8.1854858e+00 - 2.0027948e-01 3.1885059e+00 6.6570870e+00 - 1.3188997e-01 3.9118741e+00 8.2322130e+00 - 1.5063220e-01 3.7124476e+00 8.1577308e+00 - 3.1409456e-01 1.9646210e+00 4.9556843e+00 - 3.2104650e-01 1.8956670e+00 4.9894803e+00 - 3.1809744e-01 1.9174427e+00 5.2222127e+00 - 3.0569977e-01 2.0498520e+00 5.7319944e+00 - 3.1235102e-01 1.9748849e+00 5.7857131e+00 - 3.3070797e-01 1.7785685e+00 5.5311579e+00 - 3.5790737e-01 1.4941947e+00 5.0090566e+00 - 3.6426885e-01 1.4169120e+00 5.0158333e+00 - 3.6924650e-01 1.3629965e+00 5.0874472e+00 - 3.9045795e-01 1.1415701e+00 4.6338661e+00 - 3.9933278e-01 1.0450039e+00 4.5382510e+00 - 4.0525081e-01 9.7737184e-01 4.5368448e+00 - 4.1076483e-01 9.1815844e-01 4.5630604e+00 - 4.1645416e-01 8.6137743e-01 4.5980660e+00 - 4.1986769e-01 8.1413114e-01 4.6808748e+00 - 4.0982065e-01 9.1800562e-01 5.5275634e+00 - 4.1596451e-01 8.5011532e-01 5.6019620e+00 - 4.2285745e-01 7.7862684e-01 5.6654199e+00 - 4.2835560e-01 7.1412922e-01 5.7871137e+00 - 4.3066263e-01 6.8163579e-01 6.1855918e+00 - 4.4225816e-01 5.5734312e-01 5.8986900e+00 - 4.4835452e-01 4.9556296e-01 6.1565142e+00 - 4.6557819e-01 3.1258196e-01 4.9781696e+00 - 4.7247240e-01 2.4419800e-01 4.9830021e+00 - 4.7892907e-01 1.7180192e-01 4.9267597e+00 - 4.8116373e-01 1.3314308e-01 6.0487344e+00 - 4.8863611e-01 4.7417575e-02 6.2502604e+00 - 3.8127057e-01 1.9140498e+00 -9.8526594e-01 - 3.7707183e-01 1.9767683e+00 -9.7972318e-01 - 1.7687690e-01 5.1897720e+00 -9.9660581e-01 - 1.6013110e-01 5.4588750e+00 -9.9105370e-01 - 1.4114145e-01 5.7571513e+00 -9.8652631e-01 - 1.2003113e-01 6.1034210e+00 -9.8765733e-01 - 9.7704429e-02 6.4622332e+00 -9.8008806e-01 - 6.6415130e-02 6.9556767e+00 -9.9912927e-01 - 3.4531376e-02 7.4717898e+00 -1.0067696e+00 - 1.2595970e-04 8.0285663e+00 -1.0065882e+00 - -4.1753243e-02 8.6938355e+00 -1.0122129e+00 - -8.9952487e-02 9.4698117e+00 -1.0180532e+00 - -1.4549502e-01 1.0355839e+01 -1.0183634e+00 - -2.1611344e-01 1.1489889e+01 -1.0316159e+00 - -2.9425635e-01 1.2746767e+01 -1.0246486e+00 - -3.9407191e-01 1.4340780e+01 -1.0216622e+00 - -5.3305346e-01 1.6562993e+01 -1.0403108e+00 - -9.8410626e-01 2.3785474e+01 -6.7050606e-01 - -9.9443123e-01 2.3940850e+01 -2.6119253e-01 - -1.5222115e-01 1.0382760e+01 3.5918380e+00 - -1.5557002e-01 1.0432371e+01 3.7988698e+00 - -1.5471232e-01 1.0419842e+01 3.9918198e+00 - -1.6674575e-01 1.0604759e+01 4.2466980e+00 - -1.5048375e-01 1.0337764e+01 4.3636961e+00 - -1.4345556e-01 1.0230137e+01 4.5276575e+00 - -1.4672859e-01 1.0280354e+01 4.7469741e+00 - -1.3296811e-01 1.0054699e+01 4.8652526e+00 - -1.4861436e-01 1.0309595e+01 5.1715688e+00 - -1.7097329e-01 1.0649583e+01 5.5268946e+00 - -1.4551647e-01 1.0240744e+01 5.5660284e+00 - -1.4264839e-01 1.0195113e+01 5.7613998e+00 - -1.1302568e-01 9.7253562e+00 5.7504473e+00 - -3.0876484e-01 1.2833729e+01 7.5490313e+00 - -3.0343000e-01 1.2743901e+01 7.7865169e+00 - -2.9413913e-01 1.2588900e+01 7.9889458e+00 - -2.8505049e-01 1.2430735e+01 8.1880276e+00 - -2.9024106e-01 1.2509123e+01 8.5278168e+00 - -5.1946315e-02 8.7279071e+00 6.4621902e+00 - -3.0241332e-01 1.2699721e+01 9.2601048e+00 - -5.5278390e-02 8.7805319e+00 6.9316972e+00 - -4.0299463e-02 8.5449295e+00 6.9925874e+00 - -2.6297324e-02 8.3100741e+00 7.0471391e+00 - 1.5769053e-01 5.3973397e+00 5.0736733e+00 - 1.8339403e-01 4.9870766e+00 4.9028166e+00 - 1.8702061e-01 4.9262756e+00 4.9957043e+00 - 1.3755623e-01 5.7052074e+00 5.7945187e+00 - 1.4169470e-01 5.6353026e+00 5.9066755e+00 - 1.3076004e-01 5.8015798e+00 6.2318520e+00 - 1.5118123e-01 5.4828963e+00 6.1211903e+00 - 1.8091067e-01 5.0121440e+00 5.8481629e+00 - 1.8828660e-01 4.8992591e+00 5.9067512e+00 - 1.7374048e-01 5.1176907e+00 6.3081745e+00 - -1.5101289e-01 1.0226004e+01 1.1983304e+01 - -1.2704589e-01 9.8458744e+00 1.1952446e+01 - -1.8778142e-01 1.0799311e+01 1.3443386e+01 - -8.7968494e-02 9.2149038e+00 1.1998948e+01 - 8.4998287e-02 6.5027403e+00 9.0425565e+00 - -1.0891426e-01 9.5326617e+00 1.3220529e+01 - 1.1763912e-01 5.9719615e+00 8.9376760e+00 - 1.5768279e-01 5.3400739e+00 8.3614498e+00 - 1.7096885e-01 5.1305265e+00 8.3390641e+00 - 1.7084711e-01 5.1303703e+00 8.6183170e+00 - 2.0137106e-01 4.6488617e+00 8.1701987e+00 - 2.1486157e-01 4.4287852e+00 8.0976687e+00 - 2.2389706e-01 4.2784478e+00 8.1312611e+00 - 2.2820445e-01 4.2083456e+00 8.3001967e+00 - 2.4127925e-01 3.9981415e+00 8.2239782e+00 - 2.4997610e-01 3.8582923e+00 8.2663669e+00 - 2.6335920e-01 3.6536462e+00 8.1812618e+00 - 2.9861096e-01 3.1037619e+00 7.3722379e+00 - 2.9640050e-01 3.1314399e+00 7.7246225e+00 - 3.0135928e-01 3.0417017e+00 7.8423583e+00 - 3.6769691e-01 2.0138966e+00 5.7499057e+00 - 3.7402668e-01 1.9195560e+00 5.7565228e+00 - 3.3166926e-01 2.5730099e+00 7.7124024e+00 - 4.0332597e-01 1.4654802e+00 5.0314189e+00 - 4.0683009e-01 1.4047320e+00 5.0848561e+00 - 4.0544697e-01 1.4167586e+00 5.3655183e+00 - 4.2344713e-01 1.1358464e+00 4.7202512e+00 - 4.3187347e-01 1.0188918e+00 4.5569599e+00 - 4.3579147e-01 9.5135112e-01 4.5549608e+00 - 4.3930608e-01 8.9223399e-01 4.5806834e+00 - 4.4287556e-01 8.3355534e-01 4.6152950e+00 - 4.4610514e-01 7.8380768e-01 4.6879156e+00 - 4.3796998e-01 8.9801779e-01 5.6237933e+00 - 4.4133188e-01 8.4520152e-01 5.7962874e+00 - 4.4818362e-01 7.3483235e-01 5.6424931e+00 - 4.4717563e-01 7.3644750e-01 6.2388553e+00 - 4.5515335e-01 6.1539209e-01 6.0126912e+00 - 4.6983761e-01 4.0571460e-01 4.8592082e+00 - 4.6549621e-01 4.4911340e-01 6.1307652e+00 - 4.7750982e-01 2.7839276e-01 4.9707713e+00 - 4.8178828e-01 2.0466419e-01 4.8850717e+00 - 4.8624062e-01 1.3387230e-01 4.7981247e+00 - 4.8767659e-01 8.9647642e-02 6.0896877e+00 - 4.3863780e-01 1.8854066e+00 -9.8731097e-01 - 4.3642983e-01 1.9479599e+00 -9.8267347e-01 - 4.3523052e-01 2.0105364e+00 -9.7634124e-01 - 3.5008256e-01 4.5924563e+00 -9.9794718e-01 - 3.4148975e-01 4.8481896e+00 -1.0093075e+00 - 3.3437650e-01 5.0777106e+00 -1.0013617e+00 - 3.2600462e-01 5.3362410e+00 -9.9654127e-01 - 3.1603094e-01 5.6347484e+00 -9.9658649e-01 - 3.0482020e-01 5.9624375e+00 -9.9626134e-01 - 2.9314258e-01 6.3489720e+00 -1.0032415e+00 - 2.7931584e-01 6.7659526e+00 -1.0057028e+00 - 2.6241794e-01 7.2817815e+00 -1.0210310e+00 - 2.4481194e-01 7.8183405e+00 -1.0237606e+00 - 2.2493343e-01 8.4164213e+00 -1.0225024e+00 - 2.0036983e-01 9.1527149e+00 -1.0311368e+00 - 1.7377756e-01 9.9708304e+00 -1.0306786e+00 - 1.3987679e-01 1.1016391e+01 -1.0440981e+00 - 1.0284100e-01 1.2124618e+01 -1.0315537e+00 - 5.3829651e-02 1.3631740e+01 -1.0400138e+00 - -9.2907593e-03 1.5567812e+01 -1.0526252e+00 - -9.4641706e-02 1.8162851e+01 -1.0728746e+00 - -4.9698617e-01 3.0405041e+01 -3.3262080e-01 - 1.4995328e-01 1.0545073e+01 3.5316040e+00 - 1.5282220e-01 1.0451098e+01 3.7028274e+00 - 1.4597457e-01 1.0671912e+01 3.9597076e+00 - 1.5484760e-01 1.0398519e+01 4.0802709e+00 - 1.5484066e-01 1.0371860e+01 4.2704189e+00 - 1.4227595e-01 1.0759127e+01 4.6000232e+00 - 1.6357397e-01 1.0119097e+01 4.5839046e+00 - 1.6559146e-01 1.0027902e+01 4.7494893e+00 - 1.3001384e-01 1.1095090e+01 5.3709978e+00 - 1.4110889e-01 1.0777092e+01 5.4646117e+00 - 1.4300915e-01 1.0715476e+01 5.6600768e+00 - 1.4755414e-01 1.0551087e+01 5.8091316e+00 - 1.8685259e-01 9.3651858e+00 5.4675942e+00 - 1.9580697e-01 9.0797643e+00 5.5278753e+00 - 2.0965844e-01 8.6803016e+00 5.5195601e+00 - 2.2219182e-01 8.2925686e+00 5.5034656e+00 - 2.2126740e-01 8.3002239e+00 5.6967325e+00 - 2.2469618e-01 8.2169118e+00 5.8409938e+00 - 3.0443001e-01 5.8124631e+00 4.5629867e+00 - 3.0554410e-01 5.7750784e+00 4.6799659e+00 - 3.0093083e-01 5.9020032e+00 4.9072214e+00 - 3.0021895e-01 5.9149670e+00 5.0662833e+00 - 3.0755710e-01 5.7050792e+00 5.0701835e+00 - 3.0955764e-01 5.6336480e+00 5.1692125e+00 - 3.0130999e-01 5.8924405e+00 5.5225492e+00 - 3.3423065e-01 4.8974121e+00 4.8965965e+00 - 3.3849015e-01 4.7674454e+00 4.9306153e+00 - 3.2640269e-01 5.1233708e+00 5.3769048e+00 - 3.1509130e-01 5.4428203e+00 5.8167787e+00 - 3.1307216e-01 5.5128565e+00 6.0529319e+00 - 3.3105514e-01 4.9673620e+00 5.7148791e+00 - 3.3461962e-01 4.8419412e+00 5.7587905e+00 - 3.2633961e-01 5.0805761e+00 6.1706926e+00 - 2.6254303e-01 6.9572644e+00 8.3327933e+00 - 3.2998427e-01 4.9780588e+00 6.4333449e+00 - 2.6212692e-01 6.9555724e+00 8.8633336e+00 - 2.6730824e-01 6.8040048e+00 8.9683986e+00 - 2.7070570e-01 6.7026064e+00 9.1321753e+00 - 3.4998209e-01 4.3625798e+00 6.4858093e+00 - 2.9245482e-01 6.0490756e+00 8.8853344e+00 - 3.6389563e-01 3.9545447e+00 6.3454532e+00 - 3.1630731e-01 5.3236030e+00 8.4650110e+00 - 3.2068167e-01 5.1924913e+00 8.5568569e+00 - 3.3398489e-01 4.7842207e+00 8.2293853e+00 - 3.4255090e-01 4.5497193e+00 8.1431795e+00 - 3.4846327e-01 4.3517321e+00 8.1022468e+00 - 3.5251400e-01 4.2322600e+00 8.1857109e+00 - 3.5786604e-01 4.0566994e+00 8.1715097e+00 - 3.6811358e-01 3.7743054e+00 7.9511876e+00 - 3.6917132e-01 3.7307972e+00 8.1668907e+00 - 3.8908876e-01 3.1453193e+00 7.3092550e+00 - 4.2163239e-01 2.2003991e+00 5.6123150e+00 - 4.2326306e-01 2.1402381e+00 5.6954715e+00 - 4.2639101e-01 2.0576164e+00 5.7321680e+00 - 4.2927109e-01 1.9714668e+00 5.7581266e+00 - 4.0449569e-01 2.6644651e+00 7.7641114e+00 - 4.0989400e-01 2.4939160e+00 7.6691635e+00 - 4.4692602e-01 1.4393387e+00 5.0629769e+00 - 4.3967642e-01 1.6539312e+00 5.9409321e+00 - 4.5166185e-01 1.2994684e+00 5.1203095e+00 - 4.5771126e-01 1.1195956e+00 4.7780118e+00 - 4.6217490e-01 9.8941218e-01 4.5657363e+00 - 4.6509104e-01 9.2190239e-01 4.5631411e+00 - 4.6672687e-01 8.6436130e-01 4.5981091e+00 - 4.6829631e-01 8.0577398e-01 4.6321278e+00 - 4.6949754e-01 7.6856986e-01 4.7730271e+00 - 4.6831621e-01 7.8973022e-01 5.2578899e+00 - 4.6826058e-01 7.8339766e-01 5.6753171e+00 - 4.6788597e-01 7.8152160e-01 6.2223866e+00 - 4.7083261e-01 6.8322532e-01 6.1856659e+00 - 4.7531850e-01 5.5786124e-01 5.8887484e+00 - 4.8271068e-01 3.7101168e-01 4.8426181e+00 - 4.8063910e-01 4.0276503e-01 6.1046230e+00 - 4.8682898e-01 2.3836945e-01 4.8831777e+00 - 4.8890991e-01 1.7170663e-01 4.9167906e+00 - 4.8933463e-01 1.3414242e-01 6.0787719e+00 - 4.9206654e-01 4.5777260e-02 6.1003351e+00 - 4.9367354e-01 1.9172982e+00 -9.8511879e-01 - 4.9346745e-01 1.9797749e+00 -9.7958875e-01 - 4.9371168e-01 2.0499759e+00 -9.7954883e-01 - 4.8648123e-01 4.0986885e+00 -9.9896275e-01 - 4.8536254e-01 4.2785092e+00 -9.9481002e-01 - 4.8531854e-01 4.4762013e+00 -9.9304733e-01 - 4.8406193e-01 4.7037862e+00 -9.9675665e-01 - 4.8291179e-01 4.9327376e+00 -9.9302478e-01 - 4.8260526e-01 5.2092598e+00 -9.9985481e-01 - 4.8100302e-01 5.4971748e+00 -1.0010312e+00 - 4.8021658e-01 5.8151180e+00 -1.0024923e+00 - 4.7925702e-01 6.1632238e+00 -1.0027370e+00 - 4.7736758e-01 6.5791537e+00 -1.0118283e+00 - 4.7598100e-01 7.0363212e+00 -1.0180508e+00 - 4.7364289e-01 7.5438195e+00 -1.0218442e+00 - 4.7242647e-01 8.1026579e+00 -1.0205675e+00 - 4.6931817e-01 8.7795677e+00 -1.0274063e+00 - 4.6687947e-01 9.5667810e+00 -1.0340834e+00 - 4.6355377e-01 1.0454739e+01 -1.0330089e+00 - 4.6048133e-01 1.1512249e+01 -1.0308880e+00 - 4.5553585e-01 1.2870252e+01 -1.0395734e+00 - 4.4949796e-01 1.4507566e+01 -1.0403031e+00 - 4.4121980e-01 1.6753987e+01 -1.0588501e+00 - 4.1757711e-01 2.3559891e+01 -1.0638190e+00 - 4.0767238e-01 2.6395782e+01 -8.4870937e-01 - 4.0592221e-01 2.6723946e+01 -4.0351724e-01 - 4.0315365e-01 2.7183866e+01 4.7597221e-02 - 4.5579692e-01 1.1132580e+01 4.4021472e+00 - 4.5561592e-01 1.1004735e+01 4.5743594e+00 - 4.5421414e-01 1.1442183e+01 4.9382650e+00 - 4.5442895e-01 1.1417812e+01 5.1545311e+00 - 4.5393228e-01 1.1446721e+01 5.3925034e+00 - 4.5380295e-01 1.1238360e+01 5.5391504e+00 - 4.5588533e-01 1.0871807e+01 5.6135885e+00 - 4.6144192e-01 9.3717879e+00 5.3690545e+00 - 4.6160349e-01 9.1866825e+00 5.4794093e+00 - 4.6207998e-01 9.0713115e+00 5.6208648e+00 - 4.6434937e-01 8.4859462e+00 5.5109546e+00 - 4.6471255e-01 8.3533811e+00 5.6292294e+00 - 4.6350462e-01 8.4366043e+00 5.8693328e+00 - 4.6194858e-01 8.8986924e+00 6.3453637e+00 - 4.6245406e-01 8.7357184e+00 6.4574281e+00 - 4.6347541e-01 8.4211996e+00 6.4675298e+00 - 4.6373100e-01 8.3666397e+00 6.6415308e+00 - 4.7089207e-01 6.5711163e+00 5.5996622e+00 - 4.7412185e-01 5.7692081e+00 5.1905456e+00 - 4.7393864e-01 5.6470182e+00 5.2545456e+00 - 4.6795033e-01 7.1331438e+00 6.5711891e+00 - 4.7782937e-01 4.8041042e+00 4.8889989e+00 - 4.7854609e-01 4.6815846e+00 4.9272779e+00 - 4.7587591e-01 5.1859995e+00 5.5068580e+00 - 4.7622148e-01 5.0095848e+00 5.5097509e+00 - 4.7679097e-01 4.9158874e+00 5.5828538e+00 - 4.7492516e-01 5.2090025e+00 6.0290747e+00 - 4.7805648e-01 4.6048669e+00 5.6030941e+00 - 4.7884649e-01 4.4050994e+00 5.5604787e+00 - 4.7845169e-01 4.3595680e+00 5.6731633e+00 - 4.7913290e-01 4.1899613e+00 5.6519891e+00 - 4.7865354e-01 4.1742687e+00 5.7998475e+00 - 4.7606756e-01 4.7326495e+00 6.6378872e+00 - 4.7738671e-01 4.4634027e+00 6.5097861e+00 - 4.7779524e-01 4.3048113e+00 6.5080949e+00 - 4.7754433e-01 4.2136265e+00 6.5903904e+00 - 4.7096549e-01 5.5214011e+00 8.5963746e+00 - 4.7183093e-01 5.3822339e+00 8.6833329e+00 - 4.7301759e-01 5.0178061e+00 8.4361751e+00 - 4.7525590e-01 4.6095206e+00 8.0949556e+00 - 4.7570225e-01 4.5112290e+00 8.2167456e+00 - 4.7654606e-01 4.2971499e+00 8.1486034e+00 - 4.7728577e-01 4.0517243e+00 8.0147252e+00 - 4.8181573e-01 3.1087937e+00 6.6063158e+00 - 4.8016526e-01 3.3586744e+00 7.3130868e+00 - 4.8060870e-01 3.2471652e+00 7.3707489e+00 - 4.7853692e-01 3.5611979e+00 8.2981340e+00 - 4.8598697e-01 2.1692713e+00 5.6494977e+00 - 4.8618371e-01 2.0878526e+00 5.6866536e+00 - 4.8675585e-01 1.9825293e+00 5.6671150e+00 - 4.8156556e-01 2.7739712e+00 7.8612610e+00 - 4.8908018e-01 1.5278271e+00 4.9773518e+00 - 4.8845657e-01 1.5810792e+00 5.3416815e+00 - 4.8926479e-01 1.3948664e+00 5.0470873e+00 - 4.8988641e-01 1.3357103e+00 5.1088742e+00 - 4.8966108e-01 1.2646288e+00 5.1315055e+00 - 4.9127440e-01 1.0372297e+00 4.6146614e+00 - 4.9141610e-01 9.5898127e-01 4.5742658e+00 - 4.9151489e-01 8.9410000e-01 4.5807697e+00 - 4.9208926e-01 8.3559777e-01 4.6152910e+00 - 4.9265745e-01 7.7704627e-01 4.6488135e+00 - 4.9243488e-01 7.3392262e-01 4.7697887e+00 - 4.9229880e-01 6.7829576e-01 4.8411181e+00 - 4.9138205e-01 7.4919032e-01 5.7215168e+00 - 4.9034012e-01 7.3785568e-01 6.2389199e+00 - 4.9110197e-01 6.3765858e-01 6.1814808e+00 - 4.9277367e-01 4.1579744e-01 4.9486804e+00 - 4.9342672e-01 3.5534530e-01 5.0449735e+00 - 4.9372483e-01 2.8040974e-01 4.9906966e+00 - 4.9433206e-01 2.0093884e-01 4.8051793e+00 - 4.9422656e-01 1.3339363e-01 4.7981991e+00 - 4.9354003e-01 8.9313086e-02 6.0497187e+00 - 5.4986071e-01 1.8857148e+00 -9.8721175e-01 - 5.5164602e-01 1.9480312e+00 -9.8248708e-01 - 5.5326371e-01 2.0247809e+00 -9.9028794e-01 - 5.5513082e-01 2.0882667e+00 -9.8211714e-01 - 5.5706802e-01 2.1528283e+00 -9.7239787e-01 - 5.5922582e-01 2.2385359e+00 -9.8094430e-01 - 6.0001934e-01 3.8224521e+00 -9.9004231e-01 - 6.0471618e-01 3.9994926e+00 -9.9439895e-01 - 6.0898985e-01 4.1690254e+00 -9.8887091e-01 - 6.1391633e-01 4.3662526e+00 -9.9042005e-01 - 6.1952248e-01 4.5745843e+00 -9.8971768e-01 - 6.2643830e-01 4.8215324e+00 -9.9753644e-01 - 6.3350998e-01 5.0875620e+00 -1.0046954e+00 - 6.4034125e-01 5.3658963e+00 -1.0067529e+00 - 6.4844911e-01 5.6820670e+00 -1.0128873e+00 - 6.5621682e-01 5.9919093e+00 -1.0054912e+00 - 6.6644884e-01 6.3593940e+00 -1.0058597e+00 - 6.7740540e-01 6.8055597e+00 -1.0166219e+00 - 6.9028053e-01 7.2830448e+00 -1.0205305e+00 - 7.0432858e-01 7.8295997e+00 -1.0258510e+00 - 7.2128207e-01 8.4572209e+00 -1.0312834e+00 - 7.3982582e-01 9.1939504e+00 -1.0393043e+00 - 7.6114524e-01 9.9923577e+00 -1.0340646e+00 - 7.8608744e-01 1.0949939e+01 -1.0306917e+00 - 8.1693284e-01 1.2137609e+01 -1.0324974e+00 - 8.5606614e-01 1.3644435e+01 -1.0406861e+00 - 9.0517687e-01 1.5530938e+01 -1.0464389e+00 - 9.7966020e-01 1.8384650e+01 -1.0967548e+00 - 1.0468808e+00 2.0996163e+01 -1.0239417e+00 - 1.1363021e+00 2.4436120e+01 -9.2574928e-01 - 1.1409152e+00 2.4606087e+01 -5.0743560e-01 - 1.1493311e+00 2.4938214e+01 -9.1237153e-02 - 7.9005825e-01 1.1311442e+01 4.3506108e+00 - 7.3783712e-01 9.2966786e+00 3.9313777e+00 - 7.8865458e-01 1.1282476e+01 4.7751702e+00 - 7.3729346e-01 9.3017034e+00 4.2941809e+00 - 7.3642887e-01 9.2620020e+00 4.4630505e+00 - 8.1168940e-01 1.2204056e+01 5.8076979e+00 - 7.8736973e-01 1.1296405e+01 5.6795073e+00 - 8.1752632e-01 1.2450506e+01 6.4141681e+00 - 8.2283618e-01 1.2700479e+01 6.7881811e+00 - 7.3595088e-01 9.2859893e+00 5.4294637e+00 - 7.3187547e-01 9.1617496e+00 5.5685813e+00 - 7.2929231e-01 9.0455236e+00 5.7092970e+00 - 7.2415682e-01 8.8562104e+00 5.8092789e+00 - 7.4241055e-01 9.5723565e+00 6.4160321e+00 - 7.1975283e-01 8.7006784e+00 6.1256589e+00 - 7.3190090e-01 9.1729553e+00 6.6215278e+00 - 7.0877408e-01 8.2639195e+00 6.2651165e+00 - 7.0830976e-01 8.2620572e+00 6.4692630e+00 - 6.6312032e-01 6.4935342e+00 5.4630308e+00 - 6.6174934e-01 6.4472074e+00 5.5988893e+00 - 6.4275925e-01 5.6908373e+00 5.2111925e+00 - 6.7342960e-01 6.9170782e+00 6.3081428e+00 - 6.3443371e-01 5.3682855e+00 5.2703080e+00 - 6.2276656e-01 4.9221145e+00 5.0580998e+00 - 6.1435925e-01 4.5919039e+00 4.9226532e+00 - 6.1195492e-01 4.5311305e+00 5.0087684e+00 - 6.3503251e-01 5.4556318e+00 5.9992000e+00 - 6.3184112e-01 5.3019679e+00 6.0317304e+00 - 6.1608866e-01 4.6996312e+00 5.6189939e+00 - 6.0974931e-01 4.4508000e+00 5.5290814e+00 - 6.0864661e-01 4.4254845e+00 5.6642021e+00 - 6.0446846e-01 4.2424892e+00 5.6301014e+00 - 6.0399157e-01 4.2268163e+00 5.7783594e+00 - 6.0398024e-01 4.2337312e+00 5.9578402e+00 - 6.1223419e-01 4.5863115e+00 6.5633655e+00 - 6.0713530e-01 4.3887380e+00 6.5173741e+00 - 6.0530856e-01 4.3041287e+00 6.6089668e+00 - 5.9945617e-01 4.0801193e+00 6.5145227e+00 - 5.9748773e-01 4.0243765e+00 6.6418382e+00 - 6.2283811e-01 5.0635262e+00 8.3676144e+00 - 6.1688156e-01 4.8513629e+00 8.3297571e+00 - 6.1220506e-01 4.6744851e+00 8.3374097e+00 - 5.9742407e-01 4.0547692e+00 7.6165434e+00 - 5.9532182e-01 3.9948627e+00 7.7810107e+00 - 5.8704108e-01 3.6444322e+00 7.4407067e+00 - 5.7499191e-01 3.1786188e+00 6.8530055e+00 - 5.7801451e-01 3.3020526e+00 7.3422090e+00 - 5.8411967e-01 3.5744554e+00 8.1684699e+00 - 5.8147184e-01 3.4750329e+00 8.2839270e+00 - 5.4922170e-01 2.1362003e+00 5.6865829e+00 - 5.4658277e-01 2.0425220e+00 5.6956256e+00 - 5.6488767e-01 2.8135735e+00 7.7906091e+00 - 5.7480491e-01 3.2482965e+00 9.2436224e+00 - 5.3359984e-01 1.4857401e+00 4.9717440e+00 - 5.3159587e-01 1.4322921e+00 5.0442790e+00 - 5.2908018e-01 1.3142415e+00 4.9263651e+00 - 5.2851067e-01 1.3237014e+00 5.1967361e+00 - 5.3086751e-01 1.4289215e+00 5.8232103e+00 - 5.2171180e-01 1.0509983e+00 4.7874085e+00 - 5.1877914e-01 9.3013133e-01 4.5921405e+00 - 5.1781646e-01 8.6428892e-01 4.5981978e+00 - 5.1539325e-01 8.0594341e-01 4.6322292e+00 - 5.1408328e-01 7.4897288e-01 4.6750969e+00 - 5.1331383e-01 6.9838456e-01 4.7663065e+00 - 5.1218210e-01 6.6819549e-01 4.9849705e+00 - 5.1386225e-01 7.8025692e-01 6.2124532e+00 - 5.1195293e-01 7.0766629e-01 6.3641284e+00 - 5.0809644e-01 5.4344410e-01 5.7595973e+00 - 5.0467013e-01 3.7019592e-01 4.8327107e+00 - 5.0261312e-01 3.2281371e-01 5.0877724e+00 - 5.0049566e-01 2.3506471e-01 4.8332947e+00 - 4.9876684e-01 1.7062107e-01 4.8867463e+00 - 4.9656840e-01 1.3568997e-01 6.1187003e+00 - 4.9468820e-01 4.7043267e-02 6.2702662e+00 - 6.0671150e-01 1.9144897e+00 -9.8497715e-01 - 6.1093853e-01 1.9843701e+00 -9.8654797e-01 - 6.1417849e-01 2.0543997e+00 -9.8631783e-01 - 6.1804625e-01 2.1177990e+00 -9.7745426e-01 - 6.2181214e-01 2.1966731e+00 -9.8026686e-01 - 6.2658977e-01 2.2755951e+00 -9.8088535e-01 - 6.3105663e-01 2.3489393e+00 -9.7301666e-01 - 6.3536820e-01 2.4368155e+00 -9.7567594e-01 - 6.4030695e-01 2.5180566e+00 -9.6980167e-01 - 6.4521638e-01 2.6158679e+00 -9.7365559e-01 - 6.5165054e-01 2.7224681e+00 -9.8045556e-01 - 6.7558223e-01 3.1673240e+00 -9.8162139e-01 - 6.8383651e-01 3.3039412e+00 -9.8771056e-01 - 6.9117812e-01 3.4418179e+00 -9.8975115e-01 - 6.9860708e-01 3.5809083e+00 -9.8744672e-01 - 7.0715430e-01 3.7387339e+00 -9.9027855e-01 - 7.1672989e-01 3.8967405e+00 -9.8821960e-01 - 7.2649443e-01 4.0746087e+00 -9.8994502e-01 - 7.3635371e-01 4.2537497e+00 -9.8612689e-01 - 7.4896745e-01 4.4791416e+00 -9.9692243e-01 - 7.6127008e-01 4.7157575e+00 -1.0042648e+00 - 7.7520019e-01 4.9624993e+00 -1.0077112e+00 - 7.9034639e-01 5.2292738e+00 -1.0102510e+00 - 8.0577690e-01 5.5171877e+00 -1.0109317e+00 - 8.2343461e-01 5.8251773e+00 -1.0086115e+00 - 8.4361315e-01 6.1917767e+00 -1.0147048e+00 - 8.6621585e-01 6.5983774e+00 -1.0202832e+00 - 8.8967011e-01 7.0352921e+00 -1.0203535e+00 - 9.2010494e-01 7.5715265e+00 -1.0317740e+00 - 9.5260557e-01 8.1580928e+00 -1.0370795e+00 - 9.8600583e-01 8.7753573e+00 -1.0290865e+00 - 1.0296057e+00 9.5618036e+00 -1.0356094e+00 - 1.0787134e+00 1.0438680e+01 -1.0323095e+00 - 1.1384345e+00 1.1524234e+01 -1.0354639e+00 - 1.2158518e+00 1.2919115e+01 -1.0496807e+00 - 1.3035032e+00 1.4515001e+01 -1.0435386e+00 - 1.4326717e+00 1.6847897e+01 -1.0724060e+00 - 1.5721198e+00 1.9363808e+01 -1.0391769e+00 - 1.8643619e+00 2.4652747e+01 -7.2776637e-01 - 1.8850056e+00 2.5038106e+01 -3.1547075e-01 - 1.0079584e+00 9.2695104e+00 4.0157549e+00 - 1.0022584e+00 9.1677446e+00 4.1610830e+00 - 1.0141467e+00 9.3835150e+00 4.4199986e+00 - 1.0069508e+00 9.2574184e+00 4.5583260e+00 - 1.0001820e+00 9.1383448e+00 4.6972055e+00 - 1.0025130e+00 9.1825444e+00 4.9031676e+00 - 9.8964154e-01 8.9489038e+00 4.9898647e+00 - 9.8824827e-01 8.9329134e+00 5.1709845e+00 - 1.0074583e+00 9.2807276e+00 5.5324760e+00 - 9.9526643e-01 9.0581915e+00 5.6214247e+00 - 9.8913124e-01 8.9493387e+00 5.7649024e+00 - 9.7520912e-01 8.6995663e+00 5.8284722e+00 - 9.5963664e-01 8.4237122e+00 5.8698098e+00 - 9.5008648e-01 8.2607515e+00 5.9699208e+00 - 9.5054887e-01 8.2740307e+00 6.1771193e+00 - 9.4488983e-01 8.1573358e+00 6.3046607e+00 - 9.7729478e-01 8.7595122e+00 6.9160474e+00 - 8.5076553e-01 6.4459018e+00 5.5197907e+00 - 8.4174852e-01 6.2939062e+00 5.5788075e+00 - 8.4425897e-01 6.3410868e+00 5.7844212e+00 - 8.9397361e-01 7.2477411e+00 6.6701387e+00 - 7.8577955e-01 5.2700117e+00 5.2731200e+00 - 7.4924187e-01 4.6051981e+00 4.8697013e+00 - 7.4353005e-01 4.4922073e+00 4.9102533e+00 - 8.5239281e-01 6.5014542e+00 6.8614986e+00 - 8.2219353e-01 5.9525755e+00 6.5582525e+00 - 8.0803942e-01 5.7045594e+00 6.5156063e+00 - 7.8307627e-01 5.2403296e+00 6.2468000e+00 - 7.5471893e-01 4.7242209e+00 5.8987729e+00 - 7.4510463e-01 4.5496163e+00 5.8856182e+00 - 7.2862617e-01 4.2370394e+00 5.7117051e+00 - 7.2410465e-01 4.1738740e+00 5.8076633e+00 - 7.4209091e-01 4.5070527e+00 6.3777408e+00 - 7.3822433e-01 4.4374739e+00 6.4867270e+00 - 7.3799410e-01 4.4395452e+00 6.6895766e+00 - 7.3493912e-01 4.3821251e+00 6.8221879e+00 - 7.2109430e-01 4.1275122e+00 6.6875513e+00 - 7.7111181e-01 5.0697661e+00 8.2495472e+00 - 7.7181196e-01 5.0823665e+00 8.5442856e+00 - 7.3945203e-01 4.4820970e+00 7.9107774e+00 - 6.9380578e-01 3.6365343e+00 6.8262798e+00 - 6.8647553e-01 3.5140056e+00 6.8545966e+00 - 6.8635889e-01 3.5006958e+00 7.0710200e+00 - 7.0683775e-01 3.9031752e+00 8.0495716e+00 - 6.6645069e-01 3.1465715e+00 6.9248091e+00 - 6.7187711e-01 3.2604621e+00 7.4065588e+00 - 6.8196310e-01 3.4420165e+00 8.0646636e+00 - 6.1429564e-01 2.1700021e+00 5.6586820e+00 - 6.0866714e-01 2.0765445e+00 5.6685332e+00 - 6.0410180e-01 1.9988032e+00 5.7133468e+00 - 6.7707793e-01 3.3903429e+00 9.4004871e+00 - 5.7736408e-01 1.5001928e+00 4.9120885e+00 - 5.7448300e-01 1.4488041e+00 4.9846275e+00 - 6.2483410e-01 2.4034799e+00 7.9876868e+00 - 5.8044018e-01 1.5687841e+00 5.8317245e+00 - 5.7497877e-01 1.4782090e+00 5.8392298e+00 - 5.7131278e-01 1.4128119e+00 5.9316884e+00 - 5.4852022e-01 9.7246021e-01 4.6323212e+00 - 5.4484148e-01 8.9686135e-01 4.6002289e+00 - 5.4112169e-01 8.3464441e-01 4.6153357e+00 - 5.3763700e-01 7.7533776e-01 4.6489205e+00 - 5.3457013e-01 7.2143290e-01 4.7109717e+00 - 5.3162040e-01 6.6846411e-01 4.7919995e+00 - 5.2854407e-01 6.1345215e-01 4.8721275e+00 - 5.3419963e-01 7.3471799e-01 6.2290919e+00 - 5.2720423e-01 6.1456440e-01 6.0028757e+00 - 5.1754410e-01 4.1281802e-01 4.9188377e+00 - 5.1355012e-01 3.3521574e-01 4.8258709e+00 - 5.0987963e-01 2.8142977e-01 5.0106713e+00 - 5.0549746e-01 2.0175684e-01 4.8352072e+00 - 5.0326985e-01 1.8627663e-01 6.3172115e+00 - 4.9840531e-01 8.9038980e-02 6.0097529e+00 - 6.6109944e-01 1.8866652e+00 -9.9435319e-01 - 6.6687804e-01 1.9487447e+00 -9.8954137e-01 - 6.7210940e-01 2.0186139e+00 -9.9011660e-01 - 6.7841024e-01 2.0895084e+00 -9.8894678e-01 - 6.8472340e-01 2.1605013e+00 -9.8577943e-01 - 6.9193410e-01 2.2469184e+00 -9.9409168e-01 - 6.9833277e-01 2.3191103e+00 -9.8687893e-01 - 7.0374498e-01 2.3914563e+00 -9.7776535e-01 - 7.1111928e-01 2.4802122e+00 -9.7918533e-01 - 7.2001459e-01 2.5777275e+00 -9.8415061e-01 - 7.2748178e-01 2.6677414e+00 -9.8032668e-01 - 7.3692030e-01 2.7742391e+00 -9.8553815e-01 - 7.4499091e-01 2.8742324e+00 -9.8200996e-01 - 7.5458871e-01 2.9830345e+00 -9.8102830e-01 - 7.6471799e-01 3.1007253e+00 -9.8219050e-01 - 7.7595444e-01 3.2370627e+00 -9.9028674e-01 - 7.8676340e-01 3.3658580e+00 -9.8919743e-01 - 7.9962424e-01 3.5122966e+00 -9.9389715e-01 - 8.1060481e-01 3.6434948e+00 -9.8461719e-01 - 8.2415704e-01 3.8011314e+00 -9.8516775e-01 - 8.3883492e-01 3.9775625e+00 -9.8965606e-01 - 8.5564219e-01 4.1727717e+00 -9.9718641e-01 - 8.7260935e-01 4.3702902e+00 -9.9842374e-01 - 8.9129634e-01 4.5965085e+00 -1.0053927e+00 - 9.1219081e-01 4.8426448e+00 -1.0125568e+00 - 9.3471522e-01 5.0989268e+00 -1.0154256e+00 - 9.5752085e-01 5.3763234e+00 -1.0169346e+00 - 9.8407348e-01 5.6825454e+00 -1.0191878e+00 - 1.0130305e+00 6.0286110e+00 -1.0241222e+00 - 1.0458760e+00 6.4056634e+00 -1.0265040e+00 - 1.0827923e+00 6.8503165e+00 -1.0361503e+00 - 1.1230361e+00 7.3163168e+00 -1.0360569e+00 - 1.1696823e+00 7.8718595e+00 -1.0429231e+00 - 1.2202749e+00 8.4588519e+00 -1.0378482e+00 - 1.2811530e+00 9.1831357e+00 -1.0430135e+00 - 1.3527592e+00 1.0018249e+01 -1.0454016e+00 - 1.4375745e+00 1.1021966e+01 -1.0500808e+00 - 1.5410889e+00 1.2235193e+01 -1.0547972e+00 - 1.6669462e+00 1.3717995e+01 -1.0575302e+00 - 1.8343007e+00 1.5688158e+01 -1.0728455e+00 - 2.0190337e+00 1.7860159e+01 -1.0423554e+00 - 2.1899909e+00 1.9866031e+01 -9.2008256e-01 - 2.1845899e+00 1.9807786e+01 -5.6474141e-01 - 2.1645308e+00 1.9573268e+01 -2.0171589e-01 - 2.1554849e+00 1.9471756e+01 1.4647055e-01 - 2.1677360e+00 1.9623206e+01 4.8404984e-01 - 4.9089092e+00 5.1922185e+01 5.0993585e+00 - 4.9727794e+00 5.2676654e+01 6.0886143e+00 - 1.5828359e+00 1.2801913e+01 5.0503547e+00 - 1.2904774e+00 9.3457971e+00 4.1382057e+00 - 1.2906911e+00 9.3560577e+00 4.3247289e+00 - 1.2784339e+00 9.2128950e+00 4.4566204e+00 - 1.2638976e+00 9.0492427e+00 4.5771213e+00 - 1.5426120e+00 1.2345527e+01 6.1317214e+00 - 1.2984590e+00 9.4586603e+00 5.1271157e+00 - 1.2980186e+00 9.4575043e+00 5.3253199e+00 - 1.2913849e+00 9.3726040e+00 5.4859417e+00 - 1.2759636e+00 9.1946593e+00 5.6003447e+00 - 1.2685721e+00 9.1138024e+00 5.7606716e+00 - 1.2385624e+00 8.7663304e+00 5.7763951e+00 - 1.2011931e+00 8.3175420e+00 5.7224695e+00 - 1.2151905e+00 8.4836780e+00 6.0145584e+00 - 1.1994393e+00 8.3015502e+00 6.1049400e+00 - 1.2267416e+00 8.6313840e+00 6.5181312e+00 - 1.1750259e+00 8.0191275e+00 6.3262777e+00 - 1.1519458e+00 7.7527314e+00 6.3469701e+00 - 1.0548571e+00 6.5960529e+00 5.7212834e+00 - 1.0426607e+00 6.4569867e+00 5.7944002e+00 - 1.0449094e+00 6.4837244e+00 5.9920128e+00 - 9.8304924e-01 5.7481975e+00 5.5881334e+00 - 1.1316520e+00 7.5205499e+00 7.2209121e+00 - 8.7327492e-01 4.4557635e+00 4.8190364e+00 - 8.6944705e-01 4.4043300e+00 4.9097058e+00 - 1.0010516e+00 5.9809791e+00 6.4994780e+00 - 9.9025458e-01 5.8486686e+00 6.5689488e+00 - 9.4322639e-01 5.2892571e+00 6.2149628e+00 - 9.3586321e-01 5.2117214e+00 6.3210591e+00 - 8.9268998e-01 4.6993181e+00 5.9690358e+00 - 9.2936190e-01 5.1379786e+00 6.6256079e+00 - 8.5957322e-01 4.3058719e+00 5.8834184e+00 - 8.9803461e-01 4.7706942e+00 6.6043700e+00 - 8.8567989e-01 4.6156216e+00 6.6176025e+00 - 8.6772460e-01 4.4050495e+00 6.5568125e+00 - 8.3598715e-01 4.0285135e+00 6.2682031e+00 - 8.2802488e-01 3.9425802e+00 6.3458817e+00 - 8.3924208e-01 4.0744231e+00 6.7316929e+00 - 8.2573322e-01 3.9181644e+00 6.7196598e+00 - 8.1155478e-01 3.7519134e+00 6.6873981e+00 - 8.0727129e-01 3.7064232e+00 6.8365497e+00 - 8.0917967e-01 3.7242520e+00 7.0966804e+00 - 8.0423809e-01 3.6678298e+00 7.2470761e+00 - 8.2946906e-01 3.9760399e+00 8.0501264e+00 - 8.2111011e-01 3.8812635e+00 8.1713968e+00 - 7.7456416e-01 3.3189151e+00 7.3956324e+00 - 7.6644876e-01 3.2291794e+00 7.4975291e+00 - 7.6092904e-01 3.1629798e+00 7.6523155e+00 - 6.7149292e-01 2.0916504e+00 5.6048231e+00 - 6.6582897e-01 2.0273926e+00 5.6774133e+00 - 7.1409651e-01 2.6061633e+00 7.3104154e+00 - 7.6171134e-01 3.1968234e+00 9.1414801e+00 - 7.3792731e-01 2.9051185e+00 8.7933689e+00 - 6.1388645e-01 1.4049860e+00 4.9783356e+00 - 6.8464758e-01 2.2751204e+00 7.8188337e+00 - 6.2593958e-01 1.5533938e+00 5.9406366e+00 - 6.5451975e-01 1.9116621e+00 7.4723987e+00 - 6.2609438e-01 1.5673955e+00 6.6665411e+00 - 5.7440355e-01 9.3672828e-01 4.6310205e+00 - 5.6808834e-01 8.6623466e-01 4.6177160e+00 - 5.6330645e-01 8.0305166e-01 4.6322763e+00 - 5.5782235e-01 7.4384128e-01 4.6653681e+00 - 5.5387549e-01 6.9145693e-01 4.7367613e+00 - 5.4874487e-01 6.3610276e-01 4.8075074e+00 - 5.4610244e-01 6.1043100e-01 5.0950431e+00 - 5.6247677e-01 8.3015957e-01 7.3159560e+00 - 5.3961234e-01 5.3656293e-01 5.7199932e+00 - 5.2508229e-01 3.6298942e-01 4.7730663e+00 - 5.2092166e-01 3.0528670e-01 4.8784648e+00 - 5.1471578e-01 2.3669831e-01 4.8632635e+00 - 5.0900602e-01 1.6455325e-01 4.7569219e+00 - 5.0455373e-01 1.3520637e-01 6.1186748e+00 - 4.9674761e-01 4.6910759e-02 6.2902847e+00 - 7.0523272e-01 1.7884984e+00 -9.9859410e-01 - 7.1161631e-01 1.8437654e+00 -9.8884429e-01 - 7.1976530e-01 1.9123234e+00 -9.9207618e-01 - 7.2654700e-01 1.9743818e+00 -9.8646853e-01 - 7.3477778e-01 2.0441091e+00 -9.8625429e-01 - 7.4346258e-01 2.1215904e+00 -9.9093089e-01 - 7.5321932e-01 2.2001165e+00 -9.9346294e-01 - 7.6060937e-01 2.2721938e+00 -9.8735202e-01 - 7.7089698e-01 2.3596038e+00 -9.9212779e-01 - 7.7937131e-01 2.4328245e+00 -9.8187478e-01 - 7.8974873e-01 2.5214680e+00 -9.8190602e-01 - 8.0014157e-01 2.6102347e+00 -9.7944035e-01 - 8.1307340e-01 2.7251788e+00 -9.9209868e-01 - 8.2407028e-01 2.8239298e+00 -9.8982887e-01 - 8.3816263e-01 2.9411423e+00 -9.9579786e-01 - 8.4780886e-01 3.0335269e+00 -9.8199184e-01 - 8.6245367e-01 3.1597958e+00 -9.8670888e-01 - 8.7869389e-01 3.2959344e+00 -9.9272361e-01 - 8.9402268e-01 3.4333423e+00 -9.9449001e-01 - 9.1095059e-01 3.5806493e+00 -9.9695483e-01 - 9.2842294e-01 3.7369487e+00 -9.9946610e-01 - 9.4704471e-01 3.8954279e+00 -9.9708582e-01 - 9.6982494e-01 4.0901464e+00 -1.0072320e+00 - 9.9118691e-01 4.2774423e+00 -1.0069910e+00 - 1.0152644e+00 4.4933579e+00 -1.0128843e+00 - 1.0424830e+00 4.7280997e+00 -1.0196255e+00 - 1.0698702e+00 4.9652197e+00 -1.0186755e+00 - 1.0999925e+00 5.2311170e+00 -1.0206637e+00 - 1.1339172e+00 5.5267971e+00 -1.0242446e+00 - 1.1743474e+00 5.8807812e+00 -1.0375501e+00 - 1.2143852e+00 6.2275040e+00 -1.0359771e+00 - 1.2614790e+00 6.6415724e+00 -1.0431764e+00 - 1.3103056e+00 7.0671232e+00 -1.0392383e+00 - 1.3695150e+00 7.5818759e+00 -1.0442700e+00 - 1.4374878e+00 8.1752547e+00 -1.0510316e+00 - 1.5056461e+00 8.7706306e+00 -1.0375678e+00 - 1.5994123e+00 9.5917886e+00 -1.0516194e+00 - 1.6993755e+00 1.0464659e+01 -1.0469340e+00 - 1.8304884e+00 1.1604632e+01 -1.0591207e+00 - 1.9961595e+00 1.3051019e+01 -1.0801276e+00 - 2.1829220e+00 1.4678931e+01 -1.0760769e+00 - 2.3891796e+00 1.6477973e+01 -1.0360331e+00 - 2.6772846e+00 1.9000608e+01 -1.0097604e+00 - 7.1270144e+00 5.7836771e+01 -1.0329760e+00 - 6.3750115e+00 5.1327922e+01 5.5198160e+00 - 6.4690820e+00 5.2185121e+01 9.3190902e+00 - 1.5558724e+00 9.2509471e+00 4.0256036e+00 - 1.5389322e+00 9.1131257e+00 4.1583618e+00 - 1.5336152e+00 9.0663819e+00 4.3213987e+00 - 1.8818063e+00 1.2114042e+01 5.6805784e+00 - 1.8794652e+00 1.2095936e+01 5.9188788e+00 - 1.5594042e+00 9.2926655e+00 4.9701915e+00 - 1.5527733e+00 9.2403651e+00 5.1409197e+00 - 1.5278789e+00 9.0228637e+00 5.2350049e+00 - 1.5537657e+00 9.2522061e+00 5.5418246e+00 - 1.5359939e+00 9.1010350e+00 5.6673368e+00 - 1.5280497e+00 9.0274093e+00 5.8312153e+00 - 1.8323834e+00 1.1697179e+01 7.5257967e+00 - 1.4810796e+00 8.6228822e+00 6.0103558e+00 - 1.5151784e+00 8.9176762e+00 6.3927935e+00 - 1.4178934e+00 8.0723103e+00 6.0769526e+00 - 1.4745787e+00 8.5672794e+00 6.5991615e+00 - 1.3922523e+00 7.8506902e+00 6.3294408e+00 - 1.4321698e+00 8.2047893e+00 6.7820074e+00 - 1.2538357e+00 6.6325406e+00 5.8496173e+00 - 1.1775002e+00 5.9680800e+00 5.5260250e+00 - 1.1769798e+00 5.9673167e+00 5.6916701e+00 - 1.3133840e+00 7.1666771e+00 6.8404568e+00 - 1.0061466e+00 4.4685463e+00 4.7735313e+00 - 9.9303145e-01 4.3495584e+00 4.8055138e+00 - 1.1125710e+00 5.4057280e+00 5.8983901e+00 - 1.1141658e+00 5.4220822e+00 6.0881086e+00 - 1.0565912e+00 4.9177284e+00 5.7796312e+00 - 1.0524806e+00 4.8761983e+00 5.9077607e+00 - 1.0858837e+00 5.1708912e+00 6.3882286e+00 - 1.0325218e+00 4.7032102e+00 6.0760139e+00 - 1.0064669e+00 4.4754035e+00 6.0017063e+00 - 1.0549692e+00 4.9095806e+00 6.6833573e+00 - 1.0307732e+00 4.6947805e+00 6.6308243e+00 - 9.6938644e-01 4.1525282e+00 6.1606381e+00 - 9.5298406e-01 4.0135466e+00 6.1697978e+00 - 9.4490880e-01 3.9414520e+00 6.2634150e+00 - 9.7552615e-01 4.2180951e+00 6.8415098e+00 - 9.5609832e-01 4.0475015e+00 6.8164033e+00 - 1.0593052e+00 4.9572955e+00 8.3953914e+00 - 9.2418792e-01 3.7676168e+00 6.8375152e+00 - 8.8359284e-01 3.4130454e+00 6.4957127e+00 - 8.8306481e-01 3.4096425e+00 6.7091468e+00 - 9.5685368e-01 4.0598985e+00 8.0758412e+00 - 9.3771008e-01 3.8931234e+00 8.0673654e+00 - 8.4738167e-01 3.0940221e+00 6.8542956e+00 - 8.7457852e-01 3.3387760e+00 7.5938818e+00 - 8.5340732e-01 3.1586776e+00 7.5166901e+00 - 8.4529115e-01 3.0836773e+00 7.6527029e+00 - 7.9841859e-01 2.6728388e+00 7.0389758e+00 - 7.8563946e-01 2.5596307e+00 7.0665661e+00 - 7.8905426e-01 2.5951706e+00 7.4628829e+00 - 8.3874158e-01 3.0389031e+00 8.9638664e+00 - 8.0703208e-01 2.7639332e+00 8.6401096e+00 - 7.6491766e-01 2.3850576e+00 7.9689076e+00 - 6.9334246e-01 1.7482794e+00 6.4119008e+00 - 6.8558658e-01 1.6802842e+00 6.5278415e+00 - 6.8134977e-01 1.6468141e+00 6.7776247e+00 - 6.6577173e-01 1.5110246e+00 6.6703785e+00 - 5.9840873e-01 9.0257731e-01 4.6390649e+00 - 5.9027434e-01 8.3465177e-01 4.6348564e+00 - 5.8367452e-01 7.7404669e-01 4.6587124e+00 - 5.7755293e-01 7.1932622e-01 4.7208226e+00 - 5.7024616e-01 6.6214021e-01 4.7722485e+00 - 5.6405407e-01 6.0582490e-01 4.8425479e+00 - 5.8152742e-01 7.7270501e-01 6.5261951e+00 - 5.6088433e-01 5.8612528e-01 5.7945121e+00 - 5.4089053e-01 4.0443322e-01 4.8592333e+00 - 5.3214885e-01 3.3010751e-01 4.7860588e+00 - 5.2549846e-01 2.6755111e-01 4.8311374e+00 - 5.1840024e-01 2.0842153e-01 4.9849840e+00 - 5.1418864e-01 1.8512394e-01 6.3072888e+00 - 5.0364643e-01 8.9189651e-02 6.0796995e+00 - 7.4539491e-01 1.6907459e+00 -9.9932661e-01 - 7.5545473e-01 1.7579840e+00 -1.0066103e+00 - 7.6239420e-01 1.8055302e+00 -9.9007512e-01 - 7.7115682e-01 1.8673446e+00 -9.8697074e-01 - 7.8168668e-01 1.9424647e+00 -9.9654844e-01 - 7.9190948e-01 2.0120366e+00 -9.9703969e-01 - 8.0076438e-01 2.0751042e+00 -9.8879128e-01 - 8.1107021e-01 2.1458554e+00 -9.8563665e-01 - 8.2321152e-01 2.2309732e+00 -9.9391524e-01 - 8.3504516e-01 2.3105380e+00 -9.9320727e-01 - 8.4733712e-01 2.3978912e+00 -9.9669101e-01 - 8.5925934e-01 2.4786796e+00 -9.9143825e-01 - 8.7270011e-01 2.5682076e+00 -9.9013031e-01 - 8.8515936e-01 2.6579292e+00 -9.8612252e-01 - 9.0203412e-01 2.7717183e+00 -9.9704612e-01 - 9.1609619e-01 2.8713686e+00 -9.9313750e-01 - 9.3168483e-01 2.9798227e+00 -9.9187529e-01 - 9.4880313e-01 3.0971052e+00 -9.9276011e-01 - 9.6751438e-01 3.2242377e+00 -9.9534213e-01 - 9.8827445e-01 3.3689888e+00 -1.0042126e+00 - 1.0070965e+00 3.4975222e+00 -9.9865424e-01 - 1.0295455e+00 3.6534060e+00 -1.0034786e+00 - 1.0505707e+00 3.8018230e+00 -9.9881455e-01 - 1.0777469e+00 3.9863288e+00 -1.0072826e+00 - 1.1035037e+00 4.1634022e+00 -1.0055633e+00 - 1.1298750e+00 4.3505437e+00 -1.0023418e+00 - 1.1639959e+00 4.5836683e+00 -1.0130508e+00 - 1.2003857e+00 4.8377178e+00 -1.0238048e+00 - 1.2378261e+00 5.0921256e+00 -1.0260724e+00 - 1.2791253e+00 5.3772836e+00 -1.0305815e+00 - 1.3256955e+00 5.7000509e+00 -1.0388808e+00 - 1.3740372e+00 6.0351252e+00 -1.0395879e+00 - 1.4293135e+00 6.4187395e+00 -1.0441339e+00 - 1.4925991e+00 6.8519584e+00 -1.0499748e+00 - 1.5565651e+00 7.2957726e+00 -1.0436269e+00 - 1.6360341e+00 7.8473560e+00 -1.0498996e+00 - 1.7220362e+00 8.4401443e+00 -1.0466309e+00 - 1.8257194e+00 9.1598693e+00 -1.0511346e+00 - 1.9492422e+00 1.0008739e+01 -1.0567246e+00 - 2.0943678e+00 1.1015798e+01 -1.0621411e+00 - 2.2780787e+00 1.2279925e+01 -1.0754702e+00 - 2.5053743e+00 1.3850267e+01 -1.0906569e+00 - 2.7625184e+00 1.5630809e+01 -1.0784497e+00 - 2.9665507e+00 1.7041640e+01 -9.6097054e-01 - 9.3472027e+00 6.1151272e+01 4.6258411e-01 - 9.3466590e+00 6.1151741e+01 1.5409945e+00 - 9.3499342e+00 6.1182126e+01 2.6205088e+00 - 9.3485258e+00 6.1184753e+01 3.7009206e+00 - 9.3546153e+00 6.1228258e+01 4.7854774e+00 - 7.9940958e+00 5.1849873e+01 7.8984526e+00 - 1.8192383e+00 9.1531624e+00 4.2753054e+00 - 1.8844594e+00 9.6057603e+00 4.8231808e+00 - 1.8295758e+00 9.2268316e+00 4.8619358e+00 - 1.8236314e+00 9.1856898e+00 5.0360141e+00 - 1.8144265e+00 9.1242519e+00 5.2014017e+00 - 1.7997552e+00 9.0231288e+00 5.3487559e+00 - 1.7662595e+00 8.7965472e+00 5.4313274e+00 - 1.7742355e+00 8.8503138e+00 5.6550051e+00 - 1.8176358e+00 9.1507148e+00 6.0202882e+00 - 1.5297605e+00 7.1590204e+00 5.0926442e+00 - 1.7872339e+00 8.9470080e+00 6.3246871e+00 - 1.5491887e+00 7.2921828e+00 5.5149848e+00 - 1.4816816e+00 6.8289255e+00 5.3956773e+00 - 1.6954349e+00 8.3121940e+00 6.5586172e+00 - 1.6364942e+00 7.9050565e+00 6.4890533e+00 - 1.5878673e+00 7.5671870e+00 6.4533550e+00 - 1.3415896e+00 5.8565457e+00 5.3784263e+00 - 1.3467201e+00 5.8979739e+00 5.5723928e+00 - 1.3049924e+00 5.6093918e+00 5.5074877e+00 - 1.4038878e+00 6.2939089e+00 6.2418594e+00 - 1.1261300e+00 4.3657016e+00 4.7673508e+00 - 1.1193617e+00 4.3153972e+00 4.8569815e+00 - 1.2637954e+00 5.3207098e+00 5.9255799e+00 - 1.2167700e+00 4.9979153e+00 5.7915077e+00 - 1.1476922e+00 4.5184960e+00 5.4863770e+00 - 1.2029851e+00 4.9059383e+00 6.0432346e+00 - 1.1462554e+00 4.5112258e+00 5.8025339e+00 - 1.1307366e+00 4.4012670e+00 5.8518078e+00 - 1.2050952e+00 4.9267115e+00 6.6252160e+00 - 1.1973316e+00 4.8739116e+00 6.7643368e+00 - 1.1675498e+00 4.6657910e+00 6.7183172e+00 - 1.0958718e+00 4.1664099e+00 6.2909351e+00 - 9.9680726e-01 3.4779623e+00 5.5781847e+00 - 1.0127962e+00 3.5924946e+00 5.9040454e+00 - 9.8957608e-01 3.4268386e+00 5.8525865e+00 - 9.8739942e-01 3.4152037e+00 6.0194790e+00 - 1.0145343e+00 3.6061690e+00 6.5042012e+00 - 9.8598535e-01 3.4050212e+00 6.3981564e+00 - 9.6907709e-01 3.2899328e+00 6.4232617e+00 - 9.6323853e-01 3.2516999e+00 6.5752688e+00 - 9.4789835e-01 3.1452313e+00 6.6142569e+00 - 1.0005848e+00 3.5194523e+00 7.5477466e+00 - 9.7562828e-01 3.3422843e+00 7.4845511e+00 - 9.5709273e-01 3.2165559e+00 7.5155980e+00 - 9.2867002e-01 3.0184795e+00 7.3907779e+00 - 8.9472408e-01 2.7838734e+00 7.1700734e+00 - 8.7162875e-01 2.6217932e+00 7.0898021e+00 - 8.5608880e-01 2.5121809e+00 7.1258426e+00 - 8.6856127e-01 2.6062200e+00 7.6809173e+00 - 8.6736035e-01 2.6013509e+00 8.0254896e+00 - 8.2874367e-01 2.3310534e+00 7.6460765e+00 - 7.5976023e-01 1.8442649e+00 6.5671539e+00 - 7.4194071e-01 1.7188001e+00 6.5034665e+00 - 7.2844607e-01 1.6262629e+00 6.5424568e+00 - 7.2130699e-01 1.5800011e+00 6.7533401e+00 - 7.0375116e-01 1.4587065e+00 6.6931500e+00 - 6.2035551e-01 8.6753552e-01 4.6468657e+00 - 6.1022108e-01 7.9970131e-01 4.6420642e+00 - 6.0174310e-01 7.4067720e-01 4.6752654e+00 - 5.9362210e-01 6.8605300e-01 4.7368827e+00 - 5.8543533e-01 6.3038750e-01 4.7976506e+00 - 5.7718361e-01 5.7317150e-01 4.8675065e+00 - 6.1311794e-01 8.3505642e-01 7.3953004e+00 - 5.7216526e-01 5.4106318e-01 5.7895566e+00 - 5.4838846e-01 3.7551416e-01 4.9323020e+00 - 5.3876678e-01 3.0270897e-01 4.8684695e+00 - 5.2869154e-01 2.3534773e-01 4.8732562e+00 - 5.2631520e-01 2.3342047e-01 6.3654062e+00 - 5.1266380e-01 1.3520383e-01 6.1486619e+00 - 4.9974211e-01 4.6729409e-02 6.2902752e+00 - 7.8919673e-01 1.6530226e+00 -9.9873740e-01 - 7.9981181e-01 1.7125349e+00 -9.9933560e-01 - 8.1049698e-01 1.7731231e+00 -9.9838532e-01 - 8.2125161e-01 1.8347821e+00 -9.9598644e-01 - 8.3195589e-01 1.8955230e+00 -9.9193998e-01 - 8.4416886e-01 1.9649247e+00 -9.9343636e-01 - 8.5639355e-01 2.0344201e+00 -9.9303509e-01 - 8.6763116e-01 2.1040646e+00 -9.9083285e-01 - 8.8138057e-01 2.1823489e+00 -9.9337762e-01 - 8.9370123e-01 2.2531270e+00 -9.8723304e-01 - 9.0891945e-01 2.3392378e+00 -9.9197517e-01 - 9.2282999e-01 2.4198413e+00 -9.8802717e-01 - 9.3964363e-01 2.5158218e+00 -9.9406698e-01 - 9.5458193e-01 2.5966012e+00 -9.8532809e-01 - 9.7344315e-01 2.7101906e+00 -9.9785607e-01 - 9.9287566e-01 2.8161824e+00 -1.0011018e+00 - 1.0099421e+00 2.9157302e+00 -9.9560470e-01 - 1.0285357e+00 3.0240867e+00 -9.9265413e-01 - 1.0511677e+00 3.1498868e+00 -9.9709697e-01 - 1.0713746e+00 3.2682558e+00 -9.9254766e-01 - 1.0976527e+00 3.4215591e+00 -1.0042770e+00 - 1.1204797e+00 3.5499492e+00 -9.9673385e-01 - 1.1479337e+00 3.7056441e+00 -9.9927691e-01 - 1.1815388e+00 3.8974278e+00 -1.0149521e+00 - 1.2106947e+00 4.0643589e+00 -1.0113517e+00 - 1.2429775e+00 4.2500027e+00 -1.0108963e+00 - 1.2784536e+00 4.4554057e+00 -1.0126368e+00 - 1.3226849e+00 4.7067905e+00 -1.0271124e+00 - 1.3655078e+00 4.9508315e+00 -1.0296027e+00 - 1.4130641e+00 5.2235438e+00 -1.0347381e+00 - 1.4654842e+00 5.5270000e+00 -1.0410195e+00 - 1.5220706e+00 5.8494387e+00 -1.0437574e+00 - 1.5835381e+00 6.2027593e+00 -1.0448449e+00 - 1.6523585e+00 6.5947673e+00 -1.0456834e+00 - 1.7260200e+00 7.0168228e+00 -1.0415259e+00 - 1.8118804e+00 7.5081668e+00 -1.0411620e+00 - 1.9161952e+00 8.1062397e+00 -1.0505822e+00 - 2.0264048e+00 8.7347430e+00 -1.0460207e+00 - 2.1647250e+00 9.5303776e+00 -1.0552837e+00 - 2.3210694e+00 1.0424660e+01 -1.0558071e+00 - 2.5187037e+00 1.1554645e+01 -1.0670107e+00 - 2.7672683e+00 1.2980092e+01 -1.0856942e+00 - 3.0493780e+00 1.4594264e+01 -1.0807533e+00 - 3.2954495e+00 1.6006063e+01 -9.9361844e-01 - 9.6688149e+00 5.2503141e+01 -8.5785718e-01 - 9.3395173e+00 5.0709627e+01 1.3836859e+01 - 2.1449580e+00 9.4543336e+00 4.8781029e+00 - 2.1051965e+00 9.2228079e+00 4.9746738e+00 - 2.0862849e+00 9.1178846e+00 5.1211403e+00 - 2.0562537e+00 8.9468383e+00 5.2354935e+00 - 2.0525802e+00 8.9261220e+00 5.4196639e+00 - 2.0460987e+00 8.8923347e+00 5.5997907e+00 - 1.7506424e+00 7.1944580e+00 4.8833784e+00 - 1.7281326e+00 7.0660246e+00 4.9762593e+00 - 1.7260320e+00 7.0560289e+00 5.1358616e+00 - 1.7375632e+00 7.1197677e+00 5.3425051e+00 - 1.6495711e+00 6.6173625e+00 5.1977212e+00 - 1.6192713e+00 6.4452013e+00 5.2489531e+00 - 1.6232906e+00 6.4689817e+00 5.4295795e+00 - 1.4545190e+00 5.4962790e+00 4.9067977e+00 - 1.4903298e+00 5.7077520e+00 5.2092312e+00 - 1.5914485e+00 6.2871606e+00 5.8093020e+00 - 1.5831845e+00 6.2425249e+00 5.9506264e+00 - 1.5381638e+00 5.9807061e+00 5.9156599e+00 - 1.2762303e+00 4.4762333e+00 4.8124354e+00 - 1.2610439e+00 4.3877981e+00 4.8713587e+00 - 1.2496419e+00 4.3274555e+00 4.9552053e+00 - 1.2755164e+00 4.4752564e+00 5.2359103e+00 - 1.2464310e+00 4.3099202e+00 5.2241207e+00 - 1.2533451e+00 4.3479804e+00 5.4130360e+00 - 1.2941288e+00 4.5864274e+00 5.8202391e+00 - 1.2571015e+00 4.3751183e+00 5.7618060e+00 - 1.2371671e+00 4.2589268e+00 5.8014021e+00 - 1.3620572e+00 4.9776681e+00 6.8119682e+00 - 1.2726052e+00 4.4651437e+00 6.4012638e+00 - 1.2035152e+00 4.0681021e+00 6.0986777e+00 - 1.1183965e+00 3.5795041e+00 5.6499209e+00 - 1.1191104e+00 3.5821146e+00 5.8244031e+00 - 1.0833248e+00 3.3773331e+00 5.7171805e+00 - 1.0747357e+00 3.3290678e+00 5.8254449e+00 - 1.1113784e+00 3.5435781e+00 6.3312745e+00 - 1.1092704e+00 3.5319760e+00 6.5190908e+00 - 1.0859069e+00 3.3946576e+00 6.5128925e+00 - 1.0843211e+00 3.3903230e+00 6.7264792e+00 - 1.0546299e+00 3.2180824e+00 6.6557609e+00 - 1.0381794e+00 3.1250037e+00 6.7206281e+00 - 1.0672406e+00 3.2938428e+00 7.2872295e+00 - 1.0721435e+00 3.3241690e+00 7.6208166e+00 - 1.0328485e+00 3.0981342e+00 7.4449781e+00 - 9.8029642e-01 2.7953850e+00 7.0818699e+00 - 9.5895157e-01 2.6738965e+00 7.0939018e+00 - 9.3765213e-01 2.5532868e+00 7.1034870e+00 - 9.1917174e-01 2.4448036e+00 7.1384888e+00 - 1.0135568e+00 2.9994135e+00 8.9266883e+00 - 9.1852440e-01 2.4477536e+00 7.8226913e+00 - 8.7865444e-01 2.2181553e+00 7.5340929e+00 - 7.9419398e-01 1.7272102e+00 6.3930938e+00 - 7.8250504e-01 1.6604488e+00 6.5088979e+00 - 7.9139097e-01 1.7122033e+00 7.0564687e+00 - 7.5412739e-01 1.4976739e+00 6.6705918e+00 - 7.4278042e-01 1.4341610e+00 6.8319899e+00 - 6.4024388e-01 8.3160288e-01 4.6544227e+00 - 6.2947054e-01 7.6876288e-01 4.6686025e+00 - 6.1929525e-01 7.1379646e-01 4.7208377e+00 - 6.0881251e-01 6.5431014e-01 4.7624845e+00 - 5.9856610e-01 5.9774396e-01 4.8228089e+00 - 5.8825537e-01 5.3963220e-01 4.8923212e+00 - 5.9895381e-01 6.0771874e-01 6.0128829e+00 - 5.8038757e-01 4.9567005e-01 5.7742234e+00 - 5.5193008e-01 3.2641193e-01 4.7761066e+00 - 5.4047238e-01 2.6614008e-01 4.8411269e+00 - 5.2988645e-01 2.0325047e-01 4.9150818e+00 - 5.2498351e-01 1.8298097e-01 6.2772908e+00 - 5.0845149e-01 8.7918590e-02 6.0397832e+00 - 8.4355033e-01 1.6737900e+00 -9.9919623e-01 - 8.5479076e-01 1.7266524e+00 -9.9156050e-01 - 8.6885250e-01 1.7937226e+00 -9.9735871e-01 - 8.8061023e-01 1.8553606e+00 -9.9416400e-01 - 8.9469416e-01 1.9226081e+00 -9.9636665e-01 - 9.0890963e-01 1.9919382e+00 -9.9687062e-01 - 9.2313619e-01 2.0613570e+00 -9.9557682e-01 - 9.3737509e-01 2.1308744e+00 -9.9228548e-01 - 9.5312699e-01 2.2090871e+00 -9.9383783e-01 - 9.6989124e-01 2.2873526e+00 -9.9309621e-01 - 9.8717404e-01 2.3744036e+00 -9.9659584e-01 - 1.0025827e+00 2.4462633e+00 -9.8511702e-01 - 1.0228449e+00 2.5498164e+00 -9.9605722e-01 - 1.0412335e+00 2.6381832e+00 -9.9191908e-01 - 1.0626519e+00 2.7439703e+00 -9.9686908e-01 - 1.0850881e+00 2.8498547e+00 -9.9862621e-01 - 1.1051577e+00 2.9492901e+00 -9.9174036e-01 - 1.1292631e+00 3.0661494e+00 -9.9264744e-01 - 1.1563517e+00 3.1995405e+00 -1.0003958e+00 - 1.1860362e+00 3.3427605e+00 -1.0090456e+00 - 1.2118460e+00 3.4708757e+00 -1.0034096e+00 - 1.2417059e+00 3.6165281e+00 -1.0032695e+00 - 1.2756817e+00 3.7807589e+00 -1.0077757e+00 - 1.3112055e+00 3.9539660e+00 -1.0114327e+00 - 1.3453677e+00 4.1207180e+00 -1.0053512e+00 - 1.3892075e+00 4.3322711e+00 -1.0144554e+00 - 1.4363070e+00 4.5646296e+00 -1.0248062e+00 - 1.4844534e+00 4.7973168e+00 -1.0272699e+00 - 1.5399077e+00 5.0683318e+00 -1.0367757e+00 - 1.5995794e+00 5.3592523e+00 -1.0442858e+00 - 1.6593729e+00 5.6516624e+00 -1.0418577e+00 - 1.7275580e+00 5.9835387e+00 -1.0424294e+00 - 1.8015050e+00 6.3442672e+00 -1.0407554e+00 - 1.8895628e+00 6.7729742e+00 -1.0467269e+00 - 1.9792992e+00 7.2122159e+00 -1.0405127e+00 - 2.0873516e+00 7.7392431e+00 -1.0419459e+00 - 2.2153393e+00 8.3641176e+00 -1.0484288e+00 - 2.3575254e+00 9.0576702e+00 -1.0483748e+00 - 2.5280042e+00 9.8877462e+00 -1.0521261e+00 - 2.7399620e+00 1.0923490e+01 -1.0651773e+00 - 2.9860962e+00 1.2126099e+01 -1.0698498e+00 - 3.3155230e+00 1.3729006e+01 -1.0927800e+00 - 3.6684360e+00 1.5452892e+01 -1.0748649e+00 - 4.0102102e+00 1.7121633e+01 -9.8928091e-01 - 4.9862861e+00 2.1882467e+01 -1.1484484e+00 - 8.4167432e+00 3.8620216e+01 -7.1749034e-01 - 9.1141448e+00 4.2025337e+01 6.2961034e-01 - 9.1208861e+00 4.2064166e+01 1.3786797e+00 - 1.0516034e+01 4.8877296e+01 3.1828390e+00 - 1.0812647e+01 5.0335311e+01 5.0483787e+00 - 1.2022996e+01 5.6256707e+01 8.5650228e+00 - 1.2013717e+01 5.6215475e+01 9.5808644e+00 - 1.1996194e+01 5.6137506e+01 1.0594264e+01 - 1.0537955e+01 4.9052807e+01 1.6791342e+01 - 1.0827490e+01 5.0478551e+01 1.9250247e+01 - 2.3973804e+00 9.2793701e+00 4.7321866e+00 - 2.3886364e+00 9.2415138e+00 4.9084230e+00 - 2.3781413e+00 9.1915131e+00 5.0803632e+00 - 2.3963686e+00 9.2814698e+00 5.3181121e+00 - 2.3308719e+00 8.9586141e+00 5.3621765e+00 - 1.9834543e+00 7.2603330e+00 4.6955660e+00 - 1.9628068e+00 7.1617375e+00 4.8057867e+00 - 2.2953321e+00 8.7915545e+00 5.8729562e+00 - 2.2715164e+00 8.6723687e+00 6.0090428e+00 - 2.2018544e+00 8.3326018e+00 6.0105135e+00 - 2.1581436e+00 8.1200169e+00 6.0797419e+00 - 1.7593482e+00 6.1733258e+00 5.0145950e+00 - 1.7167272e+00 5.9650233e+00 5.0300394e+00 - 1.7520685e+00 6.1370722e+00 5.3055849e+00 - 1.7268705e+00 6.0148775e+00 5.3794516e+00 - 1.7695386e+00 6.2228264e+00 5.7000389e+00 - 1.7663515e+00 6.2111534e+00 5.8649370e+00 - 1.7089146e+00 5.9271748e+00 5.8130179e+00 - 1.4310786e+00 4.5666867e+00 4.8427617e+00 - 1.4089290e+00 4.4630933e+00 4.8909615e+00 - 1.3730747e+00 4.2856982e+00 4.8704971e+00 - 1.3987185e+00 4.4143355e+00 5.1286198e+00 - 1.3860830e+00 4.3501099e+00 5.2135667e+00 - 1.3882563e+00 4.3609872e+00 5.3745159e+00 - 1.4007448e+00 4.4233072e+00 5.5941394e+00 - 1.3493439e+00 4.1755293e+00 5.4908363e+00 - 1.3689214e+00 4.2697860e+00 5.7561991e+00 - 1.3611186e+00 4.2334775e+00 5.8839936e+00 - 1.6268688e+00 5.5362823e+00 7.6164063e+00 - 1.3100427e+00 3.9831398e+00 5.9314005e+00 - 1.2538289e+00 3.7091498e+00 5.7590332e+00 - 1.2402205e+00 3.6451867e+00 5.8480782e+00 - 1.1911154e+00 3.4048384e+00 5.6952338e+00 - 1.1609021e+00 3.2553298e+00 5.6574393e+00 - 1.1527776e+00 3.2143880e+00 5.7723482e+00 - 1.2379915e+00 3.6347665e+00 6.6044382e+00 - 1.2939647e+00 3.9120775e+00 7.2671482e+00 - 1.2639273e+00 3.7634588e+00 7.2676560e+00 - 1.1615109e+00 3.2626452e+00 6.6530031e+00 - 1.2000897e+00 3.4556223e+00 7.2324725e+00 - 1.1520232e+00 3.2176001e+00 7.0469667e+00 - 1.0863040e+00 2.8962745e+00 6.6775471e+00 - 1.1042094e+00 2.9870543e+00 7.1131015e+00 - 1.0785387e+00 2.8605667e+00 7.1202002e+00 - 1.0604063e+00 2.7716689e+00 7.2065983e+00 - 1.0501186e+00 2.7243567e+00 7.3925220e+00 - 1.0412438e+00 2.6823613e+00 7.6064095e+00 - 1.1568415e+00 3.2545137e+00 9.4302579e+00 - 1.0055230e+00 2.5099443e+00 7.8477219e+00 - 9.4613891e-01 2.2155632e+00 7.3823173e+00 - 8.5920840e-01 1.7884723e+00 6.4534492e+00 - 9.0288067e-01 2.0081418e+00 7.4954427e+00 - 8.2722653e-01 1.6321376e+00 6.6192531e+00 - 8.5275495e-01 1.7604540e+00 7.4762309e+00 - 7.8917151e-01 1.4460101e+00 6.7029610e+00 - 6.7262288e-01 8.6832223e-01 4.6858527e+00 - 6.5967605e-01 8.0315596e-01 4.6909494e+00 - 6.4584490e-01 7.3947571e-01 4.7046890e+00 - 6.3442729e-01 6.8107143e-01 4.7467887e+00 - 6.2324602e-01 6.2558729e-01 4.8075662e+00 - 6.1063726e-01 5.6415406e-01 4.8478202e+00 - 5.9844836e-01 5.0762326e-01 4.9266778e+00 - 6.0441361e-01 5.4158229e-01 5.8391934e+00 - 5.8728434e-01 4.5730543e-01 5.8381498e+00 - 5.5530834e-01 2.9671977e-01 4.8286134e+00 - 5.4229882e-01 2.3053683e-01 4.8333601e+00 - 5.3700878e-01 2.1491000e-01 5.9857840e+00 - 5.2096169e-01 1.3567075e-01 6.2286865e+00 - 5.0198655e-01 4.4680088e-02 6.0903157e+00 - 8.7294768e-01 1.5804833e+00 -1.0042868e+00 - 8.8754679e-01 1.6396849e+00 -1.0062960e+00 - 9.0115699e-01 1.6990208e+00 -1.0068038e+00 - 9.1346135e-01 1.7528641e+00 -9.9832194e-01 - 9.2808821e-01 1.8122874e+00 -9.9583668e-01 - 9.4178699e-01 1.8728470e+00 -9.9179976e-01 - 9.5793240e-01 1.9410100e+00 -9.9325931e-01 - 9.7414975e-01 2.0102635e+00 -9.9287075e-01 - 9.9031798e-01 2.0786088e+00 -9.9063486e-01 - 1.0104385e+00 2.1631938e+00 -9.9993766e-01 - 1.0267530e+00 2.2337400e+00 -9.9360605e-01 - 1.0440775e+00 2.3043193e+00 -9.8537997e-01 - 1.0657442e+00 2.3978657e+00 -9.9413312e-01 - 1.0861052e+00 2.4859194e+00 -9.9389654e-01 - 1.1074195e+00 2.5730390e+00 -9.9111666e-01 - 1.1317622e+00 2.6775690e+00 -9.9762468e-01 - 1.1561856e+00 2.7832585e+00 -1.0008863e+00 - 1.1801783e+00 2.8813812e+00 -9.9546179e-01 - 1.2071474e+00 2.9959816e+00 -9.9797721e-01 - 1.2342597e+00 3.1127581e+00 -9.9689630e-01 - 1.2693135e+00 3.2623096e+00 -1.0129002e+00 - 1.2975322e+00 3.3804070e+00 -1.0040816e+00 - 1.3297974e+00 3.5160119e+00 -1.0013580e+00 - 1.3676895e+00 3.6788759e+00 -1.0084242e+00 - 1.4066125e+00 3.8419406e+00 -1.0102002e+00 - 1.4497189e+00 4.0246399e+00 -1.0154735e+00 - 1.4944387e+00 4.2173518e+00 -1.0191482e+00 - 1.5442909e+00 4.4287294e+00 -1.0244761e+00 - 1.6008594e+00 4.6685491e+00 -1.0346527e+00 - 1.6600566e+00 4.9184587e+00 -1.0404372e+00 - 1.7260450e+00 5.1979255e+00 -1.0487228e+00 - 1.7921528e+00 5.4788622e+00 -1.0474698e+00 - 1.8650648e+00 5.7894595e+00 -1.0466206e+00 - 1.9472535e+00 6.1375278e+00 -1.0474767e+00 - 2.0363282e+00 6.5164261e+00 -1.0452905e+00 - 2.1388729e+00 6.9525087e+00 -1.0467091e+00 - 2.2533808e+00 7.4371296e+00 -1.0458900e+00 - 2.3882176e+00 8.0095481e+00 -1.0500279e+00 - 2.5458785e+00 8.6777569e+00 -1.0567291e+00 - 2.7182790e+00 9.4068046e+00 -1.0525050e+00 - 2.9302248e+00 1.0309563e+01 -1.0570938e+00 - 3.2009087e+00 1.1454953e+01 -1.0732128e+00 - 3.5232905e+00 1.2825137e+01 -1.0848199e+00 - 3.9128823e+00 1.4477544e+01 -1.0881356e+00 - 4.2597797e+00 1.5950029e+01 -1.0096228e+00 - 5.2876182e+00 2.0309464e+01 -1.1901600e+00 - 1.1186321e+01 4.5339685e+01 -6.2089648e-01 - 1.2058264e+01 4.9057999e+01 3.6475011e+00 - 9.1809864e+00 3.6849305e+01 3.6519352e+00 - 9.2372590e+00 3.7094969e+01 5.0102604e+00 - 1.2396154e+01 5.0538709e+01 1.3951276e+01 - 2.6790695e+00 9.2696439e+00 4.6568362e+00 - 2.6596255e+00 9.1884021e+00 4.8149537e+00 - 2.6399892e+00 9.1040758e+00 4.9713221e+00 - 2.6407699e+00 9.1067042e+00 5.1664285e+00 - 2.6023974e+00 8.9464917e+00 5.2868068e+00 - 2.5500736e+00 8.7231856e+00 5.3720362e+00 - 2.1873006e+00 7.1820290e+00 4.7603469e+00 - 2.4866903e+00 8.4575307e+00 5.6210221e+00 - 2.4698939e+00 8.3870457e+00 5.7767904e+00 - 2.4447381e+00 8.2788981e+00 5.9113396e+00 - 2.3967414e+00 8.0779218e+00 5.9869303e+00 - 2.1052354e+00 6.8360655e+00 5.3889729e+00 - 1.9026444e+00 5.9767735e+00 4.9878622e+00 - 1.8978219e+00 5.9559438e+00 5.1279910e+00 - 1.9094145e+00 6.0049159e+00 5.3201438e+00 - 1.9142315e+00 6.0254873e+00 5.4977196e+00 - 1.8918584e+00 5.9322702e+00 5.5929676e+00 - 1.8763716e+00 5.8688548e+00 5.7109329e+00 - 1.8152480e+00 5.6064298e+00 5.6643813e+00 - 1.5610908e+00 4.5267059e+00 4.9027039e+00 - 1.5973500e+00 4.6807330e+00 5.1800339e+00 - 1.5088529e+00 4.3051178e+00 4.9822411e+00 - 1.8366700e+00 5.7030487e+00 6.4638752e+00 - 1.6272101e+00 4.8117313e+00 5.7733276e+00 - 1.5341881e+00 4.4132380e+00 5.5335381e+00 - 1.4661974e+00 4.1252918e+00 5.3889653e+00 - 1.5057110e+00 4.2964712e+00 5.7328122e+00 - 1.4608408e+00 4.1041046e+00 5.6827044e+00 - 1.4327260e+00 3.9858067e+00 5.7103401e+00 - 1.4544219e+00 4.0809180e+00 5.9954721e+00 - 1.3984606e+00 3.8415232e+00 5.8736612e+00 - 1.3799916e+00 3.7641615e+00 5.9495801e+00 - 1.3113486e+00 3.4694556e+00 5.7287503e+00 - 1.2874980e+00 3.3714377e+00 5.7659723e+00 - 1.2895527e+00 3.3787885e+00 5.9567328e+00 - 1.2780885e+00 3.3321744e+00 6.0745453e+00 - 1.2495627e+00 3.2085290e+00 6.0748132e+00 - 1.4109817e+00 3.9011821e+00 7.4121423e+00 - 1.3618852e+00 3.6914165e+00 7.3095531e+00 - 1.3226517e+00 3.5253546e+00 7.2708286e+00 - 1.3028859e+00 3.4415410e+00 7.3768105e+00 - 1.2241499e+00 3.1043884e+00 6.9960369e+00 - 1.1836096e+00 2.9354045e+00 6.9171148e+00 - 1.1692110e+00 2.8726480e+00 7.0496589e+00 - 1.1365895e+00 2.7326481e+00 7.0186192e+00 - 1.1960775e+00 2.9904257e+00 7.8980371e+00 - 1.1268143e+00 2.6938581e+00 7.5179064e+00 - 1.0989455e+00 2.5790733e+00 7.5559803e+00 - 1.0906601e+00 2.5448825e+00 7.8065249e+00 - 1.0182343e+00 2.2355057e+00 7.3060963e+00 - 9.9113391e-01 2.1183086e+00 7.3167505e+00 - 9.1821489e-01 1.8065378e+00 6.7070082e+00 - 8.9095074e-01 1.6890634e+00 6.6715201e+00 - 8.6699228e-01 1.5901833e+00 6.6912637e+00 - 8.8195992e-01 1.6544788e+00 7.3371004e+00 - 8.3330552e-01 1.4494928e+00 6.9679441e+00 - 6.9045470e-01 8.3151354e-01 4.6934657e+00 - 6.7550784e-01 7.6643861e-01 4.6979694e+00 - 6.6085630e-01 7.0527091e-01 4.7209016e+00 - 6.4768240e-01 6.4993722e-01 4.7822847e+00 - 6.3432025e-01 5.9206769e-01 4.8327804e+00 - 6.1983332e-01 5.3221542e-01 4.8823797e+00 - 6.1653449e-01 5.1995088e-01 5.3379662e+00 - 6.1076289e-01 4.9729541e-01 5.8438419e+00 - 5.7101936e-01 3.2573952e-01 4.8059589e+00 - 5.5620073e-01 2.6168935e-01 4.8312370e+00 - 5.4143574e-01 1.9806780e-01 4.8652044e+00 - 5.3391565e-01 1.7450531e-01 6.0974314e+00 - 5.1362953e-01 8.8080870e-02 6.0897049e+00 - 9.2811386e-01 1.5981600e+00 -1.0053991e+00 - 9.4365586e-01 1.6563436e+00 -1.0065630e+00 - 9.5789139e-01 1.7090296e+00 -9.9883689e-01 - 9.7357232e-01 1.7693549e+00 -9.9710349e-01 - 9.9020045e-01 1.8286967e+00 -9.9382558e-01 - 1.0097144e+00 1.9032777e+00 -1.0033320e+00 - 1.0254256e+00 1.9638444e+00 -9.9670466e-01 - 1.0422056e+00 2.0254314e+00 -9.8843214e-01 - 1.0666338e+00 2.1153869e+00 -1.0055357e+00 - 1.0834974e+00 2.1781580e+00 -9.9351741e-01 - 1.1041935e+00 2.2551799e+00 -9.9283883e-01 - 1.1264069e+00 2.3409317e+00 -9.9630482e-01 - 1.1472524e+00 2.4201790e+00 -9.9103113e-01 - 1.1729973e+00 2.5146826e+00 -9.9575162e-01 - 1.2002062e+00 2.6169733e+00 -1.0034685e+00 - 1.2261079e+00 2.7137614e+00 -1.0023953e+00 - 1.2544736e+00 2.8182910e+00 -1.0040221e+00 - 1.2829800e+00 2.9249771e+00 -1.0024521e+00 - 1.3129553e+00 3.0394896e+00 -1.0030794e+00 - 1.3489689e+00 3.1713545e+00 -1.0105072e+00 - 1.3840705e+00 3.3044836e+00 -1.0137866e+00 - 1.4178066e+00 3.4311281e+00 -1.0079267e+00 - 1.4605550e+00 3.5915827e+00 -1.0172069e+00 - 1.5018820e+00 3.7445901e+00 -1.0165992e+00 - 1.5458733e+00 3.9084875e+00 -1.0156440e+00 - 1.5989580e+00 4.1073594e+00 -1.0264826e+00 - 1.6546597e+00 4.3162277e+00 -1.0348267e+00 - 1.7130417e+00 4.5361141e+00 -1.0402265e+00 - 1.7776226e+00 4.7756669e+00 -1.0460339e+00 - 1.8463533e+00 5.0340691e+00 -1.0509946e+00 - 1.9187158e+00 5.3025404e+00 -1.0507673e+00 - 1.9978794e+00 5.6006476e+00 -1.0514431e+00 - 2.0873737e+00 5.9371279e+00 -1.0545762e+00 - 2.1805203e+00 6.2838397e+00 -1.0492254e+00 - 2.2958179e+00 6.7158057e+00 -1.0574282e+00 - 2.4148520e+00 7.1591923e+00 -1.0533014e+00 - 2.5586629e+00 7.6978986e+00 -1.0588355e+00 - 2.7257548e+00 8.3233670e+00 -1.0663901e+00 - 2.9136277e+00 9.0270513e+00 -1.0693206e+00 - 3.1222479e+00 9.8081664e+00 -1.0632828e+00 - 3.3980250e+00 1.0839020e+01 -1.0769873e+00 - 3.7256150e+00 1.2063523e+01 -1.0870474e+00 - 4.1324207e+00 1.3587067e+01 -1.0991313e+00 - 4.6609153e+00 1.5565327e+01 -1.1180765e+00 - 5.1521085e+00 1.7402765e+01 -1.0490453e+00 - 6.2279721e+00 2.1425144e+01 -1.1314517e+00 - 1.1884655e+01 4.2593564e+01 -9.1767393e-01 - 1.7915145e+01 6.5160525e+01 4.2208565e-01 - 1.7937209e+01 6.5247832e+01 1.6001012e+00 - 1.0199913e+01 3.6306086e+01 3.3046879e+00 - 1.0307235e+01 3.6716305e+01 4.6655944e+00 - 1.0332287e+01 3.6812880e+01 5.3475231e+00 - 1.0241725e+01 3.6475475e+01 5.9765803e+00 - 1.0220319e+01 3.6424668e+01 1.2173559e+01 - 1.0081628e+01 3.5908743e+01 1.2724411e+01 - 1.0062833e+01 3.5843087e+01 1.3418919e+01 - 2.9847590e+00 9.3174876e+00 4.4167984e+00 - 2.9632800e+00 9.2420316e+00 4.7695834e+00 - 2.9299573e+00 9.1145651e+00 4.9091409e+00 - 2.8068066e+00 8.6562900e+00 5.4682678e+00 - 2.7266185e+00 8.3559699e+00 5.5039021e+00 - 2.7327999e+00 8.3809547e+00 5.7113890e+00 - 2.4237859e+00 7.2242667e+00 5.2315892e+00 - 2.5710542e+00 7.7763759e+00 5.7421100e+00 - 2.6125719e+00 7.9337863e+00 6.0333581e+00 - 2.5897951e+00 7.8479596e+00 6.1759028e+00 - 2.0980060e+00 6.0033105e+00 5.1134052e+00 - 2.0725504e+00 5.9090561e+00 5.2042178e+00 - 2.1009834e+00 6.0185507e+00 5.4438436e+00 - 2.0358624e+00 5.7715874e+00 5.4209841e+00 - 2.0051547e+00 5.6577114e+00 5.4940739e+00 - 1.9521355e+00 5.4603949e+00 5.4959243e+00 - 1.7584985e+00 4.7352752e+00 5.0403810e+00 - 1.7036871e+00 4.5270316e+00 5.0018309e+00 - 1.7544256e+00 4.7194032e+00 5.3215348e+00 - 1.7605529e+00 4.7449876e+00 5.5006575e+00 - 1.7387399e+00 4.6619192e+00 5.5787809e+00 - 1.8645993e+00 5.1347060e+00 6.2231067e+00 - 1.8245666e+00 4.9850362e+00 6.2508616e+00 - 1.6158709e+00 4.2042621e+00 5.5855944e+00 - 1.5742837e+00 4.0476283e+00 5.5722512e+00 - 1.6727746e+00 4.4183957e+00 6.1690133e+00 - 1.6538912e+00 4.3493689e+00 6.2708561e+00 - 1.9696954e+00 5.5383572e+00 7.9537065e+00 - 1.5085324e+00 3.8024195e+00 5.9471998e+00 - 1.5265911e+00 3.8711299e+00 6.2214416e+00 - 1.3988567e+00 3.3916979e+00 5.7438604e+00 - 1.3757653e+00 3.3054200e+00 5.7962180e+00 - 1.3923956e+00 3.3671431e+00 6.0694115e+00 - 1.3534779e+00 3.2224718e+00 6.0376398e+00 - 1.6316268e+00 4.2742982e+00 7.9422534e+00 - 1.4982276e+00 3.7724627e+00 7.3702945e+00 - 1.4698430e+00 3.6641716e+00 7.4374876e+00 - 1.4338561e+00 3.5320045e+00 7.4590476e+00 - 1.4056805e+00 3.4269309e+00 7.5306863e+00 - 1.2539452e+00 2.8526206e+00 6.6689537e+00 - 1.3491123e+00 3.2135021e+00 7.6682198e+00 - 1.3237872e+00 3.1208063e+00 7.7703688e+00 - 1.2927324e+00 3.0026092e+00 7.8166406e+00 - 1.2593682e+00 2.8799687e+00 7.8514313e+00 - 1.2013342e+00 2.6604993e+00 7.6436455e+00 - 1.1568986e+00 2.4940830e+00 7.5511042e+00 - 1.1450161e+00 2.4511323e+00 7.7824789e+00 - 1.0786453e+00 2.2008860e+00 7.4296819e+00 - 9.5619991e-01 1.7397377e+00 6.3778591e+00 - 9.4951365e-01 1.7154461e+00 6.6277052e+00 - 9.2504350e-01 1.6236084e+00 6.6674297e+00 - 9.0322117e-01 1.5404660e+00 6.7440549e+00 - 8.7737100e-01 1.4430585e+00 6.7709465e+00 - 7.2582778e-01 8.6753248e-01 4.7346238e+00 - 7.0640960e-01 7.9629568e-01 4.7106236e+00 - 6.8946332e-01 7.3131701e-01 4.7146343e+00 - 6.7411326e-01 6.7415148e-01 4.7566972e+00 - 6.5906120e-01 6.2039876e-01 4.8274255e+00 - 6.4239874e-01 5.5871959e-01 4.8578045e+00 - 6.2697222e-01 4.9939581e-01 4.9168952e+00 - 6.3511732e-01 5.3521624e-01 5.8493302e+00 - 6.1138602e-01 4.4537171e-01 5.7686034e+00 - 5.7197525e-01 2.9121655e-01 4.8188698e+00 - 5.5409472e-01 2.2732485e-01 4.8234334e+00 - 5.4868138e-01 2.1071267e-01 5.9558820e+00 - 5.2764121e-01 1.3278917e-01 6.1788258e+00 - 5.0404515e-01 4.5056788e-02 6.1003968e+00 - 9.8316145e-01 1.6138575e+00 -1.0061128e+00 - 1.0007041e+00 1.6719547e+00 -1.0065838e+00 - 1.0183168e+00 1.7311277e+00 -1.0055064e+00 - 1.0383141e+00 1.7968924e+00 -1.0101755e+00 - 1.0560068e+00 1.8572200e+00 -1.0059515e+00 - 1.0737093e+00 1.9176264e+00 -1.0001295e+00 - 1.0938597e+00 1.9856461e+00 -9.9960426e-01 - 1.1125814e+00 2.0461596e+00 -9.9038966e-01 - 1.1376325e+00 2.1294454e+00 -9.9965880e-01 - 1.1602585e+00 2.2053002e+00 -9.9993580e-01 - 1.1830192e+00 2.2832622e+00 -9.9801473e-01 - 1.2091730e+00 2.3678392e+00 -1.0001455e+00 - 1.2344050e+00 2.4536018e+00 -9.9972582e-01 - 1.2621561e+00 2.5480633e+00 -1.0028546e+00 - 1.2934277e+00 2.6511879e+00 -1.0090357e+00 - 1.3222736e+00 2.7468766e+00 -1.0063246e+00 - 1.3537044e+00 2.8523055e+00 -1.0063125e+00 - 1.3876023e+00 2.9655005e+00 -1.0085010e+00 - 1.4240304e+00 3.0874832e+00 -1.0124402e+00 - 1.4606030e+00 3.2116519e+00 -1.0125833e+00 - 1.5031587e+00 3.3522153e+00 -1.0186784e+00 - 1.5433514e+00 3.4863594e+00 -1.0155312e+00 - 1.5885955e+00 3.6380049e+00 -1.0173836e+00 - 1.6414094e+00 3.8158458e+00 -1.0278839e+00 - 1.6953783e+00 3.9959108e+00 -1.0325938e+00 - 1.7544748e+00 4.1946023e+00 -1.0397560e+00 - 1.8197026e+00 4.4119041e+00 -1.0484747e+00 - 1.8850368e+00 4.6305724e+00 -1.0497523e+00 - 1.9565110e+00 4.8679200e+00 -1.0511882e+00 - 2.0382918e+00 5.1434484e+00 -1.0589766e+00 - 2.1211903e+00 5.4203863e+00 -1.0572295e+00 - 2.2128290e+00 5.7258670e+00 -1.0558430e+00 - 2.3173245e+00 6.0784738e+00 -1.0593635e+00 - 2.4315831e+00 6.4597599e+00 -1.0592528e+00 - 2.5633063e+00 6.8980034e+00 -1.0624599e+00 - 2.7090504e+00 7.3856711e+00 -1.0632856e+00 - 2.8799355e+00 7.9578580e+00 -1.0686358e+00 - 3.0883972e+00 8.6547166e+00 -1.0829711e+00 - 3.3047182e+00 9.3811145e+00 -1.0786871e+00 - 3.5822100e+00 1.0307737e+01 -1.0885623e+00 - 3.9225928e+00 1.1445968e+01 -1.1034568e+00 - 4.3309405e+00 1.2812972e+01 -1.1149371e+00 - 4.8146333e+00 1.4430851e+01 -1.1133258e+00 - 5.6121077e+00 1.7098294e+01 -1.1871512e+00 - 6.4451921e+00 1.9886123e+01 -1.1769236e+00 - 1.2533464e+01 4.0252713e+01 -1.1931864e+00 - 1.2498940e+01 4.0140055e+01 -4.5441198e-01 - 1.9877653e+01 6.4826105e+01 -1.6766511e-01 - 1.0823268e+01 3.4544539e+01 1.6367742e+00 - 1.0780717e+01 3.4404620e+01 2.2613003e+00 - 1.0780903e+01 3.4407737e+01 2.8893202e+00 - 1.0779977e+01 3.4408974e+01 3.5185410e+00 - 1.1178946e+01 3.5746331e+01 4.2715220e+00 - 1.1038205e+01 3.5276381e+01 4.8770898e+00 - 1.1271513e+01 3.6061980e+01 5.6289745e+00 - 1.1435622e+01 3.6614917e+01 6.3784453e+00 - 1.1169022e+01 3.5724748e+01 6.9130046e+00 - 1.1069830e+01 3.5394843e+01 7.5210195e+00 - 1.0936596e+01 3.4951095e+01 8.0978147e+00 - 1.1390856e+01 3.6477024e+01 9.0995712e+00 - 1.1373535e+01 3.6419753e+01 9.7829424e+00 - 1.1385468e+01 3.6463489e+01 1.0495793e+01 - 1.1484502e+01 3.6799314e+01 1.1298327e+01 - 1.1080569e+01 3.5452122e+01 1.2319250e+01 - 1.1073532e+01 3.5431302e+01 1.3021985e+01 - 3.2348637e+00 9.1690447e+00 4.2971222e+00 - 3.2153600e+00 9.1030984e+00 4.4601926e+00 - 3.2212985e+00 9.1245947e+00 4.6577405e+00 - 3.2046165e+00 9.0718279e+00 4.8270519e+00 - 3.1927575e+00 9.0321590e+00 5.0033969e+00 - 3.1466591e+00 8.8765658e+00 5.1265987e+00 - 3.1691213e+00 8.9539907e+00 5.3595330e+00 - 3.1156190e+00 8.7761079e+00 5.4692620e+00 - 2.8506941e+00 7.8898681e+00 5.1969221e+00 - 2.7816610e+00 7.6569850e+00 5.2507877e+00 - 2.7202965e+00 7.4510855e+00 5.3119856e+00 - 2.7250087e+00 7.4692721e+00 5.5019949e+00 - 2.6801210e+00 7.3189269e+00 5.5909885e+00 - 2.8115694e+00 7.7607345e+00 6.0627933e+00 - 2.4101139e+00 6.4133920e+00 5.3480668e+00 - 2.2333728e+00 5.8239777e+00 5.1005901e+00 - 2.2504111e+00 5.8798924e+00 5.2977735e+00 - 2.1914677e+00 5.6834559e+00 5.3101300e+00 - 2.1782451e+00 5.6404118e+00 5.4370888e+00 - 2.1495681e+00 5.5429784e+00 5.5205688e+00 - 2.0397380e+00 5.1762791e+00 5.3753331e+00 - 1.8559036e+00 4.5595357e+00 4.9931804e+00 - 1.9927452e+00 5.0195126e+00 5.5545674e+00 - 1.8915248e+00 4.6797974e+00 5.3976347e+00 - 1.8731636e+00 4.6195855e+00 5.4958355e+00 - 1.8648727e+00 4.5915397e+00 5.6278312e+00 - 1.9038857e+00 4.7235628e+00 5.9299589e+00 - 1.7695308e+00 4.2749044e+00 5.6195085e+00 - 1.6960490e+00 4.0269717e+00 5.5064370e+00 - 1.6291019e+00 3.8034520e+00 5.4081407e+00 - 1.6015545e+00 3.7101021e+00 5.4540663e+00 - 1.6062155e+00 3.7278797e+00 5.6357859e+00 - 1.5774756e+00 3.6314911e+00 5.6796660e+00 - 1.5857731e+00 3.6583440e+00 5.8869475e+00 - 1.5147871e+00 3.4204703e+00 5.7371198e+00 - 1.5041016e+00 3.3862681e+00 5.8634265e+00 - 1.4663802e+00 3.2599245e+00 5.8587779e+00 - 1.4915311e+00 3.3443086e+00 6.1744548e+00 - 1.7022320e+00 4.0563528e+00 7.5178322e+00 - 1.6517159e+00 3.8854422e+00 7.4889283e+00 - 1.5884150e+00 3.6731379e+00 7.3785421e+00 - 1.5369121e+00 3.5034096e+00 7.3318641e+00 - 1.5276362e+00 3.4719189e+00 7.5346229e+00 - 1.4798058e+00 3.3125848e+00 7.4997247e+00 - 1.4408426e+00 3.1812609e+00 7.5144530e+00 - 1.4058097e+00 3.0639380e+00 7.5532971e+00 - 1.3735332e+00 2.9577249e+00 7.6172077e+00 - 1.2826155e+00 2.6522472e+00 7.2131199e+00 - 1.2813564e+00 2.6489765e+00 7.5090538e+00 - 1.2395977e+00 2.5072606e+00 7.4727485e+00 - 1.2333251e+00 2.4878222e+00 7.7601994e+00 - 1.1811598e+00 2.3117694e+00 7.6258289e+00 - 1.0198683e+00 1.7667346e+00 6.3526053e+00 - 1.0202762e+00 1.7723577e+00 6.6882397e+00 - 1.2054974e+00 2.3999259e+00 9.1869611e+00 - 9.5725563e-01 1.5597146e+00 6.6722849e+00 - 9.2971473e-01 1.4669331e+00 6.7094717e+00 - 8.6350700e-01 1.2440781e+00 6.2016330e+00 - 7.4024256e-01 8.2494981e-01 4.7228183e+00 - 7.2018484e-01 7.5870227e-01 4.7176995e+00 - 7.0123853e-01 6.9381494e-01 4.7211173e+00 - 6.8821777e-01 6.5341511e-01 4.8611607e+00 - 6.6807888e-01 5.8600311e-01 4.8526956e+00 - 6.5053642e-01 5.2584445e-01 4.8924166e+00 - 6.3638758e-01 4.8085672e-01 5.0800517e+00 - 6.8544345e-01 6.5260545e-01 7.4651294e+00 - 5.8998882e-01 3.2307813e-01 4.8360101e+00 - 5.6980944e-01 2.5637416e-01 4.8013781e+00 - 5.5241905e-01 1.9639921e-01 4.8853437e+00 - 5.4464288e-01 1.7779576e-01 6.2574005e+00 - 5.1799928e-01 8.8273701e-02 6.1998042e+00 - 1.0349814e+00 1.6121006e+00 -1.0592112e+00 - 1.0400868e+00 1.6274550e+00 -1.0064341e+00 - 1.0596307e+00 1.6854708e+00 -1.0061124e+00 - 1.0768694e+00 1.7380444e+00 -9.9699763e-01 - 1.1012426e+00 1.8102405e+00 -1.0082186e+00 - 1.1208764e+00 1.8694897e+00 -1.0031525e+00 - 1.1429573e+00 1.9363472e+00 -1.0034829e+00 - 1.1626722e+00 1.9967608e+00 -9.9507051e-01 - 1.1896527e+00 2.0788746e+00 -1.0053951e+00 - 1.2128278e+00 2.1469544e+00 -9.9998542e-01 - 1.2398980e+00 2.2303016e+00 -1.0055655e+00 - 1.2656003e+00 2.3071444e+00 -1.0024059e+00 - 1.2938188e+00 2.3926615e+00 -1.0032942e+00 - 1.3220532e+00 2.4783068e+00 -1.0015856e+00 - 1.3561890e+00 2.5791773e+00 -1.0092752e+00 - 1.3869624e+00 2.6736792e+00 -1.0079191e+00 - 1.4213176e+00 2.7778510e+00 -1.0094651e+00 - 1.4556330e+00 2.8811884e+00 -1.0076656e+00 - 1.4935340e+00 2.9942254e+00 -1.0081689e+00 - 1.5389237e+00 3.1322933e+00 -1.0206664e+00 - 1.5794423e+00 3.2553316e+00 -1.0185754e+00 - 1.6234943e+00 3.3871366e+00 -1.0174392e+00 - 1.6701442e+00 3.5287852e+00 -1.0169048e+00 - 1.7313821e+00 3.7137733e+00 -1.0348184e+00 - 1.7876917e+00 3.8827595e+00 -1.0375944e+00 - 1.8440967e+00 4.0530234e+00 -1.0347271e+00 - 1.9151106e+00 4.2667943e+00 -1.0469119e+00 - 1.9862906e+00 4.4829237e+00 -1.0518048e+00 - 2.0646677e+00 4.7186590e+00 -1.0571086e+00 - 2.1491306e+00 4.9721260e+00 -1.0615225e+00 - 2.2362874e+00 5.2367194e+00 -1.0607947e+00 - 2.3331795e+00 5.5297704e+00 -1.0609301e+00 - 2.4337146e+00 5.8329791e+00 -1.0540797e+00 - 2.5623112e+00 6.2199345e+00 -1.0637487e+00 - 2.6935759e+00 6.6172953e+00 -1.0626335e+00 - 2.8503577e+00 7.0889876e+00 -1.0687467e+00 - 3.0256933e+00 7.6188202e+00 -1.0732366e+00 - 3.2327653e+00 8.2428134e+00 -1.0820666e+00 - 3.4741932e+00 8.9709833e+00 -1.0923427e+00 - 3.7377797e+00 9.7666315e+00 -1.0903648e+00 - 4.0613770e+00 1.0742920e+01 -1.0943639e+00 - 4.4598192e+00 1.1946187e+01 -1.1025122e+00 - 4.9536681e+00 1.3434545e+01 -1.1112951e+00 - 5.6192931e+00 1.5444277e+01 -1.1376454e+00 - 6.6779095e+00 1.8636582e+01 -1.2318645e+00 - 7.6308144e+00 2.1514699e+01 -1.1766684e+00 - 1.3065542e+01 3.7914289e+01 -7.3429290e-01 - 1.1935417e+01 3.4513076e+01 1.3260844e+00 - 1.2020058e+01 3.4768563e+01 1.9679672e+00 - 1.1929731e+01 3.4501290e+01 2.5956661e+00 - 1.1890594e+01 3.4384432e+01 3.2241398e+00 - 1.2164444e+01 3.5213360e+01 3.9283810e+00 - 1.2255524e+01 3.5490439e+01 4.6089079e+00 - 1.2270583e+01 3.5538657e+01 5.2744604e+00 - 1.1751542e+01 3.3975260e+01 5.7206351e+00 - 1.1919897e+01 3.4484202e+01 6.4377074e+00 - 1.1976797e+01 3.4660061e+01 7.1188326e+00 - 1.1990554e+01 3.4703335e+01 7.7842365e+00 - 1.1808966e+01 3.4157621e+01 8.3294143e+00 - 1.1717119e+01 3.3883656e+01 8.9215083e+00 - 1.2595925e+01 3.6542043e+01 1.0964138e+01 - 1.1575304e+01 3.3462195e+01 1.0783944e+01 - 1.1588086e+01 3.3505203e+01 1.1462984e+01 - 1.1618027e+01 3.3598596e+01 1.2167567e+01 - 1.1352294e+01 3.2795977e+01 1.2567642e+01 - 1.1342783e+01 3.2769399e+01 1.3232229e+01 - 3.4732808e+00 8.9903393e+00 4.5432602e+00 - 3.4409014e+00 8.8944350e+00 4.6933699e+00 - 3.4984479e+00 9.0696954e+00 4.9596089e+00 - 3.4388032e+00 8.8894011e+00 5.0739002e+00 - 3.3841368e+00 8.7249937e+00 5.1909816e+00 - 3.3811044e+00 8.7145574e+00 5.3809487e+00 - 3.3844211e+00 8.7255037e+00 5.5850407e+00 - 3.3556722e+00 8.6396585e+00 5.7401386e+00 - 2.8788153e+00 7.2002695e+00 5.1201287e+00 - 2.8610848e+00 7.1481923e+00 5.2616783e+00 - 2.9346834e+00 7.3709704e+00 5.5751355e+00 - 2.9786749e+00 7.5041401e+00 5.8458372e+00 - 2.9461493e+00 7.4070681e+00 5.9722762e+00 - 2.3852961e+00 5.7085715e+00 4.9813922e+00 - 2.4294120e+00 5.8447977e+00 5.2330190e+00 - 2.4806308e+00 5.9978147e+00 5.5082039e+00 - 2.2004107e+00 5.1517642e+00 5.0168081e+00 - 2.2024259e+00 5.1603470e+00 5.1717640e+00 - 2.2041481e+00 5.1640090e+00 5.3282659e+00 - 2.0177208e+00 4.6010693e+00 4.9962403e+00 - 2.0642636e+00 4.7431941e+00 5.2685872e+00 - 2.0696441e+00 4.7571370e+00 5.4345718e+00 - 2.0096882e+00 4.5784827e+00 5.4200253e+00 - 1.9756683e+00 4.4769910e+00 5.4759042e+00 - 1.9552345e+00 4.4157750e+00 5.5715641e+00 - 1.7792350e+00 3.8803362e+00 5.1597209e+00 - 1.7711817e+00 3.8567677e+00 5.2811815e+00 - 1.6960759e+00 3.6313139e+00 5.1744203e+00 - 1.6768525e+00 3.5743127e+00 5.2554471e+00 - 1.6898966e+00 3.6136526e+00 5.4573776e+00 - 1.6717804e+00 3.5579772e+00 5.5462418e+00 - 1.6340463e+00 3.4467895e+00 5.5639743e+00 - 1.5658773e+00 3.2373153e+00 5.4440669e+00 - 1.6204961e+00 3.4065857e+00 5.8485896e+00 - 1.5537653e+00 3.2041775e+00 5.7313285e+00 - 1.5932449e+00 3.3241566e+00 6.0944219e+00 - 1.6240447e+00 3.4176231e+00 6.4382512e+00 - 1.6876627e+00 3.6128635e+00 6.9725991e+00 - 1.6547610e+00 3.5127862e+00 7.0381133e+00 - 1.6860121e+00 3.6098591e+00 7.4550523e+00 - 1.6430994e+00 3.4791219e+00 7.4767848e+00 - 1.6217663e+00 3.4166932e+00 7.6276781e+00 - 1.3864406e+00 2.7020877e+00 6.4652018e+00 - 1.4692931e+00 2.9542038e+00 7.2389243e+00 - 1.4351362e+00 2.8505852e+00 7.2922056e+00 - 1.3315904e+00 2.5365123e+00 6.8612860e+00 - 1.3126511e+00 2.4807491e+00 7.0079309e+00 - 1.2684287e+00 2.3480986e+00 6.9693914e+00 - 1.3142463e+00 2.4896718e+00 7.6535778e+00 - 1.2825668e+00 2.3923557e+00 7.7357690e+00 - 1.0766253e+00 1.7663083e+00 6.2515518e+00 - 1.0358544e+00 1.6433164e+00 6.1693612e+00 - 1.0577278e+00 1.7111803e+00 6.7137543e+00 - 1.0260319e+00 1.6163117e+00 6.7442613e+00 - 9.8393252e-01 1.4886781e+00 6.6477900e+00 - 9.5599008e-01 1.4043349e+00 6.7129981e+00 - 7.7619002e-01 8.5494310e-01 4.7443455e+00 - 7.5507824e-01 7.8779355e-01 4.7399786e+00 - 7.3190168e-01 7.2021804e-01 4.7245317e+00 - 7.1640204e-01 6.7402000e-01 4.8256280e+00 - 6.9681270e-01 6.1357825e-01 4.8571655e+00 - 6.7485524e-01 5.4873925e-01 4.8578962e+00 - 6.5537440e-01 4.8916460e-01 4.9070119e+00 - 6.6533231e-01 5.2288183e-01 5.8195149e+00 - 6.0850978e-01 3.4941024e-01 4.8030580e+00 - 5.8764277e-01 2.8576394e-01 4.8089296e+00 - 5.6682858e-01 2.2305546e-01 4.8135531e+00 - 5.6029315e-01 2.0551346e-01 5.9259296e+00 - 5.3413516e-01 1.2842463e-01 6.0989022e+00 - 5.0598126e-01 4.3938933e-02 6.1004400e+00 - 1.0979519e+00 1.6400099e+00 -1.0064093e+00 - 1.1194965e+00 1.6979392e+00 -1.0053949e+00 - 1.1376780e+00 1.7494949e+00 -9.9543474e-01 - 1.1593013e+00 1.8085689e+00 -9.9147358e-01 - 1.1856876e+00 1.8807772e+00 -1.0000043e+00 - 1.2097102e+00 1.9465612e+00 -9.9939264e-01 - 1.2372403e+00 2.0209050e+00 -1.0039307e+00 - 1.2637865e+00 2.0954224e+00 -1.0061684e+00 - 1.2889641e+00 2.1634306e+00 -9.9976629e-01 - 1.3165945e+00 2.2390915e+00 -9.9786190e-01 - 1.3442391e+00 2.3148657e+00 -9.9366035e-01 - 1.3778409e+00 2.4068277e+00 -9.9960556e-01 - 1.4080189e+00 2.4914142e+00 -9.9665533e-01 - 1.4451578e+00 2.5921724e+00 -1.0029562e+00 - 1.4823766e+00 2.6940852e+00 -1.0061105e+00 - 1.5161710e+00 2.7886176e+00 -1.0004692e+00 - 1.5604400e+00 2.9079306e+00 -1.0082300e+00 - 1.5978403e+00 3.0123250e+00 -1.0015956e+00 - 1.6481717e+00 3.1491824e+00 -1.0122616e+00 - 1.6951432e+00 3.2796908e+00 -1.0134825e+00 - 1.7491599e+00 3.4275600e+00 -1.0201089e+00 - 1.8067173e+00 3.5842549e+00 -1.0264915e+00 - 1.8668807e+00 3.7508575e+00 -1.0321775e+00 - 1.9316494e+00 3.9272717e+00 -1.0366738e+00 - 2.0025432e+00 4.1222469e+00 -1.0437255e+00 - 2.0734790e+00 4.3175572e+00 -1.0439856e+00 - 2.1551217e+00 4.5410528e+00 -1.0494066e+00 - 2.2393908e+00 4.7746187e+00 -1.0508351e+00 - 2.3378388e+00 5.0441298e+00 -1.0585296e+00 - 2.4364658e+00 5.3161028e+00 -1.0568350e+00 - 2.5457698e+00 5.6155057e+00 -1.0553578e+00 - 2.6658203e+00 5.9434092e+00 -1.0526495e+00 - 2.8051946e+00 6.3260222e+00 -1.0558631e+00 - 2.9615082e+00 6.7567530e+00 -1.0592519e+00 - 3.1417638e+00 7.2521083e+00 -1.0652755e+00 - 3.3470420e+00 7.8132020e+00 -1.0703910e+00 - 3.5886534e+00 8.4781988e+00 -1.0800551e+00 - 3.8579303e+00 9.2191373e+00 -1.0821219e+00 - 4.1858895e+00 1.0118753e+01 -1.0896748e+00 - 4.5787649e+00 1.1196994e+01 -1.0974285e+00 - 5.0304974e+00 1.2435826e+01 -1.0921410e+00 - 5.6421023e+00 1.4115391e+01 -1.1066772e+00 - 6.4856297e+00 1.6432897e+01 -1.1420988e+00 - 7.7026068e+00 1.9773636e+01 -1.2056694e+00 - 1.3500410e+01 3.5695152e+01 -9.8034653e-01 - 1.3516328e+01 3.5741167e+01 -3.1769443e-01 - 1.3738035e+01 3.6354509e+01 1.0107595e+00 - 1.2969357e+01 3.4248419e+01 2.2829291e+00 - 1.2867227e+01 3.3968521e+01 2.9046153e+00 - 1.3013046e+01 3.4372848e+01 3.5681146e+00 - 1.3186386e+01 3.4849902e+01 4.2550901e+00 - 1.3076431e+01 3.4555572e+01 5.5254357e+00 - 1.3087479e+01 3.4587596e+01 6.1832011e+00 - 1.2959229e+01 3.4240285e+01 7.4349468e+00 - 1.2676462e+01 3.3465601e+01 7.9323702e+00 - 1.3064496e+01 3.4532530e+01 8.8213096e+00 - 1.3438992e+01 3.5568719e+01 1.0447656e+01 - 1.1623761e+01 3.0579205e+01 9.7285808e+00 - 1.1621540e+01 3.0576590e+01 1.0339277e+01 - 3.7359122e+00 8.9013409e+00 4.0808554e+00 - 3.7366263e+00 8.9034373e+00 4.2651751e+00 - 3.7000581e+00 8.8046607e+00 4.4129492e+00 - 3.7297929e+00 8.8870383e+00 4.6332791e+00 - 1.3174344e+01 3.4860517e+01 1.5998025e+01 - 3.8038215e+00 9.0918066e+00 5.1096219e+00 - 3.6354514e+00 8.6285953e+00 5.0906577e+00 - 3.0500867e+00 7.0179237e+00 4.4848729e+00 - 3.0557297e+00 7.0360269e+00 4.6541550e+00 - 3.1070580e+00 7.1762088e+00 4.8932270e+00 - 3.1283674e+00 7.2361700e+00 5.0962920e+00 - 3.0855133e+00 7.1185797e+00 5.2009787e+00 - 3.1600670e+00 7.3246649e+00 5.5026378e+00 - 3.1414553e+00 7.2740984e+00 5.6533297e+00 - 3.0090329e+00 6.9101637e+00 5.5968065e+00 - 2.7893410e+00 6.3057915e+00 5.3594440e+00 - 2.7827383e+00 6.2878402e+00 5.5149609e+00 - 2.5145073e+00 5.5510483e+00 5.1375489e+00 - 2.3480002e+00 5.0949028e+00 4.9401050e+00 - 2.4006534e+00 5.2391827e+00 5.2026960e+00 - 2.4618171e+00 5.4065589e+00 5.4963349e+00 - 2.2163659e+00 4.7336556e+00 5.0798866e+00 - 2.1707878e+00 4.6077921e+00 5.1157128e+00 - 2.1797939e+00 4.6317548e+00 5.2858866e+00 - 2.1537607e+00 4.5613364e+00 5.3712216e+00 - 2.1774159e+00 4.6260316e+00 5.5916603e+00 - 2.1368895e+00 4.5166412e+00 5.6421618e+00 - 1.9904542e+00 4.1141777e+00 5.3786680e+00 - 1.8838980e+00 3.8193263e+00 5.2097431e+00 - 1.8309121e+00 3.6732051e+00 5.1922472e+00 - 1.7645269e+00 3.4903625e+00 5.1259829e+00 - 1.7749856e+00 3.5209904e+00 5.3109376e+00 - 1.7560451e+00 3.4683121e+00 5.3985577e+00 - 1.7226560e+00 3.3780498e+00 5.4389604e+00 - 1.6585464e+00 3.2004129e+00 5.3591089e+00 - 1.6765104e+00 3.2531101e+00 5.5935911e+00 - 1.6551274e+00 3.1933769e+00 5.6775694e+00 - 1.5935536e+00 3.0245719e+00 5.5968660e+00 - 1.6309678e+00 3.1283467e+00 5.9341386e+00 - 1.8142102e+00 3.6354935e+00 6.9560836e+00 - 1.8519793e+00 3.7410728e+00 7.3704602e+00 - 1.4359792e+00 2.5902554e+00 5.5871231e+00 - 1.7804924e+00 3.5447529e+00 7.5313716e+00 - 1.7348766e+00 3.4185889e+00 7.5611053e+00 - 1.6980723e+00 3.3194728e+00 7.6412142e+00 - 1.5626298e+00 2.9451140e+00 7.1492861e+00 - 1.5169502e+00 2.8194708e+00 7.1490575e+00 - 1.4195078e+00 2.5512056e+00 6.8197689e+00 - 1.3737257e+00 2.4252587e+00 6.7931233e+00 - 1.3402348e+00 2.3326361e+00 6.8464588e+00 - 1.2908307e+00 2.1982464e+00 6.7868109e+00 - 1.2312106e+00 2.0325893e+00 6.6305472e+00 - 1.1530634e+00 1.8177738e+00 6.3103174e+00 - 1.0945716e+00 1.6561905e+00 6.1162995e+00 - 1.0969694e+00 1.6621576e+00 6.4410913e+00 - 1.0835728e+00 1.6278225e+00 6.6623384e+00 - 1.0476367e+00 1.5301869e+00 6.6723826e+00 - 1.0128078e+00 1.4338769e+00 6.6902643e+00 - 9.8552487e-01 1.3584142e+00 6.7936779e+00 - 7.8966767e-01 8.1290862e-01 4.7424310e+00 - 7.6827868e-01 7.5570673e-01 4.7764230e+00 - 8.7095808e-01 1.0429148e+00 6.7041176e+00 - 8.2063681e-01 9.0377456e-01 6.4468656e+00 - 7.0371216e-01 5.7781387e-01 4.8725039e+00 - 6.8093575e-01 5.1498313e-01 4.8924644e+00 - 6.5957737e-01 4.5699438e-01 4.9510253e+00 - 7.2425620e-01 6.4571287e-01 7.5148911e+00 - 6.0740831e-01 3.1452043e-01 4.8060874e+00 - 5.8441796e-01 2.4998011e-01 4.7913908e+00 - 5.6321761e-01 1.9273847e-01 4.8853575e+00 - 5.5208363e-01 1.6543916e-01 5.9976430e+00 - 5.2286824e-01 8.6481824e-02 6.1898502e+00 - 1.1576942e+00 1.6504599e+00 -1.0060921e+00 - 1.1778075e+00 1.7008632e+00 -9.9678786e-01 - 1.2037373e+00 1.7652978e+00 -1.0008272e+00 - 1.2296788e+00 1.8298260e+00 -1.0029689e+00 - 1.2556916e+00 1.8954399e+00 -1.0033624e+00 - 1.2817161e+00 1.9611474e+00 -1.0018582e+00 - 1.3078126e+00 2.0279454e+00 -9.9850595e-01 - 1.3372986e+00 2.1013289e+00 -9.9980475e-01 - 1.3644781e+00 2.1692605e+00 -9.9251013e-01 - 1.3940508e+00 2.2438529e+00 -9.8956378e-01 - 1.4329597e+00 2.3411347e+00 -1.0031132e+00 - 1.4636812e+00 2.4179019e+00 -9.9537516e-01 - 1.5003034e+00 2.5098895e+00 -9.9713510e-01 - 1.5393877e+00 2.6096037e+00 -1.0018946e+00 - 1.5795501e+00 2.7104121e+00 -1.0035107e+00 - 1.6207905e+00 2.8123147e+00 -1.0019836e+00 - 1.6680049e+00 2.9305380e+00 -1.0079065e+00 - 1.7153035e+00 3.0499505e+00 -1.0099838e+00 - 1.7626864e+00 3.1705520e+00 -1.0082155e+00 - 1.8180493e+00 3.3074324e+00 -1.0123056e+00 - 1.8760126e+00 3.4541761e+00 -1.0165979e+00 - 1.9444776e+00 3.6259172e+00 -1.0298976e+00 - 2.0140982e+00 3.7998874e+00 -1.0373070e+00 - 2.0863309e+00 3.9838147e+00 -1.0430210e+00 - 2.1641124e+00 4.1765403e+00 -1.0466001e+00 - 2.2480264e+00 4.3878862e+00 -1.0515359e+00 - 2.3355624e+00 4.6092223e+00 -1.0528819e+00 - 2.4348147e+00 4.8587719e+00 -1.0575943e+00 - 2.5386374e+00 5.1173381e+00 -1.0569725e+00 - 2.6486166e+00 5.3947165e+00 -1.0538123e+00 - 2.7774336e+00 5.7187945e+00 -1.0568767e+00 - 2.9143624e+00 6.0607196e+00 -1.0542634e+00 - 3.0762614e+00 6.4679642e+00 -1.0592315e+00 - 3.2524029e+00 6.9116615e+00 -1.0601784e+00 - 3.4732884e+00 7.4663056e+00 -1.0751846e+00 - 3.7095186e+00 8.0586886e+00 -1.0791310e+00 - 3.9718041e+00 8.7170254e+00 -1.0765794e+00 - 4.3073197e+00 9.5597382e+00 -1.0896823e+00 - 4.6867254e+00 1.0514611e+01 -1.0934701e+00 - 5.1263534e+00 1.1619753e+01 -1.0884216e+00 - 5.7180501e+00 1.3102923e+01 -1.1028592e+00 - 6.4530085e+00 1.4949787e+01 -1.1129929e+00 - 7.7701223e+00 1.8259619e+01 -1.2327274e+00 - 9.0096615e+00 2.1372706e+01 -1.2075118e+00 - 1.3958082e+01 3.3802259e+01 -1.2137984e+00 - 1.3961858e+01 3.3814595e+01 -5.7754471e-01 - 1.4176071e+01 3.4357098e+01 6.8886895e-01 - 1.4193943e+01 3.4403167e+01 1.3347857e+00 - 1.4078273e+01 3.4113877e+01 1.9730387e+00 - 1.4076182e+01 3.4111783e+01 2.6145459e+00 - 1.4461818e+01 3.5082537e+01 3.3213137e+00 - 1.4506985e+01 3.5197464e+01 3.9933019e+00 - 1.0938438e+01 2.6235606e+01 4.2262168e+00 - 1.0930860e+01 2.6216655e+01 4.7237108e+00 - 1.4056131e+01 3.4073012e+01 6.4922625e+00 - 1.0991762e+01 2.6373768e+01 5.7590718e+00 - 1.0936969e+01 2.6237617e+01 6.2427139e+00 - 1.0991195e+01 2.6376630e+01 6.7846993e+00 - 1.0973182e+01 2.6333728e+01 7.2921499e+00 - 1.1120954e+01 2.6706566e+01 7.9097318e+00 - 1.1142064e+01 2.6761622e+01 8.4578653e+00 - 1.1031591e+01 2.6485026e+01 8.9138359e+00 - 1.1264919e+01 2.7073768e+01 9.6403878e+00 - 1.1147367e+01 2.6779545e+01 1.0096371e+01 - 1.2123275e+01 2.9236691e+01 1.1537975e+01 - 1.1952419e+01 2.8806997e+01 1.1988554e+01 - 4.0903573e+00 9.0340379e+00 4.6386205e+00 - 4.0045079e+00 8.8186587e+00 4.7416881e+00 - 3.7884475e+00 8.2779466e+00 5.0630559e+00 - 3.2784324e+00 6.9944719e+00 4.5932542e+00 - 3.3076317e+00 7.0689593e+00 4.7954538e+00 - 3.2892655e+00 7.0229342e+00 4.9369090e+00 - 3.9342743e+00 8.6485147e+00 6.0564252e+00 - 3.4286476e+00 7.3762119e+00 5.4938315e+00 - 3.5198059e+00 7.6068101e+00 5.8245164e+00 - 3.2077766e+00 6.8222002e+00 5.5013973e+00 - 3.1821573e+00 6.7561208e+00 5.6341745e+00 - 2.9818636e+00 6.2538557e+00 5.4566357e+00 - 2.8527152e+00 5.9281604e+00 5.3863914e+00 - 2.8022963e+00 5.8032822e+00 5.4563409e+00 - 2.7850522e+00 5.7597342e+00 5.5884557e+00 - 2.7429124e+00 5.6550716e+00 5.6715744e+00 - 2.3490063e+00 4.6621147e+00 4.9923856e+00 - 2.3173688e+00 4.5824544e+00 5.0665968e+00 - 2.3156550e+00 4.5796756e+00 5.2104217e+00 - 2.2685838e+00 4.4620811e+00 5.2493535e+00 - 2.2738328e+00 4.4739414e+00 5.4136394e+00 - 2.2052227e+00 4.3015566e+00 5.3936306e+00 - 2.0553787e+00 3.9244160e+00 5.1511361e+00 - 1.9842955e+00 3.7457632e+00 5.1029166e+00 - 1.9598140e+00 3.6848647e+00 5.1798627e+00 - 1.9005968e+00 3.5356227e+00 5.1525469e+00 - 1.9216202e+00 3.5902032e+00 5.3680941e+00 - 2.0203532e+00 3.8392995e+00 5.8379927e+00 - 1.9000694e+00 3.5356194e+00 5.6160220e+00 - 1.7751028e+00 3.2225403e+00 5.3607021e+00 - 1.7540810e+00 3.1687889e+00 5.4443831e+00 - 1.7511972e+00 3.1626345e+00 5.5995955e+00 - 1.6763003e+00 2.9740067e+00 5.4873119e+00 - 1.7322696e+00 3.1165492e+00 5.8804291e+00 - 1.7112844e+00 3.0625743e+00 5.9798403e+00 - 1.9656929e+00 3.7056275e+00 7.2596688e+00 - 1.5445029e+00 2.6424868e+00 5.6397456e+00 - 1.5067790e+00 2.5481846e+00 5.6541420e+00 - 1.8341557e+00 3.3777340e+00 7.4248379e+00 - 1.7808905e+00 3.2425740e+00 7.4257264e+00 - 1.6746040e+00 2.9744189e+00 7.1484509e+00 - 1.6492434e+00 2.9124702e+00 7.2839264e+00 - 1.5162372e+00 2.5771782e+00 6.8140859e+00 - 1.4652342e+00 2.4481485e+00 6.7796148e+00 - 1.4105639e+00 2.3097973e+00 6.7145878e+00 - 1.3680052e+00 2.2023036e+00 6.7200529e+00 - 1.3074133e+00 2.0516591e+00 6.6023030e+00 - 1.1723310e+00 1.7098770e+00 5.9186313e+00 - 1.1417272e+00 1.6325035e+00 5.9593822e+00 - 1.1343379e+00 1.6142411e+00 6.1884100e+00 - 1.1405110e+00 1.6303920e+00 6.5612361e+00 - 1.1137906e+00 1.5635503e+00 6.6773371e+00 - 1.0749148e+00 1.4670486e+00 6.6864424e+00 - 1.0385059e+00 1.3767656e+00 6.7227597e+00 - 8.2612992e-01 8.3588425e-01 4.7444768e+00 - 8.0250701e-01 7.7587327e-01 4.7595976e+00 - 9.2271328e-01 1.0853805e+00 6.7334425e+00 - 8.6858965e-01 9.4851858e-01 6.4972277e+00 - 7.3462399e-01 6.0723563e-01 4.8965935e+00 - 7.0855323e-01 5.4115865e-01 4.8875985e+00 - 6.8383762e-01 4.7942114e-01 4.9070165e+00 - 6.6184442e-01 4.2542787e-01 5.0048328e+00 - 6.8261730e-01 4.8178933e-01 6.3659067e+00 - 6.0406409e-01 2.7726669e-01 4.7790100e+00 - 5.7943932e-01 2.1728659e-01 4.7935348e+00 - 5.7202822e-01 2.0129960e-01 5.9159526e+00 - 5.4199943e-01 1.2594220e-01 6.0988760e+00 - 5.0891411e-01 4.3264910e-02 6.0904428e+00 - 1.1938378e+00 1.6021242e+00 -1.0063339e+00 - 1.2183167e+00 1.6588752e+00 -1.0052794e+00 - 1.2451801e+00 1.7222179e+00 -1.0099716e+00 - 1.2696792e+00 1.7791315e+00 -1.0056212e+00 - 1.2952461e+00 1.8370554e+00 -9.9982547e-01 - 1.3198252e+00 1.8951236e+00 -9.9232862e-01 - 1.3546029e+00 1.9737038e+00 -1.0037285e+00 - 1.3860790e+00 2.0469171e+00 -1.0060325e+00 - 1.4141307e+00 2.1127501e+00 -9.9954080e-01 - 1.4490720e+00 2.1936690e+00 -1.0040484e+00 - 1.4817080e+00 2.2691459e+00 -9.9976291e-01 - 1.5142974e+00 2.3437342e+00 -9.9323054e-01 - 1.5528459e+00 2.4345252e+00 -9.9654531e-01 - 1.5958533e+00 2.5329267e+00 -1.0027661e+00 - 1.6423235e+00 2.6390142e+00 -1.0115901e+00 - 1.6820467e+00 2.7321869e+00 -1.0059184e+00 - 1.7286792e+00 2.8406033e+00 -1.0080499e+00 - 1.7763922e+00 2.9501336e+00 -1.0066386e+00 - 1.8380358e+00 3.0920762e+00 -1.0223312e+00 - 1.8859174e+00 3.2039847e+00 -1.0132286e+00 - 1.9521854e+00 3.3558915e+00 -1.0246352e+00 - 2.0185457e+00 3.5090515e+00 -1.0308979e+00 - 2.0885101e+00 3.6720588e+00 -1.0364670e+00 - 2.1665922e+00 3.8534767e+00 -1.0451971e+00 - 2.2491642e+00 4.0427516e+00 -1.0518395e+00 - 2.3354128e+00 4.2429693e+00 -1.0558403e+00 - 2.4227623e+00 4.4444635e+00 -1.0530024e+00 - 2.5242207e+00 4.6808270e+00 -1.0579791e+00 - 2.6348221e+00 4.9357574e+00 -1.0617253e+00 - 2.7501169e+00 5.2017181e+00 -1.0598370e+00 - 2.8795470e+00 5.5027599e+00 -1.0614685e+00 - 3.0262410e+00 5.8408039e+00 -1.0645312e+00 - 3.1916751e+00 6.2237356e+00 -1.0700239e+00 - 3.3734027e+00 6.6439517e+00 -1.0724502e+00 - 3.5865873e+00 7.1372284e+00 -1.0802766e+00 - 3.8242072e+00 7.6863922e+00 -1.0843024e+00 - 4.0933309e+00 8.3089910e+00 -1.0861376e+00 - 4.4288997e+00 9.0864580e+00 -1.1001275e+00 - 4.7981003e+00 9.9388076e+00 -1.1003970e+00 - 5.2338360e+00 1.0946745e+01 -1.0982391e+00 - 5.8162819e+00 1.2293887e+01 -1.1161221e+00 - 6.5328475e+00 1.3953072e+01 -1.1306014e+00 - 7.5555035e+00 1.6317432e+01 -1.1761481e+00 - 9.1802248e+00 2.0074359e+01 -1.2906999e+00 - 1.4091667e+01 3.1434636e+01 -1.3826839e+00 - 1.4425944e+01 3.2210419e+01 -8.2667974e-01 - 2.0798826e+01 4.6952693e+01 1.2479128e-01 - 2.0791964e+01 4.6941314e+01 1.0176955e+00 - 2.0772119e+01 4.6897564e+01 1.9094732e+00 - 2.0833804e+01 4.7041775e+01 2.8072954e+00 - 1.1980837e+01 2.6564640e+01 2.5269837e+00 - 1.1908262e+01 2.6398999e+01 3.0213015e+00 - 1.1900781e+01 2.6381336e+01 3.5246387e+00 - 1.1895914e+01 2.6373644e+01 4.0299709e+00 - 1.1881416e+01 2.6339356e+01 4.5333704e+00 - 1.1819297e+01 2.6197829e+01 5.0210276e+00 - 1.1812019e+01 2.6183339e+01 5.5279115e+00 - 1.1790617e+01 2.6134366e+01 6.0301757e+00 - 1.1815950e+01 2.6194118e+01 6.5568253e+00 - 1.1863691e+01 2.6308598e+01 7.1018631e+00 - 1.1699844e+01 2.5929588e+01 7.5312757e+00 - 1.1686771e+01 2.5901743e+01 8.0449617e+00 - 1.1792795e+01 2.6148722e+01 8.6425771e+00 - 1.1547135e+01 2.5580521e+01 9.0005269e+00 - 1.2005006e+01 2.6642943e+01 9.8836506e+00 - 1.2028165e+01 2.6697269e+01 1.0459942e+01 - 1.2969228e+01 2.8880437e+01 1.2461750e+01 - 1.2542599e+01 2.7895718e+01 1.2675459e+01 - 1.2540320e+01 2.7892116e+01 1.3286404e+01 - 1.2605941e+01 2.8045950e+01 1.3978974e+01 - 3.4902822e+00 6.9310865e+00 4.6853845e+00 - 4.2193434e+00 8.6220039e+00 5.7887436e+00 - 3.6041827e+00 7.1981538e+00 5.1720248e+00 - 3.5614343e+00 7.0982126e+00 5.2888563e+00 - 3.5856260e+00 7.1555484e+00 5.5031467e+00 - 3.4621212e+00 6.8699241e+00 5.4992753e+00 - 3.4475684e+00 6.8364496e+00 5.6557072e+00 - 3.4905822e+00 6.9377812e+00 5.9102636e+00 - 3.2729877e+00 6.4313126e+00 5.7280327e+00 - 3.0051986e+00 5.8131046e+00 5.4363814e+00 - 2.9682334e+00 5.7269287e+00 5.5344760e+00 - 2.9865867e+00 5.7710891e+00 5.7389393e+00 - 2.9097101e+00 5.5922993e+00 5.7616498e+00 - 2.8644983e+00 5.4866831e+00 5.8420311e+00 - 2.5362803e+00 4.7263539e+00 5.3217724e+00 - 2.4336133e+00 4.4904323e+00 5.2534443e+00 - 2.4389274e+00 4.5033290e+00 5.4184797e+00 - 2.6487673e+00 4.9894329e+00 6.0695399e+00 - 2.1406848e+00 3.8110111e+00 5.1526992e+00 - 2.0153358e+00 3.5207492e+00 4.9725503e+00 - 1.9711880e+00 3.4192085e+00 4.9949527e+00 - 2.0070505e+00 3.5023318e+00 5.2377358e+00 - 2.1926736e+00 3.9337786e+00 5.9301892e+00 - 2.0991748e+00 3.7186874e+00 5.8279365e+00 - 2.0031796e+00 3.4966268e+00 5.7035152e+00 - 1.8809667e+00 3.2109255e+00 5.4776659e+00 - 1.8804973e+00 3.2110852e+00 5.6417633e+00 - 1.7878223e+00 2.9955724e+00 5.4916673e+00 - 1.8357984e+00 3.1080207e+00 5.8346545e+00 - 1.7821546e+00 2.9840618e+00 5.8182721e+00 - 1.7415379e+00 2.8907539e+00 5.8491577e+00 - 1.6322670e+00 2.6381184e+00 5.5979682e+00 - 1.6223542e+00 2.6157645e+00 5.7416078e+00 - 2.8251072e+00 5.4139575e+00 1.1212881e+01 - 1.8836508e+00 3.2237790e+00 7.3339056e+00 - 1.8396156e+00 3.1221067e+00 7.3941605e+00 - 1.9524456e+00 3.3858635e+00 8.2367095e+00 - 1.6754950e+00 2.7423651e+00 7.1223459e+00 - 1.7432092e+00 2.8999409e+00 7.7716660e+00 - 1.5037895e+00 2.3430133e+00 6.7292947e+00 - 1.4620149e+00 2.2469424e+00 6.7637279e+00 - 1.3998553e+00 2.1024235e+00 6.6664112e+00 - 1.2839099e+00 1.8335406e+00 6.2012995e+00 - 1.1915983e+00 1.6185681e+00 5.8405147e+00 - 1.2898461e+00 1.8480998e+00 6.8445389e+00 - 1.3393529e+00 1.9650445e+00 7.5825825e+00 - 1.1856514e+00 1.6064592e+00 6.7198325e+00 - 1.1656658e+00 1.5630511e+00 6.9321562e+00 - 1.0922423e+00 1.3910541e+00 6.6517368e+00 - 8.6576567e-01 8.6114048e-01 4.7559022e+00 - 8.3791272e-01 7.9792717e-01 4.7619958e+00 - 9.7373951e-01 1.1178950e+00 6.7231133e+00 - 9.1445159e-01 9.7891770e-01 6.4784240e+00 - 8.7251158e-01 8.8358800e-01 6.4468403e+00 - 7.3940669e-01 5.6959824e-01 4.9120373e+00 - 7.1139612e-01 5.0460956e-01 4.9023999e+00 - 6.8592238e-01 4.4588218e-01 4.9410981e+00 - 7.8307526e-01 6.7990161e-01 8.0320820e+00 - 7.3668996e-01 5.7191350e-01 8.1036766e+00 - 6.0039373e-01 2.4699086e-01 4.8313889e+00 - 5.7936600e-01 1.9916553e-01 5.1150246e+00 - 5.6225475e-01 1.6428570e-01 6.0675233e+00 - 5.2698877e-01 8.1803558e-02 5.9998209e+00 - 1.2567108e+00 1.6150289e+00 -1.0133659e+00 - 1.2764458e+00 1.6587984e+00 -9.9672349e-01 - 1.3086231e+00 1.7275152e+00 -1.0079212e+00 - 1.3361211e+00 1.7842819e+00 -1.0028812e+00 - 1.3683827e+00 1.8541877e+00 -1.0102333e+00 - 1.3959631e+00 1.9121287e+00 -1.0016473e+00 - 1.4259312e+00 1.9766861e+00 -9.9830853e-01 - 1.4593490e+00 2.0488260e+00 -9.9967038e-01 - 1.4972172e+00 2.1285075e+00 -1.0053365e+00 - 1.5307236e+00 2.2018709e+00 -1.0021536e+00 - 1.5686822e+00 2.2827908e+00 -1.0029753e+00 - 1.6067170e+00 2.3648358e+00 -1.0012498e+00 - 1.6492078e+00 2.4544667e+00 -1.0029298e+00 - 1.6951588e+00 2.5517639e+00 -1.0076124e+00 - 1.7411903e+00 2.6502206e+00 -1.0090487e+00 - 1.7873018e+00 2.7498319e+00 -1.0073384e+00 - 1.8447687e+00 2.8721942e+00 -1.0184349e+00 - 1.8989353e+00 2.9891994e+00 -1.0202356e+00 - 1.9620776e+00 3.1224033e+00 -1.0282974e+00 - 2.0173531e+00 3.2407490e+00 -1.0219609e+00 - 2.0875696e+00 3.3915452e+00 -1.0307340e+00 - 2.1658381e+00 3.5597107e+00 -1.0435174e+00 - 2.2382391e+00 3.7129218e+00 -1.0414094e+00 - 2.3291736e+00 3.9083371e+00 -1.0556152e+00 - 2.4176959e+00 4.0964248e+00 -1.0587313e+00 - 2.5143477e+00 4.3030167e+00 -1.0631109e+00 - 2.6190742e+00 4.5271602e+00 -1.0678053e+00 - 2.7329408e+00 4.7698460e+00 -1.0717686e+00 - 2.8514373e+00 5.0225403e+00 -1.0705473e+00 - 2.9861221e+00 5.3111624e+00 -1.0735009e+00 - 3.1253902e+00 5.6089045e+00 -1.0690230e+00 - 3.2980028e+00 5.9782001e+00 -1.0777922e+00 - 3.4878418e+00 6.3836832e+00 -1.0842476e+00 - 3.6984426e+00 6.8341352e+00 -1.0890445e+00 - 3.9470326e+00 7.3662676e+00 -1.0995067e+00 - 4.2139580e+00 7.9359279e+00 -1.0995180e+00 - 4.5475946e+00 8.6483586e+00 -1.1125906e+00 - 4.8986805e+00 9.3997885e+00 -1.1068691e+00 - 5.3302538e+00 1.0322589e+01 -1.1072942e+00 - 5.8847751e+00 1.1506149e+01 -1.1204400e+00 - 6.5994014e+00 1.3034569e+01 -1.1446769e+00 - 7.5474453e+00 1.5059790e+01 -1.1821452e+00 - 9.4661149e+00 1.9159860e+01 -1.4016444e+00 - 1.4925593e+01 3.0829137e+01 -1.0686065e+00 - 1.4883044e+01 3.0740157e+01 -4.6862040e-01 - 2.1458214e+01 4.4797338e+01 5.8728497e-01 - 1.4172976e+01 2.9228656e+01 1.2940991e+00 - 1.3181664e+01 2.7109739e+01 1.7954224e+00 - 1.3214892e+01 2.7184056e+01 2.3220057e+00 - 1.3198457e+01 2.7149853e+01 2.8449371e+00 - 1.3246465e+01 2.7252764e+01 3.3795303e+00 - 1.3222020e+01 2.7202036e+01 3.9033263e+00 - 1.3210329e+01 2.7179785e+01 4.4303446e+00 - 1.3333366e+01 2.7444441e+01 5.0006506e+00 - 1.2639432e+01 2.5962280e+01 5.2946135e+00 - 1.2664377e+01 2.6015839e+01 5.8172657e+00 - 1.2634153e+01 2.5953451e+01 6.3214476e+00 - 1.2496682e+01 2.5661295e+01 6.7746478e+00 - 1.2687495e+01 2.6071859e+01 7.9210580e+00 - 1.2531481e+01 2.5738973e+01 8.3596612e+00 - 1.2458510e+01 2.5583876e+01 8.8436493e+00 - 1.2446751e+01 2.5560565e+01 9.3694187e+00 - 1.2414297e+01 2.5493846e+01 9.8846414e+00 - 1.3162000e+01 2.7093915e+01 1.1019300e+01 - 1.3001459e+01 2.6751848e+01 1.1469498e+01 - 1.4015383e+01 2.8924802e+01 1.2950718e+01 - 1.3262570e+01 2.7316220e+01 1.2889835e+01 - 1.3332993e+01 2.7467200e+01 1.3571203e+01 - 1.3446416e+01 2.7712919e+01 1.4313913e+01 - 3.8236059e+00 7.1198623e+00 5.0945337e+00 - 3.8565302e+00 7.1888750e+00 5.3121991e+00 - 4.0146888e+00 7.5299125e+00 5.7062080e+00 - 3.8452319e+00 7.1658493e+00 5.6626354e+00 - 3.7153170e+00 6.8899015e+00 5.6640333e+00 - 3.6523109e+00 6.7546918e+00 5.7529929e+00 - 3.7677397e+00 7.0036726e+00 6.1197670e+00 - 3.2658202e+00 5.9279220e+00 5.5001966e+00 - 3.1772841e+00 5.7386927e+00 5.5206905e+00 - 3.1536000e+00 5.6882923e+00 5.6483771e+00 - 3.0882607e+00 5.5494803e+00 5.7023855e+00 - 3.0494921e+00 5.4665147e+00 5.8023353e+00 - 2.6222580e+00 4.5507971e+00 5.1432713e+00 - 2.6485029e+00 4.6094985e+00 5.3471689e+00 - 2.5689667e+00 4.4382073e+00 5.3358844e+00 - 2.5521236e+00 4.4019896e+00 5.4545190e+00 - 2.7078165e+00 4.7366042e+00 6.1401191e+00 - 2.7074649e+00 4.7377049e+00 6.3232930e+00 - 2.2026712e+00 3.6547594e+00 5.2527386e+00 - 2.4730366e+00 4.2364376e+00 6.1041641e+00 - 2.4574491e+00 4.2032471e+00 6.2448690e+00 - 2.5615711e+00 4.4252242e+00 6.7205776e+00 - 2.5670634e+00 4.4379974e+00 6.9438898e+00 - 2.0812766e+00 3.3960975e+00 5.7131985e+00 - 2.0458902e+00 3.3212056e+00 5.7778862e+00 - 2.2307556e+00 3.7194785e+00 6.5486753e+00 - 2.4052264e+00 4.0941253e+00 7.3360129e+00 - 1.8731138e+00 2.9516327e+00 5.7405131e+00 - 1.8586471e+00 2.9209095e+00 5.8716778e+00 - 1.7881795e+00 2.7701696e+00 5.8005510e+00 - 1.6954179e+00 2.5707688e+00 5.6314383e+00 - 1.6693421e+00 2.5162981e+00 5.7146854e+00 - 1.6407879e+00 2.4544867e+00 5.7884977e+00 - 1.6346895e+00 2.4436602e+00 5.9668887e+00 - 1.5898345e+00 2.3476000e+00 5.9776111e+00 - 1.9400465e+00 3.1013725e+00 7.8659447e+00 - 1.5305611e+00 2.2206868e+00 6.1371260e+00 - 1.8357644e+00 2.8792339e+00 7.9720627e+00 - 1.5538256e+00 2.2737937e+00 6.7697464e+00 - 1.4983978e+00 2.1542311e+00 6.7387404e+00 - 1.4312398e+00 2.0104694e+00 6.6304036e+00 - 1.3227847e+00 1.7782778e+00 6.2466383e+00 - 1.2601105e+00 1.6433571e+00 6.1198155e+00 - 1.3299581e+00 1.7952023e+00 6.9187893e+00 - 1.2898981e+00 1.7094379e+00 6.9810385e+00 - 1.2972687e+00 1.7250581e+00 7.4253715e+00 - 1.1788611e+00 1.4709256e+00 6.8504128e+00 - 9.0503744e-01 8.8090940e-01 4.7573880e+00 - 8.7612961e-01 8.1730329e-01 4.7542961e+00 - 8.6427004e-01 7.9340301e-01 4.9451821e+00 - 9.9718442e-01 1.0836936e+00 6.8707358e+00 - 9.3408038e-01 9.4740041e-01 6.6350490e+00 - 8.8057767e-01 8.3282054e-01 6.4846383e+00 - 7.4213017e-01 5.3157922e-01 4.9173001e+00 - 7.1236331e-01 4.6966113e-01 4.9269461e+00 - 6.8731396e-01 4.1535655e-01 5.0147843e+00 - 7.0580524e-01 4.5791221e-01 6.2365806e+00 - 6.1967220e-01 2.7030791e-01 4.7790567e+00 - 6.2486987e-01 2.8554054e-01 6.1211295e+00 - 5.8525692e-01 1.9995318e-01 6.0058482e+00 - 5.4892863e-01 1.2350860e-01 6.1188778e+00 - 5.1066383e-01 4.1173318e-02 6.0504858e+00 - 1.2920509e+00 1.5703720e+00 -1.0212935e+00 - 1.3137792e+00 1.6139959e+00 -1.0051568e+00 - 1.3421395e+00 1.6685851e+00 -1.0025178e+00 - 1.3763193e+00 1.7372302e+00 -1.0127231e+00 - 1.4048210e+00 1.7939808e+00 -1.0067874e+00 - 1.4332730e+00 1.8498182e+00 -9.9910434e-01 - 1.4652312e+00 1.9142055e+00 -9.9677067e-01 - 1.5048935e+00 1.9906028e+00 -1.0057902e+00 - 1.5403150e+00 2.0626809e+00 -1.0059599e+00 - 1.5733096e+00 2.1273131e+00 -9.9743706e-01 - 1.6131957e+00 2.2070462e+00 -9.9961389e-01 - 1.6540960e+00 2.2868469e+00 -9.9919710e-01 - 1.6975155e+00 2.3753465e+00 -1.0023288e+00 - 1.7429491e+00 2.4638682e+00 -1.0025704e+00 - 1.7918436e+00 2.5600610e+00 -1.0057149e+00 - 1.8408789e+00 2.6584102e+00 -1.0056626e+00 - 1.8943173e+00 2.7634077e+00 -1.0077676e+00 - 1.9547898e+00 2.8856773e+00 -1.0170758e+00 - 2.0172852e+00 3.0080378e+00 -1.0220956e+00 - 2.0833753e+00 3.1401717e+00 -1.0279202e+00 - 2.1504914e+00 3.2724669e+00 -1.0292534e+00 - 2.2256551e+00 3.4220969e+00 -1.0352961e+00 - 2.3098697e+00 3.5890406e+00 -1.0452525e+00 - 2.3941212e+00 3.7562800e+00 -1.0492162e+00 - 2.4839793e+00 3.9332951e+00 -1.0514941e+00 - 2.5854172e+00 4.1364017e+00 -1.0596361e+00 - 2.6924119e+00 4.3483709e+00 -1.0643447e+00 - 2.8085436e+00 4.5788577e+00 -1.0688216e+00 - 2.9303009e+00 4.8192729e+00 -1.0685165e+00 - 3.0636050e+00 5.0849994e+00 -1.0696314e+00 - 3.2116402e+00 5.3789209e+00 -1.0708263e+00 - 3.3857952e+00 5.7240540e+00 -1.0795145e+00 - 3.5701874e+00 6.0889764e+00 -1.0812321e+00 - 3.7853097e+00 6.5149614e+00 -1.0884545e+00 - 4.0267825e+00 6.9955481e+00 -1.0952288e+00 - 4.3000862e+00 7.5384740e+00 -1.1006690e+00 - 4.6017177e+00 8.1352137e+00 -1.0989262e+00 - 4.9695445e+00 8.8659582e+00 -1.1056040e+00 - 5.3829219e+00 9.6866745e+00 -1.1033843e+00 - 5.8997925e+00 1.0711364e+01 -1.1095622e+00 - 6.5919199e+00 1.2083501e+01 -1.1370648e+00 - 7.4140191e+00 1.3715237e+01 -1.1517426e+00 - 8.5821707e+00 1.6033724e+01 -1.1967256e+00 - 1.0434243e+01 1.9706770e+01 -1.3099449e+00 - 1.5290799e+01 2.9343956e+01 -1.2838528e+00 - 1.5306501e+01 2.9374541e+01 -7.0994851e-01 - 1.8114724e+01 3.4948231e+01 -3.5021895e-01 - 2.1803717e+01 4.2268322e+01 1.9356707e-01 - 1.5239066e+01 2.9245622e+01 1.0138448e+00 - 1.4484017e+01 2.7750382e+01 1.5556346e+00 - 1.4513335e+01 2.7808800e+01 2.1006480e+00 - 1.4214647e+01 2.7217231e+01 2.6101629e+00 - 1.4697505e+01 2.8177282e+01 3.2197387e+00 - 1.4704201e+01 2.8192450e+01 3.7752353e+00 - 1.3140367e+01 2.5089569e+01 3.9648812e+00 - 1.4931866e+01 2.8647452e+01 4.9523668e+00 - 1.4733353e+01 2.8254356e+01 5.4598834e+00 - 1.3678348e+01 2.6164122e+01 6.1783542e+00 - 1.3706523e+01 2.6220409e+01 6.7194748e+00 - 1.2998999e+01 2.4816604e+01 6.9185441e+00 - 1.2971382e+01 2.4764648e+01 7.4137849e+00 - 1.2595648e+01 2.4020053e+01 7.7174601e+00 - 1.2631786e+01 2.4093000e+01 8.2401881e+00 - 1.2616494e+01 2.4062470e+01 8.7374999e+00 - 1.2617390e+01 2.4066844e+01 9.2504115e+00 - 1.2674199e+01 2.4181455e+01 9.8091038e+00 - 1.4022592e+01 2.6860704e+01 1.1368915e+01 - 1.4491987e+01 2.7794434e+01 1.2340717e+01 - 1.4325228e+01 2.7464094e+01 1.2817509e+01 - 1.3808859e+01 2.6439802e+01 1.2973549e+01 - 1.4059238e+01 2.6940031e+01 1.3816800e+01 - 1.4642204e+01 2.8099127e+01 1.5021086e+01 - 1.4626483e+01 2.8070115e+01 1.5669512e+01 - 4.1311869e+00 7.2179770e+00 5.1215368e+00 - 4.0701404e+00 7.0976101e+00 5.2289759e+00 - 3.6669742e+00 6.2966900e+00 4.9109284e+00 - 3.5612386e+00 6.0877776e+00 4.9383066e+00 - 3.5985389e+00 6.1632218e+00 5.1494201e+00 - 3.6310519e+00 6.2258538e+00 5.3592928e+00 - 3.5848403e+00 6.1355426e+00 5.4638560e+00 - 3.5523658e+00 6.0724880e+00 5.5886167e+00 - 3.7442601e+00 6.4535659e+00 6.0623432e+00 - 3.4459179e+00 5.8602469e+00 5.7701534e+00 - 3.3390109e+00 5.6500106e+00 5.7694694e+00 - 3.2410319e+00 5.4545603e+00 5.7744089e+00 - 2.8852239e+00 4.7486870e+00 5.3072028e+00 - 2.8513075e+00 4.6800842e+00 5.3993053e+00 - 2.6775410e+00 4.3346600e+00 5.2209748e+00 - 2.6907679e+00 4.3617511e+00 5.3986778e+00 - 2.9415495e+00 4.8607689e+00 6.0767827e+00 - 2.8332077e+00 4.6460717e+00 6.0249643e+00 - 2.8086924e+00 4.5986142e+00 6.1503082e+00 - 2.8184830e+00 4.6171981e+00 6.3544841e+00 - 2.7997634e+00 4.5815429e+00 6.5023385e+00 - 2.6418734e+00 4.2674921e+00 6.3085453e+00 - 2.5701945e+00 4.1257253e+00 6.3155804e+00 - 2.7192191e+00 4.4216650e+00 6.9011036e+00 - 2.6268679e+00 4.2387384e+00 6.8621372e+00 - 2.0946726e+00 3.1788761e+00 5.5567248e+00 - 2.4362146e+00 3.8598414e+00 6.7365250e+00 - 2.4911767e+00 3.9697952e+00 7.1185402e+00 - 2.4863077e+00 3.9607557e+00 7.3343818e+00 - 1.9718668e+00 2.9373893e+00 5.8766740e+00 - 1.8755653e+00 2.7444271e+00 5.7318959e+00 - 1.7978042e+00 2.5901144e+00 5.6405652e+00 - 1.7374155e+00 2.4716095e+00 5.6046316e+00 - 1.7461290e+00 2.4880759e+00 5.8254390e+00 - 1.6948877e+00 2.3866251e+00 5.8208474e+00 - 1.6759686e+00 2.3488596e+00 5.9461793e+00 - 1.6364073e+00 2.2722370e+00 5.9911536e+00 - 1.6209471e+00 2.2405804e+00 6.1426955e+00 - 1.5917216e+00 2.1829880e+00 6.2400332e+00 - 1.5428400e+00 2.0868987e+00 6.2452751e+00 - 1.9121465e+00 2.8250839e+00 8.4486474e+00 - 1.5018291e+00 2.0054831e+00 6.5553214e+00 - 1.3901101e+00 1.7839988e+00 6.2013856e+00 - 1.3923371e+00 1.7886012e+00 6.4985116e+00 - 1.3527626e+00 1.7108420e+00 6.5609636e+00 - 1.3305514e+00 1.6657220e+00 6.7361395e+00 - 1.2746450e+00 1.5555291e+00 6.6912578e+00 - 1.2304493e+00 1.4688635e+00 6.7303482e+00 - 9.5549295e-01 9.1638442e-01 4.8261139e+00 - 9.1540262e-01 8.3708207e-01 4.7559816e+00 - 8.8703428e-01 7.8088151e-01 4.7814567e+00 - 9.7032633e-01 9.5072560e-01 5.9992775e+00 - 9.2221689e-01 8.5534826e-01 5.9188739e+00 - 9.3140786e-01 8.7489981e-01 6.5454268e+00 - 7.7864300e-01 5.6763766e-01 5.0010017e+00 - 7.4185730e-01 4.9372677e-01 4.9222728e+00 - 7.1232987e-01 4.3475346e-01 4.9510959e+00 - 6.8534337e-01 3.8104274e-01 5.0485286e+00 - 6.7897970e-01 3.7179273e-01 5.7426797e+00 - 6.5683723e-01 3.2803885e-01 6.2279704e+00 - 6.0925910e-01 2.3402766e-01 5.9738820e+00 - 5.7199492e-01 1.5968846e-01 6.0675899e+00 - 5.3173442e-01 7.9026335e-02 5.9698916e+00 - 1.3533674e+00 1.5737174e+00 -1.0207356e+00 - 1.3726644e+00 1.6098611e+00 -9.9660554e-01 - 1.4054007e+00 1.6708817e+00 -1.0005185e+00 - 1.4425197e+00 1.7383879e+00 -1.0098848e+00 - 1.4729625e+00 1.7940601e+00 -1.0031069e+00 - 1.5024175e+00 1.8498764e+00 -9.9462797e-01 - 1.5440681e+00 1.9260888e+00 -1.0049523e+00 - 1.5779816e+00 1.9895109e+00 -9.9947924e-01 - 1.6162827e+00 2.0594580e+00 -9.9866048e-01 - 1.6590957e+00 2.1379537e+00 -1.0019958e+00 - 1.7008663e+00 2.2156409e+00 -1.0026816e+00 - 1.7437703e+00 2.2953799e+00 -1.0010727e+00 - 1.7911308e+00 2.3827097e+00 -1.0027693e+00 - 1.8428902e+00 2.4766534e+00 -1.0073223e+00 - 1.8903473e+00 2.5652709e+00 -1.0031758e+00 - 1.9422659e+00 2.6615188e+00 -1.0015357e+00 - 2.0075958e+00 2.7813887e+00 -1.0128581e+00 - 2.0729517e+00 2.9014656e+00 -1.0199857e+00 - 2.1339482e+00 3.0152441e+00 -1.0178647e+00 - 2.2049211e+00 3.1451804e+00 -1.0216085e+00 - 2.2883871e+00 3.2999538e+00 -1.0351651e+00 - 2.3728857e+00 3.4549426e+00 -1.0431317e+00 - 2.4575394e+00 3.6122013e+00 -1.0456044e+00 - 2.5477370e+00 3.7782189e+00 -1.0467411e+00 - 2.6459368e+00 3.9606927e+00 -1.0501408e+00 - 2.7587146e+00 4.1691063e+00 -1.0588147e+00 - 2.8771119e+00 4.3873990e+00 -1.0637054e+00 - 3.0000741e+00 4.6146639e+00 -1.0641608e+00 - 3.1331185e+00 4.8594482e+00 -1.0631396e+00 - 3.2842867e+00 5.1390374e+00 -1.0663502e+00 - 3.4545891e+00 5.4534697e+00 -1.0717981e+00 - 3.6440995e+00 5.8038502e+00 -1.0773356e+00 - 3.8572290e+00 6.1968914e+00 -1.0838217e+00 - 4.0895950e+00 6.6261076e+00 -1.0858031e+00 - 4.3647566e+00 7.1336814e+00 -1.0939163e+00 - 4.6601879e+00 7.6776507e+00 -1.0918350e+00 - 5.0110968e+00 8.3273554e+00 -1.0947112e+00 - 5.4013581e+00 9.0473706e+00 -1.0881824e+00 - 5.9099993e+00 9.9860547e+00 -1.0991783e+00 - 6.5179935e+00 1.1109422e+01 -1.1080830e+00 - 7.2702168e+00 1.2496898e+01 -1.1171891e+00 - 8.4722810e+00 1.4715397e+01 -1.1952960e+00 - 1.5301235e+01 2.7323871e+01 -1.4312748e+00 - 1.4382131e+01 2.5627857e+01 -7.6923367e-01 - 1.4355861e+01 2.5580686e+01 -2.5681567e-01 - 1.4628926e+01 2.6088569e+01 1.2725651e+00 - 1.4390557e+01 2.5649595e+01 1.7772843e+00 - 1.4428634e+01 2.5721958e+01 2.2906176e+00 - 1.4424924e+01 2.5716511e+01 2.8021397e+00 - 1.3714588e+01 2.4404858e+01 3.1970278e+00 - 1.3759463e+01 2.4491069e+01 3.6945173e+00 - 1.3744295e+01 2.4463076e+01 4.1824918e+00 - 1.3814945e+01 2.4593612e+01 4.6949572e+00 - 1.3758135e+01 2.4490509e+01 5.1750792e+00 - 1.3796142e+01 2.4561801e+01 5.6869639e+00 - 1.3795859e+01 2.4563753e+01 6.1900900e+00 - 1.3694867e+01 2.4377193e+01 6.6527747e+00 - 1.3589484e+01 2.4184592e+01 7.1096769e+00 - 1.3619592e+01 2.4240769e+01 7.6307662e+00 - 1.3234986e+01 2.3531733e+01 7.9327422e+00 - 1.3303512e+01 2.3658794e+01 8.4736269e+00 - 1.3284042e+01 2.3625480e+01 8.9704009e+00 - 1.3315348e+01 2.3684222e+01 9.5041722e+00 - 1.3292381e+01 2.3642432e+01 1.0007794e+01 - 1.3434641e+01 2.3906965e+01 1.0639363e+01 - 1.4880269e+01 2.6581076e+01 1.2314871e+01 - 1.4703786e+01 2.6256490e+01 1.2774517e+01 - 1.4651712e+01 2.6161149e+01 1.3335828e+01 - 1.4685761e+01 2.6226255e+01 1.3980806e+01 - 1.4531890e+01 2.5943288e+01 1.4457683e+01 - 4.3148723e+00 7.0570432e+00 4.8312751e+00 - 4.2951252e+00 7.0206978e+00 4.9841761e+00 - 4.4180345e+00 7.2473251e+00 5.2937348e+00 - 3.8466635e+00 6.1913258e+00 4.8257065e+00 - 3.7430840e+00 6.0008893e+00 4.8641748e+00 - 3.7889380e+00 6.0850344e+00 5.0791116e+00 - 3.7056818e+00 5.9314219e+00 5.1364637e+00 - 3.6269062e+00 5.7855926e+00 5.1944054e+00 - 3.6979237e+00 5.9187643e+00 5.4576313e+00 - 3.6917248e+00 5.9071347e+00 5.6197424e+00 - 3.6220377e+00 5.7784055e+00 5.6897004e+00 - 3.4945146e+00 5.5432312e+00 5.6667447e+00 - 3.3113544e+00 5.2051731e+00 5.5444784e+00 - 3.2394051e+00 5.0734082e+00 5.5909710e+00 - 3.0617201e+00 4.7440764e+00 5.4491168e+00 - 2.9556003e+00 4.5483823e+00 5.4190753e+00 - 2.9505013e+00 4.5390525e+00 5.5682504e+00 - 3.0590715e+00 4.7406184e+00 5.9414107e+00 - 3.0586146e+00 4.7403625e+00 6.1173431e+00 - 2.9955878e+00 4.6233393e+00 6.1685603e+00 - 2.9883756e+00 4.6111329e+00 6.3380151e+00 - 2.7706987e+00 4.2084431e+00 6.0439339e+00 - 2.6131497e+00 3.9159849e+00 5.8611884e+00 - 2.7515671e+00 4.1734059e+00 6.3651743e+00 - 2.8172570e+00 4.2964532e+00 6.7209459e+00 - 2.2986417e+00 3.3352692e+00 5.6011170e+00 - 2.2274576e+00 3.2031289e+00 5.5804406e+00 - 2.1517353e+00 3.0632615e+00 5.5400485e+00 - 2.0818042e+00 2.9356760e+00 5.5116304e+00 - 2.1165593e+00 2.9991196e+00 5.7809225e+00 - 2.0408479e+00 2.8598550e+00 5.7324908e+00 - 1.9912568e+00 2.7676791e+00 5.7550656e+00 - 1.9280823e+00 2.6520541e+00 5.7333248e+00 - 1.8088348e+00 2.4316094e+00 5.5122480e+00 - 1.8105538e+00 2.4336995e+00 5.6976632e+00 - 1.7941726e+00 2.4042665e+00 5.8322803e+00 - 1.7400499e+00 2.3049319e+00 5.8264007e+00 - 1.7236571e+00 2.2748912e+00 5.9689576e+00 - 1.6695128e+00 2.1753841e+00 5.9595823e+00 - 1.6634006e+00 2.1634160e+00 6.1553511e+00 - 1.6001193e+00 2.0474528e+00 6.1064941e+00 - 1.5344669e+00 1.9265535e+00 6.0361685e+00 - 1.4870955e+00 1.8386208e+00 6.0459048e+00 - 1.4627217e+00 1.7933247e+00 6.1745454e+00 - 1.4223964e+00 1.7201821e+00 6.2280635e+00 - 1.4014855e+00 1.6805104e+00 6.3933508e+00 - 1.3785151e+00 1.6394239e+00 6.5680321e+00 - 1.3405255e+00 1.5699033e+00 6.6569010e+00 - 1.3313883e+00 1.5522000e+00 6.9555980e+00 - 1.2528561e+00 1.4069833e+00 6.7638000e+00 - 9.5778891e-01 8.5814449e-01 4.7670963e+00 - 9.2513011e-01 7.9825879e-01 4.7737562e+00 - 1.0176383e+00 9.7199673e-01 5.9802143e+00 - 9.7001801e-01 8.8310682e-01 5.9300254e+00 - 9.7430568e-01 8.9252873e-01 6.4678982e+00 - 9.2685574e-01 8.0448445e-01 6.4551127e+00 - 7.7470976e-01 5.2155103e-01 4.9569422e+00 - 7.4070568e-01 4.5740470e-01 4.9367873e+00 - 7.1048239e-01 4.0193912e-01 4.9949780e+00 - 7.0865806e-01 4.0042612e-01 5.7090446e+00 - 6.7165265e-01 3.3176495e-01 5.7760381e+00 - 6.4788437e-01 2.8954561e-01 6.3507735e+00 - 5.9985658e-01 2.0049379e-01 6.1757411e+00 - 5.5685742e-01 1.2051028e-01 6.1489137e+00 - 5.1353441e-01 4.0001695e-02 6.0304011e+00 - 1.4111924e+00 1.5686312e+00 -1.0124313e+00 - 1.4391749e+00 1.6165915e+00 -1.0023543e+00 - 1.4738523e+00 1.6765337e+00 -1.0054251e+00 - 1.5086015e+00 1.7375664e+00 -1.0066477e+00 - 1.5443607e+00 1.7986323e+00 -1.0059759e+00 - 1.5801315e+00 1.8597918e+00 -1.0034064e+00 - 1.6159743e+00 1.9220419e+00 -9.9898886e-01 - 1.6562650e+00 1.9918139e+00 -9.9927509e-01 - 1.6965090e+00 2.0606974e+00 -9.9731449e-01 - 1.7412655e+00 2.1381343e+00 -9.9940812e-01 - 1.7826565e+00 2.2091779e+00 -9.9295547e-01 - 1.8318229e+00 2.2933172e+00 -9.9610780e-01 - 1.8889495e+00 2.3935776e+00 -1.0083146e+00 - 1.9392721e+00 2.4799508e+00 -1.0054767e+00 - 1.9906703e+00 2.5673986e+00 -9.9989505e-01 - 2.0544190e+00 2.6775122e+00 -1.0076226e+00 - 2.1226353e+00 2.7953054e+00 -1.0168579e+00 - 2.1909384e+00 2.9143074e+00 -1.0218481e+00 - 2.2613239e+00 3.0343924e+00 -1.0226994e+00 - 2.3396317e+00 3.1697789e+00 -1.0289600e+00 - 2.4279847e+00 3.3223892e+00 -1.0397367e+00 - 2.5174307e+00 3.4762118e+00 -1.0449730e+00 - 2.6024614e+00 3.6227736e+00 -1.0402121e+00 - 2.7109592e+00 3.8102650e+00 -1.0512318e+00 - 2.8205585e+00 3.9990377e+00 -1.0553129e+00 - 2.9357128e+00 4.1966582e+00 -1.0562602e+00 - 3.0643954e+00 4.4193509e+00 -1.0610309e+00 - 3.1997018e+00 4.6519115e+00 -1.0610228e+00 - 3.3540656e+00 4.9181852e+00 -1.0658991e+00 - 3.5185252e+00 5.2020867e+00 -1.0671015e+00 - 3.7085774e+00 5.5283455e+00 -1.0729544e+00 - 3.9223035e+00 5.8982176e+00 -1.0807042e+00 - 4.1671722e+00 6.3192554e+00 -1.0907697e+00 - 4.4177234e+00 6.7506749e+00 -1.0868645e+00 - 4.7130734e+00 7.2603853e+00 -1.0879988e+00 - 5.0631759e+00 7.8638482e+00 -1.0938956e+00 - 5.4335213e+00 8.5029755e+00 -1.0841549e+00 - 5.8999313e+00 9.3062681e+00 -1.0855082e+00 - 6.4805145e+00 1.0307894e+01 -1.0948465e+00 - 7.2320776e+00 1.1602461e+01 -1.1173877e+00 - 8.1783726e+00 1.3234209e+01 -1.1423445e+00 - 1.6103692e+01 2.6895741e+01 -1.1588933e+00 - 1.6055328e+01 2.6812636e+01 -6.0922284e-01 - 1.7384887e+01 2.9106892e+01 -1.5849578e-01 - 1.5923815e+01 2.6590366e+01 1.0151421e+00 - 1.5534280e+01 2.5920680e+01 1.5377819e+00 - 1.5606724e+01 2.6046893e+01 2.0663691e+00 - 1.5294176e+01 2.5508536e+01 2.5600283e+00 - 1.4642442e+01 2.4385434e+01 2.9853031e+00 - 1.4686928e+01 2.4464922e+01 3.4883332e+00 - 1.4687615e+01 2.4466583e+01 3.9867619e+00 - 1.4708490e+01 2.4503479e+01 4.4921387e+00 - 1.4785325e+01 2.4636247e+01 5.0166708e+00 - 1.4677539e+01 2.4452685e+01 5.4910641e+00 - 1.4699595e+01 2.4492008e+01 6.0063263e+00 - 1.4593962e+01 2.4311123e+01 6.4766694e+00 - 1.4504015e+01 2.4157504e+01 6.9495756e+00 - 1.4542824e+01 2.4224594e+01 7.4787838e+00 - 1.4678109e+01 2.4459129e+01 8.0634158e+00 - 1.4816793e+01 2.4699301e+01 8.6646698e+00 - 1.4149565e+01 2.3549647e+01 8.8194146e+00 - 1.4198558e+01 2.3635064e+01 9.3664790e+00 - 1.4227444e+01 2.3686414e+01 9.9100415e+00 - 1.5260120e+01 2.5470230e+01 1.1152624e+01 - 1.5385615e+01 2.5687520e+01 1.1822371e+01 - 1.5161272e+01 2.5302647e+01 1.2241933e+01 - 1.5673936e+01 2.6188207e+01 1.3245681e+01 - 5.5511089e+00 8.7200845e+00 5.2837780e+00 - 5.4486273e+00 8.5435787e+00 5.4020516e+00 - 5.0408356e+00 7.8405184e+00 5.2309927e+00 - 5.2144750e+00 8.1410021e+00 5.5947668e+00 - 5.0444862e+00 7.8469125e+00 5.6264429e+00 - 3.9323044e+00 5.9275081e+00 4.6469556e+00 - 3.9037264e+00 5.8792166e+00 4.7707637e+00 - 3.9088463e+00 5.8890141e+00 4.9337504e+00 - 3.8273399e+00 5.7475362e+00 4.9951990e+00 - 3.9864618e+00 6.0235961e+00 5.3544603e+00 - 3.8555776e+00 5.7978363e+00 5.3553910e+00 - 3.8000136e+00 5.7025425e+00 5.4492442e+00 - 3.7938030e+00 5.6908193e+00 5.6094576e+00 - 3.8091416e+00 5.7187108e+00 5.8058311e+00 - 3.2067932e+00 4.6777214e+00 5.0774331e+00 - 3.3357138e+00 4.9021019e+00 5.4298183e+00 - 3.2619795e+00 4.7742092e+00 5.4713250e+00 - 3.1838258e+00 4.6400544e+00 5.5025548e+00 - 3.1135026e+00 4.5189197e+00 5.5429061e+00 - 3.0363598e+00 4.3853220e+00 5.5663927e+00 - 3.1057117e+00 4.5060009e+00 5.8587802e+00 - 2.6410625e+00 3.7037138e+00 5.1357797e+00 - 2.8873115e+00 4.1298934e+00 5.7757541e+00 - 2.9047597e+00 4.1590847e+00 5.9806611e+00 - 2.7960301e+00 3.9712882e+00 5.9247147e+00 - 2.8057843e+00 3.9895814e+00 6.1229978e+00 - 2.7106235e+00 3.8261491e+00 6.0893949e+00 - 2.6502982e+00 3.7213447e+00 6.1273771e+00 - 2.2897393e+00 3.0983189e+00 5.4242276e+00 - 2.2756572e+00 3.0742788e+00 5.5490528e+00 - 2.2322754e+00 3.0003058e+00 5.6023304e+00 - 2.1684484e+00 2.8895665e+00 5.5973736e+00 - 2.0900411e+00 2.7554483e+00 5.5483041e+00 - 2.0532544e+00 2.6905976e+00 5.6115039e+00 - 2.0425986e+00 2.6724053e+00 5.7572457e+00 - 1.8972899e+00 2.4216324e+00 5.4795539e+00 - 1.8424272e+00 2.3264839e+00 5.4762758e+00 - 1.9349937e+00 2.4884390e+00 5.9815492e+00 - 1.8496212e+00 2.3412093e+00 5.8822067e+00 - 1.8026699e+00 2.2592122e+00 5.9109714e+00 - 1.7615290e+00 2.1891357e+00 5.9646437e+00 - 1.7192608e+00 2.1170568e+00 6.0170200e+00 - 1.6802761e+00 2.0491686e+00 6.0769790e+00 - 1.6538696e+00 2.0037027e+00 6.1997332e+00 - 1.6058697e+00 1.9208479e+00 6.2301487e+00 - 1.5670378e+00 1.8546957e+00 6.3050396e+00 - 1.5522079e+00 1.8306548e+00 6.5096678e+00 - 1.4768160e+00 1.7001315e+00 6.3953222e+00 - 1.4344847e+00 1.6265169e+00 6.4570861e+00 - 1.4506693e+00 1.6560117e+00 6.8885654e+00 - 1.3614594e+00 1.5011953e+00 6.6722760e+00 - 1.2595619e+00 1.3251460e+00 6.3362633e+00 - 9.9987082e-01 8.7471164e-01 4.7681219e+00 - 9.6621817e-01 8.1492088e-01 4.7754842e+00 - 1.0691812e+00 9.9596099e-01 5.9801158e+00 - 1.0198734e+00 9.1120760e-01 5.9505589e+00 - 9.7279199e-01 8.2971831e-01 5.9288371e+00 - 9.5601902e-01 8.0106586e-01 6.2401361e+00 - 9.0680560e-01 7.1706626e-01 6.2258604e+00 - 7.7119927e-01 4.8090561e-01 4.9421481e+00 - 7.3761814e-01 4.2168634e-01 4.9610961e+00 - 7.0669776e-01 3.6971866e-01 5.0484548e+00 - 7.0033470e-01 3.6047357e-01 5.7427058e+00 - 6.7637942e-01 3.1882290e-01 6.2479286e+00 - 6.3058696e-01 2.4011272e-01 6.2635080e+00 - 5.8036496e-01 1.5269498e-01 5.9975965e+00 - 5.3560603e-01 7.6785699e-02 5.9698781e+00 - 1.5431847e+00 1.6801560e+00 -1.0097363e+00 - 1.5765009e+00 1.7336480e+00 -1.0029687e+00 - 1.6175770e+00 1.8001125e+00 -1.0083031e+00 - 1.6553504e+00 1.8612004e+00 -1.0047412e+00 - 1.6975108e+00 1.9288083e+00 -1.0059335e+00 - 1.7396848e+00 1.9965247e+00 -1.0049285e+00 - 1.7819325e+00 2.0653464e+00 -1.0017757e+00 - 1.8296307e+00 2.1416641e+00 -1.0026308e+00 - 1.8773449e+00 2.2181099e+00 -1.0008891e+00 - 1.9295150e+00 2.3021418e+00 -1.0025528e+00 - 1.9817632e+00 2.3873135e+00 -1.0013696e+00 - 2.0394089e+00 2.4790434e+00 -1.0029463e+00 - 2.1015776e+00 2.5794104e+00 -1.0068792e+00 - 2.1726557e+00 2.6949298e+00 -1.0180225e+00 - 2.2448180e+00 2.8115927e+00 -1.0250237e+00 - 2.3136198e+00 2.9219016e+00 -1.0226796e+00 - 2.3957850e+00 3.0549342e+00 -1.0312509e+00 - 2.4745916e+00 3.1816276e+00 -1.0301773e+00 - 2.5722796e+00 3.3395967e+00 -1.0428780e+00 - 2.6666125e+00 3.4912562e+00 -1.0453344e+00 - 2.7753902e+00 3.6667581e+00 -1.0550636e+00 - 2.8852681e+00 3.8435316e+00 -1.0580538e+00 - 3.0096626e+00 4.0452380e+00 -1.0664687e+00 - 3.1306499e+00 4.2397020e+00 -1.0632914e+00 - 3.2771302e+00 4.4752111e+00 -1.0711070e+00 - 3.4292411e+00 4.7206880e+00 -1.0733416e+00 - 3.6023523e+00 4.9988143e+00 -1.0793187e+00 - 3.7855635e+00 5.2946028e+00 -1.0809230e+00 - 3.9998923e+00 5.6413551e+00 -1.0889378e+00 - 4.2317974e+00 6.0133812e+00 -1.0917998e+00 - 4.4838731e+00 6.4204954e+00 -1.0907100e+00 - 4.7880746e+00 6.9112866e+00 -1.0984750e+00 - 5.1354482e+00 7.4697338e+00 -1.1052382e+00 - 5.5085746e+00 8.0723334e+00 -1.1005212e+00 - 5.9514762e+00 8.7849845e+00 -1.0974584e+00 - 6.5133286e+00 9.6924143e+00 -1.1075415e+00 - 7.2082516e+00 1.0812260e+01 -1.1220155e+00 - 8.0974107e+00 1.2244910e+01 -1.1456093e+00 - 9.2918934e+00 1.4170828e+01 -1.1863085e+00 - 1.1296415e+01 1.7401228e+01 -1.3220875e+00 - 1.6367734e+01 2.5575211e+01 -1.3528014e+00 - 1.7186481e+01 2.6896415e+01 -9.1920657e-01 - 1.7168613e+01 2.6869925e+01 -3.6390642e-01 - 1.6445428e+01 2.5705216e+01 7.5191054e-01 - 1.6301931e+01 2.5475198e+01 1.2774758e+00 - 1.6243918e+01 2.5383199e+01 1.7979079e+00 - 1.6096966e+01 2.5146583e+01 2.3076000e+00 - 1.6107854e+01 2.5166718e+01 2.8268814e+00 - 1.6193086e+01 2.5305388e+01 3.3592806e+00 - 1.6414972e+01 2.5664093e+01 3.9238366e+00 - 1.5976939e+01 2.4959020e+01 4.3617143e+00 - 1.5859910e+01 2.4770828e+01 4.8528132e+00 - 1.5905148e+01 2.4844676e+01 5.3845519e+00 - 1.5934843e+01 2.4893435e+01 5.9173237e+00 - 1.5167212e+01 2.3658623e+01 6.6786312e+00 - 1.5241294e+01 2.3778244e+01 7.2178461e+00 - 1.5237654e+01 2.3773872e+01 7.7309168e+00 - 1.5255065e+01 2.3802035e+01 8.2581722e+00 - 1.5205869e+01 2.3724454e+01 8.7565124e+00 - 1.5504889e+01 2.4208431e+01 9.4529837e+00 - 1.5504677e+01 2.4209403e+01 9.9970081e+00 - 1.5899444e+01 2.4846248e+01 1.0797786e+01 - 1.6511471e+01 2.5835127e+01 1.1781106e+01 - 1.6762072e+01 2.6243608e+01 1.3180262e+01 - 1.6657442e+01 2.6075382e+01 1.3724867e+01 - 1.6387030e+01 2.5641642e+01 1.4134509e+01 - 5.2906185e+00 7.7342436e+00 5.1520913e+00 - 5.3324903e+00 7.8013934e+00 5.3835103e+00 - 5.4034982e+00 7.9176845e+00 5.6501720e+00 - 4.1785283e+00 5.9405091e+00 4.6426918e+00 - 4.0933169e+00 5.8036353e+00 4.7115454e+00 - 4.0493393e+00 5.7334541e+00 4.8202082e+00 - 3.9640209e+00 5.5952088e+00 4.8815208e+00 - 4.0259649e+00 5.6961442e+00 5.1107489e+00 - 4.0142679e+00 5.6771534e+00 5.2593399e+00 - 4.0583731e+00 5.7486546e+00 5.4801176e+00 - 4.0076641e+00 5.6667150e+00 5.5861980e+00 - 3.9692405e+00 5.6048574e+00 5.7076322e+00 - 3.5146367e+00 4.8720567e+00 5.2445669e+00 - 3.2751698e+00 4.4847306e+00 5.0514877e+00 - 3.2735992e+00 4.4841280e+00 5.1989089e+00 - 3.3120564e+00 4.5455234e+00 5.4113090e+00 - 3.3192804e+00 4.5565763e+00 5.5819303e+00 - 2.9491069e+00 3.9603826e+00 5.1244211e+00 - 3.2099073e+00 4.3807432e+00 5.7255446e+00 - 2.8294760e+00 3.7671733e+00 5.2086815e+00 - 2.7830968e+00 3.6928429e+00 5.2713067e+00 - 2.7142395e+00 3.5805433e+00 5.2893863e+00 - 2.9564275e+00 3.9728093e+00 5.9282552e+00 - 2.8575389e+00 3.8137988e+00 5.8983620e+00 - 2.7944133e+00 3.7122750e+00 5.9384024e+00 - 2.5466037e+00 3.3124766e+00 5.5649666e+00 - 2.4307803e+00 3.1257983e+00 5.4623512e+00 - 2.3664028e+00 3.0217910e+00 5.4710831e+00 - 2.3569558e+00 3.0072846e+00 5.6117295e+00 - 2.2925530e+00 2.9030753e+00 5.6163664e+00 - 2.2864412e+00 2.8931736e+00 5.7729851e+00 - 2.2332902e+00 2.8077928e+00 5.8068610e+00 - 2.1452968e+00 2.6652774e+00 5.7386407e+00 - 1.9607126e+00 2.3662536e+00 5.3707571e+00 - 1.8816527e+00 2.2390827e+00 5.2992216e+00 - 1.8677932e+00 2.2183684e+00 5.4306898e+00 - 1.8559860e+00 2.1979816e+00 5.5712403e+00 - 1.9309853e+00 2.3205105e+00 6.0288056e+00 - 2.3279437e+00 2.9643343e+00 7.6991991e+00 - 1.8143896e+00 2.1320871e+00 6.0314108e+00 - 1.7588933e+00 2.0424913e+00 6.0381754e+00 - 1.7124418e+00 1.9680986e+00 6.0792776e+00 - 1.6840352e+00 1.9227241e+00 6.2014389e+00 - 1.6319189e+00 1.8386067e+00 6.2216294e+00 - 1.6295621e+00 1.8356315e+00 6.4818114e+00 - 1.5446576e+00 1.6983305e+00 6.3406252e+00 - 1.5730767e+00 1.7464703e+00 6.7988434e+00 - 1.5232254e+00 1.6648942e+00 6.8527363e+00 - 1.4485842e+00 1.5455278e+00 6.7619653e+00 - 1.3476613e+00 1.3824238e+00 6.4857826e+00 - 1.0448250e+00 8.8908876e-01 4.7689374e+00 - 1.0071229e+00 8.2908653e-01 4.7671238e+00 - 9.7618694e-01 7.7905715e-01 4.8127355e+00 - 1.2216973e+00 1.1807250e+00 7.2593505e+00 - 1.0237687e+00 8.5925812e-01 5.9595053e+00 - 9.8164481e-01 7.8987936e-01 6.0058403e+00 - 9.5249572e-01 7.4402935e-01 6.2184411e+00 - 8.0810563e-01 5.0846168e-01 4.9965300e+00 - 7.6799109e-01 4.4370748e-01 4.9567185e+00 - 7.3371267e-01 3.8850024e-01 4.9949970e+00 - 7.3195000e-01 3.8747991e-01 5.7190511e+00 - 7.1302914e-01 3.5752241e-01 6.3243903e+00 - 6.6169590e-01 2.7471983e-01 6.2508956e+00 - 6.1296484e-01 1.9715346e-01 6.2657359e+00 - 5.6098450e-01 1.1330568e-01 6.0089706e+00 - 5.1534435e-01 3.8907058e-02 5.9903945e+00 - 1.6133370e+00 1.6807467e+00 -1.0135025e+00 - 1.6476570e+00 1.7342226e+00 -1.0058393e+00 - 1.6916735e+00 1.7995581e+00 -1.0101349e+00 - 1.7347657e+00 1.8660594e+00 -1.0122795e+00 - 1.7798678e+00 1.9325481e+00 -1.0122333e+00 - 1.8196690e+00 1.9937664e+00 -1.0035840e+00 - 1.8648578e+00 2.0614640e+00 -9.9929261e-01 - 1.9188779e+00 2.1431741e+00 -1.0050584e+00 - 1.9729153e+00 2.2250222e+00 -1.0080277e+00 - 2.0280295e+00 2.3079545e+00 -1.0080533e+00 - 2.0876021e+00 2.3984926e+00 -1.0110849e+00 - 2.1481933e+00 2.4891329e+00 -1.0108238e+00 - 2.2176907e+00 2.5949009e+00 -1.0182723e+00 - 2.2882706e+00 2.7017975e+00 -1.0218784e+00 - 2.3687629e+00 2.8238255e+00 -1.0318990e+00 - 2.4415095e+00 2.9329942e+00 -1.0275206e+00 - 2.5330072e+00 3.0713659e+00 -1.0384153e+00 - 2.6255953e+00 3.2109302e+00 -1.0441692e+00 - 2.7182764e+00 3.3517527e+00 -1.0446792e+00 - 2.8219468e+00 3.5087908e+00 -1.0486601e+00 - 2.9410029e+00 3.6886385e+00 -1.0593679e+00 - 3.0612213e+00 3.8707695e+00 -1.0630868e+00 - 3.1879929e+00 4.0616877e+00 -1.0636751e+00 - 3.3247760e+00 4.2690446e+00 -1.0644353e+00 - 3.4934503e+00 4.5239641e+00 -1.0785518e+00 - 3.6587900e+00 4.7727366e+00 -1.0791282e+00 - 3.8451932e+00 5.0551801e+00 -1.0829974e+00 - 4.0590674e+00 5.3778859e+00 -1.0910248e+00 - 4.2840572e+00 5.7183314e+00 -1.0918858e+00 - 4.5431197e+00 6.1087298e+00 -1.0957216e+00 - 4.8342782e+00 6.5493597e+00 -1.0993297e+00 - 5.1750524e+00 7.0650417e+00 -1.1067461e+00 - 5.5444418e+00 7.6226073e+00 -1.1044905e+00 - 5.9790061e+00 8.2804522e+00 -1.1042796e+00 - 6.4972300e+00 9.0625564e+00 -1.1057085e+00 - 7.1632834e+00 1.0069720e+01 -1.1217549e+00 - 8.0267452e+00 1.1376184e+01 -1.1523822e+00 - 9.1237676e+00 1.3032447e+01 -1.1870880e+00 - 1.7504036e+01 2.5699833e+01 -1.1374812e+00 - 1.7504917e+01 2.5702531e+01 -5.9775388e-01 - 1.9585123e+01 2.8847119e+01 -1.8849944e-01 - 1.8461577e+01 2.7151249e+01 4.4996594e-01 - 1.7278061e+01 2.5362172e+01 1.0171051e+00 - 1.6756132e+01 2.4574659e+01 1.5308552e+00 - 1.6786726e+01 2.4622560e+01 2.0474438e+00 - 1.6756651e+01 2.4578680e+01 2.5609244e+00 - 1.6793807e+01 2.4635436e+01 3.0820418e+00 - 1.6924821e+01 2.4834898e+01 3.6217729e+00 - 1.7137546e+01 2.5158091e+01 4.1872360e+00 - 1.7612932e+01 2.5877352e+01 4.8269581e+00 - 1.6655703e+01 2.4430759e+01 5.1331070e+00 - 1.6324206e+01 2.3930376e+01 5.5605304e+00 - 1.6184816e+01 2.3721439e+01 6.0308637e+00 - 1.6323563e+01 2.3931594e+01 6.5933483e+00 - 1.6309993e+01 2.3911949e+01 7.1099370e+00 - 1.6108711e+01 2.3608984e+01 7.5506478e+00 - 1.6053159e+01 2.3525739e+01 8.0484054e+00 - 1.6291491e+01 2.3887275e+01 8.6899154e+00 - 1.6097905e+01 2.3595742e+01 9.1278120e+00 - 1.6243531e+01 2.3817287e+01 9.7461620e+00 - 1.6969404e+01 2.4916317e+01 1.0722845e+01 - 1.7065466e+01 2.5062709e+01 1.1363230e+01 - 1.7070981e+01 2.5072875e+01 1.1957929e+01 - 1.7879124e+01 2.6296491e+01 1.3119495e+01 - 1.7881490e+01 2.6301993e+01 1.3757797e+01 - 1.7902665e+01 2.6335608e+01 1.4419526e+01 - 1.7996813e+01 2.6478654e+01 1.5151701e+01 - 5.8188606e+00 8.0509673e+00 5.5066677e+00 - 1.7846849e+01 2.6254327e+01 1.6369180e+01 - 6.0084943e+00 8.3388113e+00 6.0997488e+00 - 5.8799065e+00 8.1458438e+00 6.1981700e+00 - 4.2967361e+00 5.7488221e+00 4.8246313e+00 - 4.1922276e+00 5.5920922e+00 4.8741584e+00 - 4.1773148e+00 5.5699667e+00 5.0163157e+00 - 4.1855866e+00 5.5818723e+00 5.1851864e+00 - 4.1253372e+00 5.4919000e+00 5.2795069e+00 - 4.1757067e+00 5.5673023e+00 5.5056604e+00 - 3.2556834e+00 4.1750211e+00 4.5077958e+00 - 3.2040749e+00 4.0970248e+00 4.5710346e+00 - 3.6745341e+00 4.8104022e+00 5.3487472e+00 - 3.6540152e+00 4.7790201e+00 5.4794810e+00 - 3.0748190e+00 3.9031447e+00 4.7915555e+00 - 3.0631252e+00 3.8857259e+00 4.9112333e+00 - 2.9881788e+00 3.7719576e+00 4.9327270e+00 - 2.9786964e+00 3.7576846e+00 5.0578429e+00 - 2.9070592e+00 3.6488281e+00 5.0812766e+00 - 2.9099336e+00 3.6552087e+00 5.2333320e+00 - 2.9514594e+00 3.7170141e+00 5.4577078e+00 - 2.8577356e+00 3.5764115e+00 5.4411924e+00 - 3.0282581e+00 3.8352700e+00 5.9323936e+00 - 2.9443773e+00 3.7071805e+00 5.9374276e+00 - 2.7372556e+00 3.3940391e+00 5.6819171e+00 - 2.6600667e+00 3.2773927e+00 5.6831413e+00 - 2.5829177e+00 3.1615807e+00 5.6810201e+00 - 2.5244729e+00 3.0715026e+00 5.7148601e+00 - 2.4517510e+00 2.9625310e+00 5.7144767e+00 - 2.4479983e+00 2.9579858e+00 5.8808289e+00 - 2.3529362e+00 2.8142100e+00 5.8190222e+00 - 2.0695768e+00 2.3842012e+00 5.2385386e+00 - 2.1303847e+00 2.4773900e+00 5.5728849e+00 - 2.0106398e+00 2.2956479e+00 5.4033680e+00 - 1.9365716e+00 2.1834390e+00 5.3563950e+00 - 1.9003839e+00 2.1285332e+00 5.4185999e+00 - 1.8441511e+00 2.0436674e+00 5.4187278e+00 - 2.0715895e+00 2.3900560e+00 6.3880555e+00 - 2.4009523e+00 2.8907480e+00 7.8007997e+00 - 2.2075643e+00 2.5978299e+00 7.3836087e+00 - 1.7912987e+00 1.9648852e+00 6.0499136e+00 - 1.7396135e+00 1.8873063e+00 6.0810928e+00 - 1.7013261e+00 1.8296322e+00 6.1657747e+00 - 1.6720316e+00 1.7857141e+00 6.2959796e+00 - 1.6763809e+00 1.7922339e+00 6.5938991e+00 - 1.6673813e+00 1.7787239e+00 6.8560435e+00 - 1.6372020e+00 1.7342254e+00 7.0340414e+00 - 1.5282126e+00 1.5688932e+00 6.7839504e+00 - 1.4732934e+00 1.4870035e+00 6.8253745e+00 - 1.0885374e+00 9.0003293e-01 4.7597173e+00 - 1.0489035e+00 8.4118304e-01 4.7585596e+00 - 1.0170327e+00 7.9223570e-01 4.8046244e+00 - 1.2543885e+00 1.1555149e+00 6.9936633e+00 - 1.0935254e+00 9.1049581e-01 6.1266571e+00 - 1.0336825e+00 8.1986124e-01 6.0466927e+00 - 1.0070799e+00 7.8086551e-01 6.2993896e+00 - 9.4821430e-01 6.9000298e-01 6.2160263e+00 - 8.0147938e-01 4.6651290e-01 4.9719072e+00 - 7.6402664e-01 4.0953427e-01 4.9908687e+00 - 7.2899153e-01 3.5683289e-01 5.0584645e+00 - 7.2387119e-01 3.4999741e-01 5.7825259e+00 - 6.9722805e-01 3.1200987e-01 6.3178219e+00 - 6.4519916e-01 2.3220090e-01 6.2835324e+00 - 5.8923252e-01 1.4813004e-01 6.0376161e+00 - 5.4066507e-01 7.4449788e-02 6.0299360e+00 - 1.6404920e+00 1.6161089e+00 -1.0095806e+00 - 1.6809943e+00 1.6728306e+00 -1.0098251e+00 - 1.7172559e+00 1.7252329e+00 -1.0012198e+00 - 1.7665907e+00 1.7959769e+00 -1.0113218e+00 - 1.8038726e+00 1.8484962e+00 -9.9912406e-01 - 1.8552917e+00 1.9203380e+00 -1.0047875e+00 - 1.9014111e+00 1.9869190e+00 -1.0016482e+00 - 1.9529207e+00 2.0599992e+00 -1.0024673e+00 - 2.0054444e+00 2.1331469e+00 -1.0006927e+00 - 2.0668037e+00 2.2203417e+00 -1.0082762e+00 - 2.1292412e+00 2.3086307e+00 -1.0127164e+00 - 2.1917579e+00 2.3980693e+00 -1.0141099e+00 - 2.2597362e+00 2.4950927e+00 -1.0177136e+00 - 2.3385593e+00 2.6061456e+00 -1.0285842e+00 - 2.4120262e+00 2.7109705e+00 -1.0300033e+00 - 2.4920197e+00 2.8243707e+00 -1.0325866e+00 - 2.5720391e+00 2.9379779e+00 -1.0309751e+00 - 2.6684220e+00 3.0741716e+00 -1.0393896e+00 - 2.7703439e+00 3.2190850e+00 -1.0472672e+00 - 2.8787464e+00 3.3716901e+00 -1.0539622e+00 - 2.9873063e+00 3.5265848e+00 -1.0547638e+00 - 3.1068027e+00 3.6967573e+00 -1.0577881e+00 - 3.2491408e+00 3.8971884e+00 -1.0700555e+00 - 3.3861970e+00 4.0925017e+00 -1.0706238e+00 - 3.5407176e+00 4.3116780e+00 -1.0743793e+00 - 3.7127113e+00 4.5547864e+00 -1.0799238e+00 - 3.8903411e+00 4.8079070e+00 -1.0789884e+00 - 4.1072819e+00 5.1152343e+00 -1.0899806e+00 - 4.3318743e+00 5.4326057e+00 -1.0914031e+00 - 4.5785581e+00 5.7838241e+00 -1.0913274e+00 - 4.8656586e+00 6.1905651e+00 -1.0955417e+00 - 5.2042392e+00 6.6701498e+00 -1.1053691e+00 - 5.5605044e+00 7.1763895e+00 -1.1023028e+00 - 5.9922579e+00 7.7880494e+00 -1.1064046e+00 - 6.4810976e+00 8.4818095e+00 -1.1046960e+00 - 7.0959184e+00 9.3539825e+00 -1.1139676e+00 - 7.8269192e+00 1.0390843e+01 -1.1195646e+00 - 8.9643077e+00 1.2003975e+01 -1.1859334e+00 - 1.0419476e+01 1.4067186e+01 -1.2554394e+00 - 1.7654866e+01 2.4329279e+01 -1.3251190e+00 - 1.8728158e+01 2.5851563e+01 -9.1583014e-01 - 1.8806919e+01 2.5965299e+01 -3.6824380e-01 - 2.3933870e+01 3.3235919e+01 -4.0952920e-02 - 2.3927726e+01 3.3229456e+01 6.6917925e-01 - 2.3956549e+01 3.3271030e+01 1.3792291e+00 - 2.3925142e+01 3.3227935e+01 2.0885207e+00 - 1.9045973e+01 2.6308324e+01 2.4244269e+00 - 1.7843129e+01 2.4604103e+01 2.8590412e+00 - 1.7855957e+01 2.4622641e+01 3.3889023e+00 - 1.8087094e+01 2.4951907e+01 3.9576568e+00 - 1.8219596e+01 2.5141517e+01 4.5229955e+00 - 1.7964813e+01 2.4779859e+01 5.0093842e+00 - 1.7949246e+01 2.4759291e+01 5.5453546e+00 - 1.8843198e+01 2.6029105e+01 6.3481730e+00 - 1.7659179e+01 2.4350764e+01 6.5392959e+00 - 1.8825394e+01 2.6005794e+01 7.4922423e+00 - 1.7840776e+01 2.4608769e+01 7.6927878e+00 - 1.7680374e+01 2.4382867e+01 8.1797068e+00 - 1.7303690e+01 2.3849952e+01 8.5636580e+00 - 1.9062219e+01 2.6345749e+01 9.9580749e+00 - 1.7836863e+01 2.4608144e+01 9.9358092e+00 - 1.7831289e+01 2.4601810e+01 1.0507961e+01 - 1.8862492e+01 2.6066728e+01 1.1689689e+01 - 2.0168605e+01 2.7922458e+01 1.3117170e+01 - 1.8963839e+01 2.6214311e+01 1.3652113e+01 - 1.9801324e+01 2.7404691e+01 1.4907151e+01 - 4.3455285e+00 5.4647012e+00 5.1007689e+00 - 4.3472385e+00 5.4677506e+00 5.2651109e+00 - 4.4138959e+00 5.5630720e+00 5.5082035e+00 - 4.4628765e+00 5.6318023e+00 5.7397009e+00 - 3.3649093e+00 4.0735867e+00 4.5572808e+00 - 3.8118653e+00 4.7085266e+00 5.4235118e+00 - 3.2132315e+00 3.8579592e+00 4.7569856e+00 - 3.2104511e+00 3.8546940e+00 4.8897274e+00 - 3.2495184e+00 3.9103496e+00 5.0882894e+00 - 2.9965921e+00 3.5514937e+00 4.8462301e+00 - 3.0808467e+00 3.6712232e+00 5.1174464e+00 - 3.0968646e+00 3.6949599e+00 5.2915930e+00 - 2.9055204e+00 3.4230158e+00 5.1172556e+00 - 2.8685021e+00 3.3700247e+00 5.1967927e+00 - 2.9286086e+00 3.4555454e+00 5.4567293e+00 - 3.0771374e+00 3.6681424e+00 5.8985845e+00 - 2.9860867e+00 3.5379845e+00 5.8936523e+00 - 2.7305973e+00 3.1752360e+00 5.5499752e+00 - 2.6483472e+00 3.0583303e+00 5.5398294e+00 - 2.7307065e+00 3.1758941e+00 5.8862569e+00 - 2.6496108e+00 3.0612075e+00 5.8818017e+00 - 2.5762467e+00 2.9577196e+00 5.8900627e+00 - 2.4806119e+00 2.8204983e+00 5.8383491e+00 - 2.1284704e+00 2.3201361e+00 5.1310993e+00 - 2.0615391e+00 2.2249888e+00 5.1131775e+00 - 2.0688320e+00 2.2365935e+00 5.2949850e+00 - 2.0317790e+00 2.1838406e+00 5.3590915e+00 - 1.9903110e+00 2.1248600e+00 5.4136203e+00 - 1.9511276e+00 2.0701257e+00 5.4756350e+00 - 2.0482623e+00 2.2085024e+00 5.9762361e+00 - 2.4572519e+00 2.7909969e+00 7.5574669e+00 - 2.3184925e+00 2.5942357e+00 7.3653794e+00 - 2.1874023e+00 2.4081756e+00 7.1759206e+00 - 1.8350499e+00 1.9063423e+00 6.1159095e+00 - 1.7559074e+00 1.7942847e+00 6.0456315e+00 - 1.7379068e+00 1.7690161e+00 6.2217046e+00 - 1.7122015e+00 1.7332797e+00 6.3796185e+00 - 1.7343743e+00 1.7644684e+00 6.7717288e+00 - 1.6518382e+00 1.6468240e+00 6.6858277e+00 - 1.5815821e+00 1.5471559e+00 6.6536315e+00 - 1.4755903e+00 1.3974405e+00 6.4186713e+00 - 1.1374782e+00 9.1360484e-01 4.7693588e+00 - 1.0947342e+00 8.5349594e-01 4.7592713e+00 - 1.0576355e+00 8.0192579e-01 4.7865745e+00 - 1.0181715e+00 7.4546395e-01 4.7933078e+00 - 1.1603727e+00 9.4991591e-01 6.2341354e+00 - 1.0942467e+00 8.5574667e-01 6.1359615e+00 - 1.0518559e+00 7.9536612e-01 6.2419283e+00 - 1.0016214e+00 7.2443764e-01 6.2875888e+00 - 8.4728356e-01 5.0397159e-01 5.1152561e+00 - 7.9415585e-01 4.2857615e-01 4.9666149e+00 - 7.5700542e-01 3.7504481e-01 5.0149409e+00 - 7.5524275e-01 3.7402448e-01 5.7389950e+00 - 7.2841199e-01 3.3660069e-01 6.2046786e+00 - 6.7700026e-01 2.6327071e-01 6.2409531e+00 - 6.2327325e-01 1.8802864e-01 6.2157602e+00 - 5.6766791e-01 1.0839218e-01 5.9989591e+00 - 5.1709407e-01 3.6815466e-02 5.9504375e+00 - 1.6635971e+00 1.5507407e+00 -1.0050970e+00 - 1.7050914e+00 1.6073526e+00 -1.0063435e+00 - 1.7475956e+00 1.6639976e+00 -1.0056955e+00 - 1.7954236e+00 1.7260956e+00 -1.0099550e+00 - 1.8380126e+00 1.7839347e+00 -1.0053615e+00 - 1.8816110e+00 1.8418020e+00 -9.9897335e-01 - 1.9349736e+00 1.9125850e+00 -1.0033951e+00 - 1.9830359e+00 1.9781024e+00 -9.9911399e-01 - 2.0374269e+00 2.0490664e+00 -9.9864495e-01 - 2.0963328e+00 2.1286035e+00 -1.0018306e+00 - 2.1605748e+00 2.2136921e+00 -1.0079263e+00 - 2.2259558e+00 2.3008766e+00 -1.0108283e+00 - 2.2957380e+00 2.3946946e+00 -1.0161873e+00 - 2.3720420e+00 2.4970486e+00 -1.0235095e+00 - 2.4493675e+00 2.5995293e+00 -1.0270395e+00 - 2.5321613e+00 2.7096489e+00 -1.0316810e+00 - 2.6150406e+00 2.8209675e+00 -1.0322770e+00 - 2.7043900e+00 2.9398941e+00 -1.0333885e+00 - 2.8046605e+00 3.0739753e+00 -1.0392197e+00 - 2.9168553e+00 3.2231902e+00 -1.0489748e+00 - 3.0182514e+00 3.3587449e+00 -1.0439722e+00 - 3.1543709e+00 3.5393520e+00 -1.0590280e+00 - 3.2786972e+00 3.7063890e+00 -1.0587236e+00 - 3.4214148e+00 3.8961429e+00 -1.0633579e+00 - 3.5816546e+00 4.1107372e+00 -1.0716285e+00 - 3.7429474e+00 4.3257095e+00 -1.0710132e+00 - 3.9227126e+00 4.5645633e+00 -1.0719904e+00 - 4.1363280e+00 4.8500440e+00 -1.0825853e+00 - 4.3629857e+00 5.1520728e+00 -1.0874689e+00 - 4.6082094e+00 5.4792460e+00 -1.0886011e+00 - 4.8828655e+00 5.8457657e+00 -1.0897533e+00 - 5.2109235e+00 6.2838978e+00 -1.0987726e+00 - 5.5530714e+00 6.7389116e+00 -1.0940935e+00 - 5.9715674e+00 7.2971483e+00 -1.0993830e+00 - 6.4326212e+00 7.9124586e+00 -1.0953352e+00 - 7.0135101e+00 8.6874532e+00 -1.1031080e+00 - 7.6957878e+00 9.5979435e+00 -1.1070767e+00 - 8.6351330e+00 1.0850614e+01 -1.1389230e+00 - 9.8741841e+00 1.2503699e+01 -1.1860632e+00 - 1.4901740e+01 1.9209409e+01 -1.5081288e+00 - 1.8289698e+01 2.3730601e+01 -1.0552048e+00 - 1.9021522e+01 2.4707117e+01 -5.9886409e-01 - 2.0174100e+01 2.6244881e+01 -1.2484684e-01 - 2.4428491e+01 3.1921433e+01 3.2841442e-01 - 2.4424500e+01 3.1918167e+01 1.0247588e+00 - 2.4282032e+01 3.1729461e+01 1.7167877e+00 - 1.9978571e+01 2.5989821e+01 2.1545361e+00 - 1.9825726e+01 2.5785878e+01 2.7090101e+00 - 1.9720902e+01 2.5647132e+01 3.2612731e+00 - 2.1199400e+01 2.7620764e+01 4.0413845e+00 - 2.0501459e+01 2.6691008e+01 4.5266926e+00 - 2.0097856e+01 2.6153788e+01 5.0334734e+00 - 1.8912039e+01 2.4572314e+01 5.3348709e+00 - 2.4418787e+01 3.1921594e+01 7.3431182e+00 - 2.4436669e+01 3.1947331e+01 8.0643295e+00 - 2.4417365e+01 3.1921837e+01 8.7791863e+00 - 2.4524805e+01 3.2067652e+01 9.5428819e+00 - 2.4471828e+01 3.1999001e+01 1.0256671e+01 - 1.9519978e+01 2.5389360e+01 8.9306042e+00 - 1.9404246e+01 2.5236591e+01 9.4700095e+00 - 1.9180342e+01 2.4938221e+01 9.9554886e+00 - 1.9157396e+01 2.4909278e+01 1.0535972e+01 - 4.7453947e+00 5.6733564e+00 5.2642254e+00 - 4.6486964e+00 5.5452575e+00 5.3342190e+00 - 4.6077275e+00 5.4907817e+00 5.4598103e+00 - 3.4426356e+00 3.9357550e+00 4.8452474e+00 - 3.4025369e+00 3.8812272e+00 4.9304862e+00 - 3.3242101e+00 3.7772349e+00 4.9629325e+00 - 3.2458635e+00 3.6730850e+00 4.9921828e+00 - 3.3592687e+00 3.8252676e+00 5.3059730e+00 - 3.0945650e+00 3.4713188e+00 5.0474242e+00 - 3.0435489e+00 3.4032132e+00 5.1085695e+00 - 2.9914633e+00 3.3340825e+00 5.1679698e+00 - 2.9886917e+00 3.3303721e+00 5.3119473e+00 - 2.9717256e+00 3.3084284e+00 5.4350849e+00 - 2.9810363e+00 3.3205987e+00 5.6105443e+00 - 2.8971177e+00 3.2084964e+00 5.6142892e+00 - 2.8175809e+00 3.1023557e+00 5.6222187e+00 - 2.8368552e+00 3.1285189e+00 5.8289658e+00 - 2.4508561e+00 2.6119843e+00 5.1789922e+00 - 2.3887944e+00 2.5292762e+00 5.1952697e+00 - 2.3476786e+00 2.4756893e+00 5.2578405e+00 - 2.2614020e+00 2.3603017e+00 5.2128017e+00 - 2.1399340e+00 2.1981839e+00 5.0727649e+00 - 2.1173350e+00 2.1672858e+00 5.1703469e+00 - 2.0827510e+00 2.1217996e+00 5.2423899e+00 - 2.2066979e+00 2.2884685e+00 5.7595523e+00 - 2.0432871e+00 2.0697658e+00 5.4794892e+00 - 2.2224317e+00 2.3097199e+00 6.2062593e+00 - 1.9685545e+00 1.9693527e+00 5.6286811e+00 - 2.3233952e+00 2.4463303e+00 6.9988840e+00 - 2.3442480e+00 2.4750077e+00 7.3388619e+00 - 2.5197653e+00 2.7109026e+00 8.2620966e+00 - 1.8824481e+00 1.8569585e+00 6.2091653e+00 - 1.7252256e+00 1.6456738e+00 5.8436933e+00 - 1.6764045e+00 1.5816142e+00 5.8880049e+00 - 1.7559024e+00 1.6880449e+00 6.4913154e+00 - 1.6794338e+00 1.5859228e+00 6.4425580e+00 - 1.6538956e+00 1.5515217e+00 6.6275384e+00 - 1.6074119e+00 1.4900657e+00 6.7270756e+00 - 1.1851177e+00 9.2275178e-01 4.7691142e+00 - 1.1416209e+00 8.6621151e-01 4.7693683e+00 - 1.1101794e+00 8.2327369e-01 4.8359597e+00 - 1.2844012e+00 1.0590020e+00 6.2991766e+00 - 1.0050639e+00 6.8313966e-01 4.6939366e+00 - 1.1285227e+00 8.5042078e-01 5.9897322e+00 - 9.1203384e-01 5.5891096e-01 4.5838948e+00 - 1.0387447e+00 7.3146494e-01 6.1713703e+00 - 9.9104739e-01 6.6731683e-01 6.2556287e+00 - 8.2958046e-01 4.4974958e-01 4.9916842e+00 - 7.8819568e-01 3.9452877e-01 5.0008713e+00 - 7.4910544e-01 3.4208573e-01 5.0485548e+00 - 7.4883599e-01 3.4341378e-01 5.8822193e+00 - 7.0955393e-01 2.9128603e-01 6.1781947e+00 - 6.5769110e-01 2.2341971e-01 6.2834879e+00 - 5.9672913e-01 1.4167808e-01 5.9976384e+00 - 5.4447502e-01 7.1716479e-02 6.0199349e+00 - 1.6933914e+00 1.4973099e+00 -1.0146601e+00 - 1.7324447e+00 1.5463627e+00 -1.0095112e+00 - 1.7768192e+00 1.6008486e+00 -1.0096693e+00 - 1.8212657e+00 1.6564251e+00 -1.0079794e+00 - 1.8657841e+00 1.7130921e+00 -1.0044413e+00 - 1.9199420e+00 1.7806465e+00 -1.0123132e+00 - 1.9654839e+00 1.8374551e+00 -1.0046833e+00 - 2.0110983e+00 1.8953592e+00 -9.9510552e-01 - 2.0717344e+00 1.9705856e+00 -1.0021943e+00 - 2.1271309e+00 2.0415482e+00 -1.0005299e+00 - 2.1942974e+00 2.1253796e+00 -1.0081836e+00 - 2.2614842e+00 2.2093736e+00 -1.0125414e+00 - 2.3341300e+00 2.3009326e+00 -1.0195087e+00 - 2.4034736e+00 2.3871198e+00 -1.0174799e+00 - 2.4826621e+00 2.4873822e+00 -1.0230146e+00 - 2.5682555e+00 2.5942163e+00 -1.0298141e+00 - 2.6485523e+00 2.6958144e+00 -1.0273116e+00 - 2.7515290e+00 2.8253471e+00 -1.0406446e+00 - 2.8393200e+00 2.9346996e+00 -1.0344658e+00 - 2.9498622e+00 3.0730724e+00 -1.0423743e+00 - 3.0669446e+00 3.2201290e+00 -1.0492497e+00 - 3.1949009e+00 3.3814468e+00 -1.0586979e+00 - 3.3141157e+00 3.5299854e+00 -1.0533444e+00 - 3.4670090e+00 3.7227483e+00 -1.0657993e+00 - 3.6220081e+00 3.9167814e+00 -1.0703200e+00 - 3.7889605e+00 4.1261796e+00 -1.0740704e+00 - 3.9689305e+00 4.3519287e+00 -1.0761045e+00 - 4.1782290e+00 4.6156775e+00 -1.0852003e+00 - 4.3960458e+00 4.8873273e+00 -1.0864282e+00 - 4.6314235e+00 5.1841278e+00 -1.0850001e+00 - 4.8991581e+00 5.5190176e+00 -1.0851501e+00 - 5.2157016e+00 5.9158069e+00 -1.0923593e+00 - 5.5627654e+00 6.3531156e+00 -1.0948471e+00 - 5.9486993e+00 6.8364666e+00 -1.0924369e+00 - 6.4030094e+00 7.4068257e+00 -1.0928384e+00 - 6.9679039e+00 8.1164117e+00 -1.1040944e+00 - 7.6086603e+00 8.9201772e+00 -1.1060466e+00 - 8.4542984e+00 9.9814491e+00 -1.1269719e+00 - 9.5611667e+00 1.1370246e+01 -1.1628626e+00 - 1.0980245e+01 1.3150255e+01 -1.2023565e+00 - 1.8356271e+01 2.2407607e+01 -1.2359578e+00 - 1.9305300e+01 2.3598414e+01 -8.2567056e-01 - 1.9346232e+01 2.3651133e+01 -3.0047247e-01 - 2.4619550e+01 3.0271654e+01 2.0388263e+00 - 2.4728254e+01 3.0409433e+01 2.7231121e+00 - 2.0730466e+01 2.5394197e+01 3.5766994e+00 - 2.4696809e+01 3.0375362e+01 5.4504484e+00 - 2.4811041e+01 3.0520225e+01 6.1628859e+00 - 2.4890063e+01 3.0621782e+01 8.2821091e+00 - 2.4787426e+01 3.0496079e+01 8.9581688e+00 - 2.4879954e+01 3.0611741e+01 9.7025180e+00 - 2.4921019e+01 3.0666944e+01 1.1165850e+01 - 2.4890980e+01 3.0629320e+01 1.1885977e+01 - 2.4851360e+01 3.0582316e+01 1.2607527e+01 - 3.5985401e+00 3.8973334e+00 4.8267563e+00 - 3.5173645e+00 3.7957184e+00 4.8632080e+00 - 3.5260033e+00 3.8069466e+00 5.1601679e+00 - 3.4949141e+00 3.7678552e+00 5.2642138e+00 - 3.2414848e+00 3.4492049e+00 5.0434030e+00 - 3.1559376e+00 3.3427403e+00 5.0576932e+00 - 3.1335300e+00 3.3144027e+00 5.1666619e+00 - 3.2496511e+00 3.4605682e+00 5.5039608e+00 - 3.1270035e+00 3.3071606e+00 5.4570170e+00 - 3.0609963e+00 3.2240406e+00 5.5005728e+00 - 3.0528837e+00 3.2147394e+00 5.6466613e+00 - 2.9617418e+00 3.0996259e+00 5.6415883e+00 - 2.9503287e+00 3.0854819e+00 5.7871350e+00 - 2.5491065e+00 2.5815609e+00 5.1504501e+00 - 2.5868347e+00 2.6299104e+00 5.3820211e+00 - 2.4397788e+00 2.4433095e+00 5.2228247e+00 - 2.4075823e+00 2.4034065e+00 5.3091957e+00 - 2.3042780e+00 2.2733192e+00 5.2302442e+00 - 2.2710642e+00 2.2333239e+00 5.3135222e+00 - 2.1577992e+00 2.0897824e+00 5.1939449e+00 - 2.2022082e+00 2.1463917e+00 5.4787334e+00 - 2.2039248e+00 2.1484621e+00 5.6637490e+00 - 2.0764610e+00 1.9882001e+00 5.4932202e+00 - 2.0245267e+00 1.9228569e+00 5.5281027e+00 - 1.9946181e+00 1.8867107e+00 5.6322964e+00 - 1.9493074e+00 1.8302023e+00 5.6915328e+00 - 1.9016954e+00 1.7693146e+00 5.7405867e+00 - 1.7981748e+00 1.6390453e+00 5.5971660e+00 - 1.7671778e+00 1.6012070e+00 5.7063560e+00 - 1.6976061e+00 1.5131969e+00 5.6673728e+00 - 1.7919611e+00 1.6320257e+00 6.2960121e+00 - 1.7600233e+00 1.5931587e+00 6.4439063e+00 - 1.7544904e+00 1.5863359e+00 6.7237217e+00 - 1.2812887e+00 9.8848655e-01 4.7756908e+00 - 1.2336325e+00 9.2982466e-01 4.7685659e+00 - 1.1892020e+00 8.7437627e-01 4.7694728e+00 - 1.1634766e+00 8.4105791e-01 4.8751032e+00 - 1.0758871e+00 7.3198307e-01 4.6123930e+00 - 1.0457321e+00 6.9335198e-01 4.6864735e+00 - 1.1938294e+00 8.8195701e-01 6.0779847e+00 - 9.2999384e-01 5.4869864e-01 4.4406105e+00 - 9.3899700e-01 5.5974391e-01 4.8554225e+00 - 1.0000599e+00 6.3825186e-01 5.8634214e+00 - 9.0083802e-01 5.1401213e-01 5.3823607e+00 - 8.2244045e-01 4.1379513e-01 5.0063177e+00 - 7.7805748e-01 3.5872611e-01 5.0149150e+00 - 7.7623377e-01 3.5721803e-01 5.7290814e+00 - 7.4055722e-01 3.1288598e-01 6.0652001e+00 - 6.9603894e-01 2.5755231e-01 6.3508530e+00 - 6.3495260e-01 1.8079084e-01 6.2457818e+00 - 5.7441296e-01 1.0397136e-01 5.9989353e+00 - 5.1896710e-01 3.5709219e-02 5.9304558e+00 - 1.7568059e+00 1.4855739e+00 -1.0122699e+00 - 1.7978008e+00 1.5335531e+00 -1.0061789e+00 - 1.8484892e+00 1.5933674e+00 -1.0125462e+00 - 1.8991919e+00 1.6532950e+00 -1.0166163e+00 - 1.9455924e+00 1.7078965e+00 -1.0119867e+00 - 1.9920654e+00 1.7635935e+00 -1.0054091e+00 - 2.0395489e+00 1.8193286e+00 -9.9683723e-01 - 2.0967371e+00 1.8869873e+00 -9.9892575e-01 - 2.1603757e+00 1.9620964e+00 -1.0047257e+00 - 2.2283510e+00 2.0428075e+00 -1.0136322e+00 - 2.2984622e+00 2.1255444e+00 -1.0195479e+00 - 2.3632147e+00 2.2020334e+00 -1.0164117e+00 - 2.4441247e+00 2.2979162e+00 -1.0272478e+00 - 2.5163535e+00 2.3820168e+00 -1.0233317e+00 - 2.6038105e+00 2.4866376e+00 -1.0320360e+00 - 2.6879064e+00 2.5848995e+00 -1.0314949e+00 - 2.7775314e+00 2.6918022e+00 -1.0320149e+00 - 2.8789502e+00 2.8117657e+00 -1.0379578e+00 - 2.9814583e+00 2.9329121e+00 -1.0389596e+00 - 3.0958286e+00 3.0681803e+00 -1.0441354e+00 - 3.2231255e+00 3.2185562e+00 -1.0525392e+00 - 3.3569092e+00 3.3766732e+00 -1.0587616e+00 - 3.5036301e+00 3.5499815e+00 -1.0665142e+00 - 3.6515152e+00 3.7255878e+00 -1.0669782e+00 - 3.8122257e+00 3.9144606e+00 -1.0674749e+00 - 4.0042437e+00 4.1410742e+00 -1.0778361e+00 - 4.2028345e+00 4.3766328e+00 -1.0818708e+00 - 4.4218462e+00 4.6350535e+00 -1.0854572e+00 - 4.6592918e+00 4.9165311e+00 -1.0870907e+00 - 4.9235718e+00 5.2275114e+00 -1.0881425e+00 - 5.2311943e+00 5.5927671e+00 -1.0948425e+00 - 5.5602852e+00 5.9812186e+00 -1.0931073e+00 - 5.9401507e+00 6.4306883e+00 -1.0935940e+00 - 6.3911329e+00 6.9628935e+00 -1.0988012e+00 - 6.9069279e+00 7.5725846e+00 -1.1009216e+00 - 7.5317397e+00 8.3118547e+00 -1.1081044e+00 - 8.2536953e+00 9.1659790e+00 -1.1081359e+00 - 9.3422629e+00 1.0451854e+01 -1.1583608e+00 - 1.0734096e+01 1.2097221e+01 -1.2154750e+00 - 1.5447939e+01 1.7669382e+01 -1.4162099e+00 - 1.8438190e+01 2.1205357e+01 -1.4106467e+00 - 1.9377302e+01 2.2316361e+01 -1.0236955e+00 - 1.9616409e+01 2.2599247e+01 -5.3079868e-01 - 1.9766050e+01 2.2777030e+01 -2.1151548e-02 - 2.5075471e+01 2.9054396e+01 3.6181799e-01 - 2.5104769e+01 2.9089655e+01 1.0261196e+00 - 2.4976572e+01 2.8939695e+01 1.6876140e+00 - 2.4984320e+01 2.8950085e+01 2.3500714e+00 - 2.5042769e+01 2.9019868e+01 3.0178967e+00 - 2.5170321e+01 2.9171337e+01 3.6977865e+00 - 2.5193207e+01 2.9199456e+01 4.3720917e+00 - 2.5093056e+01 2.9082704e+01 5.0294720e+00 - 2.5037133e+01 2.9017719e+01 5.6923360e+00 - 2.5126995e+01 2.9125052e+01 6.3869507e+00 - 2.5253565e+01 2.9275167e+01 7.0989528e+00 - 2.5306817e+01 2.9339993e+01 7.8019978e+00 - 2.5156941e+01 2.9163610e+01 8.4504115e+00 - 2.5124865e+01 2.9127329e+01 9.1345405e+00 - 2.5186696e+01 2.9200549e+01 9.8554411e+00 - 2.5389158e+01 2.9441980e+01 1.0640266e+01 - 2.5276086e+01 2.9309651e+01 1.1311611e+01 - 2.5180304e+01 2.9197735e+01 1.1990853e+01 - 3.6007301e+00 3.6741129e+00 5.0405039e+00 - 3.5590266e+00 3.6259291e+00 5.1303457e+00 - 3.5649189e+00 3.6323156e+00 5.2861870e+00 - 3.5069011e+00 3.5640008e+00 5.3547950e+00 - 3.4434147e+00 3.4885613e+00 5.4146770e+00 - 3.3973922e+00 3.4354325e+00 5.5006843e+00 - 3.1895349e+00 3.1885725e+00 5.3266132e+00 - 3.1358494e+00 3.1258252e+00 5.3914155e+00 - 3.2536877e+00 3.2660292e+00 5.7521264e+00 - 3.0815979e+00 3.0619500e+00 5.6144721e+00 - 3.0453106e+00 3.0199581e+00 5.7143878e+00 - 2.4407262e+00 2.3031641e+00 4.7251096e+00 - 2.5889419e+00 2.4781025e+00 5.1556080e+00 - 2.5645667e+00 2.4506315e+00 5.2594398e+00 - 2.4933412e+00 2.3659957e+00 5.2661570e+00 - 2.4265067e+00 2.2873955e+00 5.2785568e+00 - 2.3639439e+00 2.2128467e+00 5.2969380e+00 - 2.3155200e+00 2.1550546e+00 5.3467452e+00 - 2.2585137e+00 2.0888493e+00 5.3782973e+00 - 2.2155927e+00 2.0384579e+00 5.4424237e+00 - 2.1203264e+00 1.9251124e+00 5.3670022e+00 - 2.0991790e+00 1.9003556e+00 5.4890028e+00 - 2.0213326e+00 1.8079379e+00 5.4521905e+00 - 2.5696606e+00 2.4594475e+00 7.3199154e+00 - 2.0326048e+00 1.8220731e+00 5.8915665e+00 - 1.9821202e+00 1.7628564e+00 5.9505680e+00 - 1.7928502e+00 1.5384325e+00 5.5239655e+00 - 1.7466230e+00 1.4836681e+00 5.5768138e+00 - 1.7551247e+00 1.4943167e+00 5.8417635e+00 - 1.8161998e+00 1.5666477e+00 6.3420404e+00 - 1.8063149e+00 1.5556470e+00 6.5930530e+00 - 1.7701418e+00 1.5125051e+00 6.7506959e+00 - 1.2819043e+00 9.3340907e-01 4.7580788e+00 - 1.2376578e+00 8.8046205e-01 4.7691738e+00 - 1.1989361e+00 8.3457399e-01 4.8079211e+00 - 1.4180968e+00 1.0967210e+00 6.3527601e+00 - 1.0840996e+00 6.9918993e-01 4.6689277e+00 - 1.0475316e+00 6.5547049e-01 4.7135622e+00 - 1.0032448e+00 6.0271736e-01 4.7083277e+00 - 9.5123598e-01 5.4142006e-01 4.6428876e+00 - 1.0395488e+00 6.4810937e-01 5.8070227e+00 - 1.0292805e+00 6.3692498e-01 6.2556904e+00 - 8.5868114e-01 4.3242153e-01 5.0214953e+00 - 8.1124489e-01 3.7757996e-01 5.0107764e+00 - 7.6934285e-01 3.2780977e-01 5.0684579e+00 - 7.6901175e-01 3.2864515e-01 5.8921348e+00 - 7.1982183e-01 2.7019042e-01 6.0285862e+00 - 6.6881640e-01 2.1123864e-01 6.2335579e+00 - 6.0292075e-01 1.3231892e-01 5.9177628e+00 - 5.4803551e-01 6.8021041e-02 5.9499086e+00 - 1.7844232e+00 1.4292732e+00 -1.0216780e+00 - 1.8220397e+00 1.4707556e+00 -1.0091382e+00 - 1.8692877e+00 1.5230614e+00 -1.0093066e+00 - 1.9209203e+00 1.5818675e+00 -1.0146287e+00 - 1.9692507e+00 1.6353019e+00 -1.0109547e+00 - 2.0175934e+00 1.6888348e+00 -1.0052832e+00 - 2.0756378e+00 1.7542668e+00 -1.0107715e+00 - 2.1303787e+00 1.8143171e+00 -1.0074634e+00 - 2.1905098e+00 1.8808665e+00 -1.0081137e+00 - 2.2507172e+00 1.9485410e+00 -1.0062167e+00 - 2.3216354e+00 2.0281428e+00 -1.0136849e+00 - 2.3999482e+00 2.1141868e+00 -1.0238193e+00 - 2.4666460e+00 2.1896318e+00 -1.0191417e+00 - 2.5460591e+00 2.2769473e+00 -1.0225373e+00 - 2.6309354e+00 2.3718623e+00 -1.0278434e+00 - 2.7168943e+00 2.4679060e+00 -1.0293069e+00 - 2.8092593e+00 2.5705311e+00 -1.0318356e+00 - 2.9144754e+00 2.6871438e+00 -1.0400396e+00 - 3.0197819e+00 2.8049948e+00 -1.0433992e+00 - 3.1389463e+00 2.9368418e+00 -1.0510390e+00 - 3.2582054e+00 3.0699617e+00 -1.0531353e+00 - 3.3903322e+00 3.2172021e+00 -1.0582103e+00 - 3.5224985e+00 3.3647579e+00 -1.0568932e+00 - 3.6932752e+00 3.5552485e+00 -1.0731511e+00 - 3.8597103e+00 3.7395835e+00 -1.0772640e+00 - 4.0380981e+00 3.9392788e+00 -1.0807065e+00 - 4.2378317e+00 4.1606753e+00 -1.0857517e+00 - 4.4505309e+00 4.3974899e+00 -1.0877327e+00 - 4.6890492e+00 4.6637297e+00 -1.0919253e+00 - 4.9426074e+00 4.9464064e+00 -1.0902132e+00 - 5.2357959e+00 5.2716159e+00 -1.0927461e+00 - 5.5688138e+00 5.6424967e+00 -1.0966764e+00 - 5.9480785e+00 6.0657190e+00 -1.1012713e+00 - 6.3680910e+00 6.5328836e+00 -1.1005759e+00 - 6.8612308e+00 7.0827760e+00 -1.1023101e+00 - 7.4413325e+00 7.7286911e+00 -1.1047120e+00 - 8.1084988e+00 8.4719656e+00 -1.1009397e+00 - 9.1074137e+00 9.5840137e+00 -1.1450403e+00 - 1.0340518e+01 1.0956764e+01 -1.1889285e+00 - 1.2054762e+01 1.2864700e+01 -1.2624868e+00 - 1.9871324e+01 2.1569687e+01 -1.2588446e+00 - 2.1101706e+01 2.2940449e+01 -8.6167408e-01 - 2.1040177e+01 2.2871882e+01 -3.1804612e-01 - 2.5974739e+01 2.8368762e+01 6.9696652e-01 - 2.6046944e+01 2.8450690e+01 1.3635071e+00 - 2.5249931e+01 2.7564473e+01 1.9989662e+00 - 2.5354306e+01 2.7681970e+01 2.6533410e+00 - 2.5424277e+01 2.7760585e+01 3.3110477e+00 - 2.6131876e+01 2.8551427e+01 4.7246661e+00 - 2.5334458e+01 2.7663515e+01 5.2649938e+00 - 2.5432507e+01 2.7774557e+01 5.9432552e+00 - 2.5430495e+01 2.7772574e+01 6.6072843e+00 - 2.6229626e+01 2.8664246e+01 7.4766995e+00 - 2.6268577e+01 2.8707926e+01 8.1808759e+00 - 2.5426902e+01 2.7772663e+01 8.6228881e+00 - 2.5509954e+01 2.7866065e+01 9.3316486e+00 - 2.5512396e+01 2.7870107e+01 1.0021385e+01 - 2.5474640e+01 2.7831674e+01 1.2108385e+01 - 3.8260472e+00 3.7112126e+00 4.3049798e+00 - 3.7717494e+00 3.6522102e+00 5.0498402e+00 - 3.7291178e+00 3.6051627e+00 5.1412336e+00 - 3.7998577e+00 3.6851881e+00 5.3842546e+00 - 3.5963337e+00 3.4576125e+00 5.2603686e+00 - 3.5504396e+00 3.4065417e+00 5.3475752e+00 - 3.5326284e+00 3.3869135e+00 5.4759104e+00 - 3.2880746e+00 3.1152056e+00 5.2618404e+00 - 3.3803853e+00 3.2176974e+00 5.5592886e+00 - 3.3809687e+00 3.2187493e+00 5.7224344e+00 - 3.2940189e+00 3.1217920e+00 5.7446748e+00 - 2.6762412e+00 2.4314688e+00 4.8279632e+00 - 2.4994858e+00 2.2354493e+00 4.6449846e+00 - 2.4480431e+00 2.1781606e+00 4.6810687e+00 - 2.5025871e+00 2.2390010e+00 4.9220322e+00 - 2.5236853e+00 2.2631497e+00 5.1106450e+00 - 2.3131482e+00 2.0277535e+00 4.8208830e+00 - 2.4229989e+00 2.1505864e+00 5.2058289e+00 - 2.2849815e+00 1.9969743e+00 5.0553623e+00 - 2.3159348e+00 2.0327015e+00 5.2870971e+00 - 2.3283948e+00 2.0459271e+00 5.4876160e+00 - 2.2324980e+00 1.9381589e+00 5.4227366e+00 - 2.1377592e+00 1.8331537e+00 5.3543097e+00 - 2.0418848e+00 1.7265961e+00 5.2734508e+00 - 2.0968070e+00 1.7883950e+00 5.6148887e+00 - 2.2267157e+00 1.9335548e+00 6.2110714e+00 - 2.2656328e+00 1.9782102e+00 6.5715761e+00 - 2.0295726e+00 1.7139061e+00 6.0526129e+00 - 1.9064925e+00 1.5769413e+00 5.8717966e+00 - 1.8115440e+00 1.4702609e+00 5.7694116e+00 - 1.7210473e+00 1.3706180e+00 5.6727594e+00 - 1.8766012e+00 1.5441138e+00 6.5473314e+00 - 1.8003304e+00 1.4598609e+00 6.5354379e+00 - 1.3309919e+00 9.3392739e-01 4.7474375e+00 - 1.2870504e+00 8.8548057e-01 4.7687215e+00 - 1.6050829e+00 1.2416498e+00 6.6302092e+00 - 1.4948121e+00 1.1193707e+00 6.4173509e+00 - 1.1387035e+00 7.2041026e-01 4.7384313e+00 - 1.0826050e+00 6.5754806e-01 4.6768983e+00 - 1.0517496e+00 6.2290437e-01 4.7698100e+00 - 1.0022872e+00 5.6846134e-01 4.7444659e+00 - 9.5717327e-01 5.1816657e-01 4.7473255e+00 - 8.8760203e-01 4.3995952e-01 4.5221297e+00 - 9.1813328e-01 4.7497865e-01 5.2638310e+00 - 8.4636801e-01 3.9479689e-01 5.0164186e+00 - 8.0023101e-01 3.4333230e-01 5.0348613e+00 - 7.8147505e-01 3.2346010e-01 5.5002300e+00 - 7.5194945e-01 2.9170670e-01 5.9556381e+00 - 6.9384571e-01 2.2631591e-01 5.9417008e+00 - 6.3342465e-01 1.5951238e-01 5.8561590e+00 - 5.7779135e-01 9.7789340e-02 5.9190205e+00 - 5.2071825e-01 3.3113346e-02 5.9005360e+00 - 1.8475980e+00 1.4135592e+00 -1.0188898e+00 - 1.8914664e+00 1.4593582e+00 -1.0128092e+00 - 1.9353452e+00 1.5052411e+00 -1.0050307e+00 - 1.9941719e+00 1.5673409e+00 -1.0160664e+00 - 2.0444440e+00 1.6197018e+00 -1.0114504e+00 - 2.0990441e+00 1.6775956e+00 -1.0113391e+00 - 2.1547163e+00 1.7365344e+00 -1.0090833e+00 - 2.2167152e+00 1.8009050e+00 -1.0109392e+00 - 2.2841069e+00 1.8717943e+00 -1.0163539e+00 - 2.3525139e+00 1.9427612e+00 -1.0189752e+00 - 2.4209985e+00 2.0148629e+00 -1.0188496e+00 - 2.4958787e+00 2.0934624e+00 -1.0214869e+00 - 2.5771572e+00 2.1785794e+00 -1.0264876e+00 - 2.6585175e+00 2.2648657e+00 -1.0280422e+00 - 2.7472784e+00 2.3576435e+00 -1.0312643e+00 - 2.8425039e+00 2.4579850e+00 -1.0359007e+00 - 2.9387541e+00 2.5584779e+00 -1.0362456e+00 - 3.0467988e+00 2.6720365e+00 -1.0419134e+00 - 3.1569906e+00 2.7877096e+00 -1.0427927e+00 - 3.2917535e+00 2.9293258e+00 -1.0569181e+00 - 3.4211681e+00 3.0647778e+00 -1.0602935e+00 - 3.5581249e+00 3.2088828e+00 -1.0620396e+00 - 3.7089549e+00 3.3671070e+00 -1.0655692e+00 - 3.8790551e+00 3.5460036e+00 -1.0737417e+00 - 4.0566532e+00 3.7326843e+00 -1.0776387e+00 - 4.2555929e+00 3.9410317e+00 -1.0838376e+00 - 4.4684331e+00 4.1637152e+00 -1.0874252e+00 - 4.6952406e+00 4.4017857e+00 -1.0873526e+00 - 4.9552635e+00 4.6757385e+00 -1.0918581e+00 - 5.2376638e+00 4.9715981e+00 -1.0925763e+00 - 5.5671583e+00 5.3175035e+00 -1.0987572e+00 - 5.9309140e+00 5.6996101e+00 -1.1018290e+00 - 6.3374623e+00 6.1264413e+00 -1.1015639e+00 - 6.8252779e+00 6.6383007e+00 -1.1080974e+00 - 7.3762562e+00 7.2168238e+00 -1.1092981e+00 - 8.0170908e+00 7.8893568e+00 -1.1077810e+00 - 8.8771756e+00 8.7922176e+00 -1.1298924e+00 - 9.9982709e+00 9.9694010e+00 -1.1680480e+00 - 1.1566419e+01 1.1615417e+01 -1.2399995e+00 - 1.5997395e+01 1.6266739e+01 -1.3412005e+00 - 2.0752114e+01 2.1256643e+01 -1.5424018e+00 - 2.2065174e+01 2.2636801e+01 -1.1584202e+00 - 2.2363314e+01 2.2949834e+01 -6.3303258e-01 - 2.2372751e+01 2.2960734e+01 -7.9344852e-02 - 2.5698438e+01 2.6452578e+01 3.9450215e-01 - 2.5708212e+01 2.6464626e+01 1.0322349e+00 - 2.5614127e+01 2.6366481e+01 1.6677341e+00 - 2.5553269e+01 2.6304313e+01 2.3005527e+00 - 2.5664567e+01 2.6420874e+01 2.9445182e+00 - 2.5795279e+01 2.6559769e+01 3.5972744e+00 - 2.5807160e+01 2.6573097e+01 4.2431411e+00 - 2.5811639e+01 2.6579923e+01 4.8904756e+00 - 2.5630774e+01 2.6389790e+01 5.5071186e+00 - 2.5749775e+01 2.6516290e+01 6.1787811e+00 - 2.5880558e+01 2.6654724e+01 6.8626980e+00 - 2.5900034e+01 2.6676609e+01 7.5285210e+00 - 2.5938813e+01 2.6718918e+01 8.2049317e+00 - 2.5713023e+01 2.6482573e+01 8.8059091e+00 - 2.5829957e+01 2.6606052e+01 9.5151795e+00 - 2.5876327e+01 2.6656885e+01 1.0210847e+01 - 2.5785021e+01 2.6564015e+01 1.2247498e+01 - 3.9298185e+00 3.6084370e+00 4.2401235e+00 - 3.9076781e+00 3.5848132e+00 4.3433512e+00 - 5.0024133e+00 4.7372742e+00 5.9351866e+00 - 3.9009766e+00 3.5790527e+00 4.8651199e+00 - 3.8478039e+00 3.5240132e+00 4.9443571e+00 - 3.6731668e+00 3.3404940e+00 4.8741887e+00 - 3.8133566e+00 3.4881717e+00 5.1904388e+00 - 3.7214020e+00 3.3908893e+00 5.2202353e+00 - 3.4833724e+00 3.1419633e+00 5.0486551e+00 - 3.6923650e+00 3.3606762e+00 5.4852297e+00 - 3.4865386e+00 3.1455181e+00 5.3460272e+00 - 3.4763306e+00 3.1350305e+00 5.4858793e+00 - 3.1918412e+00 2.8361862e+00 5.2020064e+00 - 2.7221559e+00 2.3417789e+00 4.5928089e+00 - 2.5751139e+00 2.1863192e+00 4.4749291e+00 - 2.5195752e+00 2.1279305e+00 4.5040841e+00 - 2.4856209e+00 2.0931497e+00 4.5702887e+00 - 2.5226676e+00 2.1319274e+00 4.7698960e+00 - 2.4606524e+00 2.0663955e+00 4.7887302e+00 - 2.3824829e+00 1.9840750e+00 4.7730485e+00 - 2.3399919e+00 1.9412455e+00 4.8283888e+00 - 2.4741453e+00 2.0822031e+00 5.2644549e+00 - 2.3744091e+00 1.9769318e+00 5.2047827e+00 - 2.3998460e+00 2.0046358e+00 5.4298385e+00 - 2.3562859e+00 1.9597527e+00 5.5031087e+00 - 2.2748355e+00 1.8732612e+00 5.4802439e+00 - 2.2106985e+00 1.8058170e+00 5.4983845e+00 - 2.1044305e+00 1.6939923e+00 5.3998274e+00 - 2.3320799e+00 1.9347511e+00 6.2421012e+00 - 2.3134720e+00 1.9157611e+00 6.4226742e+00 - 2.0622793e+00 1.6505687e+00 5.8876283e+00 - 1.9754736e+00 1.5599204e+00 5.8351647e+00 - 1.8897090e+00 1.4700707e+00 5.7798519e+00 - 1.8266181e+00 1.4034644e+00 5.7959423e+00 - 1.8448825e+00 1.4234051e+00 6.1184450e+00 - 1.9218346e+00 1.5051515e+00 6.7063683e+00 - 1.3777811e+00 9.3009104e-01 4.7271130e+00 - 1.3329054e+00 8.8273118e-01 4.7489499e+00 - 1.6601754e+00 1.2292547e+00 6.5486797e+00 - 1.7007599e+00 1.2735248e+00 7.1254598e+00 - 1.4568863e+00 1.0159348e+00 6.2275466e+00 - 1.1284422e+00 6.6888196e-01 4.6982837e+00 - 1.0671057e+00 6.0383226e-01 4.6065536e+00 - 1.0463182e+00 5.8246677e-01 4.7770446e+00 - 9.8384490e-01 5.1636901e-01 4.6628454e+00 - 9.2683412e-01 4.5683261e-01 4.5662109e+00 - 8.6421412e-01 3.9110961e-01 4.3988285e+00 - 8.8466687e-01 4.1328093e-01 5.0514150e+00 - 8.3329799e-01 3.6019224e-01 5.0308218e+00 - 7.8852250e-01 3.1260224e-01 5.0885137e+00 - 7.8022395e-01 3.0447994e-01 5.7828214e+00 - 7.2248809e-01 2.4409187e-01 5.7892604e+00 - 6.6960226e-01 1.8928188e-01 5.9541902e+00 - 6.1197613e-01 1.2822344e-01 6.0078198e+00 - 5.5085017e-01 6.4339619e-02 5.9599851e+00 - 1.9116506e+00 1.3957908e+00 -1.0160058e+00 - 1.9564016e+00 1.4395749e+00 -1.0090302e+00 - 2.0065347e+00 1.4897941e+00 -1.0073113e+00 - 2.0629898e+00 1.5454056e+00 -1.0105032e+00 - 2.1195187e+00 1.6021225e+00 -1.0115473e+00 - 2.1823130e+00 1.6632644e+00 -1.0168532e+00 - 2.2399280e+00 1.7211395e+00 -1.0134556e+00 - 2.2984951e+00 1.7780705e+00 -1.0077144e+00 - 2.3731467e+00 1.8532949e+00 -1.0179935e+00 - 2.4434382e+00 1.9222159e+00 -1.0191238e+00 - 2.5148657e+00 1.9932083e+00 -1.0175598e+00 - 2.5979481e+00 2.0751199e+00 -1.0243159e+00 - 2.6821105e+00 2.1581404e+00 -1.0276291e+00 - 2.7673535e+00 2.2422748e+00 -1.0273994e+00 - 2.8653799e+00 2.3393406e+00 -1.0339941e+00 - 2.9634316e+00 2.4366084e+00 -1.0364938e+00 - 3.0688907e+00 2.5404219e+00 -1.0395624e+00 - 3.1744385e+00 2.6454590e+00 -1.0380862e+00 - 3.3001654e+00 2.7698795e+00 -1.0459008e+00 - 3.4269859e+00 2.8955174e+00 -1.0480752e+00 - 3.5867708e+00 3.0534851e+00 -1.0660652e+00 - 3.7221704e+00 3.1880258e+00 -1.0603213e+00 - 3.8840975e+00 3.3475543e+00 -1.0644843e+00 - 4.0737448e+00 3.5351094e+00 -1.0765087e+00 - 4.2708942e+00 3.7304829e+00 -1.0835584e+00 - 4.4765484e+00 3.9336491e+00 -1.0849375e+00 - 4.6961035e+00 4.1511562e+00 -1.0836054e+00 - 4.9497450e+00 4.4024369e+00 -1.0878544e+00 - 5.2267565e+00 4.6755197e+00 -1.0892179e+00 - 5.5315466e+00 4.9770971e+00 -1.0889546e+00 - 5.8853745e+00 5.3276615e+00 -1.0929123e+00 - 6.2892599e+00 5.7273250e+00 -1.0975985e+00 - 6.7358286e+00 6.1698078e+00 -1.0970509e+00 - 7.2740108e+00 6.7027208e+00 -1.1031317e+00 - 7.9059042e+00 7.3272701e+00 -1.1092048e+00 - 8.6720784e+00 8.0849407e+00 -1.1192692e+00 - 9.6716383e+00 9.0744118e+00 -1.1465139e+00 - 1.1137822e+01 1.0525792e+01 -1.2221522e+00 - 1.2587168e+01 1.1959862e+01 -1.2225411e+00 - 1.6060439e+01 1.5395738e+01 -1.4734404e+00 - 2.2327096e+01 2.1597477e+01 -1.3882138e+00 - 2.5666856e+01 2.4903077e+01 -1.1329473e+00 - 2.3849158e+01 2.3105182e+01 -4.0396420e-01 - 2.5795798e+01 2.5031832e+01 1.0073589e-01 - 2.5802294e+01 2.5040248e+01 7.2194744e-01 - 2.5816143e+01 2.5054256e+01 1.3435386e+00 - 2.5835412e+01 2.5075010e+01 1.9661652e+00 - 2.5847217e+01 2.5088246e+01 2.5899097e+00 - 2.5866386e+01 2.5107163e+01 3.2158315e+00 - 2.5898404e+01 2.5139534e+01 3.8455159e+00 - 2.5900653e+01 2.5143581e+01 4.4745786e+00 - 2.5910273e+01 2.5153364e+01 5.1069172e+00 - 2.5939173e+01 2.5183383e+01 5.7460484e+00 - 2.5945717e+01 2.5191669e+01 6.3848878e+00 - 2.5958645e+01 2.5205844e+01 7.0289040e+00 - 2.5984326e+01 2.5231677e+01 7.6807770e+00 - 2.5995131e+01 2.5243411e+01 8.3336375e+00 - 2.5989937e+01 2.5239079e+01 8.9868887e+00 - 2.6030699e+01 2.5281154e+01 9.6609959e+00 - 2.6043612e+01 2.5293659e+01 1.0331928e+01 - 2.6066305e+01 2.5318174e+01 1.1014222e+01 - 2.6081490e+01 2.5334313e+01 1.1700479e+01 - 2.6065759e+01 2.5319957e+01 1.2381423e+01 - 1.3371238e+01 1.2750775e+01 8.1563267e+00 - 1.3030773e+01 1.2413645e+01 8.3257442e+00 - 4.2147753e+00 3.6831883e+00 4.2135511e+00 - 4.1564624e+00 3.6262256e+00 4.2882091e+00 - 4.0146572e+00 3.4851083e+00 4.2836302e+00 - 3.9552502e+00 3.4269234e+00 4.3525481e+00 - 3.9193265e+00 3.3914470e+00 4.4427286e+00 - 4.9765746e+00 4.4400660e+00 5.6756685e+00 - 5.0135822e+00 4.4775001e+00 5.8885586e+00 - 4.0191442e+00 3.4909654e+00 4.9518381e+00 - 3.9533118e+00 3.4260462e+00 5.0187249e+00 - 3.7623111e+00 3.2377753e+00 4.9339735e+00 - 3.9736167e+00 3.4467350e+00 5.3385749e+00 - 3.5427191e+00 3.0194585e+00 4.9364863e+00 - 3.4318345e+00 2.9093793e+00 4.9279828e+00 - 3.9185499e+00 3.3929344e+00 5.7431641e+00 - 3.7146044e+00 3.1914744e+00 5.6194943e+00 - 3.2716074e+00 2.7512740e+00 5.1243022e+00 - 2.8799711e+00 2.3630650e+00 4.6679799e+00 - 2.6640172e+00 2.1499243e+00 4.4561509e+00 - 2.6397565e+00 2.1254312e+00 4.5393098e+00 - 2.9157324e+00 2.3993933e+00 5.1396514e+00 - 2.6696174e+00 2.1553089e+00 4.8538416e+00 - 2.5736363e+00 2.0610919e+00 4.8193326e+00 - 2.4839748e+00 1.9717335e+00 4.7893509e+00 - 2.4201254e+00 1.9091656e+00 4.8050464e+00 - 2.4935697e+00 1.9815331e+00 5.0990910e+00 - 2.5005700e+00 1.9887361e+00 5.2727071e+00 - 2.4625410e+00 1.9519945e+00 5.3550532e+00 - 2.7563897e+00 2.2432830e+00 6.2046385e+00 - 2.8345993e+00 2.3226151e+00 6.6042407e+00 - 2.4268195e+00 1.9168869e+00 5.8161719e+00 - 2.5834287e+00 2.0721263e+00 6.4256098e+00 - 2.2636637e+00 1.7550622e+00 5.7928216e+00 - 2.1912297e+00 1.6835471e+00 5.7997001e+00 - 2.1005107e+00 1.5942903e+00 5.7502959e+00 - 2.0442101e+00 1.5388821e+00 5.7981318e+00 - 1.9846684e+00 1.4801373e+00 5.8354391e+00 - 1.9380470e+00 1.4338704e+00 5.9175072e+00 - 1.7996619e+00 1.2956710e+00 5.6730676e+00 - 1.9938714e+00 1.4894702e+00 6.6600396e+00 - 1.4470225e+00 9.4514887e-01 4.7913234e+00 - 1.3765211e+00 8.7661424e-01 4.7192457e+00 - 1.3393480e+00 8.3867410e-01 4.7785172e+00 - 1.7997722e+00 1.2985728e+00 7.2250381e+00 - 1.6103631e+00 1.1107717e+00 6.6874953e+00 - 1.1565589e+00 6.5791700e-01 4.6127451e+00 - 1.0999423e+00 6.0256198e-01 4.5603567e+00 - 1.0846298e+00 5.8734225e-01 4.7602475e+00 - 1.0257601e+00 5.2902541e-01 4.6858919e+00 - 9.7341425e-01 4.7719788e-01 4.6491226e+00 - 9.2653682e-01 4.3094778e-01 4.6504920e+00 - 8.8288962e-01 3.8743154e-01 4.6704296e+00 - 8.7029576e-01 3.7528451e-01 5.0363570e+00 - 8.2022612e-01 3.2557281e-01 5.0449254e+00 - 8.1746589e-01 3.2461785e-01 5.7690827e+00 - 7.6576897e-01 2.7385031e-01 5.9158836e+00 - 7.0160947e-01 2.1035159e-01 5.8519287e+00 - 6.4067895e-01 1.4957688e-01 5.8063424e+00 - 5.8235573e-01 9.2016326e-02 5.8891399e+00 - 5.2159455e-01 3.1563268e-02 5.8905947e+00 - 1.9797768e+00 1.3794592e+00 -1.0196257e+00 - 2.0212784e+00 1.4188094e+00 -1.0049020e+00 - 2.0786044e+00 1.4723124e+00 -1.0090966e+00 - 2.1369416e+00 1.5258584e+00 -1.0111969e+00 - 2.2006658e+00 1.5858789e+00 -1.0177549e+00 - 2.2538372e+00 1.6362665e+00 -1.0089543e+00 - 2.3133343e+00 1.6920761e+00 -1.0044652e+00 - 2.3854734e+00 1.7586556e+00 -1.0100971e+00 - 2.4629474e+00 1.8307767e+00 -1.0188387e+00 - 2.5361813e+00 1.8985835e+00 -1.0186306e+00 - 2.6148121e+00 1.9729435e+00 -1.0212822e+00 - 2.6954590e+00 2.0473403e+00 -1.0207441e+00 - 2.7878862e+00 2.1346895e+00 -1.0278261e+00 - 2.8823332e+00 2.2221051e+00 -1.0311192e+00 - 2.9831852e+00 2.3160923e+00 -1.0356771e+00 - 3.0777424e+00 2.4049039e+00 -1.0309297e+00 - 3.1934080e+00 2.5119726e+00 -1.0368251e+00 - 3.3155481e+00 2.6266838e+00 -1.0425367e+00 - 3.4451037e+00 2.7480047e+00 -1.0475187e+00 - 3.5894619e+00 2.8823185e+00 -1.0556360e+00 - 3.7285308e+00 3.0114553e+00 -1.0532527e+00 - 3.8877980e+00 3.1601284e+00 -1.0570640e+00 - 4.0682710e+00 3.3283511e+00 -1.0655751e+00 - 4.2562424e+00 3.5043628e+00 -1.0697107e+00 - 4.4601014e+00 3.6945157e+00 -1.0727396e+00 - 4.6714073e+00 3.8915295e+00 -1.0699452e+00 - 4.9113970e+00 4.1157195e+00 -1.0707711e+00 - 5.1874762e+00 4.3736164e+00 -1.0760856e+00 - 5.4996610e+00 4.6653484e+00 -1.0832920e+00 - 5.8277801e+00 4.9715960e+00 -1.0818011e+00 - 6.2068203e+00 5.3247749e+00 -1.0832399e+00 - 6.6443205e+00 5.7335135e+00 -1.0864787e+00 - 7.1549802e+00 6.2089486e+00 -1.0917569e+00 - 7.7305549e+00 6.7469140e+00 -1.0920099e+00 - 8.3592101e+00 7.3335095e+00 -1.0785691e+00 - 9.3137407e+00 8.2250121e+00 -1.1135191e+00 - 1.0459292e+01 9.2927835e+00 -1.1437252e+00 - 1.2215336e+01 1.0932451e+01 -1.2361476e+00 - 1.6533710e+01 1.4962321e+01 -1.2836709e+00 - 1.9487922e+01 1.7719627e+01 -1.2471844e+00 - 2.4007231e+01 2.1936790e+01 -1.2175788e+00 - 2.6053858e+01 2.3848133e+01 -7.9844650e-01 - 2.6116446e+01 2.3906683e+01 -1.9016669e-01 - 2.6134528e+01 2.3924951e+01 4.2137607e-01 - 2.6173848e+01 2.3963026e+01 1.0334127e+00 - 2.6198235e+01 2.3986035e+01 1.6470857e+00 - 2.6192978e+01 2.3982752e+01 2.2608368e+00 - 2.6245043e+01 2.4032419e+01 2.8794318e+00 - 2.6260990e+01 2.4048158e+01 3.4980211e+00 - 2.6297144e+01 2.4082978e+01 4.1214517e+00 - 2.6325842e+01 2.4110353e+01 4.7474982e+00 - 2.6346084e+01 2.4130325e+01 5.3757643e+00 - 2.6386551e+01 2.4169527e+01 6.0118680e+00 - 2.6419565e+01 2.4201313e+01 6.6511870e+00 - 2.6436648e+01 2.4218085e+01 7.2919457e+00 - 2.6473970e+01 2.4254204e+01 7.9429390e+00 - 2.6487936e+01 2.4268634e+01 8.5933442e+00 - 2.6522091e+01 2.4301499e+01 9.2557315e+00 - 2.6540254e+01 2.4318351e+01 9.9196080e+00 - 2.6605331e+01 2.4380711e+01 1.0607583e+01 - 2.6598056e+01 2.4374278e+01 1.1276570e+01 - 2.6664306e+01 2.4438496e+01 1.1983169e+01 - 2.6637956e+01 2.4414499e+01 1.2659048e+01 - 4.1948329e+00 3.4554901e+00 4.1690372e+00 - 4.2090783e+00 3.4684572e+00 4.3059795e+00 - 4.1967272e+00 3.4569179e+00 4.4220673e+00 - 4.0800827e+00 3.3495482e+00 4.4408995e+00 - 4.0059532e+00 3.2805583e+00 4.4965241e+00 - 4.1885942e+00 3.4508490e+00 4.8148008e+00 - 4.0355723e+00 3.3074716e+00 4.7914793e+00 - 3.8964139e+00 3.1776204e+00 4.7746139e+00 - 3.8692416e+00 3.1534546e+00 4.8810032e+00 - 3.7364249e+00 3.0291535e+00 4.8624231e+00 - 3.6324292e+00 2.9326080e+00 4.8722329e+00 - 3.5347440e+00 2.8408472e+00 4.8850718e+00 - 3.5010152e+00 2.8083837e+00 4.9779937e+00 - 3.9134428e+00 3.1958110e+00 5.6860368e+00 - 3.7112403e+00 3.0064314e+00 5.5653648e+00 - 3.3691675e+00 2.6861522e+00 5.2242323e+00 - 2.7334952e+00 2.0921344e+00 4.4071092e+00 - 2.7189170e+00 2.0778403e+00 4.5054246e+00 - 3.5310681e+00 2.8393658e+00 5.9607942e+00 - 2.6643452e+00 2.0282099e+00 4.6716112e+00 - 2.6124932e+00 1.9803287e+00 4.7148432e+00 - 2.5734258e+00 1.9438414e+00 4.7808631e+00 - 2.4862831e+00 1.8626629e+00 4.7570704e+00 - 2.7187345e+00 2.0798630e+00 5.3531717e+00 - 3.0133967e+00 2.3559060e+00 6.1189997e+00 - 3.2889751e+00 2.6137976e+00 6.9000584e+00 - 2.8542811e+00 2.2068976e+00 6.1767932e+00 - 2.7501593e+00 2.1103753e+00 6.1465532e+00 - 2.3707712e+00 1.7548457e+00 5.4544546e+00 - 2.4261006e+00 1.8077365e+00 5.7786075e+00 - 2.7621454e+00 2.1224790e+00 6.8486490e+00 - 2.3032356e+00 1.6932068e+00 5.8678176e+00 - 2.1709965e+00 1.5690940e+00 5.7124560e+00 - 2.1192279e+00 1.5213638e+00 5.7790088e+00 - 2.1232141e+00 1.5249817e+00 6.0181009e+00 - 2.1530634e+00 1.5532185e+00 6.3601476e+00 - 1.8584947e+00 1.2768912e+00 5.6290758e+00 - 1.7862292e+00 1.2093016e+00 5.6142330e+00 - 1.9873097e+00 1.3991710e+00 6.6313935e+00 - 1.4263026e+00 8.7206270e-01 4.7083496e+00 - 1.3764365e+00 8.2552416e-01 4.7204648e+00 - 1.8272000e+00 1.2510718e+00 6.9888179e+00 - 1.6827498e+00 1.1146906e+00 6.6928626e+00 - 1.1803213e+00 6.4224039e-01 4.5078415e+00 - 1.1650723e+00 6.2907544e-01 4.6886071e+00 - 1.1238768e+00 5.9114062e-01 4.7430973e+00 - 1.0717268e+00 5.4139392e-01 4.7282513e+00 - 1.0229256e+00 4.9636021e-01 4.7315750e+00 - 9.5115293e-01 4.2879815e-01 4.5564301e+00 - 9.0115319e-01 3.8222370e-01 4.5272970e+00 - 8.8413613e-01 3.6739375e-01 4.8136858e+00 - 8.2646773e-01 3.1321788e-01 4.7231988e+00 - 8.0539981e-01 2.9403875e-01 5.0786120e+00 - 7.9616330e-01 2.8697385e-01 5.7728733e+00 - 7.3106792e-01 2.2558052e-01 5.6895966e+00 - 6.7524208e-01 1.7396596e-01 5.8143375e+00 - 6.1610771e-01 1.1899186e-01 5.9078258e+00 - 5.5466156e-01 6.1102029e-02 5.9600211e+00 - 1.9958466e+00 1.3141298e+00 -1.0229102e+00 - 2.0382813e+00 1.3523832e+00 -1.0089392e+00 - 2.0859162e+00 1.3940709e+00 -1.0002760e+00 - 2.1567454e+00 1.4561565e+00 -1.0171924e+00 - 2.2107146e+00 1.5033352e+00 -1.0114424e+00 - 2.2710684e+00 1.5569229e+00 -1.0102531e+00 - 2.3324340e+00 1.6105585e+00 -1.0068698e+00 - 2.3991289e+00 1.6696913e+00 -1.0074951e+00 - 2.4731519e+00 1.7342201e+00 -1.0117358e+00 - 2.5535688e+00 1.8052319e+00 -1.0190392e+00 - 2.6286872e+00 1.8709928e+00 -1.0173401e+00 - 2.7228354e+00 1.9539575e+00 -1.0298233e+00 - 2.8053692e+00 2.0263281e+00 -1.0273947e+00 - 2.8953007e+00 2.1051656e+00 -1.0271329e+00 - 2.9979548e+00 2.1959327e+00 -1.0337458e+00 - 3.0963098e+00 2.2813983e+00 -1.0311597e+00 - 3.2137763e+00 2.3852370e+00 -1.0393098e+00 - 3.3259481e+00 2.4838544e+00 -1.0378582e+00 - 3.4518547e+00 2.5944542e+00 -1.0409872e+00 - 3.5999444e+00 2.7243758e+00 -1.0522150e+00 - 3.7480728e+00 2.8546077e+00 -1.0571505e+00 - 3.8909716e+00 2.9806547e+00 -1.0517348e+00 - 4.0751103e+00 3.1434440e+00 -1.0642057e+00 - 4.2686829e+00 3.3128994e+00 -1.0723577e+00 - 4.4559773e+00 3.4773122e+00 -1.0685079e+00 - 4.6792702e+00 3.6741887e+00 -1.0740910e+00 - 4.9110126e+00 3.8779003e+00 -1.0731549e+00 - 5.1797743e+00 4.1141973e+00 -1.0779595e+00 - 5.4791782e+00 4.3767300e+00 -1.0827456e+00 - 5.8082981e+00 4.6666492e+00 -1.0856619e+00 - 6.1606909e+00 4.9765638e+00 -1.0817983e+00 - 6.5722851e+00 5.3378616e+00 -1.0821365e+00 - 7.0516822e+00 5.7601420e+00 -1.0849001e+00 - 7.6273230e+00 6.2665735e+00 -1.0939107e+00 - 8.2357753e+00 6.8010181e+00 -1.0846813e+00 - 9.1034509e+00 7.5647752e+00 -1.1112918e+00 - 1.0107582e+01 8.4471880e+00 -1.1275767e+00 - 1.1619502e+01 9.7767171e+00 -1.1976868e+00 - 1.3218336e+01 1.1181993e+01 -1.2122962e+00 - 1.6528730e+01 1.4092701e+01 -1.4102525e+00 - 2.2541853e+01 1.9381117e+01 -1.2808112e+00 - 2.8215058e+01 2.4369654e+01 -5.7488900e-01 - 2.8260741e+01 2.4411904e+01 6.8341190e-02 - 2.8306313e+01 2.4452238e+01 7.1326851e-01 - 2.8327606e+01 2.4472055e+01 1.3598584e+00 - 2.8347848e+01 2.4490994e+01 2.0076996e+00 - 2.8368038e+01 2.4509005e+01 2.6569886e+00 - 2.8415843e+01 2.4552648e+01 3.3106499e+00 - 2.8448777e+01 2.4582242e+01 3.9662976e+00 - 2.8472256e+01 2.4604488e+01 4.6240681e+00 - 2.8502054e+01 2.4631587e+01 5.2862660e+00 - 2.8575271e+01 2.4696767e+01 5.9601345e+00 - 2.8564849e+01 2.4688260e+01 6.6239366e+00 - 2.8596852e+01 2.4717937e+01 7.3003115e+00 - 2.8627768e+01 2.4745927e+01 7.9817824e+00 - 2.8678868e+01 2.4792317e+01 8.6745363e+00 - 2.8683348e+01 2.4797082e+01 9.3611207e+00 - 2.8729173e+01 2.4838403e+01 1.0066573e+01 - 2.8765498e+01 2.4871503e+01 1.0776694e+01 - 2.8813486e+01 2.4914552e+01 1.1499368e+01 - 2.8829752e+01 2.4930257e+01 1.2218581e+01 - 4.3320320e+00 3.3768846e+00 4.3889353e+00 - 4.2189124e+00 3.2776985e+00 4.4152518e+00 - 4.1492433e+00 3.2158149e+00 4.4780075e+00 - 4.1454235e+00 3.2122801e+00 4.6040607e+00 - 4.0917300e+00 3.1652422e+00 4.6822056e+00 - 4.0189766e+00 3.1023066e+00 4.7402263e+00 - 3.9524809e+00 3.0432178e+00 4.8025243e+00 - 4.0210282e+00 3.1049907e+00 5.0187249e+00 - 3.9513511e+00 3.0430431e+00 5.0801823e+00 - 3.6765727e+00 2.8003976e+00 4.8893956e+00 - 3.6356390e+00 2.7650707e+00 4.9764958e+00 - 3.5351190e+00 2.6763146e+00 4.9857998e+00 - 3.8758881e+00 2.9777090e+00 5.5911967e+00 - 3.8253984e+00 2.9331932e+00 5.6836151e+00 - 3.4600926e+00 2.6110738e+00 5.3175858e+00 - 3.4180619e+00 2.5739860e+00 5.4082840e+00 - 3.3835324e+00 2.5441927e+00 5.5135946e+00 - 3.6671761e+00 2.7947184e+00 6.1360709e+00 - 3.4219531e+00 2.5786927e+00 5.9113486e+00 - 2.6869249e+00 1.9304919e+00 4.8116590e+00 - 2.6416391e+00 1.8909872e+00 4.8699564e+00 - 2.5857213e+00 1.8422474e+00 4.9111532e+00 - 3.8699906e+00 2.9754507e+00 7.5567686e+00 - 3.7674473e+00 2.8845372e+00 7.6009344e+00 - 3.0531414e+00 2.2551183e+00 6.3594167e+00 - 2.7937402e+00 2.0266624e+00 6.0086388e+00 - 2.4809188e+00 1.7515038e+00 5.5008975e+00 - 2.4334766e+00 1.7087776e+00 5.5724833e+00 - 2.4159806e+00 1.6932142e+00 5.7224428e+00 - 2.4434173e+00 1.7182464e+00 5.9970792e+00 - 2.2572755e+00 1.5541905e+00 5.7192667e+00 - 2.1949993e+00 1.4997676e+00 5.7594815e+00 - 2.1605045e+00 1.4697360e+00 5.8802227e+00 - 2.0725336e+00 1.3920392e+00 5.8447492e+00 - 1.9171449e+00 1.2551057e+00 5.5849331e+00 - 1.8762152e+00 1.2192943e+00 5.6824701e+00 - 2.0420616e+00 1.3657023e+00 6.5290787e+00 - 1.4781366e+00 8.6783859e-01 4.7065359e+00 - 1.4273368e+00 8.2239194e-01 4.7193039e+00 - 1.3798839e+00 7.8164349e-01 4.7499418e+00 - 1.9010253e+00 1.2434936e+00 7.3498815e+00 - 1.5883224e+00 9.6713324e-01 6.2731969e+00 - 1.2200695e+00 6.4076020e-01 4.7483661e+00 - 1.1714688e+00 5.9836087e-01 4.7645746e+00 - 1.0979705e+00 5.3308254e-01 4.6332819e+00 - 1.0525896e+00 4.9333332e-01 4.6663608e+00 - 1.0115584e+00 4.5774221e-01 4.7278431e+00 - 9.6616663e-01 4.1739017e-01 4.7689617e+00 - 9.0669570e-01 3.6591539e-01 4.6902673e+00 - 8.5686962e-01 3.2124442e-01 4.6794620e+00 - 8.0933724e-01 2.7986042e-01 4.6972158e+00 - 8.3628013e-01 3.0442730e-01 5.7691615e+00 - 7.7840618e-01 2.5406714e-01 5.8561067e+00 - 7.1155532e-01 1.9523519e-01 5.8020506e+00 - 6.4924132e-01 1.4102588e-01 5.8263355e+00 - 5.8685785e-01 8.5745712e-02 5.8491718e+00 - 5.2346839e-01 2.9947814e-02 5.8805503e+00 - 2.0637909e+00 1.2947975e+00 -1.0265811e+00 - 2.1071088e+00 1.3310409e+00 -1.0116154e+00 - 2.1682463e+00 1.3813063e+00 -1.0157739e+00 - 2.2294575e+00 1.4326771e+00 -1.0177846e+00 - 2.2906221e+00 1.4831593e+00 -1.0175485e+00 - 2.3476042e+00 1.5303043e+00 -1.0088118e+00 - 2.4161670e+00 1.5872583e+00 -1.0106427e+00 - 2.4910598e+00 1.6496687e+00 -1.0160860e+00 - 2.5669685e+00 1.7121615e+00 -1.0186360e+00 - 2.6502688e+00 1.7810719e+00 -1.0243516e+00 - 2.7273325e+00 1.8457889e+00 -1.0211112e+00 - 2.8179880e+00 1.9203121e+00 -1.0260477e+00 - 2.9160417e+00 2.0013071e+00 -1.0330513e+00 - 3.0214979e+00 2.0888083e+00 -1.0414227e+00 - 3.1143988e+00 2.1667483e+00 -1.0354280e+00 - 3.2282828e+00 2.2609122e+00 -1.0407759e+00 - 3.3358733e+00 2.3499102e+00 -1.0366188e+00 - 3.4792205e+00 2.4678933e+00 -1.0516338e+00 - 3.6016345e+00 2.5700517e+00 -1.0472161e+00 - 3.7471681e+00 2.6904646e+00 -1.0510505e+00 - 3.9137753e+00 2.8283396e+00 -1.0613832e+00 - 4.0814835e+00 2.9674911e+00 -1.0648771e+00 - 4.2650066e+00 3.1196883e+00 -1.0692122e+00 - 4.4843382e+00 3.3012843e+00 -1.0843298e+00 - 4.6921250e+00 3.4733573e+00 -1.0830869e+00 - 4.9073562e+00 3.6522715e+00 -1.0764203e+00 - 5.1604760e+00 3.8616480e+00 -1.0767967e+00 - 5.4663434e+00 4.1154468e+00 -1.0880003e+00 - 5.7732916e+00 4.3698454e+00 -1.0858235e+00 - 6.1329574e+00 4.6679108e+00 -1.0895304e+00 - 6.5326902e+00 4.9988041e+00 -1.0903981e+00 - 6.9926366e+00 5.3811335e+00 -1.0931736e+00 - 7.5378888e+00 5.8323263e+00 -1.1001729e+00 - 8.1380716e+00 6.3298276e+00 -1.0975805e+00 - 8.8974934e+00 6.9594877e+00 -1.1081973e+00 - 9.8730742e+00 7.7679541e+00 -1.1333740e+00 - 1.1215624e+01 8.8807130e+00 -1.1895430e+00 - 1.2821905e+01 1.0211921e+01 -1.2322839e+00 - 1.9943989e+01 1.6115440e+01 -1.1833834e+00 - 3.0532541e+01 2.4892400e+01 -1.0045611e+00 - 3.0601253e+01 2.4949080e+01 -3.2553969e-01 - 3.0636347e+01 2.4979859e+01 3.5656888e-01 - 3.0701969e+01 2.5034934e+01 1.0398937e+00 - 3.0711732e+01 2.5044317e+01 1.7249162e+00 - 3.0781623e+01 2.5103413e+01 2.4136232e+00 - 3.0788230e+01 2.5110145e+01 3.1019999e+00 - 3.0846513e+01 2.5159211e+01 3.7967801e+00 - 3.0858387e+01 2.5169903e+01 4.4905358e+00 - 3.0890350e+01 2.5197713e+01 5.1898311e+00 - 3.0935994e+01 2.5236039e+01 5.8953317e+00 - 3.0963773e+01 2.5260496e+01 6.6028281e+00 - 3.1005240e+01 2.5295534e+01 7.3178281e+00 - 3.1028842e+01 2.5316699e+01 8.0347241e+00 - 3.1072444e+01 2.5353234e+01 8.7622526e+00 - 3.1114027e+01 2.5389197e+01 9.4960295e+00 - 3.1152414e+01 2.5421665e+01 1.0236306e+01 - 3.1186669e+01 2.5451709e+01 1.0983336e+01 - 3.1240948e+01 2.5497329e+01 1.1745194e+01 - 3.1254085e+01 2.5509047e+01 1.2501468e+01 - 5.5722343e+00 4.2127397e+00 5.4584279e+00 - 4.3211080e+00 3.1747950e+00 4.4871802e+00 - 4.2865938e+00 3.1456390e+00 4.5851503e+00 - 4.2129836e+00 3.0849252e+00 4.6464709e+00 - 4.1573504e+00 3.0389757e+00 4.7239733e+00 - 3.8200796e+00 2.7585319e+00 4.5039981e+00 - 3.8015015e+00 2.7439063e+00 4.6109651e+00 - 4.0190455e+00 2.9250131e+00 4.9874656e+00 - 3.8278244e+00 2.7660113e+00 4.9060778e+00 - 4.0676890e+00 2.9654770e+00 5.3360021e+00 - 3.6825815e+00 2.6453433e+00 5.0060415e+00 - 3.6280311e+00 2.6010414e+00 5.0776488e+00 - 3.5405679e+00 2.5284325e+00 5.1047987e+00 - 4.3814962e+00 3.2263367e+00 6.4250588e+00 - 4.3027064e+00 3.1618371e+00 6.5048206e+00 - 4.2683676e+00 3.1330520e+00 6.6508306e+00 - 4.4833019e+00 3.3122583e+00 7.1877387e+00 - 3.4806978e+00 2.4793126e+00 5.7995448e+00 - 3.3964615e+00 2.4099271e+00 5.8349262e+00 - 2.6468639e+00 1.7867847e+00 4.7171695e+00 - 2.6282729e+00 1.7720557e+00 4.8220391e+00 - 2.5597306e+00 1.7147502e+00 4.8370035e+00 - 3.9714310e+00 2.8887750e+00 7.7121051e+00 - 2.5799358e+00 1.7325793e+00 5.1799235e+00 - 2.7068732e+00 1.8374906e+00 5.6085008e+00 - 2.5736146e+00 1.7269779e+00 5.5035376e+00 - 2.4285888e+00 1.6061966e+00 5.3593043e+00 - 2.4292353e+00 1.6072369e+00 5.5424750e+00 - 2.4576043e+00 1.6316814e+00 5.8064214e+00 - 2.3817247e+00 1.5689060e+00 5.8235030e+00 - 2.2898559e+00 1.4927238e+00 5.7935858e+00 - 2.2745773e+00 1.4793224e+00 5.9695573e+00 - 2.3414952e+00 1.5358969e+00 6.4020909e+00 - 2.2891508e+00 1.4931492e+00 6.5076499e+00 - 2.1834405e+00 1.4051655e+00 6.4454597e+00 - 2.4801173e+00 1.6533834e+00 7.7437028e+00 - 2.1513561e+00 1.3791381e+00 6.9322402e+00 - 1.4728249e+00 8.1361649e-01 4.6989306e+00 - 1.4254962e+00 7.7489151e-01 4.7300687e+00 - 1.9497924e+00 1.2124836e+00 7.2090349e+00 - 1.6426632e+00 9.5728341e-01 6.2217838e+00 - 1.5591266e+00 8.8700019e-01 6.1794092e+00 - 1.2157028e+00 6.0079424e-01 4.7663842e+00 - 1.1543967e+00 5.5021210e-01 4.7236015e+00 - 1.0800753e+00 4.8794075e-01 4.5912644e+00 - 1.0326325e+00 4.4830433e-01 4.6039253e+00 - 9.8636405e-01 4.1053063e-01 4.6353103e+00 - 9.3249331e-01 3.6620175e-01 4.6062906e+00 - 8.8397181e-01 3.2546624e-01 4.6157083e+00 - 8.3226470e-01 2.8338479e-01 4.5941737e+00 - 8.2663846e-01 2.7817965e-01 5.1284238e+00 - 8.1310308e-01 2.6839383e-01 5.7828966e+00 - 7.4643781e-01 2.1259216e-01 5.7294909e+00 - 6.8449516e-01 1.6238194e-01 5.7943265e+00 - 6.2130260e-01 1.0918886e-01 5.8379907e+00 - 5.5747560e-01 5.7415680e-02 5.9699977e+00 - 2.1210558e+00 1.2637892e+00 -1.0157932e+00 - 2.1715648e+00 1.3033017e+00 -1.0070405e+00 - 2.2398355e+00 1.3558589e+00 -1.0169630e+00 - 2.2966775e+00 1.4008524e+00 -1.0113232e+00 - 2.3597837e+00 1.4502611e+00 -1.0101450e+00 - 2.4354693e+00 1.5094231e+00 -1.0194378e+00 - 2.5069148e+00 1.5642708e+00 -1.0197809e+00 - 2.5721213e+00 1.6149053e+00 -1.0115675e+00 - 2.6562888e+00 1.6816776e+00 -1.0188851e+00 - 2.7414139e+00 1.7475502e+00 -1.0229603e+00 - 2.8276172e+00 1.8145169e+00 -1.0238922e+00 - 2.9274742e+00 1.8923015e+00 -1.0327510e+00 - 3.0210973e+00 1.9659125e+00 -1.0322542e+00 - 3.1293778e+00 2.0503252e+00 -1.0387886e+00 - 3.2324225e+00 2.1305038e+00 -1.0359706e+00 - 3.3627754e+00 2.2323232e+00 -1.0489066e+00 - 3.4742523e+00 2.3191989e+00 -1.0423659e+00 - 3.6203691e+00 2.4331410e+00 -1.0545955e+00 - 3.7539338e+00 2.5375464e+00 -1.0519595e+00 - 3.9105615e+00 2.6592390e+00 -1.0569267e+00 - 4.0819384e+00 2.7929816e+00 -1.0638810e+00 - 4.2617431e+00 2.9333868e+00 -1.0678118e+00 - 4.4636344e+00 3.0913120e+00 -1.0758470e+00 - 4.6759602e+00 3.2558626e+00 -1.0791671e+00 - 4.9105079e+00 3.4400453e+00 -1.0842936e+00 - 5.1387246e+00 3.6182476e+00 -1.0761701e+00 - 5.4362148e+00 3.8495002e+00 -1.0870108e+00 - 5.7422339e+00 4.0887375e+00 -1.0882856e+00 - 6.0807802e+00 4.3521695e+00 -1.0879510e+00 - 6.4656577e+00 4.6528446e+00 -1.0892389e+00 - 6.9062167e+00 4.9962446e+00 -1.0915764e+00 - 7.4246095e+00 5.4009310e+00 -1.0982184e+00 - 8.0218657e+00 5.8670944e+00 -1.1040745e+00 - 8.6454105e+00 6.3527253e+00 -1.0899270e+00 - 9.5875149e+00 7.0885838e+00 -1.1232302e+00 - 1.0704126e+01 7.9596015e+00 -1.1513618e+00 - 1.2409363e+01 9.2895325e+00 -1.2408074e+00 - 1.7023984e+01 1.2888446e+01 -1.3651198e+00 - 2.0107044e+01 1.5293979e+01 -1.3678451e+00 - 2.2612394e+01 1.7248496e+01 -1.1774501e+00 - 3.3143696e+01 2.5464810e+01 -7.6426418e-01 - 3.7781754e+01 2.9083049e+01 -1.8870996e-01 - 3.7609740e+01 2.8951693e+01 1.4598554e+00 - 3.1756979e+01 2.4385950e+01 2.0797456e+00 - 3.1736262e+01 2.4371427e+01 2.7714420e+00 - 3.7931611e+01 2.9205650e+01 3.9536351e+00 - 3.7837718e+01 2.9133881e+01 4.7769653e+00 - 3.7936314e+01 2.9212070e+01 5.6223480e+00 - 3.1851015e+01 2.4464621e+01 5.5730986e+00 - 3.1860790e+01 2.4473065e+01 6.2795937e+00 - 3.8012305e+01 2.9274530e+01 8.1621348e+00 - 3.6788271e+01 2.8320583e+01 8.7524077e+00 - 3.6744804e+01 2.8287666e+01 9.5711072e+00 - 3.1979011e+01 2.4569358e+01 9.1679833e+00 - 3.1984699e+01 2.4575223e+01 9.8983601e+00 - 5.5732418e+00 3.9658435e+00 5.4365586e+00 - 5.4725643e+00 3.8874767e+00 5.5134351e+00 - 4.3401397e+00 3.0025226e+00 4.6163095e+00 - 3.9650117e+00 2.7097029e+00 4.3838620e+00 - 3.8809782e+00 2.6434856e+00 4.4226904e+00 - 3.9120458e+00 2.6684786e+00 4.5798613e+00 - 4.3356840e+00 2.9991507e+00 5.1686844e+00 - 4.1124268e+00 2.8250369e+00 5.0672138e+00 - 4.3283143e+00 2.9942389e+00 5.4645368e+00 - 4.1061313e+00 2.8217038e+00 5.3557728e+00 - 4.2534468e+00 2.9369726e+00 5.6946035e+00 - 4.6025203e+00 3.2094026e+00 6.3125917e+00 - 4.7933590e+00 3.3594608e+00 6.7584721e+00 - 4.7031641e+00 3.2886178e+00 6.8380165e+00 - 4.5179273e+00 3.1444732e+00 6.7802890e+00 - 4.4732153e+00 3.1100695e+00 6.9217341e+00 - 4.3713525e+00 3.0297513e+00 6.9780886e+00 - 4.1859807e+00 2.8845277e+00 6.8984881e+00 - 4.2237913e+00 2.9151834e+00 7.1777891e+00 - 2.7437046e+00 1.7570446e+00 4.8621165e+00 - 2.7082735e+00 1.7301467e+00 4.9438609e+00 - 2.5785750e+00 1.6280983e+00 4.8520750e+00 - 2.6246570e+00 1.6651984e+00 5.0894558e+00 - 2.5468238e+00 1.6039170e+00 5.0938603e+00 - 2.6014265e+00 1.6473905e+00 5.3689211e+00 - 2.5331507e+00 1.5937606e+00 5.3976196e+00 - 2.4066160e+00 1.4949472e+00 5.2940403e+00 - 2.4517691e+00 1.5305981e+00 5.5818605e+00 - 2.4461329e+00 1.5270754e+00 5.7664965e+00 - 2.3735963e+00 1.4694828e+00 5.7910114e+00 - 2.2873657e+00 1.4028134e+00 5.7777112e+00 - 2.2796635e+00 1.3973076e+00 5.9804801e+00 - 2.1360112e+00 1.2846224e+00 5.7989936e+00 - 2.2792474e+00 1.3971629e+00 6.4816078e+00 - 2.4917995e+00 1.5639080e+00 7.4510781e+00 - 2.4440515e+00 1.5267750e+00 7.6348285e+00 - 1.5223023e+00 8.0405555e-01 4.6877829e+00 - 1.4687495e+00 7.6278299e-01 4.7004621e+00 - 1.9685726e+00 1.1555329e+00 6.9538101e+00 - 2.0446608e+00 1.2164510e+00 7.6665188e+00 - 1.6135309e+00 8.7765781e-01 6.1382833e+00 - 1.2308762e+00 5.7768329e-01 4.6225519e+00 - 1.2125135e+00 5.6271564e-01 4.8036259e+00 - 1.1482096e+00 5.1280436e-01 4.7505158e+00 - 1.0687714e+00 4.5034433e-01 4.5879823e+00 - 1.0248045e+00 4.1643580e-01 4.6393874e+00 - 9.7971399e-01 3.8055440e-01 4.6900957e+00 - 9.1412913e-01 3.2947540e-01 4.5715704e+00 - 8.6472620e-01 2.9076469e-01 4.5802929e+00 - 8.2633805e-01 2.6176814e-01 4.7171269e+00 - 8.5415662e-01 2.8478002e-01 5.7790314e+00 - 7.9016935e-01 2.3482055e-01 5.8262455e+00 - 7.2274534e-01 1.8202410e-01 5.7920201e+00 - 6.5892597e-01 1.3289056e-01 5.8762382e+00 - 5.9142305e-01 7.9463489e-02 5.8292286e+00 - 5.3460476e-01 3.7496324e-02 7.6605052e+00 - 2.1372613e+00 1.2010910e+00 -1.0265174e+00 - 2.1823943e+00 1.2342177e+00 -1.0115092e+00 - 2.2463449e+00 1.2813060e+00 -1.0156284e+00 - 2.3103086e+00 1.3284977e+00 -1.0176503e+00 - 2.3690326e+00 1.3714257e+00 -1.0109190e+00 - 2.4340209e+00 1.4187688e+00 -1.0086493e+00 - 2.5116500e+00 1.4768721e+00 -1.0167004e+00 - 2.5849782e+00 1.5296592e+00 -1.0158522e+00 - 2.6709521e+00 1.5932458e+00 -1.0245256e+00 - 2.7443743e+00 1.6473008e+00 -1.0182337e+00 - 2.8323815e+00 1.7110621e+00 -1.0209209e+00 - 2.9340425e+00 1.7856414e+00 -1.0315351e+00 - 3.0232109e+00 1.8516762e+00 -1.0274332e+00 - 3.1395528e+00 1.9372445e+00 -1.0412832e+00 - 3.2444009e+00 2.0142128e+00 -1.0403205e+00 - 3.3565925e+00 2.0967003e+00 -1.0404763e+00 - 3.4761307e+00 2.1847315e+00 -1.0412513e+00 - 3.6113388e+00 2.2836175e+00 -1.0467635e+00 - 3.7549605e+00 2.3890527e+00 -1.0515494e+00 - 3.9069387e+00 2.5000649e+00 -1.0550600e+00 - 4.0590135e+00 2.6123647e+00 -1.0527274e+00 - 4.2570750e+00 2.7570921e+00 -1.0685984e+00 - 4.4489174e+00 2.8977639e+00 -1.0727168e+00 - 4.6491937e+00 3.0451476e+00 -1.0728128e+00 - 4.8808902e+00 3.2154002e+00 -1.0791370e+00 - 5.1063737e+00 3.3816466e+00 -1.0727097e+00 - 5.3789523e+00 3.5816562e+00 -1.0764488e+00 - 5.6913119e+00 3.8101461e+00 -1.0844415e+00 - 6.0205333e+00 4.0520104e+00 -1.0853884e+00 - 6.3906206e+00 4.3235035e+00 -1.0863470e+00 - 6.8162586e+00 4.6356440e+00 -1.0899539e+00 - 7.2901946e+00 4.9841560e+00 -1.0901464e+00 - 7.8605207e+00 5.4027323e+00 -1.0972935e+00 - 8.4571218e+00 5.8406675e+00 -1.0866344e+00 - 9.2926747e+00 6.4541842e+00 -1.1075379e+00 - 1.0297041e+01 7.1918757e+00 -1.1292009e+00 - 1.1799184e+01 8.2940611e+00 -1.2041561e+00 - 1.3201047e+01 9.3241472e+00 -1.1967393e+00 - 2.0384167e+01 1.4596903e+01 -1.1310184e+00 - 4.1094722e+01 2.9803185e+01 -7.0445046e-01 - 4.1148952e+01 2.9845188e+01 1.0542149e+00 - 4.1213833e+01 2.9894122e+01 1.9359917e+00 - 4.1234620e+01 2.9909679e+01 2.8191864e+00 - 2.2681079e+01 1.6288277e+01 2.4722354e+00 - 2.2287311e+01 1.5999283e+01 2.9197529e+00 - 2.2063496e+01 1.5836575e+01 3.3700043e+00 - 4.0310677e+01 2.9239483e+01 8.8778743e+00 - 4.4994399e+01 3.2680934e+01 1.0795512e+01 - 4.7185930e+00 3.1038877e+00 4.8150274e+00 - 4.1374157e+00 2.6766027e+00 4.4117643e+00 - 3.9937370e+00 2.5712284e+00 4.3975240e+00 - 3.9194824e+00 2.5170118e+00 4.4475146e+00 - 4.1976684e+00 2.7214318e+00 4.8622398e+00 - 4.2160391e+00 2.7352163e+00 5.0206428e+00 - 4.4691418e+00 2.9217639e+00 5.4489199e+00 - 4.3886269e+00 2.8626476e+00 5.5138088e+00 - 4.3470870e+00 2.8325761e+00 5.6251839e+00 - 4.2360532e+00 2.7513042e+00 5.6512045e+00 - 4.9748166e+00 3.2948312e+00 6.7684498e+00 - 4.9586500e+00 3.2828862e+00 6.9524649e+00 - 4.8266403e+00 3.1859638e+00 6.9811893e+00 - 4.5091843e+00 2.9525056e+00 6.7417531e+00 - 4.4329607e+00 2.8965653e+00 6.8353945e+00 - 4.3346664e+00 2.8252945e+00 6.8964872e+00 - 3.4941322e+00 2.2063113e+00 5.7720781e+00 - 3.2859547e+00 2.0530776e+00 5.6045043e+00 - 2.7571549e+00 1.6643782e+00 4.8707096e+00 - 2.6658492e+00 1.5968220e+00 4.8535797e+00 - 2.6515928e+00 1.5866470e+00 4.9746182e+00 - 2.6964450e+00 1.6198936e+00 5.2136985e+00 - 2.6283591e+00 1.5693286e+00 5.2437466e+00 - 2.5466432e+00 1.5101991e+00 5.2463667e+00 - 2.5673118e+00 1.5257578e+00 5.4634405e+00 - 2.4337898e+00 1.4278816e+00 5.3500460e+00 - 2.4290852e+00 1.4237664e+00 5.5238921e+00 - 2.5407851e+00 1.5065364e+00 5.9930042e+00 - 2.3956017e+00 1.3997532e+00 5.8476810e+00 - 2.3413249e+00 1.3597003e+00 5.9243835e+00 - 2.2193666e+00 1.2704668e+00 5.8172996e+00 - 2.3674072e+00 1.3801840e+00 6.4893103e+00 - 2.3799875e+00 1.3892142e+00 6.8073802e+00 - 2.3810581e+00 1.3905494e+00 7.1180910e+00 - 1.5653699e+00 7.8891674e-01 4.6575259e+00 - 1.5108822e+00 7.4872622e-01 4.6706581e+00 - 2.0661864e+00 1.1590899e+00 7.0229183e+00 - 2.1005278e+00 1.1859194e+00 7.5439274e+00 - 1.6837453e+00 8.7771291e-01 6.1641796e+00 - 1.2418178e+00 5.5135524e-01 4.4693927e+00 - 1.2437438e+00 5.5252019e-01 4.7373539e+00 - 1.1603900e+00 4.9091781e-01 4.5873177e+00 - 1.1262023e+00 4.6643444e-01 4.6989724e+00 - 1.0427032e+00 4.0470254e-01 4.5057903e+00 - 1.0118027e+00 3.8289216e-01 4.6550395e+00 - 9.5499808e-01 3.4026064e-01 4.6162422e+00 - 8.9388782e-01 2.9485400e-01 4.5365577e+00 - 8.7735761e-01 2.8443030e-01 4.8920116e+00 - 8.4251923e-01 2.5865820e-01 5.1384000e+00 - 8.2898242e-01 2.4937666e-01 5.7828356e+00 - 7.6081096e-01 1.9915997e-01 5.7794257e+00 - 6.9375112e-01 1.4978935e-01 5.7943899e+00 - 6.2674429e-01 1.0084243e-01 5.8179436e+00 - 5.8269629e-01 7.0670041e-02 7.6598735e+00 - 2.1922883e+00 1.1662109e+00 -1.0156247e+00 - 2.2571099e+00 1.2111906e+00 -1.0207467e+00 - 2.3156951e+00 1.2519769e+00 -1.0169126e+00 - 2.3690395e+00 1.2884895e+00 -1.0045251e+00 - 2.4421475e+00 1.3379704e+00 -1.0099203e+00 - 2.5153306e+00 1.3885665e+00 -1.0129679e+00 - 2.5885296e+00 1.4392907e+00 -1.0134188e+00 - 2.6690569e+00 1.4954108e+00 -1.0174852e+00 - 2.7578532e+00 1.5558942e+00 -1.0246213e+00 - 2.8404733e+00 1.6131811e+00 -1.0228509e+00 - 2.9303669e+00 1.6749114e+00 -1.0237475e+00 - 3.0203405e+00 1.7377963e+00 -1.0214976e+00 - 3.1259064e+00 1.8104010e+00 -1.0267319e+00 - 3.2314957e+00 1.8831930e+00 -1.0281709e+00 - 3.3454267e+00 1.9614436e+00 -1.0307317e+00 - 3.4750227e+00 2.0505095e+00 -1.0388287e+00 - 3.6047084e+00 2.1408089e+00 -1.0421812e+00 - 3.7436831e+00 2.2355835e+00 -1.0451109e+00 - 3.8973964e+00 2.3423244e+00 -1.0517256e+00 - 4.0677907e+00 2.4599630e+00 -1.0609833e+00 - 4.2246346e+00 2.5681255e+00 -1.0553722e+00 - 4.4274074e+00 2.7077382e+00 -1.0675157e+00 - 4.6239610e+00 2.8432954e+00 -1.0679065e+00 - 4.8445422e+00 2.9952942e+00 -1.0715595e+00 - 5.0735052e+00 3.1530719e+00 -1.0698423e+00 - 5.3276286e+00 3.3293379e+00 -1.0691924e+00 - 5.6224027e+00 3.5319660e+00 -1.0739986e+00 - 5.9339711e+00 3.7469123e+00 -1.0729080e+00 - 6.2946659e+00 3.9957817e+00 -1.0762971e+00 - 6.6887812e+00 4.2669146e+00 -1.0754839e+00 - 7.1644525e+00 4.5948677e+00 -1.0835838e+00 - 7.6819764e+00 4.9517813e+00 -1.0837589e+00 - 8.2894454e+00 5.3713532e+00 -1.0862784e+00 - 8.9554255e+00 5.8300870e+00 -1.0773739e+00 - 9.9715260e+00 6.5309795e+00 -1.1188206e+00 - 1.1145564e+01 7.3412568e+00 -1.1489161e+00 - 1.2689562e+01 8.4051957e+00 -1.1958105e+00 - 1.4825291e+01 9.8783431e+00 -1.2710486e+00 - 1.7408580e+01 1.1659939e+01 -1.3168061e+00 - 2.0504290e+01 1.3794240e+01 -1.3123376e+00 - 2.2175924e+01 1.4947453e+01 -1.0426267e+00 - 4.5110283e+01 3.0764488e+01 -1.3061103e+00 - 4.5153204e+01 3.0794850e+01 -3.6050447e-01 - 4.5173143e+01 3.0809609e+01 5.8631329e-01 - 4.5172153e+01 3.0809601e+01 1.5334880e+00 - 2.1918711e+01 1.4773825e+01 1.7104089e+00 - 2.1444427e+01 1.4446650e+01 2.1394812e+00 - 2.1809908e+01 1.4699852e+01 2.6125368e+00 - 2.2580127e+01 1.5231287e+01 3.1412580e+00 - 2.2430144e+01 1.5129514e+01 3.5954569e+00 - 2.1473579e+01 1.4469787e+01 3.9320725e+00 - 2.1868420e+01 1.4742377e+01 4.4474441e+00 - 2.1197330e+01 1.4280200e+01 4.7868704e+00 - 2.2186497e+01 1.4963048e+01 5.4394348e+00 - 2.2070930e+01 1.4883972e+01 5.8875959e+00 - 4.8174822e+00 2.9841464e+00 4.4836083e+00 - 4.7811807e+00 2.9583288e+00 4.5860304e+00 - 4.7953157e+00 2.9688667e+00 4.7345072e+00 - 4.9919216e+00 3.1051429e+00 5.0513719e+00 - 4.0987417e+00 2.4870761e+00 4.3657835e+00 - 4.0110762e+00 2.4270774e+00 4.4042273e+00 - 4.6021163e+00 2.8352723e+00 5.1215575e+00 - 4.5050380e+00 2.7682607e+00 5.1689159e+00 - 4.3890656e+00 2.6882240e+00 5.1936046e+00 - 4.4189936e+00 2.7095687e+00 5.3768945e+00 - 4.2421335e+00 2.5874512e+00 5.3285417e+00 - 4.4725874e+00 2.7473437e+00 5.7580732e+00 - 4.3051996e+00 2.6321978e+00 5.7202314e+00 - 4.6890512e+00 2.8976420e+00 6.3812024e+00 - 4.6277523e+00 2.8556700e+00 6.4914842e+00 - 4.5590506e+00 2.8077058e+00 6.5932964e+00 - 4.5639581e+00 2.8116806e+00 6.8003257e+00 - 4.4375131e+00 2.7241989e+00 6.8239444e+00 - 2.8606855e+00 1.6336016e+00 4.6194777e+00 - 2.7928753e+00 1.5878193e+00 4.6451830e+00 - 2.8280358e+00 1.6123404e+00 4.8381962e+00 - 2.8589769e+00 1.6332288e+00 5.0337175e+00 - 2.6417875e+00 1.4834072e+00 4.8027530e+00 - 2.5960082e+00 1.4521209e+00 4.8643526e+00 - 2.7038350e+00 1.5265043e+00 5.2205625e+00 - 2.6601673e+00 1.4960184e+00 5.3008327e+00 - 2.6228945e+00 1.4709922e+00 5.3978151e+00 - 2.5550852e+00 1.4247007e+00 5.4334577e+00 - 2.5304240e+00 1.4076225e+00 5.5644127e+00 - 2.6691280e+00 1.5034151e+00 6.0861817e+00 - 2.4379881e+00 1.3440146e+00 5.7464409e+00 - 2.3554056e+00 1.2870282e+00 5.7507629e+00 - 2.3002418e+00 1.2489558e+00 5.8258714e+00 - 2.2081811e+00 1.1859817e+00 5.7991085e+00 - 2.3494010e+00 1.2832261e+00 6.4540547e+00 - 2.5257896e+00 1.4060889e+00 7.2837374e+00 - 1.6177147e+00 7.7661221e-01 4.6552065e+00 - 1.5560668e+00 7.3494629e-01 4.6501331e+00 - 1.5143907e+00 7.0533331e-01 4.7100229e+00 - 2.0321840e+00 1.0649587e+00 6.9443686e+00 - 2.1088481e+00 1.1193468e+00 7.6474836e+00 - 1.6742026e+00 8.1821716e-01 6.1865973e+00 - 1.5915036e+00 7.6029963e-01 6.1720427e+00 - 1.2226808e+00 5.0462800e-01 4.6966931e+00 - 1.1576785e+00 4.5975209e-01 4.6431387e+00 - 1.0840765e+00 4.0838636e-01 4.5292827e+00 - 1.0447070e+00 3.8216382e-01 4.6198290e+00 - 9.9344364e-01 3.4569108e-01 4.6309557e+00 - 9.6272147e-01 3.2479039e-01 4.8189067e+00 - 8.8036323e-01 2.6826398e-01 4.5703928e+00 - 8.7591623e-01 2.6650831e-01 5.0947535e+00 - 8.7857718e-01 2.6868997e-01 5.8886087e+00 - 8.0747699e-01 2.1969592e-01 5.8860577e+00 - 7.3399988e-01 1.6829712e-01 5.8120518e+00 - 6.6512209e-01 1.2150442e-01 5.8363117e+00 - 5.9505112e-01 7.3729463e-02 5.8191763e+00 - 5.3641838e-01 3.4883915e-02 7.6505104e+00 - 2.2524468e+00 1.1336991e+00 -1.0113886e+00 - 2.3243409e+00 1.1799688e+00 -1.0223249e+00 - 2.3848677e+00 1.2196815e+00 -1.0175488e+00 - 2.4464050e+00 1.2594323e+00 -1.0107782e+00 - 2.5203981e+00 1.3069180e+00 -1.0148789e+00 - 2.5954651e+00 1.3554633e+00 -1.0165355e+00 - 2.6642937e+00 1.3998004e+00 -1.0095356e+00 - 2.7539567e+00 1.4581408e+00 -1.0183735e+00 - 2.8373839e+00 1.5122926e+00 -1.0181555e+00 - 2.9290821e+00 1.5708224e+00 -1.0207076e+00 - 3.0136046e+00 1.6262064e+00 -1.0145498e+00 - 3.1272313e+00 1.6999617e+00 -1.0271996e+00 - 3.2346239e+00 1.7695434e+00 -1.0304939e+00 - 3.3440978e+00 1.8401981e+00 -1.0298490e+00 - 3.4598569e+00 1.9154355e+00 -1.0302699e+00 - 3.5922188e+00 2.0004308e+00 -1.0361808e+00 - 3.7402523e+00 2.0962956e+00 -1.0465292e+00 - 3.8747945e+00 2.1836714e+00 -1.0422582e+00 - 4.0322154e+00 2.2853138e+00 -1.0460410e+00 - 4.2063775e+00 2.3988509e+00 -1.0525164e+00 - 4.3971082e+00 2.5213558e+00 -1.0602373e+00 - 4.5973269e+00 2.6514746e+00 -1.0646878e+00 - 4.8058585e+00 2.7863065e+00 -1.0651168e+00 - 5.0394202e+00 2.9375539e+00 -1.0681120e+00 - 5.2823631e+00 3.0945297e+00 -1.0655404e+00 - 5.5659493e+00 3.2778083e+00 -1.0696235e+00 - 5.8662640e+00 3.4723640e+00 -1.0686590e+00 - 6.2009726e+00 3.6889257e+00 -1.0674906e+00 - 6.5857537e+00 3.9384170e+00 -1.0694570e+00 - 7.0205662e+00 4.2199938e+00 -1.0714127e+00 - 7.5230940e+00 4.5445326e+00 -1.0752047e+00 - 8.1007602e+00 4.9187024e+00 -1.0789051e+00 - 8.6879049e+00 5.2993790e+00 -1.0612581e+00 - 9.5740862e+00 5.8724351e+00 -1.0879875e+00 - 1.0645863e+01 6.5655981e+00 -1.1163806e+00 - 1.2134682e+01 7.5297997e+00 -1.1785398e+00 - 1.3702872e+01 8.5448027e+00 -1.1917308e+00 - 1.9828397e+01 1.2509116e+01 -9.8765552e-01 - 2.2568190e+01 1.4282437e+01 -8.0789203e-01 - 4.5604769e+01 2.9193248e+01 -8.1524271e-01 - 4.5616246e+01 2.9201063e+01 1.2285855e-01 - 4.5654946e+01 2.9228297e+01 1.0609352e+00 - 2.3093217e+01 1.4625256e+01 1.5007287e+00 - 2.2109297e+01 1.3988768e+01 1.9285806e+00 - 2.1421500e+01 1.3544967e+01 2.3348871e+00 - 2.1306165e+01 1.3470844e+01 2.7618766e+00 - 2.1410889e+01 1.3538866e+01 3.2083304e+00 - 2.3044884e+01 1.4596685e+01 3.8540369e+00 - 2.1758141e+01 1.3764763e+01 4.1391082e+00 - 2.1758588e+01 1.3765031e+01 4.5890472e+00 - 2.2125337e+01 1.4003529e+01 5.1108795e+00 - 2.2863531e+01 1.4481176e+01 5.7293588e+00 - 2.3919160e+01 1.5165722e+01 6.4565217e+00 - 2.3909361e+01 1.5159315e+01 6.9615207e+00 - 5.1070851e+00 2.9875913e+00 4.4407002e+00 - 4.9469952e+00 2.8840896e+00 4.5854650e+00 - 4.9693990e+00 2.8984716e+00 4.7406096e+00 - 5.1581535e+00 3.0215602e+00 5.0449570e+00 - 5.0582205e+00 2.9563625e+00 5.1051595e+00 - 4.0660898e+00 2.3137405e+00 4.3299804e+00 - 4.0037309e+00 2.2733977e+00 4.3910277e+00 - 3.8827463e+00 2.1945239e+00 4.3926615e+00 - 3.8005472e+00 2.1421493e+00 4.4296944e+00 - 4.4037492e+00 2.5332520e+00 5.2013587e+00 - 4.3048084e+00 2.4689778e+00 5.2409842e+00 - 4.2059105e+00 2.4055626e+00 5.2777635e+00 - 4.8712074e+00 2.8367470e+00 6.2249868e+00 - 4.5325520e+00 2.6168827e+00 5.9911184e+00 - 4.9039293e+00 2.8586708e+00 6.6453234e+00 - 4.5683873e+00 2.6411234e+00 6.4013091e+00 - 4.6926532e+00 2.7218927e+00 6.7647119e+00 - 3.5507620e+00 1.9809515e+00 5.5044017e+00 - 3.4737973e+00 1.9317681e+00 5.5514574e+00 - 2.8621197e+00 1.5346517e+00 4.7494041e+00 - 2.9496243e+00 1.5916033e+00 5.0329084e+00 - 2.7466586e+00 1.4597324e+00 4.8373154e+00 - 2.7220141e+00 1.4443346e+00 4.9415546e+00 - 2.7687397e+00 1.4754468e+00 5.1803282e+00 - 2.7965123e+00 1.4925466e+00 5.3966813e+00 - 2.7184512e+00 1.4431544e+00 5.4180223e+00 - 2.6822941e+00 1.4195228e+00 5.5242405e+00 - 2.6282851e+00 1.3841886e+00 5.5953020e+00 - 2.5964067e+00 1.3641486e+00 5.7184377e+00 - 2.5382151e+00 1.3259915e+00 5.7881624e+00 - 2.5705171e+00 1.3476549e+00 6.0816579e+00 - 2.4598112e+00 1.2757075e+00 6.0333255e+00 - 2.2975178e+00 1.1703711e+00 5.8357721e+00 - 2.4289176e+00 1.2568320e+00 6.4434518e+00 - 2.3455568e+00 1.2021790e+00 6.4735955e+00 - 1.6636504e+00 7.5873474e-01 4.6338778e+00 - 1.6011291e+00 7.1915767e-01 4.6294076e+00 - 1.5532885e+00 6.8798913e-01 4.6706891e+00 - 2.1189158e+00 1.0562519e+00 6.9755013e+00 - 2.1794060e+00 1.0962743e+00 7.5919168e+00 - 1.9545695e+00 9.5036920e-01 7.0873690e+00 - 1.6638395e+00 7.6123396e-01 6.2182076e+00 - 1.2242163e+00 4.7443599e-01 4.4947220e+00 - 1.1933883e+00 4.5526843e-01 4.6165066e+00 - 1.4144828e+00 5.9967905e-01 6.1762526e+00 - 1.1221995e+00 4.0844563e-01 4.8593519e+00 - 1.0264705e+00 3.4645730e-01 4.6057833e+00 - 1.1745542e+00 4.4422692e-01 6.1474550e+00 - 9.2553497e-01 2.8128556e-01 4.6652898e+00 - 9.1342837e-01 2.7406385e-01 5.0905448e+00 - 8.5939899e-01 2.3856708e-01 5.1583103e+00 - 8.4610735e-01 2.3176052e-01 5.8326593e+00 - 7.7512329e-01 1.8472590e-01 5.8293101e+00 - 7.0313038e-01 1.3818211e-01 5.8144287e+00 - 6.3212495e-01 9.2008248e-02 5.7880087e+00 - 5.8638745e-01 6.4924406e-02 7.6698461e+00 - 2.2582873e+00 1.0649322e+00 -1.0155418e+00 - 2.3248638e+00 1.1057983e+00 -1.0205718e+00 - 2.3862013e+00 1.1424055e+00 -1.0167488e+00 - 2.4486096e+00 1.1800478e+00 -1.0109810e+00 - 2.5235327e+00 1.2264120e+00 -1.0163338e+00 - 2.5994091e+00 1.2718419e+00 -1.0191432e+00 - 2.6763594e+00 1.3183316e+00 -1.0195085e+00 - 2.7533859e+00 1.3659462e+00 -1.0173266e+00 - 2.8458726e+00 1.4211932e+00 -1.0244274e+00 - 2.9311849e+00 1.4733041e+00 -1.0226185e+00 - 3.0247682e+00 1.5297931e+00 -1.0235797e+00 - 3.1183712e+00 1.5864397e+00 -1.0213449e+00 - 3.2275666e+00 1.6528061e+00 -1.0265942e+00 - 3.3450423e+00 1.7236244e+00 -1.0331156e+00 - 3.4563429e+00 1.7912560e+00 -1.0305306e+00 - 3.5904455e+00 1.8720244e+00 -1.0386466e+00 - 3.7173780e+00 1.9496912e+00 -1.0371538e+00 - 3.8691781e+00 2.0414446e+00 -1.0449197e+00 - 4.0137511e+00 2.1291241e+00 -1.0425278e+00 - 4.1905254e+00 2.2363306e+00 -1.0521113e+00 - 4.3683994e+00 2.3448037e+00 -1.0550557e+00 - 4.5711658e+00 2.4675605e+00 -1.0632638e+00 - 4.7833029e+00 2.5959619e+00 -1.0676031e+00 - 5.0048138e+00 2.7300325e+00 -1.0675740e+00 - 5.2429700e+00 2.8742010e+00 -1.0661433e+00 - 5.5154336e+00 3.0391666e+00 -1.0687537e+00 - 5.8212173e+00 3.2250785e+00 -1.0736043e+00 - 6.1373404e+00 3.4158240e+00 -1.0695458e+00 - 6.5034660e+00 3.6384233e+00 -1.0701707e+00 - 6.9204901e+00 3.8909700e+00 -1.0723868e+00 - 7.4144902e+00 4.1907273e+00 -1.0806108e+00 - 7.9521573e+00 4.5163235e+00 -1.0809673e+00 - 8.5491817e+00 4.8787760e+00 -1.0748977e+00 - 9.3343201e+00 5.3542561e+00 -1.0887810e+00 - 1.0280636e+01 5.9271884e+00 -1.1054627e+00 - 1.1609618e+01 6.7330085e+00 -1.1580216e+00 - 1.3120687e+01 7.6493379e+00 -1.1876193e+00 - 1.5364763e+01 9.0093883e+00 -1.2674591e+00 - 1.7826445e+01 1.0501865e+01 -1.2841869e+00 - 2.0020200e+01 1.1831429e+01 -1.1707761e+00 - 2.0577820e+01 1.2170258e+01 -8.2007459e-01 - 5.0250328e+01 3.0154862e+01 -1.4724704e+00 - 5.0330757e+01 3.0205424e+01 -4.5830649e-01 - 5.0464164e+01 3.0286991e+01 5.5790580e-01 - 2.2269589e+01 1.3197188e+01 1.2521571e+00 - 2.2228433e+01 1.3172547e+01 1.6952713e+00 - 2.2478598e+01 1.3325607e+01 2.1525522e+00 - 2.2389591e+01 1.3271776e+01 2.5960000e+00 - 2.1962464e+01 1.3012979e+01 3.0050881e+00 - 2.2533086e+01 1.3359776e+01 3.5117092e+00 - 2.2100770e+01 1.3098671e+01 3.9084278e+00 - 2.2503867e+01 1.3342422e+01 4.4186630e+00 - 2.3048677e+01 1.3674088e+01 4.9729474e+00 - 2.3247965e+01 1.3794788e+01 5.4842028e+00 - 2.2798917e+01 1.3522886e+01 5.8653373e+00 - 2.4659162e+01 1.4652341e+01 7.2989915e+00 - 2.4012381e+01 1.4260815e+01 7.6363846e+00 - 5.2250582e+00 2.8700139e+00 4.3980129e+00 - 5.1087130e+00 2.7991612e+00 4.4455796e+00 - 5.0642847e+00 2.7716658e+00 4.5447304e+00 - 5.0178552e+00 2.7442518e+00 4.6430886e+00 - 4.1213799e+00 2.2002491e+00 4.0309621e+00 - 4.1509745e+00 2.2184143e+00 4.1700563e+00 - 4.0762041e+00 2.1722388e+00 4.2197535e+00 - 4.1141764e+00 2.1956343e+00 4.3733562e+00 - 4.7156281e+00 2.5614046e+00 5.0771957e+00 - 3.9073806e+00 2.0707623e+00 4.4148344e+00 - 3.8170271e+00 2.0164881e+00 4.4441015e+00 - 4.3507663e+00 2.3398350e+00 5.1404393e+00 - 4.2886332e+00 2.3023286e+00 5.2184665e+00 - 4.4019196e+00 2.3716031e+00 5.4987007e+00 - 3.8375466e+00 2.0290932e+00 4.9850212e+00 - 3.7126656e+00 1.9527772e+00 4.9728359e+00 - 4.6218858e+00 2.5053643e+00 6.2777153e+00 - 4.6831469e+00 2.5432081e+00 6.5485072e+00 - 3.6573015e+00 1.9209264e+00 5.4957915e+00 - 3.5951289e+00 1.8831047e+00 5.5674265e+00 - 3.2099109e+00 1.6486883e+00 5.1456303e+00 - 2.9803541e+00 1.5086431e+00 4.9348853e+00 - 2.7518768e+00 1.3707351e+00 4.7079083e+00 - 2.7450140e+00 1.3664782e+00 4.8359182e+00 - 2.6963636e+00 1.3373919e+00 4.8979277e+00 - 2.8904610e+00 1.4552547e+00 5.4063513e+00 - 2.8596612e+00 1.4368279e+00 5.5228928e+00 - 2.8090168e+00 1.4068490e+00 5.6048831e+00 - 2.8535872e+00 1.4332021e+00 5.8865574e+00 - 2.6992521e+00 1.3398442e+00 5.7580499e+00 - 2.6863416e+00 1.3323873e+00 5.9354157e+00 - 2.7153589e+00 1.3498501e+00 6.2211288e+00 - 2.5714333e+00 1.2624015e+00 6.1030789e+00 - 2.5124719e+00 1.2271609e+00 6.1901861e+00 - 2.6109185e+00 1.2870559e+00 6.7076665e+00 - 2.4281277e+00 1.1760814e+00 6.4726710e+00 - 1.7031181e+00 7.3429724e-01 4.5937890e+00 - 1.6428348e+00 6.9807788e-01 4.5990516e+00 - 1.5972937e+00 6.7127386e-01 4.6502160e+00 - 2.1831855e+00 1.0285721e+00 6.9205009e+00 - 2.0896246e+00 9.7174642e-01 6.9348951e+00 - 1.9834142e+00 9.0718624e-01 6.8993868e+00 - 1.8719587e+00 8.4037944e-01 6.8324829e+00 - 1.6980454e+00 7.3420284e-01 6.4626299e+00 - 1.2299137e+00 4.4771867e-01 4.5897204e+00 - 1.4957274e+00 6.1111881e-01 6.3033448e+00 - 1.1102097e+00 3.7568295e-01 4.5488570e+00 - 1.0646694e+00 3.4836972e-01 4.6099587e+00 - 1.2428451e+00 4.5766310e-01 6.2586091e+00 - 1.0281394e+00 3.2648569e-01 5.1948836e+00 - 9.5293581e-01 2.8097449e-01 5.0959674e+00 - 8.9267494e-01 2.4441836e-01 5.1146630e+00 - 8.8661400e-01 2.4068204e-01 5.7990286e+00 - 8.1599987e-01 1.9815079e-01 5.8261928e+00 - 7.4207353e-01 1.5377775e-01 5.7920927e+00 - 6.7032004e-01 1.1017873e-01 5.7963884e+00 - 5.9980352e-01 6.7911770e-02 5.8491706e+00 - 5.3829510e-01 3.2259898e-02 7.6605404e+00 - 2.3162074e+00 1.0285436e+00 -1.0113009e+00 - 2.3909140e+00 1.0716312e+00 -1.0222979e+00 - 2.4469457e+00 1.1029285e+00 -1.0106709e+00 - 2.5102366e+00 1.1385558e+00 -1.0040081e+00 - 2.5870411e+00 1.1828495e+00 -1.0083693e+00 - 2.6710521e+00 1.2305355e+00 -1.0164465e+00 - 2.7570767e+00 1.2782385e+00 -1.0217336e+00 - 2.8359865e+00 1.3237975e+00 -1.0182604e+00 - 2.9292993e+00 1.3760621e+00 -1.0238175e+00 - 3.0237505e+00 1.4304179e+00 -1.0262808e+00 - 3.1191588e+00 1.4838690e+00 -1.0256016e+00 - 3.2301587e+00 1.5470349e+00 -1.0325064e+00 - 3.3339247e+00 1.6060728e+00 -1.0303522e+00 - 3.4614846e+00 1.6781376e+00 -1.0399008e+00 - 3.5756120e+00 1.7427005e+00 -1.0350793e+00 - 3.7042839e+00 1.8161305e+00 -1.0359915e+00 - 3.8577621e+00 1.9026403e+00 -1.0463125e+00 - 4.0050714e+00 1.9860127e+00 -1.0465285e+00 - 4.1606745e+00 2.0739454e+00 -1.0458192e+00 - 4.3484827e+00 2.1814347e+00 -1.0564859e+00 - 4.5548577e+00 2.2977857e+00 -1.0681049e+00 - 4.7540134e+00 2.4101268e+00 -1.0682677e+00 - 4.9532749e+00 2.5238295e+00 -1.0610892e+00 - 5.2042966e+00 2.6658112e+00 -1.0678402e+00 - 5.4553762e+00 2.8082559e+00 -1.0652027e+00 - 5.7407059e+00 2.9705256e+00 -1.0660575e+00 - 6.0695052e+00 3.1560244e+00 -1.0714303e+00 - 6.4160421e+00 3.3528285e+00 -1.0699610e+00 - 6.8071317e+00 3.5739954e+00 -1.0690673e+00 - 7.2740048e+00 3.8393342e+00 -1.0762271e+00 - 7.7771990e+00 4.1249731e+00 -1.0748003e+00 - 8.3840403e+00 4.4681848e+00 -1.0806580e+00 - 9.0273061e+00 4.8330385e+00 -1.0709873e+00 - 9.9889026e+00 5.3780419e+00 -1.1063102e+00 - 1.1022186e+01 5.9640507e+00 -1.1174654e+00 - 1.2676611e+01 6.9012156e+00 -1.1994381e+00 - 1.4250460e+01 7.7940359e+00 -1.2019312e+00 - 1.7227418e+01 9.4801986e+00 -1.3372244e+00 - 2.0107360e+01 1.1112536e+01 -1.3414060e+00 - 2.0572359e+01 1.1377719e+01 -9.9070509e-01 - 2.1155560e+01 1.1708402e+01 -6.3154957e-01 - 2.2825693e+01 1.2657291e+01 1.4789075e+00 - 2.2520027e+01 1.2483752e+01 1.9144790e+00 - 2.2692792e+01 1.2583117e+01 2.3678777e+00 - 2.3553533e+01 1.3071407e+01 2.8852524e+00 - 2.3486611e+01 1.3034052e+01 3.3439711e+00 - 2.2513566e+01 1.2482147e+01 3.6906887e+00 - 2.2106162e+01 1.2252281e+01 4.0802058e+00 - 2.8209964e+01 1.5713576e+01 6.0846179e+00 - 2.6244586e+01 1.4599990e+01 6.2552087e+00 - 2.5913088e+01 1.4412182e+01 6.7153729e+00 - 2.5796527e+01 1.4346908e+01 7.2180273e+00 - 2.5705927e+01 1.4296425e+01 7.7269007e+00 - 2.4883191e+01 1.3830326e+01 8.0251044e+00 - 2.5259827e+01 1.4043955e+01 8.6640454e+00 - 2.5105827e+01 1.3956972e+01 9.1485779e+00 - 2.7331487e+01 1.5220351e+01 1.0471645e+01 - 2.2774371e+01 1.2639427e+01 1.2439623e+01 - 2.2162691e+01 1.2293184e+01 1.3185873e+01 - 2.3989836e+01 1.3331160e+01 1.5402704e+01 - 2.2702728e+01 1.2601997e+01 1.5191803e+01 - 2.2732710e+01 1.2618405e+01 1.5800561e+01 - 5.3772181e+00 2.7696924e+00 4.3807961e+00 - 5.3110857e+00 2.7318595e+00 4.4675748e+00 - 5.1555475e+00 2.6439299e+00 4.4871900e+00 - 5.1164438e+00 2.6213781e+00 4.5913706e+00 - 5.0680750e+00 2.5950574e+00 4.6891862e+00 - 4.2657378e+00 2.1393968e+00 4.2736695e+00 - 4.1266841e+00 2.0602792e+00 4.2686185e+00 - 4.1104458e+00 2.0513715e+00 4.3723855e+00 - 4.1451945e+00 2.0710542e+00 4.5280936e+00 - 3.9791308e+00 1.9778365e+00 4.4890618e+00 - 3.9972246e+00 1.9878616e+00 4.6320327e+00 - 3.9164202e+00 1.9416891e+00 4.6744580e+00 - 3.9533283e+00 1.9630706e+00 4.8467896e+00 - 3.7038156e+00 1.8211989e+00 4.6961317e+00 - 3.7261119e+00 1.8336904e+00 4.8534729e+00 - 3.6370490e+00 1.7842716e+00 4.8810908e+00 - 4.5419261e+00 2.2986273e+00 6.1783711e+00 - 4.4112077e+00 2.2238860e+00 6.1907747e+00 - 4.3492760e+00 2.1885047e+00 6.2916240e+00 - 3.6723910e+00 1.8048711e+00 5.5201462e+00 - 3.3413512e+00 1.6162088e+00 5.1967832e+00 - 3.1729537e+00 1.5209312e+00 5.0932878e+00 - 3.0900186e+00 1.4738056e+00 5.1139464e+00 - 2.9924603e+00 1.4182154e+00 5.1079793e+00 - 3.0023967e+00 1.4242549e+00 5.2819350e+00 - 2.9559945e+00 1.3980909e+00 5.3651127e+00 - 2.8845232e+00 1.3572625e+00 5.4053145e+00 - 3.0052191e+00 1.4263940e+00 5.8127670e+00 - 2.8230896e+00 1.3227674e+00 5.6456892e+00 - 2.7819478e+00 1.2994873e+00 5.7529220e+00 - 2.9414775e+00 1.3903461e+00 6.3016389e+00 - 2.7342336e+00 1.2727236e+00 6.0646192e+00 - 2.6074662e+00 1.2015333e+00 5.9918183e+00 - 2.5537931e+00 1.1704315e+00 6.0879001e+00 - 2.4761528e+00 1.1269799e+00 6.1283694e+00 - 2.4718053e+00 1.1252031e+00 6.3698816e+00 - 1.7446382e+00 7.1018717e-01 4.5627826e+00 - 1.6897671e+00 6.7961105e-01 4.5872575e+00 - 1.6390006e+00 6.5020393e-01 4.6200597e+00 - 2.1895701e+00 9.6488362e-01 6.6760978e+00 - 2.1403232e+00 9.3700353e-01 6.8423801e+00 - 2.0764406e+00 9.0107456e-01 6.9702018e+00 - 2.0284236e+00 8.7498647e-01 7.1740345e+00 - 1.3150716e+00 4.6756508e-01 4.5274407e+00 - 1.2716690e+00 4.4229237e-01 4.5918329e+00 - 1.2093906e+00 4.0775109e-01 4.5678890e+00 - 1.1459842e+00 3.7171659e-01 4.5327119e+00 - 1.1301530e+00 3.6245178e-01 4.7710599e+00 - 1.2895896e+00 4.5450030e-01 6.2114185e+00 - 1.1948480e+00 4.0091872e-01 6.1080149e+00 - 9.8902087e-01 2.8310001e-01 5.0614977e+00 - 9.3000499e-01 2.4948732e-01 5.1005658e+00 - 8.8500082e-01 2.2387982e-01 5.2975478e+00 - 8.6311184e-01 2.1215047e-01 5.8825822e+00 - 7.8077190e-01 1.6587016e-01 5.7595182e+00 - 7.1038938e-01 1.2570549e-01 5.8143986e+00 - 6.3663157e-01 8.3710654e-02 5.7879897e+00 - 5.9014025e-01 5.9671445e-02 7.6898064e+00 - 2.3873841e+00 9.9670556e-01 -1.0204825e+00 - 2.4505367e+00 1.0301961e+00 -1.0166170e+00 - 2.5146992e+00 1.0637198e+00 -1.0108571e+00 - 2.5923144e+00 1.1049080e+00 -1.0161714e+00 - 2.6709433e+00 1.1461590e+00 -1.0189920e+00 - 2.7506459e+00 1.1884696e+00 -1.0193684e+00 - 2.8303646e+00 1.2309083e+00 -1.0171480e+00 - 2.9245447e+00 1.2810348e+00 -1.0243070e+00 - 3.0134865e+00 1.3269074e+00 -1.0225132e+00 - 3.1097620e+00 1.3782204e+00 -1.0234359e+00 - 3.2143109e+00 1.4339311e+00 -1.0267293e+00 - 3.3198802e+00 1.4897586e+00 -1.0264303e+00 - 3.4419227e+00 1.5532763e+00 -1.0330202e+00 - 3.5640519e+00 1.6180028e+00 -1.0353649e+00 - 3.7027226e+00 1.6914803e+00 -1.0433497e+00 - 3.8269626e+00 1.7575164e+00 -1.0369612e+00 - 3.9759480e+00 1.8356304e+00 -1.0400320e+00 - 4.1414872e+00 1.9225941e+00 -1.0467454e+00 - 4.3319076e+00 2.0237527e+00 -1.0605202e+00 - 4.4995804e+00 2.1122082e+00 -1.0548048e+00 - 4.7179296e+00 2.2278043e+00 -1.0670612e+00 - 4.9290627e+00 2.3394151e+00 -1.0673620e+00 - 5.1495069e+00 2.4556785e+00 -1.0636445e+00 - 5.4123923e+00 2.5949901e+00 -1.0693358e+00 - 5.6938703e+00 2.7433704e+00 -1.0717845e+00 - 5.9847399e+00 2.8975628e+00 -1.0669685e+00 - 6.3282893e+00 3.0783149e+00 -1.0691945e+00 - 6.7153888e+00 3.2834557e+00 -1.0726921e+00 - 7.1386612e+00 3.5066809e+00 -1.0719985e+00 - 7.6323282e+00 3.7675888e+00 -1.0752003e+00 - 8.2046289e+00 4.0697871e+00 -1.0804236e+00 - 8.8142183e+00 4.3914645e+00 -1.0722199e+00 - 9.6680176e+00 4.8432389e+00 -1.0961710e+00 - 1.0629452e+01 5.3512766e+00 -1.1085434e+00 - 1.2082241e+01 6.1178158e+00 -1.1753479e+00 - 1.3601501e+01 6.9207648e+00 -1.1956988e+00 - 1.5737458e+01 8.0490284e+00 -1.2471174e+00 - 1.8176817e+01 9.3377736e+00 -1.2528567e+00 - 2.0462333e+01 1.0545119e+01 -1.1458982e+00 - 2.0863061e+01 1.0757567e+01 -7.8398918e-01 - 2.1681800e+01 1.1189838e+01 -4.3570413e-01 - 2.2133354e+01 1.1429071e+01 -3.8184157e-02 - 2.2092351e+01 1.1407719e+01 3.9054940e-01 - 2.1692214e+01 1.1196468e+01 8.2035423e-01 - 2.6440405e+01 1.3707869e+01 3.8614013e+00 - 2.5487526e+01 1.3205233e+01 4.2552253e+00 - 2.8544836e+01 1.4820631e+01 5.2155745e+00 - 2.5545782e+01 1.3237072e+01 5.2693484e+00 - 2.5467722e+01 1.3196031e+01 5.7614586e+00 - 2.8389023e+01 1.4740560e+01 6.8864408e+00 - 2.7323103e+01 1.4178139e+01 7.2114223e+00 - 2.6179288e+01 1.3573320e+01 7.4766992e+00 - 2.7466660e+01 1.4254777e+01 8.3627816e+00 - 2.5741283e+01 1.3343288e+01 8.9558571e+00 - 2.2479343e+01 1.1619817e+01 8.3977902e+00 - 2.3179356e+01 1.1990746e+01 9.1233947e+00 - 2.2924038e+01 1.1856466e+01 9.5220761e+00 - 2.2214737e+01 1.1481458e+01 9.7323841e+00 - 2.6421178e+01 1.3706497e+01 1.2004231e+01 - 2.4348027e+01 1.2610202e+01 1.1665206e+01 - 2.4710605e+01 1.2802559e+01 1.2383780e+01 - 1.8940338e+01 9.7516428e+00 1.0101150e+01 - 1.8749013e+01 9.6515936e+00 1.0438875e+01 - 1.8902908e+01 9.7334832e+00 1.0961737e+01 - 2.1901083e+01 1.1319121e+01 1.3108180e+01 - 2.2039787e+01 1.1393470e+01 1.3723220e+01 - 2.2375537e+01 1.1571119e+01 1.4476527e+01 - 2.3410425e+01 1.2118376e+01 1.5705801e+01 - 2.2966460e+01 1.1884647e+01 1.6013533e+01 - 2.1518282e+01 1.1119627e+01 1.5611956e+01 - 5.2580386e+00 2.5190620e+00 4.4404524e+00 - 5.1899436e+00 2.4821350e+00 4.5228932e+00 - 5.1053732e+00 2.4385315e+00 4.5922483e+00 - 4.3672995e+00 2.0477163e+00 4.2477282e+00 - 4.2887897e+00 2.0058689e+00 4.2992375e+00 - 4.1957914e+00 1.9571501e+00 4.3361566e+00 - 4.9675849e+00 2.3657008e+00 5.1794102e+00 - 4.1436729e+00 1.9299176e+00 4.5321614e+00 - 4.0953031e+00 1.9046202e+00 4.6102022e+00 - 4.4166465e+00 2.0747194e+00 5.0730115e+00 - 3.9310015e+00 1.8174463e+00 4.6949144e+00 - 3.7911956e+00 1.7434496e+00 4.6708924e+00 - 3.8207650e+00 1.7598655e+00 4.8353041e+00 - 3.7848356e+00 1.7406324e+00 4.9293892e+00 - 4.1053949e+00 1.9104401e+00 5.4661089e+00 - 4.6443479e+00 2.1959846e+00 6.3163668e+00 - 3.8049972e+00 1.7514083e+00 5.3927055e+00 - 3.6859993e+00 1.6891415e+00 5.3878008e+00 - 3.5191161e+00 1.6010218e+00 5.3090740e+00 - 3.3022245e+00 1.4856409e+00 5.1457943e+00 - 3.0957434e+00 1.3766933e+00 4.9833345e+00 - 3.0441896e+00 1.3490316e+00 5.0502977e+00 - 3.0863403e+00 1.3716068e+00 5.2732006e+00 - 3.0098989e+00 1.3317623e+00 5.3069765e+00 - 3.0000574e+00 1.3267817e+00 5.4571678e+00 - 2.9173195e+00 1.2827799e+00 5.4803744e+00 - 2.9460949e+00 1.2988255e+00 5.7170984e+00 - 2.8560637e+00 1.2507369e+00 5.7299385e+00 - 2.7869196e+00 1.2144947e+00 5.7845177e+00 - 2.7938558e+00 1.2180906e+00 6.0065717e+00 - 2.8102487e+00 1.2269877e+00 6.2660523e+00 - 2.6107908e+00 1.1220306e+00 6.0309630e+00 - 2.5364462e+00 1.0828682e+00 6.0810125e+00 - 2.4370143e+00 1.0299267e+00 6.0655147e+00 - 1.7954938e+00 6.8989355e-01 4.5593647e+00 - 1.7312890e+00 6.5551576e-01 4.5565507e+00 - 1.6848757e+00 6.3081044e-01 4.6085181e+00 - 2.1637059e+00 8.8593077e-01 6.3477421e+00 - 2.2715166e+00 9.4316544e-01 7.0248928e+00 - 2.2046506e+00 9.0750650e-01 7.1545218e+00 - 2.0561479e+00 8.2985528e-01 6.9858550e+00 - 1.9714519e+00 7.8473255e-01 7.0446728e+00 - 1.3164165e+00 4.3615088e-01 4.6033738e+00 - 1.2858351e+00 4.2050134e-01 4.7356966e+00 - 1.1721087e+00 3.5987383e-01 4.4674538e+00 - 1.1119932e+00 3.2808920e-01 4.4410578e+00 - 1.3403252e+00 4.5005265e-01 6.1835905e+00 - 1.2554238e+00 4.0535078e-01 6.1698994e+00 - 1.0398717e+00 2.9121928e-01 5.1453877e+00 - 9.7032870e-01 2.5333680e-01 5.1059341e+00 - 9.0837464e-01 2.2138698e-01 5.1345254e+00 - 9.0355705e-01 2.2006518e-01 5.8488012e+00 - 8.2794963e-01 1.7936381e-01 5.8461694e+00 - 7.5008777e-01 1.3775223e-01 5.7821205e+00 - 6.7564212e-01 9.9329180e-02 5.7863777e+00 - 6.0343446e-01 6.1169181e-02 5.8591928e+00 - 5.4010954e-01 2.9138280e-02 7.6604830e+00 - 2.3861139e+00 9.2634325e-01 -1.0250137e+00 - 2.4440091e+00 9.5542717e-01 -1.0152915e+00 - 2.5152324e+00 9.9014721e-01 -1.0172436e+00 - 2.5803384e+00 1.0226579e+00 -1.0105384e+00 - 2.6525863e+00 1.0575293e+00 -1.0081990e+00 - 2.7330965e+00 1.0967098e+00 -1.0100279e+00 - 2.8280664e+00 1.1435633e+00 -1.0215360e+00 - 2.9168606e+00 1.1872252e+00 -1.0240376e+00 - 2.9984793e+00 1.2277412e+00 -1.0178292e+00 - 3.0965593e+00 1.2758538e+00 -1.0204075e+00 - 3.2018539e+00 1.3274225e+00 -1.0254035e+00 - 3.3082284e+00 1.3801003e+00 -1.0269565e+00 - 3.4238788e+00 1.4371498e+00 -1.0301842e+00 - 3.5477493e+00 1.4976542e+00 -1.0346342e+00 - 3.6644473e+00 1.5550374e+00 -1.0298750e+00 - 3.7976252e+00 1.6201648e+00 -1.0309060e+00 - 3.9483482e+00 1.6940272e+00 -1.0366813e+00 - 4.1073632e+00 1.7724352e+00 -1.0418310e+00 - 4.2756726e+00 1.8553627e+00 -1.0456590e+00 - 4.4542771e+00 1.9427690e+00 -1.0477690e+00 - 4.6659731e+00 2.0477464e+00 -1.0597609e+00 - 4.8714480e+00 2.1486536e+00 -1.0602998e+00 - 5.0862322e+00 2.2541985e+00 -1.0571200e+00 - 5.3443303e+00 2.3806979e+00 -1.0640521e+00 - 5.6200192e+00 2.5162969e+00 -1.0683376e+00 - 5.8978276e+00 2.6532744e+00 -1.0624917e+00 - 6.2199782e+00 2.8113874e+00 -1.0618669e+00 - 6.5690092e+00 2.9830801e+00 -1.0580729e+00 - 6.9882220e+00 3.1892084e+00 -1.0632192e+00 - 7.4538843e+00 3.4177521e+00 -1.0654526e+00 - 7.9722278e+00 3.6723512e+00 -1.0646908e+00 - 8.5896949e+00 3.9758811e+00 -1.0689570e+00 - 9.3145360e+00 4.3320381e+00 -1.0745796e+00 - 1.0279919e+01 4.8068992e+00 -1.1038627e+00 - 1.1363058e+01 5.3395707e+00 -1.1185018e+00 - 1.2964358e+01 6.1264064e+00 -1.1817175e+00 - 1.4516361e+01 6.8896098e+00 -1.1748785e+00 - 1.8085293e+01 8.6438242e+00 -1.3809614e+00 - 2.0467650e+01 9.8144311e+00 -1.3102347e+00 - 2.1126524e+01 1.0139018e+01 -9.8178317e-01 - 2.2147786e+01 1.0641170e+01 -6.5641786e-01 - 2.2035610e+01 1.0586010e+01 -2.2747967e-01 - 2.1647811e+01 1.0396299e+01 2.0669330e-01 - 6.4117493e+01 3.1273055e+01 1.0876024e+00 - 2.2320045e+01 1.0727678e+01 1.4549623e+00 - 2.7671967e+01 1.3359135e+01 2.0953114e+00 - 2.1889129e+01 1.0516822e+01 2.2791238e+00 - 2.7271683e+01 1.3163599e+01 3.1236811e+00 - 2.1012889e+01 1.0086431e+01 3.0289551e+00 - 2.9286352e+01 1.4154133e+01 4.4120483e+00 - 2.6289335e+01 1.2681717e+01 4.5652566e+00 - 2.0915742e+01 1.0040489e+01 4.2266947e+00 - 2.0428383e+01 9.8009337e+00 4.5460956e+00 - 2.1022808e+01 1.0093620e+01 5.0625480e+00 - 2.1590438e+01 1.0372887e+01 5.5993518e+00 - 2.5341060e+01 1.2218113e+01 6.9205485e+00 - 2.5664101e+01 1.2376418e+01 7.5113864e+00 - 2.0039302e+01 9.6115451e+00 6.4584838e+00 - 1.8382691e+01 8.7962908e+00 6.3670498e+00 - 1.8364310e+01 8.7876649e+00 6.7362435e+00 - 1.9506886e+01 9.3506918e+00 7.5055092e+00 - 1.9419301e+01 9.3074122e+00 7.8804439e+00 - 2.1810040e+01 1.0483970e+01 9.2112800e+00 - 2.2276896e+01 1.0714102e+01 9.8680739e+00 - 1.9354181e+01 9.2765079e+00 9.0967682e+00 - 1.9448716e+01 9.3240972e+00 9.5637167e+00 - 2.4562243e+01 1.1839518e+01 1.2423290e+01 - 1.8718292e+01 8.9651414e+00 1.0071331e+01 - 1.9028988e+01 9.1181455e+00 1.0661605e+01 - 1.8406721e+01 8.8128413e+00 1.0765611e+01 - 2.2613588e+01 1.0883117e+01 1.3597171e+01 - 2.2262588e+01 1.0710520e+01 1.3936056e+01 - 2.2510731e+01 1.0833794e+01 1.4639220e+01 - 2.1284305e+01 1.0230647e+01 1.4413919e+01 - 2.1624507e+01 1.0398017e+01 1.5187830e+01 - 5.4101839e+00 2.4181081e+00 4.4306760e+00 - 5.3102340e+00 2.3690650e+00 4.4929853e+00 - 5.2475239e+00 2.3380786e+00 4.5804064e+00 - 5.1828088e+00 2.3071442e+00 4.6664355e+00 - 4.3491515e+00 1.8971487e+00 4.2436531e+00 - 4.2625467e+00 1.8543938e+00 4.2872473e+00 - 4.1759278e+00 1.8115256e+00 4.3285442e+00 - 4.1234614e+00 1.7851232e+00 4.3995561e+00 - 4.1974721e+00 1.8224346e+00 4.5944019e+00 - 4.1812825e+00 1.8139161e+00 4.7060591e+00 - 4.2791644e+00 1.8628088e+00 4.9409365e+00 - 4.2174239e+00 1.8320495e+00 5.0139226e+00 - 4.1287613e+00 1.7884087e+00 5.0573729e+00 - 4.1012988e+00 1.7756344e+00 5.1706112e+00 - 4.0115576e+00 1.7308946e+00 5.2108183e+00 - 3.9094294e+00 1.6810331e+00 5.2338329e+00 - 3.7834135e+00 1.6189432e+00 5.2239566e+00 - 3.8202584e+00 1.6377558e+00 5.4252509e+00 - 3.7274168e+00 1.5918357e+00 5.4581262e+00 - 3.5744362e+00 1.5170384e+00 5.4019851e+00 - 3.6133269e+00 1.5356101e+00 5.6211007e+00 - 3.6139118e+00 1.5361577e+00 5.7942837e+00 - 3.0456522e+00 1.2564976e+00 5.0671684e+00 - 2.9610537e+00 1.2152480e+00 5.0829417e+00 - 2.9355950e+00 1.2024120e+00 5.1973722e+00 - 3.0359037e+00 1.2525611e+00 5.5412071e+00 - 2.9647871e+00 1.2171461e+00 5.5898504e+00 - 2.8427712e+00 1.1569349e+00 5.5419099e+00 - 2.7935288e+00 1.1332172e+00 5.6304913e+00 - 2.7244953e+00 1.0988901e+00 5.6833733e+00 - 2.9228217e+00 1.1969543e+00 6.3233085e+00 - 2.8820359e+00 1.1775502e+00 6.4685952e+00 - 2.7736009e+00 1.1244810e+00 6.4597674e+00 - 2.1527720e+00 8.1750955e-01 5.1596150e+00 - 2.5941556e+00 1.0363300e+00 6.5265991e+00 - 1.7904864e+00 6.3913352e-01 4.5814236e+00 - 1.7244026e+00 6.0684591e-01 4.5780175e+00 - 2.2456535e+00 8.6443641e-01 6.3781333e+00 - 2.3740177e+00 9.2775748e-01 7.1018149e+00 - 2.2812520e+00 8.8244339e-01 7.1469750e+00 - 2.1059110e+00 7.9618949e-01 6.8936931e+00 - 2.0162294e+00 7.5244162e-01 6.9337508e+00 - 1.3547510e+00 4.2492103e-01 4.5854686e+00 - 1.3074183e+00 4.0142091e-01 4.6403860e+00 - 1.2496772e+00 3.7356867e-01 4.6556330e+00 - 1.1498259e+00 3.2398048e-01 4.4447315e+00 - 1.1278211e+00 3.1411941e-01 4.6433981e+00 - 1.3115784e+00 4.0505323e-01 6.1917949e+00 - 1.2183807e+00 3.5886602e-01 6.1179539e+00 - 1.0116496e+00 2.5660184e-01 5.1209370e+00 - 9.4658180e-01 2.2439665e-01 5.1204242e+00 - 8.9764417e-01 2.0105125e-01 5.2975946e+00 - 8.7805917e-01 1.9165944e-01 5.9324611e+00 - 7.9084577e-01 1.4919798e-01 5.7794020e+00 - 7.1764982e-01 1.1272460e-01 5.8244057e+00 - 6.4107510e-01 7.5424669e-02 5.7679458e+00 - 5.9370872e-01 5.2945391e-02 7.6799036e+00 - 2.4354884e+00 8.8080377e-01 -1.0134602e+00 - 2.5004548e+00 9.1116778e-01 -1.0097521e+00 - 2.5735589e+00 9.4381242e-01 -1.0108124e+00 - 2.6466771e+00 9.7657038e-01 -1.0095756e+00 - 2.7270595e+00 1.0136978e+00 -1.0125040e+00 - 2.8012639e+00 1.0476140e+00 -1.0068254e+00 - 2.8908646e+00 1.0881359e+00 -1.0109793e+00 - 2.9887344e+00 1.1330211e+00 -1.0182030e+00 - 3.0794292e+00 1.1747653e+00 -1.0166168e+00 - 3.1783354e+00 1.2198955e+00 -1.0176513e+00 - 3.2864530e+00 1.2683659e+00 -1.0210101e+00 - 3.4028472e+00 1.3212588e+00 -1.0262400e+00 - 3.5192654e+00 1.3743437e+00 -1.0275747e+00 - 3.6377642e+00 1.4284969e+00 -1.0250702e+00 - 3.7644843e+00 1.4861149e+00 -1.0235883e+00 - 3.9159468e+00 1.5557862e+00 -1.0320651e+00 - 4.0776373e+00 1.6288851e+00 -1.0398730e+00 - 4.2311620e+00 1.6989626e+00 -1.0376693e+00 - 4.4278420e+00 1.7876953e+00 -1.0516708e+00 - 4.6009569e+00 1.8667761e+00 -1.0463276e+00 - 4.8245068e+00 1.9690047e+00 -1.0588578e+00 - 5.0336340e+00 2.0638558e+00 -1.0557163e+00 - 5.2685412e+00 2.1710151e+00 -1.0561445e+00 - 5.5302364e+00 2.2905010e+00 -1.0585477e+00 - 5.8197263e+00 2.4223219e+00 -1.0615306e+00 - 6.1020709e+00 2.5512383e+00 -1.0509096e+00 - 6.4553852e+00 2.7113026e+00 -1.0538774e+00 - 6.8448558e+00 2.8893183e+00 -1.0553508e+00 - 7.2713739e+00 3.0833395e+00 -1.0530364e+00 - 7.7699787e+00 3.3099130e+00 -1.0548754e+00 - 8.3417541e+00 3.5701774e+00 -1.0568254e+00 - 8.9599661e+00 3.8522396e+00 -1.0481226e+00 - 9.8561670e+00 4.2600442e+00 -1.0777759e+00 - 1.0836930e+01 4.7067462e+00 -1.0898452e+00 - 1.2295554e+01 5.3708656e+00 -1.1517337e+00 - 1.3759511e+01 6.0374123e+00 -1.1583064e+00 - 1.5921876e+01 7.0226939e+00 -1.2088424e+00 - 1.8495365e+01 8.1943774e+00 -1.2272570e+00 - 2.0802449e+01 9.2449961e+00 -1.1193088e+00 - 2.2184897e+01 9.8742751e+00 -8.4459593e-01 - 2.2475118e+01 1.0007898e+01 -2.3355513e-02 - 2.1951124e+01 9.7693449e+00 4.1296604e-01 - 2.1811352e+01 9.7060176e+00 8.2565675e-01 - 1.9754236e+01 8.7701789e+00 1.2118219e+00 - 1.9092892e+01 8.4684016e+00 1.5612981e+00 - 1.9072433e+01 8.4592462e+00 1.9173144e+00 - 1.9663101e+01 8.7292123e+00 2.3151630e+00 - 1.9403560e+01 8.6106528e+00 2.6617317e+00 - 1.9446074e+01 8.6314929e+00 3.0317993e+00 - 1.8905140e+01 8.3851294e+00 3.3307406e+00 - 1.9307267e+01 8.5681442e+00 3.7479594e+00 - 1.9322925e+01 8.5755917e+00 4.1186531e+00 - 1.8875720e+01 8.3721446e+00 4.4060881e+00 - 2.0957400e+01 9.3208417e+00 5.1964891e+00 - 2.0646380e+01 9.1798636e+00 5.5339685e+00 - 1.8670115e+01 8.2801635e+00 5.4538797e+00 - 1.8517652e+01 8.2103239e+00 5.7806635e+00 - 1.8641586e+01 8.2669890e+00 6.1834044e+00 - 1.8371597e+01 8.1442812e+00 6.4741731e+00 - 1.8613188e+01 8.2553830e+00 6.9244653e+00 - 1.8793906e+01 8.3377104e+00 7.3676417e+00 - 2.0320826e+01 9.0340459e+00 8.3194953e+00 - 1.9241099e+01 8.5417555e+00 8.3233106e+00 - 1.8610088e+01 8.2551945e+00 8.4709011e+00 - 1.8844579e+01 8.3622042e+00 8.9715008e+00 - 2.0051072e+01 8.9118402e+00 9.9324686e+00 - 1.8488239e+01 8.2006138e+00 9.6262664e+00 - 1.8620701e+01 8.2616549e+00 1.0107236e+01 - 1.8834661e+01 8.3586326e+00 1.0643400e+01 - 1.9314028e+01 8.5780739e+00 1.1342496e+01 - 2.2114882e+01 9.8544979e+00 1.3405086e+01 - 2.4111118e+01 1.0765680e+01 1.5133018e+01 - 2.0060985e+01 8.9201800e+00 1.3200127e+01 - 2.2198840e+01 9.8950102e+00 1.5089149e+01 - 2.1390157e+01 9.5266446e+00 1.5110510e+01 - 5.2816109e+00 2.1824526e+00 5.3453069e+00 - 5.1146996e+00 2.1062709e+00 5.3452892e+00 - 4.9705065e+00 2.0404944e+00 5.3602373e+00 - 4.5585815e+00 1.8528488e+00 5.1003011e+00 - 4.4205362e+00 1.7900421e+00 5.1017483e+00 - 4.2576704e+00 1.7161038e+00 5.0710573e+00 - 4.8734543e+00 1.9972861e+00 5.9067384e+00 - 4.1066539e+00 1.6479331e+00 5.1909948e+00 - 3.9840704e+00 1.5922544e+00 5.1931964e+00 - 3.8334964e+00 1.5231931e+00 5.1544795e+00 - 3.6839530e+00 1.4548465e+00 5.1112153e+00 - 3.6182036e+00 1.4247151e+00 5.1717799e+00 - 3.6135647e+00 1.4231885e+00 5.3170629e+00 - 3.5995982e+00 1.4168763e+00 5.4556309e+00 - 3.2098207e+00 1.2392016e+00 5.0397746e+00 - 3.4350185e+00 1.3417065e+00 5.5393522e+00 - 2.8897445e+00 1.0929389e+00 4.8361027e+00 - 2.9440837e+00 1.1175019e+00 5.0734503e+00 - 2.8638122e+00 1.0812613e+00 5.0943564e+00 - 2.9213874e+00 1.1080884e+00 5.3610087e+00 - 2.9260910e+00 1.1099183e+00 5.5448162e+00 - 2.8759163e+00 1.0873023e+00 5.6342501e+00 - 2.8060106e+00 1.0550739e+00 5.6879351e+00 - 2.7652167e+00 1.0371531e+00 5.8025108e+00 - 2.9267895e+00 1.1109445e+00 6.3735836e+00 - 2.2434284e+00 7.9894901e-01 5.0376201e+00 - 2.3001190e+00 8.2468163e-01 5.3619027e+00 - 2.1938016e+00 7.7607088e-01 5.3040818e+00 - 1.8826799e+00 6.3388852e-01 4.6888461e+00 - 1.7907644e+00 5.9197356e-01 4.6217951e+00 - 2.5103878e+00 9.2160696e-01 6.9419800e+00 - 2.2065089e+00 7.8310751e-01 6.3289208e+00 - 2.3346349e+00 8.4194634e-01 7.0630375e+00 - 2.2243572e+00 7.9177211e-01 7.0496729e+00 - 2.1432702e+00 7.5498878e-01 7.1393957e+00 - 1.3929030e+00 4.1068553e-01 4.5674125e+00 - 1.3425793e+00 3.8791047e-01 4.6131012e+00 - 1.2849617e+00 3.6207677e-01 4.6287484e+00 - 1.1823027e+00 3.1571006e-01 4.4187067e+00 - 1.1591796e+00 3.0494872e-01 4.5979004e+00 - 1.1361795e+00 2.9413953e-01 4.8166446e+00 - 1.2692434e+00 3.5543328e-01 6.1107005e+00 - 1.0559024e+00 2.5815473e-01 5.1454179e+00 - 9.8678446e-01 2.2624729e-01 5.1257918e+00 - 9.2301595e-01 1.9741910e-01 5.1544406e+00 - 9.2891882e-01 2.0088089e-01 5.9981743e+00 - 8.5068355e-01 1.6535373e-01 6.0157286e+00 - 7.5934680e-01 1.2363694e-01 5.8120958e+00 - 6.8196379e-01 8.7914896e-02 5.7864011e+00 - 6.0588084e-01 5.3513304e-02 5.8292179e+00 - 5.4192460e-01 2.6021590e-02 7.6605254e+00 - 2.4970617e+00 8.3888319e-01 -1.0151766e+00 - 2.5567216e+00 8.6393230e-01 -1.0037645e+00 - 2.6369000e+00 8.9788165e-01 -1.0103395e+00 - 2.7119599e+00 9.2956610e-01 -1.0081606e+00 - 2.7931666e+00 9.6369642e-01 -1.0098448e+00 - 2.8764447e+00 9.9882103e-01 -1.0091879e+00 - 2.9751216e+00 1.0405711e+00 -1.0179640e+00 - 3.0666246e+00 1.0791901e+00 -1.0177305e+00 - 3.1591437e+00 1.1178915e+00 -1.0146038e+00 - 3.2680672e+00 1.1632171e+00 -1.0197147e+00 - 3.3770724e+00 1.2097120e+00 -1.0213795e+00 - 3.4870980e+00 1.2563239e+00 -1.0194519e+00 - 3.6227313e+00 1.3128362e+00 -1.0293846e+00 - 3.7419991e+00 1.3630347e+00 -1.0247873e+00 - 3.8879411e+00 1.4241341e+00 -1.0308047e+00 - 4.0339132e+00 1.4854750e+00 -1.0319282e+00 - 4.2055737e+00 1.5578759e+00 -1.0416655e+00 - 4.3792669e+00 1.6304465e+00 -1.0455165e+00 - 4.5612594e+00 1.7076217e+00 -1.0475432e+00 - 4.7709532e+00 1.7958690e+00 -1.0554936e+00 - 4.9734266e+00 1.8800967e+00 -1.0521874e+00 - 5.2016762e+00 1.9766029e+00 -1.0530503e+00 - 5.4668508e+00 2.0876201e+00 -1.0601635e+00 - 5.7331425e+00 2.2000418e+00 -1.0578411e+00 - 6.0189628e+00 2.3204599e+00 -1.0525294e+00 - 6.3489448e+00 2.4590227e+00 -1.0522901e+00 - 6.7251598e+00 2.6167242e+00 -1.0547822e+00 - 7.1466866e+00 2.7947551e+00 -1.0573553e+00 - 7.6154170e+00 2.9911286e+00 -1.0573198e+00 - 8.1571839e+00 3.2190906e+00 -1.0594937e+00 - 8.7380390e+00 3.4632918e+00 -1.0506951e+00 - 9.5182649e+00 3.7915541e+00 -1.0658967e+00 - 1.0491711e+01 4.2008877e+00 -1.0919972e+00 - 1.1631678e+01 4.6796657e+00 -1.1128392e+00 - 1.3303029e+01 5.3827796e+00 -1.1810682e+00 - 1.4860509e+01 6.0376013e+00 -1.1686164e+00 - 1.8361354e+01 7.5101095e+00 -1.3534744e+00 - 2.1438494e+01 8.8043689e+00 -9.5752206e-01 - 2.3683361e+01 9.7475377e+00 -7.2584385e-01 - 2.2832790e+01 9.3908381e+00 -2.3812468e-01 - 2.2637835e+01 9.3086728e+00 1.9265665e-01 - 2.1642150e+01 8.8910057e+00 6.2951143e-01 - 2.1562254e+01 8.8575466e+00 1.0297461e+00 - 2.2728429e+01 9.3487532e+00 1.4522771e+00 - 2.1851736e+01 8.9795916e+00 1.8391469e+00 - 2.1337983e+01 8.7644664e+00 2.2143757e+00 - 2.2556755e+01 9.2769256e+00 2.7046189e+00 - 1.9302438e+01 7.9090318e+00 2.8116069e+00 - 2.1938392e+01 9.0175528e+00 3.4751602e+00 - 1.9178314e+01 7.8572012e+00 3.5149933e+00 - 1.9654679e+01 8.0575964e+00 3.9483179e+00 - 1.9403914e+01 7.9526110e+00 4.2759404e+00 - 1.9711698e+01 8.0826463e+00 4.7032634e+00 - 2.0815727e+01 8.5468505e+00 5.3142403e+00 - 2.0319117e+01 8.3382814e+00 5.6000301e+00 - 1.9945947e+01 8.1821358e+00 5.8998935e+00 - 1.8845188e+01 7.7184864e+00 5.9902342e+00 - 1.8477026e+01 7.5642380e+00 6.2536282e+00 - 1.8938294e+01 7.7593838e+00 6.7648006e+00 - 1.8666786e+01 7.6447330e+00 7.0543802e+00 - 1.9031357e+01 7.7983938e+00 7.5618880e+00 - 2.8809933e+01 1.1913178e+01 1.1620582e+01 - 1.9206936e+01 7.8734427e+00 8.4174634e+00 - 1.9540756e+01 8.0137079e+00 8.9611654e+00 - 1.9443307e+01 7.9730020e+00 9.3355334e+00 - 2.4131453e+01 9.9469008e+00 1.1922872e+01 - 2.0089652e+01 8.2454330e+00 1.0496458e+01 - 2.0083964e+01 8.2438581e+00 1.0942221e+01 - 1.9332673e+01 7.9279754e+00 1.0999486e+01 - 1.8257896e+01 7.4758836e+00 1.0849401e+01 - 1.8430303e+01 7.5488757e+00 1.1377193e+01 - 1.8236047e+01 7.4673503e+00 1.1700606e+01 - 2.0207194e+01 8.2975270e+00 1.3382727e+01 - 1.9830770e+01 8.1394886e+00 1.3640552e+01 - 2.1967319e+01 9.0395429e+00 1.5597650e+01 - 2.1821910e+01 8.9793915e+00 1.6067390e+01 - 5.5259379e+00 2.1180194e+00 5.2741873e+00 - 5.3779969e+00 2.0559879e+00 5.2993866e+00 - 5.1248342e+00 1.9491583e+00 5.2237173e+00 - 5.1666131e+00 1.9672154e+00 5.4158070e+00 - 5.0150118e+00 1.9034392e+00 5.5830901e+00 - 5.0206789e+00 1.9054469e+00 5.7514639e+00 - 5.0150889e+00 1.9038411e+00 5.9141782e+00 - 4.3212266e+00 1.6116792e+00 5.3076019e+00 - 4.0884885e+00 1.5135151e+00 5.1889267e+00 - 3.9279591e+00 1.4457843e+00 5.1446988e+00 - 3.8004834e+00 1.3927435e+00 5.1334840e+00 - 3.7514001e+00 1.3718442e+00 5.2184210e+00 - 3.6362663e+00 1.3235653e+00 5.2171078e+00 - 3.3186936e+00 1.1900013e+00 4.9288906e+00 - 3.3604894e+00 1.2076773e+00 5.1335144e+00 - 4.0015563e+00 1.4781147e+00 6.2479129e+00 - 3.1362631e+00 1.1132370e+00 5.1001085e+00 - 3.0179350e+00 1.0635432e+00 5.0664447e+00 - 2.9925961e+00 1.0526962e+00 5.1806763e+00 - 2.8618022e+00 9.9725025e-01 5.1170358e+00 - 2.9182003e+00 1.0211617e+00 5.3841395e+00 - 2.9023028e+00 1.0154927e+00 5.5333008e+00 - 2.8738996e+00 1.0027230e+00 5.6656683e+00 - 2.7855629e+00 9.6581133e-01 5.6834534e+00 - 2.4632162e+00 8.2985577e-01 5.2000426e+00 - 2.3913947e+00 8.0045510e-01 5.2275679e+00 - 2.2303759e+00 7.3190707e-01 5.0452129e+00 - 2.2134310e+00 7.2539020e-01 5.1962247e+00 - 1.9476723e+00 6.1353019e-01 4.7214886e+00 - 1.8705094e+00 5.8111433e-01 4.7020374e+00 - 2.5903577e+00 8.8564101e-01 6.9411579e+00 - 2.2466858e+00 7.4001130e-01 6.2371832e+00 - 2.4845910e+00 8.4121587e-01 7.2911303e+00 - 2.2591815e+00 7.4557203e-01 6.9091610e+00 - 2.1741058e+00 7.1009325e-01 6.9799208e+00 - 2.1233972e+00 6.8918607e-01 7.1838149e+00 - 2.0071005e+00 6.4016633e-01 7.1460003e+00 - 1.3243573e+00 3.5128899e-01 4.6210275e+00 - 1.2584501e+00 3.2299095e-01 4.5971986e+00 - 1.1904774e+00 2.9426202e-01 4.5621899e+00 - 1.1664788e+00 2.8454155e-01 4.7612623e+00 - 1.3378028e+00 3.5730549e-01 6.2115099e+00 - 1.1209713e+00 2.6531230e-01 5.3079646e+00 - 1.0268642e+00 2.2608432e-01 5.1308590e+00 - 9.6110144e-01 1.9842500e-01 5.1402387e+00 - 9.8807000e-01 2.1103412e-01 6.1330758e+00 - 9.0260630e-01 1.7451790e-01 6.1017631e+00 - 8.0086003e-01 1.3153378e-01 5.7994352e+00 - 7.2384901e-01 9.9815757e-02 5.8143911e+00 - 6.4558314e-01 6.6622794e-02 5.7779640e+00 - 5.9640171e-01 4.7260206e-02 7.6898794e+00 - 2.4836109e+00 7.6556391e-01 -1.0132791e+00 - 2.5574587e+00 7.9405190e-01 -1.0163417e+00 - 2.6180621e+00 8.1808794e-01 -1.0039843e+00 - 2.7000623e+00 8.4897481e-01 -1.0094183e+00 - 2.7831370e+00 8.8092627e-01 -1.0123082e+00 - 2.8662866e+00 9.1399293e-01 -1.0128506e+00 - 2.9585800e+00 9.4934382e-01 -1.0168662e+00 - 3.0580234e+00 9.8711955e-01 -1.0239491e+00 - 3.1514116e+00 1.0236976e+00 -1.0221247e+00 - 3.2458159e+00 1.0603581e+00 -1.0174071e+00 - 3.3565648e+00 1.1026507e+00 -1.0207777e+00 - 3.4755301e+00 1.1483688e+00 -1.0259700e+00 - 3.5955773e+00 1.1952105e+00 -1.0274196e+00 - 3.7247836e+00 1.2444596e+00 -1.0298456e+00 - 3.8704699e+00 1.3014530e+00 -1.0380618e+00 - 4.0017870e+00 1.3520118e+00 -1.0317545e+00 - 4.1669251e+00 1.4158717e+00 -1.0396286e+00 - 4.3412963e+00 1.4832444e+00 -1.0463311e+00 - 4.5341026e+00 1.5573962e+00 -1.0556846e+00 - 4.7116043e+00 1.6261904e+00 -1.0501615e+00 - 4.9239516e+00 1.7084372e+00 -1.0545281e+00 - 5.1557471e+00 1.7975210e+00 -1.0591518e+00 - 5.3967959e+00 1.8902801e+00 -1.0593081e+00 - 5.6737753e+00 1.9976401e+00 -1.0651123e+00 - 5.9446043e+00 2.1020105e+00 -1.0578150e+00 - 6.2513800e+00 2.2211100e+00 -1.0535688e+00 - 6.6134667e+00 2.3605912e+00 -1.0563765e+00 - 7.0217349e+00 2.5182834e+00 -1.0604677e+00 - 7.4587205e+00 2.6866159e+00 -1.0577518e+00 - 7.9706056e+00 2.8843186e+00 -1.0592498e+00 - 8.5655684e+00 3.1139975e+00 -1.0631383e+00 - 9.2077866e+00 3.3624328e+00 -1.0560287e+00 - 1.0126798e+01 3.7167402e+00 -1.0848860e+00 - 1.1168984e+01 4.1192864e+00 -1.1034667e+00 - 1.2682888e+01 4.7037442e+00 -1.1671735e+00 - 1.4091408e+01 5.2480787e+00 -1.1571629e+00 - 1.6326471e+01 6.1104896e+00 -1.2100965e+00 - 1.8853125e+01 7.0870840e+00 -1.2146938e+00 - 2.1199530e+01 7.9929182e+00 -1.1062542e+00 - 2.2122802e+01 8.3499412e+00 -7.9274933e-01 - 2.3228729e+01 8.7772711e+00 -4.5720717e-01 - 2.4537717e+01 9.2827737e+00 8.0998081e-01 - 2.5068605e+01 9.4889987e+00 1.2654093e+00 - 2.9630118e+01 1.1251171e+01 2.4055753e+00 - 2.8820291e+01 1.0938384e+01 2.8979856e+00 - 1.9393082e+01 7.2983087e+00 2.6218027e+00 - 1.8658469e+01 7.0145239e+00 2.9011576e+00 - 1.9190191e+01 7.2204111e+00 3.3104407e+00 - 1.9241643e+01 7.2403376e+00 3.6729889e+00 - 1.9240826e+01 7.2411135e+00 4.0306970e+00 - 1.9547868e+01 7.3595517e+00 4.4457808e+00 - 2.0157826e+01 7.5958149e+00 4.9356844e+00 - 2.1735845e+01 8.2047334e+00 5.6640542e+00 - 1.9025874e+01 7.1582112e+00 5.4314342e+00 - 1.8769367e+01 7.0591729e+00 5.7304638e+00 - 2.5920034e+01 9.8227669e+00 8.0873304e+00 - 1.9115806e+01 7.1940334e+00 6.5642121e+00 - 3.0554850e+01 1.1615215e+01 1.0591735e+01 - 2.0150467e+01 7.5949405e+00 7.6740504e+00 - 1.8933681e+01 7.1242221e+00 7.6426044e+00 - 1.8980217e+01 7.1435046e+00 8.0467660e+00 - 1.9666593e+01 7.4080796e+00 8.7148234e+00 - 1.9398862e+01 7.3056889e+00 9.0134869e+00 - 1.9351939e+01 7.2878217e+00 9.4042384e+00 - 2.0580034e+01 7.7624397e+00 1.0395707e+01 - 2.0008181e+01 7.5416525e+00 1.0566220e+01 - 1.8982138e+01 7.1462172e+00 1.0485128e+01 - 1.8817022e+01 7.0818065e+00 1.0825039e+01 - 2.2390891e+01 8.4643897e+00 1.3258690e+01 - 2.2171658e+01 8.3800654e+00 1.3656888e+01 - 2.1216433e+01 8.0109621e+00 1.3606399e+01 - 2.0782297e+01 7.8436521e+00 1.3849719e+01 - 1.9950244e+01 7.5222487e+00 1.3818845e+01 - 2.1467431e+01 8.1093035e+00 1.5365376e+01 - 2.1805491e+01 8.2399570e+00 1.6164841e+01 - 5.4365819e+00 1.9108921e+00 5.3775703e+00 - 5.2375118e+00 1.8343915e+00 5.3522354e+00 - 4.7399660e+00 1.6420677e+00 5.0353874e+00 - 4.5777967e+00 1.5788527e+00 5.0194820e+00 - 4.4640205e+00 1.5349330e+00 5.0469812e+00 - 4.3780157e+00 1.5016138e+00 5.0995178e+00 - 4.2776331e+00 1.4633383e+00 5.1357671e+00 - 4.4212587e+00 1.5192072e+00 5.4455111e+00 - 4.2096317e+00 1.4372585e+00 5.3558426e+00 - 3.9474874e+00 1.3356297e+00 5.1922640e+00 - 3.7337442e+00 1.2533602e+00 5.0733884e+00 - 3.7847056e+00 1.2729788e+00 5.2878722e+00 - 3.6162592e+00 1.2083398e+00 5.2155060e+00 - 3.3209727e+00 1.0938921e+00 4.9555445e+00 - 3.4111020e+00 1.1283239e+00 5.2331348e+00 - 3.1198650e+00 1.0156350e+00 4.9529366e+00 - 3.1131314e+00 1.0129269e+00 5.0920832e+00 - 3.2260930e+00 1.0571280e+00 5.4325290e+00 - 2.9378320e+00 9.4565725e-01 5.1199125e+00 - 3.0260942e+00 9.8021146e-01 5.4380583e+00 - 2.9492858e+00 9.5062846e-01 5.4760362e+00 - 2.8848498e+00 9.2553464e-01 5.5386470e+00 - 2.7791441e+00 8.8490587e-01 5.5210787e+00 - 2.8861520e+00 9.2614177e-01 5.9358990e+00 - 2.3733786e+00 7.2744269e-01 5.0484552e+00 - 2.3677728e+00 7.2519462e-01 5.2184101e+00 - 2.2329992e+00 6.7318857e-01 5.0980548e+00 - 2.0216374e+00 5.9151087e-01 4.7719797e+00 - 1.9488307e+00 5.6382144e-01 4.7721930e+00 - 2.6772451e+00 8.4714786e-01 6.9584400e+00 - 2.5674279e+00 8.0374856e-01 6.9608582e+00 - 2.2525423e+00 6.8250397e-01 6.3385053e+00 - 2.3250800e+00 7.1019301e-01 6.8828653e+00 - 2.2703304e+00 6.9017161e-01 7.0593069e+00 - 2.1615192e+00 6.4729005e-01 7.0531829e+00 - 2.0673286e+00 6.1130593e-01 7.1026975e+00 - 1.9356315e+00 5.5977379e-01 6.9956162e+00 - 1.8091478e+00 5.1126528e-01 6.8951620e+00 - 1.2362911e+00 2.8808788e-01 4.5945516e+00 - 1.1695540e+00 2.6274262e-01 4.5685797e+00 - 1.1340889e+00 2.4876671e-01 4.7084594e+00 - 1.2780117e+00 3.0533521e-01 6.0417296e+00 - 1.0688174e+00 2.2378684e-01 5.1356194e+00 - 9.9906465e-01 1.9742222e-01 5.1258363e+00 - 9.4089796e-01 1.7472149e-01 5.2240344e+00 - 9.4680288e-01 1.7768393e-01 6.0779052e+00 - 8.5721378e-01 1.4241172e-01 5.9858818e+00 - 7.6642596e-01 1.0766025e-01 5.8221517e+00 - 6.8522788e-01 7.6693570e-02 5.7664092e+00 - 6.0957343e-01 4.7263388e-02 5.8492277e+00 - 5.4267984e-01 2.2472676e-02 7.6505833e+00 - 2.5430079e+00 7.2077829e-01 -1.0147406e+00 - 2.6177402e+00 7.4726612e-01 -1.0166087e+00 - 2.6863553e+00 7.7154455e-01 -1.0098195e+00 - 2.7692406e+00 8.0043617e-01 -1.0139590e+00 - 2.8541985e+00 8.3033194e-01 -1.0155576e+00 - 2.9309820e+00 8.5713734e-01 -1.0085430e+00 - 3.0322902e+00 8.9270958e-01 -1.0173310e+00 - 3.1254873e+00 9.2621304e-01 -1.0170558e+00 - 3.2278324e+00 9.6203521e-01 -1.0195548e+00 - 3.3393878e+00 1.0011878e+00 -1.0245777e+00 - 3.4510256e+00 1.0415148e+00 -1.0260546e+00 - 3.5728159e+00 1.0841493e+00 -1.0293099e+00 - 3.6946308e+00 1.1269808e+00 -1.0285702e+00 - 3.8256645e+00 1.1732118e+00 -1.0289562e+00 - 3.9567241e+00 1.2196497e+00 -1.0251474e+00 - 4.1153411e+00 1.2749786e+00 -1.0309584e+00 - 4.2903890e+00 1.3371434e+00 -1.0407124e+00 - 4.4593295e+00 1.3971777e+00 -1.0402110e+00 - 4.6466443e+00 1.4629892e+00 -1.0424109e+00 - 4.8687445e+00 1.5412564e+00 -1.0544511e+00 - 5.0847448e+00 1.6174521e+00 -1.0550375e+00 - 5.3191963e+00 1.7005551e+00 -1.0556780e+00 - 5.5812477e+00 1.7928890e+00 -1.0590468e+00 - 5.8627639e+00 1.8921928e+00 -1.0599760e+00 - 6.1545440e+00 1.9952101e+00 -1.0544434e+00 - 6.4923610e+00 2.1142521e+00 -1.0539905e+00 - 6.8772882e+00 2.2503737e+00 -1.0562728e+00 - 7.3000730e+00 2.3993904e+00 -1.0558205e+00 - 7.7883577e+00 2.5713871e+00 -1.0583077e+00 - 8.3340121e+00 2.7641422e+00 -1.0577677e+00 - 8.9452089e+00 2.9802173e+00 -1.0532758e+00 - 9.7804676e+00 3.2746769e+00 -1.0762609e+00 - 1.0758057e+01 3.6198155e+00 -1.0973180e+00 - 1.1980269e+01 4.0510314e+00 -1.1275354e+00 - 1.3615954e+01 4.6276297e+00 -1.1811934e+00 - 1.5274434e+01 5.2137117e+00 -1.1777888e+00 - 1.8491454e+01 6.3477229e+00 -1.3133594e+00 - 2.1265856e+01 7.3272392e+00 -1.2809825e+00 - 2.1807516e+01 7.5189742e+00 -9.4255076e-01 - 2.3199709e+01 8.0102850e+00 -6.4687484e-01 - 2.3440588e+01 8.0952859e+00 -2.3824368e-01 - 2.5087327e+01 8.6777493e+00 1.4944445e+00 - 2.2683151e+01 7.8302977e+00 2.2684731e+00 - 2.7455166e+01 9.5143965e+00 3.0421357e+00 - 1.8692103e+01 6.4215895e+00 2.7174359e+00 - 1.8323553e+01 6.2921705e+00 3.0157522e+00 - 1.9035460e+01 6.5442861e+00 3.4439702e+00 - 2.2932756e+01 7.9201715e+00 4.3801109e+00 - 1.9465886e+01 6.6961316e+00 4.2169890e+00 - 2.2519681e+01 7.7749533e+00 5.1540667e+00 - 2.2132825e+01 7.6387615e+00 5.4956829e+00 - 1.8634569e+01 6.4039833e+00 5.1187198e+00 - 1.8215653e+01 6.2560962e+00 5.3676956e+00 - 1.8679968e+01 6.4209705e+00 5.8385909e+00 - 1.8570436e+01 6.3816998e+00 6.1666055e+00 - 1.8573695e+01 6.3834131e+00 6.5279467e+00 - 1.8912049e+01 6.5029236e+00 7.0026582e+00 - 2.4071584e+01 8.3259031e+00 9.1647018e+00 - 1.1538938e+01 3.8993288e+00 5.0517811e+00 - 1.9476482e+01 6.7027940e+00 8.3599053e+00 - 1.9334313e+01 6.6531968e+00 8.7028483e+00 - 1.9108069e+01 6.5737455e+00 9.0089350e+00 - 2.1047149e+01 7.2595003e+00 1.0289174e+01 - 2.1054746e+01 7.2616693e+00 1.0745683e+01 - 2.0378525e+01 7.0238421e+00 1.0870323e+01 - 1.8840770e+01 6.4806511e+00 1.0524439e+01 - 2.0351794e+01 7.0149308e+00 1.1768535e+01 - 2.0188198e+01 6.9572033e+00 1.2143850e+01 - 2.0471853e+01 7.0581295e+00 1.2783618e+01 - 2.0340128e+01 7.0121371e+00 1.3191600e+01 - 2.0062723e+01 6.9143517e+00 1.3510621e+01 - 2.0189555e+01 6.9597546e+00 1.4093922e+01 - 2.2428068e+01 7.7514442e+00 1.6154057e+01 - 5.2699594e+00 1.6880560e+00 5.1113478e+00 - 5.2447559e+00 1.6788070e+00 5.2377147e+00 - 4.8971562e+00 1.5559854e+00 5.0686002e+00 - 4.5772267e+00 1.4429564e+00 4.9081434e+00 - 4.5674394e+00 1.4399567e+00 5.0377114e+00 - 4.5340253e+00 1.4283598e+00 5.1472238e+00 - 4.3988957e+00 1.3805147e+00 5.1505182e+00 - 4.3295238e+00 1.3561616e+00 5.2220339e+00 - 4.2210948e+00 1.3178819e+00 5.2484208e+00 - 4.5032204e+00 1.4182306e+00 5.7334358e+00 - 4.1038751e+00 1.2760132e+00 5.4139104e+00 - 3.8669764e+00 1.1930385e+00 5.2728849e+00 - 3.6957887e+00 1.1326672e+00 5.2023277e+00 - 3.3075634e+00 9.9503109e-01 4.8270392e+00 - 3.4026694e+00 1.0290474e+00 5.1023165e+00 - 3.7879235e+00 1.1658049e+00 5.8195883e+00 - 3.1639679e+00 9.4464593e-01 5.0514837e+00 - 3.0646565e+00 9.0947185e-01 5.0505277e+00 - 3.1361883e+00 9.3479566e-01 5.3240765e+00 - 3.0945429e+00 9.2016931e-01 5.4231761e+00 - 3.0652754e+00 9.1007646e-01 5.5478075e+00 - 2.9144647e+00 8.5644406e-01 5.4559663e+00 - 2.8357644e+00 8.2884778e-01 5.4912546e+00 - 2.7704371e+00 8.0569992e-01 5.5515722e+00 - 2.7763048e+00 8.0879469e-01 5.7622434e+00 - 2.3686070e+00 6.6331024e-01 5.0842884e+00 - 2.1970325e+00 6.0345875e-01 4.8824460e+00 - 2.0840869e+00 5.6278050e-01 4.7945380e+00 - 2.0392971e+00 5.4713830e-01 4.8693771e+00 - 2.4788480e+00 7.0326298e-01 6.2239460e+00 - 2.6306533e+00 7.5792477e-01 6.9229793e+00 - 2.3051104e+00 6.4301647e-01 6.2940719e+00 - 2.3795201e+00 6.6907528e-01 6.8280879e+00 - 2.3589638e+00 6.6223613e-01 7.1094987e+00 - 2.2276668e+00 6.1544877e-01 7.0378248e+00 - 2.1388332e+00 5.8415035e-01 7.1074003e+00 - 1.9971041e+00 5.3385191e-01 6.9725859e+00 - 1.8709291e+00 4.8987316e-01 6.8829199e+00 - 1.2685234e+00 2.7580008e-01 4.5681256e+00 - 1.2080819e+00 2.5357390e-01 4.5721983e+00 - 1.1476927e+00 2.3228063e-01 4.5749231e+00 - 1.0967060e+00 2.1430762e-01 4.6356979e+00 - 1.1149453e+00 2.2218680e-01 5.1796681e+00 - 1.0389638e+00 1.9426838e-01 5.1310521e+00 - 9.7150840e-01 1.7122031e-01 5.1504274e+00 - 1.0057126e+00 1.8384442e-01 6.2129050e+00 - 9.1013900e-01 1.5000260e-01 6.1020248e+00 - 8.1112172e-01 1.1533107e-01 5.8693564e+00 - 7.2793204e-01 8.5038836e-02 5.8045819e+00 - 6.4809691e-01 5.7442464e-02 5.7981257e+00 - 5.9691259e-01 4.0727110e-02 7.6599612e+00 - 2.4510344e+00 6.2437630e-01 -1.0076154e+00 - 2.5255651e+00 6.4770575e-01 -1.0127305e+00 - 2.5940400e+00 6.6983261e-01 -1.0090383e+00 - 2.6625266e+00 6.9205308e-01 -1.0034484e+00 - 2.7534100e+00 7.2107870e-01 -1.0153534e+00 - 2.8381792e+00 7.4791957e-01 -1.0181018e+00 - 2.9240223e+00 7.7582010e-01 -1.0184060e+00 - 3.0026891e+00 8.0056982e-01 -1.0101001e+00 - 3.1048234e+00 8.3315972e-01 -1.0173443e+00 - 3.1998441e+00 8.6361545e-01 -1.0156285e+00 - 3.3040130e+00 8.9638991e-01 -1.0166867e+00 - 3.4163952e+00 9.3256513e-01 -1.0200660e+00 - 3.5379918e+00 9.7210528e-01 -1.0252702e+00 - 3.6605504e+00 1.0107802e+00 -1.0265327e+00 - 3.7923273e+00 1.0528496e+00 -1.0290209e+00 - 3.9251884e+00 1.0960624e+00 -1.0273669e+00 - 4.0753500e+00 1.1439928e+00 -1.0308584e+00 - 4.2438762e+00 1.1976217e+00 -1.0386492e+00 - 4.4134952e+00 1.2524629e+00 -1.0408996e+00 - 4.6024247e+00 1.3120093e+00 -1.0461045e+00 - 4.7996560e+00 1.3761800e+00 -1.0490857e+00 - 5.0080651e+00 1.4428145e+00 -1.0494539e+00 - 5.2532056e+00 1.5208657e+00 -1.0580212e+00 - 5.4902535e+00 1.5969958e+00 -1.0545291e+00 - 5.7650451e+00 1.6845954e+00 -1.0569420e+00 - 6.0317491e+00 1.7703135e+00 -1.0464965e+00 - 6.3545637e+00 1.8732191e+00 -1.0458558e+00 - 6.7233632e+00 1.9912167e+00 -1.0489468e+00 - 7.1401591e+00 2.1243084e+00 -1.0532789e+00 - 7.5866707e+00 2.2679801e+00 -1.0508070e+00 - 8.1270769e+00 2.4406290e+00 -1.0575530e+00 - 8.6788099e+00 2.6174482e+00 -1.0473534e+00 - 9.3724811e+00 2.8392324e+00 -1.0497597e+00 - 1.0310244e+01 3.1392383e+00 -1.0787575e+00 - 1.1308373e+01 3.4588079e+00 -1.0847630e+00 - 1.2873306e+01 3.9597153e+00 -1.1529736e+00 - 1.4282147e+01 4.4099191e+00 -1.1394231e+00 - 1.6629697e+01 5.1617111e+00 -1.2026130e+00 - 1.9124558e+01 5.9601822e+00 -1.1970261e+00 - 2.1557375e+01 6.7381539e+00 -1.0940265e+00 - 2.2281803e+01 6.9705884e+00 -7.6403719e-01 - 2.3515970e+01 7.3655170e+00 -4.4020378e-01 - 2.4126163e+01 7.5609837e+00 -4.4307589e-02 - 2.5640533e+01 8.0474702e+00 1.2715110e+00 - 2.1738004e+01 6.7988868e+00 1.6189139e+00 - 1.9098952e+01 5.9543413e+00 1.8834190e+00 - 1.9898160e+01 6.2105435e+00 2.2779559e+00 - 1.9968824e+01 6.2333585e+00 2.6412443e+00 - 2.0346060e+01 6.3537507e+00 3.0396786e+00 - 1.8464687e+01 5.7521351e+00 3.1793900e+00 - 2.3126605e+01 7.2448236e+00 4.1658241e+00 - 2.3278217e+01 7.2929913e+00 4.6128676e+00 - 2.7271512e+01 8.5727223e+00 5.7492007e+00 - 2.6742196e+01 8.4037713e+00 6.6511002e+00 - 1.8474440e+01 5.7564558e+00 5.2156285e+00 - 1.8539997e+01 5.7776087e+00 5.5796311e+00 - 1.8728299e+01 5.8384201e+00 5.9825712e+00 - 1.8614939e+01 5.8022540e+00 6.3078531e+00 - 1.7675285e+01 5.5021782e+00 6.3735112e+00 - 1.7646772e+01 5.4934737e+00 6.7086291e+00 - 1.7134426e+01 5.3290890e+00 6.8753924e+00 - 1.7545744e+01 5.4612527e+00 7.3704558e+00 - 1.8453235e+01 5.7517822e+00 8.0827258e+00 - 1.9660645e+01 6.1388496e+00 8.9625972e+00 - 1.7564634e+01 5.4679263e+00 8.4560495e+00 - 1.7761272e+01 5.5310525e+00 8.9156940e+00 - 1.8285410e+01 5.6992855e+00 9.5470529e+00 - 1.8337877e+01 5.7161898e+00 9.9711197e+00 - 2.4845075e+01 7.8022360e+00 1.3796546e+01 - 2.1894148e+01 6.8567219e+00 1.2740319e+01 - 1.8961248e+01 5.9172912e+00 1.1566036e+01 - 1.9180731e+01 5.9877145e+00 1.2139721e+01 - 1.9205822e+01 5.9966672e+00 1.2612708e+01 - 2.0047919e+01 6.2669018e+00 1.3624251e+01 - 1.9024638e+01 5.9392301e+00 1.3436671e+01 - 1.9671372e+01 6.1472479e+00 1.4371689e+01 - 1.8953073e+01 5.9163931e+00 1.4363481e+01 - 1.8611683e+01 5.8079516e+00 1.4612335e+01 - 5.4627011e+00 1.5926151e+00 5.1609227e+00 - 5.3340860e+00 1.5511854e+00 5.2003054e+00 - 5.0323423e+00 1.4551048e+00 5.0800510e+00 - 4.8637039e+00 1.4005793e+00 5.0696642e+00 - 4.7811996e+00 1.3747324e+00 5.1355275e+00 - 4.5264145e+00 1.2924580e+00 5.0272182e+00 - 4.4787505e+00 1.2779579e+00 5.1215428e+00 - 4.2895623e+00 1.2173755e+00 5.0652244e+00 - 4.3392523e+00 1.2333246e+00 5.2648786e+00 - 4.4217818e+00 1.2596736e+00 5.5118763e+00 - 4.1761414e+00 1.1807216e+00 5.3806186e+00 - 3.9612532e+00 1.1120803e+00 5.2721914e+00 - 3.7627549e+00 1.0489167e+00 5.1728045e+00 - 3.5333790e+00 9.7495628e-01 5.0204746e+00 - 3.4538250e+00 9.4960650e-01 5.0595622e+00 - 3.3916821e+00 9.2934206e-01 5.1212198e+00 - 3.1899796e+00 8.6519883e-01 4.9780469e+00 - 3.0970119e+00 8.3507545e-01 4.9855134e+00 - 3.0615852e+00 8.2398553e-01 5.0825979e+00 - 3.3918618e+00 9.3034781e-01 5.7874909e+00 - 2.9742908e+00 7.9591913e-01 5.2594370e+00 - 2.9892579e+00 8.0094340e-01 5.4594439e+00 - 2.8593366e+00 7.5969128e-01 5.3999038e+00 - 2.8126770e+00 7.4517995e-01 5.4952240e+00 - 2.8081550e+00 7.4355625e-01 5.6790586e+00 - 2.3654503e+00 6.0168245e-01 4.9504791e+00 - 2.2342742e+00 5.5895539e-01 4.8395560e+00 - 2.1504585e+00 5.3221349e-01 4.8252727e+00 - 2.0830714e+00 5.1022641e-01 4.8458968e+00 - 2.4690311e+00 6.3457121e-01 6.0206401e+00 - 2.6801854e+00 7.0302918e-01 6.8473852e+00 - 2.5998013e+00 6.7805165e-01 6.9333174e+00 - 2.2635106e+00 5.6978860e-01 6.2635985e+00 - 2.3347464e+00 5.9304775e-01 6.7979725e+00 - 2.3864995e+00 6.0919406e-01 7.3270104e+00 - 2.1729028e+00 5.4150410e-01 6.9769304e+00 - 2.1421764e+00 5.3170041e-01 7.2670607e+00 - 2.0349452e+00 4.9701803e-01 7.2865546e+00 - 1.9018449e+00 4.5498830e-01 7.1873235e+00 - 1.2340850e+00 2.3921323e-01 4.5166770e+00 - 1.1799901e+00 2.2102919e-01 4.5492466e+00 - 1.1405924e+00 2.0880618e-01 4.6792520e+00 - 1.2911396e+00 2.5792674e-01 6.0321725e+00 - 1.0808569e+00 1.9045981e-01 5.1456995e+00 - 1.0103489e+00 1.6764410e-01 5.1458585e+00 - 9.5142617e-01 1.4900150e-01 5.2440613e+00 - 9.5521207e-01 1.5110441e-01 6.0780631e+00 - 8.8001467e-01 1.2635814e-01 6.2153151e+00 - 7.7044898e-01 9.1372240e-02 5.8222295e+00 - 6.8743339e-01 6.5049874e-02 5.7366325e+00 - 6.1114700e-01 4.0153952e-02 5.8493685e+00 - 5.4249713e-01 1.9981167e-02 7.6405949e+00 - 2.5134356e+00 5.8000229e-01 -1.0173259e+00 - 2.5746573e+00 5.9784836e-01 -1.0076706e+00 - 2.6439547e+00 6.1696332e-01 -1.0030339e+00 - 2.7275806e+00 6.4167366e-01 -1.0096751e+00 - 2.8132184e+00 6.6638626e-01 -1.0138257e+00 - 2.8988119e+00 6.9023000e-01 -1.0153300e+00 - 2.9854786e+00 7.1512849e-01 -1.0144899e+00 - 3.0722216e+00 7.4115203e-01 -1.0111026e+00 - 3.1680494e+00 7.6847270e-01 -1.0109393e+00 - 3.2720265e+00 7.9816761e-01 -1.0136466e+00 - 3.3770817e+00 8.2895669e-01 -1.0132107e+00 - 3.4993619e+00 8.6334323e-01 -1.0203675e+00 - 3.6064554e+00 8.9434642e-01 -1.0131463e+00 - 3.7471092e+00 9.3450531e-01 -1.0231043e+00 - 3.8715783e+00 9.7134129e-01 -1.0186810e+00 - 4.0224794e+00 1.0150806e+00 -1.0248739e+00 - 4.1835458e+00 1.0612308e+00 -1.0307479e+00 - 4.3547802e+00 1.1098118e+00 -1.0359034e+00 - 4.5261099e+00 1.1596706e+00 -1.0354155e+00 - 4.7248920e+00 1.2165495e+00 -1.0419514e+00 - 4.9349114e+00 1.2768844e+00 -1.0460237e+00 - 5.1541762e+00 1.3408305e+00 -1.0469271e+00 - 5.3835671e+00 1.4063582e+00 -1.0440662e+00 - 5.6599008e+00 1.4865971e+00 -1.0514321e+00 - 5.9372305e+00 1.5662417e+00 -1.0493633e+00 - 6.2349666e+00 1.6518285e+00 -1.0442091e+00 - 6.5785572e+00 1.7504344e+00 -1.0442856e+00 - 6.9619261e+00 1.8606943e+00 -1.0440811e+00 - 7.3738809e+00 1.9795120e+00 -1.0387682e+00 - 7.8806547e+00 2.1261412e+00 -1.0448241e+00 - 8.4271345e+00 2.2828148e+00 -1.0427095e+00 - 9.0308200e+00 2.4573891e+00 -1.0347224e+00 - 9.8352497e+00 2.6889645e+00 -1.0486081e+00 - 1.0839492e+01 2.9781288e+00 -1.0736767e+00 - 1.2075191e+01 3.3342898e+00 -1.1041798e+00 - 1.3703364e+01 3.8032086e+00 -1.1538816e+00 - 1.5345988e+01 4.2761078e+00 -1.1462979e+00 - 1.8451406e+01 5.1710078e+00 -1.2637777e+00 - 2.2327000e+01 6.2875180e+00 -9.5109351e-01 - 2.3880852e+01 6.7355967e+00 -6.6279343e-01 - 2.3885326e+01 6.7374364e+00 -2.3688634e-01 - 2.3912176e+01 6.7448856e+00 1.8780494e-01 - 2.4478233e+01 6.9090841e+00 1.4751132e+00 - 2.4081976e+01 6.7954536e+00 1.8959736e+00 - 2.2250728e+01 6.2672942e+00 2.2223873e+00 - 1.9868603e+01 5.5815277e+00 2.4418302e+00 - 1.8635648e+01 5.2265799e+00 2.6817148e+00 - 1.8240995e+01 5.1133089e+00 2.9704847e+00 - 1.7652456e+01 4.9436404e+00 3.2208811e+00 - 1.7688203e+01 4.9545026e+00 3.5434234e+00 - 1.7908582e+01 5.0180674e+00 3.8994722e+00 - 2.3884207e+01 6.7404017e+00 5.3310420e+00 - 1.7480184e+01 4.8954960e+00 4.4646492e+00 - 1.8528146e+01 5.1978112e+00 5.0196786e+00 - 1.8524120e+01 5.1960306e+00 5.3624139e+00 - 1.7478284e+01 4.8957386e+00 5.4359470e+00 - 1.7179310e+01 4.8096341e+00 5.6812349e+00 - 1.6940502e+01 4.7404490e+00 5.9364305e+00 - 1.7627476e+01 4.9386722e+00 6.4811011e+00 - 1.7806253e+01 4.9910551e+00 6.8845157e+00 - 1.7469456e+01 4.8933597e+00 7.1129871e+00 - 1.8320009e+01 5.1391554e+00 7.7843616e+00 - 2.0176361e+01 5.6752100e+00 8.8985811e+00 - 2.3485881e+01 6.6295810e+00 1.0710092e+01 - 1.7035088e+01 4.7698377e+00 8.3379615e+00 - 1.7559070e+01 4.9205366e+00 8.9392482e+00 - 1.8136328e+01 5.0878092e+00 9.5956578e+00 - 2.1639801e+01 6.0988910e+00 1.1774833e+01 - 1.9043918e+01 5.3502517e+00 1.0873108e+01 - 1.9264962e+01 5.4144855e+00 1.1425061e+01 - 1.9155044e+01 5.3827480e+00 1.1803269e+01 - 1.9228019e+01 5.4038268e+00 1.2295888e+01 - 1.9249992e+01 5.4109472e+00 1.2768585e+01 - 2.0946704e+01 5.9003875e+00 1.4345256e+01 - 1.9866241e+01 5.5891298e+00 1.4135894e+01 - 1.9491816e+01 5.4814054e+00 1.4379209e+01 - 1.9326913e+01 5.4344679e+00 1.4768218e+01 - 6.5156301e+00 1.7367110e+00 5.5658314e+00 - 6.4682028e+00 1.7241027e+00 5.6985086e+00 - 6.3808073e+00 1.6983230e+00 5.8001429e+00 - 6.3517585e+00 1.6904933e+00 5.9503930e+00 - 6.2316413e+00 1.6552546e+00 6.0237602e+00 - 5.1615066e+00 1.3465892e+00 5.2332900e+00 - 5.0464405e+00 1.3135925e+00 5.2771792e+00 - 5.6903638e+00 1.4999686e+00 6.0558874e+00 - 4.7558862e+00 1.2296536e+00 5.2937264e+00 - 4.2765690e+00 1.0918404e+00 4.9454416e+00 - 4.1828600e+00 1.0643461e+00 4.9847223e+00 - 4.1086616e+00 1.0436721e+00 5.0436711e+00 - 4.3936847e+00 1.1262593e+00 5.5179299e+00 - 4.3481611e+00 1.1133052e+00 5.6257818e+00 - 4.2636947e+00 1.0883693e+00 5.6874071e+00 - 3.9191946e+00 9.8919987e-01 5.4126780e+00 - 3.6329424e+00 9.0615902e-01 5.1901596e+00 - 3.4060628e+00 8.4071529e-01 5.0305857e+00 - 3.5797102e+00 8.9125867e-01 5.4311190e+00 - 3.2411093e+00 7.9358782e-01 5.0928013e+00 - 3.1934924e+00 7.8049530e-01 5.1751415e+00 - 3.4266534e+00 8.4718351e-01 5.7104787e+00 - 3.4231652e+00 8.4629924e-01 5.8902655e+00 - 3.2761566e+00 8.0409564e-01 5.8311782e+00 - 3.3485930e+00 8.2500134e-01 6.1582050e+00 - 2.9871868e+00 7.2138677e-01 5.6927639e+00 - 2.9354890e+00 7.0628420e-01 5.7902470e+00 - 2.3982739e+00 5.5092678e-01 4.8975120e+00 - 2.3074359e+00 5.2432721e-01 4.8775579e+00 - 2.3265357e+00 5.3022805e-01 5.1002241e+00 - 2.5655585e+00 5.9944761e-01 5.8550712e+00 - 2.6404061e+00 6.2200077e-01 6.2787211e+00 - 2.6340638e+00 6.1984062e-01 6.5302769e+00 - 2.6370617e+00 6.2050313e-01 6.8297952e+00 - 2.2973968e+00 5.2206540e-01 6.1720278e+00 - 2.3911197e+00 5.5027340e-01 6.7525763e+00 - 2.3561715e+00 5.3991196e-01 6.9859901e+00 - 2.2666518e+00 5.1374744e-01 7.0571188e+00 - 2.2009774e+00 4.9586266e-01 7.2229094e+00 - 2.0619716e+00 4.5589393e-01 7.1176056e+00 - 1.8949149e+00 4.0670167e-01 6.8733579e+00 - 1.8385551e+00 3.9091851e-01 7.0927536e+00 - 1.6413044e+00 3.3351252e-01 6.6465475e+00 - 1.1521381e+00 1.9194831e-01 4.5357344e+00 - 1.0961588e+00 1.7581011e-01 4.5668129e+00 - 1.1225053e+00 1.8314798e-01 5.1501084e+00 - 1.0501255e+00 1.6299571e-01 5.1410363e+00 - 9.8291250e-01 1.4343117e-01 5.1702506e+00 - 1.0264719e+00 1.5693472e-01 6.3223378e+00 - 9.1548836e-01 1.2462953e-01 6.0621927e+00 - 8.1802043e-01 9.5849382e-02 5.8893984e+00 - 7.3101343e-01 7.1326001e-02 5.7746015e+00 - 6.5154657e-01 4.7704084e-02 5.8081966e+00 - 5.9842102e-01 3.4128638e-02 7.6299399e+00 - 2.4911881e+00 5.1026720e-01 -1.0145496e+00 - 2.5603471e+00 5.2724538e-01 -1.0127102e+00 - 2.6295787e+00 5.4531905e-01 -1.0089228e+00 - 2.7069473e+00 5.6566843e-01 -1.0100037e+00 - 2.7923969e+00 5.8733104e-01 -1.0152042e+00 - 2.8707318e+00 6.0684965e-01 -1.0116444e+00 - 2.9572694e+00 6.2968525e-01 -1.0121035e+00 - 3.0528901e+00 6.5380321e-01 -1.0160862e+00 - 3.1485279e+00 6.7805911e-01 -1.0172723e+00 - 3.2462409e+00 7.0333888e-01 -1.0155180e+00 - 3.3439711e+00 7.2875659e-01 -1.0109672e+00 - 3.4579255e+00 7.5781251e-01 -1.0144055e+00 - 3.5728997e+00 7.8698042e-01 -1.0143513e+00 - 3.7061616e+00 8.2071680e-01 -1.0212435e+00 - 3.8405083e+00 8.5560153e-01 -1.0238937e+00 - 3.9839559e+00 8.9191149e-01 -1.0271710e+00 - 4.1193538e+00 9.2715947e-01 -1.0212351e+00 - 4.2902679e+00 9.7060295e-01 -1.0292390e+00 - 4.4632725e+00 1.0151934e+00 -1.0318056e+00 - 4.6454505e+00 1.0623047e+00 -1.0330514e+00 - 4.8560225e+00 1.1154082e+00 -1.0406753e+00 - 5.0768374e+00 1.1720577e+00 -1.0452332e+00 - 5.2986955e+00 1.2290064e+00 -1.0425034e+00 - 5.5581683e+00 1.2953617e+00 -1.0469778e+00 - 5.8369805e+00 1.3666536e+00 -1.0497125e+00 - 6.1169096e+00 1.4393500e+00 -1.0430116e+00 - 6.4455611e+00 1.5228411e+00 -1.0424505e+00 - 6.8027801e+00 1.6147421e+00 -1.0397772e+00 - 7.2078106e+00 1.7187120e+00 -1.0388956e+00 - 7.6616663e+00 1.8348135e+00 -1.0373118e+00 - 8.2009636e+00 1.9725135e+00 -1.0422268e+00 - 8.7901845e+00 2.1236018e+00 -1.0400005e+00 - 9.4954065e+00 2.3045432e+00 -1.0428664e+00 - 1.0412191e+01 2.5389779e+00 -1.0644952e+00 - 1.1426766e+01 2.7993180e+00 -1.0716855e+00 - 1.2960140e+01 3.1922293e+00 -1.1311701e+00 - 1.4403167e+01 3.5619436e+00 -1.1213695e+00 - 1.6770952e+01 4.1681058e+00 -1.1839086e+00 - 1.9385250e+01 4.8384375e+00 -1.1895587e+00 - 2.1908229e+01 5.4842973e+00 -1.0922132e+00 - 2.3388740e+01 5.8637120e+00 -8.2149977e-01 - 2.5340514e+01 6.3642840e+00 -5.2723181e-01 - 2.4210545e+01 6.0751158e+00 -2.9404724e-02 - 2.5928570e+01 6.5160313e+00 3.5465422e-01 - 2.2215072e+01 5.5652139e+00 1.2316748e+00 - 2.2905305e+01 5.7415590e+00 1.6428384e+00 - 2.2784533e+01 5.7114915e+00 2.0414560e+00 - 2.2202601e+01 5.5621703e+00 2.4065507e+00 - 2.1152422e+01 5.2937543e+00 2.7125268e+00 - 1.9808907e+01 4.9494698e+00 2.9518671e+00 - 2.1812543e+01 5.4636554e+00 3.5427104e+00 - 1.7397366e+01 4.3323188e+00 3.3254009e+00 - 1.7614194e+01 4.3874980e+00 3.6698704e+00 - 1.8082565e+01 4.5073741e+00 4.0677676e+00 - 1.8465533e+01 4.6064761e+00 4.4686185e+00 - 1.7901438e+01 4.4617455e+00 4.6853941e+00 - 1.7741649e+01 4.4216706e+00 4.9765127e+00 - 1.8133751e+01 4.5214356e+00 5.4018047e+00 - 1.8928298e+01 4.7255285e+00 5.9531310e+00 - 1.7609387e+01 4.3877608e+00 5.9296744e+00 - 1.7338486e+01 4.3182699e+00 6.1800770e+00 - 1.8503971e+01 4.6173533e+00 6.8936366e+00 - 1.8998238e+01 4.7442744e+00 7.4243909e+00 - 1.9324485e+01 4.8283248e+00 7.9176469e+00 - 2.0682936e+01 5.1767404e+00 8.8290304e+00 - 1.7287023e+01 4.3065502e+00 7.8595432e+00 - 1.7293298e+01 4.3087786e+00 8.2147328e+00 - 1.7621618e+01 4.3933141e+00 8.7202673e+00 - 1.8704172e+01 4.6706541e+00 9.6019167e+00 - 1.8284517e+01 4.5631520e+00 9.7947381e+00 - 2.2741424e+01 5.7070450e+00 1.2495034e+01 - 1.7264671e+01 4.3022108e+00 1.0045791e+01 - 2.0493678e+01 5.1305586e+00 1.2251093e+01 - 2.0292320e+01 5.0790489e+00 1.2604709e+01 - 1.9442475e+01 4.8614771e+00 1.2562615e+01 - 2.0522913e+01 5.1393156e+00 1.3714086e+01 - 2.0386893e+01 5.1048530e+00 1.4126832e+01 - 6.9042204e+00 1.6444941e+00 5.3935664e+00 - 6.7334238e+00 1.6009584e+00 5.4402219e+00 - 6.7360449e+00 1.6022195e+00 5.6100531e+00 - 4.6819377e+00 1.0748215e+00 4.2076709e+00 - 4.5731523e+00 1.0468872e+00 4.2399577e+00 - 4.5031371e+00 1.0290411e+00 4.3003430e+00 - 6.1557055e+00 1.4536832e+00 5.8314220e+00 - 6.0440087e+00 1.4250480e+00 5.9066142e+00 - 5.8445078e+00 1.3735559e+00 5.8995723e+00 - 5.6889316e+00 1.3341887e+00 5.9275055e+00 - 4.7706387e+00 1.0977104e+00 5.1998201e+00 - 4.2851418e+00 9.7347784e-01 4.8549085e+00 - 4.2866350e+00 9.7427889e-01 4.9939313e+00 - 4.1655497e+00 9.4295085e-01 5.0035331e+00 - 4.0843130e+00 9.2229114e-01 5.0542143e+00 - 3.9959114e+00 8.9960249e-01 5.0957283e+00 - 3.9953316e+00 8.9888033e-01 5.2419478e+00 - 3.7015593e+00 8.2365155e-01 5.0261992e+00 - 3.6755103e+00 8.1774629e-01 5.1380888e+00 - 3.6749657e+00 8.1730496e-01 5.2900012e+00 - 3.5507895e+00 7.8590383e-01 5.2741943e+00 - 3.5114084e+00 7.7536117e-01 5.3774839e+00 - 3.2951680e+00 7.2024003e-01 5.2165343e+00 - 3.5646856e+00 7.8916004e-01 5.8005975e+00 - 3.4926817e+00 7.7097987e-01 5.8720252e+00 - 3.3347168e+00 7.3066163e-01 5.7971932e+00 - 3.1449865e+00 6.8203628e-01 5.6578867e+00 - 3.0094512e+00 6.4723697e-01 5.6002657e+00 - 2.9496589e+00 6.3174597e-01 5.6800960e+00 - 2.8478974e+00 6.0574554e-01 5.6791032e+00 - 2.4059394e+00 4.9180082e-01 4.9684652e+00 - 2.3675785e+00 4.8188921e-01 5.0655097e+00 - 2.6429752e+00 5.5296439e-01 5.8817169e+00 - 2.5525019e+00 5.3030971e-01 5.9012148e+00 - 2.5799673e+00 5.3721941e-01 6.2148920e+00 - 2.6434937e+00 5.5409931e-01 6.6519077e+00 - 2.3178914e+00 4.6974595e-01 6.0524316e+00 - 2.5161349e+00 5.2167706e-01 6.9144140e+00 - 2.3692550e+00 4.8411194e-01 6.8075385e+00 - 2.3436461e+00 4.7708237e-01 7.0789775e+00 - 2.2811514e+00 4.6152746e-01 7.2551464e+00 - 2.0909339e+00 4.1261879e-01 6.9682749e+00 - 1.9583246e+00 3.7863859e-01 6.8701456e+00 - 1.9061420e+00 3.6511991e-01 7.0998166e+00 - 1.8499658e+00 3.5080491e-01 7.3489755e+00 - 1.4999559e+00 2.6008192e-01 6.1274965e+00 - 1.0963014e+00 1.5571840e-01 4.3645524e+00 - 1.1764959e+00 1.7698927e-01 5.2330813e+00 - 1.0907174e+00 1.5476217e-01 5.1457976e+00 - 1.0205728e+00 1.3742884e-01 5.1557963e+00 - 9.6295275e-01 1.2270692e-01 5.2739226e+00 - 9.6144079e-01 1.2265857e-01 6.0582016e+00 - 8.8236728e-01 1.0217991e-01 6.1555181e+00 - 7.6898344e-01 7.3472074e-02 5.7024727e+00 - 6.8957744e-01 5.2399370e-02 5.7067057e+00 - 6.1271851e-01 3.3543871e-02 5.8393721e+00 - 5.4156293e-01 1.6125968e-02 7.4206192e+00 - 2.5361611e+00 4.5860843e-01 -1.0103766e+00 - 2.6133299e+00 4.7581422e-01 -1.0144051e+00 - 2.6834447e+00 4.9187787e-01 -1.0096229e+00 - 2.7616370e+00 5.0922520e-01 -1.0095595e+00 - 2.8409018e+00 5.2762235e-01 -1.0072517e+00 - 2.9353177e+00 5.4860297e-01 -1.0152774e+00 - 3.0226802e+00 5.6844638e-01 -1.0143925e+00 - 3.1191866e+00 5.9057403e-01 -1.0169809e+00 - 3.2166482e+00 6.1178222e-01 -1.0167263e+00 - 3.3141884e+00 6.3413516e-01 -1.0135250e+00 - 3.4208166e+00 6.5780987e-01 -1.0130482e+00 - 3.5447300e+00 6.8607901e-01 -1.0202137e+00 - 3.6615303e+00 7.1221891e-01 -1.0183193e+00 - 3.7956220e+00 7.4300251e-01 -1.0230685e+00 - 3.9316757e+00 7.7287518e-01 -1.0235797e+00 - 4.0850280e+00 8.0745066e-01 -1.0295359e+00 - 4.2394094e+00 8.4221202e-01 -1.0305015e+00 - 4.4130932e+00 8.8161443e-01 -1.0357200e+00 - 4.5878097e+00 9.2123228e-01 -1.0353486e+00 - 4.7899189e+00 9.6687831e-01 -1.0418515e+00 - 4.9930670e+00 1.0127891e+00 -1.0417658e+00 - 5.2246178e+00 1.0647611e+00 -1.0466599e+00 - 5.4582124e+00 1.1169917e+00 -1.0438699e+00 - 5.7294254e+00 1.1786583e+00 -1.0476848e+00 - 6.0016330e+00 1.2397209e+00 -1.0422648e+00 - 6.3215587e+00 1.3115892e+00 -1.0439800e+00 - 6.6618404e+00 1.3884816e+00 -1.0409625e+00 - 7.0508637e+00 1.4763213e+00 -1.0409886e+00 - 7.4693506e+00 1.5706644e+00 -1.0358103e+00 - 7.9832915e+00 1.6867621e+00 -1.0420064e+00 - 8.5287257e+00 1.8095084e+00 -1.0376110e+00 - 9.1706613e+00 1.9543428e+00 -1.0366031e+00 - 9.8908250e+00 2.1168104e+00 -1.0297390e+00 - 1.0987613e+01 2.3634498e+00 -1.0714036e+00 - 1.2289621e+01 2.6569943e+00 -1.1106413e+00 - 1.3846567e+01 3.0076492e+00 -1.1440573e+00 - 1.5591503e+01 3.4005488e+00 -1.1484778e+00 - 1.8656574e+01 4.0918179e+00 -1.2546626e+00 - 2.2678713e+01 4.9983699e+00 -9.5195010e-01 - 2.4518026e+01 5.4132633e+00 -6.8169726e-01 - 2.3851205e+01 5.2630553e+00 -2.1561094e-01 - 2.3498112e+01 5.1834132e+00 2.1502086e-01 - 2.4364556e+01 5.3798578e+00 1.4667446e+00 - 2.9565637e+01 6.5528655e+00 2.6097976e+00 - 2.4570911e+01 5.4269403e+00 2.7657549e+00 - 2.2379834e+01 4.9339469e+00 2.9991398e+00 - 1.8841136e+01 4.1360161e+00 3.0072786e+00 - 1.7496868e+01 3.8330316e+00 3.1684925e+00 - 1.7737714e+01 3.8877669e+00 3.5130359e+00 - 1.8192969e+01 3.9899994e+00 3.9032737e+00 - 1.8266235e+01 4.0074333e+00 4.2421811e+00 - 1.8159543e+01 3.9830323e+00 4.5499206e+00 - 1.8869107e+01 4.1438295e+00 5.0350223e+00 - 1.9139604e+01 4.2050235e+00 5.4446450e+00 - 2.1076273e+01 4.6419161e+00 6.2960305e+00 - 1.7592568e+01 3.8560685e+00 5.7261221e+00 - 1.7790912e+01 3.9014988e+00 6.1143398e+00 - 1.7831638e+01 3.9104080e+00 6.4641813e+00 - 1.8125582e+01 3.9766942e+00 6.9038456e+00 - 1.9386631e+01 4.2611869e+00 7.7023396e+00 - 1.8655704e+01 4.0969906e+00 7.8090671e+00 - 1.7827046e+01 3.9104615e+00 7.8522190e+00 - 1.8340806e+01 4.0262301e+00 8.4244537e+00 - 2.0463806e+01 4.5053840e+00 9.7269648e+00 - 1.7479653e+01 3.8323552e+00 8.7848591e+00 - 1.7176695e+01 3.7643915e+00 9.0068491e+00 - 1.7669266e+01 3.8754837e+00 9.6206962e+00 - 1.7432456e+01 3.8224851e+00 9.8810885e+00 - 1.9636642e+01 4.3201383e+00 1.1472844e+01 - 1.9387747e+01 4.2639180e+00 1.1774821e+01 - 1.9150101e+01 4.2112424e+00 1.2081059e+01 - 1.9568817e+01 4.3054430e+00 1.2790011e+01 - 1.9546981e+01 4.3013549e+00 1.3246310e+01 - 1.9646240e+01 4.3235176e+00 1.3792680e+01 - 6.9523242e+00 1.4582758e+00 5.4792500e+00 - 6.7156301e+00 1.4043559e+00 5.4790656e+00 - 4.6675812e+00 9.4178830e-01 4.1170018e+00 - 4.6455615e+00 9.3696511e-01 4.2151963e+00 - 4.5665308e+00 9.1940692e-01 4.2704167e+00 - 6.0091167e+00 1.2459733e+00 5.5911627e+00 - 6.0279630e+00 1.2498492e+00 5.7727796e+00 - 4.8794833e+00 9.9086475e-01 4.9179654e+00 - 4.6670052e+00 9.4272923e-01 4.8617776e+00 - 4.5727068e+00 9.2165642e-01 4.9084547e+00 - 4.5191249e+00 9.0911875e-01 4.9947091e+00 - 4.5195789e+00 9.0913602e-01 5.1368808e+00 - 4.5700330e+00 9.2109104e-01 5.3378286e+00 - 4.1169301e+00 8.1895576e-01 4.9925282e+00 - 4.0684613e+00 8.0812453e-01 5.0789672e+00 - 4.0179329e+00 7.9639261e-01 5.1649628e+00 - 3.8899412e+00 7.6768046e-01 5.1582582e+00 - 3.9108145e+00 7.7219598e-01 5.3350251e+00 - 3.7757021e+00 7.4232374e-01 5.3165070e+00 - 3.7843736e+00 7.4422893e-01 5.4864693e+00 - 3.5583852e+00 6.9312685e-01 5.3339921e+00 - 3.2833315e+00 6.3055232e-01 5.0928734e+00 - 3.3328569e+00 6.4209131e-01 5.3246855e+00 - 3.5763855e+00 6.9703299e-01 5.8784603e+00 - 3.5239196e+00 6.8537588e-01 5.9837880e+00 - 3.2886296e+00 6.3227565e-01 5.7798031e+00 - 3.0655708e+00 5.8253638e-01 5.5775794e+00 - 2.9690511e+00 5.5978621e-01 5.5878079e+00 - 2.8807947e+00 5.4032173e-01 5.6136429e+00 - 2.5195130e+00 4.5863198e-01 5.0849428e+00 - 2.4413684e+00 4.4114987e-01 5.1024074e+00 - 2.6261163e+00 4.8270996e-01 5.6989566e+00 - 2.5808467e+00 4.7333305e-01 5.8185452e+00 - 2.6205204e+00 4.8238822e-01 6.1498631e+00 - 2.5035638e+00 4.5551599e-01 6.1128625e+00 - 2.3497193e+00 4.2061778e-01 5.9704547e+00 - 2.6069568e+00 4.7989846e-01 6.9712826e+00 - 2.0592919e+00 3.5522856e-01 5.6742014e+00 - 2.3660701e+00 4.2513821e-01 6.9289133e+00 - 2.2851349e+00 4.0688767e-01 7.0284342e+00 - 2.1528517e+00 3.7706105e-01 6.9537271e+00 - 2.0205517e+00 3.4761554e-01 6.8664859e+00 - 1.9509237e+00 3.3131615e-01 7.0190063e+00 - 1.8721268e+00 3.1356372e-01 7.1513299e+00 - 1.5240374e+00 2.3479267e-01 5.9910257e+00 - 1.4222690e+00 2.1234684e-01 5.9202717e+00 - 1.0852651e+00 1.3448634e-01 4.4486703e+00 - 1.1322447e+00 1.4545151e-01 5.1502057e+00 - 1.0601675e+00 1.2977973e-01 5.1509231e+00 - 9.9849523e-01 1.1585492e-01 5.2397989e+00 - 1.0282190e+00 1.2327645e-01 6.2526994e+00 - 9.1778238e-01 9.8435933e-02 6.0223199e+00 - 8.2391954e-01 7.6932427e-02 5.8994064e+00 - 7.3091597e-01 5.6321423e-02 5.7147675e+00 - 6.5174940e-01 3.8193488e-02 5.7381776e+00 - 5.9886882e-01 2.7607150e-02 7.5799969e+00 - 2.5110408e+00 3.9105845e-01 -1.0074902e+00 - 2.5809553e+00 4.0397358e-01 -1.0057554e+00 - 2.6651357e+00 4.2146742e-01 -1.0156485e+00 - 2.7360736e+00 4.3452410e-01 -1.0098219e+00 - 2.8232769e+00 4.5206322e-01 -1.0151302e+00 - 2.9023678e+00 4.6752370e-01 -1.0115751e+00 - 2.9905386e+00 4.8424190e-01 -1.0120429e+00 - 3.0868551e+00 5.0330478e-01 -1.0159808e+00 - 3.1841261e+00 5.2144328e-01 -1.0171756e+00 - 3.2906049e+00 5.4289252e-01 -1.0212939e+00 - 3.3899695e+00 5.6220268e-01 -1.0165520e+00 - 3.4974250e+00 5.8290490e-01 -1.0143317e+00 - 3.6221055e+00 6.0720460e-01 -1.0197042e+00 - 3.7568813e+00 6.3283951e-01 -1.0263062e+00 - 3.8846658e+00 6.5834895e-01 -1.0237477e+00 - 4.0214885e+00 6.8426696e-01 -1.0221662e+00 - 4.1766093e+00 7.1483718e-01 -1.0258332e+00 - 4.3327584e+00 7.4558836e-01 -1.0246094e+00 - 4.5162309e+00 7.8129687e-01 -1.0317086e+00 - 4.7280335e+00 8.2197122e-01 -1.0457356e+00 - 4.9135787e+00 8.5816974e-01 -1.0404564e+00 - 5.1467392e+00 9.0383720e-01 -1.0491545e+00 - 5.3626627e+00 9.4529451e-01 -1.0424199e+00 - 5.6161382e+00 9.9514174e-01 -1.0432395e+00 - 5.8989722e+00 1.0501358e+00 -1.0460962e+00 - 6.1919471e+00 1.1068296e+00 -1.0427915e+00 - 6.5052104e+00 1.1674913e+00 -1.0359030e+00 - 6.8772903e+00 1.2402731e+00 -1.0365836e+00 - 7.3060901e+00 1.3234644e+00 -1.0414318e+00 - 7.7754471e+00 1.4144339e+00 -1.0423084e+00 - 8.2945249e+00 1.5156235e+00 -1.0394905e+00 - 8.9109081e+00 1.6357416e+00 -1.0421118e+00 - 9.6823546e+00 1.7859718e+00 -1.0576886e+00 - 1.0563272e+01 1.9569311e+00 -1.0680552e+00 - 1.1582093e+01 2.1549321e+00 -1.0730977e+00 - 1.3165376e+01 2.4623446e+00 -1.1372835e+00 - 1.4792493e+01 2.7796203e+00 -1.1515640e+00 - 1.6978106e+01 3.2047910e+00 -1.1820235e+00 - 1.9656473e+01 3.7256342e+00 -1.1912081e+00 - 2.2281407e+01 4.2356363e+00 -1.1000054e+00 - 2.3733002e+01 4.5177675e+00 -8.2381401e-01 - 2.4750011e+01 4.7166343e+00 -4.7054604e-01 - 2.4045904e+01 4.5795373e+00 -7.9801150e-03 - 2.4363568e+01 4.6419716e+00 4.0319258e-01 - 2.4732931e+01 4.7138480e+00 8.2499446e-01 - 2.4614710e+01 4.6911834e+00 1.2545698e+00 - 2.4586712e+01 4.6860736e+00 1.6828223e+00 - 2.4561704e+01 4.6807579e+00 2.1105660e+00 - 2.3157738e+01 4.4082853e+00 2.4498643e+00 - 2.2004080e+01 4.1844668e+00 2.7604869e+00 - 2.4393520e+01 4.6488990e+00 3.3842434e+00 - 1.8508728e+01 3.5047491e+00 3.1210692e+00 - 1.7943832e+01 3.3947450e+00 3.3695780e+00 - 1.8473304e+01 3.4978930e+00 3.7675227e+00 - 2.4229765e+01 4.6180110e+00 5.0864743e+00 - 2.1676919e+01 4.1216981e+00 5.0354023e+00 - 1.8883300e+01 3.5777207e+00 4.8426882e+00 - 1.8967623e+01 3.5945913e+00 5.2038827e+00 - 1.9570408e+01 3.7121578e+00 5.6984842e+00 - 1.8954682e+01 3.5926496e+00 5.8958115e+00 - 1.7563658e+01 3.3224337e+00 5.8522466e+00 - 2.2059171e+01 4.1972898e+00 7.5456175e+00 - 1.8145276e+01 3.4358013e+00 6.7008221e+00 - 1.9523637e+01 3.7042408e+00 7.5207101e+00 - 1.8521033e+01 3.5087857e+00 7.5361400e+00 - 1.8875474e+01 3.5783640e+00 8.0348420e+00 - 1.9162961e+01 3.6345651e+00 8.5261066e+00 - 1.9284996e+01 3.6580070e+00 8.9644399e+00 - 1.7444678e+01 3.3007526e+00 8.5408645e+00 - 1.7634692e+01 3.3377182e+00 8.9908268e+00 - 2.2372676e+01 4.2601812e+00 1.1674379e+01 - 2.0528149e+01 3.9014344e+00 1.1215659e+01 - 1.9184058e+01 3.6403946e+00 1.0949578e+01 - 1.9415952e+01 3.6850988e+00 1.1505232e+01 - 1.9445882e+01 3.6920182e+00 1.1963371e+01 - 1.9399574e+01 3.6826767e+00 1.2385137e+01 - 2.0129460e+01 3.8255361e+00 1.3300929e+01 - 1.9237037e+01 3.6520675e+00 1.3206460e+01 - 1.9188796e+01 3.6428452e+00 1.3648457e+01 - 6.8487699e+00 1.2380417e+00 5.4631189e+00 - 4.7366267e+00 8.2600181e-01 4.0912488e+00 - 4.6831564e+00 8.1590320e-01 4.1661684e+00 - 4.6439114e+00 8.0851081e-01 4.2522808e+00 - 4.8557543e+00 8.5032464e-01 4.5437742e+00 - 4.7189018e+00 8.2313695e-01 4.5569737e+00 - 4.5749987e+00 7.9586496e-01 4.5599081e+00 - 4.6597777e+00 8.1195333e-01 4.7646453e+00 - 4.6317642e+00 8.0693930e-01 4.8718973e+00 - 4.4288030e+00 7.6716335e-01 4.8138367e+00 - 4.3844720e+00 7.5828129e-01 4.9041590e+00 - 4.1794741e+00 7.1882014e-01 4.8297752e+00 - 4.1331245e+00 7.0988163e-01 4.9165084e+00 - 4.5558000e+00 7.9192385e-01 5.5269133e+00 - 4.0037650e+00 6.8424925e-01 5.0508344e+00 - 3.8068344e+00 6.4650708e-01 4.9602963e+00 - 3.7879442e+00 6.4258150e-01 5.0803543e+00 - 3.8454579e+00 6.5417566e-01 5.3028028e+00 - 3.8194736e+00 6.4878771e-01 5.4251794e+00 - 3.7487394e+00 6.3529538e-01 5.4915621e+00 - 3.5343628e+00 5.9322025e-01 5.3531861e+00 - 3.3658271e+00 5.6096124e-01 5.2662072e+00 - 3.2970417e+00 5.4696865e-01 5.3248930e+00 - 3.6124854e+00 6.0854973e-01 5.9987454e+00 - 3.3776879e+00 5.6299476e-01 5.8058995e+00 - 3.1459103e+00 5.1849363e-01 5.5975640e+00 - 3.0180113e+00 4.9310102e-01 5.5568533e+00 - 2.9400922e+00 4.7793623e-01 5.6010353e+00 - 2.6081260e+00 4.1321310e-01 5.1466102e+00 - 2.5760617e+00 4.0694455e-01 5.2640616e+00 - 2.7134963e+00 4.3392711e-01 5.7519867e+00 - 2.6560257e+00 4.2297799e-01 5.8452956e+00 - 2.5219452e+00 3.9692507e-01 5.7636050e+00 - 2.2641557e+00 3.4651412e-01 5.3643855e+00 - 2.4427759e+00 3.8113906e-01 6.0561316e+00 - 2.3976709e+00 3.7307759e-01 6.2023873e+00 - 2.1673603e+00 3.2835137e-01 5.8298512e+00 - 2.0781288e+00 3.1016282e-01 5.8398098e+00 - 2.3598311e+00 3.6535380e-01 7.0504471e+00 - 2.2135262e+00 3.3754145e-01 6.9386815e+00 - 2.1019758e+00 3.1574906e-01 6.9297318e+00 - 1.9996954e+00 2.9621767e-01 6.9573588e+00 - 1.9199647e+00 2.8007128e-01 7.0804977e+00 - 1.5686258e+00 2.1160659e-01 5.9621575e+00 - 1.7638401e+00 2.4981733e-01 7.3920350e+00 - 1.1041649e+00 1.2013673e-01 4.3645570e+00 - 1.1736486e+00 1.3412231e-01 5.1542135e+00 - 1.0986411e+00 1.2017745e-01 5.1457526e+00 - 1.0328556e+00 1.0656200e-01 5.1954903e+00 - 1.1750582e+00 1.3554513e-01 7.1421867e+00 - 9.8144796e-01 9.7775092e-02 6.2074883e+00 - 8.6894040e-01 7.5554005e-02 5.9062051e+00 - 7.7406709e-01 5.7107078e-02 5.7224723e+00 - 6.9184418e-01 4.0729286e-02 5.6966542e+00 - 6.1535210e-01 2.6352523e-02 5.8593348e+00 - 5.4056707e-01 1.1778096e-02 7.1906560e+00 - 2.5599633e+00 3.3881301e-01 -1.0103213e+00 - 2.6307616e+00 3.4972305e-01 -1.0074918e+00 - 2.7016313e+00 3.6171873e-01 -1.0029141e+00 - 2.7876471e+00 3.7625846e-01 -1.0094688e+00 - 2.8675469e+00 3.8859865e-01 -1.0071666e+00 - 2.9555887e+00 4.0325397e-01 -1.0089336e+00 - 3.0436458e+00 4.1803245e-01 -1.0082037e+00 - 3.1488560e+00 4.3531784e-01 -1.0169147e+00 - 3.2399409e+00 4.5018102e-01 -1.0108009e+00 - 3.3552563e+00 4.6888046e-01 -1.0191435e+00 - 3.4544482e+00 4.8526380e-01 -1.0129545e+00 - 3.5637275e+00 5.0291830e-01 -1.0092935e+00 - 3.6983078e+00 5.2544411e-01 -1.0181440e+00 - 3.8339116e+00 5.4811146e-01 -1.0229026e+00 - 3.9624037e+00 5.6865944e-01 -1.0184016e+00 - 4.1091299e+00 5.9283311e-01 -1.0196988e+00 - 4.2649607e+00 6.1846157e-01 -1.0210238e+00 - 4.4400337e+00 6.4773412e-01 -1.0265521e+00 - 4.6170773e+00 6.7616471e-01 -1.0264442e+00 - 4.8295936e+00 7.1192686e-01 -1.0375300e+00 - 5.0450867e+00 7.4685065e-01 -1.0416843e+00 - 5.2697041e+00 7.8338688e-01 -1.0426704e+00 - 5.5065036e+00 8.2237580e-01 -1.0400480e+00 - 5.7888250e+00 8.6914785e-01 -1.0475021e+00 - 6.0650550e+00 9.1391744e-01 -1.0421041e+00 - 6.3797972e+00 9.6619689e-01 -1.0406184e+00 - 6.7238587e+00 1.0227937e+00 -1.0377244e+00 - 7.1164803e+00 1.0873421e+00 -1.0378253e+00 - 7.5394421e+00 1.1563297e+00 -1.0328256e+00 - 8.0403761e+00 1.2393585e+00 -1.0340061e+00 - 8.6201846e+00 1.3345711e+00 -1.0372756e+00 - 9.2222904e+00 1.4332151e+00 -1.0251327e+00 - 9.9508868e+00 1.5530028e+00 -1.0191189e+00 - 1.1089103e+01 1.7396423e+00 -1.0672909e+00 - 1.2367042e+01 1.9497124e+00 -1.0998594e+00 - 1.3990023e+01 2.2167001e+00 -1.1420713e+00 - 1.5745643e+01 2.5047015e+00 -1.1451881e+00 - 1.8875143e+01 3.0193597e+00 -1.2552738e+00 - 2.2865106e+01 3.6754505e+00 -9.4521427e-01 - 2.4095569e+01 3.8774653e+00 -6.3246736e-01 - 2.3814666e+01 3.8317125e+00 -1.9914695e-01 - 2.7826419e+01 4.4917756e+00 1.5291318e+00 - 2.5081749e+01 4.0412071e+00 2.3469603e+00 - 2.7250189e+01 4.3981299e+00 2.9406390e+00 - 2.6769917e+01 4.3192602e+00 3.3735196e+00 - 2.6234944e+01 4.2315846e+00 3.7847446e+00 - 1.9426546e+01 3.1124895e+00 3.3875649e+00 - 2.2596403e+01 3.6337110e+00 4.1851265e+00 - 2.0169867e+01 3.2349323e+00 4.1914412e+00 - 1.8188549e+01 2.9092758e+00 4.1919013e+00 - 1.8440708e+01 2.9507472e+00 4.5658648e+00 - 2.2834571e+01 3.6740115e+00 5.8505267e+00 - 1.8124863e+01 2.8988150e+00 5.1552976e+00 - 1.8222184e+01 2.9155913e+00 5.5102088e+00 - 1.9304909e+01 3.0931705e+00 6.1406623e+00 - 2.4085868e+01 3.8807040e+00 7.8972534e+00 - 2.1426339e+01 3.4429681e+00 7.5227542e+00 - 1.7906512e+01 2.8646007e+00 6.7646143e+00 - 1.8345273e+01 2.9370129e+00 7.2613544e+00 - 1.8485206e+01 2.9598481e+00 7.6688693e+00 - 1.9379993e+01 3.1067377e+00 8.3817952e+00 - 1.9542410e+01 3.1344971e+00 8.8349852e+00 - 2.0021933e+01 3.2127094e+00 9.4374185e+00 - 2.0278669e+01 3.2555247e+00 9.9650771e+00 - 1.8415252e+01 2.9489377e+00 9.5036010e+00 - 2.0152727e+01 3.2352384e+00 1.0756029e+01 - 1.9393930e+01 3.1105826e+00 1.0796999e+01 - 1.9187488e+01 3.0764661e+00 1.1110940e+01 - 2.1096793e+01 3.3910495e+00 1.2616527e+01 - 1.9647588e+01 3.1532858e+00 1.2247019e+01 - 1.9348920e+01 3.1037524e+00 1.2522141e+01 - 2.0301596e+01 3.2616229e+00 1.3586902e+01 - 2.0330171e+01 3.2663505e+00 1.4604749e+01 - 4.7853921e+00 7.0683051e-01 4.0534728e+00 - 4.7239026e+00 6.9694453e-01 4.1229246e+00 - 4.4493604e+00 6.5165215e-01 4.0283320e+00 - 4.2488221e+00 6.1825926e-01 3.9805546e+00 - 4.1203149e+00 5.9707399e-01 3.9833942e+00 - 4.0678941e+00 5.8835705e-01 4.0470253e+00 - 4.7370421e+00 6.9909780e-01 4.7473077e+00 - 4.2614669e+00 6.2058423e-01 4.4463366e+00 - 3.9928638e+00 5.7607741e-01 4.3142224e+00 - 4.3881592e+00 6.4157756e-01 4.8208832e+00 - 4.3012739e+00 6.2709477e-01 4.8678904e+00 - 4.1453890e+00 6.0206595e-01 4.8408512e+00 - 4.1184377e+00 5.9801798e-01 4.9486498e+00 - 4.1097149e+00 5.9600404e-01 5.0791637e+00 - 3.8511889e+00 5.5371784e-01 4.9232486e+00 - 3.7703908e+00 5.4068889e-01 4.9665421e+00 - 3.8318257e+00 5.5095562e-01 5.1872297e+00 - 3.7225769e+00 5.3302838e-01 5.1983001e+00 - 3.6326070e+00 5.1800764e-01 5.2307348e+00 - 3.5477265e+00 5.0398706e-01 5.2692965e+00 - 3.5360291e+00 5.0179799e-01 5.4128535e+00 - 3.3220375e+00 4.6692499e-01 5.2584004e+00 - 3.2269733e+00 4.5137881e-01 5.2740718e+00 - 3.2458151e+00 4.5418708e-01 5.4745645e+00 - 3.1283842e+00 4.3517182e-01 5.4537997e+00 - 3.0658511e+00 4.2446758e-01 5.5257013e+00 - 2.9351928e+00 4.0371393e-01 5.4740656e+00 - 2.6873373e+00 3.6241741e-01 5.1895774e+00 - 2.8916508e+00 3.9649610e-01 5.7804676e+00 - 2.9422377e+00 4.0435423e-01 6.1009639e+00 - 2.8125985e+00 3.8370764e-01 6.0527208e+00 - 2.6451409e+00 3.5563745e-01 5.9100602e+00 - 2.3532184e+00 3.0726735e-01 5.4498755e+00 - 2.2539800e+00 2.9102864e-01 5.4263583e+00 - 2.3180591e+00 3.0222460e-01 5.8304100e+00 - 2.2545656e+00 2.9136721e-01 5.9182447e+00 - 2.1032834e+00 2.6706016e-01 5.7498673e+00 - 2.0847543e+00 2.6344112e-01 5.9774405e+00 - 2.2628003e+00 2.9377944e-01 6.8849675e+00 - 1.9856251e+00 2.4786047e-01 6.2902051e+00 - 1.8936158e+00 2.3261576e-01 6.3156548e+00 - 1.7400872e+00 2.0746255e-01 6.0871587e+00 - 1.6151474e+00 1.8676389e-01 5.9426706e+00 - 1.5363771e+00 1.7386531e-01 5.9910513e+00 - 1.7077961e+00 2.0264804e-01 7.3637696e+00 - 1.2242171e+00 1.2215019e-01 5.2169690e+00 - 1.1399872e+00 1.0787101e-01 5.1502095e+00 - 1.0682131e+00 9.6684645e-02 5.1608162e+00 - 1.0108999e+00 8.6477707e-02 5.2894310e+00 - 1.0092620e+00 8.7485774e-02 6.0140852e+00 - 9.1901720e-01 7.1815039e-02 5.9725625e+00 - 8.3088073e-01 5.7434205e-02 5.9393734e+00 - 7.3181750e-01 4.0747187e-02 5.6648677e+00 - 6.5314107e-01 2.8083334e-02 5.7382672e+00 - 6.0044177e-01 2.0492788e-02 7.5800377e+00 - 2.5228474e+00 2.7133142e-01 -1.0004557e+00 - 2.6076492e+00 2.8265992e-01 -1.0125516e+00 - 2.6793904e+00 2.9255196e-01 -1.0088767e+00 - 2.7581513e+00 3.0279612e-01 -1.0097681e+00 - 2.8379233e+00 3.1308328e-01 -1.0085652e+00 - 2.9258366e+00 3.2568064e-01 -1.0115315e+00 - 3.0066351e+00 3.3613398e-01 -1.0057375e+00 - 3.1045834e+00 3.4906960e-01 -1.0098838e+00 - 3.1944797e+00 3.6092353e-01 -1.0052163e+00 - 3.3015314e+00 3.7530408e-01 -1.0095902e+00 - 3.4096010e+00 3.8978184e-01 -1.0107712e+00 - 3.5176904e+00 4.0441725e-01 -1.0087562e+00 - 3.6439432e+00 4.2159766e-01 -1.0141877e+00 - 3.7802901e+00 4.4010343e-01 -1.0210485e+00 - 3.9085879e+00 4.5755215e-01 -1.0185961e+00 - 4.0549983e+00 4.7662281e-01 -1.0220426e+00 - 4.1944180e+00 4.9557293e-01 -1.0162286e+00 - 4.3701093e+00 5.1865549e-01 -1.0244591e+00 - 4.5458954e+00 5.4301091e-01 -1.0271461e+00 - 4.7327302e+00 5.6776730e-01 -1.0285194e+00 - 4.9387587e+00 5.9526444e-01 -1.0321488e+00 - 5.1549065e+00 6.2428892e-01 -1.0331125e+00 - 5.3912567e+00 6.5607745e-01 -1.0346377e+00 - 5.6468173e+00 6.9073974e-01 -1.0357223e+00 - 5.9326128e+00 7.2848462e-01 -1.0389479e+00 - 6.2093833e+00 7.6541026e-01 -1.0292615e+00 - 6.5447139e+00 8.1034493e-01 -1.0294430e+00 - 6.9295378e+00 8.6213437e-01 -1.0333719e+00 - 7.3244671e+00 9.1482371e-01 -1.0270948e+00 - 7.7981737e+00 9.7840437e-01 -1.0288500e+00 - 8.3315070e+00 1.0504805e+00 -1.0293897e+00 - 8.9244260e+00 1.1302078e+00 -1.0255685e+00 - 9.6455799e+00 1.2268813e+00 -1.0294822e+00 - 1.0563650e+01 1.3500522e+00 -1.0480335e+00 - 1.1630177e+01 1.4925719e+00 -1.0619476e+00 - 1.3180380e+01 1.7000306e+00 -1.1188962e+00 - 1.4813602e+01 1.9196201e+00 -1.1336021e+00 - 1.6902318e+01 2.1998511e+00 -1.1506068e+00 - 1.9803025e+01 2.5886001e+00 -1.1860867e+00 - 2.2590997e+01 2.9626852e+00 -1.1087100e+00 - 2.3197151e+01 3.0445152e+00 -7.6395336e-01 - 2.3788162e+01 3.1233017e+00 -3.9792722e-01 - 2.3759189e+01 3.1194728e+00 1.4548790e-02 - 2.7147929e+01 3.5744657e+00 1.2794002e+00 - 2.7465675e+01 3.6181680e+00 1.7577781e+00 - 2.7141898e+01 3.5743607e+00 2.2185008e+00 - 2.7185835e+01 3.5801857e+00 2.6918268e+00 - 2.7093452e+01 3.5687450e+00 3.1566333e+00 - 4.4215594e+01 5.8658892e+00 5.3205660e+00 - 1.9313212e+01 2.5249872e+00 3.1950709e+00 - 1.8780784e+01 2.4539591e+00 3.4599795e+00 - 1.8588830e+01 2.4282613e+00 3.7590980e+00 - 1.8733407e+01 2.4480303e+00 4.1105661e+00 - 1.8452456e+01 2.4096250e+00 4.3889337e+00 - 1.8246322e+01 2.3820997e+00 4.6744128e+00 - 2.0346767e+01 2.6641291e+00 5.4747554e+00 - 2.1142501e+01 2.7714194e+00 6.0374576e+00 - 1.8405253e+01 2.4046527e+00 5.7047927e+00 - 1.9093781e+01 2.4968499e+00 6.2371621e+00 - 1.9171795e+01 2.5079174e+00 6.6152021e+00 - 1.9204299e+01 2.5123237e+00 6.9855414e+00 - 1.7735224e+01 2.3145543e+00 6.8516771e+00 - 1.8351151e+01 2.3975044e+00 7.4124847e+00 - 1.8784163e+01 2.4564223e+00 7.9334549e+00 - 1.8892520e+01 2.4704014e+00 8.3464075e+00 - 1.9045460e+01 2.4911497e+00 8.7882874e+00 - 2.0434505e+01 2.6785112e+00 9.7860234e+00 - 2.0576442e+01 2.6971568e+00 1.0273130e+01 - 2.2737677e+01 2.9879946e+00 1.1748397e+01 - 2.0385022e+01 2.6719077e+00 1.1046108e+01 - 2.3731386e+01 3.1220719e+00 1.3252119e+01 - 2.1235825e+01 2.7863794e+00 1.2405500e+01 - 1.9871331e+01 2.6039648e+00 1.2102225e+01 - 1.9608654e+01 2.5684771e+00 1.2400961e+01 - 2.0674863e+01 2.7122358e+00 1.3521587e+01 - 2.0329325e+01 2.6664075e+00 1.3794112e+01 - 4.4546311e+00 5.3255981e-01 3.8585575e+00 - 4.6361928e+00 5.5669537e-01 4.1006476e+00 - 4.3621717e+00 5.2020807e-01 4.0022132e+00 - 4.2318648e+00 5.0226266e-01 4.0075073e+00 - 4.1329985e+00 4.8951383e-01 4.0344782e+00 - 4.1333695e+00 4.8989919e-01 4.1435915e+00 - 4.1073674e+00 4.8591569e-01 4.2336591e+00 - 4.0439218e+00 4.7750406e-01 4.2900342e+00 - 4.1871479e+00 4.9657200e-01 4.5450263e+00 - 4.2099045e+00 5.0057917e-01 4.6936719e+00 - 4.0349760e+00 4.7658734e-01 4.6441713e+00 - 4.1215526e+00 4.8838787e-01 4.8657295e+00 - 4.1209769e+00 4.8821433e-01 5.0028106e+00 - 3.9196836e+00 4.6095089e-01 4.9159878e+00 - 3.7934029e+00 4.4406291e-01 4.9070874e+00 - 3.7573350e+00 4.3898068e-01 5.0031786e+00 - 3.7923249e+00 4.4430212e-01 5.1931350e+00 - 3.5869105e+00 4.1676985e-01 5.0757131e+00 - 3.4565273e+00 3.9924671e-01 5.0490474e+00 - 3.5300934e+00 4.0949573e-01 5.3043037e+00 - 3.3093720e+00 3.7968086e-01 5.1425339e+00 - 3.1768920e+00 3.6147557e-01 5.0995946e+00 - 3.1428797e+00 3.5674540e-01 5.2052677e+00 - 3.0804730e+00 3.4859848e-01 5.2682315e+00 - 2.9612133e+00 3.3310566e-01 5.2353895e+00 - 2.8682792e+00 3.2005500e-01 5.2433152e+00 - 2.7662401e+00 3.0657784e-01 5.2315938e+00 - 3.0890672e+00 3.5048817e-01 6.0432413e+00 - 3.0633181e+00 3.4646316e-01 6.2135083e+00 - 3.0152687e+00 3.4001530e-01 6.3482885e+00 - 2.7424337e+00 3.0363684e-01 5.9911223e+00 - 2.3717746e+00 2.5398459e-01 5.3690865e+00 - 2.3266651e+00 2.4795010e-01 5.4753931e+00 - 2.2632352e+00 2.3914750e-01 5.5441026e+00 - 2.2253391e+00 2.3449797e-01 5.6870416e+00 - 2.1772232e+00 2.2751802e-01 5.8110350e+00 - 2.0598176e+00 2.1179942e-01 5.7355402e+00 - 2.0158602e+00 2.0590297e-01 5.8863877e+00 - 1.9617407e+00 1.9865335e-01 6.0178407e+00 - 2.0936946e+00 2.1665131e-01 6.8430583e+00 - 1.7728418e+00 1.7347591e-01 6.0082339e+00 - 1.6993788e+00 1.6383569e-01 6.0882604e+00 - 1.6197998e+00 1.5354326e-01 6.1477315e+00 - 1.7855559e+00 1.7571077e-01 7.4410126e+00 - 1.3197968e+00 1.1314884e-01 5.5152912e+00 - 1.1802110e+00 9.3601540e-02 5.1541694e+00 - 1.1065055e+00 8.4086581e-02 5.1556944e+00 - 1.0420829e+00 7.5388767e-02 5.2253060e+00 - 1.0609611e+00 7.8573916e-02 6.0590610e+00 - 1.0840277e+00 8.2350937e-02 7.2529052e+00 - 8.7147878e-01 5.2344590e-02 5.8863084e+00 - 7.8563910e-01 4.1275371e-02 5.8821779e+00 - 6.9311337e-01 2.9124578e-02 5.6867059e+00 - 6.1468068e-01 1.7892650e-02 5.8093941e+00 - 5.4150952e-01 8.6937117e-03 7.2306514e+00 - 2.5765971e+00 2.1644496e-01 -1.0101950e+00 - 2.6472129e+00 2.2434935e-01 -1.0075165e+00 - 2.7187784e+00 2.3128995e-01 -1.0028939e+00 - 2.7984219e+00 2.3951916e-01 -1.0028904e+00 - 2.8861459e+00 2.4905667e-01 -1.0071063e+00 - 2.9748829e+00 2.5865199e-01 -1.0089284e+00 - 3.0645738e+00 2.6731799e-01 -1.0081073e+00 - 3.1624098e+00 2.7832374e-01 -1.0108561e+00 - 3.2612016e+00 2.8841497e-01 -1.0106621e+00 - 3.3610088e+00 2.9858370e-01 -1.0076747e+00 - 3.4699046e+00 3.1007912e-01 -1.0073120e+00 - 3.5798182e+00 3.2167174e-01 -1.0037564e+00 - 3.7068376e+00 3.3487778e-01 -1.0074947e+00 - 3.8429535e+00 3.4947456e-01 -1.0125593e+00 - 3.9730160e+00 3.6288846e-01 -1.0084169e+00 - 4.1372851e+00 3.7948978e-01 -1.0196615e+00 - 4.2865506e+00 3.9571832e-01 -1.0162771e+00 - 4.4629532e+00 4.1386898e-01 -1.0219659e+00 - 4.6403891e+00 4.3224001e-01 -1.0219649e+00 - 4.8460335e+00 4.5357312e-01 -1.0289925e+00 - 5.0718746e+00 4.7762594e-01 -1.0374803e+00 - 5.2896182e+00 4.9971835e-01 -1.0347078e+00 - 5.5275648e+00 5.2457973e-01 -1.0323968e+00 - 5.7937445e+00 5.5260027e-01 -1.0331192e+00 - 6.0720571e+00 5.8216521e-01 -1.0283858e+00 - 6.3886404e+00 6.1524727e-01 -1.0274664e+00 - 6.7354194e+00 6.5058249e-01 -1.0252425e+00 - 7.1407224e+00 6.9312191e-01 -1.0289416e+00 - 7.5571339e+00 7.3654021e-01 -1.0216390e+00 - 8.0522102e+00 7.8891995e-01 -1.0209710e+00 - 8.6077377e+00 8.4679802e-01 -1.0178436e+00 - 9.2520051e+00 9.1429604e-01 -1.0160389e+00 - 1.0054495e+01 9.9778082e-01 -1.0250106e+00 - 1.1113991e+01 1.1077937e+00 -1.0557005e+00 - 1.2323796e+01 1.2343442e+00 -1.0755185e+00 - 1.3979167e+01 1.4078290e+00 -1.1231302e+00 - 1.5679022e+01 1.5852235e+00 -1.1187445e+00 - 2.0412709e+01 2.0790663e+00 -1.0703995e+00 - 2.3022403e+01 2.3520587e+00 -9.4298134e-01 - 2.3399623e+01 2.3908798e+00 -5.7126113e-01 - 2.3393917e+01 2.3912235e+00 -1.6764506e-01 - 2.7307622e+01 2.7992456e+00 1.0395885e-01 - 2.2981649e+01 2.3482099e+00 1.4325896e+00 - 2.3110007e+01 2.3623186e+00 1.8320959e+00 - 2.3171769e+01 2.3684882e+00 2.2331057e+00 - 2.8860700e+01 2.9628008e+00 3.0420497e+00 - 2.5373912e+01 2.5989956e+00 3.2304026e+00 - 2.5252292e+01 2.5864733e+00 3.6580968e+00 - 1.8520131e+01 1.8828075e+00 3.2559740e+00 - 1.8576645e+01 1.8887721e+00 3.5859387e+00 - 1.8676569e+01 1.8996581e+00 3.9264062e+00 - 1.8427440e+01 1.8736317e+00 4.2099742e+00 - 1.9862086e+01 2.0238478e+00 4.8184790e+00 - 2.1582418e+01 2.2037044e+00 5.5431055e+00 - 2.0754275e+01 2.1169681e+00 5.7380248e+00 - 1.8999771e+01 1.9337622e+00 5.6713857e+00 - 1.9079600e+01 1.9422272e+00 6.0396306e+00 - 2.2314136e+01 2.2813965e+00 7.3295700e+00 - 1.8740785e+01 1.9073504e+00 6.6415802e+00 - 2.3017290e+01 2.3552541e+00 8.3987148e+00 - 2.0094623e+01 2.0497060e+00 7.8211749e+00 - 1.8767500e+01 1.9112312e+00 7.7208555e+00 - 1.9650944e+01 2.0034024e+00 8.4290413e+00 - 1.8882924e+01 1.9231473e+00 8.5045234e+00 - 1.8319792e+01 1.8646746e+00 8.6416452e+00 - 2.3051306e+01 2.3591115e+00 1.1141298e+01 - 2.3204315e+01 2.3752555e+00 1.1692439e+01 - 2.0121909e+01 2.0529414e+00 1.0664154e+01 - 2.1668446e+01 2.2150768e+00 1.1890644e+01 - 2.0686316e+01 2.1132289e+00 1.1836550e+01 - 2.0565532e+01 2.0998646e+00 1.2228136e+01 - 2.2071137e+01 2.2582350e+00 1.3571308e+01 - 2.1184794e+01 2.1650286e+00 1.3545132e+01 - 2.1158133e+01 2.1625730e+00 1.4028413e+01 - 4.4451858e+00 4.1332907e-01 3.7892044e+00 - 4.4283633e+00 4.1191555e-01 3.8815917e+00 - 4.4802983e+00 4.1808359e-01 4.0284487e+00 - 4.2319819e+00 3.9175606e-01 3.9436722e+00 - 4.1878367e+00 3.8693748e-01 4.0150698e+00 - 4.0658844e+00 3.7455424e-01 4.0213395e+00 - 4.1329792e+00 3.8182739e-01 4.1886739e+00 - 4.0554779e+00 3.7361173e-01 4.2319098e+00 - 4.0710122e+00 3.7513176e-01 4.3620997e+00 - 4.1482563e+00 3.8314048e-01 4.5565688e+00 - 4.0646990e+00 3.7423637e-01 4.5987747e+00 - 4.0843395e+00 3.7642112e-01 4.7473292e+00 - 4.0058672e+00 3.6848268e-01 4.7949628e+00 - 4.0983631e+00 3.7781646e-01 5.0346283e+00 - 3.9430299e+00 3.6235320e-01 4.9989037e+00 - 3.9373994e+00 3.6145540e-01 5.1354511e+00 - 3.7091006e+00 3.3744709e-01 5.0005751e+00 - 3.6690954e+00 3.3356420e-01 5.0958305e+00 - 3.5318675e+00 3.1914962e-01 5.0628461e+00 - 3.4320932e+00 3.0872787e-01 5.0749896e+00 - 3.3718303e+00 3.0267074e-01 5.1422425e+00 - 3.3166046e+00 2.9668085e-01 5.2169703e+00 - 3.1620745e+00 2.8011443e-01 5.1398440e+00 - 3.0683500e+00 2.7033187e-01 5.1520189e+00 - 3.0111002e+00 2.6424118e-01 5.2222585e+00 - 2.9923861e+00 2.6223878e-01 5.3610437e+00 - 3.0122744e+00 2.6485675e-01 5.5791612e+00 - 2.9794218e+00 2.6135694e-01 5.7109987e+00 - 3.0633320e+00 2.7080371e-01 6.0837758e+00 - 3.0051911e+00 2.6459753e-01 6.1909722e+00 - 2.5967548e+00 2.2104474e-01 5.5448391e+00 - 2.4725516e+00 2.0829499e-01 5.4804536e+00 - 2.3797930e+00 1.9870992e-01 5.4775942e+00 - 2.3083884e+00 1.9150787e-01 5.5284519e+00 - 2.2685001e+00 1.8752786e-01 5.6622590e+00 - 2.2082973e+00 1.8143448e-01 5.7490374e+00 - 2.1480879e+00 1.7477277e-01 5.8445546e+00 - 2.0390197e+00 1.6293106e-01 5.7966514e+00 - 1.9554252e+00 1.5424548e-01 5.8230272e+00 - 2.1410980e+00 1.7452939e-01 6.7998880e+00 - 2.0862945e+00 1.6881965e-01 7.0018563e+00 - 2.0417697e+00 1.6384690e-01 7.2715084e+00 - 1.7131365e+00 1.3001331e-01 6.3326434e+00 - 1.5999540e+00 1.1795697e-01 6.2552397e+00 - 1.7266993e+00 1.3172355e-01 7.4128078e+00 - 1.2213710e+00 7.7745753e-02 5.1677135e+00 - 1.1457336e+00 6.9897270e-02 5.1600570e+00 - 1.0783177e+00 6.2937991e-02 5.2004654e+00 - 1.2440490e+00 8.0866772e-02 7.1955210e+00 - 1.0081976e+00 5.5986227e-02 5.9642823e+00 - 9.2043575e-01 4.6662311e-02 5.9525683e+00 - 8.3578330e-01 3.7559284e-02 5.9692592e+00 - 7.3402627e-01 2.7066658e-02 5.6748404e+00 - 6.5346945e-01 1.8544594e-02 5.7081981e+00 - 6.0107759e-01 1.3926622e-02 7.5899696e+00 - 2.6211668e+00 1.5846944e-01 -1.0125163e+00 - 2.6996726e+00 1.6461246e-01 -1.0155067e+00 - 2.7721226e+00 1.6955290e-01 -1.0096896e+00 - 2.8516525e+00 1.7584239e-01 -1.0084883e+00 - 2.9331922e+00 1.8211936e-01 -1.0050961e+00 - 3.0217553e+00 1.8877801e-01 -1.0056708e+00 - 3.1203387e+00 1.9565667e-01 -1.0098226e+00 - 3.2109308e+00 2.0245552e-01 -1.0051103e+00 - 3.3186176e+00 2.1077912e-01 -1.0094897e+00 - 3.4272619e+00 2.1820296e-01 -1.0106267e+00 - 3.5369838e+00 2.2671604e-01 -1.0087202e+00 - 3.6557377e+00 2.3558842e-01 -1.0087896e+00 - 3.8006121e+00 2.4629556e-01 -1.0209252e+00 - 3.9123956e+00 2.5520997e-01 -1.0084382e+00 - 4.0603163e+00 2.6614961e-01 -1.0121937e+00 - 4.2172800e+00 2.7753722e-01 -1.0161274e+00 - 4.3843483e+00 2.9033396e-01 -1.0197923e+00 - 4.5714793e+00 3.0374809e-01 -1.0270158e+00 - 4.7587070e+00 3.1844986e-01 -1.0283962e+00 - 4.9840430e+00 3.3433982e-01 -1.0402829e+00 - 5.1833631e+00 3.4974669e-01 -1.0329618e+00 - 5.4118414e+00 3.6715185e-01 -1.0307252e+00 - 5.6604052e+00 3.8535670e-01 -1.0283516e+00 - 5.9562502e+00 4.0726554e-01 -1.0352635e+00 - 6.2360437e+00 4.2794884e-01 -1.0257958e+00 - 6.5732179e+00 4.5370582e-01 -1.0261440e+00 - 6.9405332e+00 4.8076334e-01 -1.0242393e+00 - 7.3662594e+00 5.1309029e-01 -1.0269600e+00 - 7.8141224e+00 5.4653450e-01 -1.0206611e+00 - 8.3505066e+00 5.8630234e-01 -1.0217286e+00 - 8.9573211e+00 6.3094430e-01 -1.0207680e+00 - 9.6437398e+00 6.8298602e-01 -1.0163584e+00 - 1.0605764e+01 7.5491012e-01 -1.0438670e+00 - 1.1640269e+01 8.3150194e-01 -1.0508270e+00 - 1.3179866e+01 9.4642795e-01 -1.1055486e+00 - 1.4861499e+01 1.0724606e+00 -1.1274526e+00 - 1.6904399e+01 1.2244123e+00 -1.1373460e+00 - 2.0060220e+01 1.4599219e+00 -1.2012842e+00 - 2.2944768e+01 1.6754562e+00 -1.1289978e+00 - 2.3495409e+01 1.7169295e+00 -7.7570010e-01 - 2.3473563e+01 1.7153431e+00 -3.6998685e-01 - 2.4809164e+01 1.8154066e+00 -2.3123192e-02 - 2.9598564e+01 2.1733522e+00 2.8499402e-01 - 2.3193915e+01 1.6947527e+00 1.2371339e+00 - 2.3206260e+01 1.6957165e+00 1.6348008e+00 - 2.2493964e+01 1.6435671e+00 2.0004125e+00 - 2.1568124e+01 1.5743478e+00 2.3281350e+00 - 2.3370198e+01 1.7088064e+00 2.8441368e+00 - 2.7235242e+01 1.9977407e+00 3.6272387e+00 - 2.4907085e+01 1.8234866e+00 3.8306282e+00 - 1.9991165e+01 1.4563256e+00 3.6071495e+00 - 1.8976358e+01 1.3808294e+00 3.8013650e+00 - 1.8747856e+01 1.3640562e+00 4.0943616e+00 - 2.0798159e+01 1.5174442e+00 4.8085448e+00 - 2.1304894e+01 1.5554963e+00 5.2818297e+00 - 1.9981785e+01 1.4570550e+00 5.3662410e+00 - 1.9903334e+01 1.4506224e+00 5.7065614e+00 - 1.9402940e+01 1.4140639e+00 5.9370318e+00 - 1.8833909e+01 1.3708994e+00 6.1328081e+00 - 1.8780661e+01 1.3675215e+00 6.4643117e+00 - 1.8254899e+01 1.3281352e+00 6.6474194e+00 - 1.9589935e+01 1.4284141e+00 7.4419281e+00 - 1.2156446e+01 8.7241809e-01 5.1626385e+00 - 2.0044796e+01 1.4629385e+00 8.3664632e+00 - 1.9812227e+01 1.4447778e+00 8.6669624e+00 - 2.2382239e+01 1.6372647e+00 1.0133443e+01 - 1.8181158e+01 1.3235402e+00 8.7458887e+00 - 2.2405355e+01 1.6395933e+00 1.1056024e+01 - 2.2307075e+01 1.6323392e+00 1.1476806e+01 - 2.1969929e+01 1.6076281e+00 1.1780777e+01 - 2.1628677e+01 1.5817332e+00 1.2076121e+01 - 2.1993155e+01 1.6092863e+00 1.2750548e+01 - 2.1699304e+01 1.5870229e+00 1.3075658e+01 - 2.1906631e+01 1.6032331e+00 1.3694144e+01 - 2.1538174e+01 1.5753932e+00 1.3977837e+01 - 4.6845988e+00 3.1362496e-01 3.7895409e+00 - 4.4872598e+00 2.9900721e-01 3.7601414e+00 - 4.3988210e+00 2.9231058e-01 3.8004663e+00 - 4.3729737e+00 2.9111102e-01 3.8861905e+00 - 4.3379836e+00 2.8815122e-01 3.9657502e+00 - 4.3009953e+00 2.8529754e-01 4.0450166e+00 - 4.2327216e+00 2.8003614e-01 4.0983625e+00 - 4.3067933e+00 2.8628825e-01 4.2738143e+00 - 4.2869586e+00 2.8439908e-01 4.3731521e+00 - 4.0441236e+00 2.6684711e-01 4.2697865e+00 - 4.0949306e+00 2.6997459e-01 4.4348228e+00 - 4.0418497e+00 2.6659848e-01 4.5042019e+00 - 4.0705094e+00 2.6852494e-01 4.6585206e+00 - 3.9588111e+00 2.5977628e-01 4.6696540e+00 - 4.0218746e+00 2.6491938e-01 4.8699589e+00 - 3.9142600e+00 2.5717221e-01 4.8860239e+00 - 3.8530568e+00 2.5215277e-01 4.9528309e+00 - 4.0555879e+00 2.6734628e-01 5.3432152e+00 - 3.7630460e+00 2.4535782e-01 5.1305398e+00 - 3.6240768e+00 2.3516528e-01 5.0996607e+00 - 3.5396768e+00 2.2911048e-01 5.1376261e+00 - 3.4158038e+00 2.1951559e-01 5.1169370e+00 - 3.4223935e+00 2.2034273e-01 5.2828603e+00 - 3.3035993e+00 2.1166425e-01 5.2666002e+00 - 3.3041434e+00 2.1188670e-01 5.4331914e+00 - 3.2470303e+00 2.0740388e-01 5.5157662e+00 - 3.2334359e+00 2.0612892e-01 5.6754097e+00 - 2.9952235e+00 1.8894224e-01 5.4437394e+00 - 2.9836655e+00 1.8786661e-01 5.6098685e+00 - 2.9579688e+00 1.8580771e-01 5.7592126e+00 - 3.0660518e+00 1.9450470e-01 6.1866449e+00 - 2.7010193e+00 1.6695048e-01 5.6527945e+00 - 2.5993078e+00 1.5866993e-01 5.6451201e+00 - 2.5260495e+00 1.5376005e-01 5.6994807e+00 - 2.3908615e+00 1.4318317e-01 5.6049186e+00 - 2.2374012e+00 1.3176979e-01 5.4511374e+00 - 2.2818659e+00 1.3583178e-01 5.8089044e+00 - 2.2106288e+00 1.3048394e-01 5.8770912e+00 - 2.1160171e+00 1.2319597e-01 5.8778344e+00 - 1.9898634e+00 1.1351222e-01 5.7718586e+00 - 1.9176010e+00 1.0800805e-01 5.8356540e+00 - 1.7486039e+00 9.5054927e-02 5.5512833e+00 - 2.1156052e+00 1.2347215e-01 7.3157969e+00 - 1.9957817e+00 1.1408872e-01 7.3042838e+00 - 1.6931730e+00 9.1938674e-02 6.4504876e+00 - 1.5567263e+00 8.1918764e-02 6.2646934e+00 - 1.2654029e+00 5.9180864e-02 5.1907851e+00 - 1.1837795e+00 5.3267047e-02 5.1542346e+00 - 1.1144311e+00 4.7969318e-02 5.1853616e+00 - 1.0595429e+00 4.3646087e-02 5.3343968e+00 - 1.0628950e+00 4.4861112e-02 6.0490978e+00 - 9.7220429e-01 3.7273977e-02 6.0284052e+00 - 8.7208248e-01 2.9748748e-02 5.8764057e+00 - 7.8866558e-01 2.4029393e-02 5.9021335e+00 - 6.9438338e-01 1.7010663e-02 5.6866949e+00 - 6.1631466e-01 1.1266034e-02 5.8193228e+00 - 5.4226189e-01 6.1533611e-03 7.2006349e+00 - 2.5852449e+00 9.4555569e-02 -1.0101431e+00 - 2.6636229e+00 9.8645556e-02 -1.0142328e+00 - 2.7289383e+00 1.0128432e-01 -1.0028515e+00 - 2.8082795e+00 1.0451890e-01 -1.0027999e+00 - 2.8966988e+00 1.0899641e-01 -1.0070709e+00 - 2.9860713e+00 1.1253969e-01 -1.0087986e+00 - 3.0755196e+00 1.1720310e-01 -1.0080790e+00 - 3.1739303e+00 1.2115494e-01 -1.0107837e+00 - 3.2734174e+00 1.2618617e-01 -1.0106448e+00 - 3.3738602e+00 1.3030286e-01 -1.0075631e+00 - 3.4833301e+00 1.3473944e-01 -1.0072562e+00 - 3.6008929e+00 1.4058287e-01 -1.0091712e+00 - 3.7204741e+00 1.4648276e-01 -1.0074971e+00 - 3.8580419e+00 1.5196634e-01 -1.0125216e+00 - 3.9966946e+00 1.5859827e-01 -1.0133041e+00 - 4.1443873e+00 1.6565355e-01 -1.0147641e+00 - 4.3121360e+00 1.7327204e-01 -1.0208812e+00 - 4.4798559e+00 1.8014484e-01 -1.0218550e+00 - 4.6586829e+00 1.8840079e-01 -1.0218643e+00 - 4.8655973e+00 1.9761998e-01 -1.0289028e+00 - 5.0735511e+00 2.0710882e-01 -1.0292528e+00 - 5.3015825e+00 2.1733331e-01 -1.0307643e+00 - 5.5396793e+00 2.2813746e-01 -1.0285618e+00 - 5.8079446e+00 2.4097798e-01 -1.0294494e+00 - 6.0962471e+00 2.5371485e-01 -1.0282529e+00 - 6.4046524e+00 2.6738936e-01 -1.0241229e+00 - 6.7432516e+00 2.8330224e-01 -1.0189881e+00 - 7.1309839e+00 3.0009801e-01 -1.0171038e+00 - 7.5790695e+00 3.2109462e-01 -1.0188028e+00 - 8.0763221e+00 3.4324510e-01 -1.0182592e+00 - 8.6529613e+00 3.6950887e-01 -1.0201105e+00 - 9.2908913e+00 3.9839701e-01 -1.0157614e+00 - 1.0058402e+01 4.3324248e-01 -1.0166111e+00 - 1.1141251e+01 4.8244817e-01 -1.0516545e+00 - 1.2326583e+01 5.3548531e-01 -1.0666939e+00 - 1.4009121e+01 6.1184582e-01 -1.1181928e+00 - 1.5775223e+01 6.9252266e-01 -1.1225613e+00 - 1.8110822e+01 7.9762153e-01 -1.1341531e+00 - 2.0511009e+01 9.0654433e-01 -1.0710393e+00 - 2.3311198e+01 1.0338728e+00 -9.5873779e-01 - 2.4238511e+01 1.0758835e+00 -6.2120835e-01 - 2.4612501e+01 1.0930977e+00 -2.2397223e-01 - 2.4470216e+01 1.0867952e+00 2.0284193e-01 - 2.8066808e+01 1.2496583e+00 5.6509104e-01 - 2.8159770e+01 1.2539468e+00 1.0469009e+00 - 2.1892298e+01 9.7050685e-01 1.4102539e+00 - 2.2380775e+01 9.9258133e-01 1.8022382e+00 - 2.1406373e+01 9.4849483e-01 2.1326251e+00 - 2.0655912e+01 9.1408635e-01 2.4455331e+00 - 2.0080285e+01 8.8868975e-01 2.7486070e+00 - 2.0602939e+01 9.1217275e-01 3.1499227e+00 - 2.1226156e+01 9.4021904e-01 3.5836336e+00 - 2.0683638e+01 9.1624883e-01 3.8749186e+00 - 2.1351167e+01 9.4631112e-01 4.3424987e+00 - 2.2380660e+01 9.9312916e-01 4.9009338e+00 - 2.1476225e+01 9.5227335e-01 5.1189917e+00 - 2.1431214e+01 9.5042197e-01 5.4912195e+00 - 2.0055135e+01 8.8825100e-01 5.5548449e+00 - 2.3267564e+01 1.0341680e+00 6.7237923e+00 - 1.8332058e+01 8.0971641e-01 5.8160594e+00 - 2.0548345e+01 9.1093076e-01 6.7922129e+00 - 1.8945621e+01 8.3766973e-01 6.6801653e+00 - 1.9479804e+01 8.6281111e-01 7.2095862e+00 - 1.0976630e+01 4.7596926e-01 4.6320899e+00 - 2.0067510e+01 8.8898176e-01 8.1678555e+00 - 1.9949097e+01 8.8416231e-01 8.5122477e+00 - 2.1481324e+01 9.5343670e-01 9.5280411e+00 - 2.1623555e+01 9.6021107e-01 1.0018836e+01 - 1.0401573e+01 4.5027393e-01 5.4343908e+00 - 2.0591154e+01 9.1414129e-01 1.0420466e+01 - 2.0531115e+01 9.1068686e-01 1.0822903e+01 - 2.1396902e+01 9.5034385e-01 1.1704298e+01 - 2.1004919e+01 9.3253988e-01 1.1959507e+01 - 2.1465330e+01 9.5361450e-01 1.2680719e+01 - 2.1509191e+01 9.5624806e-01 1.3190648e+01 - 2.1413131e+01 9.5169956e-01 1.3628204e+01 - 2.1181221e+01 9.4138116e-01 1.3986384e+01 - 4.5903964e+00 1.8703418e-01 3.6709121e+00 - 4.4195355e+00 1.7865603e-01 3.6579623e+00 - 4.3644754e+00 1.7605291e-01 3.7203069e+00 - 4.0738100e+00 1.6308606e-01 3.6107026e+00 - 4.2272107e+00 1.7041275e-01 3.8234583e+00 - 4.2245415e+00 1.7061489e-01 3.9251903e+00 - 4.2349317e+00 1.7069628e-01 4.0403643e+00 - 4.1506595e+00 1.6669451e-01 4.0794292e+00 - 4.0744611e+00 1.6343273e-01 4.1230134e+00 - 4.1010098e+00 1.6456371e-01 4.2587614e+00 - 4.0943401e+00 1.6442946e-01 4.3690452e+00 - 4.1068296e+00 1.6521272e-01 4.5008922e+00 - 4.0306609e+00 1.6218742e-01 4.5492705e+00 - 4.0169518e+00 1.6154342e-01 4.6609245e+00 - 4.0274439e+00 1.6192359e-01 4.8024156e+00 - 4.0480188e+00 1.6250724e-01 4.9602547e+00 - 3.8276324e+00 1.5217427e-01 4.8477838e+00 - 3.6899288e+00 1.4612094e-01 4.8209979e+00 - 3.7357499e+00 1.4804276e-01 5.0162616e+00 - 3.7816363e+00 1.5048680e-01 5.2221122e+00 - 3.5632267e+00 1.4090847e-01 5.0868638e+00 - 3.6383670e+00 1.4405298e-01 5.3423608e+00 - 3.4249628e+00 1.3480477e-01 5.1996561e+00 - 3.7908471e+00 1.5081372e-01 5.9058826e+00 - 3.6027046e+00 1.4302684e-01 5.8030995e+00 - 3.3336563e+00 1.3011869e-01 5.5594937e+00 - 3.2221759e+00 1.2568970e-01 5.5568960e+00 - 3.1378987e+00 1.2164852e-01 5.5951619e+00 - 3.0667500e+00 1.1803839e-01 5.6580560e+00 - 2.9249035e+00 1.1205794e-01 5.5873379e+00 - 2.8446399e+00 1.0794246e-01 5.6289869e+00 - 2.8807196e+00 1.0980967e-01 5.9122218e+00 - 2.6558631e+00 9.9514006e-02 5.6537966e+00 - 2.5989277e+00 9.7483285e-02 5.7455608e+00 - 2.4184479e+00 8.8697592e-02 5.5512667e+00 - 2.2753901e+00 8.2106137e-02 5.4264195e+00 - 2.2802309e+00 8.2968327e-02 5.6716496e+00 - 2.1512935e+00 7.6698208e-02 5.5704286e+00 - 2.4371043e+00 8.9895151e-02 6.6676697e+00 - 2.4240098e+00 8.9521102e-02 6.9671382e+00 - 1.9327815e+00 6.6602208e-02 5.7273668e+00 - 1.8281613e+00 6.2282490e-02 5.6747597e+00 - 1.7336277e+00 5.7681682e-02 5.6489373e+00 - 2.0390775e+00 7.1806363e-02 7.2327117e+00 - 1.7208170e+00 5.7812631e-02 6.3423651e+00 - 1.6519463e+00 5.4785786e-02 6.4803090e+00 - 1.3083125e+00 3.8652957e-02 5.2133598e+00 - 1.2227612e+00 3.5045577e-02 5.1578965e+00 - 1.1504215e+00 3.0987028e-02 5.1699574e+00 - 1.0874250e+00 2.8742579e-02 5.2500551e+00 - 1.1359298e+00 3.1481004e-02 6.2722820e+00 - 1.0020186e+00 2.4831853e-02 5.8748449e+00 - 9.2291555e-01 2.1437525e-02 5.9525958e+00 - 8.3232675e-01 1.7243829e-02 5.8993953e+00 - 7.3623730e-01 1.2372640e-02 5.7047876e+00 - 6.5273863e-01 8.5785581e-03 5.6682443e+00 - 6.0271363e-01 6.8006507e-03 7.6100353e+00 diff --git a/thirdparty/libpointmatcher/examples/data/cloud.00000.vtk b/thirdparty/libpointmatcher/examples/data/cloud.00000.vtk deleted file mode 100644 index 2abd060..0000000 --- a/thirdparty/libpointmatcher/examples/data/cloud.00000.vtk +++ /dev/null @@ -1,49984 +0,0 @@ -# vtk DataFile Version 3.0 -data -ASCII -DATASET POLYDATA -POINTS 24989 float --3.79521 0.0131325 -0.95763 --3.96647 0.0132124 -0.942159 --4.21193 0.0135086 -0.951972 --4.45028 0.0149599 -0.950072 --4.68963 0.0158491 -0.940528 --4.98614 0.0165773 -0.943139 --5.28464 0.0169122 -0.935906 --5.68934 0.0184896 -0.952009 --6.09701 0.0199213 -0.954469 --6.49566 0.0206151 -0.940629 --7.03255 0.0225657 -0.948424 --7.58044 0.0239559 -0.940505 --8.27664 0.0255928 -0.946401 --9.03489 0.0275564 -0.940415 --9.95236 0.0309391 -0.937922 --10.98 0.0336263 -0.921899 --12.2782 0.0373702 -0.910566 --13.8066 0.0417205 -0.884425 --15.914 0.0483003 -0.87124 --39.4918 0.116391 -0.748882 --38.0871 0.112248 -0.0131302 --12.9479 0.0393037 4.2276 --13.3745 0.0407976 4.5869 --9.16539 0.02834 3.67965 --8.77255 0.0269557 3.74578 --8.61785 0.0269976 3.87408 --8.35817 0.0257595 3.96295 --8.16352 0.0251919 4.06701 --7.90281 0.0251433 4.14069 --3.92966 0.0136516 2.74414 --3.87036 0.0133317 2.80977 --4.87437 0.0158884 3.33628 --4.78702 0.0152277 3.40897 --7.92209 0.0246748 5.01601 --7.83252 0.0240899 5.15346 --4.61893 0.0147344 3.66387 --4.47454 0.014846 3.70032 --4.34821 0.0143227 3.74242 --6.22943 0.0201209 4.96334 --6.32189 0.0203988 5.17946 --4.24012 0.0145278 4.01918 --6.23886 0.0202543 5.4591 --5.55772 0.0175404 5.16267 --6.0869 0.0189085 5.69742 --6.38211 0.0201994 6.09117 --4.02234 0.0137256 4.46954 --3.86711 0.012563 4.47334 --3.11143 0.010436 3.97657 --3.21898 0.0107732 4.17557 --3.56722 0.0116627 4.59769 --2.78176 0.0100451 4.0061 --3.14894 0.0107526 4.46209 --2.73911 0.0101856 4.18184 --2.73878 0.00976619 4.2949 --2.75639 0.0095593 4.43079 --3.58151 0.0118956 5.45282 --5.42445 0.0169997 7.6952 --2.75414 0.0101816 4.80931 --2.68686 0.00991698 4.86558 --2.68147 0.00919352 4.99884 --2.58125 0.00891665 5.01416 --2.63563 0.00918689 5.23605 --2.53243 0.00863506 5.24946 --2.46312 0.00845642 5.30992 --2.45357 0.00937001 5.461 --2.33741 0.00896699 5.45279 --2.32792 0.00831037 5.61257 --2.27652 0.00818488 5.71288 --1.02188 0.00434995 3.68924 --0.965747 0.00439902 3.6979 --0.885697 0.00474345 3.66084 --0.87443 0.00379383 3.75634 --0.852112 0.00429809 3.83397 --0.931293 0.00419197 4.13924 --0.701115 0.00355188 3.76029 --0.651956 0.0036085 3.7808 --0.772726 0.00406463 4.22848 --0.694718 0.00365618 4.19398 --0.699141 0.00333489 4.38395 --1.77307 0.00677498 7.78981 --1.6329 0.00693653 7.7616 --0.693056 0.00382696 5.02688 --0.630804 0.00351475 5.07608 --0.539845 0.00314672 5.01776 --0.427175 0.00255306 4.8602 --0.329374 0.00266556 4.73914 --0.226716 0.00294912 4.56689 --0.202016 0.00228876 4.78544 --0.0945723 0.00218172 4.55059 --0.329643 0.00232345 6.54829 --0.258825 0.00255982 6.76021 -0.00607586 0.00183589 5.33195 -0.081231 0.00170381 5.3399 -0.154507 0.00159551 5.38641 -0.254406 0.000552528 5.00247 -0.259201 0.000703484 6.50479 -0.350924 0.000764481 6.67804 -0.449371 0.000884069 6.75972 --3.71265 0.13615 -0.965409 --3.88262 0.141036 -0.952586 --4.09159 0.147767 -0.950026 --4.33754 0.156321 -0.955738 --4.58556 0.163396 -0.953355 --4.84447 0.17236 -0.946392 --5.13246 0.181008 -0.940735 --5.4984 0.193609 -0.950312 --5.89439 0.206191 -0.956398 --6.27335 0.21768 -0.943612 --6.75027 0.233421 -0.944148 --7.2782 0.250434 -0.940727 --7.8951 0.2707 -0.93962 --8.64105 0.294445 -0.944597 --9.48796 0.321601 -0.943112 --10.4258 0.351908 -0.928205 --11.5536 0.387792 -0.910898 --12.9804 0.433568 -0.896439 --14.7482 0.490298 -0.874108 --16.9748 0.562352 -0.838786 --37.5369 1.22372 -0.331574 --42.9015 1.39657 0.239088 --12.6768 0.423982 4.04265 --12.0695 0.4049 4.13436 --11.7811 0.395275 4.29125 --9.56961 0.323902 3.88794 --9.59394 0.325218 4.08667 --9.4435 0.320323 4.23156 --8.53501 0.29059 4.11178 --4.04611 0.146652 2.65499 --3.895 0.142151 2.68753 --3.80989 0.138696 2.74164 --3.94441 0.143009 2.88693 --4.23964 0.152903 3.11064 --4.09359 0.147662 3.14234 --7.31589 0.251815 4.81323 --4.63 0.165416 3.61455 --4.58371 0.164044 3.70375 --4.43062 0.159309 3.73397 --3.60289 0.13233 3.36965 --4.16145 0.150415 3.80143 --3.73901 0.136392 3.64923 --4.17768 0.151151 4.03869 --10.8363 0.365209 8.64888 --3.75795 0.137034 3.98223 --10.619 0.357519 9.08115 --3.97863 0.144848 4.37579 --3.88752 0.140981 4.42888 --3.35352 0.124524 4.12112 --3.0151 0.113636 3.95006 --3.03075 0.113526 4.07011 --3.47404 0.128508 4.57954 --4.25924 0.153474 5.43941 --5.31041 0.186997 6.61238 --2.78009 0.105843 4.2807 --2.71496 0.10337 4.33029 --3.5905 0.13158 5.3878 --3.68066 0.134729 5.64432 --3.63131 0.133203 5.75432 --2.59085 0.0994332 4.68445 --2.50075 0.097105 4.70674 --2.54614 0.0984376 4.90039 --2.80256 0.10688 5.38425 --2.57907 0.0992001 5.23898 --2.52782 0.0973633 5.32486 --2.56907 0.0990633 5.55111 --1.11184 0.0516581 3.4823 --2.36597 0.0926273 5.58772 --2.28581 0.0902349 5.637 --2.23453 0.0880909 5.73691 --0.993176 0.0479762 3.69372 --0.955039 0.0468204 3.73699 --1.05697 0.0507784 4.05602 --1.02977 0.0491294 4.13663 --0.809794 0.0426486 3.80939 --0.801469 0.041785 3.92322 --0.656113 0.0371765 3.72461 --0.807436 0.0426301 4.2357 --0.901097 0.0458149 4.65013 --0.810276 0.042796 4.59886 --0.691741 0.0387879 4.46046 --0.7109 0.0392038 4.72808 --0.739859 0.0401302 5.05462 --0.68759 0.0383511 5.14289 --0.561162 0.0346727 4.96017 --0.440801 0.0302072 4.77442 --0.38163 0.0288725 4.81947 --0.250561 0.0246739 4.53102 --0.208256 0.0226091 4.6418 --0.172698 0.0218556 4.81112 --0.360546 0.0275087 6.4322 --0.294837 0.0255541 6.65437 --0.204552 0.023196 6.73683 -0.045876 0.0146955 5.31615 -0.121843 0.0119819 5.31351 -0.215077 0.00929679 5.07007 -0.207832 0.00967554 6.56234 -0.299316 0.0067967 6.7165 -0.401015 0.00333308 6.62914 --3.28095 0.23413 -0.971906 --3.43964 0.243909 -0.968004 --3.60831 0.254327 -0.963372 --3.778 0.264065 -0.953494 --3.96661 0.27582 -0.946201 --4.20315 0.290824 -0.951989 --4.44071 0.305265 -0.950133 --4.70717 0.322318 -0.951032 --4.97564 0.338929 -0.943085 --5.30206 0.358529 -0.945441 --5.68735 0.382332 -0.95495 --6.08457 0.407354 -0.954434 --6.49276 0.432565 -0.943245 --6.99884 0.463125 -0.943431 --7.56473 0.498456 -0.940479 --8.23145 0.53976 -0.939903 --9.00698 0.587677 -0.938481 --9.9712 0.646591 -0.945147 --10.9393 0.706385 -0.918591 --12.2247 0.786657 -0.906106 --13.7897 0.883198 -0.885788 --15.7439 1.00375 -0.855342 --18.1083 1.14949 -0.796473 --39.217 2.4534 -0.740103 --48.5496 3.02997 2.28346 --13.3767 0.857356 4.08106 --11.9138 0.767219 3.98487 --12.1305 0.780511 4.2715 --11.0906 0.716114 4.2194 --10.1615 0.659203 4.16311 --10.2287 0.663408 4.38809 --9.26891 0.603769 4.27387 --9.46373 0.615442 4.53432 --3.88536 0.270715 2.64218 --3.8003 0.266273 2.69654 --3.92663 0.273839 2.83652 --4.00408 0.278711 2.96151 --4.25096 0.293877 3.16844 --4.01346 0.278938 3.15649 --4.93093 0.335907 3.71243 --3.84745 0.268376 3.26683 --3.81625 0.26648 3.34733 --3.69633 0.259761 3.37806 --3.68907 0.258945 3.47137 --3.97663 0.277023 3.74799 --3.81893 0.266894 3.75603 --3.96998 0.276301 3.96355 --3.76943 0.263985 3.93929 --3.79097 0.265555 4.0658 --4.00971 0.27848 4.34256 --3.68174 0.258297 4.21397 --3.53103 0.24909 4.21189 --3.11254 0.223464 3.98289 --3.08332 0.221773 4.0651 --3.40246 0.241548 4.45858 --4.14451 0.287211 5.26259 --4.22859 0.292783 5.49452 --4.17042 0.288375 5.59761 --4.01963 0.279745 5.60722 --3.78137 0.264969 5.51877 --3.74901 0.263246 5.64451 --4.05784 0.281438 6.15995 --2.79334 0.203771 4.86258 --2.51652 0.186258 4.66499 --2.43356 0.181667 4.69364 --2.67863 0.197033 5.14896 --2.81928 0.205587 5.49323 --2.73531 0.199957 5.54255 --2.57578 0.190369 5.48296 --1.721 0.137112 4.36043 --1.08795 0.0980535 3.49629 --1.20084 0.104905 3.7795 --1.13694 0.101214 3.78289 --1.08791 0.0986542 3.81115 --1.02008 0.0941692 3.80334 --0.975071 0.0911843 3.83835 --0.930062 0.088165 3.87267 --0.970272 0.0912023 4.08673 --0.7924 0.0801811 3.83897 --0.679012 0.0731575 3.71436 --0.867761 0.0849432 4.30738 --0.791981 0.0802177 4.28421 --0.838931 0.0830733 4.58734 --0.796758 0.0804633 4.6668 --0.732799 0.0766913 4.68882 --0.682707 0.0730706 4.75758 --0.620698 0.0697939 4.78719 --0.572553 0.0661691 4.87368 --0.497696 0.0621101 4.86281 --0.420911 0.0573784 4.84074 --0.287081 0.0490698 4.55367 --0.213376 0.0443586 4.50809 --0.225061 0.0451438 4.91332 --0.153239 0.0404219 4.9056 --0.331606 0.0515733 6.5681 --0.228893 0.0450826 6.54216 -0.0126363 0.0300646 5.28226 -0.0826828 0.0261991 5.32997 -0.170064 0.0208375 5.18702 -0.255314 0.0155463 5.00253 -0.260047 0.0151996 6.49476 -0.35047 0.00981723 6.67799 -0.44868 0.00391709 6.79973 --3.02818 0.321583 -0.963663 --3.14968 0.332683 -0.948542 --3.32505 0.34888 -0.956869 --3.48342 0.363752 -0.951018 --3.66973 0.380935 -0.952818 --3.87602 0.399223 -0.956652 --4.08326 0.417896 -0.953891 --4.31041 0.438732 -0.952015 --4.57641 0.463578 -0.957005 --4.84342 0.487917 -0.953253 --5.14032 0.515012 -0.950554 --5.49504 0.547179 -0.956459 --5.85269 0.580108 -0.95057 --6.24926 0.615439 -0.943657 --6.71449 0.658687 -0.941617 --7.24954 0.7071 -0.940702 --7.86427 0.76334 -0.939682 --8.56869 0.827122 -0.936277 --9.4325 0.906233 -0.939252 --10.367 0.991486 -0.924773 --11.4909 1.09332 -0.90774 --12.9026 1.22249 -0.892282 --14.6232 1.3799 -0.865596 --16.8718 1.58447 -0.834573 --39.5378 3.65168 0.295516 --39.5645 3.65406 0.997229 --45.2231 4.17008 1.79828 --45.641 4.20782 2.61471 --47.9508 4.41895 4.39864 --46.9909 4.33104 5.16881 --46.9415 4.32641 6.00356 --50.2274 4.62699 7.25075 --50.5153 4.65324 8.1958 --50.1271 4.61698 9.04804 --47.0173 4.33378 9.40987 --13.0696 1.23753 3.64751 --13.0309 1.23406 3.88693 --12.843 1.21685 4.09208 --12.884 1.2211 4.34964 --13.0345 1.23462 4.64056 --12.2234 1.16063 4.66233 --10.1862 0.974422 4.27967 --10.2502 0.980537 4.50654 --9.56682 0.917859 4.47959 --4.01103 0.412011 2.6482 --3.95402 0.406931 2.71618 --4.03435 0.413875 2.83898 --4.14851 0.4238 2.98067 --4.27651 0.436189 3.13494 --3.97678 0.408117 3.09583 --4.04708 0.41485 3.22659 --3.82196 0.394438 3.21059 --3.90617 0.402525 3.35169 --3.71592 0.384742 3.34618 --3.58035 0.372457 3.36467 --3.62382 0.376162 3.48731 --4.10377 0.420037 3.8877 --3.60926 0.374796 3.67932 --4.06624 0.41689 4.09198 --3.83226 0.395423 4.04533 --3.94819 0.406289 4.24416 --3.93092 0.404575 4.35177 --3.77748 0.390454 4.35502 --3.81886 0.3937 4.51131 --3.56703 0.371227 4.42576 --3.507 0.366099 4.49643 --4.35509 0.442634 5.38909 --4.48271 0.454998 5.66441 --4.27857 0.436089 5.63294 --4.12708 0.422536 5.64529 --4.01832 0.412513 5.69688 --3.75966 0.388331 5.58524 --3.79191 0.391207 5.78554 --2.96343 0.316148 4.99966 --2.79125 0.300637 4.93719 --2.58439 0.281479 4.82331 --2.98978 0.318717 5.48349 --2.85133 0.306377 5.46402 --2.831 0.304031 5.60299 --2.66482 0.288749 5.53783 --1.86203 0.215499 4.51493 --1.25779 0.160414 3.71714 --1.21581 0.156801 3.756 --0.987531 0.135596 3.48571 --0.924761 0.130353 3.47667 --0.890745 0.127381 3.51876 --0.949833 0.13277 3.73702 --0.901948 0.12811 3.76199 --0.858005 0.124095 3.79516 --0.918959 0.129616 4.05418 --0.735465 0.11324 3.78623 --0.675734 0.107308 3.77984 --0.876918 0.126257 4.42114 --0.752855 0.114597 4.27677 --0.825413 0.120741 4.65528 --0.710235 0.110403 4.52672 --0.706603 0.11016 4.72806 --0.650643 0.105216 4.77732 --0.587759 0.0998552 4.80643 --0.533747 0.0948972 4.87323 --0.531871 0.0946348 5.15277 --0.425678 0.0848316 5.02404 --0.247898 0.0686483 4.53103 --0.22238 0.0659699 4.73015 --0.186941 0.0627182 4.90962 --0.360392 0.0786365 6.45201 --0.259853 0.0692956 6.42661 -0.0445996 0.0414143 4.72201 -0.103603 0.036678 4.77915 -0.122238 0.0345223 5.32351 -0.217042 0.0262405 5.0501 -0.209796 0.0266193 6.54236 -0.298235 0.0188709 6.77649 -0.400507 0.00885762 6.67913 --2.93925 0.4167 -0.959993 --3.06848 0.432938 -0.951786 --3.22466 0.451317 -0.95343 --3.38275 0.471061 -0.950124 --3.55882 0.491711 -0.950457 --3.76371 0.516769 -0.957637 --3.9616 0.540929 -0.954203 --4.19636 0.568882 -0.959639 --4.42306 0.596908 -0.953815 --4.70756 0.630765 -0.961439 --4.97505 0.663386 -0.953086 --5.28038 0.700107 -0.948608 --5.65434 0.74545 -0.954944 --6.03023 0.791531 -0.948789 --6.44491 0.842062 -0.940612 --6.93924 0.90112 -0.938371 --7.49314 0.968924 -0.933491 --8.17444 1.05099 -0.937739 --8.92631 1.1418 -0.932471 --9.84724 1.25361 -0.932401 --10.8188 1.37165 -0.908698 --12.058 1.52158 -0.891323 --13.5646 1.70411 -0.866196 --15.4303 1.92998 -0.829276 --18.0677 2.25011 -0.802255 --45.4827 5.57124 0.592563 --46.2921 5.66946 2.23093 --46.4814 5.69215 3.06291 --48.1536 5.89419 4.85357 --45.8263 5.61272 5.48998 --44.1634 5.41132 6.12263 --49.0641 6.00495 8.45788 --48.9957 5.99649 9.33956 --48.4829 5.93414 10.1411 --41.2247 5.05499 9.54789 --13.3987 1.68427 4.10269 --13.1882 1.65875 4.3092 --12.937 1.62795 4.4993 --11.2668 1.4262 4.28618 --11.4848 1.4517 4.57493 --3.91219 0.535181 2.40091 --3.84042 0.525883 2.46251 --5.90151 0.775401 3.28273 --4.57791 0.615829 2.91178 --3.94287 0.538955 2.76246 --4.09557 0.556858 2.91691 --3.73377 0.512813 2.85387 --4.01748 0.547865 3.07307 --4.07877 0.554845 3.19956 --4.36046 0.588841 3.44032 --4.44947 0.59988 3.59461 --4.69134 0.629627 3.83864 --4.52919 0.609135 3.86558 --3.46958 0.48162 3.3546 --3.58844 0.495181 3.52337 --3.62778 0.500767 3.64849 --3.86368 0.528936 3.90838 --4.23747 0.573952 4.27913 --4.14775 0.563467 4.33866 --3.93005 0.537405 4.30086 --3.82453 0.524035 4.34172 --3.79738 0.520365 4.44215 --3.66799 0.505408 4.45991 --3.864 0.528827 4.75343 --3.57495 0.494239 4.6308 --4.07533 0.554851 5.22203 --4.22461 0.572422 5.51525 --4.11007 0.558828 5.56257 --4.12841 0.560864 5.7427 --3.91475 0.53509 5.68559 --3.8538 0.527302 5.78462 --3.76303 0.517186 5.85284 --2.93714 0.4165 5.05272 --2.97332 0.421153 5.24365 --1.45328 0.237316 3.47285 --1.41639 0.232159 3.51483 --1.36063 0.225633 3.53203 --3.38613 0.47076 6.48678 --1.26594 0.214649 3.58755 --1.24289 0.211427 3.65165 --1.09014 0.19331 3.51313 --1.11361 0.195588 3.65153 --0.991578 0.181178 3.55027 --0.884434 0.168359 3.46293 --0.864353 0.165506 3.53083 --0.839276 0.162918 3.58998 --0.851815 0.163588 3.72949 --0.838551 0.162518 3.82498 --0.760127 0.152756 3.78443 --0.708386 0.146241 3.79695 --0.690137 0.144829 3.89162 --0.628537 0.136728 3.88423 --0.57875 0.130674 3.90364 --0.773363 0.154944 4.61963 --0.726445 0.148529 4.68884 --0.673539 0.142255 4.748 --0.611771 0.13498 4.77761 --0.558876 0.128104 4.84481 --0.527529 0.124815 4.99837 --0.457851 0.116456 5.01577 --0.386245 0.107439 5.02228 --0.292051 0.096646 4.91961 --0.239063 0.0899942 5.01162 --0.531494 0.125323 7.20359 --0.344182 0.102363 6.68673 -0.00386577 0.0601603 4.78732 -0.0820976 0.0504038 4.68609 -0.0851336 0.0501246 5.32998 -0.171276 0.0403167 5.19697 -0.255226 0.029582 5.02246 -0.259023 0.0292842 6.53472 -0.351077 0.0187979 6.69797 -0.447991 0.00644583 6.84977 --2.99366 0.527372 -0.958808 --3.1406 0.549333 -0.957883 --3.30641 0.574215 -0.961491 --3.46424 0.598094 -0.955387 --3.64093 0.624948 -0.952717 --3.83648 0.654822 -0.952583 --4.042 0.685418 -0.950021 --4.26737 0.719183 -0.948192 --4.51257 0.75616 -0.9462 --4.7965 0.799207 -0.949875 --5.09132 0.844226 -0.947272 --5.43383 0.895859 -0.950308 --5.78827 0.948646 -0.944616 --6.19127 1.01028 -0.940964 --6.63506 1.07656 -0.933784 --7.15624 1.15533 -0.931048 --7.75686 1.2459 -0.928404 --8.44682 1.35 -0.923773 --9.26482 1.47381 -0.920226 --10.202 1.61522 -0.909101 --11.2979 1.78064 -0.890571 --12.6311 1.98169 -0.867228 --14.3197 2.23644 -0.841237 --16.464 2.55939 -0.804281 --30.8914 4.73667 -0.665931 --42.1902 6.44132 0.243467 --42.5234 6.49088 0.997009 --43.1395 6.58443 1.76735 --53.8716 8.20357 2.91636 --44.3902 6.77303 3.37605 --44.4215 6.77744 4.17351 --44.8616 6.84361 5.0103 --43.4677 6.63373 5.67036 --44.2939 6.75789 6.55893 --46.9229 7.15478 7.73674 --48.7133 7.42502 8.87917 --13.4477 2.10427 3.99707 --13.2495 2.07474 4.20906 --13.0483 2.04474 4.41495 --12.5952 1.97581 4.54742 --10.574 1.67146 4.21034 --7.31128 1.17905 3.4144 --3.95777 0.67249 2.46441 --4.1935 0.708199 2.63401 --4.47182 0.750768 2.82937 --4.9564 0.823448 3.11753 --4.47915 0.751338 3.03374 --3.87899 0.661259 2.87909 --3.88171 0.661043 2.97233 --4.60902 0.770789 3.40855 --4.19336 0.707895 3.31426 --4.22275 0.712566 3.43306 --4.36313 0.73408 3.61459 --4.26569 0.718956 3.67091 --4.40705 0.740134 3.86467 --3.58624 0.616375 3.48214 --3.80191 0.649156 3.71814 --3.73817 0.639492 3.78281 --3.64865 0.626358 3.82916 --3.49379 0.602877 3.82746 --4.16399 0.704223 4.42644 --3.72589 0.637378 4.21937 --3.64629 0.625306 4.27505 --3.64294 0.624883 4.39169 --4.12077 0.697086 4.92063 --3.6273 0.622628 4.6277 --3.60112 0.61928 4.73343 --4.47572 0.750832 5.69172 --4.31586 0.726662 5.70244 --4.17084 0.704884 5.72305 --4.14358 0.701133 5.86233 --5.34713 0.882396 7.34035 --3.93375 0.669164 5.97866 --4.95004 0.822242 7.33916 --5.04325 0.83676 7.67944 --1.4796 0.299006 3.47117 --1.44277 0.292871 3.5136 --1.39894 0.286892 3.54747 --1.34924 0.279119 3.57257 --1.29261 0.270466 3.58837 --1.14803 0.248848 3.4704 --1.05685 0.234999 3.42366 --0.926172 0.215268 3.30658 --0.906146 0.211981 3.36569 --0.988749 0.22493 3.60656 --0.866978 0.206894 3.49256 --0.823214 0.200412 3.51624 --0.798261 0.195801 3.57488 --0.853108 0.204486 3.80408 --0.787609 0.194881 3.79133 --0.75173 0.189167 3.84105 --0.705987 0.181917 3.87187 --0.915313 0.21381 4.54171 --0.588842 0.164519 3.86599 --0.77535 0.192356 4.54251 --0.740295 0.187068 4.64017 --0.714051 0.183185 4.77557 --0.642534 0.172934 4.77733 --0.576957 0.162922 4.79685 --0.465303 0.145444 4.64143 --0.419349 0.138841 4.72587 --0.412548 0.137754 4.99482 --0.335198 0.12589 4.9712 --0.298872 0.120657 5.15225 --0.608618 0.167443 7.35187 --0.534385 0.156117 7.59767 --0.347378 0.127619 7.0901 -0.0424254 0.0695968 4.76168 -0.103122 0.0602543 4.80893 -0.123692 0.0574899 5.3434 -0.217136 0.0427678 5.08002 -0.290478 0.0320601 5.03444 -0.299025 0.0303431 6.80646 -0.400059 0.0153791 6.72908 --3.21824 0.673923 -0.967254 --3.36583 0.701299 -0.959083 --3.5234 0.7293 -0.95048 --3.69082 0.759942 -0.941046 --3.89494 0.797289 -0.942229 --4.14575 0.841856 -0.955795 --4.37956 0.885167 -0.953785 --4.63426 0.930784 -0.950959 --4.89885 0.978253 -0.943057 --5.21991 1.03665 -0.945457 --5.52509 1.09191 -0.93088 --5.94429 1.16793 -0.940252 --6.34559 1.24083 -0.929857 --6.83511 1.32965 -0.928413 --7.36527 1.42531 -0.919447 --7.99249 1.5397 -0.913909 --8.75653 1.6781 -0.914518 --9.63947 1.83796 -0.910545 --10.6125 2.01408 -0.890498 --11.8304 2.23493 -0.873549 --13.3237 2.50583 -0.850461 --15.0448 2.81787 -0.800962 --18.0018 3.35404 -0.81176 --28.1195 5.18742 -0.78097 --28.0971 5.18333 -0.270878 --40.0058 7.34146 -0.0807478 --39.9788 7.33644 0.63822 --40.0776 7.35506 1.357 --40.0357 7.34713 2.07592 --43.0282 7.88959 3.70255 --43.3676 7.951 4.5056 --43.7787 8.02517 6.12378 --46.3665 8.49408 7.26714 --46.3291 8.48753 8.10917 --46.3264 8.48753 8.96011 --46.9566 8.60114 9.9352 --12.8256 2.41572 3.75429 --12.6901 2.39121 3.97073 --12.7329 2.39854 4.22755 --12.047 2.27427 4.29662 --11.9026 2.24831 4.49456 --4.09457 0.833176 2.38283 --4.01411 0.818418 2.44604 --4.0257 0.820709 2.53862 --4.02644 0.820214 2.62866 --4.01623 0.818906 2.71567 --4.13273 0.839846 2.85412 --4.41843 0.8919 3.06989 --4.29246 0.868578 3.11702 --4.45141 0.897953 3.29287 --4.43824 0.895125 3.39325 --4.45865 0.899237 3.51172 --4.23966 0.859691 3.50691 --4.19582 0.851175 3.59066 --4.79291 0.959863 4.04275 --4.44337 0.896447 3.95851 --4.442 0.896243 4.07716 --3.97389 0.8108 3.89566 --4.40766 0.889203 4.30017 --3.67654 0.756773 3.91671 --3.54565 0.733591 3.93227 --3.63726 0.749996 4.11064 --3.44318 0.714382 4.07396 --3.43589 0.713229 4.1807 --3.60054 0.743809 4.43442 --5.14979 1.02372 5.90289 --4.96149 0.989608 5.90962 --3.93335 0.803373 5.12749 --4.76767 0.955255 6.07963 --4.49741 0.906394 5.99006 --4.14229 0.841386 5.79984 --4.13386 0.839867 5.96116 --4.06812 0.828006 6.06477 --3.97964 0.8126 6.14488 --4.96437 0.990639 7.50105 --4.78296 0.958161 7.51205 --1.47286 0.358188 3.51977 --1.42915 0.350249 3.55444 --1.38544 0.342266 3.5882 --1.33486 0.332429 3.61321 --1.22803 0.313034 3.55463 --1.01073 0.274107 3.31802 --1.05484 0.281783 3.47941 --0.986482 0.269864 3.46396 --0.924072 0.258654 3.45552 --0.901108 0.254213 3.51517 --0.894837 0.253531 3.60998 --0.886626 0.251751 3.70523 --0.883293 0.25118 3.81888 --0.805162 0.236497 3.77987 --0.749659 0.22635 3.78444 --0.724594 0.222626 3.86106 --0.705464 0.219184 3.95633 --0.644104 0.207106 3.94934 --0.578696 0.196258 3.93165 --0.771704 0.230476 4.64794 --0.720972 0.221362 4.70785 --0.663373 0.210854 4.74806 --0.598912 0.198928 4.76807 --0.589289 0.197308 4.98937 --0.41219 0.165364 4.58205 --0.495427 0.180552 5.21029 --0.335089 0.151819 4.82704 --0.295014 0.144399 4.96863 --0.251946 0.136269 5.11975 --0.601588 0.199721 7.68695 --0.412875 0.165177 7.20109 -0.0163548 0.0875434 4.72782 -0.0817993 0.0764716 4.72586 -0.10206 0.0722672 5.19061 -0.163004 0.0612914 5.34657 -0.256197 0.0445592 5.04244 -0.327419 0.0314348 5.00621 -0.350814 0.0273116 6.76804 -0.449107 0.00990199 6.81975 --2.96613 0.734103 -0.963669 --3.10263 0.762694 -0.957929 --3.248 0.793819 -0.952359 --3.40428 0.826615 -0.946604 --3.58727 0.865659 -0.948502 --3.77227 0.904117 -0.944451 --3.98495 0.948982 -0.946052 --4.21742 0.998022 -0.948238 --4.45972 1.04987 -0.946296 --4.72186 1.10498 -0.942991 --5.00371 1.16541 -0.937524 --5.3252 1.23311 -0.934874 --5.64662 1.30134 -0.921337 --6.08288 1.39347 -0.929897 --6.49334 1.48015 -0.91572 --6.99979 1.58718 -0.911665 --7.55568 1.70453 -0.901306 --8.18969 1.83875 -0.888395 --8.54645 1.91495 -0.798038 --9.26942 2.06776 -0.761464 --10.3229 2.2903 -0.752823 --11.6592 2.57291 -0.7474 --13.2596 2.91228 -0.727829 --14.8826 3.25574 -0.653653 --26.3092 5.6731 -0.918028 --27.1684 5.85489 -0.484052 --40.2615 8.62614 0.269968 --40.375 8.65008 0.997185 --13.7946 3.02569 1.50924 --13.774 3.02104 1.76366 --42.7056 9.14294 4.08508 --13.7586 3.01739 2.27407 --43.7222 9.35819 5.74769 --47.1398 10.082 6.97552 --42.506 9.10088 7.17483 --42.2396 9.04439 7.91599 --12.9221 2.84016 3.41796 --12.7918 2.81323 3.63985 --12.7644 2.80749 3.88066 --12.722 2.79873 4.11903 --12.7331 2.8009 4.3714 --12.6454 2.78185 4.59918 --5.40669 1.24969 2.73063 --5.30153 1.22834 2.81224 --5.1668 1.19957 2.88151 --3.9867 0.949738 2.57867 --4.4646 1.0511 2.84655 --4.20444 0.996201 2.84525 --4.22687 1.00082 2.95129 --4.32732 1.022 3.09394 --4.1927 0.992841 3.135 --4.30593 1.01742 3.29018 --4.34509 1.02599 3.41505 --4.2944 1.01495 3.49658 --4.37209 1.03115 3.64745 --4.37767 1.03222 3.76308 --4.50764 1.05962 3.95466 --4.26339 1.00829 3.92505 --4.22947 1.00094 4.02022 --3.88164 0.927215 3.90807 --3.49931 0.846435 3.75651 --3.66775 0.881874 3.98228 --3.64761 0.878475 4.07964 --3.52393 0.851906 4.09901 --3.54036 0.855183 4.22571 --3.33283 0.810862 4.17144 --3.51789 0.85068 4.44496 --3.36266 0.817535 4.43092 --3.52799 0.85226 4.70667 --3.55024 0.8572 4.85975 --4.30021 1.01632 5.73712 --5.89305 1.35326 7.53315 --4.25772 1.00749 6.03496 --4.15762 0.985844 6.10449 --4.01807 0.956482 6.12731 --4.85421 1.13317 7.2938 --3.7262 0.894717 6.14747 --1.49501 0.422617 3.51773 --1.42778 0.407708 3.52146 --1.37919 0.398041 3.54747 --1.2834 0.377246 3.50785 --1.25158 0.370678 3.55564 --0.983496 0.314049 3.2466 --0.987156 0.31489 3.33979 --1.0764 0.33412 3.57789 --0.921646 0.300731 3.41708 --0.879991 0.292436 3.44206 --0.818715 0.279173 3.43133 --0.800696 0.275409 3.49858 --0.823928 0.280578 3.65506 --0.748916 0.264043 3.61537 --0.753404 0.26579 3.74597 --0.734332 0.261885 3.83185 --0.773182 0.26981 4.06519 --0.636279 0.241012 3.87413 --0.608346 0.235073 3.95004 --0.517635 0.215918 3.85651 --0.787612 0.273077 4.81975 --0.688966 0.252001 4.73758 --0.648107 0.243325 4.83467 --0.498644 0.211448 4.55658 --0.435319 0.19797 4.56416 --0.362197 0.182918 4.53181 --0.291082 0.167908 4.49787 --0.369077 0.184284 5.17658 --0.29391 0.168472 5.17179 --0.212945 0.151289 5.12628 --0.460658 0.203755 7.19267 --0.0182733 0.109438 4.763 -0.0470545 0.0964023 4.76173 -0.108506 0.0835107 4.79904 -0.127021 0.078847 5.35333 -0.21542 0.0603848 5.14985 -0.289457 0.0451312 5.09438 -0.297131 0.0434465 6.90635 -0.398056 0.0219353 6.9191 --2.858 0.815262 -0.955124 --2.98432 0.846363 -0.947067 --3.12946 0.881352 -0.944193 --3.28347 0.918889 -0.941189 --3.45628 0.960388 -0.941869 --3.63894 1.00456 -0.941018 --3.83145 1.05144 -0.938237 --4.07041 1.10951 -0.948137 --4.29255 1.16332 -0.942712 --4.54335 1.22372 -0.940439 --4.81286 1.28935 -0.936405 --5.11296 1.36283 -0.932771 --5.44076 1.44205 -0.927947 --5.79912 1.52927 -0.920325 --6.1861 1.62344 -0.908565 --6.42483 1.68123 -0.843259 --6.74753 1.75949 -0.791061 --7.26089 1.88378 -0.770994 --7.90856 2.04075 -0.760923 --8.7211 2.23837 -0.759247 --9.57406 2.44555 -0.735366 --10.7065 2.72013 -0.724199 --12.0828 3.05395 -0.705537 --13.7325 3.4543 -0.669546 --13.9452 3.50597 -0.170865 --13.9622 3.50987 0.0887676 --13.9761 3.5136 0.348591 --40.6413 9.98525 -0.111521 --40.635 9.9835 0.627739 --15.0192 3.76631 1.13825 --13.9561 3.5089 1.38848 --13.9464 3.50617 1.64808 --13.9239 3.50062 1.90673 --13.9161 3.49901 2.16648 --13.8936 3.49346 2.42514 --13.8967 3.49461 2.68682 --46.6723 11.4482 8.2511 --42.8146 10.512 9.25758 --12.9848 3.27327 3.822 --12.916 3.25585 4.05953 --12.6823 3.19932 4.25562 --11.3359 2.87296 4.14886 --12.5081 3.15726 4.71098 --11.5673 2.92923 4.67707 --11.4748 2.90686 4.88416 --4.06234 1.10736 2.57036 --4.07191 1.10965 2.66532 --4.01542 1.09575 2.73675 --4.19362 1.13879 2.90183 --5.11226 1.36204 3.3914 --8.92056 2.2865 5.21408 --8.72372 2.23898 5.32454 --9.01787 2.31004 5.67028 --4.93621 1.31998 3.78827 --4.15522 1.12974 3.49307 --4.2229 1.14607 3.63836 --4.35558 1.17846 3.82611 --4.29803 1.165 3.90782 --4.19026 1.13886 3.95691 --4.38499 1.18587 4.20189 --4.13534 1.12541 4.15668 --3.90544 1.06933 4.11487 --3.62236 1.00062 4.0251 --3.49985 0.971148 4.04512 --3.55566 0.984313 4.20181 --3.62223 1.00089 4.37372 --3.53518 0.979966 4.42177 --3.32804 0.929466 4.36381 --3.33654 0.931322 4.49173 --3.44836 0.958557 4.72216 --3.37807 0.941417 4.78565 --4.01344 1.09564 5.56253 --5.67213 1.49785 7.46158 --5.9833 1.5739 8.02835 --5.92845 1.55992 8.21743 --8.16166 2.10254 11.0727 --7.83794 2.02339 11.0443 --3.64819 1.00683 6.17721 --3.39098 0.943951 6.03184 --8.03202 2.07035 12.4395 --2.99162 0.847846 5.85499 --1.22781 0.419193 3.49102 --1.19606 0.411593 3.53816 --0.980555 0.359726 3.30139 --0.957703 0.353885 3.35291 --0.881778 0.335582 3.3191 --0.827491 0.322204 3.31772 --0.888045 0.337112 3.52391 --1.5414 0.495468 4.8666 --1.41233 0.464237 4.77853 --0.762415 0.306429 3.60415 --0.721841 0.296505 3.63543 --0.717516 0.29582 3.74797 --0.861162 0.330901 4.21871 --0.646135 0.278296 3.84542 --0.917914 0.344351 4.70289 --0.607008 0.268755 4.04409 --0.798229 0.315404 4.77047 --0.761356 0.30651 4.87851 --0.660958 0.281815 4.78619 --0.560575 0.25752 4.68174 --0.461203 0.233697 4.56536 --0.396065 0.217596 4.56275 --0.315324 0.198105 4.49072 --0.295913 0.193811 4.69026 --0.329889 0.201841 5.194 --0.252911 0.183392 5.17871 --0.543097 0.253679 7.41079 --0.380335 0.214014 7.0527 -0.0172961 0.117544 4.76748 -0.0843728 0.101378 4.74574 -0.139022 0.0883159 4.85208 -0.163402 0.0823041 5.38638 -0.258104 0.0589833 5.05243 -0.329022 0.0413685 5.00621 -0.351546 0.0367684 6.81793 -0.455948 0.0108105 6.1198 --2.7749 0.897257 -0.960182 --2.88327 0.926662 -0.944243 --3.02613 0.966407 -0.94382 --3.17791 1.0077 -0.943317 --3.34055 1.05168 -0.94218 --3.50409 1.09698 -0.935796 --3.68543 1.14623 -0.9322 --3.88645 1.20159 -0.930486 --4.13285 1.26913 -0.940707 --4.37132 1.33477 -0.939069 --4.59402 1.39519 -0.922452 --4.87191 1.47138 -0.917887 --5.15074 1.5481 -0.90393 --5.46802 1.63506 -0.892043 --5.79518 1.72402 -0.871985 --6.13309 1.81708 -0.843251 --6.47198 1.90977 -0.802778 --6.88673 2.02379 -0.768596 --7.43465 2.17321 -0.749056 --8.14416 2.36784 -0.742663 --8.93149 2.58379 -0.724926 --9.92188 2.85489 -0.71206 --11.2 3.20525 -0.705633 --12.7393 3.62618 -0.686358 --14.377 4.07534 -0.622311 --23.1393 6.47468 -0.715513 --23.1941 6.49016 -0.289112 --40.9668 11.3578 0.246607 --15.0864 4.26898 0.998922 --15.0648 4.26362 1.2806 --14.1229 4.00539 1.52842 --14.1113 4.00179 1.79295 --14.0956 3.99793 2.05717 --14.0859 3.99546 2.32196 --14.0703 3.99062 2.58673 --42.531 11.7859 6.47494 --47.7031 13.2024 8.91205 --42.5087 11.7797 8.85965 --41.5942 11.5296 9.4803 --41.0894 11.3911 11.7479 --11.3509 3.24605 4.29125 --10.8668 3.11382 4.37849 --5.65209 1.68565 2.94964 --5.58182 1.66625 3.04828 --3.87748 1.19911 2.56239 --3.87817 1.19958 2.65158 --4.12003 1.26558 2.83805 --4.03408 1.24235 2.89894 --10.6157 3.04444 5.89112 --8.85741 2.56273 5.31881 --10.0425 2.88759 6.09597 --5.37788 1.61055 3.97171 --4.13288 1.26952 3.44659 --4.42279 1.34843 3.71321 --4.83164 1.46075 4.06353 --4.40337 1.34321 3.93462 --5.40329 1.61704 4.67691 --4.49013 1.36725 4.23214 --3.86821 1.19685 3.94074 --4.16186 1.27758 4.25967 --4.35126 1.3291 4.52132 --3.94772 1.21898 4.34995 --3.82155 1.18355 4.37585 --3.83295 1.18684 4.50892 --3.87778 1.19881 4.67491 --3.54219 1.10743 4.51575 --3.48971 1.09315 4.59483 --3.38516 1.06432 4.62634 --3.57046 1.11492 4.93477 --3.85099 1.19188 5.35513 --4.0224 1.23882 5.68778 --6.10704 1.81023 8.09215 --5.78906 1.72282 7.99117 --5.70975 1.70077 8.14856 --8.53659 2.47512 11.7765 --5.06804 1.52522 7.87862 --4.98186 1.50182 8.01711 --3.12913 0.994566 5.81446 --3.01769 0.963998 5.83941 --2.95336 0.94639 5.92659 --1.85707 0.646244 4.48935 --1.8194 0.635673 4.56463 --1.66993 0.594537 4.46351 --1.65185 0.589713 4.57007 --1.63183 0.583792 4.67707 --1.56962 0.566877 4.71506 --1.53486 0.557182 4.80444 --1.52454 0.554596 4.94658 --0.783669 0.352165 3.61053 --0.768651 0.347495 3.69628 --1.11862 0.443538 4.59792 --1.02709 0.418751 4.55352 --0.642187 0.313369 3.78899 --0.928236 0.391104 4.6623 --0.88366 0.378946 4.73422 --0.566561 0.291944 4.03509 --0.467411 0.2648 3.91216 --0.728351 0.336584 4.91827 --0.592035 0.299486 4.70079 --0.545493 0.286452 4.77764 --0.419073 0.251676 4.5545 --0.350127 0.233342 4.53175 --0.28125 0.213941 4.50765 --0.372494 0.239538 5.25488 --0.704746 0.330089 7.41973 --0.573044 0.294247 7.30264 --0.171086 0.183699 5.38525 --0.0229555 0.143237 4.85207 -0.0508082 0.123734 4.7915 -0.113891 0.106253 4.79898 -0.169416 0.0906131 4.91505 -0.219443 0.0771911 5.1498 -0.294987 0.0563574 5.04443 -0.296237 0.0559852 7.01627 -0.394433 0.0290372 7.21904 --2.79619 1.00837 -0.950213 --2.9201 1.04634 -0.94221 --3.0627 1.0902 -0.939588 --3.21417 1.1366 -0.936736 --3.3666 1.18331 -0.928888 --3.55549 1.24067 -0.932754 --3.72657 1.29365 -0.922297 --3.94397 1.3598 -0.925219 --4.17116 1.42973 -0.924463 --4.35506 1.48526 -0.898433 --4.58415 1.55604 -0.882989 --4.89601 1.65084 -0.888343 --5.20974 1.7473 -0.882854 --5.53333 1.84576 -0.869193 --5.8588 1.9459 -0.84439 --6.17544 2.04218 -0.805633 --6.52939 2.15082 -0.765354 --7.0064 2.29621 -0.740645 --7.61517 2.48311 -0.727084 --8.35679 2.70995 -0.717275 --9.27156 2.98922 -0.710586 --10.3948 3.33325 -0.703502 --11.5976 3.70165 -0.66639 --13.3721 4.24378 -0.653744 --24.9722 7.79311 -1.09824 --32.1164 9.97857 0.104517 --32.5276 10.104 0.6963 --42.7579 13.2344 2.97196 --42.4133 13.1285 3.7417 --41.1314 12.7368 4.42333 --41.5912 12.8772 5.23525 --42.0656 13.0225 6.06845 --52.2362 16.1335 9.23799 --42.2159 13.0686 9.27576 --12.4416 3.9592 3.75227 --43.315 13.4046 11.9966 --12.0913 3.85208 4.4042 --10.9083 3.48995 4.30753 --10.8152 3.46199 4.50387 --11.7391 3.74478 5.03449 --5.32242 1.7814 3.03669 --11.1914 3.57685 5.32855 --4.24789 1.45273 2.85574 --4.07371 1.39945 2.88342 --8.66163 2.80328 4.96772 --5.29695 1.7735 3.63527 --5.217 1.74901 3.72409 --5.1449 1.72712 3.81513 --5.15729 1.7305 3.94891 --5.20008 1.74373 4.10251 --5.1309 1.72316 4.19651 --5.09319 1.71141 4.3086 --4.92192 1.65945 4.33914 --4.57991 1.55435 4.25481 --4.61385 1.56493 4.40608 --4.47605 1.52236 4.44367 --4.29212 1.4661 4.44341 --4.26521 1.45791 4.55348 --4.2432 1.45132 4.66972 --4.26534 1.45825 4.8226 --3.93823 1.35774 4.69117 --3.84657 1.32986 4.74615 --3.46358 1.21318 4.53918 --3.52596 1.23213 4.72356 --3.50497 1.22547 4.837 --4.41843 1.50501 5.88005 --4.00904 1.37971 5.63259 --5.47906 1.82928 7.36174 --9.28266 2.99271 11.7782 --8.46206 2.74213 11.2252 --5.3877 1.80121 7.95729 --5.15858 1.73168 7.92677 --5.01769 1.6886 7.99811 --3.10182 1.10229 5.73449 --3.0112 1.07418 5.78358 --2.93623 1.05113 5.85504 --1.84981 0.718755 4.44347 --1.82984 0.712493 4.54358 --1.74327 0.686213 4.54384 --1.66846 0.663386 4.55893 --2.28829 0.853677 5.75745 --1.5971 0.642106 4.72204 --1.6573 0.659867 4.98606 --1.50813 0.614829 4.86661 --0.829248 0.407012 3.66979 --0.793721 0.395909 3.71157 --1.0776 0.483193 4.45674 --0.738247 0.378832 3.83902 --0.762231 0.386027 4.03536 --0.854454 0.414637 4.41819 --0.878301 0.421897 4.65637 --1.3126 0.554362 6.06726 --0.474505 0.298488 3.875 --0.389227 0.272494 3.77854 --0.587332 0.332553 4.60492 --0.568146 0.326465 4.7681 --0.44871 0.290595 4.57499 --0.370198 0.266788 4.51431 --0.315053 0.249136 4.54908 --0.219135 0.220276 4.38771 --0.804844 0.399343 7.70259 --0.254753 0.231551 5.25745 --0.203246 0.214912 5.38891 --0.355595 0.262241 6.98349 -0.00774821 0.151097 4.90626 -0.0870081 0.126262 4.78545 -0.153834 0.106549 4.75256 -0.17803 0.0985447 5.26674 -0.260074 0.0733908 5.08235 -0.328941 0.0523638 5.08607 -0.353964 0.0446594 6.798 -0.456939 0.0137856 6.05978 --2.69952 1.08278 -0.950174 --2.82226 1.12359 -0.944221 --2.94591 1.16565 -0.934419 --3.08726 1.21354 -0.929701 --3.26302 1.2729 -0.937852 --3.43185 1.33034 -0.935838 --3.60164 1.38812 -0.928229 --3.73803 1.43391 -0.899208 --3.92647 1.49799 -0.88829 --4.15228 1.57397 -0.885337 --4.36922 1.64696 -0.871178 --4.61458 1.73057 -0.859371 --4.87865 1.81945 -0.845204 --5.18 1.92148 -0.833558 --5.51867 2.03578 -0.822288 --5.85921 2.15178 -0.799275 --6.17328 2.25712 -0.756776 --6.60713 2.40389 -0.732602 --7.18139 2.59849 -0.724139 --7.85971 2.82844 -0.715976 --8.6706 3.10252 -0.707569 --9.6985 3.44956 -0.705828 --10.851 3.8392 -0.684693 --12.4001 4.36366 -0.672966 --20.4776 7.09622 -0.938921 --21.3287 7.38351 -0.612825 --30.1881 10.3808 -0.699882 --30.2678 10.4076 -0.136416 --30.6234 10.5282 0.424328 --30.5617 10.5068 0.997808 --41.9885 14.3725 1.77987 --49.9784 17.0742 2.85725 --43.5738 14.9086 3.43517 --43.7155 14.9562 4.26072 --41.3811 14.1661 4.865 --41.4993 14.2066 5.65681 --41.9192 14.3486 8.89269 --40.7777 13.9622 9.467 --12.3152 4.33479 3.87444 --12.238 4.30839 4.10335 --10.7324 3.79985 3.95544 --10.8004 3.82291 4.19552 --11.2931 3.98858 4.56865 --11.2953 3.98946 4.80582 --5.26628 1.95059 2.97724 --10.5446 3.73577 5.01344 --5.34007 1.97529 3.24321 --5.24847 1.94493 3.32894 --5.16578 1.91616 3.41576 --5.11634 1.9001 3.51587 --5.09049 1.89102 3.62709 --5.12344 1.90201 3.76773 --5.14554 1.91021 3.90593 --5.83905 2.14461 4.40898 --4.92036 1.83315 4.04181 --5.0101 1.86365 4.22358 --4.95579 1.84533 4.32457 --5.02197 1.86817 4.50177 --4.81092 1.79627 4.50232 --4.65667 1.7444 4.53426 --4.43292 1.66856 4.51129 --4.19549 1.58796 4.46974 --3.99135 1.51918 4.44404 --4.50898 1.69462 4.98356 --4.03165 1.53315 4.73666 --4.06451 1.54433 4.90142 --3.65879 1.40664 4.68283 --3.48996 1.3502 4.66044 --3.52774 1.36277 4.82706 --3.41479 1.32413 4.853 --4.12775 1.56558 5.71637 --4.10866 1.55875 5.86457 --3.96916 1.51217 5.88393 --3.46778 1.34195 5.49014 --3.38022 1.31244 5.54772 --5.15579 1.91313 7.86734 --4.93205 1.8377 7.83263 --3.30431 1.28711 5.95781 --3.07597 1.2098 5.83015 --2.92686 1.15914 5.79949 --2.86377 1.13757 5.88617 --1.84793 0.794583 4.53854 --1.77816 0.770601 4.56463 --1.7445 0.75967 4.64796 --1.6191 0.716551 4.57863 --2.21813 0.919482 5.7742 --1.63183 0.721106 4.89697 --0.860358 0.460033 3.58877 --1.49709 0.676188 4.96424 --0.820616 0.446858 3.73525 --0.78415 0.434702 3.77718 --0.721376 0.41321 3.76413 --0.856429 0.458851 4.21557 --0.870591 0.463141 4.40578 --1.45914 0.663026 6.11788 --0.562841 0.359322 3.922 --0.504911 0.340328 3.91297 --0.407186 0.30674 3.77976 --0.638925 0.38551 4.69954 --0.558571 0.358284 4.65303 --0.446242 0.319815 4.47972 --0.373719 0.295337 4.43863 --0.343806 0.286045 4.57056 --0.244251 0.25152 4.40054 --0.410578 0.308125 5.51896 --0.317589 0.27636 5.43685 --0.215933 0.242552 5.2838 --0.0990527 0.202844 4.99017 --0.0130936 0.173738 4.85211 -0.0363952 0.157048 4.98008 -0.126017 0.127126 4.74932 -0.158577 0.116212 5.1142 -0.229146 0.0921946 5.08001 -0.297772 0.0687222 5.05441 -0.300019 0.0682895 7.02625 -0.399158 0.0343531 7.02902 --2.6902 1.18575 -0.925575 --2.83619 1.24036 -0.932674 --2.9842 1.29432 -0.934923 --3.14096 1.35285 -0.936742 --3.28202 1.4051 -0.924632 --3.37302 1.43875 -0.882977 --3.56599 1.51142 -0.886372 --3.74333 1.57685 -0.875388 --3.9481 1.6527 -0.869456 --4.14494 1.7266 -0.852962 --4.35162 1.80327 -0.832941 --4.58478 1.88944 -0.815327 --4.81983 1.97714 -0.789567 --5.11768 2.08711 -0.775431 --5.44386 2.20895 -0.758802 --5.81612 2.34757 -0.743117 --6.23642 2.50322 -0.725573 --6.73022 2.68627 -0.710328 --7.37192 2.9257 -0.709166 --8.13615 3.20963 -0.708142 --9.06894 3.55583 -0.708848 --10.0506 3.92034 -0.682822 --11.3586 4.4064 -0.666285 --13.2653 5.115 -0.67405 --19.3558 7.37847 -1.04097 --28.5331 10.7877 -0.896371 --21.7414 8.26455 -0.0375773 --28.9147 10.9302 0.176181 --29.111 11.0023 0.722212 --42.4869 15.9724 1.39715 --30.6106 11.5598 2.44682 --30.8351 11.643 3.04224 --41.0865 15.4525 8.42069 --41.8428 15.7339 9.36876 --40.4225 15.206 9.87874 --41.7447 15.6971 10.9877 --12.4346 4.80607 4.3116 --10.5454 4.10402 4.04631 --10.7101 4.16547 4.31553 --11.0677 4.2982 4.65442 --5.14148 2.09654 2.89698 --5.09218 2.07839 2.99539 --5.05856 2.06548 3.09925 --5.04936 2.06254 3.21288 --5.05584 2.06495 3.33415 --5.06038 2.06628 3.45636 --5.0796 2.07296 3.58751 --5.11342 2.08601 3.72825 --6.11668 2.45916 4.36604 --6.02719 2.42587 4.47086 --5.8859 2.37291 4.54569 --4.92108 2.01458 4.13929 --4.81212 1.97416 4.20519 --4.71 1.93626 4.27321 --4.75164 1.95171 4.43241 --4.59185 1.89226 4.45978 --4.46436 1.84465 4.5044 --4.14326 1.72596 4.40374 --4.42246 1.829 4.74511 --4.40637 1.8233 4.87185 --4.03751 1.6858 4.71305 --3.99015 1.66867 4.80942 --3.79722 1.59727 4.77791 --4.24822 1.76404 5.32495 --3.86772 1.6226 5.12112 --4.08315 1.70254 5.47875 --4.02205 1.68067 5.57717 --4.00689 1.675 5.72374 --3.88334 1.62907 5.75698 --3.35267 1.43136 5.33012 --3.32581 1.42179 5.45278 --3.33313 1.42456 5.6207 --8.46828 3.3326 12.2 --4.79587 1.96784 7.8516 --3.14222 1.35385 5.88313 --2.93583 1.27687 5.77572 --2.56758 1.13969 5.42097 --2.44515 1.09435 5.40412 --1.95319 0.911593 4.80726 --1.75676 0.839033 4.63551 --1.6608 0.803276 4.61796 --1.58243 0.773743 4.62354 --0.918503 0.526684 3.56751 --1.94677 0.909105 5.61264 --2.24217 1.01959 6.38687 --0.816196 0.488795 3.69641 --0.771977 0.473275 3.72043 --0.715195 0.451602 3.71664 --1.33146 0.681161 5.28577 --1.56423 0.766904 6.06204 --0.612834 0.413622 3.86397 --0.565765 0.395735 3.88418 --0.514766 0.377103 3.8942 --0.445338 0.351489 3.84667 --0.70484 0.447661 4.84066 --0.571242 0.39873 4.62398 --0.527936 0.381884 4.70094 --0.387741 0.329926 4.41118 --0.348265 0.315656 4.49494 --0.483754 0.365122 5.36591 --0.210363 0.26433 4.41692 --0.341531 0.312561 5.40958 --0.255476 0.281129 5.34592 --0.0897489 0.219816 4.75769 --0.0510499 0.204794 4.9263 -0.0193628 0.178498 4.88641 -0.0916396 0.15154 4.81531 -0.148675 0.130344 4.88198 -0.190787 0.114878 5.18706 -0.263103 0.0882306 5.12225 -0.252367 0.0921334 7.02427 -0.359187 0.0524038 6.71799 -0.458805 0.0157149 5.97977 --2.62235 1.26493 -0.945218 --2.72694 1.30713 -0.929733 --2.85501 1.35923 -0.925005 --2.98499 1.41266 -0.916125 --3.07391 1.44787 -0.880868 --3.23816 1.51497 -0.880861 --3.40343 1.58139 -0.875308 --3.57843 1.65252 -0.867924 --3.74556 1.72063 -0.850828 --3.93913 1.79913 -0.838687 --4.10725 1.86691 -0.809554 --4.32921 1.95631 -0.794171 --4.55105 2.04709 -0.771047 --4.78273 2.14072 -0.742897 --5.08584 2.26305 -0.728638 --5.41828 2.39734 -0.711183 --5.71443 2.51748 -0.672028 --6.27281 2.74403 -0.687566 --6.8977 2.99696 -0.696986 --7.52444 3.25115 -0.683428 --8.37222 3.595 -0.688448 --9.22193 3.93853 -0.662002 --10.4775 4.44752 -0.665242 --12.3325 5.19975 -0.701009 --18.2117 7.58112 -1.12321 --27.2505 11.2429 -0.0475589 --27.6713 11.4133 0.467477 --27.2863 11.2579 0.998012 --27.9831 11.5399 2.07114 --28.2298 11.6394 2.62244 --40.8046 16.7343 8.05525 --40.8241 16.7422 9.66347 --5.08527 2.26311 2.28027 --5.06345 2.25397 2.38531 --5.05821 2.25206 2.49461 --5.03345 2.24172 2.59909 --5.01549 2.2349 2.70575 --4.9956 2.22696 2.81225 --4.98355 2.22164 2.92167 --4.98613 2.22254 3.03769 --5.00428 2.23078 3.16115 --5.02053 2.23696 3.286 --11.1273 4.71106 6.06748 --11.0953 4.69807 6.30913 --10.99 4.65497 6.51856 --8.30335 3.56685 5.42836 --8.30563 3.56813 5.63286 --5.9827 2.62638 4.56332 --4.65569 2.0888 3.95727 --4.68065 2.09928 4.09749 --8.41815 3.6137 6.55425 --6.7146 2.92249 5.67601 --4.56232 2.05161 4.41229 --4.31995 1.95294 4.37642 --4.24929 1.92451 4.45538 --4.33669 1.95969 4.65333 --4.25433 1.92624 4.72616 --4.09683 1.86309 4.73691 --3.92675 1.79332 4.73059 --3.90877 1.78619 4.85108 --4.07314 1.85257 5.13918 --3.79579 1.74001 5.02788 --4.10141 1.86467 5.46937 --5.94039 2.60922 7.4784 --3.92108 1.79132 5.60523 --3.91764 1.79004 5.76547 --3.36362 1.56571 5.31566 --3.25501 1.52143 5.3439 --3.3266 1.55078 5.5849 --3.3008 1.53972 5.71664 --3.30705 1.54292 5.89464 --2.88392 1.37072 5.50714 --2.65068 1.27658 5.34955 --2.57427 1.24539 5.40017 --2.45307 1.19617 5.38463 --2.37662 1.16579 5.43132 --1.87988 0.964232 4.80511 --1.74224 0.908731 4.7235 --1.65135 0.871686 4.71425 --1.54395 0.827818 4.66849 --1.93329 0.986245 5.54637 --1.8686 0.959374 5.60907 --2.99033 1.41379 8.08095 --1.54092 0.826975 5.32122 --1.57236 0.839914 5.5837 --1.6358 0.865425 5.93917 --1.54771 0.83006 5.9603 --2.42694 1.18583 8.43745 --2.28512 1.12903 8.43577 --0.513874 0.410832 3.84737 --0.458186 0.387937 3.83785 --0.716217 0.492983 4.81036 --0.58585 0.439766 4.60442 --0.52517 0.41555 4.61476 --0.412327 0.369539 4.4316 --0.369095 0.352102 4.49657 --0.300755 0.324282 4.46388 --0.263282 0.309046 4.56613 --0.180468 0.276343 4.45279 --0.312142 0.3296 5.50558 --0.171624 0.272191 5.10655 --0.0706537 0.230838 4.88158 --0.00991277 0.206591 4.91154 -0.0679299 0.174858 4.79148 -0.132402 0.148794 4.76924 -0.16765 0.134736 5.09431 -0.236042 0.10733 5.07001 -0.301494 0.0800296 5.06445 -0.293948 0.0835516 7.34613 -0.402267 0.0392111 6.96908 --2.52912 1.33233 -0.949118 --2.61487 1.37078 -0.925555 --2.69384 1.40518 -0.894524 --2.80506 1.45376 -0.879514 --2.94063 1.51437 -0.874258 --3.10265 1.5852 -0.877252 --3.25682 1.65302 -0.870535 --3.41971 1.72545 -0.862389 --3.5758 1.79393 -0.844779 --3.73286 1.86274 -0.821772 --3.88988 1.93182 -0.793372 --4.09868 2.02336 -0.779477 --4.2918 2.10861 -0.751853 --4.52009 2.20878 -0.729353 --4.75715 2.31275 -0.701579 --5.04783 2.44165 -0.681313 --5.41961 2.60495 -0.672956 --5.70345 2.72968 -0.627495 --6.34567 3.01168 -0.658367 --7.08834 3.33897 -0.687148 --7.73525 3.62374 -0.668066 --8.62721 4.01559 -0.669274 --9.76599 4.51731 -0.676881 --11.343 5.21104 -0.70417 --19.137 8.64054 -0.689863 --25.7299 11.5412 -0.754602 --25.8094 11.5757 -0.256801 --26.1455 11.7238 0.235782 --26.0259 11.6707 0.74519 --21.0467 9.47993 1.20389 --21.0942 9.50128 1.61624 --21.0724 9.49132 2.02741 --4.96311 2.40353 2.10578 --4.93544 2.39188 2.20771 --4.90684 2.37914 2.30909 --4.92991 2.38924 2.42357 --4.93252 2.38989 2.53439 --4.94285 2.39518 2.64844 --4.94153 2.39465 2.76049 --4.95683 2.40046 2.87905 --5.01198 2.42557 3.01442 --11.8821 5.44797 5.78919 --11.3491 5.21362 5.83891 --11.5432 5.29854 6.18135 --11.67 5.35442 6.50587 --9.93474 4.59134 5.95559 --10.1035 4.66571 6.27817 --10.1495 4.68593 6.54839 --9.8877 4.5702 6.65701 --7.22951 3.40104 5.39527 --4.54449 2.21919 3.99141 --4.38438 2.14866 4.01813 --4.50081 2.2007 4.21733 --4.30758 2.11585 4.21822 --4.45622 2.18044 4.44904 --4.37011 2.1427 4.52095 --4.32099 2.12153 4.61891 --4.29914 2.11215 4.73929 --3.83444 1.90684 4.50315 --4.00237 1.9816 4.77394 --4.34358 2.1311 5.20781 --4.28179 2.10416 5.30588 --4.01765 1.98737 5.21459 --3.74379 1.8669 5.1013 --3.60322 1.80554 5.10726 --5.60947 2.68829 7.33228 --5.23238 2.52222 7.15352 --5.10821 2.46753 7.23335 --3.37576 1.70505 5.46074 --3.29749 1.6705 5.52655 --2.95768 1.52181 5.26876 --2.78226 1.44446 5.1971 --2.70312 1.40889 5.24372 --2.63457 1.37966 5.30401 --2.57096 1.35107 5.37111 --2.51119 1.32505 5.44502 --2.43979 1.29347 5.5018 --2.98499 1.53337 6.53782 --1.6931 0.964759 4.6189 --1.61501 0.930325 4.62643 --1.59511 0.922449 4.73433 --1.4792 0.871143 4.67036 --1.87163 1.04326 5.57782 --1.84196 1.03 5.71025 --2.04978 1.12141 6.34842 --1.64482 0.944266 5.69815 --1.4194 0.844387 5.3954 --1.56989 0.910579 5.95907 --1.46454 0.864831 5.93354 --1.16086 0.730663 5.37909 --0.520615 0.449415 3.82839 --0.997882 0.659384 5.37409 --0.92466 0.626791 5.39257 --0.630155 0.497794 4.68884 --0.546467 0.460427 4.62399 --0.436733 0.412134 4.45168 --0.406116 0.398884 4.56538 --0.316711 0.359491 4.44653 --0.318779 0.360373 4.72414 --0.382252 0.388015 5.34443 --0.33784 0.368881 5.49779 --0.219603 0.316715 5.23771 --0.101508 0.264969 4.92535 --0.0257057 0.23094 4.83735 -0.0415293 0.201814 4.79722 -0.079286 0.184721 5.02391 -0.14095 0.158265 5.07109 -0.197926 0.133502 5.187 -0.269815 0.101384 5.09232 -0.259139 0.106283 6.99429 -0.363415 0.0597094 6.64812 -0.459799 0.0176814 5.93982 --2.48756 1.42103 -0.910196 --2.57319 1.4615 -0.886133 --2.70562 1.5246 -0.887527 --2.82342 1.58047 -0.875238 --2.96656 1.64845 -0.872101 --3.10191 1.71241 -0.859702 --3.24599 1.78094 -0.846774 --3.40763 1.8574 -0.836632 --3.53605 1.91885 -0.80583 --3.69962 1.99597 -0.784895 --3.8621 2.07431 -0.75832 --4.03436 2.15639 -0.729066 --4.28462 2.27519 -0.721567 --4.50071 2.37792 -0.693161 --4.79577 2.51768 -0.681713 --5.10051 2.66246 -0.661943 --5.4237 2.81668 -0.635816 --5.7742 2.98286 -0.604303 --6.52322 3.33861 -0.653373 --7.31108 3.7138 -0.681535 --8.03848 4.05935 -0.667558 --9.04441 4.53804 -0.674548 --10.5988 5.27625 -0.7279 --13.9329 6.86119 -0.963121 --16.5836 8.12136 -0.989296 --17.0803 8.35811 -0.704246 --17.0861 8.36038 -0.362901 --24.4649 11.8681 -0.450431 --24.7458 12.0018 0.0220944 --25.0189 12.1316 0.504981 --25.5374 12.378 0.998145 --25.6878 12.4493 1.50428 --25.5674 12.3928 2.00594 --52.6915 25.2867 6.14873 --4.87915 2.55787 1.94286 --4.81949 2.52891 2.03803 --4.79288 2.51626 2.13872 --4.81005 2.52479 2.24914 --4.84185 2.53949 2.36505 --4.88143 2.55788 2.48504 --4.90049 2.56783 2.60161 --12.7831 6.31448 5.21625 --12.3085 6.08909 5.33487 --11.6287 5.76653 5.36231 --11.8575 5.87486 5.71001 --11.0678 5.49973 5.66086 --11.6594 5.78027 6.16671 --11.5671 5.737 6.39716 --11.7802 5.83763 6.77017 --10.7136 5.33079 6.52667 --8.64388 4.34718 5.71987 --9.50943 4.75847 6.40429 --5.89829 3.04181 4.60869 --5.84045 3.01434 4.73174 --5.85942 3.02296 4.90224 --4.23294 2.25017 4.0246 --4.65627 2.45135 4.4297 --6.67702 3.41202 5.96472 --4.32506 2.29387 4.46896 --4.19546 2.2317 4.50577 --4.13964 2.20573 4.59592 --3.84099 2.06411 4.49103 --3.8639 2.07494 4.64062 --3.98391 2.13211 4.87823 --3.8524 2.06915 4.90145 --4.3365 2.2993 5.49263 --4.23793 2.25252 5.55921 --4.35976 2.31015 5.84407 --3.39147 1.84944 5.01668 --3.34053 1.82568 5.10515 --3.21779 1.7676 5.11506 --2.98249 1.656 4.99206 --2.88796 1.61066 5.02215 --2.82444 1.58096 5.087 --2.75898 1.55007 5.15059 --2.71688 1.52908 5.24358 --2.6776 1.51063 5.34397 --3.39262 1.85079 6.51577 --3.31639 1.81456 6.6061 --1.544 0.97181 4.11452 --1.438 0.921745 4.06347 --2.04611 1.21048 5.17816 --1.97006 1.17436 5.20991 --1.89889 1.13988 5.24852 --1.51003 0.955866 4.70282 --1.50089 0.950918 4.83637 --2.8505 1.59257 7.6905 --2.78286 1.56049 7.83374 --1.51769 0.959067 5.38355 --1.4407 0.922328 5.40391 --1.57732 0.987826 5.93007 --1.46933 0.936498 5.89639 --1.19812 0.807539 5.4275 --0.522483 0.48623 3.79995 --1.00849 0.717024 5.35039 --0.405773 0.430717 3.75321 --0.658846 0.551487 4.72522 --0.560835 0.504926 4.61387 --0.469647 0.461132 4.50954 --0.416965 0.436263 4.53737 --0.381599 0.419237 4.64142 --0.269323 0.366113 4.41537 --0.246463 0.354656 4.57589 --0.319314 0.389277 5.26468 --0.185075 0.325783 4.89703 --0.156165 0.31187 5.11641 --0.0460646 0.260019 4.81241 -0.00382 0.235361 4.90163 -0.0718674 0.203658 4.85101 -0.134164 0.173706 4.8488 -0.18334 0.150904 4.9947 -0.241066 0.123067 5.09003 -0.21946 0.133673 6.91189 -0.328863 0.0813961 6.39665 -0.405499 0.0450544 6.92913 --2.36842 1.46858 -0.898359 --2.45973 1.51507 -0.881166 --2.57433 1.57444 -0.875377 --2.70551 1.64157 -0.874875 --2.82989 1.70473 -0.865308 --2.98732 1.78529 -0.86861 --3.10481 1.84569 -0.845633 --3.23881 1.91492 -0.826494 --3.39037 1.99208 -0.810341 --3.5419 2.06951 -0.788795 --3.6691 2.13422 -0.751253 --3.86338 2.23398 -0.736051 --4.05861 2.33415 -0.713755 --4.30542 2.45996 -0.702318 --4.46752 2.5434 -0.653269 --4.86112 2.74486 -0.670589 --5.16229 2.89872 -0.645381 --5.54114 3.09389 -0.629842 --6.0873 3.37308 -0.641043 --6.9319 3.80538 -0.699106 --7.70927 4.20387 -0.709959 --8.52552 4.62092 -0.697258 --9.85298 5.30086 -0.738925 --12.9059 6.86334 -0.983584 --15.7377 8.31354 -1.07949 --16.0594 8.47863 -0.792487 --16.0235 8.45978 -0.461972 --23.2748 12.1732 -0.635228 --23.4483 12.2616 -0.176251 --23.8104 12.4468 0.283227 --23.7554 12.419 0.760544 --34.3559 17.8466 1.33931 --34.4073 17.8727 2.02449 --34.5111 17.9253 2.71488 --34.577 17.9587 3.4078 --34.6136 17.9784 4.10221 --34.6484 17.9961 4.79972 --34.6725 18.0083 5.49963 --34.7393 18.0426 6.20943 --4.73855 2.68263 1.87907 --4.68868 2.6573 1.97502 --4.69906 2.66225 2.08208 --4.71623 2.67075 2.1919 --4.76637 2.69676 2.31127 --12.7342 6.77584 4.56842 --12.7372 6.77772 4.84488 --12.6665 6.74105 5.10117 --11.9521 6.37599 5.1429 --12.0474 6.42477 5.44346 --12.1961 6.5002 5.77136 --12.3378 6.57355 6.10624 --10.8648 5.81901 5.77242 --14.3001 7.57823 7.54821 --14.5087 7.68464 7.98279 --12.2188 6.51196 7.2115 --11.3583 6.0718 7.07021 --5.75124 3.20057 4.34894 --5.65865 3.15279 4.44864 --4.22162 2.41793 3.76084 --5.71974 3.18462 4.79288 --6.88402 3.78011 5.69223 --5.89718 3.27536 5.23234 --5.86851 3.26106 5.38326 --6.00959 3.33238 5.65785 --4.10302 2.35635 4.42166 --5.78739 3.21936 5.85359 --4.00817 2.3079 4.6116 --3.77899 2.19102 4.55667 --3.56827 2.0835 4.50611 --3.48557 2.04008 4.5605 --3.41536 2.00496 4.62528 --3.35198 1.9725 4.69508 --3.28085 1.93616 4.7567 --3.1952 1.89218 4.8033 --3.10375 1.84538 4.84069 --3.02389 1.80488 4.88975 --2.95087 1.76705 4.94393 --2.88845 1.73552 5.01098 --2.83768 1.70937 5.09156 --2.79756 1.68859 5.18635 --7.87215 4.28619 12.01 --3.53202 2.06474 6.49356 --3.40179 1.99747 6.50929 --1.61933 1.08507 4.10188 --1.54935 1.04918 4.11073 --7.47674 4.08363 13.5611 --1.40646 0.976568 4.11503 --1.74057 1.14726 4.80233 --1.70532 1.12932 4.8878 --1.49134 1.01927 4.64911 --1.5517 1.05101 4.91154 --1.47787 1.01212 4.92512 --1.39911 0.972405 4.9282 --2.55502 1.56372 7.59027 --1.44239 0.995268 5.37599 --1.47465 1.01074 5.64816 --1.47877 1.01335 5.87724 --1.29969 0.921997 5.64936 --1.11881 0.828886 5.38831 --1.02755 0.782559 5.35418 --0.956561 0.746158 5.37406 --0.902893 0.71856 5.44909 --0.571271 0.548706 4.59406 --0.528322 0.526427 4.66217 --0.433446 0.47841 4.5379 --0.371325 0.44602 4.5268 --0.291905 0.40566 4.43689 --0.23649 0.377497 4.44214 --0.388697 0.455349 5.50065 --0.188716 0.353377 4.80198 --0.212401 0.365327 5.31637 --0.0967847 0.305721 5.00431 --0.0174747 0.264998 4.88678 -0.0493976 0.230394 4.83691 -0.0653642 0.222475 5.28225 -0.144647 0.182568 5.14075 -0.208751 0.148921 5.14712 -0.276652 0.115013 5.09231 -0.275837 0.114433 6.73457 -0.367827 0.0679788 6.61805 -0.460979 0.0201124 5.94981 --2.26514 1.51966 -0.895509 --2.36211 1.57217 -0.885185 --2.46677 1.63009 -0.876383 --2.57241 1.68824 -0.863981 --2.70234 1.7594 -0.861483 --2.84001 1.83505 -0.858858 --2.98736 1.91634 -0.85545 --3.10366 1.97977 -0.830528 --3.2354 2.05298 -0.809296 --3.38471 2.13414 -0.790851 --3.53393 2.21656 -0.766962 --3.69187 2.30361 -0.741146 --3.88383 2.40841 -0.722502 --4.12619 2.54177 -0.71527 --4.36949 2.67564 -0.698945 --4.66423 2.83733 -0.689982 --4.96859 3.00504 -0.672247 --5.1895 3.12636 -0.618796 --5.62288 3.36446 -0.613248 --6.43564 3.81034 -0.682389 --7.35493 4.31625 -0.742621 --8.09662 4.72378 -0.730111 --9.18651 5.32219 -0.751099 --10.384 5.97956 -0.745897 --14.6629 8.3306 -1.12511 --16.1576 9.15138 -0.99858 --22.1451 12.4414 -0.808121 --22.2387 12.4933 -0.361152 --22.5545 12.6657 0.0800455 --22.4415 12.6046 0.541629 --33.3575 18.6018 0.997825 --33.308 18.5741 1.67122 --22.9128 12.8638 2.39846 --32.9421 18.3733 3.66601 --5.30684 3.19054 1.57918 --5.20958 3.13672 1.68426 --4.65872 2.83451 1.7223 --4.62058 2.81403 1.82079 --4.59023 2.79704 1.91946 --4.57536 2.78914 2.02069 --4.60221 2.80328 2.13119 --12.5823 7.18829 4.17187 --12.4982 7.14152 4.42287 --12.4605 7.12123 4.68596 --12.4277 7.10235 4.95131 --12.4753 7.12879 5.24396 --6.32325 3.74865 3.37947 --6.33533 3.75603 3.53347 --6.37076 3.77439 3.69848 --6.40997 3.79627 3.86906 --6.46373 3.82553 4.04927 --6.50481 3.84896 4.22859 --6.58373 3.89183 4.43011 --5.56192 3.33016 4.07855 --5.50531 3.29941 4.19456 --4.09267 2.52331 3.5554 --4.00616 2.47611 3.61917 --3.96514 2.454 3.70852 --3.96193 2.45139 3.82127 --3.92575 2.43178 3.91462 --3.81993 2.37354 3.9612 --3.75958 2.34051 4.03615 --3.69053 2.30261 4.10407 --3.62726 2.26825 4.17586 --3.56406 2.23282 4.24611 --3.51335 2.20566 4.32653 --3.45495 2.17369 4.39994 --3.39561 2.14058 4.47199 --3.34205 2.11109 4.54911 --3.29432 2.08421 4.63144 --3.23784 2.05344 4.7065 --3.17361 2.01879 4.77359 --3.10267 1.97932 4.83257 --3.05587 1.95364 4.91765 --3.13176 1.99552 5.14334 --3.11101 1.98428 5.26541 --3.08063 1.9671 5.38052 --3.04825 1.94981 5.49571 --8.14365 4.74843 12.3426 --7.87778 4.60335 12.3904 --7.66415 4.48561 12.5011 --6.79125 4.00619 11.6455 --6.92806 4.08132 12.2441 --1.52045 1.10962 4.17115 --2.01401 1.38097 5.09556 --1.7502 1.23625 4.80511 --1.64849 1.18041 4.7739 --1.53522 1.11845 4.71428 --1.41427 1.05199 4.63421 --1.47263 1.08362 4.89693 --1.4596 1.0765 5.03187 --1.44652 1.06984 5.17619 --1.5095 1.10476 5.49936 --1.37127 1.02813 5.37693 --1.37164 1.02805 5.57669 --1.3046 0.99117 5.62245 --1.22694 0.949194 5.63916 --2.09136 1.42329 8.31533 --0.966993 0.806255 5.35965 --0.957639 0.80094 5.56681 --0.838767 0.736019 5.43431 --0.675841 0.64673 5.12743 --0.461308 0.528627 4.58606 --0.386866 0.487129 4.52777 --0.33537 0.459271 4.55456 --0.244699 0.409282 4.40568 --0.204717 0.387411 4.4784 --0.225721 0.399253 4.89296 --0.139885 0.351845 4.74979 --0.0959786 0.327119 4.85056 --0.0519546 0.303334 4.97041 --0.0183017 0.284563 5.19871 -0.0909804 0.224622 4.79148 -0.124807 0.206206 5.06752 -0.195286 0.167758 4.96485 -0.247088 0.138739 5.10994 -0.310121 0.104057 5.11437 -0.337954 0.0889318 6.27678 -0.420142 0.0440012 6.19919 --2.08088 1.51897 -0.907526 --2.16015 1.56567 -0.891618 --2.24818 1.6168 -0.877978 --2.36517 1.6869 -0.881214 --2.46192 1.74266 -0.865846 --2.58086 1.81328 -0.860986 --2.69299 1.8799 -0.84746 --2.82941 1.95959 -0.842739 --2.96674 2.04058 -0.833171 --3.09632 2.11654 -0.814491 --3.23459 2.19808 -0.795032 --3.38158 2.28424 -0.774045 --3.55271 2.38563 -0.758266 --3.70064 2.4724 -0.726089 --3.91344 2.59721 -0.71371 --4.16106 2.74298 -0.705255 --4.30986 2.83078 -0.6533 --4.59134 2.99597 -0.638484 --4.72366 3.07368 -0.56771 --4.78814 3.11236 -0.473401 --4.91848 3.18936 -0.394194 --4.91331 3.18579 -0.278307 --7.69503 4.82228 -0.76268 --8.57817 5.34302 -0.763291 --9.6607 5.97918 -0.762458 --12.6844 7.75919 -1.01482 --14.5369 8.84935 -0.98878 --14.4962 8.82531 -0.676361 --14.6482 8.91421 -0.384143 --21.5679 12.9864 -0.119382 --21.6681 13.0457 0.325065 --22.0537 13.2726 0.770209 --4.97308 3.22056 1.05509 --4.94566 3.20431 1.16506 --4.84765 3.14646 1.27054 --4.63643 3.023 1.36413 --4.5781 2.9883 1.4634 --4.54488 2.96919 1.56326 --4.51846 2.95349 1.663 --4.51619 2.95245 1.76586 --4.48691 2.93451 1.86439 --4.45564 2.91641 1.96191 --4.46596 2.92228 2.06761 --4.33125 2.84352 2.14005 --4.1531 2.73827 2.19661 --4.1344 2.72778 2.29062 --4.13995 2.73013 2.39177 --4.1425 2.73233 2.4935 --4.12772 2.7232 2.59018 --4.10321 2.70931 2.68363 --4.0855 2.69898 2.77975 --4.05813 2.68287 2.87228 --4.04527 2.67497 2.97132 --4.02269 2.6623 3.06672 --3.99152 2.64289 3.158 --3.96607 2.628 3.25259 --3.9474 2.61672 3.35105 --3.90359 2.59123 3.43634 --3.881 2.57867 3.53404 --3.83532 2.55099 3.61783 --3.78766 2.52313 3.70041 --3.74578 2.49881 3.78675 --3.69619 2.46972 3.86728 --3.64467 2.43946 3.94655 --3.59316 2.40913 4.02463 --3.5542 2.38608 4.11263 --3.51331 2.36186 4.19988 --3.47143 2.33755 4.28642 --3.43538 2.31587 4.37828 --3.40511 2.29782 4.47571 --3.37867 2.2823 4.57914 --3.36477 2.2742 4.69529 --3.32769 2.25271 4.79244 --3.25685 2.21148 4.85612 --3.16679 2.15796 4.89785 --3.16444 2.15653 5.03347 --3.10328 2.12039 5.10707 --3.05271 2.09054 5.19363 --3.01274 2.06703 5.29397 --2.96501 2.03966 5.38654 --2.93276 2.02033 5.50093 --2.89857 1.99988 5.61537 --8.08004 5.04882 13.0752 --7.9564 4.97594 13.3332 --1.55624 1.21066 4.22326 --1.44712 1.1461 4.1668 --3.33301 2.25567 7.46903 --1.69848 1.29366 4.85242 --1.52387 1.19156 4.68547 --2.89588 1.99856 7.42865 --1.42973 1.13537 4.7996 --1.28695 1.0518 4.66407 --1.39605 1.11575 5.05117 --1.46661 1.1575 5.38165 --1.41611 1.12708 5.45663 --1.32617 1.07471 5.44054 --1.30534 1.06308 5.59507 --1.24999 1.03024 5.66764 --2.18925 1.58228 8.52936 --1.07023 0.92393 5.62402 --0.900803 0.82465 5.34602 --0.765975 0.745455 5.14754 --0.671485 0.689193 5.05872 --0.465053 0.568071 4.54769 --0.410792 0.536651 4.56673 --0.354662 0.503581 4.57502 --0.311913 0.478159 4.64019 --0.230988 0.430661 4.52959 --0.201562 0.412835 4.67086 --0.208133 0.417398 5.03723 --0.122481 0.36697 4.89361 --0.0435869 0.319831 4.76759 --0.0441035 0.320431 5.22303 -0.0470791 0.267008 4.9855 -0.0836003 0.244984 5.23257 -0.141911 0.211205 5.30997 -0.225195 0.161536 5.03747 -0.279807 0.129824 5.17216 -0.296154 0.120394 6.39483 -0.372305 0.0752281 6.62807 -0.46216 0.0225435 5.95979 --1.97158 1.55309 -0.895466 --2.05646 1.6068 -0.886678 --2.1491 1.66488 -0.88006 --2.23494 1.71895 -0.865176 --2.34396 1.78789 -0.861797 --2.44525 1.85178 -0.849905 --2.5707 1.93067 -0.847916 --2.69619 2.00879 -0.841283 --2.83029 2.09347 -0.834319 --2.96537 2.17846 -0.822359 --3.08493 2.25411 -0.797619 --3.23641 2.34923 -0.783353 --3.39657 2.44999 -0.76701 --3.54997 2.5458 -0.741153 --3.71105 2.64722 -0.712721 --3.94458 2.79406 -0.706008 --4.18005 2.94148 -0.690199 --4.44056 3.10549 -0.673453 --4.52134 3.15667 -0.589473 --4.52009 3.15509 -0.478466 --4.51583 3.1533 -0.368068 --4.51841 3.1548 -0.260293 --4.52004 3.15523 -0.152771 --4.52838 3.16097 -0.0474724 --4.53383 3.16453 0.0579158 --4.5306 3.16262 0.164622 --4.53419 3.16404 0.269703 --4.54347 3.17077 0.373557 --4.55287 3.1755 0.47761 --4.55059 3.17456 0.582572 --4.55606 3.17807 0.686761 --4.5519 3.17499 0.791316 --4.55444 3.17731 0.895446 --4.52131 3.15641 0.9997 --4.49493 3.13988 1.10268 --4.45021 3.11211 1.2038 --4.41229 3.08771 1.30379 --4.39075 3.07431 1.40354 --4.38368 3.06987 1.50434 --4.37568 3.06435 1.60488 --4.3406 3.04297 1.70164 --4.29592 3.01486 1.79577 --4.23291 2.97537 1.88513 --4.17764 2.94033 1.97383 --4.12912 2.90971 2.06255 --4.07194 2.87336 2.14739 --4.03785 2.85268 2.23691 --4.01055 2.83549 2.3278 --4.0151 2.83775 2.42834 --4.00126 2.82963 2.52397 --3.98555 2.81938 2.6194 --3.9775 2.81476 2.7178 --3.96758 2.80802 2.81639 --3.95565 2.80117 2.91498 --3.93513 2.78761 3.01014 --3.92034 2.77858 3.10871 --3.90361 2.76842 3.20733 --3.88594 2.75721 3.3059 --3.86634 2.74487 3.4044 --3.8458 2.73147 3.50276 --3.82332 2.71694 3.60106 --3.78342 2.69286 3.68971 --3.73588 2.66302 3.77279 --3.69411 2.63673 3.85963 --3.65913 2.61407 3.95084 --3.65006 2.60905 4.06257 --3.61221 2.58418 4.15318 --4.54761 3.17226 5.02024 --3.82129 2.71598 4.57309 --3.72652 2.65673 4.62629 --3.63178 2.59734 4.6768 --3.4572 2.4872 4.65061 --4.4951 3.13946 5.77617 --4.50128 3.14373 5.95551 --4.47187 3.12525 6.10373 --4.47135 3.12423 6.2858 --4.46689 3.12205 6.4692 --4.47691 3.12786 6.67493 --4.4878 3.13518 6.8898 --4.45253 3.11325 7.05647 --4.42015 3.09287 7.23069 --2.90557 2.14033 5.46601 --2.82816 2.09222 5.52047 --2.78251 2.06326 5.61893 --2.73969 2.03685 5.7248 --4.33291 3.03766 8.3045 --1.51787 1.26851 4.1624 --1.54057 1.28257 4.31683 --3.38078 2.43885 7.54469 --3.20337 2.32776 7.4828 --1.35412 1.16569 4.37131 --1.34028 1.15706 4.47678 --1.47131 1.23889 4.87425 --1.27037 1.1128 4.61981 --1.24115 1.09437 4.70824 --1.28958 1.1245 4.97308 --1.65699 1.35613 5.9983 --1.36032 1.16914 5.50277 --1.32517 1.14786 5.62195 --1.14647 1.0351 5.36659 --1.11808 1.01701 5.50117 --1.01984 0.954924 5.44105 --1.01817 0.954054 5.66776 --0.948597 0.910246 5.69833 --0.696585 0.752111 5.10343 --0.625166 0.707983 5.08945 --0.413597 0.575053 4.5287 --0.350019 0.534623 4.49887 --0.313079 0.511521 4.58348 --0.262829 0.479681 4.60937 --0.187838 0.432465 4.51742 --0.260963 0.478092 5.2255 --0.165047 0.417666 5.03445 --0.0786448 0.364164 4.87025 --0.0471085 0.344553 5.07908 -0.0117897 0.306913 5.0997 -0.102659 0.250473 4.82127 -0.14274 0.224229 5.00795 -0.207232 0.184102 4.94495 -0.253233 0.155396 5.14983 -0.316836 0.115687 5.11436 -0.344362 0.0975895 6.23676 -0.420758 0.0494421 6.28923 --1.81344 1.55161 -0.914591 --1.88267 1.59871 -0.898765 --1.95194 1.64491 -0.880693 --2.04242 1.70578 -0.875928 --2.13387 1.76688 -0.867864 --2.2465 1.84272 -0.87141 --2.3389 1.90422 -0.856252 --2.44671 1.97638 -0.847131 --2.5622 2.054 -0.838533 --2.67866 2.13189 -0.825536 --2.81052 2.22055 -0.81658 --2.96552 2.3243 -0.814533 --3.09831 2.41354 -0.794987 --3.232 2.50408 -0.770393 --3.3899 2.60886 -0.751258 --3.5477 2.71493 -0.725981 --3.76137 2.85869 -0.716934 --3.96735 2.99654 -0.69623 --4.19061 3.14658 -0.673118 --4.22981 3.17265 -0.579645 --4.26801 3.19872 -0.485077 --4.28123 3.20663 -0.382259 --4.29245 3.21443 -0.279447 --4.30173 3.2211 -0.176592 --4.31778 3.23211 -0.0755105 --4.33288 3.24208 0.0259168 --4.32966 3.24006 0.130525 --4.3332 3.24238 0.23346 --4.34349 3.24906 0.33522 --4.35285 3.25469 0.437125 --4.35152 3.25471 0.539943 --4.34162 3.24721 0.643179 --4.33742 3.24501 0.745388 --4.33235 3.24075 0.847392 --4.32528 3.23634 0.948991 --4.31727 3.23086 1.05034 --4.30733 3.22424 1.15123 --4.29646 3.21655 1.25186 --4.29127 3.21422 1.35257 --4.27753 3.20431 1.4524 --4.25411 3.18873 1.55074 --4.23644 3.17752 1.64941 --4.20149 3.15408 1.74496 --4.17428 3.13513 1.84075 --4.15282 3.12057 1.93715 --4.11402 3.09472 2.0293 --4.08196 3.07332 2.12217 --4.05663 3.0564 2.21606 --4.05538 3.05529 2.31633 --4.05119 3.05301 2.41684 --4.06245 3.05996 2.5229 --4.08711 3.07708 2.63555 --4.45027 3.32076 2.87908 --4.58069 3.40816 3.04619 --4.56593 3.39785 3.15934 --4.55689 3.39207 3.27602 --4.54592 3.38517 3.39283 --4.52634 3.37157 3.50622 --4.51155 3.36145 3.62337 --4.5112 3.36066 3.74907 --4.49248 3.34933 3.86685 --4.48059 3.34065 3.98916 --4.46577 3.3308 4.1118 --4.44901 3.31986 4.23479 --4.43709 3.31146 4.36289 --4.43088 3.3077 4.4965 --4.4285 3.30647 4.63622 --4.41754 3.29849 4.77141 --4.41034 3.29405 4.91286 --4.37343 3.26867 5.03243 --3.65856 2.7893 4.57097 --4.36771 3.26435 5.33588 --4.35665 3.25711 5.48616 --4.34265 3.24873 5.63737 --4.32584 3.23721 5.78932 --4.33208 3.24045 5.96792 --4.31521 3.22934 6.12826 --4.30117 3.22079 6.2962 --4.30154 3.22121 6.48582 --4.29909 3.21853 6.67697 --4.29753 3.21733 6.87677 --4.27385 3.20176 7.05651 --4.25883 3.1915 7.25176 --4.23892 3.17899 7.4481 --1.81395 1.55214 4.26197 --2.68575 2.13733 5.65263 --2.62871 2.09883 5.73448 --2.57933 2.06555 5.83123 --4.03108 3.03878 8.37097 --1.68079 1.46254 4.67958 --1.45721 1.31316 4.42815 --1.36586 1.25177 4.39377 --1.31184 1.21591 4.42404 --1.41385 1.2839 4.75993 --1.22871 1.16011 4.53251 --1.23021 1.16058 4.68148 --1.33108 1.22861 5.05992 --1.67089 1.45636 6.02028 --1.58326 1.39735 6.02935 --1.48127 1.32955 6.00013 --1.22559 1.15776 5.55877 --1.09317 1.0692 5.41094 --1.16886 1.11968 5.85026 --1.06223 1.0482 5.77293 --0.768815 0.850788 5.08379 --0.73377 0.828101 5.19463 --0.662585 0.780039 5.18195 --0.412529 0.611739 4.48103 --0.375702 0.587216 4.55711 --0.310311 0.544168 4.51717 --0.267805 0.515257 4.57241 --0.388319 0.596411 5.45334 --0.317186 0.547936 5.43226 --0.159947 0.442774 4.90002 --0.103091 0.404891 4.91325 --0.0378049 0.360492 4.86617 --0.00258191 0.337162 5.04503 -0.0523806 0.299703 5.08468 -0.114017 0.259318 5.07358 -0.17365 0.218481 5.07112 -0.237956 0.175837 4.99763 -0.228575 0.182441 6.33001 -0.30649 0.12984 6.3149 -0.377592 0.0824517 6.57802 -0.46328 0.0244819 5.95979 --1.72022 1.58532 -0.910122 --1.7874 1.63322 -0.89575 --1.86228 1.68645 -0.884596 --1.94387 1.74496 -0.876066 --2.03321 1.80785 -0.869705 --2.12247 1.8719 -0.860099 --2.22614 1.94652 -0.856932 --2.33178 2.02146 -0.849864 --2.42969 2.09134 -0.834284 --2.56506 2.18866 -0.836947 --2.69475 2.28008 -0.830144 --2.80893 2.3622 -0.810161 --2.95392 2.46568 -0.801454 --3.07674 2.55361 -0.775798 --3.21595 2.65245 -0.75258 --3.38588 2.77379 -0.737692 --3.54806 2.89015 -0.712694 --3.78046 3.05582 -0.709119 --3.9676 3.19002 -0.678539 --4.05383 3.25106 -0.604524 --4.07564 3.26627 -0.506618 --4.10414 3.28681 -0.410636 --4.13941 3.31169 -0.316227 --4.16603 3.33018 -0.218654 --4.18201 3.34215 -0.118421 --4.20569 3.35952 -0.0196096 --4.21117 3.36294 0.082982 --4.22334 3.37172 0.18415 --4.22588 3.37396 0.286781 --4.21986 3.36871 0.39033 --4.21953 3.36875 0.492452 --4.20958 3.36222 0.595139 --4.20638 3.36005 0.696652 --4.21762 3.36774 0.797266 --4.21255 3.36345 0.898672 --4.21316 3.36449 0.999649 --4.21191 3.36342 1.10072 --4.20965 3.36229 1.20178 --4.19016 3.34802 1.30169 --4.18503 3.34468 1.40215 --4.16267 3.32817 1.50084 --4.13833 3.3115 1.59864 --4.15342 3.32155 1.70166 --4.18286 3.34267 1.80833 --4.23531 3.38053 1.92103 --4.29354 3.42196 2.03809 --4.34214 3.45683 2.15592 --4.36485 3.4729 2.27001 --4.37794 3.48232 2.38307 --4.38049 3.48401 2.49474 --4.3907 3.49133 2.60948 --4.39037 3.49091 2.72244 --4.39576 3.49501 2.83871 --4.39255 3.49245 2.95266 --4.3874 3.4888 3.06705 --4.38031 3.48404 3.18168 --4.37134 3.47718 3.29681 --4.37575 3.48054 3.41962 --4.37057 3.47716 3.5394 --4.37016 3.47729 3.66375 --4.36888 3.47541 3.78888 --4.37231 3.47808 3.91923 --4.39588 3.49473 4.06404 --4.39449 3.49422 4.19672 --4.40558 3.50201 4.33998 --4.42716 3.51802 4.49462 --4.46128 3.54142 4.66158 --5.78202 4.48431 5.8218 --5.67126 4.40542 5.92303 --5.55953 4.3263 6.02106 --10.3021 7.71078 10.2911 --6.11198 4.71936 6.90088 --4.38182 3.48496 5.51923 --4.36216 3.47102 5.66628 --4.33292 3.45019 5.80759 --4.3075 3.43194 5.95552 --4.29163 3.42094 6.11686 --4.33993 3.45464 6.35269 --4.32211 3.44201 6.52381 --4.48321 3.55725 6.91111 --4.41558 3.50933 7.03831 --4.32309 3.44338 7.13561 --1.58792 1.48996 3.74971 --1.59139 1.49332 3.85349 --1.58822 1.49094 3.95071 --1.47319 1.40864 3.88778 --2.6094 2.22017 5.71696 --2.52192 2.15742 5.75145 --1.56297 1.47274 4.36206 --1.53871 1.4554 4.44627 --6.28854 4.84612 12.9098 --1.39365 1.35247 4.44865 --1.37611 1.33927 4.54741 --1.32032 1.29933 4.57857 --1.19387 1.20971 4.46277 --1.17347 1.19421 4.55922 --1.12246 1.15778 4.59455 --1.36896 1.33398 5.31748 --1.38835 1.34885 5.55285 --1.48782 1.41952 6.00604 --1.03083 1.09278 5.03292 --1.08927 1.13487 5.38485 --0.953473 1.03756 5.20658 --0.7968 0.925596 4.9404 --0.859877 0.970846 5.35037 --0.717556 0.868872 5.10632 --0.650304 0.821535 5.10343 --0.451177 0.678913 4.5949 --0.402085 0.64431 4.62434 --0.354937 0.610251 4.66237 --0.267034 0.547511 4.51594 --0.384499 0.631493 5.35657 --0.221847 0.515697 4.83893 --0.202974 0.501436 5.05929 --0.112295 0.437279 4.86755 --0.0688108 0.406089 4.95883 --0.00745917 0.361881 4.931 -0.0482594 0.321911 4.94124 -0.113341 0.275876 4.86101 -0.15886 0.243837 4.97805 -0.217428 0.202528 4.96481 -0.261252 0.170443 5.17978 -0.258994 0.172552 6.63218 -0.350956 0.107221 6.23675 -0.425738 0.0536931 6.19918 --1.63295 1.62015 -0.910576 --1.69902 1.66992 -0.897605 --1.77752 1.73005 -0.893278 --1.85127 1.78528 -0.880629 --1.93067 1.84675 -0.870655 --2.01111 1.90742 -0.857732 --2.12033 1.99006 -0.861535 --2.22281 2.06772 -0.856323 --2.31848 2.14139 -0.842546 --2.42191 2.2195 -0.82954 --2.55503 2.32081 -0.829911 --2.67376 2.4109 -0.816501 --2.81552 2.51806 -0.810499 --2.94384 2.61504 -0.791162 --3.07876 2.7185 -0.770402 --3.23006 2.83291 -0.751282 --3.38133 2.94762 -0.72597 --3.59393 3.10921 -0.720013 --3.81418 3.27657 -0.708286 --3.99029 3.41047 -0.67025 --4.08972 3.48524 -0.598332 --4.11809 3.50789 -0.500052 --4.13124 3.51685 -0.396285 --4.12607 3.51389 -0.288137 --4.13535 3.52061 -0.184483 --4.12831 3.51548 -0.0773414 --4.13472 3.51999 0.025903 --4.1315 3.51798 0.130611 --4.12741 3.51388 0.234817 --4.12895 3.51607 0.337445 --4.12962 3.51619 0.43997 --4.12067 3.50974 0.543059 --4.11846 3.50765 0.644974 --4.12295 3.51095 0.746264 --4.1092 3.50114 0.848089 --4.11081 3.50224 0.949169 --4.11149 3.50229 1.0502 --4.11785 3.50771 1.15149 --4.08312 3.48046 1.25094 --4.03872 3.44751 1.34831 --3.98577 3.40689 1.443 --3.95482 3.38368 1.53837 --3.9708 3.39568 1.63931 --4.03277 3.44199 1.74894 --4.12335 3.51152 1.86732 --4.36233 3.6931 2.02134 --4.36295 3.69359 2.13135 --4.35396 3.6874 2.23974 --4.3441 3.67915 2.34812 --4.3399 3.67637 2.45866 --4.33484 3.67154 2.56951 --4.33543 3.67221 2.68322 --4.34176 3.67741 2.80025 --4.33854 3.67489 2.91509 --4.34871 3.68256 3.03673 --4.35027 3.68357 3.15603 --4.36428 3.69373 3.28298 --4.36868 3.69718 3.40759 --4.42276 3.7391 3.55974 --6.44567 5.27564 4.79153 --6.39922 5.24045 4.94737 --6.1922 5.08249 5.00755 --5.33033 4.42785 4.64945 --6.42333 5.25856 5.52454 --5.58264 4.61923 5.14609 --5.61358 4.64391 5.34271 --5.594 4.6278 5.50648 --5.63159 4.65762 5.7177 --5.80017 4.7851 6.03936 --9.9 7.899 9.64247 --6.20783 5.09469 6.78814 --5.9063 4.86529 6.73682 --5.98589 4.92555 7.025 --5.4962 4.55463 6.77665 --5.3151 4.41683 6.80756 --2.02623 1.91893 3.61401 --4.33912 3.67514 6.18872 --4.64782 3.90967 6.71802 --4.52022 3.81356 6.77584 --4.4805 3.78287 6.9332 --4.35105 3.68436 6.98532 --5.13273 4.27823 8.19618 --5.19588 4.32603 8.53613 --1.56109 1.56523 3.82363 --1.55315 1.55918 3.91329 --1.49655 1.51671 3.93496 --1.48574 1.50848 4.02461 --1.63221 1.61951 4.36506 --2.44288 2.23507 5.81542 --1.57521 1.57666 4.52071 --1.47103 1.49653 4.46795 --1.44865 1.48069 4.56001 --1.36829 1.41886 4.54384 --1.34504 1.40092 4.63489 --1.22271 1.30906 4.52973 --1.14145 1.24641 4.49808 --1.14007 1.24526 4.638 --1.1196 1.23021 4.74364 --1.31306 1.37748 5.37276 --1.50447 1.52287 6.04721 --1.02969 1.16155 5.02542 --0.976894 1.12133 5.06743 --0.942063 1.09591 5.16328 --0.847488 1.02404 5.08344 --0.743481 0.944586 4.96347 --0.719118 0.926491 5.09317 --0.683375 0.899282 5.19461 --0.574712 0.816341 5.03023 --0.619405 0.850121 5.45376 --0.349057 0.644686 4.59546 --0.411582 0.692798 5.12423 --0.402255 0.684686 5.37598 --0.310661 0.616196 5.23942 --0.279525 0.591839 5.41284 --0.126008 0.47589 4.86083 --0.0751408 0.437336 4.89365 --0.016781 0.392814 4.87606 -0.00601514 0.37466 5.14395 -0.0821676 0.317558 4.97558 -0.137755 0.275505 4.98412 -0.193334 0.233394 4.99147 -0.23885 0.198754 5.1571 -0.2404 0.196786 6.31011 -0.316826 0.139286 6.23497 -0.387998 0.0854508 6.3281 -0.46446 0.0269129 5.96977 --1.61089 1.70266 -0.898663 --1.67483 1.75437 -0.884598 --1.7522 1.81649 -0.879075 --1.83049 1.87981 -0.870702 --1.91548 1.94844 -0.864551 --2.00144 2.0173 -0.855102 --2.10741 2.10385 -0.857015 --2.19433 2.17311 -0.840471 --2.29553 2.25499 -0.829768 --2.41778 2.35373 -0.828177 --2.53329 2.4475 -0.817472 --2.66413 2.55306 -0.810157 --2.79593 2.65895 -0.797545 --2.93534 2.77139 -0.783308 --3.06037 2.87257 -0.756189 --3.23041 3.0088 -0.744538 --3.36401 3.11691 -0.709497 --3.59422 3.30236 -0.709114 --3.83201 3.49462 -0.701911 --3.97418 3.60917 -0.648612 --4.04174 3.66362 -0.563574 --4.04719 3.66726 -0.456587 --4.03531 3.65902 -0.345518 --4.03789 3.66044 -0.239441 --4.03854 3.66072 -0.13372 --4.03819 3.66092 -0.0283022 --4.05893 3.67719 0.0720478 --4.0634 3.68061 0.175835 --4.07357 3.68932 0.278195 --4.08279 3.69699 0.3809 --4.09877 3.70904 0.482831 --4.10512 3.71455 0.586026 --4.10959 3.71795 0.689313 --4.11307 3.72129 0.792698 --4.11567 3.72258 0.896178 --4.11627 3.72375 0.999652 --4.10737 3.71631 1.10299 --4.1051 3.71529 1.20625 --4.02465 3.6491 1.30434 --3.9183 3.56401 1.39659 --3.83496 3.49626 1.48693 --3.78878 3.45992 1.57875 --3.74935 3.42797 1.66999 --3.73189 3.41352 1.76381 --3.72872 3.4111 1.86013 --3.76947 3.44394 1.96689 --11.7943 9.91607 4.0693 --11.4231 9.61701 4.25507 --10.7552 9.07823 4.3375 --10.5492 8.91228 4.53855 --10.0789 8.53288 4.64087 --10.3873 8.78148 5.00978 --9.55645 8.11141 4.94919 --9.50132 8.0671 5.17412 --9.53209 8.09104 5.43675 --9.49886 8.06475 5.67473 --9.3321 7.93089 5.84801 --9.52497 8.08554 6.20252 --6.3 5.48534 4.7075 --8.96452 7.63484 6.41293 --9.10109 7.74415 6.7511 --8.88861 7.57333 6.88217 --6.12332 5.34236 5.33513 --5.52129 4.85658 5.11207 --5.92677 5.18398 5.57612 --5.60788 4.92669 5.52947 --5.37197 4.73602 5.53191 --5.03884 4.46786 5.44556 --11.1722 9.41547 10.7372 --5.79898 5.08063 6.45721 --5.76786 5.05563 6.63777 --6.35776 5.53139 7.40041 --2.19795 2.17694 3.61165 --2.10721 2.10349 3.61632 --2.04697 2.05434 3.64921 --2.00479 2.02019 3.69949 --1.94451 1.97187 3.72904 --1.91853 1.9506 3.79681 --4.36794 3.92645 6.83071 --4.31594 3.88427 6.97364 --5.53314 4.86655 8.74934 --1.60329 1.69691 3.79807 --1.56018 1.66216 3.83746 --1.6255 1.71488 4.03181 --1.49205 1.60713 3.94318 --1.54213 1.64729 4.12524 --1.46002 1.5813 4.10836 --4.18743 3.78107 8.70637 --4.08683 3.69931 8.81822 --2.2912 2.25189 5.9347 --1.46522 1.58519 4.60411 --1.42017 1.54894 4.65589 --1.31056 1.46035 4.58098 --1.26552 1.42394 4.62956 --1.16828 1.34568 4.56564 --1.16214 1.34084 4.6978 --1.06686 1.26348 4.62954 --2.29622 2.25537 7.7543 --1.22891 1.39468 5.35687 --1.15537 1.33518 5.35905 --0.964371 1.18105 5.03297 --0.880411 1.11431 4.98287 --0.826867 1.07046 5.01324 --0.786535 1.03767 5.0888 --0.713991 0.979749 5.06097 --0.717149 0.981505 5.2943 --0.636114 0.91653 5.23582 --0.520191 0.823184 5.03236 --0.493031 0.801269 5.16934 --0.438543 0.756403 5.20065 --0.391509 0.718857 5.2693 --0.297459 0.642784 5.10426 --0.285203 0.632941 5.36509 --0.225934 0.585064 5.38201 --0.0936002 0.478713 4.91666 --0.0353572 0.432227 4.89977 -0.00969433 0.394906 4.97051 -0.0632963 0.352549 4.9907 -0.11127 0.313951 5.05949 -0.173108 0.263532 4.988 -0.227625 0.22045 4.9947 -0.272081 0.18383 5.17975 -0.277754 0.179051 6.42249 -0.356555 0.115904 6.25681 -0.428101 0.058051 6.22918 --1.58476 1.78596 -0.886212 --1.65331 1.84474 -0.876674 --1.74858 1.92626 -0.886014 --1.81237 1.98029 -0.865457 --1.89517 2.05187 -0.857764 --1.9856 2.12986 -0.851641 --2.08272 2.2132 -0.846742 --2.19519 2.30825 -0.847132 --2.28648 2.38786 -0.82957 --2.40654 2.4896 -0.825537 --2.52745 2.59364 -0.816506 --2.65503 2.70315 -0.806503 --2.79787 2.82551 -0.798841 --2.93403 2.94192 -0.781415 --3.0568 3.04713 -0.751205 --3.21581 3.18304 -0.732697 --3.36814 3.31303 -0.704127 --3.63576 3.54319 -0.717333 --3.85476 3.73087 -0.698706 --3.93549 3.79985 -0.61981 --3.94851 3.81086 -0.515043 --3.97587 3.83354 -0.414968 --3.9936 3.84976 -0.31193 --4.01808 3.87032 -0.210468 --4.04825 3.89619 -0.110132 --4.09175 3.93378 -0.0120951 --10.2487 9.20792 -1.11584 --12.1424 10.8301 -1.19238 --15.8136 13.9748 -1.06943 --15.9297 14.0743 -0.703659 --16.1391 14.2534 -0.341145 --16.1475 14.2599 0.0418587 --16.1949 14.3008 0.423307 --4.23175 4.05301 0.945275 --4.16279 3.99503 1.05324 --4.13107 3.96729 1.15934 --4.1136 3.95243 1.2649 --4.1095 3.94842 1.3709 --4.11108 3.9498 1.47747 --3.73371 3.62701 1.53642 --3.64302 3.54852 1.62123 --3.58181 3.49593 1.70715 --3.5263 3.44864 1.79195 --3.50792 3.43299 1.88272 --3.50284 3.42931 1.97648 --3.51209 3.43674 2.07429 --3.52602 3.44961 2.17497 --4.63234 4.39727 2.62205 --4.69858 4.45375 2.76976 --4.74771 4.49506 2.91571 --4.79389 4.53533 3.06439 --4.84584 4.57925 3.21884 --4.90916 4.63334 3.38257 --4.99146 4.7043 3.5599 --9.34571 8.43414 5.8461 --10.1704 9.14001 6.53336 --8.7765 7.9459 6.05841 --8.95161 8.09634 6.41031 --8.67132 7.85628 6.50222 --8.63822 7.82789 6.73801 --5.37333 5.03044 4.85468 --6.12272 5.67241 5.53852 --6.00805 5.57482 5.65176 --5.15889 4.84681 5.21475 --4.92552 4.64777 5.20701 --4.97917 4.69368 5.41984 --4.77819 4.52141 5.42689 --5.45406 5.09957 6.18772 --6.07271 5.63004 6.94673 --5.50409 5.14303 6.63814 --2.16835 2.28588 3.59919 --2.07878 2.20955 3.6053 --1.99117 2.13418 3.60808 --2.04407 2.17905 3.76038 --1.909 2.06297 3.70801 --1.87261 2.03241 3.76295 --1.82958 1.99605 3.81024 --6.76707 6.22486 10.0788 --4.2947 4.10702 7.20262 --1.55547 1.76099 3.75296 --1.52859 1.73834 3.81429 --1.47621 1.69224 3.83836 --4.50334 4.28564 8.44414 --1.59219 1.79163 4.22396 --1.49038 1.70501 4.17894 --1.43413 1.65655 4.20071 --1.36362 1.59694 4.19701 --6.0876 5.64302 12.7196 --1.9435 2.09343 5.50994 --1.82372 1.98993 5.45013 --1.76448 1.93982 5.5028 --1.7204 1.90227 5.58788 --1.13985 1.40394 4.52124 --1.08825 1.36112 4.54976 --1.14272 1.40696 4.82067 --1.43909 1.66122 5.70146 --1.22202 1.47542 5.35505 --1.34051 1.57685 5.8593 --0.997927 1.28337 5.13366 --0.895356 1.19584 5.03101 --0.806128 1.11834 4.95238 --0.727242 1.05072 4.89866 --0.694546 1.02326 4.99143 --0.747573 1.06949 5.39287 --0.729894 1.05424 5.57163 --0.522046 0.875881 5.02076 --0.511894 0.867357 5.22487 --0.438757 0.80408 5.17077 --0.3919 0.764082 5.23022 --0.343173 0.721921 5.28877 --0.240052 0.633844 5.05469 --0.239929 0.634615 5.39327 --0.125765 0.536283 5.04698 --0.0761334 0.493312 5.09034 --0.0208851 0.445974 5.09304 -0.0436673 0.39107 5.01535 -0.106274 0.337205 4.93602 -0.158623 0.291841 4.93453 -0.211963 0.246357 4.93184 -0.251614 0.212042 5.13724 -0.297131 0.174313 5.36179 -0.324603 0.150335 6.26492 -0.39254 0.0921792 6.36809 -0.465955 0.0297853 6.06975 --1.7969 2.08672 -0.864595 --1.88423 2.16645 -0.860079 --1.97919 2.25258 -0.856933 --2.0684 2.33379 -0.84517 --2.1576 2.41517 -0.82971 --2.26778 2.5144 -0.823812 --2.37788 2.61486 -0.81317 --2.50224 2.72805 -0.806071 --2.63422 2.84778 -0.797546 --2.76716 2.96786 -0.783324 --2.92094 3.108 -0.774169 --3.07468 3.24848 -0.758223 --3.23037 3.38941 -0.735478 --3.38603 3.53067 -0.706042 --3.67564 3.79496 -0.725301 --3.88261 3.98234 -0.698223 --3.96883 4.05974 -0.617906 --4.42661 4.4765 -0.659868 --4.91574 4.92083 -0.68968 --5.77637 5.70343 -0.80297 --6.55425 6.40993 -0.853244 --7.6931 7.44475 -0.952328 --8.90119 8.54187 -1.01231 --10.9261 10.3826 -1.1705 --11.8193 11.1941 -1.04452 --11.6161 11.0093 -0.721372 --15.2703 14.3299 -0.491054 --15.3396 14.3915 -0.122609 --15.27 14.3288 0.254916 --22.8217 21.1903 0.998444 --29.4857 27.245 1.7051 --24.4562 22.6756 2.1758 --4.19367 4.26452 1.332 --4.0775 4.15917 1.43219 --4.03443 4.12059 1.53566 --4.01227 4.10038 1.64044 --3.73863 3.85124 1.70291 --3.46495 3.60347 1.75259 --3.40395 3.54771 1.83506 --3.34864 3.49727 1.91661 --3.29995 3.45322 1.99768 --3.25795 3.41459 2.07882 --3.20742 3.36823 2.15599 --3.17011 3.33484 2.2359 --3.11766 3.28718 2.30932 --3.05762 3.2328 2.37791 --3.00426 3.18386 2.44698 --2.95659 3.14032 2.51702 --4.74182 4.76341 3.43809 --4.77172 4.79093 3.59211 --4.81399 4.82868 3.75542 --4.83918 4.85112 3.91406 --4.86908 4.87815 4.07852 --2.64394 2.85717 2.8911 --4.94019 4.9429 4.42699 --5.0023 4.99862 4.62488 --8.41603 8.10112 7.13727 --5.80668 5.73013 5.52991 --4.41335 4.46422 4.67934 --4.19881 4.26898 4.66462 --4.23338 4.30093 4.84178 --4.58428 4.62035 5.29196 --4.65861 4.6876 5.52549 --5.28689 5.25819 6.27267 --4.35644 4.41296 5.59394 --2.15277 2.41054 3.60366 --2.11268 2.37479 3.65974 --2.01399 2.28426 3.65328 --1.99099 2.26335 3.72476 --2.31809 2.56122 4.19438 --1.9194 2.19858 3.84055 --4.37331 4.42812 6.92805 --4.10685 4.18616 6.80337 --2.37533 2.6124 4.7509 --2.30021 2.54425 4.78283 --1.75801 2.05113 4.15771 --1.74629 2.04118 4.25435 --4.58657 4.62197 8.63161 --1.45262 1.77375 4.03374 --1.47965 1.79902 4.18655 --1.42452 1.74868 4.20942 --1.39579 1.72327 4.27788 --1.37564 1.70417 4.3621 --1.18827 1.53431 4.13884 --1.13883 1.48933 4.16178 --1.10637 1.46 4.21649 --1.07679 1.43223 4.27905 --1.2226 1.5654 4.72274 --1.18914 1.53498 4.79712 --1.51025 1.82606 5.70238 --1.4342 1.75785 5.71399 --1.20651 1.55073 5.33512 --1.15415 1.50283 5.38362 --1.10644 1.46007 5.44891 --0.936422 1.30503 5.15984 --0.77682 1.15978 4.87336 --0.688722 1.08077 4.7831 --0.745572 1.13116 5.16294 --0.710117 1.09959 5.25699 --0.91319 1.28426 6.24336 --0.932032 1.30092 6.61621 --0.511812 0.919456 5.20357 --0.463187 0.875967 5.25548 --0.400616 0.818208 5.23902 --0.362264 0.784125 5.3466 --0.267001 0.696518 5.15279 --0.244487 0.677141 5.35535 --0.188455 0.625448 5.37227 --0.0849164 0.531646 5.06388 --0.0159657 0.46861 4.94902 -0.0409076 0.417153 4.91115 -0.0912722 0.371489 4.92141 -0.130629 0.335852 5.05949 -0.188355 0.283167 4.99795 -0.239635 0.236268 5.00465 -0.281161 0.199309 5.21969 -0.331804 0.153292 5.32407 -0.362215 0.125075 6.28676 -0.432148 0.0613423 6.17923 --1.86911 2.28383 -0.861457 --1.95522 2.36676 -0.8515 --2.04791 2.45706 -0.842566 --2.14821 2.55382 -0.834004 --2.24184 2.64457 -0.816977 --2.36305 2.76046 -0.812333 --2.49745 2.89004 -0.810486 --2.63941 3.0272 -0.806464 --2.76903 3.15227 -0.788705 --2.9252 3.3026 -0.779237 --3.0832 3.45539 -0.76277 --3.22135 3.58776 -0.729499 --3.42764 3.78725 -0.720344 --3.68988 4.03961 -0.724265 --3.93305 4.27478 -0.707932 --4.19044 4.52316 -0.685354 --4.52652 4.84582 -0.676468 --5.34093 5.63118 -0.798991 --6.06807 6.33225 -0.856519 --7.11621 7.34326 -0.961295 --8.09887 8.29044 -0.999249 --9.67425 9.81031 -1.11286 --11.348 11.4233 -1.16747 --13.047 13.0617 -1.14499 --14.4124 14.3784 -0.995555 --14.4634 14.4273 -0.636912 --14.4964 14.4594 -0.275139 --14.5105 14.4723 0.0886602 --15.2033 15.1398 0.427761 --15.7473 15.6657 0.801867 --16.0936 15.9983 1.20001 --21.4995 21.2114 1.79864 --21.5301 21.2399 2.33449 --21.5673 21.2759 2.8732 --21.5837 21.2917 3.41259 --3.98575 4.32545 1.59964 --3.89934 4.24176 1.69585 --3.83281 4.17732 1.79194 --3.46642 3.82372 1.82304 --3.46892 3.8268 1.92232 --3.41471 3.77459 2.00746 --3.2111 3.57776 2.04846 --3.14839 3.5175 2.12303 --3.07054 3.44292 2.19031 --2.97101 3.34642 2.24662 --2.90643 3.28458 2.31185 --2.84852 3.22816 2.37725 --2.78864 3.1715 2.44015 --2.73643 3.12035 2.50373 --2.68324 3.06904 2.5653 --2.64233 3.02975 2.63177 --2.58822 2.97718 2.6893 --2.54634 2.93767 2.75246 --2.50452 2.89708 2.81408 --2.48063 2.87417 2.88665 --2.4634 2.85685 2.96289 --4.84162 5.15005 4.69852 --4.46803 4.79018 4.59201 --4.45437 4.77644 4.73578 --4.20552 4.53684 4.6977 --4.17772 4.50946 4.82644 --4.42931 4.75262 5.19527 --4.82532 5.13422 5.71164 --4.76528 5.07679 5.84006 --4.62696 4.94269 5.89328 --4.98595 5.2892 6.43489 --5.20045 5.49674 6.85851 --2.44186 2.83657 4.1349 --2.36226 2.75989 4.16213 --2.30533 2.70476 4.21195 --1.87115 2.28552 3.81194 --4.11063 4.44532 6.66495 --1.97422 2.38568 4.14805 --1.98045 2.39209 4.26942 --1.96034 2.37217 4.35709 --1.94306 2.35477 4.45196 --1.89362 2.3082 4.50331 --1.85466 2.26995 4.56823 --1.5179 1.94585 4.16793 --1.49215 1.92076 4.2392 --1.49279 1.9206 4.35645 --1.46792 1.89695 4.43546 --1.32818 1.76281 4.30805 --1.20074 1.63997 4.19117 --1.11851 1.56076 4.15042 --1.05797 1.50182 4.14805 --1.03779 1.48345 4.22693 --1.22929 1.66745 4.76981 --1.58044 2.00645 5.71484 --1.41922 1.84978 5.52343 --1.43929 1.86981 5.76066 --1.22827 1.66661 5.42025 --1.09907 1.54183 5.26641 --1.22898 1.66719 5.81451 --0.852055 1.30381 4.9351 --0.75115 1.20637 4.81263 --0.709354 1.16611 4.86072 --0.735042 1.19052 5.13882 --0.658519 1.11699 5.0844 --0.919959 1.36941 6.27334 --0.928475 1.37709 6.59912 --0.526448 0.989241 5.25789 --0.462166 0.927019 5.23443 --0.354856 0.825012 5.00772 --0.337326 0.807019 5.19172 --0.260942 0.733935 5.08552 --0.209775 0.684587 5.10336 --0.193889 0.669528 5.3444 --0.103773 0.581496 5.1156 --0.0432538 0.524447 5.07058 -0.0125072 0.470591 5.04366 -0.0802011 0.405033 4.89669 -0.126692 0.360043 4.93597 -0.172239 0.315556 4.98424 -0.228778 0.260909 4.90198 -0.2645 0.226306 5.13716 -0.311276 0.18154 5.26203 -0.332444 0.161373 6.31489 -0.399579 0.096807 6.28812 -0.46801 0.0311706 6.05975 --1.1519 1.68926 -0.91325 --1.21988 1.75818 -0.920936 --1.28219 1.82118 -0.919854 --1.35008 1.89137 -0.922196 --1.40756 1.9506 -0.910146 --1.93957 2.49305 -0.854522 --2.04237 2.59867 -0.852389 --2.13383 2.69223 -0.836915 --2.23192 2.7922 -0.821617 --2.34981 2.91303 -0.814234 --2.47431 3.04035 -0.805329 --2.61201 3.18142 -0.798321 --2.77149 3.34366 -0.795627 --2.91763 3.49375 -0.7787 --3.09025 3.67021 -0.768017 --3.25152 3.83466 -0.743093 --3.44578 4.03385 -0.725287 --3.71467 4.30872 -0.728476 --3.97219 4.57176 -0.713729 --4.22306 4.82811 -0.684076 --4.95834 5.57983 -0.802223 --5.64254 6.27893 -0.867428 --6.55699 7.21416 -0.961983 --7.50908 8.18758 -1.02004 --8.72823 9.43329 -1.09059 --10.1511 10.8869 -1.14119 --10.0087 10.7425 -0.845792 --10.0579 10.7924 -0.587529 --14.3173 15.1469 -0.854834 --14.673 15.5101 -0.51822 --14.8993 15.7405 -0.155024 --14.9387 15.7809 0.227997 --14.7705 15.6096 0.617782 --15.1647 16.0125 0.998935 --15.6729 16.5316 1.40249 --15.7698 16.631 1.81129 --20.5631 21.5295 2.57695 --20.5888 21.5564 3.10724 --20.574 21.5417 3.63493 --20.6082 21.5764 4.17089 --3.86669 4.46295 1.76624 --3.26758 3.85155 1.75676 --3.26448 3.84808 1.85233 --3.26038 3.84456 1.94779 --3.26202 3.84549 2.04538 --3.7 4.29367 2.27628 --3.69781 4.29094 2.38534 --3.71445 4.30777 2.50205 --3.74897 4.34319 2.62768 --3.77594 4.37109 2.75272 --2.79761 3.37069 2.44109 --2.71915 3.29041 2.49543 --2.62744 3.1978 2.53968 --2.56222 3.13034 2.59357 --2.50357 3.07033 2.64823 --2.44399 3.00914 2.70045 --2.39103 2.95445 2.75418 --2.34368 2.90621 2.80973 --2.28875 2.85118 2.85927 --2.25368 2.81496 2.91981 --2.21669 2.77756 2.9792 --2.1797 2.7401 3.03729 --2.16063 2.72043 3.10873 --2.14062 2.69969 3.17981 --3.93583 4.5342 4.81091 --4.80193 5.41994 5.73706 --4.6847 5.30034 5.81412 --4.50357 5.11442 5.82548 --4.93097 5.5518 6.43702 --2.45403 3.01954 4.06798 --2.40478 2.96945 4.12912 --2.31605 2.87866 4.14577 --2.29977 2.86133 4.24074 --4.30543 4.91245 6.76537 --1.8488 2.40084 3.91925 --1.91709 2.47068 4.11127 --4.66625 5.28091 7.88772 --1.99066 2.54555 4.43833 --2.15559 2.71476 4.79696 --1.84713 2.39923 4.4742 --1.63737 2.18414 4.27626 --1.55904 2.10485 4.26968 --1.50988 2.05451 4.3054 --1.50111 2.04507 4.40874 --1.42846 1.97123 4.40372 --1.29106 1.83129 4.27791 --1.25505 1.7946 4.33016 --1.83152 2.38338 5.58686 --1.04053 1.57486 4.14544 --1.03362 1.56759 4.24968 --1.5844 2.12975 5.58733 --1.50884 2.05341 5.59624 --1.44928 1.99266 5.63712 --1.39906 1.94171 5.7023 --1.33487 1.87509 5.73152 --1.23689 1.77587 5.67063 --0.847126 1.37694 4.77768 --0.815763 1.34482 4.85566 --1.03118 1.56503 5.69458 --0.72406 1.2506 4.92813 --0.664606 1.19049 4.92122 --1.24845 1.78659 7.18414 --1.17469 1.7115 7.23615 --0.916295 1.44777 6.56282 --0.841758 1.37135 6.56893 --0.782128 1.31008 6.63967 --0.400564 0.919961 5.20767 --0.316081 0.833593 5.06603 --0.267836 0.784998 5.09546 --0.215908 0.732145 5.10426 --0.201957 0.718219 5.34555 --0.138968 0.652673 5.29403 --0.0971319 0.61067 5.38776 -0.00179411 0.50906 5.03772 -0.0389848 0.47167 5.15808 -0.1155 0.392112 4.90162 -0.144489 0.362542 5.12897 -0.222727 0.283765 4.76923 -0.250893 0.254113 5.05447 -0.289366 0.215325 5.28953 -0.338707 0.164877 5.38393 -0.368936 0.134175 6.33673 -0.437132 0.0640756 6.1192 --1.03616 1.66612 -0.935451 --1.09071 1.72466 -0.933797 --1.12914 1.76723 -0.911229 --1.18834 1.83197 -0.911654 --1.24945 1.89795 -0.909526 --1.31522 1.97008 -0.910675 --1.37164 2.03031 -0.897578 --1.4337 2.09673 -0.887756 --1.52393 2.19575 -0.902196 --1.7476 2.43825 -0.876232 --1.83501 2.53308 -0.870559 --1.91674 2.62197 -0.856417 --1.99945 2.71111 -0.838476 --2.09996 2.82093 -0.829856 --2.2081 2.93725 -0.820709 --2.3228 3.06104 -0.810488 --2.45622 3.20672 -0.806438 --2.60284 3.36618 -0.803387 --2.76359 3.54055 -0.800282 --2.93087 3.72255 -0.792808 --3.10668 3.91233 -0.780359 --3.28244 4.10253 -0.75942 --3.4713 4.30771 -0.735635 --3.69407 4.54883 -0.715917 --3.96289 4.84055 -0.702916 --4.58174 5.51204 -0.800203 --5.15154 6.13083 -0.848836 --5.85679 6.89568 -0.908443 --6.72472 7.83646 -0.975926 --7.66305 8.85409 -1.01573 --8.83825 10.1296 -1.05967 --10.1384 11.5398 -1.06695 --10.0671 11.4616 -0.776876 --9.97876 11.3663 -0.489268 --9.9272 11.3098 -0.211359 --14.4183 16.1823 -0.347196 --14.9061 16.7108 0.00660964 --15.1795 17.0074 0.393163 --15.2657 17.1008 0.795888 --15.0897 16.9096 1.19962 --15.1392 16.9638 1.60306 --19.565 21.764 2.291 --19.5606 21.7593 2.80864 --19.5901 21.7911 3.3311 --19.6402 21.8455 3.85948 --10.3834 11.8054 2.82859 --10.1928 11.5975 3.07586 --3.07362 3.87647 1.78757 --3.07053 3.8729 1.88104 --3.06551 3.86822 1.97466 --3.06055 3.86255 2.06832 --3.62284 4.47213 2.3481 --3.60655 4.45434 2.45401 --3.60148 4.4495 2.56455 --3.61523 4.46425 2.68326 --3.60741 4.45528 2.79469 --3.62488 4.47451 2.9182 --3.66584 4.51892 3.05573 --3.69175 4.5472 3.18947 --3.72898 4.58662 3.33203 --3.76326 4.625 3.47723 --6.48327 7.57442 5.26629 --2.33446 3.07458 2.81809 --2.2517 2.98386 2.84929 --2.18009 2.9071 2.88537 --2.12076 2.84241 2.92735 --2.07357 2.79183 2.97601 --2.01987 2.73351 3.0182 --1.98396 2.69494 3.07285 --1.94712 2.65525 3.12634 --1.91035 2.6145 3.17859 --1.89043 2.59256 3.24573 --1.85733 2.55721 3.30134 --1.82988 2.52746 3.36171 --1.75748 2.44851 3.37487 --1.76754 2.45907 3.47423 --1.71105 2.39785 3.50183 --1.68641 2.3714 3.56456 --1.65518 2.33819 3.62047 --1.67555 2.35943 3.7405 --1.56198 2.23571 3.69003 --4.39869 5.31265 7.62038 --1.743 2.43244 4.13871 --3.84213 4.71011 7.29373 --2.02772 2.74201 4.79422 --1.5305 2.20176 4.15519 --1.46093 2.12635 4.15537 --1.45398 2.11998 4.25777 --1.61829 2.29722 4.65734 --1.40187 2.06285 4.40264 --1.24355 1.89034 4.23205 --1.18797 1.83144 4.24463 --1.24656 1.89384 4.48051 --1.19287 1.83643 4.50053 --1.65016 2.33269 5.61487 --1.53947 2.21217 5.54444 --1.46333 2.12939 5.54575 --2.63886 3.40413 8.55411 --1.38572 2.04517 5.72154 --1.48962 2.15784 6.1871 --0.826878 1.43925 4.60297 --0.796627 1.40575 4.67212 --1.39714 2.05797 6.61098 --1.00051 1.62762 5.63913 --0.784764 1.3941 5.15842 --0.673437 1.27318 4.97987 --0.590116 1.18195 4.88023 --1.08776 1.72288 6.94519 --1.26253 1.91076 7.94995 --0.837903 1.45146 6.57086 --0.76555 1.37212 6.57603 --0.403875 0.980195 5.22484 --0.326133 0.896729 5.11324 --0.305029 0.872569 5.2784 --0.262472 0.82726 5.34686 --0.201525 0.760437 5.30752 --0.150723 0.705073 5.32496 --0.112755 0.664312 5.43897 --0.0132464 0.556226 5.08044 -0.0311447 0.508986 5.13246 -0.0818484 0.453353 5.12418 -0.148924 0.380278 4.92612 -0.200542 0.325461 4.87484 -0.239342 0.282281 4.98156 -0.275697 0.243153 5.18702 -0.324732 0.190776 5.22204 -0.38563 0.124288 4.84628 -0.406619 0.10093 6.21819 -0.470002 0.0330767 6.0198 --1.10244 1.84398 -0.908672 --1.15585 1.90472 -0.901827 --1.21484 1.97264 -0.898605 --1.28414 2.05277 -0.904333 --1.3497 2.12809 -0.901436 --1.40964 2.19648 -0.890021 --1.50899 2.31066 -0.913163 --1.55292 2.3611 -0.880036 --1.6475 2.47063 -0.890162 --1.72049 2.55496 -0.87635 --1.80012 2.64565 -0.863912 --1.87966 2.73751 -0.847927 --1.97708 2.84905 -0.841313 --2.0754 2.96187 -0.830052 --2.1737 3.07492 -0.814196 --2.29073 3.20982 -0.805309 --2.3289 3.25438 -0.742092 --2.56326 3.52284 -0.792035 --2.74304 3.73094 -0.799288 --2.92475 3.93961 -0.797346 --3.10082 4.14153 -0.783291 --3.28336 4.35216 -0.763218 --3.49875 4.59965 -0.747764 --3.75912 4.89865 -0.739479 --4.18535 5.38976 -0.780898 --4.72313 6.00818 -0.838222 --5.34612 6.7251 -0.894471 --6.13404 7.63077 -0.965821 --6.93673 8.55526 -0.999261 --8.03466 9.81717 -1.06084 --9.29172 11.2624 -1.09804 --11.0527 13.2884 -1.16278 --12.6157 15.086 -1.10193 --13.0494 15.5853 -0.807687 --13.5129 16.1193 -0.494455 --13.9934 16.6716 -0.158687 --15.3749 18.2601 0.153954 --15.6443 18.5708 0.569317 --15.6271 18.551 0.998817 --16.3657 19.4003 1.44748 --16.1152 19.113 1.88313 --18.6187 21.9923 2.5257 --18.6443 22.0214 3.03896 --18.6241 21.9984 3.5488 --27.1471 31.8015 5.42679 --27.1505 31.8057 6.17252 --2.87886 3.88659 1.72339 --2.87672 3.88398 1.81472 --2.8792 3.88776 1.90786 --2.8818 3.88956 2.00151 --2.88901 3.89778 2.09757 --2.71558 3.6994 2.13121 --2.79764 3.79365 2.25292 --2.85255 3.8569 2.36889 --3.51732 4.62142 2.7555 --3.5161 4.61905 2.87085 --3.50639 4.60802 2.98357 --3.50789 4.61002 3.10283 --3.53835 4.64576 3.23993 --3.55484 4.66436 3.37208 --3.57598 4.68851 3.50949 --3.59523 4.71064 3.64879 --3.6182 4.7373 3.79389 --3.66268 4.78826 3.95796 --3.68753 4.81648 4.11211 --2.06118 2.94616 2.98824 --2.00298 2.87942 3.02792 --1.93361 2.79936 3.05537 --1.88104 2.73896 3.09477 --1.83408 2.68507 3.13719 --1.79837 2.64333 3.18839 --1.75043 2.58921 3.22741 --1.70356 2.53406 3.26458 --1.66589 2.49198 3.31128 --1.62928 2.4489 3.35683 --1.59068 2.40564 3.40108 --1.55315 2.36137 3.44398 --1.51928 2.32259 3.49195 --1.48542 2.28375 3.53881 --1.44592 2.23918 3.57811 --1.41213 2.19924 3.62282 --1.38105 2.16376 3.67324 --1.34528 2.1236 3.71595 --1.32363 2.09733 3.77879 --1.29628 2.06633 3.83402 --1.28104 2.04915 3.91057 --1.28727 2.05619 4.0244 --1.32982 2.10496 4.20728 --1.28479 2.05272 4.24022 --1.20621 1.96219 4.20946 --1.17701 1.92833 4.27012 --1.27713 2.04475 4.5937 --1.64441 2.46695 5.49788 --1.41222 2.19947 5.16111 --1.45643 2.25005 5.41861 --1.4234 2.21156 5.51192 --1.38197 2.16368 5.58781 --1.36281 2.14215 5.72282 --0.826007 1.52529 4.49859 --0.814478 1.51117 4.61206 --1.3331 2.10855 6.25335 --0.569336 1.23007 4.19859 --1.28998 2.05849 6.59026 --0.709454 1.3913 4.95134 --0.619022 1.2864 4.82769 --0.566503 1.22714 4.82919 --0.517809 1.17049 4.83849 --1.19567 1.95101 7.73089 --1.21962 1.97767 8.1979 --0.464064 1.10916 5.26421 --0.394989 1.02928 5.19403 --0.33513 0.960773 5.1598 --0.302067 0.922546 5.2583 --0.220134 0.828256 5.09544 --0.195286 0.800325 5.24985 --0.12176 0.715313 5.102 --0.118943 0.711432 5.43098 --0.059139 0.642998 5.37802 -0.0243618 0.547229 5.10659 -0.0566256 0.509621 5.25693 -0.141725 0.412614 4.88182 -0.174035 0.375376 5.03965 -0.236101 0.303483 4.81894 -0.264147 0.271836 5.10427 -0.307382 0.22082 5.17981 -0.351856 0.171146 5.30404 -0.378094 0.139667 6.27673 -0.441116 0.0673786 6.04922 --1.3171 2.21954 -0.898739 --1.38045 2.29796 -0.891403 --1.45051 2.38169 -0.88629 --1.51942 2.4675 -0.878083 --1.61747 2.58613 -0.891038 --1.69393 2.67955 -0.880157 --1.76477 2.76604 -0.860957 --1.85336 2.87415 -0.851826 --1.94194 2.98248 -0.8384 --2.04266 3.10539 -0.828923 --2.14895 3.23571 -0.818475 --2.25713 3.36741 -0.802577 --2.2643 3.37701 -0.719103 --2.50234 3.66759 -0.772217 --2.71883 3.93209 -0.799447 --2.90075 4.15388 -0.796149 --3.08919 4.38341 -0.786383 --3.29061 4.62998 -0.772472 --3.51729 4.90616 -0.758664 --3.87928 5.34885 -0.787979 --4.34769 5.92134 -0.837557 --4.89357 6.58776 -0.887686 --5.58409 7.43061 -0.954236 --6.40135 8.43063 -1.01965 --7.32221 9.55517 -1.06693 --8.24669 10.6834 -1.06401 --9.95127 12.766 -1.17274 --11.7041 14.907 -1.19584 --12.2314 15.5505 -0.936078 --12.6801 16.099 -0.638365 --13.1194 16.636 -0.316018 --13.581 17.2006 0.028437 --15.8824 20.0113 0.321613 --16.0145 20.172 0.771263 --15.7613 19.8622 1.22282 --16.009 20.1658 1.68116 --17.6696 22.1942 2.25097 --15.8198 19.9339 2.57442 --17.7319 22.2703 3.26375 --17.7426 22.2822 3.77146 --17.7466 22.2876 4.28034 --17.7637 22.3092 4.79422 --2.70198 3.91058 1.75506 --2.68675 3.89289 1.84144 --2.68275 3.88807 1.93097 --2.70295 3.9132 2.02847 --8.98722 11.5885 4.3194 --2.54967 3.72467 2.15527 --2.54842 3.724 2.24411 --2.56494 3.74387 2.34125 --2.57958 3.76168 2.43969 --2.58112 3.76442 2.53327 --3.47126 4.85126 3.09701 --3.45323 4.82868 3.20945 --3.43421 4.80602 3.32149 --3.43206 4.80196 3.44423 --3.41583 4.78265 3.55982 --3.42755 4.79711 3.69525 --3.44298 4.81608 3.83618 --3.45753 4.83308 3.97881 --3.47479 4.85455 4.12754 --3.49576 4.88058 4.28268 --3.51391 4.90353 4.43996 --6.83303 8.95779 7.54861 --1.83679 2.85347 3.17205 --1.77975 2.78445 3.20474 --1.72273 2.7153 3.23494 --1.66573 2.64603 3.26273 --1.61992 2.58992 3.29936 --1.58436 2.54595 3.34586 --1.54788 2.50085 3.39102 --1.51599 2.46229 3.44098 --1.47394 2.4104 3.47742 --1.43089 2.35839 3.51236 --1.39809 2.31858 3.55868 --1.35506 2.26642 3.59062 --1.32234 2.2255 3.63459 --1.28304 2.17777 3.67064 --1.24932 2.13668 3.71231 --1.21474 2.09348 3.75298 --1.17911 2.05117 3.79249 --1.14354 2.0078 3.83096 --1.10799 1.96438 3.86832 --1.07984 1.93013 3.9198 --1.0517 1.89585 3.97058 --1.02633 1.8651 4.02851 --1.04274 1.88431 4.17324 --0.973779 1.8004 4.14291 --1.43591 2.36439 5.28208 --0.863749 1.6658 4.13155 --1.3497 2.25927 5.41109 --1.29459 2.19141 5.44453 --3.5853 4.98997 11.5212 --0.792767 1.57972 4.46356 --2.41699 3.56316 9.13752 --0.604244 1.34798 4.2076 --1.23803 2.12263 6.26869 --1.19112 2.06573 6.3515 --0.67862 1.43999 4.89898 --0.632897 1.3832 4.92183 --0.629534 1.37977 5.09909 --0.78577 1.57027 5.89645 --0.605208 1.35055 5.42869 --0.509659 1.23317 5.26178 --0.417764 1.12183 5.09099 --0.374784 1.06877 5.12508 --0.330873 1.0146 5.15812 --0.315393 0.995788 5.34338 --0.286082 0.960243 5.4711 --0.160572 0.806234 5.02747 --0.12302 0.761114 5.09364 --0.0645089 0.689352 5.01252 --0.0689548 0.69431 5.40959 -0.0160657 0.591517 5.11977 -0.0717349 0.522701 5.03391 -0.125577 0.456908 4.94612 -0.169465 0.403581 4.95578 -0.216034 0.347057 4.92454 -0.252718 0.301495 5.04131 -0.290459 0.255302 5.18703 -0.332756 0.203796 5.29193 -0.393042 0.130359 4.85634 -0.412847 0.105579 6.1982 -0.472058 0.0344619 6.0098 --1.75239 2.92184 -0.879632 --1.8276 3.0187 -0.858815 --1.91857 3.13712 -0.846974 --2.01051 3.25584 -0.830435 --2.11913 3.39728 -0.820922 --2.22865 3.54006 -0.805763 --2.27027 3.5939 -0.74188 --2.31194 3.64683 -0.67605 --2.36929 3.72238 -0.618247 --2.41558 3.78165 -0.551499 --2.47861 3.86268 -0.491328 --2.4002 3.76106 -0.361846 --2.40177 3.76354 -0.273549 --4.00296 5.84027 -0.83889 --4.4796 6.45866 -0.883173 --5.07894 7.23519 -0.942308 --5.72733 8.07779 -0.982973 --6.45102 9.01599 -1.00786 --7.6301 10.5446 -1.10933 --9.08961 12.4384 -1.20796 --10.4997 14.2666 -1.21274 --11.4876 15.5474 -1.06427 --11.8908 16.0705 -0.776299 --12.3284 16.6378 -0.469971 --12.7686 17.2094 -0.139811 --16.2448 21.7184 0.0410957 --16.4664 22.0051 0.513723 --16.4138 21.9377 0.998715 --16.7839 22.4169 1.4928 --16.8001 22.4385 1.98804 --16.8051 22.4454 2.48395 --16.8417 22.4926 2.98457 --16.8421 22.4933 3.48345 --9.67148 13.1928 2.75004 --9.93612 13.5361 3.09779 --2.52971 3.92939 1.697 --2.50344 3.89576 1.77879 --2.50688 3.9004 1.868 --2.50289 3.89549 1.95572 --2.52866 3.928 2.0539 --2.49316 3.88156 2.13127 --2.40858 3.77221 2.45573 --2.42128 3.7889 2.55411 --5.33193 7.56357 4.28772 --3.63727 5.36609 3.46563 --3.58772 5.30204 3.5691 --3.46862 5.1482 3.62562 --3.36725 5.01578 3.68789 --3.3381 4.97837 3.79799 --3.32477 4.96055 3.91994 --3.31416 4.94714 4.04639 --3.31374 4.94684 4.18217 --3.32818 4.96524 4.33294 --3.33979 4.98054 4.48545 --3.34498 4.98626 4.63468 --3.38892 5.04458 4.82631 --3.45147 5.12532 5.04289 --3.47974 5.16148 5.23151 --2.04695 3.30323 3.81248 --1.61158 2.73786 3.42027 --1.60939 2.73615 3.50965 --1.69984 2.85308 3.714 --1.73284 2.89626 3.85645 --1.73994 2.90535 3.97019 --1.68044 2.82776 3.99517 --1.68014 2.82708 4.10294 --1.7103 2.86673 4.25846 --1.29108 2.32287 3.73462 --1.23066 2.2451 3.73679 --1.18419 2.18415 3.75753 --1.15061 2.141 3.798 --1.11245 2.09114 3.83016 --1.06966 2.03555 3.85346 --1.03052 1.9855 3.88282 --0.996091 1.94005 3.91849 --0.964373 1.89911 3.96077 --0.928959 1.8535 3.99424 --0.897314 1.81147 4.03466 --0.868376 1.77397 4.08219 --0.834806 1.73073 4.12086 --0.76712 1.64314 4.0756 --0.770443 1.6477 4.20366 --0.752569 1.62443 4.28179 --0.679335 1.53038 4.21419 --0.636641 1.474 4.22151 --0.649131 1.49032 4.3934 --0.738908 1.60693 4.81422 --1.14695 2.13636 6.29238 --0.62203 1.45503 4.76583 --0.612273 1.44336 4.90602 --0.561279 1.37582 4.90072 --0.670005 1.517 5.51029 --0.50682 1.30618 5.07944 --0.450279 1.23217 5.0516 --0.37352 1.13311 4.92776 --0.371053 1.12953 5.14128 --0.331011 1.07711 5.18457 --0.291854 1.02616 5.2363 --0.252584 0.976638 5.29677 --0.1596 0.855344 5.02784 --0.117717 0.801041 5.0558 --0.0749641 0.745139 5.07281 --0.0765955 0.748477 5.44071 -0.00882615 0.636726 5.13261 -0.0679471 0.560767 5.00813 -0.107977 0.508248 5.04952 -0.146309 0.459257 5.11949 -0.196147 0.393098 5.03964 -0.23803 0.338795 5.06759 -0.27565 0.291647 5.19394 -0.3289 0.221628 5.00022 -0.369823 0.167697 5.03447 -0.388251 0.145103 6.21683 -0.446164 0.069596 6.01924 --1.98696 3.43036 -0.842393 --2.09232 3.57579 -0.829393 --2.13841 3.63868 -0.770334 --2.16686 3.67807 -0.698611 --2.20541 3.73283 -0.63249 --2.21074 3.73949 -0.545478 --2.21513 3.74507 -0.458619 --2.21301 3.74237 -0.369188 --2.22111 3.75303 -0.28556 --2.21618 3.74711 -0.19699 --2.22241 3.75563 -0.113768 --2.21667 3.7466 -0.0260509 --2.22102 3.75299 0.0567635 --2.22445 3.75832 0.139624 --2.22147 3.75331 0.224057 --2.22308 3.7555 0.306561 --2.22375 3.75663 0.389011 --2.22349 3.75668 0.471208 --2.23431 3.77235 0.551202 --2.23873 3.77767 0.632667 --2.23665 3.7746 0.714707 --2.23921 3.77779 0.796066 --2.23432 3.77153 0.877845 --2.2415 3.78101 0.959022 --2.24124 3.78104 1.04052 --2.24004 3.78 1.12206 --2.2444 3.78634 1.20388 --2.25339 3.79902 1.28671 --2.25594 3.80228 1.36927 --2.25754 3.80449 1.45217 --2.26477 3.81312 1.5364 --2.26999 3.82166 1.62111 --2.27533 3.82822 1.70633 --2.27324 3.82525 1.79036 --2.28226 3.83718 1.87814 --2.29033 3.84809 1.96676 --2.35374 3.93667 2.07762 --2.25094 3.7954 2.12501 --5.12721 7.76213 4.39431 --5.17467 7.82705 4.61368 --3.66162 5.74089 3.79241 --3.67597 5.76044 3.94633 --8.12333 11.8954 7.38724 --8.04591 11.7877 7.63437 --3.31497 5.26177 4.09936 --3.26103 5.18801 4.19448 --3.23291 5.14995 4.31042 --3.20951 5.11638 4.43048 --3.20905 5.1165 4.57465 --3.19757 5.10045 4.70974 --3.25889 5.185 4.92361 --3.29711 5.23823 5.12077 --1.80106 3.1732 3.5939 --1.70576 3.0435 3.58259 --1.77001 3.13134 3.75818 --1.74672 3.09845 3.83114 --1.53088 2.80077 3.65406 --1.8115 3.18748 4.13102 --1.69691 3.03082 4.08478 --3.82519 5.96587 7.29276 --4.2351 6.53106 8.13598 --4.09162 6.33438 8.16752 --3.98782 6.19102 8.25485 --3.87946 6.04081 8.33108 --1.56974 2.85453 4.5875 --1.5896 2.88186 4.74998 --1.10641 2.21587 3.98577 --1.01324 2.08728 3.91334 --0.967873 2.02505 3.92744 --0.92622 1.96736 3.94745 --0.889217 1.91528 3.97382 --0.854865 1.8687 4.00665 --0.81688 1.81643 4.03042 --0.785305 1.77331 4.06909 --0.753797 1.72915 4.10682 --0.724996 1.68953 4.15195 --0.70166 1.65807 4.21323 --0.66923 1.61272 4.24841 --1.16577 2.2974 5.81637 --0.774722 1.75873 4.8381 --0.701914 1.65767 4.77004 --2.06785 3.54106 9.39968 --0.592959 1.50675 4.73176 --0.516498 1.4017 4.62823 --0.535199 1.42774 4.86716 --0.509023 1.39228 4.95235 --0.488365 1.36353 5.06498 --0.436692 1.29132 5.0472 --0.363982 1.19102 4.93395 --0.362392 1.18951 5.14758 --0.323404 1.13617 5.19152 --0.279034 1.07402 5.20583 --0.277326 1.0719 5.46804 --0.275553 1.06927 5.76022 --0.162077 0.912959 5.35663 --0.0868153 0.809455 5.16172 --0.235927 1.01493 6.65266 --0.0269088 0.726879 5.40963 -0.0670312 0.597158 4.9723 -0.107698 0.540143 4.98457 -0.149416 0.484006 4.99559 -0.188315 0.429969 5.02525 -0.23171 0.370121 5.00401 -0.261839 0.327916 5.20054 -0.308783 0.263261 5.12725 -0.355653 0.199556 5.01246 -0.398016 0.140536 4.96625 -0.421572 0.108127 6.05825 -0.474114 0.0358472 5.99981 --2.13478 3.86753 -0.520724 --2.13364 3.86495 -0.429992 --2.13058 3.86122 -0.339915 --2.12758 3.85645 -0.250489 --2.12822 3.85778 -0.163944 --2.12799 3.85704 -0.0778022 --2.12225 3.84801 0.0100152 --2.12009 3.8461 0.0952013 --2.12357 3.85044 0.178311 --2.11408 3.83709 0.264417 --2.12127 3.84658 0.345594 --2.11543 3.83935 0.429317 --2.12073 3.84672 0.510487 --2.11959 3.84471 0.59268 --2.11745 3.84264 0.67457 --2.11543 3.83855 0.75626 --2.11705 3.84067 0.837365 --2.11867 3.8428 0.918471 --2.11841 3.8428 0.999669 --2.11815 3.84281 1.08077 --2.11151 3.83238 1.16164 --2.11494 3.83764 1.243 --2.11193 3.83346 1.32399 --2.11448 3.83667 1.40585 --2.1096 3.83037 1.48673 --2.11583 3.8389 1.57005 --2.11556 3.83896 1.65235 --2.11991 3.84541 1.73646 --2.11783 3.84237 1.8192 --2.12036 3.84574 1.90405 --2.11091 3.83215 1.98516 --2.12325 3.85072 2.78781 --2.12671 3.8547 2.88386 --2.13832 3.87264 2.98847 --2.13896 3.87352 3.08616 --2.14425 3.87994 3.1888 --2.1476 3.88529 3.29228 --2.14908 3.88856 3.39666 --2.15067 3.88988 3.50194 --2.15038 3.88911 3.6079 --2.15374 3.89386 3.71963 --1.59477 3.07469 3.23494 --1.5872 3.06319 3.31546 --2.15913 3.90237 4.06597 --1.62423 3.11791 3.54397 --1.62673 3.12102 3.64386 --1.83726 3.43002 4.01499 --1.6903 3.21433 3.93051 --1.43067 2.83302 3.67788 --1.64474 3.14796 4.08329 --1.57576 3.0459 4.0915 --3.16363 5.37662 6.65462 --3.89479 6.44882 8.02519 --3.52409 5.90588 7.66251 --1.4856 2.91353 4.40355 --1.47149 2.89339 4.49987 --3.36549 5.67261 8.10647 --3.26409 5.52404 8.16664 --3.35216 5.65192 8.59431 --0.908453 2.06602 3.87529 --0.890774 2.04015 3.94144 --0.879504 2.02346 4.02289 --0.842621 1.96938 4.04936 --0.794702 1.90035 4.05057 --0.758836 1.84619 4.07405 --0.718279 1.78726 4.08802 --0.684073 1.73848 4.11694 --0.653632 1.69331 4.15323 --0.61956 1.64243 4.18006 --0.593594 1.6053 4.23139 --0.57591 1.57895 4.30807 --0.609287 1.62714 4.5508 --0.632561 1.66094 4.77886 --0.584657 1.59179 4.77767 --0.515002 1.48913 4.6939 --0.480788 1.4399 4.73386 --0.473973 1.42882 4.88245 --0.47343 1.428 5.06852 --0.439169 1.37863 5.12581 --0.350573 1.2472 4.9303 --0.322663 1.20747 5.01238 --0.309352 1.1874 5.16958 --0.266037 1.12434 5.18454 --0.241833 1.08765 5.30325 --0.381058 1.29249 6.45023 --0.162443 0.971575 5.38518 --0.107447 0.890675 5.31774 --0.0605425 0.82209 5.30662 --0.0343076 0.784011 5.46032 -0.0654792 0.638048 4.96569 -0.104093 0.580187 4.97861 -0.141068 0.526842 5.01987 -0.179788 0.470348 5.04024 -0.22107 0.408661 5.01979 -0.258085 0.355127 5.07748 -0.268139 0.339926 5.69202 -0.344169 0.228766 4.9404 -0.381165 0.174046 5.01456 -0.423839 0.111024 4.82767 -0.450276 0.0723665 5.99926 --3.08412 5.61183 -0.84731 --3.38246 6.07929 -0.866025 --3.77153 6.6876 -0.905745 --4.23564 7.41352 -0.951003 --4.75363 8.22542 -0.986654 --5.32745 9.12368 -1.0075 --6.14205 10.3987 -1.06606 --7.28892 12.1944 -1.16398 --8.59948 14.2464 -1.22728 --9.70471 15.9765 -1.16192 --10.0342 16.4926 -0.886374 --10.3839 17.0388 -0.593368 --10.7243 17.5726 -0.277577 --13.9977 22.6965 0.291864 --2.08424 4.04528 0.957631 --2.07846 4.03705 1.0413 --2.07274 4.02781 1.12463 --2.07616 4.03319 1.20849 --2.06313 4.01241 1.29073 --2.06561 4.01673 1.37454 --2.06171 4.01059 1.45762 --2.05143 3.99398 1.53947 --2.04666 3.98576 1.62215 --2.02896 3.95955 1.70163 --2.03886 3.97349 1.78841 --2.0568 4.00319 1.87967 --2.05389 3.99719 1.96445 --2.02476 3.95202 2.84669 --2.03176 3.96346 2.94739 --2.03334 3.9654 3.04503 --2.02849 3.95776 3.13929 --2.02731 3.95558 3.23821 --2.02518 3.95237 3.33758 --2.02671 3.95465 3.44221 --2.0273 3.95591 3.54748 --2.02607 3.95409 3.65369 --1.5277 3.17409 3.21751 --2.01637 3.93782 3.86279 --1.49341 3.12084 3.35829 --2.02389 3.95012 4.10132 --2.02078 3.94564 4.21667 --1.84084 3.66419 4.10048 --1.22711 2.70326 3.37304 --1.69621 3.43718 4.12861 --1.15187 2.58569 3.43995 --1.20356 2.66635 3.60761 --2.03495 3.96734 5.01958 --2.03727 3.97081 5.1673 --1.01333 2.36831 3.57367 --0.95292 2.27473 3.5604 --1.34055 2.87938 4.35698 --1.3947 2.96596 4.58012 --2.04314 3.98024 5.97557 --2.04723 3.98567 6.16046 --1.35638 2.90403 4.89423 --2.05336 3.99639 6.55045 --2.0655 4.01551 6.77896 --2.07123 4.02493 7.00201 --1.28737 2.79681 5.32341 --1.25872 2.75238 5.41283 --0.719646 1.90901 4.17483 --0.65942 1.81395 4.13149 --0.620932 1.75404 4.14352 --0.585154 1.69866 4.16255 --0.547683 1.63867 4.17159 --0.525539 1.60417 4.23093 --0.49794 1.56143 4.27231 --0.474926 1.52482 4.33055 --0.479902 1.53328 4.49466 --0.533799 1.61729 4.84799 --0.450896 1.48859 4.70044 --0.458565 1.50015 4.90357 --0.788855 2.01682 6.50212 --0.494586 1.55471 5.45298 --0.387398 1.38709 5.17744 --0.308255 1.2636 5.00882 --0.269684 1.20436 5.03434 --0.241202 1.15806 5.10613 --0.217057 1.1209 5.21535 --0.250374 1.17399 5.69803 --0.152493 1.02113 5.36515 --0.100487 0.939931 5.30816 --0.0664672 0.886059 5.37559 --0.0252528 0.821255 5.39325 -0.0533997 0.69796 5.06663 -0.104297 0.618002 4.95262 -0.139218 0.563805 4.99442 -0.176762 0.504914 5.00551 -0.184383 0.492535 5.4317 -0.254455 0.382809 4.98422 -0.260818 0.373354 5.58879 -0.326111 0.270771 5.07741 -0.368744 0.204324 4.94266 -0.406992 0.143541 4.89636 -0.426868 0.11232 6.06832 -0.475982 0.0367679 5.93988 --3.0706 5.96826 -0.864175 --3.38543 6.49466 -0.887697 --3.76764 7.13304 -0.919631 --4.29092 8.008 -0.984392 --4.85786 8.9548 -1.0293 --5.52654 10.0744 -1.07109 --6.30997 11.383 -1.10227 --7.50746 13.3847 -1.19362 --8.9378 15.7749 -1.25894 --9.3192 16.412 -1.01207 --9.63774 16.9438 -0.729458 --9.9534 17.4725 -0.425883 --10.3082 18.0655 -0.105418 --13.0205 22.5988 0.0776909 --13.5041 23.4073 0.520984 --14.0305 24.2863 0.997012 --14.5412 25.1399 1.50823 --16.6944 28.7392 2.1659 --8.21188 14.5604 1.88741 --16.7012 28.7499 3.92748 --8.27295 14.6623 2.79398 --8.19383 14.5312 3.0773 --8.01217 14.2257 3.32804 --7.72584 13.7483 3.53565 --7.31787 13.066 3.68293 --3.99517 7.51309 4.7149 --3.80235 7.18918 4.72888 --3.71196 7.03899 4.82384 --3.58441 6.82638 4.8787 --3.60938 6.86678 5.07601 --2.89587 5.67542 4.51561 --2.83745 5.57685 4.60141 --2.83968 5.58157 4.75428 --5.32814 9.73989 7.81783 --1.45991 3.27557 3.3842 --1.97273 4.1318 4.12569 --1.97775 4.14149 4.254 --1.19996 2.84026 3.31696 --1.1707 2.79161 3.36253 --1.08347 2.64594 3.32272 --1.4265 3.21944 3.93013 --1.2324 2.89489 3.73088 --1.03476 2.56387 3.50659 --0.961076 2.4424 3.47308 --0.958176 2.43631 3.55576 --0.890051 2.32224 3.52312 --1.94571 4.087 5.59815 --1.94074 4.07826 5.75123 --1.9366 4.07199 5.91262 --1.93428 4.06825 6.0824 --1.93385 4.06606 6.26092 --1.93329 4.06532 6.44849 --1.92733 4.05492 6.62988 --1.92761 4.05615 6.83588 --1.2396 2.90678 5.33371 --1.19132 2.82534 5.36817 --1.13666 2.73458 5.38452 --1.08835 2.65392 5.41484 --0.608785 1.8524 4.19987 --0.566015 1.78138 4.1951 --0.526955 1.71491 4.19694 --0.484148 1.6447 4.18852 --0.455906 1.59649 4.22146 --0.423913 1.54455 4.24465 --0.394746 1.49518 4.27554 --0.380015 1.46934 4.35893 --0.358894 1.4342 4.42421 --0.390789 1.48773 4.71573 --0.426252 1.54645 5.04686 --0.379856 1.46967 5.03164 --0.422337 1.54072 5.44101 --0.32121 1.37238 5.16364 --0.275841 1.29544 5.14392 --0.219642 1.20188 5.06559 --0.181382 1.1381 5.07991 --0.186941 1.14684 5.37017 --0.132647 1.05518 5.28715 --0.0907158 0.986514 5.28858 --0.0578715 0.930251 5.34682 --0.0177723 0.864057 5.35535 -0.0232557 0.796732 5.36242 -0.0889542 0.687078 5.11291 -0.139423 0.601635 4.96873 -0.164333 0.558943 5.10875 -0.208705 0.485674 5.02048 -0.23817 0.436616 5.13886 -0.2824 0.362733 5.01788 -0.314481 0.308921 5.10434 -0.355187 0.2416 5.01019 -0.392259 0.178421 4.9546 -0.428568 0.118217 4.9176 -0.454449 0.0756297 5.98926 --2.80894 5.92249 -0.881955 --3.08922 6.42382 -0.903553 --3.39932 6.97838 -0.919683 --3.93379 7.93471 -1.01592 --4.34685 8.67451 -1.02253 --4.85313 9.57915 -1.03479 --5.6008 10.9173 -1.09399 --6.52923 12.5793 -1.15502 --7.72162 14.7133 -1.22059 --8.65956 16.3928 -1.14135 --8.93897 16.8929 -0.865222 --9.24 17.4321 -0.573573 --9.56908 18.02 -0.264628 --12.5738 23.3971 0.295474 --7.75843 14.778 2.03367 --7.86955 14.9779 2.34849 --7.85147 14.9465 2.6468 --7.83614 14.9193 2.94531 --7.81362 14.8785 3.24195 --7.69271 14.6607 3.50806 --6.82767 13.1131 3.51218 --4.24765 8.49479 5.22972 --3.55839 7.26071 4.78943 --2.69808 5.72214 4.70723 --2.69135 5.70985 4.85147 --4.85422 9.58018 7.72336 --4.84989 9.57179 7.98367 --1.12326 2.90514 3.20185 --1.10053 2.86423 3.25399 --4.02022 8.08867 7.60736 --1.46902 3.52368 3.98557 --1.45166 3.49161 4.06775 --1.18766 3.02059 3.75113 --1.11904 2.89727 3.73477 --2.5614 5.47693 6.3573 --0.936914 2.56981 3.60381 --0.94289 2.58141 3.70881 --1.05408 2.78021 4.02159 --1.01423 2.70894 4.04868 --0.906129 2.51502 3.93123 --3.07073 6.38894 8.70991 --3.27209 6.74802 9.43355 --2.8115 5.92387 8.66857 --3.21105 6.6393 9.90351 --1.95908 4.3987 7.11074 --1.78432 4.08703 6.88474 --1.11636 2.89141 5.31549 --2.60366 5.552 9.59255 --1.03658 2.74796 5.41218 --1.02086 2.71989 5.53242 --1.02212 2.72283 5.7111 --0.51292 1.81125 4.25528 --0.472281 1.73824 4.24841 --0.434293 1.67074 4.2482 --0.394554 1.5996 4.23755 --0.364681 1.54576 4.26025 --0.336516 1.49642 4.29064 --0.306718 1.44147 4.31109 --0.282143 1.39816 4.35753 --0.267365 1.37271 4.44861 --0.298081 1.42814 4.75975 --0.343088 1.50725 5.16653 --0.343361 1.50795 5.38206 --0.267927 1.37325 5.20552 --0.213897 1.27689 5.12864 --0.163514 1.18612 5.05871 --0.142426 1.14813 5.16759 --0.106173 1.08385 5.18996 --0.0850338 1.04576 5.31696 --0.0408351 0.966983 5.27912 --0.00823617 0.907211 5.32703 -0.0341876 0.831872 5.29564 -0.0686461 0.770371 5.3312 -0.141684 0.639817 4.95261 -0.174305 0.58177 4.9747 -0.197338 0.54015 5.134 -0.207592 0.522636 5.54081 -0.273065 0.404695 5.06372 -0.28782 0.37781 5.48928 -0.340121 0.284436 5.12721 -0.382019 0.210055 4.91266 -0.416277 0.148501 4.88634 -0.434845 0.115381 5.99833 -0.478162 0.0386293 5.9598 --3.74868 8.15254 6.09437 --2.55059 5.85272 4.80931 --2.53944 5.83093 4.94969 --4.45502 9.50662 7.69709 --4.40777 9.41625 7.894 --4.78061 10.132 8.70443 --2.23368 5.2452 5.14059 --2.22254 5.22329 5.27848 --4.55023 9.68994 9.23164 --1.07023 3.01264 3.65318 --1.03068 2.93638 3.68063 --0.973257 2.82625 3.67369 --0.944385 2.77142 3.71576 --0.850398 2.59093 3.62937 --0.876022 2.63987 3.7755 --0.864233 2.61567 3.84781 --0.850509 2.59034 3.92006 --0.839494 2.56954 3.99931 --3.11647 6.93796 9.38778 --2.70462 6.14859 8.69818 --2.03014 4.85343 7.2937 --2.2701 5.31316 8.13887 --2.56422 5.87731 9.18268 --2.45469 5.66789 9.17891 --1.53684 3.90764 6.8455 --2.35423 5.47387 9.49404 --0.9698 2.81838 5.53776 --0.961307 2.80205 5.68379 --0.651331 2.2084 4.83247 --0.649108 2.20442 4.97714 --0.41673 1.75951 4.29989 --0.376461 1.68096 4.28209 --0.343241 1.61708 4.28844 --0.308271 1.54958 4.28444 --0.27501 1.48654 4.28765 --0.247973 1.43518 4.31645 --0.221942 1.38383 4.34415 --0.196737 1.33494 4.38005 --0.185662 1.31359 4.48856 --0.214317 1.3689 4.81992 --0.267566 1.47231 5.32228 --0.199889 1.34147 5.1533 --0.148104 1.2417 5.06559 --0.12801 1.2038 5.17506 --0.100078 1.14899 5.23637 --0.0702148 1.09301 5.29672 --0.0281286 1.01239 5.25968 -0.0051701 0.948629 5.28865 -0.0367063 0.887886 5.33591 -0.0734993 0.817319 5.33316 -0.122441 0.723067 5.19152 -0.168677 0.633878 5.04756 -0.194978 0.583132 5.14832 -0.19822 0.578009 5.63445 -0.253823 0.470634 5.31761 -0.300706 0.380642 5.07756 -0.333989 0.317783 5.08436 -0.36877 0.250304 5.02019 -0.404414 0.182723 4.91467 -0.43736 0.119236 4.82768 -0.458625 0.0778843 5.99933 --0.503264 2.07275 2.00065 --0.499604 2.06469 2.04478 --0.499486 2.06409 2.09327 --0.486927 2.03801 2.12872 --3.23079 7.70531 5.45503 --3.17349 7.58645 5.57508 --3.6769 8.62583 6.42062 --2.38821 5.96489 4.9023 --2.36563 5.9176 5.02784 --4.04742 9.39115 7.64531 --4.17792 9.66048 8.10231 --4.7551 10.8535 9.28525 --2.04114 5.24743 5.15722 --2.02654 5.21695 5.28809 --4.62486 10.5833 10.0207 --3.96218 9.21461 9.14142 --4.91786 11.1895 11.2459 --0.938997 2.97079 3.81834 --0.952834 3.00015 3.94833 --0.879072 2.84775 3.89793 --0.853037 2.79539 3.9458 --0.781138 2.64572 3.88746 --2.84298 6.90237 8.80222 --3.92291 9.13333 11.6909 --2.12164 5.4129 7.56113 --2.1545 5.482 7.88222 --1.9912 5.14466 7.691 --2.4226 6.03477 9.13228 --2.22747 5.63152 8.86462 --2.17548 5.52359 8.99638 --1.38014 3.88224 6.82756 --2.18076 5.53589 9.62087 --0.895505 2.88095 5.65596 --0.857015 2.80272 5.70284 --0.80715 2.69955 5.70581 --2.42098 6.03029 11.9301 --0.32315 1.69834 4.33326 --0.291051 1.63251 4.33932 --0.255442 1.55949 4.32608 --0.219844 1.48638 4.31114 --0.193108 1.43055 4.33035 --0.163683 1.37005 4.33946 --0.140478 1.32125 4.37467 --0.116342 1.27134 4.40902 --0.107969 1.25405 4.53548 --0.175741 1.39351 5.13997 --0.133973 1.30777 5.10039 --0.0887647 1.21429 5.03023 --0.0618899 1.15906 5.08185 --0.0428045 1.12062 5.19947 --0.0245989 1.08319 5.33627 -0.0178785 0.994053 5.26952 -0.0543208 0.918622 5.24918 -0.0700597 0.887136 5.44207 -0.114261 0.795186 5.34101 -0.14466 0.732357 5.38527 -0.201624 0.614112 5.07336 -0.197912 0.622871 5.62853 -0.230168 0.556746 5.68947 -0.27338 0.466988 5.55055 -0.310567 0.389475 5.48927 -0.334534 0.339546 5.78524 -0.392043 0.221436 5.01256 -0.425439 0.152476 4.85635 -0.441139 0.119004 6.01834 -0.479346 0.0400518 5.98986 --0.490874 2.20975 2.02746 --0.490746 2.20923 2.07765 --0.47917 2.18333 2.1155 --3.73397 9.44012 6.04469 --2.84062 7.4473 5.15777 --3.10305 8.03276 5.67978 --2.92921 7.64632 5.64361 --3.66101 9.27808 6.86904 --2.23282 6.09333 5.01154 --2.19025 5.99717 5.10624 --2.18801 5.99284 5.26393 --3.0863 7.99658 6.90978 --3.00055 7.80368 6.98735 --1.85108 5.24174 5.17275 --1.83749 5.21125 5.30242 --3.79928 9.58512 9.20574 --0.915813 3.15606 3.80014 --0.861134 3.03386 3.78941 --0.816065 2.9341 3.79456 --0.765835 2.82117 3.7833 --0.760213 2.81014 3.87091 --0.716128 2.71107 3.86872 --0.678114 2.62697 3.87764 --2.2021 6.02207 7.83305 --1.86751 5.27735 7.20129 --1.96857 5.50159 7.69518 --1.8987 5.34608 7.73896 --2.28406 6.20655 9.10403 --2.06359 5.71433 8.73196 --2.16696 5.94422 9.33652 --2.10492 5.80523 9.44091 --1.23574 3.86775 6.83259 --2.01576 5.60568 9.7725 --1.96146 5.48594 9.91154 --2.07144 5.73085 10.6692 --1.99526 5.56184 10.7519 --2.85415 7.47403 15.1846 --0.43893 2.09333 5.13671 --0.395726 1.99733 5.11435 --0.215869 1.59537 4.4302 --0.168495 1.48889 4.34334 --0.139363 1.42398 4.34416 --0.111999 1.36257 4.35263 --0.0863402 1.30565 4.3689 --0.0650231 1.25836 4.41195 --0.0419545 1.20744 4.44475 --0.0423134 1.20797 4.63657 --0.0902629 1.31406 5.1791 --0.0393906 1.20133 5.05139 --0.0275075 1.17427 5.20764 --0.00596808 1.12772 5.30632 -0.0266172 1.05361 5.30797 -0.0636413 0.972216 5.26921 -0.0953298 0.900011 5.26767 -0.114334 0.858347 5.42119 -0.150333 0.776793 5.37804 -0.182995 0.704331 5.3725 -0.21991 0.622579 5.30632 -0.231433 0.596555 5.64434 -0.264136 0.523385 5.66497 -0.296076 0.452677 5.71402 -0.340346 0.35479 5.43302 -0.384226 0.257393 5.02014 -0.414131 0.191132 4.97457 -0.444651 0.123303 4.83765 -0.463049 0.0810912 6.06924 --3.83911 10.4954 -1.10577 --4.82376 12.879 -1.08381 --5.80716 15.256 -1.17467 --13.7545 34.4777 4.58894 --5.72166 15.0498 2.85393 --13.5386 33.9568 5.83391 --5.63721 14.8441 3.39902 --5.60497 14.7665 3.67228 --0.421663 2.22921 1.99864 --0.400632 2.17808 2.02466 --0.397965 2.17013 2.06969 --2.85957 8.12522 5.19233 --3.14197 8.809 5.75107 --2.87941 8.1729 5.60281 --2.97643 8.40605 5.93773 --2.87916 8.17268 6.00221 --2.87161 8.15479 6.19638 --3.56962 9.84279 7.52496 --2.01719 6.08746 5.19573 --2.01153 6.07365 5.34867 --2.76925 7.90666 6.87842 --2.69212 7.72036 6.95722 --1.65727 5.21611 5.17512 --1.67419 5.25763 5.36431 --0.824847 3.20461 3.75744 --0.78293 3.10223 3.76663 --0.74709 3.01476 3.78585 --0.713736 2.93566 3.80917 --0.686633 2.86855 3.84395 --1.75991 5.46412 6.6095 --2.29471 6.75726 8.18363 --1.8499 5.68117 7.25466 --2.0184 6.08857 7.94117 --1.59201 5.0577 6.97143 --1.50649 4.85093 6.93124 --1.67748 5.26401 7.66826 --1.71059 5.34435 8.01353 --1.78269 5.51756 8.50465 --1.74547 5.42951 8.65534 --1.86075 5.7064 9.34346 --1.83562 5.64662 9.56392 --1.85376 5.69036 9.95766 --1.97295 5.97879 10.7725 --1.84406 5.66664 10.6225 --1.57793 5.02222 9.86697 --2.62665 7.55749 14.88 --0.428327 2.24377 5.29062 --0.346768 2.04671 5.07756 --0.312726 1.96353 5.08006 --0.33977 2.02935 5.40288 --0.132681 1.52792 4.46585 --0.0858017 1.41439 4.35762 --0.0586788 1.3495 4.35635 --0.0340825 1.29162 4.37207 --0.0122488 1.23732 4.39594 -0.00793974 1.18802 4.43749 -0.0196381 1.16052 4.54421 --0.000323697 1.20884 4.907 --0.00570565 1.22106 5.18667 --0.0151711 1.24444 5.54472 -0.0529704 1.0803 5.21098 -0.0801013 1.01392 5.24042 -0.111431 0.936792 5.22 -0.129378 0.894715 5.36394 -0.156488 0.827656 5.39982 -0.188792 0.750265 5.3754 -0.0200671 1.15879 8.48575 -0.231552 0.646369 5.67803 -0.263894 0.56877 5.66964 -0.296165 0.490609 5.64987 -0.3325 0.402674 5.51912 -0.35435 0.350866 5.8151 -0.403064 0.232752 5.11235 -0.434726 0.156422 4.86632 -0.447619 0.123596 6.07825 -0.482401 0.0408723 5.9899 --2.24586 7.23431 -0.645164 --2.24553 7.23227 -0.504192 --2.25025 7.24638 -0.367189 --2.24429 7.23083 -0.087515 --2.25429 7.25715 0.0464152 --12.9731 35.496 -0.329017 --12.9835 35.5216 0.333606 --13.0101 35.5932 0.996757 --13.0437 35.6805 1.66288 --13.0513 35.7021 2.33029 --13.0659 35.7403 3.00013 --13.0555 35.7117 3.6677 --13.0728 35.7553 4.34259 --13.0777 35.7701 5.01792 --5.25998 15.1722 2.99123 --5.1832 14.9707 3.2491 --13.143 35.94 7.0851 --13.1479 35.9546 7.77757 --0.451719 2.50602 2.08239 --2.52273 7.96076 4.61354 --2.48692 7.86685 4.74531 --2.64311 8.27848 5.12826 --2.74503 8.54674 5.45738 --2.54909 8.03132 5.37566 --2.49008 7.87537 5.47801 --2.64527 8.28438 5.91035 --2.49768 7.89452 5.8743 --2.90469 8.9683 6.7624 --2.91101 8.98366 7.00308 --1.84002 6.16321 5.28031 --1.82239 6.11651 5.41147 --2.49829 7.89602 6.91281 --2.5364 7.99545 7.21212 --1.47048 5.19013 5.18215 --1.76037 5.95315 5.97403 --1.60277 5.53752 5.79491 --0.626266 2.96514 3.66089 --0.63882 2.99929 3.78794 --0.608589 2.91832 3.81007 --0.606611 2.91289 3.90505 --1.62769 5.60332 6.78594 --1.67427 5.7262 7.12299 --2.19055 7.08587 8.84732 --1.66963 5.71416 7.55239 --1.35804 4.89316 6.8109 --1.58536 5.4904 7.75414 --1.55212 5.40368 7.88617 --1.64725 5.65499 8.46779 --1.47041 5.18667 8.09952 --1.33627 4.83364 7.85979 --1.88347 6.27684 10.2383 --1.79537 6.04447 10.2312 --1.67227 5.72004 10.0691 --1.80036 6.05548 10.9712 --1.70629 5.80744 10.9385 --1.12851 4.28654 8.62831 --0.316734 2.15056 4.98355 --0.287374 2.07221 4.99684 --0.263886 2.01093 5.04367 --0.277975 2.04631 5.29453 --0.239962 1.94746 5.26913 --0.0771178 1.51825 4.4801 --0.041794 1.42615 4.42565 --0.0099962 1.34162 4.37816 -0.0142976 1.27927 4.38409 -0.0358287 1.22049 4.39817 -0.0550154 1.17121 4.43913 -0.0707434 1.12954 4.50777 -0.0644735 1.14476 4.76608 -0.0145912 1.27684 5.46585 -0.0549457 1.17104 5.36398 -0.0893224 1.07992 5.30799 -0.119479 0.9999 5.28862 --0.269319 2.02188 10.3635 -0.168086 0.871211 5.38208 -0.19746 0.794519 5.36816 -0.209441 0.763605 5.62853 -0.0831339 1.09644 8.39773 -0.179583 0.839778 7.38723 -0.29668 0.532978 5.63516 -0.315543 0.482958 5.90294 -0.369629 0.340162 5.15412 -0.397933 0.266573 5.06005 -0.426917 0.191404 4.89468 -0.434676 0.169907 6.16686 -0.467349 0.083822 6.10922 --0.432743 2.69449 0.367771 --0.436004 2.70419 0.417675 --0.432406 2.6946 0.471391 --0.435728 2.70329 0.521145 --0.441568 2.7201 0.569713 --3.62829 11.9281 -0.216263 --0.435504 2.70229 0.924991 --0.429419 2.68434 0.975 --0.432681 2.69403 1.0247 --0.42917 2.68324 1.07417 --0.422216 2.66317 1.12278 --0.414328 2.64201 1.17073 --2.32743 8.16926 4.4041 --3.09002 10.3724 5.54537 --2.26869 7.99986 4.67973 --2.3277 8.16977 4.93884 --2.52343 8.73451 5.4077 --2.26992 8.00072 5.22036 --2.22778 7.87973 5.33971 --2.43268 8.47196 5.86624 --2.34721 8.22591 5.92351 --2.61236 8.98984 6.60244 --2.21475 7.84067 6.08317 --2.16585 7.69957 6.18965 --1.67172 6.27299 5.3929 --1.64418 6.19251 5.50234 --1.64201 6.18658 5.66832 --1.32284 5.26547 5.12166 --1.29359 5.18163 5.20601 --0.56307 3.0698 3.58315 --0.605949 3.1948 3.78571 --0.532951 2.98226 3.69502 --0.556337 3.05084 3.85568 --1.47336 5.70043 6.52579 --1.55326 5.93015 6.95369 --1.52554 5.85166 7.08335 --1.48872 5.74307 7.18339 --1.54047 5.89387 7.57136 --1.26181 5.08917 6.87563 --1.36266 5.37974 7.43302 --1.23194 5.00302 7.19679 --1.31073 5.23002 7.71263 --1.25608 5.07188 7.74562 --1.20146 4.91355 7.77482 --1.70164 6.35884 10.091 --1.85076 6.78964 11.07 --1.69903 6.34948 10.7735 --0.744661 3.59401 6.74514 --1.53709 5.88092 10.7659 --1.03459 4.43029 8.64778 --0.95387 4.19732 8.53892 --0.233608 2.11828 4.9599 --0.217213 2.0708 5.03362 --0.220225 2.07734 5.22205 --0.169326 1.93172 5.09866 --0.142056 1.85223 5.10662 --0.11134 1.76452 5.09464 -0.0013946 1.44043 4.50308 -0.0368064 1.33532 4.40902 -0.0615572 1.26496 4.39592 -0.0820263 1.20522 4.40946 -0.0991534 1.15504 4.44997 -0.116456 1.1073 4.49928 -0.116031 1.10575 4.70992 -0.00983912 1.41564 6.05286 -0.0925998 1.17457 5.48082 -0.129003 1.06986 5.37593 -0.161943 0.973234 5.28808 --0.0384053 1.55376 8.40996 -0.209 0.837097 5.35087 -0.224882 0.792533 5.52298 -0.0912708 1.17861 8.44639 -0.131415 1.06082 8.50662 -0.226326 0.787737 7.32533 -0.320316 0.517624 5.79898 -0.369484 0.373641 5.10101 -0.375612 0.356124 5.78527 -0.4211 0.226755 4.91269 -0.442451 0.163438 4.95633 -0.45485 0.126667 6.08826 -0.484771 0.0421897 6.07983 --1.84164 7.46566 -0.806854 --2.40166 9.24922 -1.06109 --2.68454 10.1536 -1.06911 --3.0339 11.2674 -1.08294 --3.31928 12.1763 -1.02209 --3.84846 13.8613 -1.04267 --4.66899 16.4788 -1.12176 --5.50948 19.159 -1.11192 --0.521083 3.25383 0.999838 --0.515062 3.23434 1.05893 --3.72472 13.4661 3.48723 --3.68125 13.3283 3.71413 --3.67803 13.3186 3.9658 --2.76944 10.4189 4.9734 --2.58893 9.8436 4.95911 --2.56984 9.78535 5.14229 --2.42716 9.32869 5.14872 --2.15552 8.46479 4.94866 --2.053 8.13798 4.97616 --2.10186 8.29339 5.23833 --2.13818 8.40836 5.4893 --2.24625 8.75413 5.87701 --2.18144 8.54589 5.96377 --2.63447 9.9911 7.0441 --1.99493 7.95092 6.00549 --2.0345 8.07667 6.28788 --2.01142 8.00288 6.44567 --2.35975 9.11356 7.44113 --1.47695 6.30072 5.62242 --1.45226 6.22267 5.73696 --1.14077 5.22771 5.128 --0.474875 3.10558 3.54249 --0.461219 3.06343 3.59886 --0.456876 3.04815 3.68018 --0.429103 2.96 3.69617 --1.49181 6.34742 6.9881 --1.40138 6.05768 6.91923 --1.35088 5.8965 6.96662 --1.49099 6.34297 7.64622 --1.45373 6.22471 7.75405 --1.1121 5.13505 6.76992 --1.11309 5.14063 6.98181 --1.08182 5.04006 7.07499 --1.17941 5.34882 7.67942 --1.11982 5.15845 7.67523 --2.0283 8.0545 11.8029 --1.91775 7.70112 11.7091 --1.70752 7.03345 11.1445 --1.9297 7.73921 12.5821 --1.50492 6.3873 10.923 --0.614128 3.55015 6.72778 --0.882666 4.40509 8.38606 --0.841481 4.27129 8.44837 --0.175624 2.1522 4.9056 --0.157825 2.09574 4.96184 --0.140032 2.03924 5.01718 --0.129687 2.00587 5.1252 --0.0962095 1.89931 5.08039 --0.0842954 1.85931 5.178 --0.0499621 1.75103 5.11995 -0.0171876 1.53711 4.79238 -0.0842463 1.32348 4.43044 -0.106937 1.25222 4.41679 -0.126105 1.18806 4.42044 -0.142989 1.1344 4.45112 -0.158231 1.08574 4.49978 -0.163772 1.06942 4.66255 -0.118036 1.21619 5.44096 -0.151329 1.10971 5.33698 -0.161724 1.07364 5.51181 --0.113857 1.95221 9.85688 -0.0195439 1.52822 8.53161 -0.0647134 1.38452 8.46022 -0.253 0.786001 5.66791 -0.143574 1.13082 8.47676 -0.214754 0.905519 7.74361 -0.323009 0.56235 5.79395 -0.342834 0.499819 5.97263 -0.395409 0.330212 4.94489 -0.416403 0.263525 4.94044 -0.437386 0.197277 4.92466 -0.445466 0.170301 6.08697 -0.471711 0.0870455 6.1592 --1.55133 7.28812 -0.958484 --1.7467 7.98435 -0.991822 --2.00743 8.90987 -1.05249 --2.21847 9.65937 -1.0422 --2.52603 10.7528 -1.07101 --2.75422 11.564 -1.01109 --3.11449 12.8434 -0.994884 --3.64472 14.726 -1.01509 --4.45867 17.6173 -1.08651 --5.23349 20.3707 -1.03913 --3.26802 13.386 3.07715 --3.22231 13.223 3.54478 --3.19606 13.1315 3.77411 --3.20612 13.1669 4.03134 --3.35185 13.6851 4.41188 --3.27811 13.4204 4.6044 --2.60668 11.0342 5.05818 --2.38091 10.234 4.97401 --1.75454 8.00791 4.27586 --1.7385 7.95094 4.42055 --1.73974 7.95453 4.59209 --1.73673 7.94567 4.76062 --1.85128 8.35043 5.13655 --1.83602 8.29625 5.29622 --2.05527 9.07713 5.90765 --1.94904 8.69742 5.9045 --1.87543 8.43785 5.958 --1.80528 8.18737 6.00867 --1.71617 7.87212 6.01006 --1.88206 8.46002 6.59794 --1.78071 8.10036 6.5684 --1.74997 7.98884 6.70307 --1.8852 8.47188 7.27671 --1.27397 6.29934 5.84131 --0.962482 5.19342 5.13921 --0.885092 4.92023 5.0646 --0.861879 4.83634 5.14048 --0.341428 2.98749 3.64952 --0.320784 2.91337 3.67678 --0.760893 4.47922 5.2626 --0.845675 4.7763 5.70794 --1.3295 6.49591 7.63007 --2.15266 9.42019 10.9562 --1.27108 6.28931 7.8833 --1.23871 6.1726 7.99619 --0.912654 5.01445 6.88637 --0.987817 5.28348 7.42495 --1.02957 5.4322 7.84379 --0.915014 5.02288 7.5578 --0.872034 4.87055 7.59238 --1.2312 6.14476 9.62483 --1.46706 6.98296 11.1677 --1.37093 6.64167 11.0372 --1.33327 6.50979 11.2145 --0.483493 3.49237 6.69258 --0.735361 4.38657 8.43462 --0.708729 4.29012 8.56477 --0.669741 4.15329 8.62394 --0.656082 4.10239 8.84754 --0.792836 4.58782 10.1536 --0.0678091 2.01473 5.19707 --0.0527865 1.96123 5.2691 --0.00862461 1.80536 5.11291 -0.0127525 1.72752 5.12663 -0.0406747 1.62839 5.08349 -0.120219 1.34852 4.55414 -0.151197 1.23754 4.43757 -0.169363 1.17341 4.44062 -0.185764 1.11279 4.45182 -0.199944 1.06317 4.50004 -0.208574 1.03372 4.62429 -0.167774 1.17872 5.41337 -0.189194 1.10174 5.42434 -0.167928 1.17849 6.09512 --0.050083 1.9488 10.1282 -0.0865055 1.46278 8.46694 -0.123651 1.33194 8.46285 -0.28704 0.752707 5.66503 -0.198591 1.06689 8.40768 -0.257121 0.859207 7.77147 -0.34942 0.532377 5.84863 -0.366493 0.471455 6.07651 -0.414696 0.300598 4.95775 -0.436574 0.223878 4.79289 -0.45111 0.169892 5.03616 -0.462143 0.129725 6.11831 -0.486827 0.043575 6.06984 --1.24722 6.98135 -0.928608 --1.38427 7.53092 -0.935848 --1.64752 8.58266 -1.04307 --1.8338 9.32809 -1.04435 --2.05396 10.2089 -1.04619 --2.34684 11.379 -1.06896 --2.51116 12.035 -0.965642 --2.84583 13.3726 -0.938145 --2.84838 13.3839 -0.694883 --2.50786 12.0216 -0.303185 --6.31345 27.2323 -0.964829 --5.25389 22.9984 1.41216 --5.2595 23.0163 1.82693 --3.36153 15.4294 4.37956 --3.38157 15.5123 4.69029 --2.47495 11.8891 4.05461 --2.46147 11.8357 4.26802 --2.51961 12.0677 4.56582 --2.32135 11.2726 4.55145 --2.27091 11.0717 4.70743 --2.15623 10.6133 4.76598 --2.0737 10.2839 4.85722 --2.06591 10.2532 5.05593 --2.14487 10.569 5.40088 --1.50765 8.01959 4.50815 --1.53838 8.14518 4.73734 --1.54684 8.17732 4.92974 --1.56732 8.25775 5.15078 --2.16377 10.6411 6.58781 --2.0467 10.1761 6.57658 --1.8217 9.27402 6.29829 --1.5549 8.2092 5.8844 --1.51913 8.06611 5.99527 --1.56594 8.25231 6.31447 --1.82422 9.28356 7.21367 --1.25562 7.01411 5.87562 --1.58913 8.34504 7.02192 --1.15472 6.60842 5.94868 --1.0941 6.36892 5.9464 --0.759252 5.0303 5.05068 --1.01155 6.03961 6.04043 --1.0169 6.05679 6.23826 --0.721478 4.87633 5.36903 --0.658539 4.62914 5.29543 --0.695831 4.7754 5.58951 --0.667482 4.66185 5.63999 --0.734821 4.93272 6.08371 --1.08794 6.34176 7.76855 --1.06897 6.26616 7.92545 --1.46707 7.85534 9.99146 --0.966546 5.8556 7.94287 --0.966729 5.85599 8.19266 --0.903941 5.60553 8.13374 --0.80942 5.22684 7.89472 --0.784049 5.1268 8.01163 --1.25094 6.99161 10.918 --1.00354 6.0052 9.83816 --1.15142 6.59204 11.0723 --0.644636 4.57073 8.25417 --0.363144 3.44543 6.68163 --0.585383 4.33221 8.43127 --0.558413 4.22578 8.54269 --0.512596 4.04097 8.51267 --0.0434207 2.16901 5.20262 --0.0176788 2.06596 5.17871 -0.000209399 1.99548 5.21522 -0.0155698 1.932 5.26852 -0.0364804 1.84682 5.27529 -0.059958 1.75546 5.26183 -0.101306 1.58905 5.05172 -0.163083 1.34237 4.60354 -0.194156 1.21844 4.44856 -0.210261 1.1534 4.45107 -0.225601 1.09182 4.46182 -0.239538 1.03871 4.5 -0.251016 0.993165 4.56625 -0.254676 0.97737 4.75745 -0.225124 1.09436 5.52151 -0.216814 1.12853 6.03741 -0.113224 1.54022 8.46316 -0.280254 0.873911 5.63327 -0.299764 0.797736 5.65813 -0.209458 1.15738 8.5261 -0.264853 0.933499 7.84275 -0.354352 0.579961 5.86347 -0.401743 0.39127 4.8289 -0.416429 0.331982 4.90513 -0.433183 0.263051 4.87058 -0.450111 0.196547 4.84472 -0.455566 0.172708 6.06697 -0.477011 0.0892115 6.20922 --0.353361 3.89787 -0.10659 --0.424136 4.21859 -0.116968 --0.450624 4.34103 -0.0670755 --0.483419 4.49182 -0.0196436 --0.518584 4.65292 0.0307981 --0.541248 4.75491 0.0976956 --2.06961 11.7353 -1.01105 --2.33719 12.9565 -0.982935 --2.71693 14.6927 -0.981032 --2.37764 13.1418 -0.533559 --4.17395 21.3436 -1.10517 --2.19201 12.2958 0.229416 --2.19704 12.317 0.448671 --2.19652 12.3139 0.669093 --2.19514 12.3087 0.889212 --2.19789 12.3178 1.10925 --2.19883 12.3238 1.32953 --2.20623 12.3554 1.5514 --2.20804 12.3635 1.77328 --2.20903 12.3686 1.99561 --2.84842 15.2904 3.61831 --2.84076 15.2534 3.89282 --2.71016 14.6556 4.05136 --2.73132 14.7538 4.34732 --2.68766 14.5529 4.57533 --2.11027 11.9172 4.15391 --1.94784 11.174 4.17134 --1.93938 11.1375 4.37614 --1.88958 10.91 4.52052 --1.78657 10.4411 4.57525 --1.76745 10.3504 4.75132 --1.7654 10.3404 4.95655 --1.76551 10.344 5.17004 --1.97903 11.3179 5.79805 --1.31943 8.30542 4.69584 --1.82872 10.6318 5.95893 --1.41999 8.76476 5.27865 --1.41575 8.74249 5.46135 --1.48918 9.08163 5.83846 --1.42251 8.77453 5.87592 --1.42432 8.78308 6.08607 --1.32551 8.33369 6.02402 --1.34841 8.43768 6.29227 --1.51323 9.18647 6.99026 --0.986774 6.78643 5.59714 --1.37187 8.54192 7.00897 --1.37113 8.54213 7.23613 --1.90521 10.9787 9.31474 --0.632571 5.16956 5.06005 --0.618992 5.10741 5.15805 --1.58411 9.51363 9.02659 --0.693761 5.44577 5.76008 --0.527771 4.69005 5.24706 --0.567021 4.8688 5.56669 --0.538598 4.74059 5.60478 --0.529849 4.69682 5.72383 --0.551769 4.80012 5.99951 --0.552083 4.80203 6.17884 --0.529996 4.69987 6.24903 --0.795265 5.91023 7.83749 --0.775348 5.81844 7.97245 --0.747631 5.6921 8.06763 --0.674239 5.35808 7.89442 --0.685966 5.41204 8.21913 --0.650731 5.24737 8.25847 --0.920272 6.47935 10.2967 --0.885511 6.31943 10.4111 --0.782809 5.85079 10.0472 --0.499038 4.55619 8.32027 --0.240993 3.38003 6.64426 --0.439933 4.28494 8.44412 --0.408998 4.14754 8.50217 --0.39828 4.09776 8.72453 -0.0246739 2.16562 5.25754 -0.0557811 2.0231 5.15234 -0.0747661 1.93912 5.16077 -0.0828044 1.90081 5.26754 -0.0618531 1.99555 5.69523 -0.141815 1.63056 5.02799 -0.150707 1.59 5.13096 -0.199995 1.36584 4.73722 -0.236235 1.20086 4.46889 -0.251098 1.13238 4.46127 -0.265376 1.06984 4.47147 -0.276255 1.01589 4.50921 -0.286672 0.96938 4.57502 -0.29563 0.929869 4.67894 -0.236258 1.19791 6.10486 -0.0193498 2.18475 11.085 -0.297205 0.922123 5.63499 -0.314602 0.844109 5.66066 -0.329664 0.774634 5.73418 -0.338289 0.735857 6.0341 -0.360646 0.631928 5.90763 -0.377259 0.55517 5.9778 -0.419341 0.365272 4.87213 -0.434287 0.297965 4.86805 -0.449163 0.230615 4.84284 -0.452106 0.215971 6.04523 -0.470751 0.128756 6.00836 -0.488885 0.0439468 6.07982 --0.741286 6.58403 -0.921544 --0.826249 7.03368 -0.918169 --1.02975 8.11424 -1.05922 --1.15958 8.79972 -1.06781 --1.30648 9.58367 -1.07343 --1.49553 10.5821 -1.09378 --1.70631 11.7009 -1.10011 --1.83867 12.405 -0.999956 --2.13819 13.9937 -1.00209 --2.77188 17.3518 -1.16903 --3.18714 19.5563 -1.09279 --2.22278 14.4397 3.58993 --2.31073 14.9041 3.94703 --2.218 14.4107 4.38461 --2.24073 14.5324 4.68592 --1.63257 11.306 4.08178 --2.27707 14.7274 5.29619 --1.77568 12.0672 4.75329 --1.739 11.8698 4.9237 --1.72932 11.8198 5.14047 --1.35131 9.81693 4.63499 --1.33284 9.71641 4.79443 --1.31109 9.60436 4.9477 --1.35437 9.83347 5.24655 --1.23803 9.2109 5.17252 --1.25546 9.3073 5.41577 --1.24738 9.26571 5.5979 --1.18145 8.91381 5.62106 --1.23967 9.22354 5.98991 --1.30766 9.5843 6.40497 --1.29966 9.54056 6.60432 --1.29084 9.49377 6.80382 --1.25653 9.30983 6.91851 --1.14846 8.73635 6.77262 --1.0802 8.37591 6.74792 --1.10666 8.51779 7.06779 --1.3316 9.70788 8.17621 --0.484442 5.2199 5.00169 --0.464769 5.11142 5.06298 --0.716557 6.44649 6.311 --0.466288 5.11978 5.37056 --0.454611 5.05902 5.47401 --0.423556 4.89308 5.4829 --0.426046 4.90895 5.65775 --0.418342 4.86435 5.77895 --0.417243 4.85736 5.94239 --0.397963 4.75842 6.01344 --0.396754 4.75283 6.18492 --0.376142 4.64329 6.24626 --0.357192 4.53913 6.31286 --1.30679 9.57041 12.6049 --0.615902 5.91275 8.42909 --0.564591 5.63961 8.34382 --0.763713 6.69586 10.04 --0.561003 5.62147 8.87135 --0.429353 4.92171 8.15082 --0.581867 5.73248 9.64646 --0.332788 4.41143 7.91027 --0.338225 4.43743 8.22511 --0.12877 3.33091 6.63998 --0.31676 4.3244 8.62073 --0.280461 4.13174 8.58265 -0.106879 2.08176 4.98192 -0.121238 2.00357 5.00051 -0.134247 1.93531 5.03544 -0.131702 1.94816 5.25048 -0.110824 2.05926 5.7046 -0.127566 1.97085 5.72207 -0.188477 1.65004 5.1537 -0.209375 1.5363 5.07027 -0.214225 1.5093 5.21916 -0.276195 1.18139 4.48893 -0.289997 1.11195 4.48086 -0.301276 1.04956 4.49047 -0.311911 0.992112 4.51817 -0.321267 0.944643 4.58353 -0.329164 0.904176 4.68711 -0.120599 2.0038 9.82766 -0.31621 0.970681 5.64619 -0.331192 0.887372 5.6431 -0.345711 0.810985 5.67782 -0.355301 0.760232 5.87921 -0.370113 0.686181 5.96126 -0.386511 0.59502 5.92301 -0.420848 0.415559 5.01792 -0.436327 0.332317 4.85533 -0.44852 0.267636 4.88057 -0.461273 0.198883 4.84473 -0.465731 0.174595 6.07692 -0.482186 0.0908965 6.22923 --0.554107 6.66813 -0.999838 --0.654218 7.3006 -1.05004 --0.739644 7.84222 -1.0535 --0.841658 8.49081 -1.06414 --0.967837 9.28681 -1.08481 --1.10186 10.1343 -1.08794 --1.25465 11.1017 -1.08355 --1.46614 12.4413 -1.10838 --1.71104 13.9893 -1.11734 --2.04273 16.0903 -1.14544 --2.44694 18.6471 -1.15193 --4.71241 32.9785 -1.044 --4.75309 33.2361 -0.47103 --1.55523 12.9963 4.40192 --1.40893 12.0756 4.62045 --1.52227 12.7935 5.08275 --1.82386 14.6978 5.9776 --1.7712 14.3671 6.14978 --0.968877 9.28937 4.51548 --0.934652 9.07167 4.61682 --1.08757 10.0392 5.20883 --0.956749 9.21313 5.05473 --0.95566 9.20451 5.24588 --0.909843 8.91578 5.3046 --0.913895 8.93729 5.51051 --0.925387 9.01613 5.7508 --1.05018 9.80054 6.38651 --1.39215 11.9674 7.85377 --0.9902 9.42224 6.61786 --1.0164 9.58454 6.94543 --0.822044 8.3565 6.38855 --0.887436 8.77294 6.87753 --0.806516 8.26312 6.74849 --0.986761 9.40094 7.78783 --0.969829 9.29105 7.95875 --0.312393 5.13355 4.98706 --0.311439 5.1254 5.12693 --0.267931 4.85522 5.05158 --0.308537 5.10849 5.4159 --0.288189 4.97901 5.45911 --0.296276 5.03301 5.66795 --0.316788 5.1589 5.95583 --0.264837 4.83345 5.80797 --0.234594 4.63958 5.77849 --0.267765 4.84869 6.17158 --0.244317 4.70513 6.19754 --0.232649 4.62801 6.29479 --0.581107 6.8326 9.09788 --0.442288 5.95676 8.31461 --0.459559 6.06402 8.71613 --0.362881 5.45454 8.19532 --0.357406 5.41779 8.41116 --0.300029 5.05438 8.17201 --0.276059 4.9018 8.21904 --0.212378 4.49891 7.87928 --0.471783 6.13571 10.7492 --0.199229 4.4132 8.28983 --0.0197286 3.27893 6.63486 --0.158307 4.15502 8.43257 -0.168424 2.09312 4.90189 -0.177105 2.0351 4.95596 -0.182452 2.00197 5.06289 -0.182131 2.00332 5.25106 -0.193078 1.93363 5.29498 -0.204716 1.85936 5.3284 -0.209648 1.83353 5.48073 -0.221333 1.75963 5.52175 -0.264923 1.48074 5.00889 -0.273023 1.4287 5.0816 -0.316032 1.15991 4.50877 -0.327654 1.08809 4.49051 -0.336874 1.02479 4.49968 -0.346447 0.966384 4.52684 -0.353743 0.918019 4.59185 -0.361276 0.872574 4.67555 -0.142275 2.25222 11.2803 -0.349686 0.942454 5.68402 -0.364118 0.85166 5.65077 -0.376759 0.77685 5.69473 -0.378527 0.76438 6.17252 -0.39749 0.643218 5.93738 -0.411948 0.552626 5.90822 -0.439405 0.37754 4.96171 -0.451437 0.300447 4.85811 -0.461876 0.237829 4.92271 -0.464955 0.216227 5.98526 -0.478734 0.129286 5.98836 -0.49194 0.0447673 6.07986 --0.298467 6.22641 -1.0398 --0.346795 6.6027 -1.03524 --0.402677 7.03642 -1.03456 --0.472071 7.5786 -1.04766 --0.539416 8.10376 -1.0374 --0.633931 8.84364 -1.0588 --0.738583 9.66383 -1.07128 --0.866154 10.6517 -1.08798 --1.0088 11.7704 -1.09303 --1.18774 13.167 -1.10324 --1.41321 14.9203 -1.11485 --1.71995 17.3176 -1.1447 --2.11401 20.3898 -1.16175 --3.75015 33.1535 -0.75369 --0.84444 10.4824 4.23009 --1.15397 12.8956 5.22343 --1.09677 12.4455 5.31957 --0.779738 9.97318 4.659 --0.678439 9.1865 4.55441 --0.663128 9.06809 4.69312 --0.687813 9.25845 4.96142 --0.628098 8.78961 4.94483 --0.62836 8.79193 5.13265 --0.7135 9.45975 5.65051 --0.711102 9.43934 5.84805 --0.792232 10.0724 6.39824 --0.731069 9.59545 6.36141 --0.6969 9.32895 6.42941 --0.633909 8.83475 6.35068 --0.566791 8.31139 6.23511 --0.558293 8.24469 6.39684 --0.61567 8.69294 6.91004 --0.59502 8.53175 7.02199 --0.599858 8.5708 7.27701 --0.159364 5.134 4.89949 --0.149715 5.05732 4.98301 --0.14469 5.01853 5.09663 --0.153617 5.09168 5.30634 --0.178889 5.28591 5.63143 --0.136327 4.95363 5.49627 --0.160819 5.14347 5.83508 --0.162296 5.15887 6.02206 --0.119811 4.8265 5.86458 --0.122664 4.85162 6.06381 --0.719306 9.49855 11.2676 --0.108062 4.733 6.29835 --0.384922 6.88532 8.98433 --0.371469 6.78442 9.15023 --0.623639 8.7462 11.8872 --0.216271 5.57603 8.19422 --0.181745 5.30744 8.09953 --0.18983 5.37052 8.4507 --0.136188 4.94993 8.12629 --0.0956024 4.63783 7.93048 --0.08065 4.51656 8.01106 --0.0476266 4.25874 7.86888 --0.0342879 4.15899 7.97705 --0.0490228 4.27096 8.45621 --0.0120913 3.98223 8.24165 -0.0156956 3.768 8.14281 -0.242404 2.00451 4.96487 -0.250657 1.93999 5.00855 -0.247471 1.95832 5.23235 -0.254032 1.91263 5.33008 -0.118803 2.96187 8.03245 -0.268703 1.7992 5.48747 -0.298385 1.56488 5.10766 -0.31234 1.45244 5.02181 -0.321474 1.3864 5.05625 -0.351657 1.14959 4.56643 -0.363193 1.06234 4.50007 -0.370593 1.00161 4.51814 -0.378924 0.939764 4.53526 -0.385038 0.888958 4.59009 -0.389936 0.848114 4.70261 -0.376889 0.953673 5.519 -0.385214 0.888173 5.60378 -0.394864 0.813568 5.64825 -0.402544 0.751466 5.78043 -0.405971 0.72143 6.16916 -0.423258 0.592852 5.86351 -0.430476 0.533545 6.1119 -0.454965 0.339684 4.90511 -0.463981 0.272698 4.92047 -0.473126 0.198191 4.80484 -0.475833 0.176499 6.06695 -0.487114 0.0906108 6.20929 -0.31595 1.87776 -0.987578 -0.30907 1.94626 -0.990014 -0.303498 2.00243 -0.97663 --0.0304712 5.40719 -1.03148 --0.0591074 5.69504 -1.02648 --0.0899812 6.01211 -1.02151 --0.124433 6.36944 -1.01809 --0.168675 6.81396 -1.02823 --0.21693 7.30795 -1.03678 --0.277089 7.92035 -1.05861 --0.338465 8.54479 -1.0618 --0.41391 9.31797 -1.07625 --0.498888 10.1814 -1.08197 --0.604331 11.2533 -1.09645 --0.723638 12.4761 -1.09856 --0.879884 14.0657 -1.11313 --1.08701 16.1722 -1.14037 --1.34339 18.788 -1.15217 --3.3343 39.0753 -0.71706 --0.523916 10.426 3.70834 --0.51744 10.3582 3.88546 --0.516646 10.3447 4.07796 --0.511792 10.2994 4.26189 --0.474454 9.91954 4.33416 --0.494367 10.1226 4.60111 --0.49833 10.1616 4.81648 --0.491421 10.0846 4.99045 --0.472497 9.89413 5.11697 --0.416755 9.32795 5.07457 --0.381889 8.97548 5.10896 --0.445384 9.6211 5.61006 --0.412759 9.28101 5.64876 --0.716358 12.3771 7.47275 --0.754624 12.7618 7.96073 --0.735651 12.5691 8.14413 --0.737033 12.5801 8.44467 --0.302901 8.16368 6.0259 --0.284035 7.97483 6.10378 --0.355288 8.69801 6.78363 --0.359231 8.73565 7.03161 --0.344174 8.58109 7.14897 --0.0066509 5.14511 4.82431 -0.00408701 5.03808 4.88359 --0.029805 5.38286 5.30122 --0.00521209 5.13001 5.24866 --0.0546761 5.63874 5.83803 --0.0720239 5.81467 6.16798 --0.116879 6.26653 6.76913 --0.0112939 5.19126 5.94895 --0.00226992 5.10392 6.03921 -0.0236672 4.84212 5.94963 -0.0333658 4.7343 6.01206 --0.38471 8.99049 10.8567 --0.387397 9.00921 11.23 --0.409015 9.2313 11.8578 --0.372787 8.85683 11.7944 --0.131036 6.40689 9.09167 --0.0235176 5.31388 7.95736 --0.0266191 5.34609 8.25846 -0.00555848 5.0112 8.05802 -0.0316058 4.75234 7.94707 -0.0483725 4.58217 7.95426 -0.0631855 4.42824 7.98299 -0.073424 4.32679 8.09366 -0.0738382 4.31927 8.36666 -0.099987 4.04907 8.1889 -0.116132 3.88557 8.18845 -0.298326 2.03649 4.92941 -0.307092 1.94966 4.92873 -0.192032 3.12006 7.57064 -0.291276 2.1133 5.65897 -0.296893 2.05284 5.74111 -0.306223 1.95837 5.74862 -0.344368 1.56883 5.00075 -0.354353 1.47155 4.95272 -0.35702 1.44215 5.09103 -0.364614 1.36822 5.10624 -0.387799 1.13227 4.605 -0.396854 1.03817 4.51888 -0.403012 0.974004 4.52691 -0.408526 0.914791 4.55313 -0.414396 0.860487 4.59782 -0.418414 0.821163 4.71969 -0.406976 0.933091 5.60563 -0.413303 0.867183 5.69996 -0.422431 0.773156 5.63556 -0.421665 0.778769 6.23192 -0.434725 0.646495 5.92748 -0.443887 0.552739 5.86857 -0.449595 0.497958 6.18602 -0.468387 0.310399 4.95783 -0.474851 0.238062 4.90279 -0.482118 0.165136 4.79651 -0.485155 0.132377 6.05836 -0.493999 0.045144 6.08994 -0.371581 1.87122 -1.01123 -0.368552 1.91947 -0.992564 -0.364354 1.98219 -0.986921 -0.359784 2.03834 -0.972842 -0.172744 4.77601 -1.03204 -0.156094 5.01381 -1.03055 -0.137246 5.28167 -1.03223 -0.119452 5.54992 -1.02503 -0.0980633 5.85829 -1.02209 -0.0703789 6.26231 -1.03984 -0.0410189 6.68788 -1.04984 -0.0095792 7.14496 -1.05387 --0.0298484 7.71911 -1.07354 --0.0690348 8.29622 -1.07373 --0.120188 9.04064 -1.09251 --0.176022 9.85609 -1.10046 --0.243615 10.8415 -1.1129 --0.319492 11.9376 -1.11053 --0.422865 13.4412 -1.1346 --0.550595 15.3034 -1.15669 --0.725886 17.8537 -1.19841 --0.915467 20.6278 -1.17448 --2.02557 36.7927 -0.935142 --2.0928 37.768 -0.324424 --0.224083 10.5278 3.43554 --0.218474 10.4458 3.60966 --0.22494 10.5425 3.83081 --0.243425 10.8182 4.10849 --0.220759 10.4758 4.20964 --0.208179 10.2955 4.35212 --0.205065 10.2544 4.53825 --0.198605 10.1539 4.70337 --0.194496 10.0965 4.8841 --0.263962 11.101 5.49449 --0.231972 10.6351 5.52398 --0.200321 10.1807 5.5426 --0.211097 10.3351 5.82981 --0.131689 9.18284 5.48827 --0.600664 16.0013 9.17067 --0.370352 12.6504 7.74068 --0.0889501 8.55134 5.75064 --0.0844629 8.48474 5.90949 --0.0786824 8.40672 6.06229 --0.126083 9.09608 6.696 -0.0936418 5.89082 4.83396 -0.0969816 5.8567 4.95867 --0.0709768 8.29553 6.82125 -0.114468 5.59351 5.07307 -0.136495 5.26746 4.97768 -0.160788 4.91448 4.84756 -0.157734 4.97005 5.03367 -0.102689 5.7557 5.8398 -0.11566 5.57209 5.85449 --0.247952 10.8549 10.7953 --0.239511 10.7337 11.0315 -0.164594 4.86581 5.7095 -0.159849 4.92446 5.93532 -0.144775 5.15033 6.34439 -0.0233503 6.90697 8.42276 --0.182436 9.88796 12.0053 --0.148989 9.40651 11.8445 --0.137714 9.23552 12.0304 --0.127636 9.09248 12.2524 --0.116052 8.92602 12.4491 -0.114831 5.57282 8.41101 -0.130844 5.34311 8.36978 -0.137814 5.23657 8.49494 -0.1574 4.95492 8.36153 -0.180393 4.61897 8.12845 -0.194302 4.42059 8.08939 -0.202067 4.31184 8.19132 -0.214765 4.12605 8.16176 -0.22482 3.97634 8.18911 -0.237415 3.78972 8.14287 -0.276919 3.21166 7.31709 -0.272457 3.28114 7.74081 -0.34852 2.18037 5.68554 -0.355169 2.09064 5.70465 -0.359129 2.02034 5.76816 -0.30929 2.74449 7.80541 -0.323065 2.54968 7.65634 -0.398832 1.44388 4.97484 -0.398725 1.44642 5.2075 -0.405635 1.34816 5.15614 -0.422341 1.10607 4.62441 -0.429394 1.01206 4.53749 -0.433552 0.947984 4.54503 -0.437067 0.888866 4.57075 -0.440998 0.835141 4.62474 -0.443441 0.80137 4.77567 -0.436607 0.8931 5.60392 -0.442263 0.818732 5.6483 -0.443936 0.793848 6.01747 -0.448952 0.721375 6.13956 -0.456988 0.601816 5.90321 -0.470528 0.402163 4.82894 -0.46806 0.44446 6.08062 -0.479888 0.272256 4.89056 -0.484844 0.204456 4.90479 -0.485999 0.177887 6.08705 -0.491606 0.0888984 6.07939 -0.425979 1.89182 -0.994758 -0.424151 1.96103 -0.997059 -0.421017 2.02473 -0.99057 -0.327147 4.44691 -1.02797 -0.318351 4.68267 -1.03775 -0.309203 4.912 -1.03609 -0.299209 5.16045 -1.03426 -0.288069 5.45665 -1.0419 -0.275225 5.77416 -1.04646 -0.262206 6.12183 -1.05002 -0.245731 6.52856 -1.06007 -0.227404 7.0043 -1.07641 -0.208417 7.50168 -1.08211 -0.186615 8.0684 -1.0885 -0.160858 8.73545 -1.09912 -0.129432 9.5409 -1.11723 -0.0945893 10.4383 -1.12574 -0.0530042 11.5056 -1.13458 -0.00225276 12.8021 -1.14465 --0.0618195 14.4581 -1.16317 --0.155054 16.8422 -1.21982 --0.243657 19.1323 -1.18246 --0.627102 28.9746 -0.77509 --0.615584 28.6908 -0.255238 -0.0895227 10.5234 3.52764 -0.0877367 10.5778 4.13492 -0.0870079 10.5881 4.34027 -0.0799694 10.7559 4.60077 -0.104887 10.1258 4.58784 -0.0761846 10.8675 5.06527 -0.0647516 11.1575 5.39736 -0.0793701 10.7831 5.4691 -0.132444 9.40265 5.28736 -0.142285 9.16359 5.37349 -0.143774 9.11291 5.54629 -0.172264 8.38513 5.36765 -0.175067 8.30795 5.51341 -0.177771 8.24524 5.66767 -0.170407 8.43842 5.97338 -0.27321 5.79378 4.55269 -0.272497 5.80724 4.70171 -0.270668 5.86663 4.88532 -0.269533 5.8889 5.04944 -0.27739 5.68728 5.05883 -0.274921 5.73588 5.24668 -0.268636 5.91439 5.54109 -0.311709 4.79445 4.81581 -0.308076 4.90437 5.0452 -0.304655 4.98547 5.26009 -0.299623 5.11966 5.53204 -0.302674 5.01756 5.60054 -0.294982 5.21924 5.95589 -0.290579 5.34579 6.25655 -0.323154 4.49666 5.57885 -0.298832 5.11115 6.38923 -0.30225 5.02981 6.49244 -0.30501 4.95384 6.6019 -0.229715 6.87364 9.0523 -0.323373 4.48766 6.44746 -0.255993 6.19621 8.7944 -0.338096 4.10703 6.35491 -0.282036 5.53423 8.48357 -0.289418 5.35675 8.514 -0.301318 5.04901 8.35089 -0.316265 4.66626 8.05439 -0.322624 4.50545 8.0758 -0.328673 4.35536 8.1108 -0.334348 4.1997 8.13406 -0.375967 3.1495 6.57012 -0.348367 3.83879 8.07428 -0.371788 3.24401 7.23551 -0.347345 3.85349 8.73198 -0.412124 2.20788 5.63023 -0.415618 2.13076 5.67716 -0.418967 2.03672 5.68609 -0.382301 2.95639 8.14143 -0.436927 1.57527 5.00076 -0.438144 1.55396 5.1588 -0.441495 1.462 5.12878 -0.442962 1.41475 5.22952 -0.447607 1.2987 5.12007 -0.456796 1.06444 4.59561 -0.460754 0.983512 4.54621 -0.462851 0.91853 4.55311 -0.465485 0.860928 4.58807 -0.466722 0.811326 4.6612 -0.468165 0.777092 4.82178 -0.459931 0.990911 6.34898 -0.467955 0.779412 5.65529 -0.467823 0.780505 6.22204 -0.471585 0.680171 6.16549 -0.481198 0.454377 4.98429 -0.484216 0.365422 4.79252 -0.486492 0.301863 4.82828 -0.489207 0.232742 4.79303 -0.489081 0.225725 6.14514 -0.492766 0.13096 5.95836 -0.496057 0.0455158 6.09992 -0.482289 1.86225 -0.996551 -0.481075 1.92471 -0.992516 -0.480869 1.98719 -0.986986 -0.480116 2.05746 -0.986743 -0.479436 2.12882 -0.984652 -0.478594 2.21467 -0.993988 -0.461787 3.97351 -1.02488 -0.45958 4.15216 -1.02536 -0.457988 4.34088 -1.02445 -0.456117 4.5584 -1.02966 -0.452977 4.80484 -1.0397 -0.451005 5.05361 -1.04174 -0.447718 5.33042 -1.04637 -0.4453 5.63821 -1.05232 -0.442232 5.98502 -1.061 -0.438768 6.32455 -1.0552 -0.433668 6.77048 -1.07016 -0.429075 7.25768 -1.08135 -0.424536 7.79521 -1.08901 -0.417784 8.41207 -1.09777 -0.410457 9.16885 -1.11713 -0.402445 9.99645 -1.12527 -0.392658 10.9935 -1.13744 -0.382968 12.0737 -1.1295 -0.36732 13.62 -1.15781 -0.349268 15.5067 -1.18008 -0.295346 21.0532 -1.21385 -0.264002 24.2363 -1.12167 -0.249436 25.7657 -0.803033 -0.255415 25.0944 -0.316397 -0.390735 11.0358 4.37348 -0.390889 11.1087 4.60878 -0.383717 11.8099 5.06574 -0.381999 11.9811 5.36018 -0.381692 11.9962 5.60444 -0.390361 11.1359 5.49844 -0.376565 12.4547 6.28592 -0.377536 12.3601 6.50254 -0.409765 9.07788 5.42712 -0.411541 8.91908 5.54398 -0.413389 8.69726 5.6239 -0.414954 8.51946 5.72157 -0.413767 8.63491 5.98451 -0.414838 8.52944 6.12417 -0.415365 8.46334 6.28823 -0.415802 8.41178 6.46228 -0.416576 8.36549 6.64178 -0.44202 5.80811 5.06637 -0.441999 5.76815 5.1907 -0.427714 7.23598 6.45212 -0.442518 5.76043 5.50026 -0.452269 4.74829 4.84495 -0.452936 4.68847 4.9337 -0.448419 5.14791 5.47406 -0.449149 5.00921 5.50974 -0.449258 5.00286 5.66464 -0.452132 4.74058 5.57764 -0.454665 4.50506 5.50403 -0.455544 4.36961 5.52453 -0.457839 4.14693 5.44649 -0.456752 4.21586 5.68169 -0.451486 4.79632 6.51675 -0.453236 4.56464 6.43866 -0.453953 4.55047 6.61858 -0.456531 4.22377 6.40559 -0.457913 4.08069 6.41454 -0.444298 5.49633 8.56403 -0.447046 5.13995 8.3394 -0.447612 5.0889 8.54406 -0.452536 4.62961 8.12855 -0.453769 4.45174 8.1234 -0.456106 4.29094 8.14003 -0.458914 3.97071 7.87606 -0.466705 3.25859 6.87736 -0.464069 3.43286 7.45421 -0.461319 3.72312 8.30607 -0.468292 3.06498 7.28249 -0.47724 2.17325 5.65837 -0.468591 3.02632 7.79673 -0.478708 1.982 5.66689 -0.483087 1.58115 4.91268 -0.484027 1.52711 4.97702 -0.483883 1.4572 5.0031 -0.484589 1.37078 4.98062 -0.485651 1.33247 5.09905 -0.483055 1.53839 6.03017 -0.488639 1.04234 4.63365 -0.488996 0.953137 4.55464 -0.490092 0.88819 4.56105 -0.490908 0.833162 4.60521 -0.491083 0.782598 4.67789 -0.491103 0.742449 4.81864 -0.491374 0.75553 5.28397 -0.490406 0.823949 6.19522 -0.49119 0.747744 6.31782 -0.493676 0.504967 5.10918 -0.494606 0.402715 4.82897 -0.495458 0.33479 4.81549 -0.495429 0.26785 4.8208 -0.496821 0.20424 4.89481 -0.496041 0.178279 6.08697 -0.497717 0.0900253 6.08931 -0.537262 1.89312 -0.994708 -0.539048 1.95545 -0.989884 -0.540286 2.02555 -0.990546 -0.541154 2.08909 -0.982472 -0.5433 2.17471 -0.992916 -0.544252 2.23943 -0.981196 -0.546485 2.32626 -0.987295 -0.547412 2.40759 -0.984504 -0.549244 2.5044 -0.991995 -0.5516 2.61004 -1.00283 -0.562975 3.16244 -1.01493 -0.564754 3.27409 -1.00643 -0.567549 3.41995 -1.01494 -0.570977 3.55921 -1.01402 -0.573525 3.71732 -1.01843 -0.576587 3.86685 -1.01321 -0.58035 4.04498 -1.01692 -0.583668 4.23224 -1.01917 -0.587664 4.43059 -1.01956 -0.592484 4.67634 -1.03372 -0.597936 4.9323 -1.04358 -0.603144 5.20055 -1.04883 -0.608515 5.48793 -1.05232 -0.615173 5.79643 -1.05307 -0.621769 6.1538 -1.05942 -0.629785 6.5512 -1.06606 -0.638943 7.01742 -1.0792 -0.649615 7.52492 -1.08738 -0.661239 8.13127 -1.10344 -0.674232 8.75939 -1.10357 -0.689558 9.57596 -1.12362 -0.706491 10.4346 -1.12362 -0.728438 11.4921 -1.13067 -0.754101 12.8099 -1.14447 -0.786875 14.477 -1.16443 -0.829838 16.6436 -1.19217 -0.882219 19.2623 -1.19581 -0.986832 24.5491 -0.933403 -0.995118 24.9789 -0.529032 -1.00137 25.2915 -0.105548 -0.722377 11.3024 4.34807 -0.684449 9.37333 3.95556 -0.680288 9.15015 4.06161 -0.683729 9.3591 4.31431 -0.681914 9.2715 4.46672 -0.681434 9.23796 4.63899 -0.684444 9.35789 4.87616 -0.682215 9.27966 5.03492 -0.683381 9.3531 5.26268 -0.680696 9.18667 5.38224 -0.734357 11.9098 6.93836 -0.676518 9.00243 5.68632 -0.725021 11.4756 7.23118 -0.687239 9.55515 6.40641 -0.683619 9.37352 6.52162 -0.663589 8.32059 6.0992 -0.663498 8.35686 6.32429 -0.668152 8.59644 6.69011 -0.666488 8.47901 6.82797 -0.6176 5.99968 5.27952 -0.62877 6.58311 5.87133 -0.63292 6.78298 6.20457 -0.603409 5.32116 5.23287 -0.592108 4.70647 4.87989 -0.588426 4.56208 4.89655 -0.639306 7.14402 7.32112 -0.605633 5.41861 5.96536 -0.612554 5.80218 6.50659 -0.590919 4.65056 5.56971 -0.589203 4.58415 5.66451 -0.586849 4.46069 5.70025 -0.583901 4.29681 5.68892 -0.580571 4.17409 5.71833 -0.673608 8.91644 11.44 -0.587456 4.49717 6.45518 -0.586288 4.43824 6.57984 -0.582694 4.24878 6.53745 -0.58062 4.17591 6.64288 -0.576928 4.00092 6.60908 -0.600081 5.16013 8.50757 -0.590335 4.6752 8.06277 -0.588922 4.60967 8.23612 -0.578397 4.05491 7.61635 -0.568178 3.553 7.03132 -0.565338 3.40731 7.02281 -0.564305 3.34945 7.16924 -0.56298 3.30195 7.34201 -0.5683 3.54766 8.11462 -0.542433 2.20904 5.63017 -0.540936 2.13222 5.67712 -0.538535 2.04199 5.6953 -0.56266 3.27997 8.91753 -0.528669 1.54003 4.90772 -0.527788 1.48855 4.98085 -0.526362 1.38591 4.91193 -0.53017 1.61572 5.82692 -0.528129 1.53094 5.85444 -0.526476 1.43762 5.85164 -0.51858 1.0074 4.63299 -0.517176 0.92175 4.56283 -0.515637 0.861913 4.58812 -0.514212 0.803507 4.62214 -0.513628 0.755949 4.714 -0.512738 0.703881 4.79548 -0.51154 0.647293 4.86636 -0.513557 0.776271 6.19243 -0.511718 0.6693 6.07626 -0.507476 0.445827 4.90476 -0.505727 0.370608 4.8423 -0.504765 0.304252 4.85819 -0.50318 0.232405 4.78305 -0.502984 0.23183 6.30505 -0.501 0.131947 6.00842 -0.499053 0.0448301 6.10995 -0.591333 1.85968 -0.996496 -0.594113 1.9219 -0.992474 -0.59796 1.98514 -0.986906 -0.601581 2.06182 -0.993615 -0.604512 2.12629 -0.984598 -0.608661 2.21183 -0.99395 -0.612058 2.28415 -0.987826 -0.615912 2.36424 -0.986194 -0.620731 2.46082 -0.994892 -0.625181 2.55083 -0.994754 -0.630094 2.64867 -0.998009 -0.635085 2.74765 -0.998416 -0.640154 2.84777 -0.996077 -0.645241 2.94803 -0.990742 -0.650882 3.07468 -0.998826 -0.658056 3.21019 -1.00836 -0.663866 3.33921 -1.00865 -0.670698 3.46838 -1.00495 -0.677706 3.6173 -1.00714 -0.68629 3.79274 -1.01875 -0.694453 3.96069 -1.02027 -0.703226 4.13867 -1.0209 -0.713711 4.34529 -1.02855 -0.723818 4.56209 -1.0337 -0.737231 4.81737 -1.04748 -0.749236 5.06532 -1.04917 -0.763041 5.34312 -1.05354 -0.776488 5.63126 -1.05212 -0.793443 5.97786 -1.06091 -0.812288 6.35555 -1.06745 -0.833088 6.78217 -1.076 -0.856919 7.25879 -1.08394 -0.884094 7.82412 -1.09918 -0.912568 8.39334 -1.09519 -0.947854 9.10888 -1.10568 -0.989647 9.96521 -1.12094 -1.03775 10.9419 -1.12967 -1.09535 12.1085 -1.13791 -1.17019 13.6434 -1.16382 -1.26444 15.5483 -1.18829 -1.37761 17.8642 -1.19659 -1.11027 12.4555 4.81214 -0.977225 9.74647 4.17024 -0.962598 9.43445 4.2521 -0.958486 9.35828 4.40967 -0.953987 9.25962 4.55834 -0.948981 9.16907 4.70832 -0.954868 9.28686 4.94607 -0.938164 8.94278 4.98568 -0.959347 9.38751 5.38223 -0.95335 9.2645 5.5237 -0.946189 9.12291 5.65308 -0.942146 9.03151 5.8071 -0.910058 8.37762 5.64911 -0.908266 8.33907 5.81974 -0.90675 8.30477 5.99565 -0.907794 8.32734 6.2088 -0.902117 8.22627 6.34808 -0.823382 6.6248 5.47339 -0.808053 6.30821 5.42212 -0.811834 6.37586 5.63743 -0.82736 6.69329 6.049 -0.762425 5.36803 5.19864 -0.838661 6.93261 6.61954 -0.720943 4.52214 4.79878 -0.719047 4.48532 4.90344 -0.799825 6.14662 6.54021 -0.797975 6.1076 6.70134 -0.764659 5.43225 6.25146 -0.756407 5.26204 6.26782 -0.721661 4.55177 5.71875 -0.751043 5.14358 6.5216 -0.742325 4.96656 6.52138 -0.69881 4.07648 5.69418 -0.723058 4.58498 6.46943 -0.713797 4.40051 6.43994 -0.71462 4.40349 6.64204 -0.712565 4.37705 6.81397 -0.698006 4.08054 6.62263 -0.743258 4.99593 8.14283 -0.738874 4.91551 8.2954 -0.678773 3.67779 6.66935 -0.67435 3.59964 6.76664 -0.692223 3.95108 7.58293 -0.690724 3.93063 7.81553 -0.688205 3.87905 8.00562 -0.660049 3.30631 7.22475 -0.65998 3.29235 7.46864 -0.664416 3.38956 7.95662 -0.604178 2.15375 5.6221 -0.600381 2.07256 5.65907 -0.669597 3.50548 9.266 -0.6638 3.38666 9.39094 -0.572371 1.50048 4.91171 -0.56925 1.44563 4.9749 -0.61405 2.37829 7.9117 -0.576047 1.57747 5.85996 -0.570564 1.4725 5.81981 -0.567498 1.41551 5.94089 -0.546341 0.970085 4.62224 -0.542662 0.894486 4.59015 -0.539063 0.833749 4.61499 -0.536939 0.779345 4.66815 -0.533812 0.724443 4.73025 -0.53186 0.671414 4.81128 -0.528785 0.616412 4.8916 -0.541046 0.889221 7.32789 -0.521449 0.466934 4.8015 -0.518073 0.39633 4.76936 -0.515098 0.340578 4.89528 -0.511522 0.268378 4.83078 -0.50812 0.1986 4.77487 -0.507206 0.179097 6.11699 -0.502771 0.0897115 6.10932 -0.642972 1.81874 -0.99059 -0.649119 1.88737 -0.994715 -0.653899 1.94951 -0.9899 -0.65875 2.01273 -0.983536 -0.664433 2.09033 -0.989302 -0.671189 2.16899 -0.992923 -0.676516 2.24014 -0.987755 -0.681916 2.31238 -0.980739 -0.68966 2.40771 -0.990795 -0.697036 2.49648 -0.991916 -0.70349 2.58643 -0.990585 -0.711466 2.68515 -0.992601 -0.719908 2.79172 -0.997509 -0.72849 2.90045 -0.999321 -0.737092 3.00933 -0.997937 -0.746286 3.1281 -0.998746 -0.757526 3.26446 -1.00634 -0.768366 3.41083 -1.01493 -0.779719 3.54861 -1.01399 -0.791734 3.69736 -1.01359 -0.804871 3.86487 -1.01783 -0.819135 4.05119 -1.02571 -0.835012 4.24752 -1.03198 -0.84999 4.44522 -1.03202 -0.869786 4.6901 -1.04562 -0.888755 4.93743 -1.05123 -0.910458 5.21354 -1.05978 -0.933799 5.49986 -1.06273 -0.958015 5.81719 -1.06632 -0.98716 6.18311 -1.07524 -1.01873 6.58901 -1.08394 -1.05473 7.03488 -1.09044 -1.09223 7.522 -1.09257 -1.14138 8.13601 -1.11075 -1.18707 8.72453 -1.10111 -1.25019 9.51936 -1.11698 -1.3237 10.453 -1.13345 -1.41057 11.5573 -1.14881 -1.52086 12.9497 -1.17392 -1.65154 14.612 -1.19085 -1.81285 16.6641 -1.20105 -2.00711 19.1266 -1.18635 -6.31886 73.8488 0.351345 -4.58387 51.8492 5.09165 -4.57514 51.7401 5.99579 -1.23762 9.37548 3.96476 -1.229 9.27501 4.11254 -1.23196 9.31362 4.30776 -1.21568 9.10525 4.41426 -1.21432 9.09007 4.59153 -1.23936 9.40415 4.90699 -1.23806 9.38949 5.09496 -1.24153 9.43521 5.31255 -1.23104 9.30431 5.45124 -1.21444 9.09138 5.54655 -1.20918 9.02882 5.71427 -1.19938 8.89337 5.84286 -1.19165 8.80725 5.99784 -1.20862 9.02028 6.32885 -1.19034 8.78104 6.39713 -1.13515 8.08064 6.16319 -1.11571 7.84012 6.20451 -1.10908 7.75631 6.34666 -1.01642 6.57442 5.70356 -0.975537 6.05907 5.49675 -0.964056 5.91613 5.55343 -1.05635 7.08458 6.65225 -0.854601 4.51584 4.73369 -0.846473 4.4123 4.77969 -0.973253 6.02625 6.34723 -0.9592 5.85842 6.38433 -0.958843 5.84319 6.5618 -0.9374 5.57535 6.49495 -0.918494 5.33213 6.44198 -0.870545 4.72916 5.99774 -0.900653 5.11215 6.59582 -0.893031 5.01471 6.68448 -0.865398 4.66831 6.48247 -0.838483 4.31858 6.25468 -0.815752 4.03477 6.0869 -0.807793 3.93361 6.1408 -0.806942 3.92659 6.32147 -0.813801 4.00689 6.63356 -0.800637 3.84071 6.60399 -0.788986 3.69796 6.60369 -0.7854 3.64795 6.74345 -0.785715 3.65695 6.9855 -0.793951 3.75496 7.39323 -0.807893 3.93776 7.98016 -0.746431 3.14946 6.81774 -0.766706 3.41145 7.57274 -0.753959 3.2522 7.54193 -0.746357 3.15492 7.63398 -0.720255 2.82819 7.22413 -0.708082 2.66447 7.14427 -0.704906 2.63299 7.37473 -0.762567 3.36995 9.57838 -0.726665 2.91621 8.82113 -0.689002 2.42694 7.87179 -0.638894 1.79397 6.37704 -0.633415 1.71594 6.45522 -0.616854 1.51023 6.11053 -0.62068 1.56173 6.64693 -0.572405 0.936829 4.63063 -0.566725 0.861317 4.59784 -0.561127 0.800676 4.62219 -0.557306 0.75033 4.69439 -0.553118 0.694472 4.75614 -0.549107 0.640542 4.83672 -0.562488 0.822639 6.51884 -0.547907 0.634736 5.82844 -0.532941 0.438811 4.85508 -0.52726 0.364831 4.79259 -0.522916 0.305146 4.87806 -0.517325 0.241989 4.9527 -0.516083 0.232539 6.31505 -0.508048 0.132017 6.01839 -0.502107 0.0456457 6.10989 -0.686183 1.72176 -0.992281 -0.692935 1.78357 -0.991567 -0.699636 1.84447 -0.989206 -0.706407 1.90645 -0.985296 -0.713629 1.97614 -0.986876 -0.72224 2.05253 -0.993601 -0.729546 2.12341 -0.991335 -0.737862 2.19434 -0.987176 -0.747136 2.28169 -0.994345 -0.754539 2.35387 -0.986137 -0.765287 2.44908 -0.994805 -0.774282 2.5311 -0.988493 -0.783737 2.62093 -0.985974 -0.795164 2.72724 -0.99249 -0.80667 2.83471 -0.99596 -0.819704 2.95098 -1.00188 -0.832821 3.06844 -1.00415 -0.847044 3.20452 -1.01365 -0.860779 3.33208 -1.01372 -0.876626 3.47827 -1.01993 -0.89262 3.62667 -1.02164 -0.910674 3.79277 -1.02804 -0.92882 3.96013 -1.0293 -0.948575 4.13746 -1.02956 -0.970042 4.34343 -1.03695 -0.994126 4.5594 -1.04174 -1.02152 4.81386 -1.05517 -1.04902 5.06973 -1.06025 -1.08032 5.35535 -1.06772 -1.1129 5.66208 -1.07264 -1.15135 6.01629 -1.08364 -1.1921 6.39172 -1.0889 -1.23517 6.78841 -1.0875 -1.28695 7.26337 -1.09483 -1.34648 7.81688 -1.10678 -1.41154 8.41164 -1.10959 -1.48664 9.10598 -1.11457 -1.58047 9.97806 -1.13323 -1.68641 10.9503 -1.14099 -1.82762 12.2581 -1.17424 -1.99266 13.7768 -1.1949 -2.18671 15.5752 -1.20191 -2.33061 16.9032 -1.08779 -2.65224 19.8764 -0.0480695 -7.64817 65.994 -1.31943 -7.00371 60.0504 -0.0555682 -6.02017 50.9769 4.58444 -6.12824 51.9851 9.2804 -1.49484 9.19429 4.18387 -1.84146 12.3983 5.53835 -1.84899 12.4748 5.81627 -1.5068 9.31063 4.7834 -1.50141 9.26226 4.95403 -1.49099 9.16502 5.10377 -1.51396 9.37993 5.3993 -1.4989 9.24001 5.53255 -1.47265 9.00082 5.6124 -1.46366 8.91065 5.76498 -1.45824 8.8615 5.94005 -1.46983 8.97251 6.20985 -1.45193 8.80354 6.32022 -1.39479 8.27961 6.20364 -1.39857 8.3137 6.42991 -1.36477 8.00377 6.42959 -1.2079 6.54825 5.61146 -1.18881 6.37934 5.66106 -1.15812 6.09007 5.61585 -1.11924 5.73491 5.50655 -1.15471 6.06627 5.94004 -0.974902 4.40234 4.71531 -0.977949 4.42794 4.87073 -1.07604 5.33537 5.831 -1.0476 5.06843 5.75343 -1.03736 4.9778 5.83476 -1.09929 5.54768 6.57892 -1.0385 4.99392 6.20081 -0.985605 4.50253 5.85612 -0.966339 4.31849 5.82296 -1.02286 4.84656 6.60747 -0.973139 4.39109 6.26269 -0.948893 4.16115 6.16795 -0.940069 4.0774 6.24813 -0.924239 3.93185 6.24699 -0.956325 4.23107 6.85721 -1.03642 4.97321 8.14294 -0.902428 3.73663 6.57115 -0.881352 3.54204 6.48486 -0.86697 3.40416 6.47833 -0.969289 4.35345 8.28586 -0.843359 3.19197 6.55983 -0.913307 3.84265 7.97068 -0.867579 3.41251 7.45432 -0.847421 3.23247 7.37962 -0.838896 3.15162 7.4983 -0.806189 2.84569 7.13563 -0.792473 2.71829 7.139 -0.791033 2.71254 7.42514 -0.784951 2.65246 7.60156 -0.818383 2.9617 8.75804 -0.757143 2.39156 7.60599 -0.698137 1.84517 6.38947 -0.687771 1.75456 6.43055 -0.685558 1.73644 6.7092 -0.673433 1.62043 6.68105 -0.661777 1.51125 6.66999 -0.595867 0.895248 4.60961 -0.587973 0.830792 4.61494 -0.582977 0.778054 4.67794 -0.576552 0.719367 4.72043 -0.570487 0.665095 4.79163 -0.564902 0.616213 4.91132 -0.594011 0.886515 7.33781 -0.561758 0.584556 5.78417 -0.541276 0.397414 4.7992 -0.534632 0.334912 4.84538 -0.527739 0.269381 4.87068 -0.528145 0.280323 6.36278 -0.517313 0.178974 6.14697 -0.507698 0.0894208 6.08927 -0.724484 1.62624 -0.990709 -0.733097 1.68582 -0.9922 -0.740405 1.73993 -0.984601 -0.749475 1.80729 -0.990583 -0.758178 1.86811 -0.987429 -0.768388 1.93758 -0.989918 -0.777612 2.00721 -0.990506 -0.786848 2.07693 -0.989196 -0.797535 2.15434 -0.99288 -0.809355 2.23379 -0.994369 -0.818687 2.3048 -0.987216 -0.831039 2.39315 -0.99085 -0.843346 2.48062 -0.991936 -0.856236 2.57791 -0.996615 -0.870141 2.67527 -0.9985 -0.88608 2.79014 -1.00907 -0.900144 2.8898 -1.00496 -0.914736 2.99833 -1.0034 -0.934388 3.14175 -1.0202 -0.950083 3.25157 -1.0115 -0.968397 3.38872 -1.01488 -0.989762 3.54346 -1.02374 -1.01076 3.69168 -1.02307 -1.03231 3.8489 -1.02235 -1.05901 4.04228 -1.03456 -1.08587 4.23796 -1.04057 -1.11434 4.44368 -1.04439 -1.14812 4.68774 -1.05744 -1.18352 4.94194 -1.06639 -1.2212 5.21711 -1.07439 -1.26204 5.51127 -1.08014 -1.30616 5.82643 -1.08284 -1.35627 6.19112 -1.09103 -1.41174 6.59462 -1.09886 -1.47205 7.02817 -1.10169 -1.54004 7.52237 -1.10587 -1.6203 8.10382 -1.11572 -1.70557 8.71771 -1.11269 -1.81973 9.54518 -1.13629 -1.94214 10.4252 -1.14121 -2.1028 11.5908 -1.16865 -2.2969 12.994 -1.19522 -2.52617 14.6465 -1.20986 -2.71629 16.0282 -1.13031 -7.60884 51.4115 5.99658 -7.76323 52.5329 7.98102 -1.80398 9.43861 4.75283 -1.77227 9.20762 4.84972 -1.76476 9.15732 5.01925 -1.74919 9.04184 5.15921 -1.73822 8.96814 5.31791 -1.71867 8.8209 5.43963 -1.73296 8.92783 5.69129 -1.49313 7.19082 4.94132 -1.48541 7.13886 5.07719 -1.49198 7.18734 5.27341 -1.44692 6.85853 5.24264 -1.42455 6.70069 5.30914 -1.60708 8.02175 6.35923 -1.27545 5.61694 4.89684 -1.28779 5.71011 5.11134 -1.30883 5.86151 5.37788 -1.2855 5.68985 5.40742 -1.49718 7.22587 6.80176 -1.11589 4.46401 4.71471 -1.10574 4.39195 4.78631 -1.31781 5.92858 6.29425 -1.3485 6.14993 6.68845 -1.0988 4.34061 5.15764 -1.11244 4.43718 5.4017 -1.1549 4.7492 5.87865 -1.13741 4.62382 5.91798 -1.13661 4.61824 6.08717 -1.18026 4.93019 6.6246 -1.16334 4.81298 6.68775 -1.13021 4.5686 6.59428 -0.989056 3.55217 5.50789 -0.980659 3.49174 5.59352 -0.962204 3.35346 5.57393 -1.16868 4.85542 7.87109 -1.0102 3.70351 6.43925 -1.0111 3.70709 6.65373 -0.96124 3.34872 6.30497 -0.949512 3.26691 6.38016 -0.948323 3.25358 6.57477 -0.940532 3.20056 6.70949 -0.961359 3.3516 7.23087 -0.963553 3.37171 7.53724 -0.959189 3.33775 7.75671 -0.892224 2.84925 7.02929 -0.87677 2.74084 7.06948 -0.856562 2.59195 7.01597 -0.842854 2.49461 7.07913 -0.885364 2.80715 8.19215 -0.845162 2.51233 7.78151 -0.823192 2.35223 7.70214 -0.744399 1.78258 6.37705 -0.73393 1.70486 6.45534 -0.732917 1.70303 6.80087 -0.714232 1.5655 6.69513 -0.629026 0.942837 4.67904 -0.618357 0.867637 4.64647 -0.609583 0.8047 4.66115 -0.602224 0.747101 4.70418 -0.593922 0.69 4.75611 -0.585676 0.633342 4.81703 -0.578301 0.574581 4.87704 -0.588481 0.651203 5.98707 -0.559017 0.438225 4.87498 -0.547856 0.359093 4.76271 -0.539273 0.297684 4.80834 -0.531054 0.238667 4.92274 -0.529812 0.229218 6.28509 -0.516718 0.134936 6.16837 -0.504044 0.0445279 6.10993 -0.776584 1.64248 -0.983922 -0.786199 1.70204 -0.984817 -0.7972 1.76825 -0.991455 -0.807954 1.82991 -0.989156 -0.819097 1.89828 -0.992497 -0.83125 1.96668 -0.993944 -0.842476 2.03624 -0.99354 -0.855154 2.11348 -0.998129 -0.868904 2.19177 -1.00057 -0.88167 2.27023 -1.00082 -0.894064 2.34211 -0.992526 -0.90836 2.42941 -0.994818 -0.922285 2.51013 -0.988473 -0.941068 2.62257 -1.00395 -0.959484 2.72848 -1.01009 -0.975535 2.82795 -1.00738 -0.99405 2.93516 -1.00738 -1.01461 3.05992 -1.01506 -1.03479 3.17814 -1.01361 -1.05703 3.31396 -1.01884 -1.08035 3.45091 -1.01994 -1.10672 3.60548 -1.02642 -1.13621 3.77869 -1.03735 -1.16182 3.9368 -1.03379 -1.19459 4.13098 -1.04267 -1.22746 4.32646 -1.04541 -1.26656 4.55919 -1.05803 -1.30829 4.80198 -1.06686 -1.35228 5.06572 -1.07524 -1.3995 5.3494 -1.08201 -1.44935 5.64326 -1.0828 -1.50718 5.98646 -1.09007 -1.56977 6.35858 -1.095 -1.63885 6.77147 -1.09917 -1.71529 7.22319 -1.1002 -1.80611 7.76392 -1.10931 -1.90905 8.3722 -1.11672 -2.0296 9.08957 -1.12792 -2.17198 9.93591 -1.14141 -2.34401 10.9577 -1.15984 -2.5491 12.1782 -1.17746 -2.81053 13.7338 -1.20564 -3.10612 15.4883 -1.20721 -3.3699 17.0603 -1.12418 -4.3416 22.8321 -1.43341 -9.04998 50.8155 -1.70074 -8.87836 49.8238 13.5964 -9.22243 51.8798 21.1935 -2.05696 9.26292 4.79477 -2.06105 9.28677 4.99712 -2.03374 9.12703 5.12021 -2.00314 8.94678 5.23042 -2.01341 9.00542 5.45384 -1.7061 7.17946 4.70908 -1.7007 7.14889 4.8544 -1.68233 7.0387 4.95606 -1.71818 7.25151 5.24501 -1.69176 7.09239 5.32121 -1.5859 6.46471 5.09631 -1.59325 6.50981 5.28628 -1.53658 6.17301 5.22194 -1.47158 5.78404 5.10686 -1.55432 6.27928 5.62589 -1.56125 6.31692 5.82654 -1.56239 6.32605 6.01151 -1.26657 4.56804 4.7508 -1.25245 4.48065 4.81176 -1.23574 4.38396 4.8642 -1.23657 4.39006 5.00817 -1.26432 4.55151 5.30341 -1.24285 4.42697 5.33471 -1.24866 4.46319 5.52553 -1.22664 4.33013 5.54624 -1.22113 4.29867 5.67339 -1.2491 4.46084 6.02366 -1.30419 4.79471 6.59237 -1.19272 4.1274 5.98699 -1.12062 3.69984 5.63176 -1.10871 3.63134 5.7123 -1.08017 3.46075 5.65611 -1.0643 3.3622 5.69231 -1.03254 3.17374 5.59547 -1.14059 3.82218 6.74528 -1.0757 3.43277 6.35909 -1.07512 3.42891 6.56323 -1.06817 3.38884 6.71734 -1.05168 3.2949 6.78505 -1.02297 3.12245 6.71134 -0.992286 2.93611 6.59787 -1.03746 3.2104 7.38855 -1.01173 3.05234 7.34554 -0.968674 2.80153 7.09045 -0.951158 2.6922 7.12989 -0.926253 2.54802 7.08459 -1.04988 3.28475 9.2427 -0.933295 2.59132 7.84315 -0.889177 2.32837 7.48394 -0.80332 1.81441 6.34228 -0.852204 2.10976 7.58135 -0.779591 1.67602 6.55621 -0.80924 1.84934 7.53659 -0.750554 1.50384 6.68943 -0.650613 0.902857 4.66776 -0.638305 0.832701 4.65398 -0.628832 0.773762 4.68768 -0.618295 0.713837 4.72044 -0.609113 0.658257 4.78171 -0.599805 0.600638 4.84218 -0.589737 0.545501 4.93147 -0.595637 0.580999 5.79415 -0.57287 0.446297 5.29641 -0.554536 0.332706 4.84537 -0.543464 0.265939 4.84072 -0.542269 0.263562 6.08307 -0.528479 0.179282 6.18694 -0.512691 0.0886143 6.0993 -0.821019 1.61601 -0.99841 -0.830936 1.66324 -0.984581 -0.842553 1.72272 -0.984583 -0.855555 1.78885 -0.990528 -0.86831 1.85042 -0.987436 -0.880017 1.91113 -0.982694 -0.89599 1.99369 -0.997478 -0.908838 2.05652 -0.989242 -0.924516 2.13363 -0.992843 -0.937829 2.2043 -0.9877 -0.953594 2.28261 -0.987155 -0.970815 2.36866 -0.990805 -0.989617 2.46445 -0.998149 -1.00799 2.55269 -0.996608 -1.02833 2.6574 -1.0044 -1.04975 2.7632 -1.00905 -1.06875 2.86156 -1.00491 -1.09328 2.98599 -1.0144 -1.11884 3.11055 -1.0201 -1.14349 3.23636 -1.02196 -1.17072 3.37199 -1.02491 -1.19956 3.51751 -1.02866 -1.22843 3.66326 -1.02772 -1.26147 3.82858 -1.03157 -1.29758 4.0116 -1.03902 -1.33478 4.19585 -1.04043 -1.38078 4.42697 -1.05672 -1.42841 4.66821 -1.06932 -1.47621 4.91185 -1.07402 -1.53074 5.18402 -1.08157 -1.58691 5.4664 -1.08353 -1.65298 5.79696 -1.09284 -1.72235 6.14864 -1.0973 -1.79849 6.52914 -1.09872 -1.88363 6.95918 -1.10153 -1.97563 7.41924 -1.09766 -1.9749 7.41632 -0.955336 -1.97717 7.43001 -0.818456 -1.97766 7.43087 -0.67943 -1.99994 7.54456 -0.564827 -1.99189 7.50321 -0.417658 -2.00824 7.58461 -0.293817 -3.66119 15.8988 -1.13396 -4.69375 21.0877 -1.44956 -9.9032 47.2879 -1.10487 -11.6993 56.318 -0.503488 -11.7041 56.3445 0.498815 -11.6901 56.2758 1.50092 -10.1681 48.6216 2.29819 -10.4692 50.1412 5.02343 -10.443 50.028 19.0622 -2.37278 9.42641 4.59322 -2.32614 9.1934 5.07528 -2.3154 9.13937 5.24652 -1.9531 7.31241 4.55612 -1.93358 7.21583 4.66783 -2.17964 8.45644 5.48831 -2.20841 8.60272 5.76206 -2.17549 8.4343 5.86519 -2.13846 8.24834 5.95359 -1.80742 6.58151 5.11211 -1.68973 5.98979 4.89011 -1.66583 5.87249 4.96303 -1.65049 5.79604 5.06121 -1.72127 6.14918 5.47148 -1.73987 6.24523 5.71103 -1.73319 6.2098 5.858 -1.63267 5.70379 5.62536 -1.40292 4.54934 4.82287 -1.40341 4.5502 4.96169 -1.36744 4.37087 4.94262 -1.33555 4.20877 4.93199 -1.41905 4.63224 5.48119 -1.40215 4.54771 5.55595 -1.34498 4.25629 5.41509 -1.38864 4.47686 5.80924 -1.35242 4.29392 5.77764 -1.30039 4.03699 5.65106 -1.28893 3.97515 5.74499 -1.27077 3.88706 5.80732 -1.26551 3.85918 5.9462 -1.20833 3.57074 5.74431 -1.15581 3.30887 5.55791 -1.14605 3.2582 5.65679 -1.17802 3.41716 6.06847 -1.17761 3.41676 6.26183 -1.27447 3.90536 7.24958 -1.23207 3.69078 7.13907 -1.21549 3.60988 7.2469 -1.18824 3.47365 7.25789 -1.12774 3.16909 6.94969 -1.09867 3.02175 6.91638 -1.0805 2.93252 6.99609 -1.06927 2.87202 7.13761 -1.04028 2.7263 7.09682 -1.0556 2.80533 7.57532 -1.01596 2.60601 7.41179 -1.03302 2.69285 7.96889 -0.962427 2.33631 7.36945 -0.936314 2.20423 7.34409 -0.856173 1.80255 6.49092 -0.842435 1.73498 6.60798 -0.83005 1.67172 6.75305 -0.846281 1.75436 7.44673 -0.815051 1.59466 7.28339 -0.670262 0.863465 4.66598 -0.657314 0.798294 4.67098 -0.644722 0.738027 4.69435 -0.634606 0.683528 4.75608 -0.623244 0.625568 4.80717 -0.610878 0.567109 4.8672 -0.622712 0.627682 5.85816 -0.605226 0.53952 5.81886 -0.570061 0.359729 4.80249 -0.557302 0.296579 4.82821 -0.544723 0.234349 4.89283 -0.541864 0.221042 6.13524 -0.524517 0.132969 6.13829 -0.506663 0.0434125 6.00995 -0.860396 1.57095 -0.989321 -0.873935 1.6292 -0.991577 -0.887544 1.68853 -0.992285 -0.899786 1.74136 -0.984053 -0.916228 1.81498 -0.996397 -0.928549 1.86896 -0.985218 -0.944693 1.93712 -0.986778 -0.96129 2.01301 -0.993528 -0.978899 2.08896 -0.998084 -0.99514 2.1584 -0.9938 -1.01434 2.24416 -1.00085 -1.03066 2.31481 -0.992523 -1.05095 2.40173 -0.994833 -1.07269 2.49642 -1.00074 -1.09307 2.5846 -0.997906 -1.11886 2.69679 -1.01001 -1.14229 2.80255 -1.01307 -1.16679 2.90941 -1.01288 -1.19382 3.02503 -1.01505 -1.22239 3.1495 -1.01886 -1.25104 3.27516 -1.01873 -1.28379 3.41932 -1.02484 -1.31758 3.56365 -1.02636 -1.3585 3.74396 -1.04202 -1.39649 3.90814 -1.04274 -1.43861 4.09095 -1.04701 -1.48491 4.29344 -1.05378 -1.53787 4.52334 -1.06605 -1.59099 4.75562 -1.07073 -1.65236 5.02516 -1.0826 -1.71232 5.28738 -1.08199 -1.78154 5.58692 -1.08608 -1.85916 5.92592 -1.09316 -1.942 6.28494 -1.09497 -2.03738 6.70212 -1.10192 -2.10559 6.99906 -1.05881 -2.09143 6.93923 -0.907291 -2.10699 7.0082 -0.792443 -2.11003 7.0185 -0.662208 -2.10266 6.98871 -0.523824 -2.09768 6.96562 -0.38889 -2.10501 6.99739 -0.265648 -2.12318 7.07628 -0.149604 -2.16878 7.27813 -0.0492054 -2.20599 7.43994 0.0630315 -5.54695 22.004 -1.37247 -10.6432 44.2195 -1.37709 -16.0283 67.7015 -0.211649 -16.0705 67.8876 1.00072 -8.93367 36.7729 2.31788 -8.91188 36.6763 2.97248 -8.94908 36.8418 3.64342 -8.96004 36.8884 4.31138 -8.85658 36.4379 4.92958 -8.87734 36.5303 5.60213 -9.1698 37.8076 6.45174 -9.19177 37.9016 7.15915 -2.62514 9.27266 4.65191 -2.60669 9.19135 4.80993 -2.59939 9.16059 4.98951 -2.51958 8.81318 5.41014 -2.42428 8.39867 5.39022 -2.40558 8.31372 5.5352 -2.44783 8.49953 5.83365 -2.4049 8.31509 5.92512 -2.27628 7.75392 5.77968 -2.38051 8.20894 6.26222 -1.88215 6.03375 5.01952 -1.8552 5.91567 5.0934 -1.89337 6.08463 5.37078 -1.88562 6.04881 5.50846 -1.7965 5.6594 5.37533 -1.74895 5.45344 5.37137 -1.63082 4.9397 5.10327 -1.53989 4.5403 4.90827 -1.59722 4.78958 5.27098 -1.61471 4.86795 5.49669 -1.76814 5.53952 6.29925 -1.73431 5.39223 6.34207 -1.47531 4.26022 5.37004 -1.48293 4.2933 5.5607 -1.43913 4.10197 5.51253 -1.4468 4.13548 5.71168 -1.51169 4.41938 6.21511 -1.39672 3.91661 5.78787 -1.37093 3.80333 5.81844 -1.32433 3.60105 5.72819 -1.30425 3.51476 5.78393 -1.26859 3.35829 5.74091 -1.28646 3.43918 6.03788 -1.25071 3.28152 5.99091 -1.28546 3.43547 6.42624 -1.3919 3.90087 7.40286 -1.33244 3.64033 7.21453 -1.32204 3.59214 7.38268 -1.28514 3.43124 7.34979 -1.16352 2.9017 6.59801 -1.16185 2.89514 6.82722 -1.17303 2.94473 7.19276 -1.16011 2.88829 7.35332 -1.18274 2.98628 7.8791 -1.12463 2.73564 7.60927 -1.11617 2.69907 7.85193 -1.06024 2.45291 7.55383 -1.00741 2.22423 7.26787 -0.910456 1.79637 6.35172 -0.904951 1.77503 6.60181 -0.884598 1.68446 6.65186 -0.868795 1.61542 6.77732 -0.847425 1.52425 6.83431 -0.704755 0.901519 4.70665 -0.688274 0.829133 4.68328 -0.673388 0.765055 4.68774 -0.661035 0.707733 4.73029 -0.647983 0.653884 4.80151 -0.634318 0.592048 4.83238 -0.621194 0.536599 4.91169 -0.631939 0.581764 5.85366 -0.6096 0.484395 5.72414 -0.573075 0.326092 4.81554 -0.558132 0.261051 4.82074 -0.556198 0.252767 5.94335 -0.538154 0.17571 6.14701 -0.517558 0.0873267 6.07931 -0.915877 1.59424 -0.998322 -0.929105 1.64691 -0.992091 -0.943339 1.69958 -0.984564 -0.960334 1.76547 -0.990522 -0.977401 1.83244 -0.994632 -0.993101 1.89292 -0.989802 -1.01263 1.96759 -0.997411 -1.02841 2.02923 -0.989235 -1.0504 2.11165 -0.999544 -1.07008 2.18863 -1.00096 -1.0884 2.2591 -0.993636 -1.11161 2.34479 -0.997105 -1.13528 2.4383 -1.00427 -1.15865 2.52624 -1.00264 -1.18592 2.62953 -1.01031 -1.21082 2.72639 -1.00903 -1.2397 2.83964 -1.0162 -1.26815 2.94534 -1.01438 -1.30214 3.07715 -1.0254 -1.33471 3.20148 -1.02712 -1.37133 3.34332 -1.03505 -1.40507 3.46999 -1.02859 -1.44437 3.6229 -1.03247 -1.48879 3.79434 -1.0407 -1.53827 3.98336 -1.05223 -1.58791 4.17469 -1.05757 -1.64525 4.39433 -1.06916 -1.70522 4.62402 -1.07725 -1.76782 4.86377 -1.08156 -1.83814 5.13199 -1.08881 -1.91115 5.41136 -1.09053 -1.99091 5.71938 -1.0927 -2.07848 6.05708 -1.09398 -2.18144 6.4507 -1.10162 -2.2974 6.89365 -1.10996 -2.2695 6.78817 -0.945193 -2.20754 6.54885 -0.749879 -2.19766 6.51101 -0.615188 -2.19954 6.51896 -0.493241 -2.19764 6.5142 -0.369342 -2.20339 6.53675 -0.251743 -2.22604 6.62393 -0.145146 -2.32651 7.00891 0.174962 -9.22031 33.4494 -0.508536 -9.86255 35.9172 1.97268 -9.88997 36.0212 2.62589 -9.76227 35.5342 3.24664 -9.86421 35.9248 3.92251 -10.0108 36.4867 5.29671 -10.1327 36.9561 6.02854 -9.73967 35.4515 7.79066 -10.325 37.6989 11.0759 -9.94962 36.2598 12.0999 -9.99993 36.454 12.8784 -2.94126 9.3695 4.23989 -2.94421 9.38143 4.62485 -2.88332 9.14829 4.72384 -2.90124 9.21742 4.9457 -2.87186 9.10507 5.09139 -2.78416 8.76978 5.32254 -2.76257 8.68641 5.47557 -2.55268 7.87987 5.239 -2.40071 7.29707 5.09418 -2.40412 7.31084 5.2744 -2.48266 7.61284 5.63398 -2.49001 7.64062 5.83852 -2.15833 6.36663 5.19103 -2.07203 6.03673 5.12864 -2.03699 5.90155 5.19159 -2.03245 5.88503 5.33801 -1.98685 5.70963 5.36617 -1.98756 5.71268 5.52932 -1.91021 5.41556 5.45114 -1.69785 4.60047 4.91835 -1.83897 5.14442 5.53974 -1.73223 4.73305 5.32701 -1.73842 4.75964 5.50628 -1.91411 5.43383 6.32799 -1.82207 5.08092 6.15884 -1.57703 4.13777 5.35092 -1.55774 4.06337 5.4249 -1.55849 4.06732 5.586 -1.49658 3.82864 5.47139 -1.63463 4.36189 6.27737 -1.53662 3.98252 5.99251 -1.48147 3.77158 5.89923 -1.40238 3.47021 5.67298 -1.38688 3.40822 5.75894 -1.36514 3.32729 5.81963 -1.41669 3.52455 6.29929 -1.56744 4.10299 7.40433 -1.51486 3.90063 7.32552 -1.4812 3.77302 7.36076 -1.44051 3.61504 7.34167 -1.41747 3.52707 7.44077 -1.38641 3.40881 7.48574 -1.37017 3.34743 7.64386 -1.31864 3.148 7.52416 -1.30792 3.10889 7.73341 -1.26454 2.94186 7.67013 -1.20617 2.71709 7.4562 -1.17366 2.59322 7.46721 -1.16278 2.55078 7.68985 -1.10988 2.34951 7.49124 -0.974483 1.82881 6.33551 -0.972934 1.82116 6.62365 -1.12063 2.39033 8.83012 -0.919508 1.61646 6.63798 -0.917197 1.60921 6.99389 -0.858993 1.38396 6.52827 -0.723345 0.861186 4.70481 -0.705106 0.792365 4.6905 -0.688219 0.728378 4.69436 -0.676955 0.684908 4.81512 -0.660178 0.621798 4.83676 -0.644513 0.560059 4.86714 -0.633726 0.519883 5.07494 -0.635562 0.529189 5.78915 -0.590903 0.355956 4.81246 -0.573907 0.290578 4.80838 -0.558393 0.229522 4.87286 -0.55472 0.217753 6.14523 -0.532569 0.131465 6.17836 -0.509657 0.0432312 6.00994 -0.953451 1.55291 -0.997116 -0.970984 1.61093 -0.999185 -0.986152 1.66251 -0.992211 -1.00277 1.72173 -0.99143 -1.02039 1.78097 -0.989154 -1.03939 1.84686 -0.992322 -1.05947 1.91378 -0.993845 -1.081 1.98839 -1.00036 -1.10122 2.0575 -0.998088 -1.12284 2.1333 -1.00056 -1.14552 2.21016 -1.00079 -1.16822 2.28712 -0.998915 -1.19344 2.37275 -1.00109 -1.22256 2.47372 -1.01306 -1.24542 2.55304 -1.0038 -1.28059 2.67139 -1.02177 -1.30605 2.76056 -1.01311 -1.33887 2.87266 -1.01844 -1.37283 2.98687 -1.02038 -1.40832 3.10992 -1.02406 -1.44985 3.25035 -1.03415 -1.48645 3.37474 -1.0298 -1.53067 3.52623 -1.03594 -1.57995 3.69525 -1.04669 -1.63434 3.88284 -1.06088 -1.68738 4.06402 -1.06454 -1.74297 4.25416 -1.06635 -1.80627 4.47263 -1.07412 -1.87822 4.71844 -1.08628 -1.95134 4.96661 -1.09007 -2.02962 5.23358 -1.09261 -2.11821 5.53882 -1.0997 -2.21297 5.86295 -1.10286 -2.31654 6.21672 -1.10413 -2.43656 6.62743 -1.11061 -2.30372 6.17327 -0.843684 -2.293 6.13828 -0.713133 -2.27956 6.09145 -0.581881 -2.28744 6.11655 -0.470829 -2.29168 6.13096 -0.357326 -2.29739 6.15322 -0.24572 -2.32294 6.23889 -0.145775 -2.46006 6.71145 0.265406 -11.949 39.1854 -1.13833 -17.207 57.1801 -0.0382399 -10.7182 34.9757 2.27346 -10.7193 34.9782 2.91072 -10.84 35.3939 5.52832 -10.896 35.588 6.21156 -10.4795 34.1635 7.27652 -10.4416 34.034 7.8929 -10.4999 34.2332 8.58127 -10.9034 35.6159 9.56698 -10.8974 35.5969 10.2471 -10.8697 35.5022 10.911 -10.45 34.0663 11.1773 -10.4655 34.1198 11.8683 -3.19042 9.21223 4.30478 -3.17604 9.1644 4.47523 -3.20855 9.27538 4.70935 -3.19533 9.22973 4.8849 -3.10339 8.91618 4.94269 -3.10924 8.93591 5.14493 -3.01978 8.63073 5.19257 -2.99379 8.54133 5.34012 -2.76022 7.7405 5.10883 -2.6948 7.51752 5.16449 -2.67646 7.45541 5.30533 -2.65542 7.38214 5.44024 -2.63074 7.29873 5.56856 -2.89803 8.21399 6.34708 -2.19861 5.821 4.93795 -2.16987 5.72254 5.02078 -2.25842 6.0236 5.39376 -2.01892 5.20296 4.93841 -2.0757 5.39693 5.23697 -2.02541 5.2273 5.25436 -1.86241 4.66983 4.93974 -1.85643 4.64721 5.06264 -1.89154 4.76707 5.31704 -1.89241 4.77294 5.47664 -1.83152 4.56382 5.43316 -1.8476 4.61964 5.64748 -1.8314 4.56162 5.75197 -1.67557 4.02821 5.345 -1.64805 3.93509 5.39562 -1.61143 3.80948 5.40695 -1.59814 3.76641 5.51329 -1.5795 3.70246 5.59645 -1.54284 3.57651 5.60089 -1.49969 3.42815 5.57063 -1.49394 3.40845 5.71211 -1.4819 3.36889 5.82998 -1.44894 3.25409 5.84135 -1.52076 3.50047 6.40547 -1.63147 3.87947 7.22312 -1.61199 3.81526 7.36057 -1.56109 3.63923 7.3089 -1.53512 3.55248 7.40875 -1.50372 3.44419 7.47236 -1.30743 2.77233 6.43029 -1.42133 3.15967 7.45997 -1.41362 3.13577 7.69619 -1.26612 2.62932 6.87303 -1.31441 2.79602 7.54114 -1.26194 2.61443 7.41606 -1.25425 2.58969 7.67585 -1.22428 2.48786 7.74994 -1.04162 1.8625 6.32812 -1.02426 1.80122 6.44629 -1.01498 1.76868 6.66843 -0.984866 1.66779 6.6806 -0.954558 1.56433 6.68119 -0.902846 1.38748 6.38996 -0.762252 0.904429 4.77453 -0.73912 0.823501 4.71248 -0.719062 0.757248 4.70727 -0.705319 0.707985 4.78918 -0.68785 0.648931 4.83105 -0.668952 0.584428 4.84226 -0.652651 0.527184 4.90175 -0.66694 0.578104 5.90329 -0.611847 0.38661 4.82904 -0.591737 0.320458 4.80559 -0.572862 0.256656 4.81076 -0.570865 0.247879 5.92337 -0.54789 0.172626 6.11696 -0.523487 0.085967 6.07934 -1.01212 1.57963 -1.01371 -1.0256 1.61901 -0.992111 -1.04414 1.67707 -0.992086 -1.06507 1.74173 -0.997807 -1.08469 1.80089 -0.994539 -1.1057 1.8667 -0.996914 -1.13016 1.94008 -1.00439 -1.14893 2.00156 -0.996023 -1.17585 2.08267 -1.0063 -1.19809 2.15181 -1.00093 -1.22516 2.23515 -1.00661 -1.25231 2.31962 -1.00975 -1.27808 2.39757 -1.00434 -1.30776 2.49085 -1.00872 -1.34341 2.60037 -1.02216 -1.37174 2.6873 -1.0148 -1.40854 2.79907 -1.02185 -1.44192 2.90348 -1.01989 -1.48378 3.03281 -1.03074 -1.52421 3.15467 -1.03229 -1.56975 3.29497 -1.04009 -1.61187 3.42792 -1.0384 -1.667 3.59446 -1.05156 -1.72128 3.76333 -1.05913 -1.78514 3.95831 -1.07455 -1.84313 4.13836 -1.07477 -1.90976 4.34564 -1.08151 -1.98598 4.57919 -1.0931 -2.06594 4.82475 -1.1006 -2.14596 5.07072 -1.09971 -2.23829 5.35479 -1.10448 -2.3393 5.66642 -1.10926 -2.44401 5.98924 -1.10651 -2.57221 6.38623 -1.11657 -2.38243 5.80026 -0.805946 -2.37679 5.7835 -0.685937 -2.37361 5.77443 -0.569527 -2.37023 5.76232 -0.454067 -2.37697 5.78523 -0.348107 -2.38717 5.81588 -0.243751 -2.41468 5.90115 -0.149505 -2.53934 6.28449 0.24753 -12.6065 37.3012 -1.39718 -12.5896 37.2502 -0.708509 -11.8034 34.8307 1.32084 -11.6801 34.4492 1.94958 -11.6939 34.4949 2.58462 -11.7024 34.52 3.22092 -11.5004 33.8993 3.80616 -11.5089 33.924 4.43527 -11.5338 34.0034 5.07419 -11.7424 34.6467 6.445 -7.0276 20.1169 4.92064 -11.3303 33.3777 8.14046 -11.4825 33.8491 8.89032 -12.3029 36.3765 10.1825 -11.4086 33.6207 10.8034 -11.4275 33.6807 11.4898 -3.43733 9.05385 4.00138 -3.46159 9.12903 4.21149 -3.41416 8.98406 4.34509 -3.38146 8.883 4.49195 -3.39345 8.92144 4.69463 -3.42755 9.02539 4.93049 -3.35519 8.80168 5.02368 -2.82455 7.16744 4.43393 -2.81147 7.12602 4.57353 -2.8383 7.21087 4.77954 -2.88605 7.35768 5.02671 -2.8073 7.11438 5.06093 -2.9483 7.55054 5.4912 -2.91054 7.43403 5.60361 -2.86762 7.29911 5.70275 -2.94049 7.52513 6.04018 -2.36237 5.74279 4.99627 -2.47241 6.08299 5.39562 -2.25546 5.41335 5.05933 -2.16399 5.13064 4.99154 -2.23939 5.36551 5.32852 -2.0446 4.76436 4.98431 -1.99916 4.62482 5.0075 -2.0457 4.76695 5.28005 -2.00539 4.64502 5.32055 -1.99347 4.60748 5.43882 -1.95659 4.49246 5.48137 -1.86129 4.20024 5.33877 -1.74948 3.85422 5.12275 -1.7202 3.7651 5.17108 -1.66591 3.59878 5.12895 -1.62386 3.46744 5.11937 -1.65468 3.56517 5.3877 -1.62382 3.46741 5.42155 -1.58444 3.34643 5.42185 -1.61033 3.42874 5.69677 -1.56188 3.2761 5.65454 -1.50889 3.1157 5.59179 -1.64138 3.52451 6.38992 -1.71622 3.75407 6.96245 -1.67069 3.61441 6.96292 -1.68807 3.66887 7.29263 -1.66016 3.58328 7.39345 -1.61824 3.45246 7.41468 -1.60809 3.42248 7.62648 -1.48287 3.03521 7.12941 -1.46244 2.97195 7.26472 -1.35232 2.63371 6.8038 -1.31142 2.50553 6.77843 -1.2976 2.46628 6.96098 -1.25036 2.31893 6.88524 -1.20064 2.16514 6.77809 -1.16498 2.05602 6.77938 -1.05766 1.72474 6.11865 -1.09734 1.84768 6.8039 -1.05008 1.70268 6.67477 -1.01802 1.60286 6.6859 -0.980994 1.48982 6.64705 -0.928059 1.32442 6.383 -0.774887 0.851017 4.72432 -0.755316 0.791243 4.74912 -0.733258 0.725086 4.74341 -0.718879 0.680318 4.85444 -0.696747 0.613056 4.84658 -0.67697 0.550078 4.86723 -0.660155 0.498314 4.97582 -0.726785 0.704906 7.49804 -0.611501 0.349204 4.80255 -0.59051 0.284568 4.78835 -0.572554 0.22914 4.92275 -0.567329 0.212997 6.10524 -0.538688 0.125658 6.0084 -0.511592 0.0426176 5.99995 -1.06667 1.58671 -1.00689 -1.08477 1.63712 -0.999778 -1.10532 1.69511 -0.99886 -1.12588 1.75317 -0.996344 -1.14988 1.81877 -0.999528 -1.17526 1.89104 -1.00796 -1.19459 1.94476 -0.993503 -1.22106 2.01817 -0.997989 -1.25005 2.10021 -1.00722 -1.27661 2.17484 -1.00726 -1.3043 2.2515 -1.00531 -1.33095 2.32734 -1.001 -1.36455 2.41931 -1.00685 -1.39967 2.52005 -1.01584 -1.43337 2.61331 -1.01584 -1.46715 2.7077 -1.013 -1.5069 2.81838 -1.0184 -1.54923 2.93883 -1.0258 -1.59504 3.06702 -1.03461 -1.63848 3.18881 -1.03408 -1.68896 3.32791 -1.03975 -1.7445 3.48451 -1.05042 -1.80363 3.65095 -1.0607 -1.8638 3.81761 -1.06529 -1.92664 3.99519 -1.06883 -2.00012 4.19988 -1.07898 -2.07364 4.40492 -1.08214 -2.15939 4.64691 -1.094 -2.24625 4.89025 -1.09743 -2.34629 5.16961 -1.10682 -2.44751 5.45139 -1.10643 -2.56099 5.77039 -1.10935 -2.68522 6.11792 -1.11024 -2.45601 5.47526 -0.777252 -2.45293 5.46802 -0.664437 -2.44965 5.45773 -0.552572 -2.45143 5.46491 -0.446305 -2.45661 5.47878 -0.342593 -2.47031 5.51791 -0.244985 -2.49466 5.58424 -0.152188 -2.53014 5.68578 -0.0641009 -2.55587 5.75821 0.0319904 -2.5815 5.82877 0.130578 -2.67397 6.08842 0.32095 -13.0232 35.0602 -1.60169 -13.0197 35.0507 -0.948993 -12.9391 34.8255 1.0016 -12.9128 34.7538 1.64579 -12.9744 34.9269 2.29669 -12.773 34.3639 2.91393 -13.0581 35.1622 4.26811 -12.8493 34.5784 4.86069 -12.9821 34.9491 5.55817 -10.8545 28.9937 5.32821 -10.8578 29.0018 5.87887 -7.75945 20.3298 4.80729 -12.6988 34.1583 8.05185 -11.4279 30.6009 7.90818 -11.4351 30.6212 8.50787 -11.4446 30.6478 9.11535 -11.3914 30.5005 9.67953 -10.2305 27.2486 9.29783 -3.74473 9.08692 3.9505 -3.64631 8.8135 4.04119 -3.75231 9.10938 4.33101 -12.4986 33.6018 13.9878 -3.70784 8.98613 4.66297 -3.04918 7.14097 4.37628 -2.98057 6.9477 4.44051 -3.14389 7.40686 4.83607 -3.09973 7.28435 4.941 -3.05544 7.15967 5.04254 -3.13489 7.3805 5.34425 -3.11395 7.32483 5.4903 -2.98093 6.95095 5.43477 -2.95983 6.89292 5.57353 -2.75009 6.30351 5.34648 -2.69604 6.15229 5.40674 -2.45473 5.47721 5.07268 -2.29969 5.04425 4.89144 -2.45712 5.48369 5.38753 -2.32503 5.11331 5.24221 -2.16126 4.65491 5.00271 -2.23745 4.86964 5.33908 -2.15145 4.62772 5.27114 -2.18026 4.71075 5.50346 -2.15153 4.62918 5.58325 -2.08129 4.43083 5.54331 -1.88788 3.88934 5.12977 -1.84213 3.76203 5.13643 -1.78292 3.59708 5.09577 -1.77484 3.57335 5.21384 -1.83307 3.7388 5.56616 -1.76514 3.5475 5.48921 -1.67763 3.30207 5.32885 -1.63917 3.19572 5.34214 -1.668 3.27682 5.6163 -1.6317 3.17266 5.63588 -1.62276 3.15006 5.77582 -1.8283 3.72423 6.86151 -1.83674 3.75015 7.13091 -1.46137 2.69568 5.57966 -1.42659 2.60022 5.5946 -1.73882 3.47612 7.39144 -1.68808 3.33342 7.38497 -1.54225 2.92278 6.83653 -1.56065 2.97592 7.20164 -1.45182 2.67141 6.81534 -1.40952 2.5523 6.80956 -1.36721 2.43307 6.80119 -1.3177 2.29681 6.74414 -1.25415 2.11713 6.56326 -1.16211 1.86013 6.14417 -1.10705 1.70439 5.97117 -1.10313 1.6929 6.21947 -1.10583 1.70283 6.56388 -1.08211 1.63584 6.68057 -1.04476 1.53233 6.67159 -1.01093 1.43596 6.68947 -0.810289 0.873561 4.71638 -0.788605 0.812452 4.73195 -0.90601 1.14204 6.70272 -0.857127 1.00739 6.4972 -0.73138 0.651709 4.91965 -0.704585 0.576234 4.86196 -0.681991 0.515895 4.89191 -0.664237 0.464659 5.00999 -0.682331 0.517754 6.22136 -0.610216 0.312332 4.78565 -0.588591 0.251696 4.8108 -0.584535 0.243052 5.9034 -0.557504 0.168052 6.07698 -0.528417 0.0846629 6.07927 -1.12679 1.60374 -1.01491 -1.14121 1.64213 -0.991962 -1.16607 1.70554 -0.997747 -1.191 1.77003 -1.00178 -1.21456 1.82803 -0.99688 -1.24195 1.90023 -1.00432 -1.2656 1.9594 -0.995966 -1.29407 2.03274 -0.999459 -1.32362 2.10712 -1.00091 -1.35562 2.18916 -1.00655 -1.38764 2.27133 -1.0097 -1.41973 2.35461 -1.0104 -1.45289 2.43896 -1.00866 -1.49196 2.53853 -1.01622 -1.52866 2.63168 -1.01473 -1.56783 2.73256 -1.01615 -1.60813 2.83554 -1.01426 -1.6603 2.96999 -1.03073 -1.70761 3.08943 -1.03221 -1.76095 3.22625 -1.03999 -1.81789 3.37286 -1.04817 -1.87837 3.5283 -1.05621 -1.93994 3.68493 -1.05901 -2.01109 3.86766 -1.06997 -2.08338 4.05263 -1.07473 -2.16275 4.25514 -1.08141 -2.24925 4.47622 -1.08904 -2.33937 4.70731 -1.09289 -2.44015 4.96569 -1.09965 -2.54915 5.24374 -1.10432 -2.6653 5.54058 -1.10587 -2.77454 5.82161 -1.09057 -2.52334 5.17953 -0.752667 -2.52017 5.17108 -0.643997 -2.52045 5.17026 -0.538929 -2.51862 5.16755 -0.434255 -2.53082 5.19861 -0.339543 -2.53591 5.21128 -0.239776 -2.56469 5.28503 -0.153881 -2.71588 5.67292 0.306545 -13.2109 32.527 -1.74652 -13.5167 33.3108 -1.18543 -13.8533 34.1726 0.681739 -13.915 34.3312 1.32354 -13.9579 34.442 1.97021 -14.0695 34.7278 2.62976 -10.7075 26.1244 2.71696 -10.7675 26.2783 3.22183 -10.7695 26.2848 3.71871 -10.7832 26.3199 4.22091 -10.848 26.4845 4.74495 -10.8038 26.374 5.23317 -10.808 26.384 5.74158 -10.7721 26.2943 6.23333 -10.7906 26.3421 6.7551 -10.7782 26.3079 7.26299 -10.8385 26.4645 7.82269 -10.9105 26.6474 8.40015 -10.9876 26.8458 8.99453 -11.0158 26.9174 9.56163 -11.8446 29.0399 10.8315 -11.8422 29.0347 11.4312 -11.7053 28.6845 11.9069 -4.01634 9.00422 4.61462 -3.2707 7.09626 4.63394 -3.27969 7.11956 4.81095 -3.91432 8.74154 5.88575 -3.55981 7.83433 5.56684 -3.52968 7.75915 5.71291 -3.34551 7.28765 5.60885 -3.23273 6.9973 5.60364 -3.26094 7.07034 5.83616 -2.90827 6.16736 5.38276 -2.80755 5.9116 5.36166 -2.79489 5.87716 5.5008 -2.69874 5.63084 5.4734 -2.77949 5.83827 5.80959 -2.72037 5.68666 5.85598 -2.29887 4.60719 5.07761 -2.31631 4.65367 5.26714 -2.2594 4.50733 5.28082 -2.24801 4.47809 5.40518 -2.0798 4.04795 5.12347 -1.9833 3.80036 5.00952 -2.01137 3.8718 5.2298 -1.8886 3.55915 5.02611 -1.88304 3.54363 5.15106 -2.05639 3.98761 5.83856 -1.93103 3.66677 5.60826 -1.91973 3.63879 5.73797 -1.74863 3.20107 5.32027 -1.7215 3.13042 5.37959 -1.68014 3.02608 5.3893 -1.76007 3.22923 5.86048 -1.71266 3.10841 5.85432 -1.67357 3.00765 5.87845 -1.5489 2.68788 5.52925 -1.53517 2.65345 5.64707 -1.49245 2.54412 5.63571 -1.82912 3.40822 7.46702 -1.75386 3.21357 7.35413 -1.7394 3.1793 7.55526 -1.61079 2.84799 7.13045 -1.50272 2.57057 6.78576 -1.43353 2.39508 6.64196 -1.40182 2.31428 6.71352 -1.3493 2.17864 6.64504 -1.28729 2.02212 6.50827 -1.15303 1.67779 5.8146 -1.17357 1.72985 6.24124 -1.22743 1.86831 6.99361 -1.15892 1.69235 6.76062 -1.10384 1.55121 6.61883 -1.06478 1.45223 6.61815 -0.851223 0.902698 4.74693 -0.823888 0.833011 4.72431 -0.804045 0.783218 4.78816 -0.900324 1.02947 6.42896 -0.861142 0.930521 6.38843 -0.735679 0.608143 4.89594 -0.709487 0.540581 4.87711 -0.687072 0.482189 4.92628 -0.793052 0.757092 8.12403 -0.745574 0.636765 8.08731 -0.607116 0.278058 4.77845 -0.587717 0.227689 4.99272 -0.578819 0.206308 6.06535 -0.545555 0.123236 6.00838 -0.514651 0.0419154 6.0299 -1.18309 1.60674 -1.0072 -1.2042 1.65705 -0.998694 -1.22869 1.71387 -0.996242 -1.25556 1.77728 -0.999435 -1.28251 1.84179 -1.00078 -1.31052 1.90733 -1.00028 -1.33849 1.97196 -0.997836 -1.36659 2.03868 -0.993591 -1.40289 2.12609 -1.00714 -1.43201 2.19296 -0.998702 -1.46941 2.28156 -1.00711 -1.50451 2.36472 -1.00662 -1.5465 2.46305 -1.01564 -1.58507 2.554 -1.01565 -1.62471 2.64603 -1.01283 -1.67033 2.75435 -1.01825 -1.71702 2.86378 -1.02013 -1.77069 2.98949 -1.02907 -1.821 3.10883 -1.02876 -1.88524 3.26065 -1.04455 -1.95058 3.41365 -1.05511 -2.01601 3.56792 -1.06042 -2.08598 3.73097 -1.06509 -2.15961 3.9049 -1.06852 -2.24377 4.10393 -1.07865 -2.32557 4.29663 -1.07785 -2.42247 4.5241 -1.08586 -2.52751 4.77015 -1.09334 -2.6397 5.0349 -1.09939 -2.76363 5.32799 -1.1062 -2.72214 5.23064 -0.955961 -2.59431 4.92816 -0.739103 -2.58308 4.90227 -0.627821 -2.58687 4.90996 -0.529102 -2.5886 4.91675 -0.430626 -2.59114 4.92048 -0.332304 -2.60326 4.95037 -0.241038 -2.49641 4.69979 -0.0846413 -2.78174 5.37192 0.28404 -14.0462 31.8769 -1.41874 -14.018 31.8097 -0.808099 -20.0363 45.974 0.132619 -20.1061 46.1375 1.00451 -12.9112 29.2076 1.55684 -12.8187 28.9916 2.10293 -13.1376 29.7421 2.69652 -12.2698 27.6994 3.10731 -11.8134 26.6258 3.53364 -11.6341 26.2052 3.99524 -11.6934 26.3459 4.51729 -11.5982 26.1214 4.99122 -12.5032 28.252 6.41533 -12.3261 27.8355 6.88151 -11.477 25.8369 6.96962 -11.4721 25.8275 7.48115 -11.5732 26.0661 8.59104 -11.512 25.9226 9.07869 -11.5866 26.097 9.67127 -12.0903 27.284 10.6347 -12.8357 29.0395 11.867 -12.3444 27.8836 12.0294 -12.3127 27.8108 13.211 -13.243 30.0001 14.8385 -3.5963 7.29021 5.03677 -3.58181 7.25773 5.19315 -3.58011 7.25353 5.36889 -3.60075 7.30193 5.58074 -3.38414 6.79321 5.43526 -3.54228 7.16514 5.86549 -3.55478 7.19495 6.0768 -3.10755 6.14321 5.50217 -2.95167 5.77512 5.39423 -2.93707 5.74175 5.53244 -2.95636 5.78485 5.73695 -2.96306 5.80287 5.92595 -2.57389 4.88544 5.29887 -2.47208 4.64675 5.23649 -2.43135 4.54995 5.29778 -2.65709 5.08239 5.97219 -2.61175 4.97518 6.04053 -2.58532 4.91325 6.15489 -2.06338 3.68384 5.00266 -2.01913 3.58049 5.02875 -2.0987 3.76709 5.38861 -2.3272 4.30493 6.1951 -2.04864 3.65052 5.72698 -1.99138 3.5161 5.71775 -1.94942 3.41703 5.75213 -1.81391 3.09698 5.46478 -2.20534 4.01986 7.0115 -1.79028 3.04081 5.7187 -1.76619 2.98556 5.80878 -1.6946 2.81765 5.71368 -1.63722 2.68326 5.6646 -1.57964 2.54627 5.60332 -1.56501 2.51328 5.7289 -1.85698 3.20022 7.27145 -1.62121 2.64474 6.404 -1.94371 3.40571 8.26212 -1.6874 2.80056 7.23805 -1.52392 2.41603 6.62855 -1.49504 2.34751 6.72833 -1.42683 2.18762 6.59696 -1.37774 2.07302 6.57268 -1.23499 1.7358 5.91096 -1.1988 1.65038 5.92431 -1.29723 1.8824 6.93812 -1.27337 1.82699 7.1061 -1.28204 1.84704 7.56052 -1.15807 1.55554 6.89282 -1.06029 1.32486 6.37085 -0.861347 0.855916 4.72615 -0.83821 0.802368 4.77099 -0.974038 1.12234 6.7322 -0.915809 0.983791 6.4974 -0.874808 0.887409 6.46596 -0.739221 0.567596 4.89171 -0.712451 0.505521 4.90185 -0.68934 0.450633 4.98029 -0.716581 0.515616 6.32088 -0.6267 0.304332 4.76582 -0.642837 0.341357 6.29729 -0.599575 0.240106 5.96333 -0.567429 0.164933 6.10701 -0.532103 0.0814584 6.03946 -1.2426 1.6132 -1.00678 -1.2657 1.66342 -0.997586 -1.29788 1.73213 -1.00888 -1.32338 1.78902 -1.00384 -1.35333 1.85339 -1.00419 -1.38328 1.91786 -1.00265 -1.41563 1.98896 -1.00606 -1.44567 2.05462 -1.00067 -1.48598 2.14185 -1.01283 -1.51949 2.21522 -1.00955 -1.55745 2.29615 -1.01027 -1.59204 2.37068 -1.00235 -1.64286 2.48299 -1.02192 -1.68543 2.57379 -1.02035 -1.72702 2.66478 -1.01589 -1.78008 2.78048 -1.02513 -1.83317 2.89637 -1.03047 -1.88734 3.01339 -1.03197 -1.94849 3.14673 -1.03973 -2.01417 3.2888 -1.04784 -2.09141 3.45679 -1.06552 -2.15828 3.60131 -1.06334 -2.23671 3.77179 -1.06964 -2.31974 3.95211 -1.07434 -2.4143 4.15751 -1.08515 -2.51353 4.37381 -1.09273 -2.62536 4.61626 -1.10398 -2.73378 4.8515 -1.10294 -2.85838 5.1226 -1.10747 -2.71161 4.80414 -0.87188 -2.65333 4.67768 -0.722206 -2.64214 4.65264 -0.61407 -2.64139 4.65154 -0.51589 -2.64403 4.6571 -0.420963 -2.65366 4.67903 -0.331292 -2.66769 4.70763 -0.243479 -2.58988 4.54055 -0.1074 -2.5982 4.55743 -0.0199754 -2.84617 5.09711 0.262055 -14.451 30.2997 -1.62138 -14.4762 30.3552 -1.04005 -15.3825 32.3249 -0.549675 -20.8307 44.1578 -0.267493 -20.783 44.0535 0.582289 -13.5181 28.2763 1.27524 -13.0251 27.2051 1.78768 -13.2094 27.6061 2.33036 -13.3603 27.9345 2.88443 -12.043 25.0755 3.17567 -12.2132 25.4434 3.70034 -12.2741 25.5774 4.21139 -12.1697 25.3521 4.67751 -12.1911 25.397 5.18179 -12.2901 25.6144 5.72183 -12.2052 25.4282 6.19141 -12.2546 25.5379 6.72305 -12.8469 26.8251 8.09298 -12.3517 25.7496 8.33432 -12.3086 25.6557 8.83592 -12.225 25.4757 9.31059 -12.3461 25.7383 9.93708 -12.3469 25.7394 10.4842 -13.3986 28.0256 11.9289 -13.43 28.0955 12.5672 -13.32 27.857 13.0832 -13.3883 28.0055 13.7735 -13.1972 27.5904 14.2099 -3.86285 7.309 5.01227 -3.72558 7.01065 5.01812 -3.89779 7.38507 5.41471 -3.77333 7.11564 5.43277 -3.84926 7.27885 5.72112 -3.63902 6.82433 5.60416 -3.72442 7.01027 5.91726 -3.70542 6.96929 6.07879 -3.26158 6.00455 5.5434 -3.19378 5.85799 5.60001 -3.10264 5.6594 5.61067 -3.07537 5.59982 5.73092 -2.85759 5.12651 5.48908 -2.65362 4.68258 5.24972 -2.5775 4.51759 5.24811 -2.53975 4.43622 5.32094 -2.79741 4.99707 6.04061 -2.71195 4.81091 6.02569 -2.66264 4.70471 6.08931 -2.66669 4.71188 6.27876 -2.49512 4.33998 6.03474 -2.58203 4.5295 6.44177 -2.60026 4.56958 6.68518 -2.59971 4.56656 6.88618 -2.58303 4.53058 7.05016 -2.05193 3.3768 5.67268 -2.44238 4.2257 7.06186 -2.39771 4.12908 7.1421 -2.32372 3.96708 7.12271 -1.85721 2.95413 5.73098 -1.81806 2.86817 5.7703 -1.71815 2.6511 5.58008 -1.67557 2.55918 5.59619 -1.67388 2.55507 5.77382 -1.63246 2.4654 5.79612 -1.61324 2.42322 5.91306 -1.58121 2.35409 5.97654 -1.56322 2.31469 6.11046 -1.84873 2.93806 7.77885 -1.61796 2.43382 6.8788 -1.54737 2.28261 6.77786 -1.45886 2.09021 6.55291 -1.35843 1.87156 6.2293 -1.36296 1.88051 6.53611 -1.33098 1.81078 6.62796 -1.31696 1.78208 6.86094 -1.29092 1.72427 7.01835 -1.19963 1.52575 6.66696 -1.125 1.36532 6.41591 -0.901798 0.878102 4.73732 -0.875369 0.820808 4.76334 -0.966634 1.01904 6.05751 -0.950324 0.983985 6.32126 -0.930535 0.941121 6.58512 -0.774429 0.600233 4.94535 -0.740946 0.529638 4.89698 -0.714478 0.471 4.93628 -0.691852 0.421536 5.06391 -0.688603 0.415127 5.73828 -0.669701 0.374705 6.234 -0.624818 0.276576 5.96087 -0.589495 0.201158 6.05542 -0.552236 0.119341 5.97849 -0.515464 0.0403819 6.00003 -1.27899 1.56948 -1.01466 -1.30304 1.61861 -1.00612 -1.33046 1.67426 -1.00353 -1.35889 1.72992 -0.999339 -1.39308 1.79865 -1.00775 -1.42059 1.85555 -1.00011 -1.45593 1.92641 -1.00462 -1.4879 1.9909 -1.00019 -1.52664 2.06847 -1.00706 -1.56651 2.14809 -1.01144 -1.6054 2.2279 -1.01331 -1.64536 2.30877 -1.01274 -1.68978 2.39722 -1.01558 -1.73322 2.48588 -1.01551 -1.78218 2.58308 -1.01841 -1.83466 2.68898 -1.02375 -1.89405 2.81015 -1.0364 -1.95108 2.9249 -1.03961 -2.01709 3.05585 -1.04918 -2.07874 3.18051 -1.04931 -2.15288 3.32998 -1.05984 -2.23155 3.48824 -1.06973 -2.31033 3.64776 -1.07408 -2.40161 3.83224 -1.08595 -2.48609 4.00283 -1.08277 -2.59556 4.22315 -1.09802 -2.70614 4.44481 -1.10523 -2.82034 4.67649 -1.10825 -2.94463 4.92568 -1.1099 -2.71412 4.46192 -0.811961 -2.70198 4.43786 -0.70517 -2.70233 4.4386 -0.60919 -2.69804 4.42871 -0.510755 -2.70072 4.43512 -0.418774 -2.70675 4.44722 -0.329497 -2.72535 4.48528 -0.247485 -2.67438 4.38193 -0.128433 -2.69173 4.41602 -0.0471188 -2.85797 4.75133 0.160793 -2.9029 4.84388 0.240955 -3.03658 5.11258 0.300166 -12.7318 24.6468 -1.40371 -12.7792 24.7438 -0.927993 -12.7969 24.7787 -0.446128 -15.2831 29.7884 0.423705 -14.5515 28.3147 1.00404 -13.5401 26.2778 1.51576 -13.4587 26.1132 2.02169 -13.3727 25.9416 2.52139 -13.4168 26.0307 3.03566 -13.4827 26.1641 3.55903 -13.5051 26.2097 4.07889 -13.347 25.8907 4.55246 -13.3261 25.8489 5.05907 -13.3532 25.9055 5.58397 -13.3162 25.8294 6.08806 -13.7022 26.6087 6.77754 -13.6812 26.5661 7.30752 -12.7813 24.7535 7.38297 -12.6128 24.4153 7.79898 -12.5495 24.2879 8.26843 -12.4999 24.1883 8.74593 -12.5738 24.3372 9.30963 -12.5963 24.3827 9.84742 -14.2908 27.7983 11.6889 -13.9748 27.1627 12.6434 -13.676 26.5617 12.9835 -13.7607 26.7332 13.6711 -14.4971 28.2166 15.028 -4.07187 7.20108 4.74978 -4.05418 7.16561 4.90262 -4.14999 7.35952 5.18693 -4.07386 7.20614 5.27797 -3.54612 6.14309 4.80181 -3.57763 6.20625 5.00095 -3.57702 6.20429 5.16245 -3.4538 5.95661 5.1555 -3.62888 6.31098 5.57598 -3.42056 5.88927 5.43537 -3.39954 5.8492 5.57224 -3.31742 5.68246 5.60911 -3.21009 5.46575 5.59873 -3.05803 5.16015 5.50131 -2.84722 4.73459 5.2801 -2.79267 4.62517 5.33319 -2.71853 4.47571 5.34382 -2.64203 4.32082 5.34333 -2.86801 4.77678 5.97255 -2.82503 4.69133 6.05783 -2.82339 4.68811 6.23331 -2.80105 4.64295 6.36704 -2.61644 4.27134 6.11287 -2.55838 4.15435 6.15064 -2.65234 4.34344 6.57797 -2.16092 3.35157 5.45899 -2.11774 3.26495 5.50017 -2.44826 3.93252 6.61913 -2.59205 4.2222 7.25395 -2.47985 3.99668 7.14111 -1.98175 2.99057 5.76796 -1.94204 2.91116 5.81718 -1.7982 2.62042 5.5041 -1.74582 2.51681 5.49512 -1.75911 2.54241 5.72346 -1.73786 2.49998 5.83291 -1.67838 2.38024 5.79333 -1.67222 2.3684 5.97147 -1.62549 2.2744 5.9811 -1.61232 2.24706 6.14153 -1.5795 2.18076 6.22079 -1.56645 2.15432 6.3995 -1.5338 2.08987 6.49589 -1.42174 1.8626 6.14625 -1.38318 1.78591 6.19102 -1.35744 1.73465 6.31906 -1.34559 1.70929 6.54116 -1.31637 1.65019 6.66871 -1.29092 1.60123 6.84339 -1.19947 1.41557 6.50839 -0.943064 0.89773 4.7384 -0.914521 0.839107 4.75529 -1.00799 1.02822 5.96959 -0.958708 0.930513 5.8812 -0.974732 0.962636 6.52681 -0.926622 0.865711 6.47582 -0.773614 0.55547 4.91152 -0.742913 0.494639 4.92172 -0.715748 0.439504 4.99029 -0.718462 0.445723 5.72417 -0.771466 0.553267 8.05332 -0.656096 0.321598 6.11766 -0.618721 0.245344 6.21306 -0.577355 0.161309 6.14708 -0.53585 0.0787367 6.00943 -1.33263 1.56099 -0.999254 -1.36535 1.62192 -1.00497 -1.39472 1.67649 -1.00163 -1.43084 1.74406 -1.01089 -1.46028 1.79979 -1.00411 -1.49411 1.86202 -1.00258 -1.53476 1.9383 -1.01271 -1.56874 2.00272 -1.00728 -1.60604 2.07274 -1.00626 -1.64786 2.1513 -1.00949 -1.69069 2.22993 -1.01013 -1.73604 2.31725 -1.01442 -1.78678 2.41112 -1.02177 -1.82978 2.49214 -1.01441 -1.88512 2.59577 -1.02147 -1.94493 2.70706 -1.03053 -2.00933 2.82803 -1.0411 -2.07375 2.9492 -1.04758 -2.13481 3.06401 -1.04471 -2.2093 3.20255 -1.0527 -2.29177 3.35743 -1.06535 -2.36644 3.49847 -1.06326 -2.46351 3.67942 -1.07849 -2.55278 3.84655 -1.07858 -2.65901 4.04623 -1.08928 -2.77086 4.25577 -1.09661 -2.89729 4.49132 -1.1077 -3.01933 4.71973 -1.10641 -2.76279 4.23911 -0.795664 -2.75873 4.23317 -0.698226 -2.75455 4.22518 -0.601588 -2.74924 4.21523 -0.505646 -2.75291 4.22144 -0.416465 -2.7635 4.24302 -0.33269 -2.77397 4.26262 -0.248617 -2.77082 4.25532 -0.157025 -2.77006 4.25476 -0.068383 -2.87905 4.45938 0.0641271 -2.91888 4.53402 0.140999 -3.07188 4.81965 0.281757 -16.0034 29.0501 -1.58694 -15.3594 27.844 -0.926035 -18.0354 32.8582 -0.620995 -21.6985 39.7227 -0.172923 -21.7228 39.7693 0.6127 -14.9436 27.0666 1.27194 -14.8394 26.8725 1.8018 -14.4592 26.1599 2.29867 -14.399 26.0485 2.80985 -13.5515 24.4593 3.18574 -13.5828 24.5191 3.67981 -14.3729 25.9998 4.36153 -15.006 27.1859 5.06085 -13.7545 24.8416 5.21195 -13.7133 24.7641 5.70103 -14.2697 25.8077 6.42537 -13.6649 24.6739 6.69369 -13.5287 24.4195 7.13972 -13.5261 24.4158 7.64754 -13.3366 24.0614 8.05687 -13.6532 24.6546 8.75365 -13.2224 23.8468 9.00992 -13.3377 24.065 9.6038 -13.4086 24.1967 10.1801 -14.2014 25.6841 11.8883 -14.8939 26.982 13.0509 -14.7057 26.6298 13.5062 -14.3201 25.9069 13.7717 -5.24415 8.89559 5.59621 -4.32619 7.17514 4.88005 -4.71583 7.90402 5.46776 -3.70559 6.01047 4.54724 -3.71299 6.02506 4.70848 -3.82139 6.22833 4.99455 -3.646 5.89916 4.93948 -3.66135 5.92818 5.11827 -3.63022 5.87093 5.24034 -3.7955 6.18059 5.63725 -3.60979 5.83206 5.54355 -3.64106 5.89022 5.76276 -3.33608 5.31995 5.46207 -3.2024 5.06757 5.40836 -3.17685 5.01982 5.52652 -3.07293 4.8267 5.51065 -2.94613 4.58926 5.44305 -2.9694 4.63204 5.64575 -3.03149 4.74887 5.93266 -3.02423 4.73629 6.09463 -2.80499 4.32343 5.81598 -2.79089 4.29824 5.95788 -2.63319 4.00306 5.78088 -2.6098 3.95805 5.89628 -2.66291 4.05813 6.19839 -2.59755 3.937 6.2247 -2.23766 3.2609 5.48371 -2.18244 3.15875 5.50061 -2.13389 3.06688 5.53067 -2.1333 3.06506 5.69507 -2.04492 2.90059 5.60841 -2.04203 2.89386 5.77226 -1.96278 2.74679 5.70371 -1.86153 2.5555 5.54636 -1.83364 2.50418 5.63027 -1.77595 2.39634 5.61021 -1.78002 2.40318 5.8135 -1.74189 2.33303 5.86916 -1.70368 2.2618 5.92337 -1.65959 2.17748 5.94943 -1.62031 2.10518 6.0008 -1.5729 2.01643 6.01438 -1.53001 1.93525 6.04428 -1.49058 1.86071 6.09095 -1.5054 1.88891 6.43409 -1.42918 1.74605 6.29263 -1.39455 1.68242 6.38289 -1.38418 1.66339 6.6334 -1.33913 1.57891 6.67499 -1.26973 1.44912 6.54235 -0.987382 0.91764 4.74886 -0.954549 0.855337 4.74703 -0.954606 0.857118 5.04531 -1.01092 0.963432 5.9208 -0.966717 0.879806 5.89997 -0.961503 0.870889 6.31966 -0.827343 0.617834 5.18215 -0.774402 0.518059 4.92668 -0.742821 0.458749 4.94622 -0.72105 0.418694 5.16329 -0.711954 0.403687 5.7383 -0.691116 0.364383 6.23398 -0.644283 0.276328 6.10064 -0.600924 0.193467 6.01548 -0.558981 0.115429 5.96853 -0.518398 0.0391987 5.99997 -1.46223 1.6832 -1.00648 -1.49692 1.74324 -1.00766 -1.52837 1.79889 -1.00008 -1.56414 1.86004 -0.997713 -1.60335 1.92877 -1.00014 -1.6504 2.01152 -1.01353 -1.68633 2.07497 -1.00496 -1.73109 2.15242 -1.00696 -1.77486 2.23004 -1.00645 -1.82415 2.31619 -1.0095 -1.87783 2.40894 -1.01551 -1.92722 2.49637 -1.01262 -1.98989 2.60539 -1.02359 -2.06153 2.73056 -1.04172 -2.12092 2.83441 -1.0395 -2.19374 2.96193 -1.04915 -2.26313 3.08211 -1.04929 -2.34056 3.21959 -1.05485 -2.42447 3.36471 -1.06023 -2.52188 3.53469 -1.07392 -2.61049 3.69089 -1.07266 -2.718 3.87849 -1.08268 -2.82666 4.06838 -1.0857 -2.95437 4.29179 -1.09731 -3.08664 4.52418 -1.10439 -2.80766 4.03638 -0.783838 -2.80458 4.03026 -0.6887 -2.8049 4.03075 -0.597714 -2.79858 4.02074 -0.504067 -2.80223 4.02684 -0.417183 -2.80923 4.03862 -0.333203 -2.81622 4.0504 -0.249222 -2.85469 4.11961 -0.182187 -2.86497 4.13616 -0.0991629 -2.90334 4.20356 -0.0283329 -2.92156 4.23557 0.0525775 -2.96331 4.3089 0.125697 -3.14869 4.63393 0.250796 -3.28785 4.87728 0.311223 -15.3509 25.9698 -1.61279 -15.7616 26.6894 -1.1453 -15.7726 26.7094 -0.607893 -15.7417 26.6555 0.468584 -15.58 26.3729 1.00446 -15.8161 26.7856 1.54314 -15.1087 25.5507 2.03214 -15.1374 25.5997 2.54979 -15.1863 25.685 3.07333 -15.4719 26.1866 3.64346 -15.0028 25.3657 4.07533 -14.9935 25.3497 4.58961 -14.8216 25.0505 5.05969 -14.765 24.9512 5.55645 -14.7332 24.8959 6.06079 -14.1752 23.9204 6.35996 -14.2331 24.0222 6.88583 -14.9699 25.3126 8.27393 -14.6125 24.6865 8.62371 -14.0475 23.6999 8.83206 -14.6096 24.6818 9.69628 -14.0927 23.7785 9.90363 -15.1765 25.6756 11.188 -14.9841 25.338 11.6273 -15.3987 26.0649 12.5294 -15.6414 26.4894 13.3327 -5.4558 8.67055 5.24095 -5.00578 7.88351 5.04436 -4.92448 7.74271 5.15994 -5.10173 8.05309 5.52541 -3.9125 5.97185 4.50592 -3.89055 5.93344 4.63481 -3.87537 5.90712 4.77297 -3.82975 5.82673 4.87604 -3.84271 5.8496 5.04924 -3.88616 5.927 5.26693 -3.83267 5.83273 5.36362 -3.8479 5.85927 5.55286 -3.77084 5.72475 5.61834 -3.38168 5.04343 5.22121 -3.18173 4.69417 5.07517 -3.20478 4.73412 5.26129 -3.17838 4.6892 5.37471 -3.13714 4.61577 5.46179 -3.09384 4.54139 5.54733 -3.04255 4.4517 5.61785 -2.69786 3.84763 5.13364 -2.68268 3.82233 5.25202 -2.76555 3.96646 5.5686 -2.90399 4.21033 6.02179 -2.79274 4.01433 5.95936 -2.70639 3.86325 5.94271 -2.66303 3.78844 6.01956 -2.3584 3.25376 5.4667 -2.28446 3.1258 5.44593 -2.27601 3.11124 5.58688 -2.20979 2.99438 5.57683 -2.15501 2.89933 5.59577 -2.10356 2.80938 5.62055 -2.0135 2.65069 5.52711 -1.99497 2.61964 5.6468 -1.855 2.37392 5.37644 -1.8375 2.34362 5.49208 -1.91197 2.47457 5.93692 -1.85481 2.37453 5.9334 -1.80903 2.29494 5.97155 -1.76201 2.21188 5.99906 -1.72651 2.15078 6.07869 -1.70793 2.11729 6.22984 -1.62801 1.97805 6.11635 -1.62089 1.96504 6.3302 -1.58318 1.90032 6.41513 -1.51797 1.78612 6.35919 -1.47553 1.71112 6.41301 -1.49154 1.73917 6.81533 -1.44356 1.65544 6.86841 -1.3199 1.44014 6.42263 -1.03146 0.934052 4.74918 -0.996632 0.871909 4.74816 -0.966516 0.819362 4.78447 -1.06948 1.0004 5.98911 -1.02117 0.915588 5.95955 -0.985644 0.8533 6.05565 -0.957255 0.804454 6.24927 -0.809187 0.544741 4.96089 -0.773252 0.481752 4.94149 -0.739793 0.424022 4.97038 -0.743505 0.430181 5.70426 -0.727824 0.40406 6.30999 -0.679369 0.319121 6.23738 -0.634577 0.239846 6.263 -0.584418 0.152417 6.01711 -0.540533 0.0759711 5.95948 -1.53156 1.68682 -1.01089 -1.56825 1.74678 -1.01108 -1.60164 1.80136 -1.00266 -1.64273 1.86792 -1.006 -1.68395 1.93658 -1.00723 -1.72613 2.0043 -1.00623 -1.77281 2.08056 -1.00948 -1.81951 2.15695 -1.01013 -1.86623 2.23346 -1.00829 -1.92184 2.32501 -1.01585 -1.97409 2.4102 -1.01437 -2.03524 2.51048 -1.02139 -2.10624 2.62483 -1.03598 -2.17294 2.73389 -1.04107 -2.23972 2.84415 -1.04222 -2.31642 2.96954 -1.04968 -2.38976 3.08859 -1.04769 -2.48097 3.23891 -1.06058 -2.56883 3.38293 -1.06322 -2.66662 3.54222 -1.06947 -2.77001 3.71127 -1.07415 -2.89337 3.91271 -1.08915 -3.01232 4.10698 -1.09246 -3.14685 4.32718 -1.09995 -2.85446 3.84935 -0.776603 -2.85137 3.84313 -0.683563 -2.84622 3.83598 -0.591366 -2.85092 3.84294 -0.506332 -2.84905 3.84039 -0.418487 -2.85608 3.85305 -0.336854 -2.85848 3.8551 -0.252465 -2.91437 3.94782 -0.195908 -2.9257 3.9652 -0.114934 -2.95048 4.00653 -0.0402312 -2.98966 4.07085 0.0300451 -3.60403 5.0744 -0.101447 -3.66999 5.18301 -0.0155985 -3.31412 4.60086 0.290955 -16.5076 26.1678 -1.40933 -16.7874 26.6254 -0.904074 -18.7468 29.8281 -0.521172 -22.7168 36.3193 -0.108241 -16.1796 25.6335 0.742469 -16.0335 25.3945 1.26449 -15.9865 25.3187 1.78185 -15.8626 25.1157 2.29014 -15.9368 25.2376 2.81413 -16.0065 25.351 3.34357 -16.3822 25.9666 3.93575 -16.464 26.1004 5.03281 -15.728 24.8976 5.36641 -15.2589 24.1309 5.73794 -15.2843 24.1742 6.25639 -15.3372 24.2587 6.79005 -15.3324 24.2526 7.30712 -15.3889 24.3457 7.85607 -15.2794 24.1663 8.33047 -15.21 24.0535 8.82376 -15.3466 24.2762 9.434 -15.8691 25.132 10.2933 -15.9948 25.3382 10.9424 -16.8496 26.7362 12.7227 -17.1674 27.2566 13.5905 -16.2932 25.8277 13.5451 -16.1527 25.5975 14.0516 -5.51727 8.20556 5.38486 -5.57497 8.30115 5.64251 -5.6996 8.5056 5.97228 -5.62564 8.3849 6.11776 -4.09838 5.88533 4.74683 -3.99518 5.71731 4.7928 -3.97342 5.68203 4.92444 -4.02642 5.76801 5.14455 -4.01028 5.74205 5.2888 -4.08793 5.86893 5.5546 -3.1088 4.26774 4.43895 -3.06797 4.20172 4.51415 -3.216 4.44445 4.85539 -3.30032 4.58202 5.12223 -2.97665 4.05291 4.77947 -3.00623 4.10141 4.96362 -2.96641 4.03541 5.04041 -2.90102 3.92978 5.07597 -2.89476 3.91875 5.20971 -2.78449 3.7383 5.15842 -2.82759 3.80933 5.38854 -2.70719 3.61203 5.3088 -2.9082 3.94063 5.86806 -2.8248 3.80418 5.8668 -2.7964 3.75943 5.98132 -2.56497 3.38026 5.63921 -2.38952 3.09304 5.39894 -2.36881 3.05961 5.50845 -2.34358 3.01804 5.60998 -2.28816 2.92853 5.63887 -2.28205 2.91865 5.79579 -2.07268 2.57626 5.39315 -2.15641 2.71298 5.8038 -1.91878 2.32398 5.27658 -1.85863 2.22524 5.25519 -1.85135 2.21299 5.40342 -1.84971 2.20976 5.57861 -1.93717 2.35378 6.08009 -1.86366 2.23436 6.02987 -2.16661 2.73037 7.41727 -1.75132 2.04991 6.03695 -1.68111 1.93587 5.97793 -1.64582 1.87802 6.06271 -1.63993 1.86835 6.28499 -1.59681 1.79798 6.35041 -1.55932 1.73661 6.44247 -1.55938 1.73788 6.75059 -1.50941 1.65482 6.79465 -1.41645 1.50378 6.58921 -1.07858 0.950745 4.75888 -1.03947 0.884927 4.73924 -1.00742 0.833528 4.77611 -1.12072 1.01987 5.97892 -1.15434 1.07487 6.68237 -1.03084 0.873237 6.02736 -1.00718 0.833592 6.27056 -0.954851 0.748842 6.23741 -0.805679 0.504111 4.9464 -0.768985 0.444127 4.94618 -0.73819 0.393678 5.04408 -0.736244 0.39068 5.7483 -0.712473 0.352559 6.24404 -0.667054 0.277349 6.31031 -0.612847 0.189209 6.06538 -0.564601 0.111092 5.92846 -0.520334 0.0380808 6.00002 -1.59403 1.67554 -1.00051 -1.63603 1.74089 -1.007 -1.67574 1.8008 -1.00449 -1.71445 1.86087 -1.00008 -1.76631 1.94032 -1.01353 -1.80611 2.00154 -1.00489 -1.85474 2.07674 -1.00699 -1.90876 2.15846 -1.01256 -1.95842 2.23386 -1.00938 -2.02135 2.33077 -1.02135 -2.07655 2.41485 -1.01833 -2.14503 2.52051 -1.02917 -2.21897 2.63379 -1.04162 -2.28961 2.7417 -1.04478 -2.36473 2.85732 -1.04915 -2.44531 2.98059 -1.05422 -2.53149 3.11354 -1.05961 -2.62308 3.25319 -1.06476 -2.72027 3.40257 -1.06933 -2.82846 3.56818 -1.07696 -2.94758 3.74907 -1.08682 -3.07132 3.93986 -1.09369 -3.16639 4.08576 -1.06984 -2.90238 3.68105 -0.774705 -2.89283 3.66728 -0.679851 -2.88315 3.65146 -0.586096 -2.88784 3.6583 -0.50326 -2.88595 3.65566 -0.417512 -2.89397 3.66814 -0.338179 -2.91637 3.70343 -0.267067 -2.95516 3.76146 -0.202586 -2.97645 3.79493 -0.128876 -2.99217 3.81888 -0.0518572 -3.72955 4.94917 -0.147508 -3.41176 4.46163 0.252264 -16.8887 25.1103 -1.61823 -18.0562 26.8991 -1.2407 -19.0628 28.4423 -0.774258 -23.1576 34.7154 -0.440648 -16.7571 24.9098 0.485847 -16.8362 25.0312 1.00502 -16.7298 24.8678 1.52337 -16.6831 24.7979 2.03903 -16.6606 24.7627 2.55464 -16.7519 24.9029 3.08443 -16.8002 24.9775 3.61441 -17.2938 25.7348 4.23512 -17.3587 25.8338 4.79283 -16.188 24.0411 5.03937 -16.2119 24.0775 5.55857 -16.1341 23.9581 6.04924 -16.1416 23.9715 6.56868 -16.1345 23.9605 7.0861 -16.2171 24.0876 7.64532 -16.2256 24.1006 8.18018 -16.2707 24.1708 8.73824 -16.0215 23.788 9.14974 -17.2107 25.6117 10.355 -17.8103 26.5301 11.2986 -18.9802 28.3241 12.651 -18.3572 27.3701 12.9008 -17.8116 26.5334 14.4541 -17.8649 26.6162 15.1555 -17.9593 26.7622 15.9067 -5.91714 8.30497 6.05462 -4.32446 5.86453 4.72414 -4.18311 5.64712 4.73914 -4.19473 5.66475 4.9062 -4.13767 5.57772 5.00306 -4.10829 5.53261 5.12932 -4.23308 5.72408 5.4401 -3.27537 4.25617 4.42878 -3.18922 4.12291 4.4481 -3.739 4.96705 5.30948 -3.6575 4.84299 5.35816 -3.10412 3.99339 4.72565 -3.4965 4.59519 5.44397 -2.9974 3.8299 4.8383 -3.02673 3.8744 5.02255 -2.90282 3.68429 4.96211 -3.09566 3.98195 5.43384 -3.04948 3.91025 5.50925 -2.87884 3.64817 5.35662 -2.84388 3.59556 5.44634 -3.02461 3.87294 5.95939 -2.93293 3.73258 5.95016 -2.62418 3.25824 5.47615 -2.57703 3.18781 5.53568 -2.66773 3.32605 5.90457 -2.53358 3.11974 5.76819 -2.50083 3.07033 5.86435 -2.39898 2.91431 5.79007 -2.1031 2.46024 5.19463 -2.01338 2.32316 5.11264 -2.02502 2.33994 5.30297 -1.97441 2.26388 5.32566 -1.93594 2.20475 5.38068 -1.87736 2.11467 5.37397 -1.8545 2.07912 5.47859 -2.47013 3.02448 7.79057 -2.23404 2.6622 7.23769 -1.83211 2.04554 6.00683 -1.77697 1.96133 6.02144 -1.71834 1.8703 6.01588 -1.71928 1.87264 6.26577 -1.69898 1.84255 6.44299 -1.72352 1.87909 6.84474 -1.64269 1.75642 6.76078 -1.58302 1.6641 6.7681 -1.51892 1.56598 6.75431 -1.13665 0.979642 4.82558 -1.08554 0.900699 4.74929 -1.04808 0.8442 4.75772 -1.25093 1.1558 6.531 -1.21622 1.10312 6.70042 -1.09612 0.918777 6.15517 -1.04747 0.842385 6.17355 -0.995637 0.764118 6.17053 -0.84924 0.539205 5.05964 -0.802473 0.466932 4.96137 -0.76502 0.409953 4.98033 -0.768795 0.416605 5.7242 -0.747324 0.383377 6.22028 -0.69767 0.306986 6.23747 -0.646821 0.229604 6.21306 -0.593097 0.147383 6.00709 -0.544404 0.0737255 5.95936 -1.62887 1.62277 -1.01084 -1.66512 1.67508 -1.00403 -1.70907 1.73936 -1.00948 -1.75403 1.80369 -1.01263 -1.79575 1.86363 -1.00713 -1.84617 1.93554 -1.01269 -1.89229 2.00213 -1.00935 -1.94818 2.08166 -1.01632 -1.99977 2.15588 -1.01429 -2.06019 2.24415 -1.02172 -2.11287 2.31957 -1.01436 -2.18959 2.42938 -1.03266 -2.26195 2.5329 -1.04142 -2.33446 2.63861 -1.04638 -2.41337 2.75089 -1.05261 -2.49243 2.86537 -1.05474 -2.57696 2.98752 -1.05748 -2.67241 3.1248 -1.06524 -2.77433 3.26976 -1.07232 -2.88087 3.42451 -1.07841 -2.99388 3.58699 -1.08271 -3.09809 3.73567 -1.07247 -3.02401 3.62932 -0.920986 -2.93681 3.50482 -0.767025 -2.97539 3.55964 -0.70689 -2.98665 3.57595 -0.627465 -2.91585 3.47532 -0.497911 -2.92491 3.48865 -0.420628 -2.93386 3.49998 -0.343246 -2.95173 3.52654 -0.271476 -2.99149 3.58438 -0.209695 -3.01471 3.61662 -0.138238 -3.05338 3.6727 -0.0728589 -3.84936 4.81803 -0.299573 -3.85629 4.82782 -0.194969 -3.58219 4.43341 0.194132 -3.62416 4.49335 0.280627 -17.6938 24.7262 -1.36486 -18.3878 25.7239 -0.910737 -19.4869 27.3056 -0.446164 -23.5674 33.1743 -0.0508705 -23.5974 33.2176 0.654083 -23.4834 33.0528 1.35847 -19.5665 27.4214 1.88051 -19.6574 27.5516 2.47116 -19.1841 26.8716 3.00754 -18.0012 25.1717 3.95746 -17.8724 24.9865 4.47281 -18.0611 25.2588 5.05565 -17.6961 24.7336 5.50764 -21.2298 29.8153 7.08343 -18.8085 26.334 6.95011 -18.394 25.7376 7.38328 -18.528 25.931 8.0073 -18.72 26.2074 9.26054 -18.3649 25.6973 9.68539 -18.5055 25.9003 10.3495 -18.6813 26.1532 11.0491 -20.7707 29.1587 12.8892 -20.0627 28.1408 13.1431 -19.1126 26.7749 13.8514 -4.61509 5.92123 5.2495 -4.4505 5.68514 5.24394 -4.42236 5.64347 5.38033 -3.84289 4.81171 5.33743 -3.29038 4.01647 4.89167 -3.33497 4.08017 5.09731 -3.04206 3.65912 4.8067 -3.08891 3.7269 5.01643 -2.96029 3.54194 4.95306 -2.90341 3.46046 5.00018 -2.85531 3.39106 5.05907 -2.92316 3.48835 5.32308 -2.89065 3.44289 5.41834 -2.90443 3.46219 5.60143 -2.94144 3.5149 5.8391 -2.71874 3.19429 5.55562 -2.74148 3.22762 5.7695 -2.68346 3.14405 5.81383 -2.64204 3.08442 5.89572 -2.5044 2.88697 5.75152 -2.19504 2.44137 5.16896 -2.08925 2.28865 5.0553 -2.03888 2.2166 5.07829 -2.05939 2.24612 5.29347 -2.10216 2.30831 5.58781 -1.99297 2.15041 5.44659 -2.19233 2.43904 6.24883 -2.46619 2.83353 7.35457 -2.52151 2.91216 7.81302 -2.20372 2.45546 6.99667 -2.17578 2.41537 7.16522 -1.80185 1.87622 6.01447 -1.74263 1.79165 6.01681 -1.76468 1.82337 6.35903 -1.72333 1.76433 6.45271 -1.66739 1.6828 6.48001 -1.6272 1.62551 6.59031 -1.58372 1.5639 6.69044 -1.18087 0.983534 4.79618 -1.13013 0.909569 4.73977 -1.09174 0.854162 4.74884 -1.06918 0.822571 4.87289 -1.27973 1.12575 6.70822 -1.12674 0.904703 5.96974 -1.09113 0.854923 6.1156 -1.06229 0.813622 6.33938 -0.994838 0.715874 6.20795 -0.835777 0.487231 4.96627 -0.796209 0.429428 4.96606 -0.762541 0.381159 5.06397 -0.763143 0.383478 5.8379 -0.730344 0.335962 6.19419 -0.681112 0.264494 6.25038 -0.622094 0.180156 5.99538 -0.571347 0.106676 5.92853 -0.522208 0.0364654 5.98997 -1.61923 1.51366 -1.01801 -1.65203 1.5584 -1.0064 -1.69453 1.61495 -1.00765 -1.73603 1.67165 -1.007 -1.78292 1.73481 -1.01131 -1.82551 1.79264 -1.00682 -1.88218 1.86881 -1.02003 -1.92153 1.92235 -1.0049 -1.97829 1.99976 -1.01317 -2.02737 2.06534 -1.00639 -2.09603 2.15774 -1.02139 -2.1594 2.2449 -1.02718 -2.22378 2.33216 -1.02978 -2.29901 2.43342 -1.04035 -2.36993 2.52938 -1.04161 -2.45171 2.63937 -1.05005 -2.53895 2.75702 -1.05929 -2.62189 2.86937 -1.05914 -2.71569 2.99585 -1.06435 -2.80959 3.12357 -1.06472 -2.92629 3.28134 -1.07833 -3.02782 3.41894 -1.07253 -2.97365 3.3446 -0.93887 -2.96633 3.33463 -0.845619 -2.96785 3.33873 -0.761227 -2.95828 3.32479 -0.669768 -2.99778 3.37846 -0.611684 -3.05899 3.46031 -0.565437 -2.95691 3.32216 -0.421724 -2.9649 3.33445 -0.346386 -2.98475 3.36079 -0.27672 -3.01447 3.40134 -0.211821 -3.04412 3.44095 -0.145574 -3.09017 3.50336 -0.0852579 -3.94338 4.65755 -0.12453 -3.673 4.29232 0.250993 -17.6823 23.2375 -1.52294 -18.6079 24.4883 -1.12388 -18.6392 24.5309 -0.593118 -23.8756 31.6124 -0.365608 -23.8802 31.6192 0.320978 -23.9012 31.648 1.00737 -23.838 31.5625 1.69252 -23.9518 31.7174 2.38484 -19.576 25.7989 2.68758 -20.0944 26.5017 3.31093 -24.0061 31.7925 4.46647 -20.2535 26.7166 4.49852 -19.1286 25.1953 4.85325 -24.0833 31.898 6.58261 -24.0978 31.9175 7.29444 -24.1047 31.9275 8.00878 -24.1104 31.9348 8.72748 -24.148 31.9871 9.46307 -24.2018 32.0592 10.2123 -24.2056 32.0656 10.9503 -24.1044 31.9298 11.6473 -19.2418 25.3523 10.0467 -4.58656 5.53021 5.299 -3.44648 3.98838 4.7383 -3.40305 3.92877 4.8181 -3.31149 3.80568 4.83355 -3.25819 3.73277 4.89625 -3.35635 3.86633 5.18011 -3.33386 3.83638 5.29687 -3.07649 3.48734 5.04514 -2.97827 3.3551 5.02995 -3.0501 3.45211 5.29305 -2.98036 3.35756 5.32407 -2.99184 3.37257 5.49878 -2.97605 3.35299 5.6306 -2.86895 3.20796 5.58946 -2.82116 3.14305 5.65834 -2.51068 2.72286 5.18176 -2.41993 2.59977 5.13773 -2.41938 2.59931 5.28935 -2.33301 2.4821 5.248 -2.17187 2.26498 5.02272 -2.13055 2.2087 5.0712 -2.1201 2.19479 5.20231 -2.1328 2.21197 5.40204 -2.13234 2.21171 5.57797 -2.07015 2.1274 5.58191 -1.99037 2.02036 5.53111 -2.36726 2.52986 6.9164 -2.40792 2.58503 7.30901 -2.32716 2.47562 7.3102 -2.29388 2.42993 7.48077 -1.82061 1.78999 5.99758 -1.64998 1.55919 5.56618 -1.75821 1.70592 6.24832 -1.71381 1.64652 6.33122 -1.71486 1.64823 6.6293 -1.63714 1.54263 6.56961 -1.2182 0.974905 4.72849 -1.17783 0.919713 4.73947 -1.13533 0.863107 4.73962 -1.07039 0.774513 4.59361 -1.049 0.745803 4.71651 -1.19122 0.939266 6.05735 -0.931192 0.585904 4.42375 -1.08655 0.796999 6.09495 -1.01741 0.704381 5.96378 -0.89241 0.533954 5.18809 -0.829515 0.449741 4.97126 -0.789189 0.394943 4.99023 -0.796264 0.404381 5.77399 -0.764829 0.362311 6.14061 -0.720823 0.302002 6.36713 -0.656701 0.216022 6.11325 -0.600595 0.140426 5.97715 -0.54915 0.0704391 5.93937 -1.6524 1.46671 -1.03432 -1.6742 1.49411 -1.00147 -1.72188 1.55396 -1.01072 -1.76963 1.61491 -1.01803 -1.80445 1.65972 -1.00253 -1.85766 1.72822 -1.01265 -1.89781 1.77856 -1.00046 -1.95642 1.85366 -1.01264 -2.00635 1.917 -1.00936 -2.06174 1.98785 -1.00999 -2.12251 2.06522 -1.01428 -2.1843 2.14266 -1.01568 -2.25593 2.23412 -1.02594 -2.33302 2.33317 -1.03831 -2.41213 2.43228 -1.04689 -2.486 2.52715 -1.04632 -2.56527 2.62863 -1.04741 -2.6564 2.74413 -1.05467 -2.74861 2.8608 -1.05739 -2.85175 2.9926 -1.06523 -2.95591 3.12461 -1.06768 -3.03305 3.22251 -1.04255 -2.98789 3.16517 -0.919094 -2.99046 3.17014 -0.836153 -2.99929 3.17954 -0.757473 -3.01158 3.19655 -0.682795 -3.00646 3.19009 -0.596939 -3.13889 3.35868 -0.59596 -2.99834 3.17977 -0.431076 -3.00833 3.19187 -0.357142 -3.0162 3.2021 -0.283003 -3.05335 3.24997 -0.223117 -3.08394 3.28843 -0.158821 -3.15028 3.3722 -0.108195 -3.98167 4.43053 -0.145107 -14.9344 18.3665 -1.65669 -17.8141 22.0315 -1.69245 -18.444 22.8335 -1.27973 -18.8917 23.4023 -0.814544 -19.0563 23.6122 -0.305275 -24.182 30.1348 0.00395854 -24.2017 30.1598 0.672829 -24.2073 30.1677 1.34233 -24.2313 30.1975 2.01324 -24.2652 30.242 2.68687 -20.6538 25.6471 3.0015 -24.3068 30.2957 4.03994 -24.3005 30.2886 4.71676 -24.3181 30.3115 5.39977 -24.377 30.3866 6.09536 -24.3978 30.4128 6.7883 -24.4111 30.4305 7.4839 -24.4102 30.429 8.18024 -24.4561 30.4879 8.89644 -24.4815 30.521 9.61313 -24.5056 30.5515 10.336 -24.5321 30.5863 11.0677 -24.5031 30.5493 11.7825 -3.50144 3.82295 5.00834 -3.4441 3.74939 5.0731 -3.39447 3.68695 5.14898 -3.18988 3.42678 4.99366 -3.16519 3.39427 5.09665 -3.12866 3.34873 5.18532 -3.10073 3.31236 5.28761 -3.06641 3.26999 5.38213 -3.01888 3.20922 5.454 -3.01176 3.19983 5.59949 -2.93364 3.10008 5.61651 -3.47636 3.79162 6.84991 -2.54453 2.60459 5.16426 -2.4762 2.51791 5.17376 -2.4527 2.48837 5.27729 -2.31753 2.3156 5.12825 -2.29295 2.28495 5.22844 -2.24424 2.22276 5.27015 -2.27438 2.26108 5.51278 -2.20598 2.17385 5.5111 -2.0817 2.01596 5.35185 -2.03412 1.95583 5.39596 -2.03917 1.9625 5.59684 -1.9894 1.89943 5.63971 -1.93087 1.82545 5.65423 -1.92604 1.81829 5.84746 -1.76086 1.60772 5.4867 -1.70993 1.54287 5.51244 -1.83073 1.69769 6.21123 -1.81738 1.68103 6.4249 -1.80185 1.66099 6.64866 -1.75768 1.604 6.76008 -1.27082 0.983172 4.73677 -1.22305 0.923025 4.71981 -1.18626 0.876034 4.7589 -1.40438 1.15465 6.29071 -1.08613 0.748732 4.67929 -1.04721 0.700204 4.70505 -0.985899 0.621659 4.56382 -0.953553 0.580564 4.62602 -1.04782 0.701845 5.80843 -1.0429 0.695336 6.27696 -0.866873 0.469772 4.99587 -0.821255 0.412358 4.97596 -0.783471 0.363351 5.054 -0.793283 0.377551 5.97728 -0.744852 0.316087 6.09445 -0.695418 0.253105 6.24044 -0.630284 0.170172 5.92554 -0.577157 0.102304 5.94854 -0.524146 0.0348432 6.00005 -1.70201 1.44082 -1.01063 -1.74199 1.48877 -1.00643 -1.7863 1.5422 -1.00754 -1.82736 1.59125 -0.999996 -1.88238 1.65658 -1.01127 -1.92784 1.71224 -1.00678 -1.97962 1.7733 -1.00681 -2.03148 1.83547 -1.00479 -2.09305 1.90957 -1.01313 -2.15038 1.97936 -1.01252 -2.21941 2.06102 -1.02138 -2.28853 2.14382 -1.0271 -2.36304 2.2332 -1.03537 -2.43325 2.31726 -1.03464 -2.52068 2.4217 -1.04704 -2.59738 2.51348 -1.04463 -2.68598 2.62026 -1.04895 -2.78 2.73369 -1.05412 -2.88148 2.85468 -1.05951 -2.98844 2.98337 -1.06472 -3.04039 3.04468 -1.01921 -3.02779 3.03014 -0.923493 -3.04318 3.04891 -0.850122 -3.04017 3.04433 -0.764172 -3.04155 3.04627 -0.683076 -3.04832 3.05471 -0.606038 -3.04752 3.05374 -0.525586 -3.17286 3.20405 -0.517555 -3.03733 3.04237 -0.363163 -3.04618 3.05246 -0.290625 -3.0788 3.09162 -0.229881 -3.11683 3.13742 -0.170398 -3.17318 3.20487 -0.117103 -3.96949 4.15952 0.239995 -18.7198 21.8398 -1.48233 -20.1577 23.5624 -1.13934 -20.1013 23.4955 -0.597225 -20.3213 23.759 -0.0740171 -24.5055 28.7755 0.353664 -24.5413 28.8188 1.00771 -24.5306 28.8069 1.66247 -24.5642 28.8466 2.31962 -24.5783 28.8634 2.97762 -24.5968 28.886 3.6382 -24.6337 28.931 4.30399 -24.6566 28.9587 4.9714 -24.6654 28.9694 5.63995 -24.699 29.01 6.31717 -24.7046 29.0172 6.99292 -24.7222 29.039 7.67577 -24.7385 29.0582 8.36338 -24.7528 29.0757 9.05588 -24.7898 29.1206 9.76271 -24.7934 29.1252 10.4644 -24.8261 29.165 11.1845 -24.8373 29.179 11.9036 -3.624 3.74861 4.95318 -3.56038 3.67112 5.01206 -3.62062 3.74398 5.23928 -3.49737 3.59582 5.21662 -3.46321 3.55579 5.31812 -3.33228 3.39796 5.27315 -3.24707 3.29678 5.29309 -3.09657 3.11577 5.20192 -3.26765 3.32069 5.63781 -3.17695 3.21221 5.64562 -2.73403 2.68106 5.01584 -2.46165 2.35457 4.65476 -2.40118 2.28169 4.66884 -2.58437 2.50113 5.16942 -2.55665 2.46846 5.26552 -2.39937 2.27948 5.08628 -2.33892 2.20681 5.10465 -2.31775 2.18234 5.21222 -2.29104 2.14977 5.31151 -2.25576 2.10883 5.39355 -2.18007 2.01805 5.37216 -2.10213 1.92384 5.33944 -2.10606 1.92912 5.5312 -1.99215 1.79251 5.38885 -2.04737 1.85827 5.74972 -2.39873 2.27958 7.08554 -2.0861 1.90537 6.32066 -1.89126 1.67195 5.88803 -1.7946 1.55451 5.76876 -1.7211 1.4677 5.72915 -1.85449 1.62725 6.51804 -1.77663 1.53418 6.48836 -1.32221 0.988015 4.73521 -1.27362 0.930436 4.72854 -1.2326 0.880771 4.74906 -1.48239 1.18168 6.36429 -1.11766 0.743531 4.61297 -1.07886 0.697012 4.63893 -1.05442 0.667462 4.76139 -0.986876 0.586795 4.59007 -0.960246 0.554286 4.71088 -1.06859 0.684632 6.05245 -0.933098 0.522362 5.28683 -0.856436 0.430552 4.98115 -0.812239 0.377999 5.00024 -0.81471 0.381244 5.71434 -0.775487 0.333203 5.95134 -0.724056 0.272394 6.05789 -0.660787 0.196841 5.87357 -0.607969 0.132989 5.9172 -0.552775 0.0662277 5.89941 -1.76436 1.42812 -1.00868 -1.80628 1.47499 -1.00364 -1.85253 1.52735 -1.00401 -1.90417 1.58615 -1.00933 -1.9515 1.63964 -1.00585 -2.00421 1.69959 -1.00703 -2.06326 1.76495 -1.01262 -2.11706 1.82607 -1.00926 -2.18151 1.89806 -1.01622 -2.24609 1.97219 -1.02037 -2.31707 2.0528 -1.02759 -2.38369 2.1271 -1.02586 -2.46753 2.22173 -1.03825 -2.54062 2.3037 -1.03584 -2.63094 2.40605 -1.04625 -2.72129 2.50862 -1.05247 -2.80833 2.60582 -1.04949 -2.91162 2.72357 -1.05734 -3.02337 2.84884 -1.06511 -3.05264 2.88226 -1.00296 -3.06364 2.89442 -0.926531 -3.09719 2.93245 -0.867338 -3.10607 2.94275 -0.790406 -3.07744 2.91137 -0.689659 -3.0723 2.9048 -0.606201 -3.07255 2.90469 -0.5273 -3.28859 3.14925 -0.571335 -3.05595 2.88671 -0.364311 -3.07764 2.91067 -0.299945 -3.10479 2.94221 -0.23789 -3.13829 2.97929 -0.177649 -3.20841 3.05957 -0.13208 -4.23343 4.21579 0.26002 -15.4928 16.9297 -1.57154 -19.5463 21.5062 -1.75983 -21.2938 23.4798 -1.46147 -21.4441 23.6508 -0.925362 -21.4836 23.6949 -0.374996 -26.1694 28.9866 0.670394 -24.9296 27.5867 1.32952 -24.8748 27.5255 1.97066 -24.9921 27.6581 2.62101 -26.3413 29.1816 4.07613 -24.9762 27.6405 5.21457 -25.0873 27.7677 5.89086 -26.4631 29.3214 7.56239 -25.048 27.7233 8.54195 -25.2022 27.8986 9.26937 -25.2702 27.9759 9.97921 -25.2449 27.9478 11.3607 -25.1664 27.8585 12.0305 -3.94055 3.88782 4.18322 -3.8417 3.77597 4.21428 -3.73212 3.65297 4.22994 -3.78564 3.71247 4.80588 -3.76131 3.68535 4.91681 -3.66459 3.57591 4.93842 -3.55817 3.45619 4.94328 -3.67538 3.58934 5.24187 -3.56777 3.46654 5.24378 -3.47432 3.36175 5.26195 -3.86935 3.80782 5.99864 -3.48079 3.36915 5.58013 -3.40895 3.28864 5.6289 -3.16721 3.01479 5.3952 -2.72964 2.52041 4.80552 -2.47042 2.22717 4.48347 -2.45037 2.20577 4.57336 -2.42586 2.17723 4.65552 -2.42312 2.1748 4.78502 -2.3911 2.13829 4.8592 -2.27676 2.00897 4.76196 -2.30436 2.04045 4.96469 -2.30595 2.04206 5.12009 -2.35746 2.10016 5.40326 -2.28213 2.01487 5.39181 -2.20361 1.92721 5.36909 -2.13037 1.84354 5.35244 -2.04425 1.74774 5.29803 -2.06544 1.77063 5.54217 -2.29001 2.02457 6.42406 -2.22451 1.95014 6.46138 -1.95236 1.64253 5.81431 -1.92813 1.61522 5.96189 -1.81908 1.49309 5.814 -1.78825 1.45713 5.94111 -1.88308 1.56603 6.59247 -1.37223 0.987442 4.72392 -1.32494 0.934297 4.72733 -1.29182 0.896588 4.79618 -1.69116 1.34905 7.07944 -1.45922 1.08728 6.23292 -1.12576 0.709268 4.65996 -1.07954 0.657721 4.65648 -1.05081 0.624432 4.75903 -0.99357 0.560521 4.67502 -1.08339 0.662634 5.76909 -0.883179 0.435729 4.472 -0.89797 0.451809 5.03552 -0.846301 0.394779 4.99579 -0.804585 0.347525 5.06396 -0.801641 0.344588 5.7682 -0.749027 0.283909 5.81537 -0.697956 0.227529 5.95093 -0.639657 0.161091 5.89549 -0.582842 0.0974508 5.93853 -0.526081 0.0337204 6 -1.82659 1.41345 -1.00634 -1.87046 1.45923 -1.00046 -1.91865 1.51051 -0.999981 -1.97216 1.56724 -1.00441 -2.02144 1.61965 -0.999992 -2.09203 1.69464 -1.01995 -2.14139 1.74827 -1.01118 -2.2024 1.8127 -1.01303 -2.26447 1.87819 -1.01244 -2.34263 1.962 -1.02727 -2.41118 2.03511 -1.0271 -2.48506 2.11377 -1.02963 -2.57178 2.20631 -1.04024 -2.65952 2.29897 -1.04695 -2.74735 2.39282 -1.04992 -2.84158 2.49325 -1.05405 -2.94327 2.60121 -1.05901 -3.05138 2.71579 -1.06422 -3.08697 2.75454 -1.00828 -3.09257 2.76017 -0.928398 -3.1025 2.77133 -0.853216 -3.10599 2.77506 -0.773924 -3.10835 2.77684 -0.695028 -3.10226 2.77127 -0.612715 -3.1025 2.77111 -0.534812 -3.17122 2.84507 -0.496933 -3.09234 2.76049 -0.377333 -3.10863 2.77785 -0.311006 -3.13026 2.80077 -0.24739 -3.17114 2.8442 -0.191813 -3.22482 2.9007 -0.140064 -4.27563 4.02098 0.226216 -21.0426 21.8713 -1.61837 -22.8942 23.8425 -1.27988 -22.9315 23.8827 -0.709688 -23.2021 24.17 -0.150421 -25.3072 26.4111 0.375736 -25.3373 26.4447 1.00817 -25.1895 26.2873 1.63762 -25.288 26.3922 2.27253 -25.3095 26.4154 2.90743 -25.4198 26.5331 3.55355 -25.4606 26.5767 4.19804 -25.3632 26.4734 4.82551 -25.3279 26.4359 5.46116 -25.4265 26.5412 6.12548 -25.5231 26.645 6.7978 -25.5446 26.6675 7.45917 -25.5169 26.6385 8.11198 -25.4216 26.5373 8.74653 -25.5247 26.6482 9.4482 -25.646 26.777 10.1673 -25.6848 26.8184 10.8665 -25.6218 26.752 11.532 -25.4923 26.614 12.1707 -12.5195 12.8004 8.09896 -4.03444 3.76504 4.22845 -3.90278 3.62566 4.23093 -3.87525 3.59606 4.32838 -4.88272 4.66897 5.82806 -3.85882 3.57919 4.83674 -3.74317 3.45594 4.84003 -3.64466 3.35043 4.85785 -3.57205 3.27389 4.90463 -3.5101 3.20728 4.96237 -3.42232 3.11335 4.98396 -3.9448 3.67118 5.86384 -3.56218 3.26282 5.47714 -3.2463 2.92704 5.15884 -2.69231 2.3369 4.43824 -2.61944 2.25822 4.44157 -2.57359 2.21011 4.48758 -2.56217 2.19801 4.59358 -2.48398 2.11497 4.58344 -2.62666 2.2665 4.98028 -2.42996 2.05812 4.74638 -2.39699 2.02261 4.81932 -2.48053 2.11162 5.13751 -2.44656 2.07567 5.22049 -2.44059 2.06843 5.37027 -2.39157 2.01706 5.42757 -2.70431 2.35078 6.36666 -2.31185 1.93268 5.59062 -2.29306 1.91278 5.7324 -2.14022 1.74959 5.51251 -2.20043 1.81454 5.88339 -2.10049 1.70711 5.8002 -2.03091 1.63326 5.80407 -1.93423 1.53034 5.71453 -1.98705 1.58681 6.12783 -1.82316 1.41261 5.79411 -1.97699 1.57626 6.63003 -1.90644 1.50165 6.65758 -1.37173 0.930456 4.70691 -1.3312 0.887783 4.74761 -1.77188 1.35785 7.09223 -1.62611 1.20214 6.74887 -1.16805 0.713318 4.65159 -1.10455 0.645987 4.55168 -1.08918 0.630289 4.74188 -1.04202 0.579726 4.73686 -0.988255 0.522043 4.68146 -0.92465 0.455451 4.53575 -0.899493 0.428227 4.70416 -0.883357 0.410853 5.00098 -0.836287 0.360481 5.02008 -0.841061 0.366567 5.77398 -0.791181 0.313731 5.90154 -0.729963 0.24808 5.8584 -0.669854 0.184288 5.81366 -0.614469 0.125584 5.8972 -0.555464 0.0625695 5.86943 -1.84684 1.35092 -1.00869 -1.89058 1.39467 -1.00361 -1.94502 1.4502 -1.01099 -1.99615 1.50035 -1.00937 -2.0516 1.55602 -1.01256 -2.10813 1.61274 -1.0136 -2.16999 1.67493 -1.01905 -2.22223 1.72643 -1.0092 -2.29055 1.79619 -1.01617 -2.3652 1.87141 -1.02635 -2.44087 1.94674 -1.03343 -2.5123 2.01774 -1.03157 -2.59445 2.10072 -1.03817 -2.68405 2.19117 -1.04679 -2.77468 2.28176 -1.05152 -2.86001 2.36709 -1.04724 -2.96982 2.4772 -1.05956 -3.07541 2.58304 -1.06223 -3.11824 2.62605 -1.01255 -3.12384 2.63164 -0.933665 -3.19856 2.70583 -0.904144 -3.13824 2.64637 -0.781291 -3.14066 2.64909 -0.703344 -3.14196 2.64986 -0.625794 -3.1358 2.64321 -0.545029 -3.1542 2.6624 -0.479607 -3.13208 2.63997 -0.392759 -3.14197 2.6508 -0.324169 -3.16453 2.6726 -0.261805 -3.19994 2.70841 -0.204717 -3.24815 2.75726 -0.152056 -3.3442 2.85256 -0.115899 -4.34045 3.85269 0.188461 -18.9846 18.5382 -1.51454 -22.9408 22.5061 -1.49379 -25.4069 24.9792 -1.14921 -25.4506 25.0231 -0.53459 -25.472 25.0455 0.0821384 -25.5007 25.0744 0.699297 -25.5081 25.0816 1.31736 -25.5284 25.1021 1.93649 -25.5476 25.1218 2.55716 -25.5743 25.1491 3.18032 -25.586 25.1604 3.80456 -25.617 25.1928 4.43375 -25.6276 25.2024 5.06319 -25.6575 25.2332 5.69937 -25.6725 25.2479 6.33674 -25.6929 25.2696 6.97964 -25.7196 25.2962 7.62886 -25.7378 25.3145 8.28116 -25.7539 25.3312 8.93855 -25.7829 25.3606 9.60604 -25.7958 25.374 10.2748 -25.8131 25.3916 10.9522 -25.8421 25.4211 11.6418 -25.822 25.4007 12.3178 -13.1691 12.7097 8.07399 -4.15887 3.67176 4.17811 -4.10688 3.61966 4.2573 -3.95429 3.46658 4.24116 -3.90226 3.4142 4.31475 -3.95838 3.47103 4.49703 -5.04423 4.55984 5.76616 -4.02675 3.53994 4.83644 -3.99615 3.50891 4.94178 -3.85957 3.37192 4.92585 -3.79471 3.30675 4.98884 -3.72345 3.23552 5.04316 -3.47007 2.98186 4.85869 -3.61196 3.12399 5.18632 -3.78607 3.29845 5.57813 -3.33855 2.8491 5.09513 -3.25864 2.76896 5.12121 -2.70159 2.21041 4.40708 -2.73952 2.24823 4.58831 -3.0339 2.544 5.20598 -2.65786 2.16704 4.71236 -2.61217 2.12127 4.76516 -2.50955 2.01759 4.71374 -2.44243 1.95087 4.72265 -2.67488 2.18436 5.32376 -2.55727 2.06619 5.24501 -2.47727 1.98636 5.23692 -2.81959 2.32965 6.16244 -2.75147 2.26092 6.21051 -2.3823 1.89145 5.53285 -2.60126 2.11028 6.26642 -2.3405 1.84847 5.80786 -2.27125 1.77932 5.82602 -2.13948 1.64679 5.66326 -2.12725 1.63418 5.83857 -2.03758 1.54575 5.78702 -1.99843 1.50602 5.88854 -1.90314 1.40931 5.80479 -1.81983 1.32661 5.75502 -1.98389 1.49159 6.62996 -1.41939 0.92454 4.68618 -1.37364 0.879259 4.70842 -1.84559 1.35264 7.05668 -1.70061 1.2079 6.75344 -1.17757 0.681624 4.46947 -1.16762 0.672114 4.66965 -1.10982 0.614352 4.60777 -1.09234 0.596787 4.79818 -1.01704 0.521076 4.61625 -0.966752 0.470119 4.57933 -0.897845 0.401346 4.3833 -0.905914 0.409869 4.86732 -0.867866 0.371428 4.97599 -0.826698 0.33062 5.0938 -0.821514 0.325334 5.76822 -0.757239 0.261428 5.67575 -0.706595 0.210519 5.84118 -0.6504 0.153897 5.94544 -0.588467 0.0916009 5.92857 -0.527956 0.0316007 5.99999 -1.90784 1.33231 -1.00634 -1.95883 1.38032 -1.00752 -2.00558 1.42402 -0.999956 -2.06191 1.47757 -1.00435 -2.12562 1.53747 -1.0134 -2.18834 1.59755 -1.01986 -2.24783 1.65325 -1.01756 -2.30632 1.70912 -1.01307 -2.38384 1.7821 -1.02476 -2.46138 1.85523 -1.03325 -2.53367 1.92411 -1.03289 -2.61231 1.99848 -1.03524 -2.69834 2.07931 -1.04006 -2.79714 2.17304 -1.0523 -2.89066 2.26153 -1.05514 -2.99057 2.35661 -1.05915 -3.09251 2.45177 -1.05896 -3.15004 2.50637 -1.02056 -3.14931 2.50652 -0.937862 -3.16017 2.51651 -0.864832 -3.16364 2.52015 -0.787437 -3.17344 2.52919 -0.714753 -3.20766 2.56202 -0.658412 -3.17501 2.53067 -0.561847 -3.16679 2.52308 -0.482325 -3.22008 2.57333 -0.435971 -3.15561 2.5123 -0.329436 -3.19294 2.54685 -0.275101 -3.21549 2.56862 -0.213336 -3.25817 2.60883 -0.159614 -3.35608 2.70187 -0.126261 -4.3815 3.67202 0.155168 -12.6294 11.4729 -1.34226 -16.1407 14.7939 -1.63799 -26.1117 24.2262 -1.45664 -26.3635 24.4645 -0.857092 -26.4049 24.5038 -0.236522 -26.424 24.5216 0.385853 -26.4421 24.5394 1.00863 -26.4963 24.5912 1.63331 -26.5207 24.6139 2.25952 -26.5441 24.6366 2.88753 -26.5952 24.6851 3.52061 -26.6175 24.7062 4.15411 -26.6452 24.7332 4.7916 -26.6729 24.7594 5.43253 -26.7134 24.7981 6.08017 -26.7453 24.8286 6.73107 -26.7752 24.8573 7.38678 -26.7827 24.8644 8.0419 -26.8392 24.9175 8.71596 -26.8852 24.9625 9.3948 -26.9087 24.9848 10.0735 -26.9301 25.0045 10.7584 -26.991 25.0621 11.4664 -27.0136 25.0846 12.1685 -4.21355 3.51492 4.19673 -4.11697 3.42342 4.23648 -4.08217 3.38998 4.32856 -4.14023 3.44572 4.51158 -4.02445 3.33617 4.52801 -3.97369 3.28795 4.60609 -3.93892 3.25467 4.70137 -3.84019 3.16159 4.72679 -3.82573 3.14828 4.84508 -3.63412 2.96674 4.75379 -3.56951 2.90616 4.80845 -3.53157 2.87064 4.89534 -3.47116 2.81299 4.95372 -3.54422 2.88172 5.19428 -3.48069 2.82225 5.25237 -2.80719 2.18407 4.40903 -2.72 2.10148 4.39702 -3.20455 2.56183 5.28775 -3.55659 2.89387 6.01872 -2.67004 2.05497 4.69228 -2.60428 1.99374 4.71233 -2.56187 1.95204 4.77042 -2.65867 2.04455 5.09446 -3.03148 2.39712 5.98139 -3.09747 2.46047 6.30676 -3.17955 2.53861 6.68717 -2.78084 2.15989 6.02978 -2.47313 1.8696 5.52656 -2.51013 1.90396 5.79857 -2.46687 1.86296 5.88987 -2.37649 1.77795 5.86579 -2.23886 1.64789 5.70525 -2.15696 1.5705 5.68334 -2.14914 1.56352 5.87657 -2.21753 1.62745 6.31754 -1.89397 1.32196 5.52951 -1.85063 1.28036 5.60863 -2.04404 1.46372 6.54606 -1.46917 0.919959 4.67468 -1.42031 0.873419 4.68799 -1.38226 0.837553 4.74757 -1.88172 1.3112 7.23562 -1.20893 0.672904 4.41284 -1.20656 0.671392 4.64191 -1.17495 0.640866 4.73602 -1.14023 0.608497 4.82965 -1.07184 0.543853 4.71732 -1.00773 0.483343 4.61266 -0.976228 0.453096 4.7327 -0.938246 0.416729 4.82263 -0.893784 0.374736 4.87224 -0.856099 0.340225 5.02005 -0.860689 0.344334 5.75413 -0.805755 0.292321 5.85175 -0.740723 0.230921 5.7886 -0.681227 0.173569 5.81362 -0.620847 0.117194 5.85722 -0.559277 0.0588277 5.87951 -1.97596 1.31594 -1.01066 -2.02783 1.36195 -1.01085 -2.07553 1.40463 -1.00233 -2.14011 1.46241 -1.01249 -2.19939 1.51495 -1.01355 -2.25449 1.56415 -1.006 -2.32642 1.62754 -1.01558 -2.39318 1.68768 -1.01616 -2.47258 1.7586 -1.02635 -2.54668 1.82429 -1.02745 -2.62718 1.89645 -1.0316 -2.70869 1.96872 -1.03247 -2.80299 2.05387 -1.04125 -2.89824 2.13815 -1.0461 -3.00096 2.22993 -1.05236 -3.1047 2.32186 -1.05443 -3.17679 2.38604 -1.02771 -3.16974 2.38075 -0.940996 -3.21438 2.4206 -0.892074 -3.19876 2.40599 -0.801546 -3.20216 2.40857 -0.7253 -3.20351 2.41025 -0.649398 -3.19741 2.40454 -0.569981 -3.19663 2.40429 -0.495172 -3.2645 2.46425 -0.457598 -3.19182 2.3999 -0.347243 -3.21636 2.42145 -0.287382 -3.23245 2.43568 -0.223704 -3.28351 2.48218 -0.174649 -3.35565 2.54614 -0.132093 -3.47757 2.65546 -0.105197 -4.45357 3.52425 0.115254 -12.4229 10.6288 -1.38295 -19.4768 16.9172 -1.44142 -26.7542 23.404 -1.75917 -28.5519 25.0069 -1.28904 -28.5775 25.03 -0.632827 -28.6167 25.0652 0.0231037 -28.6476 25.093 0.680355 -28.6773 25.1189 1.33891 -28.6976 25.1385 1.99863 -28.7326 25.1693 2.66092 -28.7666 25.1992 3.32565 -28.8134 25.2417 3.99479 -28.8666 25.29 4.66882 -28.8963 25.3158 5.344 -28.9315 25.3475 6.02426 -28.9497 25.3642 6.70606 -29.0113 25.4191 7.40173 -29.0328 25.4392 8.09477 -29.1041 25.5034 8.80674 -29.1223 25.5193 9.51122 -29.1448 25.5393 10.2236 -29.179 25.5702 10.947 -29.225 25.612 11.6829 -4.2582 3.35158 4.33507 -4.16417 3.26908 4.37707 -4.14436 3.25059 4.48553 -4.05024 3.16684 4.52269 -4.01032 3.13152 4.61118 -3.90345 3.03663 4.63054 -3.94848 3.076 4.81135 -4.03403 3.15277 5.04733 -3.791 2.93564 4.90405 -3.73408 2.88537 4.97366 -3.62719 2.79082 4.97978 -3.55951 2.72927 5.0314 -3.86216 2.99941 5.58741 -3.63719 2.79971 5.43314 -3.40777 2.59408 5.25517 -3.33171 2.52731 5.29257 -4.41396 3.49289 7.14541 -3.5692 2.73939 5.99353 -3.37384 2.56528 5.84542 -2.65641 1.92521 4.76925 -2.6025 1.87639 4.81114 -3.07622 2.29937 5.84496 -3.83695 2.97822 7.51178 -2.91643 2.15608 5.89587 -2.88829 2.13122 6.02753 -2.78336 2.03776 5.99734 -2.45644 1.74671 5.45543 -2.41974 1.71464 5.55275 -2.47801 1.76585 5.88698 -2.33776 1.64151 5.73739 -2.2957 1.60368 5.83343 -2.26221 1.57368 5.95587 -2.27696 1.58756 6.23303 -2.24142 1.55563 6.3747 -1.9061 1.25631 5.55531 -1.93152 1.27873 5.87594 -2.32697 1.63231 7.55746 -1.46997 0.866854 4.6768 -1.42452 0.826034 4.70843 -1.93142 1.27913 7.09482 -1.70156 1.07423 6.44664 -1.57256 0.959158 6.19449 -1.22889 0.652118 4.7858 -1.21377 0.639444 4.99678 -1.09055 0.529043 4.58336 -1.09054 0.528756 4.90047 -0.993128 0.442447 4.57933 -0.955206 0.407595 4.65948 -0.906507 0.364408 4.65971 -0.846843 0.311386 4.54965 -0.845451 0.309937 5.08389 -0.841448 0.306572 5.77824 -0.773423 0.246397 5.69572 -0.71654 0.195403 5.7913 -0.655288 0.141121 5.83561 -0.594278 0.0867197 5.95851 -0.5394 0.038722 7.5699 -2.03765 1.29232 -1.00737 -2.08622 1.33289 -0.999763 -2.14636 1.3832 -1.00422 -2.20657 1.43462 -1.00653 -2.2741 1.49139 -1.01325 -2.33534 1.54297 -1.01096 -2.4039 1.59993 -1.01279 -2.48517 1.66866 -1.0245 -2.5664 1.73656 -1.03305 -2.63713 1.79579 -1.0268 -2.72051 1.86585 -1.02937 -2.81022 1.94143 -1.03435 -2.91466 2.0288 -1.04661 -3.01918 2.11737 -1.05483 -3.12472 2.20609 -1.05886 -3.205 2.27345 -1.03875 -3.20527 2.27347 -0.95735 -3.21079 2.27792 -0.881309 -3.22895 2.29317 -0.814691 -3.23136 2.29578 -0.739041 -3.21998 2.28558 -0.655365 -3.22026 2.28626 -0.580908 -3.22048 2.28591 -0.506901 -3.25445 2.31467 -0.45216 -3.2084 2.27704 -0.356905 -3.23386 2.29747 -0.298396 -3.26473 2.32447 -0.242347 -3.31027 2.36236 -0.191532 -3.36954 2.41226 -0.144798 -3.46568 2.49247 -0.109399 -4.49553 3.35855 0.0814178 -11.8047 9.49997 -1.33406 -13.4565 10.8888 -1.37322 -16.5793 13.5129 -1.5723 -19.7098 16.1435 -1.62957 -22.3735 18.3818 -1.4909 -30.9049 25.5518 -1.06932 -30.9811 25.6166 -0.378335 -31.0331 25.66 0.315863 -31.0608 25.6839 1.01207 -31.0325 25.66 1.70818 -30.9948 25.6297 2.40307 -31.2389 25.8349 3.11653 -35.1899 29.1564 4.97833 -31.1573 25.7669 5.22138 -31.0964 25.716 5.91962 -35.5972 29.4987 7.45741 -35.2482 29.2058 8.20331 -31.1494 25.7615 8.79511 -31.1973 25.8024 9.53631 -5.54438 4.24181 5.28295 -5.35228 4.08074 5.27987 -4.30457 3.19967 4.48325 -4.20759 3.1182 4.52241 -4.02586 2.96528 4.47401 -3.85159 2.81988 4.42448 -3.78836 2.76535 4.48163 -4.06954 3.00167 4.91609 -4.1432 3.06458 5.14131 -3.94548 2.89778 5.05645 -4.06997 3.00228 5.3527 -3.76842 2.74952 5.12773 -3.6268 2.62974 5.08846 -4.6188 3.46428 6.57666 -4.31405 3.20851 6.34776 -4.29244 3.19071 6.50827 -4.41937 3.2976 6.8959 -3.79402 2.7719 6.13391 -3.44544 2.47835 5.75746 -2.63712 1.79854 4.57858 -2.63971 1.80113 4.7146 -2.59447 1.76254 4.77105 -4.05342 2.98941 7.63665 -3.09167 2.18101 6.02512 -2.53228 1.71111 5.09367 -2.58277 1.75339 5.3599 -2.49295 1.67749 5.33817 -2.41908 1.61526 5.3484 -2.41227 1.60985 5.51392 -2.4491 1.64067 5.79532 -2.36358 1.56912 5.78556 -2.28552 1.50391 5.79146 -2.30226 1.51816 6.05808 -2.03863 1.29584 5.5228 -2.24738 1.47156 6.38582 -2.18862 1.42318 6.47117 -2.46614 1.65627 7.704 -1.51851 0.858341 4.6654 -1.46683 0.814978 4.67868 -2.17602 1.41244 7.75326 -2.01148 1.27413 7.47495 -1.63231 0.954442 6.17223 -1.24289 0.626596 4.63238 -1.22017 0.607451 4.78465 -1.13627 0.537899 4.61529 -1.08343 0.493188 4.6 -1.05435 0.468819 4.74035 -1.00802 0.429554 4.78202 -0.931307 0.36476 4.57583 -0.879485 0.321243 4.54546 -0.839735 0.288367 4.64294 -0.879321 0.321652 5.74422 -0.820514 0.272389 5.83191 -0.753851 0.216088 5.78865 -0.691787 0.164393 5.84364 -0.626288 0.109361 5.82734 -0.563212 0.0560662 5.90945 -2.05592 1.23053 -1.01745 -2.10017 1.26566 -1.00354 -2.16118 1.31387 -1.0089 -2.22326 1.36312 -1.01211 -2.28635 1.41241 -1.01323 -2.34852 1.46288 -1.0121 -2.41895 1.51766 -1.01514 -2.49471 1.57794 -1.02188 -2.57255 1.63924 -1.02589 -2.6504 1.70069 -1.027 -2.73459 1.76762 -1.03112 -2.82717 1.84094 -1.03771 -2.92709 1.91974 -1.04622 -3.02071 1.99336 -1.04562 -3.13538 2.08416 -1.05712 -3.22384 2.15471 -1.04382 -3.23774 2.16541 -0.973045 -3.27061 2.19231 -0.916604 -3.24778 2.1743 -0.822359 -3.25117 2.17681 -0.747512 -3.25351 2.17836 -0.673111 -3.31889 2.2304 -0.636432 -3.25505 2.17958 -0.525598 -3.27525 2.19546 -0.46403 -3.22192 2.15343 -0.365508 -3.2621 2.1856 -0.315179 -3.27918 2.19967 -0.253501 -3.32564 2.23643 -0.204138 -3.37206 2.27228 -0.153027 -3.45533 2.33837 -0.114549 -3.6132 2.463 -0.0992441 -4.54071 3.19664 0.0472738 -11.3295 8.56717 -1.30524 -12.8414 9.76277 -1.34552 -19.9777 15.4084 -1.3818 -32.7999 25.5502 -1.50316 -38.3845 29.9688 -1.09068 -32.0396 24.9511 2.06835 -32.0431 24.9547 2.77131 -38.9184 30.3929 4.01474 -21.468 16.5881 3.11444 -38.7337 30.2487 5.71287 -32.2431 25.1137 5.62717 -38.9543 30.4232 7.47429 -37.4386 29.2255 8.9003 -32.5668 25.372 8.59451 -32.4818 25.3035 9.31299 -5.50579 3.9627 5.39227 -4.39181 3.08208 4.54428 -4.10398 2.85278 4.40428 -3.89439 2.68801 4.32569 -3.9159 2.70487 4.46921 -4.26694 2.98314 4.96475 -4.24207 2.96331 5.08052 -4.40941 3.09521 5.4151 -4.18069 2.914 5.3055 -4.24574 2.96678 5.53819 -4.28429 2.9969 5.74713 -4.6526 3.28767 6.39433 -4.80973 3.4126 6.798 -4.73537 3.35397 6.90038 -4.50773 3.17436 6.78398 -4.42277 3.10728 6.86481 -4.28805 3.00014 6.86632 -4.14281 2.88563 6.84804 -3.22292 2.15758 5.53155 -2.73661 1.7724 4.8598 -2.5973 1.66123 4.75431 -2.71328 1.75433 5.11365 -2.61422 1.67534 5.07891 -2.58299 1.65095 5.17602 -2.56656 1.63739 5.30705 -2.53856 1.61568 5.42134 -2.42042 1.52225 5.33546 -2.45072 1.54604 5.58851 -2.44826 1.54478 5.78213 -2.39692 1.50363 5.86057 -2.32973 1.45057 5.90215 -2.27209 1.40524 5.96942 -2.35052 1.46799 6.43923 -2.29718 1.42527 6.54429 -2.39068 1.49902 7.13261 -1.56574 0.845417 4.64442 -1.51002 0.801853 4.64872 -1.47022 0.77012 4.7086 -1.99163 1.18387 7.04749 -1.74415 0.987615 6.37015 -1.25377 0.599271 4.47927 -1.24176 0.589408 4.66987 -1.18804 0.546341 4.66641 -1.12368 0.495927 4.60312 -1.05388 0.441309 4.489 -1.02916 0.421118 4.65815 -0.959284 0.366388 4.52151 -0.908706 0.32581 4.51141 -0.874436 0.298605 4.64893 -0.865509 0.291647 5.12371 -0.857268 0.286563 5.77832 -0.791974 0.234201 5.7756 -0.726795 0.18275 5.79136 -0.661608 0.130726 5.81575 -0.632082 0.108724 7.65809 -0.54009 0.0362031 7.52006 -2.11019 1.19968 -1.00716 -2.16688 1.24242 -1.00651 -2.22458 1.28521 -1.00397 -2.29379 1.33675 -1.01295 -2.36408 1.38935 -1.01948 -2.42913 1.4377 -1.01716 -2.50044 1.49048 -1.0189 -2.57909 1.54865 -1.02426 -2.66512 1.61325 -1.03279 -2.74486 1.67265 -1.0324 -2.83193 1.73748 -1.03484 -2.92734 1.80771 -1.03959 -3.02914 1.88448 -1.04641 -3.13923 1.9657 -1.0545 -3.24946 2.04911 -1.05859 -3.25703 2.05439 -0.983408 -3.26355 2.05872 -0.908569 -3.27538 2.0685 -0.838737 -3.27245 2.06558 -0.759878 -3.27484 2.06809 -0.686126 -3.27611 2.06865 -0.612771 -3.27638 2.06925 -0.539912 -3.28285 2.07326 -0.471465 -3.27367 2.06655 -0.395684 -3.26236 2.05792 -0.320797 -3.28043 2.07186 -0.260421 -3.32049 2.10207 -0.209493 -3.3595 2.1314 -0.157214 -3.47496 2.21692 -0.132709 -3.58312 2.29723 -0.100793 -4.59284 3.05021 0.0100207 -10.807 7.67813 -1.26086 -12.413 8.8748 -1.34673 -17.0403 12.3219 -1.5242 -20.1278 14.622 -1.56271 -22.4451 16.3496 -1.38339 -41.9754 30.8986 -1.69037 -42.0141 30.9281 -0.787644 -42.0969 30.99 0.114708 -42.1031 30.9945 1.02016 -42.1838 31.0558 1.92757 -22.5466 16.426 1.97086 -22.2964 16.2405 2.43522 -21.8257 15.8893 2.87016 -21.9721 15.9987 3.35326 -21.473 15.6268 3.75936 -21.4704 15.6258 4.22149 -21.2399 15.4532 4.64534 -41.1512 30.2896 9.04937 -44.6643 32.9074 10.7334 -4.81342 3.21632 4.77065 -4.55821 3.0267 4.68165 -4.03239 2.63444 4.32388 -3.99807 2.60883 4.41266 -3.92481 2.55457 4.46305 -4.28107 2.81963 4.96161 -4.34582 2.86843 5.17457 -4.42424 2.92663 5.41161 -4.40264 2.91046 5.5442 -4.29784 2.83229 5.57985 -4.26784 2.8102 5.70427 -4.68037 3.11699 6.40448 -5.33032 3.60301 7.46764 -4.69755 3.13063 6.82101 -4.43153 2.93244 6.6473 -4.4396 2.93863 6.86231 -3.35303 2.12915 5.40019 -3.3156 2.10132 5.50112 -3.27182 2.06844 5.59362 -2.78803 1.70774 4.93306 -2.63123 1.59034 4.80215 -2.55147 1.53076 4.79817 -2.68084 1.62791 5.19458 -2.57894 1.55193 5.1566 -2.60378 1.5702 5.37271 -2.54202 1.52402 5.41793 -2.4951 1.48964 5.49671 -2.50315 1.49561 5.70732 -2.51754 1.50562 5.94624 -2.38075 1.40422 5.81862 -2.28301 1.33084 5.77728 -2.24781 1.3053 5.90682 -2.38216 1.40601 6.54251 -2.49969 1.49306 7.18549 -1.6151 0.833813 4.63238 -1.55844 0.79134 4.63732 -1.5103 0.755716 4.66932 -2.17112 1.24922 7.43013 -2.20971 1.27781 7.99158 -1.68105 0.883344 6.15311 -1.26975 0.575916 4.59386 -1.21516 0.534922 4.59072 -1.16274 0.49622 4.59595 -1.1092 0.456045 4.59036 -1.05141 0.413592 4.55396 -1.0075 0.380656 4.60481 -0.952874 0.339876 4.58574 -0.900358 0.300401 4.57529 -0.898904 0.299482 5.07977 -0.907857 0.3063 5.87366 -0.835396 0.253437 5.83196 -0.766043 0.201298 5.80862 -0.700105 0.152857 5.84366 -0.631792 0.101512 5.81738 -0.588619 0.0702894 7.63923 -2.45515 1.36755 -1.89235 -2.17152 1.17007 -1.00357 -2.23534 1.2151 -1.00889 -2.29393 1.25587 -1.00536 -2.37127 1.30966 -1.0198 -2.43819 1.35583 -1.01859 -2.51044 1.4075 -1.02148 -2.57738 1.45389 -1.01567 -2.67148 1.51962 -1.03191 -2.75308 1.57683 -1.03293 -2.83471 1.63419 -1.03106 -2.93092 1.70127 -1.03757 -3.02821 1.76947 -1.04063 -3.13284 1.84315 -1.04561 -3.24575 1.92128 -1.05176 -3.28885 1.95219 -1.00319 -3.30994 1.96616 -0.938532 -3.30087 1.96086 -0.854511 -3.29794 1.95791 -0.776051 -3.30132 1.96035 -0.702801 -3.30265 1.96188 -0.629995 -3.30291 1.96245 -0.557636 -3.30212 1.96206 -0.485723 -3.36081 2.00267 -0.444935 -3.27436 1.94226 -0.332487 -3.30069 1.9605 -0.276679 -3.33435 1.98418 -0.223488 -3.36696 2.00697 -0.169245 -3.46122 2.07305 -0.137943 -3.57118 2.15011 -0.108781 -3.82327 2.32675 -0.123256 -4.63433 2.89353 -0.0244582 -10.4167 6.9405 -1.23829 -11.8539 7.94531 -1.31315 -13.4408 9.0561 -1.35401 -20.6437 14.0975 -1.3574 -44.7163 30.9443 -1.33478 -44.7676 30.981 -0.393339 -44.821 31.0186 0.549441 -21.8493 14.9421 1.23796 -21.7032 14.8399 1.68815 -20.8792 14.264 2.09611 -21.1224 14.4343 2.54978 -20.8769 14.2623 2.96758 -21.5377 14.7255 3.48313 -21.2964 14.5563 3.90257 -21.3241 14.5762 4.35688 -22.1808 15.1756 4.96601 -22.0233 15.0656 5.40745 -45.163 31.2629 11.1265 -4.8494 3.04612 4.5181 -4.852 3.04879 4.65562 -4.73279 2.9644 4.68976 -4.92951 3.10262 5.00552 -4.04635 2.48424 4.3258 -4.14546 2.5543 4.544 -3.86032 2.35402 4.38573 -3.83657 2.33721 4.48283 -4.39352 2.72787 5.20964 -4.22389 2.60878 5.17041 -4.54995 2.83692 5.69671 -4.44656 2.76508 5.74024 -4.29793 2.6609 5.72377 -4.67569 2.92533 6.37722 -4.52606 2.82064 6.36949 -4.63291 2.89627 6.70922 -4.55053 2.83838 6.79639 -4.50916 2.80907 6.94357 -2.86416 1.65712 4.63261 -2.82674 1.63094 4.70623 -2.90503 1.68558 4.97238 -2.79085 1.60588 4.92535 -2.67349 1.52378 4.86645 -2.81189 1.62077 5.27081 -2.76401 1.58722 5.34475 -2.69299 1.53786 5.37526 -2.61351 1.48205 5.38691 -2.58674 1.46369 5.50964 -2.66643 1.51934 5.87866 -2.53214 1.42492 5.77331 -2.49279 1.39787 5.88752 -2.39113 1.32582 5.84805 -2.2737 1.24428 5.76018 -2.41709 1.34533 6.3934 -2.39048 1.32619 6.58134 -2.42421 1.34971 6.97446 -1.6045 0.775477 4.6163 -1.55542 0.740934 4.64874 -2.14187 1.15257 7.00385 -2.20354 1.19603 7.61028 -1.97799 1.03828 7.10862 -1.67885 0.82785 6.20442 -1.23158 0.51472 4.46656 -1.20157 0.493025 4.57885 -1.17597 0.475487 4.73977 -1.09172 0.416844 4.56747 -1.0437 0.383203 4.59916 -0.978551 0.337649 4.5116 -0.929457 0.303473 4.53121 -0.935415 0.307592 5.06533 -0.886566 0.272787 5.17348 -0.877326 0.267764 5.82809 -0.807101 0.217724 5.80556 -0.737049 0.169587 5.80136 -0.667927 0.120325 5.7958 -0.638646 0.100798 7.66805 -0.541027 0.031746 7.27007 -2.18473 1.10756 -1.01419 -2.23793 1.14185 -1.00639 -2.30363 1.18481 -1.01072 -2.37566 1.23318 -1.01956 -2.4362 1.27298 -1.01289 -2.51025 1.32146 -1.01714 -2.59157 1.37433 -1.02515 -2.66671 1.424 -1.02416 -2.75644 1.48336 -1.03275 -2.83987 1.53752 -1.03233 -2.93063 1.59711 -1.03473 -3.02873 1.66217 -1.03955 -3.13516 1.73264 -1.04628 -3.24262 1.80324 -1.04923 -3.3011 1.84066 -1.01219 -3.30867 1.84588 -0.938398 -3.32143 1.85454 -0.869718 -3.33314 1.86226 -0.801086 -3.32926 1.86033 -0.723572 -3.33885 1.86615 -0.655333 -3.39326 1.90209 -0.612787 -3.33205 1.86188 -0.507398 -3.36143 1.88092 -0.451849 -3.29708 1.83867 -0.350746 -3.3244 1.85681 -0.295641 -3.34234 1.8687 -0.236464 -3.39154 1.90115 -0.189908 -3.46468 1.94882 -0.15096 -3.56077 2.01185 -0.118017 -3.68921 2.09664 -0.0924549 -4.67637 2.74577 -0.0601821 -10.0573 6.28114 -1.21796 -11.257 7.07001 -1.26408 -12.7989 8.08325 -1.32468 -17.4456 11.138 -1.48132 -19.6234 12.5694 -1.39567 -22.0612 14.1719 -1.24666 -45.9325 29.8605 -0.876213 -46.0693 29.9515 0.0704303 -23.3458 15.017 1.01127 -22.2393 14.2899 1.46487 -21.8202 14.0139 1.90159 -21.1194 13.5536 2.30338 -21.0217 13.4903 2.72753 -22.4092 14.4012 3.30481 -22.3471 14.3613 3.75882 -21.7139 13.9454 4.12787 -22.1288 14.2181 4.64862 -22.0719 14.1807 5.09986 -22.2228 14.2805 5.59503 -21.9476 14.0996 6.00024 -23.3913 15.0489 6.8348 -5.068 3.00499 4.42036 -4.98263 2.94831 4.48806 -4.87534 2.87796 4.53645 -4.87161 2.87567 4.66745 -3.97215 2.2841 4.02314 -3.94842 2.26795 4.11329 -4.09955 2.36786 4.36966 -4.16695 2.41224 4.55759 -3.85854 2.20922 4.37647 -4.43274 2.58744 5.09588 -4.32227 2.51526 5.12385 -4.26196 2.4747 5.20312 -4.45833 2.60394 5.57991 -4.50919 2.63805 5.80339 -4.67007 2.74406 6.17423 -4.85086 2.86213 6.58981 -4.72898 2.78311 6.6278 -4.72334 2.77901 6.82108 -3.60127 2.04138 5.42942 -3.55775 2.01263 5.52462 -3.445 1.93781 5.51699 -2.84036 1.54067 4.72301 -2.80094 1.51456 4.79563 -2.76891 1.49381 4.88406 -2.74004 1.47528 4.98067 -2.84552 1.54439 5.32884 -2.81771 1.52577 5.44507 -2.72169 1.46275 5.43286 -2.716 1.45936 5.59986 -2.72506 1.46533 5.81167 -2.61115 1.39041 5.7603 -2.62132 1.39725 5.99089 -2.58421 1.37302 6.12438 -2.36186 1.22622 5.78646 -2.4711 1.29875 6.30886 -2.40349 1.25406 6.37686 -2.34645 1.21653 6.48079 -1.65049 0.758601 4.59502 -1.59737 0.723862 4.61859 -2.18604 1.11128 6.87265 -2.1228 1.06991 6.99263 -2.18218 1.10852 7.59951 -1.95199 0.957989 7.0761 -1.71405 0.801272 6.439 -1.24985 0.494671 4.61011 -1.57366 0.708625 6.58391 -1.13826 0.422158 4.60987 -1.1032 0.399186 4.73067 -1.27313 0.510532 6.26933 -1.05572 0.367091 5.21794 -0.973862 0.314061 5.06056 -0.917659 0.277271 5.09967 -0.918951 0.278095 5.80399 -0.851277 0.233406 5.85187 -0.777051 0.185091 5.79864 -0.707178 0.139412 5.80373 -0.637297 0.0931545 5.81736 -0.592249 0.064056 7.63932 -2.23758 1.06979 -1.00344 -2.30416 1.11064 -1.00887 -2.36455 1.14829 -1.00529 -2.4394 1.19354 -1.01309 -2.50713 1.23664 -1.01203 -2.58926 1.28639 -1.0214 -2.66627 1.33387 -1.02181 -2.74955 1.38582 -1.02579 -2.8411 1.44212 -1.03294 -2.92641 1.49424 -1.03103 -3.02632 1.55609 -1.0376 -3.12724 1.61805 -1.04058 -3.2365 1.68543 -1.04548 -3.3322 1.74331 -1.03611 -3.33976 1.74852 -0.962522 -3.37536 1.7711 -0.908888 -3.35171 1.75607 -0.816288 -3.35509 1.75846 -0.743737 -3.33456 1.7459 -0.658186 -3.33582 1.74636 -0.586928 -3.34334 1.75122 -0.520232 -3.35812 1.76046 -0.457801 -3.33234 1.74401 -0.376031 -3.34401 1.7514 -0.314091 -3.35567 1.75879 -0.25215 -3.39747 1.78477 -0.203328 -3.43095 1.80545 -0.150088 -3.53717 1.8706 -0.122919 -3.66735 1.95114 -0.100161 -3.91291 2.10233 -0.109836 -4.69762 2.58549 -0.0907541 -4.73016 2.60567 -0.00844747 -10.6984 6.27971 -1.21444 -12.3006 7.26634 -1.31295 -13.823 8.2036 -1.33153 -20.1224 12.0821 -1.20901 -20.5597 12.3517 -0.843932 -22.0075 13.2442 0.790286 -22.5522 13.5796 1.23696 -22.3497 13.4555 1.68277 -22.4729 13.5308 2.13756 -22.8346 13.7534 2.61545 -21.8139 13.1251 2.98065 -22.1714 13.346 3.46145 -21.9116 13.1857 3.87577 -22.2952 13.4224 4.38096 -22.8142 13.7422 4.92798 -24.1383 14.5581 5.65772 -24.116 14.5439 6.15247 -24.3187 14.6694 6.70372 -24.6047 14.8457 7.28859 -24.0023 14.4752 7.63909 -21.6825 13.0482 12.8796 -5.25955 2.93209 4.29642 -5.13696 2.85747 4.3412 -5.06536 2.81253 4.41966 -5.03458 2.79476 4.52926 -5.00994 2.7789 4.64443 -4.22672 2.29692 4.12617 -4.09144 2.21374 4.1248 -4.09806 2.21739 4.24663 -4.12977 2.23688 4.39465 -3.98611 2.14851 4.37948 -3.84554 2.06172 4.35949 -4.01727 2.16857 4.65954 -4.33934 2.36642 5.1367 -3.89483 2.09206 4.78782 -3.86813 2.07578 4.89192 -3.7683 2.01452 4.91037 -3.67995 1.96017 4.94053 -4.49457 2.46239 6.12623 -4.37289 2.38754 6.14739 -3.74311 1.99949 5.46535 -3.63807 1.93521 5.47718 -3.38553 1.77952 5.26685 -3.14128 1.6289 5.04761 -2.84254 1.44426 4.72325 -2.85141 1.45034 4.87648 -2.70119 1.3577 4.76754 -2.9414 1.50593 5.33756 -2.8802 1.46837 5.39545 -2.9216 1.49348 5.64827 -2.82587 1.43493 5.64555 -2.74476 1.3847 5.66635 -2.76009 1.39419 5.89627 -2.68318 1.3465 5.93304 -2.60527 1.29879 5.96811 -2.56087 1.27106 6.08279 -2.53022 1.25277 6.24258 -2.56047 1.27157 6.57698 -2.37339 1.15689 6.32267 -1.69314 0.736444 4.56431 -1.63914 0.703784 4.58828 -2.2701 1.09268 6.88316 -2.14488 1.01517 6.78583 -2.06077 0.964175 6.82821 -1.98612 0.918446 6.90723 -1.77532 0.788425 6.41643 -1.27785 0.480669 4.54404 -1.2365 0.455739 4.61782 -1.16233 0.410468 4.52499 -1.15597 0.406598 4.80266 -1.3284 0.513287 6.27086 -1.22166 0.447545 6.08983 -0.965097 0.288635 4.6796 -0.954987 0.282325 5.08528 -0.907623 0.253413 5.23307 -0.894085 0.245674 5.848 -0.815747 0.197164 5.76567 -0.747244 0.155428 5.8114 -0.674246 0.109919 5.77575 -0.644089 0.0919472 7.65804 -0.542841 0.0291336 7.26007 -2.30181 1.03868 -1.00641 -2.36927 1.07753 -1.01074 -2.4388 1.11736 -1.01283 -2.50734 1.15735 -1.01283 -2.58414 1.20165 -1.01709 -2.66196 1.24602 -1.01876 -2.74605 1.29483 -1.02419 -2.83941 1.34795 -1.03269 -2.92559 1.39793 -1.03228 -3.02004 1.45229 -1.03465 -3.12177 1.51111 -1.03948 -3.23283 1.57528 -1.04623 -3.3366 1.63433 -1.04378 -3.35967 1.64808 -0.98122 -3.38894 1.66525 -0.923275 -3.3726 1.65553 -0.835788 -3.37698 1.65786 -0.76354 -3.37204 1.65493 -0.687171 -3.4511 1.70167 -0.659727 -3.37361 1.65688 -0.545102 -3.37281 1.65641 -0.474787 -3.44244 1.69606 -0.440027 -3.35148 1.64392 -0.328159 -3.3714 1.65561 -0.270587 -3.39854 1.67073 -0.215932 -3.44855 1.70007 -0.170329 -3.53171 1.74794 -0.135457 -3.63976 1.81007 -0.106248 -3.7893 1.89628 -0.0868939 -4.74554 2.44774 -0.0392993 -10.3233 5.66119 -1.19874 -11.6861 6.44695 -1.27074 -13.1652 7.29958 -1.30881 -17.8371 9.99155 -1.44811 -20.0692 11.2782 -1.36406 -20.4731 11.5103 -1.00675 -21.6846 12.2087 -0.699144 -21.3518 12.0174 -0.250813 -21.9905 12.3856 0.144594 -22.3015 12.5659 1.88965 -26.5848 15.0343 2.5909 -26.7984 15.1578 3.13577 -26.3131 14.8781 3.61963 -26.1581 14.7893 4.12559 -25.4193 14.3632 4.54415 -27.0776 15.3189 5.32471 -26.6651 15.0824 5.79668 -27.715 15.6875 6.55283 -25.6326 14.4873 7.17907 -25.6364 14.4894 7.7115 -25.3546 14.3274 8.16588 -24.9074 14.0702 8.5618 -27.82 15.749 10.0571 -27.1652 15.3715 10.4246 -22.9601 12.9493 12.0179 -18.5727 10.4196 10.2988 -23.8382 13.4551 13.5759 -22.1106 12.4595 13.1798 -21.4832 12.0979 13.3543 -23.427 13.219 15.086 -22.551 12.7141 15.1236 -22.5363 12.7056 15.7009 -21.2492 11.9642 15.4055 -5.22222 2.72333 4.40987 -5.0822 2.64296 4.43913 -5.03683 2.61644 4.53654 -4.14391 2.10166 4.17356 -4.17761 2.12097 4.32048 -4.17386 2.11902 4.43814 -4.12744 2.09269 4.51802 -4.05493 2.05055 4.57091 -3.90953 1.96693 4.5483 -3.94433 1.98701 4.712 -3.83121 1.92193 4.71831 -3.7264 1.86155 4.72824 -3.87377 1.94625 5.03734 -4.5445 2.33333 6.01194 -4.44499 2.27568 6.06296 -4.3789 2.23819 6.15673 -3.62136 1.80099 5.29928 -3.64278 1.81398 5.48584 -3.26568 1.59648 5.09129 -3.24531 1.58457 5.21035 -3.03816 1.46516 5.0384 -2.81321 1.33542 4.81861 -3.02142 1.45513 5.32074 -2.9364 1.40692 5.33726 -2.88471 1.3766 5.41117 -2.88425 1.37635 5.5872 -2.86607 1.36591 5.73851 -2.79881 1.3276 5.79418 -2.81514 1.33654 6.03414 -2.74687 1.29769 6.09785 -2.59697 1.21119 5.97158 -2.54012 1.17781 6.05838 -2.44568 1.12407 6.05301 -1.79387 0.747533 4.52639 -1.73683 0.714675 4.54269 -1.68613 0.686314 4.57644 -2.17983 0.970758 6.33845 -2.1914 0.978183 6.68354 -2.16942 0.965429 6.94513 -2.10231 0.926242 7.06402 -2.01215 0.874543 7.10497 -1.3206 0.475153 4.54556 -1.28355 0.453962 4.63924 -1.21486 0.414352 4.58625 -1.13022 0.364745 4.43383 -1.36961 0.503456 6.18368 -1.28653 0.455677 6.17083 -1.06509 0.327492 5.13894 -0.99431 0.28673 5.08041 -0.934235 0.25269 5.10959 -0.935527 0.253513 5.81391 -0.861799 0.210731 5.81207 -0.785942 0.167516 5.77873 -0.714314 0.125955 5.78382 -0.642865 0.0847848 5.83736 -0.595938 0.0588147 7.63925 -2.3036 0.969167 -1.0104 -2.37199 1.0069 -1.01568 -2.42895 1.03708 -1.00531 -2.51274 1.08145 -1.01973 -2.58317 1.11939 -1.01843 -2.66185 1.16163 -1.0214 -2.74781 1.20827 -1.02804 -2.83478 1.25499 -1.03188 -2.92896 1.30513 -1.03874 -3.01703 1.35307 -1.03674 -3.11331 1.40439 -1.03746 -3.22511 1.46442 -1.04602 -3.338 1.52557 -1.05084 -3.37646 1.54586 -0.99941 -3.38396 1.55001 -0.926971 -3.39765 1.55755 -0.859644 -3.38757 1.55218 -0.778116 -3.39088 1.55352 -0.706715 -3.39319 1.5549 -0.63581 -3.37792 1.54671 -0.556715 -3.40196 1.56014 -0.499554 -3.43215 1.57603 -0.445757 -3.36416 1.53999 -0.345338 -3.39329 1.55492 -0.292088 -3.42869 1.57436 -0.241501 -3.4641 1.59384 -0.190015 -3.51499 1.62115 -0.143718 -3.62483 1.68004 -0.116863 -3.75952 1.75226 -0.0944241 -4.209 1.9943 -0.0871105 -4.7827 2.30226 -0.0755059 -10.0551 5.13558 -1.20199 -11.1009 5.69817 -1.22508 -12.7243 6.56956 -1.31594 -14.2217 7.3746 -1.32094 -20.166 10.5698 -1.53377 -20.6135 10.8107 -1.18857 -21.1625 11.105 -0.835717 -21.7063 11.3977 -0.461828 -21.7957 11.4461 -0.044851 -21.8872 11.4956 0.374867 -62.5076 33.328 0.416258 -27.9036 14.7301 3.46233 -26.2314 13.8311 3.82588 -25.7178 13.5555 4.7822 -20.6653 10.8402 4.43179 -21.2521 11.1556 4.95338 -28.1675 14.8728 6.83613 -25.2168 13.287 6.72221 -26.6819 14.0749 7.60355 -26.3531 13.8988 8.06051 -24.8509 13.0908 8.16291 -19.8571 10.407 7.10532 -19.8367 10.3954 7.51362 -23.3703 12.2949 9.19952 -21.9038 11.5071 9.14311 -25.2039 13.2821 10.9462 -24.7339 13.0292 11.301 -24.2193 12.7532 11.6219 -19.195 10.0515 9.80334 -18.6695 9.76905 9.98091 -18.7529 9.81469 10.4557 -18.9702 9.93164 11.0142 -18.6168 9.74087 11.2671 -22.7521 11.9653 14.1661 -21.8574 11.4844 14.1801 -21.0923 11.0732 14.2416 -21.2872 11.1783 14.9167 -5.312 2.58763 4.35183 -5.21493 2.53642 4.41433 -5.12504 2.48792 4.47966 -4.40537 2.10158 4.16694 -4.34961 2.07036 4.23791 -4.23582 2.01007 4.25891 -4.19257 1.98656 4.33873 -4.11298 1.94356 4.3859 -4.11443 1.94457 4.50899 -4.19801 1.9901 4.71929 -4.23165 2.00742 4.88664 -3.93488 1.84782 4.70521 -3.85218 1.80362 4.74474 -3.99814 1.882 5.04605 -3.80215 1.77698 4.95512 -4.70938 2.26561 6.22212 -4.51235 2.15883 6.15501 -3.74642 1.74736 5.32088 -3.68455 1.71453 5.39226 -3.52898 1.63053 5.32948 -3.31719 1.51626 5.17463 -3.11165 1.40628 5.01271 -3.03927 1.36725 5.04763 -3.03143 1.36266 5.18797 -3.05386 1.37525 5.38766 -2.94819 1.31857 5.37018 -2.88517 1.28406 5.42664 -2.87532 1.27849 5.58527 -2.82596 1.25284 5.67515 -2.74525 1.20895 5.70295 -2.90448 1.29485 6.25251 -2.84267 1.26201 6.34412 -2.63159 1.14843 6.0828 -2.56447 1.11177 6.1516 -2.52665 1.09143 6.30182 -1.7814 0.690837 4.52086 -1.73077 0.663498 4.55506 -1.70004 0.647195 4.65387 -2.35701 1.00138 6.96803 -2.30161 0.971511 7.12724 -2.11945 0.873308 6.84725 -2.05774 0.8397 6.98406 -1.36628 0.46792 4.55644 -1.32618 0.446452 4.64085 -1.25026 0.404864 4.55947 -1.16811 0.361619 4.43716 -1.15016 0.352013 4.6459 -1.34056 0.454505 6.17256 -1.24501 0.403515 6.07994 -1.03775 0.291344 5.10494 -0.97244 0.255685 5.09519 -0.933978 0.235681 5.35233 -0.913025 0.224427 5.9077 -0.827634 0.178389 5.76562 -0.756318 0.139835 5.81142 -0.681751 0.0999223 5.80573 -0.649719 0.0840702 7.68804 -0.543342 0.0266446 7.15006 -2.37178 0.937476 -1.02027 -2.4358 0.968853 -1.01751 -2.50089 1.00126 -1.0128 -2.57938 1.04033 -1.01931 -2.65175 1.0772 -1.01707 -2.73126 1.11645 -1.0187 -2.82529 1.16436 -1.03025 -2.92134 1.2123 -1.03872 -3.00396 1.25277 -1.03221 -3.10829 1.30525 -1.04035 -3.20646 1.35453 -1.03948 -3.32728 1.41484 -1.05162 -3.40484 1.45346 -1.02787 -3.40513 1.45429 -0.950314 -3.47445 1.48881 -0.918303 -3.40974 1.45638 -0.801763 -3.41411 1.45865 -0.730614 -3.42462 1.46331 -0.664426 -3.41768 1.46043 -0.589549 -3.41793 1.46088 -0.519687 -3.43258 1.46805 -0.458455 -3.40598 1.45461 -0.377629 -3.41031 1.45655 -0.313172 -3.43017 1.46722 -0.25615 -3.46645 1.48459 -0.205567 -3.51 1.50643 -0.157252 -3.61238 1.55781 -0.12918 -3.72406 1.61368 -0.100385 -3.90386 1.70366 -0.0896136 -4.82127 2.16364 -0.113361 -9.71169 4.60952 -1.18443 -10.7096 5.1095 -1.21376 -12.1083 5.80899 -1.28273 -13.6166 6.5638 -1.31625 -15.883 7.69815 -1.40953 -18.2086 8.86201 -1.42232 -20.4932 10.006 -1.33967 -21.3372 10.4279 -1.02797 -21.8839 10.701 -0.661245 -22.146 10.8326 0.165676 -21.762 10.6404 0.595741 -26.9484 13.2372 3.0815 -21.1213 10.3216 3.028 -25.5245 12.525 3.95394 -19.342 9.43019 3.59679 -20.7769 10.1487 4.19728 -20.1239 9.82235 4.48584 -21.1228 10.322 5.0772 -26.6473 13.088 6.69726 -21.0791 10.3005 5.90245 -27.1937 13.3618 7.90579 -18.1544 8.83761 5.93199 -18.2911 8.90583 6.34059 -18.3161 8.91831 6.72289 -19.4385 9.48021 7.48553 -19.4027 9.46281 7.87889 -22.014 10.7698 9.29645 -22.6797 11.1026 10.0404 -19.2713 9.3975 9.06908 -19.3078 9.41616 9.50918 -18.6625 9.09214 9.63248 -18.8843 9.2035 10.1648 -19.0058 9.265 10.6618 -18.6512 9.0872 10.9119 -22.4205 10.9744 13.5046 -23.0672 11.2985 14.4333 -23.9097 11.7202 15.5267 -21.6039 10.5666 14.6405 -5.32728 2.41803 4.50999 -5.23452 2.37173 4.57572 -4.28271 1.89457 4.19173 -4.1971 1.8517 4.23422 -4.14569 1.82627 4.30598 -4.19685 1.85155 4.47312 -4.1755 1.84098 4.5776 -4.37186 1.93959 4.90314 -4.25825 1.88227 4.92359 -4.23491 1.87131 5.03801 -4.12648 1.8168 5.06079 -4.11867 1.81295 5.1957 -4.06523 1.78628 5.28034 -3.7701 1.63902 5.06676 -3.71246 1.60991 5.13753 -3.60091 1.5545 5.13835 -3.60343 1.55494 5.2916 -3.57486 1.54032 5.40674 -3.61281 1.55995 5.62581 -3.29875 1.40291 5.3136 -3.08738 1.29663 5.13822 -2.99234 1.24921 5.13834 -2.94194 1.2238 5.2116 -2.96121 1.23356 5.41124 -2.93375 1.22035 5.53582 -2.8314 1.16867 5.52198 -2.77276 1.13963 5.59306 -3.01998 1.26354 6.30791 -2.95307 1.22964 6.392 -2.89561 1.20146 6.50197 -2.75271 1.12939 6.412 -2.75466 1.13128 6.67441 -1.85716 0.681258 4.58164 -1.77334 0.63979 4.53344 -1.74056 0.623155 4.62307 -2.22757 0.86664 6.31976 -2.35082 0.929308 7.02409 -2.22656 0.866159 6.95468 -2.1306 0.818946 6.97792 -1.40661 0.456025 4.54777 -1.36551 0.435156 4.62284 -1.29825 0.40151 4.59068 -1.18583 0.345337 4.33292 -1.17946 0.342466 4.59032 -1.13734 0.320462 4.68167 -1.30222 0.40365 6.11182 -1.08094 0.29245 5.11914 -1.0127 0.258517 5.10021 -0.951871 0.228026 5.13934 -0.958584 0.231986 5.91335 -0.885347 0.194669 5.9615 -0.797015 0.150788 5.79871 -0.720515 0.112542 5.78385 -0.647248 0.0755019 5.81736 -0.599507 0.0520886 7.62935 -2.42209 0.890874 -1.00877 -2.48705 0.921228 -1.00526 -2.5726 0.961484 -1.01969 -2.64578 0.995239 -1.0185 -2.72616 1.03237 -1.02133 -2.81481 1.07383 -1.02803 -2.89722 1.1111 -1.02567 -2.9869 1.15277 -1.02678 -3.09304 1.20204 -1.03667 -3.1992 1.25148 -1.04307 -3.30738 1.30097 -1.04598 -3.40745 1.34838 -1.04002 -3.42414 1.3557 -0.973303 -3.45522 1.36968 -0.916713 -3.438 1.36198 -0.830121 -3.43417 1.36097 -0.754254 -3.43748 1.36227 -0.683652 -3.43873 1.36268 -0.613493 -3.43998 1.36305 -0.543833 -3.44742 1.36684 -0.478785 -3.51148 1.39691 -0.441716 -3.42521 1.35633 -0.333852 -3.44601 1.3659 -0.277382 -3.47401 1.3789 -0.223929 -3.5185 1.39963 -0.176566 -3.57947 1.42815 -0.134195 -3.70115 1.48415 -0.110775 -3.84867 1.55343 -0.0915743 -4.40829 1.81251 -0.112014 -4.86682 2.0245 -0.153136 -9.38447 4.11864 -1.16621 -10.3245 4.55479 -1.19793 -11.4634 5.08302 -1.23402 -13.0721 5.82854 -1.31237 -14.5606 6.51818 -1.30892 -18.148 8.18217 -1.55191 -21.1178 9.55807 -1.17765 -22.5144 10.2058 -0.898526 -22.3694 10.1389 -0.463199 -22.4255 10.1653 -0.0440318 -22.701 10.2927 0.370407 -21.8005 9.87521 0.805864 -18.8249 8.49601 1.18563 -19.227 8.68242 1.55011 -19.3602 8.74478 1.91727 -19.6687 8.88771 2.3021 -19.1843 8.66347 2.63044 -19.5082 8.81308 3.02716 -19.1484 8.64631 3.3516 -19.7468 8.92449 3.80296 -19.1344 8.6402 4.07938 -28.6018 13.0304 6.19823 -20.7026 9.36742 5.13779 -21.1846 9.59144 5.64972 -18.5306 8.36092 5.41581 -18.5814 8.38471 5.7947 -18.5207 8.35673 6.14688 -18.558 8.37453 6.53025 -18.8502 8.50972 7.00197 -20.1023 9.09082 7.82383 -19.0706 8.61228 7.85992 -19.3609 8.74664 8.37324 -18.8172 8.49485 8.55963 -18.6854 8.43382 8.90727 -20.0412 9.06297 9.93389 -18.8234 8.49863 9.79362 -19.3172 8.72683 10.4645 -19.009 8.58477 10.7431 -21.5951 9.78405 12.6072 -23.4278 10.6338 14.1712 -18.2016 8.21002 11.6065 -19.7204 8.91476 13 -21.7074 9.83636 14.7851 -21.7805 9.87002 15.3897 -5.31132 2.23277 5.22319 -5.11747 2.14305 5.20058 -5.05692 2.1143 5.29529 -5.06266 2.11789 5.45527 -4.94524 2.06276 5.49506 -4.33343 1.77897 5.01522 -4.95563 2.06783 5.83166 -4.31888 1.77237 5.28868 -4.06281 1.65425 5.1438 -3.93594 1.59443 5.13802 -3.87538 1.56661 5.21105 -3.68437 1.47811 5.11557 -3.6652 1.4693 5.23798 -3.52383 1.40356 5.19653 -3.2975 1.29831 5.0239 -3.28668 1.29458 5.15752 -3.12038 1.21732 5.05582 -2.93845 1.13208 4.91597 -2.92549 1.12628 5.0458 -2.96335 1.14411 5.26896 -2.92868 1.12843 5.37548 -2.91472 1.12166 5.52498 -2.8292 1.08166 5.54461 -3.02909 1.17453 6.14254 -3.04748 1.18337 6.40341 -2.31516 0.84286 5.01939 -2.25453 0.815572 5.06266 -2.21258 0.796391 5.15048 -1.94816 0.673547 4.67838 -1.86143 0.633337 4.63173 -1.80375 0.606002 4.65747 -2.26345 0.819849 6.20901 -2.49461 0.927481 7.22263 -2.29569 0.834587 6.92817 -2.23958 0.809168 7.09528 -2.13969 0.763183 7.11829 -1.39949 0.419205 4.58537 -1.33129 0.386646 4.55376 -1.30818 0.376482 4.72481 -1.21387 0.333063 4.56404 -1.16664 0.310924 4.6263 -1.36972 0.405574 6.19221 -1.15136 0.303734 5.31069 -1.0549 0.259703 5.11481 -0.988895 0.22859 5.11495 -1.02197 0.244348 6.07766 -0.940506 0.206102 6.07694 -0.837526 0.15923 5.77562 -0.764455 0.12479 5.82132 -0.686013 0.0886405 5.78574 -0.654042 0.0737903 7.66809 -0.545156 0.023523 7.15 -2.41076 0.819462 -1.00628 -2.48997 0.854242 -1.01749 -2.54863 0.879352 -1.00608 -2.62981 0.913236 -1.01276 -2.71106 0.94824 -1.01699 -2.79233 0.983367 -1.01872 -2.88286 1.02277 -1.02413 -2.98054 1.06459 -1.0326 -3.0731 1.10416 -1.03222 -3.16568 1.14387 -1.02884 -3.28086 1.19356 -1.03941 -3.39806 1.24333 -1.0461 -3.43833 1.26043 -0.996025 -3.43037 1.25696 -0.914204 -3.44499 1.26337 -0.848228 -3.45756 1.26889 -0.782296 -3.46192 1.27113 -0.711847 -3.50529 1.28992 -0.664382 -3.44902 1.26525 -0.563194 -3.46467 1.27233 -0.502765 -3.48852 1.28272 -0.446254 -3.44357 1.26374 -0.358033 -3.4571 1.26891 -0.298197 -3.46863 1.2742 -0.238255 -3.51398 1.29282 -0.191895 -3.5502 1.30921 -0.140963 -3.67263 1.36105 -0.119846 -3.79514 1.41409 -0.0944827 -3.97106 1.48938 -0.0812604 -4.81527 1.85232 -0.168554 -4.90493 1.89022 -0.104295 -9.92078 4.04172 -1.17394 -10.8835 4.45518 -1.19076 -12.3561 5.08656 -1.26864 -13.7981 5.7048 -1.28491 -15.999 6.64932 -1.36211 -18.5517 7.74493 -1.40258 -20.8909 8.74813 -1.32162 -21.758 9.12035 -1.01293 -22.7774 9.5576 -0.683749 -22.6543 9.50424 -0.252128 -22.2937 9.35004 0.182928 -21.21 8.8854 0.617137 -21.3512 8.94658 1.01054 -21.5037 9.01137 1.4097 -21.6232 9.06233 1.81345 -18.5785 7.75694 2.04021 -18.6228 7.77558 2.38835 -22.0769 9.25763 3.06517 -19.1982 8.02233 3.14818 -19.1881 8.01869 3.50657 -19.0997 7.98111 3.85409 -19.4138 8.1162 4.26961 -19.6301 8.20882 4.68062 -20.8757 8.74316 5.32071 -25.9806 10.934 6.90705 -20.0888 8.4058 5.93183 -19.1687 8.01111 6.07533 -18.6758 7.79977 6.30977 -18.6678 7.79654 6.67903 -18.7761 7.84255 7.09061 -20.4322 8.55396 8.05874 -24.5467 10.3189 10.0238 -19.3381 8.08491 8.4724 -19.3961 8.10989 8.90435 -19.3511 8.09013 9.29959 -24.0704 10.115 11.9014 -18.369 7.66926 9.66843 -18.6187 7.77616 10.2053 -19.2032 8.02705 10.9385 -18.2958 7.63755 10.8787 -18.4756 7.7154 11.4125 -20.1291 8.4254 12.8537 -20.2709 8.48585 13.4349 -22.1156 9.27809 15.1485 -21.3319 8.94184 15.1805 -21.3863 8.96512 15.7756 -5.47895 2.13814 5.23844 -5.27522 2.05086 5.21267 -5.22823 2.03005 5.32212 -5.18544 2.01229 5.4375 -5.0518 1.95456 5.4656 -5.10085 1.97601 5.6742 -5.01882 1.94078 5.75384 -4.38967 1.67027 5.23771 -4.15479 1.56947 5.12388 -4.08821 1.5418 5.19264 -3.88522 1.454 5.0966 -3.83099 1.4311 5.17536 -3.71059 1.37888 5.16906 -3.60883 1.33555 5.18274 -3.52975 1.30133 5.22547 -3.8207 1.42674 5.80161 -3.14424 1.13617 4.96566 -3.09098 1.11357 5.03169 -2.97981 1.06584 5.00569 -2.94514 1.05067 5.10247 -3.00981 1.07848 5.37734 -3.00108 1.07485 5.53587 -2.88682 1.02604 5.50474 -2.8222 0.997928 5.5669 -2.91296 1.03736 5.94587 -2.44961 0.838266 5.17108 -2.31033 0.77826 5.04574 -2.29127 0.770443 5.18822 -2.0337 0.659182 4.75565 -1.94098 0.619957 4.70139 -1.88144 0.594791 4.72813 -2.60364 0.904634 6.97618 -2.30038 0.7747 6.39494 -2.35754 0.799481 6.88227 -2.29632 0.773448 7.03081 -2.21536 0.738708 7.12143 -2.08961 0.684441 7.04729 -1.37486 0.377549 4.56495 -1.33506 0.360537 4.65865 -1.26186 0.32923 4.60578 -1.19277 0.299082 4.56104 -1.15507 0.282277 4.68165 -1.31069 0.34958 6.02313 -1.09685 0.257386 5.11917 -1.02792 0.228 5.11013 -0.96745 0.202487 5.16914 -0.988999 0.211964 6.09237 -0.894933 0.171524 5.95147 -0.80709 0.133612 5.82863 -0.726714 0.099633 5.77383 -0.650695 0.0667721 5.80736 -0.602198 0.0469077 7.62929 -2.54418 0.806106 -1.01195 -2.6181 0.83569 -1.01306 -2.70016 0.867583 -1.01835 -2.7761 0.897268 -1.01497 -2.86644 0.933603 -1.02173 -2.9578 0.970016 -1.02569 -3.0573 1.00879 -1.03272 -3.15069 1.04538 -1.0308 -3.26048 1.08857 -1.03741 -3.3703 1.13194 -1.04043 -3.474 1.17311 -1.03459 -3.47429 1.17391 -0.957636 -3.52164 1.19239 -0.911682 -3.46349 1.16933 -0.80055 -3.48419 1.17711 -0.739887 -3.4793 1.1751 -0.665165 -3.53075 1.19519 -0.622319 -3.48079 1.17588 -0.526542 -3.49638 1.18195 -0.466263 -3.55398 1.20456 -0.425682 -3.45687 1.16679 -0.314685 -3.48575 1.17767 -0.262635 -3.52389 1.19285 -0.213458 -3.55999 1.20721 -0.163226 -3.62271 1.23158 -0.121461 -3.76443 1.28805 -0.104696 -3.9164 1.34801 -0.0858643 -4.27346 1.4891 -0.122963 -4.64281 1.63399 -0.149411 -4.93228 1.7483 -0.141417 -9.60087 3.58911 -1.16385 -10.5276 3.95523 -1.18773 -11.7232 4.42657 -1.23018 -13.3271 5.05941 -1.30073 -14.9354 5.69396 -1.31162 -18.532 7.11125 -1.54251 -21.5014 8.28281 -1.16307 -23.0357 8.88854 -0.895039 -23.0258 8.8852 -0.469589 -24.5459 9.48474 0.786651 -24.9179 9.63132 1.2415 -20.7216 7.97641 2.33996 -18.1655 6.96837 2.50368 -17.9808 6.89587 2.81848 -18.6791 7.17135 3.23592 -18.9903 7.29433 3.62642 -19.3406 7.43199 4.03669 -19.4342 7.46927 4.41624 -20.3361 7.82512 4.96272 -18.7926 7.21658 5.01058 -18.8513 7.2396 5.38354 -18.8505 7.2396 5.74589 -18.4911 7.09798 6.01171 -19.4467 7.47466 6.65906 -24.319 9.39719 8.598 -19.1276 7.34945 7.32422 -19.1803 7.37045 7.72996 -19.4631 7.48153 8.22986 -19.4213 7.46513 8.6161 -19.4329 7.46989 9.02861 -20.5803 7.92299 9.95335 -20.5078 7.89466 10.3647 -20.1073 7.73686 10.6183 -18.8741 7.25046 10.4331 -19.6332 7.55001 11.2677 -20.4871 7.88673 12.1982 -21.8142 8.41068 13.4549 -20.1108 7.73875 12.9412 -20.1783 7.76522 13.475 -19.8539 7.63768 13.7639 -22.1299 8.53571 15.8296 -5.22229 1.86406 5.04269 -5.34219 1.91154 5.29612 -4.78374 1.69176 4.93795 -4.6009 1.61892 4.90512 -4.55712 1.60229 5.00173 -4.43813 1.55532 5.02211 -4.43859 1.5554 5.16558 -4.27219 1.48955 5.1318 -4.24901 1.48091 5.25272 -4.13612 1.43547 5.27088 -3.85638 1.32571 5.08368 -3.7476 1.28258 5.09279 -3.75117 1.28395 5.24579 -3.32899 1.11719 4.82859 -3.35729 1.12841 5.00808 -3.18046 1.05951 4.90024 -3.11694 1.03372 4.94996 -3.28974 1.10231 5.36943 -3.19225 1.06356 5.37946 -3.09581 1.02563 5.38713 -3.09224 1.02414 5.55463 -2.98962 0.984008 5.55084 -2.86937 0.936074 5.50989 -2.80909 0.913107 5.57998 -2.76941 0.89708 5.69365 -2.42693 0.761977 5.16256 -2.30761 0.714969 5.08082 -2.09409 0.630079 4.76823 -2.01401 0.59899 4.75173 -2.41211 0.755941 5.97165 -2.65429 0.852196 6.89085 -2.32375 0.721239 6.25586 -2.43981 0.767415 6.90216 -2.38283 0.744643 7.06093 -2.2533 0.693796 6.99045 -2.16105 0.656773 7.0416 -2.03043 0.605777 6.9466 -1.91742 0.561467 6.90664 -1.2898 0.313722 4.5497 -1.24064 0.293269 4.60318 -1.18537 0.272165 4.6361 -1.12274 0.247499 4.62879 -1.15126 0.258226 5.2022 -1.06887 0.225763 5.1149 -1.00329 0.20062 5.13476 -1.04672 0.217192 6.18698 -0.953031 0.180261 6.09696 -0.850537 0.139857 5.82545 -0.769352 0.107965 5.79148 -0.690277 0.0768544 5.77578 -0.657427 0.0645678 7.6481 -0.545847 0.0204899 7.10999 -2.53685 0.73506 -1.01741 -2.59733 0.757048 -1.00605 -2.68026 0.786814 -1.01274 -2.77033 0.81896 -1.02339 -2.85429 0.848921 -1.02489 -2.94646 0.882209 -1.0302 -3.03151 0.913363 -1.02655 -3.1329 0.950094 -1.0321 -3.22817 0.984622 -1.02888 -3.34692 1.02708 -1.03932 -3.46675 1.07066 -1.04611 -3.49151 1.07921 -0.985411 -3.4836 1.07672 -0.903839 -3.59628 1.11733 -0.898228 -3.50347 1.08328 -0.767717 -3.49044 1.07899 -0.688327 -3.50908 1.08588 -0.628007 -3.49292 1.0797 -0.550007 -3.50131 1.08238 -0.485812 -3.55064 1.10063 -0.442061 -3.47827 1.07485 -0.342322 -3.49993 1.08232 -0.286855 -3.5124 1.08653 -0.227366 -3.57604 1.1097 -0.188451 -3.60387 1.11973 -0.134351 -3.72071 1.162 -0.110624 -3.87336 1.21678 -0.094444 -4.04445 1.27846 -0.0784178 -4.48882 1.43944 -0.133957 -4.89944 1.58769 -0.163629 -9.19894 3.13761 -1.13019 -10.1339 3.47527 -1.17174 -11.1284 3.83454 -1.1906 -12.6173 4.37083 -1.26499 -14.0748 4.897 -1.27841 -16.4199 5.74281 -1.37026 -18.8749 6.62874 -1.38896 -21.2974 7.50228 -1.31304 -22.0154 7.76184 -0.990057 -25.7613 9.11258 -0.864944 -24.0221 8.48548 -0.298426 -25.8259 9.13623 0.0727497 -25.8468 9.14327 0.542653 -25.8883 9.15812 1.01295 -19.3468 6.79903 1.35943 -18.6995 6.56542 1.68503 -22.4797 7.92924 2.23591 -22.8508 8.06295 2.67298 -18.6312 6.54155 2.69577 -18.8904 6.63449 3.06445 -22.2524 7.84768 3.85062 -22.3495 7.88356 4.69039 -22.8038 8.04759 5.19273 -18.4852 6.48879 4.72618 -18.0436 6.33017 4.97382 -18.3337 6.43447 5.3866 -18.4958 6.49337 5.77989 -18.9778 6.66735 6.27375 -18.7801 6.59634 6.58265 -19.6836 6.9218 7.24606 -21.8145 7.69074 8.37464 -20.9608 7.38351 8.50169 -18.2713 6.41306 7.88703 -19.4468 6.83698 8.74315 -17.4594 6.12026 8.29466 -17.7529 6.22575 8.79607 -28.6441 10.1565 14.3388 -24.952 8.82424 13.1372 -20.4806 7.21018 11.3732 -20.1733 7.10004 11.6696 -19.2062 6.7511 11.5867 -19.573 6.8834 12.2523 -20.5084 7.22077 13.2951 -20.0297 7.04869 13.4892 -20.1165 7.08014 14.0459 -22.3602 7.88969 16.1083 -5.40409 1.77059 5.07831 -5.32241 1.74127 5.15606 -5.13079 1.67159 5.13565 -4.81383 1.55717 4.99126 -4.62835 1.49044 4.95685 -4.53533 1.45735 5.00551 -4.53679 1.45739 5.14938 -4.56815 1.46947 5.32971 -4.29319 1.37038 5.18141 -4.45505 1.42832 5.51467 -4.16667 1.32445 5.33454 -3.8854 1.2227 5.14525 -3.74395 1.17158 5.11551 -3.43898 1.06216 4.86407 -3.35197 1.03041 4.8865 -3.42344 1.05628 5.13058 -3.22843 0.986244 4.99807 -3.1733 0.965793 5.0645 -3.03275 0.914782 4.9975 -3.12493 0.948518 5.30395 -2.99985 0.90367 5.25867 -3.00144 0.904216 5.43305 -2.90514 0.869029 5.43548 -2.79962 0.83141 5.41816 -2.79815 0.830583 5.60154 -2.74315 0.811122 5.68804 -2.30333 0.651951 4.93787 -2.15946 0.600102 4.78943 -2.09607 0.577349 4.81968 -2.41885 0.693602 5.81539 -2.71621 0.801923 6.84259 -2.65004 0.777991 6.96683 -2.2788 0.643288 6.20701 -2.39468 0.685964 6.86341 -2.36478 0.675269 7.11643 -2.2148 0.621274 6.97794 -2.15593 0.599431 7.1531 -2.04429 0.559594 7.14424 -1.32801 0.300008 4.54223 -1.26135 0.275754 4.51811 -1.20196 0.254454 4.52193 -1.20619 0.255851 4.87808 -1.3298 0.301285 6.02319 -1.11076 0.222444 5.11921 -1.04213 0.197538 5.11996 -0.990325 0.177954 5.26842 -0.997041 0.180911 6.06262 -0.919483 0.153374 6.14085 -0.813986 0.115138 5.8286 -0.730795 0.0853505 5.75379 -0.655266 0.0579586 5.8374 -0.604768 0.0402372 7.61929 -2.45194 0.639884 -1.0174 -2.51328 0.65968 -1.00874 -2.58076 0.681862 -1.00514 -2.66356 0.70957 -1.01303 -2.74731 0.736343 -1.01837 -2.82501 0.761913 -1.01491 -2.91699 0.792132 -1.02167 -3.01816 0.825641 -1.03176 -3.11317 0.855964 -1.03274 -3.20825 0.887431 -1.03077 -3.31968 0.924506 -1.03739 -3.44025 0.963939 -1.04599 -3.51393 0.987938 -1.01849 -3.50602 0.985459 -0.936722 -3.50525 0.985261 -0.860914 -3.56869 1.00528 -0.825047 -3.51486 0.987636 -0.720717 -3.51816 0.98888 -0.651313 -3.62143 1.02254 -0.635689 -3.53599 0.995225 -0.522176 -3.54337 0.997969 -0.457978 -3.51501 0.988615 -0.377943 -3.50292 0.983846 -0.306946 -3.52359 0.991363 -0.251676 -3.56155 1.00353 -0.202949 -3.61687 1.02139 -0.159817 -3.6722 1.03933 -0.114987 -3.79901 1.08093 -0.0925907 -3.9892 1.14401 -0.0857624 -4.32741 1.25454 -0.114829 -4.64012 1.35655 -0.124394 -4.97232 1.46573 -0.127325 -9.77801 3.03999 -1.15949 -10.7255 3.35068 -1.18366 -11.9376 3.74787 -1.22456 -13.5748 4.2844 -1.29557 -15.2745 4.84173 -1.31593 -18.6367 5.94334 -1.50327 -21.9535 7.02978 -1.16272 -23.0379 7.38481 -0.854919 -23.5012 7.53652 -0.468573 -23.9594 7.68734 -0.0658315 -23.609 7.57301 1.22405 -22.168 7.10038 1.6082 -19.4296 6.203 1.87953 -19.6015 6.25965 2.23932 -20.213 6.46043 2.64285 -18.4331 5.87693 2.8264 -22.3842 7.17202 3.63523 -27.528 8.85706 4.75859 -26.9161 8.6576 5.16829 -22.8753 7.33318 5.37591 -20.2848 6.48419 5.24665 -18.4214 5.87378 5.19074 -18.4971 5.89842 5.55672 -29.1726 9.39685 8.81886 -18.5455 5.91423 6.27653 -17.499 5.57178 6.30839 -17.8152 5.6752 6.75539 -16.9067 5.37755 6.7865 -18.1245 5.77666 7.5783 -19.8635 6.3468 8.63039 -17.3481 5.52225 7.99414 -17.3789 5.53292 8.36758 -17.3842 5.53488 8.73631 -17.668 5.62826 9.24449 -25.8729 8.31668 13.7516 -24.0585 7.72252 13.376 -19.004 6.06652 11.1493 -19.2092 6.13279 11.7027 -19.2435 6.14505 12.1727 -20.9052 6.6895 13.6632 -20.5545 6.57434 13.9472 -19.6639 6.28285 13.8618 -19.0908 6.09481 13.9633 -18.8497 6.01608 14.2858 -6.3324 1.91267 5.71488 -5.36849 1.5963 5.08012 -5.34441 1.58901 5.20709 -5.21572 1.54644 5.24342 -5.08091 1.50272 5.26974 -5.73047 1.71589 6.04949 -5.59058 1.67017 6.08966 -4.25173 1.23077 4.88518 -4.18757 1.20996 4.95348 -4.17364 1.20498 5.07867 -4.37419 1.27077 5.45535 -4.29366 1.24466 5.51831 -3.82317 1.09082 5.10048 -3.80311 1.08406 5.22269 -3.59726 1.01631 5.10264 -3.33184 0.929444 4.8891 -3.52127 0.991705 5.30237 -3.08528 0.848608 4.81971 -3.09702 0.851956 4.98208 -3.37084 0.941941 5.57138 -3.12168 0.86006 5.33656 -3.12845 0.862776 5.52051 -3.01491 0.825439 5.49913 -2.87877 0.78115 5.43147 -2.83205 0.765667 5.52733 -2.46744 0.646332 4.98389 -2.31157 0.595011 4.83149 -2.23181 0.568564 4.82808 -2.2623 0.579128 5.07768 -2.55759 0.675847 5.99002 -2.68206 0.716412 6.55385 -2.70779 0.725512 6.90948 -2.3333 0.602124 6.17156 -2.43131 0.635045 6.75125 -2.37146 0.614944 6.89969 -2.31895 0.59828 7.08587 -2.22613 0.567811 7.14712 -2.06086 0.513185 6.93697 -1.93593 0.472683 6.85824 -1.78289 0.421961 6.64061 -1.24566 0.246402 4.5543 -1.18328 0.225778 4.54789 -1.13335 0.208767 4.60911 -1.15446 0.215479 5.1331 -1.07979 0.191506 5.1049 -1.01763 0.171143 5.16456 -1.05882 0.184857 6.19691 -0.961316 0.152691 6.07705 -0.859371 0.119252 5.84544 -0.775371 0.0915514 5.79145 -0.69454 0.0650684 5.76582 -0.660688 0.0543551 7.60803 -0.546477 0.0169692 7.0601 -2.43988 0.573227 -1.02104 -2.50115 0.591981 -1.01324 -2.57662 0.614298 -1.01741 -2.64498 0.634475 -1.01271 -2.71535 0.654625 -1.00613 -2.79999 0.679388 -1.01048 -2.89996 0.709745 -1.02491 -2.98663 0.734649 -1.02397 -3.08864 0.765176 -1.03251 -3.17639 0.791282 -1.02623 -3.28143 0.821923 -1.02879 -3.39468 0.85596 -1.03377 -3.52416 0.89367 -1.04605 -3.52545 0.894388 -0.969495 -3.54201 0.899658 -0.903876 -3.53104 0.896303 -0.823244 -3.56995 0.907505 -0.772573 -3.55698 0.904217 -0.693033 -3.53375 0.896717 -0.609817 -3.55133 0.902638 -0.550044 -3.55965 0.904325 -0.485799 -3.61894 0.921776 -0.446075 -3.51018 0.889951 -0.330594 -3.54093 0.898665 -0.27935 -3.5524 0.902915 -0.220257 -3.61779 0.921953 -0.181551 -3.64649 0.92991 -0.127853 -3.76491 0.965049 -0.104386 -3.91085 1.00832 -0.0855943 -4.10369 1.06538 -0.0756818 -4.5106 1.18612 -0.118392 -4.77992 1.26554 -0.110455 -9.38638 2.62655 -1.13447 -10.2748 2.88952 -1.16124 -11.3163 3.19749 -1.18666 -12.8248 3.64339 -1.25962 -14.2539 4.06539 -1.26423 -19.1469 5.51151 -1.37778 -21.6729 6.25806 -1.30955 -23.0366 6.6613 -1.0444 -23.8039 6.88848 -0.687281 -23.7716 6.87858 -0.259767 -25.4855 7.38589 0.10302 -24.6367 7.1353 1.01242 -24.0964 6.97462 1.4416 -24.2764 7.02857 1.87807 -22.2086 6.41706 2.19764 -19.8611 5.72342 2.42186 -18.5929 5.34845 2.66005 -17.8368 5.12565 2.90929 -17.5929 5.05341 3.19761 -17.9338 5.15435 3.56419 -18.3043 5.26349 3.9501 -17.6195 5.06137 4.15704 -17.301 4.96702 4.41457 -18.1382 5.21506 5.25612 -17.2643 4.95644 5.36809 -17.1981 4.93759 5.67511 -17.0255 4.88648 5.95063 -17.7925 5.11334 6.52293 -18.8648 5.42991 7.233 -19.057 5.48636 7.67388 -20.3207 5.86104 8.53449 -23.1095 6.6854 10.0639 -17.407 4.99902 8.13373 -17.4531 5.01316 8.51461 -17.9641 5.16381 9.11929 -18.3557 5.28006 9.69396 -21.6972 6.26793 11.7947 -19.2923 5.55708 10.9973 -23.5491 6.81621 13.7953 -19.9441 5.74961 12.2526 -18.8479 5.42606 12.0593 -22.0703 6.37937 14.5307 -19.8895 5.73402 13.6484 -6.92359 1.9002 5.3551 -19.3192 5.56572 14.2513 -6.5852 1.7999 5.44844 -4.67139 1.23381 4.16465 -4.61042 1.21586 4.234 -6.323 1.72239 5.74985 -6.29494 1.71445 5.8992 -6.21162 1.68958 6.00397 -6.27256 1.70758 6.23839 -5.74932 1.55356 5.93433 -4.88003 1.29595 5.26486 -4.31248 1.12774 4.84363 -4.21368 1.09926 4.87698 -4.18135 1.08928 4.98 -4.16648 1.08535 5.10494 -4.37277 1.14623 5.49074 -4.27805 1.11819 5.53787 -4.01637 1.04069 5.3761 -3.73824 0.958232 5.17513 -3.5912 0.914764 5.13092 -3.59071 0.9153 5.28238 -3.56353 0.906878 5.40281 -3.42877 0.867135 5.36776 -3.51035 0.891823 5.6609 -3.55709 0.905708 5.91635 -3.37307 0.850938 5.80164 -3.22799 0.807573 5.74169 -3.11476 0.774712 5.73 -3.22112 0.806068 6.12688 -2.93744 0.722052 5.78695 -2.38666 0.559196 4.86814 -2.3554 0.550287 4.9738 -2.69302 0.649819 5.91348 -2.71638 0.656598 6.19935 -2.61746 0.627059 6.21133 -2.70888 0.654487 6.71283 -2.64089 0.634171 6.82689 -2.49061 0.590519 6.71453 -2.42883 0.572089 6.85389 -2.40211 0.563685 7.1165 -2.29098 0.531525 7.12147 -2.14264 0.487795 6.98968 -2.01068 0.447836 6.89314 -2.00903 0.447447 7.32731 -1.26737 0.228317 4.47916 -1.22168 0.214601 4.55131 -1.13455 0.189097 4.41664 -1.22104 0.21497 5.2845 -1.12256 0.185623 5.11925 -1.05529 0.165635 5.13987 -0.999611 0.149311 5.26848 -1.00832 0.151637 6.0726 -0.926953 0.128351 6.13082 -0.812339 0.0942425 5.70889 -0.733815 0.0711499 5.71392 -0.658715 0.0482153 5.84738 -0.602406 0.0319802 7.34938 -2.47278 0.519963 -1.0033 -2.54812 0.540221 -1.00867 -2.61735 0.55828 -1.00518 -2.70898 0.583125 -1.01959 -2.77923 0.601335 -1.01181 -2.86575 0.624042 -1.01486 -2.94416 0.644666 -1.00916 -3.0551 0.67426 -1.02562 -3.15893 0.701739 -1.03272 -3.25565 0.727089 -1.03076 -3.36151 0.754753 -1.03168 -3.47553 0.784821 -1.03487 -3.56622 0.809249 -1.01841 -3.55018 0.804513 -0.931373 -3.59922 0.81784 -0.886176 -3.55471 0.805463 -0.785668 -3.62711 0.824725 -0.754124 -3.56231 0.8079 -0.646663 -3.64081 0.828665 -0.617835 -3.58108 0.813168 -0.51788 -3.59754 0.81716 -0.457904 -3.5591 0.806608 -0.373843 -3.54613 0.803884 -0.303142 -3.56768 0.809337 -0.247975 -3.60651 0.819438 -0.199352 -3.6535 0.831938 -0.153101 -3.71879 0.8491 -0.111898 -3.84718 0.883576 -0.0896608 -4.03248 0.93204 -0.0800791 -4.27377 0.995697 -0.0802031 -4.63718 1.09191 -0.104314 -9.09409 2.26633 -1.12902 -9.78034 2.44787 -1.12268 -10.838 2.7267 -1.1696 -12.1277 3.06645 -1.22255 -13.7188 3.48603 -1.28061 -15.3997 3.92945 -1.29503 -22.3201 5.75388 -1.16152 -24.5412 6.33967 -0.944306 -25.1402 6.49783 -0.545899 -23.1526 5.97442 -0.0111987 -23.8784 6.16545 1.22304 -23.2332 5.99582 1.62737 -22.2245 5.72983 1.99214 -22.5231 5.80852 2.40444 -22.669 5.84724 2.81594 -18.2564 4.68351 2.77753 -17.3011 4.43173 2.98858 -17.7157 4.54116 3.35318 -18.0844 4.63779 3.72731 -18.5703 4.76622 4.13699 -17.676 4.53046 4.62342 -18.1314 4.65065 5.05222 -18.9436 4.86502 5.58972 -20.6424 5.31316 6.39846 -17.9208 4.59544 6.00632 -18.0278 4.62358 6.37973 -18.6721 4.79388 6.93626 -19.5325 5.0205 7.597 -18.9803 4.87533 7.77908 -20.6196 5.30811 8.7919 -17.319 4.43716 7.86221 -17.4955 4.48392 8.29115 -20.6064 5.30443 10.0539 -17.4326 4.46736 8.99152 -17.6796 4.53217 9.48551 -17.4381 4.46938 9.74522 -21.6871 5.58949 12.4206 -20.5903 5.30043 12.295 -19.6391 5.04986 12.2124 -20.6546 5.31805 13.2926 -20.6838 5.32576 13.8062 -7.0534 1.72929 5.32338 -6.8264 1.66941 5.33615 -6.73614 1.64584 5.43829 -6.62137 1.61576 5.52118 -4.64083 1.09262 4.1727 -4.57897 1.07667 4.24086 -4.4926 1.05419 4.28905 -5.94373 1.43723 5.64631 -5.98918 1.44883 5.85432 -5.66708 1.364 5.73393 -5.95766 1.44074 6.17791 -5.19634 1.24006 5.61449 -5.32457 1.27403 5.90899 -4.24527 0.98846 4.94643 -4.2049 0.978615 5.04238 -4.09705 0.950112 5.06438 -3.98918 0.921482 5.08378 -3.81282 0.874641 5.01679 -3.78162 0.866724 5.1223 -3.75346 0.859019 5.2358 -3.70489 0.846357 5.32563 -3.53972 0.802627 5.25411 -3.35511 0.754215 5.1455 -3.38839 0.76352 5.353 -3.59767 0.818543 5.8466 -3.42734 0.77329 5.75837 -3.36142 0.75606 5.83613 -3.10809 0.688687 5.5854 -2.98687 0.657308 5.55345 -2.90554 0.635894 5.58885 -2.59566 0.55356 5.1702 -2.41692 0.506939 4.98367 -2.75687 0.596263 5.90241 -2.63042 0.562795 5.84226 -2.60969 0.558171 6.02674 -2.76139 0.598312 6.65551 -2.61549 0.559506 6.56521 -2.42641 0.509594 6.34025 -2.4654 0.519645 6.75133 -2.4079 0.504885 6.9092 -2.35969 0.491921 7.11449 -2.23739 0.459478 7.08 -2.13159 0.431798 7.10084 -1.98036 0.391602 6.93575 -1.93852 0.380895 7.21438 -1.85649 0.359331 7.34681 -1.46809 0.256677 5.93953 -1.12128 0.165027 4.48128 -1.16614 0.17666 5.13314 -1.09283 0.157599 5.12472 -1.03203 0.142154 5.20425 -1.07092 0.152013 6.21678 -0.967604 0.125237 6.05703 -0.867207 0.0987033 5.86532 -0.777148 0.0744222 5.73151 -0.697806 0.0533428 5.75587 -0.661952 0.0447724 7.55804 -0.547291 0.0144123 7.05001 -2.45584 0.455607 -1.00693 -2.52493 0.471529 -1.00624 -2.60923 0.490962 -1.01733 -2.67128 0.505831 -1.00603 -2.7566 0.525426 -1.01263 -2.83586 0.543818 -1.01042 -2.92221 0.563589 -1.01223 -3.02583 0.587841 -1.02398 -3.12947 0.612251 -1.03253 -3.21892 0.633241 -1.02621 -3.32459 0.657825 -1.02878 -3.43935 0.683751 -1.03367 -3.5552 0.710786 -1.03511 -3.57269 0.714999 -0.969448 -3.56384 0.713547 -0.888322 -3.64619 0.731894 -0.863103 -3.58358 0.718072 -0.7531 -3.6558 0.734363 -0.721008 -3.58099 0.717328 -0.609771 -3.59031 0.718955 -0.545529 -3.59869 0.721629 -0.481533 -3.67602 0.739582 -0.450156 -3.55749 0.711564 -0.330497 -3.57903 0.717006 -0.27553 -3.60052 0.721472 -0.220115 -3.65758 0.73516 -0.178089 -3.68622 0.742109 -0.124542 -3.80721 0.770064 -0.101236 -3.9556 0.804154 -0.0826077 -4.15076 0.850025 -0.0728588 -4.42303 0.912618 -0.0769262 -9.49739 2.09358 -1.12759 -10.4088 2.30589 -1.1569 -11.4097 2.53863 -1.17116 -12.9316 2.89246 -1.24376 -14.4974 3.25704 -1.26861 -16.8201 3.79698 -1.34603 -19.4386 4.4066 -1.37734 -22.0433 5.01278 -1.31329 -23.486 5.34784 -1.05247 -24.7806 5.64976 -0.730328 -26.557 6.063 -0.388317 -23.5205 5.35619 0.186836 -24.0983 5.49072 1.01246 -24.3385 5.5466 1.43986 -22.4974 5.11903 1.80032 -22.7629 5.18051 2.20976 -23.1271 5.26499 2.63658 -21.864 4.97173 2.93047 -18.467 4.18077 2.94851 -17.3091 3.91158 3.12823 -17.8398 4.03499 3.51155 -18.275 4.13636 3.90035 -21.2734 4.83412 4.77217 -21.837 4.96526 5.27014 -19.0368 4.31428 5.05572 -19.2209 4.35676 5.44817 -17.9336 4.05759 5.47268 -17.6194 3.98452 5.71952 -17.4994 3.95628 6.01452 -17.8677 4.04252 6.46185 -19.2441 4.36238 7.26439 -18.5647 4.20439 7.39713 -18.7826 4.25552 7.84322 -18.5997 4.21334 8.14459 -19.0527 4.3183 8.70792 -19.349 4.38738 9.22693 -17.6681 3.99618 8.85902 -18.1579 4.1101 9.46583 -17.5566 3.9702 9.55284 -19.5946 4.44474 11.0024 -19.2754 4.37066 11.2631 -19.1923 4.35184 11.6513 -22.7521 5.1806 14.2065 -19.745 4.48016 12.8868 -20.3412 4.61917 13.7443 -7.13782 1.54601 5.43153 -6.82771 1.47328 5.38757 -4.75761 0.991958 4.06531 -4.62659 0.961599 4.08234 -4.6198 0.959437 4.19202 -4.57334 0.949141 4.27151 -6.11325 1.30693 5.67272 -4.86249 1.01627 4.76273 -4.78955 0.999136 4.83381 -4.70951 0.981015 4.89667 -4.50708 0.933346 4.8419 -4.44131 0.918791 4.91311 -4.51919 0.935992 5.13185 -4.29232 0.88383 5.03771 -4.51611 0.935799 5.42695 -4.2902 0.883305 5.3273 -3.86434 0.784405 4.97927 -3.84639 0.779466 5.10027 -3.87441 0.785902 5.28401 -3.83717 0.777429 5.39119 -3.76732 0.761912 5.45827 -3.50245 0.70031 5.24908 -3.34569 0.663183 5.17939 -3.40543 0.676984 5.42875 -3.55206 0.711267 5.83255 -3.38208 0.671912 5.74233 -3.21102 0.631968 5.63892 -3.06857 0.599236 5.57413 -2.95674 0.573106 5.55829 -2.68228 0.508766 5.22184 -2.51312 0.470023 5.0642 -2.76436 0.52824 5.77395 -2.63305 0.497642 5.70509 -2.60821 0.492318 5.87051 -2.51374 0.470404 5.87988 -2.4377 0.452601 5.93379 -2.3637 0.43508 5.99589 -2.60455 0.491004 6.94962 -2.05982 0.364641 5.66242 -2.39538 0.442065 7.00239 -2.26722 0.413066 6.94934 -2.23562 0.405856 7.23004 -2.02613 0.357194 6.86418 -1.98018 0.346297 7.1138 -1.92713 0.333829 7.36355 -1.54384 0.243938 6.05784 -1.13906 0.149248 4.38724 -1.21072 0.167102 5.15646 -1.13435 0.148289 5.12913 -1.06745 0.133274 5.16953 -1.07261 0.134922 5.81441 -1.01131 0.120388 6.03277 -0.921766 0.0996676 5.9914 -0.817177 0.0753976 5.69888 -0.736837 0.0559309 5.69392 -0.724183 0.054391 7.72628 -0.602728 0.0254819 7.25938 -2.49976 0.402997 -1.003 -2.57686 0.419137 -1.00838 -2.64684 0.433142 -1.0048 -2.73203 0.450679 -1.0126 -2.80404 0.464761 -1.00502 -2.89026 0.482469 -1.00813 -2.98556 0.501444 -1.01506 -3.09 0.522714 -1.02527 -3.17927 0.540635 -1.0204 -3.28575 0.562079 -1.02461 -3.40032 0.58492 -1.03125 -3.51696 0.60881 -1.03445 -3.61737 0.628375 -1.02332 -3.60952 0.626902 -0.9414 -3.58347 0.621971 -0.850285 -3.59684 0.624397 -0.785206 -3.63557 0.632598 -0.734587 -3.60439 0.625838 -0.646152 -3.60563 0.626181 -0.577192 -3.61395 0.627863 -0.513047 -3.64863 0.635349 -0.461566 -3.59215 0.62428 -0.369459 -3.59741 0.625083 -0.306553 -3.60975 0.627274 -0.247464 -3.64032 0.633032 -0.195372 -3.69727 0.644755 -0.152648 -3.75323 0.656622 -0.108223 -3.88413 0.682916 -0.0860982 -4.06167 0.718941 -0.0738526 -4.30611 0.76835 -0.0742944 -9.14563 1.74349 -1.11155 -9.79274 1.87372 -1.09544 -10.9417 2.10603 -1.16025 -12.1343 2.34637 -1.19198 -13.7944 2.68102 -1.26069 -15.5469 3.0344 -1.28423 -22.5819 4.45249 -1.15481 -24.3353 4.80668 -0.898354 -24.7261 4.88533 -0.496041 -24.4445 4.82815 -0.0511395 -24.7826 4.89672 0.366914 -24.7212 4.88483 0.799812 -24.7012 4.88038 1.23099 -24.5758 4.85504 1.65854 -25.266 4.99472 2.11897 -24.8221 4.9057 2.5332 -19.4274 3.81718 2.53189 -18.9497 3.72115 2.82432 -18.4769 3.62605 3.10126 -17.8458 3.49855 3.34103 -20.0326 3.93941 3.99083 -20.9359 4.1219 4.5022 -18.8973 3.71084 4.49061 -18.5077 3.6329 4.74967 -18.9766 3.72683 5.1913 -18.5494 3.64127 5.43294 -19.0875 3.74917 5.91681 -18.7079 3.67304 6.164 -18.8238 3.69626 6.55002 -19.1093 3.75449 6.99895 -17.9722 3.52515 6.97643 -18.5694 3.64552 7.54081 -19.3363 3.80039 8.19826 -19.3192 3.79715 8.5766 -18.1911 3.56905 8.48888 -18.5448 3.6412 9.0184 -17.5577 3.44135 8.94394 -18.3309 3.59725 9.69051 -20.5651 4.04796 11.2217 -19.2225 3.77792 10.958 -19.5744 3.84882 11.5812 -19.5951 3.85319 12.0375 -20.0701 3.94853 12.7772 -19.1306 3.7599 12.6635 -19.3333 3.80023 13.257 -20.2974 3.9947 14.386 -19.8386 3.90255 14.5777 -4.71099 0.850516 4.06897 -4.51611 0.810516 4.0364 -4.37006 0.78112 4.03435 -4.94599 0.897498 4.61368 -4.10537 0.728009 4.0366 -4.76076 0.860698 4.71776 -4.67368 0.842631 4.77316 -4.11767 0.73065 4.38723 -4.32257 0.772233 4.70601 -4.38402 0.78417 4.89978 -4.12498 0.732105 4.76848 -4.13355 0.733721 4.91233 -4.22461 0.752242 5.15345 -3.86168 0.679422 4.88194 -3.81934 0.67039 4.97166 -3.80151 0.667415 5.09196 -3.82847 0.672895 5.27535 -3.68942 0.644761 5.24666 -3.72659 0.6519 5.45564 -3.65578 0.637337 5.52057 -3.33329 0.572338 5.21338 -3.37971 0.582133 5.4467 -3.50363 0.607138 5.81786 -3.34415 0.574921 5.74274 -3.14281 0.534145 5.5858 -3.21893 0.549711 5.91076 -2.70938 0.446804 5.15845 -2.60585 0.425818 5.13509 -2.80554 0.466245 5.727 -2.75418 0.456437 5.83052 -2.78041 0.461001 6.11569 -2.39592 0.383349 5.45837 -2.30467 0.365598 5.45451 -2.40051 0.384577 5.93267 -2.35634 0.375424 6.07827 -2.11264 0.327125 5.65794 -2.41158 0.38703 6.8431 -2.32871 0.370451 6.93354 -2.18534 0.34144 6.82142 -2.07478 0.319563 6.81197 -2.0494 0.313813 7.1296 -1.95534 0.295151 7.20489 -1.59254 0.221471 6.04843 -1.74356 0.252642 7.26276 -1.27157 0.156939 5.26813 -1.1727 0.136663 5.12346 -1.10381 0.122822 5.14469 -1.04326 0.11086 5.23406 -1.0852 0.120016 6.27654 -0.964481 0.0949036 5.96764 -0.875107 0.0776385 5.91528 -0.774809 0.0570635 5.64177 -0.698014 0.0418101 5.7259 -0.663344 0.0346623 7.55813 -0.54711 0.0114165 7.05006 -2.47989 0.339829 -1.00647 -2.5568 0.352924 -1.0128 -2.62666 0.364886 -1.01012 -2.69753 0.376882 -1.00554 -2.78355 0.391416 -1.01219 -2.86357 0.405751 -1.00999 -2.96675 0.422876 -1.02439 -3.04779 0.437391 -1.01729 -3.16107 0.455896 -1.03202 -3.25122 0.471832 -1.02566 -3.35853 0.490298 -1.02823 -3.46685 0.508867 -1.02751 -3.59234 0.530027 -1.03454 -3.6512 0.540455 -0.995365 -3.61808 0.534254 -0.898035 -3.65874 0.541332 -0.847472 -3.62061 0.535315 -0.752524 -3.91999 0.586989 -0.842426 -3.62609 0.535864 -0.613713 -3.64455 0.539736 -0.553744 -3.64473 0.539123 -0.48513 -3.73289 0.55422 -0.457684 -3.61179 0.533391 -0.337763 -3.62519 0.536519 -0.278727 -3.63754 0.53871 -0.219638 -3.68622 0.54606 -0.174044 -3.72388 0.553295 -0.123971 -3.83735 0.572833 -0.0975004 -3.99634 0.600109 -0.0820054 -4.20386 0.635072 -0.0748985 -4.51763 0.688632 -0.0891893 -9.02122 1.46125 -1.14943 -9.58519 1.55796 -1.12163 -10.5073 1.71546 -1.15102 -11.5399 1.89291 -1.16935 -13.0319 2.14869 -1.23303 -14.7325 2.43998 -1.27722 -16.8198 2.79846 -1.31569 -19.7331 3.29723 -1.38271 -22.4181 3.75794 -1.32229 -23.1622 3.88568 -0.996066 -23.793 3.99383 -0.63664 -24.0535 4.03812 -0.236334 -26.9133 4.52855 1.01802 -26.8703 4.52125 1.48492 -25.5374 4.29359 1.90417 -27.497 4.62885 2.45395 -26.966 4.53845 2.89582 -19.2512 3.21518 2.67751 -19.1905 3.20509 3.00619 -19.0356 3.17899 3.32212 -18.8756 3.15095 3.63317 -19.0712 3.18533 3.99742 -18.3369 3.05939 4.20381 -18.1445 3.02617 4.49238 -18.2549 3.0449 4.84191 -21.1343 3.53888 5.84826 -19.2115 3.20965 5.74711 -25.6376 4.31135 7.85241 -24.1902 4.0636 7.90972 -17.9229 2.98881 6.41787 -18.2392 3.04292 6.8618 -18.4623 3.08078 7.28918 -18.5091 3.08959 7.66452 -19.2654 3.21909 8.32349 -19.8221 3.31421 8.93603 -20.3983 3.41403 9.58606 -20.1755 3.37511 9.90465 -20.4932 3.42945 10.476 -20.2918 3.39507 10.811 -19.2336 3.21379 10.7009 -19.3505 3.23386 11.1863 -20.5852 3.44606 12.3145 -19.3047 3.22654 12.0328 -20.4371 3.42046 13.1735 -20.1253 3.36733 13.461 -21.0724 3.53 14.5753 -4.84361 0.745709 3.97811 -4.80849 0.740162 4.066 -4.64345 0.711693 4.05952 -4.34646 0.660783 3.94571 -4.41884 0.672699 4.11199 -4.13504 0.624696 3.99195 -4.42267 0.674037 4.34538 -4.07478 0.613536 4.15838 -4.06401 0.612283 4.26133 -4.00038 0.600846 4.31716 -4.1765 0.631746 4.60801 -4.33634 0.658623 4.89906 -4.1052 0.619197 4.7936 -4.20011 0.635369 5.03251 -3.96588 0.59536 4.91158 -3.83321 0.572547 4.8968 -3.84182 0.574489 5.04724 -3.82704 0.571742 5.17582 -3.62725 0.537351 5.06851 -3.50367 0.51588 5.05141 -3.49707 0.515289 5.19296 -3.43042 0.503273 5.25364 -3.21935 0.467138 5.09752 -3.22294 0.468102 5.26256 -3.19603 0.46385 5.38649 -3.15585 0.456556 5.49363 -3.03935 0.436375 5.47071 -2.78031 0.392561 5.18251 -2.74931 0.387317 5.30171 -3.06372 0.440917 6.11643 -2.97171 0.425172 6.15202 -2.76143 0.388829 5.93214 -2.43995 0.334255 5.43229 -2.31413 0.312501 5.34623 -2.31997 0.313827 5.58182 -2.37179 0.322414 5.95884 -2.18776 0.290498 5.71865 -2.09665 0.274978 5.71948 -2.04641 0.266056 5.84218 -2.06894 0.270572 6.22279 -2.01682 0.261689 6.38435 -1.88792 0.239975 6.27518 -1.71171 0.20936 5.94957 -1.64212 0.196925 6.03862 -1.84924 0.233325 7.46671 -1.43415 0.161436 5.89928 -1.21504 0.123743 5.13695 -1.1411 0.110779 5.12933 -1.07961 0.100413 5.20932 -1.07748 0.10004 5.80469 -1.01437 0.0896423 6.00313 -0.915765 0.0730317 5.872 -0.827505 0.0576606 5.81873 -0.737986 0.0423323 5.68408 -0.661372 0.0285274 5.79757 -0.600991 0.0191211 7.14947 -2.52775 0.286612 -1.00995 -2.59748 0.296527 -1.00827 -2.67629 0.307654 -1.0115 -2.76212 0.319144 -1.01911 -2.84195 0.330433 -1.01786 -2.92279 0.34177 -1.01441 -3.01072 0.354491 -1.01488 -3.10873 0.368428 -1.01897 -3.21483 0.383728 -1.02619 -3.3058 0.396667 -1.01858 -3.42194 0.412384 -1.02538 -3.53916 0.42921 -1.02873 -3.66548 0.447402 -1.03392 -3.64149 0.443426 -0.941258 -3.63165 0.442029 -0.860229 -3.73178 0.456846 -0.844056 -3.64119 0.443403 -0.720082 -3.69689 0.451144 -0.678255 -3.65475 0.445236 -0.585991 -3.655 0.445629 -0.517227 -3.69858 0.451382 -0.46962 -3.6332 0.442066 -0.373239 -3.63746 0.442939 -0.310131 -3.6508 0.445075 -0.250945 -3.68131 0.449835 -0.198804 -3.73902 0.457515 -0.155785 -3.77657 0.462796 -0.104813 -3.91813 0.483267 -0.0859715 -4.08891 0.506803 -0.0708653 -4.35466 0.544627 -0.0766744 -9.19456 1.22746 -1.10182 -9.99376 1.33984 -1.1187 -11.0768 1.49275 -1.16567 -12.2712 1.6619 -1.19501 -13.919 1.89423 -1.25839 -15.6893 2.14422 -1.28195 -22.5196 3.10857 -1.12608 -22.5825 3.11694 -0.740002 -22.4605 3.09998 -0.341423 -22.4506 3.09883 0.0471738 -22.4438 3.09844 0.434713 -22.4511 3.09917 0.821509 -22.4605 3.10079 1.20855 -22.4637 3.10078 1.59591 -22.469 3.10169 1.98381 -22.4885 3.10483 2.37331 -22.5109 3.10787 2.76471 -22.5264 3.1104 3.15717 -22.5549 3.11431 3.55309 -18.8653 2.59303 3.4547 -18.8593 2.5927 3.78396 -18.5156 2.54381 4.05752 -18.3529 2.52125 4.35441 -20.3196 2.79894 5.0866 -20.604 2.8392 5.51569 -21.1583 2.91724 6.02386 -18.9589 2.60738 5.83495 -26.1328 3.61955 8.19807 -18.857 2.59269 6.50543 -18.145 2.49254 6.63221 -18.2513 2.50703 7.01241 -18.8453 2.5914 7.57519 -19.4424 2.67605 8.16757 -18.8365 2.59031 8.3095 -18.3875 2.52647 8.49745 -23.856 3.29917 11.2756 -20.253 2.79072 10.1076 -20.4223 2.81468 10.6139 -21.6261 2.98435 11.6561 -21.3341 2.94343 11.9714 -20.2191 2.78612 11.8306 -20.5202 2.82818 12.4575 -20.7364 2.85899 13.0576 -20.7451 2.86079 13.5484 -21.0919 2.90976 14.2691 -4.49543 0.565231 3.7784 -4.43093 0.555976 3.83672 -4.42114 0.55445 3.93538 -4.2837 0.534752 3.9371 -4.23241 0.528101 4.00333 -4.14866 0.516083 4.04318 -4.11863 0.512011 4.12657 -4.08653 0.507053 4.20982 -4.08895 0.507697 4.32661 -4.10249 0.509407 4.45821 -4.12724 0.51322 4.60535 -4.1266 0.512583 4.73304 -4.21119 0.524578 4.95611 -4.03524 0.50046 4.90281 -3.87545 0.477875 4.85966 -3.8079 0.467835 4.91864 -3.75864 0.460786 4.99949 -3.71348 0.454856 5.08767 -3.58816 0.437588 5.07228 -3.42318 0.413739 4.99738 -3.56676 0.433613 5.34975 -3.27795 0.393001 5.08981 -3.16882 0.378032 5.0798 -3.09216 0.367496 5.11774 -3.01039 0.355772 5.14576 -2.93876 0.34522 5.18947 -2.85597 0.333404 5.2144 -2.99989 0.353867 5.65975 -3.08803 0.36701 6.03132 -3.05823 0.362784 6.19261 -2.71305 0.313776 5.69524 -2.49595 0.282771 5.43318 -2.38364 0.267103 5.38509 -2.33037 0.259648 5.47309 -2.27816 0.252562 5.56978 -2.27179 0.251214 5.79727 -2.15234 0.234727 5.72403 -2.0859 0.225459 5.79989 -2.0797 0.224466 6.07511 -2.19109 0.239888 6.78314 -2.1515 0.234674 7.03375 -1.76709 0.179839 5.96781 -1.69562 0.170073 6.04773 -1.60981 0.157693 6.0778 -1.79002 0.183895 7.42947 -1.2582 0.107751 5.15019 -1.18138 0.097511 5.13334 -1.11379 0.0875854 5.1744 -1.30637 0.115787 7.22716 -1.06301 0.0809283 6.02819 -0.965656 0.0667766 5.92787 -0.878706 0.054357 5.9154 -0.776776 0.0398994 5.6419 -0.700221 0.029148 5.716 -0.66592 0.0254605 7.59811 -0.546867 0.00792803 7.04012 -2.56643 0.230317 -1.00581 -2.63705 0.238216 -1.00323 -2.72374 0.247578 -1.01224 -2.79538 0.255619 -1.00557 -2.89117 0.266346 -1.0164 -2.97997 0.276948 -1.01807 -3.06165 0.285402 -1.01108 -3.16756 0.297622 -1.01995 -3.25834 0.307486 -1.01389 -3.37429 0.320118 -1.02244 -3.49132 0.33386 -1.02754 -3.61738 0.347966 -1.03452 -3.7203 0.359433 -1.02181 -3.66921 0.353859 -0.913482 -3.66745 0.353727 -0.837571 -3.66461 0.352628 -0.762206 -3.80884 0.36874 -0.767296 -3.6701 0.353207 -0.622797 -3.68042 0.354794 -0.558159 -3.69776 0.356747 -0.497788 -3.77754 0.365555 -0.465774 -3.64679 0.350537 -0.341575 -3.67021 0.35388 -0.286215 -3.67341 0.353812 -0.223154 -3.72197 0.359168 -0.177461 -3.76954 0.364649 -0.130466 -3.8554 0.374294 -0.0944264 -4.00675 0.391136 -0.0761667 -4.21559 0.414966 -0.06942 -4.55138 0.451881 -0.0891333 -9.0536 0.953236 -1.13969 -9.55505 1.00933 -1.09689 -10.5333 1.11869 -1.13856 -11.544 1.2315 -1.15217 -13.0779 1.40216 -1.22262 -14.6845 1.58057 -1.25055 -16.484 1.78189 -1.24906 -19.9633 2.16951 -1.39108 -22.829 2.48816 -1.34589 -23.4403 2.55651 -1.00361 -23.7784 2.59418 -0.621875 -24.3002 2.65293 -0.238713 -27.3982 2.9983 0.545939 -23.0293 2.51117 1.01545 -22.8964 2.49662 1.40877 -22.9753 2.50553 1.80514 -22.3925 2.44049 2.16958 -28.8919 3.1653 3.01715 -28.4768 3.1182 3.4821 -25.1286 2.7456 3.62167 -18.6479 2.02349 3.25485 -18.7337 2.03302 3.59137 -19.3342 2.10005 4.01489 -19.7783 2.14923 4.43414 -20.9058 2.27504 5.0057 -20.8131 2.26511 5.3593 -19.5243 2.12095 5.43334 -19.6476 2.13461 5.81768 -18.8886 2.05069 5.97158 -19.0583 2.06918 6.36831 -18.7626 2.03695 6.63185 -19.616 2.1322 7.26448 -12.1297 1.29718 5.03862 -19.8637 2.15909 8.10676 -19.0783 2.07229 8.19078 -18.5371 2.01144 8.34711 -18.1868 1.9724 8.56887 -22.8365 2.49068 11.025 -22.5693 2.46095 11.3734 -20.1352 2.19002 10.6532 -22.1431 2.41421 12.1148 -20.7008 2.25324 11.8256 -22.6737 2.47349 13.3874 -22.1539 2.41514 13.5997 -21.6341 2.35807 13.7976 -4.68303 0.466873 3.84377 -4.56814 0.454099 3.87094 -4.44514 0.440359 3.889 -4.33834 0.429076 3.91564 -4.28712 0.423462 3.98262 -4.22775 0.415978 4.04243 -4.1897 0.412114 4.12025 -4.17184 0.41 4.21748 -4.10144 0.402723 4.26804 -4.1969 0.413216 4.47409 -4.14265 0.407003 4.54551 -4.09449 0.40173 4.62307 -4.00384 0.391833 4.65685 -4.05483 0.396967 4.84232 -4.15349 0.408336 5.09005 -4.161 0.408522 5.24419 -3.84356 0.373253 5.0166 -3.74277 0.362245 5.03589 -3.61664 0.348072 5.02125 -3.55229 0.341003 5.08337 -3.42918 0.32739 5.06347 -3.32329 0.315816 5.0652 -3.34712 0.318802 5.25514 -3.19153 0.301329 5.17867 -3.19811 0.301553 5.35263 -3.29603 0.312451 5.6909 -3.07958 0.28822 5.5054 -3.03048 0.282971 5.60249 -3.27162 0.309897 6.25568 -3.04909 0.28579 6.04508 -2.83556 0.261839 5.82841 -2.6463 0.239934 5.64202 -2.44891 0.218458 5.41402 -2.44149 0.217779 5.61334 -2.30499 0.202713 5.5076 -2.28436 0.19989 5.68808 -2.23942 0.19522 5.82206 -2.1303 0.182485 5.7763 -2.02834 0.171147 5.74715 -1.93963 0.161802 5.75407 -2.24265 0.19605 7.13431 -2.14603 0.18522 7.20263 -1.74383 0.139546 6.03702 -1.69199 0.134422 6.21401 -1.59919 0.123489 6.22433 -1.30434 0.0905254 5.18259 -1.21943 0.080861 5.12712 -1.15096 0.0735385 5.15894 -1.08972 0.0666663 5.24897 -1.10417 0.0681869 5.98331 -1.02166 0.0595869 6.03291 -0.920302 0.0481737 5.88191 -0.836648 0.0390103 5.8986 -0.739073 0.0277269 5.67408 -0.661763 0.018977 5.78752 -0.60169 0.0125433 7.17943 -2.80243 0.18759 -1.90157 -2.53351 0.166251 -1.00285 -2.611 0.172336 -1.00823 -2.6905 0.178409 -1.01142 -2.76201 0.184397 -1.00585 -2.8426 0.191613 -1.0049 -2.93115 0.198149 -1.00798 -3.02778 0.206012 -1.01487 -3.11742 0.213735 -1.0129 -3.22415 0.222973 -1.02022 -3.32382 0.231074 -1.01863 -3.44054 0.239737 -1.02539 -3.55033 0.249262 -1.02323 -3.67815 0.259333 -1.02852 -3.74673 0.264962 -0.993379 -3.68669 0.26016 -0.880433 -3.69293 0.260294 -0.80959 -3.68816 0.260308 -0.734369 -3.71858 0.263268 -0.678233 -3.70267 0.261128 -0.599332 -3.70292 0.261547 -0.530069 -3.74737 0.265259 -0.482067 -3.68124 0.260026 -0.385182 -3.67643 0.259657 -0.317751 -3.69873 0.261086 -0.26189 -3.7211 0.263531 -0.205679 -3.76954 0.266933 -0.159087 -3.79895 0.269859 -0.104846 -3.93087 0.280036 -0.0828336 -4.12122 0.296076 -0.0736861 -4.39 0.317677 -0.0793143 -9.21342 0.711213 -1.09249 -10.0168 0.776169 -1.10996 -11.0486 0.860515 -1.14573 -12.1923 0.953934 -1.1658 -13.9187 1.09455 -1.24347 -15.6222 1.23373 -1.25685 -20.3361 1.61819 -1.25375 -23.1001 1.84369 -1.16779 -23.8009 1.90071 -0.823797 -23.6996 1.8934 -0.4077 -24.9451 1.99423 -0.0540098 -28.6563 2.2972 0.279495 -27.5882 2.21063 1.25575 -22.6076 1.80418 1.5961 -22.345 1.78256 1.97205 -20.1862 1.60639 2.22175 -19.8731 1.5811 2.54332 -27.8396 2.23169 3.66013 -18.2729 1.45089 3.04422 -19.0746 1.51574 3.4667 -18.98 1.50814 3.78415 -20.7863 1.65635 4.4205 -21.2428 1.69335 4.87212 -21.7387 1.73333 5.35078 -20.1329 1.60214 5.38128 -21.8651 1.74395 6.16208 -20.0164 1.59368 6.07858 -21.4808 1.71326 6.85351 -18.634 1.48066 6.40307 -19.1542 1.52286 6.91561 -20.1642 1.60502 7.6166 -12.0241 0.940679 5.10382 -19.8008 1.57548 8.25549 -19.8101 1.57634 8.64747 -22.4175 1.78927 10.1266 -22.5026 1.79645 10.6169 -22.4225 1.79034 11.0422 -21.3813 1.70521 11.0106 -24.396 1.95172 12.9743 -22.2485 1.77598 12.3784 -21.7236 1.73348 12.5808 -22.0046 1.75664 13.2267 -21.6511 1.72737 13.5201 -21.5236 1.71713 13.9461 -4.54509 0.331192 3.69091 -4.38294 0.317473 3.68198 -4.22181 0.304453 3.6682 -4.47948 0.325421 3.95923 -4.22145 0.304476 3.87005 -4.28035 0.309475 4.02202 -4.27264 0.309086 4.12592 -4.53647 0.330043 4.46458 -4.15422 0.299315 4.24958 -4.04655 0.290576 4.2658 -4.09742 0.294695 4.43068 -4.12913 0.297408 4.58434 -4.02447 0.288684 4.60454 -4.07136 0.292659 4.78188 -3.94447 0.28205 4.77748 -3.85192 0.274076 4.80728 -3.73918 0.265078 4.81212 -4.00244 0.286963 5.26969 -3.75322 0.266052 5.11116 -3.71228 0.263266 5.20716 -3.44881 0.241073 5.00553 -3.46549 0.242653 5.17867 -3.44276 0.241239 5.30423 -3.3401 0.232849 5.31339 -3.36592 0.234676 5.5228 -3.22986 0.223642 5.47853 -3.09074 0.212193 5.42218 -3.02856 0.207431 5.49298 -2.95523 0.201426 5.5454 -2.91228 0.197614 5.65869 -3.13689 0.215814 6.31802 -2.7231 0.182325 5.68624 -2.63658 0.174956 5.71537 -2.53897 0.16781 5.71533 -2.32355 0.149435 5.42691 -2.32939 0.150242 5.67223 -2.24489 0.143399 5.69422 -2.48856 0.163046 6.64802 -2.15313 0.135596 5.97061 -1.97308 0.12114 5.7031 -2.27535 0.145881 7.03246 -2.12489 0.133283 6.89884 -2.07737 0.130054 7.13939 -1.84012 0.110619 6.62147 -1.6863 0.0973864 6.39029 -1.36464 0.0718206 5.28316 -1.26146 0.0629312 5.14036 -1.18901 0.0569033 5.15302 -1.12377 0.051835 5.21395 -1.21131 0.059019 6.45378 -1.05559 0.0463459 5.92882 -0.971133 0.0398428 5.9577 -0.880307 0.0316958 5.9054 -0.783044 0.0239336 5.71174 -0.699368 0.0176874 5.66601 -0.667312 0.0148411 7.60814 -0.547684 0.00487179 7.04017 -2.57608 0.108367 -1.00576 -2.65545 0.112387 -1.01005 -2.72684 0.116326 -1.00548 -2.80624 0.120553 -1.00558 -2.89465 0.125026 -1.00995 -2.97608 0.129358 -1.00546 -3.07354 0.134224 -1.01111 -3.17201 0.139173 -1.01386 -3.27155 0.145196 -1.01387 -3.38007 0.150538 -1.01671 -3.49761 0.156218 -1.02192 -3.61623 0.163013 -1.02359 -3.74383 0.16918 -1.02698 -3.74506 0.16895 -0.949384 -3.72627 0.168388 -0.862433 -3.71449 0.168105 -0.781547 -3.70972 0.168119 -0.706325 -3.71191 0.167454 -0.63632 -3.72217 0.168063 -0.571233 -3.74953 0.170226 -0.514638 -3.82099 0.173754 -0.477907 -3.68071 0.166546 -0.349429 -3.71303 0.168185 -0.297344 -3.72526 0.168417 -0.237457 -3.75659 0.170171 -0.184271 -3.814 0.17291 -0.140106 -3.87142 0.175728 -0.0943423 -4.0142 0.183202 -0.0731647 -4.22432 0.194909 -0.0666288 -4.59003 0.213575 -0.0942371 -9.07609 0.447583 -1.13481 -9.55966 0.472871 -1.08778 -10.5133 0.522802 -1.12396 -11.5384 0.576406 -1.14074 -13.0496 0.654359 -1.20688 -14.6254 0.736563 -1.23018 -16.6394 0.842126 -1.26003 -19.8782 1.0112 -1.36906 -24.0882 1.23015 -1.05011 -24.8572 1.27087 -0.688713 -24.7732 1.26631 -0.257137 -24.9112 1.27384 0.163159 -25.2422 1.29085 0.5846 -28.351 1.45266 1.0192 -22.6649 1.15617 1.40273 -21.5575 1.09894 1.75091 -21.621 1.10256 2.123 -20.6813 1.05307 2.42721 -20.0662 1.02091 2.72785 -20.7982 1.0589 3.15059 -21.1734 1.07947 3.55646 -21.2349 1.08242 3.9327 -24.6227 1.25905 4.84294 -21.3358 1.08708 4.69399 -24.1598 1.23447 5.62236 -21.1361 1.07743 5.40738 -25.5898 1.30986 6.81861 -19.9919 1.01761 5.88086 -17.762 0.900836 5.64477 -20.2417 1.03038 6.68349 -18.3918 0.933959 6.4914 -19.6043 0.997764 7.2305 -20.4838 1.04341 7.90596 -20.7356 1.05633 8.39127 -21.6757 1.10579 9.15658 -21.5211 1.09717 9.52171 -20.8271 1.06155 9.65691 -20.6734 1.05331 10.0108 -20.5761 1.04802 10.3916 -9.59768 0.475609 5.45152 -21.0108 1.071 11.4831 -22.2616 1.13652 12.6061 -21.4185 1.09236 12.6303 -21.3334 1.08797 13.0642 -4.49499 0.208586 3.50423 -4.4752 0.208026 3.58999 -4.23078 0.195472 3.52473 -4.26835 0.197277 3.64706 -4.08432 0.187619 3.61253 -4.26191 0.19639 3.84339 -4.21192 0.194629 3.90866 -4.19109 0.193325 3.99837 -4.13803 0.190684 4.0624 -4.15955 0.191773 4.19118 -4.04397 0.185206 4.20113 -4.11188 0.188923 4.37864 -4.17477 0.192104 4.55942 -4.09755 0.188196 4.60895 -4.12422 0.190322 4.76487 -4.1196 0.189972 4.89348 -4.01815 0.184329 4.91901 -3.87033 0.176733 4.88926 -3.87278 0.176654 5.03193 -3.74509 0.169748 5.02034 -3.69917 0.167853 5.10802 -3.69962 0.167316 5.25923 -3.51948 0.158655 5.16876 -3.78953 0.172381 5.71259 -3.57806 0.161446 5.57867 -3.5958 0.162494 5.78276 -3.28523 0.145718 5.47142 -3.51013 0.157657 6.02532 -3.38651 0.151645 6.01647 -3.15365 0.139089 5.80376 -2.88737 0.125274 5.50492 -2.94363 0.128181 5.81341 -2.77641 0.119838 5.68449 -2.66984 0.114481 5.66919 -2.5916 0.110476 5.71553 -2.35736 0.0975317 5.39241 -2.34794 0.0969443 5.59114 -2.30313 0.0948269 5.71608 -2.21071 0.0905074 5.71866 -2.48543 0.104002 6.78823 -2.02677 0.0805499 5.71859 -1.92615 0.0750341 5.68714 -1.81437 0.0697087 5.60559 -1.77774 0.0671517 5.79218 -1.69853 0.0639432 5.83317 -1.80981 0.0692731 6.70129 -1.46141 0.0511178 5.54932 -1.30238 0.0430383 5.15311 -1.22593 0.03832 5.1469 -1.15976 0.0348478 5.19844 -1.1204 0.0335328 5.44706 -1.0874 0.0312172 5.82454 -1.01548 0.0279233 5.95341 -0.923843 0.022872 5.90186 -0.827889 0.0180564 5.7489 -0.74016 0.0131215 5.66408 -0.663214 0.0098589 5.78746 -0.602263 0.0059937 7.16943 -2.65543 0.0492232 -2.01859 -2.88552 0.0536745 -1.89157 -2.61052 0.0483301 -1.00131 -2.68172 0.0492151 -0.997889 -2.777 0.0517601 -1.01252 -2.84928 0.0537934 -1.00486 -2.93852 0.0552689 -1.00798 -3.02778 0.0568675 -1.00861 -3.12612 0.0597436 -1.01287 -3.23243 0.0619883 -1.02014 -3.33274 0.0640322 -1.01856 -3.45009 0.0666384 -1.02532 -3.56045 0.0691093 -1.02312 -3.67885 0.0719901 -1.02309 -3.81628 0.0753862 -1.02991 -3.7394 0.07316 -0.905776 -3.74565 0.073334 -0.834135 -3.73387 0.0730456 -0.753348 -3.7281 0.0731155 -0.678223 -3.7564 0.0742213 -0.621582 -3.75759 0.0736168 -0.551574 -3.79291 0.075119 -0.4986 -3.71795 0.0726555 -0.397091 -3.72321 0.0735124 -0.333087 -3.74646 0.0739136 -0.27658 -3.76771 0.0744555 -0.219668 -3.79799 0.0753073 -0.16573 -3.83724 0.075492 -0.114318 -3.96072 0.078325 -0.0888873 -4.12332 0.0824433 -0.0707703 -4.39213 0.0879836 -0.0766077 -9.23944 0.198089 -1.09237 -9.97779 0.214555 -1.09484 -10.9929 0.236865 -1.12773 -12.1495 0.263131 -1.15119 -13.8518 0.302066 -1.22539 -15.5792 0.341262 -1.2435 -20.5561 0.453511 -1.27164 -23.4786 0.519411 -1.19712 -24.879 0.550787 -0.902234 -24.7982 0.549083 -0.469718 -25.3994 0.562717 -0.0702034 -28.6328 0.635701 0.282501 -26.3311 0.584413 0.792347 -23.4222 0.518377 1.21596 -23.3853 0.517377 1.61523 -21.8726 0.48387 1.94821 -22.8701 0.506463 2.38409 -20.451 0.450907 2.58459 -20.0427 0.441894 2.89593 -20.096 0.443088 3.24708 -21.5794 0.4768 3.79084 -22.0715 0.488466 4.24009 -21.1242 0.466689 4.46698 -21.1103 0.466794 4.83572 -20.9318 0.462241 5.17296 -23.764 0.526575 6.17586 -18.7425 0.412898 5.39436 -18.2084 0.400924 5.59419 -17.7888 0.391804 5.80889 -17.3379 0.381481 6.00182 -18.287 0.4032 6.62346 -19.8356 0.437803 7.48637 -22.8941 0.507355 8.94989 -19.8592 0.438505 8.25564 -26.5181 0.589456 11.2725 -22.4946 0.497889 10.1306 -21.2131 0.468785 10.026 -21.098 0.466589 10.407 -21.2822 0.47058 10.9332 -20.8285 0.460914 11.156 -21.0389 0.464845 11.7128 -20.963 0.463171 12.1318 -4.57853 0.0927017 3.31249 -4.48535 0.0903099 3.35293 -4.42739 0.0897096 3.41169 -4.32516 0.0873692 3.44218 -4.2571 0.085933 3.49203 -4.25439 0.0857361 3.58567 -4.24967 0.0856847 3.67982 -4.20976 0.0846072 3.7509 -4.18495 0.0841914 3.83348 -4.14304 0.0831905 3.90367 -4.15342 0.0832177 4.01775 -4.07735 0.0819695 4.06163 -4.0988 0.0820363 4.18996 -4.22594 0.0848527 4.42132 -4.16596 0.0836571 4.48583 -4.1764 0.0836481 4.61943 -4.12649 0.0825132 4.69739 -4.08161 0.0814011 4.78192 -4.1908 0.0844104 5.03572 -3.94758 0.0785441 4.90464 -4.13233 0.0830911 5.26102 -3.87899 0.0767257 5.1076 -3.70119 0.0727195 5.03291 -3.62413 0.0716993 5.08019 -3.50568 0.068311 5.06987 -3.27141 0.0636715 4.89363 -3.24263 0.0626319 4.99919 -3.38226 0.0662807 5.3634 -3.40193 0.066087 5.56503 -3.5155 0.0693678 5.93052 -3.47881 0.0684191 6.06867 -3.34123 0.0649181 6.03284 -2.92412 0.0553711 5.4751 -2.7673 0.0523933 5.36588 -2.75274 0.0514104 5.53022 -2.7302 0.0514991 5.68624 -2.65209 0.0495423 5.73358 -2.44563 0.0446921 5.48599 -2.33615 0.0422677 5.44543 -2.2914 0.0416663 5.56058 -2.19399 0.0387168 5.5443 -2.55116 0.046867 6.80836 -2.10053 0.0370035 5.79988 -1.94844 0.0336319 5.60775 -1.87635 0.0316131 5.66116 -1.78101 0.0301128 5.63619 -1.89684 0.0321221 6.42284 -1.79962 0.0306604 6.43673 -1.83873 0.0313898 7.06403 -1.34105 0.019768 5.15572 -1.26373 0.0176576 5.14038 -1.19769 0.0162138 5.19252 -1.1481 0.0156089 5.36227 -1.12738 0.0145121 5.79939 -1.04935 0.0131713 5.85921 -0.964136 0.0117398 5.86812 -0.871491 0.00873639 5.77582 -0.780829 0.00704615 5.65181 -0.698578 0.00570601 5.64598 -0.668768 0.00421015 7.63819 -0.547502 0.00187108 7.04012 -2.62954 -0.0133339 -2.03727 -2.95037 -0.0156811 -1.91658 -2.57973 -0.0132252 -1.00579 -2.65781 -0.0141397 -1.01004 -2.72995 -0.0142629 -1.00557 -2.81004 -0.0150914 -1.00562 -2.88321 -0.015073 -0.997063 -2.97928 -0.0162806 -1.00551 -3.06943 -0.0166822 -1.00494 -3.16759 -0.0167428 -1.00795 -3.26671 -0.0177179 -1.00801 -3.39182 -0.0189655 -1.02234 -3.49304 -0.0187641 -1.01636 -3.62019 -0.0197827 -1.02361 -3.74836 -0.0206747 -1.02706 -3.85157 -0.0211033 -1.01115 -3.76486 -0.0205045 -0.88249 -3.77105 -0.0213176 -0.810599 -3.76728 -0.0213193 -0.734482 -3.76152 -0.0212346 -0.659057 -3.77179 -0.0205814 -0.593071 -3.78995 -0.0216255 -0.531456 -3.85222 -0.021325 -0.490104 -3.74944 -0.0205177 -0.37677 -3.75464 -0.020638 -0.312317 -3.77684 -0.0211486 -0.255258 -3.79803 -0.021584 -0.197896 -3.83728 -0.0214092 -0.146684 -3.87547 -0.0221167 -0.0943199 -4.02879 -0.0224489 -0.0761264 -4.24808 -0.0244599 -0.0720743 -9.10669 -0.0560302 -1.13959 -9.5525 -0.0590974 -1.08332 -10.4678 -0.0646273 -1.11152 -11.5342 -0.0721241 -1.13686 -12.9191 -0.0807295 -1.18093 -14.6444 -0.0921004 -1.23017 -16.7012 -0.105754 -1.26552 -24.0996 -0.153657 -1.0483 -26.0172 -0.166218 -0.766659 -26.324 -0.168337 -0.335514 -26.6229 -0.169474 0.105743 -25.8953 -0.16543 0.574308 -23.5984 -0.150184 1.01596 -23.5847 -0.150388 1.41895 -23.1042 -0.14731 1.80514 -21.0592 -0.133914 2.09184 -23.9301 -0.151964 2.65473 -20.2621 -0.12864 2.7429 -20.2682 -0.128721 3.0918 -21.7271 -0.137351 3.62148 -21.3816 -0.135282 3.94961 -21.3467 -0.134989 4.31677 -21.3539 -0.135813 4.69233 -22.4844 -0.142335 5.28931 -17.6043 -0.111129 4.64827 -17.918 -0.112902 5.0342 -17.893 -0.11276 5.34974 -18.2108 -0.114624 5.75898 -18.0675 -0.113535 6.05077 -25.6629 -0.163184 8.71247 -19.7437 -0.125207 7.26781 -19.4855 -0.12307 7.92531 -20.733 -0.130704 8.78335 -20.6411 -0.130795 9.15408 -22.1607 -0.139879 10.2127 -20.8463 -0.131473 10.0761 -22.5697 -0.14314 11.3102 -21.2182 -0.133994 11.1231 -20.4593 -0.129083 11.1876 -20.6754 -0.130435 11.7459 -4.4157 -0.0246675 3.17491 -4.42096 -0.0253776 3.26792 -4.38016 -0.0245436 3.33602 -4.3644 -0.024467 3.41932 -4.27937 -0.0243713 3.45918 -4.31881 -0.0247208 3.58081 -4.19167 -0.0236233 3.58965 -4.3074 -0.0245894 3.77141 -4.23447 -0.023823 3.81928 -4.279 -0.0236323 3.95796 -4.24319 -0.0235999 4.03618 -4.12003 -0.0228378 4.04311 -4.07418 -0.0226394 4.11247 -4.3166 -0.023906 4.44214 -4.31392 -0.0247617 4.56295 -4.28723 -0.0241599 4.66371 -4.13796 -0.0231267 4.64436 -4.15748 -0.0229014 4.79371 -4.30159 -0.0242074 5.08384 -4.29001 -0.0239376 5.21646 -4.1377 -0.023004 5.19143 -3.92911 -0.0212994 5.09331 -3.91949 -0.0219357 5.23027 -3.60528 -0.0193146 4.98187 -3.37944 -0.0183494 4.82772 -3.1596 -0.017075 4.66692 -3.15204 -0.0162817 4.79478 -3.16958 -0.0169096 4.96492 -3.45287 -0.0186723 5.55629 -3.53699 -0.0191862 5.87018 -3.51849 -0.01896 6.03388 -3.43055 -0.0180867 6.08585 -2.91552 -0.014717 5.36627 -2.80629 -0.0141424 5.34599 -2.70209 -0.0135547 5.33209 -2.60897 -0.0128536 5.33393 -2.52892 -0.0126888 5.36105 -2.46904 -0.0125524 5.4323 -2.41832 -0.0116298 5.53048 -2.31307 -0.0108814 5.49836 -2.1916 -0.010583 5.41729 -2.09038 -0.00931591 5.38031 -2.00323 -0.00913022 5.37903 -1.89282 -0.00839631 5.29998 -1.79449 -0.00808903 5.24721 -1.70119 -0.00771449 5.20191 -1.66062 -0.00704024 5.3478 -1.70533 -0.00672216 5.85254 -1.77766 -0.00726867 6.55508 -1.38165 -0.00515398 5.16781 -1.30147 -0.0045356 5.14334 -1.23249 -0.00374322 5.17637 -1.18496 -0.00344746 5.34656 -1.12222 -0.00319723 5.45697 -1.09451 -0.00285734 5.87414 -1.00525 -0.00297762 5.84396 -0.923265 -0.00215493 5.88197 -0.820375 -0.00098724 5.63915 -0.740249 -0.00142352 5.65408 -0.663609 -0.000700008 5.79749 -0.601774 2.53405e-05 7.12948 -2.65373 -0.0780581 -2.0185 -2.95475 -0.0891355 -1.97646 -2.53206 -0.0730435 -0.99584 -2.603 -0.0762547 -0.994418 -2.68096 -0.0791287 -0.997861 -2.77588 -0.0825752 -1.01239 -2.84892 -0.0846049 -1.00484 -2.92985 -0.088332 -1.00165 -3.01086 -0.0909488 -0.996211 -3.10883 -0.0940791 -1.00067 -3.22372 -0.0986853 -1.01426 -3.32373 -0.101641 -1.01273 -3.43265 -0.10628 -1.01408 -3.5586 -0.110328 -1.02317 -3.67757 -0.114501 -1.02309 -3.79749 -0.119559 -1.01948 -3.88457 -0.122447 -0.99194 -3.78802 -0.119023 -0.858749 -3.80223 -0.119549 -0.791528 -3.78851 -0.118705 -0.710485 -3.80072 -0.11914 -0.643857 -3.81093 -0.119464 -0.577422 -3.8281 -0.120418 -0.515204 -3.7904 -0.118869 -0.428941 -3.76867 -0.117753 -0.352168 -3.7918 -0.119311 -0.294863 -3.80404 -0.119015 -0.233677 -3.81621 -0.119717 -0.172442 -3.87333 -0.121908 -0.126931 -3.95941 -0.125214 -0.0888513 -4.12141 -0.13109 -0.0707383 -4.39031 -0.140604 -0.0766346 -9.22632 -0.316572 -1.09003 -9.88618 -0.339655 -1.07544 -10.9007 -0.376564 -1.10982 -12.0751 -0.419839 -1.13847 -13.7184 -0.479217 -1.20395 -15.4646 -0.542727 -1.22732 -20.7466 -0.733687 -1.29406 -23.8567 -0.84635 -1.23421 -24.4306 -0.867827 -0.867935 -24.5289 -0.871244 -0.453962 -24.6112 -0.874529 -0.0365931 -24.7155 -0.878067 0.382255 -25.4316 -0.903592 0.799512 -25.5719 -0.908415 1.23632 -25.1934 -0.895377 1.66424 -24.31 -0.862631 2.05676 -20.4979 -0.724678 2.23789 -20.533 -0.72626 2.59179 -21.0191 -0.743778 2.99155 -20.1173 -0.71054 3.25049 -19.6193 -0.692531 3.53242 -21.4306 -0.758444 4.14515 -21.1458 -0.748059 4.4721 -19.6476 -0.694068 4.56509 -19.0835 -0.67355 4.79695 -19.5998 -0.692191 5.25114 -18.7236 -0.660616 5.72978 -22.6057 -0.801399 7.15103 -19.1611 -0.676584 6.54557 -19.7856 -0.69881 7.0996 -19.2124 -0.678302 7.27975 -18.8543 -0.664863 7.51859 -19.2528 -0.679509 8.03109 -19.2389 -0.679315 8.40162 -20.1871 -0.713135 9.17619 -20.9482 -0.740484 9.91416 -20.8083 -0.73601 10.2782 -4.62889 -0.149796 2.97491 -4.53108 -0.145889 3.01537 -24.2651 -0.860846 13.4004 -22.5704 -0.799911 13.0109 -4.37671 -0.140469 3.19918 -4.38103 -0.140132 3.29195 -4.32324 -0.137825 3.34887 -4.27341 -0.136792 3.41 -4.26373 -0.135864 3.49762 -4.32711 -0.138796 3.63675 -4.26432 -0.136295 3.69148 -4.35282 -0.139379 3.85809 -4.28704 -0.136702 3.91273 -4.16508 -0.132867 3.92241 -4.1063 -0.130484 3.97962 -4.17484 -0.132369 4.1461 -4.29148 -0.13669 4.36236 -4.28383 -0.136631 4.47534 -4.2511 -0.136041 4.56853 -4.31674 -0.137524 4.75973 -4.20884 -0.13386 4.78305 -4.12898 -0.13158 4.83279 -4.06125 -0.128383 4.89552 -4.35662 -0.139726 5.36935 -4.58492 -0.147474 5.79364 -4.03049 -0.127835 5.29298 -3.6376 -0.112899 4.95455 -3.50152 -0.108327 4.92152 -3.29619 -0.100538 4.78834 -3.12589 -0.0951392 4.69 -3.16254 -0.095748 4.88374 -3.73857 -0.116863 5.90569 -3.4388 -0.105733 5.62404 -3.13793 -0.0948258 5.31638 -3.17365 -0.0963302 5.55153 -2.89278 -0.0857932 5.24056 -3.01401 -0.0902097 5.64212 -2.87282 -0.085268 5.56996 -2.68128 -0.0787797 5.38699 -2.60042 -0.0754946 5.41537 -2.47725 -0.0712419 5.35124 -2.38933 -0.0676207 5.35761 -2.2933 -0.0645159 5.34373 -2.19526 -0.0608451 5.31862 -2.0992 -0.0574035 5.29131 -2.00719 -0.0538343 5.27148 -1.91716 -0.0504796 5.24974 -1.82406 -0.0475051 5.21663 -1.73401 -0.0438087 5.18156 -1.65803 -0.0416634 5.19294 -1.58716 -0.0389385 5.22217 -1.55076 -0.0371217 5.39612 -1.42008 -0.0324564 5.16972 -1.34102 -0.0303793 5.15579 -1.26706 -0.0277078 5.16002 -1.22982 -0.0260771 5.38975 -1.15796 -0.0236729 5.43153 -1.09845 -0.0216678 5.58118 -1.08023 -0.0210006 6.13754 -0.965498 -0.0159326 5.87808 -0.869098 -0.0126695 5.74585 -0.778739 -0.00986943 5.63183 -0.699911 -0.00641952 5.66599 -0.717305 -0.00714916 9.56753 -0.547259 -0.00161739 7.03018 -2.64178 -0.140675 -2.0618 -2.6948 -0.143995 -2.02382 -2.56734 -0.135509 -0.998884 -2.64617 -0.140487 -1.00323 -2.71006 -0.144796 -0.992098 -2.79686 -0.150385 -0.999067 -2.88567 -0.155972 -1.00354 -2.97444 -0.162433 -1.00548 -3.07123 -0.168557 -1.01108 -3.16208 -0.173886 -1.00787 -3.26084 -0.180857 -1.00794 -3.36963 -0.18758 -1.01098 -3.48632 -0.195895 -1.0163 -3.60509 -0.203163 -1.01817 -3.72483 -0.21131 -1.01641 -3.86155 -0.219819 -1.02144 -3.88765 -0.22222 -0.957301 -3.80825 -0.216353 -0.834849 -3.83036 -0.218572 -0.771899 -3.83461 -0.218258 -0.699852 -3.82785 -0.218078 -0.623725 -3.82811 -0.217571 -0.552664 -3.87316 -0.220799 -0.50232 -3.78866 -0.215438 -0.396233 -3.8118 -0.216971 -0.338428 -3.81601 -0.216992 -0.273173 -3.82819 -0.217673 -0.211538 -3.86826 -0.220525 -0.159681 -3.91629 -0.223954 -0.109747 -4.01123 -0.229878 -0.073195 -4.22182 -0.243275 -0.0666252 -9.49434 -0.589765 -1.0743 -10.3395 -0.644543 -1.08873 -11.471 -0.718909 -1.1292 -12.6953 -0.799728 -1.14628 -14.5152 -0.919064 -1.21451 -16.469 -1.04726 -1.23777 -24.2679 -1.55802 -1.06737 -25.8535 -1.66254 -0.759021 -27.9531 -1.79973 -0.422791 -27.5845 -1.776 0.0709212 -25.5115 -1.63953 0.579806 -24.6866 -1.58604 1.0169 -24.4735 -1.57139 1.436 -23.7442 -1.52383 1.82964 -23.9751 -1.53898 2.24938 -24.2988 -1.55998 2.68436 -20.7067 -1.32493 2.78595 -20.8217 -1.33259 3.15487 -19.7317 -1.26057 3.38012 -19.5781 -1.2504 3.70076 -19.4294 -1.24069 4.01829 -18.48 -1.1788 4.19031 -22.7905 -1.46136 5.3583 -22.6031 -1.44889 5.72449 -18.9305 -1.20813 5.27792 -20.6922 -1.32379 6.06052 -18.0767 -1.15199 5.73308 -17.6753 -1.12606 5.94864 -20.553 -1.31492 7.1596 -20.3357 -1.30007 7.86047 -18.7694 -1.19744 7.67865 -19.3211 -1.23418 8.25567 -19.4792 -1.24371 8.70011 -19.3235 -1.23431 9.02301 -20.6668 -1.32231 10.0151 -21.4197 -1.37121 10.7938 -4.53379 -0.264377 2.97574 -22.3541 -1.43305 12.1787 -4.4444 -0.258509 3.10627 -4.38974 -0.254286 3.16517 -4.43796 -0.258363 3.28302 -4.44925 -0.259115 3.38251 -4.31362 -0.249409 3.39278 -4.27989 -0.247809 3.4647 -4.3192 -0.250153 3.58642 -4.34752 -0.252014 3.70448 -4.17079 -0.240685 3.67728 -4.21116 -0.24268 3.80729 -4.17745 -0.240838 3.8841 -4.14175 -0.238891 3.96062 -4.09708 -0.235738 4.03033 -4.25453 -0.246049 4.27657 -4.12282 -0.237176 4.27484 -4.23331 -0.243958 4.49466 -4.37984 -0.253617 4.76096 -4.2361 -0.244452 4.75049 -4.32962 -0.250691 4.9808 -4.06972 -0.233851 4.8423 -3.98804 -0.228588 4.88931 -3.82823 -0.218176 4.84402 -3.76757 -0.214272 4.90938 -3.71193 -0.210341 4.98142 -3.56813 -0.200586 4.94238 -3.43932 -0.192129 4.91562 -3.35258 -0.186576 4.94212 -3.32897 -0.185456 5.05705 -3.3365 -0.185736 5.22202 -3.6529 -0.206493 5.8751 -3.11388 -0.17138 5.19996 -3.00411 -0.16349 5.18493 -2.96048 -0.16114 5.2801 -2.99719 -0.163283 5.52378 -3.05403 -0.166896 5.82288 -2.74743 -0.146835 5.43009 -2.83142 -0.152511 5.80141 -2.86128 -0.1542 6.08626 -2.48109 -0.129819 5.46894 -2.40643 -0.124169 5.51208 -2.35782 -0.121937 5.619 -2.20163 -0.111643 5.45465 -2.08263 -0.103598 5.37099 -1.96761 -0.0959334 5.28451 -1.91802 -0.0929246 5.3857 -1.80298 -0.0849425 5.28539 -1.70905 -0.0785012 5.24029 -1.61705 -0.0732762 5.19325 -1.53925 -0.0676036 5.19265 -1.45433 -0.0620135 5.16156 -1.37845 -0.0576016 5.1581 -1.30567 -0.0524744 5.17282 -1.23999 -0.0478871 5.22566 -1.2436 -0.0480224 5.73187 -1.12503 -0.0410111 5.48665 -1.0831 -0.0382114 5.79475 -1.00549 -0.0330976 5.86386 -0.92587 -0.0274128 5.92185 -0.822285 -0.0211802 5.67918 -0.740525 -0.0149948 5.68408 -0.664065 -0.0107662 5.81751 -0.601223 -0.00644062 7.07944 -2.6808 -0.207503 -2.06735 -2.5238 -0.192908 -0.995784 -2.6015 -0.199883 -1.00133 -2.67321 -0.207054 -0.997911 -2.75988 -0.214692 -1.00588 -2.82467 -0.220917 -0.991854 -2.92026 -0.230184 -1.0016 -3.01685 -0.239378 -1.00865 -3.09857 -0.246927 -1.00067 -3.22099 -0.259301 -1.02014 -3.31269 -0.267484 -1.01279 -3.41329 -0.277355 -1.00842 -3.53876 -0.289403 -1.01761 -3.6573 -0.30058 -1.01769 -3.78482 -0.312384 -1.0195 -3.92324 -0.325904 -1.02239 -3.87973 -0.322089 -0.917783 -3.83326 -0.317199 -0.815311 -3.85537 -0.319398 -0.751961 -3.84962 -0.319239 -0.675038 -3.84292 -0.318058 -0.598861 -3.86999 -0.320781 -0.540021 -3.92394 -0.325697 -0.492653 -3.81075 -0.315021 -0.375037 -3.83383 -0.317532 -0.316783 -3.83804 -0.317533 -0.251128 -3.86909 -0.320665 -0.195697 -3.92703 -0.325863 -0.149141 -3.95609 -0.328786 -0.0919052 -4.11748 -0.344646 -0.0735963 -4.36554 -0.367673 -0.0739916 -9.1734 -0.826707 -1.08537 -9.82093 -0.888073 -1.06891 -10.8119 -0.982573 -1.09991 -11.9235 -1.08875 -1.11845 -13.5201 -1.24037 -1.1793 -15.289 -1.40891 -1.20964 -20.9355 -1.94726 -1.32447 -23.8715 -2.22649 -0.831406 -24.0192 -2.24047 -0.428631 -24.0404 -2.24331 -0.016013 -26.5826 -2.48488 0.332045 -28.4417 -2.66245 0.774477 -23.9517 -2.2346 1.22193 -24.3326 -2.27075 1.64358 -23.1444 -2.15775 2.00899 -20.917 -1.9451 2.26877 -23.3133 -2.17381 2.81964 -20.5536 -1.91116 2.95398 -20.9612 -1.94989 3.35647 -21.0561 -1.95896 3.7332 -19.4398 -1.80502 3.85713 -21.2527 -1.97769 4.50356 -19.4501 -1.80561 4.88697 -22.2661 -2.07363 5.86332 -22.2265 -2.06978 6.25596 -20.0605 -1.86362 6.09636 -21.1773 -1.97052 6.77608 -19.0319 -1.76597 6.52852 -22.3783 -2.0842 7.94642 -19.2156 -1.7836 7.30521 -18.6245 -1.72707 7.46177 -19.8144 -1.84004 8.26969 -19.0277 -1.76563 8.34657 -19.7341 -1.83305 9.01907 -21.1617 -1.96875 10.042 -20.9836 -1.9515 10.3945 -4.58628 -0.389602 2.96197 -4.48882 -0.379718 3.00204 -21.8428 -2.03403 12.1799 -4.41657 -0.372479 3.1406 -4.32703 -0.36414 3.17938 -4.2827 -0.359834 3.33324 -4.26699 -0.358815 3.41538 -4.34916 -0.366425 3.56393 -4.2217 -0.354197 3.57433 -4.26593 -0.358492 3.70313 -4.34611 -0.366372 3.86402 -4.18571 -0.350572 3.84571 -4.15107 -0.347678 3.92237 -4.11542 -0.344739 3.99874 -4.19069 -0.351701 4.17214 -4.27698 -0.359498 4.36232 -4.27636 -0.359522 4.48218 -4.32371 -0.364011 4.65121 -4.36609 -0.36807 4.82286 -4.30654 -0.362781 4.89726 -4.19009 -0.350977 4.91252 -4.06055 -0.339249 4.91034 -4.02505 -0.335181 5.00958 -3.96147 -0.329927 5.07839 -3.83998 -0.317656 5.07674 -3.90444 -0.32415 5.30694 -3.73188 -0.308075 5.23903 -3.62835 -0.298029 5.25479 -3.7329 -0.308157 5.56153 -3.85658 -0.319157 5.91434 -3.21056 -0.258351 5.12155 -3.11201 -0.248152 5.12626 -3.10749 -0.24815 5.28228 -3.11805 -0.249294 5.47391 -3.27992 -0.264704 5.94585 -3.22246 -0.259237 6.04656 -2.81725 -0.220729 5.48127 -2.92517 -0.230648 5.8972 -2.8617 -0.224497 5.9842 -2.52338 -0.192526 5.46957 -2.42573 -0.183165 5.4585 -2.37425 -0.178204 5.55629 -2.29465 -0.170795 5.58846 -2.14175 -0.155767 5.42246 -2.69433 -0.209041 7.24212 -2.50747 -0.190628 7.04242 -1.93304 -0.136379 5.57908 -1.88668 -0.13166 5.71861 -1.70429 -0.114602 5.37597 -1.57319 -0.10221 5.18343 -1.49045 -0.0942291 5.16272 -1.41376 -0.0867265 5.15992 -1.34005 -0.0799883 5.16555 -1.2745 -0.0733726 5.21899 -1.40696 -0.0861608 6.47486 -1.16583 -0.0628338 5.50079 -1.09228 -0.0558725 5.55147 -1.18066 -0.0643814 7.04168 -0.962804 -0.0433467 5.86814 -0.875005 -0.0356454 5.83566 -0.779831 -0.0265018 5.66178 -0.701371 -0.0190775 5.73599 -0.717642 -0.0202277 9.60752 -0.547139 -0.00412543 7.04011 -2.7177 -0.276184 -2.0724 -2.54908 -0.255426 -0.991855 -2.62661 -0.265353 -0.996449 -2.70515 -0.275231 -0.99885 -2.7847 -0.285062 -0.999056 -2.86426 -0.294784 -0.997065 -2.96067 -0.307043 -1.00547 -3.04126 -0.316595 -0.998784 -3.1397 -0.328714 -1.0019 -3.2381 -0.341687 -1.00207 -3.35341 -0.356111 -1.01088 -3.46179 -0.369669 -1.01068 -3.57914 -0.383879 -1.0127 -3.7064 -0.399775 -1.01641 -3.82573 -0.414743 -1.0111 -3.97188 -0.432903 -1.01721 -3.87688 -0.420507 -0.883274 -3.86517 -0.419681 -0.80014 -3.87733 -0.421019 -0.731565 -3.87164 -0.419849 -0.654392 -3.87284 -0.420345 -0.582186 -3.89986 -0.42403 -0.522597 -3.91598 -0.425837 -0.458629 -3.84865 -0.417915 -0.360883 -3.86277 -0.419665 -0.298207 -3.87489 -0.421289 -0.235424 -3.90594 -0.424377 -0.179094 -3.9538 -0.430763 -0.128312 -4.02951 -0.440197 -0.0848602 -4.21946 -0.464073 -0.0720392 -9.40573 -1.11057 -1.06539 -10.1286 -1.20089 -1.05548 -11.2541 -1.34123 -1.09876 -12.4621 -1.49234 -1.11689 -14.3103 -1.72317 -1.1943 -16.1637 -1.95413 -1.20727 -21.4316 -2.61111 -1.20237 -24.1655 -2.95222 -1.06996 -24.3368 -2.97344 -0.663067 -24.5698 -3.00231 -0.254377 -25.8377 -3.1613 0.126008 -25.8491 -3.16189 0.571818 -25.3364 -3.09875 1.01742 -22.5744 -2.75423 1.40375 -22.7228 -2.77271 1.79763 -22.6952 -2.7687 2.18788 -23.513 -2.87095 2.63793 -21.6623 -2.63978 2.88075 -21.4686 -2.61544 3.23589 -27.1087 -3.31993 4.31145 -25.25 -3.08781 4.52303 -24.3123 -2.97038 4.81789 -22.2493 -2.71325 4.88062 -25.6751 -3.14087 5.94989 -27.187 -3.32953 6.73613 -19.6978 -2.39489 5.48091 -20.0124 -2.43433 5.91735 -19.924 -2.423 6.25986 -18.5905 -2.25711 6.24149 -20.4986 -2.49537 7.17711 -20.1813 -2.45514 7.45984 -19.0816 -2.31837 7.46248 -19.8244 -2.41061 8.10354 -19.2263 -2.33665 8.25927 -18.8123 -2.28506 8.47124 -20.5699 -2.50353 9.60217 -22.9281 -2.7981 11.0823 -22.5443 -2.75019 11.3778 -21.4603 -2.61534 11.3207 -21.5523 -2.62675 11.8286 -21.6066 -2.63325 12.3289 -4.46941 -0.495015 3.50426 -4.38401 -0.484752 3.54643 -4.26476 -0.469657 3.56394 -4.24413 -0.467289 3.64705 -4.39099 -0.484949 3.85367 -4.35643 -0.480885 3.93379 -4.21126 -0.462415 3.92716 -4.22949 -0.465498 4.04875 -4.17605 -0.458029 4.11389 -4.12155 -0.451547 4.17809 -4.17673 -0.45878 4.34181 -4.44442 -0.491605 4.71303 -4.15158 -0.45547 4.55947 -4.29265 -0.472698 4.82828 -3.89501 -0.423443 4.54896 -4.02911 -0.44012 4.82039 -4.02255 -0.439362 4.94875 -4.1098 -0.450629 5.19137 -3.60926 -0.387626 4.74069 -3.93114 -0.42756 5.27694 -3.64309 -0.39182 5.06069 -3.52971 -0.378014 5.0594 -3.34844 -0.355035 4.95836 -3.30198 -0.349141 5.04066 -3.34842 -0.354917 5.26343 -3.54378 -0.379519 5.73242 -3.34647 -0.355189 5.59867 -3.60296 -0.387242 6.21403 -3.19968 -0.337182 5.72204 -3.0213 -0.314728 5.59378 -2.91392 -0.300682 5.58444 -3.00958 -0.313185 5.97384 -2.88418 -0.297446 5.93629 -2.50049 -0.249045 5.33383 -2.42502 -0.23976 5.36838 -2.36457 -0.232629 5.43839 -2.34324 -0.229848 5.6097 -2.25279 -0.218183 5.61338 -2.61672 -0.263733 6.87484 -2.35585 -0.231088 6.44771 -2.23435 -0.216389 6.39397 -1.96714 -0.18316 5.84981 -1.99734 -0.186742 6.27863 -1.66948 -0.145648 5.41536 -1.52651 -0.127461 5.16354 -1.44994 -0.11792 5.16154 -1.37536 -0.109089 5.16787 -1.30688 -0.100237 5.2022 -1.5614 -0.132773 7.09707 -1.32315 -0.102551 6.26522 -1.12896 -0.0779099 5.53611 -1.05965 -0.0692591 5.62592 -1.00579 -0.0627298 5.89366 -0.919241 -0.0520654 5.88195 -0.826376 -0.040535 5.75891 -0.740678 -0.0300606 5.70405 -0.722773 -0.0277021 7.58647 -0.599738 -0.0128528 7.04953 -2.75236 -0.348713 -2.07685 -2.50961 -0.311418 -0.995858 -2.58601 -0.323328 -1.00135 -2.66443 -0.335249 -1.00465 -2.72796 -0.345511 -0.99262 -2.81534 -0.358095 -0.998346 -2.90268 -0.371557 -1.00163 -2.99097 -0.385959 -1.00246 -3.07933 -0.399236 -1.00075 -3.1776 -0.414282 -1.00242 -3.28377 -0.430951 -1.00696 -3.39196 -0.447589 -1.0084 -3.50806 -0.46582 -1.01213 -3.63406 -0.485746 -1.01773 -3.7532 -0.503804 -1.01427 -3.88915 -0.525204 -1.01726 -4.00138 -0.542228 -1.00139 -3.9045 -0.527727 -0.867743 -3.90081 -0.526594 -0.788879 -3.90502 -0.527198 -0.715184 -3.90722 -0.5277 -0.641882 -3.90843 -0.528162 -0.568977 -3.94335 -0.533486 -0.51256 -3.87815 -0.523607 -0.413223 -3.87441 -0.522868 -0.342349 -3.89644 -0.526241 -0.282544 -3.90956 -0.527891 -0.219066 -3.95836 -0.535329 -0.168137 -3.99621 -0.54189 -0.112879 -4.10949 -0.559099 -0.0792884 -4.35664 -0.597101 -0.07934 -9.10068 -1.33276 -1.08308 -9.71413 -1.42786 -1.06035 -10.6589 -1.57437 -1.08399 -11.83 -1.75607 -1.1167 -13.1609 -1.96174 -1.13489 -15.1606 -2.27167 -1.20674 -16.1863 -2.43056 -1.07858 -25.4052 -3.85949 -0.965974 -24.2416 -3.67944 -0.452738 -24.233 -3.67806 -0.0319334 -26.1249 -3.97151 0.338917 -26.429 -4.01866 0.78912 -27.9203 -4.24977 1.26129 -27.7442 -4.22231 1.74102 -22.159 -3.35689 1.9722 -22.4639 -3.40444 2.37496 -21.7573 -3.29505 2.70804 -21.3902 -3.2378 3.0504 -21.9603 -3.32664 3.48971 -24.4905 -3.71834 4.2133 -24.8127 -3.76805 4.69446 -20.7306 -3.13589 4.44057 -29.4016 -4.47999 6.44159 -19.999 -3.02234 5.02891 -23.7754 -3.60757 6.23895 -19.8383 -2.9977 5.71283 -20.1564 -3.04689 6.15904 -20.3304 -3.07357 6.5804 -20.9614 -3.1717 7.14905 -20.1172 -3.04025 7.27433 -19.9962 -3.02194 7.6167 -19.0127 -2.86966 7.649 -21.3114 -3.22564 8.89069 -21.5482 -3.2624 9.40748 -20.67 -3.12694 9.4714 -23.5646 -3.57554 11.1682 -23.8086 -3.61357 11.7692 -24.7606 -3.76068 12.731 -21.5751 -3.26682 11.652 -21.2396 -3.21499 11.944 -22.4282 -3.39942 13.0682 -4.42259 -0.608083 3.53365 -4.34532 -0.596073 3.58049 -4.30088 -0.58903 3.648 -4.46336 -0.614093 3.86591 -4.34234 -0.594959 3.88183 -4.26802 -0.584013 3.93101 -4.18579 -0.57098 3.97222 -4.30157 -0.588862 4.17694 -4.09589 -0.55752 4.11359 -4.09427 -0.556994 4.22311 -3.97914 -0.539569 4.23197 -4.38872 -0.602219 4.74066 -4.31641 -0.5918 4.80187 -3.86978 -0.521835 4.47607 -3.82332 -0.515373 4.54963 -3.56776 -0.475581 4.39385 -3.62691 -0.484824 4.58248 -3.91025 -0.528955 5.04798 -4.0851 -0.555689 5.40876 -3.60927 -0.481927 4.96241 -3.53997 -0.471028 5.01677 -3.42378 -0.453535 5.00551 -3.37744 -0.445579 5.08911 -3.50155 -0.465324 5.42793 -3.27273 -0.429417 5.24665 -3.23035 -0.422942 5.34561 -3.22193 -0.421578 5.50409 -3.18453 -0.416542 5.62052 -3.0454 -0.394961 5.56274 -3.15483 -0.411983 5.9587 -3.11461 -0.404862 6.09346 -2.94747 -0.379451 5.9778 -2.44856 -0.30246 5.14455 -2.43422 -0.299603 5.3057 -2.2619 -0.272846 5.1099 -2.14154 -0.25398 5.0203 -2.27427 -0.274805 5.56989 -2.38215 -0.291767 6.10642 -2.4181 -0.297584 6.49727 -2.2668 -0.274224 6.35958 -2.17159 -0.259411 6.38046 -2.08946 -0.246103 6.44749 -1.95606 -0.225821 6.33017 -1.56538 -0.164929 5.18347 -1.48089 -0.152311 5.15303 -1.40949 -0.141149 5.16974 -1.34313 -0.130899 5.2146 -1.64344 -0.177068 7.27426 -1.36127 -0.133286 6.23807 -1.22941 -0.112782 5.96563 -1.09322 -0.0920758 5.59109 -1.02919 -0.0818126 5.73996 -0.962171 -0.0719166 5.89799 -0.874797 -0.0577261 5.8755 -0.777865 -0.0429364 5.67182 -0.697461 -0.0303451 5.66598 -0.715796 -0.0341591 9.60752 -0.546958 -0.00712122 7.04016 -2.46833 -0.364269 -0.999404 -2.53078 -0.375693 -0.991917 -2.60706 -0.389552 -0.99641 -2.6853 -0.40443 -0.998862 -2.76355 -0.419195 -0.999018 -2.84281 -0.433917 -0.997078 -2.93003 -0.449324 -0.99926 -3.01821 -0.465661 -0.998798 -3.11529 -0.483716 -1.00191 -3.21338 -0.501689 -1.00213 -3.31938 -0.521285 -1.00522 -3.42734 -0.541841 -1.00507 -3.54326 -0.562994 -1.00725 -3.66904 -0.586834 -1.01116 -3.7959 -0.609546 -1.01122 -3.92372 -0.633123 -1.00734 -4.01787 -0.651498 -0.980082 -3.91234 -0.631257 -0.842359 -3.93434 -0.635351 -0.776912 -3.93855 -0.63592 -0.702518 -3.93086 -0.63458 -0.624341 -3.93107 -0.634961 -0.551033 -3.96694 -0.641303 -0.493771 -3.90085 -0.629375 -0.394629 -3.91492 -0.632048 -0.330405 -3.91909 -0.632952 -0.262802 -3.94012 -0.636211 -0.201896 -4.01652 -0.650735 -0.159099 -4.05432 -0.658224 -0.102393 -4.21389 -0.687828 -0.0802912 -9.27644 -1.6248 -1.05414 -10.0126 -1.7613 -1.04935 -11.0795 -1.95885 -1.08364 -12.2465 -2.17449 -1.09793 -14.0385 -2.50604 -1.17103 -15.5831 -2.79263 -1.145 -17.0913 -3.07209 -1.05993 -25.195 -4.5726 -1.17981 -26.2979 -4.77662 -0.816408 -27.7585 -5.04644 -0.433748 -27.5727 -5.01281 0.0575461 -27.7615 -5.04761 0.535186 -27.2736 -4.957 1.01873 -27.3286 -4.96774 1.4951 -22.3927 -4.05396 1.79298 -23.0341 -4.17194 2.21696 -25.7267 -4.67113 2.81179 -21.1953 -3.8315 2.85612 -21.689 -3.92351 3.28003 -19.9092 -3.59352 3.43764 -20.0788 -3.62525 3.81252 -20.4259 -3.68896 4.22402 -22.4493 -4.06387 4.95202 -21.2966 -3.85116 5.12656 -19.655 -3.54697 5.15503 -19.5045 -3.5189 5.47637 -20.1114 -3.63145 5.98771 -20.1939 -3.64694 6.38175 -21.0439 -3.80364 7.0067 -23.2309 -4.20912 8.08542 -20.7786 -3.75533 7.71683 -20.6877 -3.73853 8.08552 -20.7475 -3.74908 8.51119 -21.1386 -3.82196 9.07417 -22.7559 -4.12129 10.1634 -21.4826 -3.88524 10.0757 -22.1765 -4.01386 10.8337 -21.1321 -3.82094 10.8023 -21.2338 -3.83931 11.303 -21.4922 -3.88759 11.8968 -21.8917 -3.96166 12.5873 -5.60109 -0.944383 4.37509 -5.61639 -0.947355 4.51552 -4.72616 -0.78207 4.01444 -4.40276 -0.722628 3.88905 -4.38424 -0.718901 3.9819 -4.53357 -0.746644 4.21063 -4.30247 -0.704249 4.13697 -4.16473 -0.679065 4.13318 -4.02902 -0.653193 4.12553 -4.06311 -0.660201 4.26814 -4.20063 -0.68532 4.51513 -4.4505 -0.731125 4.88611 -4.28595 -0.700586 4.85658 -4.21879 -0.6882 4.92327 -3.64162 -0.581438 4.43246 -3.54254 -0.563889 4.44312 -3.52206 -0.559746 4.54197 -3.77011 -0.605583 4.97062 -3.98644 -0.645161 5.38575 -4.0615 -0.659923 5.64413 -3.54967 -0.564616 5.12335 -3.3342 -0.524893 4.97454 -3.37847 -0.533 5.18813 -3.23963 -0.506993 5.13904 -3.12065 -0.485123 5.11157 -3.28843 -0.516711 5.54773 -3.2004 -0.49979 5.57937 -3.20991 -0.502301 5.78259 -3.21257 -0.502306 5.98753 -3.08961 -0.479988 5.96426 -2.58083 -0.385776 5.16276 -2.48767 -0.368544 5.15408 -2.38254 -0.34903 5.11622 -2.24848 -0.323496 5.00285 -2.16725 -0.308422 5.00561 -2.58034 -0.384893 6.24956 -2.32839 -0.339074 5.85617 -2.60415 -0.389428 6.89363 -2.33622 -0.339705 6.43827 -2.24219 -0.322416 6.47004 -2.25727 -0.325828 6.8637 -2.02106 -0.281791 6.41323 -1.67434 -0.217287 5.47333 -1.51683 -0.188061 5.16358 -1.44256 -0.174165 5.17127 -1.37127 -0.161034 5.18738 -1.49745 -0.184405 6.24285 -1.43658 -0.173571 6.42722 -1.30509 -0.149028 6.19614 -1.13384 -0.117394 5.61542 -1.05665 -0.103195 5.64583 -1.00198 -0.0925915 5.89365 -0.916731 -0.0774971 5.89193 -0.82011 -0.0591911 5.71901 -0.736711 -0.0438429 5.6641 -0.719927 -0.0405596 7.56649 -0.599375 -0.0188493 7.04953 -2.43206 -0.416755 -1.00971 -2.4875 -0.428443 -0.995856 -2.55671 -0.443587 -0.994435 -2.62594 -0.458637 -0.991116 -2.70406 -0.475465 -0.992571 -2.7822 -0.492189 -0.991928 -2.86923 -0.510656 -0.995359 -2.94833 -0.528206 -0.989975 -3.05216 -0.550059 -1.00075 -3.14018 -0.569205 -0.996446 -3.24593 -0.592877 -1.00114 -3.35176 -0.6154 -1.00278 -3.46743 -0.640635 -1.00666 -3.59202 -0.667504 -1.01241 -3.70873 -0.692439 -1.009 -3.8442 -0.721849 -1.01229 -3.97968 -0.751047 -1.01128 -4.00563 -0.756292 -0.944 -3.95158 -0.744601 -0.835008 -3.9469 -0.743368 -0.755341 -3.96785 -0.748365 -0.689143 -3.96017 -0.746994 -0.610366 -3.96928 -0.749084 -0.540433 -4.01299 -0.758042 -0.485894 -3.94703 -0.74409 -0.386251 -3.9512 -0.74494 -0.317551 -3.97318 -0.749211 -0.255699 -3.98526 -0.751709 -0.19037 -4.05165 -0.7664 -0.142897 -4.0983 -0.77651 -0.0878187 -4.3238 -0.82495 -0.0820154 -8.96954 -1.82791 -1.07377 -9.5659 -1.95701 -1.04955 -10.3472 -2.12522 -1.04237 -11.5436 -2.3842 -1.08584 -12.8212 -2.65971 -1.10047 -14.8957 -3.10746 -1.19061 -16.0837 -3.36368 -1.08778 -26.0708 -5.52033 -1.04074 -27.2043 -5.76508 -0.652096 -28.332 -6.00849 -0.223527 -29.4519 -6.25047 0.244767 -29.2064 -6.19679 0.763877 -30.282 -6.42936 1.28675 -26.2852 -5.56614 1.70888 -25.1175 -5.31483 2.117 -32.7726 -6.96701 3.04205 -25.4151 -5.37902 3.02375 -21.242 -4.47828 3.05804 -20.0768 -4.22655 3.29602 -20.3252 -4.28043 3.68452 -24.4432 -5.16889 4.67803 -20.2801 -4.27019 4.40068 -22.8994 -4.83589 5.26366 -23.7814 -5.02589 5.86293 -19.7066 -4.14623 5.3704 -20.351 -4.28568 5.89064 -20.6996 -4.36066 6.35976 -20.5959 -4.33865 6.71696 -20.0833 -4.22792 6.94965 -20.3983 -4.29609 7.43407 -21.2866 -4.4876 8.13168 -20.5998 -4.33956 8.29773 -21.3318 -4.49805 8.98527 -24.1937 -5.11588 10.5675 -24.5498 -5.19264 11.2115 -25.3485 -5.3655 12.0747 -22.4534 -4.73992 11.2541 -21.8696 -4.61385 11.4462 -22.1771 -4.68035 12.0764 -5.60127 -1.10152 3.95832 -5.46592 -1.07231 3.99816 -5.47225 -1.07351 4.12304 -5.58362 -1.09758 4.31898 -5.59096 -1.09936 4.45339 -5.49921 -1.07942 4.52115 -4.84943 -0.938783 4.17971 -4.88943 -0.947852 4.32839 -4.83928 -0.936637 4.41235 -4.40639 -0.843598 4.18406 -4.23823 -0.806658 4.15784 -4.53305 -0.87119 4.52956 -4.46506 -0.855836 4.5944 -4.46047 -0.855396 4.71876 -4.42421 -0.847344 4.81651 -4.36609 -0.835014 4.89306 -4.33976 -0.8289 5.00425 -4.33821 -0.828841 5.14483 -3.63308 -0.676644 4.50449 -3.56001 -0.661193 4.54493 -4.14016 -0.78575 5.36751 -4.02153 -0.760019 5.37778 -3.47791 -0.642716 4.83709 -3.37603 -0.62127 4.84207 -3.3457 -0.614513 4.94114 -3.66899 -0.68486 5.55337 -3.23139 -0.590002 5.0734 -3.12356 -0.566947 5.06312 -3.03863 -0.547739 5.08402 -3.01922 -0.544118 5.21402 -3.30415 -0.605513 5.87901 -3.22021 -0.587956 5.92843 -3.1453 -0.571158 5.99374 -2.59968 -0.453481 5.13525 -2.52859 -0.438328 5.17209 -2.4366 -0.4182 5.16255 -2.3605 -0.402335 5.18747 -2.3163 -0.392846 5.28429 -2.75453 -0.48722 6.58204 -2.36957 -0.404184 5.86764 -2.2657 -0.381025 5.84411 -2.24156 -0.376619 6.04469 -2.04684 -0.333711 5.74301 -2.05373 -0.335621 6.05604 -2.00875 -0.326414 6.22698 -1.70074 -0.259483 5.44351 -1.55159 -0.226771 5.17369 -1.47744 -0.210837 5.18217 -1.40429 -0.195033 5.18925 -1.3522 -0.184238 5.30278 -1.47334 -0.210291 6.39907 -1.29568 -0.17256 5.89288 -1.19249 -0.149472 5.76783 -1.09316 -0.128723 5.64076 -1.03144 -0.114599 5.80955 -0.957543 -0.0992263 5.90797 -0.86935 -0.0804519 5.85563 -0.772717 -0.0591498 5.62188 -0.693614 -0.0421286 5.62604 -0.713012 -0.0465239 9.59753 -0.546776 -0.0101219 7.04011 -2.44334 -0.479113 -0.999392 -2.51149 -0.495243 -0.998917 -2.57371 -0.510576 -0.989633 -2.65064 -0.530394 -0.992135 -2.72765 -0.549105 -0.992488 -2.80567 -0.567774 -0.990747 -2.89942 -0.590909 -0.999196 -2.98723 -0.613247 -0.998836 -3.07512 -0.63446 -0.995929 -3.17874 -0.660084 -1.00211 -3.27649 -0.683915 -0.999538 -3.38208 -0.710357 -0.999587 -3.49659 -0.738448 -1.00181 -3.62094 -0.769231 -1.00587 -3.74632 -0.799883 -1.00603 -3.88055 -0.833131 -1.00732 -4.03254 -0.87073 -1.01401 -3.98056 -0.858074 -0.90328 -3.97788 -0.856898 -0.822322 -3.99094 -0.860148 -0.750754 -3.9931 -0.861529 -0.675006 -4.00322 -0.863616 -0.603777 -3.9946 -0.861183 -0.524947 -4.0382 -0.87209 -0.46941 -3.98026 -0.857797 -0.373338 -3.99428 -0.861374 -0.307167 -4.0063 -0.864824 -0.240889 -4.02729 -0.868967 -0.177637 -4.08366 -0.883832 -0.125688 -4.18645 -0.909124 -0.0858262 -4.49541 -0.984633 -0.0994277 -9.10909 -2.12257 -1.04077 -9.85536 -2.30609 -1.04113 -10.8512 -2.55197 -1.06468 -12.0702 -2.85268 -1.09272 -13.6958 -3.25329 -1.14307 -15.6047 -3.72429 -1.17557 -16.9505 -4.05604 -1.06859 -27.3875 -6.62989 -0.917445 -28.2497 -6.8417 -0.478284 -31.0938 -7.54331 -0.0788594 -28.2736 -6.84768 0.520195 -28.7331 -6.96194 1.01991 -29.1365 -7.061 1.53504 -30.84 -7.48125 2.11265 -30.7973 -7.47068 2.65676 -24.9343 -6.02526 2.77715 -25.2201 -6.09549 3.24512 -20.3692 -4.89969 3.16522 -21.1199 -5.0848 3.62257 -24.6585 -5.95735 4.51445 -19.5609 -4.69993 4.12334 -19.8109 -4.76146 4.52132 -22.1884 -5.34795 5.35809 -20.0028 -4.80935 5.28424 -20.4386 -4.91655 5.75602 -20.8161 -5.00996 6.23258 -20.4153 -4.91071 6.5113 -20.5143 -4.93517 6.92651 -20.0857 -4.83033 7.1829 -19.831 -4.76686 7.48442 -20.021 -4.81395 7.93853 -22.0076 -5.30352 9.07991 -22.0663 -5.31809 9.54424 -22.0351 -5.31062 9.9794 -21.7815 -5.24818 10.3221 -23.0127 -5.55167 11.3428 -22.3152 -5.38055 11.4962 -22.4216 -5.4065 12.0316 -5.60068 -1.25798 3.91758 -5.47447 -1.227 3.96379 -5.42342 -1.21448 4.0527 -5.40401 -1.20988 4.16202 -5.44796 -1.21997 4.31514 -5.38308 -1.20391 4.39795 -5.26077 -1.17441 4.4393 -5.17016 -1.15183 4.50082 -4.96277 -1.10072 4.46985 -4.85036 -1.07306 4.50642 -5.00913 -1.11184 4.76677 -4.86204 -1.07639 4.77645 -4.63682 -1.01996 4.70987 -4.57288 -1.0044 4.78369 -4.44458 -0.973022 4.79495 -4.3658 -0.953424 4.85134 -4.32068 -0.942207 4.94148 -4.28053 -0.931958 5.03834 -4.33046 -0.945136 5.23753 -3.55624 -0.754347 4.50259 -3.64285 -0.775321 4.73077 -3.79193 -0.811728 5.04724 -3.64968 -0.776774 5.01255 -3.43703 -0.724411 4.87932 -3.33633 -0.700059 4.88364 -3.70863 -0.791378 5.55728 -3.2143 -0.66987 4.99965 -3.08092 -0.636282 4.94826 -3.0556 -0.63014 5.06125 -3.18708 -0.662519 5.4374 -3.32157 -0.696512 5.84525 -3.24879 -0.677737 5.91255 -3.16005 -0.656349 5.9525 -3.0435 -0.627977 5.9377 -2.5594 -0.508419 5.17165 -2.46661 -0.485186 5.16306 -2.45327 -0.482364 5.32471 -2.798 -0.566674 6.32787 -2.78287 -0.563623 6.55249 -2.48125 -0.489434 6.0641 -2.31187 -0.447484 5.87484 -2.2161 -0.423927 5.86916 -2.07948 -0.390072 5.73848 -2.06443 -0.386416 5.97538 -1.98359 -0.366656 6.01235 -1.71611 -0.300458 5.38446 -1.58223 -0.266729 5.17387 -1.5112 -0.249467 5.19268 -1.43518 -0.230929 5.19073 -1.45239 -0.234847 5.63737 -1.48284 -0.243186 6.23313 -1.40717 -0.223832 6.32876 -1.20854 -0.175196 5.63303 -1.36202 -0.213063 7.35838 -1.05572 -0.137783 5.6955 -1.11025 -0.151104 7.02757 -0.935875 -0.107426 6.18085 -0.818026 -0.0786429 5.74892 -0.731745 -0.0575648 5.62416 -0.654944 -0.03874 5.68759 -0.598076 -0.0248019 7.06945 -2.45845 -0.544047 -0.995882 -2.51955 -0.561368 -0.987595 -2.60324 -0.584994 -0.997959 -2.67224 -0.603943 -0.992645 -2.75695 -0.627402 -0.998418 -2.8348 -0.649003 -0.99533 -2.92049 -0.673283 -0.996263 -3.00719 -0.697495 -0.994603 -3.11062 -0.726194 -1.00234 -3.20624 -0.751978 -1.00125 -3.31065 -0.781428 -1.00275 -3.41707 -0.810848 -1.00115 -3.53923 -0.844599 -1.00705 -3.66336 -0.879281 -1.00911 -3.79634 -0.916561 -1.0123 -3.92145 -0.951906 -1.00632 -4.06531 -0.991677 -1.00605 -4.00362 -0.974178 -0.890386 -4.01762 -0.978431 -0.817673 -4.02179 -0.979874 -0.740733 -4.02401 -0.980219 -0.664236 -4.03408 -0.983263 -0.592159 -4.01563 -0.978005 -0.508801 -4.06801 -0.99258 -0.455841 -4.01019 -0.976278 -0.359569 -4.03306 -0.982511 -0.295724 -4.02641 -0.980451 -0.221993 -4.08372 -0.996374 -0.169998 -4.1302 -1.00941 -0.113373 -4.27804 -1.05102 -0.0846989 -8.79136 -2.30594 -1.0599 -9.36976 -2.46701 -1.0346 -10.1491 -2.6834 -1.03054 -11.2712 -2.99559 -1.06422 -12.549 -3.35161 -1.08418 -14.5074 -3.8961 -1.16283 -16.0031 -4.31269 -1.10735 -26.3649 -7.19482 -1.09473 -26.4738 -7.22547 -0.630715 -26.7471 -7.30139 -0.171094 -26.7624 -7.30575 0.304614 -26.8762 -7.33817 0.779595 -27.0688 -7.39116 1.25931 -33.5596 -9.19699 2.52142 -21.839 -5.93652 2.75834 -20.2722 -5.50035 2.99019 -31.5584 -8.64108 4.69515 -21.5873 -5.86674 3.89685 -30.2904 -8.2887 5.64277 -19.5009 -5.28664 4.31435 -20.7589 -5.63684 4.91229 -20.4259 -5.54413 5.22266 -20.5494 -5.57855 5.62859 -24.468 -6.66836 6.9906 -20.9689 -5.69549 6.51015 -20.1862 -5.47718 6.68193 -20.3461 -5.52237 7.11741 -21.021 -5.71012 7.73216 -25.938 -7.07822 9.85466 -27.3284 -7.46519 10.8826 -21.086 -5.72797 9.00611 -21.3972 -5.81446 9.56134 -21.8011 -5.92665 10.1762 -24.3026 -6.6228 11.7629 -29.1134 -7.962 14.5595 -5.50347 -1.39225 3.94353 -5.60259 -1.4193 4.12517 -5.36803 -1.35412 4.10208 -5.44539 -1.37624 4.27581 -5.31744 -1.34048 4.31518 -5.28426 -1.33131 4.41896 -5.43776 -1.37363 4.6621 -5.35226 -1.34989 4.73315 -5.25095 -1.32189 4.79006 -5.13382 -1.28966 4.83195 -4.76379 -1.18686 4.65434 -4.66545 -1.15867 4.69852 -4.54432 -1.12519 4.72034 -4.4528 -1.10034 4.76604 -4.48687 -1.10912 4.93347 -4.40622 -1.08734 4.99116 -4.52725 -1.12135 5.26122 -4.47535 -1.10652 5.35523 -4.375 -1.07832 5.39711 -3.58635 -0.859299 4.62733 -3.58082 -0.857822 4.75125 -3.43786 -0.817328 4.70608 -3.33935 -0.790032 4.71175 -3.41102 -0.809838 4.94527 -3.39066 -0.804822 5.06179 -3.65145 -0.877371 5.59411 -3.42628 -0.814857 5.42792 -3.05458 -0.710712 5.01307 -2.98571 -0.692245 5.05874 -2.97335 -0.688639 5.19701 -3.41973 -0.812436 6.15483 -3.25193 -0.76594 6.05896 -3.11183 -0.727181 6.00254 -3.11549 -0.728305 6.22655 -2.98926 -0.693277 6.19266 -2.90964 -0.671324 6.25505 -2.78439 -0.636612 6.21596 -2.98873 -0.692534 6.95367 -2.71853 -0.617909 6.57279 -2.68763 -0.609769 6.77973 -2.67772 -0.606172 7.06207 -2.08811 -0.442268 5.66751 -2.21036 -0.476326 6.32154 -2.07996 -0.440482 6.21825 -1.71145 -0.337544 5.25826 -1.61368 -0.310292 5.18323 -1.54079 -0.290352 5.19311 -1.47493 -0.271464 5.23073 -1.41804 -0.255755 5.31622 -1.48136 -0.273354 6.02797 -1.45086 -0.264543 6.34982 -1.24467 -0.207817 5.64623 -1.38044 -0.245467 7.1526 -1.09216 -0.164832 5.70012 -1.01845 -0.144372 5.75984 -1.04272 -0.151194 6.90334 -0.981247 -0.1348 7.42084 -0.766694 -0.0743174 5.59193 -0.690892 -0.0540007 5.62604 -0.710166 -0.0593814 9.57756 -0.545596 -0.0130573 7.04016 -2.41143 -0.592528 -0.999207 -2.46557 -0.60912 -0.984706 -2.54031 -0.631926 -0.989449 -2.61601 -0.65568 -0.991948 -2.6996 -0.681132 -0.998818 -2.76844 -0.702929 -0.990458 -2.84617 -0.726479 -0.986372 -2.93168 -0.753706 -0.986258 -3.03298 -0.784362 -0.995584 -3.13518 -0.816924 -1.00182 -3.22374 -0.843923 -0.993423 -3.33586 -0.878067 -0.999239 -3.44795 -0.913036 -1.00151 -3.56199 -0.94895 -1.00024 -3.69377 -0.989278 -1.00567 -3.82553 -1.0304 -1.00696 -3.96714 -1.07415 -1.00878 -4.10187 -1.11602 -1.00134 -4.04125 -1.09757 -0.885333 -4.07193 -1.10723 -0.820366 -4.04075 -1.09761 -0.725231 -4.0695 -1.10615 -0.660307 -4.06089 -1.1036 -0.579179 -4.05129 -1.10104 -0.498947 -4.09378 -1.11376 -0.440911 -4.03609 -1.09545 -0.344338 -4.0579 -1.10257 -0.279542 -4.0611 -1.10323 -0.208141 -4.12614 -1.1237 -0.157471 -4.19119 -1.14406 -0.104704 -4.38399 -1.20393 -0.0861201 -8.9233 -2.61027 -1.02868 -9.60968 -2.8238 -1.01948 -10.4771 -3.09197 -1.02192 -11.6757 -3.46385 -1.05363 -13.1516 -3.92179 -1.08731 -15.36 -4.60617 -1.17421 -17.5745 -5.29294 -1.18084 -21.5893 -6.53757 -1.30332 -26.7887 -8.14875 -0.903306 -26.683 -8.11611 -0.41536 -26.5409 -8.07242 0.0690605 -26.5325 -8.07031 0.545396 -26.8615 -8.17184 1.02136 -29.7218 -9.05922 1.5577 -26.3383 -8.01006 1.96568 -34.6262 -10.5797 2.90013 -21.7843 -6.59829 2.57565 -22.0117 -6.66877 2.98803 -21.7946 -6.60202 3.36084 -20.51 -6.20315 3.58889 -19.6405 -5.9339 3.83239 -19.9683 -6.03553 4.24458 -20.6168 -6.23711 4.73071 -22.9039 -6.94598 5.57848 -20.4332 -6.18009 5.45303 -20.5417 -6.21347 5.86171 -20.6709 -6.2535 6.283 -20.8561 -6.31175 6.72868 -21.3456 -6.46353 7.27662 -21.2928 -6.44661 7.6741 -20.8688 -6.31512 7.94767 -21.1112 -6.39109 8.44944 -21.783 -6.59946 9.1299 -21.688 -6.56955 9.53551 -27.687 -8.43029 12.526 -26.963 -8.20612 12.7862 -28.577 -8.70597 14.1153 -5.83475 -1.65412 4.10248 -5.67455 -1.60474 4.13448 -5.61387 -1.58562 4.22342 -5.51083 -1.55329 4.28454 -5.43141 -1.52873 4.35921 -5.34208 -1.50194 4.42642 -5.25379 -1.47432 4.49148 -5.33308 -1.49864 4.68373 -5.2714 -1.47952 4.77148 -5.23733 -1.46892 4.8827 -5.30581 -1.49023 5.08218 -4.65941 -1.28956 4.66106 -4.56909 -1.26159 4.7103 -4.42847 -1.21799 4.71041 -4.28876 -1.17563 4.70658 -4.28821 -1.1751 4.83782 -4.56193 -1.2599 5.26033 -4.47654 -1.23375 5.31955 -4.17013 -1.13849 5.12811 -4.11334 -1.12099 5.20939 -3.50381 -0.93165 4.6253 -3.46179 -0.918244 4.7027 -3.35755 -0.885911 4.70185 -3.34809 -0.883259 4.82442 -3.43347 -0.909633 5.08372 -3.39243 -0.897493 5.17719 -3.73876 -1.00422 5.85224 -3.46556 -0.920412 5.6122 -3.10735 -0.809306 5.21254 -3.40052 -0.899638 5.8704 -3.3784 -0.892596 6.02558 -3.37011 -0.890652 6.21607 -3.27383 -0.86107 6.25025 -3.08655 -0.80277 6.10585 -2.97939 -0.76912 6.10776 -2.85633 -0.731396 6.07141 -2.80755 -0.716272 6.19532 -2.87271 -0.736548 6.59311 -2.71901 -0.688341 6.48825 -2.64552 -0.665578 6.57439 -2.28543 -0.553744 5.88435 -2.1384 -0.508483 5.72833 -2.02801 -0.474972 5.66298 -2.09745 -0.496303 6.16582 -1.72177 -0.379205 5.19948 -1.64408 -0.354806 5.19235 -1.5733 -0.333472 5.21266 -1.5125 -0.314889 5.27049 -1.44077 -0.292616 5.28836 -1.5908 -0.338681 6.40057 -1.34832 -0.263763 5.59508 -1.30976 -0.251446 5.83641 -1.20806 -0.220379 5.71226 -1.36205 -0.267824 7.46751 -1.05285 -0.171762 5.75507 -1.08386 -0.181488 6.86853 -0.987549 -0.152128 6.89821 -1.06983 -0.178319 9.63978 -0.725843 -0.0707336 5.59421 -0.650343 -0.0469697 5.65768 -0.595843 -0.0307007 7.10951 -2.47651 -0.676769 -0.980335 -2.55791 -0.705273 -0.990745 -2.63349 -0.730972 -0.992147 -2.71591 -0.759305 -0.997866 -2.7778 -0.780314 -0.982093 -2.87007 -0.811334 -0.989543 -2.95441 -0.841427 -0.987978 -3.04765 -0.873239 -0.989988 -3.14191 -0.904968 -0.989105 -3.24495 -0.940369 -0.990899 -3.35585 -0.978372 -0.995115 -3.47653 -1.02006 -1.00101 -3.59823 -1.06162 -1.00322 -3.72879 -1.10578 -1.00655 -3.85932 -1.15074 -1.00574 -4.00847 -1.2021 -1.01014 -4.11748 -1.23961 -0.98653 -4.08148 -1.22731 -0.883787 -4.07783 -1.22595 -0.800229 -4.15842 -1.25383 -0.758801 -4.0744 -1.22476 -0.639268 -4.10994 -1.23685 -0.576914 -4.08272 -1.22778 -0.488084 -4.1241 -1.24238 -0.428746 -4.05769 -1.21933 -0.328348 -4.07951 -1.2264 -0.262453 -4.11796 -1.23978 -0.202257 -4.1819 -1.26207 -0.149388 -4.22822 -1.27794 -0.0893177 -8.63202 -2.78663 -1.05613 -9.15426 -2.96583 -1.01998 -9.90016 -3.22217 -1.01284 -10.9179 -3.57045 -1.03148 -12.2653 -4.03292 -1.07045 -13.9356 -4.60523 -1.1103 -16.1634 -5.36844 -1.1656 -21.7902 -7.29728 -1.14794 -26.8025 -9.01518 -1.16473 -27.5419 -9.26865 -0.724254 -27.5474 -9.27121 -0.224245 -27.072 -9.1077 0.288162 -27.2502 -9.16939 0.777106 -30.1628 -10.1679 1.30009 -32.1394 -10.8451 1.90401 -24.9657 -8.38635 2.15111 -24.5656 -8.24971 2.57767 -21.9144 -7.34022 2.80098 -22.4084 -7.51024 3.24996 -22.5462 -7.5576 3.67547 -21.814 -7.30636 3.98589 -21.3783 -7.15723 4.31774 -23.9975 -8.05504 5.17849 -21.4416 -7.17923 5.12263 -20.9538 -7.01169 5.41834 -20.6093 -6.89404 5.73206 -20.804 -6.96114 6.17261 -20.9084 -6.99639 6.59923 -21.0314 -7.03913 7.03922 -20.7832 -6.95445 7.37159 -20.7923 -6.95758 7.78399 -20.6325 -6.90208 8.14138 -21.5633 -7.22219 8.90666 -21.6954 -7.26686 9.39935 -26.3834 -8.87485 11.8054 -26.9611 -9.07313 12.6149 -26.5226 -8.9227 12.9895 -28.1452 -9.47877 14.3486 -27.7756 -9.35259 14.7833 -5.74891 -1.80021 4.14666 -5.7041 -1.78444 4.24809 -5.61009 -1.75224 4.31747 -5.57018 -1.73861 4.42207 -5.50469 -1.71626 4.50958 -5.37623 -1.67237 4.55036 -5.20154 -1.61256 4.55259 -5.22558 -1.62052 4.70432 -5.09613 -1.57601 4.73607 -5.27075 -1.63565 5.01978 -4.95529 -1.52772 4.89065 -5.05611 -1.56245 5.12182 -5.10777 -1.57989 5.31801 -4.42208 -1.34519 4.80734 -4.24925 -1.2855 4.76892 -4.19354 -1.26634 4.84461 -4.87734 -1.50192 5.71878 -4.09686 -1.23398 5.01482 -4.01654 -1.20654 5.06583 -3.95494 -1.1852 5.13765 -4.12586 -1.24384 5.49752 -4.14117 -1.24876 5.6796 -4.06973 -1.2247 5.75394 -3.44439 -1.00953 5.06485 -3.96044 -1.18703 5.95511 -3.75199 -1.11542 5.83091 -3.64506 -1.07897 5.849 -3.47107 -1.01891 5.7561 -3.16873 -0.916106 5.43901 -3.3765 -0.987336 5.97379 -3.25082 -0.943889 5.9485 -3.20606 -0.928217 6.06815 -3.12179 -0.899614 6.11742 -3.01084 -0.862099 6.11175 -2.9177 -0.830019 6.13948 -2.86506 -0.812047 6.25546 -2.75413 -0.773831 6.24375 -2.65209 -0.738376 6.24783 -2.69543 -0.753618 6.61948 -2.38752 -0.648381 6.08213 -2.20128 -0.583676 5.82567 -2.08023 -0.542815 5.73379 -1.8551 -0.465639 5.29754 -1.74387 -0.427236 5.1883 -1.6693 -0.401509 5.19149 -1.61754 -0.383961 5.27986 -1.55886 -0.363974 5.34832 -1.48034 -0.336671 5.33804 -1.62295 -0.385742 6.38077 -1.40399 -0.31085 5.72442 -1.33748 -0.288574 5.80924 -1.23503 -0.252896 5.67605 -1.23178 -0.252082 6.21319 -1.09111 -0.20345 5.78964 -1.01365 -0.176709 5.80972 -1.02869 -0.182911 6.87375 -0.972566 -0.162865 7.43089 -0.759675 -0.0904331 5.58206 -0.686234 -0.0647451 5.6262 -0.705575 -0.0721693 9.63759 -0.543419 -0.0159322 7.04022 -2.37365 -0.703581 -0.999003 -2.42661 -0.723113 -0.984549 -2.50005 -0.750853 -0.989241 -2.56668 -0.775732 -0.985021 -2.64791 -0.807069 -0.992087 -2.72339 -0.83461 -0.990293 -2.79982 -0.863094 -0.986156 -2.88304 -0.895194 -0.985987 -2.97515 -0.929013 -0.989393 -3.07499 -0.967456 -0.995722 -3.16125 -0.999344 -0.987573 -3.27095 -1.04037 -0.993436 -3.38161 -1.08228 -0.995856 -3.50112 -1.12681 -1 -3.6216 -1.17222 -1.00031 -3.75187 -1.22129 -1.0017 -3.89877 -1.27664 -1.00848 -4.0467 -1.33181 -1.01048 -4.11248 -1.35645 -0.962112 -4.11861 -1.35883 -0.881334 -4.30955 -1.43116 -0.893762 -4.1093 -1.35591 -0.712812 -4.17118 -1.37912 -0.660786 -4.12841 -1.36261 -0.562214 -4.12666 -1.36261 -0.483606 -4.15921 -1.37442 -0.419146 -4.09392 -1.34941 -0.318251 -4.1147 -1.35735 -0.251005 -4.17067 -1.37901 -0.195013 -4.24334 -1.40589 -0.142973 -4.35223 -1.44639 -0.0987949 -8.71914 -3.08695 -1.01913 -9.39212 -3.33983 -1.01061 -10.2502 -3.66272 -1.01549 -11.4157 -4.10075 -1.04594 -12.7978 -4.61972 -1.06932 -14.8233 -5.38038 -1.13722 -17.0576 -6.22044 -1.15663 -20.3027 -7.43899 -1.20546 -27.2925 -10.0656 -0.977265 -27.676 -10.2093 -0.497056 -29.324 -10.8283 -0.0494704 -29.3463 -10.837 0.487886 -29.3783 -10.8493 1.02586 -29.5318 -10.9069 1.56732 -32.2785 -11.9394 2.21395 -32.7672 -12.1236 2.83548 -33.7969 -12.51 3.51721 -26.9625 -9.94265 3.49713 -27.1042 -9.99587 4.01121 -21.8297 -8.01382 3.81724 -22.5121 -8.27053 4.32511 -22.482 -8.25914 4.73964 -22.2059 -8.15591 5.10892 -21.4368 -7.86691 5.36734 -21.2068 -7.78024 5.72152 -22.504 -8.26786 6.44775 -23.1739 -8.51958 7.06107 -20.7576 -7.61233 6.81827 -20.6324 -7.56539 7.18679 -20.3581 -7.46177 7.50547 -21.6106 -7.93284 8.34879 -21.6728 -7.95682 8.80976 -21.7713 -7.99294 9.29243 -30.3419 -11.2149 13.2683 -28.4538 -10.5056 13.0947 -27.8043 -10.2611 13.4105 -28.2722 -10.4377 14.2396 -27.6619 -10.2084 14.5606 -5.98982 -2.06299 4.25826 -5.99217 -2.06435 4.39518 -5.87973 -2.02219 4.46098 -5.8144 -1.9975 4.55548 -5.61458 -1.92221 4.55591 -5.45498 -1.86233 4.57797 -5.37293 -1.8316 4.65255 -5.32719 -1.81473 4.75473 -5.10866 -1.73216 4.71756 -5.26132 -1.78944 4.98167 -5.44249 -1.85757 5.28408 -5.07755 -1.72072 5.11178 -5.06624 -1.71622 5.24909 -5.03133 -1.70323 5.36711 -4.93156 -1.66631 5.42358 -4.16558 -1.37772 4.7895 -4.66523 -1.56622 5.45883 -4.50751 -1.50636 5.44224 -4.18552 -1.38608 5.23084 -3.91566 -1.28394 5.06096 -3.95244 -1.29871 5.25239 -4.26174 -1.4146 5.79907 -4.08817 -1.34967 5.74417 -3.90082 -1.27932 5.66056 -3.95355 -1.29834 5.90698 -3.74155 -1.2188 5.7764 -3.34644 -1.07056 5.35261 -3.30663 -1.05505 5.45472 -3.20769 -1.0185 5.46444 -3.46133 -1.11385 6.07433 -3.26692 -1.04099 5.93156 -3.12571 -0.987391 5.86972 -3.36281 -1.0772 6.53049 -3.05699 -0.962276 6.15025 -2.97195 -0.929733 6.19713 -2.84645 -0.882242 6.1525 -2.80471 -0.867613 6.29522 -2.69895 -0.827291 6.29178 -2.63755 -0.804337 6.39646 -2.32926 -0.688438 5.85117 -2.24308 -0.656424 5.86585 -2.16581 -0.627641 5.90706 -1.87296 -0.516971 5.27533 -1.76784 -0.477941 5.18614 -1.69639 -0.450886 5.19967 -1.64376 -0.430725 5.279 -1.60205 -0.415394 5.41567 -1.52365 -0.386038 5.40649 -1.44724 -0.357401 5.40545 -1.49721 -0.376088 6.03875 -1.35022 -0.320698 5.70311 -1.26686 -0.28978 5.67897 -1.20552 -0.266447 5.79134 -1.29376 -0.299944 7.08134 -1.04786 -0.207615 5.81474 -1.07076 -0.215291 6.85866 -0.97781 -0.181129 6.90832 -1.0568 -0.211125 9.62986 -0.720004 -0.083914 5.58428 -0.646741 -0.055769 5.63771 -0.594607 -0.03666 7.14956 -2.38847 -0.772857 -1.00249 -2.44032 -0.794289 -0.98723 -2.50683 -0.821216 -0.98401 -2.58693 -0.854546 -0.992172 -2.66805 -0.887818 -0.99794 -2.73553 -0.915497 -0.98848 -2.81762 -0.949595 -0.989508 -2.90854 -0.986413 -0.99416 -2.99266 -1.02038 -0.99 -3.09232 -1.06175 -0.994883 -3.18524 -1.09926 -0.991002 -3.29371 -1.14413 -0.995066 -3.4042 -1.18896 -0.995739 -3.53026 -1.24108 -1.00326 -3.64951 -1.29033 -1.00156 -3.77855 -1.34322 -1.00085 -3.932 -1.40611 -1.01011 -4.07964 -1.46616 -1.00966 -4.14432 -1.49266 -0.959595 -4.167 -1.50242 -0.886263 -4.15458 -1.49719 -0.796133 -4.16655 -1.5021 -0.71887 -4.18537 -1.50963 -0.645625 -4.15044 -1.49576 -0.550275 -4.1751 -1.50585 -0.481145 -4.19882 -1.51486 -0.411661 -4.13266 -1.48776 -0.310063 -4.17973 -1.50769 -0.250298 -4.21709 -1.52282 -0.186304 -4.28959 -1.55258 -0.132018 -8.4366 -3.25105 -1.05154 -8.9294 -3.45335 -1.01146 -9.72218 -3.77845 -1.01894 -10.6274 -4.14909 -1.01886 -11.8904 -4.66623 -1.04931 -13.4964 -5.32481 -1.08701 -15.8218 -6.27765 -1.1658 -17.9785 -7.16074 -1.13615 -22.0635 -8.8352 -1.22425 -27.6821 -11.1372 -0.772221 -27.9837 -11.2609 -0.272167 -29.0919 -11.7148 0.216467 -28.8873 -11.6314 0.757687 -28.9055 -11.639 1.29341 -29.3677 -11.8282 1.84286 -39.8417 -16.121 2.89157 -41.1719 -16.6655 3.72482 -33.5393 -13.5387 3.83987 -21.8476 -8.74769 3.24088 -22.0376 -8.82602 3.6717 -22.2208 -8.90055 4.11038 -22.4695 -9.00313 4.56867 -23.5028 -9.42627 5.1815 -22.8859 -9.17433 5.50489 -30.3621 -12.2374 7.59378 -22.8446 -9.15669 6.37475 -27.7467 -11.1658 8.09533 -27.9147 -11.2347 8.68862 -26.0925 -10.4883 8.69529 -22.8952 -9.17879 8.19146 -25.167 -10.1091 9.42972 -29.8868 -12.0439 11.6559 -26.3966 -10.614 10.9372 -5.94908 -2.23423 4.47672 -5.72717 -2.14296 4.46918 -5.61593 -2.09713 4.52958 -5.51151 -2.0546 4.59241 -5.3532 -1.98987 4.61262 -5.36246 -1.99333 4.75601 -5.52359 -2.05987 5.02583 -5.5603 -2.07523 5.20528 -5.46279 -2.03478 5.27518 -5.32898 -1.97978 5.31083 -5.11767 -1.89375 5.27135 -5.24958 -1.94705 5.55011 -5.07943 -1.87788 5.54434 -4.53564 -1.6551 5.14783 -4.39585 -1.59759 5.14615 -4.30211 -1.55963 5.19052 -3.97986 -1.42669 4.97118 -4.05881 -1.4589 5.20597 -4.13676 -1.49149 5.4524 -4.01066 -1.43976 5.45183 -3.99744 -1.43388 5.5946 -3.888 -1.38924 5.6129 -3.85216 -1.37516 5.73167 -3.68183 -1.30536 5.65749 -3.56848 -1.25828 5.65977 -3.46196 -1.21435 5.66747 -3.4163 -1.19633 5.7728 -3.18988 -1.10326 5.57396 -3.42435 -1.20015 6.16993 -3.06815 -1.05333 5.72434 -3.06876 -1.05367 5.92009 -3.07335 -1.0553 6.13491 -2.96874 -1.0127 6.13836 -2.87298 -0.973883 6.15726 -2.77726 -0.934157 6.17422 -2.84298 -0.961516 6.57145 -2.62705 -0.873551 6.30292 -2.38939 -0.775685 5.94482 -2.25808 -0.7218 5.84014 -2.16023 -0.681965 5.81635 -1.9104 -0.579255 5.31892 -1.79269 -0.531254 5.19313 -1.72828 -0.504643 5.22645 -2.08114 -0.649709 6.79306 -1.64305 -0.469204 5.47264 -1.55885 -0.435392 5.44516 -1.5064 -0.413876 5.55195 -1.66144 -0.477857 6.69325 -1.39173 -0.366341 5.76358 -1.29958 -0.329263 5.69123 -1.36803 -0.357323 6.64276 -1.32916 -0.342052 7.04405 -1.12114 -0.255732 6.14657 -1.00885 -0.210075 5.87928 -1.01577 -0.213214 6.8538 -0.962888 -0.191378 7.45088 -0.754776 -0.105689 5.59205 -0.681575 -0.0754994 5.62616 -0.701983 -0.0850177 9.69762 -0.54224 -0.0193767 7.05021 -2.38754 -0.838458 -0.991534 -2.44516 -0.863554 -0.982442 -2.52414 -0.898881 -0.9918 -2.59731 -0.931404 -0.992149 -2.67049 -0.963817 -0.990301 -2.75145 -0.999913 -0.992525 -2.82659 -1.03322 -0.986039 -2.92411 -1.07669 -0.99541 -3.00705 -1.11352 -0.9899 -3.10561 -1.15676 -0.993282 -3.19729 -1.19814 -0.987902 -3.31337 -1.24968 -0.995888 -3.43046 -1.30109 -1.00008 -3.54752 -1.35331 -1.00033 -3.67431 -1.41019 -1.00171 -3.80112 -1.46686 -0.998899 -3.95428 -1.53463 -1.00581 -4.09193 -1.59474 -0.998491 -4.17982 -1.63426 -0.960238 -4.16935 -1.63007 -0.868467 -4.19882 -1.6434 -0.798105 -4.19324 -1.64077 -0.711594 -4.21107 -1.64817 -0.637047 -4.20255 -1.64441 -0.551574 -4.20959 -1.64799 -0.473845 -4.22448 -1.65422 -0.399439 -4.18473 -1.63717 -0.306519 -4.21425 -1.64964 -0.238903 -4.2505 -1.66662 -0.173209 -4.33068 -1.70189 -0.1194 -8.47909 -3.54434 -1.0081 -9.13566 -3.83639 -1.00035 -9.99122 -4.21654 -1.00991 -10.9317 -4.6341 -1.00292 -12.4515 -5.30951 -1.06019 -14.2377 -6.10347 -1.10003 -16.5916 -7.14875 -1.14731 -19.2862 -8.34647 -1.14351 -27.7857 -12.1228 -1.06326 -27.8693 -12.1603 -0.544888 -28.6299 -12.4976 -0.0495495 -28.4686 -12.4269 0.490928 -28.5639 -12.4693 1.02529 -28.7597 -12.5566 1.56525 -28.9751 -12.6516 2.11378 -41.7738 -18.3397 3.4041 -42.1119 -18.4901 4.22163 -27.4529 -11.976 3.60492 -27.6252 -12.0529 4.14451 -22.5741 -9.80874 3.98619 -23.5271 -10.2329 4.56272 -22.5728 -9.80905 4.84628 -22.4727 -9.76437 5.2603 -29.9108 -13.0701 7.86873 -29.5836 -12.9239 8.37516 -6.25906 -2.55969 4.50097 -6.08353 -2.48218 4.53528 -6.03416 -2.45962 4.64661 -5.71981 -2.31974 4.57657 -5.56179 -2.2506 4.60497 -5.66296 -2.29525 4.81861 -5.81795 -2.36368 5.08315 -5.6854 -2.30514 5.13115 -5.42962 -2.19128 5.07294 -5.52887 -2.23573 5.30831 -5.2965 -2.13287 5.25881 -5.18545 -2.08344 5.31123 -5.047 -2.02176 5.33437 -4.97015 -1.98809 5.41388 -4.8395 -1.92989 5.43725 -4.36725 -1.71976 5.09529 -4.33347 -1.70429 5.20397 -4.25361 -1.66949 5.26222 -4.14148 -1.61961 5.28198 -4.39661 -1.73237 5.74503 -4.24823 -1.66707 5.72821 -3.97839 -1.54748 5.54615 -3.97993 -1.5473 5.71294 -3.76391 -1.45151 5.58159 -3.65169 -1.40232 5.58737 -3.51404 -1.34071 5.54973 -3.29987 -1.24566 5.38537 -3.30529 -1.24822 5.56258 -3.13818 -1.17321 5.45598 -3.30841 -1.2492 5.92996 -3.06469 -1.14145 5.68275 -2.98091 -1.10375 5.71375 -2.8922 -1.06428 5.73418 -2.96154 -1.09544 6.07951 -3.26963 -1.2326 6.96366 -2.83034 -1.03729 6.24245 -2.73479 -0.994585 6.25896 -3.01375 -1.11931 7.19644 -2.9429 -1.08797 7.31718 -2.2818 -0.793363 5.84182 -2.19798 -0.755473 5.85649 -1.92402 -0.634378 5.29602 -1.80755 -0.582385 5.17133 -1.8251 -0.590122 5.48098 -1.98281 -0.660848 6.32834 -1.71936 -0.543089 5.67315 -1.59293 -0.486715 5.48322 -1.52077 -0.455271 5.50344 -1.63083 -0.504136 6.38966 -1.55991 -0.472859 6.48878 -1.32524 -0.367797 5.67365 -1.26408 -0.34089 5.77743 -1.35551 -0.382076 6.95695 -1.26695 -0.342403 7.02192 -1.04193 -0.242414 5.87426 -1.05061 -0.247131 6.79898 -0.97219 -0.211938 6.98797 -1.04688 -0.245669 9.6897 -0.714165 -0.0970944 5.57436 -0.643203 -0.0650892 5.64771 -0.592313 -0.0435607 7.18956 -2.34553 -0.885966 -1.00956 -2.38355 -0.904865 -0.980324 -2.45464 -0.938431 -0.984013 -2.51892 -0.969146 -0.97899 -2.59774 -1.00731 -0.985003 -2.67075 -1.04267 -0.982208 -2.75059 -1.08066 -0.98343 -2.83916 -1.12335 -0.988078 -2.92097 -1.1622 -0.984164 -3.01728 -1.20939 -0.989139 -3.10784 -1.25278 -0.985254 -3.21395 -1.30354 -0.989613 -3.32885 -1.35794 -0.995849 -3.44366 -1.41413 -0.998091 -3.56048 -1.47026 -0.996544 -3.69388 -1.5337 -1.00085 -3.81947 -1.59421 -0.995934 -3.97035 -1.66674 -1.0005 -4.11442 -1.73637 -0.995248 -4.21869 -1.78623 -0.963695 -4.21607 -1.78467 -0.874846 -4.23671 -1.79516 -0.798562 -4.23115 -1.79247 -0.710653 -4.24892 -1.80079 -0.634458 -4.24041 -1.79696 -0.547687 -4.23874 -1.79576 -0.465034 -4.27014 -1.81025 -0.395528 -4.23047 -1.79214 -0.30126 -4.26766 -1.81013 -0.23452 -4.32143 -1.83534 -0.172032 -4.45299 -1.89839 -0.130286 -8.20499 -3.70113 -1.04473 -8.6403 -3.91049 -0.994337 -9.36848 -4.26035 -0.993288 -10.2768 -4.69575 -1.00095 -11.444 -5.25677 -1.02163 -12.9898 -5.99999 -1.05929 -15.1206 -7.02353 -1.12198 -17.4901 -8.16117 -1.13195 -20.7776 -9.74074 -1.14771 -29.3354 -13.8528 -0.930516 -30.1899 -14.2628 -0.411345 -29.5677 -13.9641 0.181703 -29.4594 -13.9124 0.745723 -30.0355 -14.1899 1.31264 -30.711 -14.5142 1.90488 -27.3059 -12.8789 3.88806 -27.7662 -13.1004 4.47155 -5.98718 -2.63697 4.59347 -6.07538 -2.68024 4.79871 -6.05243 -2.66917 4.93297 -5.62944 -2.46592 4.77467 -5.68067 -2.48997 4.95847 -5.72798 -2.51263 5.14542 -5.73429 -2.51609 5.30555 -4.87194 -2.10142 4.72983 -4.85479 -2.09334 4.85139 -5.05825 -2.19175 5.17708 -5.10072 -2.21188 5.36875 -4.88346 -2.10732 5.31127 -4.8351 -2.08416 5.41585 -4.72523 -2.0313 5.45778 -4.37895 -1.86487 5.23734 -4.24163 -1.7996 5.23327 -4.14346 -1.75178 5.26876 -4.05791 -1.71114 5.31664 -3.97141 -1.66953 5.36238 -3.95428 -1.66178 5.49747 -4.04377 -1.70431 5.77986 -3.74416 -1.55999 5.5345 -3.70458 -1.5411 5.64435 -3.60438 -1.49287 5.66552 -3.51488 -1.45062 5.70053 -3.29827 -1.34584 5.52729 -3.19116 -1.29448 5.52241 -3.2602 -1.32806 5.81861 -3.19327 -1.29547 5.8884 -3.09791 -1.24975 5.90536 -2.95355 -1.18086 5.82435 -2.97185 -1.18909 6.06454 -2.88824 -1.14903 6.10283 -2.83891 -1.12619 6.21995 -2.69848 -1.05803 6.12905 -2.97189 -1.18998 7.03558 -3.00616 -1.2064 7.41285 -2.45349 -0.940939 6.24974 -2.21965 -0.827888 5.85873 -1.91588 -0.681962 5.21672 -1.82816 -0.639497 5.17742 -1.81122 -0.631215 5.36385 -1.99313 -0.719251 6.27579 -1.86124 -0.655751 6.12168 -1.62278 -0.541294 5.51116 -1.54687 -0.504524 5.51292 -1.63485 -0.547359 6.27162 -1.5789 -0.520083 6.42952 -1.39527 -0.431465 5.91065 -1.27477 -0.37388 5.67156 -1.37176 -0.420944 6.82029 -1.29424 -0.38398 6.9451 -1.10387 -0.292294 6.13666 -1.01209 -0.247505 6.0383 -0.996855 -0.241118 6.79411 -0.949152 -0.218116 7.42095 -0.975898 -0.232165 9.7944 -0.677917 -0.0873227 5.64619 -0.699518 -0.0994724 9.82761 -0.541122 -0.0218194 7.06025 -2.26589 -0.912031 -0.984951 -2.32808 -0.943858 -0.984666 -2.39799 -0.980409 -0.989302 -2.4679 -1.01685 -0.991741 -2.53207 -1.04951 -0.98562 -2.61077 -1.08961 -0.990336 -2.68267 -1.12685 -0.986239 -2.75451 -1.16498 -0.979996 -2.8352 -1.20584 -0.977477 -2.93715 -1.25876 -0.990014 -3.0188 -1.3004 -0.981955 -3.11496 -1.35037 -0.982387 -3.21984 -1.40498 -0.985046 -3.348 -1.47165 -1.00007 -3.44715 -1.52228 -0.990175 -3.57829 -1.58972 -0.99687 -3.70163 -1.6542 -0.994149 -3.83476 -1.72231 -0.991812 -3.98336 -1.79961 -0.994023 -4.13398 -1.87676 -0.990946 -4.2603 -1.94252 -0.969859 -4.2664 -1.94562 -0.883438 -4.30356 -1.96442 -0.813053 -4.2815 -1.95324 -0.715649 -4.29045 -1.95874 -0.633932 -4.28201 -1.95384 -0.545512 -4.28807 -1.9572 -0.464484 -4.39506 -2.01264 -0.420658 -4.26337 -1.9441 -0.291464 -4.32569 -1.97695 -0.230955 -4.37836 -2.00399 -0.165967 -8.19554 -3.97581 -0.992574 -8.82504 -4.30128 -0.983909 -9.63129 -4.71836 -0.989138 -10.5882 -5.21267 -0.992689 -12.0044 -5.94453 -1.04012 -13.5644 -6.75065 -1.05464 -16.0375 -8.02835 -1.13304 -18.3302 -9.21304 -1.09306 -34.9585 -17.806 -1.00161 -35.1083 -17.8839 -0.329163 -35.0793 -17.8684 0.35179 -35.1814 -17.9221 1.03134 -45.0169 -23.0075 11.6932 -45.8811 -23.4555 13.7802 -5.54738 -2.60925 4.69744 -5.44458 -2.55667 4.76257 -5.90952 -2.79713 5.27258 -5.46203 -2.56569 5.06638 -4.98722 -2.31987 4.81378 -4.89217 -2.27118 4.87064 -4.92766 -2.28975 5.04455 -5.21161 -2.43676 5.45905 -4.87306 -2.2613 5.28829 -4.72051 -2.18296 5.28657 -4.64693 -2.14468 5.36203 -4.30433 -1.96731 5.14393 -4.18288 -1.90529 5.15434 -4.16092 -1.89388 5.27656 -4.16729 -1.89639 5.43564 -3.9727 -1.79657 5.35082 -3.95762 -1.78792 5.48635 -3.84688 -1.7314 5.50007 -3.80445 -1.70963 5.60399 -3.74351 -1.6779 5.684 -3.58009 -1.59341 5.61125 -3.5084 -1.55601 5.67103 -4.53402 -2.08677 7.49981 -3.66378 -1.63683 6.29242 -3.27666 -1.43706 5.82518 -3.20693 -1.40066 5.8875 -2.86559 -1.22361 5.44263 -2.91599 -1.24986 5.72236 -2.86766 -1.22596 5.8217 -2.78915 -1.18428 5.85858 -2.72915 -1.15361 5.93853 -2.66821 -1.12193 6.01755 -2.63462 -1.10539 6.16822 -2.60796 -1.0919 6.34654 -2.19936 -0.880529 5.52163 -2.38138 -0.974232 6.25914 -1.90873 -0.730145 5.14675 -1.84178 -0.695129 5.16446 -1.82291 -0.68519 5.34151 -1.74122 -0.643243 5.31932 -1.89439 -0.722245 6.1561 -1.64863 -0.595132 5.52898 -1.5827 -0.561018 5.57015 -1.62708 -0.584774 6.11482 -1.56133 -0.550269 6.20444 -1.52715 -0.533043 6.46913 -1.33588 -0.433911 5.86998 -1.39493 -0.464836 6.75243 -1.31255 -0.422466 6.81863 -1.2452 -0.387233 7.02186 -1.03202 -0.276463 5.92386 -1.03463 -0.278759 6.78903 -0.978749 -0.249613 7.247 -1.02679 -0.276013 9.61983 -0.70845 -0.109799 5.59434 -0.638664 -0.0733354 5.63773 -0.59008 -0.0494596 7.22962 -2.26585 -0.979063 -0.981544 -2.32693 -1.01279 -0.980358 -2.39572 -1.05123 -0.984093 -2.46552 -1.08963 -0.985633 -2.53527 -1.12892 -0.985027 -2.59933 -1.16343 -0.97591 -2.68359 -1.21102 -0.983394 -2.76209 -1.25481 -0.982119 -2.84837 -1.30225 -0.984116 -2.93561 -1.35062 -0.98337 -3.02964 -1.40254 -0.985395 -3.13333 -1.46017 -0.9897 -3.23705 -1.51763 -0.990509 -3.33401 -1.57124 -0.982556 -3.4619 -1.6426 -0.99154 -3.58305 -1.71008 -0.991062 -3.71293 -1.78213 -0.991213 -3.85155 -1.85871 -0.991295 -3.99886 -1.94082 -0.990957 -4.15492 -2.02741 -0.989552 -4.31201 -2.11379 -0.982556 -4.32583 -2.12146 -0.898159 -4.33767 -2.12902 -0.813856 -4.31568 -2.11676 -0.715002 -4.34214 -2.13061 -0.638589 -4.31621 -2.1172 -0.54167 -4.32328 -2.12054 -0.458947 -4.57819 -2.26169 -0.466374 -4.31511 -2.11558 -0.28843 -4.37633 -2.15025 -0.225422 -4.45307 -2.19303 -0.165314 -7.8807 -4.09454 -1.01922 -8.3548 -4.35713 -0.983759 -9.05269 -4.74423 -0.981587 -9.91532 -5.22288 -0.98663 -10.9272 -5.78448 -0.985699 -12.4004 -6.60152 -1.02277 -14.3379 -7.67583 -1.07045 -16.8694 -9.08089 -1.11769 -19.8761 -10.7489 -1.11575 -23.5935 -12.8112 -1.05729 -40.4218 -22.1475 -0.159459 -40.3729 -22.12 0.638069 -24.4312 -13.2772 1.26066 -24.4153 -13.2675 1.73797 -24.4264 -13.2745 2.21654 -19.2323 -10.3949 7.36474 -18.7571 -10.1317 7.6021 -5.51855 -2.78571 4.66387 -5.36643 -2.70192 4.69162 -5.05794 -2.52986 4.58982 -5.0807 -2.54262 4.7442 -5.16954 -2.59243 4.96007 -4.90078 -2.44325 4.86996 -4.86814 -2.42568 4.98214 -4.89486 -2.43994 5.15148 -4.87105 -2.42621 5.27761 -4.85009 -2.41533 5.41067 -4.65315 -2.30656 5.36166 -4.38327 -2.1567 5.22347 -4.11921 -2.00967 5.07588 -4.15466 -2.02965 5.26177 -4.25144 -2.08335 5.53005 -4.19941 -2.05435 5.62636 -3.93132 -1.90576 5.44477 -3.92502 -1.90186 5.5962 -3.93817 -1.90958 5.77983 -3.70114 -1.77818 5.61281 -3.58288 -1.71227 5.60458 -3.49576 -1.66405 5.64129 -3.49042 -1.66155 5.8063 -4.48084 -2.2111 7.63813 -3.29374 -1.55273 5.83939 -2.98054 -1.37793 5.46415 -2.83488 -1.29668 5.36793 -2.76324 -1.2574 5.40528 -2.64772 -1.19378 5.35409 -2.77316 -1.26342 5.8008 -2.70742 -1.22726 5.8632 -2.69155 -1.21747 6.04074 -2.60628 -1.17095 6.0658 -2.33351 -1.01938 5.61556 -2.14071 -0.912574 5.33034 -2.03094 -0.851135 5.24238 -1.89272 -0.774703 5.05824 -1.84548 -0.748107 5.13231 -1.80017 -0.723197 5.21516 -1.75198 -0.696136 5.29743 -1.91937 -0.790227 6.17081 -1.67523 -0.653581 5.55582 -1.62122 -0.623765 5.6461 -1.55641 -0.588241 5.69681 -1.60079 -0.613511 6.27159 -1.56574 -0.593677 6.52715 -1.43907 -0.523476 6.3124 -1.33797 -0.466655 6.20259 -1.34565 -0.471528 6.82025 -1.26844 -0.428546 6.92523 -1.07873 -0.323828 6.0771 -1.01123 -0.286188 6.1873 -0.982063 -0.270319 6.79404 -1.09691 -0.334799 9.79371 -0.97041 -0.265019 9.95415 -0.829585 -0.186854 9.86226 -0.697115 -0.113434 9.96758 -0.540006 -0.0247713 7.08022 -2.21539 -1.01766 -0.992045 -2.26958 -1.04966 -0.984693 -2.33048 -1.08633 -0.982559 -2.39816 -1.12666 -0.985193 -2.46685 -1.16694 -0.985632 -2.53549 -1.20812 -0.983925 -2.61191 -1.25297 -0.986289 -2.68252 -1.29504 -0.980044 -2.76662 -1.34543 -0.983484 -2.85173 -1.39574 -0.984131 -2.9378 -1.44697 -0.981935 -3.03165 -1.50181 -0.982412 -3.13318 -1.56225 -0.985164 -3.25014 -1.63198 -0.994861 -3.34594 -1.68844 -0.985059 -3.4716 -1.76358 -0.99194 -3.59152 -1.83489 -0.989363 -3.71918 -1.9107 -0.987212 -3.86423 -1.99681 -0.989567 -4.00932 -2.08267 -0.986628 -4.17081 -2.17869 -0.986793 -4.34971 -2.28491 -0.989166 -4.38665 -2.3075 -0.914588 -4.36668 -2.29523 -0.812945 -4.36114 -2.29227 -0.719841 -4.37883 -2.3023 -0.637755 -4.37041 -2.29722 -0.54584 -4.49911 -2.37429 -0.507089 -4.41443 -2.32312 -0.38774 -4.40114 -2.3158 -0.297107 -4.43714 -2.33736 -0.222875 -4.65478 -2.46676 -0.200615 -7.9153 -4.4018 -0.983748 -8.53326 -4.76884 -0.977868 -9.30398 -5.22684 -0.98176 -10.1879 -5.75145 -0.977358 -11.3967 -6.46939 -0.996863 -13.1624 -7.51692 -1.05772 -15.2482 -8.75601 -1.09227 -17.6891 -10.2051 -1.08522 -41.8097 -24.5266 0.198836 -44.5416 -26.1543 12.8676 -4.98638 -2.66607 4.52729 -5.05953 -2.70899 4.72119 -4.98238 -2.66352 4.79562 -4.87714 -2.6006 4.84383 -4.79124 -2.55012 4.90755 -4.66561 -2.47516 4.93106 -4.61851 -2.44744 5.02791 -4.62866 -2.45338 5.18313 -4.56605 -2.41637 5.26639 -4.36279 -2.29515 5.19809 -4.14487 -2.16639 5.10217 -4.04633 -2.10774 5.13303 -4.42531 -2.33332 5.73715 -4.32391 -2.27293 5.77955 -4.32637 -2.27448 5.95313 -4.0036 -2.08211 5.69772 -3.8827 -2.01054 5.69925 -3.65011 -1.8723 5.53397 -3.56026 -1.81916 5.56564 -3.48597 -1.7749 5.61918 -3.28531 -1.65591 5.46867 -3.18276 -1.59563 5.46713 -3.16389 -1.58368 5.60393 -3.06624 -1.52547 5.60697 -2.83726 -1.38943 5.36137 -2.73558 -1.33021 5.33966 -2.6233 -1.26275 5.28906 -2.54596 -1.21714 5.30531 -2.71498 -1.31721 5.85858 -2.68054 -1.29747 5.99199 -2.61304 -1.25723 6.0535 -2.54747 -1.21873 6.12289 -2.13587 -0.973644 5.28642 -1.99417 -0.888734 5.10719 -1.91283 -0.840972 5.08131 -1.88224 -0.823058 5.20276 -1.80973 -0.779598 5.20197 -1.73229 -0.733851 5.18066 -1.68808 -0.7076 5.27166 -1.69672 -0.713223 5.57265 -1.65656 -0.688847 5.71157 -1.57921 -0.642356 5.70535 -1.59495 -0.653082 6.13431 -1.5481 -0.625389 6.31165 -1.48265 -0.586433 6.41046 -1.43398 -0.557735 6.62601 -1.35684 -0.51161 6.6934 -1.29855 -0.476384 6.90748 -1.22645 -0.434281 7.06154 -1.02404 -0.313667 6.01326 -1.01772 -0.310348 6.7989 -0.975072 -0.285094 7.39646 -1.00788 -0.30494 9.57993 -0.700612 -0.12185 5.56435 -0.75725 -0.15726 9.86525 -0.585404 -0.0531292 7.08955 -2.15147 -1.04771 -0.988065 -2.20459 -1.08069 -0.98166 -2.26437 -1.11935 -0.980422 -2.33098 -1.16067 -0.984202 -2.39178 -1.19919 -0.979072 -2.4593 -1.24237 -0.978561 -2.52683 -1.28543 -0.975952 -2.60884 -1.33691 -0.983531 -2.68405 -1.38551 -0.982099 -2.75455 -1.42941 -0.972359 -2.8442 -1.48725 -0.977668 -2.93587 -1.54505 -0.979788 -3.02849 -1.60375 -0.978766 -3.12885 -1.66704 -0.979868 -3.24365 -1.73957 -0.987812 -3.34493 -1.80455 -0.981427 -3.46937 -1.88353 -0.98631 -3.59477 -1.96333 -0.986551 -3.72892 -2.04768 -0.986823 -3.87069 -2.13848 -0.986523 -4.02893 -2.23847 -0.989676 -4.19679 -2.34496 -0.990866 -4.37242 -2.45583 -0.989886 -4.57306 -2.58348 -0.993538 -4.70338 -2.66675 -0.956494 -4.44747 -2.50329 -0.743607 -4.43229 -2.49446 -0.645026 -4.49615 -2.53518 -0.579333 -4.44632 -2.50364 -0.469444 -4.42637 -2.49064 -0.373543 -4.46226 -2.5141 -0.297415 -7.52044 -4.45345 -0.989176 -8.07613 -4.80662 -0.981793 -8.73317 -5.22316 -0.975815 -9.55036 -5.74105 -0.97784 -10.5614 -6.3822 -0.984294 -12.0335 -7.31698 -1.03047 -13.7449 -8.40245 -1.05257 -16.584 -10.203 -1.1552 -19.0587 -11.774 -1.09918 -32.1348 -20.0703 -0.606857 -32.4243 -20.2533 0.0390699 -5.84655 -3.39478 5.36082 -4.86047 -2.76865 4.69172 -4.76513 -2.70805 4.74559 -4.68912 -2.65989 4.81497 -4.59959 -2.60261 4.86987 -4.49648 -2.53724 4.90944 -4.46978 -2.5209 5.02404 -4.42279 -2.49129 5.11878 -4.33613 -2.43626 5.17217 -4.48858 -2.53288 5.49199 -4.35546 -2.44838 5.49665 -4.4131 -2.48462 5.72556 -4.20342 -2.35224 5.63162 -4.3967 -2.47468 6.04677 -3.92446 -2.17574 5.5946 -4.28928 -2.40716 6.26578 -4.16778 -2.32983 6.28154 -3.70607 -2.03674 5.78493 -3.50209 -1.90703 5.64412 -3.46287 -1.88216 5.75378 -3.22096 -1.72925 5.52936 -3.0974 -1.64972 5.48595 -2.72343 -1.41313 4.98838 -2.60555 -1.33799 4.92403 -2.51577 -1.28124 4.90727 -2.44155 -1.2333 4.91387 -2.55757 -1.30743 5.31921 -2.77079 -1.44355 5.9677 -2.67432 -1.3819 5.96075 -2.64972 -1.36641 6.12133 -2.22562 -1.09684 5.29825 -2.02882 -0.972013 4.98733 -1.94961 -0.922275 4.96344 -1.94341 -0.918106 5.14069 -1.8691 -0.870888 5.13261 -1.83764 -0.850914 5.25407 -1.73019 -0.782373 5.13021 -1.67139 -0.746016 5.16462 -1.73954 -0.788974 5.67475 -1.6174 -0.711604 5.48866 -1.60469 -0.703238 5.74244 -1.6175 -0.711224 6.14224 -1.55699 -0.673503 6.24238 -1.50633 -0.642054 6.40995 -1.4332 -0.595573 6.46919 -1.39157 -0.568886 6.73355 -1.30281 -0.511961 6.72158 -1.22884 -0.465172 6.82636 -1.0557 -0.355011 6.04734 -1.08012 -0.370788 7.09156 -0.968333 -0.300611 6.83387 -1.08483 -0.375772 9.92336 -0.962927 -0.298771 10.1338 -0.817393 -0.205673 9.85225 -0.692713 -0.126776 10.0974 -0.53889 -0.0282274 7.11024 -2.14079 -1.10875 -0.97798 -2.20527 -1.1521 -0.98475 -2.25723 -1.1879 -0.975796 -2.32267 -1.23211 -0.978524 -2.38912 -1.27627 -0.979159 -2.45552 -1.32133 -0.977546 -2.52194 -1.36628 -0.973836 -2.59601 -1.4169 -0.973899 -2.67687 -1.47112 -0.977631 -2.75863 -1.52725 -0.978371 -2.84146 -1.5823 -0.976267 -2.92518 -1.63927 -0.97127 -3.01564 -1.70079 -0.968894 -3.12825 -1.7763 -0.97908 -3.23411 -1.84794 -0.980005 -3.34864 -1.92517 -0.982008 -3.46414 -2.00325 -0.979771 -3.58732 -2.08683 -0.97791 -3.73355 -2.1863 -0.98512 -3.8731 -2.28085 -0.982319 -4.02906 -2.38558 -0.982721 -4.2013 -2.50243 -0.985129 -4.38224 -2.62468 -0.984821 -4.57089 -2.75226 -0.981295 -4.80094 -2.90692 -0.988201 -4.48719 -2.69578 -0.653056 -4.51058 -2.71106 -0.568844 -4.50892 -2.71033 -0.475354 -4.51304 -2.71312 -0.385131 -4.55656 -2.74301 -0.308132 -7.13959 -4.48876 -0.991892 -7.58719 -4.79146 -0.968209 -8.17428 -5.18869 -0.96155 -8.87589 -5.66318 -0.957293 -9.75166 -6.25587 -0.960396 -10.8912 -7.02565 -0.976917 -12.379 -8.03166 -1.00406 -14.1902 -9.25707 -1.01637 -17.2081 -11.2974 -1.10436 -32.9365 -21.9329 -0.337702 -32.619 -21.7189 0.352565 -5.42494 -3.33225 3.90684 -5.36073 -3.2888 3.99661 -5.30135 -3.24852 4.08911 -5.24514 -3.21035 4.58689 -4.87319 -2.95869 4.43549 -5.58462 -3.44067 5.14853 -5.5774 -3.43566 5.30102 -5.26716 -3.22586 5.18966 -4.57759 -2.75932 4.71724 -4.45832 -2.67872 4.74103 -4.37761 -2.62484 4.79865 -4.38577 -2.63014 4.94414 -4.29066 -2.56513 4.98607 -4.18868 -2.49718 5.01849 -4.06359 -2.41228 5.02059 -3.97515 -2.35281 5.06035 -3.88097 -2.28844 5.0905 -3.79829 -2.23322 5.13234 -3.66446 -2.14219 5.10615 -3.50545 -2.03464 5.03834 -3.54455 -2.06123 5.23706 -3.40774 -1.96888 5.1933 -3.3367 -1.92022 5.23839 -3.14765 -1.79228 5.10039 -3.14224 -1.78986 5.24358 -3.09533 -1.758 5.32289 -3.03682 -1.71827 5.38517 -2.69576 -1.48708 4.94024 -2.6159 -1.43291 4.94407 -2.51085 -1.36181 4.89475 -2.4706 -1.33554 4.9709 -2.42175 -1.30161 5.0291 -2.76813 -1.53641 5.95277 -2.36947 -1.26702 5.2579 -2.28575 -1.20953 5.24317 -2.13698 -1.10912 5.06441 -2.04243 -1.04605 5.00772 -1.93728 -0.974259 4.91161 -1.89709 -0.947 4.98741 -1.82971 -0.90175 4.9885 -1.84296 -0.911111 5.24009 -1.7591 -0.854243 5.19255 -1.67428 -0.795893 5.13332 -1.68766 -0.80586 5.4334 -1.61449 -0.755992 5.41948 -1.52279 -0.693864 5.32697 -1.58227 -0.734245 5.89859 -1.43881 -0.637529 5.57131 -1.52308 -0.694717 6.37981 -1.45694 -0.650172 6.46913 -1.42225 -0.626433 6.76334 -1.33168 -0.565308 6.73275 -1.25683 -0.515397 6.81855 -1.11191 -0.41663 6.30875 -1.01706 -0.352972 6.1423 -1.00188 -0.342014 6.8287 -1.16141 -0.452151 10.2557 -0.993092 -0.338195 9.65975 -0.886667 -0.26685 10.1183 -0.747296 -0.171698 9.84519 -0.635364 -0.0965658 11.019 -2.08764 -1.14215 -0.988119 -2.13853 -1.17901 -0.981709 -2.19613 -1.22055 -0.980516 -2.24797 -1.2583 -0.970664 -2.31806 -1.30809 -0.979153 -2.37664 -1.3504 -0.972221 -2.44763 -1.40202 -0.97602 -2.51958 -1.45458 -0.977276 -2.59261 -1.50608 -0.976188 -2.66653 -1.55951 -0.972406 -2.74617 -1.61746 -0.971942 -2.82783 -1.67538 -0.968587 -2.9161 -1.73985 -0.967754 -3.01209 -1.80891 -0.969145 -3.11576 -1.88354 -0.972212 -3.23482 -1.96843 -0.981575 -3.33942 -2.04471 -0.976555 -3.4604 -2.13128 -0.977037 -3.58807 -2.22328 -0.977692 -3.71771 -2.31616 -0.97331 -3.86935 -2.4258 -0.976848 -4.02296 -2.53627 -0.974449 -4.19193 -2.65779 -0.974003 -4.38385 -2.79698 -0.978334 -4.57782 -2.93592 -0.974981 -4.81008 -3.10373 -0.981353 -5.04434 -3.2722 -0.978294 -5.29491 -3.45253 -0.972046 -5.60881 -3.67849 -0.979558 -5.93905 -3.91612 -0.979887 -6.32585 -4.19553 -0.985213 -6.69935 -4.46406 -0.969467 -7.16784 -4.80113 -0.966144 -7.70157 -5.18616 -0.960458 -8.31694 -5.62917 -0.952317 -9.03789 -6.14864 -0.941755 -9.96809 -6.81878 -0.943476 -11.2227 -7.72213 -0.964532 -12.8978 -8.92841 -0.999772 -15.6343 -10.8987 -1.11071 -17.6725 -12.3675 -1.0217 -30.4069 -21.5385 -0.58164 -30.1401 -21.3465 0.0707509 -30.4329 -21.5573 0.705515 -39.9376 -28.4041 2.30882 -40.3261 -28.6842 3.17939 -40.3134 -28.6749 4.03747 -40.3371 -28.6926 4.90046 -38.4601 -27.3443 10.5544 -5.33961 -3.48791 3.98093 -5.28229 -3.44666 4.07537 -5.30966 -3.46592 4.22553 -5.34082 -3.48908 4.38278 -5.64816 -3.71028 4.74553 -4.89623 -3.16807 4.32743 -4.8764 -3.15411 4.44301 -4.87392 -3.1524 4.5753 -5.09665 -3.31314 4.90135 -5.20587 -3.39188 5.14506 -4.83958 -3.12791 4.96579 -4.42321 -2.82723 4.71734 -4.38893 -2.80301 4.81988 -4.36529 -2.78584 4.93482 -4.30212 -2.74113 5.0109 -4.23321 -2.69146 5.07887 -4.04868 -2.55903 5.0166 -4.19752 -2.66562 5.33343 -3.88674 -2.44226 5.11076 -3.79373 -2.37499 5.14016 -3.6294 -2.25609 5.07253 -3.59801 -2.23399 5.17616 -3.4365 -2.1177 5.09984 -3.36753 -2.06805 5.14717 -3.96297 -2.4976 6.18885 -4.7062 -3.03347 7.53113 -3.48856 -2.15572 5.81077 -3.10609 -1.8796 5.35155 -3.26581 -1.99485 5.78989 -3.03663 -1.82993 5.56009 -2.65391 -1.55372 5.02168 -2.51434 -1.45369 4.90717 -2.49647 -1.44065 5.02669 -2.44769 -1.40566 5.08624 -2.49752 -1.44107 5.36261 -2.34629 -1.33255 5.2028 -2.19311 -1.22204 5.02008 -2.12109 -1.17055 5.02008 -2.06072 -1.12653 5.04542 -1.90936 -1.01707 4.82349 -1.96123 -1.05484 5.15594 -1.82137 -0.954485 4.9466 -1.77163 -0.918076 4.99307 -1.75962 -0.910574 5.16979 -1.70893 -0.873696 5.22455 -1.63303 -0.818522 5.19296 -1.59106 -0.788414 5.28355 -1.54428 -0.754509 5.36397 -1.46055 -0.693977 5.28941 -1.41962 -0.664633 5.40626 -1.36994 -0.62921 5.49353 -1.3242 -0.596622 5.60925 -1.44968 -0.68782 6.79263 -1.35936 -0.622135 6.7532 -1.27583 -0.562537 6.76099 -1.17756 -0.491475 6.63844 -1.03962 -0.392207 6.10685 -1.03018 -0.386108 6.80336 -1.22238 -0.526493 10.3678 -1.05169 -0.401764 9.76375 -0.944263 -0.325732 10.1337 -0.805202 -0.224997 9.85227 -0.686252 -0.139471 10.1974 -0.536711 -0.030598 7.10026 -2.02315 -1.16512 -0.983584 -2.07291 -1.20395 -0.977971 -2.12845 -1.24642 -0.977821 -2.17823 -1.2851 -0.969011 -2.24149 -1.33219 -0.971884 -2.30464 -1.38118 -0.972661 -2.37357 -1.43374 -0.977703 -2.43198 -1.4789 -0.967526 -2.50282 -1.53334 -0.967881 -2.58038 -1.59238 -0.971655 -2.65219 -1.64763 -0.966669 -2.74408 -1.71786 -0.976388 -2.81786 -1.77394 -0.965767 -2.90402 -1.84022 -0.96353 -3.0055 -1.91782 -0.968538 -3.11366 -2.0009 -0.97492 -3.21612 -2.07917 -0.972092 -3.33386 -2.16968 -0.974962 -3.45162 -2.25996 -0.973338 -3.58472 -2.36143 -0.976164 -3.71873 -2.46469 -0.973699 -3.86815 -2.57806 -0.974336 -4.02514 -2.69882 -0.973052 -4.19843 -2.83167 -0.973276 -4.38702 -2.9765 -0.973904 -4.59191 -3.13332 -0.974041 -4.80546 -3.29644 -0.969116 -5.05726 -3.48931 -0.971569 -5.33298 -3.70062 -0.972859 -5.62599 -3.92473 -0.968419 -5.96494 -4.18391 -0.968139 -6.35935 -4.48676 -0.971555 -6.77874 -4.80769 -0.965522 -7.26995 -5.18323 -0.961744 -7.81568 -5.60185 -0.951471 -8.44189 -6.08129 -0.936693 -9.22604 -6.68199 -0.929524 -10.2476 -7.46417 -0.935193 -11.6492 -8.53721 -0.962902 -13.6454 -10.0649 -1.02041 -18.3284 -13.6513 -0.947908 -29.2893 -22.0452 -0.873746 -29.6913 -22.3538 -0.25706 -29.7996 -22.4368 0.382854 -39.8811 -30.1618 8.89368 -37.8619 -28.6166 10.1835 -5.60554 -3.91199 4.00561 -5.3777 -3.73686 4.00329 -5.35603 -3.72054 4.12367 -5.22113 -3.61786 4.16889 -5.18986 -3.5943 4.28197 -5.08184 -3.51169 4.33953 -5.06882 -3.50163 4.46557 -5.00685 -3.45433 4.55493 -4.91034 -3.3803 4.61536 -4.80037 -3.29614 4.66145 -4.59345 -3.13736 4.61765 -4.57471 -3.1223 4.73646 -4.52229 -3.08261 4.82554 -4.48717 -3.05615 4.93189 -4.24752 -2.8722 4.83008 -4.34493 -2.94727 5.07267 -4.19263 -2.83079 5.05165 -4.26515 -2.88603 5.2795 -4.304 -2.91664 5.47772 -4.17287 -2.81546 5.47724 -3.73512 -2.4796 5.0833 -3.79317 -2.52525 5.30507 -3.77058 -2.50774 5.428 -3.76244 -2.50101 5.5737 -3.70327 -2.45642 5.65226 -3.80668 -2.5359 5.97504 -3.67737 -2.43687 5.95363 -3.24692 -2.10642 5.43937 -3.28975 -2.13943 5.67492 -3.16902 -2.04668 5.63845 -3.12716 -2.01516 5.73748 -2.94576 -1.87567 5.57883 -2.55815 -1.57898 5.00269 -2.44399 -1.49151 4.92859 -2.44158 -1.48974 5.08221 -2.3216 -1.39802 4.98581 -2.23533 -1.33213 4.95526 -2.17317 -1.28426 4.97521 -2.1178 -1.241 5.01136 -2.00923 -1.15916 4.91158 -2.03878 -1.18116 5.1708 -1.92638 -1.09518 5.04871 -1.7927 -0.992699 4.84924 -1.78943 -0.990302 5.03477 -1.79882 -0.996868 5.27733 -1.70952 -0.929019 5.20195 -1.59406 -0.840819 5.01989 -1.62097 -0.861315 5.36676 -1.54231 -0.800993 5.31431 -1.46943 -0.745191 5.27887 -1.81708 -1.01265 7.2221 -1.36934 -0.668131 5.41605 -1.30612 -0.620745 5.42482 -1.47112 -0.747327 6.79193 -1.38292 -0.680229 6.76333 -1.30451 -0.619914 6.79178 -1.18095 -0.525477 6.46298 -1.07092 -0.441104 6.17014 -1.01795 -0.399857 6.37058 -0.983033 -0.373493 6.8586 -1.11498 -0.476251 9.9767 -0.979372 -0.373051 9.78942 -0.873365 -0.291662 10.1882 -0.736345 -0.186575 9.83528 -0.629892 -0.105272 11.039 -2.01225 -1.22953 -0.98104 -2.06095 -1.26927 -0.974675 -2.11537 -1.31363 -0.973624 -2.17075 -1.35896 -0.970728 -2.23754 -1.41356 -0.97916 -2.29393 -1.45876 -0.972273 -2.36169 -1.51419 -0.976064 -2.41905 -1.56024 -0.964936 -2.50014 -1.62688 -0.976266 -2.56411 -1.67941 -0.96656 -2.64151 -1.74125 -0.966191 -2.72553 -1.80963 -0.968642 -2.80285 -1.87317 -0.962381 -2.90114 -1.95368 -0.969229 -3.00045 -2.03405 -0.972285 -3.09407 -2.10963 -0.966432 -3.20097 -2.19735 -0.966769 -3.32219 -2.29624 -0.972452 -3.45204 -2.40164 -0.977766 -3.57521 -2.50214 -0.973369 -3.72131 -2.62048 -0.976944 -3.86739 -2.73952 -0.974577 -4.02876 -2.87062 -0.974112 -4.20537 -3.01471 -0.974602 -4.39729 -3.17077 -0.975098 -4.60546 -3.33979 -0.974453 -4.82888 -3.52166 -0.971767 -5.07617 -3.72303 -0.968967 -5.36067 -3.95495 -0.970697 -5.68438 -4.21743 -0.974466 -6.03194 -4.50011 -0.972079 -6.44057 -4.83286 -0.974708 -6.86639 -5.18003 -0.964016 -7.39917 -5.61348 -0.965047 -7.94157 -6.05448 -0.944639 -8.61568 -6.60307 -0.931151 -9.42824 -7.26434 -0.917564 -10.1818 -7.87754 -0.856124 -12.3974 -9.67998 -1.00797 -14.3259 -11.2504 -1.0178 -17.8803 -14.1413 -1.14124 -18.9276 -14.9937 -0.852446 -18.9499 -15.0125 -0.437543 -18.9272 -14.9944 -0.0200804 -18.9696 -15.0286 0.393652 -18.9594 -15.0203 0.809521 -28.5995 -22.8654 1.34215 -28.5985 -22.865 1.97461 -39.9422 -32.0965 4.14667 -37.7561 -30.3195 6.50761 -36.7527 -29.5039 7.18765 -34.718 -27.8495 10.009 -35.1244 -28.1832 13.4156 -38.4381 -30.8803 15.528 -39.1006 -31.4202 16.7322 -5.13074 -3.77046 3.85458 -5.07083 -3.72222 3.94499 -5.11237 -3.756 4.10289 -5.20658 -3.83205 4.3018 -5.14764 -3.78462 4.39745 -5.10019 -3.74649 4.50149 -4.95328 -3.62606 4.52599 -4.88571 -3.57168 4.60963 -4.69377 -3.4148 4.58626 -4.58023 -3.32285 4.62337 -4.44279 -3.21074 4.63331 -4.42976 -3.20078 4.75725 -4.42159 -3.1938 4.88782 -4.42299 -3.19477 5.03153 -4.39177 -3.1702 5.14476 -4.29357 -3.08999 5.18626 -4.03345 -2.87798 5.03894 -4.01856 -2.86579 5.16518 -4.06785 -2.9065 5.37465 -4.10763 -2.93879 5.58054 -4.05058 -2.89287 5.66824 -3.91206 -2.78029 5.64592 -3.71796 -2.62149 5.53756 -3.80474 -2.69261 5.82669 -3.78893 -2.6802 5.97646 -3.25806 -2.24724 5.324 -3.2566 -2.24645 5.47936 -3.23408 -2.22784 5.60433 -3.07428 -2.09818 5.4963 -2.94998 -1.9972 5.43952 -2.90249 -1.95829 5.51879 -2.51595 -1.64383 4.93817 -2.45016 -1.58974 4.95763 -2.36796 -1.5234 4.94125 -2.31082 -1.47618 4.97412 -2.2334 -1.41393 4.96211 -2.1945 -1.38184 5.03566 -2.18927 -1.3775 5.19748 -1.9906 -1.21637 4.86786 -1.90839 -1.14861 4.81957 -1.88193 -1.1278 4.92363 -1.85366 -1.10388 5.02746 -1.89668 -1.13898 5.36234 -1.80571 -1.06583 5.2908 -1.73113 -1.00551 5.26336 -1.66527 -0.951438 5.2622 -1.59067 -0.890781 5.22142 -1.55182 -0.859375 5.32174 -1.49948 -0.816528 5.37351 -1.42579 -0.757165 5.32798 -1.37929 -0.718369 5.40626 -1.32113 -0.671292 5.43513 -1.49912 -0.817385 6.84928 -1.4083 -0.742497 6.79258 -1.33195 -0.681766 6.8319 -1.24204 -0.607639 6.76102 -1.09617 -0.488624 6.19325 -1.02259 -0.428854 6.17624 -1.01122 -0.420609 6.85304 -0.934005 -0.35776 6.89357 -1.02267 -0.431072 9.7039 -0.922599 -0.349975 10.0838 -0.791074 -0.242698 9.84222 -0.679791 -0.152676 10.3073 -0.534467 -0.0324527 7.06021 -1.95747 -1.2568 -0.990771 -1.99935 -1.2938 -0.978091 -2.0527 -1.33914 -0.977886 -2.10601 -1.3854 -0.975933 -2.16027 -1.43261 -0.971937 -2.22025 -1.48442 -0.972755 -2.28017 -1.53711 -0.971226 -2.34211 -1.58983 -0.967607 -2.41542 -1.65275 -0.974066 -2.48298 -1.71188 -0.971667 -2.55155 -1.77095 -0.966774 -2.63344 -1.84129 -0.970718 -2.70298 -1.90114 -0.960285 -2.79249 -1.97793 -0.963658 -2.88196 -2.05554 -0.963385 -2.9857 -2.14539 -0.969906 -3.07716 -2.22375 -0.9622 -3.18188 -2.31425 -0.960585 -3.32079 -2.43485 -0.978121 -3.43411 -2.53266 -0.971693 -3.56171 -2.64257 -0.969462 -3.71779 -2.77783 -0.978672 -3.86159 -2.9016 -0.973254 -4.02628 -3.04396 -0.973456 -4.19862 -3.19264 -0.97039 -4.40807 -3.37317 -0.977796 -4.61178 -3.54972 -0.972647 -4.83742 -3.7447 -0.968527 -5.0936 -3.96471 -0.966865 -5.38681 -4.21823 -0.968585 -5.71712 -4.50411 -0.97114 -6.07895 -4.81576 -0.969214 -6.49308 -5.17373 -0.96813 -6.96151 -5.57798 -0.964197 -7.48229 -6.02819 -0.953714 -8.05642 -6.52425 -0.933188 -8.79723 -7.16239 -0.924706 -9.20212 -7.51328 -0.812476 -10.2818 -8.44485 -0.80683 -12.8737 -10.6831 -0.99537 -18.266 -15.338 -1.03673 -28.6266 -24.2835 -0.921246 -29.0255 -24.6292 -0.28949 -28.9551 -24.5681 0.370246 -36.3172 -30.9271 3.51332 -36.4292 -31.0245 4.35287 -36.8686 -31.4043 6.08441 -36.9149 -31.4458 6.94182 -36.9001 -31.4331 8.6519 -31.446 -26.7253 9.7213 -32.6722 -27.7858 11.6306 -33.6664 -28.6447 13.5996 -32.7852 -27.8848 14.0753 -37.1843 -31.6839 16.7873 -37.9498 -32.346 18.0778 -4.9926 -3.88175 4.43443 -4.72008 -3.64645 4.35712 -4.47617 -3.43547 4.28945 -4.41926 -3.38691 4.36981 -4.45496 -3.4181 4.53253 -4.50124 -3.45724 4.70929 -4.40902 -3.37794 4.75991 -4.38268 -3.35565 4.87361 -4.29529 -3.27958 4.92557 -4.25461 -3.2451 5.02514 -4.1538 -3.15805 5.05972 -3.9517 -2.98366 4.97267 -3.89865 -2.93741 5.05171 -3.8723 -2.91521 5.16362 -3.77813 -2.83388 5.19213 -3.9258 -2.96112 5.53601 -3.82303 -2.87263 5.55681 -3.69059 -2.75862 5.53038 -3.55913 -2.6449 5.49915 -3.48401 -2.58083 5.54651 -3.22916 -2.35963 5.30799 -3.14827 -2.29039 5.33151 -3.13727 -2.28079 5.47077 -3.09568 -2.24461 5.56296 -2.95063 -2.12018 5.46841 -2.89562 -2.07255 5.53248 -2.58206 -1.8008 5.08938 -2.44173 -1.67935 4.9607 -2.3684 -1.61666 4.96247 -2.36699 -1.61494 5.11648 -2.23995 -1.50601 4.99435 -2.22706 -1.49447 5.13013 -2.16908 -1.44431 5.16055 -2.13797 -1.41739 5.26084 -1.95231 -1.25725 4.94741 -1.83286 -1.15355 4.78994 -1.84394 -1.16369 5.00293 -1.89739 -1.21012 5.36484 -1.81633 -1.14013 5.32224 -1.76696 -1.09817 5.38005 -1.65219 -0.998785 5.20184 -1.58939 -0.943951 5.19952 -1.53424 -0.89627 5.22404 -1.47816 -0.847591 5.24732 -1.43361 -0.809849 5.32693 -1.36883 -0.753654 5.30924 -1.3224 -0.71389 5.38686 -1.50758 -0.873565 6.79883 -1.42856 -0.805978 6.8114 -1.34759 -0.736328 6.80256 -1.27054 -0.669558 6.82127 -1.09968 -0.52213 6.0481 -1.0331 -0.464297 6.06118 -1.03834 -0.469201 6.85687 -0.960315 -0.401214 6.85851 -0.883216 -0.335392 6.87826 -0.962717 -0.406218 9.9091 -0.852878 -0.311447 10.1083 -0.723392 -0.199314 9.78523 -0.603385 -0.0959235 9.45927 -1.88564 -1.26891 -0.978617 -1.92646 -1.30689 -0.966782 -1.97769 -1.35417 -0.96777 -2.03564 -1.40612 -0.973776 -2.08783 -1.45426 -0.970822 -2.14568 -1.508 -0.972633 -2.20455 -1.56169 -0.972351 -2.27007 -1.621 -0.976137 -2.32419 -1.67086 -0.965 -2.39533 -1.73661 -0.970207 -2.46178 -1.79761 -0.966606 -2.54153 -1.86991 -0.972043 -2.6146 -1.93735 -0.968667 -2.68962 -2.00576 -0.962451 -2.77032 -2.07966 -0.958603 -2.86427 -2.16574 -0.961945 -2.95254 -2.24703 -0.956378 -3.06739 -2.35179 -0.966938 -3.16989 -2.44605 -0.96302 -3.28667 -2.55246 -0.964099 -3.42326 -2.67854 -0.973542 -3.54864 -2.79219 -0.968509 -3.68719 -2.91982 -0.966473 -3.84756 -3.06711 -0.970309 -4.00798 -3.21407 -0.967155 -4.18459 -3.37505 -0.964309 -4.38858 -3.56307 -0.967607 -4.59364 -3.75071 -0.96192 -4.84891 -3.98515 -0.969152 -5.10619 -4.22015 -0.964955 -5.39951 -4.48855 -0.963338 -5.72982 -4.79128 -0.961658 -6.10374 -5.13476 -0.959939 -6.52237 -5.51789 -0.955038 -7.01402 -5.96874 -0.952354 -7.54469 -6.45441 -0.936979 -8.22805 -7.08138 -0.935101 -8.60043 -7.42268 -0.830753 -9.41776 -8.17161 -0.799155 -11.106 -9.71918 -0.883823 -13.1797 -11.62 -0.947439 -9.10197 -7.88421 0.906436 -9.10163 -7.88409 1.11018 -9.09941 -7.88186 1.31384 -35.0246 -31.644 6.36833 -35.1762 -31.783 7.22551 -35.9802 -32.5211 8.22665 -30.1335 -27.1631 9.20743 -30.2972 -27.3136 9.9903 -32.444 -29.2847 14.6965 -31.9693 -28.85 15.3173 -31.2941 -28.2313 15.8261 -36.7511 -33.2348 19.4262 -36.5839 -33.0818 20.3221 -4.33658 -3.51893 4.19631 -4.86701 -4.00535 4.78162 -4.35069 -3.53153 4.46447 -4.37868 -3.55743 4.62327 -4.68465 -3.8382 5.05745 -4.62034 -3.77985 5.14408 -4.64175 -3.79948 5.32023 -4.19947 -3.39346 5.00026 -4.21611 -3.40841 5.1637 -4.07746 -3.28217 5.15362 -3.96262 -3.17739 5.16478 -3.87639 -3.09793 5.20565 -3.97693 -3.18943 5.48468 -3.88683 -3.10779 5.52436 -3.9007 -3.11978 5.70379 -3.75346 -2.98466 5.66019 -3.85215 -3.0754 5.97263 -3.72393 -2.95824 5.95393 -3.41542 -2.67629 5.64155 -3.37873 -2.64267 5.74856 -3.07019 -2.35884 5.39314 -3.02679 -2.31894 5.47714 -2.74097 -2.05672 5.11814 -2.56766 -1.8985 4.9426 -2.51274 -1.84805 4.9828 -2.4282 -1.7707 4.96309 -2.38472 -1.73089 5.02507 -2.32116 -1.67297 5.04353 -2.24999 -1.60751 5.04305 -2.20942 -1.56963 5.11001 -2.1487 -1.5147 5.13231 -2.09183 -1.46265 5.16193 -2.24838 -1.60629 5.77199 -2.01544 -1.39275 5.32516 -1.96241 -1.34421 5.36955 -2.12878 -1.49746 6.10078 -1.80463 -1.19929 5.28838 -1.75158 -1.15098 5.32798 -1.6602 -1.06628 5.22584 -1.59272 -1.00504 5.20552 -1.53677 -0.95373 5.22135 -1.47987 -0.901432 5.23574 -1.43932 -0.864431 5.32548 -1.37566 -0.806257 5.30859 -1.3371 -0.770509 5.4159 -1.28017 -0.718971 5.43513 -1.44951 -0.875576 6.84925 -1.37847 -0.810568 6.90035 -1.28806 -0.727238 6.81219 -1.22481 -0.669482 6.92868 -1.05136 -0.509851 6.05481 -0.994699 -0.458246 6.15644 -0.988383 -0.452366 6.89269 -0.911469 -0.381971 6.88359 -1.00378 -0.468116 9.82359 -0.895998 -0.369874 9.974 -0.780199 -0.263163 9.96214 -0.673397 -0.1669 10.4574 -0.546227 -0.0488085 9.49014 -1.83111 -1.29213 -0.987547 -1.86622 -1.32544 -0.9692 -1.91068 -1.36899 -0.963922 -1.96651 -1.42287 -0.971021 -2.01664 -1.47194 -0.96911 -2.06772 -1.52198 -0.965255 -2.12452 -1.57661 -0.966214 -2.18791 -1.63787 -0.971294 -2.23997 -1.68867 -0.9614 -2.30899 -1.75635 -0.967899 -2.3743 -1.81937 -0.965694 -2.43864 -1.8822 -0.960889 -2.52188 -1.96294 -0.970736 -2.58818 -2.02661 -0.960295 -2.66004 -2.09778 -0.952723 -2.75187 -2.18584 -0.958057 -2.837 -2.26904 -0.954478 -2.93541 -2.3644 -0.957191 -3.04138 -2.46726 -0.96058 -3.14165 -2.5653 -0.954661 -3.26846 -2.68771 -0.962622 -3.38299 -2.79862 -0.956256 -3.52394 -2.9358 -0.961773 -3.67246 -3.08035 -0.965071 -3.82856 -3.23224 -0.965651 -3.98565 -3.38484 -0.959093 -4.17012 -3.56454 -0.959879 -4.36318 -3.75152 -0.955552 -4.57705 -3.95886 -0.952251 -4.82588 -4.2007 -0.954573 -5.08987 -4.4572 -0.951059 -5.38985 -4.74806 -0.949076 -5.73237 -5.08067 -0.9486 -6.09664 -5.43522 -0.939167 -6.53947 -5.8651 -0.937316 -7.04662 -6.35793 -0.933057 -7.62667 -6.92111 -0.923675 -8.26448 -7.54026 -0.900475 -8.64139 -7.90655 -0.789115 -8.83958 -8.09996 -0.625406 -8.86578 -8.12461 -0.423504 -29.7358 -28.3947 -0.394686 -8.7621 -8.02612 1.00835 -8.7968 -8.0593 1.21032 -9.54595 -8.78678 1.44954 -9.54565 -8.78683 1.67011 -9.54348 -8.78476 1.8908 -9.53749 -8.77944 2.11164 -30.3018 -28.9485 5.39615 -28.7719 -27.4649 7.97858 -29.2635 -27.9441 8.8244 -30.6639 -29.3056 10.7403 -30.424 -29.0755 13.788 -30.7292 -29.3726 15.5462 -32.4817 -31.0761 18.1537 -4.72016 -4.10164 4.54268 -4.75373 -4.13528 4.71394 -4.77884 -4.15953 4.88229 -4.68254 -4.06553 4.94112 -4.45618 -3.84575 4.8701 -4.25069 -3.64589 4.80695 -4.28807 -3.68328 4.98808 -4.28283 -3.67797 5.12893 -4.21871 -3.61601 5.20777 -3.91345 -3.31894 5.00176 -3.85214 -3.25962 5.0712 -3.9599 -3.36446 5.35305 -3.758 -3.16904 5.24553 -3.74616 -3.15663 5.37986 -3.74664 -3.15692 5.53606 -3.6986 -3.11129 5.62882 -3.58697 -3.0024 5.62554 -3.5333 -2.94996 5.70739 -3.39404 -2.8149 5.65213 -3.30701 -2.73122 5.67597 -3.11355 -2.5422 5.51035 -2.95894 -2.39291 5.39981 -2.95941 -2.39386 5.56295 -2.59929 -2.04304 5.03945 -2.44933 -1.89782 4.89324 -2.33269 -1.78411 4.79914 -2.30841 -1.7599 4.89351 -2.29746 -1.74884 5.02189 -2.22835 -1.68247 5.02215 -2.25269 -1.70593 5.24563 -2.17501 -1.63098 5.22639 -2.10113 -1.55994 5.21363 -2.08075 -1.53934 5.3411 -2.52222 -1.96897 6.79954 -2.24612 -1.70122 6.24056 -2.08738 -1.54661 5.98992 -2.01358 -1.47489 5.99104 -1.90253 -1.36636 5.86012 -1.66223 -1.13291 5.23993 -1.59399 -1.06702 5.21127 -1.56219 -1.0355 5.32245 -1.47478 -0.9508 5.20497 -1.41132 -0.889014 5.18029 -1.3785 -0.858105 5.29811 -1.67256 -1.14466 7.13518 -1.5556 -1.03096 6.93966 -1.4511 -0.928296 6.77935 -1.386 -0.865657 6.85055 -1.33162 -0.812381 7.00876 -1.23071 -0.715808 6.8312 -1.08605 -0.573636 6.20612 -1.00421 -0.494651 6.06115 -1.01433 -0.504911 6.91645 -0.943537 -0.435886 6.96795 -0.861859 -0.356663 6.86833 -0.935064 -0.430099 9.85919 -0.833639 -0.331349 10.1083 -0.711564 -0.212641 9.78526 -0.596905 -0.10103 9.4092 -1.80399 -1.34384 -0.971012 -1.84739 -1.38837 -0.966581 -1.89644 -1.43852 -0.967513 -1.94551 -1.48858 -0.966548 -2.00017 -1.54524 -0.970499 -2.0492 -1.59612 -0.965789 -2.10018 -1.64801 -0.959038 -2.16612 -1.71671 -0.969473 -2.22835 -1.78072 -0.970905 -2.28496 -1.83895 -0.963776 -2.34817 -1.90379 -0.960367 -2.41698 -1.97513 -0.960076 -2.48581 -2.04635 -0.957088 -2.5566 -2.11853 -0.951061 -2.63865 -2.20282 -0.952916 -2.72725 -2.29461 -0.956345 -2.81022 -2.3806 -0.950913 -2.913 -2.48639 -0.956641 -3.0102 -2.58537 -0.95306 -3.11291 -2.69272 -0.9498 -3.23644 -2.81981 -0.955207 -3.35994 -2.94763 -0.955071 -3.49107 -3.08186 -0.953564 -3.64852 -3.24425 -0.961845 -3.79468 -3.39518 -0.955202 -3.9607 -3.56557 -0.952727 -4.14644 -3.75736 -0.953124 -4.34072 -3.95742 -0.94796 -4.5755 -4.19952 -0.952685 -4.81029 -4.44208 -0.946274 -5.08099 -4.72006 -0.942744 -5.39873 -5.0483 -0.944934 -5.73919 -5.39858 -0.939168 -6.10696 -5.77824 -0.926215 -6.58505 -6.27072 -0.929904 -7.11976 -6.8214 -0.926065 -7.73737 -7.45912 -0.917744 -8.26093 -7.99823 -0.855935 -8.8816 -8.63824 -0.789047 -10.4071 -10.2105 -0.861582 -27.137 -27.4555 -0.640238 -27.6407 -27.9742 0.00981383 -29.6464 -30.0427 0.667368 -34.4039 -34.9476 2.31302 -28.853 -29.2295 5.67197 -28.2468 -28.6059 6.9878 -28.9246 -29.3098 12.3573 -29.1025 -29.493 13.2048 -29.2748 -29.6712 14.0676 -31.235 -31.696 17.5464 -4.62806 -4.2588 4.09414 -4.45455 -4.07992 4.09199 -4.41717 -4.04065 4.19071 -4.42504 -4.05029 4.32921 -4.43776 -4.06291 4.47423 -4.62351 -4.25442 4.7822 -4.62299 -4.2541 4.92927 -4.20824 -3.82671 4.66925 -4.19069 -3.80858 4.79071 -4.21196 -3.82983 4.95413 -4.22372 -3.84267 5.11369 -4.22228 -3.8412 5.26251 -3.8423 -3.44978 4.9669 -3.77745 -3.38251 5.03066 -3.81094 -3.41833 5.21835 -3.65711 -3.2592 5.1656 -3.63107 -3.23195 5.27855 -3.5889 -3.18872 5.3705 -3.44733 -3.04231 5.31879 -3.40892 -3.00317 5.41392 -3.41504 -3.01022 5.58214 -3.34069 -2.93341 5.62466 -3.30706 -2.89889 5.7333 -3.21373 -2.80259 5.74124 -3.17728 -2.765 5.84775 -3.04603 -2.62908 5.77918 -2.64817 -2.21942 5.18291 -2.57656 -2.14526 5.19541 -2.44704 -2.01167 5.08199 -2.2824 -1.84125 4.87996 -2.23443 -1.79202 4.92409 -2.16457 -1.72101 4.91591 -2.19071 -1.74765 5.13813 -2.26724 -1.82646 5.50219 -2.13288 -1.68724 5.33486 -2.025 -1.57688 5.22435 -2.28616 -1.84676 6.1662 -2.24116 -1.80104 6.26444 -2.10768 -1.66328 6.08896 -2.0065 -1.55927 6.00015 -1.72523 -1.26862 5.27016 -1.67636 -1.21757 5.3096 -1.58453 -1.12275 5.18855 -1.53083 -1.06749 5.20578 -1.4838 -1.01932 5.25005 -1.41959 -0.952891 5.21693 -1.37828 -0.910783 5.2874 -1.31118 -0.84129 5.23172 -1.57862 -1.11897 7.03327 -1.49267 -1.03008 6.98166 -1.39902 -0.932731 6.869 -1.3216 -0.853693 6.85156 -1.19483 -0.722947 7.02742 -1.03491 -0.557646 6.20334 -0.96793 -0.48774 6.17628 -0.963553 -0.483987 6.93265 -0.887997 -0.406134 6.89364 -0.980957 -0.50544 9.97326 -0.873588 -0.394108 10.0041 -0.763204 -0.281211 10.0022 -0.667572 -0.183271 10.8273 -0.541991 -0.0520551 9.48022 -1.74399 -1.35836 -0.972729 -1.78533 -1.4038 -0.969041 -1.82762 -1.45022 -0.963708 -1.88027 -1.50692 -0.970748 -1.92722 -1.55881 -0.968878 -1.98077 -1.61735 -0.971728 -2.02869 -1.67011 -0.965917 -2.0832 -1.72951 -0.964625 -2.13773 -1.7888 -0.961136 -2.19786 -1.85464 -0.961463 -2.26365 -1.92602 -0.965457 -2.32469 -1.99366 -0.960595 -2.3914 -2.06682 -0.959 -2.45906 -2.14089 -0.954462 -2.53898 -2.22714 -0.95791 -2.6188 -2.31521 -0.957763 -2.69965 -2.40316 -0.954123 -2.7927 -2.50421 -0.956922 -2.89231 -2.61271 -0.960295 -2.97964 -2.70974 -0.94964 -3.09898 -2.83972 -0.957782 -3.21269 -2.96386 -0.955965 -3.33297 -3.09536 -0.953024 -3.46736 -3.24187 -0.952534 -3.63267 -3.42301 -0.965244 -3.78023 -3.58406 -0.958712 -3.94745 -3.76754 -0.955799 -4.13541 -3.97245 -0.955162 -4.32991 -4.18549 -0.948557 -4.56486 -4.44154 -0.950994 -4.8129 -4.71314 -0.947638 -5.09482 -5.02096 -0.945808 -5.41711 -5.37342 -0.94543 -5.76013 -5.74776 -0.936191 -6.17737 -6.20319 -0.934423 -6.64809 -6.71879 -0.928215 -7.20624 -7.329 -0.922886 -7.89313 -8.07961 -0.92214 -8.40829 -8.64257 -0.845886 -9.51134 -9.84863 -0.865391 -10.886 -11.3506 -0.876785 -29.157 -31.3217 0.291737 -29.5726 -31.7764 1.03319 -32.3664 -34.8311 2.685 -33.0351 -35.5631 3.56332 -27.1061 -29.086 5.87101 -27.9863 -30.0491 6.75553 -27.4281 -29.4391 7.35065 -28.0816 -30.158 11.9846 -28.8619 -31.0121 13.0859 -29.3075 -31.5021 15.7353 -4.41142 -4.27906 4.08926 -4.35055 -4.21316 4.17059 -4.29107 -4.14784 4.3834 -4.26225 -4.11665 4.49158 -4.17501 -4.02147 4.54479 -4.11605 -3.95687 4.62247 -4.07213 -3.90947 4.71552 -3.96226 -3.78943 4.73681 -3.94475 -3.77042 4.85593 -3.95176 -3.77842 5.00616 -3.73628 -3.54232 4.89332 -3.68482 -3.48625 4.97007 -3.70879 -3.51316 5.14386 -3.61498 -3.4091 5.16594 -3.51062 -3.29623 5.17083 -3.4809 -3.26313 5.27591 -3.49644 -3.28042 5.45149 -3.32603 -3.0947 5.34846 -3.33876 -3.10884 5.52339 -3.25805 -3.02032 5.55156 -3.27457 -3.03888 5.74311 -3.1967 -2.9533 5.77592 -3.12729 -2.87762 5.82167 -3.02485 -2.76507 5.80224 -2.82592 -2.54809 5.58721 -2.55322 -2.24987 5.20152 -2.48092 -2.1701 5.20494 -2.33667 -2.0127 5.04828 -2.24819 -1.91633 5.00292 -2.17964 -1.84028 4.99659 -2.16021 -1.81952 5.10813 -2.1247 -1.78144 5.18526 -2.0911 -1.74509 5.27038 -2.32188 -1.99779 6.09713 -2.24289 -1.91213 6.09009 -2.22183 -1.88779 6.25132 -2.1077 -1.76446 6.132 -1.80101 -1.42769 5.35043 -1.89472 -1.52991 5.88996 -1.73011 -1.351 5.53582 -1.60734 -1.21507 5.29619 -1.53285 -1.1346 5.2303 -1.45936 -1.05379 5.15238 -1.43916 -1.03171 5.30981 -1.37226 -0.959075 5.25697 -1.68513 -1.30249 7.16352 -1.61956 -1.23093 7.23198 -1.51956 -1.12188 7.10477 -1.39175 -0.981361 6.76972 -1.3558 -0.942824 7.01705 -1.29986 -0.881376 7.15614 -1.20442 -0.777085 6.97907 -1.05862 -0.617197 6.28523 -0.985012 -0.536724 6.18019 -0.988321 -0.540496 6.97614 -0.926702 -0.473587 7.1173 -0.839506 -0.378378 6.86844 -0.911479 -0.45981 9.93909 -0.811407 -0.351065 10.1084 -0.698869 -0.227448 9.85535 -0.589556 -0.107107 9.41926 -1.68313 -1.37079 -0.974043 -1.72334 -1.41821 -0.971051 -1.76363 -1.46456 -0.966611 -1.80951 -1.51753 -0.967585 -1.85534 -1.57141 -0.966612 -1.89653 -1.61956 -0.957082 -1.95268 -1.68457 -0.965836 -2.00513 -1.7449 -0.965586 -2.06783 -1.81741 -0.975913 -2.1156 -1.87291 -0.96476 -2.17361 -1.94056 -0.963883 -2.23259 -2.00915 -0.960364 -2.30282 -2.0899 -0.966025 -2.36276 -2.15929 -0.957165 -2.43391 -2.24179 -0.956638 -2.5106 -2.33177 -0.95828 -2.58832 -2.42163 -0.95643 -2.67818 -2.52559 -0.961168 -2.76242 -2.62375 -0.956746 -2.85881 -2.73595 -0.957914 -2.96182 -2.85457 -0.959106 -3.06574 -2.97502 -0.955408 -3.18177 -3.11041 -0.955253 -3.31097 -3.25977 -0.957794 -3.44669 -3.41743 -0.957964 -3.59553 -3.58997 -0.959082 -3.74435 -3.76315 -0.95286 -3.91945 -3.96533 -0.953279 -4.10103 -4.17666 -0.94818 -4.32099 -4.43192 -0.952867 -4.54849 -4.69525 -0.949491 -4.81435 -5.0033 -0.951456 -5.09427 -5.32782 -0.945086 -5.42466 -5.71186 -0.944401 -5.78979 -6.13482 -0.938106 -6.22502 -6.64049 -0.936575 -6.72029 -7.21375 -0.930278 -7.33805 -7.93125 -0.93254 -8.02891 -8.73269 -0.920399 -8.81157 -9.6402 -0.89238 -9.82913 -10.8209 -0.869753 -11.4316 -12.6803 -0.894556 -28.8109 -32.8406 -0.860519 -32.572 -37.2056 2.32307 -28.0129 -31.9209 5.08963 -28.854 -32.9007 9.08354 -28.6992 -32.7251 12.2067 -28.1322 -32.0682 13.5736 -4.42196 -4.55424 4.13551 -4.27129 -4.37919 4.14443 -4.18909 -4.28393 4.20542 -4.10121 -4.18273 4.25784 -4.21995 -4.31929 4.50013 -4.16774 -4.2596 4.58832 -4.1648 -4.25658 4.86754 -3.89664 -3.94575 4.7208 -3.71769 -3.73754 4.65626 -3.63919 -3.64641 4.69921 -3.58133 -3.57951 4.76395 -3.61837 -3.62277 4.94768 -3.63761 -3.64471 5.11495 -3.5854 -3.58458 5.1917 -3.61876 -3.62295 5.38853 -3.51578 -3.50404 5.39551 -3.44193 -3.4191 5.44054 -3.31362 -3.26907 5.39719 -3.23126 -3.17464 5.42107 -3.22891 -3.17188 5.57464 -3.1419 -3.07072 5.58701 -3.1358 -3.06371 5.74079 -3.05631 -2.97148 5.76426 -2.96552 -2.86583 5.76151 -2.86237 -2.74774 5.7315 -2.82433 -2.70262 5.82622 -2.481 -2.30436 5.26873 -2.38445 -2.19192 5.21392 -2.22098 -2.00126 4.99667 -2.19216 -1.96908 5.08437 -2.09461 -1.85498 5.00114 -2.07144 -1.82943 5.10365 -2.00878 -1.75554 5.1015 -2.03948 -1.79163 5.36111 -2.18826 -1.96508 5.98741 -2.13982 -1.90846 6.05871 -2.07622 -1.83516 6.08382 -1.82642 -1.54421 5.47898 -1.68135 -1.37659 5.18365 -1.65357 -1.34462 5.28857 -1.62584 -1.31221 5.40259 -1.52801 -1.19825 5.23537 -1.49078 -1.15521 5.30947 -1.41659 -1.06883 5.22157 -1.35849 -1.00131 5.19777 -1.32698 -0.964912 5.3065 -1.60755 -1.293 7.15932 -1.52885 -1.20196 7.1397 -1.37668 -1.02495 6.6412 -1.35709 -1.0021 6.97641 -1.29459 -0.929074 7.03767 -1.18984 -0.808002 6.76311 -1.0599 -0.657165 6.18898 -0.996161 -0.582841 6.15386 -1.00416 -0.591914 6.94974 -0.936786 -0.5145 6.97237 -0.867525 -0.433532 6.9633 -0.958133 -0.542259 10.1129 -0.856306 -0.424764 10.1937 -0.750457 -0.301583 10.1621 -0.658051 -0.19476 10.8873 -0.538754 -0.0553623 9.47029 -1.63173 -1.39154 -0.989823 -1.65789 -1.42401 -0.965455 -1.70076 -1.47693 -0.969116 -1.74457 -1.53083 -0.970933 -1.78934 -1.58568 -0.970807 -1.83777 -1.64603 -0.975738 -1.87891 -1.69513 -0.96516 -1.93288 -1.76295 -0.97256 -1.97857 -1.81949 -0.964647 -2.03457 -1.88721 -0.967559 -2.08123 -1.9446 -0.955505 -2.14273 -2.02073 -0.959538 -2.19959 -2.09114 -0.954814 -2.26771 -2.1737 -0.959072 -2.33573 -2.25811 -0.960134 -2.39911 -2.33679 -0.952539 -2.4737 -2.42856 -0.952577 -2.54925 -2.52122 -0.949174 -2.64154 -2.63452 -0.957071 -2.72361 -2.73545 -0.950696 -2.82244 -2.85696 -0.954524 -2.92217 -2.98029 -0.953461 -3.03407 -3.11758 -0.95609 -3.14688 -3.25665 -0.953131 -3.2718 -3.41062 -0.952715 -3.4033 -3.57188 -0.949777 -3.54687 -3.74896 -0.947735 -3.7091 -3.9484 -0.948911 -3.88436 -4.16459 -0.94854 -4.0783 -4.40301 -0.948789 -4.27873 -4.65049 -0.941924 -4.50441 -4.92765 -0.936254 -4.76826 -5.25247 -0.935076 -5.06288 -5.6152 -0.932819 -5.40132 -6.03179 -0.931679 -5.78454 -6.50313 -0.928016 -6.21151 -7.02995 -0.918181 -6.75232 -7.69461 -0.919571 -7.37514 -8.46117 -0.913938 -8.07346 -9.32182 -0.893116 -8.99935 -10.4606 -0.883909 -10.1201 -11.8402 -0.861622 -11.3994 -13.4151 -0.803744 -30.8499 -37.3579 0.194864 -30.7405 -37.2232 1.03484 -4.13102 -4.47471 4.07031 -4.13518 -4.47934 4.20428 -4.1103 -4.44928 4.31458 -4.12191 -4.46379 4.46051 -4.07742 -4.40927 4.55501 -3.88884 -4.17642 4.77267 -3.67316 -3.9109 4.66599 -3.60712 -3.82985 4.72317 -3.55606 -3.76695 4.79638 -3.43012 -3.61204 4.7734 -3.34903 -3.51341 4.80257 -3.32138 -3.47878 4.90066 -3.40883 -3.58724 5.16579 -3.33063 -3.49064 5.19795 -3.28796 -3.43871 5.28276 -3.27156 -3.41841 5.40892 -3.21392 -3.34766 5.47066 -3.19003 -3.31827 5.58911 -3.08466 -3.18765 5.56629 -3.05888 -3.15625 5.68255 -2.99466 -3.0778 5.72984 -2.93048 -2.99846 5.77488 -2.88878 -2.94731 5.86523 -2.77865 -2.81096 5.81082 -2.53237 -2.50797 5.45237 -2.48688 -2.45189 5.51627 -2.34189 -2.27302 5.34664 -2.3142 -2.23926 5.44747 -2.66129 -2.66798 6.50676 -2.03052 -1.89048 5.05666 -1.96057 -1.80336 5.02916 -2.04098 -1.90276 5.42775 -1.99547 -1.84632 5.47872 -2.10515 -1.98259 6.01862 -2.06344 -1.93152 6.10737 -1.72044 -1.50798 5.17087 -1.64843 -1.42026 5.11272 -1.6104 -1.37291 5.17159 -1.6723 -1.45023 5.62848 -1.51356 -1.25371 5.21206 -1.46703 -1.19637 5.23956 -1.41575 -1.13373 5.2469 -1.34554 -1.04766 5.15758 -1.29804 -0.988962 5.1709 -1.6874 -1.47076 7.61525 -1.52752 -1.27279 7.12558 -1.44149 -1.16669 7.03677 -1.30398 -0.997782 6.57483 -1.30163 -0.994753 7.03656 -1.22018 -0.895323 6.94015 -1.06211 -0.699224 6.11234 -1.01006 -0.635712 6.17661 -0.949377 -0.56113 6.15038 -0.951686 -0.563823 6.92645 -0.892301 -0.491006 7.02776 -0.824213 -0.406633 7.0079 -0.886956 -0.488463 10.019 -0.793358 -0.372595 10.1981 -0.68736 -0.24287 9.99526 -0.582144 -0.112664 9.39935 -1.59627 -1.43239 -0.966764 -1.63337 -1.48164 -0.963963 -1.67612 -1.53651 -0.966726 -1.71782 -1.59224 -0.967639 -1.76054 -1.64794 -0.966757 -1.80426 -1.7036 -0.963981 -1.85153 -1.76674 -0.965864 -1.89515 -1.82421 -0.959193 -1.94903 -1.89387 -0.963299 -1.99827 -1.9578 -0.958647 -2.05205 -2.02921 -0.957859 -2.10226 -2.09398 -0.948666 -2.1626 -2.17286 -0.948752 -2.22296 -2.25159 -0.945942 -2.28328 -2.33119 -0.940285 -2.36033 -2.4315 -0.947727 -2.43735 -2.53263 -0.951424 -2.51073 -2.62808 -0.946168 -2.59426 -2.73749 -0.947094 -2.6843 -2.85534 -0.948544 -2.76877 -2.96638 -0.940785 -2.87093 -3.09901 -0.942182 -2.98415 -3.24751 -0.94687 -3.10388 -3.40434 -0.949685 -3.21905 -3.55436 -0.942295 -3.3629 -3.74288 -0.947901 -3.50119 -3.92447 -0.9422 -3.6581 -4.12941 -0.939467 -3.82709 -4.35005 -0.935133 -4.01464 -4.59488 -0.931022 -4.23742 -4.88637 -0.934739 -4.4556 -5.17181 -0.923407 -4.72112 -5.51876 -0.921449 -5.01723 -5.90656 -0.917163 -5.34957 -6.34157 -0.910472 -5.74878 -6.86312 -0.908936 -6.20928 -7.46449 -0.904943 -6.7421 -8.16229 -0.896639 -7.39659 -9.01804 -0.891307 -8.15414 -10.0088 -0.873843 -9.06396 -11.1988 -0.845788 -10.4221 -12.9752 -0.849149 -11.5586 -14.4617 -0.739883 -30.2844 -38.9549 1.46249 -3.65095 -4.12667 4.31382 -3.57502 -4.02652 4.35971 -3.51852 -3.95366 4.42505 -3.45181 -3.86683 4.47645 -3.43915 -3.85036 4.59066 -3.46848 -3.88785 4.75993 -3.37566 -3.76709 4.77617 -4.35557 -5.05017 6.24616 -3.25256 -3.605 4.88078 -3.36945 -3.75912 5.19143 -3.27103 -3.63076 5.19232 -3.24817 -3.60066 5.30581 -3.2197 -3.56356 5.41229 -3.13804 -3.4573 5.43279 -3.13663 -3.45553 5.5878 -3.14457 -3.4662 5.7663 -3.12547 -3.44127 5.90155 -2.97947 -3.24923 5.79386 -2.951 -3.21261 5.91077 -2.81511 -3.03596 5.80838 -2.74187 -2.93936 5.8266 -2.43777 -2.54157 5.32746 -2.40556 -2.49915 5.41517 -2.35837 -2.43744 5.46929 -2.36448 -2.4456 5.65569 -2.27894 -2.33408 5.61587 -1.99603 -1.96268 5.0352 -1.94972 -1.90203 5.06904 -1.9062 -1.8452 5.11016 -1.90572 -1.84566 5.2819 -1.90998 -1.85205 5.48153 -1.85153 -1.77509 5.4856 -2.20568 -2.23904 6.91434 -1.63515 -1.49112 5.1239 -1.5869 -1.42834 5.13772 -1.52647 -1.34915 5.10365 -1.52052 -1.34149 5.29084 -1.47043 -1.27577 5.30093 -1.41653 -1.20583 5.2905 -1.35799 -1.12808 5.24988 -1.32667 -1.0881 5.35033 -1.26243 -1.00304 5.26813 -1.40022 -1.1854 6.38815 -1.43542 -1.23214 7.00409 -1.28428 -1.03402 6.42715 -1.3103 -1.06864 7.074 -1.18455 -0.903222 6.59663 -1.10327 -0.796811 6.41887 -1.02947 -0.701069 6.27774 -0.965219 -0.616632 6.20328 -0.966346 -0.619704 6.92992 -0.90039 -0.532307 6.89278 -0.844117 -0.458735 7.01305 -0.953141 -0.606517 10.711 -0.841092 -0.459611 10.4832 -0.733585 -0.31865 10.222 -0.645405 -0.204017 10.8673 -0.525003 -0.0409126 7.08031 -1.5718 -1.48903 -0.965621 -1.60785 -1.53918 -0.961968 -1.64849 -1.59589 -0.963927 -1.68549 -1.64693 -0.957032 -1.73538 -1.71574 -0.969064 -1.777 -1.77324 -0.965284 -1.81856 -1.83164 -0.959556 -1.86473 -1.89656 -0.95844 -1.9119 -1.96143 -0.955031 -1.96362 -2.03379 -0.955585 -2.01629 -2.10709 -0.953597 -2.06898 -2.18026 -0.949111 -2.12721 -2.26095 -0.947793 -2.19006 -2.34806 -0.94909 -2.24921 -2.43051 -0.941784 -2.32309 -2.53356 -0.94747 -2.40254 -2.64402 -0.954426 -2.47282 -2.74119 -0.947263 -2.55873 -2.86091 -0.950899 -2.64006 -2.97388 -0.945328 -2.73244 -3.1028 -0.944545 -2.83139 -3.2391 -0.943138 -2.93479 -3.38465 -0.940701 -3.0559 -3.55165 -0.944825 -3.18242 -3.72887 -0.946076 -3.31097 -3.90588 -0.940441 -3.44954 -4.09953 -0.934847 -3.6122 -4.32503 -0.935141 -3.7859 -4.56711 -0.932782 -3.97716 -4.83329 -0.929844 -4.18602 -5.12351 -0.924927 -4.41341 -5.43873 -0.916188 -4.68597 -5.81824 -0.91507 -4.98265 -6.23001 -0.907903 -5.34301 -6.73125 -0.908231 -5.74406 -7.2888 -0.902127 -6.21529 -7.94483 -0.895203 -6.79193 -8.74583 -0.89199 -7.41569 -9.61381 -0.867143 -8.4053 -10.9889 -0.89283 -9.25837 -12.1748 -0.830787 -10.3849 -13.7412 -0.767179 -12.1763 -16.2433 7.51556 -3.5656 -4.26776 4.41883 -3.42412 -4.07122 4.38698 -3.3318 -3.94238 4.40502 -3.2774 -3.86786 4.46576 -3.21377 -3.77946 4.51216 -3.29671 -3.89487 4.75303 -3.85191 -4.66766 5.6613 -3.77257 -4.55784 5.71584 -3.40747 -4.04891 5.34036 -3.21116 -3.77559 5.19232 -3.2914 -3.88797 5.47071 -3.1619 -3.70741 5.41454 -3.06201 -3.56962 5.40155 -3.02163 -3.51289 5.48481 -2.99512 -3.47666 5.59622 -2.57283 -2.88914 4.95639 -2.93754 -3.39694 5.81832 -2.83949 -3.26098 5.7909 -2.83819 -3.25846 5.96129 -2.70851 -3.07826 5.85718 -2.63365 -2.97496 5.86667 -2.37459 -2.6146 5.43608 -2.29979 -2.50869 5.4177 -2.20803 -2.38289 5.35489 -2.25229 -2.4446 5.64031 -2.16811 -2.32665 5.59036 -1.9618 -2.03943 5.18508 -1.89896 -1.95124 5.1676 -1.87896 -1.92344 5.27889 -1.88129 -1.92814 5.46974 -1.76433 -1.7645 5.26985 -2.23347 -2.41935 7.1143 -1.67111 -1.63576 5.32495 -1.52783 -1.43584 4.97556 -1.50503 -1.40422 5.07947 -1.4879 -1.3796 5.21102 -1.46135 -1.34375 5.31475 -1.44234 -1.31808 5.46509 -1.35122 -1.19108 5.26575 -1.30135 -1.12051 5.25266 -1.26078 -1.06479 5.29512 -1.21552 -1.00225 5.30783 -1.37744 -1.22808 6.65212 -1.29376 -1.11308 6.50298 -1.24318 -1.04174 6.56496 -1.24739 -1.04923 7.08544 -1.11162 -0.859 6.44922 -1.05907 -0.786275 6.49642 -0.982693 -0.680327 6.29512 -0.920553 -0.593547 6.20983 -0.917051 -0.589817 6.92645 -0.856084 -0.504798 6.92824 -0.803925 -0.432044 7.09758 -0.865499 -0.521883 10.2085 -0.773312 -0.39349 10.2781 -0.676978 -0.259394 10.1951 -0.575853 -0.11781 9.40926 -1.514 -1.50001 -0.974234 -1.54434 -1.54547 -0.964069 -1.58292 -1.60311 -0.966771 -1.61786 -1.65507 -0.960719 -1.66205 -1.71923 -0.966838 -1.69695 -1.77202 -0.95724 -1.74568 -1.8436 -0.966025 -1.7862 -1.90289 -0.959345 -1.83484 -1.97624 -0.963336 -1.8799 -2.04294 -0.958823 -1.93051 -2.11717 -0.957976 -1.97654 -2.18469 -0.948822 -2.03625 -2.27385 -0.954605 -2.09137 -2.35627 -0.95168 -2.14746 -2.43962 -0.945913 -2.21822 -2.54456 -0.953188 -2.28541 -2.64282 -0.951559 -2.36623 -2.76355 -0.961422 -2.4298 -2.85595 -0.947244 -2.51155 -2.97832 -0.948721 -2.59526 -3.10159 -0.94566 -2.69456 -3.24829 -0.951251 -2.78375 -3.38064 -0.94277 -2.89861 -3.55143 -0.949873 -3.00985 -3.71646 -0.946424 -3.12661 -3.88972 -0.9404 -3.26546 -4.09481 -0.942355 -3.4043 -4.30049 -0.93627 -3.56519 -4.53886 -0.935317 -3.72701 -4.77882 -0.924879 -3.921 -5.06628 -0.92301 -4.138 -5.38722 -0.920934 -4.37798 -5.74253 -0.916403 -4.65559 -6.15444 -0.915019 -4.9728 -6.62388 -0.913244 -5.335 -7.16113 -0.909303 -5.75338 -7.77992 -0.90339 -6.24983 -8.51575 -0.89719 -6.85299 -9.40852 -0.891818 -7.49022 -10.3521 -0.858217 -8.53913 -11.9061 -0.881449 -9.54597 -13.3978 -0.830804 -11.0161 -15.5753 -0.796847 -3.92809 -5.08424 4.47599 -3.87503 -5.00554 4.56225 -3.33407 -4.2038 4.11263 -3.26063 -4.09508 4.15217 -3.19278 -3.99363 4.19374 -3.17924 -3.97449 4.30001 -3.16484 -3.95328 4.40649 -3.19845 -4.00294 4.57844 -3.26062 -4.09617 4.79622 -3.81768 -4.92201 5.72912 -3.67135 -4.70569 5.68561 -3.76608 -4.84532 5.9985 -3.14319 -3.922 5.19125 -3.00686 -3.72082 5.11769 -3.10801 -3.87057 5.43644 -3.08814 -3.8412 5.55936 -2.98881 -3.69375 5.53959 -2.8552 -3.49655 5.44968 -2.53944 -3.02882 4.99152 -2.53711 -3.02483 5.12951 -2.80853 -3.42785 5.84688 -2.49078 -2.95682 5.33159 -2.46259 -2.91439 5.42449 -2.86751 -3.51568 6.53289 -2.26545 -2.62183 5.27901 -2.20387 -2.53057 5.2847 -2.15799 -2.4634 5.32903 -2.15842 -2.46511 5.49702 -2.48608 -2.95195 6.59444 -1.95649 -2.16451 5.26537 -1.91155 -2.09781 5.30161 -1.84147 -1.99543 5.25804 -1.78909 -1.91774 5.26424 -1.72653 -1.82424 5.23288 -1.71961 -1.81471 5.39596 -1.66539 -1.73357 5.38839 -1.63987 -1.69755 5.497 -1.56054 -1.57895 5.38521 -1.52208 -1.52193 5.4363 -1.45851 -1.42687 5.37454 -1.3855 -1.31965 5.26337 -1.33115 -1.23906 5.22448 -1.29365 -1.18243 5.26888 -1.24858 -1.11626 5.274 -1.211 -1.06128 5.32559 -1.33833 -1.25101 6.44593 -1.27663 -1.15963 6.41337 -1.28447 -1.17133 6.89389 -1.18889 -1.03096 6.61502 -1.12629 -0.937279 6.56713 -1.07305 -0.858412 6.59581 -0.973353 -0.71005 6.12974 -0.945658 -0.669324 6.41095 -0.933469 -0.652882 6.98933 -0.873747 -0.562858 6.97224 -0.810015 -0.469121 6.88371 -0.75897 -0.394983 7.06209 -0.811806 -0.477374 10.4333 -0.729364 -0.356334 10.8714 -0.632756 -0.212261 10.8273 -0.521824 -0.0427185 7.0603 -1.4866 -1.55547 -0.972932 -1.51589 -1.60184 -0.962114 -1.55606 -1.6659 -0.971117 -1.59354 -1.72533 -0.97102 -1.63196 -1.78573 -0.969079 -1.67405 -1.85161 -0.971996 -1.71244 -1.91282 -0.96621 -1.75549 -1.97956 -0.964986 -1.79843 -2.04818 -0.961465 -1.84138 -2.11669 -0.955748 -1.88988 -2.19274 -0.953698 -1.9384 -2.26867 -0.94925 -1.99599 -2.35963 -0.953629 -2.0536 -2.45044 -0.954812 -2.11211 -2.54314 -0.952803 -2.17517 -2.64325 -0.95296 -2.24833 -2.75835 -0.959749 -2.31232 -2.86014 -0.952319 -2.3874 -2.97695 -0.951025 -2.46592 -3.10303 -0.950197 -2.55101 -3.23651 -0.949244 -2.64061 -3.37826 -0.947711 -2.7412 -3.53688 -0.949318 -2.84731 -3.70377 -0.94905 -2.96342 -3.88738 -0.950222 -3.08045 -4.0727 -0.944406 -3.20849 -4.27474 -0.938634 -3.35209 -4.50091 -0.935372 -3.50666 -4.74469 -0.929808 -3.67674 -5.01346 -0.924008 -3.87787 -5.3316 -0.925176 -4.09094 -5.66816 -0.9192 -4.34157 -6.06239 -0.918021 -4.62867 -6.51606 -0.91794 -4.94328 -7.01217 -0.910929 -5.33185 -7.62653 -0.912859 -5.76446 -8.30828 -0.905229 -6.27647 -9.11812 -0.895876 -6.96504 -10.2044 -0.905117 -7.59612 -11.2009 -0.854748 -8.7601 -13.0381 -0.884849 -3.67855 -5.02496 4.57853 -3.13673 -4.16904 4.0877 -3.11594 -4.13691 4.18417 -3.19252 -4.25702 4.40348 -3.16899 -4.2206 4.50235 -3.12717 -4.15416 4.57723 -3.67838 -5.0259 5.4877 -3.59343 -4.89232 5.5292 -3.68398 -5.03425 5.831 -3.67062 -5.01472 5.98571 -3.07955 -4.0801 5.20225 -2.9954 -3.94814 5.21218 -2.99496 -3.94672 5.36129 -2.96134 -3.89484 5.45606 -2.95354 -3.88222 5.59956 -2.85843 -3.7311 5.57818 -2.76785 -3.58814 5.55937 -2.41788 -3.03442 4.99335 -2.40073 -3.00899 5.10074 -2.40301 -3.01254 5.25419 -2.42741 -3.05075 5.46348 -2.29346 -2.83889 5.30507 -2.22019 -2.72422 5.28314 -2.14883 -2.61083 5.25777 -2.11798 -2.56196 5.33564 -2.07415 -2.49394 5.37962 -2.07651 -2.49734 5.55629 -2.14716 -2.6086 5.94652 -1.90779 -2.23115 5.39932 -1.81327 -2.08133 5.27146 -1.77593 -2.02237 5.32255 -1.75062 -1.98206 5.41664 -1.65779 -1.83631 5.26975 -1.64357 -1.81364 5.40589 -2.0262 -2.41925 7.14701 -1.93537 -2.27671 7.05894 -1.4334 -1.48141 5.13468 -1.41821 -1.45842 5.27592 -1.35401 -1.3558 5.18394 -1.29803 -1.268 5.12669 -1.6461 -1.81988 7.26117 -1.2307 -1.16133 5.23358 -1.19049 -1.09856 5.25687 -1.34132 -1.33835 6.52872 -1.27244 -1.2303 6.43951 -1.24091 -1.18081 6.60968 -1.16926 -1.06672 6.47723 -1.14997 -1.03736 6.78208 -1.09235 -0.945541 6.76329 -1.04879 -0.877933 6.9001 -0.952388 -0.724278 6.42343 -0.942074 -0.708413 6.97229 -0.886354 -0.620619 6.99594 -0.825805 -0.525037 6.92822 -0.776819 -0.447941 7.0677 -0.841108 -0.554124 10.3979 -0.754397 -0.418028 10.4678 -0.670051 -0.285307 10.7147 -0.568501 -0.122875 9.39934 -1.42076 -1.55119 -0.966929 -1.45163 -1.60407 -0.96411 -1.48709 -1.66353 -0.966903 -1.52609 -1.73047 -0.974755 -1.55893 -1.78422 -0.9669 -1.59889 -1.85203 -0.97091 -1.63528 -1.91317 -0.966117 -1.67161 -1.97522 -0.959476 -1.71614 -2.05033 -0.963555 -1.75344 -2.11323 -0.952672 -1.79888 -2.19017 -0.952061 -1.84526 -2.26804 -0.948906 -1.89167 -2.34579 -0.943155 -1.94615 -2.43851 -0.946227 -2.00619 -2.53869 -0.951568 -2.07426 -2.65477 -0.964184 -2.13516 -2.75765 -0.962089 -2.20061 -2.8679 -0.96166 -2.2579 -2.96494 -0.947414 -2.33335 -3.09195 -0.948924 -2.40978 -3.21978 -0.945793 -2.49519 -3.36443 -0.946995 -2.57609 -3.5013 -0.93864 -2.677 -3.67105 -0.941803 -2.77335 -3.834 -0.934661 -2.88873 -4.02965 -0.936835 -3.01063 -4.23353 -0.93534 -3.13695 -4.4475 -0.92947 -3.27877 -4.68658 -0.925661 -3.44053 -4.96013 -0.92518 -3.60329 -5.23423 -0.914366 -3.80603 -5.57554 -0.915503 -4.02319 -5.94353 -0.911406 -4.27233 -6.36264 -0.90799 -4.55588 -6.84199 -0.904317 -4.89135 -7.40687 -0.903354 -5.27216 -8.05048 -0.897786 -5.70495 -8.77913 -0.88494 -6.26844 -9.731 -0.885819 -6.93567 -10.8562 -0.877986 -7.79011 -12.2978 -0.873124 -8.63654 -13.7259 -0.808004 -3.50047 -5.07114 4.90621 -3.69158 -5.3944 5.31456 -3.46672 -5.01326 5.16178 -3.51457 -5.0952 5.3878 -3.43468 -4.9609 5.42963 -3.45068 -4.98768 5.61668 -3.00105 -4.22711 5.05519 -2.92559 -4.10118 5.07538 -2.88489 -4.03276 5.15125 -2.93736 -4.12214 5.39463 -2.90592 -4.06728 5.49134 -2.90175 -4.06149 5.64327 -2.36812 -3.1613 5.30649 -2.30355 -3.05299 5.30826 -2.26196 -2.98162 5.36166 -2.16072 -2.81191 5.26271 -2.15942 -2.80825 5.41552 -2.11038 -2.72647 5.44743 -2.48014 -3.35192 6.67278 -2.45968 -3.31772 6.83162 -2.01199 -2.55978 5.67461 -2.04186 -2.61079 5.95608 -1.9763 -2.50133 5.93938 -1.76488 -2.14294 5.40596 -1.7397 -2.10056 5.50145 -1.66217 -1.96945 5.40144 -1.61763 -1.89549 5.4228 -1.60721 -1.87712 5.57785 -1.57832 -1.82968 5.66981 -1.44548 -1.60464 5.29347 -1.37611 -1.48685 5.17746 -1.33525 -1.41765 5.18831 -1.27871 -1.32166 5.11334 -1.59051 -1.85152 7.08175 -1.52587 -1.7433 7.06149 -1.17817 -1.15308 5.25483 -1.12983 -1.07212 5.21048 -1.26056 -1.29341 6.42658 -1.21429 -1.21618 6.47131 -1.18019 -1.15798 6.61183 -1.12652 -1.06781 6.60511 -1.10647 -1.0349 6.9199 -1.08192 -0.9942 7.24485 -0.932487 -0.740707 6.14943 -0.928674 -0.734308 6.71754 -0.89584 -0.679717 7.00911 -0.834599 -0.57648 6.89276 -0.779975 -0.48384 6.85378 -0.740924 -0.41855 7.19162 -0.78565 -0.500419 10.5231 -0.706423 -0.365428 10.7614 -0.573388 -0.136214 7.09853 -0.51977 -0.044608 7.08033 -1.30462 -1.45028 -0.974894 -1.32718 -1.49207 -0.960757 -1.35704 -1.54501 -0.960333 -1.38585 -1.59881 -0.958457 -1.41931 -1.6582 -0.962242 -1.45365 -1.71955 -0.964134 -1.48702 -1.78074 -0.964125 -1.52139 -1.84191 -0.962421 -1.55571 -1.90399 -0.95877 -1.59457 -1.97359 -0.959781 -1.63238 -2.04403 -0.958643 -1.67221 -2.11447 -0.955214 -1.71105 -2.18475 -0.949684 -1.75797 -2.27004 -0.953876 -1.79871 -2.3422 -0.943459 -1.85013 -2.43581 -0.94807 -1.89892 -2.5238 -0.94383 -1.96745 -2.6483 -0.963844 -2.01722 -2.73703 -0.953066 -2.07047 -2.83411 -0.944401 -2.1373 -2.95465 -0.947478 -2.20415 -3.07499 -0.94636 -2.27191 -3.19717 -0.940951 -2.34417 -3.32767 -0.935861 -2.42541 -3.47496 -0.934804 -2.49861 -3.60704 -0.92003 -2.59885 -3.78787 -0.924945 -2.71258 -3.99383 -0.934811 -2.81023 -4.16862 -0.922187 -2.92935 -4.38539 -0.92104 -3.06397 -4.62729 -0.922053 -3.19946 -4.87178 -0.913833 -3.35745 -5.15808 -0.912 -3.53091 -5.47028 -0.907983 -3.72871 -5.82717 -0.905817 -3.94543 -6.21913 -0.900235 -4.18657 -6.65456 -0.891759 -4.49004 -7.20169 -0.895579 -4.80882 -7.77808 -0.884233 -5.19991 -8.48353 -0.879083 -5.6876 -9.36367 -0.880929 -6.1329 -10.1686 -0.834059 -6.77689 -11.3309 -0.812442 -7.78199 -13.1451 -0.835986 -25.5413 -45.2094 0.128035 -3.64436 -5.68397 4.17361 -3.58447 -5.57613 4.39374 -3.44896 -5.33175 4.38302 -3.40772 -5.25654 4.47388 -3.45252 -5.33772 4.67095 -3.49459 -5.4145 4.87242 -3.42424 -5.28899 4.93074 -2.96141 -4.45205 4.43685 -2.95997 -4.44959 4.5653 -2.95671 -4.44396 4.6947 -2.98243 -4.49182 4.87312 -2.90758 -4.35584 4.89431 -2.94612 -4.42517 5.10024 -3.28498 -5.03892 5.8375 -2.84163 -4.23762 5.21509 -2.79484 -4.15338 5.27891 -2.81893 -4.19614 5.47711 -2.79751 -4.15891 5.59485 -2.77528 -4.11862 5.71245 -2.5914 -3.78483 5.48436 -2.51638 -3.65018 5.47868 -2.53315 -3.68145 5.67726 -2.44278 -3.51689 5.62915 -2.12312 -2.93962 5.00882 -2.01348 -2.74117 4.87245 -2.06665 -2.83766 5.15512 -2.15896 -3.00554 5.56262 -2.05202 -2.8122 5.42759 -2.02242 -2.75929 5.50767 -1.99742 -2.7139 5.6034 -2.00067 -2.71982 5.79101 -1.993 -2.7062 5.95478 -1.94616 -2.62133 5.99084 -1.87192 -2.48748 5.92972 -1.8414 -2.43389 6.02239 -1.6613 -2.10638 5.53136 -1.57596 -1.953 5.38545 -1.59849 -1.99311 5.67544 -1.55425 -1.91417 5.69635 -1.50094 -1.81698 5.66986 -1.84034 -2.43283 7.55603 -1.29526 -1.44418 5.09024 -1.25002 -1.36258 5.06247 -1.21395 -1.29736 5.0796 -1.50663 -1.83042 7.08133 -1.45253 -1.73205 7.09783 -1.4186 -1.672 7.25578 -1.30649 -1.46746 6.8555 -1.31778 -1.48934 7.35723 -1.16656 -1.21589 6.58043 -1.18547 -1.25052 7.19828 -1.12479 -1.14123 7.144 -1.04547 -0.997525 6.87127 -0.967869 -0.856073 6.55539 -0.916275 -0.762819 6.51227 -0.895699 -0.727133 6.92274 -0.847028 -0.639788 6.96609 -0.798407 -0.551525 7.00779 -0.737195 -0.441857 6.77869 -0.804892 -0.569453 10.328 -0.728412 -0.432496 10.4478 -0.652286 -0.29322 10.6348 -0.543995 -0.0922546 7.09965 -1.26929 -1.48855 -0.960373 -1.29708 -1.54241 -0.960791 -1.32124 -1.59059 -0.952256 -1.35623 -1.65749 -0.96419 -1.38393 -1.71311 -0.959816 -1.41629 -1.7743 -0.960902 -1.45218 -1.84298 -0.967047 -1.48444 -1.90597 -0.964239 -1.51665 -1.96988 -0.959584 -1.55346 -2.04031 -0.959541 -1.59022 -2.11162 -0.957251 -1.62341 -2.17629 -0.946656 -1.66467 -2.25599 -0.946083 -1.70594 -2.33557 -0.943113 -1.75524 -2.43113 -0.949117 -1.79649 -2.51144 -0.940704 -1.85029 -2.61527 -0.946227 -1.90046 -2.71342 -0.942797 -1.95519 -2.81897 -0.941432 -2.02602 -2.95541 -0.956766 -2.07713 -3.05509 -0.942652 -2.14082 -3.17815 -0.939579 -2.21249 -3.31799 -0.941433 -2.28961 -3.46715 -0.942762 -2.36316 -3.6096 -0.934487 -2.44023 -3.76025 -0.925428 -2.53525 -3.94461 -0.926933 -2.63574 -4.13819 -0.925614 -2.74069 -4.34089 -0.920869 -2.8536 -4.56111 -0.915809 -2.98539 -4.81683 -0.915923 -3.11817 -5.07314 -0.906502 -3.2813 -5.39003 -0.908598 -3.45088 -5.7169 -0.901731 -3.63731 -6.0798 -0.893091 -3.865 -6.52187 -0.893315 -4.11158 -6.99982 -0.88608 -4.4084 -7.57435 -0.884302 -4.72853 -8.19483 -0.870489 -5.12124 -8.95638 -0.86188 -5.58747 -9.86063 -0.85019 -6.10934 -10.8727 -0.82111 -6.80075 -12.2114 -0.801093 -7.69382 -13.9423 -0.778393 -3.49956 -5.82285 4.12959 -3.43698 -5.70207 4.20322 -3.40325 -5.63577 4.30539 -3.35596 -5.54437 4.39168 -3.34015 -5.51422 4.51485 -3.35141 -5.53511 4.6733 -2.78664 -4.43991 4.06508 -2.74549 -4.36196 4.13027 -2.73602 -4.34202 4.23748 -2.77776 -4.42352 4.42427 -2.77897 -4.42703 4.5571 -2.69923 -4.2716 4.56013 -2.69502 -4.26509 4.68609 -2.69099 -4.25554 4.8128 -2.77237 -4.41572 5.09955 -3.26129 -5.36448 6.16039 -3.18154 -5.21065 6.19194 -2.71511 -4.30397 5.44172 -2.56579 -4.01555 5.29134 -2.52475 -3.93566 5.35554 -2.44758 -3.78636 5.33934 -2.4255 -3.74281 5.44206 -2.36187 -3.61928 5.44847 -2.32251 -3.54457 5.51131 -2.29866 -3.49707 5.61064 -1.98209 -2.88249 4.93748 -1.99874 -2.91522 5.12663 -1.9178 -2.75875 5.04832 -1.98063 -2.88031 5.38323 -1.90509 -2.7346 5.31694 -1.89381 -2.71255 5.44418 -1.89786 -2.7216 5.63023 -1.86581 -2.65903 5.69983 -1.79482 -2.5207 5.63187 -2.15405 -3.22002 7.15449 -2.09313 -3.10206 7.17317 -1.61426 -2.17023 5.50135 -1.57753 -2.10073 5.54331 -1.53729 -2.02194 5.5659 -1.50247 -1.95426 5.61384 -1.46945 -1.89031 5.66976 -1.4865 -1.923 5.98125 -1.71455 -2.36975 7.44136 -1.68636 -2.31517 7.61716 -1.56434 -2.07787 7.25868 -1.48146 -1.91568 7.09109 -1.42218 -1.80124 7.06138 -1.42961 -1.81665 7.48682 -1.33743 -1.63757 7.22424 -1.30111 -1.56637 7.36133 -1.1435 -1.26109 6.49069 -1.14934 -1.27265 6.97161 -1.09735 -1.17043 6.94687 -1.04703 -1.07499 6.94928 -0.969054 -0.921858 6.60559 -0.911202 -0.810488 6.45517 -0.902825 -0.795217 6.99444 -0.854459 -0.700272 6.98925 -0.803206 -0.601713 6.95237 -0.757634 -0.513188 7.00305 -0.703411 -0.407547 6.84268 -0.75962 -0.523498 10.6527 -0.682546 -0.373964 10.6616 -0.565038 -0.141222 7.08852 -0.51659 -0.0459096 7.05027 -1.23461 -1.53225 -0.953298 -1.26399 -1.59255 -0.960417 -1.29068 -1.64824 -0.958535 -1.31997 -1.71038 -0.962259 -1.35026 -1.77248 -0.964188 -1.38051 -1.8355 -0.96427 -1.41071 -1.89943 -0.962505 -1.44191 -1.96332 -0.958845 -1.47307 -2.02812 -0.953338 -1.51036 -2.10687 -0.958694 -1.54148 -2.17247 -0.949043 -1.57715 -2.24557 -0.943654 -1.61536 -2.32604 -0.942023 -1.66165 -2.42148 -0.949516 -1.70431 -2.51126 -0.948154 -1.74798 -2.60096 -0.943999 -1.79862 -2.70751 -0.947666 -1.84928 -2.8139 -0.947937 -1.9009 -2.92117 -0.944666 -1.96049 -3.04529 -0.947722 -2.01652 -3.16272 -0.941675 -2.08058 -3.29596 -0.941205 -2.15257 -3.44695 -0.945115 -2.22106 -3.59023 -0.939371 -2.29499 -3.74282 -0.932901 -2.38034 -3.92152 -0.933223 -2.47022 -4.10841 -0.931268 -2.57246 -4.32234 -0.933662 -2.66318 -4.51259 -0.917728 -2.78677 -4.77104 -0.922262 -2.90786 -5.0217 -0.91415 -3.03233 -5.28328 -0.899912 -3.20404 -5.64013 -0.9083 -3.37123 -5.98988 -0.90069 -3.56869 -6.4019 -0.898105 -3.78398 -6.85081 -0.889705 -4.04194 -7.38886 -0.887085 -4.33455 -8.00002 -0.88057 -4.67083 -8.70088 -0.870101 -5.072 -9.53804 -0.858916 -5.56296 -10.5632 -0.848623 -6.15803 -11.805 -0.832491 -6.96032 -13.4792 -0.82705 -8.01343 -15.6768 -0.817559 -8.9741 -17.6896 3.76774 -8.43551 -16.5662 3.9197 -9.08049 -17.915 5.59755 -9.17599 -18.1169 6.39429 -9.21265 -18.1944 6.79657 -3.27143 -5.79271 4.2771 -3.20045 -5.64425 4.33229 -3.17142 -5.58318 4.43609 -3.17088 -5.58308 4.57866 -2.75168 -4.70691 4.13974 -2.63948 -4.47326 4.10307 -2.67376 -4.54496 4.27641 -2.63744 -4.47004 4.34703 -2.62977 -4.45385 4.46172 -2.59617 -4.38395 4.53557 -2.60011 -4.39235 4.67403 -2.59964 -4.3907 4.80772 -2.61073 -4.41451 4.96772 -2.54767 -4.28229 4.98822 -2.50064 -4.18471 5.03767 -2.4661 -4.11377 5.11127 -2.88249 -4.98557 6.15925 -2.57077 -4.33238 5.64326 -2.39851 -3.97157 5.40795 -2.33174 -3.83327 5.40505 -2.27123 -3.70787 5.41265 -2.25194 -3.66822 5.52095 -2.13061 -3.41325 5.35713 -2.1301 -3.41343 5.51444 -2.07139 -3.29075 5.50975 -1.9759 -3.09125 5.39147 -1.89384 -2.91938 5.29879 -1.82784 -2.78244 5.24939 -1.79331 -2.70991 5.29438 -1.84493 -2.8184 5.63643 -1.85442 -2.83847 5.84963 -1.7265 -2.57008 5.56444 -1.68469 -2.48415 5.58769 -2.03778 -3.22305 7.1944 -1.96911 -3.08177 7.16833 -1.53517 -2.17099 5.53122 -1.50236 -2.10332 5.58145 -1.4696 -2.03471 5.63043 -1.47829 -2.05359 5.88662 -1.44465 -1.98352 5.94385 -1.69088 -2.50096 7.53749 -1.63222 -2.37746 7.52915 -1.53187 -2.16782 7.26602 -1.47853 -2.0561 7.26935 -1.41513 -1.92511 7.20421 -1.33633 -1.76038 7.01214 -1.32195 -1.73094 7.28441 -1.26312 -1.60717 7.2207 -1.15133 -1.374 6.69055 -1.19451 -1.4657 7.52172 -1.0963 -1.25942 7.05209 -1.03916 -1.13876 6.94827 -0.967121 -0.98897 6.64546 -0.91808 -0.885194 6.57496 -0.904075 -0.858418 7.01597 -0.855956 -0.758403 6.99201 -0.808763 -0.659034 6.95616 -0.766314 -0.569157 7.01767 -0.716155 -0.465243 6.90823 -0.771741 -0.588017 10.3381 -0.704614 -0.448652 10.5176 -0.634713 -0.302696 10.6448 -0.537699 -0.0948645 7.05967 -1.20687 -1.59251 -0.968376 -1.23514 -1.6547 -0.974494 -1.25978 -1.71121 -0.971558 -1.28437 -1.76865 -0.967075 -1.31361 -1.83165 -0.968052 -1.34174 -1.89649 -0.96713 -1.3673 -1.95474 -0.957606 -1.39904 -2.02598 -0.959795 -1.43168 -2.09916 -0.95969 -1.46686 -2.17972 -0.963743 -1.4934 -2.23866 -0.946782 -1.52955 -2.32006 -0.946294 -1.56665 -2.4024 -0.943263 -1.60977 -2.50059 -0.949298 -1.64938 -2.59111 -0.946479 -1.69696 -2.69857 -0.951885 -1.73848 -2.79091 -0.94298 -1.78603 -2.89904 -0.941645 -1.84156 -3.02402 -0.946836 -1.898 -3.15085 -0.947737 -1.95092 -3.27 -0.939683 -2.01436 -3.41335 -0.941614 -2.0822 -3.56697 -0.942965 -2.151 -3.72139 -0.939077 -2.22326 -3.88499 -0.933956 -2.31049 -4.0821 -0.939189 -2.39957 -4.28199 -0.937388 -2.48765 -4.48246 -0.928443 -2.59607 -4.72681 -0.930075 -2.70897 -4.98019 -0.926183 -2.81826 -5.22772 -0.909942 -2.97074 -5.57135 -0.917962 -3.10834 -5.88079 -0.902046 -3.29691 -6.30681 -0.909529 -3.45913 -6.67342 -0.883735 -3.70855 -7.23575 -0.895783 -3.95892 -7.8001 -0.886912 -4.25427 -8.46552 -0.878939 -4.60605 -9.25774 -0.871468 -4.9622 -10.0619 -0.836002 -5.46723 -11.2022 -0.824721 -6.10631 -12.6435 -0.813438 -7.03269 -14.7324 -0.827655 -8.23498 -17.444 -0.827371 -8.32877 -17.6642 3.554 -8.29258 -17.5844 3.8848 -8.35436 -17.7252 4.25482 -8.35449 -17.725 4.60373 -8.32717 -17.6644 4.94153 -8.59819 -18.2777 5.443 -8.34844 -17.7151 5.66259 -8.2285 -17.4441 5.94482 -8.0899 -17.1328 6.20747 -8.6579 -18.4147 6.97747 -7.57865 -15.9799 6.52101 -7.55742 -15.9337 6.84105 -8.84692 -18.8476 9.13229 -8.7429 -18.6132 9.44477 -8.47801 -18.0148 9.57918 -3.13627 -5.95531 4.25201 -3.05881 -5.78094 4.29585 -3.04594 -5.75193 4.42005 -2.9958 -5.64087 4.49478 -2.69179 -4.9543 4.19556 -2.67628 -4.91807 4.3001 -3.06167 -5.78934 5.03866 -3.03646 -5.73192 5.15413 -2.556 -4.64822 4.49769 -2.48824 -4.49404 4.51033 -2.49567 -4.51137 4.65512 -2.47922 -4.47412 4.75891 -2.4423 -4.39237 4.82509 -2.42148 -4.34421 4.92107 -2.42093 -4.3442 5.06184 -2.40718 -4.31256 5.17731 -2.96712 -5.57977 6.59734 -2.08506 -3.58629 4.72636 -2.07928 -3.5721 4.84334 -2.23846 -3.9331 5.38191 -2.22379 -3.90028 5.49983 -2.20825 -3.86539 5.61785 -1.94494 -3.27003 5.04654 -2.07056 -3.55516 5.55714 -1.98221 -3.35431 5.45456 -1.90162 -3.17514 5.36913 -1.7972 -2.93796 5.19097 -1.74779 -2.82709 5.1821 -1.69486 -2.70693 5.15387 -1.76556 -2.86818 5.56769 -1.74474 -2.82004 5.66336 -1.67046 -2.65136 5.55618 -1.64593 -2.59756 5.64018 -1.60274 -2.50037 5.64597 -1.88781 -3.14616 7.0859 -1.64751 -2.60353 6.24842 -1.60536 -2.5066 6.27063 -1.56576 -2.41806 6.30876 -1.42332 -2.09709 5.81241 -1.37744 -1.99323 5.78795 -1.63768 -2.58367 7.50385 -1.57764 -2.44838 7.46891 -1.53201 -2.34405 7.51461 -1.42613 -2.10527 7.16487 -1.39022 -2.02512 7.26066 -1.33817 -1.90758 7.24146 -1.2906 -1.80005 7.24827 -1.27459 -1.76445 7.52135 -1.13403 -1.44542 6.70589 -1.13969 -1.45941 7.17803 -1.11834 -1.41208 7.43835 -1.02811 -1.20589 6.95655 -0.960252 -1.0543 6.67476 -0.917027 -0.955879 6.64494 -0.898575 -0.914656 6.98774 -0.857211 -0.822083 7.02408 -0.812201 -0.719791 6.98918 -0.769935 -0.624322 7.00195 -0.727661 -0.529955 7.0329 -0.6719 -0.403507 6.62331 -0.728646 -0.539186 10.6627 -0.658793 -0.382533 10.6016 -0.556809 -0.144232 7.0785 -0.513536 -0.0472344 7.06027 -1.14921 -1.58502 -0.96849 -1.16926 -1.63498 -0.960542 -1.19548 -1.69802 -0.965905 -1.21806 -1.75538 -0.962314 -1.24524 -1.81931 -0.964334 -1.27137 -1.88408 -0.964404 -1.29746 -1.94977 -0.962627 -1.32455 -2.01542 -0.958955 -1.35165 -2.08098 -0.953485 -1.38477 -2.16249 -0.95888 -1.41537 -2.23639 -0.955524 -1.44586 -2.31218 -0.949971 -1.47736 -2.38792 -0.942124 -1.51395 -2.47848 -0.94379 -1.55503 -2.57748 -0.948371 -1.59253 -2.66981 -0.944148 -1.637 -2.77901 -0.947847 -1.67895 -2.88059 -0.942795 -1.73041 -3.00643 -0.949921 -1.77577 -3.11815 -0.942888 -1.83164 -3.25412 -0.946738 -1.88046 -3.37493 -0.936675 -1.94074 -3.52098 -0.936251 -2.00441 -3.67724 -0.935143 -2.06812 -3.83324 -0.928943 -2.14319 -4.01634 -0.929385 -2.22869 -4.22543 -0.935419 -2.30814 -4.41936 -0.926443 -2.40494 -4.65702 -0.928734 -2.51059 -4.9142 -0.929415 -2.61523 -5.17187 -0.920955 -2.72872 -5.44898 -0.909488 -2.87189 -5.79777 -0.91159 -3.01159 -6.13856 -0.898245 -3.18431 -6.56213 -0.895839 -3.36493 -7.00471 -0.882931 -3.58748 -7.54855 -0.878504 -3.84406 -8.17563 -0.872785 -4.13814 -8.89504 -0.862942 -4.50031 -9.78029 -0.857755 -4.86337 -10.669 -0.819663 -5.373 -11.9156 -0.802666 -6.02664 -13.514 -0.785327 -6.9821 -15.8509 -0.791489 -9.48117 -21.9697 1.8405 -9.48931 -21.9896 2.25665 -9.49482 -22.0033 2.6739 -9.49331 -22.0005 3.09109 -8.05536 -18.4873 3.81696 -8.01708 -18.3928 4.15716 -8.11854 -18.6436 4.92524 -8.01728 -18.3964 5.23447 -7.29899 -16.6386 5.1592 -7.28844 -16.6147 5.48439 -7.22812 -16.4682 5.77621 -7.27538 -16.5841 6.14668 -7.27628 -16.5872 6.48785 -6.13056 -13.7845 5.84654 -7.09877 -16.1549 7.0186 -6.19768 -13.9509 6.49352 -6.13897 -13.8081 6.73414 -6.03047 -13.5416 6.91851 -7.16988 -16.3324 8.49893 -8.28247 -19.0585 10.1779 -8.07358 -18.5466 10.3538 -8.85215 -20.4562 11.7902 -2.94319 -5.98643 4.29939 -2.8779 -5.82647 4.35078 -2.91511 -5.91724 4.54736 -2.90409 -5.89101 4.6784 -2.87903 -5.83084 4.78893 -2.86626 -5.80051 4.91947 -2.79571 -5.62713 4.9519 -2.7944 -5.62359 5.10212 -2.78253 -5.59514 5.23626 -2.3654 -4.57473 4.59417 -2.79131 -5.61686 5.577 -2.29815 -4.40899 4.86045 -2.33534 -4.50141 5.08445 -2.27073 -4.34409 5.08329 -2.26581 -4.33308 5.21815 -2.24341 -4.27787 5.31288 -1.96803 -3.60161 4.76038 -2.00973 -3.70333 5.00454 -1.92215 -3.49018 4.90826 -1.88292 -3.39511 4.93685 -1.81646 -3.23236 4.88127 -1.78342 -3.15126 4.91903 -1.73542 -3.03351 4.90881 -1.80715 -3.20877 5.28416 -2.04796 -3.7998 6.2584 -2.13466 -4.01579 6.76062 -2.09652 -3.9215 6.83541 -2.06181 -3.83773 6.9248 -1.68332 -2.90772 5.66106 -1.68906 -2.92294 5.86623 -1.9226 -3.49616 7.04879 -1.56835 -2.62578 5.72476 -1.51405 -2.49384 5.66962 -1.59934 -2.70559 6.27578 -1.54696 -2.57593 6.23767 -1.54138 -2.56268 6.43689 -1.42429 -2.27523 6.04387 -1.34164 -2.07247 5.80489 -1.5515 -2.58925 7.28699 -1.44229 -2.32147 6.9113 -1.50704 -2.48174 7.6403 -1.43328 -2.30165 7.48069 -1.34262 -2.07865 7.17528 -1.31332 -2.00655 7.29866 -1.29732 -1.96981 7.55427 -1.21004 -1.75507 7.2077 -1.11723 -1.52701 6.75918 -1.07086 -1.4128 6.70017 -1.09086 -1.46411 7.34697 -1.00674 -1.25724 6.88633 -0.952201 -1.12311 6.71344 -0.910222 -1.02019 6.67478 -0.89371 -0.979543 7.00829 -0.850836 -0.87522 6.97648 -0.812581 -0.780878 7.01181 -0.769681 -0.675734 6.95613 -0.725707 -0.569597 6.85855 -0.691179 -0.485867 7.00782 -0.617961 -0.307369 7.36191 -0.6162 -0.31061 10.6447 -0.532588 -0.0970702 7.06962 -1.09075 -1.57445 -0.96815 -1.11231 -1.63194 -0.968451 -1.1313 -1.68281 -0.959851 -1.15547 -1.74668 -0.964359 -1.177 -1.80494 -0.960016 -1.20113 -1.86965 -0.961178 -1.2262 -1.93532 -0.960396 -1.25123 -2.0019 -0.957767 -1.27628 -2.06839 -0.95324 -1.3038 -2.14328 -0.953321 -1.33233 -2.21812 -0.951207 -1.35729 -2.2863 -0.940588 -1.38932 -2.36947 -0.940288 -1.42031 -2.45345 -0.937438 -1.45479 -2.54583 -0.9378 -1.49022 -2.63912 -0.935319 -1.53069 -2.74817 -0.941003 -1.56604 -2.84316 -0.93243 -1.61096 -2.96144 -0.936585 -1.65578 -3.08151 -0.936846 -1.70156 -3.20246 -0.933165 -1.75327 -3.34109 -0.935156 -1.80501 -3.4795 -0.932553 -1.86362 -3.63659 -0.934277 -1.92319 -3.79448 -0.930661 -1.98522 -3.96149 -0.925909 -2.05514 -4.14715 -0.923491 -2.13194 -4.35133 -0.922303 -2.21121 -4.56453 -0.917782 -2.30523 -4.81506 -0.919822 -2.39925 -5.06615 -0.913122 -2.50111 -5.33666 -0.904012 -2.62616 -5.67032 -0.906347 -2.74518 -5.9887 -0.890977 -2.89185 -6.37946 -0.885823 -3.04191 -6.7809 -0.86915 -3.24119 -7.31159 -0.870634 -3.45427 -7.8797 -0.861548 -3.69578 -8.52451 -0.847551 -4.00273 -9.34536 -0.844799 -4.36675 -10.3159 -0.838219 -4.7937 -11.4553 -0.822496 -5.25013 -12.6722 -0.775201 -5.89097 -14.3834 -0.742806 -6.50191 -16.0129 -0.638559 -7.48015 -18.6237 -0.555963 -7.31214 -18.1767 0.161534 -7.34749 -18.2724 0.498148 -7.4992 -18.6801 0.835214 -7.83312 -19.5732 1.55704 -8.08086 -20.2344 1.95349 -8.23456 -20.6459 2.35871 -8.81645 -22.198 2.87663 -6.62344 -16.3484 2.68932 -6.49742 -16.0115 2.95623 -8.82828 -22.2344 4.137 -5.91798 -14.4651 3.31606 -5.69846 -13.8806 3.48763 -5.66109 -13.7828 3.73505 -6.19647 -15.2128 4.31311 -5.86035 -14.3156 4.39659 -5.76 -14.0483 4.60909 -5.73398 -13.9787 4.86784 -6.18832 -15.195 5.50786 -5.87462 -14.3555 5.54858 -5.78897 -14.127 5.76422 -6.62321 -16.3561 6.85284 -5.71698 -13.9367 6.27772 -5.68653 -13.8576 6.54023 -5.6155 -13.669 6.75725 -6.75831 -16.7214 8.40552 -6.58267 -16.2549 8.55631 -6.55166 -16.1718 8.8789 -7.53676 -18.8045 10.588 -7.37247 -18.3683 10.7896 -7.14074 -17.7491 10.8762 -7.4605 -18.6054 11.7976 -2.65253 -5.75648 4.92002 -2.74825 -6.01407 5.58504 -2.74527 -6.0057 5.74995 -2.1472 -4.41115 5.31955 -2.09817 -4.27883 5.33906 -2.06648 -4.19344 5.40412 -1.84526 -3.60241 4.91787 -1.84731 -3.6093 5.06428 -1.72508 -3.28263 4.82845 -1.70369 -3.2258 4.89656 -1.66573 -3.12551 4.91047 -1.71316 -3.25166 5.21507 -1.70222 -3.22323 5.32978 -1.92479 -3.8185 6.31765 -2.00975 -4.04812 6.84639 -1.68005 -3.16439 5.74012 -1.92205 -3.81309 6.92776 -1.57899 -2.89388 5.67153 -1.77316 -3.41578 6.72865 -1.51711 -2.72929 5.75942 -1.48272 -2.63674 5.7837 -1.45605 -2.56766 5.84954 -1.52313 -2.74665 6.40643 -1.51844 -2.73593 6.61649 -1.48233 -2.63942 6.65761 -1.51192 -2.71982 7.09413 -1.40654 -2.43834 6.71614 -1.4135 -2.45597 7.03586 -1.36505 -2.32811 7.00673 -1.43794 -2.52534 7.84953 -1.31397 -2.19269 7.26779 -1.27267 -2.08128 7.27947 -1.23479 -1.98135 7.32674 -1.20671 -1.90593 7.45806 -1.13441 -1.71195 7.1761 -1.06196 -1.51814 6.8504 -1.00982 -1.37833 6.69384 -0.985191 -1.31316 6.84506 -0.940092 -1.19271 6.75139 -0.905682 -1.10082 6.78252 -0.847669 -0.948277 7.0567 -0.807087 -0.837587 6.99432 -0.770005 -0.738816 6.99908 -0.731973 -0.639083 7.00191 -0.692106 -0.530724 6.89348 -0.656868 -0.436896 6.94234 -0.630592 -0.367513 7.43859 -0.58982 -0.260412 7.3845 -0.548583 -0.148255 7.08846 -0.511418 -0.0491124 7.06027 -1.03698 -1.56854 -0.975218 -1.05231 -1.6139 -0.960961 -1.07188 -1.67124 -0.960656 -1.08982 -1.72302 -0.951404 -1.11193 -1.78774 -0.955257 -1.134 -1.85337 -0.957362 -1.15708 -1.91897 -0.957572 -1.1801 -1.98548 -0.955936 -1.20308 -2.05289 -0.952452 -1.2286 -2.12772 -0.953624 -1.25154 -2.19594 -0.946195 -1.27803 -2.27161 -0.943126 -1.306 -2.35559 -0.943962 -1.33239 -2.43304 -0.9363 -1.3638 -2.5263 -0.938001 -1.39623 -2.61949 -0.937009 -1.43363 -2.72943 -0.944232 -1.4609 -2.80942 -0.926236 -1.50424 -2.93699 -0.937633 -1.54004 -3.04106 -0.929516 -1.58523 -3.17135 -0.93308 -1.62946 -3.30138 -0.932446 -1.67458 -3.43325 -0.927521 -1.72564 -3.58278 -0.927369 -1.78014 -3.74151 -0.926684 -1.83705 -3.91036 -0.924914 -1.89841 -4.08843 -0.921515 -1.96317 -4.27663 -0.916035 -2.0363 -4.49166 -0.915491 -2.11285 -4.71674 -0.911069 -2.19724 -4.9613 -0.905734 -2.28997 -5.23352 -0.901789 -2.38363 -5.50732 -0.88826 -2.51121 -5.8816 -0.897319 -2.64318 -6.26664 -0.89586 -2.77505 -6.65402 -0.88077 -2.93591 -7.12478 -0.873659 -3.05355 -7.46817 -0.818298 -3.184 -7.84825 -0.759104 -3.41201 -8.51734 -0.745429 -3.79501 -9.63506 -0.790779 -4.13624 -10.6349 -0.775105 -4.55584 -11.8629 -0.756165 -5.05636 -13.3269 -0.722985 -5.62158 -14.9817 -0.656961 -6.41671 -17.3065 -0.592149 -6.6923 -18.1139 0.0051703 -6.71272 -18.1748 0.337657 -6.80882 -18.4581 0.668028 -7.39627 -20.1799 1.75407 -7.53944 -20.5992 2.15044 -6.57646 -17.7831 2.32244 -6.06894 -16.2975 2.51452 -6.14295 -16.5154 2.8422 -5.99048 -16.0684 3.09263 -6.0346 -16.2006 3.41386 -5.42959 -14.4293 3.42214 -5.24862 -13.9032 3.59735 -5.3951 -14.3318 3.9509 -5.58346 -14.882 4.35014 -5.38033 -14.2899 4.49339 -5.4663 -14.5427 4.83885 -5.39718 -14.3396 5.06755 -5.35087 -14.2073 5.31212 -5.43104 -14.4409 5.67298 -5.3516 -14.2089 5.886 -5.48455 -14.6006 6.32001 -5.77207 -15.4443 6.94808 -5.55352 -14.805 7.01311 -5.47069 -14.5628 7.22525 -5.84563 -15.6597 8.03258 -6.14114 -16.5269 8.78441 -5.89943 -15.8212 8.80455 -5.76201 -15.4182 8.95474 -5.80222 -15.5372 9.37417 -5.92794 -15.9066 9.946 -7.0589 -19.2236 12.2708 -5.9634 -16.0205 12.8632 -5.84556 -15.6764 13.045 -2.5351 -5.96956 5.75738 -2.49948 -5.8676 5.84828 -2.47168 -5.78636 5.95569 -2.17919 -4.92798 5.37348 -2.10592 -4.71295 5.33249 -1.93231 -4.20423 5.00369 -1.9043 -4.12417 5.067 -1.84641 -3.95359 5.03811 -1.81675 -3.86701 5.08919 -1.82654 -3.89684 5.26782 -1.70759 -3.54868 5.0244 -1.66599 -3.4249 5.02236 -1.63197 -3.32632 5.04714 -1.64869 -3.37525 5.2535 -1.6972 -3.51869 5.59489 -1.80329 -3.83269 6.18724 -1.79183 -3.79787 6.32897 -1.6133 -3.27537 5.76704 -1.54749 -3.08239 5.65459 -1.53596 -3.04752 5.7771 -1.49244 -2.92151 5.75703 -1.45501 -2.81182 5.75916 -1.47447 -2.86973 6.05046 -1.4095 -2.67753 5.90331 -1.37453 -2.57744 5.91691 -1.47108 -2.85991 6.68788 -1.44398 -2.78271 6.77535 -1.37889 -2.59196 6.61906 -1.37187 -2.57006 6.82908 -1.32918 -2.44698 6.81166 -1.31521 -2.40598 6.99395 -1.27255 -2.2821 6.97249 -1.29864 -2.35881 7.49916 -1.22908 -2.15486 7.25974 -1.19613 -2.05672 7.31738 -1.19189 -2.04552 7.65868 -1.14135 -1.89937 7.57108 -1.06107 -1.66347 7.13401 -0.994659 -1.4686 6.7967 -0.965026 -1.38233 6.86172 -0.926617 -1.26983 6.81806 -0.916498 -1.24054 7.17312 -0.841564 -1.01916 7.1166 -0.799474 -0.897221 6.9961 -0.772722 -0.818235 7.16028 -0.728664 -0.691315 6.95605 -0.689099 -0.574862 6.78885 -0.660562 -0.492004 6.94804 -0.600509 -0.314846 7.3719 -0.56146 -0.201278 7.10692 -0.526417 -0.0997083 7.06959 -0.962497 -1.49223 -0.963204 -0.978464 -1.54313 -0.958789 -0.996025 -1.60045 -0.960676 -1.01353 -1.6587 -0.961014 -1.02947 -1.7104 -0.952555 -1.04958 -1.77504 -0.9573 -1.07058 -1.84165 -0.960151 -1.0906 -1.90811 -0.961202 -1.11162 -1.97454 -0.960458 -1.13001 -2.03537 -0.951063 -1.15353 -2.11013 -0.953327 -1.17953 -2.19327 -0.959899 -1.19783 -2.25582 -0.944912 -1.22226 -2.33232 -0.940789 -1.24818 -2.41712 -0.94047 -1.27506 -2.50286 -0.937608 -1.30436 -2.59794 -0.938005 -1.33622 -2.70032 -0.941161 -1.3655 -2.7961 -0.935616 -1.39728 -2.90018 -0.932581 -1.43249 -3.0136 -0.931509 -1.47263 -3.14468 -0.937005 -1.5113 -3.26721 -0.933402 -1.55236 -3.39995 -0.930612 -1.60083 -3.55869 -0.937399 -1.64531 -3.70143 -0.930031 -1.69218 -3.85434 -0.922277 -1.75337 -4.05102 -0.930275 -1.80958 -4.23163 -0.923715 -1.87068 -4.43067 -0.918779 -1.93866 -4.64821 -0.914475 -2.01143 -4.88608 -0.909599 -2.09111 -5.14235 -0.903457 -2.17564 -5.41785 -0.894794 -2.28716 -5.7761 -0.903643 -2.4093 -6.17404 -0.9112 -2.49329 -6.44375 -0.867575 -2.56548 -6.67769 -0.804517 -2.70134 -7.11523 -0.784874 -2.85374 -7.61081 -0.76257 -3.03061 -8.18202 -0.738689 -3.29443 -9.03601 -0.748955 -3.63537 -10.138 -0.771392 -3.98651 -11.272 -0.758374 -4.39279 -12.588 -0.729105 -4.87626 -14.1525 -0.681648 -5.41688 -15.9001 -0.595674 -6.15273 -18.2802 -0.162416 -6.16606 -18.3257 0.170352 -6.19878 -18.4315 0.502674 -6.35375 -18.9339 0.83508 -6.62857 -19.8267 1.55185 -6.89361 -20.6823 1.95397 -6.13848 -18.2414 2.17564 -5.85666 -17.3338 2.43539 -5.1163 -14.9391 2.51217 -5.09609 -14.8734 2.78028 -5.13868 -15.0128 3.07535 -4.88434 -14.1915 3.22624 -4.93622 -14.3595 3.52156 -4.93932 -14.3722 3.79441 -4.9241 -14.3231 4.05651 -5.03138 -14.6711 4.41093 -5.05311 -14.7417 4.71114 -4.94227 -14.3816 4.89962 -4.97235 -14.4804 5.20988 -4.94701 -14.3997 5.47098 -5.03502 -14.6869 5.85366 -5.07951 -14.8308 6.20061 -5.1601 -15.0926 6.601 -5.14406 -15.042 6.89347 -5.05735 -14.764 7.09395 -5.08759 -14.8624 7.45076 -5.37854 -15.8047 8.20011 -5.39115 -15.8474 8.56659 -5.41223 -15.9167 8.95395 -5.33315 -15.6629 9.18102 -5.38965 -15.8461 9.64146 -5.26345 -15.4393 9.78147 -6.11044 -18.1838 11.7769 -1.7752 -4.13677 4.09141 -5.3907 -15.8627 13.748 -2.23487 -5.62978 5.6902 -1.76712 -4.11242 4.55143 -1.7666 -4.11111 4.67792 -1.78205 -4.16325 4.85852 -1.76213 -4.09911 4.93407 -1.7861 -4.17796 5.15288 -1.77295 -4.1359 5.25662 -1.62881 -3.66894 4.91057 -1.57 -3.47836 4.83906 -1.53232 -3.35589 4.83565 -1.52588 -3.33583 4.94884 -1.5474 -3.40606 5.17645 -1.58599 -3.52948 5.48497 -1.69986 -3.90021 6.13584 -1.51734 -3.30813 5.51593 -1.73901 -4.02794 6.70139 -1.46983 -3.15596 5.63407 -1.37619 -2.85072 5.34476 -1.35367 -2.7786 5.3962 -1.36339 -2.81203 5.62337 -1.49129 -3.22866 6.51831 -1.34478 -2.75324 5.89563 -1.30363 -2.61965 5.84934 -1.38077 -2.87093 6.53809 -1.44696 -3.08724 7.21077 -1.34541 -2.75688 6.79181 -1.29742 -2.60234 6.71479 -1.25972 -2.47953 6.69785 -1.25619 -2.46809 6.94402 -1.21584 -2.33874 6.91416 -1.18672 -2.24317 6.96529 -1.1935 -2.26749 7.35202 -1.15061 -2.12915 7.29811 -1.20142 -2.29655 8.18964 -1.14744 -2.12172 8.04928 -1.07961 -1.90115 7.72253 -0.981453 -1.57975 6.96597 -0.950503 -1.4802 6.99389 -0.932629 -1.4225 7.20482 -0.90429 -1.3329 7.29809 -0.846304 -1.14404 6.89024 -0.829344 -1.09119 7.16599 -0.804725 -1.00969 7.32292 -0.768504 -0.893202 7.26132 -0.725055 -0.752645 6.98913 -0.694132 -0.651335 6.99193 -0.657615 -0.533093 6.8039 -0.607082 -0.37157 7.36875 -0.574483 -0.264997 7.37451 -0.539359 -0.152213 7.09853 -0.508362 -0.0494237 7.0503 -0.912976 -1.48251 -0.968985 -0.925297 -1.52781 -0.957314 -0.939271 -1.57855 -0.952294 -0.955777 -1.63679 -0.953628 -0.971294 -1.69489 -0.953361 -0.989346 -1.76045 -0.95885 -1.00835 -1.82698 -0.962593 -1.02636 -1.89336 -0.964536 -1.04373 -1.95426 -0.957735 -1.06012 -2.01501 -0.949233 -1.08157 -2.0907 -0.95254 -1.10204 -2.16622 -0.953747 -1.12593 -2.25118 -0.959115 -1.14324 -2.31363 -0.943226 -1.1671 -2.39937 -0.94405 -1.19097 -2.48499 -0.942477 -1.21727 -2.57994 -0.944063 -1.24353 -2.67575 -0.942903 -1.27229 -2.77988 -0.944452 -1.30354 -2.89229 -0.948211 -1.33321 -2.99815 -0.943172 -1.36532 -3.11328 -0.939994 -1.39987 -3.23765 -0.938278 -1.4394 -3.37866 -0.942379 -1.47885 -3.52144 -0.941787 -1.51826 -3.665 -0.936651 -1.56106 -3.81878 -0.931332 -1.6088 -3.99008 -0.929384 -1.66136 -4.18085 -0.92991 -1.71981 -4.39011 -0.931964 -1.77575 -4.59166 -0.923268 -1.83411 -4.80323 -0.911389 -1.90322 -5.05189 -0.906058 -1.98061 -5.3292 -0.902068 -2.07845 -5.68172 -0.913318 -2.15335 -5.9517 -0.886045 -2.20037 -6.12174 -0.819175 -2.30983 -6.51501 -0.808861 -2.42175 -6.91791 -0.787175 -2.55506 -7.39752 -0.769446 -2.69904 -7.91646 -0.743034 -2.8907 -8.60659 -0.732702 -3.16939 -9.61154 -0.755037 -3.47034 -10.6969 -0.753917 -3.80683 -11.9078 -0.732009 -4.19676 -13.3125 -0.691055 -4.62466 -14.8532 -0.614195 -5.21785 -16.9895 -0.535903 -5.85392 -19.2816 -0.391719 -5.74306 -18.8833 0.323022 -5.75533 -18.9303 0.664482 -4.99405 -16.1959 2.18183 -4.95381 -16.0481 2.46354 -4.79973 -15.4946 2.69631 -4.70813 -15.1671 2.93884 -4.9838 -16.1627 3.36391 -4.83467 -15.6256 3.57473 -4.7744 -15.4099 3.82609 -4.72903 -15.246 4.08181 -4.70334 -15.1549 4.34921 -4.67354 -15.0487 4.61189 -4.67916 -15.0706 4.90569 -4.52573 -14.5179 5.04327 -4.67074 -15.0414 5.48232 -4.66403 -15.0186 5.77159 -4.69448 -15.1291 6.10786 -4.58384 -14.7312 6.27024 -4.56308 -14.6582 6.54301 -4.89564 -15.8582 7.32424 -4.74869 -15.3293 7.43423 -4.72317 -15.2364 7.71866 -4.83456 -15.6408 8.23373 -4.94032 -16.0232 8.76127 -4.87925 -15.8037 9.00633 -4.99335 -16.2163 9.58217 -5.17103 -16.8608 10.3114 -5.15213 -16.7948 10.6687 -5.14578 -16.7711 11.0565 -5.51892 -18.1197 12.3069 -5.37847 -17.6165 12.4318 -5.37797 -17.6153 12.8799 -1.7064 -4.3611 4.05524 -1.67699 -4.2531 4.09355 -1.64496 -4.13836 4.12313 -4.95111 -16.082 13.5841 -1.6422 -4.12987 4.35111 -1.64658 -4.14739 4.48841 -1.65116 -4.16183 4.62727 -1.7385 -4.47843 5.04334 -1.67324 -4.24543 4.96997 -1.6471 -4.15014 5.0189 -1.63165 -4.09566 5.10732 -1.63703 -4.11484 5.27284 -1.62088 -4.05532 5.36111 -1.42188 -3.33706 4.71696 -1.42546 -3.35194 4.86605 -1.45071 -3.44441 5.11486 -1.46121 -3.47964 5.30687 -1.45739 -3.46743 5.44696 -1.41537 -3.31543 5.40668 -1.42325 -3.34493 5.60974 -1.32784 -3.00102 5.28929 -1.23738 -2.67459 4.96617 -1.25857 -2.75264 5.23782 -1.29236 -2.87523 5.59739 -1.2795 -2.82825 5.69968 -1.35843 -3.11594 6.38461 -1.36656 -3.14503 6.65673 -1.34621 -3.07264 6.75651 -1.27147 -2.80323 6.47576 -1.35334 -3.10029 7.31883 -1.20478 -2.56341 6.45703 -1.19963 -2.5437 6.66575 -1.22123 -2.62463 7.12216 -1.16569 -2.42323 6.92935 -1.13701 -2.31952 6.96305 -1.10669 -2.20871 6.9761 -1.10996 -2.22371 7.34417 -1.14214 -2.34233 8.06431 -1.12376 -2.27649 8.27684 -1.0188 -1.89815 7.44662 -0.953737 -1.6592 7.00891 -0.955662 -1.66783 7.46308 -0.938107 -1.60552 7.6864 -0.888023 -1.42554 7.4123 -0.855029 -1.30738 7.38825 -0.823774 -1.19449 7.38147 -0.80216 -1.11463 7.56951 -0.761285 -0.967005 7.3418 -0.718447 -0.813314 7.01169 -0.688828 -0.704465 6.96595 -0.655373 -0.586377 6.79873 -0.724241 -0.849582 11.0923 -0.682194 -0.699068 11.3854 -0.581118 -0.320191 7.36187 -0.549238 -0.204051 7.09682 -0.520244 -0.101328 7.04968 -0.872253 -1.51047 -0.955539 -0.88675 -1.56869 -0.958865 -0.901256 -1.62683 -0.960792 -0.914123 -1.67942 -0.953672 -0.930174 -1.7449 -0.960052 -0.943059 -1.79734 -0.950136 -0.960008 -1.86472 -0.953125 -0.975969 -1.93195 -0.954412 -0.99447 -2.0066 -0.960656 -1.0098 -2.06824 -0.951302 -1.02668 -2.13725 -0.946901 -1.04603 -2.21466 -0.947107 -1.06693 -2.2994 -0.951466 -1.08372 -2.3701 -0.940973 -1.10553 -2.45666 -0.940643 -1.12877 -2.55251 -0.943668 -1.15055 -2.63981 -0.938194 -1.17376 -2.73638 -0.935677 -1.20047 -2.84132 -0.935871 -1.22607 -2.94803 -0.932768 -1.25418 -3.06302 -0.931675 -1.28472 -3.18726 -0.932143 -1.32019 -3.32914 -0.938579 -1.35308 -3.46439 -0.935615 -1.39091 -3.61723 -0.93762 -1.4287 -3.77084 -0.934782 -1.4664 -3.92619 -0.926851 -1.51396 -4.11681 -0.930557 -1.56143 -4.30913 -0.927972 -1.61124 -4.5125 -0.922853 -1.66352 -4.72489 -0.914702 -1.72065 -4.95662 -0.906427 -1.78647 -5.22628 -0.903744 -1.86302 -5.53387 -0.904663 -1.89282 -5.65758 -0.834966 -1.96929 -5.9673 -0.818058 -2.05444 -6.31565 -0.801199 -2.15271 -6.71197 -0.78496 -2.26207 -7.157 -0.766586 -2.38984 -7.67846 -0.750062 -2.53066 -8.24945 -0.725268 -2.7324 -9.07022 -0.727678 -2.98252 -10.0847 -0.734048 -3.25822 -11.207 -0.720736 -3.57119 -12.4761 -0.687001 -3.92662 -13.922 -0.628385 -4.33197 -15.571 -0.538432 -4.79301 -17.4439 -0.407536 -5.18425 -19.0347 -0.192212 -6.03133 -22.4768 -0.00271729 -5.39913 -19.9167 2.26165 -4.60654 -16.6983 2.35939 -5.04414 -18.4804 2.83918 -5.24221 -19.2854 3.26975 -4.839 -17.6457 3.39882 -4.77132 -17.3719 3.68009 -4.32839 -15.5713 3.68922 -4.40071 -15.8674 4.03449 -6.13654 -22.9313 5.8128 -4.13945 -14.807 4.38609 -4.14092 -14.8142 4.66808 -4.66307 -16.94 5.51784 -4.1897 -15.0177 5.29458 -4.12751 -14.7655 5.50981 -4.01298 -14.2983 5.64807 -3.93376 -13.978 5.82179 -3.98047 -14.168 6.17239 -4.02213 -14.3424 6.52797 -4.22067 -15.1499 7.1516 -4.08669 -14.6041 7.23533 -4.08174 -14.5858 7.53673 -4.22951 -15.1879 8.13402 -4.19378 -15.0473 8.39724 -4.35861 -15.7196 9.07728 -4.29888 -15.477 9.30308 -4.70555 -17.1339 10.5874 -5.01935 -18.4148 11.7364 -4.98004 -18.2549 12.0809 -5.0118 -18.3869 12.611 -4.87367 -17.8273 12.7032 -4.8141 -17.5856 12.9941 -1.5861 -4.43289 4.13982 -1.54444 -4.26025 4.13187 -1.55603 -4.30849 4.28536 -1.54324 -4.25945 4.36833 -1.5372 -4.23201 4.46923 -1.56097 -4.33037 4.67839 -1.53456 -4.22256 4.71669 -1.59318 -4.4643 5.07038 -1.59193 -4.45925 5.21081 -1.55493 -4.30938 5.21456 -1.58282 -4.42522 5.48072 -1.54108 -4.25323 5.45968 -1.34895 -3.46862 4.76635 -1.31346 -3.32538 4.73958 -1.36982 -3.55747 5.14337 -1.35884 -3.51203 5.23711 -1.37707 -3.58808 5.48475 -1.36683 -3.54785 5.59557 -1.33472 -3.41594 5.58716 -1.29106 -3.23954 5.51114 -1.22787 -2.98201 5.30809 -1.18353 -2.79832 5.19618 -1.1945 -2.84458 5.42928 -1.16785 -2.73865 5.42922 -1.16178 -2.71358 5.56299 -1.24728 -3.06426 6.36082 -1.24622 -3.05974 6.57177 -1.20413 -2.88998 6.48516 -1.16952 -2.74776 6.43871 -1.14063 -2.62891 6.43352 -1.11654 -2.53232 6.47096 -1.12858 -2.58475 6.84323 -1.11867 -2.54296 7.02635 -1.08812 -2.41826 7.01569 -1.07563 -2.36934 7.19778 -1.04267 -2.23306 7.15511 -1.01353 -2.11941 7.16601 -0.978154 -1.97057 7.07037 -0.953292 -1.87059 7.11436 -0.920088 -1.73679 7.04158 -0.928598 -1.77413 7.59225 -0.908032 -1.69135 7.73938 -0.857301 -1.48396 7.37002 -0.837524 -1.40549 7.53237 -0.784929 -1.18816 7.01765 -0.799196 -1.24989 7.95246 -0.752401 -1.05639 7.51027 -0.719022 -0.920898 7.3503 -0.680287 -0.763478 6.97913 -0.652774 -0.650254 6.8827 -0.633234 -0.572982 7.14223 -0.682629 -0.788679 11.3387 -0.585696 -0.377304 7.36867 -0.558145 -0.268509 7.34455 -0.530192 -0.154166 7.08847 -0.505245 -0.0507369 7.04027 -0.826084 -1.51075 -0.976867 -0.834763 -1.55043 -0.957442 -0.845682 -1.60199 -0.952363 -0.859721 -1.66748 -0.961234 -0.871595 -1.71997 -0.953411 -0.885594 -1.78628 -0.958937 -0.897424 -1.83964 -0.948369 -0.911323 -1.90779 -0.950499 -0.927822 -1.98237 -0.957836 -0.941091 -2.04494 -0.949324 -0.957493 -2.12132 -0.952666 -0.972315 -2.19116 -0.94731 -0.988148 -2.26097 -0.94006 -1.00747 -2.3549 -0.949663 -1.02321 -2.42648 -0.938019 -1.04351 -2.52122 -0.942582 -1.06223 -2.60941 -0.938348 -1.0819 -2.69853 -0.93157 -1.10454 -2.8043 -0.933401 -1.12572 -2.90154 -0.926632 -1.15224 -3.02582 -0.93278 -1.1773 -3.14154 -0.92993 -1.20474 -3.2675 -0.928492 -1.23511 -3.41098 -0.932815 -1.26496 -3.54696 -0.927994 -1.2962 -3.69305 -0.923283 -1.33137 -3.85664 -0.92274 -1.36646 -4.02197 -0.917004 -1.40786 -4.2151 -0.917945 -1.45023 -4.40898 -0.912748 -1.5003 -4.64087 -0.916036 -1.54649 -4.85473 -0.904571 -1.60425 -5.12513 -0.906407 -1.645 -5.31435 -0.869891 -1.68336 -5.49394 -0.824123 -1.75069 -5.80541 -0.81338 -1.82189 -6.13591 -0.797516 -1.90172 -6.50602 -0.780753 -1.98924 -6.91456 -0.761041 -2.09648 -7.41085 -0.747335 -2.21384 -7.95556 -0.726896 -2.35615 -8.61732 -0.71035 -2.53597 -9.45328 -0.701863 -2.76664 -10.5244 -0.701413 -3.0084 -11.6458 -0.670215 -3.2852 -12.9339 -0.620098 -3.60675 -14.4272 -0.546421 -3.97063 -16.1168 -0.437085 -4.10715 -16.7539 -0.19284 -4.36731 -17.9626 0.0428949 -5.4161 -22.8441 2.23203 -5.3873 -22.7122 2.6319 -5.42806 -22.9051 3.05728 -5.29592 -22.2931 3.40397 -5.28585 -22.2487 3.80163 -5.42465 -22.8944 4.2987 -5.34879 -22.5449 4.6599 -5.34755 -22.5373 5.07234 -3.66682 -14.7298 3.93374 -3.67469 -14.7634 4.215 -3.66336 -14.7164 4.48038 -3.68047 -14.7969 4.77891 -3.72755 -15.0135 5.12011 -3.78621 -15.2885 5.48965 -4.06467 -16.5835 6.192 -3.76874 -15.21 6.06049 -3.54014 -14.1505 5.98912 -3.53145 -14.1095 6.25809 -3.58785 -14.3734 6.64902 -3.65606 -14.6922 7.07724 -4.39274 -18.123 8.87513 -3.78951 -15.3154 7.98053 -3.81615 -15.442 8.37129 -3.83735 -15.5424 8.75978 -3.80585 -15.3986 9.03152 -3.73916 -15.0867 9.21119 -3.98535 -16.2354 10.2117 -4.65573 -19.3609 12.4411 -4.22388 -17.3529 11.672 -4.1258 -16.895 11.8052 -4.13619 -16.9461 12.2631 -1.58602 -5.06511 4.49691 -1.43191 -4.34751 4.11624 -1.42502 -4.31731 4.21101 -1.44504 -4.41033 4.40201 -1.47996 -4.57521 4.65883 -1.44255 -4.39808 4.64552 -1.43329 -4.35758 4.7428 -1.45414 -4.45515 4.96435 -1.43947 -4.38715 5.04329 -1.4074 -4.23863 5.04597 -1.4528 -4.45052 5.39897 -1.42313 -4.31257 5.41407 -1.41943 -4.29831 5.55517 -1.4008 -4.21252 5.62384 -1.43449 -4.36908 5.96597 -1.24794 -3.50101 5.12221 -1.39963 -4.20915 6.13421 -1.40893 -4.25007 6.37176 -1.25235 -3.5201 5.61133 -1.21051 -3.32943 5.52178 -1.14515 -3.02169 5.25679 -1.12733 -2.93753 5.2937 -1.08866 -2.7599 5.18796 -1.07485 -2.69304 5.24492 -1.09668 -2.79704 5.58072 -1.07638 -2.70336 5.60426 -1.16445 -3.11723 6.52655 -1.12986 -2.957 6.45898 -1.11767 -2.90002 6.5816 -1.04392 -2.55574 6.13344 -1.02689 -2.47636 6.19621 -1.05374 -2.60642 6.72 -0.984727 -2.28182 6.24485 -0.962846 -2.18058 6.25721 -1.02137 -2.45611 7.22262 -0.948782 -2.11912 6.64925 -0.969824 -2.21584 7.23131 -0.941466 -2.08711 7.20371 -0.915719 -1.96575 7.19237 -0.890773 -1.84809 7.18832 -0.91039 -1.94425 7.94137 -0.865989 -1.7345 7.62722 -0.833672 -1.58331 7.50192 -0.798643 -1.42399 7.31475 -0.766224 -1.27102 7.12398 -0.772655 -1.30292 7.86243 -0.751777 -1.20944 8.02255 -0.724408 -1.08032 7.98371 -0.670625 -0.825986 7.02152 -0.647055 -0.716498 6.97581 -0.62435 -0.609681 6.93795 -0.606047 -0.527988 7.18704 -0.640539 -0.70707 11.3554 -0.562788 -0.325104 7.36183 -0.537018 -0.207832 7.10679 -0.515195 -0.103041 7.06962 -0.784545 -1.53566 -0.963467 -0.794401 -1.58819 -0.959035 -0.804266 -1.64066 -0.953303 -0.814666 -1.7005 -0.95382 -0.826075 -1.76031 -0.952742 -0.837492 -1.82006 -0.950266 -0.849389 -1.88813 -0.953289 -0.862295 -1.95618 -0.954518 -0.873562 -2.01868 -0.946999 -0.88643 -2.08754 -0.944583 -0.899249 -2.15732 -0.940419 -0.915085 -2.24287 -0.94721 -0.927869 -2.31344 -0.938901 -0.94461 -2.40083 -0.941102 -0.958834 -2.48061 -0.934651 -0.975545 -2.56875 -0.932009 -0.99275 -2.66511 -0.932568 -1.01085 -2.76338 -0.930135 -1.03045 -2.8699 -0.930508 -1.051 -2.97732 -0.927539 -1.07199 -3.09389 -0.926624 -1.09543 -3.21972 -0.927271 -1.12179 -3.36306 -0.933779 -1.14516 -3.49048 -0.926236 -1.17239 -3.63646 -0.924009 -1.20101 -3.79254 -0.921593 -1.23061 -3.94943 -0.914137 -1.26209 -4.12466 -0.910093 -1.29696 -4.31004 -0.904368 -1.33753 -4.53333 -0.907821 -1.38293 -4.77598 -0.91135 -1.42975 -5.02852 -0.910296 -1.44856 -5.13486 -0.847395 -1.48956 -5.3526 -0.819386 -1.54301 -5.64516 -0.808188 -1.60264 -5.96811 -0.795729 -1.66751 -6.32032 -0.780258 -1.74389 -6.73056 -0.767902 -1.82449 -7.17079 -0.748386 -1.92038 -7.68929 -0.731111 -2.02909 -8.27757 -0.709772 -2.16647 -9.02048 -0.697302 -2.32951 -9.90223 -0.681947 -2.53163 -10.9991 -0.668238 -2.74753 -12.1675 -0.625151 -2.99206 -13.493 -0.559174 -3.28574 -15.0832 -0.472431 -3.45674 -16.0086 -0.276451 -3.50187 -16.2537 -0.00612233 -3.79419 -17.8403 0.213112 -4.81323 -23.3705 2.87717 -4.81191 -23.3647 3.29461 -4.83008 -23.4677 3.72581 -4.66926 -22.5992 4.03209 -4.77139 -23.1556 4.52598 -4.76096 -23.1014 4.93798 -4.71056 -22.8281 5.30909 -3.46351 -16.073 4.33026 -3.1851 -14.5637 4.28777 -3.23031 -14.8107 4.62047 -3.23248 -14.8229 4.9028 -3.38375 -15.644 5.41676 -3.32238 -15.3114 5.6169 -3.31391 -15.2677 5.90004 -3.31979 -15.3027 6.21152 -3.1401 -14.3303 6.16496 -3.13703 -14.3131 6.44648 -3.17776 -14.5373 6.82794 -3.35814 -15.5168 7.54077 -3.34969 -15.474 7.84709 -3.37456 -15.6134 8.24099 -3.44441 -15.9929 8.7625 -3.43385 -15.9361 9.08527 -3.36099 -15.5422 9.23289 -3.74286 -17.6202 10.7344 -3.58345 -16.7573 10.6465 -3.56608 -16.665 10.9881 -3.62923 -17.0113 11.6064 -3.38019 -15.6568 11.1487 -1.46389 -5.24746 4.5343 -1.36153 -4.69114 4.28121 -1.34199 -4.58627 4.32912 -1.31574 -4.44149 4.34457 -1.30391 -4.376 4.4168 -1.30476 -4.38548 4.54993 -1.29681 -4.3394 4.63992 -1.32756 -4.508 4.91778 -1.28673 -4.28582 4.85801 -1.26709 -4.18226 4.89968 -1.27587 -4.22882 5.08355 -1.24335 -4.05285 5.05274 -1.31072 -4.42388 5.58066 -1.39375 -4.87335 6.22448 -1.32691 -4.50996 6.00772 -1.25467 -4.11693 5.73497 -1.35064 -4.64192 6.52982 -1.3228 -4.49018 6.54193 -1.30016 -4.3701 6.58941 -1.24924 -4.09419 6.42804 -1.15764 -3.59609 5.94507 -1.00858 -2.78014 4.96598 -0.983562 -2.64471 4.9158 -0.980733 -2.63207 5.04555 -1.01415 -2.8153 5.49643 -1.01445 -2.82013 5.68219 -1.00195 -2.74886 5.74874 -1.00006 -2.73986 5.92743 -1.03359 -2.92682 6.48502 -1.01564 -2.82835 6.52733 -0.965173 -2.55321 6.2097 -0.94719 -2.45452 6.23608 -0.929762 -2.36407 6.27888 -0.910192 -2.25735 6.28335 -0.902193 -2.21584 6.44275 -0.877214 -2.07855 6.36955 -0.858421 -1.97571 6.37751 -0.93099 -2.37553 7.82575 -0.937285 -2.41449 8.34116 -0.917871 -2.31116 8.45914 -0.875041 -2.07442 8.12503 -0.839842 -1.88336 7.91017 -0.796587 -1.64899 7.48747 -0.77396 -1.52526 7.46708 -0.743219 -1.35918 7.23941 -0.738099 -1.33426 7.67415 -0.723544 -1.25528 7.89342 -0.701748 -1.13655 7.91463 -0.667545 -0.95001 7.4689 -0.638038 -0.789631 7.10794 -0.616758 -0.672757 7.01179 -0.601511 -0.588172 7.22188 -0.580974 -0.48114 7.23134 -0.562373 -0.381406 7.3587 -0.542931 -0.272109 7.35453 -0.521087 -0.155626 7.0884 -0.502252 -0.0510598 7.05031 -0.742009 -1.5605 -0.949765 -0.751458 -1.61938 -0.952525 -0.761444 -1.68562 -0.961334 -0.768676 -1.73244 -0.946053 -0.778621 -1.79953 -0.951716 -0.787985 -1.86011 -0.948485 -0.79889 -1.92808 -0.950606 -0.810276 -2.00436 -0.957927 -0.820551 -2.06675 -0.949507 -0.831368 -2.13645 -0.946135 -0.84267 -2.21443 -0.947465 -0.854389 -2.28599 -0.940102 -0.867131 -2.37319 -0.943489 -0.880349 -2.45297 -0.938233 -0.894536 -2.54934 -0.942679 -0.906187 -2.62247 -0.926728 -0.922819 -2.72805 -0.931735 -0.937934 -2.82607 -0.927994 -0.954484 -2.93333 -0.92681 -0.972472 -3.04982 -0.927684 -0.991843 -3.17649 -0.930065 -1.01272 -3.31134 -0.933755 -1.03202 -3.43962 -0.928247 -1.05524 -3.58546 -0.928205 -1.07738 -3.733 -0.923466 -1.10197 -3.88972 -0.918591 -1.12795 -4.05652 -0.913027 -1.15676 -4.24268 -0.910129 -1.19131 -4.46577 -0.916959 -1.2243 -4.6822 -0.912594 -1.25834 -4.89835 -0.901241 -1.27556 -5.01396 -0.845182 -1.31378 -5.26032 -0.831163 -1.35343 -5.51654 -0.812061 -1.40154 -5.8309 -0.802057 -1.45491 -6.17454 -0.789641 -1.5139 -6.55759 -0.776016 -1.58236 -6.99945 -0.763854 -1.65597 -7.47231 -0.743286 -1.7409 -8.0231 -0.723248 -1.84229 -8.68232 -0.705173 -1.95837 -9.43034 -0.679905 -2.11965 -10.473 -0.675524 -2.28091 -11.5179 -0.63479 -2.47752 -12.7902 -0.58566 -2.69584 -14.2017 -0.506566 -2.86812 -15.3188 -0.352 -2.92248 -15.6749 -0.104886 -2.99076 -16.1158 0.149726 -3.51012 -19.476 0.31688 -5.33941 -31.3124 0.454818 -7.24824 -43.6604 1.01079 -7.20089 -43.3576 1.77651 -7.13666 -42.9523 2.52836 -3.96837 -22.4692 4.20121 -3.9606 -22.4199 4.59902 -3.97306 -22.501 5.02056 -2.99244 -16.1512 4.18123 -3.01186 -16.2777 4.50555 -2.93959 -15.8104 4.69791 -2.94092 -15.8207 4.99588 -2.83531 -15.1387 5.10886 -2.86624 -15.341 5.45557 -2.85282 -15.2626 5.72582 -2.86427 -15.3386 6.04719 -2.86934 -15.3705 6.35962 -2.85489 -15.2759 6.63028 -2.87852 -15.4345 6.9995 -2.85396 -15.2742 7.24876 -2.87839 -15.437 7.63481 -2.88622 -15.4914 7.98367 -2.82817 -15.1181 8.13773 -2.95441 -15.934 8.86855 -2.97316 -16.0599 9.28495 -2.93091 -15.7928 9.50152 -2.95711 -15.9632 9.95852 -1.33322 -5.41732 4.16672 -1.31737 -5.31863 4.23614 -1.29745 -5.18676 4.28182 -1.35569 -5.56861 4.66174 -1.31011 -5.27589 4.60293 -1.2038 -4.58095 4.24801 -1.20319 -4.58089 4.36956 -1.18308 -4.45099 4.39572 -1.16451 -4.32907 4.42456 -1.15589 -4.27732 4.50676 -1.18548 -4.46545 4.7939 -1.15869 -4.29499 4.78035 -1.15911 -4.2953 4.91583 -1.1316 -4.11945 4.88881 -1.15154 -4.25084 5.15549 -1.21309 -4.65325 5.71092 -1.2142 -4.66067 5.88589 -1.2022 -4.5823 5.97472 -1.14189 -4.19145 5.71301 -1.15391 -4.27144 5.975 -1.19823 -4.55989 6.50169 -1.20156 -4.58289 6.72908 -1.0658 -3.69843 5.79239 -1.075 -3.75847 6.0487 -0.925056 -2.78156 4.87625 -0.917312 -2.73132 4.94941 -0.907253 -2.66875 5.00536 -0.9325 -2.83618 5.42097 -0.941099 -2.88991 5.68238 -0.925978 -2.79349 5.70696 -0.911594 -2.70179 5.73827 -0.939319 -2.88385 6.26632 -0.941994 -2.90309 6.52837 -0.909902 -2.69606 6.35606 -0.875653 -2.47236 6.13317 -0.864977 -2.40515 6.22134 -0.852161 -2.32215 6.2813 -0.839337 -2.23922 6.33997 -0.830322 -2.17945 6.46203 -0.815915 -2.08897 6.50912 -0.872675 -2.46302 7.85135 -0.853254 -2.3383 7.87495 -0.857166 -2.36601 8.37171 -0.796465 -1.96667 7.51335 -0.7807 -1.86736 7.59515 -0.756748 -1.70999 7.46289 -0.728187 -1.52164 7.18154 -0.712257 -1.42417 7.24651 -0.700458 -1.34675 7.41738 -0.694887 -1.31172 7.8329 -0.678483 -1.20742 7.93379 -0.653553 -1.0426 7.66759 -0.623563 -0.84629 7.10071 -0.611026 -0.76829 7.34304 -0.590337 -0.635351 7.12685 -0.575559 -0.536699 7.21689 -0.571677 -0.5253 8.61208 -0.543522 -0.329969 7.38181 -0.524858 -0.209598 7.09684 -0.508085 -0.104112 7.0596 -0.700359 -1.60258 -0.959046 -0.70617 -1.65581 -0.953353 -0.715163 -1.72195 -0.961459 -0.722518 -1.78252 -0.960319 -0.729233 -1.8376 -0.950334 -0.738136 -1.90549 -0.953348 -0.74599 -1.97424 -0.954611 -0.754794 -2.04395 -0.95403 -0.761486 -2.09973 -0.938004 -0.771782 -2.17771 -0.940528 -0.782627 -2.26296 -0.947403 -0.791832 -2.34266 -0.945431 -0.802049 -2.42231 -0.941265 -0.812697 -2.51121 -0.940851 -0.824357 -2.60004 -0.938042 -0.834974 -2.68969 -0.932685 -0.848502 -2.79699 -0.935985 -0.860571 -2.89576 -0.930687 -0.875495 -3.01313 -0.9331 -0.889442 -3.13028 -0.932113 -0.90577 -3.25767 -0.932538 -0.922122 -3.38487 -0.929067 -0.938801 -3.52317 -0.926454 -0.958413 -3.67894 -0.928803 -0.97651 -3.82713 -0.921805 -0.997426 -3.99475 -0.918672 -1.02023 -4.18069 -0.918652 -1.04729 -4.39526 -0.924554 -1.0747 -4.62073 -0.927218 -1.09323 -4.76342 -0.889656 -1.11682 -4.9542 -0.865072 -1.14044 -5.14469 -0.834395 -1.17345 -5.41091 -0.822868 -1.20968 -5.70643 -0.811518 -1.2501 -6.03224 -0.798901 -1.29478 -6.38724 -0.783367 -1.34728 -6.81119 -0.773291 -1.40537 -7.27535 -0.758163 -1.46852 -7.78872 -0.738035 -1.54286 -8.38193 -0.716341 -1.62826 -9.074 -0.692441 -1.73553 -9.9341 -0.672703 -1.86687 -10.9922 -0.652657 -2.00567 -12.1106 -0.603755 -2.16809 -13.4191 -0.537409 -2.31679 -14.6095 -0.414022 -2.37715 -15.0967 -0.19362 -2.44557 -15.65 0.0392036 -2.68831 -17.6071 0.229465 -2.82903 -18.7392 0.509915 -2.83018 -18.7539 0.839443 -2.83304 -18.7738 1.16941 -2.8342 -18.7886 1.50014 -2.83334 -18.7871 1.83098 -2.83324 -18.7897 2.16242 -2.8339 -18.7963 2.49505 -2.82968 -18.7676 2.82537 -2.82901 -18.763 3.15856 -2.82917 -18.7614 3.49339 -2.82764 -18.7547 3.82888 -2.83155 -18.791 4.17317 -2.83016 -18.782 4.51236 -2.82815 -18.767 4.85205 -2.49875 -16.1204 4.60528 -2.47175 -15.9009 4.85084 -2.5378 -16.4379 5.28783 -2.46728 -15.8734 5.43984 -2.45508 -15.7748 5.71259 -2.43735 -15.6345 5.97131 -2.43803 -15.6394 6.27722 -2.53456 -16.4255 6.86538 -2.41187 -15.4383 6.82055 -2.38544 -15.2248 7.04717 -2.39013 -15.264 7.37518 -2.49012 -16.0801 8.0496 -2.44195 -15.693 8.21092 -2.56478 -16.6851 9.02415 -2.5472 -16.5441 9.31637 -2.57036 -16.7321 9.78166 -1.19912 -5.65937 4.09838 -2.36037 -15.0442 9.58145 -1.14938 -5.25794 4.12294 -1.1455 -5.22828 4.23054 -1.14224 -5.20541 4.34357 -1.15142 -5.27831 4.52283 -1.1434 -5.21706 4.61517 -1.08799 -4.76565 4.42754 -1.04862 -4.45062 4.32043 -1.05084 -4.47095 4.45909 -1.04904 -4.45708 4.57456 -1.04316 -4.41009 4.6652 -1.04339 -4.4134 4.80062 -1.08888 -4.77839 5.2621 -1.11155 -4.96714 5.58876 -1.06552 -4.59192 5.39311 -1.06897 -4.62772 5.58529 -1.06463 -4.59022 5.70883 -1.16559 -5.40938 6.74654 -1.02615 -4.28278 5.71252 -1.02711 -4.29298 5.89204 -1.07425 -4.67213 6.5144 -1.05813 -4.54366 6.55702 -0.965632 -3.79862 5.81427 -0.961883 -3.7685 5.95167 -0.870242 -3.02107 5.11679 -0.850549 -2.86285 5.04713 -0.850166 -2.86045 5.19589 -0.881532 -3.11587 5.74586 -0.872112 -3.04356 5.81685 -0.859435 -2.93956 5.83552 -0.837684 -2.76387 5.73137 -0.857918 -2.93582 6.23184 -0.852219 -2.88789 6.36187 -0.847014 -2.84971 6.51822 -0.82246 -2.65139 6.3616 -0.795876 -2.43382 6.14568 -0.796339 -2.43941 6.39706 -0.77373 -2.25842 6.23729 -0.774367 -2.26209 6.5072 -0.7538 -2.09818 6.36938 -0.80416 -2.51547 7.78247 -0.791563 -2.41393 7.87276 -0.787562 -2.37984 8.17027 -0.748602 -2.0673 7.61012 -0.731174 -1.92128 7.53995 -0.74565 -2.0434 8.43047 -0.696593 -1.64127 7.40019 -0.685299 -1.55312 7.52537 -0.662395 -1.36984 7.22952 -0.662991 -1.37406 7.81124 -0.64656 -1.24698 7.78515 -0.633962 -1.14751 7.91459 -0.613374 -0.972923 7.56769 -0.595433 -0.826877 7.33602 -0.580449 -0.705857 7.25024 -0.566091 -0.594566 7.23182 -0.588463 -0.803541 11.3087 -0.541058 -0.390701 7.4485 -0.525717 -0.273561 7.32457 -0.511984 -0.157585 7.09846 -0.499197 -0.0518804 7.05027 -0.650732 -1.57844 -0.957627 -0.65554 -1.63165 -0.95263 -0.660945 -1.69121 -0.95383 -0.666299 -1.75171 -0.953582 -0.673189 -1.81961 -0.959186 -0.677972 -1.87353 -0.948546 -0.684823 -1.94227 -0.950805 -0.691625 -2.0119 -0.951116 -0.698377 -2.08245 -0.94958 -0.705675 -2.16029 -0.952894 -0.712924 -2.23903 -0.954161 -0.719119 -2.30291 -0.940235 -0.728342 -2.39823 -0.949908 -0.735036 -2.47028 -0.938385 -0.743633 -2.56 -0.936816 -0.752724 -2.65793 -0.938649 -0.762311 -2.76407 -0.943385 -0.771835 -2.85544 -0.93373 -0.782817 -2.97166 -0.937877 -0.793218 -3.08139 -0.93313 -0.804543 -3.20857 -0.935436 -0.81683 -3.33662 -0.933901 -0.829564 -3.47378 -0.933222 -0.842777 -3.60349 -0.923701 -0.857292 -3.76085 -0.923738 -0.871776 -3.91896 -0.918831 -0.889569 -4.10474 -0.921692 -0.910621 -4.31911 -0.930771 -0.928678 -4.51751 -0.925001 -0.943565 -4.67035 -0.894125 -0.962574 -4.87023 -0.876473 -0.979759 -5.05128 -0.84552 -1.00289 -5.29873 -0.831554 -1.02875 -5.56731 -0.815462 -1.05735 -5.87331 -0.802346 -1.09088 -6.22995 -0.792771 -1.1273 -6.60547 -0.776474 -1.16806 -7.04153 -0.761824 -1.21342 -7.51771 -0.741518 -1.26648 -8.08174 -0.723735 -1.33134 -8.76502 -0.709554 -1.39975 -9.48982 -0.678729 -1.48682 -10.4026 -0.652766 -1.58291 -11.4153 -0.609111 -1.70019 -12.6576 -0.558365 -1.82215 -13.9404 -0.468806 -1.87414 -14.4984 -0.271189 -1.91148 -14.8865 -0.042517 -2.00268 -15.8565 0.16857 -2.25004 -18.4651 0.355992 -3.62597 -32.9866 0.427934 -3.69933 -33.7577 1.00639 -4.09377 -37.9332 1.67219 -4.33587 -40.4931 2.42795 -6.31753 -61.4226 5.32555 -2.80341 -24.3358 3.57409 -2.79589 -24.2672 3.99777 -2.64598 -22.684 4.20675 -2.62381 -22.4576 4.57739 -2.61884 -22.4115 4.97394 -2.67667 -23.0228 5.49985 -2.592 -22.1336 5.73015 -2.59962 -22.2122 6.1557 -2.007 -15.9567 4.99974 -2.0169 -16.0585 5.32549 -2.02901 -16.1907 5.66705 -1.97701 -15.6508 5.80975 -1.97514 -15.631 6.10505 -1.98813 -15.7658 6.45645 -2.02177 -16.127 6.89968 -1.92812 -15.1393 6.84082 -1.94343 -15.3032 7.21406 -1.9893 -15.7974 7.73938 -2.01344 -16.0507 8.18205 -2.0121 -16.041 8.5173 -2.02036 -16.1403 8.91142 -2.00617 -15.9922 9.18866 -1.02862 -5.62457 4.00601 -1.01668 -5.49375 4.0606 -1.00329 -5.35325 4.10642 -0.998883 -5.31573 4.21013 -0.998167 -5.30074 4.32924 -1.00013 -5.32565 4.47614 -1.03109 -5.66063 4.83749 -0.981937 -5.13711 4.61493 -0.91646 -4.44535 4.2458 -0.920649 -4.4833 4.39543 -0.936354 -4.65104 4.65211 -0.962369 -4.93542 5.01641 -0.990394 -5.23817 5.41725 -0.959624 -4.91253 5.29194 -0.949513 -4.80101 5.34397 -0.91291 -4.4187 5.14091 -0.914625 -4.4319 5.30115 -0.905007 -4.3286 5.34988 -0.906335 -4.34902 5.52589 -0.88727 -4.14804 5.46974 -0.965451 -4.98227 6.56 -0.982714 -5.16549 6.97113 -0.843332 -3.67913 5.40583 -0.865192 -3.92138 5.8661 -0.845781 -3.70739 5.76855 -0.808478 -3.31234 5.41749 -0.769942 -2.90177 5.0137 -0.768812 -2.89473 5.15403 -0.763438 -2.83852 5.22909 -0.788138 -3.10621 5.80654 -0.785455 -3.07509 5.94509 -0.820199 -3.45505 6.77832 -0.76826 -2.90133 6.04987 -0.768748 -2.90465 6.26619 -0.748324 -2.68609 6.07782 -0.751183 -2.72014 6.36483 -0.739623 -2.59587 6.34876 -0.739219 -2.59931 6.60185 -0.721801 -2.41599 6.45474 -0.714218 -2.3293 6.51469 -0.702543 -2.20646 6.48978 -0.717084 -2.36764 7.19981 -0.726671 -2.4742 7.83238 -0.722491 -2.4431 8.13014 -0.706445 -2.27262 8.02911 -0.679344 -1.98167 7.51321 -0.66975 -1.8792 7.58541 -0.654271 -1.71275 7.42421 -0.642568 -1.59116 7.41438 -0.627804 -1.42755 7.21716 -0.620875 -1.35295 7.39775 -0.614335 -1.29463 7.69539 -0.600098 -1.13845 7.49053 -0.590422 -1.03922 7.59843 -0.578821 -0.91321 7.53642 -0.565682 -0.771554 7.32316 -0.553624 -0.651771 7.23622 -0.544254 -0.541845 7.23677 -0.54137 -0.530506 8.63195 -0.523375 -0.331256 7.37179 -0.51276 -0.211381 7.10682 -0.502035 -0.104752 7.05957 -0.605034 -1.60547 -0.951507 -0.608848 -1.65858 -0.945906 -0.612199 -1.719 -0.946551 -0.617149 -1.78582 -0.952998 -0.620459 -1.84709 -0.950497 -0.625309 -1.91574 -0.953548 -0.629578 -1.97789 -0.947705 -0.633861 -2.05571 -0.954106 -0.638091 -2.11869 -0.944817 -0.643337 -2.19737 -0.947276 -0.648062 -2.26856 -0.94099 -0.653274 -2.34803 -0.939205 -0.658438 -2.42838 -0.935173 -0.664094 -2.51698 -0.934943 -0.670658 -2.62316 -0.944163 -0.677223 -2.71355 -0.938643 -0.683285 -2.8121 -0.936223 -0.690242 -2.91256 -0.93081 -0.697661 -3.03778 -0.938696 -0.705079 -3.14724 -0.932241 -0.713782 -3.28445 -0.937741 -0.721121 -3.39557 -0.924395 -0.729329 -3.5251 -0.917156 -0.739895 -3.68134 -0.919826 -0.750796 -3.84862 -0.922055 -0.76167 -4.01663 -0.918941 -0.775225 -4.22248 -0.927193 -0.787333 -4.41969 -0.924748 -0.798639 -4.58168 -0.900708 -0.810209 -4.77205 -0.882577 -0.823187 -4.97242 -0.86186 -0.837575 -5.18274 -0.837958 -0.854487 -5.45 -0.826381 -0.872271 -5.71988 -0.805869 -0.893166 -6.03735 -0.790738 -0.915256 -6.38486 -0.773031 -0.942178 -6.80116 -0.761172 -0.97126 -7.24834 -0.742197 -1.00377 -7.7548 -0.72122 -1.04469 -8.37032 -0.704827 -1.09061 -9.08532 -0.68566 -1.14268 -9.88136 -0.655125 -1.2012 -10.7866 -0.613536 -1.2719 -11.8717 -0.564051 -1.35199 -13.1169 -0.495312 -1.41204 -14.0352 -0.351763 -1.4255 -14.2553 -0.121719 -1.45869 -14.7609 0.0978595 -1.65506 -17.7947 0.224472 -2.70891 -34.0166 0.707881 -2.70962 -34.0363 1.30308 -2.71252 -34.086 1.89985 -2.11974 -24.9893 2.97496 -2.12526 -25.0707 3.42319 -1.9645 -22.6055 3.58472 -1.95117 -22.3986 3.95877 -2.10301 -24.7615 4.71258 -1.96061 -22.5675 4.78826 -2.04153 -23.8126 5.42669 -1.91297 -21.8344 5.45546 -1.9159 -21.8903 5.867 -1.82405 -20.4823 5.93138 -1.55283 -16.2883 5.22415 -1.55006 -16.2504 5.51906 -1.54747 -16.2262 5.81966 -1.89677 -21.6317 7.83851 -1.53277 -16.0015 6.36835 -1.78612 -19.9311 8.0766 -1.76311 -19.5806 8.34 -1.50656 -15.6161 7.16722 -1.51029 -15.6716 7.50825 -1.51664 -15.7849 7.88105 -1.53008 -15.9991 8.30955 -1.59696 -17.0398 9.14804 -1.5598 -16.4667 9.23064 -1.46779 -15.0378 8.84763 -1.45073 -14.7841 9.04739 -0.85188 -5.4882 4.11331 -0.845539 -5.38127 4.17836 -0.872382 -5.80202 4.5647 -0.860356 -5.62148 4.59041 -1.52698 -15.9923 11.6109 -0.859539 -5.61657 4.86982 -0.792591 -4.57305 4.27048 -0.825317 -5.08472 4.77231 -0.818425 -4.98683 4.83641 -0.832005 -5.19218 5.14092 -0.835102 -5.25072 5.33923 -0.822547 -5.06069 5.33303 -0.812005 -4.88745 5.33467 -0.788378 -4.52378 5.15597 -0.767542 -4.19758 4.99353 -0.772436 -4.27721 5.21349 -0.783999 -4.46838 5.55877 -0.784349 -4.47126 5.72331 -0.773245 -4.30664 5.71226 -0.781442 -4.43595 6.02656 -0.7464 -3.88148 5.55588 -0.738576 -3.76361 5.57675 -0.722726 -3.52178 5.43836 -0.71729 -3.43194 5.48342 -0.684837 -2.93181 4.97195 -0.682961 -2.90228 5.07954 -0.682641 -2.89886 5.22866 -0.707964 -3.29858 5.99594 -0.696485 -3.11963 5.90939 -0.697364 -3.13303 6.12531 -0.68817 -3.00282 6.11033 -0.674449 -2.79057 5.94446 -0.678313 -2.84194 6.24744 -0.667005 -2.67637 6.15434 -0.664213 -2.63035 6.28985 -0.665189 -2.64503 6.5607 -0.650568 -2.42832 6.34225 -0.651657 -2.44209 6.63158 -0.639512 -2.25269 6.4517 -0.634029 -2.16426 6.50885 -0.643582 -2.32615 7.23896 -0.649809 -2.44061 7.91039 -0.644634 -2.35126 8.04679 -0.626468 -2.0633 7.56232 -0.617472 -1.92893 7.53031 -0.608133 -1.78051 7.43775 -0.598715 -1.63271 7.33239 -0.591326 -1.52509 7.36968 -0.584802 -1.42065 7.42474 -0.576998 -1.30058 7.40936 -0.570966 -1.20849 7.53932 -0.562259 -1.08604 7.5101 -0.554416 -0.966275 7.48852 -0.547318 -0.852201 7.49455 -0.538101 -0.710835 7.26006 -0.530792 -0.598966 7.24167 -0.540123 -0.80612 11.2788 -0.516971 -0.386691 7.35864 -0.509627 -0.275611 7.3445 -0.502939 -0.158042 7.09844 -0.496202 -0.051699 7.05028 -0.563877 -1.77134 -0.968602 -0.566004 -1.8198 -0.952007 -0.567854 -1.88831 -0.955848 -0.570121 -1.95039 -0.950897 -0.572399 -2.01238 -0.944249 -0.57569 -2.09009 -0.949747 -0.577403 -2.16124 -0.946348 -0.580659 -2.23975 -0.947703 -0.583333 -2.31177 -0.940462 -0.586508 -2.40773 -0.950066 -0.589148 -2.48053 -0.938481 -0.592293 -2.57724 -0.943041 -0.595378 -2.65918 -0.933011 -0.598854 -2.76696 -0.937828 -0.603827 -2.88297 -0.945152 -0.606321 -2.97478 -0.932629 -0.611153 -3.09347 -0.933312 -0.615491 -3.22023 -0.935696 -0.619732 -3.3488 -0.934086 -0.62445 -3.46994 -0.923735 -0.629102 -3.60842 -0.919235 -0.634997 -3.77552 -0.923945 -0.640924 -3.94236 -0.923461 -0.647617 -4.12947 -0.926187 -0.654655 -4.32753 -0.926874 -0.660092 -4.47086 -0.89791 -0.666281 -4.65086 -0.879457 -0.673678 -4.86028 -0.866069 -0.681428 -5.08059 -0.849242 -0.690029 -5.31997 -0.83178 -0.699051 -5.56918 -0.80973 -0.710059 -5.86797 -0.793958 -0.721755 -6.20498 -0.779409 -0.73459 -6.57298 -0.761335 -0.750209 -7.01058 -0.747755 -0.766677 -7.46778 -0.724002 -0.786484 -8.03489 -0.707564 -0.808697 -8.66193 -0.683278 -0.83569 -9.4086 -0.658428 -0.864908 -10.235 -0.620547 -0.900067 -11.2118 -0.575081 -0.939772 -12.3296 -0.512883 -0.97882 -13.4272 -0.410121 -0.995017 -13.8979 -0.214588 -1.01305 -14.4052 -0.00584925 -1.07219 -16.0676 0.159793 -1.17873 -19.0654 0.336447 -1.72147 -34.3074 1.00436 -1.5699 -30.0553 1.52885 -1.72031 -34.3069 2.20322 -1.85167 -38.0027 2.99767 -1.85204 -38.0317 3.66592 -1.8501 -37.9995 4.33147 -1.30943 -22.8087 3.40195 -1.28694 -22.1883 3.72922 -1.30013 -22.573 4.17755 -1.2534 -21.2705 4.37401 -1.25649 -21.3563 4.77101 -1.19206 -19.5602 4.80736 -1.29805 -22.5604 5.80154 -1.30431 -22.7457 6.2578 -1.21562 -20.2459 6.05403 -1.20843 -20.0676 6.3835 -1.19536 -19.7022 6.65601 -1.25358 -21.3679 7.54021 -1.1498 -18.4377 6.99742 -1.09278 -16.838 6.80392 -1.08948 -16.7428 7.10051 -1.04915 -15.6168 7.00127 -1.05331 -15.7325 7.36299 -1.16464 -18.912 9.03591 -1.17085 -19.116 9.51962 -1.11215 -17.4519 9.14623 -1.11099 -17.4239 9.50671 -1.13294 -18.0749 10.2184 -1.05026 -15.7229 9.36811 -1.01097 -14.6043 9.10321 -0.702643 -5.81493 4.36113 -0.700518 -5.77316 4.47243 -0.694484 -5.59295 4.49852 -0.689951 -5.47239 4.55758 -0.688585 -5.43465 4.66936 -0.693401 -5.56584 4.90138 -0.69315 -5.57817 5.05678 -0.692005 -5.55444 5.18969 -0.687324 -5.40197 5.22455 -0.675507 -5.07861 5.11676 -0.669359 -4.89879 5.11483 -0.671296 -4.97744 5.33096 -0.667743 -4.85657 5.37709 -0.646476 -4.2603 4.97695 -0.643763 -4.17591 5.03688 -0.657224 -4.57788 5.58297 -0.657581 -4.58071 5.74862 -0.661658 -4.72915 6.07661 -0.65587 -4.55966 6.06918 -0.652517 -4.47028 6.148 -0.663285 -4.78513 6.70803 -0.61964 -3.51517 5.34506 -0.613664 -3.34615 5.28759 -0.614612 -3.39156 5.50519 -0.600655 -2.9718 5.09439 -0.594299 -2.80786 5.01466 -0.635752 -4.01196 6.95342 -0.60876 -3.23207 5.98246 -0.605205 -3.14483 6.03825 -0.620631 -3.60245 7.00099 -0.600064 -3.00738 6.21423 -0.598608 -2.9551 6.33601 -0.5916 -2.74804 6.17476 -0.589248 -2.69385 6.29335 -0.585433 -2.59292 6.32163 -0.583302 -2.51655 6.40238 -0.57972 -2.43004 6.46372 -0.575291 -2.30297 6.43165 -0.571736 -2.19686 6.44326 -0.572078 -2.22692 6.80758 -0.582275 -2.55244 8.02025 -0.577688 -2.41293 8.0164 -0.570097 -2.2136 7.81979 -0.562564 -1.97145 7.45576 -0.557856 -1.83084 7.39308 -0.552948 -1.69338 7.32746 -0.54817 -1.57323 7.31725 -0.544706 -1.46742 7.36332 -0.540204 -1.34094 7.31946 -0.5359 -1.23123 7.34191 -0.532099 -1.13378 7.44126 -0.528952 -1.02132 7.46006 -0.524835 -0.93465 7.66507 -0.519402 -0.77478 7.3231 -0.516212 -0.66059 7.29586 -0.519595 -0.895514 11.2514 -0.509241 -0.529041 8.58201 -0.504233 -0.335136 7.41174 -0.499725 -0.212611 7.12678 -0.496046 -0.104389 7.05959 -0.511733 -1.78949 -0.953167 -0.511581 -1.85792 -0.957801 -0.512845 -1.91998 -0.953646 -0.513061 -1.9829 -0.94784 -0.513412 -2.05947 -0.954278 -0.514054 -2.11589 -0.938182 -0.513844 -2.20159 -0.94737 -0.514516 -2.27354 -0.941122 -0.515211 -2.36107 -0.945619 -0.515385 -2.44112 -0.941571 -0.51599 -2.53041 -0.941175 -0.51655 -2.62058 -0.938333 -0.517603 -2.71897 -0.938793 -0.517575 -2.83476 -0.947699 -0.518064 -2.92652 -0.936568 -0.519472 -3.03578 -0.933489 -0.51984 -3.14583 -0.927262 -0.521133 -3.27333 -0.927889 -0.521331 -3.40257 -0.924619 -0.522492 -3.53267 -0.917307 -0.523014 -3.68932 -0.920096 -0.524213 -3.88376 -0.935644 -0.525047 -4.05215 -0.932148 -0.526363 -4.21307 -0.919112 -0.52714 -4.38294 -0.905131 -0.52869 -4.57303 -0.89336 -0.529278 -4.76276 -0.875595 -0.531018 -4.98287 -0.862145 -0.532369 -5.19341 -0.838351 -0.533945 -5.43319 -0.817221 -0.53594 -5.73168 -0.806214 -0.537372 -6.03981 -0.78832 -0.539753 -6.39831 -0.773354 -0.542342 -6.78669 -0.754012 -0.545165 -7.25361 -0.740409 -0.547988 -7.77042 -0.721741 -0.551147 -8.34817 -0.697366 -0.556073 -9.04549 -0.675314 -0.560388 -9.80328 -0.639262 -0.565476 -10.6811 -0.594893 -0.571148 -11.6987 -0.538722 -0.579439 -12.9054 -0.468935 -0.581682 -13.4072 -0.289407 -0.583644 -13.7168 -0.0779056 -0.589491 -14.672 0.104345 -0.609032 -17.9616 0.217733 -0.627607 -20.9923 0.452523 -0.695196 -32.1981 0.72222 -0.694459 -32.1571 1.2838 -0.675641 -29.0688 1.76405 -0.679116 -29.8505 2.30631 -0.678856 -29.8326 2.82768 -0.678276 -29.8367 3.35122 -0.630938 -22.0373 3.12428 -0.634204 -22.6028 3.57768 -0.607249 -18.2913 3.41023 -0.606578 -18.2364 3.72761 -0.610888 -18.8661 4.15935 -0.614641 -19.6736 4.64861 -0.616024 -19.9203 5.05516 -0.613057 -19.554 5.33738 -0.599764 -17.2488 5.14315 -0.599367 -17.2222 5.45613 -0.609575 -19.0493 6.2853 -0.597141 -16.9412 6.02039 -0.595987 -16.8602 6.31827 -0.595817 -16.9646 6.67837 -0.604132 -18.3427 7.49782 -0.593443 -16.6523 7.22847 -0.596081 -17.1832 7.77108 -0.605916 -18.8454 8.80869 -0.607109 -19.2017 9.35171 -0.59964 -17.9429 9.17962 -0.583653 -15.1799 8.24284 -0.583329 -15.2032 8.58251 -0.580811 -14.8388 8.72665 -0.581919 -14.9741 9.13241 -0.580835 -14.977 9.47619 -0.530542 -5.79776 4.41662 -0.529488 -5.66939 4.47557 -0.529087 -5.66661 4.6116 -0.529235 -5.58606 4.69884 -0.527946 -5.49574 4.7788 -0.528092 -5.5354 4.94966 -0.528005 -5.56218 5.11709 -0.525619 -5.16342 4.96387 -0.524955 -4.90656 4.90405 -0.523869 -4.82937 4.98265 -0.524053 -4.78212 5.08584 -0.523135 -4.70204 5.1621 -0.522841 -4.68058 5.2908 -0.520497 -4.32932 5.11029 -0.51987 -4.12153 5.05198 -0.51956 -4.2398 5.31594 -0.520281 -4.21826 5.44733 -0.519855 -4.23456 5.62346 -0.519818 -4.22682 5.77917 -0.517612 -3.86981 5.53279 -0.521911 -4.75734 6.77262 -0.514579 -3.30455 5.15639 -0.514346 -3.31725 5.32453 -0.513468 -3.07477 5.15668 -0.511439 -2.7983 4.92469 -0.511427 -2.73531 4.98125 -0.517107 -3.98997 7.02976 -0.515403 -3.83575 7.02256 -0.514747 -3.73471 7.09708 -0.512749 -3.222 6.47206 -0.511967 -3.06691 6.42296 -0.511148 -2.85707 6.26474 -0.509636 -2.69564 6.18079 -0.509167 -2.68074 6.3792 -0.508749 -2.64707 6.55156 -0.508132 -2.59923 6.7061 -0.50695 -2.35557 6.42045 -0.507 -2.31404 6.59011 -0.505889 -2.14271 6.44359 -0.507483 -2.64971 8.0913 -0.506499 -2.47943 8.00451 -0.506221 -2.35341 8.03724 -0.504192 -1.98393 7.29513 -0.503685 -1.91943 7.48229 -0.503084 -1.7766 7.40876 -0.501651 -1.6293 7.30329 -0.500969 -1.54939 7.45714 -0.500564 -1.39984 7.31721 -0.500047 -1.27314 7.2623 -0.499486 -1.16928 7.31305 -0.498588 -1.09832 7.56917 -0.497915 -0.974941 7.52805 -0.497209 -0.878932 7.68291 -0.496992 -0.710344 7.24016 -0.495674 -0.599855 7.24163 -0.493022 -0.804258 11.2388 -0.49483 -0.388871 7.3686 -0.493602 -0.278686 7.40442 -0.492899 -0.159453 7.1184 -0.493208 -0.0515177 7.05029 -0.459641 -1.77208 -0.968723 -0.458366 -1.8267 -0.959413 -0.457099 -1.88127 -0.948803 -0.454906 -1.95045 -0.950984 -0.453661 -2.02061 -0.95132 -0.452428 -2.09068 -0.949859 -0.450148 -2.16159 -0.946547 -0.448887 -2.24817 -0.954383 -0.446571 -2.31988 -0.947027 -0.445218 -2.40823 -0.95027 -0.443343 -2.4891 -0.944868 -0.44044 -2.58643 -0.94926 -0.438491 -2.68469 -0.950809 -0.435981 -2.79209 -0.955207 -0.433987 -2.87546 -0.939769 -0.431391 -2.98456 -0.938276 -0.428239 -3.10276 -0.938834 -0.425564 -3.21353 -0.93065 -0.422816 -3.34169 -0.929317 -0.420546 -3.46241 -0.919143 -0.417063 -3.61893 -0.924116 -0.412404 -3.79463 -0.933242 -0.408144 -3.98034 -0.941277 -0.405086 -4.13088 -0.926423 -0.400937 -4.28312 -0.906872 -0.396539 -4.472 -0.898229 -0.392685 -4.65241 -0.879794 -0.387477 -4.87127 -0.869867 -0.382385 -5.0724 -0.846098 -0.376757 -5.33132 -0.835394 -0.369993 -5.60911 -0.82235 -0.36354 -5.89865 -0.803121 -0.355716 -6.22729 -0.78526 -0.347531 -6.59501 -0.76687 -0.337698 -7.02292 -0.750608 -0.325676 -7.51997 -0.735727 -0.31346 -8.03744 -0.708123 -0.298765 -8.69464 -0.689531 -0.28145 -9.41227 -0.659031 -0.262976 -10.1994 -0.614884 -0.242005 -11.1274 -0.563171 -0.216417 -12.215 -0.499052 -0.199742 -12.9443 -0.359746 -0.19115 -13.295 -0.162368 -0.17911 -13.802 0.0358295 -0.126144 -16.0727 0.158776 -0.0455827 -19.5123 0.319933 --0.296389 -34.2107 1.00233 --0.302877 -34.4652 1.60406 --0.3034 -34.4393 2.20532 --0.316219 -34.982 2.83611 --0.317629 -35.0045 3.45079 --0.31516 -34.8963 4.05619 --0.0670733 -24.2389 3.55008 -0.0776986 -18.0093 3.21335 -0.0731356 -18.1855 3.55799 -0.0687857 -18.3752 3.9127 -0.0646314 -18.5288 4.26953 -0.0641956 -18.5371 4.60576 -0.0956041 -17.1606 4.6502 -0.0963592 -17.1145 4.9537 -0.0928979 -17.2563 5.30514 --0.01415 -21.7845 6.84049 -0.0981333 -17.0182 5.88279 -0.110521 -16.4914 6.04476 -0.107178 -16.5813 6.39054 -0.0988519 -16.9576 6.84198 -0.104063 -16.7022 7.08237 -0.103284 -16.7332 7.42682 -0.0446359 -19.1774 8.75204 -0.0450119 -19.1584 9.13637 --0.0176618 -21.781 10.7022 -0.0431767 -19.1987 9.95668 -0.0660933 -18.2213 9.89151 -0.14593 -14.8484 8.56921 -0.139047 -15.1193 9.04319 -0.138241 -15.1516 9.40292 -0.143676 -14.8903 9.60116 -0.0977367 -16.803 11.1011 -0.360382 -5.78941 4.62011 -0.362979 -5.6671 4.68254 -0.365655 -5.56045 4.75296 -0.366908 -5.47806 4.83799 -0.341998 -6.55005 5.7618 -0.367875 -5.46023 5.11715 -0.376766 -5.05666 4.95321 -0.381548 -4.87842 4.9528 -0.384124 -4.75524 4.99237 -0.383313 -4.75987 5.14038 -0.386985 -4.63495 5.17605 -0.388013 -4.59055 5.28359 -0.385137 -4.66643 5.50902 -0.399126 -4.09972 5.10191 -0.397788 -4.1662 5.31666 -0.39508 -4.23972 5.54969 -0.394918 -4.234 5.7048 -0.401155 -3.993 5.59685 -0.415289 -3.4179 5.07599 -0.416835 -3.34585 5.135 -0.413204 -3.48954 5.46872 -0.414871 -3.39817 5.51286 -0.421414 -3.14852 5.3369 -0.412978 -3.45146 5.93191 -0.42174 -3.10789 5.61004 -0.421615 -3.10239 5.78098 -0.421991 -3.08825 5.94478 -0.424591 -2.98015 5.96356 -0.410113 -3.52791 7.11476 -0.413958 -3.36283 7.07045 -0.433913 -2.58994 5.87447 -0.436208 -2.48633 5.88326 -0.434878 -2.52377 6.17768 -0.438259 -2.38179 6.11218 -0.436731 -2.40608 6.40875 -0.438894 -2.34332 6.52359 -0.442841 -2.17124 6.37821 -0.437877 -2.36013 7.1529 -0.443432 -2.1189 6.82668 -0.442026 -2.14737 7.241 -0.444918 -2.03486 7.26797 -0.443028 -2.07752 7.79994 -0.449628 -1.83133 7.39297 -0.452705 -1.69435 7.32742 -0.454452 -1.60544 7.44337 -0.458168 -1.45407 7.30472 -0.461772 -1.32505 7.24107 -0.464271 -1.21981 7.28292 -0.465702 -1.11662 7.3427 -0.468337 -1.03328 7.52921 -0.468975 -0.953965 7.79382 -0.474361 -0.773559 7.31311 -0.477221 -0.658221 7.27596 -0.478486 -0.564607 7.46578 -0.47823 -0.525129 8.52213 -0.484212 -0.33696 7.45161 -0.487685 -0.212383 7.11673 -0.490062 -0.106053 7.09956 -0.405683 -1.7871 -0.953231 -0.402536 -1.85536 -0.957955 -0.398809 -1.91711 -0.953784 -0.395564 -1.98719 -0.954913 -0.391796 -2.04978 -0.947497 -0.388107 -2.12701 -0.951875 -0.384775 -2.19882 -0.947511 -0.379991 -2.27778 -0.947792 -0.375697 -2.36501 -0.952173 -0.370821 -2.44574 -0.94786 -0.366435 -2.53473 -0.947448 -0.361484 -2.63288 -0.950386 -0.356549 -2.73089 -0.950627 -0.351033 -2.82242 -0.942173 -0.346012 -2.92215 -0.936722 -0.340372 -3.03199 -0.933672 -0.334234 -3.14993 -0.932622 -0.327998 -3.26969 -0.927978 -0.321269 -3.39752 -0.924835 -0.313869 -3.53637 -0.922345 -0.304264 -3.71091 -0.934102 -0.293999 -3.89639 -0.944813 -0.286506 -4.03754 -0.928093 -0.279407 -4.18873 -0.911079 -0.269571 -4.3682 -0.901364 -0.259709 -4.54839 -0.886007 -0.249686 -4.74771 -0.872208 -0.237511 -4.96599 -0.858963 -0.225631 -5.19613 -0.84193 -0.212044 -5.45436 -0.827006 -0.196637 -5.74259 -0.812592 -0.179422 -6.06076 -0.797092 -0.162026 -6.39872 -0.776509 -0.140416 -6.80594 -0.761995 -0.116412 -7.25292 -0.743202 -0.089169 -7.76992 -0.72434 -0.0583294 -8.34661 -0.699908 -0.0248497 -8.98389 -0.666763 --0.0160528 -9.76022 -0.634925 --0.0623803 -10.6268 -0.589688 --0.112492 -11.5735 -0.525059 --0.159297 -12.4511 -0.419902 --0.176778 -12.7828 -0.231724 --0.188357 -13.0014 -0.0238225 --0.275883 -14.6519 0.103387 --0.439922 -17.7474 0.224857 --1.13215 -30.8254 0.731769 --1.15903 -31.3144 1.27479 --1.15611 -31.2453 1.82055 --1.13713 -30.8771 2.35114 --1.29836 -33.9086 3.07808 --1.29217 -33.7875 3.66411 --1.15665 -31.2207 4.01164 --0.504632 -18.9207 3.15968 --0.616673 -21.018 3.77195 --0.609443 -20.8675 4.12413 --0.417425 -17.2545 3.89246 --0.430904 -17.4958 4.24827 --0.397194 -16.8497 4.43386 --0.403598 -16.9731 4.76899 --0.402985 -16.9627 5.07906 --0.405361 -16.9857 5.4 --0.361993 -16.1753 5.49302 --0.362303 -16.18 5.80064 --0.370272 -16.3136 6.1519 --0.379003 -16.4772 6.52187 --0.417777 -17.1974 7.0994 --0.385226 -16.5831 7.20997 --1.12185 -30.3904 12.9892 --0.511696 -18.94 8.8573 --0.507394 -18.8545 9.211 --0.509722 -18.8812 9.61803 --0.4307 -17.3947 9.30963 --0.371366 -16.273 9.12597 --0.324985 -15.4029 9.0305 --0.340772 -15.6899 9.53226 --0.30414 -15.0006 9.49993 --0.298166 -14.8837 9.78108 --1.0606 -29.109 18.865 -0.203459 -5.50366 4.64883 -0.129607 -6.87955 5.73571 -0.226518 -5.07196 4.62409 -0.231546 -4.97579 4.6884 -0.236113 -4.88741 4.7566 -0.240283 -4.80583 4.82904 -0.239163 -4.81551 4.97601 -0.120111 -7.03778 7.02095 -0.23652 -4.86006 5.30753 -0.245468 -4.69593 5.31079 -0.250976 -4.59128 5.36467 -0.268172 -4.26553 5.19901 -0.278304 -4.07957 5.15874 -0.271126 -4.21325 5.44712 -0.276252 -4.11475 5.4979 -0.28067 -4.02859 5.56161 -0.281749 -4.0011 5.69221 -0.301088 -3.65183 5.43737 -0.292353 -3.79766 5.78223 -0.292525 -3.80454 5.9669 -0.322421 -3.24786 5.39758 -0.306121 -3.54779 5.98288 -0.321635 -3.24528 5.73097 -0.326136 -3.15692 5.77865 -0.328947 -3.11693 5.90061 -0.334236 -3.01454 5.92877 -0.297496 -3.674 7.24731 -0.30765 -3.4858 7.17138 -0.338928 -2.91064 6.37007 -0.355826 -2.59531 5.99436 -0.342921 -2.8281 6.68336 -0.351308 -2.66898 6.60558 -0.353934 -2.61675 6.75147 -0.358156 -2.53526 6.84214 -0.368098 -2.34566 6.67313 -0.358825 -2.52107 7.41113 -0.372982 -2.25085 7.03267 -0.382214 -2.09249 6.92027 -0.381097 -2.09669 7.27843 -0.386427 -1.99552 7.34269 -0.39248 -1.8798 7.35747 -0.399923 -1.73596 7.27373 -0.403572 -1.66936 7.46777 -0.40983 -1.54942 7.46672 -0.418348 -1.40193 7.33664 -0.430661 -1.1679 6.75261 -0.430127 -1.17518 7.35231 -0.435607 -1.07178 7.42117 -0.439478 -0.984021 7.59724 -0.444645 -0.892406 7.79194 -0.454888 -0.711829 7.26002 -0.43594 -0.988706 11.2929 -0.464935 -0.507385 7.47045 -0.471812 -0.388992 7.37856 -0.477564 -0.275681 7.3445 -0.483915 -0.158909 7.11843 -0.489154 -0.0522777 7.05026 -0.374917 -1.53329 -0.969566 -0.351907 -1.8149 -0.952229 -0.346239 -1.87558 -0.9489 -0.341051 -1.94458 -0.951071 -0.334816 -2.01444 -0.951492 -0.32959 -2.08427 -0.950017 -0.322852 -2.16226 -0.953337 -0.316067 -2.24115 -0.95451 -0.310757 -2.31269 -0.947144 -0.303877 -2.39336 -0.944023 -0.296549 -2.48124 -0.94495 -0.289115 -2.57098 -0.943381 -0.281177 -2.66888 -0.94501 -0.273196 -2.76765 -0.943894 -0.265751 -2.858 -0.934285 -0.257165 -2.96675 -0.932972 -0.247024 -3.08453 -0.933708 -0.236328 -3.21139 -0.936095 -0.227625 -3.32264 -0.924546 -0.215191 -3.47782 -0.933836 -0.202242 -3.62548 -0.933681 -0.186518 -3.81801 -0.951621 -0.17716 -3.94067 -0.928391 -0.164627 -4.08242 -0.909707 -0.15084 -4.2608 -0.903025 -0.136029 -4.43985 -0.890698 -0.119627 -4.62872 -0.876274 -0.102439 -4.84687 -0.866608 -0.084176 -5.06661 -0.849849 -0.0632036 -5.3144 -0.835694 -0.0420306 -5.58214 -0.819653 -0.0164229 -5.88988 -0.806417 --0.00974382 -6.20725 -0.785695 --0.0399492 -6.57464 -0.767285 --0.0747372 -7.00103 -0.751043 --0.115087 -7.48624 -0.733969 --0.15731 -8.00291 -0.70652 --0.209763 -8.63859 -0.684351 --0.266159 -9.32353 -0.649214 --0.330617 -10.1089 -0.60617 --0.405268 -11.0135 -0.552776 --0.487358 -12.009 -0.479037 --0.516657 -12.3696 -0.304072 --0.542768 -12.6785 -0.112557 --0.595165 -13.3215 0.0656636 --0.820396 -16.0527 0.156126 --1.12686 -19.7812 0.307291 --1.88539 -29.0074 0.492248 --1.89284 -29.091 1.00024 --1.8998 -29.1665 1.51103 --1.89876 -29.1433 2.02141 --1.8996 -29.1509 2.53312 --1.90729 -29.239 3.05175 --1.90582 -29.2086 3.56427 --1.90401 -29.1891 4.07854 --1.90265 -29.1607 4.59286 --1.18593 -20.4484 3.88394 --1.18831 -20.474 4.25407 --0.940172 -17.4599 4.08944 --0.929656 -17.3347 4.38137 --0.920509 -17.2155 4.672 --0.913323 -17.129 4.96836 --0.866954 -16.5544 5.14198 --0.843885 -16.2684 5.37433 --0.887791 -16.8026 5.83489 --0.960014 -17.6787 6.42373 --0.935156 -17.3635 6.66143 --0.863653 -16.4992 6.70096 --0.963523 -17.7089 7.46782 --0.954564 -17.5938 7.77697 --1.04452 -18.6743 8.57104 --1.04175 -18.6312 8.93596 --1.03332 -18.5265 9.27726 --0.866398 -16.5019 8.7215 --0.806772 -15.7822 8.72428 --0.802339 -15.7256 9.04036 --0.792357 -15.592 9.31926 --0.781087 -15.4536 9.59591 --0.922083 -17.1576 10.9402 --1.89233 -28.8563 18.3979 --0.0293607 -6.37209 4.99598 -0.0520777 -5.38216 4.5079 -0.0566542 -5.32836 4.60715 --0.0759231 -6.92193 5.86433 -0.0761117 -5.09547 4.71519 -0.0893997 -4.92623 4.72568 -0.0994132 -4.81307 4.7744 -0.106462 -4.7163 4.83296 -0.0880217 -4.9387 5.15924 -0.106411 -4.71538 5.11387 -0.109938 -4.67976 5.22933 -0.110323 -4.664 5.36522 -0.114154 -4.62338 5.48094 -0.116347 -4.59399 5.61074 -0.128089 -4.45051 5.62571 -0.134603 -4.36318 5.69566 -0.161937 -4.03369 5.49641 -0.169282 -3.94878 5.55886 -0.190214 -3.69513 5.42046 -0.166838 -3.97545 5.92754 -0.162645 -4.02434 6.16978 -0.159583 -4.05388 6.39913 -0.203887 -3.52612 5.87071 -0.164518 -3.98918 6.71811 -0.23614 -3.13133 5.6596 -0.241632 -3.06092 5.73058 -0.245493 -3.02005 5.85129 -0.242002 -3.05818 6.10911 -0.245109 -3.01376 6.23986 -0.262198 -2.80598 6.08193 -0.27529 -2.65202 6.00677 -0.276814 -2.63674 6.19494 -0.257181 -2.86549 6.8965 -0.263917 -2.77483 6.97298 -0.256026 -2.86454 7.45915 -0.277431 -2.61204 7.17703 -0.297191 -2.36981 6.88802 -0.29177 -2.43493 7.36745 -0.318229 -2.11944 6.8453 -0.324032 -2.04655 6.96662 -0.327298 -2.00446 7.19181 -0.332782 -1.9398 7.36941 -0.344531 -1.79008 7.26783 -0.349632 -1.73466 7.50106 -0.356617 -1.64149 7.60816 -0.3732 -1.45147 7.31433 -0.392695 -1.21528 6.74217 -0.402714 -1.09485 6.65467 -0.399459 -1.12069 7.38206 -0.407868 -1.01902 7.45999 -0.413135 -0.949084 7.78381 -0.428444 -0.770279 7.30312 -0.438349 -0.653349 7.24602 -0.445487 -0.564632 7.4857 -0.453156 -0.464451 7.67415 -0.465237 -0.331254 7.36173 -0.474775 -0.21364 7.17665 -0.484071 -0.105186 7.08954 -0.294322 -1.83944 -0.950863 -0.287133 -1.90836 -0.953827 -0.279424 -1.9698 -0.948045 -0.271729 -2.04689 -0.954508 -0.26392 -2.11016 -0.945231 -0.254726 -2.19531 -0.95429 -0.246415 -2.26671 -0.947914 -0.238116 -2.33802 -0.939639 -0.228783 -2.42583 -0.941858 -0.218408 -2.51446 -0.941527 -0.207466 -2.61226 -0.944645 -0.19806 -2.70169 -0.939174 -0.187092 -2.80021 -0.93675 -0.176082 -2.89958 -0.93138 -0.163453 -3.00901 -0.928507 -0.150327 -3.12654 -0.927635 -0.137678 -3.23664 -0.918121 -0.121873 -3.38147 -0.924996 -0.104462 -3.53625 -0.932172 -0.0848159 -3.71116 -0.943548 -0.067858 -3.85922 -0.936139 -0.0544582 -3.98255 -0.91105 -0.0352952 -4.15051 -0.903047 -0.0161048 -4.31921 -0.889701 --0.00587646 -4.51713 -0.882406 --0.0272516 -4.70556 -0.865169 --0.053598 -4.9424 -0.859231 --0.0778288 -5.1616 -0.838957 --0.10639 -5.41893 -0.824184 --0.138142 -5.69601 -0.806916 --0.174828 -6.02119 -0.794755 --0.21281 -6.36807 -0.776809 --0.256137 -6.75367 -0.75742 --0.305477 -7.189 -0.736643 --0.359814 -7.67397 -0.711784 --0.424539 -8.24767 -0.688491 --0.500913 -8.93101 -0.665426 --0.577264 -9.61519 -0.61899 --0.672777 -10.4668 -0.574089 --0.777128 -11.3992 -0.51013 --0.841083 -11.9662 -0.37203 --0.874072 -12.256 -0.187523 --0.902993 -12.5123 0.00912457 --1.16004 -14.8089 0.0884537 --1.38253 -16.7879 0.262241 --2.53958 -27.1105 0.28507 --2.66386 -28.2113 0.751643 --2.74808 -28.9666 1.2537 --2.74576 -28.9385 1.76182 --2.73684 -28.8507 2.26687 --2.75886 -29.0432 2.78683 --2.75725 -29.0269 3.29815 --2.75515 -29.0027 3.80947 --2.7531 -28.9793 4.32184 --2.75265 -28.9658 4.8367 --1.76991 -20.2068 4.03863 --1.7351 -19.8966 4.35011 --2.74531 -28.8931 6.38799 --2.74285 -28.8634 6.90855 --1.61301 -18.8018 5.19426 --1.65011 -19.1224 5.61951 --1.57921 -18.4912 5.81202 --1.67719 -19.3627 6.40319 --2.7644 -29.0326 9.65311 --1.48546 -17.6463 6.59878 --2.75958 -28.9781 10.7563 --1.46788 -17.4885 7.23188 --1.49255 -17.7035 7.66065 --1.44472 -17.2708 7.84597 --1.42305 -17.0761 8.11758 --1.45157 -17.3232 8.5799 --1.40024 -16.8643 8.73376 --1.37882 -16.6737 9.00287 --1.35661 -16.4695 9.2633 --2.75485 -28.8848 16.1306 --2.72453 -28.609 16.6308 --2.66296 -28.0571 16.9733 --2.76378 -28.9402 18.1538 --0.211367 -6.29452 4.88234 --0.195465 -6.15099 4.94395 --0.112146 -5.41933 4.60987 --0.108401 -5.37991 4.72155 --0.0787887 -5.12015 4.67611 --0.0668089 -5.00787 4.72977 --0.0696077 -5.02912 4.88412 --0.0630895 -4.97639 4.98431 --0.0701758 -5.03748 5.1793 --0.056804 -4.91851 5.22812 --0.0554634 -4.90367 5.36685 --0.0333763 -4.70284 5.33749 --0.0181729 -4.56901 5.36443 --0.01071 -4.49996 5.45099 -0.00885395 -4.32467 5.42951 -0.029645 -4.14503 5.39609 -0.04502 -4.00726 5.40181 -0.0542992 -3.92348 5.464 -0.00558582 -4.34907 6.12539 -0.0407831 -4.03888 5.93095 -0.0536699 -3.92739 5.96982 -0.0476052 -3.97413 6.21266 -0.0567226 -3.89423 6.29768 -0.0579645 -3.88327 6.47925 -0.0598896 -3.86067 6.65384 -0.13847 -3.164 5.8118 -0.149635 -3.06391 5.84133 -0.154059 -3.03121 5.97977 -0.167445 -2.90903 5.97195 -0.181001 -2.78342 5.95266 -0.115039 -3.36086 7.23109 -0.191038 -2.69772 6.216 -0.197038 -2.63748 6.32523 -0.174089 -2.83604 6.98447 -0.173638 -2.84244 7.27905 -0.181746 -2.76463 7.40141 -0.200454 -2.6003 7.3197 -0.219326 -2.43209 7.21557 -0.221145 -2.41755 7.51021 -0.258252 -2.08909 6.93899 -0.256829 -2.09935 7.31617 -0.261586 -2.04925 7.54285 -0.286507 -1.837 7.24227 -0.294646 -1.75997 7.38931 -0.297529 -1.73074 7.73868 -0.309296 -1.62273 7.80697 -0.346976 -1.30061 6.90706 -0.365054 -1.13617 6.6252 -0.374371 -1.05363 6.72299 -0.374321 -1.05394 7.34227 -0.387496 -0.932931 7.29057 -0.391862 -0.887218 7.79181 -0.413085 -0.706792 7.25002 -0.435048 -0.503561 7.45052 -0.439275 -0.460408 8.58627 -0.460663 -0.277206 7.41436 -0.473997 -0.15883 7.14832 -0.486158 -0.0515921 7.04023 -0.245872 -1.7961 -0.944992 -0.236741 -1.86396 -0.948998 -0.228027 -1.92538 -0.944112 -0.217859 -1.994 -0.944669 -0.20864 -2.06359 -0.943282 -0.19697 -2.14029 -0.946836 -0.186192 -2.21895 -0.948096 -0.17589 -2.29018 -0.940814 -0.163092 -2.38519 -0.950566 -0.151236 -2.46545 -0.945132 -0.139393 -2.5456 -0.937501 -0.126463 -2.64321 -0.939314 -0.112553 -2.74062 -0.938328 -0.0985387 -2.83988 -0.934447 -0.0830263 -2.94721 -0.933162 -0.0689885 -3.04719 -0.923338 -0.0518198 -3.16539 -0.920805 -0.0325843 -3.30083 -0.924718 -0.0112272 -3.45448 -0.934128 --0.0112189 -3.60983 -0.938642 --0.0358388 -3.78431 -0.947305 --0.0500433 -3.88819 -0.91546 --0.0742125 -4.05597 -0.909938 --0.0967817 -4.21436 -0.895177 --0.121576 -4.39281 -0.883117 --0.1489 -4.58005 -0.869107 --0.179066 -4.79742 -0.8597 --0.210187 -5.0144 -0.843298 --0.246699 -5.27046 -0.832745 --0.28322 -5.5271 -0.813752 --0.325115 -5.8227 -0.798011 --0.373992 -6.16721 -0.786022 --0.422859 -6.51215 -0.762497 --0.480925 -6.92601 -0.744227 --0.548608 -7.39944 -0.725362 --0.622216 -7.92138 -0.700763 --0.709252 -8.53274 -0.675375 --0.800123 -9.17518 -0.634113 --0.90971 -9.9448 -0.591167 --1.03009 -10.7942 -0.532503 --1.13964 -11.5661 -0.434678 --1.17523 -11.8158 -0.254634 --1.22362 -12.1611 -0.0750056 --1.29226 -12.6424 0.106755 --1.63939 -15.0873 0.200764 --3.02046 -24.8357 0.12276 --3.14734 -25.7288 0.545166 --3.39971 -27.5046 0.998567 --3.6886 -29.5396 1.51915 --3.69252 -29.5655 2.0412 --3.64692 -29.2363 2.54592 --3.7101 -29.6796 3.09453 --3.70656 -29.6488 3.61823 --3.70362 -29.6279 4.14363 --3.7002 -29.599 4.66903 --3.70155 -29.5996 5.19993 --3.69876 -29.5814 5.73047 --3.69536 -29.5532 6.26161 --2.25605 -19.4079 4.80952 --2.19471 -18.9713 5.07205 --3.69372 -29.5288 7.884 --2.23213 -19.2327 5.84231 --3.68693 -29.474 8.97511 --3.68346 -29.4458 9.52648 --3.68308 -29.436 10.0881 --3.6795 -29.4063 10.6489 --3.67952 -29.4038 11.2244 --3.67575 -29.3716 11.7959 --3.6724 -29.347 12.3765 --2.00344 -17.5976 8.18033 --2.03067 -17.7895 8.6262 --2.00788 -17.6275 8.92645 --3.66863 -29.2961 14.7967 --3.66132 -29.2404 15.4031 --3.64563 -29.1279 15.989 --0.287834 -5.52392 3.96712 --0.273832 -5.42887 4.03984 --3.65519 -29.1772 18.0131 --0.459438 -6.7289 5.08422 --0.366755 -6.07877 4.83661 --0.356843 -6.00313 4.93775 --0.268106 -5.38394 4.66836 --0.241765 -5.19754 4.67663 --0.303605 -5.63057 5.1322 --0.258586 -5.31267 5.04426 --0.249025 -5.24241 5.13735 --0.22974 -5.10812 5.17877 --0.218578 -5.02743 5.26173 --0.199329 -4.89342 5.29725 --0.171688 -4.70056 5.27585 --0.15725 -4.59739 5.33085 --0.152866 -4.56451 5.45285 --0.104977 -4.22738 5.27102 --0.0685975 -3.96773 5.15076 --0.0695943 -3.97591 5.30786 --0.0556893 -3.88113 5.35496 --0.0278378 -3.68195 5.27938 --0.0236613 -3.65227 5.39724 --0.0742036 -4.00557 5.9972 --0.119138 -4.31497 6.57924 --0.0735734 -3.99766 6.35905 --0.0672683 -3.95024 6.49334 --0.0693314 -3.96303 6.71786 -0.0300565 -3.27144 5.89987 -0.0561387 -3.08351 5.79742 -0.0699188 -2.99024 5.83409 -0.0759574 -2.9465 5.95464 -0.0803109 -2.9154 6.10116 -0.0296199 -3.26805 6.95641 -0.0199213 -3.3321 7.33098 -0.0360455 -3.2173 7.37979 -0.0875393 -2.85536 6.91436 -0.098587 -2.77765 7.0181 -0.0972603 -2.78198 7.31288 -0.11749 -2.64559 7.29652 -0.160665 -2.33934 6.85081 -0.154167 -2.38667 7.28322 -0.171739 -2.26163 7.27744 -0.183033 -2.18092 7.40145 -0.179193 -2.20164 7.84784 -0.218353 -1.92687 7.36928 -0.223487 -1.89057 7.66192 -0.246877 -1.7285 7.52031 -0.246547 -1.7259 7.99617 -0.309496 -1.29502 6.67122 -0.320946 -1.20945 6.75194 -0.339133 -1.08548 6.64478 -0.350382 -1.00513 6.7615 -0.348158 -1.01241 7.45993 -0.369274 -0.867184 7.23908 -0.381055 -0.783091 7.45192 -0.399481 -0.650503 7.25604 -0.411553 -0.564614 7.52556 -0.427489 -0.449772 7.51449 -0.443307 -0.343608 7.63141 -0.460073 -0.220888 7.41659 -0.47702 -0.104242 7.0596 -0.236706 -1.5333 -0.956197 -0.187002 -1.82494 -0.950916 -0.176348 -1.88528 -0.946873 -0.164178 -1.95382 -0.948222 -0.151553 -2.02961 -0.954618 -0.140749 -2.09269 -0.945333 -0.12709 -2.16922 -0.947781 -0.114322 -2.2477 -0.948036 -0.100508 -2.32702 -0.946141 -0.0867079 -2.40622 -0.941948 -0.0714018 -2.49355 -0.941651 -0.0560501 -2.58176 -0.938907 -0.0401344 -2.67912 -0.939313 -0.0231775 -2.77728 -0.93687 -0.00617763 -2.87629 -0.93158 --0.0123194 -2.98336 -0.928687 --0.0309178 -3.09227 -0.922599 --0.0556113 -3.23476 -0.933541 --0.0773121 -3.36167 -0.93015 --0.105278 -3.52506 -0.941842 --0.13421 -3.68814 -0.948437 --0.152991 -3.80109 -0.922925 --0.178967 -3.94941 -0.911344 --0.205485 -4.10669 -0.899217 --0.236226 -4.28392 -0.889984 --0.265365 -4.45175 -0.871213 --0.300853 -4.65777 -0.861732 --0.34262 -4.90089 -0.859594 --0.378202 -5.1092 -0.835883 --0.4258 -5.38276 -0.827701 --0.472465 -5.65793 -0.810336 --0.526493 -5.97187 -0.795016 --0.587874 -6.32451 -0.779946 --0.651481 -6.69772 -0.75784 --0.725654 -7.12953 -0.736982 --0.810375 -7.61981 -0.714478 --0.906301 -8.17947 -0.688982 --1.01279 -8.79826 -0.655097 --1.13306 -9.49606 -0.612925 --1.2767 -10.3317 -0.567314 --1.43243 -11.2358 -0.501729 --1.48886 -11.5643 -0.337596 --1.52808 -11.7915 -0.152734 --1.60909 -12.2614 0.0201337 --1.88484 -13.8598 0.138928 --3.43493 -22.8716 -0.0151215 --3.56128 -23.6051 0.370871 --4.04928 -26.4398 0.763626 --4.62952 -29.8105 1.26138 --4.6357 -29.841 1.79037 --4.62072 -29.7536 2.31562 --4.64234 -29.8741 2.85146 --4.6486 -29.9064 3.38564 --4.64432 -29.8802 3.91688 --4.6411 -29.855 4.44898 --4.63846 -29.8396 4.98366 --4.63687 -29.8251 5.5203 --4.63427 -29.8105 6.05933 --2.9005 -19.738 4.71053 --2.79684 -19.1307 4.94796 --4.62636 -29.749 7.68966 --4.62215 -29.725 8.23883 --4.61263 -29.6624 8.78166 --4.61725 -29.686 9.35115 --4.61602 -29.679 9.91819 --4.61265 -29.653 10.4846 --4.61129 -29.6445 11.0622 --4.60825 -29.6248 11.6424 --4.60916 -29.6214 12.2355 --4.60487 -29.5982 12.8279 --4.57516 -29.417 13.3618 --4.60077 -29.5613 14.0403 --4.59593 -29.5301 14.6531 --4.5898 -29.4947 15.273 --4.57233 -29.3861 15.8645 --0.487637 -5.71587 4.01967 --0.465558 -5.58593 4.0776 --0.455935 -5.53147 4.17598 --0.462764 -5.56958 4.32929 --0.4529 -5.51113 4.42747 --0.421637 -5.32663 4.44401 --0.413699 -5.28378 4.54888 --0.405073 -5.22925 4.64756 --0.490789 -5.7279 5.14607 --0.474666 -5.63147 5.22902 --0.448322 -5.4797 5.26723 --0.435059 -5.39778 5.35742 --0.401096 -5.20056 5.35069 --0.38719 -5.12464 5.44208 --0.363817 -4.98879 5.47919 --0.296757 -4.59869 5.2765 --0.253696 -4.34603 5.18518 --0.222955 -4.16777 5.15637 --0.2255 -4.18545 5.32236 --0.231924 -4.21877 5.51188 --0.296866 -4.5935 6.08715 --0.240446 -4.26362 5.89071 --0.220222 -4.14666 5.92746 --0.217707 -4.12996 6.08502 --0.213945 -4.10927 6.24347 --0.207252 -4.07245 6.38689 --0.204684 -4.05585 6.56268 --0.198812 -4.01653 6.71509 --0.166861 -3.83354 6.66171 --0.146535 -3.71473 6.69548 --0.121674 -3.56833 6.6845 --0.110173 -3.50019 6.79801 --0.110706 -3.50518 7.04006 --0.118216 -3.54688 7.36235 --0.0919716 -3.39385 7.34513 --0.0806217 -3.33001 7.493 --0.0485595 -3.14304 7.39887 -0.000712731 -2.85876 7.08358 -0.000759931 -2.85602 7.36078 -0.0198269 -2.74182 7.40119 -0.0556645 -2.53744 7.21787 -0.103276 -2.25994 6.82462 -0.0875774 -2.34981 7.37893 -0.111931 -2.21004 7.33474 -0.119509 -2.16306 7.56266 -0.153699 -1.9669 7.3329 -0.154435 -1.95814 7.71193 -0.184435 -1.78425 7.53366 -0.210017 -1.63754 7.42875 -0.22307 -1.564 7.61247 -0.282739 -1.21947 6.58476 -0.294454 -1.15014 6.74267 -0.315507 -1.0284 6.6344 -0.313037 -1.03816 7.30272 -0.334256 -0.915106 7.22123 -0.340258 -0.878576 7.78189 -0.387581 -0.606479 7.40082 -0.405168 -0.503292 7.50035 -0.423976 -0.392707 7.52822 -0.444748 -0.273215 7.37441 -0.464208 -0.159783 7.23834 -0.483164 -0.0514108 7.04024 -0.12626 -1.85163 -0.956333 -0.114553 -1.91286 -0.951338 -0.101857 -1.97396 -0.944742 -0.087707 -2.04225 -0.943488 -0.0735081 -2.11145 -0.940288 -0.0562755 -2.19707 -0.948273 -0.0405795 -2.27432 -0.947469 -0.0247766 -2.35345 -0.944369 -0.00600694 -2.44796 -0.951406 --0.0113472 -2.5361 -0.949655 --0.0282255 -2.61682 -0.939461 --0.0480651 -2.71287 -0.938505 --0.0670097 -2.81084 -0.934657 --0.0869948 -2.9096 -0.92786 --0.109536 -3.01735 -0.923507 --0.134087 -3.14138 -0.926148 --0.161307 -3.27634 -0.929936 --0.194157 -3.43755 -0.944008 --0.225525 -3.59134 -0.948243 --0.249762 -3.71132 -0.92946 --0.278686 -3.85856 -0.920016 --0.307071 -3.99736 -0.90178 --0.341131 -4.1633 -0.891382 --0.378353 -4.34823 -0.883431 --0.419789 -4.55304 -0.876878 --0.462748 -4.76662 -0.867278 --0.506843 -4.98279 -0.850435 --0.555644 -5.2269 -0.836391 --0.611198 -5.49974 -0.82339 --0.671499 -5.80137 -0.810041 --0.737035 -6.12351 -0.791944 --0.811539 -6.49435 -0.775894 --0.891257 -6.88556 -0.7519 --0.981474 -7.33431 -0.728105 --1.08846 -7.86135 -0.705352 --1.20702 -8.44753 -0.675905 --1.33713 -9.09271 -0.636468 --1.49133 -9.8546 -0.593328 --1.67709 -10.7739 -0.545734 --1.77236 -11.2458 -0.409827 --1.83597 -11.5606 -0.240719 --1.89201 -11.8339 -0.0573793 --2.10299 -12.8766 0.08006 --3.64458 -20.5059 -0.0986832 --3.95492 -22.0404 0.212318 --4.11922 -22.8543 0.590494 --5.08542 -27.6305 0.996764 --5.45916 -29.4786 1.52157 --5.4525 -29.446 2.04566 --5.41698 -29.267 2.56146 --5.43293 -29.3431 3.08996 --5.4258 -29.3025 3.61206 --5.41614 -29.2531 4.13341 --5.40494 -29.1948 4.65381 --5.39639 -29.1473 5.17586 --5.38272 -29.0812 5.69586 --5.37009 -29.016 6.21641 --5.35588 -28.9408 6.73607 --5.26784 -28.5029 7.17779 --5.34637 -28.8895 7.80129 --5.30942 -28.7025 8.29776 --5.32226 -28.7621 8.85947 --5.30815 -28.6895 9.38966 --5.29967 -28.644 9.93144 --5.29432 -28.6179 10.4834 --5.28572 -28.571 11.0338 --5.26737 -28.4782 11.5718 --5.25461 -28.4124 12.1238 --5.22485 -28.2628 12.6468 --5.17362 -28.0044 13.1249 --5.29657 -28.6079 13.9917 --5.23444 -28.3014 14.4611 --5.511 -29.6607 15.7562 --0.65025 -5.66757 3.9461 --0.639797 -5.61607 4.04662 --0.623754 -5.53758 4.13156 --0.61761 -5.50826 4.24472 --0.633803 -5.5866 4.4247 --0.620368 -5.51856 4.51838 --0.641025 -5.62239 4.72508 --0.564189 -5.24073 4.60656 --0.649255 -5.65924 5.04334 --0.637165 -5.59752 5.14945 --0.633692 -5.58068 5.29068 --0.583971 -5.33675 5.25401 --0.583161 -5.33131 5.40492 --0.568239 -5.2553 5.4993 --0.468194 -4.76342 5.22481 --0.447752 -4.6605 5.28219 --0.512785 -4.98089 5.73964 --0.400276 -4.42668 5.36227 --0.375685 -4.30336 5.39098 --0.370579 -4.27532 5.51732 --0.362855 -4.23676 5.63662 --0.514077 -4.98383 6.64771 --0.335102 -4.10218 5.81494 --0.306207 -3.95569 5.81064 --0.413628 -4.48326 6.64963 --0.34075 -4.12643 6.38988 --0.311884 -3.98068 6.39072 --0.294339 -3.8936 6.46882 --0.253401 -3.69277 6.38177 --0.261906 -3.7313 6.64564 --0.22537 -3.55494 6.58555 --0.224216 -3.54675 6.7921 --0.206792 -3.46218 6.88013 --0.180841 -3.33191 6.88897 --0.208299 -3.46353 7.37592 --0.194698 -3.39519 7.51614 --0.162238 -3.23814 7.48647 --0.128056 -3.0671 7.41745 --0.0317301 -2.59587 6.68263 --0.00880449 -2.48247 6.69151 --0.0289299 -2.57659 7.19509 --0.0301423 -2.58052 7.51819 -0.0278165 -2.29658 7.10574 -0.0239166 -2.3152 7.49336 -0.0416367 -2.22672 7.59992 -0.0834373 -2.01929 7.34373 -0.10504 -1.91306 7.38832 -0.105592 -1.90887 7.79631 -0.152304 -1.67888 7.3947 -0.167296 -1.60644 7.57886 -0.227789 -1.31088 6.79776 -0.253221 -1.18269 6.68335 -0.271831 -1.0936 6.74282 -0.27444 -1.07635 7.23416 -0.293524 -0.981397 7.33138 -0.318789 -0.856604 7.22915 -0.32597 -0.818176 7.80923 -0.380025 -0.551118 7.43588 -0.401659 -0.44722 7.53445 -0.424509 -0.333388 7.51147 -0.448148 -0.21613 7.35656 -0.471153 -0.10239 7.06956 -0.147655 -1.51489 -0.956255 -0.0786989 -1.80973 -0.958306 -0.0665166 -1.8626 -0.947013 -0.0489495 -1.93718 -0.95534 -0.0352012 -1.99917 -0.947792 -0.0190607 -2.06729 -0.945534 -0.00287168 -2.13632 -0.941328 --0.0172878 -2.2207 -0.948155 --0.0365554 -2.30702 -0.952589 --0.0538248 -2.37768 -0.942088 --0.0755816 -2.47195 -0.947917 --0.094404 -2.55162 -0.939065 --0.11473 -2.63939 -0.933708 --0.139134 -2.74441 -0.936988 --0.162062 -2.84206 -0.931729 --0.183974 -2.93963 -0.923477 --0.211015 -3.05532 -0.92281 --0.24212 -3.18814 -0.928681 --0.277343 -3.33905 -0.940144 --0.312658 -3.49172 -0.946813 --0.342352 -3.61873 -0.934857 --0.372141 -3.74752 -0.918708 --0.406981 -3.8933 -0.907297 --0.44499 -4.05813 -0.899433 --0.484024 -4.22363 -0.886222 --0.528783 -4.41717 -0.879202 --0.578691 -4.62951 -0.873026 --0.630241 -4.85261 -0.863404 --0.682803 -5.07627 -0.84624 --0.738566 -5.31975 -0.827978 --0.806199 -5.61 -0.816647 --0.87901 -5.91979 -0.801117 --0.957614 -6.25919 -0.782988 --1.04817 -6.64706 -0.765699 --1.14388 -7.05426 -0.739816 --1.25637 -7.53984 -0.717071 --1.3901 -8.11145 -0.695458 --1.52389 -8.68508 -0.653821 --1.68372 -9.37448 -0.611919 --1.88361 -10.229 -0.570935 --2.09598 -11.1419 -0.507574 --2.16021 -11.4174 -0.337193 --2.19039 -11.5453 -0.142864 --2.2939 -11.9899 0.0295896 --2.65074 -13.5212 0.149078 --4.28463 -20.5297 0.0767537 --4.40763 -21.0574 0.430745 --5.50113 -25.7482 0.765505 --5.57462 -26.0597 1.22968 --5.56851 -26.0329 1.69619 --5.55411 -25.9686 2.16041 --5.57105 -26.0414 2.63168 --5.60107 -26.1653 3.11066 --5.57864 -26.0674 3.57347 --5.56979 -26.0286 4.04128 --5.56625 -26.0114 4.5125 --5.5561 -25.9677 4.98106 --5.54953 -25.9336 5.45242 --5.54054 -25.8927 5.92383 --5.52642 -25.8331 6.39298 --5.5077 -25.747 6.8573 --5.41789 -25.3598 7.24785 --5.53296 -25.853 7.86152 --5.48353 -25.6388 8.29709 --5.75446 -26.7988 9.14717 --5.75203 -26.7861 9.66827 --5.74546 -26.7547 10.1882 --5.73476 -26.7045 10.7063 --5.49582 -25.6784 10.8545 --5.48138 -25.6152 11.3571 --5.48013 -25.606 11.8873 --5.45749 -25.5064 12.3844 --5.44447 -25.4512 12.9061 --5.2903 -24.787 13.1366 --0.891559 -5.95191 4.04702 --0.833264 -5.70065 4.04708 --0.812697 -5.61353 4.12967 --0.794594 -5.53415 4.21505 --0.79688 -5.54615 4.35433 --0.82681 -5.67113 4.56823 --0.816651 -5.62506 4.68004 --0.824215 -5.65946 4.84649 --0.811366 -5.60178 4.9531 --0.81743 -5.6281 5.12244 --0.796888 -5.54169 5.21086 --0.789405 -5.50764 5.34 --0.777915 -5.45639 5.45675 --0.710711 -5.16958 5.3758 --0.71543 -5.19062 5.55219 --0.66677 -4.98124 5.52534 --0.645887 -4.8885 5.60033 --0.509873 -4.30882 5.19874 --0.462636 -4.10485 5.14213 --0.46061 -4.09515 5.27931 --0.504882 -4.28243 5.63485 --0.490965 -4.22322 5.73307 --0.549964 -4.47744 6.19743 --0.724941 -5.22351 7.2805 --0.607498 -4.71892 6.87942 --0.597259 -4.67375 7.03362 --0.397356 -3.82262 6.11692 --0.366206 -3.68892 6.12035 --0.344061 -3.59052 6.16953 --0.387955 -3.77788 6.64511 --0.372682 -3.71381 6.76201 --0.338833 -3.56791 6.7518 --0.330007 -3.53013 6.91719 --0.307969 -3.43465 6.98823 --0.263759 -3.24549 6.89222 --0.305492 -3.41898 7.46794 --0.258937 -3.22355 7.35979 --0.238066 -3.13194 7.45236 --0.245905 -3.16463 7.81447 --0.0942174 -2.51909 6.67823 --0.0774499 -2.44596 6.77754 --0.0567111 -2.35489 6.839 --0.0311293 -2.24798 6.86171 -0.0088606 -2.07566 6.70438 --0.0472687 -2.31055 7.70223 --0.000892497 -2.11242 7.48661 -0.0301149 -1.97883 7.44729 -0.0622872 -1.84139 7.38595 -0.0867448 -1.738 7.43726 -0.111434 -1.63019 7.47705 -0.14462 -1.49062 7.37895 -0.203968 -1.23805 6.74085 -0.223279 -1.15602 6.84061 -0.218392 -1.17212 7.49955 -0.252632 -1.02649 7.30272 -0.281896 -0.901891 7.20148 -0.306373 -0.796287 7.21674 -0.353063 -0.594833 7.351 -0.377631 -0.489024 7.39068 -0.40225 -0.383834 7.45833 -0.425125 -0.28424 7.714 -0.454417 -0.160232 7.31832 -0.48023 -0.0502275 7.0403 -0.0992822 -1.52031 -0.942573 -0.016143 -1.8333 -0.963566 -0.00437315 -1.87978 -0.94428 --0.0137207 -1.94692 -0.944861 --0.0333272 -2.02224 -0.950336 --0.0514572 -2.09019 -0.946973 --0.0696364 -2.15905 -0.941762 --0.0943054 -2.25144 -0.953873 --0.115038 -2.32927 -0.950706 --0.135758 -2.407 -0.945343 --0.158043 -2.49384 -0.943725 --0.181311 -2.5805 -0.939607 --0.206141 -2.67625 -0.938635 --0.234528 -2.78094 -0.940404 --0.259443 -2.87839 -0.933441 --0.285337 -2.97564 -0.923578 --0.317874 -3.09919 -0.926294 --0.35547 -3.23979 -0.935046 --0.399753 -3.40757 -0.95383 --0.434963 -3.54259 -0.948454 --0.462047 -3.64388 -0.920462 --0.504911 -3.80578 -0.920222 --0.538654 -3.93403 -0.897767 --0.581578 -4.09743 -0.88754 --0.630718 -4.28064 -0.879701 --0.683952 -4.48174 -0.873357 --0.739828 -4.69355 -0.863866 --0.798283 -4.91505 -0.850676 --0.864437 -5.16429 -0.839876 --0.933219 -5.42414 -0.82373 --1.00881 -5.71366 -0.80738 --1.09313 -6.03166 -0.789471 --1.19191 -6.40619 -0.776193 --1.2969 -6.80101 -0.754668 --1.41121 -7.23415 -0.728491 --1.55139 -7.7633 -0.707932 --1.69163 -8.29453 -0.668746 --1.85671 -8.92149 -0.62829 --2.06051 -9.69163 -0.589243 --2.30057 -10.5976 -0.54227 --2.46915 -11.2368 -0.4288 --2.56866 -11.6148 -0.26446 --2.62756 -11.8364 -0.0729412 --2.92053 -12.9425 0.0618232 --4.51581 -18.9815 -0.0322329 --4.69626 -19.6619 0.286295 --5.47074 -22.5902 0.588113 --5.93428 -24.3435 0.995551 --6.01551 -24.6494 1.44058 --5.95908 -24.4355 1.87823 --5.88829 -24.1658 2.30563 --6.06806 -24.8439 2.79235 --6.06471 -24.8287 3.24234 --6.06247 -24.8155 3.69332 --6.0594 -24.8052 4.14576 --6.05067 -24.7673 4.59589 --6.04104 -24.7314 5.04712 --6.04024 -24.7258 5.5051 --6.03537 -24.7024 5.96218 --6.02036 -24.6437 6.41366 --6.00799 -24.5958 6.86898 --5.92172 -24.2669 7.25402 --6.00648 -24.5872 7.81011 --5.96405 -24.422 8.23914 --6.00204 -24.5641 8.76372 --5.99092 -24.5212 9.23692 --5.99257 -24.5247 9.73041 --5.98245 -24.4823 10.2129 --5.97136 -24.4407 10.7 --5.9445 -24.3359 11.166 --5.91264 -24.2146 11.6273 --5.87264 -24.0573 12.0749 --5.84584 -23.9541 12.5499 --1.05987 -5.88152 3.96709 --5.62598 -23.1195 13.1808 --5.90564 -24.1729 14.2909 --7.47476 -30.0923 18.2486 --1.00998 -5.69253 4.39931 --0.995097 -5.63418 4.50167 --1.00491 -5.67254 4.66642 --0.963059 -5.51277 4.70294 --0.981857 -5.58524 4.89696 --0.966955 -5.52671 5.00292 --0.981796 -5.58341 5.19614 --0.928475 -5.38111 5.19404 --0.902015 -5.27883 5.26593 --0.896319 -5.25824 5.40465 --0.854729 -5.1021 5.42833 --0.905102 -5.2894 5.75587 --0.813446 -4.94243 5.60313 --0.62594 -4.23425 5.08484 --0.601249 -4.14374 5.1398 --0.579943 -4.05979 5.1999 --0.79397 -4.86808 6.2147 --0.781575 -4.81918 6.34577 --0.75025 -4.70191 6.40217 --0.695874 -4.49613 6.35043 --0.67846 -4.42947 6.46148 --0.717091 -4.57464 6.84374 --0.523989 -3.84438 6.09024 --0.483842 -3.69329 6.07113 --0.488164 -3.7096 6.28262 --0.51901 -3.8248 6.65184 --0.471096 -3.64232 6.58748 --0.423453 -3.46407 6.51832 --0.440077 -3.52359 6.83434 --0.44422 -3.53951 7.09427 --0.493437 -3.72066 7.66811 --0.343625 -3.15829 6.89482 --0.356516 -3.20745 7.24225 --0.350213 -3.18097 7.45968 --0.331456 -3.11008 7.59704 --0.183445 -2.55251 6.66441 --0.174821 -2.51944 6.85586 --0.143611 -2.40103 6.85443 --0.192184 -2.58117 7.61084 --0.0714619 -2.13014 6.7416 --0.03787 -2.0031 6.69468 --0.0920339 -2.20166 7.61873 --0.0596319 -2.08073 7.62899 --0.00617685 -1.87869 7.35957 -0.0273098 -1.75455 7.33482 -0.0487893 -1.67075 7.4526 -0.0678975 -1.59602 7.62732 -0.138913 -1.3319 6.97316 -0.175875 -1.19277 6.81048 -0.178004 -1.18349 7.30242 -0.210223 -1.06144 7.23412 -0.237653 -0.957384 7.26226 -0.262777 -0.861357 7.34798 -0.295951 -0.73714 7.2236 -0.319998 -0.645287 7.3653 -0.348562 -0.538657 7.386 -0.375123 -0.434026 7.44475 -0.402734 -0.33058 7.54151 -0.432436 -0.218255 7.49653 -0.464164 -0.100953 7.04961 -0.0574986 -1.49779 -0.964051 -0.0462161 -1.53625 -0.944263 --0.044416 -1.84121 -0.954092 --0.0595842 -1.89382 -0.94139 --0.0821311 -1.96802 -0.947904 --0.103727 -2.04316 -0.952274 --0.122385 -2.10368 -0.941364 --0.142555 -2.17237 -0.935248 --0.166694 -2.25641 -0.939964 --0.191876 -2.34126 -0.942132 --0.217044 -2.42599 -0.941902 --0.240797 -2.50437 -0.933183 --0.271088 -2.60717 -0.939539 --0.296388 -2.69451 -0.93147 --0.325186 -2.78981 -0.926291 --0.3566 -2.89511 -0.923607 --0.386995 -3.0003 -0.917629 --0.428478 -3.13878 -0.928765 --0.467543 -3.27091 -0.930516 --0.519312 -3.44638 -0.951778 --0.549342 -3.54659 -0.925724 --0.588508 -3.68108 -0.914443 --0.628706 -3.8163 -0.898914 --0.676577 -3.97854 -0.891316 --0.733111 -4.16767 -0.890449 --0.783599 -4.34042 -0.875608 --0.841236 -4.53187 -0.862304 --0.908146 -4.76026 -0.856633 --0.973506 -4.98016 -0.839875 --1.04918 -5.23781 -0.8283 --1.12075 -5.47793 -0.801897 --1.2164 -5.80071 -0.792993 --1.32091 -6.15388 -0.780634 --1.4315 -6.52538 -0.761125 --1.5551 -6.94618 -0.740206 --1.69456 -7.41398 -0.715368 --1.84437 -7.92085 -0.682031 --2.01162 -8.48449 -0.641581 --2.21451 -9.17344 -0.60254 --2.45588 -9.98518 -0.558304 --2.72156 -10.8849 -0.496565 --2.89226 -11.4608 -0.364076 --3.05408 -12.007 -0.208077 --3.15642 -12.3503 -0.0160921 --4.70122 -17.5716 -0.124565 --4.92788 -18.3351 0.161201 --5.11294 -18.9592 0.478079 --6.23373 -22.7428 0.787982 --6.31117 -23.0013 1.20421 --6.2955 -22.9464 1.62152 --6.29395 -22.9428 2.03965 --6.46439 -23.5147 2.49474 --6.51289 -23.6773 2.9381 --6.42923 -23.3924 3.34394 --6.61473 -24.0171 3.84849 --6.61149 -24.0034 4.29034 --6.59711 -23.9544 4.72827 --6.56995 -23.8594 5.15876 --6.50401 -23.6357 5.56333 --6.43052 -23.3858 5.95695 --6.36442 -23.1587 6.34943 --6.35637 -23.1314 6.78658 --6.25024 -22.7703 7.13667 --6.35619 -23.1259 7.68372 --6.30651 -22.9554 8.08661 --7.03535 -25.4124 9.35081 --7.03582 -25.414 9.86282 --7.02863 -25.3882 10.3708 --6.73697 -24.4009 10.5096 --6.30544 -22.9448 10.4212 --6.27444 -22.8366 10.8604 --6.26971 -22.8169 11.3423 --6.25892 -22.7797 11.8224 --6.17416 -22.491 12.1838 --6.19454 -22.5581 12.7254 --6.04989 -22.0689 12.9773 --6.28505 -22.8594 13.9401 --6.21785 -22.6315 14.3493 --1.08998 -5.34914 4.83382 --1.13548 -5.50201 5.09315 --1.15464 -5.56411 5.29378 --1.0333 -5.15646 5.12664 --1.05749 -5.23645 5.3444 --0.974632 -4.95572 5.26105 --1.14184 -5.51793 5.91549 --1.18096 -5.65019 6.21391 --0.770315 -4.2689 5.08003 --0.736043 -4.15117 5.10896 --0.878142 -4.62858 5.74454 --0.838924 -4.49522 5.77106 --0.820864 -4.43402 5.87396 --0.836447 -4.48861 6.10873 --0.820711 -4.43353 6.22717 --0.759307 -4.22679 6.16262 --0.838932 -4.49386 6.68632 --0.687109 -3.98057 6.21962 --0.613541 -3.73431 6.07706 --0.599064 -3.68331 6.1925 --0.738896 -4.1527 7.07277 --0.640592 -3.82206 6.80144 --0.602662 -3.69302 6.82017 --0.541422 -3.48657 6.70939 --0.520746 -3.41538 6.81468 --0.552893 -3.5218 7.23785 --0.570437 -3.5827 7.60561 --0.439389 -3.14242 7.03721 --0.421184 -3.08058 7.17342 --0.458997 -3.20344 7.70286 --0.275921 -2.59087 6.66817 --0.235842 -2.45608 6.62353 --0.358906 -2.86678 7.87777 --0.219978 -2.39812 7.04209 --0.160702 -2.20242 6.83373 --0.106059 -2.01727 6.62952 --0.105935 -2.01495 6.93868 --0.150343 -2.16189 7.74259 --0.0885211 -1.95367 7.46631 --0.046182 -1.81277 7.3859 --0.00616287 -1.67744 7.3119 --0.0245756 -1.73694 8.00951 -0.0511497 -1.4826 7.44701 -0.0980848 -1.32526 7.23882 -0.128539 -1.22063 7.262 -0.161281 -1.10967 7.25382 -0.178865 -1.04991 7.54923 -0.2289 -0.881596 7.16196 -0.259125 -0.781376 7.19698 -0.268364 -0.745153 7.83612 -0.316556 -0.586622 7.37094 -0.346994 -0.484187 7.43058 -0.374501 -0.387763 7.6281 -0.407333 -0.277111 7.65418 -0.442627 -0.159037 7.36839 -0.476237 -0.0494765 7.03037 -0.00449158 -1.51274 -0.96599 --0.0101917 -1.55736 -0.953186 --0.107316 -1.85433 -0.951454 --0.129341 -1.92022 -0.951872 --0.148953 -1.97981 -0.943605 --0.173538 -2.05473 -0.947067 --0.19811 -2.12955 -0.948431 --0.22027 -2.19807 -0.94121 --0.249854 -2.28904 -0.950858 --0.273046 -2.35829 -0.939389 --0.3012 -2.44278 -0.937951 --0.328402 -2.5282 -0.93397 --0.362675 -2.63069 -0.938815 --0.393417 -2.72494 -0.934977 --0.430227 -2.83626 -0.939071 --0.461112 -2.9332 -0.929092 --0.504024 -3.06239 -0.936772 --0.54446 -3.18426 -0.935317 --0.597546 -3.34849 -0.954122 --0.63303 -3.45571 -0.934596 --0.671063 -3.57187 -0.916217 --0.721282 -3.72308 -0.911752 --0.767965 -3.86602 -0.898004 --0.82075 -4.02683 -0.887844 --0.882255 -4.2155 -0.883864 --0.944781 -4.40481 -0.87364 --1.00989 -4.60385 -0.860616 --1.08108 -4.82058 -0.847683 --1.16465 -5.07596 -0.840277 --1.24816 -5.3309 -0.824082 --1.34148 -5.61535 -0.807873 --1.44446 -5.92721 -0.789951 --1.55878 -6.27747 -0.771467 --1.69254 -6.68385 -0.755201 --1.83506 -7.11941 -0.731234 --1.99959 -7.6208 -0.706387 --2.17385 -8.15109 -0.669441 --2.37892 -8.77672 -0.630706 --2.61217 -9.48751 -0.583691 --2.9044 -10.3783 -0.537444 --3.22834 -11.3635 -0.471126 --3.67905 -12.7377 -0.412076 --4.20202 -14.3306 -0.323061 --4.84904 -16.3027 -0.203863 --5.16621 -17.2684 0.0430693 --5.29626 -17.6617 0.346424 --6.54238 -21.4606 0.600184 --6.65363 -21.7964 0.994299 --6.69368 -21.9164 1.39696 --6.61846 -21.6877 1.79141 --6.52341 -21.3956 2.1746 --6.81512 -22.2829 2.63409 --6.81827 -22.2903 3.04668 --6.9455 -22.6783 3.50274 --7.05531 -23.0106 3.96756 --7.05098 -22.9946 4.39528 --7.05041 -22.9913 4.82654 --6.915 -22.5775 5.18416 --7.04545 -22.9716 5.69351 --6.82938 -22.3141 5.98604 --6.69267 -21.8938 6.3143 --6.67763 -21.8491 6.72781 --6.44688 -21.1444 6.95756 --6.67874 -21.8464 7.58745 --6.63546 -21.7151 7.9819 --7.01887 -22.8791 8.81824 --6.82647 -22.2869 10.4716 --6.91843 -22.5633 11.0747 --6.7626 -22.0889 11.3455 --6.57859 -21.5266 11.5597 --6.53149 -21.3826 11.9711 --6.49643 -21.273 12.4031 --6.45293 -21.1393 12.825 --6.28732 -20.6325 13.0323 --6.57052 -21.4914 14.0543 --6.46359 -21.1657 14.3802 --1.50961 -6.10194 5.66582 --1.37253 -5.68281 5.50653 --1.58113 -6.31807 6.19486 --1.55343 -6.23076 6.31023 --1.27941 -5.39958 5.76842 --1.21074 -5.19104 5.7489 --1.18315 -5.10408 5.83686 --1.05279 -4.71032 5.62309 --1.03739 -4.66047 5.73678 --1.00649 -4.56754 5.8076 --0.963282 -4.43446 5.83321 --0.968671 -4.45075 6.02368 --0.947372 -4.38572 6.12697 --0.940454 -4.36237 6.28227 --0.888997 -4.20724 6.2774 --0.807145 -3.95701 6.14411 --0.73869 -3.74813 6.05058 --0.692115 -3.60708 6.03893 --0.824162 -4.00824 6.80805 --0.790759 -3.90674 6.87273 --0.783706 -3.88282 7.05974 --0.712958 -3.66808 6.94568 --0.702308 -3.63386 7.12235 --0.608841 -3.35107 6.87123 --0.575395 -3.2482 6.92322 --0.525131 -3.09404 6.87705 --0.706375 -3.6426 8.21315 --0.529042 -3.10419 7.41484 --0.382056 -2.65998 6.74302 --0.323768 -2.48455 6.60986 --0.45017 -2.86265 7.76909 --0.438282 -2.82813 8.01402 --0.280968 -2.35102 7.12855 --0.194112 -2.08655 6.72279 --0.170333 -2.01365 6.82608 --0.261362 -2.288 7.9967 --0.247843 -2.24486 8.27553 --0.195392 -2.08518 8.18183 --0.179463 -2.03628 8.47859 --0.104847 -1.81091 8.11888 --0.0187576 -1.55051 7.54962 -0.0170786 -1.43945 7.56745 -0.0643385 -1.29684 7.42665 -0.0895891 -1.22072 7.61638 -0.112839 -1.1471 7.85451 -0.178189 -0.949844 7.32153 -0.214891 -0.838348 7.28857 -0.252636 -0.723981 7.21371 -0.279382 -0.641887 7.44488 -0.313935 -0.535106 7.45572 -0.349474 -0.428478 7.46466 -0.382084 -0.32837 7.62142 -0.419704 -0.214485 7.51655 -0.458234 -0.0990844 7.03964 --0.0479813 -1.5193 -0.959836 --0.173028 -1.86426 -0.948556 --0.197044 -1.92999 -0.948069 --0.218647 -1.98942 -0.938997 --0.247623 -2.07037 -0.948141 --0.274184 -2.14501 -0.9484 --0.301791 -2.22049 -0.946509 --0.325928 -2.28873 -0.936186 --0.359542 -2.38028 -0.942075 --0.392142 -2.47175 -0.945272 --0.425843 -2.56502 -0.945569 --0.459526 -2.65815 -0.94297 --0.494251 -2.75208 -0.937622 --0.534044 -2.86313 -0.939908 --0.571364 -2.96689 -0.933558 --0.617198 -3.09479 -0.939181 --0.670206 -3.24161 -0.950435 --0.720674 -3.38007 -0.952104 --0.756572 -3.47792 -0.92603 --0.809677 -3.62705 -0.923652 --0.857738 -3.75978 -0.907797 --0.911903 -3.91038 -0.895829 --0.976729 -4.08777 -0.890784 --1.04058 -4.26592 -0.879699 --1.11508 -4.47076 -0.873641 --1.18966 -4.67724 -0.860492 --1.27393 -4.91137 -0.850225 --1.36178 -5.15507 -0.835058 --1.46286 -5.43526 -0.823416 --1.56501 -5.7169 -0.801884 --1.68655 -6.05385 -0.786515 --1.82591 -6.43688 -0.771667 --1.97404 -6.84915 -0.750115 --2.14357 -7.31721 -0.726781 --2.32644 -7.82415 -0.694539 --2.52714 -8.3777 -0.653179 --2.77739 -9.07092 -0.616537 --3.066 -9.86871 -0.570897 --3.38827 -10.76 -0.509224 --3.82147 -11.9607 -0.452325 --4.32049 -13.3398 -0.369605 --4.93397 -15.0387 -0.262789 --5.33496 -16.1456 -0.0547251 --5.49998 -16.6022 0.224433 --5.92493 -17.7776 0.499699 --6.87921 -20.4161 0.804349 --6.91737 -20.5203 1.18429 --6.91475 -20.5135 1.56501 --6.89749 -20.4636 1.94391 --6.93201 -20.5577 2.33073 --6.9978 -20.7385 2.72924 --6.99378 -20.7256 3.11575 --6.99093 -20.7155 3.50342 --6.98473 -20.6996 3.89138 --6.9771 -20.6768 4.27958 --6.96705 -20.6471 4.66764 --6.96528 -20.6386 5.06119 --6.95304 -20.6059 5.45159 --6.95261 -20.6032 5.85064 --6.94363 -20.575 6.24619 --6.94087 -20.5672 6.64978 --6.848 -20.3085 6.98258 --6.9651 -20.6312 7.49192 --6.94536 -20.5744 7.8919 --6.95917 -20.6101 8.32658 --6.9432 -20.5666 8.73804 --6.93535 -20.542 9.16051 --6.92754 -20.5182 9.58811 --6.91372 -20.4779 10.0136 --6.9 -20.4392 10.444 --6.88975 -20.409 10.8841 --6.87952 -20.3794 11.3302 --6.86926 -20.3495 11.7827 --6.7716 -20.0774 12.108 --6.79728 -20.1484 12.6268 --6.64815 -19.7332 12.8663 --6.9115 -20.4589 13.809 --6.84615 -20.2775 14.2077 --1.72043 -6.12439 5.6441 --1.70168 -6.06986 5.77496 --1.7189 -6.1173 5.99037 --1.59298 -5.76933 5.87911 --1.38494 -5.19527 5.55314 --1.42725 -5.31264 5.82422 --1.32275 -5.02104 5.72339 --1.28887 -4.92889 5.80234 --1.28564 -4.91714 5.96193 --1.16842 -4.59423 5.8003 --1.16548 -4.58731 5.96324 --1.35007 -5.09386 6.70756 --1.10579 -4.42111 6.1305 --1.09318 -4.38576 6.27175 --1.17073 -4.59829 6.72486 --1.05236 -4.27014 6.50849 --1.0409 -4.23796 6.66523 --1.03413 -4.21835 6.84615 --1.19567 -4.66451 7.70318 --0.93776 -3.953 6.89344 --0.966459 -4.03145 7.2378 --0.878093 -3.78852 7.0867 --0.860506 -3.73781 7.24039 --0.84174 -3.68416 7.39412 --0.766542 -3.47868 7.28069 --0.633446 -3.111 6.84832 --0.595844 -3.00499 6.88762 --0.644332 -3.13846 7.41264 --0.643137 -3.13304 7.6846 --0.524673 -2.80905 7.26359 --0.532906 -2.83066 7.60593 --0.50227 -2.74396 7.7125 --0.474072 -2.66582 7.84564 --0.291528 -2.16297 6.8428 --0.219236 -1.96516 6.5918 --0.213384 -1.94848 6.85377 --0.370151 -2.37691 8.55794 --0.294027 -2.16536 8.30534 --0.243621 -2.02636 8.27734 --0.224335 -1.97113 8.56436 --0.125633 -1.70123 7.99976 --0.04556 -1.48099 7.56357 --0.0183563 -1.40535 7.7463 -0.0350704 -1.2591 7.58527 -0.0409356 -1.23995 8.11895 -0.0865053 -1.11467 8.09156 -0.13771 -0.97165 7.92339 -0.210761 -0.771983 7.24647 -0.210951 -0.768536 8.18386 -0.27788 -0.585863 7.48048 -0.319583 -0.470462 7.3707 -0.358048 -0.364563 7.36854 -0.392594 -0.268667 7.58417 -0.433825 -0.155498 7.36837 -0.473605 -0.0466984 6.78034 --0.100392 -1.52484 -0.953332 --0.217584 -1.82195 -0.958678 --0.241138 -1.88038 -0.952046 --0.267084 -1.94494 -0.950604 --0.293139 -2.01141 -0.947264 --0.325102 -2.09212 -0.9552 --0.351133 -2.15839 -0.947866 --0.380729 -2.23369 -0.94477 --0.416226 -2.32317 -0.951851 --0.449309 -2.40635 -0.950147 --0.482437 -2.4904 -0.945897 --0.518065 -2.58248 -0.944739 --0.554734 -2.67536 -0.940733 --0.594957 -2.77717 -0.939267 --0.638673 -2.8869 -0.939892 --0.68845 -3.01366 -0.947349 --0.735751 -3.13309 -0.945571 --0.796185 -3.28659 -0.959253 --0.831519 -3.37529 -0.930129 --0.886001 -3.51421 -0.925544 --0.944022 -3.66193 -0.920802 --0.996001 -3.7933 -0.902587 --1.06215 -3.9595 -0.896183 --1.13089 -4.1355 -0.888078 --1.19709 -4.30314 -0.870289 --1.28462 -4.52444 -0.868144 --1.3686 -4.73737 -0.854819 --1.46328 -4.97786 -0.843974 --1.56964 -5.24577 -0.833806 --1.67961 -5.52416 -0.816992 --1.80026 -5.82992 -0.798662 --1.94585 -6.19973 -0.787531 --1.7756 -5.76676 -0.547415 --2.264 -7.00571 -0.740803 --2.45438 -7.48734 -0.713267 --2.66619 -8.02556 -0.679603 --1.66945 -5.49635 -0.0432704 --1.66792 -5.49316 0.0630943 --1.65568 -5.46234 0.173336 --1.64328 -5.4286 0.282032 --1.45796 -4.95757 0.438476 --1.55245 -5.19809 0.509696 --1.66112 -5.47456 0.586982 --5.67008 -15.6335 0.114019 --5.94247 -16.3239 0.381745 --7.09418 -19.2421 0.632322 --7.35307 -19.8966 0.99321 --7.37409 -19.9489 1.36748 --7.15129 -19.3821 1.72102 --7.06118 -19.1534 2.07263 --7.38371 -19.9686 2.4943 --7.38453 -19.9688 2.87138 --7.33464 -19.8424 3.23529 --7.38155 -19.9595 3.62794 --7.38241 -19.9606 4.00906 --7.38078 -19.9537 4.39089 --7.36873 -19.9236 4.76999 --7.3659 -19.9137 5.15466 --7.35971 -19.8979 5.54012 --7.34046 -19.8481 5.91952 --7.24441 -19.6029 6.24775 --7.23462 -19.5773 6.63291 --7.09148 -19.2138 6.91676 --7.23613 -19.5778 7.42832 --7.21102 -19.5142 7.8101 --7.34381 -19.8489 8.34117 --7.33394 -19.8232 8.75014 --7.32861 -19.8068 9.16742 --7.32688 -19.8007 9.59403 --7.31463 -19.7695 10.0151 --7.28332 -19.6872 10.4172 --7.27916 -19.6746 10.857 --7.17857 -19.4201 11.1766 --7.11562 -19.2602 11.544 --7.06074 -19.1183 11.9226 --7.04477 -19.0763 12.3621 --6.98062 -18.9133 12.7334 --6.81051 -18.4804 12.9321 --7.12256 -19.2691 13.9391 --7.01718 -19.0017 14.2607 --1.90727 -6.0794 5.57545 --1.85966 -5.95903 5.65362 --1.81789 -5.85291 5.74065 --1.49444 -5.03428 5.22829 --1.56085 -5.20386 5.52972 --1.6024 -5.30791 5.78732 --1.7436 -5.66445 6.29278 --1.69015 -5.52934 6.35157 --1.55685 -5.18973 6.20223 --1.33244 -4.62251 5.79891 --1.35293 -4.67516 6.02631 --1.52307 -5.10377 6.68138 --1.48134 -4.99798 6.76171 --1.56242 -5.20244 7.21134 --1.60711 -5.31421 7.57206 --1.56284 -5.20002 7.66318 --1.19056 -4.26045 6.65655 --1.17691 -4.22534 6.81453 --1.25068 -4.40979 7.29216 --1.07728 -3.9733 6.88058 --1.01691 -3.81927 6.8643 --0.978785 -3.72277 6.935 --0.952336 -3.65624 7.05441 --0.951286 -3.65095 7.28322 --0.980675 -3.72635 7.66789 --1.02839 -3.8454 8.16116 --0.696301 -3.00665 6.83315 --0.664002 -2.92427 6.91519 --0.697847 -3.00984 7.35226 --0.752372 -3.14695 7.93807 --0.581123 -2.71544 7.26212 --0.633036 -2.84362 7.86931 --0.577476 -2.70259 7.84809 --0.372205 -2.1872 6.82247 --0.319197 -2.05254 6.75062 --0.331767 -2.08285 7.15479 --0.245415 -1.86376 6.82425 --0.359882 -2.15138 8.12313 --0.312385 -2.02987 8.14338 --0.309453 -2.02118 8.58417 --0.217557 -1.78972 8.18641 --0.146341 -1.6103 7.94734 --0.0967299 -1.48436 7.91809 --0.0449562 -1.35411 7.85688 --0.0560519 -1.37986 8.63718 -0.0261551 -1.17132 8.1498 -0.0822407 -1.03206 8.01282 -0.164711 -0.824819 7.31815 -0.203977 -0.72417 7.35259 -0.236714 -0.64191 7.57421 -0.281482 -0.526643 7.48564 -0.320902 -0.426315 7.57437 -0.362487 -0.322692 7.6513 -0.406909 -0.210703 7.51654 -0.452302 -0.0962069 7.0096 --0.281648 -1.82159 -0.948689 --0.311999 -1.8923 -0.955126 --0.336535 -1.95054 -0.945894 --0.364521 -2.01585 -0.941699 --0.396013 -2.0892 -0.942091 --0.43341 -2.17675 -0.953061 --0.462476 -2.24369 -0.942571 --0.500959 -2.33293 -0.948344 --0.535971 -2.41493 -0.945485 --0.574542 -2.5059 -0.945766 --0.614094 -2.59667 -0.943247 --0.657201 -2.69638 -0.943368 --0.70386 -2.80501 -0.945532 --0.747047 -2.90639 -0.939062 --0.797235 -3.02375 -0.939472 --0.862554 -3.17508 -0.955633 --0.913808 -3.29395 -0.947551 --0.958144 -3.39855 -0.926298 --1.02105 -3.54409 -0.923937 --1.08048 -3.68236 -0.912344 --1.13988 -3.8204 -0.896157 --1.21451 -3.99418 -0.891129 --1.2891 -4.16767 -0.880108 --1.37083 -4.35985 -0.870324 --1.46877 -4.58753 -0.8679 --1.55959 -4.79784 -0.850657 --1.65761 -5.02773 -0.832304 --1.77181 -5.29295 -0.817816 --1.88245 -5.54973 -0.790949 --1.79907 -5.35661 -0.618365 --1.79508 -5.34627 -0.506361 --1.80164 -5.36077 -0.402278 --1.79187 -5.33769 -0.289436 --1.79264 -5.33942 -0.183816 --1.79684 -5.34807 -0.0804363 --1.79998 -5.35578 0.0229905 --1.80655 -5.37038 0.124876 --1.80391 -5.36534 0.22954 --1.80576 -5.36812 0.332716 --1.81812 -5.3955 0.432865 --1.84116 -5.45039 0.531533 --1.86402 -5.50219 0.63205 --1.8426 -5.45202 0.739178 --1.83182 -5.42842 0.843678 --3.53321 -9.38986 0.907516 --7.42775 -18.459 1.16826 --7.41718 -18.4353 1.51826 --7.40526 -18.4056 1.86745 --7.44583 -18.4987 2.22423 --7.65306 -18.9802 2.61832 --7.633 -18.9325 2.97668 --7.78307 -19.2814 3.3834 --7.78516 -19.2858 3.75579 --7.77317 -19.2562 4.12461 --7.77054 -19.2488 4.49819 --7.75736 -19.2161 4.86866 --7.74541 -19.1873 5.24102 --7.74627 -19.1884 5.62215 --7.58653 -18.8157 5.90906 --7.49083 -18.592 6.22574 --7.48465 -18.5759 6.59947 --7.33546 -18.2274 6.86921 --7.4828 -18.569 7.36476 --7.46037 -18.5158 7.73546 --7.34607 -18.2485 8.02614 --7.56227 -18.7448 10.29 --8.12133 -20.0442 11.3976 --7.43356 -18.4434 11.001 --7.36343 -18.2799 11.3498 --7.34074 -18.2246 11.7623 --7.27282 -18.0647 12.1168 --7.28384 -18.0896 12.5902 --7.12206 -17.7125 12.8068 --7.42383 -18.4113 13.7589 --7.34785 -18.235 14.1289 --2.06077 -5.9453 5.78635 --1.97439 -5.74345 5.79518 --1.6439 -4.97523 5.3063 --1.85502 -5.46548 5.90239 --1.77911 -5.2879 5.91468 --1.78585 -5.30303 6.28813 --1.80942 -5.35766 6.53267 --1.97728 -5.74639 7.14511 --1.93149 -5.64082 7.24625 --1.86941 -5.49536 7.30177 --1.80397 -5.34364 7.34625 --1.90457 -5.5759 7.85864 --1.72371 -5.15489 7.56833 --1.32287 -4.22429 6.57759 --1.2725 -4.10596 6.618 --1.23831 -4.02617 6.71097 --1.25253 -4.0595 6.97152 --1.16306 -3.85095 6.87678 --1.107 -3.7202 6.89151 --1.04641 -3.57967 6.88631 --1.03751 -3.55855 7.07995 --1.01244 -3.4992 7.21484 --1.20881 -3.95371 8.30549 --0.822463 -3.05774 6.88291 --0.749373 -2.88819 6.79079 --0.687714 -2.74406 6.73834 --0.860577 -3.14312 7.86336 --0.809203 -3.02484 7.90406 --0.633277 -2.61656 7.25086 --0.73012 -2.838 8.10652 --0.59556 -2.52716 7.6422 --0.424666 -2.13056 6.88918 --0.373582 -2.01356 6.86327 --0.459634 -2.20976 7.79602 --0.471815 -2.23799 8.28278 --0.400019 -2.07126 8.15257 --0.359863 -1.97669 8.2676 --0.306091 -1.84965 8.26551 --0.234535 -1.68484 8.09634 --0.164182 -1.52212 7.90375 --0.103929 -1.38119 7.78529 --0.0738563 -1.31034 8.0163 --0.0681021 -1.29672 8.62024 -0.0153648 -1.10296 8.18023 -0.0677877 -0.980201 8.15073 -0.162519 -0.761104 7.30581 -0.167 -0.749326 8.17387 -0.243609 -0.57327 7.49038 -0.291125 -0.463255 7.42058 -0.33142 -0.367572 7.55819 -0.377857 -0.260722 7.5243 -0.42409 -0.152922 7.40836 -0.471542 -0.0450432 6.73041 --0.350455 -1.83266 -0.952224 --0.376933 -1.88983 -0.943934 --0.41032 -1.96121 -0.947415 --0.440235 -2.02535 -0.942265 --0.477115 -2.10465 -0.947937 --0.510583 -2.17771 -0.944928 --0.545036 -2.2506 -0.939718 --0.585508 -2.33966 -0.944286 --0.626962 -2.42852 -0.946055 --0.665004 -2.51114 -0.939241 --0.710995 -2.60875 -0.940951 --0.753574 -2.70013 -0.934078 --0.803159 -2.80751 -0.934883 --0.856232 -2.92278 -0.93728 --0.921867 -3.06293 -0.950787 --0.980576 -3.18872 -0.949726 --1.0278 -3.29123 -0.930361 --1.08301 -3.40959 -0.916772 --1.14984 -3.55378 -0.912251 --1.21319 -3.69071 -0.898597 --1.28457 -3.84437 -0.888374 --1.36855 -4.02367 -0.884518 --1.45162 -4.20471 -0.874274 --1.5402 -4.39431 -0.861271 --1.64042 -4.61046 -0.851792 --1.74165 -4.82717 -0.83457 --1.86268 -5.0892 -0.824902 --1.96849 -5.31599 -0.794038 --2.13551 -5.67515 -0.796417 --2.29447 -6.01782 -0.780235 --2.47067 -6.39742 -0.761123 --2.67217 -6.83062 -0.741413 --2.88634 -7.29166 -0.711742 --3.10962 -7.77154 -0.66867 --3.39066 -8.37765 -0.632031 --3.7304 -9.10956 -0.594531 --4.08841 -9.87939 -0.534823 --3.83517 -9.33473 -0.267488 --3.48033 -8.56833 0.00370016 --3.47045 -8.54651 0.172172 --3.49287 -8.59429 0.333964 --3.45533 -8.51284 0.50473 --3.82822 -9.31726 0.637524 --7.57107 -17.3744 0.658278 --7.64006 -17.5221 0.992594 --7.64691 -17.537 1.33009 --7.61903 -17.4749 1.66537 --7.53262 -17.2894 1.9917 --7.64642 -17.5328 2.34433 --7.69104 -17.6261 2.69283 --7.68524 -17.6145 3.03384 --7.67002 -17.5795 3.37254 --7.65957 -17.5572 3.7133 --7.65588 -17.5474 4.05702 --7.63624 -17.5056 4.39596 --7.63135 -17.4928 4.74182 --7.61511 -17.4577 5.08421 --7.59652 -17.4167 5.4263 --7.59172 -17.4056 5.77776 --7.57651 -17.3712 6.1249 --7.56598 -17.3482 6.47774 --7.46106 -17.1197 6.76408 --7.58959 -17.3969 7.2254 --7.59149 -17.3983 7.59824 --7.52581 -17.257 7.91847 --7.64721 -17.5173 8.40705 --7.63881 -17.4978 8.78801 --7.62001 -17.4553 9.16265 --7.59328 -17.3973 9.53389 --7.58714 -17.383 9.93084 --7.56954 -17.3446 10.321 --7.55648 -17.3154 10.7215 --7.54444 -17.2869 11.1283 --7.53142 -17.2591 11.542 --7.48615 -17.1599 11.9175 --7.48445 -17.1551 12.3594 --7.41505 -17.0035 12.7091 --7.24617 -16.6407 12.9094 --7.50085 -17.1861 13.7756 --7.44749 -17.0702 14.1733 --2.22272 -5.84386 5.85444 --2.00523 -5.37624 5.79979 --2.52495 -6.48871 8.15341 --2.03205 -5.42947 7.1987 --1.95374 -5.26253 7.22192 --1.8832 -5.10865 7.25545 --1.89727 -5.13984 7.5189 --1.85988 -5.05848 7.64742 --1.4602 -4.19996 6.71841 --1.38423 -4.03615 6.69604 --1.40512 -4.08133 6.97244 --1.45778 -4.19402 7.3656 --1.23392 -3.71271 6.84757 --1.13189 -3.49295 6.71094 --1.07999 -3.38211 6.7439 --1.16093 -3.55547 7.2745 --0.938615 -3.07745 6.6479 --1.15671 -3.54508 7.77127 --0.790657 -2.76012 6.49187 --0.714964 -2.59646 6.3853 --0.751513 -2.6754 6.79092 --0.714311 -2.59455 6.8685 --0.848892 -2.88144 7.81463 --0.674836 -2.50667 7.21145 --0.777605 -2.72776 8.08716 --0.639866 -2.43141 7.63805 --0.628493 -2.40719 7.91724 --0.586543 -2.31539 8.01898 --0.539061 -2.21338 8.09095 --0.47914 -2.08336 8.07546 --0.4216 -1.96041 8.07624 --0.375218 -1.86069 8.16105 --0.313163 -1.7266 8.109 --0.261208 -1.61532 8.15085 --0.171498 -1.42247 7.80096 --0.110803 -1.29223 7.71006 --0.123959 -1.31888 8.48981 --0.089347 -1.24236 8.77999 --0.104736 -1.27254 9.86941 -0.0638544 -0.914845 8.18948 -0.117952 -0.798911 8.18623 -0.196459 -0.631501 7.63382 -0.251204 -0.513783 7.4856 -0.297545 -0.412339 7.52446 -0.324132 -0.353393 8.46025 -0.394237 -0.205427 7.52657 -0.446497 -0.093857 7.02964 --0.361883 -1.72311 -0.961662 --0.390312 -1.77927 -0.955812 --0.41527 -1.82821 -0.94143 --0.446142 -1.89144 -0.939322 --0.484918 -1.96879 -0.948483 --0.520222 -2.0389 -0.948812 --0.553173 -2.1037 -0.940506 --0.592028 -2.18271 -0.942777 --0.63638 -2.26959 -0.94853 --0.676322 -2.35028 -0.945604 --0.716248 -2.43086 -0.940182 --0.761668 -2.51927 -0.937743 --0.809646 -2.61669 -0.937948 --0.862114 -2.72197 -0.940441 --0.915619 -2.82802 -0.939285 --0.97712 -2.94995 -0.944705 --1.04667 -3.08874 -0.955852 --1.11281 -3.22123 -0.957319 --1.15149 -3.29939 -0.921886 --1.22665 -3.44843 -0.924183 --1.28938 -3.57525 -0.908328 --1.36559 -3.72573 -0.900535 --1.44539 -3.88597 -0.891437 --1.53078 -4.05579 -0.88043 --1.61969 -4.23432 -0.86697 --1.72674 -4.44723 -0.861213 --1.8338 -4.66077 -0.847716 --1.95798 -4.90861 -0.839029 --2.07873 -5.15005 -0.818264 --2.22115 -5.43457 -0.80275 --2.38632 -5.764 -0.790085 --2.57319 -6.13727 -0.777628 --2.77824 -6.54632 -0.76049 --2.99241 -6.97432 -0.732248 --3.21671 -7.42117 -0.6918 --3.47984 -7.9469 -0.650826 --3.79654 -8.57971 -0.609646 --4.19412 -9.37327 -0.570951 --4.6316 -10.2477 -0.5134 --5.13268 -11.2469 -0.438193 --3.76198 -8.5084 0.0800783 --3.73281 -8.44944 0.252506 --3.71616 -8.415 0.420614 --3.69741 -8.37877 0.587219 --3.70018 -8.38351 0.750772 --3.68816 -8.35903 0.914794 --7.99166 -16.951 1.15743 --7.92666 -16.8213 1.48474 --7.8376 -16.6413 1.80482 --7.82154 -16.6081 2.12828 --8.03449 -17.0336 2.49131 --8.03545 -17.0339 2.82644 --7.98515 -16.9316 3.14959 --8.0294 -17.019 3.498 --8.02598 -17.0134 3.83582 --8.01662 -16.9923 4.17233 --8.00854 -16.9759 4.5109 --7.99804 -16.9527 4.84971 --7.99235 -16.943 5.19302 --7.98071 -16.9177 5.53482 --7.96577 -16.8875 5.87686 --7.9143 -16.7824 6.19776 --7.90728 -16.7675 6.54731 --7.76849 -16.4911 6.80776 --7.89211 -16.7362 7.25555 --7.89299 -16.737 7.62135 --7.84947 -16.6479 7.9542 --7.97758 -16.9029 8.43925 --7.9637 -16.8753 8.81016 --7.95988 -16.8655 9.19423 --7.95163 -16.8488 9.58023 --7.9444 -16.8327 9.97238 --7.91336 -16.77 10.3443 --7.89928 -16.7402 10.7395 --7.81039 -16.5626 11.0506 --7.76572 -16.4728 11.4167 --7.73004 -16.3999 11.7976 --7.69438 -16.3277 12.1841 --7.67796 -16.2938 12.6032 --7.49615 -15.9315 12.7872 --7.7992 -16.5338 13.7022 --7.75765 -16.4485 14.1159 --2.77147 -6.51008 7.90828 --2.7208 -6.40822 8.04141 --2.63971 -6.24729 8.10846 --2.67274 -6.3111 8.70184 --2.01125 -4.9928 7.3117 --2.5273 -6.02 8.88283 --1.61932 -4.21353 6.71616 --1.98841 -4.94714 7.9554 --1.59176 -4.157 7.05963 --1.90531 -4.78029 8.2248 --1.44368 -3.86222 7.05558 --1.27721 -3.52872 6.74294 --1.17413 -3.32544 6.61924 --1.13503 -3.24654 6.70021 --1.05995 -3.096 6.65197 --0.97253 -2.92088 6.54798 --0.849276 -2.67529 6.2909 --0.856453 -2.69134 6.54455 --0.775898 -2.53005 6.43667 --0.801853 -2.58016 6.78943 --0.789649 -2.55475 6.99246 --0.912769 -2.79763 7.86927 --0.702497 -2.37989 7.12527 --0.598709 -2.1749 6.87532 --0.751524 -2.47624 8.03324 --0.490521 -1.95936 6.86312 --0.595036 -2.16514 7.84301 --0.565805 -2.10669 8.0455 --0.49754 -1.96912 7.99024 --0.552385 -2.07591 8.84269 --0.390129 -1.75537 8.08236 --0.338531 -1.65108 8.14468 --0.237465 -1.45124 7.76754 --0.166235 -1.30893 7.6094 --0.192523 -1.35853 8.47667 --0.140848 -1.25516 8.58089 --0.183549 -1.33722 9.94548 --0.00923899 -0.993908 8.44734 -0.0640308 -0.846734 8.20794 -0.12311 -0.730137 8.18371 -0.213627 -0.551856 7.42062 -0.266949 -0.445209 7.35065 -0.316033 -0.346475 7.3585 -0.362311 -0.25378 7.54417 -0.41448 -0.150375 7.48829 -0.469289 -0.0428489 6.61037 --0.394338 -1.66373 -0.956881 --0.42365 -1.71789 -0.951927 --0.456474 -1.78012 -0.952359 --0.490223 -1.84121 -0.950939 --0.524083 -1.90419 -0.947623 --0.561328 -1.97323 -0.948994 --0.598682 -2.04415 -0.948168 --0.63702 -2.11491 -0.945142 --0.682256 -2.1998 -0.95219 --0.721624 -2.27126 -0.944517 --0.767947 -2.35782 -0.946269 --0.818765 -2.45228 -0.950908 --0.866171 -2.54049 -0.946765 --0.917072 -2.63664 -0.945212 --0.970009 -2.7335 -0.940307 --1.03785 -2.86043 -0.952951 --1.10333 -2.98201 -0.955961 --1.17329 -3.11138 -0.959761 --1.22637 -3.21151 -0.940076 --1.2929 -3.33441 -0.930699 --1.36395 -3.46607 -0.921363 --1.43961 -3.60747 -0.911619 --1.51623 -3.74855 -0.896877 --1.60995 -3.92323 -0.892688 --1.70469 -4.09854 -0.882154 --1.80751 -4.29145 -0.872404 --1.9214 -4.50174 -0.862429 --2.04335 -4.72953 -0.851241 --2.17087 -4.96675 -0.834547 --2.31295 -5.22917 -0.817922 --2.48228 -5.54443 -0.807833 --2.67076 -5.89457 -0.796206 --2.86931 -6.26274 -0.776119 --3.09964 -6.69227 -0.757714 --3.34109 -7.14057 -0.726901 --3.578 -7.58117 -0.676972 --3.91319 -8.20438 -0.646564 --4.29576 -8.91558 -0.607719 --4.7494 -9.75857 -0.562134 --2.85808 -6.2406 0.127035 --5.76595 -11.6479 -0.39608 --6.14015 -12.3434 -0.232507 --6.32902 -12.6942 -0.0143865 --6.72546 -13.4283 0.193979 --7.33205 -14.5562 0.415262 --8.01298 -15.822 0.678248 --8.41815 -16.5734 0.99145 --8.40783 -16.5527 1.31957 --8.0252 -15.8417 1.62005 --7.92918 -15.6619 1.92398 --8.26089 -16.2779 2.28412 --8.28221 -16.3165 2.61265 --8.26298 -16.2806 2.93476 --8.44789 -16.6239 3.30928 --8.75674 -17.197 3.73554 --8.75649 -17.1947 4.08376 --8.73943 -17.1626 4.4276 --8.73805 -17.1583 4.77861 --8.39526 -16.521 4.97915 --8.80422 -17.2809 5.52147 --8.36569 -16.4653 5.65325 --8.18865 -16.1356 5.90142 --8.11529 -15.9988 6.2012 --8.11278 -15.9919 6.54377 --7.95723 -15.7024 6.78584 --8.09221 -15.9531 7.22957 --8.08864 -15.9458 7.58243 --8.06916 -15.9068 7.92611 --8.36267 -16.4514 8.53971 --8.34669 -16.422 8.90761 --8.3328 -16.3943 9.28072 --8.31004 -16.3522 9.65086 --8.28491 -16.3042 10.0219 --8.26871 -16.2719 10.4072 --8.42803 -16.5681 10.9957 --8.1791 -16.1041 11.129 --7.97524 -15.7246 11.3017 --7.95797 -15.6919 11.6994 --7.87214 -15.532 12.0142 --7.90418 -15.5897 12.4891 --7.75312 -15.3076 12.7181 --7.5809 -14.9884 12.911 --7.9776 -15.7216 13.9641 --7.82325 -15.4352 14.2017 --2.91461 -6.3275 7.9367 --2.5775 -5.69849 8.71138 --2.56517 -5.67307 8.95536 --2.37531 -5.32231 8.73584 --2.30045 -5.1818 8.80834 --1.62039 -3.92204 7.13071 --1.44653 -3.59998 6.83911 --1.43236 -3.57392 7.01736 --1.26306 -3.2598 6.70165 --1.21323 -3.16778 6.75708 --1.1243 -3.00178 6.67335 --0.950808 -2.68007 6.27314 --0.92998 -2.64128 6.41297 --0.961356 -2.69814 6.7647 --0.8571 -2.5057 6.58576 --0.846206 -2.4853 6.78743 --0.820729 -2.43634 6.93555 --1.37214 -3.4546 9.81426 --0.660163 -2.13954 6.72497 --0.612596 -2.05108 6.76647 --0.578312 -1.98727 6.88106 --0.691941 -2.19407 7.84964 --0.658527 -2.13175 8.03399 --0.585382 -1.99641 7.98021 --0.657489 -2.1275 8.90796 --0.513873 -1.8624 8.38196 --0.424273 -1.69652 8.19581 --0.293173 -1.45387 7.62684 --0.232379 -1.34222 7.60604 --0.18243 -1.24925 7.68064 --0.207292 -1.29239 8.55841 --0.270532 -1.40703 10.0699 --0.151726 -1.18607 9.5138 -0.0102859 -0.890058 8.1993 -0.0701915 -0.777991 8.20602 -0.129026 -0.667992 8.23037 -0.22005 -0.499882 7.50543 -0.275249 -0.39844 7.49448 -0.328381 -0.298986 7.50156 -0.38256 -0.199203 7.51653 -0.443919 -0.0870366 6.71974 --0.524447 -1.77783 -0.948448 --0.560188 -1.83875 -0.946223 --0.599376 -1.90672 -0.948636 --0.638612 -1.97558 -0.948902 --0.683288 -2.05134 -0.953399 --0.723614 -2.12191 -0.949068 --0.771777 -2.20555 -0.954858 --0.813133 -2.27683 -0.94578 --0.865835 -2.36924 -0.95191 --0.919577 -2.46244 -0.954991 --0.965457 -2.54237 -0.943756 --1.02918 -2.65124 -0.951409 --1.08404 -2.7469 -0.94475 --1.15235 -2.86541 -0.950096 --1.23415 -3.0077 -0.965901 --1.30803 -3.1357 -0.967141 --1.36053 -3.2265 -0.940611 --1.43097 -3.34806 -0.928974 --1.5015 -3.47139 -0.912943 --1.58645 -3.61733 -0.90502 --1.6805 -3.7809 -0.899674 --1.77556 -3.94511 -0.888384 --1.88415 -4.13383 -0.882009 --1.99831 -4.33207 -0.872126 --2.12254 -4.54772 -0.861423 --2.25683 -4.78072 -0.8489 --2.39662 -5.02213 -0.830722 --2.57012 -5.32323 -0.823109 --2.74916 -5.63357 -0.806595 --2.94383 -5.97084 -0.785652 --3.08018 -6.20727 -0.723587 --3.02243 -6.10562 -0.565756 --3.00074 -6.06902 -0.428524 --2.95875 -5.99525 -0.285941 --2.94488 -5.97161 -0.156632 --2.93539 -5.95386 -0.0302091 --2.92373 -5.9333 0.0950603 --2.91101 -5.91184 0.219378 --2.95303 -5.98295 0.331779 --2.95824 -5.99269 0.45254 --2.96228 -5.99948 0.573348 --2.96625 -6.00526 0.694307 --2.93788 -5.95675 0.816893 --8.28599 -15.2269 0.838006 --8.29154 -15.2354 1.14494 --8.24903 -15.1616 1.44982 --8.20872 -15.0908 1.75215 --8.18178 -15.0423 2.05377 --8.42569 -15.465 2.39642 --8.40771 -15.4326 2.7069 --8.35632 -15.3444 3.00971 --8.40211 -15.4227 3.33545 --8.40641 -15.4277 3.65332 --8.39635 -15.4107 3.9687 --8.37947 -15.38 4.28238 --8.37939 -15.3791 4.60383 --8.35692 -15.3388 4.91749 --8.35024 -15.3282 5.24002 --8.3412 -15.3117 5.56325 --8.30983 -15.2569 5.87645 --8.30517 -15.2468 6.20583 --8.30172 -15.2405 6.5393 --8.13855 -14.957 6.76962 --8.29024 -15.2187 7.21349 --8.27669 -15.1947 7.55064 --8.20954 -15.0777 7.84863 --8.28295 -15.2031 8.26227 --8.26382 -15.1701 8.60735 --8.26025 -15.1633 8.97005 --8.25776 -15.1581 9.33893 --8.25078 -15.1451 9.71 --8.23598 -15.1187 10.0786 --8.19552 -15.0478 10.4248 --8.18183 -15.0237 10.8053 --8.17353 -15.0066 11.1979 --8.15198 -14.9688 11.5824 --8.05013 -14.791 11.8718 --8.07533 -14.834 12.3282 --7.99137 -14.6888 12.6481 --7.79594 -14.3485 12.8091 --8.17402 -15.0032 13.8098 --8.08199 -14.8408 14.1406 --2.67566 -5.48381 8.41114 --2.63254 -5.40908 8.5746 --2.56608 -5.29338 8.68252 --2.48078 -5.14519 8.74056 --1.86128 -4.07381 7.35655 --1.7153 -3.82131 7.1855 --1.64037 -3.69351 7.20397 --1.19333 -2.92008 6.09384 --1.15943 -2.8614 6.18565 --1.31347 -3.12601 6.89041 --1.34575 -3.18107 7.23675 --1.28627 -3.07806 7.28266 --1.25992 -3.03226 7.44925 --0.9179 -2.44212 6.41869 --0.888362 -2.39079 6.53873 --0.884081 -2.38173 6.76664 --0.847884 -2.31923 6.87747 --0.886496 -2.38538 7.33604 --0.90958 -2.42501 7.76186 --0.675403 -2.0213 6.92609 --0.803691 -2.23993 7.92118 --0.716746 -2.08899 7.81458 --0.656295 -1.98628 7.85579 --0.595614 -1.87914 7.88528 --0.691272 -2.04328 8.96709 --0.581338 -1.85266 8.71811 --0.399821 -1.54101 7.88321 --0.315349 -1.39427 7.70914 --0.23432 -1.25506 7.54098 --0.250537 -1.28 8.27081 --0.227658 -1.2411 8.73803 --0.201115 -1.19343 9.24514 --0.144276 -1.0931 9.45601 -0.0134576 -0.822636 8.22769 -0.0782854 -0.710905 8.21347 -0.180598 -0.535835 7.44046 -0.248931 -0.417411 7.14134 -0.294682 -0.337183 7.39842 -0.344838 -0.249259 7.63407 -0.403872 -0.147259 7.55829 -0.467288 -0.040706 6.57033 --0.642283 -1.85359 -0.961104 --0.675605 -1.90815 -0.949096 --0.721165 -1.98191 -0.954688 --0.758919 -2.04336 -0.945316 --0.810024 -2.12589 -0.952444 --0.861172 -2.20927 -0.956726 --0.904456 -2.27937 -0.946393 --0.961081 -2.37047 -0.951061 --1.0133 -2.45538 -0.946951 --1.07001 -2.54817 -0.945428 --1.1322 -2.64876 -0.945889 --1.20884 -2.77213 -0.958354 --1.27662 -2.88228 -0.956207 --1.36227 -3.02222 -0.969701 --1.41766 -3.11093 -0.945058 --1.48204 -3.21545 -0.926389 --1.56534 -3.35061 -0.921611 --1.64418 -3.47856 -0.907704 --1.74305 -3.63897 -0.905288 --1.84195 -3.8001 -0.89693 --1.94636 -3.96979 -0.886212 --2.06179 -4.15592 -0.876318 --2.18174 -4.35062 -0.86277 --2.3273 -4.58734 -0.858104 --2.46937 -4.81664 -0.84111 --2.63598 -5.08689 -0.830055 --2.81824 -5.38415 -0.81657 --3.01702 -5.7063 -0.799251 --3.24236 -6.06995 -0.781424 --3.49791 -6.48591 -0.762732 --3.18024 -5.96915 -0.494019 --3.14197 -5.90724 -0.35223 --3.12816 -5.88455 -0.222172 --3.13331 -5.89321 -0.0998629 --3.13285 -5.8921 0.0239323 --3.12572 -5.88032 0.148562 --3.12297 -5.87439 0.271304 --3.10808 -5.85006 0.395366 --3.15544 -5.92677 0.509879 --3.16395 -5.9413 0.630897 --8.10739 -13.9595 0.41875 --8.40525 -14.4424 0.695015 --9.0474 -15.4832 0.990519 --8.83177 -15.1318 1.30106 --8.36638 -14.3766 1.58103 --8.31202 -14.2883 1.871 --8.61288 -14.7741 2.2047 --8.64738 -14.8308 2.51529 --8.63286 -14.8055 2.81913 --8.60958 -14.7679 3.1212 --8.98914 -15.3826 3.53043 --8.99576 -15.3932 3.8548 --8.89133 -15.2226 4.1441 --8.97998 -15.3651 4.49951 --8.89009 -15.2196 4.79125 --8.84898 -15.1525 5.10047 --8.96308 -15.3363 5.483 --8.71339 -14.9298 5.69089 --8.52266 -14.6211 5.91659 --8.46704 -14.5287 6.20985 --8.47808 -14.5465 6.54401 --8.30623 -14.2681 6.7635 --8.45566 -14.5085 7.1953 --8.44669 -14.4935 7.52762 --8.39008 -14.4018 7.82762 --10.7836 -18.2786 10.1043 --8.76413 -15.0069 8.84069 --10.7537 -18.2281 10.975 --8.73915 -14.9634 9.56528 --8.62787 -14.7818 10.2253 --8.72602 -14.9398 10.7208 --8.59955 -14.7347 10.9858 --8.40331 -14.4155 11.1682 --8.25585 -14.1762 11.3988 --8.23888 -14.148 11.786 --8.22624 -14.1258 12.1862 --8.19597 -14.0764 12.5717 --8.00762 -13.7711 12.7472 --8.36959 -14.3558 13.7014 --8.29819 -14.2379 14.0616 --2.84204 -5.40353 7.80587 --2.85756 -5.42613 8.07911 --2.70905 -5.18685 8.00842 --2.82709 -5.37661 8.52714 --2.82063 -5.36624 8.784 --2.64889 -5.08744 8.64874 --2.5874 -4.98854 8.77595 --1.89083 -3.86098 7.24361 --1.77563 -3.67518 7.16635 --1.6868 -3.53091 7.14968 --1.57597 -3.35039 7.06189 --1.15434 -2.66936 6.01925 --1.45014 -3.14683 7.153 --1.098 -2.57819 6.24699 --1.02696 -2.46244 6.22042 --0.99429 -2.40815 6.32317 --0.973789 -2.37558 6.47873 --0.932404 -2.30871 6.56259 --0.901879 -2.25805 6.69066 --0.85166 -2.17611 6.74528 --0.832059 -2.14373 6.9364 --0.70432 -1.93765 6.63659 --0.674894 -1.88979 6.78754 --0.758824 -2.02489 7.53944 --0.683414 -1.90227 7.49498 --0.67331 -1.88479 7.81845 --0.801005 -2.08859 9.03208 --0.661395 -1.86367 8.64135 --0.500331 -1.60433 8.04104 --0.392545 -1.43004 7.74323 --0.336713 -1.33931 7.82031 --0.262588 -1.21994 7.74898 --0.306445 -1.28774 8.79378 --0.231028 -1.1666 8.77983 --0.209777 -1.12877 9.38528 --0.192379 -1.09989 10.2094 -0.0257265 -0.750725 8.19604 -0.0903097 -0.646105 8.24024 -0.187905 -0.488966 7.58509 -0.259106 -0.373276 7.29499 -0.315869 -0.281592 7.33177 -0.370942 -0.191472 7.49649 -0.43911 -0.0837385 6.71971 --0.713875 -1.84497 -0.95538 --0.753584 -1.90545 -0.949048 --0.801073 -1.97803 -0.953585 --0.845271 -2.04637 -0.949241 --0.894848 -2.12059 -0.948878 --0.944469 -2.19568 -0.945968 --1.00298 -2.28474 -0.952128 --1.05708 -2.3676 -0.949509 --1.11222 -2.45126 -0.94394 --1.1773 -2.54975 -0.946189 --1.24242 -2.64907 -0.944893 --1.32298 -2.77111 -0.955297 --1.39362 -2.87898 -0.951342 --1.48413 -3.01651 -0.962622 --1.537 -3.09704 -0.93169 --1.62413 -3.22907 -0.929245 --1.70685 -3.3549 -0.917522 --1.79504 -3.48838 -0.905286 --1.89877 -3.64636 -0.899958 --1.99801 -3.79709 -0.884801 --2.11821 -3.9791 -0.878685 --2.24843 -4.17755 -0.872397 --2.38521 -4.38542 -0.8618 --2.523 -4.59383 -0.842959 --2.69183 -4.85101 -0.834137 --2.86721 -5.11745 -0.817809 --3.07016 -5.4255 -0.804364 --3.26754 -5.72513 -0.776151 --3.29475 -5.7669 -0.660882 --3.46558 -6.02654 -0.603066 --4.10483 -6.99825 -0.708882 --4.4456 -7.51548 -0.672153 --4.84495 -8.12332 -0.632496 --5.30596 -8.8233 -0.584208 --5.82204 -9.60644 -0.520264 --6.43639 -10.5405 -0.444463 --6.54261 -10.7005 -0.240474 --6.68533 -10.9174 -0.0356548 --7.00684 -11.406 0.157436 --7.70574 -12.4681 0.340196 --8.48054 -13.644 0.56318 --8.57114 -13.7819 0.846883 --8.56673 -13.7738 1.13482 --8.55803 -13.7611 1.42229 --8.53708 -13.7281 1.70849 --8.41911 -13.548 1.98303 --8.64418 -13.8898 2.29944 --8.81727 -14.1512 2.62189 --8.78422 -14.1006 2.91395 --8.97714 -14.3928 3.25896 --9.06973 -14.5328 3.90172 --9.02452 -14.4635 4.1995 --9.06749 -14.5288 4.52908 --8.93075 -14.3194 4.79105 --9.74921 -15.5617 5.46232 --8.82592 -14.1576 5.69124 --8.66844 -13.9187 5.92689 --8.53629 -13.7181 6.16899 --8.60007 -13.8139 6.52454 --8.35452 -13.4404 6.68913 --8.61859 -13.8401 7.18586 --8.60866 -13.8255 7.51079 --8.52491 -13.6977 7.78351 --10.9969 -17.4489 10.0716 --8.91619 -14.2892 8.7866 --10.9662 -17.3993 10.9243 --10.958 -17.3869 11.3667 --10.4857 -16.6696 11.3779 --8.82286 -14.1451 10.1853 --9.4854 -15.1494 11.2518 --8.90244 -14.2638 11.0498 --8.49543 -13.6448 11.0019 --8.48192 -13.6237 11.3822 --8.43551 -13.554 11.7315 --8.38129 -13.471 12.0754 --8.39073 -13.4841 12.5063 --8.20024 -13.1931 12.6794 --8.04722 -12.9608 12.8987 --8.48797 -13.6282 13.9702 --8.29863 -13.3404 14.1578 --3.04576 -5.37078 8.01557 --2.96383 -5.2463 8.09693 --2.90597 -5.15801 8.22829 --2.85687 -5.08315 8.38138 --2.86466 -5.09459 8.66645 --2.78055 -4.96722 8.74805 --1.42669 -2.91569 5.7171 --1.39757 -2.8703 5.8181 --1.78268 -3.45261 7.01424 --1.68793 -3.30931 6.98546 --1.26227 -2.66439 6.00836 --1.59229 -3.16298 7.1799 --1.22152 -2.60174 6.28907 --1.18914 -2.55287 6.4036 --1.08254 -2.39033 6.27177 --1.09041 -2.40134 6.52488 --1.04172 -2.32872 6.59228 --0.985307 -2.24293 6.63106 --0.920176 -2.14351 6.63176 --0.870273 -2.0672 6.69407 --0.946426 -2.18249 7.30918 --0.73796 -1.86651 6.67484 --0.696756 -1.80366 6.77852 --0.81478 -1.98137 7.70134 --0.711639 -1.82444 7.53316 --0.851877 -2.03615 8.73374 --0.782082 -1.92955 8.80394 --0.619611 -1.6838 8.27478 --0.488629 -1.4855 7.88302 --0.412604 -1.36908 7.83536 --0.330242 -1.24406 7.72636 --0.269437 -1.15326 7.79069 --0.291573 -1.18398 8.65931 --0.27392 -1.15698 9.28454 --0.208098 -1.05566 9.46577 --0.0265361 -0.783019 8.12857 -0.0388704 -0.68192 8.18365 -0.184835 -0.464934 6.79345 -0.233968 -0.389306 6.9419 -0.281354 -0.316729 7.22869 -0.332278 -0.23793 7.5642 -0.404139 -0.130466 7.00848 -0.464354 -0.0395227 6.57039 --0.748211 -1.783 -0.961229 --0.785404 -1.83533 -0.949207 --0.831438 -1.90071 -0.948401 --0.881915 -1.97306 -0.951729 --0.927982 -2.03922 -0.946379 --0.988333 -2.12537 -0.956876 --1.04088 -2.19921 -0.952508 --1.10231 -2.287 -0.95701 --1.15495 -2.36258 -0.94715 --1.21746 -2.45201 -0.945557 --1.27996 -2.54128 -0.940767 --1.36334 -2.66024 -0.953408 --1.43687 -2.76604 -0.951439 --1.52676 -2.89345 -0.960219 --1.62219 -3.02954 -0.968736 --1.67248 -3.10087 -0.931166 --1.75802 -3.22363 -0.921879 --1.85554 -3.36191 -0.916358 --1.95759 -3.50887 -0.90958 --2.05617 -3.64855 -0.893271 --2.17564 -3.81854 -0.886551 --2.29619 -3.99014 -0.873137 --2.43775 -4.19391 -0.866517 --2.58681 -4.40602 -0.855134 --2.74686 -4.6344 -0.841479 --2.92889 -4.89468 -0.830419 --3.11747 -5.1642 -0.811454 --3.34654 -5.48982 -0.799686 --3.5976 -5.84803 -0.784371 --3.89373 -6.27189 -0.772248 --4.18632 -6.68796 -0.740506 --4.4955 -7.13055 -0.697241 --4.88567 -7.6859 -0.660029 --5.33185 -8.32276 -0.615447 --5.85256 -9.06604 -0.562252 --6.41482 -9.86786 -0.486388 --6.63909 -10.1888 -0.314781 --6.77205 -10.3765 -0.115868 --6.94792 -10.6278 0.0849416 --7.50103 -11.4161 0.261309 --8.59049 -12.9715 0.437574 --8.72212 -13.1576 0.710092 --8.71787 -13.152 0.990633 --8.69933 -13.1252 1.27034 --8.68956 -13.1109 1.54972 --8.65455 -13.0601 1.82645 --8.69632 -13.1197 2.11089 --8.76984 -13.2241 2.40335 --8.76104 -13.2096 2.68593 --8.74802 -13.1913 2.96849 --8.73928 -13.1777 3.25212 --8.73177 -13.168 3.53735 --8.72843 -13.161 3.82444 --8.71538 -13.1425 4.1103 --8.70009 -13.1202 4.39616 --8.69901 -13.1178 4.68879 --8.68265 -13.0944 4.9775 --8.67503 -13.0832 5.27146 --8.6641 -13.0673 5.56617 --8.66185 -13.0624 5.86739 --8.62244 -13.0056 6.1512 --8.63453 -13.0233 6.46663 --8.49774 -12.8277 6.69223 --8.66507 -13.0654 7.1151 --8.66165 -13.0588 7.43384 --8.61132 -12.9873 7.72287 --8.6954 -13.1061 8.11652 --8.68545 -13.0914 8.44554 --8.67212 -13.0707 8.77595 --8.6545 -13.0453 9.1079 --8.65323 -13.0429 9.45981 --8.63232 -13.0132 9.79953 --8.63315 -13.0131 10.1656 --8.61871 -12.9921 10.5239 --8.59985 -12.9643 10.8842 --8.58645 -12.9446 11.2571 --8.56424 -12.9115 11.6265 --8.50381 -12.8245 11.9575 --8.53625 -12.8712 12.4113 --8.3983 -12.6739 12.654 --8.20792 -12.4011 12.824 --8.52607 -12.8537 13.7029 --8.47311 -12.7768 14.0843 --3.27229 -5.36944 6.69757 --3.13121 -5.16716 6.88227 --3.2373 -5.31806 7.26923 --3.14501 -5.1871 7.33229 --3.08537 -5.10164 7.44915 --3.07578 -5.08675 7.65932 --3.2122 -5.2813 8.16046 --3.39306 -5.53762 8.77737 --2.31561 -4.00447 6.82709 --2.96667 -4.93046 8.434 --2.6013 -4.41073 7.89228 --1.51062 -2.85775 5.63045 --1.50454 -2.84829 5.78774 --1.43653 -2.75155 5.79867 --1.39787 -2.69661 5.88153 --1.42981 -2.74221 6.15631 --1.3292 -2.59869 6.07842 --1.27304 -2.51696 6.1159 --2.47651 -4.22806 9.94334 --2.43502 -4.1676 10.1809 --1.50591 -2.84734 7.54097 --2.04759 -3.6157 9.66728 --1.02309 -2.16037 6.40965 --0.946481 -2.05145 6.37337 --0.974764 -2.0909 6.73603 --0.894871 -1.97676 6.68776 --0.859257 -1.9251 6.82176 --0.796659 -1.83553 6.84338 --0.758941 -1.78262 6.98502 --0.76741 -1.79344 7.36257 --0.923126 -2.01293 8.56943 --0.856994 -1.91871 8.6686 --0.780096 -1.80903 8.70848 --0.602423 -1.55617 8.09887 --0.503206 -1.41473 7.93709 --0.420199 -1.29775 7.86893 --0.339267 -1.18179 7.79773 --0.366819 -1.21922 8.66612 --0.284661 -1.10202 8.64181 --0.274295 -1.08576 9.38516 --0.207659 -0.990084 9.61512 --0.0196741 -0.723929 8.21582 -0.0454325 -0.632447 8.35959 -0.195823 -0.420275 6.87788 -0.244963 -0.349755 7.12541 -0.301495 -0.267656 7.2718 -0.36219 -0.182372 7.40659 -0.434174 -0.0804124 6.67972 --0.77269 -1.7079 -0.953168 --0.815224 -1.7653 -0.948873 --0.863141 -1.82862 -0.949158 --0.9155 -1.89891 -0.953678 --0.967904 -1.97007 -0.955652 --1.02129 -2.04104 -0.955125 --1.07572 -2.11283 -0.952149 --1.13465 -2.19254 -0.952359 --1.19356 -2.2721 -0.949672 --1.25351 -2.35246 -0.944137 --1.32439 -2.44759 -0.946416 --1.41054 -2.56247 -0.960843 --1.48695 -2.66618 -0.960662 --1.55444 -2.7557 -0.946718 --1.66359 -2.90261 -0.967633 --1.7366 -3.00066 -0.950431 --1.81608 -3.10637 -0.933913 --1.91093 -3.23368 -0.926447 --2.00686 -3.36267 -0.913885 --2.10826 -3.49931 -0.900211 --2.22707 -3.65827 -0.892838 --2.36332 -3.84048 -0.890017 --2.49515 -4.0164 -0.876321 --2.65442 -4.23125 -0.872148 --2.80476 -4.43186 -0.852914 --2.98801 -4.67911 -0.843491 --3.15029 -4.89547 -0.812594 --3.17497 -4.92792 -0.708414 --3.23795 -5.01305 -0.620924 --3.11521 -4.84774 -0.455421 --3.07771 -4.79763 -0.330066 --3.062 -4.77583 -0.215396 --3.0617 -4.77651 -0.107631 --3.06128 -4.7752 -0.000165232 --3.03026 -4.73227 0.114269 --3.05066 -4.76014 0.214892 --3.02851 -4.73096 0.324353 --3.01721 -4.71534 0.430345 --3.09428 -4.8184 0.523512 --3.07532 -4.79213 0.631034 --3.06626 -4.78043 0.736231 --8.81753 -12.4932 0.582287 --8.85037 -12.5369 0.853878 --8.857 -12.545 1.12695 --8.8604 -12.5493 1.40032 --8.84302 -12.5248 1.67254 --8.71563 -12.354 1.93307 --8.87156 -12.5618 2.22363 --8.92293 -12.6309 2.50749 --8.90659 -12.6072 2.78227 --8.90454 -12.6045 3.06036 --8.88726 -12.5818 3.33598 --8.88514 -12.5781 3.61613 --8.88084 -12.5714 3.89692 --8.86677 -12.5524 4.17624 --8.84947 -12.5295 4.45555 --8.83639 -12.5103 4.73717 --8.83645 -12.5099 5.02641 --8.8278 -12.4981 5.31423 --8.8104 -12.474 5.59988 --8.80713 -12.4685 5.89486 --8.77128 -12.4207 6.17513 --8.77237 -12.4216 6.47815 --8.61353 -12.2082 6.68492 --8.82022 -12.4848 7.12556 --8.81584 -12.4785 7.43851 --8.75271 -12.3935 7.71327 --8.85047 -12.5233 8.11056 --8.84055 -12.5088 8.43378 --8.83611 -12.5026 8.76746 --8.82296 -12.4849 9.09861 --8.81083 -12.4678 9.43602 --8.78996 -12.4385 9.77015 --8.77999 -12.4246 10.1209 --8.76021 -12.3975 10.4684 --8.75021 -12.384 10.8336 --8.73684 -12.3645 11.2011 --8.71272 -12.3328 11.5652 --8.66022 -12.2611 11.9018 --8.68918 -12.2995 12.3456 --8.56504 -12.1326 12.6057 --8.36814 -11.8675 12.7687 --3.34619 -5.14557 6.2885 --3.313 -5.10131 6.43229 --3.40009 -5.21646 6.75439 --3.17163 -4.91041 6.61063 --2.96922 -4.63876 6.48975 --3.07371 -4.77873 6.85624 --2.86055 -4.4933 6.70288 --2.78834 -4.39662 6.77816 --2.68359 -4.25581 6.79209 --2.84098 -4.46603 7.29554 --3.39023 -5.19992 8.59269 --2.98655 -4.6595 8.0494 --2.73671 -4.32477 7.78214 --1.61822 -2.82971 5.5997 --1.56674 -2.75997 5.65261 --1.53151 -2.71239 5.74456 --1.47144 -2.6321 5.77828 --1.44808 -2.60029 5.90162 --1.39664 -2.53141 5.95757 --1.41648 -2.55788 6.20811 --1.75467 -3.00912 7.37406 --1.65555 -2.87622 7.34307 --1.62976 -2.84051 7.52778 --2.4837 -3.98123 10.5415 --2.12982 -3.50698 9.77697 --1.03434 -2.04524 6.35117 --0.971014 -1.95998 6.3677 --1.0056 -2.00569 6.75805 --0.899272 -1.86369 6.61622 --0.728505 -1.63481 6.18166 --0.802686 -1.73361 6.78773 --0.758615 -1.67351 6.90014 --0.879583 -1.83486 7.8459 --0.958399 -1.93928 8.67635 --0.90859 -1.87249 8.89012 --0.705961 -1.6007 8.20724 --0.591208 -1.44793 7.98943 --0.542508 -1.38196 8.18523 --0.424742 -1.22562 7.90195 --0.442644 -1.2464 8.65271 --0.354549 -1.12946 8.61005 --0.281169 -1.03049 8.69272 --0.261277 -1.00322 9.38661 -0.0681758 -0.566013 6.37373 --0.000602193 -0.655975 8.19353 -0.145592 -0.462208 7.00241 -0.217953 -0.365184 6.80234 -0.273069 -0.291011 6.96915 -0.321707 -0.224196 7.44424 -0.399127 -0.121562 6.83846 -0.462417 -0.0378957 6.56041 --0.715161 -1.53514 -0.959342 --0.754142 -1.58362 -0.952805 --0.802967 -1.64513 -0.95808 --0.846384 -1.70051 -0.95468 --0.900638 -1.76884 -0.962488 --0.945089 -1.82497 -0.95504 --1.00037 -1.89401 -0.958202 --1.05471 -1.96398 -0.95892 --1.10563 -2.02772 -0.951056 --1.17183 -2.11136 -0.958537 --1.23362 -2.18881 -0.957238 --1.29545 -2.26711 -0.952994 --1.36377 -2.35317 -0.951231 --1.43208 -2.43908 -0.946271 --1.52215 -2.55262 -0.958738 --1.60142 -2.65405 -0.956649 --1.69355 -2.76904 -0.96042 --1.79666 -2.89965 -0.96896 --1.86164 -2.98158 -0.940488 --1.94943 -3.09194 -0.926593 --2.05463 -3.22472 -0.920895 --2.17074 -3.37204 -0.918018 --2.28243 -3.51311 -0.905363 --2.41258 -3.67742 -0.898057 --2.55462 -3.85607 -0.891371 --2.70317 -4.04317 -0.880625 --2.86372 -4.24652 -0.868601 --3.04263 -4.47188 -0.857382 --3.23459 -4.71432 -0.842535 --3.41562 -4.94259 -0.811835 --3.44022 -4.97388 -0.704209 --3.46475 -5.00411 -0.595635 --3.65657 -5.246 -0.549378 --4.63803 -6.48631 -0.763985 --5.01641 -6.96241 -0.732357 --5.41877 -7.47147 -0.68684 --3.22929 -4.70662 0.0453479 --3.2083 -4.68026 0.157358 --3.19269 -4.65972 0.266584 --3.19994 -4.66917 0.370423 --3.18764 -4.65358 0.47711 --3.23606 -4.71395 0.575805 --9.11254 -12.1323 0.178829 --9.1332 -12.1568 0.448295 --9.29285 -12.3586 0.71455 --9.27563 -12.337 0.989816 --9.25618 -12.3115 1.26398 --9.25192 -12.3051 1.53808 --9.2076 -12.2492 1.80888 --9.25328 -12.3068 2.08775 --9.38885 -12.4766 2.38241 --9.37268 -12.4557 2.66003 --9.3782 -12.4624 2.94204 --9.35009 -12.4263 3.21783 --9.35553 -12.432 3.50199 --9.33288 -12.4035 3.78019 --9.34383 -12.4175 4.0693 --9.33409 -12.404 4.35373 --9.32012 -12.3866 4.63834 --9.31036 -12.373 4.92576 --9.30176 -12.362 5.21623 --9.29743 -12.3557 5.51015 --9.28235 -12.3371 5.8022 --9.25306 -12.2986 6.08847 --9.28446 -12.3378 6.4104 --9.14265 -12.1586 6.63658 --9.12747 -12.1387 6.93517 --9.33205 -12.3971 7.38041 --9.29621 -12.3503 7.67895 --9.42162 -12.5076 8.09519 --9.44431 -12.5368 8.4487 --9.44088 -12.5312 8.78812 --9.42131 -12.5068 9.12051 --9.42543 -12.5109 9.47758 --9.40896 -12.4887 9.82271 --9.38713 -12.4608 10.1695 --9.38259 -12.4548 10.5384 --9.35641 -12.4216 10.8937 --9.35821 -12.4222 11.2832 --9.31791 -12.371 11.6367 --9.19112 -12.2101 11.8992 --9.24264 -12.2749 12.3692 --9.08782 -12.08 12.6049 --8.88752 -11.8256 12.78 --3.49477 -5.02994 6.1943 --3.40887 -4.92218 6.26705 --3.47403 -5.00366 6.54641 --3.18193 -4.63521 6.32278 --3.51037 -5.04891 7.00453 --3.15796 -4.60527 6.67189 --3.1184 -4.55471 6.80892 --2.94725 -4.33827 6.72991 --2.86349 -4.23205 6.78913 --2.78306 -4.13143 6.85286 --2.7726 -4.11764 7.04214 --2.78264 -4.13036 7.27852 --2.68701 -4.00893 7.3152 --1.74825 -2.82707 5.61579 --1.66797 -2.72567 5.61429 --1.62861 -2.67571 5.69859 --1.58065 -2.61509 5.7657 --1.53594 -2.55893 5.83994 --1.50628 -2.52191 5.95488 --1.44317 -2.44098 5.98494 --1.78957 -2.87672 7.10963 --1.77906 -2.86345 7.32868 --1.72231 -2.79181 7.42652 --1.65584 -2.70708 7.49663 --2.56993 -3.856 10.6557 --1.13056 -2.04624 6.35552 --1.03542 -1.92666 6.27354 --0.990621 -1.86984 6.36138 --0.784145 -1.60926 5.84102 --0.921254 -1.78058 6.62698 --0.810208 -1.64209 6.46057 --0.802727 -1.63157 6.72182 --0.939294 -1.8032 7.68381 --1.03913 -1.92669 8.5693 --1.00557 -1.88471 8.86929 --0.835686 -1.6706 8.43927 --0.72764 -1.53404 8.31122 --0.559243 -1.32225 7.77208 --0.488557 -1.23285 7.8201 --0.466468 -1.2044 8.23777 --0.424078 -1.14991 8.55812 --0.346881 -1.05361 8.63189 --0.327172 -1.02729 9.28638 --0.340336 -1.04257 10.4765 -0.0801632 -0.517797 6.3897 -0.123355 -0.462362 6.6292 -0.174946 -0.397916 6.81804 -0.238911 -0.31762 6.81608 -0.294029 -0.247031 7.05206 -0.351694 -0.173717 7.40653 -0.430234 -0.0756288 6.60973 --0.830186 -1.58152 -0.962652 --0.875544 -1.63583 -0.960093 --0.921889 -1.68999 -0.955734 --0.968282 -1.74504 -0.949328 --1.02445 -1.81209 -0.953784 --1.07627 -1.87395 -0.949611 --1.13892 -1.94868 -0.95525 --1.19717 -2.01724 -0.95231 --1.25984 -2.0927 -0.952506 --1.32456 -2.16891 -0.949849 --1.4001 -2.2579 -0.955406 --1.4649 -2.3358 -0.946557 --1.55779 -2.44626 -0.96106 --1.64088 -2.54454 -0.960806 --1.72401 -2.64364 -0.956806 --1.81356 -2.74941 -0.953539 --1.92053 -2.87767 -0.959868 --2.00026 -2.9711 -0.938647 --2.0964 -3.08707 -0.926626 --2.2064 -3.21643 -0.918265 --2.3273 -3.3603 -0.912524 --2.46116 -3.51952 -0.908449 --2.59609 -3.68035 -0.897581 --2.74935 -3.86233 -0.890661 --2.91012 -4.05266 -0.879179 --3.07738 -4.25138 -0.862737 --3.26951 -4.47987 -0.84988 --3.49396 -4.74574 -0.841387 --3.5758 -4.84406 -0.759637 --3.58292 -4.85192 -0.643864 --3.66902 -4.95483 -0.558758 --4.05664 -5.41563 -0.573584 --5.04502 -6.58983 -0.758068 --5.44429 -7.0642 -0.717185 --5.90074 -7.60604 -0.670218 --6.42191 -8.22474 -0.613853 --6.9431 -8.84507 -0.529574 --6.99098 -8.90164 -0.33335 --7.47951 -9.48146 -0.20161 --8.26824 -10.4188 -0.0809161 --9.38504 -11.7451 0.0506731 --9.87653 -12.3296 0.285492 --9.91543 -12.3746 0.56539 --10.0344 -12.5169 0.846084 --10.0484 -12.532 1.13176 --10.0388 -12.5204 1.41738 --10.013 -12.4898 1.70157 --9.85647 -12.3022 1.9725 --10.0692 -12.5549 2.28024 --10.1491 -12.6495 2.58066 --10.1426 -12.6414 2.87128 --10.133 -12.6296 3.162 --10.1201 -12.6139 3.4527 --10.1168 -12.6085 3.74658 --10.0975 -12.5852 4.03747 --10.0867 -12.5722 4.33213 --10.0857 -12.5705 4.63141 --10.0749 -12.5573 4.92926 --10.0663 -12.5469 5.23016 --10.0554 -12.5325 5.53176 --10.0394 -12.5145 5.83405 --10.0145 -12.484 6.13386 --10.035 -12.5078 6.45906 --9.86357 -12.3033 6.68371 --9.93682 -12.3903 7.04399 --10.1554 -12.6493 7.50136 --10.0336 -12.5034 7.75844 --10.2338 -12.7408 8.22975 --10.2336 -12.7395 8.57741 --10.2108 -12.7121 8.91424 --10.201 -12.7003 9.26553 --10.1868 -12.6826 9.6186 --10.1682 -12.6601 9.97352 --10.1443 -12.6307 10.3299 --10.1322 -12.616 10.7028 --10.1319 -12.6156 11.0937 --10.0821 -12.556 11.4445 --9.99566 -12.4522 11.7625 --9.9641 -12.4142 12.1413 --9.95827 -12.4059 12.5564 --9.7181 -12.1208 12.713 --9.49831 -11.8587 12.8845 --3.75074 -5.04043 6.23735 --3.63187 -4.89927 6.27541 --3.56242 -4.81634 6.37341 --3.56925 -4.82395 6.57528 --3.51589 -4.75989 6.69804 --3.54954 -4.79948 6.95031 --3.37596 -4.59391 6.89785 --3.16911 -4.34841 6.78094 --3.09864 -4.26489 6.872 --3.10647 -4.27345 7.09374 --3.03809 -4.19153 7.1904 --2.96335 -4.10344 7.27761 --2.84347 -3.96022 7.27782 --2.69582 -3.7855 7.21873 --2.88148 -4.00422 7.81959 --2.73161 -3.82578 7.75739 --2.95469 -4.09062 8.49463 --2.25543 -3.2622 7.20311 --2.15393 -3.14102 7.20171 --2.04926 -3.01661 7.18822 --1.85368 -2.78494 6.9408 --1.78332 -2.70124 6.9949 --1.78566 -2.70361 7.24715 --1.76224 -2.67439 7.4397 --2.51877 -3.57044 9.96483 --2.53015 -3.58253 10.3939 --1.12415 -1.91893 6.26079 --1.19685 -2.00359 6.74962 --0.93265 -1.6923 6.08863 --0.937071 -1.69673 6.35741 --0.947849 -1.70941 6.67449 --1.1085 -1.89848 7.63979 --1.06254 -1.84291 7.80467 --1.44992 -2.29977 9.98846 --1.05221 -1.82956 8.59042 --0.928607 -1.68251 8.42982 --0.841166 -1.57956 8.44793 --0.668004 -1.37401 7.95052 --0.566958 -1.25445 7.83516 --0.52393 -1.20291 8.09708 --0.464963 -1.13216 8.28036 --0.414349 -1.07264 8.57067 --0.335222 -0.977513 8.64339 --0.324855 -0.964335 9.44586 --0.316852 -0.952644 10.4779 -0.0951421 -0.469787 6.40516 -0.127008 -0.431405 6.87305 -0.196962 -0.347868 6.80231 -0.260805 -0.272151 6.84935 -0.318916 -0.202792 7.10459 -0.393375 -0.11467 6.7885 -0.460541 -0.0357809 6.56032 --0.891974 -1.56018 -0.951508 --0.944598 -1.61836 -0.954922 --0.991875 -1.67141 -0.94961 --1.04459 -1.73138 -0.94883 --1.0983 -1.79118 -0.945849 --1.15738 -1.85687 -0.946849 --1.2219 -1.92943 -0.951282 --1.28746 -2.00279 -0.952966 --1.35945 -2.08292 -0.95748 --1.42609 -2.15792 -0.953168 --1.49916 -2.23969 -0.951487 --1.5776 -2.32725 -0.95189 --1.67435 -2.43537 -0.964282 --1.75393 -2.52549 -0.957043 --1.84636 -2.62918 -0.955863 --1.94521 -2.73954 -0.955216 --2.06242 -2.87129 -0.963612 --2.14506 -2.96343 -0.940034 --2.246 -3.07598 -0.925549 --2.36523 -3.20886 -0.918559 --2.48455 -3.34345 -0.905777 --2.62963 -3.50604 -0.902368 --2.77573 -3.66922 -0.891915 --2.9477 -3.86225 -0.887939 --3.11419 -4.04802 -0.872441 --3.30653 -4.26354 -0.861124 --3.51823 -4.50091 -0.849009 --3.75676 -4.76779 -0.837475 --3.91889 -4.94987 -0.782738 --3.92598 -4.95747 -0.66177 --3.99658 -5.0366 -0.563616 --4.14458 -5.20141 -0.487389 --5.47495 -6.69187 -0.750481 --5.90143 -7.16923 -0.701873 --6.39997 -7.72827 -0.648591 --6.97901 -8.3763 -0.586518 --7.1547 -8.57306 -0.419836 --7.4486 -8.90161 -0.263244 --8.05217 -9.57787 -0.133045 --9.05446 -10.7 -0.0139327 --10.5876 -12.4165 0.114847 --10.6769 -12.5163 0.401264 --10.7952 -12.6482 0.69105 --10.8372 -12.6952 0.986987 --10.85 -12.7077 1.28435 --10.8512 -12.7099 1.58203 --10.8297 -12.6844 1.87821 --11.0241 -12.9016 2.1963 --11.3013 -13.211 2.53607 --11.2884 -13.1964 2.84596 --11.1992 -13.0958 3.14242 --11.9778 -13.967 3.61732 --11.9152 -13.8965 4.60719 --11.6574 -13.6065 4.86352 --11.8828 -13.8592 5.27547 --11.9094 -13.8873 5.62805 --11.3716 -13.2843 5.75889 --11.129 -13.0127 5.9894 --11.0441 -12.917 6.28152 --11.0569 -12.9315 6.62004 --10.8262 -12.6729 6.83744 --11.076 -12.9514 7.30708 --11.064 -12.9373 7.64513 --10.9234 -12.7792 7.9095 --11.9033 -13.8753 8.88224 --11.8763 -13.8446 9.25052 --11.8696 -13.8369 9.63667 --11.8574 -13.8223 10.0249 --11.8345 -13.7955 10.4105 --11.2169 -13.1046 10.3289 --11.5798 -13.5095 11.0264 --11.2419 -13.1305 11.1514 --10.9223 -12.7724 11.2772 --10.9037 -12.751 11.6699 --10.7159 -12.5409 11.907 --10.8097 -12.644 12.4224 --10.6529 -12.4685 12.6937 --10.3912 -12.1757 12.8489 --10.9773 -12.8298 13.9498 --10.783 -12.6115 14.1989 --3.75935 -4.75848 6.34985 --3.70629 -4.69936 6.47366 --3.75588 -4.75451 6.73661 --3.79152 -4.79392 6.99018 --3.80785 -4.81128 7.22643 --3.71619 -4.70835 7.30999 --3.29858 -4.24201 6.88742 --3.06167 -3.97699 6.71549 --3.02572 -3.93688 6.85978 --2.92669 -3.8256 6.89833 --2.97827 -3.88265 7.20133 --2.89313 -3.78718 7.26809 --2.87308 -3.7639 7.45815 --3.09531 -4.01168 8.13606 --2.38376 -3.21661 6.93532 --2.25289 -3.07085 6.87877 --2.24359 -3.06028 7.08244 --2.16176 -2.96867 7.12808 --1.98076 -2.76557 6.93392 --1.88724 -2.66069 6.93788 --2.01526 -2.80306 7.51009 --1.81212 -2.57729 7.23387 --1.86863 -2.6392 7.65519 --1.69635 -2.44666 7.43988 --1.71556 -2.46752 7.78385 --1.16397 -1.85201 6.32772 --1.09091 -1.77086 6.33378 --1.04749 -1.72112 6.43889 --1.0211 -1.69177 6.61751 --0.985048 -1.65034 6.76833 --1.25631 -1.95316 8.19658 --1.64124 -2.38036 10.2736 --1.16661 -1.85203 8.6451 --0.997918 -1.66194 8.29536 --0.921371 -1.57702 8.38141 --0.75728 -1.3941 7.9827 --0.649175 -1.27284 7.84959 --0.576855 -1.1911 7.92712 --0.55071 -1.16135 8.33549 --0.461525 -1.06158 8.33222 --0.417205 -1.01084 8.7007 --0.331096 -0.915654 8.76286 --0.342278 -0.926016 9.85258 --0.101947 -0.659782 8.21577 -0.0956189 -0.441135 6.63913 -0.151081 -0.378929 6.82796 -0.22085 -0.29996 6.78619 -0.279719 -0.233611 7.02215 -0.34207 -0.164585 7.35657 -0.424551 -0.0717893 6.63971 --1.01347 -1.59788 -0.9494 --1.0734 -1.6608 -0.956139 --1.11726 -1.70757 -0.941446 --1.18368 -1.77821 -0.949967 --1.2393 -1.83672 -0.943533 --1.30675 -1.90803 -0.946708 --1.38056 -1.98512 -0.952862 --1.44364 -2.05112 -0.944612 --1.52937 -2.14279 -0.955781 --1.98316 -2.62131 -0.963617 --2.07404 -2.71651 -0.951251 --2.20786 -2.85762 -0.966092 --2.28055 -2.93477 -0.931601 --2.40361 -3.06454 -0.927243 --2.52669 -3.19503 -0.917243 --2.65723 -3.33299 -0.905327 --2.81448 -3.49787 -0.90213 --2.9718 -3.66437 -0.891444 --3.13656 -3.83825 -0.876743 --3.32807 -4.03985 -0.866919 --3.5335 -4.25649 -0.853962 --3.7732 -4.5094 -0.845314 --4.03324 -4.78398 -0.833168 --4.1539 -4.91125 -0.755558 --4.12778 -4.88406 -0.620792 --4.27411 -5.03794 -0.544515 --4.31224 -5.07805 -0.429161 --4.316 -5.08059 -0.303158 --4.3038 -5.0679 -0.174199 --4.30339 -5.06772 -0.0491561 --4.30187 -5.06563 0.0754853 --4.29823 -5.06169 0.199622 --4.28711 -5.05014 0.324438 --4.28772 -5.05004 0.446788 --4.27979 -5.04141 0.569465 --4.27728 -5.03952 0.691307 --4.2736 -5.03471 0.812697 --4.26886 -5.02897 0.933934 --4.26206 -5.02237 1.05482 --4.25409 -5.01286 1.17525 --4.258 -5.01764 1.29626 --4.24039 -4.99773 1.41561 --4.24112 -4.99969 1.53656 --4.25461 -5.01383 1.6596 --12.1351 -13.3264 3.07597 --12.1638 -13.3554 3.40648 --12.1531 -13.3439 3.73175 --12.1455 -13.3351 4.05877 --12.1347 -13.3225 4.38629 --12.1196 -13.3061 4.71409 --12.1067 -13.2925 5.04435 --12.0905 -13.274 5.37505 --12.0829 -13.2658 5.71121 --12.0315 -13.2108 6.03218 --11.9757 -13.1511 6.35199 --11.9692 -13.1435 6.6945 --11.7095 -12.8703 6.91811 --11.9871 -13.1622 7.40651 --11.973 -13.1467 7.75709 --11.961 -13.1327 8.11256 --11.995 -13.1686 8.50002 --11.9787 -13.1505 8.86337 --11.971 -13.1415 9.23644 --11.9505 -13.1203 9.60723 --11.9384 -13.1061 9.98842 --11.9209 -13.0861 10.3715 --11.8908 -13.055 10.7517 --11.8381 -12.9988 11.1183 --11.8164 -12.9743 11.5157 --11.7295 -12.8821 11.8628 --11.6789 -12.828 12.2462 --11.6625 -12.811 12.669 --11.3506 -12.481 12.8058 --11.1517 -12.2704 13.0463 --11.8027 -12.9553 14.1952 --3.93575 -4.66768 6.48913 --3.91665 -4.64784 7.07296 --3.86262 -4.59003 7.21195 --3.7586 -4.48064 7.2788 --3.20419 -3.89522 6.65367 --3.10244 -3.78898 6.69506 --3.01978 -3.70132 6.76291 --3.29567 -3.99123 7.43623 --3.05555 -3.73834 7.24615 --3.03137 -3.71265 7.42906 --2.80299 -3.47143 7.23203 --2.73951 -3.40476 7.33879 --2.4188 -3.06662 6.92354 --2.32027 -2.96248 6.93892 --2.16022 -2.79461 6.81761 --2.06067 -2.68933 6.81671 --1.45279 -2.05074 5.61091 --2.15134 -2.78376 7.51108 --1.99448 -2.61834 7.37709 --1.48248 -2.0799 6.27976 --1.76363 -2.37498 7.28657 --1.69063 -2.29791 7.3518 --1.69706 -2.30433 7.65884 --1.1784 -1.75916 6.32173 --1.15848 -1.73796 6.51 --1.07926 -1.65373 6.50485 --1.05824 -1.6317 6.71139 --1.07195 -1.64523 7.06818 --1.22063 -1.80101 8.01164 --1.64829 -2.24806 10.263 --1.11654 -1.69019 8.3899 --0.971791 -1.53778 8.16112 --0.941745 -1.50539 8.48614 --0.75621 -1.3106 7.98909 --0.652715 -1.20176 7.90298 --0.637157 -1.1845 8.37021 --0.541975 -1.08399 8.34874 --0.450983 -0.987905 8.35416 --0.411956 -0.945987 8.801 --0.393301 -0.925203 9.54458 --0.330676 -0.858107 10.002 -0.0429881 -0.469367 6.69332 -0.113531 -0.395346 6.67401 -0.179019 -0.326686 6.74251 -0.243624 -0.257564 6.83942 -0.311333 -0.185685 6.91486 -0.384757 -0.109138 6.8086 -0.456672 -0.0340396 6.57047 --1.14947 -1.64313 -0.955539 --1.2006 -1.69374 -0.946119 --2.00341 -2.49258 -0.961232 --2.10794 -2.59756 -0.960414 --2.22627 -2.71498 -0.964104 --2.3403 -2.82816 -0.958118 --2.44049 -2.92847 -0.938734 --2.56733 -3.05485 -0.931316 --2.68239 -3.16922 -0.910246 --2.84978 -3.33585 -0.91421 --3.01181 -3.49722 -0.906851 --3.16842 -3.65236 -0.88872 --3.35921 -3.842 -0.87969 --3.56286 -4.04578 -0.86808 --3.79623 -4.27697 -0.85864 --4.04995 -4.52986 -0.846601 --4.33885 -4.81779 -0.835521 --4.43016 -4.90785 -0.740403 --4.4233 -4.90077 -0.609734 --4.41439 -4.89285 -0.479919 --4.41173 -4.8887 -0.352883 --4.40602 -4.88378 -0.226605 --4.4002 -4.87687 -0.100826 --4.39232 -4.86913 0.0241985 --4.38232 -4.85955 0.148418 --4.38511 -4.86237 0.269824 --4.37189 -4.84903 0.392837 --4.37893 -4.85568 0.512856 --4.36353 -4.83952 0.634715 --4.36739 -4.84337 0.754476 --4.35525 -4.83111 0.874646 --4.35693 -4.83208 0.994251 --4.34161 -4.81705 1.11346 --4.34012 -4.81523 1.23261 --4.32904 -4.80399 1.35124 --4.33079 -4.80597 1.47069 --4.34634 -4.82106 1.59218 --13.2348 -13.6671 3.01856 --13.5181 -13.9475 3.4096 --13.7034 -14.1327 3.79725 --13.6882 -14.116 4.15107 --13.6827 -14.1096 4.50856 --13.6857 -14.1125 4.87037 --13.5247 -13.9521 5.18586 --13.6789 -14.1049 5.59775 --13.3933 -13.8199 5.86658 --13.0567 -13.4843 6.10456 --12.9787 -13.4056 6.43201 --12.937 -13.364 6.77462 --12.7218 -13.1491 7.03974 --12.9941 -13.4191 7.53303 --12.9513 -13.3761 7.88458 --13.6395 -14.0597 8.63292 --13.5296 -13.9502 8.97217 --13.6058 -14.0255 9.42161 --13.5321 -13.9516 9.78776 --13.5699 -13.9876 10.2287 --13.1664 -13.5864 10.3766 --13.3968 -13.8142 10.9607 --13.1592 -13.5771 11.2168 --12.7951 -13.2145 11.3674 --12.7937 -13.2132 11.7978 --12.5976 -13.0179 12.0719 --12.7002 -13.1176 12.604 --12.4415 -12.8605 12.8237 --12.1349 -12.5549 12.9896 --12.8802 -13.2952 14.1807 --4.08701 -4.55259 7.45038 --3.2752 -3.74655 6.69283 --3.19071 -3.66193 6.76253 --3.29601 -3.76625 7.13898 --3.21042 -3.68033 7.21601 --2.93203 -3.4041 6.95677 --2.88789 -3.36076 7.09533 --2.53434 -3.0086 6.65896 --2.4722 -2.9467 6.74884 --2.36031 -2.83558 6.73917 --2.18495 -2.66184 6.59314 --2.13547 -2.61137 6.70008 --1.56349 -2.04377 5.63678 --1.49416 -1.97554 5.66102 --2.05585 -2.53139 7.21529 --1.61638 -2.09495 6.35922 --1.59979 -2.0788 6.54275 --1.86397 -2.33973 7.51073 --1.4144 -1.89414 6.50777 --1.29222 -1.77292 6.3908 --1.19957 -1.68015 6.35181 --1.27988 -1.76037 6.88031 --1.10081 -1.58186 6.5524 --1.06507 -1.54599 6.71211 --1.29646 -1.77417 7.91446 --1.23415 -1.71192 8.05198 --0.848334 -1.33054 6.80988 --1.05587 -1.5346 8.12303 --0.97776 -1.45684 8.20823 --0.655641 -1.13782 7.02657 --0.773271 -1.25238 8.1307 --0.634625 -1.11578 7.85878 --0.597198 -1.07809 8.19841 --0.507563 -0.988946 8.2241 --0.488466 -0.968543 8.79908 --0.459652 -0.938694 9.41449 --0.36743 -0.845982 9.55543 --0.140816 -0.623333 8.21571 -0.0700588 -0.416014 6.62914 -0.130328 -0.355584 6.78809 -0.198807 -0.287135 6.85598 -0.260557 -0.226002 7.15195 -0.341962 -0.144817 6.94689 -0.419742 -0.0684863 6.63978 --1.94969 -2.29925 -0.981913 --2.02504 -2.36996 -0.962441 --2.12696 -2.46495 -0.959128 --2.24811 -2.57931 -0.965355 --2.36385 -2.6875 -0.961907 --2.4935 -2.81007 -0.962069 --2.59848 -2.90695 -0.940021 --2.73556 -3.03677 -0.933572 --2.88103 -3.173 -0.924853 --3.03396 -3.31666 -0.913419 --3.21552 -3.48604 -0.909349 --3.38972 -3.65028 -0.893864 --3.58616 -3.83433 -0.880069 --3.82513 -4.05839 -0.875451 --4.07258 -4.29058 -0.862871 --4.36889 -4.56832 -0.857754 --4.6248 -4.80897 -0.823878 --4.6052 -4.7903 -0.68685 --4.59729 -4.78226 -0.555833 --4.59474 -4.78006 -0.427599 --4.59108 -4.77594 -0.299967 --4.57146 -4.75661 -0.16968 --4.55621 -4.74317 -0.0421789 --4.57595 -4.7611 0.077574 --4.54364 -4.73059 0.20603 --4.54637 -4.73239 0.327786 --4.54704 -4.73333 0.449486 --4.53818 -4.72579 0.571511 --4.53562 -4.72294 0.692504 --4.52452 -4.71157 0.813625 --4.52626 -4.71352 0.93388 --4.51947 -4.70695 1.05406 --4.51056 -4.69852 1.17384 --4.50801 -4.69573 1.29363 --4.49593 -4.68452 1.41285 --4.49761 -4.68547 1.53306 --4.49717 -4.68453 1.65336 --14.1351 -13.7237 3.26651 --14.3144 -13.8913 3.65394 --14.2643 -13.8437 4.00503 --14.2376 -13.8186 4.36096 --14.215 -13.7962 4.71846 --14.2297 -13.8101 5.08779 --14.1616 -13.7458 5.43523 --14.1667 -13.7501 5.80623 --14.0762 -13.6634 6.14632 --14.1068 -13.6926 6.53152 --13.9645 -13.5589 6.85175 --13.9642 -13.5581 7.22988 --14.0838 -13.6696 7.66665 --13.9286 -13.523 7.98116 --14.029 -13.6163 8.42292 --14.0277 -13.6147 8.82052 --14.0072 -13.5944 9.21258 --14.0079 -13.5951 9.62202 --14.0489 -13.6329 10.0628 --13.9319 -13.5224 10.4093 --13.9081 -13.4995 10.8199 --13.9045 -13.4953 11.2505 --13.868 -13.4599 11.6648 --13.7054 -13.3072 11.9872 --13.7526 -13.3503 12.4771 --13.5794 -13.1874 12.7953 --13.2368 -12.8657 12.9639 --13.9838 -13.5643 14.1061 --13.7184 -13.3159 14.3599 --3.51763 -3.75665 7.20405 --3.4377 -3.68253 7.29913 --3.09683 -3.36287 6.96046 --2.97892 -3.2529 6.97513 --2.90737 -3.18454 7.06523 --2.65968 -2.95329 6.83243 --2.54708 -2.84768 6.83383 --1.69816 -2.05313 5.36564 --1.61002 -1.96992 5.35068 --1.63687 -1.99514 5.57747 --1.6352 -1.99342 5.75549 --1.75673 -2.10605 6.22767 --1.66119 -2.01635 6.21114 --1.61839 -1.97724 6.32349 --1.33761 -1.71456 5.81469 --1.48839 -1.85496 6.43921 --1.3876 -1.7599 6.39555 --1.32475 -1.70141 6.45806 --1.25237 -1.63291 6.49148 --1.56858 -1.92759 7.80687 --1.16015 -1.54592 6.73913 --1.12977 -1.51786 6.937 --0.944125 -1.34364 6.5509 --0.966079 -1.36393 6.96364 --0.866453 -1.27015 6.89282 --1.06384 -1.45404 8.18019 --0.733139 -1.14446 7.04099 --0.874589 -1.27586 8.22119 --0.740409 -1.15003 8.0098 --0.669817 -1.08387 8.15539 --0.422696 -0.854184 7.1436 --0.49215 -0.917571 8.24601 --0.270507 -0.710973 7.2231 --0.450286 -0.875665 9.58404 --0.359304 -0.790499 9.79364 -0.0257683 -0.433641 6.58393 -0.0928988 -0.370511 6.64408 -0.152112 -0.314606 6.87214 -0.22651 -0.24502 6.88937 -0.304816 -0.17119 6.79494 -0.380001 -0.101803 6.7486 -0.453862 -0.0323802 6.60044 --1.8555 -2.0846 -0.968452 --1.95079 -2.1692 -0.969999 --2.04812 -2.25448 -0.967694 --2.15186 -2.34644 -0.966322 --2.26302 -2.445 -0.96538 --2.38159 -2.55013 -0.964368 --2.50119 -2.65596 -0.95841 --2.64832 -2.7858 -0.964513 --2.75622 -2.88136 -0.939709 --2.90441 -3.01256 -0.934125 --3.06104 -3.15114 -0.925822 --3.23251 -3.30289 -0.917979 --3.39761 -3.44947 -0.899316 --3.5997 -3.62737 -0.889794 --3.83684 -3.83759 -0.887071 --4.08339 -4.05489 -0.876633 --4.3448 -4.28607 -0.860812 --4.67928 -4.58175 -0.85938 --5.00742 -4.87295 -0.840488 --5.47637 -5.28742 -0.849688 --5.95372 -5.70947 -0.839639 --6.41728 -6.12004 -0.80411 --6.91245 -6.55709 -0.754463 --7.46697 -7.04824 -0.694773 --8.07327 -7.58464 -0.619716 --8.3236 -7.80622 -0.457756 --4.78237 -4.67173 0.252459 --9.32709 -8.69276 -0.160425 --10.3196 -9.5709 -0.0239743 --11.9238 -10.9898 0.11459 --14.0593 -12.8786 0.302246 --14.8384 -13.5669 0.622556 --15.1483 -13.8404 0.979481 --15.6181 -14.2558 1.3545 --4.8986 -4.77386 1.24503 --4.93305 -4.80352 1.37336 --4.8374 -4.71916 1.49156 --15.6213 -14.2559 2.86139 --15.5428 -14.1862 3.22942 --15.6081 -14.2432 3.61851 --15.5793 -14.2172 3.99482 --15.5674 -14.206 4.37507 --15.5502 -14.1912 4.7558 --15.5436 -14.1845 5.1405 --15.5233 -14.1666 5.52397 --15.506 -14.1505 5.90995 --15.3746 -14.0327 6.26026 --15.333 -13.9953 6.63953 --15.0843 -13.7746 6.9416 --15.2975 -13.9635 7.42311 --15.2972 -13.9625 7.82706 --15.2768 -13.9439 8.22641 --15.4412 -14.088 8.71893 --15.4429 -14.0889 9.14261 --15.4108 -14.0604 9.55381 --15.3998 -14.0499 9.98145 --15.3835 -14.0345 10.4113 --15.3534 -14.007 10.8388 --15.2029 -13.8731 11.1933 --15.081 -13.7646 11.5665 --15.0065 -13.6987 11.9746 --14.9131 -13.6164 12.3727 --8.41124 -7.87056 7.8485 --14.459 -13.2131 12.9652 --15.1973 -13.8655 14.0577 --14.9686 -13.6611 14.3723 --7.59343 -7.14249 11.4026 --7.44569 -7.01143 11.5752 --7.1452 -6.74567 11.5358 --3.68605 -3.69124 7.18535 --3.60948 -3.62349 7.28936 --3.51188 -3.53756 7.36102 --3.42897 -3.46374 7.45348 --3.03357 -3.11516 7.01623 --4.74455 -4.6231 10.2577 --2.87943 -2.97766 7.18502 --1.8197 -2.04385 5.40458 --1.72443 -1.95838 5.38326 --1.67031 -1.91155 5.44269 --1.64024 -1.88388 5.55177 --1.59974 -1.84865 5.6437 --1.77133 -1.99981 6.22843 --2.0488 -2.24412 7.11086 --1.58089 -1.83125 6.19841 --1.50248 -1.76172 6.21933 --1.51317 -1.77016 6.48063 --1.40015 -1.67022 6.40872 --1.3836 -1.65588 6.61647 --1.62772 -1.87047 7.65303 --1.30627 -1.58668 6.93218 --1.15563 -1.4538 6.72124 --1.05004 -1.3606 6.6461 --0.995666 -1.31224 6.75692 --0.929764 -1.25347 6.82871 --1.10684 -1.4082 7.96042 --0.815694 -1.15287 7.07405 --0.728875 -1.07531 7.06509 --0.640073 -0.997462 7.04408 --0.558515 -0.925372 7.05984 --0.432409 -0.813995 6.79004 --0.350942 -0.741597 6.77155 --0.275718 -0.674994 6.79033 --0.526676 -0.893652 9.53293 --0.0985777 -0.51836 6.58497 --0.025507 -0.45392 6.59796 -0.0506055 -0.387221 6.57938 -0.120664 -0.324804 6.62873 -0.18181 -0.271075 6.87592 -0.254217 -0.20648 6.99213 -0.336262 -0.133888 6.83696 -0.415927 -0.063731 6.60973 --1.61248 -1.76107 -0.964886 --1.68951 -1.82549 -0.962033 --1.77923 -1.90057 -0.967288 --1.8636 -1.97052 -0.963617 --1.94163 -2.03542 -0.951523 --2.04717 -2.1236 -0.956735 --2.16006 -2.21738 -0.962726 --2.27399 -2.31188 -0.96417 --2.38795 -2.40715 -0.960969 --2.52407 -2.52058 -0.966649 --2.64009 -2.61725 -0.953755 --2.81215 -2.7611 -0.969426 --2.91546 -2.84757 -0.93779 --3.04088 -2.95114 -0.913684 --3.23718 -3.11519 -0.921101 --3.41331 -3.26146 -0.909695 --3.60531 -3.42178 -0.897497 --3.82581 -3.60569 -0.889968 --4.0558 -3.79773 -0.875871 --4.33111 -4.02651 -0.868994 --4.64342 -4.28723 -0.863617 --5.00315 -4.58627 -0.859561 --5.41469 -4.93037 -0.856167 --5.84403 -5.28776 -0.838992 --6.39471 -5.74579 -0.834925 --6.85666 -6.13063 -0.784255 --7.40936 -6.59122 -0.733192 --5.83668 -5.28053 -0.240655 --8.6623 -7.63545 -0.581934 --5.49994 -4.99893 0.102819 --9.15801 -8.04807 -0.222907 --10.0227 -8.76869 -0.0916108 --11.2166 -9.76371 0.0519489 --13.1469 -11.3717 0.206562 --15.9885 -13.7394 0.41619 --15.9788 -13.7314 0.791098 --16.179 -13.8972 1.16746 --16.1904 -13.9057 1.54682 --16.1648 -13.8845 1.92499 --16.0739 -13.8083 2.29743 --16.2687 -13.9693 2.69526 --16.2664 -13.9674 3.07872 --16.2597 -13.9608 3.46263 --16.2469 -13.9505 3.84681 --16.237 -13.941 4.23266 --16.2294 -13.9342 4.62046 --16.209 -13.9162 5.00712 --16.1982 -13.9065 5.39786 --16.1821 -13.893 5.78938 --16.167 -13.8803 6.18375 --16.1478 -13.8638 6.579 --16.0336 -13.7674 6.9428 --16.1586 -13.8707 7.39662 --16.1804 -13.8885 7.81895 --16.101 -13.8221 8.20296 --16.1975 -13.9024 8.66879 --16.1718 -13.8803 9.08515 --16.1619 -13.8706 9.51374 --16.1446 -13.8563 9.94416 --16.1283 -13.8416 10.3804 --16.112 -13.8276 10.8227 --16.0894 -13.8079 11.2672 --8.80598 -7.74444 7.0205 --8.58718 -7.5622 7.13872 --6.67272 -5.9674 6.0535 --8.50432 -7.49255 7.61146 --8.45496 -7.45081 7.84528 --16.0278 -13.7528 14.1449 --8.33097 -7.34637 8.30124 --7.00662 -6.24404 7.44801 --6.83016 -6.09774 7.53833 --6.79147 -6.06549 7.75006 --6.59494 -5.90067 7.81361 --7.04623 -6.2759 8.51464 --6.2883 -5.64477 8.00715 --6.18129 -5.55599 8.14739 --7.85358 -6.94546 10.5906 --7.8083 -6.90774 10.8799 --7.52971 -6.67539 10.8882 --7.54428 -6.68723 11.258 --7.46005 -6.61659 11.5102 --4.77502 -4.38112 10.2458 --2.86129 -2.78989 7.11006 --1.84897 -1.94948 5.43124 --1.74252 -1.86055 5.39216 --1.70844 -1.83252 5.49299 --1.66064 -1.79157 5.56787 --1.64955 -1.78227 5.72804 --1.57773 -1.7229 5.75871 --1.72354 -1.84338 6.30572 --1.4926 -1.65101 5.95639 --1.54212 -1.69289 6.30489 --1.41792 -1.58895 6.20598 --1.43381 -1.60175 6.49416 --1.42143 -1.59125 6.72055 --1.2211 -1.42491 6.37539 --1.23681 -1.43683 6.70178 --1.10334 -1.32536 6.54357 --1.04608 -1.27864 6.64504 --1.02414 -1.25988 6.88768 --0.948007 -1.19614 6.93082 --0.883299 -1.14196 7.02978 --0.808189 -1.07936 7.089 --0.728912 -1.01303 7.12739 --0.629949 -0.930744 7.06676 --0.502079 -0.824445 6.81802 --0.390871 -0.731976 6.63405 --0.331341 -0.682095 6.76149 --0.265587 -0.627605 6.86813 --0.150558 -0.532624 6.57788 --0.0756069 -0.470264 6.59166 -0.00244578 -0.404135 6.56399 -0.0753216 -0.344346 6.60425 -0.136289 -0.293074 6.84214 -0.21145 -0.230587 6.91929 -0.29544 -0.160592 6.79497 -0.373439 -0.0948903 6.75861 -0.451985 -0.0297562 6.59041 --1.63021 -1.67305 -0.971221 --1.69641 -1.72457 -0.958158 --1.7743 -1.78686 -0.953904 --1.8605 -1.85379 -0.952273 --1.95406 -1.9264 -0.952719 --2.05405 -2.00573 -0.954797 --2.16239 -2.09062 -0.957951 --2.27814 -2.18211 -0.961634 --2.40225 -2.27913 -0.965594 --2.51901 -2.3711 -0.960136 --2.65155 -2.47537 -0.95868 --2.79243 -2.5851 -0.956303 --2.95547 -2.71288 -0.960407 --3.07533 -2.80766 -0.934367 --3.24778 -2.94246 -0.929857 --3.42025 -3.07791 -0.918306 --3.61591 -3.23218 -0.909888 --3.81989 -3.39173 -0.896754 --4.04704 -3.56998 -0.884356 --4.31315 -3.77923 -0.876997 --4.60236 -4.006 -0.86683 --4.96208 -4.28824 -0.867608 --5.35235 -4.59543 -0.862761 --5.80667 -4.95098 -0.859239 --6.33155 -5.36341 -0.854878 --6.82684 -5.75205 -0.820035 --7.34626 -6.15948 -0.769096 --5.80047 -4.94547 -0.27663 --5.76316 -4.91621 -0.126817 --9.09458 -7.53155 -0.5102 --5.79798 -4.94344 0.150682 --9.85914 -8.13127 -0.165715 --10.8148 -8.88182 -0.0206663 --12.3353 -10.0755 0.128002 --14.8296 -12.0328 0.299121 --16.7956 -13.5755 0.593211 --16.9247 -13.6771 0.976882 --17.0875 -13.8043 1.36684 --17.064 -13.7854 1.75624 --17.0438 -13.7693 2.1453 --17.1202 -13.8282 2.54256 --17.2766 -13.9508 2.95307 --17.2553 -13.9334 3.34808 --17.236 -13.9179 3.74408 --17.2115 -13.8977 4.13982 --17.1818 -13.8739 4.53535 --17.1615 -13.8573 4.9339 --17.1285 -13.8305 5.33077 --17.1051 -13.812 5.73151 --17.0911 -13.8007 6.13687 --16.9951 -13.7254 6.51913 --16.9474 -13.6864 6.91661 --16.6445 -13.4487 7.22311 --17.1368 -13.8334 7.82664 --16.9652 -13.6995 8.18603 --17.2736 -13.9407 8.75081 --17.2384 -13.9125 9.17793 --17.2053 -13.8851 9.60941 --17.1797 -13.8647 10.0493 --17.154 -13.8442 10.4946 --17.1366 -13.8296 10.9496 --17.1046 -13.804 11.4024 --9.29582 -7.67907 7.05424 --6.86111 -5.77035 5.75299 --6.64843 -5.60347 5.81703 --6.79462 -5.71777 6.12474 --6.64176 -5.5976 6.22591 --6.48787 -5.47675 6.32172 --7.22878 -6.05729 7.12118 --6.58286 -5.55009 6.82945 --6.59892 -5.56328 7.06939 --6.57296 -5.54247 7.27736 --6.90661 -5.80326 7.82054 --6.66144 -5.6105 7.83945 --6.57878 -5.54486 8.00942 --5.93649 -5.04199 7.60599 --6.02578 -5.11127 7.94016 --8.42772 -6.99288 10.8358 --6.08905 -5.16091 8.51931 --7.90989 -6.58669 10.9395 --7.69913 -6.42019 11.0341 --7.23714 -6.05827 10.8046 --5.83599 -4.96113 9.31469 --4.93069 -4.2491 10.1295 --2.95026 -2.69897 7.01501 --2.8951 -2.65498 7.13966 --4.6271 -4.01001 10.627 --1.73995 -1.75062 5.36709 --1.74671 -1.75608 5.55163 --1.89959 -1.87531 6.05467 --1.73082 -1.7432 5.89062 --1.62573 -1.6602 5.85193 --1.61041 -1.64767 6.02173 --2.07172 -2.0084 7.38563 --1.99465 -1.94775 7.46857 --1.56432 -1.61173 6.59889 --1.2821 -1.38979 6.05925 --1.25214 -1.36668 6.21752 --1.65711 -1.68244 7.74766 --1.1983 -1.32431 6.59056 --1.11097 -1.25541 6.58963 --1.10056 -1.24711 6.8702 --1.0329 -1.19295 6.95222 --0.941433 -1.12151 6.94693 --0.865502 -1.06194 7.0067 --0.826804 -1.03067 7.2387 --0.702263 -0.934087 7.07307 --0.599437 -0.853072 6.99155 --0.450311 -0.736922 6.62375 --0.37756 -0.679672 6.67334 --0.305816 -0.622954 6.73118 --0.231963 -0.564432 6.78751 --0.126466 -0.482062 6.57504 --0.0517005 -0.423761 6.60785 -0.0271644 -0.361241 6.58926 -0.104961 -0.300764 6.5888 -0.167923 -0.250661 6.84596 -0.246884 -0.188919 6.87236 -0.329756 -0.123952 6.80697 -0.412303 -0.0600239 6.65973 --1.63329 -1.57526 -0.965112 --1.69937 -1.62486 -0.953447 --1.77909 -1.68411 -0.950833 --1.86711 -1.748 -0.950842 --1.96156 -1.81864 -0.952983 --2.05699 -1.88904 -0.951724 --2.16077 -1.96503 -0.951841 --2.2783 -2.05252 -0.958013 --2.39047 -2.13486 -0.954761 --2.5247 -2.2334 -0.961287 --2.65901 -2.33367 -0.96242 --2.79528 -2.43357 -0.958353 --2.93996 -2.53992 -0.953015 --3.1141 -2.66907 -0.958084 --3.25245 -2.77101 -0.936983 --3.436 -2.90714 -0.932439 --3.61313 -3.03711 -0.917025 --3.82183 -3.19156 -0.907918 --4.03783 -3.35133 -0.893497 --4.30205 -3.54575 -0.888283 --4.58206 -3.753 -0.877933 --4.91762 -4.00039 -0.874772 --5.2941 -4.27834 -0.870052 --5.71042 -4.58577 -0.861328 --6.32401 -5.0386 -0.88957 --6.79061 -5.38376 -0.853443 --7.29066 -5.75237 -0.80504 --5.75992 -4.62159 -0.310178 --8.52984 -6.66681 -0.689406 --5.76111 -4.62276 -0.0324704 --9.50743 -7.3883 -0.430414 --9.85398 -7.64441 -0.25284 --10.6558 -8.23666 -0.106037 --11.8665 -9.13006 0.0435272 --13.9761 -10.6873 0.195239 --17.4184 -13.2289 0.392826 --18.4385 -13.9811 0.769139 --19.0265 -14.4144 1.18552 --19.2138 -14.5523 1.6151 --18.6881 -14.1639 2.01542 --18.3584 -13.9195 2.40813 --19.3226 -14.6307 2.91203 --19.2771 -14.5961 3.33978 --19.3291 -14.6343 3.78072 --19.3108 -14.6208 4.21428 --19.2947 -14.6082 4.6494 --19.2733 -14.5919 5.0847 --19.2362 -14.5645 5.51836 --19.2178 -14.5498 5.95766 --19.1451 -14.4959 6.38448 --19.1142 -14.4719 6.82375 --18.6632 -14.1388 7.13104 --19.11 -14.4673 7.72932 --18.9744 -14.3668 8.13944 --19.1708 -14.5118 8.67755 --19.1514 -14.4969 9.14087 --19.133 -14.4828 9.60914 --19.1156 -14.4684 10.0824 --19.0972 -14.4547 10.5612 --8.413 -6.57226 5.57284 --8.34006 -6.51915 5.76151 --18.8368 -14.2616 11.9177 --7.16936 -5.65438 5.532 --8.22146 -6.42999 6.38755 --6.65939 -5.27771 5.6175 --6.93289 -5.47987 6.00062 --6.86832 -5.43142 6.16584 --6.61449 -5.24479 6.19312 --6.65038 -5.27097 6.43002 --6.51887 -5.17308 6.54122 --6.56835 -5.20952 6.79734 --6.49855 -5.15746 6.96084 --7.06345 -5.5738 7.68573 --6.85242 -5.41726 7.74169 --6.69897 -5.30402 7.84529 --6.21734 -4.94905 7.62116 --6.06085 -4.8341 7.70223 --6.46853 -5.13312 8.37521 --6.32142 -5.02551 8.47882 --6.12091 -4.87621 8.51758 --6.04899 -4.82329 8.70116 --6.09508 -4.85728 9.03092 --6.021 -4.80208 9.22248 --6.97638 -5.50545 10.7611 --4.74679 -3.8599 10.4543 --4.64968 -3.78766 10.6333 --3.56391 -2.98862 8.89759 --3.33892 -2.82276 8.75435 --2.30803 -2.06345 6.899 --1.692 -1.60996 5.7933 --2.80274 -2.42708 8.52757 --2.20137 -1.98388 7.41886 --2.09646 -1.90688 7.44065 --1.9915 -1.82902 7.45969 --1.35457 -1.36078 6.03023 --1.30908 -1.32683 6.14292 --1.22728 -1.26705 6.15358 --1.31461 -1.33129 6.69235 --1.1808 -1.23195 6.55286 --1.11132 -1.17982 6.61664 --1.19315 -1.2408 7.24783 --1.0128 -1.10744 6.92114 --0.957743 -1.06635 7.06806 --0.885115 -1.01319 7.1564 --0.800029 -0.950206 7.19502 --0.688146 -0.867607 7.09584 --0.546482 -0.763073 6.80816 --0.433822 -0.680751 6.64381 --0.378648 -0.6392 6.82034 --0.296804 -0.57905 6.83839 --0.183315 -0.495562 6.59758 --0.102557 -0.435538 6.59162 --0.0238663 -0.377502 6.60369 -0.0528209 -0.320951 6.64398 -0.122522 -0.269643 6.79231 -0.199439 -0.212802 6.89926 -0.286121 -0.147987 6.77488 -0.368747 -0.0880756 6.72856 -0.450173 -0.0276481 6.61044 --1.72564 -1.54492 -0.971445 --1.79359 -1.59233 -0.958374 --1.8825 -1.65423 -0.959778 --1.97245 -1.71692 -0.957933 --2.0697 -1.78428 -0.958215 --2.18164 -1.86213 -0.965298 --2.28728 -1.93588 -0.963111 --2.3949 -2.00932 -0.957021 --2.53089 -2.10386 -0.965836 --2.66797 -2.20007 -0.969355 --2.79963 -2.29012 -0.9634 --2.9534 -2.39726 -0.964975 --3.11656 -2.51077 -0.964677 --3.31006 -2.64498 -0.973783 --3.44488 -2.73873 -0.945198 --3.64041 -2.87412 -0.940216 --3.82232 -3.00058 -0.92054 --4.03561 -3.1485 -0.90682 --4.28032 -3.3188 -0.897009 --4.56581 -3.51697 -0.89208 --4.88475 -3.73816 -0.886509 --5.2518 -3.99269 -0.883702 --5.62924 -4.25399 -0.868183 --6.15848 -4.62183 -0.880112 --5.75082 -4.3389 -0.62545 --5.74927 -4.33711 -0.486677 --5.8587 -4.41311 -0.372917 --5.75566 -4.34123 -0.214098 --5.78868 -4.36386 -0.0838193 --5.96611 -4.48714 0.025283 --5.96355 -4.48537 0.164952 --10.6134 -7.71319 -0.198302 --11.5885 -8.38893 -0.0449096 --13.2665 -9.55408 0.103423 --15.9537 -11.4193 0.278498 --20.2991 -14.4343 0.529942 --20.3604 -14.4769 0.971861 --21.0888 -14.9819 1.4294 --20.8415 -14.809 1.87811 --20.4813 -14.5585 2.30978 --21.2304 -15.0777 2.81981 --21.2174 -15.0685 3.28285 --21.222 -15.0712 3.74888 --21.2048 -15.0582 4.2135 --21.1958 -15.0515 4.6809 --21.164 -15.0293 5.14578 --21.1425 -15.0134 5.61394 --21.1137 -14.9928 6.08243 --21.0379 -14.9395 6.5407 --20.9715 -14.8935 7.0018 --20.6429 -14.6647 7.38467 --21.0403 -14.9404 7.99255 --21.001 -14.912 8.4709 --21.0244 -14.9276 8.97594 --21.0007 -14.9106 9.46876 --8.65007 -6.3446 4.81996 --8.63994 -6.33758 5.03411 --8.44289 -6.20062 5.16331 --8.42016 -6.18364 5.37119 --7.70538 -5.68843 5.2248 --7.44891 -5.50995 5.29291 --7.4973 -5.54368 5.52426 --7.34313 -5.43586 5.64084 --7.36331 -5.44978 5.86102 --7.39388 -5.47051 6.09282 --7.14066 -5.29495 6.13876 --7.17958 -5.32173 6.38002 --7.07973 -5.25226 6.52676 --6.95069 -5.16267 6.64981 --6.82786 -5.07662 6.77456 --6.72289 -5.00489 6.91245 --6.66473 -4.96357 7.08787 --6.66288 -4.96141 7.31524 --6.512 -4.85737 7.4123 --6.71758 -4.99908 7.84298 --6.36234 -4.75264 7.74373 --6.69294 -4.98164 8.32486 --6.46281 -4.82199 8.3454 --6.28372 -4.6971 8.41183 --6.1401 -4.59739 8.51386 --6.26838 -4.68626 8.93114 --6.72986 -5.00574 9.77286 --7.14635 -5.29318 10.6075 --7.13063 -5.28216 10.9291 --5.93485 -4.45138 11.358 --5.73703 -4.3142 11.4121 --3.77706 -2.95706 8.68819 --3.71474 -2.91368 8.86989 --3.48411 -2.75404 8.72933 --2.55346 -2.10991 7.15942 --2.43532 -2.02862 7.16269 --3.66557 -2.87816 10.1084 --3.70477 -2.90534 10.5836 --3.58926 -2.82506 10.7247 --2.10796 -1.80105 7.47735 --2.00432 -1.72872 7.50448 --1.38049 -1.29687 6.11395 --1.39108 -1.30447 6.39223 --1.31352 -1.25003 6.43142 --1.24121 -1.20045 6.4877 --1.14509 -1.13404 6.46741 --1.27109 -1.21944 7.21972 --1.14597 -1.13349 7.1232 --1.04351 -1.0616 7.09979 --0.953537 -0.999735 7.12192 --0.871745 -0.942575 7.18067 --0.748812 -0.857499 7.04385 --0.656818 -0.794023 7.04025 --0.513471 -0.69418 6.74098 --0.416458 -0.627177 6.6732 --0.366518 -0.592426 6.90837 --0.270526 -0.525544 6.83689 --0.155291 -0.445725 6.58494 --0.0777721 -0.392112 6.62767 -0.00677781 -0.333931 6.58924 -0.0863313 -0.278586 6.60874 -0.148121 -0.234973 6.93572 -0.241608 -0.170488 6.75244 -0.323311 -0.113523 6.78697 -0.409483 -0.0538063 6.59977 --1.88856 -1.55569 -0.962299 --1.97934 -1.6154 -0.962097 --2.07109 -1.67488 -0.958597 --2.17121 -1.73997 -0.957071 --2.28594 -1.81455 -0.962196 --2.39439 -1.88503 -0.958249 --2.51851 -1.96588 -0.959803 --2.65098 -2.05225 -0.961433 --2.80643 -2.1537 -0.971589 --2.93989 -2.2405 -0.962879 --3.1057 -2.34798 -0.965765 --3.26422 -2.45139 -0.958384 --3.47807 -2.5906 -0.971824 --3.63131 -2.69047 -0.947429 --3.83156 -2.82136 -0.938434 --4.02545 -2.94707 -0.918321 --4.26739 -3.10456 -0.909759 --4.526 -3.2729 -0.897756 --4.83369 -3.47373 -0.892559 --5.18406 -3.70112 -0.888591 --5.57524 -3.95707 -0.883062 --5.961 -4.20744 -0.85952 --5.75804 -4.07556 -0.663727 --5.70745 -4.04214 -0.515102 --5.81973 -4.11518 -0.405777 --5.72324 -4.05212 -0.250787 --5.93149 -4.18726 -0.155228 --5.88093 -4.15403 -0.0105977 --5.90347 -4.16919 0.121251 --10.5606 -7.20214 -0.285613 --11.4884 -7.80599 -0.141866 --12.7665 -8.63783 0.0139885 --15.1565 -10.1943 0.163188 --18.5673 -12.415 0.37839 --22.5284 -14.9939 0.728802 --22.7895 -15.1628 1.21073 --22.8161 -15.1802 1.69665 --22.7779 -15.1544 2.18084 --24.6813 -16.3928 2.80315 --24.7181 -16.4163 3.33339 --24.6058 -16.3423 3.84969 --24.5936 -16.3339 4.37645 --24.5657 -16.3155 4.90242 --24.5055 -16.2751 5.4237 --24.4704 -16.2521 5.9503 --24.4102 -16.2127 6.47303 --24.4178 -16.2165 7.01273 --22.5413 -14.9944 7.06121 --24.4307 -16.2236 8.10461 --24.3236 -16.1532 8.62262 --24.3541 -16.1725 9.18616 --7.23563 -5.03217 3.72212 --7.40273 -5.14063 3.96059 --7.15113 -4.97722 4.04249 --8.54403 -5.88323 4.80676 --8.44018 -5.81501 4.97356 --6.89834 -4.81202 4.46481 --7.39649 -5.13598 4.88917 --7.10016 -4.94323 4.92969 --7.81989 -5.4106 5.50917 --6.9437 -4.83984 5.2222 --7.44375 -5.16553 5.71033 --7.04649 -4.90655 5.67227 --6.82209 -4.76083 5.72868 --7.54043 -5.22718 6.41103 --7.27956 -5.0574 6.4509 --6.85539 -4.78152 6.36168 --7.03048 -4.89521 6.70699 --7.27517 -5.0534 7.1218 --7.03208 -4.89576 7.15828 --6.20345 -4.35631 6.68802 --5.96356 -4.20018 6.69005 --6.57841 -4.60013 7.4619 --6.47673 -4.53311 7.60194 --6.34081 -4.44477 7.70808 --6.38783 -4.47564 7.99855 --6.00765 -4.22816 7.84963 --6.2416 -4.37881 8.34841 --6.47352 -4.53034 8.87255 --7.01589 -4.88246 9.78657 --7.31084 -5.07318 10.4545 --7.42503 -5.14775 10.9345 --5.90733 -4.15916 11.2972 --5.79089 -4.0826 11.4858 --5.57905 -3.94442 11.5162 --3.90768 -2.85959 8.91647 --4.18851 -3.041 9.74847 --2.64659 -2.03998 7.10118 --2.53081 -1.96509 7.11399 --2.45743 -1.91656 7.21087 --3.86664 -2.83072 10.5561 --3.78451 -2.77649 10.7784 --2.22601 -1.766 7.49407 --2.13501 -1.70609 7.55874 --1.47961 -1.28171 6.15736 --1.36092 -1.20352 6.07858 --1.37352 -1.21155 6.36581 --1.30345 -1.16637 6.43183 --1.25085 -1.13144 6.55274 --1.15498 -1.0696 6.54108 --1.23738 -1.12248 7.15295 --1.13416 -1.05511 7.14038 --1.04847 -0.999521 7.19248 --0.93505 -0.926354 7.12739 --0.847273 -0.868553 7.16595 --0.71748 -0.78441 6.9985 --0.596996 -0.705923 6.8472 --0.506267 -0.646582 6.83961 --0.420721 -0.591576 6.8596 --0.323907 -0.52822 6.79891 --0.229163 -0.465854 6.73597 --0.123399 -0.397643 6.56184 --0.0501167 -0.350377 6.65338 -0.0303217 -0.29806 6.69375 -0.102897 -0.249441 6.85201 -0.190419 -0.193166 6.83938 -0.276868 -0.136403 6.79489 -0.366045 -0.0788457 6.64863 -0.448423 -0.0255565 6.6504 --1.99694 -1.52478 -0.976671 --2.06867 -1.56868 -0.958043 --2.17687 -1.63464 -0.963733 --2.27879 -1.69652 -0.960252 --2.38906 -1.76399 -0.958246 --2.50763 -1.83602 -0.957265 --2.63455 -1.91358 -0.95666 --2.76876 -1.99572 -0.955986 --2.92063 -2.08801 -0.959206 --3.07252 -2.18103 -0.956784 --3.25769 -2.29363 -0.965005 --3.41994 -2.39264 -0.954514 --3.65408 -2.53583 -0.971737 --3.80168 -2.62566 -0.940462 --4.03053 -2.76519 -0.938074 --4.24476 -2.8958 -0.920197 --4.49129 -3.04675 -0.906723 --4.78879 -3.22811 -0.901247 --5.10294 -3.42021 -0.889732 --5.47638 -3.64814 -0.884093 --5.9008 -3.90708 -0.878312 --5.72017 -3.79632 -0.690651 --7.04717 -4.60572 -0.889338 --5.70884 -3.78866 -0.421867 --5.73752 -3.80577 -0.296492 --5.84849 -3.87383 -0.186119 --5.85639 -3.87886 -0.0547604 --5.84652 -3.87181 0.0789962 --11.0112 -7.02475 -0.432756 --11.3455 -7.22819 -0.229922 --12.4352 -7.89302 -0.0769612 --14.2646 -9.0098 0.0736237 --15.0355 -9.47943 0.343447 --15.1114 -9.52533 0.659667 --15.4807 -9.75099 0.978354 --26.6682 -16.5783 1.51816 --26.657 -16.5705 2.07349 --26.5948 -16.5317 2.62598 --27.6818 -17.1944 3.26942 --27.6871 -17.1964 3.84946 --27.8016 -17.2662 4.44494 --27.7892 -17.2579 5.02898 --27.7581 -17.2389 5.61217 --27.753 -17.2349 6.20157 --27.2426 -16.9225 6.69034 --27.0785 -16.8219 7.23954 --27.0818 -16.8236 7.82717 --27.035 -16.7936 8.40562 --27.6826 -17.188 9.18881 --27.6473 -17.1662 9.79206 --7.50617 -4.88166 3.67692 --7.39129 -4.81158 3.81393 --7.43742 -4.83924 4.00861 --7.15003 -4.66282 4.07303 --7.07056 -4.6154 4.21538 --7.03772 -4.59433 4.37664 --7.11296 -4.64037 4.58993 --7.10611 -4.63592 4.76839 --7.20414 -4.69551 5.00432 --7.20557 -4.69599 5.19489 --7.03468 -4.59222 5.29054 --7.00803 -4.57506 5.46645 --6.86518 -4.48814 5.57242 --7.01191 -4.57721 5.86247 --6.97597 -4.5555 6.0402 --6.91401 -4.51708 6.20242 --6.42972 -4.22154 6.057 --6.36058 -4.17934 6.20317 --6.08391 -4.01032 6.18632 --5.92144 -3.91158 6.25133 --5.9737 -3.94354 6.49323 --6.13683 -4.04179 6.841 --6.34558 -4.16853 7.24613 --6.36455 -4.18024 7.49193 --6.31918 -4.15245 7.68251 --6.35365 -4.17377 7.95842 --6.46576 -4.24108 8.32458 --6.57373 -4.30697 8.70416 --6.79663 -4.44195 9.22903 --7.10237 -4.62793 9.87828 --7.18835 -4.68011 10.2981 --7.26494 -4.72653 10.7241 --6.67234 -4.36503 10.3021 --7.29671 -4.74459 11.4726 --5.89222 -3.88879 10.9028 --5.80919 -3.83704 11.1368 --5.40656 -3.59191 10.8467 --5.12088 -3.41758 10.7257 --5.07309 -3.38804 11.0149 --3.56146 -2.46867 8.58497 --2.64579 -1.9113 7.10784 --2.51166 -1.82928 7.08465 --4.24308 -2.8821 10.9822 --2.58533 -1.87409 7.76855 --3.82617 -2.62737 10.9026 --3.64413 -2.51671 10.9085 --3.56833 -2.47003 11.1728 --1.42915 -1.17073 6.04995 --1.47158 -1.19539 6.41047 --1.43257 -1.17174 6.57036 --1.33991 -1.11463 6.58089 --1.2535 -1.06232 6.60822 --1.16093 -1.00639 6.6148 --1.17311 -1.01209 6.99002 --1.07026 -0.950815 6.97545 --1.01658 -0.917263 7.15068 --0.958781 -0.881973 7.3255 --0.799476 -0.784748 7.05349 --0.69762 -0.722319 7.02065 --0.636678 -0.684961 7.20055 --0.522626 -0.615838 7.09521 --0.386271 -0.533451 6.81967 --0.29276 -0.476506 6.78745 --0.180003 -0.407121 6.58489 --0.10079 -0.359138 6.6375 --0.0124887 -0.305192 6.59915 -0.065769 -0.257322 6.6685 -0.126448 -0.219701 7.07537 -0.233468 -0.154434 6.72246 -0.319731 -0.10173 6.697 -0.405733 -0.0495668 6.59978 --2.16595 -1.52071 -0.958808 --2.26869 -1.57963 -0.95727 --2.38073 -1.64308 -0.957353 --2.49281 -1.70733 -0.953492 --2.6215 -1.78089 -0.955176 --2.75848 -1.85897 -0.956987 --2.89642 -1.93674 -0.953901 --3.05009 -2.02579 -0.954467 --3.22228 -2.12288 -0.957727 --3.41013 -2.23013 -0.96259 --3.60004 -2.33893 -0.960557 --3.81485 -2.46146 -0.962398 --4.02236 -2.57984 -0.952774 --4.22356 -2.69405 -0.931982 --4.44971 -2.82289 -0.913217 --4.71845 -2.97657 -0.901073 --5.02141 -3.14931 -0.890082 --5.35028 -3.33636 -0.875521 --5.77264 -3.57768 -0.875928 --6.37461 -3.92112 -0.909137 --7.30055 -4.44955 -1.00151 --6.84514 -4.18973 -0.730082 --5.78866 -3.5858 -0.09006 --5.78723 -3.58548 0.039075 --6.854 -4.19375 0.0259032 --11.6223 -6.91301 -0.360104 --12.2817 -7.2893 -0.175372 --13.6239 -8.05479 -0.0136841 --15.104 -8.89892 0.194486 --15.1579 -8.9283 0.50665 --15.0324 -8.85698 0.822752 --15.3281 -9.02509 1.13735 --29.8614 -17.3127 1.87306 --29.8261 -17.2916 2.48196 --32.4187 -18.7698 3.27174 --32.3272 -18.7167 3.92797 --32.269 -18.6835 4.58609 --32.2366 -18.6636 5.24722 --32.2012 -18.6429 5.9093 --32.1658 -18.622 6.57288 --31.982 -18.5162 7.21011 --29.5679 -17.1394 7.3711 --32.0895 -18.5768 8.58446 --32.2158 -18.648 9.30042 --32.1533 -18.6112 9.97486 --32.122 -18.593 10.6618 --7.71773 -4.6826 3.61073 --7.73478 -4.69246 3.79515 --7.25218 -4.41638 3.80138 --7.42262 -4.51364 4.03882 --7.56397 -4.59373 4.27393 --7.35824 -4.47704 4.36913 --7.29025 -4.43759 4.51905 --7.22022 -4.39733 4.66742 --7.54595 -4.58317 5.01271 --7.04084 -4.29521 4.94212 --7.23904 -4.40712 5.23461 --6.97122 -4.25485 5.27361 --6.99755 -4.27017 5.47828 --7.02794 -4.2869 5.69005 --7.00139 -4.27154 5.86995 --7.11357 -4.33527 6.14653 --6.44205 -3.95268 5.88151 --6.38136 -3.91783 6.0308 --6.44904 -3.9566 6.27843 --6.15337 -3.78742 6.24754 --6.00886 -3.70488 6.32818 --6.3331 -3.88941 6.80246 --6.1337 -3.77514 6.84144 --6.21372 -3.82121 7.12916 --5.98642 -3.69116 7.13606 --6.92377 -4.22481 8.27694 --6.64363 -4.06438 8.25288 --6.35223 -3.89873 8.20626 --6.18595 -3.80376 8.28085 --5.91939 -3.65142 8.23895 --6.5408 -4.00539 9.22163 --6.67832 -4.08361 9.6805 --6.57494 -4.02376 9.86004 --6.37036 -3.9072 9.911 --6.27427 -3.85242 10.1007 --6.21324 -3.81697 10.3432 --6.02111 -3.70808 10.4062 --5.87229 -3.62276 10.5278 --5.80507 -3.58446 10.7747 --5.49416 -3.40634 10.6394 --5.37121 -3.33661 10.7994 --5.24615 -3.26509 10.9574 --2.83856 -1.89653 7.00938 --2.70165 -1.81848 6.99027 --2.65442 -1.79084 7.1396 --2.51343 -1.71074 7.10634 --2.67434 -1.80183 7.70156 --2.51994 -1.71447 7.64904 --3.77622 -2.42737 10.8299 --3.66047 -2.36094 10.9954 --2.19574 -1.52913 7.77606 --2.06095 -1.45247 7.74662 --1.46761 -1.11494 6.43952 --1.40808 -1.08028 6.54327 --1.32085 -1.03099 6.57134 --1.20687 -0.96556 6.51274 --1.13608 -0.925703 6.59344 --1.19647 -0.959604 7.14977 --1.0456 -0.873713 6.96238 --1.0463 -0.873568 7.36808 --0.927198 -0.805841 7.30132 --0.907203 -0.79382 7.68859 --0.644274 -0.644961 6.88614 --0.581463 -0.609263 7.0551 --0.484934 -0.553339 7.04634 --0.346896 -0.475118 6.74957 --0.262734 -0.427778 6.79528 --0.147233 -0.361608 6.57173 --0.064156 -0.314378 6.59372 -0.0149845 -0.269038 6.67379 -0.0951765 -0.223848 6.77229 -0.17947 -0.175453 6.83937 -0.267678 -0.12534 6.84487 -0.362349 -0.071078 6.59861 -0.447481 -0.0224721 6.6104 --2.28389 -1.48227 -0.974494 --2.36659 -1.52547 -0.955332 --2.4805 -1.5867 -0.953411 --2.61821 -1.66007 -0.962258 --2.73306 -1.72084 -0.952143 --2.88109 -1.79936 -0.956167 --3.0219 -1.87484 -0.950574 --3.18749 -1.96224 -0.952749 --3.36974 -2.05977 -0.957026 --3.56225 -2.16157 -0.958626 --3.7714 -2.27342 -0.960728 --3.98256 -2.38577 -0.955084 --4.24347 -2.52484 -0.962333 --4.44003 -2.6289 -0.933659 --4.67914 -2.75687 -0.913155 --4.96897 -2.91131 -0.901545 --5.25248 -3.06144 -0.876169 --5.60442 -3.24907 -0.861037 --6.15418 -3.54121 -0.888388 --7.06858 -4.02763 -0.98951 --7.05461 -4.02051 -0.82915 --6.99504 -3.98864 -0.660379 --5.58572 -3.23857 -0.223383 --5.57703 -3.23387 -0.0982132 --5.68118 -3.2885 0.00805145 --5.75637 -3.32846 0.121724 --12.3352 -6.83002 -0.545626 --12.3655 -6.84671 -0.292506 --13.2738 -7.32943 -0.109698 --15.148 -8.32671 0.0495866 --15.1873 -8.34712 0.358015 --15.1159 -8.30885 0.669874 --15.0921 -8.29595 0.978672 --16.6168 -9.10694 1.31484 --16.5391 -9.06486 1.6505 --36.2847 -19.5714 3.1321 --36.898 -19.8969 3.90957 --33.0479 -17.8483 4.27726 --32.9225 -17.7802 4.93164 --36.6867 -19.7828 6.11888 --34.0841 -18.3976 6.456 --31.4405 -16.9902 6.68405 --31.3048 -16.9174 7.30589 --31.3936 -16.9635 8.63154 --31.2455 -16.8833 9.25405 --31.2423 -16.8817 9.91646 --31.6123 -17.0773 10.697 --31.6534 -17.0984 11.3934 --9.58655 -5.36319 4.47736 --9.52376 -5.32917 4.67303 --7.91226 -4.47171 4.26725 --7.76899 -4.39575 4.39549 --7.51818 -4.26163 4.47263 --8.20078 -4.62414 4.9667 --7.8942 -4.46141 5.02116 --7.03164 -4.00267 4.78485 --7.50848 -4.25638 5.21553 --7.00566 -3.98896 5.13265 --7.24059 -4.11334 5.45242 --7.22548 -4.10506 5.63744 --7.55436 -4.27979 6.04098 --7.3915 -4.19321 6.14444 --7.28129 -4.13399 6.27911 --6.77146 -3.86323 6.13054 --7.536 -4.26964 6.89322 --6.05243 -3.4803 5.99057 --6.11171 -3.51206 6.22809 --6.35979 -3.64271 6.62775 --6.44068 -3.68616 6.90663 --6.31407 -3.61935 7.01219 --6.13785 -3.52478 7.07042 --6.76863 -3.85934 7.8874 --6.83491 -3.89495 8.20035 --6.55855 -3.74729 8.17704 --6.31737 -3.61932 8.17925 --6.16179 -3.53622 8.2643 --6.05474 -3.47968 8.40183 --6.24049 -3.57799 8.88221 --6.04572 -3.47421 8.92655 --6.49733 -3.71372 9.77468 --6.44784 -3.68723 10.0247 --6.22312 -3.56735 10.0458 --6.19421 -3.55184 10.3324 --6.294 -3.60395 10.8175 --6.00857 -3.45299 10.7507 --6.1597 -3.53161 11.3466 --5.56742 -3.21735 10.7808 --5.61359 -3.24236 11.2306 --5.37862 -3.11686 11.2158 --2.7431 -1.71833 6.85603 --2.70735 -1.69921 7.02197 --2.57902 -1.63106 7.01521 --2.38697 -1.52931 6.87404 --2.50844 -1.59311 7.38016 --2.43352 -1.55296 7.49195 --3.78956 -2.27177 10.9173 --2.32477 -1.49557 7.83027 --2.15433 -1.40499 7.72062 --1.57655 -1.09776 6.51153 --1.46078 -1.03669 6.46826 --1.3922 -1.00052 6.55286 --1.34609 -0.975362 6.71143 --1.31022 -0.956272 6.91712 --1.27322 -0.936296 7.14199 --1.11142 -0.850407 6.92749 --1.11218 -0.85074 7.3235 --1.01271 -0.797517 7.34469 --0.921368 -0.747995 7.40266 --0.734369 -0.649855 7.00108 --0.626842 -0.591873 6.94619 --0.549938 -0.551948 7.05589 --0.447548 -0.496898 7.01649 --0.330082 -0.434709 6.85651 --0.216747 -0.374416 6.69374 --0.119695 -0.32287 6.61771 --0.0306963 -0.275511 6.60911 -0.0215226 -0.246875 7.04692 -0.125522 -0.19246 6.89581 -0.224395 -0.139345 6.73249 -0.31522 -0.091405 6.65707 -0.403041 -0.0443909 6.59974 --2.48802 -1.47862 -0.967606 --2.59541 -1.53187 -0.95861 --2.73586 -1.60094 -0.964949 --2.87015 -1.6679 -0.961818 --3.0126 -1.73738 -0.958613 --3.16339 -1.81233 -0.954686 --3.33178 -1.8964 -0.953705 --3.52694 -1.99219 -0.958888 --3.747 -2.10175 -0.968446 --3.96075 -2.20709 -0.966335 --4.18383 -2.31768 -0.960004 --4.46683 -2.45752 -0.969081 --4.6588 -2.55243 -0.932576 --4.92725 -2.68487 -0.916476 --5.205 -2.82242 -0.893259 --5.48474 -2.96033 -0.859798 --5.5133 -2.97487 -0.742962 --5.5129 -2.97473 -0.618618 --5.51144 -2.97368 -0.494726 --5.50793 -2.97178 -0.371489 --5.50136 -2.96909 -0.248811 --5.50298 -2.96902 -0.128455 --5.4933 -2.96457 -0.00698446 --5.48152 -2.95828 0.113782 --5.50286 -2.96931 0.229199 --13.2128 -6.78337 -0.491948 --13.2874 -6.82 -0.22956 --14.7988 -7.5681 -0.0649818 --15.5116 -7.92022 0.198085 --15.2616 -7.79605 0.517821 --15.4733 -7.90052 0.822449 --15.4733 -7.90011 1.13351 --39.7527 -19.9098 2.1193 --39.7377 -19.9018 2.90318 --33.7969 -16.9633 3.29186 --33.8194 -16.9727 3.96459 --33.7047 -16.9167 4.62574 --33.8036 -16.9649 5.31127 --36.1405 -18.1193 6.32881 --33.5957 -16.8605 6.63538 --31.7604 -15.9524 6.97564 --32.7025 -16.4174 7.8164 --31.8706 -16.0053 8.29926 --30.0625 -15.1098 9.13934 --30.7548 -15.452 9.96979 --30.896 -15.5203 10.6647 --30.2758 -15.2131 11.1217 --10.2271 -5.30161 4.75622 --9.63119 -5.00715 4.76535 --9.12295 -4.75498 4.78571 --9.21306 -4.80033 5.03521 --30.9914 -15.5632 15.4976 --9.19224 -4.78839 5.68409 --9.10901 -4.74717 5.86788 --10.7475 -5.55764 6.96446 --7.5705 -3.98705 5.47346 --7.5389 -3.97101 5.65289 --7.51244 -3.95743 5.83719 --8.96597 -4.67569 6.95531 --7.35651 -3.88028 6.14611 --7.12914 -3.768 6.19914 --7.10682 -3.75687 6.38969 --6.23657 -3.32633 5.95848 --6.35025 -3.38192 6.23576 --6.42071 -3.41718 6.49005 --6.29027 -3.35297 6.5883 --6.38737 -3.39993 6.87757 --6.35783 -3.3853 7.0666 --6.59391 -3.50177 7.50393 --6.85979 -3.63301 7.99124 --6.70864 -3.55781 8.09363 --6.69648 -3.55161 8.33404 --6.37247 -3.39166 8.25296 --6.2574 -3.33484 8.38562 --6.08467 -3.24869 8.45189 --5.16928 -2.79746 7.64432 --6.61776 -3.51159 9.63869 --5.52351 -2.97171 8.57153 --5.3807 -2.90086 8.65717 --6.12925 -3.26924 9.94202 --5.94931 -3.18019 10.0149 --6.10753 -3.25815 10.5749 --6.01082 -3.21055 10.7823 --5.7466 -3.08033 10.7367 --2.80955 -1.631 6.35281 --2.74006 -1.5967 6.4413 --2.79992 -1.62557 6.75638 --2.79813 -1.62452 6.9815 --2.52231 -1.48864 6.70036 --2.51636 -1.48493 6.92351 --2.48788 -1.47122 7.11299 --2.37519 -1.41476 7.13464 --2.38661 -1.4204 7.43116 --2.43691 -1.44528 7.8381 --2.30372 -1.37947 7.83052 --3.3379 -1.88768 10.7986 --1.56135 -1.01287 6.52257 --1.57681 -1.02074 6.85006 --1.40908 -0.937764 6.66481 --1.35997 -0.912778 6.82357 --1.2823 -0.875245 6.90624 --1.18411 -0.826285 6.92085 --1.22261 -0.844223 7.44151 --1.08564 -0.776815 7.3295 --1.00676 -0.737652 7.44643 --0.768164 -0.620571 6.84285 --0.762524 -0.617447 7.29602 --0.593318 -0.534146 6.93753 --0.509374 -0.491634 7.0069 --0.395135 -0.435768 6.89741 --0.296124 -0.387215 6.86447 --0.171006 -0.325595 6.60144 --0.0861725 -0.282987 6.63345 -0.0344888 -0.223802 6.27565 -0.0746789 -0.203615 6.87195 -0.174438 -0.154032 6.73953 -0.249017 -0.117335 7.12453 -0.35965 -0.0628616 6.53864 -0.445733 -0.0208798 6.6605 --2.49061 -1.37182 -0.981269 --2.59988 -1.42302 -0.973664 --2.71007 -1.47298 -0.962509 --2.84507 -1.535 -0.96172 --3.01312 -1.61275 -0.974569 --3.15011 -1.67517 -0.963937 --3.31289 -1.74947 -0.961469 --3.4932 -1.83186 -0.961399 --3.69003 -1.92235 -0.962828 --3.90644 -2.02172 -0.964701 --4.14036 -2.12903 -0.966174 --4.36704 -2.23318 -0.955732 --4.73299 -2.40132 -0.989434 --4.91831 -2.4862 -0.944554 --5.16655 -2.60006 -0.913576 --5.43129 -2.72179 -0.879304 --5.81148 -2.89593 -0.869168 --6.72177 -3.31341 -0.990938 --7.07094 -3.47403 -0.933401 --6.82499 -3.36106 -0.722923 --6.78014 -3.33996 -0.566647 --5.70315 -2.84571 -0.211499 --5.63157 -2.81223 -0.0765234 --5.67449 -2.83207 0.037159 --12.0927 -5.77699 -0.718615 --13.5825 -6.46086 -0.64795 --14.2857 -6.78337 -0.443574 --14.5692 -6.91264 -0.180133 --16.0565 -7.59511 0.0225107 --15.7061 -7.43425 0.354935 --15.5504 -7.36182 0.669595 --16.0986 -7.61334 0.976946 --16.4057 -7.75421 1.30118 --40.0623 -18.6062 2.50096 --34.5403 -16.0723 3.64599 --35.0098 -16.286 4.3673 --35.0508 -16.3042 5.0599 --35.1165 -16.3337 5.75992 --34.4591 -16.0319 6.35473 --33.9656 -15.8051 6.95536 --34.2648 -15.9408 8.38295 --31.1539 -14.5142 8.35495 --30.7317 -14.3197 8.88552 --10.627 -5.10064 4.03539 --10.4986 -5.04178 4.22533 --10.3321 -4.9649 4.40033 --10.564 -5.07122 4.70388 --10.2873 -4.94381 4.83866 --9.40767 -4.54059 4.73705 --9.2269 -4.45819 4.87895 --8.98638 -4.34683 4.99011 --8.94659 -4.32863 5.18271 --9.16402 -4.42832 5.49595 --9.01619 -4.36067 5.64419 --6.48881 -3.20101 4.90406 --7.55791 -3.69179 5.69791 --8.97021 -4.33826 6.75637 --8.78329 -4.25226 6.87733 --8.68894 -4.20903 7.05464 --7.4883 -3.65843 6.47389 --7.04144 -3.45381 6.37093 --7.17334 -3.5139 6.67668 --6.58366 -3.24334 6.43952 --6.45146 -3.18317 6.53937 --7.26363 -3.55491 7.41697 --7.69953 -3.75409 8.02592 --6.72364 -3.30674 7.41571 --6.60681 -3.25342 7.54052 --7.10007 -3.47846 8.24582 --6.72642 -3.30785 8.13667 --6.80566 -3.34358 8.47174 --6.52242 -3.21395 8.43736 --5.39831 -2.69904 7.46927 --5.24458 -2.62837 7.52401 --6.68084 -3.28571 9.44482 --5.60733 -2.79373 8.43822 --5.39815 -2.69789 8.44121 --6.38631 -3.14955 9.99948 --6.39758 -3.15502 10.3398 --6.28771 -3.10426 10.5259 --6.28863 -3.10476 10.8781 --3.08428 -1.63775 6.40781 --2.96162 -1.58144 6.41849 --2.83385 -1.52299 6.41782 --2.74301 -1.48162 6.47259 --2.66543 -1.4453 6.55082 --2.62375 -1.42654 6.69642 --2.52777 -1.38269 6.74673 --2.55154 -1.3932 7.03114 --2.46369 -1.35264 7.1064 --2.44545 -1.34456 7.33156 --2.5284 -1.38245 7.80022 --2.3965 -1.32208 7.80293 --2.2738 -1.26541 7.82091 --2.12252 -1.19619 7.76269 --1.80988 -1.05269 7.25587 --1.50053 -0.911333 6.70202 --1.40362 -0.86711 6.72066 --1.44636 -0.885753 7.18161 --1.20466 -0.775194 6.73312 --1.57518 -0.943881 8.4186 --1.16962 -0.759099 7.36189 --1.04008 -0.699928 7.27697 --1.03349 -0.69671 7.71301 --0.835924 -0.606164 7.31274 --0.681167 -0.535099 7.05376 --0.574136 -0.486239 7.01655 --0.469175 -0.438369 6.9771 --0.352132 -0.384722 6.84657 --0.235229 -0.331154 6.6739 --0.140533 -0.28804 6.64736 --0.00103226 -0.2243 6.14173 -0.0754954 -0.188408 6.21018 -0.12167 -0.167589 6.78608 -0.214389 -0.125225 6.78241 -0.31077 -0.0805927 6.62703 -0.400348 -0.0392149 6.5997 --2.57665 -1.30402 -0.972969 --2.69592 -1.35478 -0.968628 --2.82442 -1.40903 -0.965158 --2.96216 -1.46676 -0.962061 --3.11643 -1.53273 -0.963261 --3.27167 -1.59838 -0.959165 --3.4537 -1.6758 -0.962232 --3.64493 -1.75658 -0.963074 --3.86294 -1.84901 -0.968683 --4.08195 -1.942 -0.966649 --4.31123 -2.03918 -0.96034 --4.56725 -2.14787 -0.955901 --4.86851 -2.27524 -0.958372 --5.11005 -2.37754 -0.928806 --5.37007 -2.48761 -0.89634 --5.67432 -2.61628 -0.86809 --6.52298 -2.97593 -0.98238 --7.10909 -3.22399 -0.99446 --7.0592 -3.2028 -0.830409 --6.93423 -3.15037 -0.652744 --5.6023 -2.58522 -0.236285 --5.60293 -2.58528 -0.117131 --5.58303 -2.57742 0.00460885 --8.10809 -3.64686 -0.24254 --13.1397 -5.77936 -0.706729 --15.1168 -6.61729 -0.654893 --13.5987 -5.97342 -0.224643 --13.5526 -5.95368 0.0471348 --13.3265 -5.85822 0.325281 --13.4552 -5.91182 0.583834 --16.4795 -7.19313 0.815392 --16.683 -7.27911 1.13888 --40.3896 -17.3233 2.10478 --40.3562 -17.3089 2.87912 --38.8496 -16.67 3.55769 --37.974 -16.2977 4.96809 --38.2522 -16.4151 5.73914 --38.4902 -16.5145 6.51807 --33.4038 -14.3604 6.4534 --32.6761 -14.0512 6.98053 --32.8466 -14.1223 7.66263 --32.9236 -14.1555 8.33527 --31.7316 -13.6491 8.71153 --10.106 -4.49032 3.74946 --10.0427 -4.46336 3.94498 --9.92283 -4.4126 4.12306 --10.1183 -4.4954 4.39928 --10.0621 -4.47176 4.60002 --9.65367 -4.29821 4.67314 --9.44551 -4.20977 4.80847 --9.52998 -4.24454 5.05561 --9.00874 -4.02446 5.05155 --9.0101 -4.02497 5.26154 --8.8646 -3.96242 5.40534 --8.868 -3.96362 5.61928 --9.04179 -4.03724 5.92486 --6.71739 -3.05427 4.89453 --6.47458 -2.95085 4.92938 --6.32932 -2.88925 5.01335 --8.52573 -3.81879 6.52746 --10.0476 -4.46273 7.72564 --8.49958 -3.80738 6.97038 --7.15898 -3.23949 6.28209 --7.71121 -3.47314 6.88354 --7.28071 -3.29117 6.78951 --7.32922 -3.3116 7.04613 --7.09772 -3.21323 7.08671 --6.88884 -3.12497 7.13854 --7.0203 -3.17947 7.47645 --6.97954 -3.16203 7.67508 --6.52056 -2.96817 7.49157 --5.86897 -2.69293 7.10092 --6.81006 -3.0904 8.25272 --6.59294 -2.99749 8.28695 --6.52656 -2.97003 8.47622 --5.33314 -2.46441 7.42575 --5.79559 -2.65999 8.43809 --5.38204 -2.4853 8.19714 --5.0136 -2.32936 7.98842 --5.10595 -2.36843 8.36158 --4.87778 -2.27102 8.31812 --6.25955 -2.85475 10.5349 --6.16527 -2.81466 10.7498 --3.06012 -1.50312 6.40132 --2.95714 -1.45911 6.44316 --2.79796 -1.39207 6.39122 --2.72567 -1.36102 6.47805 --2.64728 -1.32781 6.55542 --5.73907 -2.63303 12.46 --2.60797 -1.31103 6.94073 --2.63979 -1.32367 7.25333 --2.56848 -1.2939 7.37388 --2.39093 -1.2185 7.27004 --2.50123 -1.26465 7.80185 --2.37164 -1.20978 7.81216 --2.26959 -1.16624 7.88377 --1.89645 -1.00954 7.25187 --1.76187 -0.951878 7.20334 --1.46443 -0.826632 6.67409 --1.49694 -0.839243 7.08722 --1.33708 -0.771696 6.9251 --1.18036 -0.70565 6.74917 --1.22386 -0.723859 7.27849 --1.10877 -0.674936 7.25233 --1.05658 -0.652482 7.48499 --0.995222 -0.627053 7.70794 --0.883104 -0.579279 7.7156 --0.626499 -0.470988 6.95705 --0.525768 -0.428377 6.94792 --0.435149 -0.390333 6.99604 --0.312308 -0.338056 6.8248 --0.195654 -0.288546 6.65093 --0.0602501 -0.231591 6.24599 -0.0310021 -0.19343 6.17616 -0.0641521 -0.178399 6.86196 -0.166544 -0.135499 6.73956 -0.25054 -0.0992815 6.94471 -0.357014 -0.0546617 6.49861 -0.443981 -0.0177748 6.68048 --2.66243 -1.23218 -0.963868 --2.79171 -1.28249 -0.962691 --2.92921 -1.33634 -0.961889 --3.07694 -1.39358 -0.961158 --3.2257 -1.45151 -0.955379 --3.40838 -1.52304 -0.961637 --3.59307 -1.59513 -0.961546 --3.78798 -1.6705 -0.959128 --4.00034 -1.75289 -0.957558 --4.23947 -1.84686 -0.959256 --4.49903 -1.94755 -0.959495 --4.76784 -2.0524 -0.953765 --5.11775 -2.18838 -0.966625 --5.3803 -2.29043 -0.937442 --5.57198 -2.36512 -0.876906 --6.00603 -2.53465 -0.879982 --6.81281 -2.84933 -0.967011 --7.47974 -3.10801 -0.988181 --8.17541 -3.37909 -0.99124 --8.17897 -3.38053 -0.82274 --7.99668 -3.30923 -0.619626 --7.99409 -3.30825 -0.455588 --11.4767 -4.66488 -0.823133 --12.836 -5.1943 -0.776011 --14.3451 -5.78223 -0.695442 --16.6904 -6.69595 -0.638496 --18.7964 -7.51656 -0.475482 --18.9573 -7.57854 -0.122 --35.1066 -13.8671 0.948708 --43.8787 -17.2838 1.76723 --40.7027 -16.0457 2.48453 --40.6724 -16.0333 3.25599 --39.5138 -15.5815 3.94464 --39.2283 -15.4703 4.6721 --38.6524 -15.2453 5.35881 --32.4307 -12.8206 6.54826 --33.5658 -13.2627 7.39498 --32.2399 -12.7459 7.78002 --33.3255 -13.1681 9.32842 --10.0752 -4.11587 3.8133 --10.1451 -4.14229 4.04441 --10.0491 -4.10479 4.2295 --9.69176 -3.96602 4.32758 --9.75153 -3.98908 4.55797 --9.38395 -3.84592 4.63585 --9.42015 -3.85978 4.85793 --9.19917 -3.77383 4.97878 --7.36034 -3.05734 4.39433 --7.27784 -3.02553 4.52932 --6.78553 -2.83364 4.46765 --7.1763 -2.98577 4.8269 --7.0702 -2.94403 4.94814 --6.76445 -2.82559 4.95793 --6.58361 -2.75481 5.02781 --8.76016 -3.60188 6.48977 --8.43579 -3.47464 6.51763 --7.49721 -3.10979 6.13941 --6.26492 -2.63015 5.52162 --5.55696 -2.35451 5.20738 --5.83588 -2.46302 5.5712 --5.43207 -2.30621 5.44302 --5.22991 -2.22762 5.45362 --5.09014 -2.17227 5.50609 --4.98629 -2.13247 5.58549 --7.10864 -2.9568 7.59106 --7.72168 -3.19548 8.38068 --6.05858 -2.54817 7.09895 --6.08343 -2.55771 7.34107 --6.81901 -2.84372 8.30098 --5.87334 -2.47609 7.58365 --5.64662 -2.38791 7.5749 --5.36368 -2.27757 7.49492 --7.01372 -2.91888 9.61961 --6.73573 -2.81048 9.59573 --5.26525 -2.23869 8.09404 --5.24499 -2.23053 8.32329 --5.04897 -2.15383 8.32881 --4.90003 -2.09648 8.39225 --5.82439 -2.45543 9.97609 --5.90805 -2.48787 10.4326 --3.03716 -1.37207 6.40192 --2.93849 -1.33348 6.45067 --2.79905 -1.27972 6.43044 --2.71977 -1.24854 6.50831 --5.88317 -2.47596 12.3573 --2.70705 -1.24305 6.93689 --2.64203 -1.21793 7.0572 --2.74004 -1.2556 7.51212 --2.45177 -1.14363 7.18893 --2.32148 -1.09275 7.18031 --2.44584 -1.14126 7.74836 --2.34297 -1.10075 7.82072 --2.26152 -1.06932 7.94653 --2.00096 -0.967483 7.60789 --1.54435 -0.790258 6.6832 --1.44175 -0.750858 6.69244 --1.43458 -0.747412 6.99249 --1.29943 -0.694767 6.90416 --1.1613 -0.641409 6.79344 --1.1864 -0.650528 7.26563 --1.18398 -0.64954 7.69209 --1.08319 -0.61006 7.76131 --0.990513 -0.57425 7.8679 --0.765502 -0.486308 7.32752 --0.592284 -0.419378 6.96741 --0.486688 -0.378084 6.93768 --0.397254 -0.344053 7.00454 --0.256642 -0.288756 6.69366 --0.147284 -0.246442 6.56795 --0.0122549 -0.194029 6.1317 -0.0708919 -0.161502 6.14049 -0.112022 -0.145451 6.79596 -0.206373 -0.108696 6.78235 -0.30551 -0.0697596 6.65696 -0.398717 -0.0336017 6.60975 --2.65593 -1.12397 -0.978557 --2.75411 -1.15821 -0.959341 --2.88519 -1.20531 -0.956209 --3.04189 -1.26136 -0.962689 --3.19955 -1.3171 -0.963973 --3.35104 -1.37073 -0.955587 --3.54465 -1.44065 -0.962957 --3.73196 -1.50641 -0.959858 --3.94598 -1.58285 -0.961775 --4.1702 -1.66251 -0.960166 --4.41387 -1.74898 -0.957701 --4.69347 -1.84958 -0.960224 --4.96676 -1.9459 -0.949881 --5.33032 -2.07591 -0.960047 --5.68661 -2.20257 -0.954603 --5.84403 -2.25843 -0.877385 --6.63993 -2.54201 -0.971123 --7.14774 -2.72247 -0.960689 --7.87787 -2.98246 -0.984407 --8.60077 -3.24048 -0.979533 --7.87272 -2.9807 -0.660026 --7.87115 -2.97984 -0.49968 --7.8573 -2.97467 -0.338421 --9.42181 -3.53083 -0.0291938 --18.893 -6.90354 -0.650503 --23.7458 -8.63036 -0.161707 --41.0286 -14.781 1.3188 --41.0168 -14.7766 2.08806 --40.9927 -14.7669 2.85688 --35.2012 -12.7053 3.2609 --35.5348 -12.8233 3.95263 --35.6308 -12.8569 4.63471 --35.3871 -12.7702 5.28224 --33.7053 -12.1707 5.72438 --35.3928 -12.7708 6.63527 --33.3716 -12.0512 6.96066 --32.6746 -11.8021 7.47142 --32.6009 -11.7757 8.09293 --33.145 -11.968 9.51641 --10.2698 -3.8301 3.93797 --10.129 -3.77988 4.11044 --10.0669 -3.75797 4.30392 --9.95681 -3.7187 4.48122 --9.03154 -3.38902 4.36794 --9.03703 -3.39082 4.56721 --9.16214 -3.43507 4.81646 --9.21159 -3.45296 5.04233 --7.32349 -2.78121 4.42473 --6.64407 -2.53942 4.28296 --6.63128 -2.53462 4.43543 --6.82907 -2.60502 4.69574 --6.69971 -2.55874 4.79528 --6.75334 -2.5778 4.99249 --6.83656 -2.60701 5.21182 --8.59665 -3.23196 6.44218 --6.02713 -2.3191 5.06586 --6.37702 -2.44303 5.45701 --5.81761 -2.24404 5.25671 --5.66792 -2.19085 5.31804 --5.61222 -2.17096 5.44287 --5.43087 -2.10612 5.4743 --5.3333 -2.07137 5.5656 --5.24287 -2.039 5.66076 --5.42307 -2.10334 5.98384 --5.20909 -2.02726 5.97847 --6.67647 -2.5479 7.48362 --6.15207 -2.36171 7.2253 --6.09009 -2.33931 7.38801 --6.02505 -2.31612 7.55027 --5.70798 -2.20368 7.45315 --5.53479 -2.14181 7.49589 --5.45343 -2.11269 7.63563 --6.96329 -2.64833 9.61487 --5.94445 -2.28668 8.70464 --5.35718 -2.07778 8.25317 --5.18914 -2.01846 8.29887 --5.06287 -1.97315 8.39528 --6.25656 -2.39659 10.3118 --6.02915 -2.31508 10.3311 --3.2097 -1.31474 6.49818 --3.0756 -1.26757 6.50023 --2.97405 -1.23116 6.54887 --2.8674 -1.19257 6.58706 --2.85857 -1.18988 6.79332 --2.69593 -1.13143 6.73407 --2.76435 -1.15541 7.09672 --2.67704 -1.12433 7.18246 --2.60603 -1.09958 7.30245 --2.37533 -1.01772 7.09063 --2.32358 -0.998825 7.25118 --2.42828 -1.03521 7.78437 --2.32766 -0.999167 7.86498 --2.1235 -0.927138 7.68545 --1.68395 -0.771547 6.84964 --1.50133 -0.706453 6.64566 --1.51249 -0.710595 6.99276 --1.41914 -0.677377 7.04802 --1.26296 -0.621347 6.8919 --1.27084 -0.62379 7.29737 --1.21282 -0.603054 7.50254 --1.16886 -0.587189 7.79445 --1.03999 -0.541183 7.74653 --0.441384 -0.329839 5.46091 --0.779376 -0.448688 7.60339 --0.561246 -0.372149 7.00684 --0.450788 -0.332177 6.95642 --0.336473 -0.291993 6.85441 --0.240133 -0.25697 6.86891 --0.0663651 -0.196563 6.17641 -0.0255825 -0.163976 6.11636 -0.0595471 -0.150988 6.78224 -0.154782 -0.116756 6.77946 -0.244276 -0.0853426 6.91483 -0.352509 -0.0468683 6.50866 -0.442105 -0.0151458 6.67055 --2.72922 -1.04462 -0.964498 --2.861 -1.08676 -0.963408 --2.99382 -1.12962 -0.95797 --3.14406 -1.17869 -0.957326 --3.30446 -1.23014 -0.956201 --3.48227 -1.28771 -0.958271 --3.67955 -1.35223 -0.962481 --3.88697 -1.41902 -0.964014 --4.1036 -1.4891 -0.962223 --4.33962 -1.56502 -0.960325 --4.59508 -1.64773 -0.957071 --4.86072 -1.73357 -0.948394 --5.20822 -1.84648 -0.958501 --5.5863 -1.96842 -0.965171 --6.00122 -2.10307 -0.969685 --6.4467 -2.24656 -0.967366 --6.96783 -2.41476 -0.968668 --7.48996 -2.58398 -0.95149 --8.21038 -2.81671 -0.959693 --7.76501 -2.6723 -0.701535 --7.76353 -2.67261 -0.544435 --7.75069 -2.66753 -0.38637 --12.1248 -4.08214 -0.885023 --7.90505 -2.71708 -0.0977205 --15.2258 -5.08539 -0.762526 --17.5083 -5.82335 -0.685001 --41.358 -13.5335 0.931292 --41.3432 -13.5284 1.69889 --41.3161 -13.519 2.46591 --37.1136 -12.16 3.00982 --36.4585 -11.9478 3.65502 --34.6061 -11.3478 4.81948 --33.9615 -11.1388 5.38931 --34.7601 -11.3968 6.14868 --33.9644 -11.1387 6.67841 --33.8928 -11.1154 7.31481 --33.8478 -11.1002 7.95787 --10.8514 -3.66747 3.51643 --10.6322 -3.59626 3.68177 --10.4753 -3.54589 3.85664 --10.5175 -3.55917 4.08313 --10.3279 -3.49745 4.24362 --10.1087 -3.42622 4.38924 --10.1958 -3.45401 4.63244 --10.3227 -3.49543 4.89609 --9.13809 -3.11288 4.66836 --9.05779 -3.08626 4.83736 --7.77449 -2.67214 4.49713 --7.65346 -2.63216 4.62106 --6.94887 -2.40438 4.47011 --6.47599 -2.25167 4.40399 --6.61526 -2.29713 4.63187 --6.58716 -2.28746 4.7798 --6.54892 -2.27562 4.92326 --6.94101 -2.40184 5.31778 --8.56703 -2.9269 6.48071 --6.45035 -2.24321 5.37221 --6.21525 -2.16709 5.39324 --5.95773 -2.08347 5.39073 --5.60748 -1.97006 5.31318 --5.43263 -1.91359 5.35007 --5.38315 -1.89729 5.47582 --5.42238 -1.91019 5.67304 --5.44834 -1.91905 5.86697 --5.31528 -1.87574 5.9313 --5.21788 -1.8439 6.02434 --6.16171 -2.14843 7.06485 --6.03876 -2.1087 7.16596 --6.1796 -2.15366 7.52318 --6.05661 -2.11361 7.63078 --5.58846 -1.96298 7.37586 --5.57448 -1.95834 7.58701 --5.46376 -1.92243 7.69739 --5.76628 -2.01925 8.28796 --6.92675 -2.39331 9.94678 --5.45925 -1.92006 8.43676 --5.15518 -1.82225 8.31211 --5.87253 -2.05291 9.54011 --6.03425 -2.10466 10.0783 --5.82666 -2.03709 10.116 --3.18993 -1.18767 6.51572 --3.02859 -1.13525 6.47489 --2.99945 -1.12583 6.63925 --2.86969 -1.08432 6.64321 --2.85473 -1.0794 6.84112 --2.76147 -1.0485 6.91031 --2.73735 -1.04108 7.10904 --2.62581 -1.00467 7.1497 --2.26766 -0.889119 6.68083 --2.18976 -0.864484 6.76664 --2.23148 -0.877359 7.12287 --2.17169 -0.85749 7.27241 --2.10786 -0.836879 7.42158 --1.75728 -0.724552 6.83826 --1.57096 -0.664601 6.63621 --1.49706 -0.640351 6.72958 --1.49194 -0.638305 7.03933 --1.332 -0.586435 6.8848 --1.22574 -0.552534 6.88878 --1.33857 -0.588241 7.68812 --1.22808 -0.552165 7.7208 --1.12066 -0.518052 7.77082 --0.494616 -0.316587 5.48121 --0.413956 -0.29095 5.46943 --0.139511 -0.203416 4.41583 --0.528276 -0.326578 7.05565 --0.4011 -0.286029 6.89587 --0.272008 -0.244191 6.68365 --0.172987 -0.212366 6.65724 --0.0234769 -0.163754 6.12176 -0.05937 -0.137748 6.16042 -0.102373 -0.122799 6.796 -0.198421 -0.0921725 6.80241 -0.298319 -0.0593216 6.71697 -0.394154 -0.0283281 6.64977 --2.70852 -0.933986 -0.973687 --2.82474 -0.967635 -0.964502 --2.96652 -1.0093 -0.965977 --3.11028 -1.05062 -0.962951 --3.27139 -1.09712 -0.964268 --3.42433 -1.14163 -0.955922 --3.60488 -1.19488 -0.954985 --3.8129 -1.25479 -0.960257 --4.04956 -1.32423 -0.969888 --4.2688 -1.38794 -0.964191 --4.52579 -1.46274 -0.965123 --4.80216 -1.54329 -0.964049 --5.07129 -1.62064 -0.950362 --5.45993 -1.73439 -0.966682 --5.85154 -1.84829 -0.969459 --6.28086 -1.97281 -0.969277 --6.77752 -2.11747 -0.971792 --7.37823 -2.29236 -0.982585 --7.98192 -2.46802 -0.972096 --8.88863 -2.73183 -1.00445 --9.66667 -2.95839 -0.978758 --10.7966 -3.28676 -0.987024 --9.62254 -2.94483 -0.591721 --9.49544 -2.9082 -0.386356 --14.7254 -4.42993 -0.831189 --39.4888 -11.6305 4.94336 --35.0945 -10.3511 6.47983 --10.7774 -3.27804 4.23697 --10.0119 -3.05477 4.43239 --9.76064 -2.98153 4.55649 --10.1979 -3.10832 4.92519 --7.58375 -2.34872 4.13217 --9.32673 -2.8547 5.01223 --9.63155 -2.94286 5.35027 --9.48627 -2.90097 5.50189 --9.51406 -2.9089 5.73234 --7.15228 -2.22297 4.78512 --6.89002 -2.14574 4.82124 --6.9872 -2.17401 5.0424 --7.04469 -2.19135 5.24927 --6.9637 -2.16764 5.38076 --6.99767 -2.17668 5.58147 --7.76337 -2.39893 6.25377 --5.76926 -1.82026 5.14369 --5.52248 -1.74829 5.13582 --5.23808 -1.66533 5.09202 --5.77982 -1.82266 5.6476 --5.70806 -1.80201 5.76688 --5.65051 -1.78497 5.89715 --5.59704 -1.76941 6.03302 --5.14897 -1.63896 5.83188 --5.70261 -1.80012 6.49776 --5.31457 -1.68704 6.3384 --5.74196 -1.81109 6.93558 --6.38773 -1.99776 7.78331 --5.65615 -1.78523 7.2776 --5.64423 -1.7815 7.4882 --5.61401 -1.77251 7.68572 --5.54009 -1.75125 7.84 --5.648 -1.78249 8.21047 --5.67659 -1.79028 8.50329 --6.02101 -1.88994 9.20769 --5.68497 -1.79285 9.06696 --5.56011 -1.75597 9.19393 --5.46775 -1.72888 9.36694 --5.77936 -1.81944 10.1328 --3.0952 -1.04139 6.42581 --3.00926 -1.01588 6.49862 --2.99942 -1.01267 6.69624 --3.10013 -1.04212 7.0912 --2.75254 -0.940879 6.72522 --2.75583 -0.941753 6.96598 --2.71548 -0.929606 7.13835 --2.29622 -0.808815 6.5666 --2.25384 -0.795538 6.72378 --2.18618 -0.775991 6.83604 --2.2005 -0.780154 7.13851 --2.09733 -0.74989 7.18664 --0.941217 -0.415581 4.60155 --1.70095 -0.635343 6.78436 --1.53623 -0.587458 6.6362 --1.61905 -0.611079 7.19046 --1.42002 -0.553593 6.93408 --1.29066 -0.515306 6.87272 --1.52137 -0.582066 8.05439 --1.28912 -0.515083 7.66618 --1.20397 -0.4893 7.80405 --0.547669 -0.300354 5.50116 --0.262197 -0.217748 4.54345 --0.826926 -0.379796 7.72083 --0.581512 -0.309746 7.00669 --0.460498 -0.274348 6.89726 --0.332578 -0.236923 6.71591 --0.226747 -0.206426 6.65087 --0.0803368 -0.16415 6.20614 -0.0133054 -0.136674 6.14623 -0.0520751 -0.124957 6.77219 -0.150876 -0.0964377 6.73953 -0.240129 -0.0700399 6.89477 -0.347258 -0.0395751 6.60866 -0.440479 -0.0120689 6.73048 --2.79286 -0.854467 -0.96968 --2.90988 -0.884966 -0.958642 --3.0626 -0.925099 -0.962829 --3.20709 -0.962247 -0.957501 --3.37914 -1.00718 -0.960731 --3.54295 -1.04912 -0.954146 --3.74349 -1.10142 -0.958539 --3.95319 -1.15605 -0.960257 --4.17408 -1.21384 -0.958646 --4.43261 -1.28074 -0.964062 --4.70128 -1.34978 -0.964205 --4.99851 -1.42716 -0.965061 --5.3344 -1.51435 -0.968098 --5.70083 -1.60959 -0.968347 --6.09573 -1.71193 -0.964466 --6.54769 -1.82996 -0.962362 --7.10546 -1.97426 -0.971425 --7.77014 -2.14647 -0.98576 --8.49285 -2.3347 -0.989335 --9.18994 -2.5149 -0.961626 --9.63137 -2.62973 -0.861924 --11.3813 -3.08376 -0.963491 --13.0711 -3.52278 -0.99248 --9.40447 -2.56999 -0.272238 --10.3843 -2.82192 4.20474 --9.8843 -2.69185 4.26091 --9.61522 -2.6221 4.37686 --9.67555 -2.63742 4.60077 --9.9961 -2.72021 4.92672 --7.58628 -2.09588 4.1911 --7.58467 -2.09467 4.35874 --7.60749 -2.10038 4.53898 --7.4667 -2.06434 4.64807 --9.37868 -2.55967 5.73871 --7.63426 -2.1079 5.08159 --7.16728 -1.98674 5.01936 --6.90149 -1.91705 5.04932 --6.95073 -1.93019 5.24982 --6.26546 -1.75233 5.01945 --7.25123 -2.00741 5.79305 --7.11148 -1.97166 5.89505 --5.44318 -1.53854 4.97209 --5.41528 -1.53154 5.10654 --5.52745 -1.5601 5.34413 --5.64168 -1.58999 5.59281 --5.52433 -1.559 5.67276 --5.42127 -1.53269 5.76224 --5.31716 -1.50556 5.84937 --5.53889 -1.56319 6.21653 --5.43573 -1.53561 6.31145 --5.31639 -1.50477 6.3909 --6.30199 -1.75977 7.52974 --5.57687 -1.57208 7.04102 --5.48081 -1.54705 7.15674 --5.6657 -1.59446 7.57243 --5.33538 -1.50958 7.44155 --5.8487 -1.64162 8.25802 --6.16422 -1.72348 8.89138 --6.03654 -1.6898 9.01789 --5.80247 -1.62908 9.01035 --5.6779 -1.59714 9.13846 --5.56242 -1.56697 9.28044 --5.86736 -1.64526 10.0187 --5.88045 -1.6487 10.3776 --4.86958 -1.38757 9.19102 --4.70346 -1.34379 9.2445 --6.16326 -1.7209 11.9717 --4.76708 -1.35969 10.0179 --2.87156 -0.869612 7.00539 --2.81614 -0.855615 7.15254 --3.04487 -0.914198 7.8553 --2.23601 -0.705411 6.52048 --2.80229 -0.85138 7.96094 --2.37278 -0.740118 7.33103 --2.23744 -0.704809 7.31794 --1.00245 -0.386181 4.63432 --0.926136 -0.366244 4.62366 --0.846837 -0.346024 4.60214 --2.03728 -0.65313 8.157 --1.55817 -0.529304 7.13378 --1.36957 -0.479912 6.9037 --1.59392 -0.537962 8.02613 --1.45657 -0.501643 7.99546 --1.27007 -0.45395 7.76898 --0.58251 -0.277069 5.44296 --0.278359 -0.198406 4.44878 --0.248362 -0.190741 4.5991 --0.791642 -0.330265 7.79156 --0.588643 -0.277596 7.30181 --0.384048 -0.22515 6.68841 --0.277334 -0.196668 6.62427 --0.182606 -0.172161 6.64721 --0.0326407 -0.13362 6.13165 -0.0489682 -0.112565 6.19028 -0.0967156 -0.0993755 6.77606 -0.192525 -0.0747782 6.82231 -0.293122 -0.0485002 6.76693 -0.392523 -0.022715 6.65981 --2.86775 -0.768203 -0.959756 --2.99471 -0.797253 -0.951832 --3.13898 -0.830536 -0.9492 --3.329 -0.873979 -0.964407 --3.47626 -0.907586 -0.951728 --3.66827 -0.951328 -0.955193 --3.85311 -0.992987 -0.948393 --4.10105 -1.04992 -0.962376 --4.33368 -1.10299 -0.960725 --4.58557 -1.15988 -0.958367 --4.87509 -1.22578 -0.960938 --5.20329 -1.30152 -0.96649 --5.55172 -1.3808 -0.966937 --5.93975 -1.46869 -0.966814 --6.34711 -1.56205 -0.958793 --6.86113 -1.67873 -0.964482 --7.48088 -1.82052 -0.978193 --8.1412 -1.97125 -0.978896 --8.99462 -2.16635 -0.996845 --9.89054 -2.36978 -0.992093 --10.9898 -2.62128 -0.990724 --12.2555 -2.91022 -0.976067 --13.7467 -3.25001 -0.946997 --15.569 -3.66542 -0.904143 --17.5791 -4.12336 -0.815179 --58.2357 -13.3961 2.47958 --10.1641 -2.4292 4.22065 --9.92188 -2.37415 4.35121 --9.80754 -2.34768 4.5182 --10.087 -2.41184 4.82516 --10.0294 -2.39873 5.0175 --9.86843 -2.36182 5.16878 --7.66835 -1.86019 4.45412 --9.43388 -2.26272 5.41021 --9.57107 -2.29286 5.68648 --9.5684 -2.29321 5.90465 --9.27451 -2.22511 5.97728 --7.7861 -1.88602 5.40579 --8.03495 -1.94294 5.73413 --6.48398 -1.58981 5.03681 --6.27155 -1.54156 5.07507 --6.25071 -1.53628 5.22687 --7.38045 -1.7933 6.12951 --7.23484 -1.75993 6.2312 --6.57337 -1.60937 5.96758 --6.62241 -1.62034 6.1919 --5.88201 -1.45154 5.82596 --5.63624 -1.39587 5.81189 --5.66808 -1.40295 6.01408 --6.31989 -1.5509 6.74579 --5.63446 -1.39507 6.35491 --5.76955 -1.42547 6.66883 --5.86716 -1.44812 6.9623 --6.84773 -1.67105 8.12667 --6.48844 -1.58877 8.01907 --5.66352 -1.40107 7.40968 --5.41176 -1.34418 7.36688 --5.47475 -1.35775 7.6631 --6.66817 -1.62861 9.27959 --6.06309 -1.4908 8.85225 --5.88512 -1.45031 8.91463 --5.7183 -1.41257 8.98853 --1.23957 -0.394325 3.31446 --5.49588 -1.36145 9.2784 --5.88112 -1.44879 10.1406 --4.92266 -1.2314 9.05989 --4.79525 -1.20141 9.17227 --6.12111 -1.50239 11.6163 --6.09252 -1.49663 11.9888 --5.58701 -1.38127 11.554 --2.82952 -0.754596 7.00937 --2.97414 -0.788026 7.53335 --3.01658 -0.796538 7.89578 --2.70682 -0.726407 7.56421 --2.62414 -0.707407 7.68371 --2.3468 -0.644222 7.3748 --1.05539 -0.351207 4.64804 --0.986306 -0.335882 4.65687 --0.90912 -0.318029 4.6457 --1.55997 -0.465593 6.61732 --2.00381 -0.566365 8.20778 --1.44618 -0.439139 6.92459 --1.34452 -0.416512 6.95849 --1.53512 -0.458719 7.99673 --0.584981 -0.24382 4.97876 --1.22499 -0.388692 7.7846 --0.315487 -0.182996 4.45135 --0.257535 -0.169752 4.46536 --0.194539 -0.154828 4.45873 --0.78331 -0.287363 8.01908 --0.468151 -0.216671 6.85772 --0.337721 -0.186909 6.66651 --0.227265 -0.161187 6.57155 --0.0883222 -0.130058 6.19619 --0.00190135 -0.110734 6.22585 -0.0963535 -0.0876134 6.12428 -0.144165 -0.0764915 6.76943 -0.24172 -0.0545345 6.78486 -0.342941 -0.0318216 6.67869 -0.439536 -0.00898449 6.69049 --2.82092 -0.656682 -0.959739 --2.94766 -0.681838 -0.953911 --3.09363 -0.710114 -0.953518 --3.25691 -0.742584 -0.957616 --3.42221 -0.775674 -0.956466 --3.5976 -0.810109 -0.954285 --3.78215 -0.846921 -0.950529 --4.00524 -0.890917 -0.956493 --4.23741 -0.936189 -0.958834 --4.48991 -0.98623 -0.960715 --4.7444 -1.03673 -0.95405 --5.06384 -1.10007 -0.961869 --5.3954 -1.16532 -0.962111 --5.77461 -1.23989 -0.965703 --6.17517 -1.31982 -0.961891 --6.6436 -1.41193 -0.962666 --7.18 -1.51804 -0.964433 --7.81476 -1.64349 -0.970247 --8.53775 -1.78652 -0.972946 --9.39861 -1.95641 -0.977374 --10.1843 -2.11161 -0.937735 --11.4264 -2.35692 -0.945 --13.1574 -2.6994 -0.978896 --14.9318 -3.05052 -0.956731 --15.8215 -3.2255 -0.775402 --15.8591 -3.2329 -0.485748 --15.7841 -3.21859 -0.187347 --55.3511 -11.0388 -0.0870047 --23.4084 -4.7239 2.23751 --9.54088 -1.98243 3.91662 --9.53618 -1.98116 4.10937 --9.59327 -1.99211 4.32422 --9.25634 -1.92514 4.40605 --8.93871 -1.86223 4.48369 --9.05153 -1.88485 4.71889 --8.76837 -1.82878 4.79868 --9.7408 -2.02049 5.41047 --11.3591 -2.34007 6.35786 --9.71712 -2.01585 5.83522 --8.06223 -1.68908 5.23858 --8.07578 -1.69151 5.43543 --7.9729 -1.67082 5.57325 --7.59277 -1.59644 5.55401 --6.7562 -1.4312 5.25354 --6.39638 -1.35994 5.20736 --6.26527 -1.33354 5.29235 --6.21516 -1.3238 5.42823 --6.54541 -1.3884 5.82584 --6.81592 -1.44163 6.2022 --6.3763 -1.35522 6.07347 --6.0217 -1.28545 5.99085 --5.94218 -1.26918 6.1122 --5.89207 -1.25997 6.25742 --4.4465 -0.974777 5.21557 --6.4651 -1.37261 7.1494 --6.13177 -1.30665 7.06529 --6.78205 -1.43466 7.89714 --6.74787 -1.42721 8.10872 --6.33269 -1.34532 7.94012 --5.74884 -1.23036 7.5722 --6.53414 -1.3846 8.66078 --6.28984 -1.33728 8.65854 --6.22227 -1.32365 8.85349 --6.02947 -1.28569 8.903 --5.875 -1.25435 8.99461 --1.27589 -0.348383 3.30671 --1.23628 -0.341198 3.33795 --5.70452 -1.221 9.67105 --1.1156 -0.317249 3.34083 --3.74281 -0.834205 7.38548 --6.22069 -1.32129 11.5063 --6.2224 -1.32165 11.9208 --5.86706 -1.252 11.7561 --1.28837 -0.350277 4.14141 --2.57512 -0.603343 6.62818 --2.33955 -0.556838 6.41727 --2.55039 -0.59881 7.07235 --2.43268 -0.575521 7.09871 --2.49819 -0.587682 7.52113 --2.48615 -0.585499 7.8017 --1.00703 -0.294456 4.59739 --0.949126 -0.283148 4.63292 --0.858081 -0.266029 4.58345 --0.773041 -0.249185 4.54134 --1.79376 -0.448441 7.74791 --1.35784 -0.362914 6.78963 --0.693608 -0.232752 4.94835 --0.62863 -0.220129 4.97856 --0.598669 -0.213778 5.14277 --0.603714 -0.215161 5.47207 --0.293664 -0.154387 4.46823 --0.23877 -0.143016 4.50137 --0.172903 -0.129778 4.48449 --0.658567 -0.224615 7.61682 --0.403857 -0.174356 6.73779 --0.287648 -0.151913 6.62423 --0.160664 -0.127128 6.38923 --0.0378143 -0.102201 6.11171 -0.0503522 -0.0855175 6.11054 -0.0939898 -0.0761164 6.73618 -0.194298 -0.056272 6.71245 -0.289858 -0.0372789 6.78692 -0.390829 -0.0175994 6.65977 --2.89766 -0.567548 -0.954851 --3.0262 -0.589493 -0.947168 --3.17291 -0.613608 -0.944673 --3.35614 -0.644207 -0.955549 --3.52211 -0.672113 -0.951846 --3.70832 -0.702961 -0.951177 --3.91274 -0.736822 -0.952551 --4.14557 -0.776225 -0.958681 --4.38035 -0.815133 -0.957215 --4.63539 -0.857792 -0.954938 --4.90963 -0.903226 -0.951105 --5.22336 -0.955477 -0.950796 --5.61307 -1.02087 -0.964088 --6.00476 -1.08648 -0.96414 --6.42778 -1.15697 -0.959053 --6.93784 -1.24167 -0.96224 --7.49751 -1.33513 -0.959682 --8.19388 -1.45198 -0.968342 --8.99949 -1.58621 -0.97507 --9.8952 -1.73649 -0.970238 --11.056 -1.92963 -0.979477 --12.2391 -2.12758 -0.951096 --14.0892 -2.43611 -0.971314 --16.1295 -2.77715 -0.948305 --16.0617 -2.76612 -0.644091 --18.9245 -3.24299 -0.236544 --10.0482 -1.75872 3.94656 --9.59765 -1.68427 4.0141 --9.63844 -1.69052 4.22222 --9.77834 -1.71402 4.46744 --9.16811 -1.61219 4.45264 --9.0431 -1.59041 4.59878 --8.87773 -1.56294 4.72687 --9.01355 -1.58548 4.97602 --8.75323 -1.54285 5.06032 --8.7364 -1.53955 5.24818 --9.49056 -1.66468 5.80989 --10.5013 -1.83329 6.53733 --10.4045 -1.81746 6.73109 --10.4078 -1.81793 6.98014 --7.69961 -1.36583 5.68457 --7.83938 -1.38881 5.96051 --6.17016 -1.11075 5.12769 --6.02318 -1.0861 5.19675 --5.99943 -1.0822 5.3446 --6.50076 -1.16572 5.86004 --5.29053 -0.964076 5.17199 --6.8297 -1.22043 6.47852 --6.35052 -1.14041 6.30972 --6.13387 -1.1043 6.33073 --4.78374 -0.879045 5.39986 --4.47442 -0.827875 5.2917 --4.44463 -0.82236 5.4187 --6.53084 -1.17025 7.50828 --6.73991 -1.20433 7.94088 --6.67659 -1.19404 8.12391 --2.87499 -0.561164 4.46858 --6.66484 -1.19182 8.62685 --5.77751 -1.04381 7.92051 --6.27986 -1.12716 8.74093 --5.98559 -1.07825 8.66992 --6.17318 -1.10895 9.17641 --1.32315 -0.302023 3.31423 --1.24129 -0.289081 3.29065 --1.19563 -0.280698 3.31299 --1.17827 -0.278657 3.37516 --1.08732 -0.263305 3.33038 --3.67821 -0.693288 7.37293 --3.56163 -0.674053 7.43744 --1.07329 -0.260269 3.59017 --1.34473 -0.305833 4.15989 --1.19233 -0.279956 4.0181 --1.11247 -0.266879 3.99483 --1.04167 -0.255474 3.98743 --0.967829 -0.242769 3.96952 --2.48119 -0.494138 7.30485 --1.07849 -0.261256 4.49236 --1.02269 -0.251776 4.5289 --0.957858 -0.240796 4.54608 --0.783648 -0.212231 4.28307 --0.828207 -0.219022 4.57664 --1.91062 -0.398743 7.85912 --0.794776 -0.213182 4.89624 --0.730907 -0.202419 4.92806 --0.67104 -0.192521 4.97796 --0.600195 -0.181236 4.98838 --0.613232 -0.1827 5.32655 --0.576221 -0.176264 5.50102 --0.310716 -0.132281 4.67029 --0.206092 -0.115038 4.47836 --0.777895 -0.208808 7.91094 --0.571064 -0.174987 7.40988 --0.34873 -0.137612 6.67626 --0.258469 -0.123356 6.7499 --0.0844566 -0.0946118 6.10681 --0.00713354 -0.0813304 6.22583 -0.0936292 -0.0648586 6.09444 -0.134586 -0.0568964 6.84932 -0.248986 -0.0388097 6.56517 -0.337813 -0.023548 6.79856 -0.43872 -0.00592333 6.69054 --2.87031 -0.462616 -0.969808 --2.99048 -0.478886 -0.958852 --3.12884 -0.497355 -0.953683 --3.28543 -0.518969 -0.953252 --3.45212 -0.541949 -0.952191 --3.63804 -0.567945 -0.954467 --3.83399 -0.59424 -0.954764 --4.04009 -0.622813 -0.952683 --4.28459 -0.656501 -0.958923 --4.53005 -0.689739 -0.95727 --4.79576 -0.726699 -0.954207 --5.10085 -0.768522 -0.955568 --5.45343 -0.816766 -0.962225 --5.82725 -0.868446 -0.962875 --6.2414 -0.924641 -0.962152 --6.7233 -0.99099 -0.965517 --7.24658 -1.06253 -0.962162 --7.8588 -1.14688 -0.961431 --8.61751 -1.25099 -0.971036 --9.5055 -1.37231 -0.979595 --10.4844 -1.50645 -0.973143 --11.7007 -1.67359 -0.970606 --12.92 -1.84146 -0.925764 --15.0354 -2.1312 -0.951077 --16.6434 -2.35189 -0.847063 --16.4454 -2.32475 -0.524423 --16.3999 -2.31841 -0.220641 --10.2727 -1.47593 3.89425 --10.2306 -1.46993 4.08623 --10.1946 -1.46445 4.28058 --10.8156 -1.55004 4.68973 --9.87844 -1.42117 4.58718 --9.56294 -1.37756 4.6775 --9.16475 -1.32298 4.72571 --9.25497 -1.33604 4.9588 --8.79227 -1.27252 4.96262 --8.72302 -1.26258 5.12571 --10.2314 -1.46864 6.02857 --12.4779 -1.77626 7.36132 --10.2107 -1.46626 6.48499 --10.0264 -1.4403 6.62595 --12.0697 -1.72081 8.00426 --6.39886 -0.943595 5.00401 --7.00832 -1.0268 5.53582 --5.83524 -0.866475 4.98031 --5.84079 -0.867222 5.14018 --6.26164 -0.924971 5.58587 --5.43357 -0.811707 5.17788 --5.23245 -0.783238 5.18785 --6.68818 -0.982793 6.44701 --6.60792 -0.971752 6.58504 --4.85308 -0.731437 5.35917 --4.8828 -0.735571 5.54258 --4.52669 -0.68721 5.39442 --4.58964 -0.695803 5.6092 --6.75954 -0.992068 7.80838 --6.89775 -1.01115 8.18484 --2.94765 -0.470598 4.46687 --2.83851 -0.455634 4.47677 --5.71629 -0.848624 7.70405 --5.48002 -0.817001 7.67891 --5.44801 -0.811894 7.88111 --4.03938 -0.619557 6.43967 --3.87572 -0.596657 6.43333 --1.29967 -0.245251 3.31448 --1.21088 -0.23317 3.282 --1.20659 -0.23255 3.36024 --1.16505 -0.226562 3.38993 --1.09641 -0.217287 3.37743 --1.05489 -0.211397 3.40512 --1.03949 -0.20888 3.47449 --0.990976 -0.202885 3.49261 --1.25581 -0.238184 4.05488 --1.18812 -0.229023 4.05911 --1.12549 -0.221193 4.07076 --1.02266 -0.206802 4.00093 --0.813476 -0.178026 3.70395 --0.716789 -0.165067 3.61801 --1.0754 -0.213353 4.55176 --1.00668 -0.204025 4.56058 --0.784626 -0.173758 4.18816 --0.882256 -0.186946 4.61144 --2.01108 -0.340398 7.92204 --0.843946 -0.182294 4.91304 --0.776139 -0.172211 4.93596 --0.708399 -0.16318 4.95782 --0.658642 -0.156797 5.04581 --0.56789 -0.144075 4.98825 --0.59784 -0.147676 5.40413 --1.08987 -0.214229 7.8869 --0.254136 -0.101026 4.54044 --0.797598 -0.173759 7.66383 --0.449251 -0.126882 6.36637 --0.424542 -0.123045 6.81669 --0.312624 -0.1079 6.75287 --0.15849 -0.0875794 6.31979 --0.0576438 -0.0730181 6.25096 -0.0819832 -0.0545603 5.70222 -0.102986 -0.0509854 6.56658 -0.200873 -0.0380234 6.5427 -0.28753 -0.0261015 6.78698 -0.390194 -0.0115425 6.65978 --2.93468 -0.367959 -0.959863 --3.0728 -0.382533 -0.956789 --3.22103 -0.398522 -0.954084 --3.38744 -0.416635 -0.955668 --3.55481 -0.434426 -0.951955 --3.75141 -0.454822 -0.955442 --3.95717 -0.477561 -0.956655 --4.18401 -0.501078 -0.9588 --4.42907 -0.52751 -0.96099 --4.68619 -0.554994 -0.958648 --4.97258 -0.585804 -0.957863 --5.25084 -0.615474 -0.94447 --5.66234 -0.65981 -0.964273 --6.05762 -0.702139 -0.96435 --6.48312 -0.747398 -0.959191 --7.00748 -0.803276 -0.964912 --7.59137 -0.866406 -0.966904 --8.26395 -0.938203 -0.968523 --9.0283 -1.02026 -0.965163 --9.97919 -1.12158 -0.970616 --11.0904 -1.24098 -0.969781 --12.4699 -1.38842 -0.970914 --14.1186 -1.56512 -0.95973 --16.2734 -1.79558 -0.949979 --18.6994 -2.05537 -0.891351 --19.2349 -2.11261 -0.594963 --19.3588 -2.12633 -0.254604 --11.657 -1.29952 4.36858 --11.1012 -1.23954 4.43458 --10.4226 -1.16776 4.44327 --10.0411 -1.12645 4.52709 --7.98066 -0.905778 4.00397 --7.88042 -0.895295 4.13489 --7.81542 -0.888106 4.27781 --8.09783 -0.918001 4.56418 --8.93807 -1.00774 5.10775 --8.65654 -0.978137 5.17775 --8.58951 -0.970238 5.94289 --6.36242 -0.732844 4.88906 --5.8486 -0.677716 4.7458 --6.23254 -0.718546 5.13276 --5.88279 -0.680435 5.07335 --6.1842 -0.713591 5.43248 --5.51557 -0.642016 5.14228 --5.51603 -0.641204 5.29933 --7.51341 -0.855217 6.94132 --5.9787 -0.690689 5.98157 --5.16746 -0.604305 5.51684 --4.7194 -0.556347 5.31086 --4.68871 -0.552753 5.44065 --4.59574 -0.5435 5.51782 --4.59015 -0.542098 5.67391 --6.47354 -0.7433 7.63144 --2.97575 -0.369806 4.42232 --2.90199 -0.361934 4.46853 --2.78604 -0.34982 4.46972 --5.73382 -0.664394 7.81733 --4.21589 -0.501496 6.34022 --4.03849 -0.482951 6.32349 --4.00877 -0.480009 6.47936 --1.25737 -0.186667 3.21261 --1.24908 -0.185691 3.2827 --1.22172 -0.183033 3.32906 --1.12807 -0.172789 3.28572 --1.11672 -0.171032 3.35505 --1.11443 -0.170894 3.44133 --1.08203 -0.167615 3.48613 --1.03858 -0.162863 3.51346 --0.990131 -0.157875 3.53144 --0.970738 -0.155604 3.60069 --1.1017 -0.169407 3.95091 --1.03115 -0.16202 3.9431 --0.975655 -0.156482 3.96051 --0.769848 -0.133634 3.66125 --0.727431 -0.129641 3.69223 --0.835138 -0.141436 4.07074 --0.762565 -0.132935 4.04744 --0.735078 -0.130281 4.13425 --0.841516 -0.14152 4.58602 --1.95007 -0.25914 7.91565 --0.821191 -0.139018 4.94361 --0.737589 -0.130273 4.91843 --0.680899 -0.123719 4.97793 --0.611295 -0.116896 4.99799 --0.542637 -0.109074 5.01681 --0.586443 -0.113978 5.51073 --0.51074 -0.106116 5.53891 --0.215589 -0.0743726 4.49794 --0.492074 -0.103602 6.31853 --0.436852 -0.0978511 6.56191 --0.364666 -0.089563 6.73567 --0.265787 -0.0792913 6.75978 --0.10311 -0.0614848 6.22594 --0.013302 -0.0518876 6.24564 -0.082297 -0.0421683 6.19411 -0.145271 -0.0348588 6.63971 -0.248769 -0.0237372 6.52508 -0.339105 -0.0145598 6.71861 -0.438841 -0.00392449 6.69054 --3.01301 -0.271902 -0.958911 --3.14287 -0.282622 -0.94897 --3.30998 -0.295813 -0.953295 --3.47707 -0.308743 -0.952327 --3.66426 -0.322625 -0.954591 --3.87061 -0.338463 -0.958944 --4.07798 -0.354917 -0.956753 --4.31456 -0.373842 -0.959064 --4.57123 -0.393538 -0.960914 --4.83896 -0.414321 -0.957735 --5.14496 -0.438028 -0.958982 --5.48214 -0.463815 -0.959234 --5.83943 -0.491137 -0.954279 --6.26525 -0.524717 -0.956702 --6.74034 -0.561277 -0.957873 --7.25673 -0.602042 -0.952574 --7.91099 -0.652242 -0.961579 --8.65586 -0.709839 -0.967156 --9.47119 -0.773609 -0.960579 --10.4757 -0.851289 -0.959257 --11.6796 -0.944869 -0.955019 --13.1723 -1.06009 -0.950134 --15.0253 -1.20433 -0.937788 --17.3263 -1.38289 -0.909069 --27.8974 -2.20186 -0.0423784 --11.6125 -0.9378 4.23342 --11.5736 -0.934386 4.45038 --11.3788 -0.919644 4.62046 --10.7827 -0.872652 4.65561 --8.17089 -0.670897 3.97794 --8.14518 -0.66844 4.13935 --8.02402 -0.659472 4.26522 --7.44846 -0.614974 4.20511 --7.44589 -0.614107 4.36695 --10.7774 -0.872721 6.01286 --3.83339 -0.33504 3.11078 --8.82047 -0.72049 5.74266 --6.60409 -0.548503 4.77253 --6.31021 -0.526227 4.77061 --5.91485 -0.495452 4.69977 --5.79884 -0.4864 4.78071 --5.79938 -0.486842 4.93262 --6.41662 -0.534315 5.48765 --5.60048 -0.470905 5.11153 --5.52865 -0.464951 5.21773 --5.35748 -0.452513 5.2522 --5.33787 -0.45056 5.39606 --5.44175 -0.458295 5.63888 --5.48439 -0.461646 5.84256 --4.97887 -0.422299 5.5937 --4.06893 -0.351851 4.96865 --3.9912 -0.34591 5.04137 --3.77501 -0.329764 4.98317 --6.54206 -0.543396 7.79632 --3.00451 -0.269818 4.50207 --2.8045 -0.254923 4.4192 --2.78503 -0.25308 4.52031 --2.69035 -0.245774 4.54019 --4.20121 -0.361793 6.40402 --4.0422 -0.350088 6.40897 --4.01047 -0.347247 6.56523 --3.8023 -0.330888 6.50156 --3.62128 -0.317587 6.46445 --2.37999 -0.221588 4.96001 --1.14109 -0.126135 3.34077 --2.25178 -0.211582 5.07497 --3.0736 -0.274855 6.4964 --1.06507 -0.11981 3.49989 --1.00568 -0.115307 3.5012 --1.0224 -0.116877 3.63094 --1.18016 -0.128932 4.02409 --0.948628 -0.110997 3.7178 --0.882209 -0.10551 3.70711 --0.835843 -0.102114 3.73089 --0.796418 -0.0984436 3.77191 --0.703101 -0.0919176 3.69372 --0.6517 -0.0874356 3.7051 --0.758157 -0.0962475 4.10478 --0.707694 -0.0917462 4.13558 --2.10299 -0.198197 8.12856 --0.86213 -0.103559 4.94131 --0.784636 -0.0974686 4.93603 --0.710149 -0.0918048 4.93869 --0.654583 -0.0877374 5.00733 --0.615876 -0.0843508 5.1427 --0.628789 -0.0848188 5.50104 --1.07444 -0.119181 7.77969 --0.252531 -0.0564413 4.5111 --0.528789 -0.0776687 6.2508 --0.45291 -0.0709787 6.35653 --0.421458 -0.0690021 6.75743 --0.309904 -0.0598639 6.69342 --0.20435 -0.051994 6.65713 --0.0548955 -0.0410427 6.1913 -0.111501 -0.0280271 5.34358 -0.189937 -0.0214076 5.30973 -0.196975 -0.0212543 6.57264 -0.287195 -0.0140364 6.76697 -0.390494 -0.00553436 6.63975 --3.24686 -0.179529 -0.95872 --3.41365 -0.187583 -0.960197 --3.56427 -0.193915 -0.947741 --3.77935 -0.204588 -0.959704 --3.96923 -0.213833 -0.952669 --4.20536 -0.224955 -0.958873 --4.4425 -0.23664 -0.957433 --4.70972 -0.248652 -0.958796 --4.979 -0.262104 -0.951263 --5.30555 -0.277632 -0.954189 --5.67127 -0.294864 -0.95829 --6.0591 -0.313447 -0.95588 --6.47708 -0.333977 -0.948583 --6.9935 -0.358143 -0.952413 --7.57022 -0.385522 -0.95291 --8.26554 -0.419102 -0.959977 --9.04222 -0.456414 -0.959349 --9.98771 -0.501816 -0.963388 --10.9662 -0.547876 -0.940058 --12.3408 -0.614437 -0.942707 --14.0368 -0.695431 -0.940258 --16.1125 -0.794861 -0.92264 --18.9267 -0.928945 -0.905362 --8.96869 -0.451469 3.79061 --8.86173 -0.446607 3.93769 --9.28268 -0.466419 4.25856 --8.22626 -0.415886 4.07683 --7.97484 -0.404087 4.1556 --7.3973 -0.376596 4.09882 --7.42585 -0.377365 4.27064 --3.92964 -0.210363 2.91909 --3.84105 -0.206092 2.9714 --3.88693 -0.208681 3.08555 --6.60612 -0.337689 4.53135 --6.64077 -0.339976 4.7056 --6.64524 -0.339668 4.86781 --6.70694 -0.343158 5.0657 --6.64418 -0.33947 5.196 --6.41602 -0.328675 5.2263 --5.7427 -0.29702 4.96606 --5.66396 -0.292648 5.06899 --5.66646 -0.292673 5.2269 --5.65696 -0.292643 5.38033 --7.34042 -0.372821 6.78679 --5.39727 -0.27963 5.51375 --5.27149 -0.273965 5.57878 --5.15975 -0.268975 5.65354 --4.05098 -0.216077 4.87664 --3.58563 -0.19349 4.60502 --3.2787 -0.179446 4.45335 --3.27626 -0.178624 4.57374 --6.21755 -0.318734 7.58479 --5.96842 -0.306638 7.56584 --5.88759 -0.303151 7.71405 --2.5717 -0.145396 4.34277 --2.5463 -0.144437 4.43328 --2.72003 -0.151848 4.75922 --3.24606 -0.176984 5.53145 --3.7579 -0.201236 6.3387 --3.40211 -0.184848 6.07157 --2.4081 -0.137692 4.9186 --2.35161 -0.13479 4.98509 --2.29813 -0.132344 5.05893 --2.26559 -0.130019 5.16544 --2.99988 -0.16493 6.47681 --2.85727 -0.158306 6.46048 --1.00184 -0.0704785 3.54001 --1.06147 -0.0735669 3.74849 --0.960181 -0.0681076 3.67871 --0.913868 -0.0656491 3.70374 --0.870559 -0.0636071 3.73691 --0.814324 -0.061712 3.74248 --0.77896 -0.0593704 3.7922 --0.689765 -0.0551846 3.72246 --0.676392 -0.054864 3.82589 --0.807456 -0.0604192 4.30156 --0.686367 -0.0549383 4.15536 --1.8907 -0.112076 7.7177 --0.824514 -0.061053 4.93408 --0.752141 -0.0577616 4.94698 --0.700687 -0.0559505 5.02578 --0.622337 -0.0520822 5.01719 --0.673013 -0.054079 5.5007 --1.13199 -0.0752384 7.74624 --0.290292 -0.0359876 4.53365 --0.27545 -0.0350581 4.77221 --0.535112 -0.0476101 6.52499 --0.409997 -0.041581 6.37454 --0.363698 -0.0389406 6.70593 --0.252395 -0.033345 6.63088 --0.125569 -0.0276613 6.39482 -0.0467126 -0.019964 5.60871 -0.0652873 -0.0186887 6.38349 -0.146355 -0.0143381 6.58973 -0.248556 -0.00966837 6.50517 -0.338588 -0.00549056 6.69865 -0.438149 -0.000387187 6.72051 -VERTICES 24989 49978 -1 0 -1 1 -1 2 -1 3 -1 4 -1 5 -1 6 -1 7 -1 8 -1 9 -1 10 -1 11 -1 12 -1 13 -1 14 -1 15 -1 16 -1 17 -1 18 -1 19 -1 20 -1 21 -1 22 -1 23 -1 24 -1 25 -1 26 -1 27 -1 28 -1 29 -1 30 -1 31 -1 32 -1 33 -1 34 -1 35 -1 36 -1 37 -1 38 -1 39 -1 40 -1 41 -1 42 -1 43 -1 44 -1 45 -1 46 -1 47 -1 48 -1 49 -1 50 -1 51 -1 52 -1 53 -1 54 -1 55 -1 56 -1 57 -1 58 -1 59 -1 60 -1 61 -1 62 -1 63 -1 64 -1 65 -1 66 -1 67 -1 68 -1 69 -1 70 -1 71 -1 72 -1 73 -1 74 -1 75 -1 76 -1 77 -1 78 -1 79 -1 80 -1 81 -1 82 -1 83 -1 84 -1 85 -1 86 -1 87 -1 88 -1 89 -1 90 -1 91 -1 92 -1 93 -1 94 -1 95 -1 96 -1 97 -1 98 -1 99 -1 100 -1 101 -1 102 -1 103 -1 104 -1 105 -1 106 -1 107 -1 108 -1 109 -1 110 -1 111 -1 112 -1 113 -1 114 -1 115 -1 116 -1 117 -1 118 -1 119 -1 120 -1 121 -1 122 -1 123 -1 124 -1 125 -1 126 -1 127 -1 128 -1 129 -1 130 -1 131 -1 132 -1 133 -1 134 -1 135 -1 136 -1 137 -1 138 -1 139 -1 140 -1 141 -1 142 -1 143 -1 144 -1 145 -1 146 -1 147 -1 148 -1 149 -1 150 -1 151 -1 152 -1 153 -1 154 -1 155 -1 156 -1 157 -1 158 -1 159 -1 160 -1 161 -1 162 -1 163 -1 164 -1 165 -1 166 -1 167 -1 168 -1 169 -1 170 -1 171 -1 172 -1 173 -1 174 -1 175 -1 176 -1 177 -1 178 -1 179 -1 180 -1 181 -1 182 -1 183 -1 184 -1 185 -1 186 -1 187 -1 188 -1 189 -1 190 -1 191 -1 192 -1 193 -1 194 -1 195 -1 196 -1 197 -1 198 -1 199 -1 200 -1 201 -1 202 -1 203 -1 204 -1 205 -1 206 -1 207 -1 208 -1 209 -1 210 -1 211 -1 212 -1 213 -1 214 -1 215 -1 216 -1 217 -1 218 -1 219 -1 220 -1 221 -1 222 -1 223 -1 224 -1 225 -1 226 -1 227 -1 228 -1 229 -1 230 -1 231 -1 232 -1 233 -1 234 -1 235 -1 236 -1 237 -1 238 -1 239 -1 240 -1 241 -1 242 -1 243 -1 244 -1 245 -1 246 -1 247 -1 248 -1 249 -1 250 -1 251 -1 252 -1 253 -1 254 -1 255 -1 256 -1 257 -1 258 -1 259 -1 260 -1 261 -1 262 -1 263 -1 264 -1 265 -1 266 -1 267 -1 268 -1 269 -1 270 -1 271 -1 272 -1 273 -1 274 -1 275 -1 276 -1 277 -1 278 -1 279 -1 280 -1 281 -1 282 -1 283 -1 284 -1 285 -1 286 -1 287 -1 288 -1 289 -1 290 -1 291 -1 292 -1 293 -1 294 -1 295 -1 296 -1 297 -1 298 -1 299 -1 300 -1 301 -1 302 -1 303 -1 304 -1 305 -1 306 -1 307 -1 308 -1 309 -1 310 -1 311 -1 312 -1 313 -1 314 -1 315 -1 316 -1 317 -1 318 -1 319 -1 320 -1 321 -1 322 -1 323 -1 324 -1 325 -1 326 -1 327 -1 328 -1 329 -1 330 -1 331 -1 332 -1 333 -1 334 -1 335 -1 336 -1 337 -1 338 -1 339 -1 340 -1 341 -1 342 -1 343 -1 344 -1 345 -1 346 -1 347 -1 348 -1 349 -1 350 -1 351 -1 352 -1 353 -1 354 -1 355 -1 356 -1 357 -1 358 -1 359 -1 360 -1 361 -1 362 -1 363 -1 364 -1 365 -1 366 -1 367 -1 368 -1 369 -1 370 -1 371 -1 372 -1 373 -1 374 -1 375 -1 376 -1 377 -1 378 -1 379 -1 380 -1 381 -1 382 -1 383 -1 384 -1 385 -1 386 -1 387 -1 388 -1 389 -1 390 -1 391 -1 392 -1 393 -1 394 -1 395 -1 396 -1 397 -1 398 -1 399 -1 400 -1 401 -1 402 -1 403 -1 404 -1 405 -1 406 -1 407 -1 408 -1 409 -1 410 -1 411 -1 412 -1 413 -1 414 -1 415 -1 416 -1 417 -1 418 -1 419 -1 420 -1 421 -1 422 -1 423 -1 424 -1 425 -1 426 -1 427 -1 428 -1 429 -1 430 -1 431 -1 432 -1 433 -1 434 -1 435 -1 436 -1 437 -1 438 -1 439 -1 440 -1 441 -1 442 -1 443 -1 444 -1 445 -1 446 -1 447 -1 448 -1 449 -1 450 -1 451 -1 452 -1 453 -1 454 -1 455 -1 456 -1 457 -1 458 -1 459 -1 460 -1 461 -1 462 -1 463 -1 464 -1 465 -1 466 -1 467 -1 468 -1 469 -1 470 -1 471 -1 472 -1 473 -1 474 -1 475 -1 476 -1 477 -1 478 -1 479 -1 480 -1 481 -1 482 -1 483 -1 484 -1 485 -1 486 -1 487 -1 488 -1 489 -1 490 -1 491 -1 492 -1 493 -1 494 -1 495 -1 496 -1 497 -1 498 -1 499 -1 500 -1 501 -1 502 -1 503 -1 504 -1 505 -1 506 -1 507 -1 508 -1 509 -1 510 -1 511 -1 512 -1 513 -1 514 -1 515 -1 516 -1 517 -1 518 -1 519 -1 520 -1 521 -1 522 -1 523 -1 524 -1 525 -1 526 -1 527 -1 528 -1 529 -1 530 -1 531 -1 532 -1 533 -1 534 -1 535 -1 536 -1 537 -1 538 -1 539 -1 540 -1 541 -1 542 -1 543 -1 544 -1 545 -1 546 -1 547 -1 548 -1 549 -1 550 -1 551 -1 552 -1 553 -1 554 -1 555 -1 556 -1 557 -1 558 -1 559 -1 560 -1 561 -1 562 -1 563 -1 564 -1 565 -1 566 -1 567 -1 568 -1 569 -1 570 -1 571 -1 572 -1 573 -1 574 -1 575 -1 576 -1 577 -1 578 -1 579 -1 580 -1 581 -1 582 -1 583 -1 584 -1 585 -1 586 -1 587 -1 588 -1 589 -1 590 -1 591 -1 592 -1 593 -1 594 -1 595 -1 596 -1 597 -1 598 -1 599 -1 600 -1 601 -1 602 -1 603 -1 604 -1 605 -1 606 -1 607 -1 608 -1 609 -1 610 -1 611 -1 612 -1 613 -1 614 -1 615 -1 616 -1 617 -1 618 -1 619 -1 620 -1 621 -1 622 -1 623 -1 624 -1 625 -1 626 -1 627 -1 628 -1 629 -1 630 -1 631 -1 632 -1 633 -1 634 -1 635 -1 636 -1 637 -1 638 -1 639 -1 640 -1 641 -1 642 -1 643 -1 644 -1 645 -1 646 -1 647 -1 648 -1 649 -1 650 -1 651 -1 652 -1 653 -1 654 -1 655 -1 656 -1 657 -1 658 -1 659 -1 660 -1 661 -1 662 -1 663 -1 664 -1 665 -1 666 -1 667 -1 668 -1 669 -1 670 -1 671 -1 672 -1 673 -1 674 -1 675 -1 676 -1 677 -1 678 -1 679 -1 680 -1 681 -1 682 -1 683 -1 684 -1 685 -1 686 -1 687 -1 688 -1 689 -1 690 -1 691 -1 692 -1 693 -1 694 -1 695 -1 696 -1 697 -1 698 -1 699 -1 700 -1 701 -1 702 -1 703 -1 704 -1 705 -1 706 -1 707 -1 708 -1 709 -1 710 -1 711 -1 712 -1 713 -1 714 -1 715 -1 716 -1 717 -1 718 -1 719 -1 720 -1 721 -1 722 -1 723 -1 724 -1 725 -1 726 -1 727 -1 728 -1 729 -1 730 -1 731 -1 732 -1 733 -1 734 -1 735 -1 736 -1 737 -1 738 -1 739 -1 740 -1 741 -1 742 -1 743 -1 744 -1 745 -1 746 -1 747 -1 748 -1 749 -1 750 -1 751 -1 752 -1 753 -1 754 -1 755 -1 756 -1 757 -1 758 -1 759 -1 760 -1 761 -1 762 -1 763 -1 764 -1 765 -1 766 -1 767 -1 768 -1 769 -1 770 -1 771 -1 772 -1 773 -1 774 -1 775 -1 776 -1 777 -1 778 -1 779 -1 780 -1 781 -1 782 -1 783 -1 784 -1 785 -1 786 -1 787 -1 788 -1 789 -1 790 -1 791 -1 792 -1 793 -1 794 -1 795 -1 796 -1 797 -1 798 -1 799 -1 800 -1 801 -1 802 -1 803 -1 804 -1 805 -1 806 -1 807 -1 808 -1 809 -1 810 -1 811 -1 812 -1 813 -1 814 -1 815 -1 816 -1 817 -1 818 -1 819 -1 820 -1 821 -1 822 -1 823 -1 824 -1 825 -1 826 -1 827 -1 828 -1 829 -1 830 -1 831 -1 832 -1 833 -1 834 -1 835 -1 836 -1 837 -1 838 -1 839 -1 840 -1 841 -1 842 -1 843 -1 844 -1 845 -1 846 -1 847 -1 848 -1 849 -1 850 -1 851 -1 852 -1 853 -1 854 -1 855 -1 856 -1 857 -1 858 -1 859 -1 860 -1 861 -1 862 -1 863 -1 864 -1 865 -1 866 -1 867 -1 868 -1 869 -1 870 -1 871 -1 872 -1 873 -1 874 -1 875 -1 876 -1 877 -1 878 -1 879 -1 880 -1 881 -1 882 -1 883 -1 884 -1 885 -1 886 -1 887 -1 888 -1 889 -1 890 -1 891 -1 892 -1 893 -1 894 -1 895 -1 896 -1 897 -1 898 -1 899 -1 900 -1 901 -1 902 -1 903 -1 904 -1 905 -1 906 -1 907 -1 908 -1 909 -1 910 -1 911 -1 912 -1 913 -1 914 -1 915 -1 916 -1 917 -1 918 -1 919 -1 920 -1 921 -1 922 -1 923 -1 924 -1 925 -1 926 -1 927 -1 928 -1 929 -1 930 -1 931 -1 932 -1 933 -1 934 -1 935 -1 936 -1 937 -1 938 -1 939 -1 940 -1 941 -1 942 -1 943 -1 944 -1 945 -1 946 -1 947 -1 948 -1 949 -1 950 -1 951 -1 952 -1 953 -1 954 -1 955 -1 956 -1 957 -1 958 -1 959 -1 960 -1 961 -1 962 -1 963 -1 964 -1 965 -1 966 -1 967 -1 968 -1 969 -1 970 -1 971 -1 972 -1 973 -1 974 -1 975 -1 976 -1 977 -1 978 -1 979 -1 980 -1 981 -1 982 -1 983 -1 984 -1 985 -1 986 -1 987 -1 988 -1 989 -1 990 -1 991 -1 992 -1 993 -1 994 -1 995 -1 996 -1 997 -1 998 -1 999 -1 1000 -1 1001 -1 1002 -1 1003 -1 1004 -1 1005 -1 1006 -1 1007 -1 1008 -1 1009 -1 1010 -1 1011 -1 1012 -1 1013 -1 1014 -1 1015 -1 1016 -1 1017 -1 1018 -1 1019 -1 1020 -1 1021 -1 1022 -1 1023 -1 1024 -1 1025 -1 1026 -1 1027 -1 1028 -1 1029 -1 1030 -1 1031 -1 1032 -1 1033 -1 1034 -1 1035 -1 1036 -1 1037 -1 1038 -1 1039 -1 1040 -1 1041 -1 1042 -1 1043 -1 1044 -1 1045 -1 1046 -1 1047 -1 1048 -1 1049 -1 1050 -1 1051 -1 1052 -1 1053 -1 1054 -1 1055 -1 1056 -1 1057 -1 1058 -1 1059 -1 1060 -1 1061 -1 1062 -1 1063 -1 1064 -1 1065 -1 1066 -1 1067 -1 1068 -1 1069 -1 1070 -1 1071 -1 1072 -1 1073 -1 1074 -1 1075 -1 1076 -1 1077 -1 1078 -1 1079 -1 1080 -1 1081 -1 1082 -1 1083 -1 1084 -1 1085 -1 1086 -1 1087 -1 1088 -1 1089 -1 1090 -1 1091 -1 1092 -1 1093 -1 1094 -1 1095 -1 1096 -1 1097 -1 1098 -1 1099 -1 1100 -1 1101 -1 1102 -1 1103 -1 1104 -1 1105 -1 1106 -1 1107 -1 1108 -1 1109 -1 1110 -1 1111 -1 1112 -1 1113 -1 1114 -1 1115 -1 1116 -1 1117 -1 1118 -1 1119 -1 1120 -1 1121 -1 1122 -1 1123 -1 1124 -1 1125 -1 1126 -1 1127 -1 1128 -1 1129 -1 1130 -1 1131 -1 1132 -1 1133 -1 1134 -1 1135 -1 1136 -1 1137 -1 1138 -1 1139 -1 1140 -1 1141 -1 1142 -1 1143 -1 1144 -1 1145 -1 1146 -1 1147 -1 1148 -1 1149 -1 1150 -1 1151 -1 1152 -1 1153 -1 1154 -1 1155 -1 1156 -1 1157 -1 1158 -1 1159 -1 1160 -1 1161 -1 1162 -1 1163 -1 1164 -1 1165 -1 1166 -1 1167 -1 1168 -1 1169 -1 1170 -1 1171 -1 1172 -1 1173 -1 1174 -1 1175 -1 1176 -1 1177 -1 1178 -1 1179 -1 1180 -1 1181 -1 1182 -1 1183 -1 1184 -1 1185 -1 1186 -1 1187 -1 1188 -1 1189 -1 1190 -1 1191 -1 1192 -1 1193 -1 1194 -1 1195 -1 1196 -1 1197 -1 1198 -1 1199 -1 1200 -1 1201 -1 1202 -1 1203 -1 1204 -1 1205 -1 1206 -1 1207 -1 1208 -1 1209 -1 1210 -1 1211 -1 1212 -1 1213 -1 1214 -1 1215 -1 1216 -1 1217 -1 1218 -1 1219 -1 1220 -1 1221 -1 1222 -1 1223 -1 1224 -1 1225 -1 1226 -1 1227 -1 1228 -1 1229 -1 1230 -1 1231 -1 1232 -1 1233 -1 1234 -1 1235 -1 1236 -1 1237 -1 1238 -1 1239 -1 1240 -1 1241 -1 1242 -1 1243 -1 1244 -1 1245 -1 1246 -1 1247 -1 1248 -1 1249 -1 1250 -1 1251 -1 1252 -1 1253 -1 1254 -1 1255 -1 1256 -1 1257 -1 1258 -1 1259 -1 1260 -1 1261 -1 1262 -1 1263 -1 1264 -1 1265 -1 1266 -1 1267 -1 1268 -1 1269 -1 1270 -1 1271 -1 1272 -1 1273 -1 1274 -1 1275 -1 1276 -1 1277 -1 1278 -1 1279 -1 1280 -1 1281 -1 1282 -1 1283 -1 1284 -1 1285 -1 1286 -1 1287 -1 1288 -1 1289 -1 1290 -1 1291 -1 1292 -1 1293 -1 1294 -1 1295 -1 1296 -1 1297 -1 1298 -1 1299 -1 1300 -1 1301 -1 1302 -1 1303 -1 1304 -1 1305 -1 1306 -1 1307 -1 1308 -1 1309 -1 1310 -1 1311 -1 1312 -1 1313 -1 1314 -1 1315 -1 1316 -1 1317 -1 1318 -1 1319 -1 1320 -1 1321 -1 1322 -1 1323 -1 1324 -1 1325 -1 1326 -1 1327 -1 1328 -1 1329 -1 1330 -1 1331 -1 1332 -1 1333 -1 1334 -1 1335 -1 1336 -1 1337 -1 1338 -1 1339 -1 1340 -1 1341 -1 1342 -1 1343 -1 1344 -1 1345 -1 1346 -1 1347 -1 1348 -1 1349 -1 1350 -1 1351 -1 1352 -1 1353 -1 1354 -1 1355 -1 1356 -1 1357 -1 1358 -1 1359 -1 1360 -1 1361 -1 1362 -1 1363 -1 1364 -1 1365 -1 1366 -1 1367 -1 1368 -1 1369 -1 1370 -1 1371 -1 1372 -1 1373 -1 1374 -1 1375 -1 1376 -1 1377 -1 1378 -1 1379 -1 1380 -1 1381 -1 1382 -1 1383 -1 1384 -1 1385 -1 1386 -1 1387 -1 1388 -1 1389 -1 1390 -1 1391 -1 1392 -1 1393 -1 1394 -1 1395 -1 1396 -1 1397 -1 1398 -1 1399 -1 1400 -1 1401 -1 1402 -1 1403 -1 1404 -1 1405 -1 1406 -1 1407 -1 1408 -1 1409 -1 1410 -1 1411 -1 1412 -1 1413 -1 1414 -1 1415 -1 1416 -1 1417 -1 1418 -1 1419 -1 1420 -1 1421 -1 1422 -1 1423 -1 1424 -1 1425 -1 1426 -1 1427 -1 1428 -1 1429 -1 1430 -1 1431 -1 1432 -1 1433 -1 1434 -1 1435 -1 1436 -1 1437 -1 1438 -1 1439 -1 1440 -1 1441 -1 1442 -1 1443 -1 1444 -1 1445 -1 1446 -1 1447 -1 1448 -1 1449 -1 1450 -1 1451 -1 1452 -1 1453 -1 1454 -1 1455 -1 1456 -1 1457 -1 1458 -1 1459 -1 1460 -1 1461 -1 1462 -1 1463 -1 1464 -1 1465 -1 1466 -1 1467 -1 1468 -1 1469 -1 1470 -1 1471 -1 1472 -1 1473 -1 1474 -1 1475 -1 1476 -1 1477 -1 1478 -1 1479 -1 1480 -1 1481 -1 1482 -1 1483 -1 1484 -1 1485 -1 1486 -1 1487 -1 1488 -1 1489 -1 1490 -1 1491 -1 1492 -1 1493 -1 1494 -1 1495 -1 1496 -1 1497 -1 1498 -1 1499 -1 1500 -1 1501 -1 1502 -1 1503 -1 1504 -1 1505 -1 1506 -1 1507 -1 1508 -1 1509 -1 1510 -1 1511 -1 1512 -1 1513 -1 1514 -1 1515 -1 1516 -1 1517 -1 1518 -1 1519 -1 1520 -1 1521 -1 1522 -1 1523 -1 1524 -1 1525 -1 1526 -1 1527 -1 1528 -1 1529 -1 1530 -1 1531 -1 1532 -1 1533 -1 1534 -1 1535 -1 1536 -1 1537 -1 1538 -1 1539 -1 1540 -1 1541 -1 1542 -1 1543 -1 1544 -1 1545 -1 1546 -1 1547 -1 1548 -1 1549 -1 1550 -1 1551 -1 1552 -1 1553 -1 1554 -1 1555 -1 1556 -1 1557 -1 1558 -1 1559 -1 1560 -1 1561 -1 1562 -1 1563 -1 1564 -1 1565 -1 1566 -1 1567 -1 1568 -1 1569 -1 1570 -1 1571 -1 1572 -1 1573 -1 1574 -1 1575 -1 1576 -1 1577 -1 1578 -1 1579 -1 1580 -1 1581 -1 1582 -1 1583 -1 1584 -1 1585 -1 1586 -1 1587 -1 1588 -1 1589 -1 1590 -1 1591 -1 1592 -1 1593 -1 1594 -1 1595 -1 1596 -1 1597 -1 1598 -1 1599 -1 1600 -1 1601 -1 1602 -1 1603 -1 1604 -1 1605 -1 1606 -1 1607 -1 1608 -1 1609 -1 1610 -1 1611 -1 1612 -1 1613 -1 1614 -1 1615 -1 1616 -1 1617 -1 1618 -1 1619 -1 1620 -1 1621 -1 1622 -1 1623 -1 1624 -1 1625 -1 1626 -1 1627 -1 1628 -1 1629 -1 1630 -1 1631 -1 1632 -1 1633 -1 1634 -1 1635 -1 1636 -1 1637 -1 1638 -1 1639 -1 1640 -1 1641 -1 1642 -1 1643 -1 1644 -1 1645 -1 1646 -1 1647 -1 1648 -1 1649 -1 1650 -1 1651 -1 1652 -1 1653 -1 1654 -1 1655 -1 1656 -1 1657 -1 1658 -1 1659 -1 1660 -1 1661 -1 1662 -1 1663 -1 1664 -1 1665 -1 1666 -1 1667 -1 1668 -1 1669 -1 1670 -1 1671 -1 1672 -1 1673 -1 1674 -1 1675 -1 1676 -1 1677 -1 1678 -1 1679 -1 1680 -1 1681 -1 1682 -1 1683 -1 1684 -1 1685 -1 1686 -1 1687 -1 1688 -1 1689 -1 1690 -1 1691 -1 1692 -1 1693 -1 1694 -1 1695 -1 1696 -1 1697 -1 1698 -1 1699 -1 1700 -1 1701 -1 1702 -1 1703 -1 1704 -1 1705 -1 1706 -1 1707 -1 1708 -1 1709 -1 1710 -1 1711 -1 1712 -1 1713 -1 1714 -1 1715 -1 1716 -1 1717 -1 1718 -1 1719 -1 1720 -1 1721 -1 1722 -1 1723 -1 1724 -1 1725 -1 1726 -1 1727 -1 1728 -1 1729 -1 1730 -1 1731 -1 1732 -1 1733 -1 1734 -1 1735 -1 1736 -1 1737 -1 1738 -1 1739 -1 1740 -1 1741 -1 1742 -1 1743 -1 1744 -1 1745 -1 1746 -1 1747 -1 1748 -1 1749 -1 1750 -1 1751 -1 1752 -1 1753 -1 1754 -1 1755 -1 1756 -1 1757 -1 1758 -1 1759 -1 1760 -1 1761 -1 1762 -1 1763 -1 1764 -1 1765 -1 1766 -1 1767 -1 1768 -1 1769 -1 1770 -1 1771 -1 1772 -1 1773 -1 1774 -1 1775 -1 1776 -1 1777 -1 1778 -1 1779 -1 1780 -1 1781 -1 1782 -1 1783 -1 1784 -1 1785 -1 1786 -1 1787 -1 1788 -1 1789 -1 1790 -1 1791 -1 1792 -1 1793 -1 1794 -1 1795 -1 1796 -1 1797 -1 1798 -1 1799 -1 1800 -1 1801 -1 1802 -1 1803 -1 1804 -1 1805 -1 1806 -1 1807 -1 1808 -1 1809 -1 1810 -1 1811 -1 1812 -1 1813 -1 1814 -1 1815 -1 1816 -1 1817 -1 1818 -1 1819 -1 1820 -1 1821 -1 1822 -1 1823 -1 1824 -1 1825 -1 1826 -1 1827 -1 1828 -1 1829 -1 1830 -1 1831 -1 1832 -1 1833 -1 1834 -1 1835 -1 1836 -1 1837 -1 1838 -1 1839 -1 1840 -1 1841 -1 1842 -1 1843 -1 1844 -1 1845 -1 1846 -1 1847 -1 1848 -1 1849 -1 1850 -1 1851 -1 1852 -1 1853 -1 1854 -1 1855 -1 1856 -1 1857 -1 1858 -1 1859 -1 1860 -1 1861 -1 1862 -1 1863 -1 1864 -1 1865 -1 1866 -1 1867 -1 1868 -1 1869 -1 1870 -1 1871 -1 1872 -1 1873 -1 1874 -1 1875 -1 1876 -1 1877 -1 1878 -1 1879 -1 1880 -1 1881 -1 1882 -1 1883 -1 1884 -1 1885 -1 1886 -1 1887 -1 1888 -1 1889 -1 1890 -1 1891 -1 1892 -1 1893 -1 1894 -1 1895 -1 1896 -1 1897 -1 1898 -1 1899 -1 1900 -1 1901 -1 1902 -1 1903 -1 1904 -1 1905 -1 1906 -1 1907 -1 1908 -1 1909 -1 1910 -1 1911 -1 1912 -1 1913 -1 1914 -1 1915 -1 1916 -1 1917 -1 1918 -1 1919 -1 1920 -1 1921 -1 1922 -1 1923 -1 1924 -1 1925 -1 1926 -1 1927 -1 1928 -1 1929 -1 1930 -1 1931 -1 1932 -1 1933 -1 1934 -1 1935 -1 1936 -1 1937 -1 1938 -1 1939 -1 1940 -1 1941 -1 1942 -1 1943 -1 1944 -1 1945 -1 1946 -1 1947 -1 1948 -1 1949 -1 1950 -1 1951 -1 1952 -1 1953 -1 1954 -1 1955 -1 1956 -1 1957 -1 1958 -1 1959 -1 1960 -1 1961 -1 1962 -1 1963 -1 1964 -1 1965 -1 1966 -1 1967 -1 1968 -1 1969 -1 1970 -1 1971 -1 1972 -1 1973 -1 1974 -1 1975 -1 1976 -1 1977 -1 1978 -1 1979 -1 1980 -1 1981 -1 1982 -1 1983 -1 1984 -1 1985 -1 1986 -1 1987 -1 1988 -1 1989 -1 1990 -1 1991 -1 1992 -1 1993 -1 1994 -1 1995 -1 1996 -1 1997 -1 1998 -1 1999 -1 2000 -1 2001 -1 2002 -1 2003 -1 2004 -1 2005 -1 2006 -1 2007 -1 2008 -1 2009 -1 2010 -1 2011 -1 2012 -1 2013 -1 2014 -1 2015 -1 2016 -1 2017 -1 2018 -1 2019 -1 2020 -1 2021 -1 2022 -1 2023 -1 2024 -1 2025 -1 2026 -1 2027 -1 2028 -1 2029 -1 2030 -1 2031 -1 2032 -1 2033 -1 2034 -1 2035 -1 2036 -1 2037 -1 2038 -1 2039 -1 2040 -1 2041 -1 2042 -1 2043 -1 2044 -1 2045 -1 2046 -1 2047 -1 2048 -1 2049 -1 2050 -1 2051 -1 2052 -1 2053 -1 2054 -1 2055 -1 2056 -1 2057 -1 2058 -1 2059 -1 2060 -1 2061 -1 2062 -1 2063 -1 2064 -1 2065 -1 2066 -1 2067 -1 2068 -1 2069 -1 2070 -1 2071 -1 2072 -1 2073 -1 2074 -1 2075 -1 2076 -1 2077 -1 2078 -1 2079 -1 2080 -1 2081 -1 2082 -1 2083 -1 2084 -1 2085 -1 2086 -1 2087 -1 2088 -1 2089 -1 2090 -1 2091 -1 2092 -1 2093 -1 2094 -1 2095 -1 2096 -1 2097 -1 2098 -1 2099 -1 2100 -1 2101 -1 2102 -1 2103 -1 2104 -1 2105 -1 2106 -1 2107 -1 2108 -1 2109 -1 2110 -1 2111 -1 2112 -1 2113 -1 2114 -1 2115 -1 2116 -1 2117 -1 2118 -1 2119 -1 2120 -1 2121 -1 2122 -1 2123 -1 2124 -1 2125 -1 2126 -1 2127 -1 2128 -1 2129 -1 2130 -1 2131 -1 2132 -1 2133 -1 2134 -1 2135 -1 2136 -1 2137 -1 2138 -1 2139 -1 2140 -1 2141 -1 2142 -1 2143 -1 2144 -1 2145 -1 2146 -1 2147 -1 2148 -1 2149 -1 2150 -1 2151 -1 2152 -1 2153 -1 2154 -1 2155 -1 2156 -1 2157 -1 2158 -1 2159 -1 2160 -1 2161 -1 2162 -1 2163 -1 2164 -1 2165 -1 2166 -1 2167 -1 2168 -1 2169 -1 2170 -1 2171 -1 2172 -1 2173 -1 2174 -1 2175 -1 2176 -1 2177 -1 2178 -1 2179 -1 2180 -1 2181 -1 2182 -1 2183 -1 2184 -1 2185 -1 2186 -1 2187 -1 2188 -1 2189 -1 2190 -1 2191 -1 2192 -1 2193 -1 2194 -1 2195 -1 2196 -1 2197 -1 2198 -1 2199 -1 2200 -1 2201 -1 2202 -1 2203 -1 2204 -1 2205 -1 2206 -1 2207 -1 2208 -1 2209 -1 2210 -1 2211 -1 2212 -1 2213 -1 2214 -1 2215 -1 2216 -1 2217 -1 2218 -1 2219 -1 2220 -1 2221 -1 2222 -1 2223 -1 2224 -1 2225 -1 2226 -1 2227 -1 2228 -1 2229 -1 2230 -1 2231 -1 2232 -1 2233 -1 2234 -1 2235 -1 2236 -1 2237 -1 2238 -1 2239 -1 2240 -1 2241 -1 2242 -1 2243 -1 2244 -1 2245 -1 2246 -1 2247 -1 2248 -1 2249 -1 2250 -1 2251 -1 2252 -1 2253 -1 2254 -1 2255 -1 2256 -1 2257 -1 2258 -1 2259 -1 2260 -1 2261 -1 2262 -1 2263 -1 2264 -1 2265 -1 2266 -1 2267 -1 2268 -1 2269 -1 2270 -1 2271 -1 2272 -1 2273 -1 2274 -1 2275 -1 2276 -1 2277 -1 2278 -1 2279 -1 2280 -1 2281 -1 2282 -1 2283 -1 2284 -1 2285 -1 2286 -1 2287 -1 2288 -1 2289 -1 2290 -1 2291 -1 2292 -1 2293 -1 2294 -1 2295 -1 2296 -1 2297 -1 2298 -1 2299 -1 2300 -1 2301 -1 2302 -1 2303 -1 2304 -1 2305 -1 2306 -1 2307 -1 2308 -1 2309 -1 2310 -1 2311 -1 2312 -1 2313 -1 2314 -1 2315 -1 2316 -1 2317 -1 2318 -1 2319 -1 2320 -1 2321 -1 2322 -1 2323 -1 2324 -1 2325 -1 2326 -1 2327 -1 2328 -1 2329 -1 2330 -1 2331 -1 2332 -1 2333 -1 2334 -1 2335 -1 2336 -1 2337 -1 2338 -1 2339 -1 2340 -1 2341 -1 2342 -1 2343 -1 2344 -1 2345 -1 2346 -1 2347 -1 2348 -1 2349 -1 2350 -1 2351 -1 2352 -1 2353 -1 2354 -1 2355 -1 2356 -1 2357 -1 2358 -1 2359 -1 2360 -1 2361 -1 2362 -1 2363 -1 2364 -1 2365 -1 2366 -1 2367 -1 2368 -1 2369 -1 2370 -1 2371 -1 2372 -1 2373 -1 2374 -1 2375 -1 2376 -1 2377 -1 2378 -1 2379 -1 2380 -1 2381 -1 2382 -1 2383 -1 2384 -1 2385 -1 2386 -1 2387 -1 2388 -1 2389 -1 2390 -1 2391 -1 2392 -1 2393 -1 2394 -1 2395 -1 2396 -1 2397 -1 2398 -1 2399 -1 2400 -1 2401 -1 2402 -1 2403 -1 2404 -1 2405 -1 2406 -1 2407 -1 2408 -1 2409 -1 2410 -1 2411 -1 2412 -1 2413 -1 2414 -1 2415 -1 2416 -1 2417 -1 2418 -1 2419 -1 2420 -1 2421 -1 2422 -1 2423 -1 2424 -1 2425 -1 2426 -1 2427 -1 2428 -1 2429 -1 2430 -1 2431 -1 2432 -1 2433 -1 2434 -1 2435 -1 2436 -1 2437 -1 2438 -1 2439 -1 2440 -1 2441 -1 2442 -1 2443 -1 2444 -1 2445 -1 2446 -1 2447 -1 2448 -1 2449 -1 2450 -1 2451 -1 2452 -1 2453 -1 2454 -1 2455 -1 2456 -1 2457 -1 2458 -1 2459 -1 2460 -1 2461 -1 2462 -1 2463 -1 2464 -1 2465 -1 2466 -1 2467 -1 2468 -1 2469 -1 2470 -1 2471 -1 2472 -1 2473 -1 2474 -1 2475 -1 2476 -1 2477 -1 2478 -1 2479 -1 2480 -1 2481 -1 2482 -1 2483 -1 2484 -1 2485 -1 2486 -1 2487 -1 2488 -1 2489 -1 2490 -1 2491 -1 2492 -1 2493 -1 2494 -1 2495 -1 2496 -1 2497 -1 2498 -1 2499 -1 2500 -1 2501 -1 2502 -1 2503 -1 2504 -1 2505 -1 2506 -1 2507 -1 2508 -1 2509 -1 2510 -1 2511 -1 2512 -1 2513 -1 2514 -1 2515 -1 2516 -1 2517 -1 2518 -1 2519 -1 2520 -1 2521 -1 2522 -1 2523 -1 2524 -1 2525 -1 2526 -1 2527 -1 2528 -1 2529 -1 2530 -1 2531 -1 2532 -1 2533 -1 2534 -1 2535 -1 2536 -1 2537 -1 2538 -1 2539 -1 2540 -1 2541 -1 2542 -1 2543 -1 2544 -1 2545 -1 2546 -1 2547 -1 2548 -1 2549 -1 2550 -1 2551 -1 2552 -1 2553 -1 2554 -1 2555 -1 2556 -1 2557 -1 2558 -1 2559 -1 2560 -1 2561 -1 2562 -1 2563 -1 2564 -1 2565 -1 2566 -1 2567 -1 2568 -1 2569 -1 2570 -1 2571 -1 2572 -1 2573 -1 2574 -1 2575 -1 2576 -1 2577 -1 2578 -1 2579 -1 2580 -1 2581 -1 2582 -1 2583 -1 2584 -1 2585 -1 2586 -1 2587 -1 2588 -1 2589 -1 2590 -1 2591 -1 2592 -1 2593 -1 2594 -1 2595 -1 2596 -1 2597 -1 2598 -1 2599 -1 2600 -1 2601 -1 2602 -1 2603 -1 2604 -1 2605 -1 2606 -1 2607 -1 2608 -1 2609 -1 2610 -1 2611 -1 2612 -1 2613 -1 2614 -1 2615 -1 2616 -1 2617 -1 2618 -1 2619 -1 2620 -1 2621 -1 2622 -1 2623 -1 2624 -1 2625 -1 2626 -1 2627 -1 2628 -1 2629 -1 2630 -1 2631 -1 2632 -1 2633 -1 2634 -1 2635 -1 2636 -1 2637 -1 2638 -1 2639 -1 2640 -1 2641 -1 2642 -1 2643 -1 2644 -1 2645 -1 2646 -1 2647 -1 2648 -1 2649 -1 2650 -1 2651 -1 2652 -1 2653 -1 2654 -1 2655 -1 2656 -1 2657 -1 2658 -1 2659 -1 2660 -1 2661 -1 2662 -1 2663 -1 2664 -1 2665 -1 2666 -1 2667 -1 2668 -1 2669 -1 2670 -1 2671 -1 2672 -1 2673 -1 2674 -1 2675 -1 2676 -1 2677 -1 2678 -1 2679 -1 2680 -1 2681 -1 2682 -1 2683 -1 2684 -1 2685 -1 2686 -1 2687 -1 2688 -1 2689 -1 2690 -1 2691 -1 2692 -1 2693 -1 2694 -1 2695 -1 2696 -1 2697 -1 2698 -1 2699 -1 2700 -1 2701 -1 2702 -1 2703 -1 2704 -1 2705 -1 2706 -1 2707 -1 2708 -1 2709 -1 2710 -1 2711 -1 2712 -1 2713 -1 2714 -1 2715 -1 2716 -1 2717 -1 2718 -1 2719 -1 2720 -1 2721 -1 2722 -1 2723 -1 2724 -1 2725 -1 2726 -1 2727 -1 2728 -1 2729 -1 2730 -1 2731 -1 2732 -1 2733 -1 2734 -1 2735 -1 2736 -1 2737 -1 2738 -1 2739 -1 2740 -1 2741 -1 2742 -1 2743 -1 2744 -1 2745 -1 2746 -1 2747 -1 2748 -1 2749 -1 2750 -1 2751 -1 2752 -1 2753 -1 2754 -1 2755 -1 2756 -1 2757 -1 2758 -1 2759 -1 2760 -1 2761 -1 2762 -1 2763 -1 2764 -1 2765 -1 2766 -1 2767 -1 2768 -1 2769 -1 2770 -1 2771 -1 2772 -1 2773 -1 2774 -1 2775 -1 2776 -1 2777 -1 2778 -1 2779 -1 2780 -1 2781 -1 2782 -1 2783 -1 2784 -1 2785 -1 2786 -1 2787 -1 2788 -1 2789 -1 2790 -1 2791 -1 2792 -1 2793 -1 2794 -1 2795 -1 2796 -1 2797 -1 2798 -1 2799 -1 2800 -1 2801 -1 2802 -1 2803 -1 2804 -1 2805 -1 2806 -1 2807 -1 2808 -1 2809 -1 2810 -1 2811 -1 2812 -1 2813 -1 2814 -1 2815 -1 2816 -1 2817 -1 2818 -1 2819 -1 2820 -1 2821 -1 2822 -1 2823 -1 2824 -1 2825 -1 2826 -1 2827 -1 2828 -1 2829 -1 2830 -1 2831 -1 2832 -1 2833 -1 2834 -1 2835 -1 2836 -1 2837 -1 2838 -1 2839 -1 2840 -1 2841 -1 2842 -1 2843 -1 2844 -1 2845 -1 2846 -1 2847 -1 2848 -1 2849 -1 2850 -1 2851 -1 2852 -1 2853 -1 2854 -1 2855 -1 2856 -1 2857 -1 2858 -1 2859 -1 2860 -1 2861 -1 2862 -1 2863 -1 2864 -1 2865 -1 2866 -1 2867 -1 2868 -1 2869 -1 2870 -1 2871 -1 2872 -1 2873 -1 2874 -1 2875 -1 2876 -1 2877 -1 2878 -1 2879 -1 2880 -1 2881 -1 2882 -1 2883 -1 2884 -1 2885 -1 2886 -1 2887 -1 2888 -1 2889 -1 2890 -1 2891 -1 2892 -1 2893 -1 2894 -1 2895 -1 2896 -1 2897 -1 2898 -1 2899 -1 2900 -1 2901 -1 2902 -1 2903 -1 2904 -1 2905 -1 2906 -1 2907 -1 2908 -1 2909 -1 2910 -1 2911 -1 2912 -1 2913 -1 2914 -1 2915 -1 2916 -1 2917 -1 2918 -1 2919 -1 2920 -1 2921 -1 2922 -1 2923 -1 2924 -1 2925 -1 2926 -1 2927 -1 2928 -1 2929 -1 2930 -1 2931 -1 2932 -1 2933 -1 2934 -1 2935 -1 2936 -1 2937 -1 2938 -1 2939 -1 2940 -1 2941 -1 2942 -1 2943 -1 2944 -1 2945 -1 2946 -1 2947 -1 2948 -1 2949 -1 2950 -1 2951 -1 2952 -1 2953 -1 2954 -1 2955 -1 2956 -1 2957 -1 2958 -1 2959 -1 2960 -1 2961 -1 2962 -1 2963 -1 2964 -1 2965 -1 2966 -1 2967 -1 2968 -1 2969 -1 2970 -1 2971 -1 2972 -1 2973 -1 2974 -1 2975 -1 2976 -1 2977 -1 2978 -1 2979 -1 2980 -1 2981 -1 2982 -1 2983 -1 2984 -1 2985 -1 2986 -1 2987 -1 2988 -1 2989 -1 2990 -1 2991 -1 2992 -1 2993 -1 2994 -1 2995 -1 2996 -1 2997 -1 2998 -1 2999 -1 3000 -1 3001 -1 3002 -1 3003 -1 3004 -1 3005 -1 3006 -1 3007 -1 3008 -1 3009 -1 3010 -1 3011 -1 3012 -1 3013 -1 3014 -1 3015 -1 3016 -1 3017 -1 3018 -1 3019 -1 3020 -1 3021 -1 3022 -1 3023 -1 3024 -1 3025 -1 3026 -1 3027 -1 3028 -1 3029 -1 3030 -1 3031 -1 3032 -1 3033 -1 3034 -1 3035 -1 3036 -1 3037 -1 3038 -1 3039 -1 3040 -1 3041 -1 3042 -1 3043 -1 3044 -1 3045 -1 3046 -1 3047 -1 3048 -1 3049 -1 3050 -1 3051 -1 3052 -1 3053 -1 3054 -1 3055 -1 3056 -1 3057 -1 3058 -1 3059 -1 3060 -1 3061 -1 3062 -1 3063 -1 3064 -1 3065 -1 3066 -1 3067 -1 3068 -1 3069 -1 3070 -1 3071 -1 3072 -1 3073 -1 3074 -1 3075 -1 3076 -1 3077 -1 3078 -1 3079 -1 3080 -1 3081 -1 3082 -1 3083 -1 3084 -1 3085 -1 3086 -1 3087 -1 3088 -1 3089 -1 3090 -1 3091 -1 3092 -1 3093 -1 3094 -1 3095 -1 3096 -1 3097 -1 3098 -1 3099 -1 3100 -1 3101 -1 3102 -1 3103 -1 3104 -1 3105 -1 3106 -1 3107 -1 3108 -1 3109 -1 3110 -1 3111 -1 3112 -1 3113 -1 3114 -1 3115 -1 3116 -1 3117 -1 3118 -1 3119 -1 3120 -1 3121 -1 3122 -1 3123 -1 3124 -1 3125 -1 3126 -1 3127 -1 3128 -1 3129 -1 3130 -1 3131 -1 3132 -1 3133 -1 3134 -1 3135 -1 3136 -1 3137 -1 3138 -1 3139 -1 3140 -1 3141 -1 3142 -1 3143 -1 3144 -1 3145 -1 3146 -1 3147 -1 3148 -1 3149 -1 3150 -1 3151 -1 3152 -1 3153 -1 3154 -1 3155 -1 3156 -1 3157 -1 3158 -1 3159 -1 3160 -1 3161 -1 3162 -1 3163 -1 3164 -1 3165 -1 3166 -1 3167 -1 3168 -1 3169 -1 3170 -1 3171 -1 3172 -1 3173 -1 3174 -1 3175 -1 3176 -1 3177 -1 3178 -1 3179 -1 3180 -1 3181 -1 3182 -1 3183 -1 3184 -1 3185 -1 3186 -1 3187 -1 3188 -1 3189 -1 3190 -1 3191 -1 3192 -1 3193 -1 3194 -1 3195 -1 3196 -1 3197 -1 3198 -1 3199 -1 3200 -1 3201 -1 3202 -1 3203 -1 3204 -1 3205 -1 3206 -1 3207 -1 3208 -1 3209 -1 3210 -1 3211 -1 3212 -1 3213 -1 3214 -1 3215 -1 3216 -1 3217 -1 3218 -1 3219 -1 3220 -1 3221 -1 3222 -1 3223 -1 3224 -1 3225 -1 3226 -1 3227 -1 3228 -1 3229 -1 3230 -1 3231 -1 3232 -1 3233 -1 3234 -1 3235 -1 3236 -1 3237 -1 3238 -1 3239 -1 3240 -1 3241 -1 3242 -1 3243 -1 3244 -1 3245 -1 3246 -1 3247 -1 3248 -1 3249 -1 3250 -1 3251 -1 3252 -1 3253 -1 3254 -1 3255 -1 3256 -1 3257 -1 3258 -1 3259 -1 3260 -1 3261 -1 3262 -1 3263 -1 3264 -1 3265 -1 3266 -1 3267 -1 3268 -1 3269 -1 3270 -1 3271 -1 3272 -1 3273 -1 3274 -1 3275 -1 3276 -1 3277 -1 3278 -1 3279 -1 3280 -1 3281 -1 3282 -1 3283 -1 3284 -1 3285 -1 3286 -1 3287 -1 3288 -1 3289 -1 3290 -1 3291 -1 3292 -1 3293 -1 3294 -1 3295 -1 3296 -1 3297 -1 3298 -1 3299 -1 3300 -1 3301 -1 3302 -1 3303 -1 3304 -1 3305 -1 3306 -1 3307 -1 3308 -1 3309 -1 3310 -1 3311 -1 3312 -1 3313 -1 3314 -1 3315 -1 3316 -1 3317 -1 3318 -1 3319 -1 3320 -1 3321 -1 3322 -1 3323 -1 3324 -1 3325 -1 3326 -1 3327 -1 3328 -1 3329 -1 3330 -1 3331 -1 3332 -1 3333 -1 3334 -1 3335 -1 3336 -1 3337 -1 3338 -1 3339 -1 3340 -1 3341 -1 3342 -1 3343 -1 3344 -1 3345 -1 3346 -1 3347 -1 3348 -1 3349 -1 3350 -1 3351 -1 3352 -1 3353 -1 3354 -1 3355 -1 3356 -1 3357 -1 3358 -1 3359 -1 3360 -1 3361 -1 3362 -1 3363 -1 3364 -1 3365 -1 3366 -1 3367 -1 3368 -1 3369 -1 3370 -1 3371 -1 3372 -1 3373 -1 3374 -1 3375 -1 3376 -1 3377 -1 3378 -1 3379 -1 3380 -1 3381 -1 3382 -1 3383 -1 3384 -1 3385 -1 3386 -1 3387 -1 3388 -1 3389 -1 3390 -1 3391 -1 3392 -1 3393 -1 3394 -1 3395 -1 3396 -1 3397 -1 3398 -1 3399 -1 3400 -1 3401 -1 3402 -1 3403 -1 3404 -1 3405 -1 3406 -1 3407 -1 3408 -1 3409 -1 3410 -1 3411 -1 3412 -1 3413 -1 3414 -1 3415 -1 3416 -1 3417 -1 3418 -1 3419 -1 3420 -1 3421 -1 3422 -1 3423 -1 3424 -1 3425 -1 3426 -1 3427 -1 3428 -1 3429 -1 3430 -1 3431 -1 3432 -1 3433 -1 3434 -1 3435 -1 3436 -1 3437 -1 3438 -1 3439 -1 3440 -1 3441 -1 3442 -1 3443 -1 3444 -1 3445 -1 3446 -1 3447 -1 3448 -1 3449 -1 3450 -1 3451 -1 3452 -1 3453 -1 3454 -1 3455 -1 3456 -1 3457 -1 3458 -1 3459 -1 3460 -1 3461 -1 3462 -1 3463 -1 3464 -1 3465 -1 3466 -1 3467 -1 3468 -1 3469 -1 3470 -1 3471 -1 3472 -1 3473 -1 3474 -1 3475 -1 3476 -1 3477 -1 3478 -1 3479 -1 3480 -1 3481 -1 3482 -1 3483 -1 3484 -1 3485 -1 3486 -1 3487 -1 3488 -1 3489 -1 3490 -1 3491 -1 3492 -1 3493 -1 3494 -1 3495 -1 3496 -1 3497 -1 3498 -1 3499 -1 3500 -1 3501 -1 3502 -1 3503 -1 3504 -1 3505 -1 3506 -1 3507 -1 3508 -1 3509 -1 3510 -1 3511 -1 3512 -1 3513 -1 3514 -1 3515 -1 3516 -1 3517 -1 3518 -1 3519 -1 3520 -1 3521 -1 3522 -1 3523 -1 3524 -1 3525 -1 3526 -1 3527 -1 3528 -1 3529 -1 3530 -1 3531 -1 3532 -1 3533 -1 3534 -1 3535 -1 3536 -1 3537 -1 3538 -1 3539 -1 3540 -1 3541 -1 3542 -1 3543 -1 3544 -1 3545 -1 3546 -1 3547 -1 3548 -1 3549 -1 3550 -1 3551 -1 3552 -1 3553 -1 3554 -1 3555 -1 3556 -1 3557 -1 3558 -1 3559 -1 3560 -1 3561 -1 3562 -1 3563 -1 3564 -1 3565 -1 3566 -1 3567 -1 3568 -1 3569 -1 3570 -1 3571 -1 3572 -1 3573 -1 3574 -1 3575 -1 3576 -1 3577 -1 3578 -1 3579 -1 3580 -1 3581 -1 3582 -1 3583 -1 3584 -1 3585 -1 3586 -1 3587 -1 3588 -1 3589 -1 3590 -1 3591 -1 3592 -1 3593 -1 3594 -1 3595 -1 3596 -1 3597 -1 3598 -1 3599 -1 3600 -1 3601 -1 3602 -1 3603 -1 3604 -1 3605 -1 3606 -1 3607 -1 3608 -1 3609 -1 3610 -1 3611 -1 3612 -1 3613 -1 3614 -1 3615 -1 3616 -1 3617 -1 3618 -1 3619 -1 3620 -1 3621 -1 3622 -1 3623 -1 3624 -1 3625 -1 3626 -1 3627 -1 3628 -1 3629 -1 3630 -1 3631 -1 3632 -1 3633 -1 3634 -1 3635 -1 3636 -1 3637 -1 3638 -1 3639 -1 3640 -1 3641 -1 3642 -1 3643 -1 3644 -1 3645 -1 3646 -1 3647 -1 3648 -1 3649 -1 3650 -1 3651 -1 3652 -1 3653 -1 3654 -1 3655 -1 3656 -1 3657 -1 3658 -1 3659 -1 3660 -1 3661 -1 3662 -1 3663 -1 3664 -1 3665 -1 3666 -1 3667 -1 3668 -1 3669 -1 3670 -1 3671 -1 3672 -1 3673 -1 3674 -1 3675 -1 3676 -1 3677 -1 3678 -1 3679 -1 3680 -1 3681 -1 3682 -1 3683 -1 3684 -1 3685 -1 3686 -1 3687 -1 3688 -1 3689 -1 3690 -1 3691 -1 3692 -1 3693 -1 3694 -1 3695 -1 3696 -1 3697 -1 3698 -1 3699 -1 3700 -1 3701 -1 3702 -1 3703 -1 3704 -1 3705 -1 3706 -1 3707 -1 3708 -1 3709 -1 3710 -1 3711 -1 3712 -1 3713 -1 3714 -1 3715 -1 3716 -1 3717 -1 3718 -1 3719 -1 3720 -1 3721 -1 3722 -1 3723 -1 3724 -1 3725 -1 3726 -1 3727 -1 3728 -1 3729 -1 3730 -1 3731 -1 3732 -1 3733 -1 3734 -1 3735 -1 3736 -1 3737 -1 3738 -1 3739 -1 3740 -1 3741 -1 3742 -1 3743 -1 3744 -1 3745 -1 3746 -1 3747 -1 3748 -1 3749 -1 3750 -1 3751 -1 3752 -1 3753 -1 3754 -1 3755 -1 3756 -1 3757 -1 3758 -1 3759 -1 3760 -1 3761 -1 3762 -1 3763 -1 3764 -1 3765 -1 3766 -1 3767 -1 3768 -1 3769 -1 3770 -1 3771 -1 3772 -1 3773 -1 3774 -1 3775 -1 3776 -1 3777 -1 3778 -1 3779 -1 3780 -1 3781 -1 3782 -1 3783 -1 3784 -1 3785 -1 3786 -1 3787 -1 3788 -1 3789 -1 3790 -1 3791 -1 3792 -1 3793 -1 3794 -1 3795 -1 3796 -1 3797 -1 3798 -1 3799 -1 3800 -1 3801 -1 3802 -1 3803 -1 3804 -1 3805 -1 3806 -1 3807 -1 3808 -1 3809 -1 3810 -1 3811 -1 3812 -1 3813 -1 3814 -1 3815 -1 3816 -1 3817 -1 3818 -1 3819 -1 3820 -1 3821 -1 3822 -1 3823 -1 3824 -1 3825 -1 3826 -1 3827 -1 3828 -1 3829 -1 3830 -1 3831 -1 3832 -1 3833 -1 3834 -1 3835 -1 3836 -1 3837 -1 3838 -1 3839 -1 3840 -1 3841 -1 3842 -1 3843 -1 3844 -1 3845 -1 3846 -1 3847 -1 3848 -1 3849 -1 3850 -1 3851 -1 3852 -1 3853 -1 3854 -1 3855 -1 3856 -1 3857 -1 3858 -1 3859 -1 3860 -1 3861 -1 3862 -1 3863 -1 3864 -1 3865 -1 3866 -1 3867 -1 3868 -1 3869 -1 3870 -1 3871 -1 3872 -1 3873 -1 3874 -1 3875 -1 3876 -1 3877 -1 3878 -1 3879 -1 3880 -1 3881 -1 3882 -1 3883 -1 3884 -1 3885 -1 3886 -1 3887 -1 3888 -1 3889 -1 3890 -1 3891 -1 3892 -1 3893 -1 3894 -1 3895 -1 3896 -1 3897 -1 3898 -1 3899 -1 3900 -1 3901 -1 3902 -1 3903 -1 3904 -1 3905 -1 3906 -1 3907 -1 3908 -1 3909 -1 3910 -1 3911 -1 3912 -1 3913 -1 3914 -1 3915 -1 3916 -1 3917 -1 3918 -1 3919 -1 3920 -1 3921 -1 3922 -1 3923 -1 3924 -1 3925 -1 3926 -1 3927 -1 3928 -1 3929 -1 3930 -1 3931 -1 3932 -1 3933 -1 3934 -1 3935 -1 3936 -1 3937 -1 3938 -1 3939 -1 3940 -1 3941 -1 3942 -1 3943 -1 3944 -1 3945 -1 3946 -1 3947 -1 3948 -1 3949 -1 3950 -1 3951 -1 3952 -1 3953 -1 3954 -1 3955 -1 3956 -1 3957 -1 3958 -1 3959 -1 3960 -1 3961 -1 3962 -1 3963 -1 3964 -1 3965 -1 3966 -1 3967 -1 3968 -1 3969 -1 3970 -1 3971 -1 3972 -1 3973 -1 3974 -1 3975 -1 3976 -1 3977 -1 3978 -1 3979 -1 3980 -1 3981 -1 3982 -1 3983 -1 3984 -1 3985 -1 3986 -1 3987 -1 3988 -1 3989 -1 3990 -1 3991 -1 3992 -1 3993 -1 3994 -1 3995 -1 3996 -1 3997 -1 3998 -1 3999 -1 4000 -1 4001 -1 4002 -1 4003 -1 4004 -1 4005 -1 4006 -1 4007 -1 4008 -1 4009 -1 4010 -1 4011 -1 4012 -1 4013 -1 4014 -1 4015 -1 4016 -1 4017 -1 4018 -1 4019 -1 4020 -1 4021 -1 4022 -1 4023 -1 4024 -1 4025 -1 4026 -1 4027 -1 4028 -1 4029 -1 4030 -1 4031 -1 4032 -1 4033 -1 4034 -1 4035 -1 4036 -1 4037 -1 4038 -1 4039 -1 4040 -1 4041 -1 4042 -1 4043 -1 4044 -1 4045 -1 4046 -1 4047 -1 4048 -1 4049 -1 4050 -1 4051 -1 4052 -1 4053 -1 4054 -1 4055 -1 4056 -1 4057 -1 4058 -1 4059 -1 4060 -1 4061 -1 4062 -1 4063 -1 4064 -1 4065 -1 4066 -1 4067 -1 4068 -1 4069 -1 4070 -1 4071 -1 4072 -1 4073 -1 4074 -1 4075 -1 4076 -1 4077 -1 4078 -1 4079 -1 4080 -1 4081 -1 4082 -1 4083 -1 4084 -1 4085 -1 4086 -1 4087 -1 4088 -1 4089 -1 4090 -1 4091 -1 4092 -1 4093 -1 4094 -1 4095 -1 4096 -1 4097 -1 4098 -1 4099 -1 4100 -1 4101 -1 4102 -1 4103 -1 4104 -1 4105 -1 4106 -1 4107 -1 4108 -1 4109 -1 4110 -1 4111 -1 4112 -1 4113 -1 4114 -1 4115 -1 4116 -1 4117 -1 4118 -1 4119 -1 4120 -1 4121 -1 4122 -1 4123 -1 4124 -1 4125 -1 4126 -1 4127 -1 4128 -1 4129 -1 4130 -1 4131 -1 4132 -1 4133 -1 4134 -1 4135 -1 4136 -1 4137 -1 4138 -1 4139 -1 4140 -1 4141 -1 4142 -1 4143 -1 4144 -1 4145 -1 4146 -1 4147 -1 4148 -1 4149 -1 4150 -1 4151 -1 4152 -1 4153 -1 4154 -1 4155 -1 4156 -1 4157 -1 4158 -1 4159 -1 4160 -1 4161 -1 4162 -1 4163 -1 4164 -1 4165 -1 4166 -1 4167 -1 4168 -1 4169 -1 4170 -1 4171 -1 4172 -1 4173 -1 4174 -1 4175 -1 4176 -1 4177 -1 4178 -1 4179 -1 4180 -1 4181 -1 4182 -1 4183 -1 4184 -1 4185 -1 4186 -1 4187 -1 4188 -1 4189 -1 4190 -1 4191 -1 4192 -1 4193 -1 4194 -1 4195 -1 4196 -1 4197 -1 4198 -1 4199 -1 4200 -1 4201 -1 4202 -1 4203 -1 4204 -1 4205 -1 4206 -1 4207 -1 4208 -1 4209 -1 4210 -1 4211 -1 4212 -1 4213 -1 4214 -1 4215 -1 4216 -1 4217 -1 4218 -1 4219 -1 4220 -1 4221 -1 4222 -1 4223 -1 4224 -1 4225 -1 4226 -1 4227 -1 4228 -1 4229 -1 4230 -1 4231 -1 4232 -1 4233 -1 4234 -1 4235 -1 4236 -1 4237 -1 4238 -1 4239 -1 4240 -1 4241 -1 4242 -1 4243 -1 4244 -1 4245 -1 4246 -1 4247 -1 4248 -1 4249 -1 4250 -1 4251 -1 4252 -1 4253 -1 4254 -1 4255 -1 4256 -1 4257 -1 4258 -1 4259 -1 4260 -1 4261 -1 4262 -1 4263 -1 4264 -1 4265 -1 4266 -1 4267 -1 4268 -1 4269 -1 4270 -1 4271 -1 4272 -1 4273 -1 4274 -1 4275 -1 4276 -1 4277 -1 4278 -1 4279 -1 4280 -1 4281 -1 4282 -1 4283 -1 4284 -1 4285 -1 4286 -1 4287 -1 4288 -1 4289 -1 4290 -1 4291 -1 4292 -1 4293 -1 4294 -1 4295 -1 4296 -1 4297 -1 4298 -1 4299 -1 4300 -1 4301 -1 4302 -1 4303 -1 4304 -1 4305 -1 4306 -1 4307 -1 4308 -1 4309 -1 4310 -1 4311 -1 4312 -1 4313 -1 4314 -1 4315 -1 4316 -1 4317 -1 4318 -1 4319 -1 4320 -1 4321 -1 4322 -1 4323 -1 4324 -1 4325 -1 4326 -1 4327 -1 4328 -1 4329 -1 4330 -1 4331 -1 4332 -1 4333 -1 4334 -1 4335 -1 4336 -1 4337 -1 4338 -1 4339 -1 4340 -1 4341 -1 4342 -1 4343 -1 4344 -1 4345 -1 4346 -1 4347 -1 4348 -1 4349 -1 4350 -1 4351 -1 4352 -1 4353 -1 4354 -1 4355 -1 4356 -1 4357 -1 4358 -1 4359 -1 4360 -1 4361 -1 4362 -1 4363 -1 4364 -1 4365 -1 4366 -1 4367 -1 4368 -1 4369 -1 4370 -1 4371 -1 4372 -1 4373 -1 4374 -1 4375 -1 4376 -1 4377 -1 4378 -1 4379 -1 4380 -1 4381 -1 4382 -1 4383 -1 4384 -1 4385 -1 4386 -1 4387 -1 4388 -1 4389 -1 4390 -1 4391 -1 4392 -1 4393 -1 4394 -1 4395 -1 4396 -1 4397 -1 4398 -1 4399 -1 4400 -1 4401 -1 4402 -1 4403 -1 4404 -1 4405 -1 4406 -1 4407 -1 4408 -1 4409 -1 4410 -1 4411 -1 4412 -1 4413 -1 4414 -1 4415 -1 4416 -1 4417 -1 4418 -1 4419 -1 4420 -1 4421 -1 4422 -1 4423 -1 4424 -1 4425 -1 4426 -1 4427 -1 4428 -1 4429 -1 4430 -1 4431 -1 4432 -1 4433 -1 4434 -1 4435 -1 4436 -1 4437 -1 4438 -1 4439 -1 4440 -1 4441 -1 4442 -1 4443 -1 4444 -1 4445 -1 4446 -1 4447 -1 4448 -1 4449 -1 4450 -1 4451 -1 4452 -1 4453 -1 4454 -1 4455 -1 4456 -1 4457 -1 4458 -1 4459 -1 4460 -1 4461 -1 4462 -1 4463 -1 4464 -1 4465 -1 4466 -1 4467 -1 4468 -1 4469 -1 4470 -1 4471 -1 4472 -1 4473 -1 4474 -1 4475 -1 4476 -1 4477 -1 4478 -1 4479 -1 4480 -1 4481 -1 4482 -1 4483 -1 4484 -1 4485 -1 4486 -1 4487 -1 4488 -1 4489 -1 4490 -1 4491 -1 4492 -1 4493 -1 4494 -1 4495 -1 4496 -1 4497 -1 4498 -1 4499 -1 4500 -1 4501 -1 4502 -1 4503 -1 4504 -1 4505 -1 4506 -1 4507 -1 4508 -1 4509 -1 4510 -1 4511 -1 4512 -1 4513 -1 4514 -1 4515 -1 4516 -1 4517 -1 4518 -1 4519 -1 4520 -1 4521 -1 4522 -1 4523 -1 4524 -1 4525 -1 4526 -1 4527 -1 4528 -1 4529 -1 4530 -1 4531 -1 4532 -1 4533 -1 4534 -1 4535 -1 4536 -1 4537 -1 4538 -1 4539 -1 4540 -1 4541 -1 4542 -1 4543 -1 4544 -1 4545 -1 4546 -1 4547 -1 4548 -1 4549 -1 4550 -1 4551 -1 4552 -1 4553 -1 4554 -1 4555 -1 4556 -1 4557 -1 4558 -1 4559 -1 4560 -1 4561 -1 4562 -1 4563 -1 4564 -1 4565 -1 4566 -1 4567 -1 4568 -1 4569 -1 4570 -1 4571 -1 4572 -1 4573 -1 4574 -1 4575 -1 4576 -1 4577 -1 4578 -1 4579 -1 4580 -1 4581 -1 4582 -1 4583 -1 4584 -1 4585 -1 4586 -1 4587 -1 4588 -1 4589 -1 4590 -1 4591 -1 4592 -1 4593 -1 4594 -1 4595 -1 4596 -1 4597 -1 4598 -1 4599 -1 4600 -1 4601 -1 4602 -1 4603 -1 4604 -1 4605 -1 4606 -1 4607 -1 4608 -1 4609 -1 4610 -1 4611 -1 4612 -1 4613 -1 4614 -1 4615 -1 4616 -1 4617 -1 4618 -1 4619 -1 4620 -1 4621 -1 4622 -1 4623 -1 4624 -1 4625 -1 4626 -1 4627 -1 4628 -1 4629 -1 4630 -1 4631 -1 4632 -1 4633 -1 4634 -1 4635 -1 4636 -1 4637 -1 4638 -1 4639 -1 4640 -1 4641 -1 4642 -1 4643 -1 4644 -1 4645 -1 4646 -1 4647 -1 4648 -1 4649 -1 4650 -1 4651 -1 4652 -1 4653 -1 4654 -1 4655 -1 4656 -1 4657 -1 4658 -1 4659 -1 4660 -1 4661 -1 4662 -1 4663 -1 4664 -1 4665 -1 4666 -1 4667 -1 4668 -1 4669 -1 4670 -1 4671 -1 4672 -1 4673 -1 4674 -1 4675 -1 4676 -1 4677 -1 4678 -1 4679 -1 4680 -1 4681 -1 4682 -1 4683 -1 4684 -1 4685 -1 4686 -1 4687 -1 4688 -1 4689 -1 4690 -1 4691 -1 4692 -1 4693 -1 4694 -1 4695 -1 4696 -1 4697 -1 4698 -1 4699 -1 4700 -1 4701 -1 4702 -1 4703 -1 4704 -1 4705 -1 4706 -1 4707 -1 4708 -1 4709 -1 4710 -1 4711 -1 4712 -1 4713 -1 4714 -1 4715 -1 4716 -1 4717 -1 4718 -1 4719 -1 4720 -1 4721 -1 4722 -1 4723 -1 4724 -1 4725 -1 4726 -1 4727 -1 4728 -1 4729 -1 4730 -1 4731 -1 4732 -1 4733 -1 4734 -1 4735 -1 4736 -1 4737 -1 4738 -1 4739 -1 4740 -1 4741 -1 4742 -1 4743 -1 4744 -1 4745 -1 4746 -1 4747 -1 4748 -1 4749 -1 4750 -1 4751 -1 4752 -1 4753 -1 4754 -1 4755 -1 4756 -1 4757 -1 4758 -1 4759 -1 4760 -1 4761 -1 4762 -1 4763 -1 4764 -1 4765 -1 4766 -1 4767 -1 4768 -1 4769 -1 4770 -1 4771 -1 4772 -1 4773 -1 4774 -1 4775 -1 4776 -1 4777 -1 4778 -1 4779 -1 4780 -1 4781 -1 4782 -1 4783 -1 4784 -1 4785 -1 4786 -1 4787 -1 4788 -1 4789 -1 4790 -1 4791 -1 4792 -1 4793 -1 4794 -1 4795 -1 4796 -1 4797 -1 4798 -1 4799 -1 4800 -1 4801 -1 4802 -1 4803 -1 4804 -1 4805 -1 4806 -1 4807 -1 4808 -1 4809 -1 4810 -1 4811 -1 4812 -1 4813 -1 4814 -1 4815 -1 4816 -1 4817 -1 4818 -1 4819 -1 4820 -1 4821 -1 4822 -1 4823 -1 4824 -1 4825 -1 4826 -1 4827 -1 4828 -1 4829 -1 4830 -1 4831 -1 4832 -1 4833 -1 4834 -1 4835 -1 4836 -1 4837 -1 4838 -1 4839 -1 4840 -1 4841 -1 4842 -1 4843 -1 4844 -1 4845 -1 4846 -1 4847 -1 4848 -1 4849 -1 4850 -1 4851 -1 4852 -1 4853 -1 4854 -1 4855 -1 4856 -1 4857 -1 4858 -1 4859 -1 4860 -1 4861 -1 4862 -1 4863 -1 4864 -1 4865 -1 4866 -1 4867 -1 4868 -1 4869 -1 4870 -1 4871 -1 4872 -1 4873 -1 4874 -1 4875 -1 4876 -1 4877 -1 4878 -1 4879 -1 4880 -1 4881 -1 4882 -1 4883 -1 4884 -1 4885 -1 4886 -1 4887 -1 4888 -1 4889 -1 4890 -1 4891 -1 4892 -1 4893 -1 4894 -1 4895 -1 4896 -1 4897 -1 4898 -1 4899 -1 4900 -1 4901 -1 4902 -1 4903 -1 4904 -1 4905 -1 4906 -1 4907 -1 4908 -1 4909 -1 4910 -1 4911 -1 4912 -1 4913 -1 4914 -1 4915 -1 4916 -1 4917 -1 4918 -1 4919 -1 4920 -1 4921 -1 4922 -1 4923 -1 4924 -1 4925 -1 4926 -1 4927 -1 4928 -1 4929 -1 4930 -1 4931 -1 4932 -1 4933 -1 4934 -1 4935 -1 4936 -1 4937 -1 4938 -1 4939 -1 4940 -1 4941 -1 4942 -1 4943 -1 4944 -1 4945 -1 4946 -1 4947 -1 4948 -1 4949 -1 4950 -1 4951 -1 4952 -1 4953 -1 4954 -1 4955 -1 4956 -1 4957 -1 4958 -1 4959 -1 4960 -1 4961 -1 4962 -1 4963 -1 4964 -1 4965 -1 4966 -1 4967 -1 4968 -1 4969 -1 4970 -1 4971 -1 4972 -1 4973 -1 4974 -1 4975 -1 4976 -1 4977 -1 4978 -1 4979 -1 4980 -1 4981 -1 4982 -1 4983 -1 4984 -1 4985 -1 4986 -1 4987 -1 4988 -1 4989 -1 4990 -1 4991 -1 4992 -1 4993 -1 4994 -1 4995 -1 4996 -1 4997 -1 4998 -1 4999 -1 5000 -1 5001 -1 5002 -1 5003 -1 5004 -1 5005 -1 5006 -1 5007 -1 5008 -1 5009 -1 5010 -1 5011 -1 5012 -1 5013 -1 5014 -1 5015 -1 5016 -1 5017 -1 5018 -1 5019 -1 5020 -1 5021 -1 5022 -1 5023 -1 5024 -1 5025 -1 5026 -1 5027 -1 5028 -1 5029 -1 5030 -1 5031 -1 5032 -1 5033 -1 5034 -1 5035 -1 5036 -1 5037 -1 5038 -1 5039 -1 5040 -1 5041 -1 5042 -1 5043 -1 5044 -1 5045 -1 5046 -1 5047 -1 5048 -1 5049 -1 5050 -1 5051 -1 5052 -1 5053 -1 5054 -1 5055 -1 5056 -1 5057 -1 5058 -1 5059 -1 5060 -1 5061 -1 5062 -1 5063 -1 5064 -1 5065 -1 5066 -1 5067 -1 5068 -1 5069 -1 5070 -1 5071 -1 5072 -1 5073 -1 5074 -1 5075 -1 5076 -1 5077 -1 5078 -1 5079 -1 5080 -1 5081 -1 5082 -1 5083 -1 5084 -1 5085 -1 5086 -1 5087 -1 5088 -1 5089 -1 5090 -1 5091 -1 5092 -1 5093 -1 5094 -1 5095 -1 5096 -1 5097 -1 5098 -1 5099 -1 5100 -1 5101 -1 5102 -1 5103 -1 5104 -1 5105 -1 5106 -1 5107 -1 5108 -1 5109 -1 5110 -1 5111 -1 5112 -1 5113 -1 5114 -1 5115 -1 5116 -1 5117 -1 5118 -1 5119 -1 5120 -1 5121 -1 5122 -1 5123 -1 5124 -1 5125 -1 5126 -1 5127 -1 5128 -1 5129 -1 5130 -1 5131 -1 5132 -1 5133 -1 5134 -1 5135 -1 5136 -1 5137 -1 5138 -1 5139 -1 5140 -1 5141 -1 5142 -1 5143 -1 5144 -1 5145 -1 5146 -1 5147 -1 5148 -1 5149 -1 5150 -1 5151 -1 5152 -1 5153 -1 5154 -1 5155 -1 5156 -1 5157 -1 5158 -1 5159 -1 5160 -1 5161 -1 5162 -1 5163 -1 5164 -1 5165 -1 5166 -1 5167 -1 5168 -1 5169 -1 5170 -1 5171 -1 5172 -1 5173 -1 5174 -1 5175 -1 5176 -1 5177 -1 5178 -1 5179 -1 5180 -1 5181 -1 5182 -1 5183 -1 5184 -1 5185 -1 5186 -1 5187 -1 5188 -1 5189 -1 5190 -1 5191 -1 5192 -1 5193 -1 5194 -1 5195 -1 5196 -1 5197 -1 5198 -1 5199 -1 5200 -1 5201 -1 5202 -1 5203 -1 5204 -1 5205 -1 5206 -1 5207 -1 5208 -1 5209 -1 5210 -1 5211 -1 5212 -1 5213 -1 5214 -1 5215 -1 5216 -1 5217 -1 5218 -1 5219 -1 5220 -1 5221 -1 5222 -1 5223 -1 5224 -1 5225 -1 5226 -1 5227 -1 5228 -1 5229 -1 5230 -1 5231 -1 5232 -1 5233 -1 5234 -1 5235 -1 5236 -1 5237 -1 5238 -1 5239 -1 5240 -1 5241 -1 5242 -1 5243 -1 5244 -1 5245 -1 5246 -1 5247 -1 5248 -1 5249 -1 5250 -1 5251 -1 5252 -1 5253 -1 5254 -1 5255 -1 5256 -1 5257 -1 5258 -1 5259 -1 5260 -1 5261 -1 5262 -1 5263 -1 5264 -1 5265 -1 5266 -1 5267 -1 5268 -1 5269 -1 5270 -1 5271 -1 5272 -1 5273 -1 5274 -1 5275 -1 5276 -1 5277 -1 5278 -1 5279 -1 5280 -1 5281 -1 5282 -1 5283 -1 5284 -1 5285 -1 5286 -1 5287 -1 5288 -1 5289 -1 5290 -1 5291 -1 5292 -1 5293 -1 5294 -1 5295 -1 5296 -1 5297 -1 5298 -1 5299 -1 5300 -1 5301 -1 5302 -1 5303 -1 5304 -1 5305 -1 5306 -1 5307 -1 5308 -1 5309 -1 5310 -1 5311 -1 5312 -1 5313 -1 5314 -1 5315 -1 5316 -1 5317 -1 5318 -1 5319 -1 5320 -1 5321 -1 5322 -1 5323 -1 5324 -1 5325 -1 5326 -1 5327 -1 5328 -1 5329 -1 5330 -1 5331 -1 5332 -1 5333 -1 5334 -1 5335 -1 5336 -1 5337 -1 5338 -1 5339 -1 5340 -1 5341 -1 5342 -1 5343 -1 5344 -1 5345 -1 5346 -1 5347 -1 5348 -1 5349 -1 5350 -1 5351 -1 5352 -1 5353 -1 5354 -1 5355 -1 5356 -1 5357 -1 5358 -1 5359 -1 5360 -1 5361 -1 5362 -1 5363 -1 5364 -1 5365 -1 5366 -1 5367 -1 5368 -1 5369 -1 5370 -1 5371 -1 5372 -1 5373 -1 5374 -1 5375 -1 5376 -1 5377 -1 5378 -1 5379 -1 5380 -1 5381 -1 5382 -1 5383 -1 5384 -1 5385 -1 5386 -1 5387 -1 5388 -1 5389 -1 5390 -1 5391 -1 5392 -1 5393 -1 5394 -1 5395 -1 5396 -1 5397 -1 5398 -1 5399 -1 5400 -1 5401 -1 5402 -1 5403 -1 5404 -1 5405 -1 5406 -1 5407 -1 5408 -1 5409 -1 5410 -1 5411 -1 5412 -1 5413 -1 5414 -1 5415 -1 5416 -1 5417 -1 5418 -1 5419 -1 5420 -1 5421 -1 5422 -1 5423 -1 5424 -1 5425 -1 5426 -1 5427 -1 5428 -1 5429 -1 5430 -1 5431 -1 5432 -1 5433 -1 5434 -1 5435 -1 5436 -1 5437 -1 5438 -1 5439 -1 5440 -1 5441 -1 5442 -1 5443 -1 5444 -1 5445 -1 5446 -1 5447 -1 5448 -1 5449 -1 5450 -1 5451 -1 5452 -1 5453 -1 5454 -1 5455 -1 5456 -1 5457 -1 5458 -1 5459 -1 5460 -1 5461 -1 5462 -1 5463 -1 5464 -1 5465 -1 5466 -1 5467 -1 5468 -1 5469 -1 5470 -1 5471 -1 5472 -1 5473 -1 5474 -1 5475 -1 5476 -1 5477 -1 5478 -1 5479 -1 5480 -1 5481 -1 5482 -1 5483 -1 5484 -1 5485 -1 5486 -1 5487 -1 5488 -1 5489 -1 5490 -1 5491 -1 5492 -1 5493 -1 5494 -1 5495 -1 5496 -1 5497 -1 5498 -1 5499 -1 5500 -1 5501 -1 5502 -1 5503 -1 5504 -1 5505 -1 5506 -1 5507 -1 5508 -1 5509 -1 5510 -1 5511 -1 5512 -1 5513 -1 5514 -1 5515 -1 5516 -1 5517 -1 5518 -1 5519 -1 5520 -1 5521 -1 5522 -1 5523 -1 5524 -1 5525 -1 5526 -1 5527 -1 5528 -1 5529 -1 5530 -1 5531 -1 5532 -1 5533 -1 5534 -1 5535 -1 5536 -1 5537 -1 5538 -1 5539 -1 5540 -1 5541 -1 5542 -1 5543 -1 5544 -1 5545 -1 5546 -1 5547 -1 5548 -1 5549 -1 5550 -1 5551 -1 5552 -1 5553 -1 5554 -1 5555 -1 5556 -1 5557 -1 5558 -1 5559 -1 5560 -1 5561 -1 5562 -1 5563 -1 5564 -1 5565 -1 5566 -1 5567 -1 5568 -1 5569 -1 5570 -1 5571 -1 5572 -1 5573 -1 5574 -1 5575 -1 5576 -1 5577 -1 5578 -1 5579 -1 5580 -1 5581 -1 5582 -1 5583 -1 5584 -1 5585 -1 5586 -1 5587 -1 5588 -1 5589 -1 5590 -1 5591 -1 5592 -1 5593 -1 5594 -1 5595 -1 5596 -1 5597 -1 5598 -1 5599 -1 5600 -1 5601 -1 5602 -1 5603 -1 5604 -1 5605 -1 5606 -1 5607 -1 5608 -1 5609 -1 5610 -1 5611 -1 5612 -1 5613 -1 5614 -1 5615 -1 5616 -1 5617 -1 5618 -1 5619 -1 5620 -1 5621 -1 5622 -1 5623 -1 5624 -1 5625 -1 5626 -1 5627 -1 5628 -1 5629 -1 5630 -1 5631 -1 5632 -1 5633 -1 5634 -1 5635 -1 5636 -1 5637 -1 5638 -1 5639 -1 5640 -1 5641 -1 5642 -1 5643 -1 5644 -1 5645 -1 5646 -1 5647 -1 5648 -1 5649 -1 5650 -1 5651 -1 5652 -1 5653 -1 5654 -1 5655 -1 5656 -1 5657 -1 5658 -1 5659 -1 5660 -1 5661 -1 5662 -1 5663 -1 5664 -1 5665 -1 5666 -1 5667 -1 5668 -1 5669 -1 5670 -1 5671 -1 5672 -1 5673 -1 5674 -1 5675 -1 5676 -1 5677 -1 5678 -1 5679 -1 5680 -1 5681 -1 5682 -1 5683 -1 5684 -1 5685 -1 5686 -1 5687 -1 5688 -1 5689 -1 5690 -1 5691 -1 5692 -1 5693 -1 5694 -1 5695 -1 5696 -1 5697 -1 5698 -1 5699 -1 5700 -1 5701 -1 5702 -1 5703 -1 5704 -1 5705 -1 5706 -1 5707 -1 5708 -1 5709 -1 5710 -1 5711 -1 5712 -1 5713 -1 5714 -1 5715 -1 5716 -1 5717 -1 5718 -1 5719 -1 5720 -1 5721 -1 5722 -1 5723 -1 5724 -1 5725 -1 5726 -1 5727 -1 5728 -1 5729 -1 5730 -1 5731 -1 5732 -1 5733 -1 5734 -1 5735 -1 5736 -1 5737 -1 5738 -1 5739 -1 5740 -1 5741 -1 5742 -1 5743 -1 5744 -1 5745 -1 5746 -1 5747 -1 5748 -1 5749 -1 5750 -1 5751 -1 5752 -1 5753 -1 5754 -1 5755 -1 5756 -1 5757 -1 5758 -1 5759 -1 5760 -1 5761 -1 5762 -1 5763 -1 5764 -1 5765 -1 5766 -1 5767 -1 5768 -1 5769 -1 5770 -1 5771 -1 5772 -1 5773 -1 5774 -1 5775 -1 5776 -1 5777 -1 5778 -1 5779 -1 5780 -1 5781 -1 5782 -1 5783 -1 5784 -1 5785 -1 5786 -1 5787 -1 5788 -1 5789 -1 5790 -1 5791 -1 5792 -1 5793 -1 5794 -1 5795 -1 5796 -1 5797 -1 5798 -1 5799 -1 5800 -1 5801 -1 5802 -1 5803 -1 5804 -1 5805 -1 5806 -1 5807 -1 5808 -1 5809 -1 5810 -1 5811 -1 5812 -1 5813 -1 5814 -1 5815 -1 5816 -1 5817 -1 5818 -1 5819 -1 5820 -1 5821 -1 5822 -1 5823 -1 5824 -1 5825 -1 5826 -1 5827 -1 5828 -1 5829 -1 5830 -1 5831 -1 5832 -1 5833 -1 5834 -1 5835 -1 5836 -1 5837 -1 5838 -1 5839 -1 5840 -1 5841 -1 5842 -1 5843 -1 5844 -1 5845 -1 5846 -1 5847 -1 5848 -1 5849 -1 5850 -1 5851 -1 5852 -1 5853 -1 5854 -1 5855 -1 5856 -1 5857 -1 5858 -1 5859 -1 5860 -1 5861 -1 5862 -1 5863 -1 5864 -1 5865 -1 5866 -1 5867 -1 5868 -1 5869 -1 5870 -1 5871 -1 5872 -1 5873 -1 5874 -1 5875 -1 5876 -1 5877 -1 5878 -1 5879 -1 5880 -1 5881 -1 5882 -1 5883 -1 5884 -1 5885 -1 5886 -1 5887 -1 5888 -1 5889 -1 5890 -1 5891 -1 5892 -1 5893 -1 5894 -1 5895 -1 5896 -1 5897 -1 5898 -1 5899 -1 5900 -1 5901 -1 5902 -1 5903 -1 5904 -1 5905 -1 5906 -1 5907 -1 5908 -1 5909 -1 5910 -1 5911 -1 5912 -1 5913 -1 5914 -1 5915 -1 5916 -1 5917 -1 5918 -1 5919 -1 5920 -1 5921 -1 5922 -1 5923 -1 5924 -1 5925 -1 5926 -1 5927 -1 5928 -1 5929 -1 5930 -1 5931 -1 5932 -1 5933 -1 5934 -1 5935 -1 5936 -1 5937 -1 5938 -1 5939 -1 5940 -1 5941 -1 5942 -1 5943 -1 5944 -1 5945 -1 5946 -1 5947 -1 5948 -1 5949 -1 5950 -1 5951 -1 5952 -1 5953 -1 5954 -1 5955 -1 5956 -1 5957 -1 5958 -1 5959 -1 5960 -1 5961 -1 5962 -1 5963 -1 5964 -1 5965 -1 5966 -1 5967 -1 5968 -1 5969 -1 5970 -1 5971 -1 5972 -1 5973 -1 5974 -1 5975 -1 5976 -1 5977 -1 5978 -1 5979 -1 5980 -1 5981 -1 5982 -1 5983 -1 5984 -1 5985 -1 5986 -1 5987 -1 5988 -1 5989 -1 5990 -1 5991 -1 5992 -1 5993 -1 5994 -1 5995 -1 5996 -1 5997 -1 5998 -1 5999 -1 6000 -1 6001 -1 6002 -1 6003 -1 6004 -1 6005 -1 6006 -1 6007 -1 6008 -1 6009 -1 6010 -1 6011 -1 6012 -1 6013 -1 6014 -1 6015 -1 6016 -1 6017 -1 6018 -1 6019 -1 6020 -1 6021 -1 6022 -1 6023 -1 6024 -1 6025 -1 6026 -1 6027 -1 6028 -1 6029 -1 6030 -1 6031 -1 6032 -1 6033 -1 6034 -1 6035 -1 6036 -1 6037 -1 6038 -1 6039 -1 6040 -1 6041 -1 6042 -1 6043 -1 6044 -1 6045 -1 6046 -1 6047 -1 6048 -1 6049 -1 6050 -1 6051 -1 6052 -1 6053 -1 6054 -1 6055 -1 6056 -1 6057 -1 6058 -1 6059 -1 6060 -1 6061 -1 6062 -1 6063 -1 6064 -1 6065 -1 6066 -1 6067 -1 6068 -1 6069 -1 6070 -1 6071 -1 6072 -1 6073 -1 6074 -1 6075 -1 6076 -1 6077 -1 6078 -1 6079 -1 6080 -1 6081 -1 6082 -1 6083 -1 6084 -1 6085 -1 6086 -1 6087 -1 6088 -1 6089 -1 6090 -1 6091 -1 6092 -1 6093 -1 6094 -1 6095 -1 6096 -1 6097 -1 6098 -1 6099 -1 6100 -1 6101 -1 6102 -1 6103 -1 6104 -1 6105 -1 6106 -1 6107 -1 6108 -1 6109 -1 6110 -1 6111 -1 6112 -1 6113 -1 6114 -1 6115 -1 6116 -1 6117 -1 6118 -1 6119 -1 6120 -1 6121 -1 6122 -1 6123 -1 6124 -1 6125 -1 6126 -1 6127 -1 6128 -1 6129 -1 6130 -1 6131 -1 6132 -1 6133 -1 6134 -1 6135 -1 6136 -1 6137 -1 6138 -1 6139 -1 6140 -1 6141 -1 6142 -1 6143 -1 6144 -1 6145 -1 6146 -1 6147 -1 6148 -1 6149 -1 6150 -1 6151 -1 6152 -1 6153 -1 6154 -1 6155 -1 6156 -1 6157 -1 6158 -1 6159 -1 6160 -1 6161 -1 6162 -1 6163 -1 6164 -1 6165 -1 6166 -1 6167 -1 6168 -1 6169 -1 6170 -1 6171 -1 6172 -1 6173 -1 6174 -1 6175 -1 6176 -1 6177 -1 6178 -1 6179 -1 6180 -1 6181 -1 6182 -1 6183 -1 6184 -1 6185 -1 6186 -1 6187 -1 6188 -1 6189 -1 6190 -1 6191 -1 6192 -1 6193 -1 6194 -1 6195 -1 6196 -1 6197 -1 6198 -1 6199 -1 6200 -1 6201 -1 6202 -1 6203 -1 6204 -1 6205 -1 6206 -1 6207 -1 6208 -1 6209 -1 6210 -1 6211 -1 6212 -1 6213 -1 6214 -1 6215 -1 6216 -1 6217 -1 6218 -1 6219 -1 6220 -1 6221 -1 6222 -1 6223 -1 6224 -1 6225 -1 6226 -1 6227 -1 6228 -1 6229 -1 6230 -1 6231 -1 6232 -1 6233 -1 6234 -1 6235 -1 6236 -1 6237 -1 6238 -1 6239 -1 6240 -1 6241 -1 6242 -1 6243 -1 6244 -1 6245 -1 6246 -1 6247 -1 6248 -1 6249 -1 6250 -1 6251 -1 6252 -1 6253 -1 6254 -1 6255 -1 6256 -1 6257 -1 6258 -1 6259 -1 6260 -1 6261 -1 6262 -1 6263 -1 6264 -1 6265 -1 6266 -1 6267 -1 6268 -1 6269 -1 6270 -1 6271 -1 6272 -1 6273 -1 6274 -1 6275 -1 6276 -1 6277 -1 6278 -1 6279 -1 6280 -1 6281 -1 6282 -1 6283 -1 6284 -1 6285 -1 6286 -1 6287 -1 6288 -1 6289 -1 6290 -1 6291 -1 6292 -1 6293 -1 6294 -1 6295 -1 6296 -1 6297 -1 6298 -1 6299 -1 6300 -1 6301 -1 6302 -1 6303 -1 6304 -1 6305 -1 6306 -1 6307 -1 6308 -1 6309 -1 6310 -1 6311 -1 6312 -1 6313 -1 6314 -1 6315 -1 6316 -1 6317 -1 6318 -1 6319 -1 6320 -1 6321 -1 6322 -1 6323 -1 6324 -1 6325 -1 6326 -1 6327 -1 6328 -1 6329 -1 6330 -1 6331 -1 6332 -1 6333 -1 6334 -1 6335 -1 6336 -1 6337 -1 6338 -1 6339 -1 6340 -1 6341 -1 6342 -1 6343 -1 6344 -1 6345 -1 6346 -1 6347 -1 6348 -1 6349 -1 6350 -1 6351 -1 6352 -1 6353 -1 6354 -1 6355 -1 6356 -1 6357 -1 6358 -1 6359 -1 6360 -1 6361 -1 6362 -1 6363 -1 6364 -1 6365 -1 6366 -1 6367 -1 6368 -1 6369 -1 6370 -1 6371 -1 6372 -1 6373 -1 6374 -1 6375 -1 6376 -1 6377 -1 6378 -1 6379 -1 6380 -1 6381 -1 6382 -1 6383 -1 6384 -1 6385 -1 6386 -1 6387 -1 6388 -1 6389 -1 6390 -1 6391 -1 6392 -1 6393 -1 6394 -1 6395 -1 6396 -1 6397 -1 6398 -1 6399 -1 6400 -1 6401 -1 6402 -1 6403 -1 6404 -1 6405 -1 6406 -1 6407 -1 6408 -1 6409 -1 6410 -1 6411 -1 6412 -1 6413 -1 6414 -1 6415 -1 6416 -1 6417 -1 6418 -1 6419 -1 6420 -1 6421 -1 6422 -1 6423 -1 6424 -1 6425 -1 6426 -1 6427 -1 6428 -1 6429 -1 6430 -1 6431 -1 6432 -1 6433 -1 6434 -1 6435 -1 6436 -1 6437 -1 6438 -1 6439 -1 6440 -1 6441 -1 6442 -1 6443 -1 6444 -1 6445 -1 6446 -1 6447 -1 6448 -1 6449 -1 6450 -1 6451 -1 6452 -1 6453 -1 6454 -1 6455 -1 6456 -1 6457 -1 6458 -1 6459 -1 6460 -1 6461 -1 6462 -1 6463 -1 6464 -1 6465 -1 6466 -1 6467 -1 6468 -1 6469 -1 6470 -1 6471 -1 6472 -1 6473 -1 6474 -1 6475 -1 6476 -1 6477 -1 6478 -1 6479 -1 6480 -1 6481 -1 6482 -1 6483 -1 6484 -1 6485 -1 6486 -1 6487 -1 6488 -1 6489 -1 6490 -1 6491 -1 6492 -1 6493 -1 6494 -1 6495 -1 6496 -1 6497 -1 6498 -1 6499 -1 6500 -1 6501 -1 6502 -1 6503 -1 6504 -1 6505 -1 6506 -1 6507 -1 6508 -1 6509 -1 6510 -1 6511 -1 6512 -1 6513 -1 6514 -1 6515 -1 6516 -1 6517 -1 6518 -1 6519 -1 6520 -1 6521 -1 6522 -1 6523 -1 6524 -1 6525 -1 6526 -1 6527 -1 6528 -1 6529 -1 6530 -1 6531 -1 6532 -1 6533 -1 6534 -1 6535 -1 6536 -1 6537 -1 6538 -1 6539 -1 6540 -1 6541 -1 6542 -1 6543 -1 6544 -1 6545 -1 6546 -1 6547 -1 6548 -1 6549 -1 6550 -1 6551 -1 6552 -1 6553 -1 6554 -1 6555 -1 6556 -1 6557 -1 6558 -1 6559 -1 6560 -1 6561 -1 6562 -1 6563 -1 6564 -1 6565 -1 6566 -1 6567 -1 6568 -1 6569 -1 6570 -1 6571 -1 6572 -1 6573 -1 6574 -1 6575 -1 6576 -1 6577 -1 6578 -1 6579 -1 6580 -1 6581 -1 6582 -1 6583 -1 6584 -1 6585 -1 6586 -1 6587 -1 6588 -1 6589 -1 6590 -1 6591 -1 6592 -1 6593 -1 6594 -1 6595 -1 6596 -1 6597 -1 6598 -1 6599 -1 6600 -1 6601 -1 6602 -1 6603 -1 6604 -1 6605 -1 6606 -1 6607 -1 6608 -1 6609 -1 6610 -1 6611 -1 6612 -1 6613 -1 6614 -1 6615 -1 6616 -1 6617 -1 6618 -1 6619 -1 6620 -1 6621 -1 6622 -1 6623 -1 6624 -1 6625 -1 6626 -1 6627 -1 6628 -1 6629 -1 6630 -1 6631 -1 6632 -1 6633 -1 6634 -1 6635 -1 6636 -1 6637 -1 6638 -1 6639 -1 6640 -1 6641 -1 6642 -1 6643 -1 6644 -1 6645 -1 6646 -1 6647 -1 6648 -1 6649 -1 6650 -1 6651 -1 6652 -1 6653 -1 6654 -1 6655 -1 6656 -1 6657 -1 6658 -1 6659 -1 6660 -1 6661 -1 6662 -1 6663 -1 6664 -1 6665 -1 6666 -1 6667 -1 6668 -1 6669 -1 6670 -1 6671 -1 6672 -1 6673 -1 6674 -1 6675 -1 6676 -1 6677 -1 6678 -1 6679 -1 6680 -1 6681 -1 6682 -1 6683 -1 6684 -1 6685 -1 6686 -1 6687 -1 6688 -1 6689 -1 6690 -1 6691 -1 6692 -1 6693 -1 6694 -1 6695 -1 6696 -1 6697 -1 6698 -1 6699 -1 6700 -1 6701 -1 6702 -1 6703 -1 6704 -1 6705 -1 6706 -1 6707 -1 6708 -1 6709 -1 6710 -1 6711 -1 6712 -1 6713 -1 6714 -1 6715 -1 6716 -1 6717 -1 6718 -1 6719 -1 6720 -1 6721 -1 6722 -1 6723 -1 6724 -1 6725 -1 6726 -1 6727 -1 6728 -1 6729 -1 6730 -1 6731 -1 6732 -1 6733 -1 6734 -1 6735 -1 6736 -1 6737 -1 6738 -1 6739 -1 6740 -1 6741 -1 6742 -1 6743 -1 6744 -1 6745 -1 6746 -1 6747 -1 6748 -1 6749 -1 6750 -1 6751 -1 6752 -1 6753 -1 6754 -1 6755 -1 6756 -1 6757 -1 6758 -1 6759 -1 6760 -1 6761 -1 6762 -1 6763 -1 6764 -1 6765 -1 6766 -1 6767 -1 6768 -1 6769 -1 6770 -1 6771 -1 6772 -1 6773 -1 6774 -1 6775 -1 6776 -1 6777 -1 6778 -1 6779 -1 6780 -1 6781 -1 6782 -1 6783 -1 6784 -1 6785 -1 6786 -1 6787 -1 6788 -1 6789 -1 6790 -1 6791 -1 6792 -1 6793 -1 6794 -1 6795 -1 6796 -1 6797 -1 6798 -1 6799 -1 6800 -1 6801 -1 6802 -1 6803 -1 6804 -1 6805 -1 6806 -1 6807 -1 6808 -1 6809 -1 6810 -1 6811 -1 6812 -1 6813 -1 6814 -1 6815 -1 6816 -1 6817 -1 6818 -1 6819 -1 6820 -1 6821 -1 6822 -1 6823 -1 6824 -1 6825 -1 6826 -1 6827 -1 6828 -1 6829 -1 6830 -1 6831 -1 6832 -1 6833 -1 6834 -1 6835 -1 6836 -1 6837 -1 6838 -1 6839 -1 6840 -1 6841 -1 6842 -1 6843 -1 6844 -1 6845 -1 6846 -1 6847 -1 6848 -1 6849 -1 6850 -1 6851 -1 6852 -1 6853 -1 6854 -1 6855 -1 6856 -1 6857 -1 6858 -1 6859 -1 6860 -1 6861 -1 6862 -1 6863 -1 6864 -1 6865 -1 6866 -1 6867 -1 6868 -1 6869 -1 6870 -1 6871 -1 6872 -1 6873 -1 6874 -1 6875 -1 6876 -1 6877 -1 6878 -1 6879 -1 6880 -1 6881 -1 6882 -1 6883 -1 6884 -1 6885 -1 6886 -1 6887 -1 6888 -1 6889 -1 6890 -1 6891 -1 6892 -1 6893 -1 6894 -1 6895 -1 6896 -1 6897 -1 6898 -1 6899 -1 6900 -1 6901 -1 6902 -1 6903 -1 6904 -1 6905 -1 6906 -1 6907 -1 6908 -1 6909 -1 6910 -1 6911 -1 6912 -1 6913 -1 6914 -1 6915 -1 6916 -1 6917 -1 6918 -1 6919 -1 6920 -1 6921 -1 6922 -1 6923 -1 6924 -1 6925 -1 6926 -1 6927 -1 6928 -1 6929 -1 6930 -1 6931 -1 6932 -1 6933 -1 6934 -1 6935 -1 6936 -1 6937 -1 6938 -1 6939 -1 6940 -1 6941 -1 6942 -1 6943 -1 6944 -1 6945 -1 6946 -1 6947 -1 6948 -1 6949 -1 6950 -1 6951 -1 6952 -1 6953 -1 6954 -1 6955 -1 6956 -1 6957 -1 6958 -1 6959 -1 6960 -1 6961 -1 6962 -1 6963 -1 6964 -1 6965 -1 6966 -1 6967 -1 6968 -1 6969 -1 6970 -1 6971 -1 6972 -1 6973 -1 6974 -1 6975 -1 6976 -1 6977 -1 6978 -1 6979 -1 6980 -1 6981 -1 6982 -1 6983 -1 6984 -1 6985 -1 6986 -1 6987 -1 6988 -1 6989 -1 6990 -1 6991 -1 6992 -1 6993 -1 6994 -1 6995 -1 6996 -1 6997 -1 6998 -1 6999 -1 7000 -1 7001 -1 7002 -1 7003 -1 7004 -1 7005 -1 7006 -1 7007 -1 7008 -1 7009 -1 7010 -1 7011 -1 7012 -1 7013 -1 7014 -1 7015 -1 7016 -1 7017 -1 7018 -1 7019 -1 7020 -1 7021 -1 7022 -1 7023 -1 7024 -1 7025 -1 7026 -1 7027 -1 7028 -1 7029 -1 7030 -1 7031 -1 7032 -1 7033 -1 7034 -1 7035 -1 7036 -1 7037 -1 7038 -1 7039 -1 7040 -1 7041 -1 7042 -1 7043 -1 7044 -1 7045 -1 7046 -1 7047 -1 7048 -1 7049 -1 7050 -1 7051 -1 7052 -1 7053 -1 7054 -1 7055 -1 7056 -1 7057 -1 7058 -1 7059 -1 7060 -1 7061 -1 7062 -1 7063 -1 7064 -1 7065 -1 7066 -1 7067 -1 7068 -1 7069 -1 7070 -1 7071 -1 7072 -1 7073 -1 7074 -1 7075 -1 7076 -1 7077 -1 7078 -1 7079 -1 7080 -1 7081 -1 7082 -1 7083 -1 7084 -1 7085 -1 7086 -1 7087 -1 7088 -1 7089 -1 7090 -1 7091 -1 7092 -1 7093 -1 7094 -1 7095 -1 7096 -1 7097 -1 7098 -1 7099 -1 7100 -1 7101 -1 7102 -1 7103 -1 7104 -1 7105 -1 7106 -1 7107 -1 7108 -1 7109 -1 7110 -1 7111 -1 7112 -1 7113 -1 7114 -1 7115 -1 7116 -1 7117 -1 7118 -1 7119 -1 7120 -1 7121 -1 7122 -1 7123 -1 7124 -1 7125 -1 7126 -1 7127 -1 7128 -1 7129 -1 7130 -1 7131 -1 7132 -1 7133 -1 7134 -1 7135 -1 7136 -1 7137 -1 7138 -1 7139 -1 7140 -1 7141 -1 7142 -1 7143 -1 7144 -1 7145 -1 7146 -1 7147 -1 7148 -1 7149 -1 7150 -1 7151 -1 7152 -1 7153 -1 7154 -1 7155 -1 7156 -1 7157 -1 7158 -1 7159 -1 7160 -1 7161 -1 7162 -1 7163 -1 7164 -1 7165 -1 7166 -1 7167 -1 7168 -1 7169 -1 7170 -1 7171 -1 7172 -1 7173 -1 7174 -1 7175 -1 7176 -1 7177 -1 7178 -1 7179 -1 7180 -1 7181 -1 7182 -1 7183 -1 7184 -1 7185 -1 7186 -1 7187 -1 7188 -1 7189 -1 7190 -1 7191 -1 7192 -1 7193 -1 7194 -1 7195 -1 7196 -1 7197 -1 7198 -1 7199 -1 7200 -1 7201 -1 7202 -1 7203 -1 7204 -1 7205 -1 7206 -1 7207 -1 7208 -1 7209 -1 7210 -1 7211 -1 7212 -1 7213 -1 7214 -1 7215 -1 7216 -1 7217 -1 7218 -1 7219 -1 7220 -1 7221 -1 7222 -1 7223 -1 7224 -1 7225 -1 7226 -1 7227 -1 7228 -1 7229 -1 7230 -1 7231 -1 7232 -1 7233 -1 7234 -1 7235 -1 7236 -1 7237 -1 7238 -1 7239 -1 7240 -1 7241 -1 7242 -1 7243 -1 7244 -1 7245 -1 7246 -1 7247 -1 7248 -1 7249 -1 7250 -1 7251 -1 7252 -1 7253 -1 7254 -1 7255 -1 7256 -1 7257 -1 7258 -1 7259 -1 7260 -1 7261 -1 7262 -1 7263 -1 7264 -1 7265 -1 7266 -1 7267 -1 7268 -1 7269 -1 7270 -1 7271 -1 7272 -1 7273 -1 7274 -1 7275 -1 7276 -1 7277 -1 7278 -1 7279 -1 7280 -1 7281 -1 7282 -1 7283 -1 7284 -1 7285 -1 7286 -1 7287 -1 7288 -1 7289 -1 7290 -1 7291 -1 7292 -1 7293 -1 7294 -1 7295 -1 7296 -1 7297 -1 7298 -1 7299 -1 7300 -1 7301 -1 7302 -1 7303 -1 7304 -1 7305 -1 7306 -1 7307 -1 7308 -1 7309 -1 7310 -1 7311 -1 7312 -1 7313 -1 7314 -1 7315 -1 7316 -1 7317 -1 7318 -1 7319 -1 7320 -1 7321 -1 7322 -1 7323 -1 7324 -1 7325 -1 7326 -1 7327 -1 7328 -1 7329 -1 7330 -1 7331 -1 7332 -1 7333 -1 7334 -1 7335 -1 7336 -1 7337 -1 7338 -1 7339 -1 7340 -1 7341 -1 7342 -1 7343 -1 7344 -1 7345 -1 7346 -1 7347 -1 7348 -1 7349 -1 7350 -1 7351 -1 7352 -1 7353 -1 7354 -1 7355 -1 7356 -1 7357 -1 7358 -1 7359 -1 7360 -1 7361 -1 7362 -1 7363 -1 7364 -1 7365 -1 7366 -1 7367 -1 7368 -1 7369 -1 7370 -1 7371 -1 7372 -1 7373 -1 7374 -1 7375 -1 7376 -1 7377 -1 7378 -1 7379 -1 7380 -1 7381 -1 7382 -1 7383 -1 7384 -1 7385 -1 7386 -1 7387 -1 7388 -1 7389 -1 7390 -1 7391 -1 7392 -1 7393 -1 7394 -1 7395 -1 7396 -1 7397 -1 7398 -1 7399 -1 7400 -1 7401 -1 7402 -1 7403 -1 7404 -1 7405 -1 7406 -1 7407 -1 7408 -1 7409 -1 7410 -1 7411 -1 7412 -1 7413 -1 7414 -1 7415 -1 7416 -1 7417 -1 7418 -1 7419 -1 7420 -1 7421 -1 7422 -1 7423 -1 7424 -1 7425 -1 7426 -1 7427 -1 7428 -1 7429 -1 7430 -1 7431 -1 7432 -1 7433 -1 7434 -1 7435 -1 7436 -1 7437 -1 7438 -1 7439 -1 7440 -1 7441 -1 7442 -1 7443 -1 7444 -1 7445 -1 7446 -1 7447 -1 7448 -1 7449 -1 7450 -1 7451 -1 7452 -1 7453 -1 7454 -1 7455 -1 7456 -1 7457 -1 7458 -1 7459 -1 7460 -1 7461 -1 7462 -1 7463 -1 7464 -1 7465 -1 7466 -1 7467 -1 7468 -1 7469 -1 7470 -1 7471 -1 7472 -1 7473 -1 7474 -1 7475 -1 7476 -1 7477 -1 7478 -1 7479 -1 7480 -1 7481 -1 7482 -1 7483 -1 7484 -1 7485 -1 7486 -1 7487 -1 7488 -1 7489 -1 7490 -1 7491 -1 7492 -1 7493 -1 7494 -1 7495 -1 7496 -1 7497 -1 7498 -1 7499 -1 7500 -1 7501 -1 7502 -1 7503 -1 7504 -1 7505 -1 7506 -1 7507 -1 7508 -1 7509 -1 7510 -1 7511 -1 7512 -1 7513 -1 7514 -1 7515 -1 7516 -1 7517 -1 7518 -1 7519 -1 7520 -1 7521 -1 7522 -1 7523 -1 7524 -1 7525 -1 7526 -1 7527 -1 7528 -1 7529 -1 7530 -1 7531 -1 7532 -1 7533 -1 7534 -1 7535 -1 7536 -1 7537 -1 7538 -1 7539 -1 7540 -1 7541 -1 7542 -1 7543 -1 7544 -1 7545 -1 7546 -1 7547 -1 7548 -1 7549 -1 7550 -1 7551 -1 7552 -1 7553 -1 7554 -1 7555 -1 7556 -1 7557 -1 7558 -1 7559 -1 7560 -1 7561 -1 7562 -1 7563 -1 7564 -1 7565 -1 7566 -1 7567 -1 7568 -1 7569 -1 7570 -1 7571 -1 7572 -1 7573 -1 7574 -1 7575 -1 7576 -1 7577 -1 7578 -1 7579 -1 7580 -1 7581 -1 7582 -1 7583 -1 7584 -1 7585 -1 7586 -1 7587 -1 7588 -1 7589 -1 7590 -1 7591 -1 7592 -1 7593 -1 7594 -1 7595 -1 7596 -1 7597 -1 7598 -1 7599 -1 7600 -1 7601 -1 7602 -1 7603 -1 7604 -1 7605 -1 7606 -1 7607 -1 7608 -1 7609 -1 7610 -1 7611 -1 7612 -1 7613 -1 7614 -1 7615 -1 7616 -1 7617 -1 7618 -1 7619 -1 7620 -1 7621 -1 7622 -1 7623 -1 7624 -1 7625 -1 7626 -1 7627 -1 7628 -1 7629 -1 7630 -1 7631 -1 7632 -1 7633 -1 7634 -1 7635 -1 7636 -1 7637 -1 7638 -1 7639 -1 7640 -1 7641 -1 7642 -1 7643 -1 7644 -1 7645 -1 7646 -1 7647 -1 7648 -1 7649 -1 7650 -1 7651 -1 7652 -1 7653 -1 7654 -1 7655 -1 7656 -1 7657 -1 7658 -1 7659 -1 7660 -1 7661 -1 7662 -1 7663 -1 7664 -1 7665 -1 7666 -1 7667 -1 7668 -1 7669 -1 7670 -1 7671 -1 7672 -1 7673 -1 7674 -1 7675 -1 7676 -1 7677 -1 7678 -1 7679 -1 7680 -1 7681 -1 7682 -1 7683 -1 7684 -1 7685 -1 7686 -1 7687 -1 7688 -1 7689 -1 7690 -1 7691 -1 7692 -1 7693 -1 7694 -1 7695 -1 7696 -1 7697 -1 7698 -1 7699 -1 7700 -1 7701 -1 7702 -1 7703 -1 7704 -1 7705 -1 7706 -1 7707 -1 7708 -1 7709 -1 7710 -1 7711 -1 7712 -1 7713 -1 7714 -1 7715 -1 7716 -1 7717 -1 7718 -1 7719 -1 7720 -1 7721 -1 7722 -1 7723 -1 7724 -1 7725 -1 7726 -1 7727 -1 7728 -1 7729 -1 7730 -1 7731 -1 7732 -1 7733 -1 7734 -1 7735 -1 7736 -1 7737 -1 7738 -1 7739 -1 7740 -1 7741 -1 7742 -1 7743 -1 7744 -1 7745 -1 7746 -1 7747 -1 7748 -1 7749 -1 7750 -1 7751 -1 7752 -1 7753 -1 7754 -1 7755 -1 7756 -1 7757 -1 7758 -1 7759 -1 7760 -1 7761 -1 7762 -1 7763 -1 7764 -1 7765 -1 7766 -1 7767 -1 7768 -1 7769 -1 7770 -1 7771 -1 7772 -1 7773 -1 7774 -1 7775 -1 7776 -1 7777 -1 7778 -1 7779 -1 7780 -1 7781 -1 7782 -1 7783 -1 7784 -1 7785 -1 7786 -1 7787 -1 7788 -1 7789 -1 7790 -1 7791 -1 7792 -1 7793 -1 7794 -1 7795 -1 7796 -1 7797 -1 7798 -1 7799 -1 7800 -1 7801 -1 7802 -1 7803 -1 7804 -1 7805 -1 7806 -1 7807 -1 7808 -1 7809 -1 7810 -1 7811 -1 7812 -1 7813 -1 7814 -1 7815 -1 7816 -1 7817 -1 7818 -1 7819 -1 7820 -1 7821 -1 7822 -1 7823 -1 7824 -1 7825 -1 7826 -1 7827 -1 7828 -1 7829 -1 7830 -1 7831 -1 7832 -1 7833 -1 7834 -1 7835 -1 7836 -1 7837 -1 7838 -1 7839 -1 7840 -1 7841 -1 7842 -1 7843 -1 7844 -1 7845 -1 7846 -1 7847 -1 7848 -1 7849 -1 7850 -1 7851 -1 7852 -1 7853 -1 7854 -1 7855 -1 7856 -1 7857 -1 7858 -1 7859 -1 7860 -1 7861 -1 7862 -1 7863 -1 7864 -1 7865 -1 7866 -1 7867 -1 7868 -1 7869 -1 7870 -1 7871 -1 7872 -1 7873 -1 7874 -1 7875 -1 7876 -1 7877 -1 7878 -1 7879 -1 7880 -1 7881 -1 7882 -1 7883 -1 7884 -1 7885 -1 7886 -1 7887 -1 7888 -1 7889 -1 7890 -1 7891 -1 7892 -1 7893 -1 7894 -1 7895 -1 7896 -1 7897 -1 7898 -1 7899 -1 7900 -1 7901 -1 7902 -1 7903 -1 7904 -1 7905 -1 7906 -1 7907 -1 7908 -1 7909 -1 7910 -1 7911 -1 7912 -1 7913 -1 7914 -1 7915 -1 7916 -1 7917 -1 7918 -1 7919 -1 7920 -1 7921 -1 7922 -1 7923 -1 7924 -1 7925 -1 7926 -1 7927 -1 7928 -1 7929 -1 7930 -1 7931 -1 7932 -1 7933 -1 7934 -1 7935 -1 7936 -1 7937 -1 7938 -1 7939 -1 7940 -1 7941 -1 7942 -1 7943 -1 7944 -1 7945 -1 7946 -1 7947 -1 7948 -1 7949 -1 7950 -1 7951 -1 7952 -1 7953 -1 7954 -1 7955 -1 7956 -1 7957 -1 7958 -1 7959 -1 7960 -1 7961 -1 7962 -1 7963 -1 7964 -1 7965 -1 7966 -1 7967 -1 7968 -1 7969 -1 7970 -1 7971 -1 7972 -1 7973 -1 7974 -1 7975 -1 7976 -1 7977 -1 7978 -1 7979 -1 7980 -1 7981 -1 7982 -1 7983 -1 7984 -1 7985 -1 7986 -1 7987 -1 7988 -1 7989 -1 7990 -1 7991 -1 7992 -1 7993 -1 7994 -1 7995 -1 7996 -1 7997 -1 7998 -1 7999 -1 8000 -1 8001 -1 8002 -1 8003 -1 8004 -1 8005 -1 8006 -1 8007 -1 8008 -1 8009 -1 8010 -1 8011 -1 8012 -1 8013 -1 8014 -1 8015 -1 8016 -1 8017 -1 8018 -1 8019 -1 8020 -1 8021 -1 8022 -1 8023 -1 8024 -1 8025 -1 8026 -1 8027 -1 8028 -1 8029 -1 8030 -1 8031 -1 8032 -1 8033 -1 8034 -1 8035 -1 8036 -1 8037 -1 8038 -1 8039 -1 8040 -1 8041 -1 8042 -1 8043 -1 8044 -1 8045 -1 8046 -1 8047 -1 8048 -1 8049 -1 8050 -1 8051 -1 8052 -1 8053 -1 8054 -1 8055 -1 8056 -1 8057 -1 8058 -1 8059 -1 8060 -1 8061 -1 8062 -1 8063 -1 8064 -1 8065 -1 8066 -1 8067 -1 8068 -1 8069 -1 8070 -1 8071 -1 8072 -1 8073 -1 8074 -1 8075 -1 8076 -1 8077 -1 8078 -1 8079 -1 8080 -1 8081 -1 8082 -1 8083 -1 8084 -1 8085 -1 8086 -1 8087 -1 8088 -1 8089 -1 8090 -1 8091 -1 8092 -1 8093 -1 8094 -1 8095 -1 8096 -1 8097 -1 8098 -1 8099 -1 8100 -1 8101 -1 8102 -1 8103 -1 8104 -1 8105 -1 8106 -1 8107 -1 8108 -1 8109 -1 8110 -1 8111 -1 8112 -1 8113 -1 8114 -1 8115 -1 8116 -1 8117 -1 8118 -1 8119 -1 8120 -1 8121 -1 8122 -1 8123 -1 8124 -1 8125 -1 8126 -1 8127 -1 8128 -1 8129 -1 8130 -1 8131 -1 8132 -1 8133 -1 8134 -1 8135 -1 8136 -1 8137 -1 8138 -1 8139 -1 8140 -1 8141 -1 8142 -1 8143 -1 8144 -1 8145 -1 8146 -1 8147 -1 8148 -1 8149 -1 8150 -1 8151 -1 8152 -1 8153 -1 8154 -1 8155 -1 8156 -1 8157 -1 8158 -1 8159 -1 8160 -1 8161 -1 8162 -1 8163 -1 8164 -1 8165 -1 8166 -1 8167 -1 8168 -1 8169 -1 8170 -1 8171 -1 8172 -1 8173 -1 8174 -1 8175 -1 8176 -1 8177 -1 8178 -1 8179 -1 8180 -1 8181 -1 8182 -1 8183 -1 8184 -1 8185 -1 8186 -1 8187 -1 8188 -1 8189 -1 8190 -1 8191 -1 8192 -1 8193 -1 8194 -1 8195 -1 8196 -1 8197 -1 8198 -1 8199 -1 8200 -1 8201 -1 8202 -1 8203 -1 8204 -1 8205 -1 8206 -1 8207 -1 8208 -1 8209 -1 8210 -1 8211 -1 8212 -1 8213 -1 8214 -1 8215 -1 8216 -1 8217 -1 8218 -1 8219 -1 8220 -1 8221 -1 8222 -1 8223 -1 8224 -1 8225 -1 8226 -1 8227 -1 8228 -1 8229 -1 8230 -1 8231 -1 8232 -1 8233 -1 8234 -1 8235 -1 8236 -1 8237 -1 8238 -1 8239 -1 8240 -1 8241 -1 8242 -1 8243 -1 8244 -1 8245 -1 8246 -1 8247 -1 8248 -1 8249 -1 8250 -1 8251 -1 8252 -1 8253 -1 8254 -1 8255 -1 8256 -1 8257 -1 8258 -1 8259 -1 8260 -1 8261 -1 8262 -1 8263 -1 8264 -1 8265 -1 8266 -1 8267 -1 8268 -1 8269 -1 8270 -1 8271 -1 8272 -1 8273 -1 8274 -1 8275 -1 8276 -1 8277 -1 8278 -1 8279 -1 8280 -1 8281 -1 8282 -1 8283 -1 8284 -1 8285 -1 8286 -1 8287 -1 8288 -1 8289 -1 8290 -1 8291 -1 8292 -1 8293 -1 8294 -1 8295 -1 8296 -1 8297 -1 8298 -1 8299 -1 8300 -1 8301 -1 8302 -1 8303 -1 8304 -1 8305 -1 8306 -1 8307 -1 8308 -1 8309 -1 8310 -1 8311 -1 8312 -1 8313 -1 8314 -1 8315 -1 8316 -1 8317 -1 8318 -1 8319 -1 8320 -1 8321 -1 8322 -1 8323 -1 8324 -1 8325 -1 8326 -1 8327 -1 8328 -1 8329 -1 8330 -1 8331 -1 8332 -1 8333 -1 8334 -1 8335 -1 8336 -1 8337 -1 8338 -1 8339 -1 8340 -1 8341 -1 8342 -1 8343 -1 8344 -1 8345 -1 8346 -1 8347 -1 8348 -1 8349 -1 8350 -1 8351 -1 8352 -1 8353 -1 8354 -1 8355 -1 8356 -1 8357 -1 8358 -1 8359 -1 8360 -1 8361 -1 8362 -1 8363 -1 8364 -1 8365 -1 8366 -1 8367 -1 8368 -1 8369 -1 8370 -1 8371 -1 8372 -1 8373 -1 8374 -1 8375 -1 8376 -1 8377 -1 8378 -1 8379 -1 8380 -1 8381 -1 8382 -1 8383 -1 8384 -1 8385 -1 8386 -1 8387 -1 8388 -1 8389 -1 8390 -1 8391 -1 8392 -1 8393 -1 8394 -1 8395 -1 8396 -1 8397 -1 8398 -1 8399 -1 8400 -1 8401 -1 8402 -1 8403 -1 8404 -1 8405 -1 8406 -1 8407 -1 8408 -1 8409 -1 8410 -1 8411 -1 8412 -1 8413 -1 8414 -1 8415 -1 8416 -1 8417 -1 8418 -1 8419 -1 8420 -1 8421 -1 8422 -1 8423 -1 8424 -1 8425 -1 8426 -1 8427 -1 8428 -1 8429 -1 8430 -1 8431 -1 8432 -1 8433 -1 8434 -1 8435 -1 8436 -1 8437 -1 8438 -1 8439 -1 8440 -1 8441 -1 8442 -1 8443 -1 8444 -1 8445 -1 8446 -1 8447 -1 8448 -1 8449 -1 8450 -1 8451 -1 8452 -1 8453 -1 8454 -1 8455 -1 8456 -1 8457 -1 8458 -1 8459 -1 8460 -1 8461 -1 8462 -1 8463 -1 8464 -1 8465 -1 8466 -1 8467 -1 8468 -1 8469 -1 8470 -1 8471 -1 8472 -1 8473 -1 8474 -1 8475 -1 8476 -1 8477 -1 8478 -1 8479 -1 8480 -1 8481 -1 8482 -1 8483 -1 8484 -1 8485 -1 8486 -1 8487 -1 8488 -1 8489 -1 8490 -1 8491 -1 8492 -1 8493 -1 8494 -1 8495 -1 8496 -1 8497 -1 8498 -1 8499 -1 8500 -1 8501 -1 8502 -1 8503 -1 8504 -1 8505 -1 8506 -1 8507 -1 8508 -1 8509 -1 8510 -1 8511 -1 8512 -1 8513 -1 8514 -1 8515 -1 8516 -1 8517 -1 8518 -1 8519 -1 8520 -1 8521 -1 8522 -1 8523 -1 8524 -1 8525 -1 8526 -1 8527 -1 8528 -1 8529 -1 8530 -1 8531 -1 8532 -1 8533 -1 8534 -1 8535 -1 8536 -1 8537 -1 8538 -1 8539 -1 8540 -1 8541 -1 8542 -1 8543 -1 8544 -1 8545 -1 8546 -1 8547 -1 8548 -1 8549 -1 8550 -1 8551 -1 8552 -1 8553 -1 8554 -1 8555 -1 8556 -1 8557 -1 8558 -1 8559 -1 8560 -1 8561 -1 8562 -1 8563 -1 8564 -1 8565 -1 8566 -1 8567 -1 8568 -1 8569 -1 8570 -1 8571 -1 8572 -1 8573 -1 8574 -1 8575 -1 8576 -1 8577 -1 8578 -1 8579 -1 8580 -1 8581 -1 8582 -1 8583 -1 8584 -1 8585 -1 8586 -1 8587 -1 8588 -1 8589 -1 8590 -1 8591 -1 8592 -1 8593 -1 8594 -1 8595 -1 8596 -1 8597 -1 8598 -1 8599 -1 8600 -1 8601 -1 8602 -1 8603 -1 8604 -1 8605 -1 8606 -1 8607 -1 8608 -1 8609 -1 8610 -1 8611 -1 8612 -1 8613 -1 8614 -1 8615 -1 8616 -1 8617 -1 8618 -1 8619 -1 8620 -1 8621 -1 8622 -1 8623 -1 8624 -1 8625 -1 8626 -1 8627 -1 8628 -1 8629 -1 8630 -1 8631 -1 8632 -1 8633 -1 8634 -1 8635 -1 8636 -1 8637 -1 8638 -1 8639 -1 8640 -1 8641 -1 8642 -1 8643 -1 8644 -1 8645 -1 8646 -1 8647 -1 8648 -1 8649 -1 8650 -1 8651 -1 8652 -1 8653 -1 8654 -1 8655 -1 8656 -1 8657 -1 8658 -1 8659 -1 8660 -1 8661 -1 8662 -1 8663 -1 8664 -1 8665 -1 8666 -1 8667 -1 8668 -1 8669 -1 8670 -1 8671 -1 8672 -1 8673 -1 8674 -1 8675 -1 8676 -1 8677 -1 8678 -1 8679 -1 8680 -1 8681 -1 8682 -1 8683 -1 8684 -1 8685 -1 8686 -1 8687 -1 8688 -1 8689 -1 8690 -1 8691 -1 8692 -1 8693 -1 8694 -1 8695 -1 8696 -1 8697 -1 8698 -1 8699 -1 8700 -1 8701 -1 8702 -1 8703 -1 8704 -1 8705 -1 8706 -1 8707 -1 8708 -1 8709 -1 8710 -1 8711 -1 8712 -1 8713 -1 8714 -1 8715 -1 8716 -1 8717 -1 8718 -1 8719 -1 8720 -1 8721 -1 8722 -1 8723 -1 8724 -1 8725 -1 8726 -1 8727 -1 8728 -1 8729 -1 8730 -1 8731 -1 8732 -1 8733 -1 8734 -1 8735 -1 8736 -1 8737 -1 8738 -1 8739 -1 8740 -1 8741 -1 8742 -1 8743 -1 8744 -1 8745 -1 8746 -1 8747 -1 8748 -1 8749 -1 8750 -1 8751 -1 8752 -1 8753 -1 8754 -1 8755 -1 8756 -1 8757 -1 8758 -1 8759 -1 8760 -1 8761 -1 8762 -1 8763 -1 8764 -1 8765 -1 8766 -1 8767 -1 8768 -1 8769 -1 8770 -1 8771 -1 8772 -1 8773 -1 8774 -1 8775 -1 8776 -1 8777 -1 8778 -1 8779 -1 8780 -1 8781 -1 8782 -1 8783 -1 8784 -1 8785 -1 8786 -1 8787 -1 8788 -1 8789 -1 8790 -1 8791 -1 8792 -1 8793 -1 8794 -1 8795 -1 8796 -1 8797 -1 8798 -1 8799 -1 8800 -1 8801 -1 8802 -1 8803 -1 8804 -1 8805 -1 8806 -1 8807 -1 8808 -1 8809 -1 8810 -1 8811 -1 8812 -1 8813 -1 8814 -1 8815 -1 8816 -1 8817 -1 8818 -1 8819 -1 8820 -1 8821 -1 8822 -1 8823 -1 8824 -1 8825 -1 8826 -1 8827 -1 8828 -1 8829 -1 8830 -1 8831 -1 8832 -1 8833 -1 8834 -1 8835 -1 8836 -1 8837 -1 8838 -1 8839 -1 8840 -1 8841 -1 8842 -1 8843 -1 8844 -1 8845 -1 8846 -1 8847 -1 8848 -1 8849 -1 8850 -1 8851 -1 8852 -1 8853 -1 8854 -1 8855 -1 8856 -1 8857 -1 8858 -1 8859 -1 8860 -1 8861 -1 8862 -1 8863 -1 8864 -1 8865 -1 8866 -1 8867 -1 8868 -1 8869 -1 8870 -1 8871 -1 8872 -1 8873 -1 8874 -1 8875 -1 8876 -1 8877 -1 8878 -1 8879 -1 8880 -1 8881 -1 8882 -1 8883 -1 8884 -1 8885 -1 8886 -1 8887 -1 8888 -1 8889 -1 8890 -1 8891 -1 8892 -1 8893 -1 8894 -1 8895 -1 8896 -1 8897 -1 8898 -1 8899 -1 8900 -1 8901 -1 8902 -1 8903 -1 8904 -1 8905 -1 8906 -1 8907 -1 8908 -1 8909 -1 8910 -1 8911 -1 8912 -1 8913 -1 8914 -1 8915 -1 8916 -1 8917 -1 8918 -1 8919 -1 8920 -1 8921 -1 8922 -1 8923 -1 8924 -1 8925 -1 8926 -1 8927 -1 8928 -1 8929 -1 8930 -1 8931 -1 8932 -1 8933 -1 8934 -1 8935 -1 8936 -1 8937 -1 8938 -1 8939 -1 8940 -1 8941 -1 8942 -1 8943 -1 8944 -1 8945 -1 8946 -1 8947 -1 8948 -1 8949 -1 8950 -1 8951 -1 8952 -1 8953 -1 8954 -1 8955 -1 8956 -1 8957 -1 8958 -1 8959 -1 8960 -1 8961 -1 8962 -1 8963 -1 8964 -1 8965 -1 8966 -1 8967 -1 8968 -1 8969 -1 8970 -1 8971 -1 8972 -1 8973 -1 8974 -1 8975 -1 8976 -1 8977 -1 8978 -1 8979 -1 8980 -1 8981 -1 8982 -1 8983 -1 8984 -1 8985 -1 8986 -1 8987 -1 8988 -1 8989 -1 8990 -1 8991 -1 8992 -1 8993 -1 8994 -1 8995 -1 8996 -1 8997 -1 8998 -1 8999 -1 9000 -1 9001 -1 9002 -1 9003 -1 9004 -1 9005 -1 9006 -1 9007 -1 9008 -1 9009 -1 9010 -1 9011 -1 9012 -1 9013 -1 9014 -1 9015 -1 9016 -1 9017 -1 9018 -1 9019 -1 9020 -1 9021 -1 9022 -1 9023 -1 9024 -1 9025 -1 9026 -1 9027 -1 9028 -1 9029 -1 9030 -1 9031 -1 9032 -1 9033 -1 9034 -1 9035 -1 9036 -1 9037 -1 9038 -1 9039 -1 9040 -1 9041 -1 9042 -1 9043 -1 9044 -1 9045 -1 9046 -1 9047 -1 9048 -1 9049 -1 9050 -1 9051 -1 9052 -1 9053 -1 9054 -1 9055 -1 9056 -1 9057 -1 9058 -1 9059 -1 9060 -1 9061 -1 9062 -1 9063 -1 9064 -1 9065 -1 9066 -1 9067 -1 9068 -1 9069 -1 9070 -1 9071 -1 9072 -1 9073 -1 9074 -1 9075 -1 9076 -1 9077 -1 9078 -1 9079 -1 9080 -1 9081 -1 9082 -1 9083 -1 9084 -1 9085 -1 9086 -1 9087 -1 9088 -1 9089 -1 9090 -1 9091 -1 9092 -1 9093 -1 9094 -1 9095 -1 9096 -1 9097 -1 9098 -1 9099 -1 9100 -1 9101 -1 9102 -1 9103 -1 9104 -1 9105 -1 9106 -1 9107 -1 9108 -1 9109 -1 9110 -1 9111 -1 9112 -1 9113 -1 9114 -1 9115 -1 9116 -1 9117 -1 9118 -1 9119 -1 9120 -1 9121 -1 9122 -1 9123 -1 9124 -1 9125 -1 9126 -1 9127 -1 9128 -1 9129 -1 9130 -1 9131 -1 9132 -1 9133 -1 9134 -1 9135 -1 9136 -1 9137 -1 9138 -1 9139 -1 9140 -1 9141 -1 9142 -1 9143 -1 9144 -1 9145 -1 9146 -1 9147 -1 9148 -1 9149 -1 9150 -1 9151 -1 9152 -1 9153 -1 9154 -1 9155 -1 9156 -1 9157 -1 9158 -1 9159 -1 9160 -1 9161 -1 9162 -1 9163 -1 9164 -1 9165 -1 9166 -1 9167 -1 9168 -1 9169 -1 9170 -1 9171 -1 9172 -1 9173 -1 9174 -1 9175 -1 9176 -1 9177 -1 9178 -1 9179 -1 9180 -1 9181 -1 9182 -1 9183 -1 9184 -1 9185 -1 9186 -1 9187 -1 9188 -1 9189 -1 9190 -1 9191 -1 9192 -1 9193 -1 9194 -1 9195 -1 9196 -1 9197 -1 9198 -1 9199 -1 9200 -1 9201 -1 9202 -1 9203 -1 9204 -1 9205 -1 9206 -1 9207 -1 9208 -1 9209 -1 9210 -1 9211 -1 9212 -1 9213 -1 9214 -1 9215 -1 9216 -1 9217 -1 9218 -1 9219 -1 9220 -1 9221 -1 9222 -1 9223 -1 9224 -1 9225 -1 9226 -1 9227 -1 9228 -1 9229 -1 9230 -1 9231 -1 9232 -1 9233 -1 9234 -1 9235 -1 9236 -1 9237 -1 9238 -1 9239 -1 9240 -1 9241 -1 9242 -1 9243 -1 9244 -1 9245 -1 9246 -1 9247 -1 9248 -1 9249 -1 9250 -1 9251 -1 9252 -1 9253 -1 9254 -1 9255 -1 9256 -1 9257 -1 9258 -1 9259 -1 9260 -1 9261 -1 9262 -1 9263 -1 9264 -1 9265 -1 9266 -1 9267 -1 9268 -1 9269 -1 9270 -1 9271 -1 9272 -1 9273 -1 9274 -1 9275 -1 9276 -1 9277 -1 9278 -1 9279 -1 9280 -1 9281 -1 9282 -1 9283 -1 9284 -1 9285 -1 9286 -1 9287 -1 9288 -1 9289 -1 9290 -1 9291 -1 9292 -1 9293 -1 9294 -1 9295 -1 9296 -1 9297 -1 9298 -1 9299 -1 9300 -1 9301 -1 9302 -1 9303 -1 9304 -1 9305 -1 9306 -1 9307 -1 9308 -1 9309 -1 9310 -1 9311 -1 9312 -1 9313 -1 9314 -1 9315 -1 9316 -1 9317 -1 9318 -1 9319 -1 9320 -1 9321 -1 9322 -1 9323 -1 9324 -1 9325 -1 9326 -1 9327 -1 9328 -1 9329 -1 9330 -1 9331 -1 9332 -1 9333 -1 9334 -1 9335 -1 9336 -1 9337 -1 9338 -1 9339 -1 9340 -1 9341 -1 9342 -1 9343 -1 9344 -1 9345 -1 9346 -1 9347 -1 9348 -1 9349 -1 9350 -1 9351 -1 9352 -1 9353 -1 9354 -1 9355 -1 9356 -1 9357 -1 9358 -1 9359 -1 9360 -1 9361 -1 9362 -1 9363 -1 9364 -1 9365 -1 9366 -1 9367 -1 9368 -1 9369 -1 9370 -1 9371 -1 9372 -1 9373 -1 9374 -1 9375 -1 9376 -1 9377 -1 9378 -1 9379 -1 9380 -1 9381 -1 9382 -1 9383 -1 9384 -1 9385 -1 9386 -1 9387 -1 9388 -1 9389 -1 9390 -1 9391 -1 9392 -1 9393 -1 9394 -1 9395 -1 9396 -1 9397 -1 9398 -1 9399 -1 9400 -1 9401 -1 9402 -1 9403 -1 9404 -1 9405 -1 9406 -1 9407 -1 9408 -1 9409 -1 9410 -1 9411 -1 9412 -1 9413 -1 9414 -1 9415 -1 9416 -1 9417 -1 9418 -1 9419 -1 9420 -1 9421 -1 9422 -1 9423 -1 9424 -1 9425 -1 9426 -1 9427 -1 9428 -1 9429 -1 9430 -1 9431 -1 9432 -1 9433 -1 9434 -1 9435 -1 9436 -1 9437 -1 9438 -1 9439 -1 9440 -1 9441 -1 9442 -1 9443 -1 9444 -1 9445 -1 9446 -1 9447 -1 9448 -1 9449 -1 9450 -1 9451 -1 9452 -1 9453 -1 9454 -1 9455 -1 9456 -1 9457 -1 9458 -1 9459 -1 9460 -1 9461 -1 9462 -1 9463 -1 9464 -1 9465 -1 9466 -1 9467 -1 9468 -1 9469 -1 9470 -1 9471 -1 9472 -1 9473 -1 9474 -1 9475 -1 9476 -1 9477 -1 9478 -1 9479 -1 9480 -1 9481 -1 9482 -1 9483 -1 9484 -1 9485 -1 9486 -1 9487 -1 9488 -1 9489 -1 9490 -1 9491 -1 9492 -1 9493 -1 9494 -1 9495 -1 9496 -1 9497 -1 9498 -1 9499 -1 9500 -1 9501 -1 9502 -1 9503 -1 9504 -1 9505 -1 9506 -1 9507 -1 9508 -1 9509 -1 9510 -1 9511 -1 9512 -1 9513 -1 9514 -1 9515 -1 9516 -1 9517 -1 9518 -1 9519 -1 9520 -1 9521 -1 9522 -1 9523 -1 9524 -1 9525 -1 9526 -1 9527 -1 9528 -1 9529 -1 9530 -1 9531 -1 9532 -1 9533 -1 9534 -1 9535 -1 9536 -1 9537 -1 9538 -1 9539 -1 9540 -1 9541 -1 9542 -1 9543 -1 9544 -1 9545 -1 9546 -1 9547 -1 9548 -1 9549 -1 9550 -1 9551 -1 9552 -1 9553 -1 9554 -1 9555 -1 9556 -1 9557 -1 9558 -1 9559 -1 9560 -1 9561 -1 9562 -1 9563 -1 9564 -1 9565 -1 9566 -1 9567 -1 9568 -1 9569 -1 9570 -1 9571 -1 9572 -1 9573 -1 9574 -1 9575 -1 9576 -1 9577 -1 9578 -1 9579 -1 9580 -1 9581 -1 9582 -1 9583 -1 9584 -1 9585 -1 9586 -1 9587 -1 9588 -1 9589 -1 9590 -1 9591 -1 9592 -1 9593 -1 9594 -1 9595 -1 9596 -1 9597 -1 9598 -1 9599 -1 9600 -1 9601 -1 9602 -1 9603 -1 9604 -1 9605 -1 9606 -1 9607 -1 9608 -1 9609 -1 9610 -1 9611 -1 9612 -1 9613 -1 9614 -1 9615 -1 9616 -1 9617 -1 9618 -1 9619 -1 9620 -1 9621 -1 9622 -1 9623 -1 9624 -1 9625 -1 9626 -1 9627 -1 9628 -1 9629 -1 9630 -1 9631 -1 9632 -1 9633 -1 9634 -1 9635 -1 9636 -1 9637 -1 9638 -1 9639 -1 9640 -1 9641 -1 9642 -1 9643 -1 9644 -1 9645 -1 9646 -1 9647 -1 9648 -1 9649 -1 9650 -1 9651 -1 9652 -1 9653 -1 9654 -1 9655 -1 9656 -1 9657 -1 9658 -1 9659 -1 9660 -1 9661 -1 9662 -1 9663 -1 9664 -1 9665 -1 9666 -1 9667 -1 9668 -1 9669 -1 9670 -1 9671 -1 9672 -1 9673 -1 9674 -1 9675 -1 9676 -1 9677 -1 9678 -1 9679 -1 9680 -1 9681 -1 9682 -1 9683 -1 9684 -1 9685 -1 9686 -1 9687 -1 9688 -1 9689 -1 9690 -1 9691 -1 9692 -1 9693 -1 9694 -1 9695 -1 9696 -1 9697 -1 9698 -1 9699 -1 9700 -1 9701 -1 9702 -1 9703 -1 9704 -1 9705 -1 9706 -1 9707 -1 9708 -1 9709 -1 9710 -1 9711 -1 9712 -1 9713 -1 9714 -1 9715 -1 9716 -1 9717 -1 9718 -1 9719 -1 9720 -1 9721 -1 9722 -1 9723 -1 9724 -1 9725 -1 9726 -1 9727 -1 9728 -1 9729 -1 9730 -1 9731 -1 9732 -1 9733 -1 9734 -1 9735 -1 9736 -1 9737 -1 9738 -1 9739 -1 9740 -1 9741 -1 9742 -1 9743 -1 9744 -1 9745 -1 9746 -1 9747 -1 9748 -1 9749 -1 9750 -1 9751 -1 9752 -1 9753 -1 9754 -1 9755 -1 9756 -1 9757 -1 9758 -1 9759 -1 9760 -1 9761 -1 9762 -1 9763 -1 9764 -1 9765 -1 9766 -1 9767 -1 9768 -1 9769 -1 9770 -1 9771 -1 9772 -1 9773 -1 9774 -1 9775 -1 9776 -1 9777 -1 9778 -1 9779 -1 9780 -1 9781 -1 9782 -1 9783 -1 9784 -1 9785 -1 9786 -1 9787 -1 9788 -1 9789 -1 9790 -1 9791 -1 9792 -1 9793 -1 9794 -1 9795 -1 9796 -1 9797 -1 9798 -1 9799 -1 9800 -1 9801 -1 9802 -1 9803 -1 9804 -1 9805 -1 9806 -1 9807 -1 9808 -1 9809 -1 9810 -1 9811 -1 9812 -1 9813 -1 9814 -1 9815 -1 9816 -1 9817 -1 9818 -1 9819 -1 9820 -1 9821 -1 9822 -1 9823 -1 9824 -1 9825 -1 9826 -1 9827 -1 9828 -1 9829 -1 9830 -1 9831 -1 9832 -1 9833 -1 9834 -1 9835 -1 9836 -1 9837 -1 9838 -1 9839 -1 9840 -1 9841 -1 9842 -1 9843 -1 9844 -1 9845 -1 9846 -1 9847 -1 9848 -1 9849 -1 9850 -1 9851 -1 9852 -1 9853 -1 9854 -1 9855 -1 9856 -1 9857 -1 9858 -1 9859 -1 9860 -1 9861 -1 9862 -1 9863 -1 9864 -1 9865 -1 9866 -1 9867 -1 9868 -1 9869 -1 9870 -1 9871 -1 9872 -1 9873 -1 9874 -1 9875 -1 9876 -1 9877 -1 9878 -1 9879 -1 9880 -1 9881 -1 9882 -1 9883 -1 9884 -1 9885 -1 9886 -1 9887 -1 9888 -1 9889 -1 9890 -1 9891 -1 9892 -1 9893 -1 9894 -1 9895 -1 9896 -1 9897 -1 9898 -1 9899 -1 9900 -1 9901 -1 9902 -1 9903 -1 9904 -1 9905 -1 9906 -1 9907 -1 9908 -1 9909 -1 9910 -1 9911 -1 9912 -1 9913 -1 9914 -1 9915 -1 9916 -1 9917 -1 9918 -1 9919 -1 9920 -1 9921 -1 9922 -1 9923 -1 9924 -1 9925 -1 9926 -1 9927 -1 9928 -1 9929 -1 9930 -1 9931 -1 9932 -1 9933 -1 9934 -1 9935 -1 9936 -1 9937 -1 9938 -1 9939 -1 9940 -1 9941 -1 9942 -1 9943 -1 9944 -1 9945 -1 9946 -1 9947 -1 9948 -1 9949 -1 9950 -1 9951 -1 9952 -1 9953 -1 9954 -1 9955 -1 9956 -1 9957 -1 9958 -1 9959 -1 9960 -1 9961 -1 9962 -1 9963 -1 9964 -1 9965 -1 9966 -1 9967 -1 9968 -1 9969 -1 9970 -1 9971 -1 9972 -1 9973 -1 9974 -1 9975 -1 9976 -1 9977 -1 9978 -1 9979 -1 9980 -1 9981 -1 9982 -1 9983 -1 9984 -1 9985 -1 9986 -1 9987 -1 9988 -1 9989 -1 9990 -1 9991 -1 9992 -1 9993 -1 9994 -1 9995 -1 9996 -1 9997 -1 9998 -1 9999 -1 10000 -1 10001 -1 10002 -1 10003 -1 10004 -1 10005 -1 10006 -1 10007 -1 10008 -1 10009 -1 10010 -1 10011 -1 10012 -1 10013 -1 10014 -1 10015 -1 10016 -1 10017 -1 10018 -1 10019 -1 10020 -1 10021 -1 10022 -1 10023 -1 10024 -1 10025 -1 10026 -1 10027 -1 10028 -1 10029 -1 10030 -1 10031 -1 10032 -1 10033 -1 10034 -1 10035 -1 10036 -1 10037 -1 10038 -1 10039 -1 10040 -1 10041 -1 10042 -1 10043 -1 10044 -1 10045 -1 10046 -1 10047 -1 10048 -1 10049 -1 10050 -1 10051 -1 10052 -1 10053 -1 10054 -1 10055 -1 10056 -1 10057 -1 10058 -1 10059 -1 10060 -1 10061 -1 10062 -1 10063 -1 10064 -1 10065 -1 10066 -1 10067 -1 10068 -1 10069 -1 10070 -1 10071 -1 10072 -1 10073 -1 10074 -1 10075 -1 10076 -1 10077 -1 10078 -1 10079 -1 10080 -1 10081 -1 10082 -1 10083 -1 10084 -1 10085 -1 10086 -1 10087 -1 10088 -1 10089 -1 10090 -1 10091 -1 10092 -1 10093 -1 10094 -1 10095 -1 10096 -1 10097 -1 10098 -1 10099 -1 10100 -1 10101 -1 10102 -1 10103 -1 10104 -1 10105 -1 10106 -1 10107 -1 10108 -1 10109 -1 10110 -1 10111 -1 10112 -1 10113 -1 10114 -1 10115 -1 10116 -1 10117 -1 10118 -1 10119 -1 10120 -1 10121 -1 10122 -1 10123 -1 10124 -1 10125 -1 10126 -1 10127 -1 10128 -1 10129 -1 10130 -1 10131 -1 10132 -1 10133 -1 10134 -1 10135 -1 10136 -1 10137 -1 10138 -1 10139 -1 10140 -1 10141 -1 10142 -1 10143 -1 10144 -1 10145 -1 10146 -1 10147 -1 10148 -1 10149 -1 10150 -1 10151 -1 10152 -1 10153 -1 10154 -1 10155 -1 10156 -1 10157 -1 10158 -1 10159 -1 10160 -1 10161 -1 10162 -1 10163 -1 10164 -1 10165 -1 10166 -1 10167 -1 10168 -1 10169 -1 10170 -1 10171 -1 10172 -1 10173 -1 10174 -1 10175 -1 10176 -1 10177 -1 10178 -1 10179 -1 10180 -1 10181 -1 10182 -1 10183 -1 10184 -1 10185 -1 10186 -1 10187 -1 10188 -1 10189 -1 10190 -1 10191 -1 10192 -1 10193 -1 10194 -1 10195 -1 10196 -1 10197 -1 10198 -1 10199 -1 10200 -1 10201 -1 10202 -1 10203 -1 10204 -1 10205 -1 10206 -1 10207 -1 10208 -1 10209 -1 10210 -1 10211 -1 10212 -1 10213 -1 10214 -1 10215 -1 10216 -1 10217 -1 10218 -1 10219 -1 10220 -1 10221 -1 10222 -1 10223 -1 10224 -1 10225 -1 10226 -1 10227 -1 10228 -1 10229 -1 10230 -1 10231 -1 10232 -1 10233 -1 10234 -1 10235 -1 10236 -1 10237 -1 10238 -1 10239 -1 10240 -1 10241 -1 10242 -1 10243 -1 10244 -1 10245 -1 10246 -1 10247 -1 10248 -1 10249 -1 10250 -1 10251 -1 10252 -1 10253 -1 10254 -1 10255 -1 10256 -1 10257 -1 10258 -1 10259 -1 10260 -1 10261 -1 10262 -1 10263 -1 10264 -1 10265 -1 10266 -1 10267 -1 10268 -1 10269 -1 10270 -1 10271 -1 10272 -1 10273 -1 10274 -1 10275 -1 10276 -1 10277 -1 10278 -1 10279 -1 10280 -1 10281 -1 10282 -1 10283 -1 10284 -1 10285 -1 10286 -1 10287 -1 10288 -1 10289 -1 10290 -1 10291 -1 10292 -1 10293 -1 10294 -1 10295 -1 10296 -1 10297 -1 10298 -1 10299 -1 10300 -1 10301 -1 10302 -1 10303 -1 10304 -1 10305 -1 10306 -1 10307 -1 10308 -1 10309 -1 10310 -1 10311 -1 10312 -1 10313 -1 10314 -1 10315 -1 10316 -1 10317 -1 10318 -1 10319 -1 10320 -1 10321 -1 10322 -1 10323 -1 10324 -1 10325 -1 10326 -1 10327 -1 10328 -1 10329 -1 10330 -1 10331 -1 10332 -1 10333 -1 10334 -1 10335 -1 10336 -1 10337 -1 10338 -1 10339 -1 10340 -1 10341 -1 10342 -1 10343 -1 10344 -1 10345 -1 10346 -1 10347 -1 10348 -1 10349 -1 10350 -1 10351 -1 10352 -1 10353 -1 10354 -1 10355 -1 10356 -1 10357 -1 10358 -1 10359 -1 10360 -1 10361 -1 10362 -1 10363 -1 10364 -1 10365 -1 10366 -1 10367 -1 10368 -1 10369 -1 10370 -1 10371 -1 10372 -1 10373 -1 10374 -1 10375 -1 10376 -1 10377 -1 10378 -1 10379 -1 10380 -1 10381 -1 10382 -1 10383 -1 10384 -1 10385 -1 10386 -1 10387 -1 10388 -1 10389 -1 10390 -1 10391 -1 10392 -1 10393 -1 10394 -1 10395 -1 10396 -1 10397 -1 10398 -1 10399 -1 10400 -1 10401 -1 10402 -1 10403 -1 10404 -1 10405 -1 10406 -1 10407 -1 10408 -1 10409 -1 10410 -1 10411 -1 10412 -1 10413 -1 10414 -1 10415 -1 10416 -1 10417 -1 10418 -1 10419 -1 10420 -1 10421 -1 10422 -1 10423 -1 10424 -1 10425 -1 10426 -1 10427 -1 10428 -1 10429 -1 10430 -1 10431 -1 10432 -1 10433 -1 10434 -1 10435 -1 10436 -1 10437 -1 10438 -1 10439 -1 10440 -1 10441 -1 10442 -1 10443 -1 10444 -1 10445 -1 10446 -1 10447 -1 10448 -1 10449 -1 10450 -1 10451 -1 10452 -1 10453 -1 10454 -1 10455 -1 10456 -1 10457 -1 10458 -1 10459 -1 10460 -1 10461 -1 10462 -1 10463 -1 10464 -1 10465 -1 10466 -1 10467 -1 10468 -1 10469 -1 10470 -1 10471 -1 10472 -1 10473 -1 10474 -1 10475 -1 10476 -1 10477 -1 10478 -1 10479 -1 10480 -1 10481 -1 10482 -1 10483 -1 10484 -1 10485 -1 10486 -1 10487 -1 10488 -1 10489 -1 10490 -1 10491 -1 10492 -1 10493 -1 10494 -1 10495 -1 10496 -1 10497 -1 10498 -1 10499 -1 10500 -1 10501 -1 10502 -1 10503 -1 10504 -1 10505 -1 10506 -1 10507 -1 10508 -1 10509 -1 10510 -1 10511 -1 10512 -1 10513 -1 10514 -1 10515 -1 10516 -1 10517 -1 10518 -1 10519 -1 10520 -1 10521 -1 10522 -1 10523 -1 10524 -1 10525 -1 10526 -1 10527 -1 10528 -1 10529 -1 10530 -1 10531 -1 10532 -1 10533 -1 10534 -1 10535 -1 10536 -1 10537 -1 10538 -1 10539 -1 10540 -1 10541 -1 10542 -1 10543 -1 10544 -1 10545 -1 10546 -1 10547 -1 10548 -1 10549 -1 10550 -1 10551 -1 10552 -1 10553 -1 10554 -1 10555 -1 10556 -1 10557 -1 10558 -1 10559 -1 10560 -1 10561 -1 10562 -1 10563 -1 10564 -1 10565 -1 10566 -1 10567 -1 10568 -1 10569 -1 10570 -1 10571 -1 10572 -1 10573 -1 10574 -1 10575 -1 10576 -1 10577 -1 10578 -1 10579 -1 10580 -1 10581 -1 10582 -1 10583 -1 10584 -1 10585 -1 10586 -1 10587 -1 10588 -1 10589 -1 10590 -1 10591 -1 10592 -1 10593 -1 10594 -1 10595 -1 10596 -1 10597 -1 10598 -1 10599 -1 10600 -1 10601 -1 10602 -1 10603 -1 10604 -1 10605 -1 10606 -1 10607 -1 10608 -1 10609 -1 10610 -1 10611 -1 10612 -1 10613 -1 10614 -1 10615 -1 10616 -1 10617 -1 10618 -1 10619 -1 10620 -1 10621 -1 10622 -1 10623 -1 10624 -1 10625 -1 10626 -1 10627 -1 10628 -1 10629 -1 10630 -1 10631 -1 10632 -1 10633 -1 10634 -1 10635 -1 10636 -1 10637 -1 10638 -1 10639 -1 10640 -1 10641 -1 10642 -1 10643 -1 10644 -1 10645 -1 10646 -1 10647 -1 10648 -1 10649 -1 10650 -1 10651 -1 10652 -1 10653 -1 10654 -1 10655 -1 10656 -1 10657 -1 10658 -1 10659 -1 10660 -1 10661 -1 10662 -1 10663 -1 10664 -1 10665 -1 10666 -1 10667 -1 10668 -1 10669 -1 10670 -1 10671 -1 10672 -1 10673 -1 10674 -1 10675 -1 10676 -1 10677 -1 10678 -1 10679 -1 10680 -1 10681 -1 10682 -1 10683 -1 10684 -1 10685 -1 10686 -1 10687 -1 10688 -1 10689 -1 10690 -1 10691 -1 10692 -1 10693 -1 10694 -1 10695 -1 10696 -1 10697 -1 10698 -1 10699 -1 10700 -1 10701 -1 10702 -1 10703 -1 10704 -1 10705 -1 10706 -1 10707 -1 10708 -1 10709 -1 10710 -1 10711 -1 10712 -1 10713 -1 10714 -1 10715 -1 10716 -1 10717 -1 10718 -1 10719 -1 10720 -1 10721 -1 10722 -1 10723 -1 10724 -1 10725 -1 10726 -1 10727 -1 10728 -1 10729 -1 10730 -1 10731 -1 10732 -1 10733 -1 10734 -1 10735 -1 10736 -1 10737 -1 10738 -1 10739 -1 10740 -1 10741 -1 10742 -1 10743 -1 10744 -1 10745 -1 10746 -1 10747 -1 10748 -1 10749 -1 10750 -1 10751 -1 10752 -1 10753 -1 10754 -1 10755 -1 10756 -1 10757 -1 10758 -1 10759 -1 10760 -1 10761 -1 10762 -1 10763 -1 10764 -1 10765 -1 10766 -1 10767 -1 10768 -1 10769 -1 10770 -1 10771 -1 10772 -1 10773 -1 10774 -1 10775 -1 10776 -1 10777 -1 10778 -1 10779 -1 10780 -1 10781 -1 10782 -1 10783 -1 10784 -1 10785 -1 10786 -1 10787 -1 10788 -1 10789 -1 10790 -1 10791 -1 10792 -1 10793 -1 10794 -1 10795 -1 10796 -1 10797 -1 10798 -1 10799 -1 10800 -1 10801 -1 10802 -1 10803 -1 10804 -1 10805 -1 10806 -1 10807 -1 10808 -1 10809 -1 10810 -1 10811 -1 10812 -1 10813 -1 10814 -1 10815 -1 10816 -1 10817 -1 10818 -1 10819 -1 10820 -1 10821 -1 10822 -1 10823 -1 10824 -1 10825 -1 10826 -1 10827 -1 10828 -1 10829 -1 10830 -1 10831 -1 10832 -1 10833 -1 10834 -1 10835 -1 10836 -1 10837 -1 10838 -1 10839 -1 10840 -1 10841 -1 10842 -1 10843 -1 10844 -1 10845 -1 10846 -1 10847 -1 10848 -1 10849 -1 10850 -1 10851 -1 10852 -1 10853 -1 10854 -1 10855 -1 10856 -1 10857 -1 10858 -1 10859 -1 10860 -1 10861 -1 10862 -1 10863 -1 10864 -1 10865 -1 10866 -1 10867 -1 10868 -1 10869 -1 10870 -1 10871 -1 10872 -1 10873 -1 10874 -1 10875 -1 10876 -1 10877 -1 10878 -1 10879 -1 10880 -1 10881 -1 10882 -1 10883 -1 10884 -1 10885 -1 10886 -1 10887 -1 10888 -1 10889 -1 10890 -1 10891 -1 10892 -1 10893 -1 10894 -1 10895 -1 10896 -1 10897 -1 10898 -1 10899 -1 10900 -1 10901 -1 10902 -1 10903 -1 10904 -1 10905 -1 10906 -1 10907 -1 10908 -1 10909 -1 10910 -1 10911 -1 10912 -1 10913 -1 10914 -1 10915 -1 10916 -1 10917 -1 10918 -1 10919 -1 10920 -1 10921 -1 10922 -1 10923 -1 10924 -1 10925 -1 10926 -1 10927 -1 10928 -1 10929 -1 10930 -1 10931 -1 10932 -1 10933 -1 10934 -1 10935 -1 10936 -1 10937 -1 10938 -1 10939 -1 10940 -1 10941 -1 10942 -1 10943 -1 10944 -1 10945 -1 10946 -1 10947 -1 10948 -1 10949 -1 10950 -1 10951 -1 10952 -1 10953 -1 10954 -1 10955 -1 10956 -1 10957 -1 10958 -1 10959 -1 10960 -1 10961 -1 10962 -1 10963 -1 10964 -1 10965 -1 10966 -1 10967 -1 10968 -1 10969 -1 10970 -1 10971 -1 10972 -1 10973 -1 10974 -1 10975 -1 10976 -1 10977 -1 10978 -1 10979 -1 10980 -1 10981 -1 10982 -1 10983 -1 10984 -1 10985 -1 10986 -1 10987 -1 10988 -1 10989 -1 10990 -1 10991 -1 10992 -1 10993 -1 10994 -1 10995 -1 10996 -1 10997 -1 10998 -1 10999 -1 11000 -1 11001 -1 11002 -1 11003 -1 11004 -1 11005 -1 11006 -1 11007 -1 11008 -1 11009 -1 11010 -1 11011 -1 11012 -1 11013 -1 11014 -1 11015 -1 11016 -1 11017 -1 11018 -1 11019 -1 11020 -1 11021 -1 11022 -1 11023 -1 11024 -1 11025 -1 11026 -1 11027 -1 11028 -1 11029 -1 11030 -1 11031 -1 11032 -1 11033 -1 11034 -1 11035 -1 11036 -1 11037 -1 11038 -1 11039 -1 11040 -1 11041 -1 11042 -1 11043 -1 11044 -1 11045 -1 11046 -1 11047 -1 11048 -1 11049 -1 11050 -1 11051 -1 11052 -1 11053 -1 11054 -1 11055 -1 11056 -1 11057 -1 11058 -1 11059 -1 11060 -1 11061 -1 11062 -1 11063 -1 11064 -1 11065 -1 11066 -1 11067 -1 11068 -1 11069 -1 11070 -1 11071 -1 11072 -1 11073 -1 11074 -1 11075 -1 11076 -1 11077 -1 11078 -1 11079 -1 11080 -1 11081 -1 11082 -1 11083 -1 11084 -1 11085 -1 11086 -1 11087 -1 11088 -1 11089 -1 11090 -1 11091 -1 11092 -1 11093 -1 11094 -1 11095 -1 11096 -1 11097 -1 11098 -1 11099 -1 11100 -1 11101 -1 11102 -1 11103 -1 11104 -1 11105 -1 11106 -1 11107 -1 11108 -1 11109 -1 11110 -1 11111 -1 11112 -1 11113 -1 11114 -1 11115 -1 11116 -1 11117 -1 11118 -1 11119 -1 11120 -1 11121 -1 11122 -1 11123 -1 11124 -1 11125 -1 11126 -1 11127 -1 11128 -1 11129 -1 11130 -1 11131 -1 11132 -1 11133 -1 11134 -1 11135 -1 11136 -1 11137 -1 11138 -1 11139 -1 11140 -1 11141 -1 11142 -1 11143 -1 11144 -1 11145 -1 11146 -1 11147 -1 11148 -1 11149 -1 11150 -1 11151 -1 11152 -1 11153 -1 11154 -1 11155 -1 11156 -1 11157 -1 11158 -1 11159 -1 11160 -1 11161 -1 11162 -1 11163 -1 11164 -1 11165 -1 11166 -1 11167 -1 11168 -1 11169 -1 11170 -1 11171 -1 11172 -1 11173 -1 11174 -1 11175 -1 11176 -1 11177 -1 11178 -1 11179 -1 11180 -1 11181 -1 11182 -1 11183 -1 11184 -1 11185 -1 11186 -1 11187 -1 11188 -1 11189 -1 11190 -1 11191 -1 11192 -1 11193 -1 11194 -1 11195 -1 11196 -1 11197 -1 11198 -1 11199 -1 11200 -1 11201 -1 11202 -1 11203 -1 11204 -1 11205 -1 11206 -1 11207 -1 11208 -1 11209 -1 11210 -1 11211 -1 11212 -1 11213 -1 11214 -1 11215 -1 11216 -1 11217 -1 11218 -1 11219 -1 11220 -1 11221 -1 11222 -1 11223 -1 11224 -1 11225 -1 11226 -1 11227 -1 11228 -1 11229 -1 11230 -1 11231 -1 11232 -1 11233 -1 11234 -1 11235 -1 11236 -1 11237 -1 11238 -1 11239 -1 11240 -1 11241 -1 11242 -1 11243 -1 11244 -1 11245 -1 11246 -1 11247 -1 11248 -1 11249 -1 11250 -1 11251 -1 11252 -1 11253 -1 11254 -1 11255 -1 11256 -1 11257 -1 11258 -1 11259 -1 11260 -1 11261 -1 11262 -1 11263 -1 11264 -1 11265 -1 11266 -1 11267 -1 11268 -1 11269 -1 11270 -1 11271 -1 11272 -1 11273 -1 11274 -1 11275 -1 11276 -1 11277 -1 11278 -1 11279 -1 11280 -1 11281 -1 11282 -1 11283 -1 11284 -1 11285 -1 11286 -1 11287 -1 11288 -1 11289 -1 11290 -1 11291 -1 11292 -1 11293 -1 11294 -1 11295 -1 11296 -1 11297 -1 11298 -1 11299 -1 11300 -1 11301 -1 11302 -1 11303 -1 11304 -1 11305 -1 11306 -1 11307 -1 11308 -1 11309 -1 11310 -1 11311 -1 11312 -1 11313 -1 11314 -1 11315 -1 11316 -1 11317 -1 11318 -1 11319 -1 11320 -1 11321 -1 11322 -1 11323 -1 11324 -1 11325 -1 11326 -1 11327 -1 11328 -1 11329 -1 11330 -1 11331 -1 11332 -1 11333 -1 11334 -1 11335 -1 11336 -1 11337 -1 11338 -1 11339 -1 11340 -1 11341 -1 11342 -1 11343 -1 11344 -1 11345 -1 11346 -1 11347 -1 11348 -1 11349 -1 11350 -1 11351 -1 11352 -1 11353 -1 11354 -1 11355 -1 11356 -1 11357 -1 11358 -1 11359 -1 11360 -1 11361 -1 11362 -1 11363 -1 11364 -1 11365 -1 11366 -1 11367 -1 11368 -1 11369 -1 11370 -1 11371 -1 11372 -1 11373 -1 11374 -1 11375 -1 11376 -1 11377 -1 11378 -1 11379 -1 11380 -1 11381 -1 11382 -1 11383 -1 11384 -1 11385 -1 11386 -1 11387 -1 11388 -1 11389 -1 11390 -1 11391 -1 11392 -1 11393 -1 11394 -1 11395 -1 11396 -1 11397 -1 11398 -1 11399 -1 11400 -1 11401 -1 11402 -1 11403 -1 11404 -1 11405 -1 11406 -1 11407 -1 11408 -1 11409 -1 11410 -1 11411 -1 11412 -1 11413 -1 11414 -1 11415 -1 11416 -1 11417 -1 11418 -1 11419 -1 11420 -1 11421 -1 11422 -1 11423 -1 11424 -1 11425 -1 11426 -1 11427 -1 11428 -1 11429 -1 11430 -1 11431 -1 11432 -1 11433 -1 11434 -1 11435 -1 11436 -1 11437 -1 11438 -1 11439 -1 11440 -1 11441 -1 11442 -1 11443 -1 11444 -1 11445 -1 11446 -1 11447 -1 11448 -1 11449 -1 11450 -1 11451 -1 11452 -1 11453 -1 11454 -1 11455 -1 11456 -1 11457 -1 11458 -1 11459 -1 11460 -1 11461 -1 11462 -1 11463 -1 11464 -1 11465 -1 11466 -1 11467 -1 11468 -1 11469 -1 11470 -1 11471 -1 11472 -1 11473 -1 11474 -1 11475 -1 11476 -1 11477 -1 11478 -1 11479 -1 11480 -1 11481 -1 11482 -1 11483 -1 11484 -1 11485 -1 11486 -1 11487 -1 11488 -1 11489 -1 11490 -1 11491 -1 11492 -1 11493 -1 11494 -1 11495 -1 11496 -1 11497 -1 11498 -1 11499 -1 11500 -1 11501 -1 11502 -1 11503 -1 11504 -1 11505 -1 11506 -1 11507 -1 11508 -1 11509 -1 11510 -1 11511 -1 11512 -1 11513 -1 11514 -1 11515 -1 11516 -1 11517 -1 11518 -1 11519 -1 11520 -1 11521 -1 11522 -1 11523 -1 11524 -1 11525 -1 11526 -1 11527 -1 11528 -1 11529 -1 11530 -1 11531 -1 11532 -1 11533 -1 11534 -1 11535 -1 11536 -1 11537 -1 11538 -1 11539 -1 11540 -1 11541 -1 11542 -1 11543 -1 11544 -1 11545 -1 11546 -1 11547 -1 11548 -1 11549 -1 11550 -1 11551 -1 11552 -1 11553 -1 11554 -1 11555 -1 11556 -1 11557 -1 11558 -1 11559 -1 11560 -1 11561 -1 11562 -1 11563 -1 11564 -1 11565 -1 11566 -1 11567 -1 11568 -1 11569 -1 11570 -1 11571 -1 11572 -1 11573 -1 11574 -1 11575 -1 11576 -1 11577 -1 11578 -1 11579 -1 11580 -1 11581 -1 11582 -1 11583 -1 11584 -1 11585 -1 11586 -1 11587 -1 11588 -1 11589 -1 11590 -1 11591 -1 11592 -1 11593 -1 11594 -1 11595 -1 11596 -1 11597 -1 11598 -1 11599 -1 11600 -1 11601 -1 11602 -1 11603 -1 11604 -1 11605 -1 11606 -1 11607 -1 11608 -1 11609 -1 11610 -1 11611 -1 11612 -1 11613 -1 11614 -1 11615 -1 11616 -1 11617 -1 11618 -1 11619 -1 11620 -1 11621 -1 11622 -1 11623 -1 11624 -1 11625 -1 11626 -1 11627 -1 11628 -1 11629 -1 11630 -1 11631 -1 11632 -1 11633 -1 11634 -1 11635 -1 11636 -1 11637 -1 11638 -1 11639 -1 11640 -1 11641 -1 11642 -1 11643 -1 11644 -1 11645 -1 11646 -1 11647 -1 11648 -1 11649 -1 11650 -1 11651 -1 11652 -1 11653 -1 11654 -1 11655 -1 11656 -1 11657 -1 11658 -1 11659 -1 11660 -1 11661 -1 11662 -1 11663 -1 11664 -1 11665 -1 11666 -1 11667 -1 11668 -1 11669 -1 11670 -1 11671 -1 11672 -1 11673 -1 11674 -1 11675 -1 11676 -1 11677 -1 11678 -1 11679 -1 11680 -1 11681 -1 11682 -1 11683 -1 11684 -1 11685 -1 11686 -1 11687 -1 11688 -1 11689 -1 11690 -1 11691 -1 11692 -1 11693 -1 11694 -1 11695 -1 11696 -1 11697 -1 11698 -1 11699 -1 11700 -1 11701 -1 11702 -1 11703 -1 11704 -1 11705 -1 11706 -1 11707 -1 11708 -1 11709 -1 11710 -1 11711 -1 11712 -1 11713 -1 11714 -1 11715 -1 11716 -1 11717 -1 11718 -1 11719 -1 11720 -1 11721 -1 11722 -1 11723 -1 11724 -1 11725 -1 11726 -1 11727 -1 11728 -1 11729 -1 11730 -1 11731 -1 11732 -1 11733 -1 11734 -1 11735 -1 11736 -1 11737 -1 11738 -1 11739 -1 11740 -1 11741 -1 11742 -1 11743 -1 11744 -1 11745 -1 11746 -1 11747 -1 11748 -1 11749 -1 11750 -1 11751 -1 11752 -1 11753 -1 11754 -1 11755 -1 11756 -1 11757 -1 11758 -1 11759 -1 11760 -1 11761 -1 11762 -1 11763 -1 11764 -1 11765 -1 11766 -1 11767 -1 11768 -1 11769 -1 11770 -1 11771 -1 11772 -1 11773 -1 11774 -1 11775 -1 11776 -1 11777 -1 11778 -1 11779 -1 11780 -1 11781 -1 11782 -1 11783 -1 11784 -1 11785 -1 11786 -1 11787 -1 11788 -1 11789 -1 11790 -1 11791 -1 11792 -1 11793 -1 11794 -1 11795 -1 11796 -1 11797 -1 11798 -1 11799 -1 11800 -1 11801 -1 11802 -1 11803 -1 11804 -1 11805 -1 11806 -1 11807 -1 11808 -1 11809 -1 11810 -1 11811 -1 11812 -1 11813 -1 11814 -1 11815 -1 11816 -1 11817 -1 11818 -1 11819 -1 11820 -1 11821 -1 11822 -1 11823 -1 11824 -1 11825 -1 11826 -1 11827 -1 11828 -1 11829 -1 11830 -1 11831 -1 11832 -1 11833 -1 11834 -1 11835 -1 11836 -1 11837 -1 11838 -1 11839 -1 11840 -1 11841 -1 11842 -1 11843 -1 11844 -1 11845 -1 11846 -1 11847 -1 11848 -1 11849 -1 11850 -1 11851 -1 11852 -1 11853 -1 11854 -1 11855 -1 11856 -1 11857 -1 11858 -1 11859 -1 11860 -1 11861 -1 11862 -1 11863 -1 11864 -1 11865 -1 11866 -1 11867 -1 11868 -1 11869 -1 11870 -1 11871 -1 11872 -1 11873 -1 11874 -1 11875 -1 11876 -1 11877 -1 11878 -1 11879 -1 11880 -1 11881 -1 11882 -1 11883 -1 11884 -1 11885 -1 11886 -1 11887 -1 11888 -1 11889 -1 11890 -1 11891 -1 11892 -1 11893 -1 11894 -1 11895 -1 11896 -1 11897 -1 11898 -1 11899 -1 11900 -1 11901 -1 11902 -1 11903 -1 11904 -1 11905 -1 11906 -1 11907 -1 11908 -1 11909 -1 11910 -1 11911 -1 11912 -1 11913 -1 11914 -1 11915 -1 11916 -1 11917 -1 11918 -1 11919 -1 11920 -1 11921 -1 11922 -1 11923 -1 11924 -1 11925 -1 11926 -1 11927 -1 11928 -1 11929 -1 11930 -1 11931 -1 11932 -1 11933 -1 11934 -1 11935 -1 11936 -1 11937 -1 11938 -1 11939 -1 11940 -1 11941 -1 11942 -1 11943 -1 11944 -1 11945 -1 11946 -1 11947 -1 11948 -1 11949 -1 11950 -1 11951 -1 11952 -1 11953 -1 11954 -1 11955 -1 11956 -1 11957 -1 11958 -1 11959 -1 11960 -1 11961 -1 11962 -1 11963 -1 11964 -1 11965 -1 11966 -1 11967 -1 11968 -1 11969 -1 11970 -1 11971 -1 11972 -1 11973 -1 11974 -1 11975 -1 11976 -1 11977 -1 11978 -1 11979 -1 11980 -1 11981 -1 11982 -1 11983 -1 11984 -1 11985 -1 11986 -1 11987 -1 11988 -1 11989 -1 11990 -1 11991 -1 11992 -1 11993 -1 11994 -1 11995 -1 11996 -1 11997 -1 11998 -1 11999 -1 12000 -1 12001 -1 12002 -1 12003 -1 12004 -1 12005 -1 12006 -1 12007 -1 12008 -1 12009 -1 12010 -1 12011 -1 12012 -1 12013 -1 12014 -1 12015 -1 12016 -1 12017 -1 12018 -1 12019 -1 12020 -1 12021 -1 12022 -1 12023 -1 12024 -1 12025 -1 12026 -1 12027 -1 12028 -1 12029 -1 12030 -1 12031 -1 12032 -1 12033 -1 12034 -1 12035 -1 12036 -1 12037 -1 12038 -1 12039 -1 12040 -1 12041 -1 12042 -1 12043 -1 12044 -1 12045 -1 12046 -1 12047 -1 12048 -1 12049 -1 12050 -1 12051 -1 12052 -1 12053 -1 12054 -1 12055 -1 12056 -1 12057 -1 12058 -1 12059 -1 12060 -1 12061 -1 12062 -1 12063 -1 12064 -1 12065 -1 12066 -1 12067 -1 12068 -1 12069 -1 12070 -1 12071 -1 12072 -1 12073 -1 12074 -1 12075 -1 12076 -1 12077 -1 12078 -1 12079 -1 12080 -1 12081 -1 12082 -1 12083 -1 12084 -1 12085 -1 12086 -1 12087 -1 12088 -1 12089 -1 12090 -1 12091 -1 12092 -1 12093 -1 12094 -1 12095 -1 12096 -1 12097 -1 12098 -1 12099 -1 12100 -1 12101 -1 12102 -1 12103 -1 12104 -1 12105 -1 12106 -1 12107 -1 12108 -1 12109 -1 12110 -1 12111 -1 12112 -1 12113 -1 12114 -1 12115 -1 12116 -1 12117 -1 12118 -1 12119 -1 12120 -1 12121 -1 12122 -1 12123 -1 12124 -1 12125 -1 12126 -1 12127 -1 12128 -1 12129 -1 12130 -1 12131 -1 12132 -1 12133 -1 12134 -1 12135 -1 12136 -1 12137 -1 12138 -1 12139 -1 12140 -1 12141 -1 12142 -1 12143 -1 12144 -1 12145 -1 12146 -1 12147 -1 12148 -1 12149 -1 12150 -1 12151 -1 12152 -1 12153 -1 12154 -1 12155 -1 12156 -1 12157 -1 12158 -1 12159 -1 12160 -1 12161 -1 12162 -1 12163 -1 12164 -1 12165 -1 12166 -1 12167 -1 12168 -1 12169 -1 12170 -1 12171 -1 12172 -1 12173 -1 12174 -1 12175 -1 12176 -1 12177 -1 12178 -1 12179 -1 12180 -1 12181 -1 12182 -1 12183 -1 12184 -1 12185 -1 12186 -1 12187 -1 12188 -1 12189 -1 12190 -1 12191 -1 12192 -1 12193 -1 12194 -1 12195 -1 12196 -1 12197 -1 12198 -1 12199 -1 12200 -1 12201 -1 12202 -1 12203 -1 12204 -1 12205 -1 12206 -1 12207 -1 12208 -1 12209 -1 12210 -1 12211 -1 12212 -1 12213 -1 12214 -1 12215 -1 12216 -1 12217 -1 12218 -1 12219 -1 12220 -1 12221 -1 12222 -1 12223 -1 12224 -1 12225 -1 12226 -1 12227 -1 12228 -1 12229 -1 12230 -1 12231 -1 12232 -1 12233 -1 12234 -1 12235 -1 12236 -1 12237 -1 12238 -1 12239 -1 12240 -1 12241 -1 12242 -1 12243 -1 12244 -1 12245 -1 12246 -1 12247 -1 12248 -1 12249 -1 12250 -1 12251 -1 12252 -1 12253 -1 12254 -1 12255 -1 12256 -1 12257 -1 12258 -1 12259 -1 12260 -1 12261 -1 12262 -1 12263 -1 12264 -1 12265 -1 12266 -1 12267 -1 12268 -1 12269 -1 12270 -1 12271 -1 12272 -1 12273 -1 12274 -1 12275 -1 12276 -1 12277 -1 12278 -1 12279 -1 12280 -1 12281 -1 12282 -1 12283 -1 12284 -1 12285 -1 12286 -1 12287 -1 12288 -1 12289 -1 12290 -1 12291 -1 12292 -1 12293 -1 12294 -1 12295 -1 12296 -1 12297 -1 12298 -1 12299 -1 12300 -1 12301 -1 12302 -1 12303 -1 12304 -1 12305 -1 12306 -1 12307 -1 12308 -1 12309 -1 12310 -1 12311 -1 12312 -1 12313 -1 12314 -1 12315 -1 12316 -1 12317 -1 12318 -1 12319 -1 12320 -1 12321 -1 12322 -1 12323 -1 12324 -1 12325 -1 12326 -1 12327 -1 12328 -1 12329 -1 12330 -1 12331 -1 12332 -1 12333 -1 12334 -1 12335 -1 12336 -1 12337 -1 12338 -1 12339 -1 12340 -1 12341 -1 12342 -1 12343 -1 12344 -1 12345 -1 12346 -1 12347 -1 12348 -1 12349 -1 12350 -1 12351 -1 12352 -1 12353 -1 12354 -1 12355 -1 12356 -1 12357 -1 12358 -1 12359 -1 12360 -1 12361 -1 12362 -1 12363 -1 12364 -1 12365 -1 12366 -1 12367 -1 12368 -1 12369 -1 12370 -1 12371 -1 12372 -1 12373 -1 12374 -1 12375 -1 12376 -1 12377 -1 12378 -1 12379 -1 12380 -1 12381 -1 12382 -1 12383 -1 12384 -1 12385 -1 12386 -1 12387 -1 12388 -1 12389 -1 12390 -1 12391 -1 12392 -1 12393 -1 12394 -1 12395 -1 12396 -1 12397 -1 12398 -1 12399 -1 12400 -1 12401 -1 12402 -1 12403 -1 12404 -1 12405 -1 12406 -1 12407 -1 12408 -1 12409 -1 12410 -1 12411 -1 12412 -1 12413 -1 12414 -1 12415 -1 12416 -1 12417 -1 12418 -1 12419 -1 12420 -1 12421 -1 12422 -1 12423 -1 12424 -1 12425 -1 12426 -1 12427 -1 12428 -1 12429 -1 12430 -1 12431 -1 12432 -1 12433 -1 12434 -1 12435 -1 12436 -1 12437 -1 12438 -1 12439 -1 12440 -1 12441 -1 12442 -1 12443 -1 12444 -1 12445 -1 12446 -1 12447 -1 12448 -1 12449 -1 12450 -1 12451 -1 12452 -1 12453 -1 12454 -1 12455 -1 12456 -1 12457 -1 12458 -1 12459 -1 12460 -1 12461 -1 12462 -1 12463 -1 12464 -1 12465 -1 12466 -1 12467 -1 12468 -1 12469 -1 12470 -1 12471 -1 12472 -1 12473 -1 12474 -1 12475 -1 12476 -1 12477 -1 12478 -1 12479 -1 12480 -1 12481 -1 12482 -1 12483 -1 12484 -1 12485 -1 12486 -1 12487 -1 12488 -1 12489 -1 12490 -1 12491 -1 12492 -1 12493 -1 12494 -1 12495 -1 12496 -1 12497 -1 12498 -1 12499 -1 12500 -1 12501 -1 12502 -1 12503 -1 12504 -1 12505 -1 12506 -1 12507 -1 12508 -1 12509 -1 12510 -1 12511 -1 12512 -1 12513 -1 12514 -1 12515 -1 12516 -1 12517 -1 12518 -1 12519 -1 12520 -1 12521 -1 12522 -1 12523 -1 12524 -1 12525 -1 12526 -1 12527 -1 12528 -1 12529 -1 12530 -1 12531 -1 12532 -1 12533 -1 12534 -1 12535 -1 12536 -1 12537 -1 12538 -1 12539 -1 12540 -1 12541 -1 12542 -1 12543 -1 12544 -1 12545 -1 12546 -1 12547 -1 12548 -1 12549 -1 12550 -1 12551 -1 12552 -1 12553 -1 12554 -1 12555 -1 12556 -1 12557 -1 12558 -1 12559 -1 12560 -1 12561 -1 12562 -1 12563 -1 12564 -1 12565 -1 12566 -1 12567 -1 12568 -1 12569 -1 12570 -1 12571 -1 12572 -1 12573 -1 12574 -1 12575 -1 12576 -1 12577 -1 12578 -1 12579 -1 12580 -1 12581 -1 12582 -1 12583 -1 12584 -1 12585 -1 12586 -1 12587 -1 12588 -1 12589 -1 12590 -1 12591 -1 12592 -1 12593 -1 12594 -1 12595 -1 12596 -1 12597 -1 12598 -1 12599 -1 12600 -1 12601 -1 12602 -1 12603 -1 12604 -1 12605 -1 12606 -1 12607 -1 12608 -1 12609 -1 12610 -1 12611 -1 12612 -1 12613 -1 12614 -1 12615 -1 12616 -1 12617 -1 12618 -1 12619 -1 12620 -1 12621 -1 12622 -1 12623 -1 12624 -1 12625 -1 12626 -1 12627 -1 12628 -1 12629 -1 12630 -1 12631 -1 12632 -1 12633 -1 12634 -1 12635 -1 12636 -1 12637 -1 12638 -1 12639 -1 12640 -1 12641 -1 12642 -1 12643 -1 12644 -1 12645 -1 12646 -1 12647 -1 12648 -1 12649 -1 12650 -1 12651 -1 12652 -1 12653 -1 12654 -1 12655 -1 12656 -1 12657 -1 12658 -1 12659 -1 12660 -1 12661 -1 12662 -1 12663 -1 12664 -1 12665 -1 12666 -1 12667 -1 12668 -1 12669 -1 12670 -1 12671 -1 12672 -1 12673 -1 12674 -1 12675 -1 12676 -1 12677 -1 12678 -1 12679 -1 12680 -1 12681 -1 12682 -1 12683 -1 12684 -1 12685 -1 12686 -1 12687 -1 12688 -1 12689 -1 12690 -1 12691 -1 12692 -1 12693 -1 12694 -1 12695 -1 12696 -1 12697 -1 12698 -1 12699 -1 12700 -1 12701 -1 12702 -1 12703 -1 12704 -1 12705 -1 12706 -1 12707 -1 12708 -1 12709 -1 12710 -1 12711 -1 12712 -1 12713 -1 12714 -1 12715 -1 12716 -1 12717 -1 12718 -1 12719 -1 12720 -1 12721 -1 12722 -1 12723 -1 12724 -1 12725 -1 12726 -1 12727 -1 12728 -1 12729 -1 12730 -1 12731 -1 12732 -1 12733 -1 12734 -1 12735 -1 12736 -1 12737 -1 12738 -1 12739 -1 12740 -1 12741 -1 12742 -1 12743 -1 12744 -1 12745 -1 12746 -1 12747 -1 12748 -1 12749 -1 12750 -1 12751 -1 12752 -1 12753 -1 12754 -1 12755 -1 12756 -1 12757 -1 12758 -1 12759 -1 12760 -1 12761 -1 12762 -1 12763 -1 12764 -1 12765 -1 12766 -1 12767 -1 12768 -1 12769 -1 12770 -1 12771 -1 12772 -1 12773 -1 12774 -1 12775 -1 12776 -1 12777 -1 12778 -1 12779 -1 12780 -1 12781 -1 12782 -1 12783 -1 12784 -1 12785 -1 12786 -1 12787 -1 12788 -1 12789 -1 12790 -1 12791 -1 12792 -1 12793 -1 12794 -1 12795 -1 12796 -1 12797 -1 12798 -1 12799 -1 12800 -1 12801 -1 12802 -1 12803 -1 12804 -1 12805 -1 12806 -1 12807 -1 12808 -1 12809 -1 12810 -1 12811 -1 12812 -1 12813 -1 12814 -1 12815 -1 12816 -1 12817 -1 12818 -1 12819 -1 12820 -1 12821 -1 12822 -1 12823 -1 12824 -1 12825 -1 12826 -1 12827 -1 12828 -1 12829 -1 12830 -1 12831 -1 12832 -1 12833 -1 12834 -1 12835 -1 12836 -1 12837 -1 12838 -1 12839 -1 12840 -1 12841 -1 12842 -1 12843 -1 12844 -1 12845 -1 12846 -1 12847 -1 12848 -1 12849 -1 12850 -1 12851 -1 12852 -1 12853 -1 12854 -1 12855 -1 12856 -1 12857 -1 12858 -1 12859 -1 12860 -1 12861 -1 12862 -1 12863 -1 12864 -1 12865 -1 12866 -1 12867 -1 12868 -1 12869 -1 12870 -1 12871 -1 12872 -1 12873 -1 12874 -1 12875 -1 12876 -1 12877 -1 12878 -1 12879 -1 12880 -1 12881 -1 12882 -1 12883 -1 12884 -1 12885 -1 12886 -1 12887 -1 12888 -1 12889 -1 12890 -1 12891 -1 12892 -1 12893 -1 12894 -1 12895 -1 12896 -1 12897 -1 12898 -1 12899 -1 12900 -1 12901 -1 12902 -1 12903 -1 12904 -1 12905 -1 12906 -1 12907 -1 12908 -1 12909 -1 12910 -1 12911 -1 12912 -1 12913 -1 12914 -1 12915 -1 12916 -1 12917 -1 12918 -1 12919 -1 12920 -1 12921 -1 12922 -1 12923 -1 12924 -1 12925 -1 12926 -1 12927 -1 12928 -1 12929 -1 12930 -1 12931 -1 12932 -1 12933 -1 12934 -1 12935 -1 12936 -1 12937 -1 12938 -1 12939 -1 12940 -1 12941 -1 12942 -1 12943 -1 12944 -1 12945 -1 12946 -1 12947 -1 12948 -1 12949 -1 12950 -1 12951 -1 12952 -1 12953 -1 12954 -1 12955 -1 12956 -1 12957 -1 12958 -1 12959 -1 12960 -1 12961 -1 12962 -1 12963 -1 12964 -1 12965 -1 12966 -1 12967 -1 12968 -1 12969 -1 12970 -1 12971 -1 12972 -1 12973 -1 12974 -1 12975 -1 12976 -1 12977 -1 12978 -1 12979 -1 12980 -1 12981 -1 12982 -1 12983 -1 12984 -1 12985 -1 12986 -1 12987 -1 12988 -1 12989 -1 12990 -1 12991 -1 12992 -1 12993 -1 12994 -1 12995 -1 12996 -1 12997 -1 12998 -1 12999 -1 13000 -1 13001 -1 13002 -1 13003 -1 13004 -1 13005 -1 13006 -1 13007 -1 13008 -1 13009 -1 13010 -1 13011 -1 13012 -1 13013 -1 13014 -1 13015 -1 13016 -1 13017 -1 13018 -1 13019 -1 13020 -1 13021 -1 13022 -1 13023 -1 13024 -1 13025 -1 13026 -1 13027 -1 13028 -1 13029 -1 13030 -1 13031 -1 13032 -1 13033 -1 13034 -1 13035 -1 13036 -1 13037 -1 13038 -1 13039 -1 13040 -1 13041 -1 13042 -1 13043 -1 13044 -1 13045 -1 13046 -1 13047 -1 13048 -1 13049 -1 13050 -1 13051 -1 13052 -1 13053 -1 13054 -1 13055 -1 13056 -1 13057 -1 13058 -1 13059 -1 13060 -1 13061 -1 13062 -1 13063 -1 13064 -1 13065 -1 13066 -1 13067 -1 13068 -1 13069 -1 13070 -1 13071 -1 13072 -1 13073 -1 13074 -1 13075 -1 13076 -1 13077 -1 13078 -1 13079 -1 13080 -1 13081 -1 13082 -1 13083 -1 13084 -1 13085 -1 13086 -1 13087 -1 13088 -1 13089 -1 13090 -1 13091 -1 13092 -1 13093 -1 13094 -1 13095 -1 13096 -1 13097 -1 13098 -1 13099 -1 13100 -1 13101 -1 13102 -1 13103 -1 13104 -1 13105 -1 13106 -1 13107 -1 13108 -1 13109 -1 13110 -1 13111 -1 13112 -1 13113 -1 13114 -1 13115 -1 13116 -1 13117 -1 13118 -1 13119 -1 13120 -1 13121 -1 13122 -1 13123 -1 13124 -1 13125 -1 13126 -1 13127 -1 13128 -1 13129 -1 13130 -1 13131 -1 13132 -1 13133 -1 13134 -1 13135 -1 13136 -1 13137 -1 13138 -1 13139 -1 13140 -1 13141 -1 13142 -1 13143 -1 13144 -1 13145 -1 13146 -1 13147 -1 13148 -1 13149 -1 13150 -1 13151 -1 13152 -1 13153 -1 13154 -1 13155 -1 13156 -1 13157 -1 13158 -1 13159 -1 13160 -1 13161 -1 13162 -1 13163 -1 13164 -1 13165 -1 13166 -1 13167 -1 13168 -1 13169 -1 13170 -1 13171 -1 13172 -1 13173 -1 13174 -1 13175 -1 13176 -1 13177 -1 13178 -1 13179 -1 13180 -1 13181 -1 13182 -1 13183 -1 13184 -1 13185 -1 13186 -1 13187 -1 13188 -1 13189 -1 13190 -1 13191 -1 13192 -1 13193 -1 13194 -1 13195 -1 13196 -1 13197 -1 13198 -1 13199 -1 13200 -1 13201 -1 13202 -1 13203 -1 13204 -1 13205 -1 13206 -1 13207 -1 13208 -1 13209 -1 13210 -1 13211 -1 13212 -1 13213 -1 13214 -1 13215 -1 13216 -1 13217 -1 13218 -1 13219 -1 13220 -1 13221 -1 13222 -1 13223 -1 13224 -1 13225 -1 13226 -1 13227 -1 13228 -1 13229 -1 13230 -1 13231 -1 13232 -1 13233 -1 13234 -1 13235 -1 13236 -1 13237 -1 13238 -1 13239 -1 13240 -1 13241 -1 13242 -1 13243 -1 13244 -1 13245 -1 13246 -1 13247 -1 13248 -1 13249 -1 13250 -1 13251 -1 13252 -1 13253 -1 13254 -1 13255 -1 13256 -1 13257 -1 13258 -1 13259 -1 13260 -1 13261 -1 13262 -1 13263 -1 13264 -1 13265 -1 13266 -1 13267 -1 13268 -1 13269 -1 13270 -1 13271 -1 13272 -1 13273 -1 13274 -1 13275 -1 13276 -1 13277 -1 13278 -1 13279 -1 13280 -1 13281 -1 13282 -1 13283 -1 13284 -1 13285 -1 13286 -1 13287 -1 13288 -1 13289 -1 13290 -1 13291 -1 13292 -1 13293 -1 13294 -1 13295 -1 13296 -1 13297 -1 13298 -1 13299 -1 13300 -1 13301 -1 13302 -1 13303 -1 13304 -1 13305 -1 13306 -1 13307 -1 13308 -1 13309 -1 13310 -1 13311 -1 13312 -1 13313 -1 13314 -1 13315 -1 13316 -1 13317 -1 13318 -1 13319 -1 13320 -1 13321 -1 13322 -1 13323 -1 13324 -1 13325 -1 13326 -1 13327 -1 13328 -1 13329 -1 13330 -1 13331 -1 13332 -1 13333 -1 13334 -1 13335 -1 13336 -1 13337 -1 13338 -1 13339 -1 13340 -1 13341 -1 13342 -1 13343 -1 13344 -1 13345 -1 13346 -1 13347 -1 13348 -1 13349 -1 13350 -1 13351 -1 13352 -1 13353 -1 13354 -1 13355 -1 13356 -1 13357 -1 13358 -1 13359 -1 13360 -1 13361 -1 13362 -1 13363 -1 13364 -1 13365 -1 13366 -1 13367 -1 13368 -1 13369 -1 13370 -1 13371 -1 13372 -1 13373 -1 13374 -1 13375 -1 13376 -1 13377 -1 13378 -1 13379 -1 13380 -1 13381 -1 13382 -1 13383 -1 13384 -1 13385 -1 13386 -1 13387 -1 13388 -1 13389 -1 13390 -1 13391 -1 13392 -1 13393 -1 13394 -1 13395 -1 13396 -1 13397 -1 13398 -1 13399 -1 13400 -1 13401 -1 13402 -1 13403 -1 13404 -1 13405 -1 13406 -1 13407 -1 13408 -1 13409 -1 13410 -1 13411 -1 13412 -1 13413 -1 13414 -1 13415 -1 13416 -1 13417 -1 13418 -1 13419 -1 13420 -1 13421 -1 13422 -1 13423 -1 13424 -1 13425 -1 13426 -1 13427 -1 13428 -1 13429 -1 13430 -1 13431 -1 13432 -1 13433 -1 13434 -1 13435 -1 13436 -1 13437 -1 13438 -1 13439 -1 13440 -1 13441 -1 13442 -1 13443 -1 13444 -1 13445 -1 13446 -1 13447 -1 13448 -1 13449 -1 13450 -1 13451 -1 13452 -1 13453 -1 13454 -1 13455 -1 13456 -1 13457 -1 13458 -1 13459 -1 13460 -1 13461 -1 13462 -1 13463 -1 13464 -1 13465 -1 13466 -1 13467 -1 13468 -1 13469 -1 13470 -1 13471 -1 13472 -1 13473 -1 13474 -1 13475 -1 13476 -1 13477 -1 13478 -1 13479 -1 13480 -1 13481 -1 13482 -1 13483 -1 13484 -1 13485 -1 13486 -1 13487 -1 13488 -1 13489 -1 13490 -1 13491 -1 13492 -1 13493 -1 13494 -1 13495 -1 13496 -1 13497 -1 13498 -1 13499 -1 13500 -1 13501 -1 13502 -1 13503 -1 13504 -1 13505 -1 13506 -1 13507 -1 13508 -1 13509 -1 13510 -1 13511 -1 13512 -1 13513 -1 13514 -1 13515 -1 13516 -1 13517 -1 13518 -1 13519 -1 13520 -1 13521 -1 13522 -1 13523 -1 13524 -1 13525 -1 13526 -1 13527 -1 13528 -1 13529 -1 13530 -1 13531 -1 13532 -1 13533 -1 13534 -1 13535 -1 13536 -1 13537 -1 13538 -1 13539 -1 13540 -1 13541 -1 13542 -1 13543 -1 13544 -1 13545 -1 13546 -1 13547 -1 13548 -1 13549 -1 13550 -1 13551 -1 13552 -1 13553 -1 13554 -1 13555 -1 13556 -1 13557 -1 13558 -1 13559 -1 13560 -1 13561 -1 13562 -1 13563 -1 13564 -1 13565 -1 13566 -1 13567 -1 13568 -1 13569 -1 13570 -1 13571 -1 13572 -1 13573 -1 13574 -1 13575 -1 13576 -1 13577 -1 13578 -1 13579 -1 13580 -1 13581 -1 13582 -1 13583 -1 13584 -1 13585 -1 13586 -1 13587 -1 13588 -1 13589 -1 13590 -1 13591 -1 13592 -1 13593 -1 13594 -1 13595 -1 13596 -1 13597 -1 13598 -1 13599 -1 13600 -1 13601 -1 13602 -1 13603 -1 13604 -1 13605 -1 13606 -1 13607 -1 13608 -1 13609 -1 13610 -1 13611 -1 13612 -1 13613 -1 13614 -1 13615 -1 13616 -1 13617 -1 13618 -1 13619 -1 13620 -1 13621 -1 13622 -1 13623 -1 13624 -1 13625 -1 13626 -1 13627 -1 13628 -1 13629 -1 13630 -1 13631 -1 13632 -1 13633 -1 13634 -1 13635 -1 13636 -1 13637 -1 13638 -1 13639 -1 13640 -1 13641 -1 13642 -1 13643 -1 13644 -1 13645 -1 13646 -1 13647 -1 13648 -1 13649 -1 13650 -1 13651 -1 13652 -1 13653 -1 13654 -1 13655 -1 13656 -1 13657 -1 13658 -1 13659 -1 13660 -1 13661 -1 13662 -1 13663 -1 13664 -1 13665 -1 13666 -1 13667 -1 13668 -1 13669 -1 13670 -1 13671 -1 13672 -1 13673 -1 13674 -1 13675 -1 13676 -1 13677 -1 13678 -1 13679 -1 13680 -1 13681 -1 13682 -1 13683 -1 13684 -1 13685 -1 13686 -1 13687 -1 13688 -1 13689 -1 13690 -1 13691 -1 13692 -1 13693 -1 13694 -1 13695 -1 13696 -1 13697 -1 13698 -1 13699 -1 13700 -1 13701 -1 13702 -1 13703 -1 13704 -1 13705 -1 13706 -1 13707 -1 13708 -1 13709 -1 13710 -1 13711 -1 13712 -1 13713 -1 13714 -1 13715 -1 13716 -1 13717 -1 13718 -1 13719 -1 13720 -1 13721 -1 13722 -1 13723 -1 13724 -1 13725 -1 13726 -1 13727 -1 13728 -1 13729 -1 13730 -1 13731 -1 13732 -1 13733 -1 13734 -1 13735 -1 13736 -1 13737 -1 13738 -1 13739 -1 13740 -1 13741 -1 13742 -1 13743 -1 13744 -1 13745 -1 13746 -1 13747 -1 13748 -1 13749 -1 13750 -1 13751 -1 13752 -1 13753 -1 13754 -1 13755 -1 13756 -1 13757 -1 13758 -1 13759 -1 13760 -1 13761 -1 13762 -1 13763 -1 13764 -1 13765 -1 13766 -1 13767 -1 13768 -1 13769 -1 13770 -1 13771 -1 13772 -1 13773 -1 13774 -1 13775 -1 13776 -1 13777 -1 13778 -1 13779 -1 13780 -1 13781 -1 13782 -1 13783 -1 13784 -1 13785 -1 13786 -1 13787 -1 13788 -1 13789 -1 13790 -1 13791 -1 13792 -1 13793 -1 13794 -1 13795 -1 13796 -1 13797 -1 13798 -1 13799 -1 13800 -1 13801 -1 13802 -1 13803 -1 13804 -1 13805 -1 13806 -1 13807 -1 13808 -1 13809 -1 13810 -1 13811 -1 13812 -1 13813 -1 13814 -1 13815 -1 13816 -1 13817 -1 13818 -1 13819 -1 13820 -1 13821 -1 13822 -1 13823 -1 13824 -1 13825 -1 13826 -1 13827 -1 13828 -1 13829 -1 13830 -1 13831 -1 13832 -1 13833 -1 13834 -1 13835 -1 13836 -1 13837 -1 13838 -1 13839 -1 13840 -1 13841 -1 13842 -1 13843 -1 13844 -1 13845 -1 13846 -1 13847 -1 13848 -1 13849 -1 13850 -1 13851 -1 13852 -1 13853 -1 13854 -1 13855 -1 13856 -1 13857 -1 13858 -1 13859 -1 13860 -1 13861 -1 13862 -1 13863 -1 13864 -1 13865 -1 13866 -1 13867 -1 13868 -1 13869 -1 13870 -1 13871 -1 13872 -1 13873 -1 13874 -1 13875 -1 13876 -1 13877 -1 13878 -1 13879 -1 13880 -1 13881 -1 13882 -1 13883 -1 13884 -1 13885 -1 13886 -1 13887 -1 13888 -1 13889 -1 13890 -1 13891 -1 13892 -1 13893 -1 13894 -1 13895 -1 13896 -1 13897 -1 13898 -1 13899 -1 13900 -1 13901 -1 13902 -1 13903 -1 13904 -1 13905 -1 13906 -1 13907 -1 13908 -1 13909 -1 13910 -1 13911 -1 13912 -1 13913 -1 13914 -1 13915 -1 13916 -1 13917 -1 13918 -1 13919 -1 13920 -1 13921 -1 13922 -1 13923 -1 13924 -1 13925 -1 13926 -1 13927 -1 13928 -1 13929 -1 13930 -1 13931 -1 13932 -1 13933 -1 13934 -1 13935 -1 13936 -1 13937 -1 13938 -1 13939 -1 13940 -1 13941 -1 13942 -1 13943 -1 13944 -1 13945 -1 13946 -1 13947 -1 13948 -1 13949 -1 13950 -1 13951 -1 13952 -1 13953 -1 13954 -1 13955 -1 13956 -1 13957 -1 13958 -1 13959 -1 13960 -1 13961 -1 13962 -1 13963 -1 13964 -1 13965 -1 13966 -1 13967 -1 13968 -1 13969 -1 13970 -1 13971 -1 13972 -1 13973 -1 13974 -1 13975 -1 13976 -1 13977 -1 13978 -1 13979 -1 13980 -1 13981 -1 13982 -1 13983 -1 13984 -1 13985 -1 13986 -1 13987 -1 13988 -1 13989 -1 13990 -1 13991 -1 13992 -1 13993 -1 13994 -1 13995 -1 13996 -1 13997 -1 13998 -1 13999 -1 14000 -1 14001 -1 14002 -1 14003 -1 14004 -1 14005 -1 14006 -1 14007 -1 14008 -1 14009 -1 14010 -1 14011 -1 14012 -1 14013 -1 14014 -1 14015 -1 14016 -1 14017 -1 14018 -1 14019 -1 14020 -1 14021 -1 14022 -1 14023 -1 14024 -1 14025 -1 14026 -1 14027 -1 14028 -1 14029 -1 14030 -1 14031 -1 14032 -1 14033 -1 14034 -1 14035 -1 14036 -1 14037 -1 14038 -1 14039 -1 14040 -1 14041 -1 14042 -1 14043 -1 14044 -1 14045 -1 14046 -1 14047 -1 14048 -1 14049 -1 14050 -1 14051 -1 14052 -1 14053 -1 14054 -1 14055 -1 14056 -1 14057 -1 14058 -1 14059 -1 14060 -1 14061 -1 14062 -1 14063 -1 14064 -1 14065 -1 14066 -1 14067 -1 14068 -1 14069 -1 14070 -1 14071 -1 14072 -1 14073 -1 14074 -1 14075 -1 14076 -1 14077 -1 14078 -1 14079 -1 14080 -1 14081 -1 14082 -1 14083 -1 14084 -1 14085 -1 14086 -1 14087 -1 14088 -1 14089 -1 14090 -1 14091 -1 14092 -1 14093 -1 14094 -1 14095 -1 14096 -1 14097 -1 14098 -1 14099 -1 14100 -1 14101 -1 14102 -1 14103 -1 14104 -1 14105 -1 14106 -1 14107 -1 14108 -1 14109 -1 14110 -1 14111 -1 14112 -1 14113 -1 14114 -1 14115 -1 14116 -1 14117 -1 14118 -1 14119 -1 14120 -1 14121 -1 14122 -1 14123 -1 14124 -1 14125 -1 14126 -1 14127 -1 14128 -1 14129 -1 14130 -1 14131 -1 14132 -1 14133 -1 14134 -1 14135 -1 14136 -1 14137 -1 14138 -1 14139 -1 14140 -1 14141 -1 14142 -1 14143 -1 14144 -1 14145 -1 14146 -1 14147 -1 14148 -1 14149 -1 14150 -1 14151 -1 14152 -1 14153 -1 14154 -1 14155 -1 14156 -1 14157 -1 14158 -1 14159 -1 14160 -1 14161 -1 14162 -1 14163 -1 14164 -1 14165 -1 14166 -1 14167 -1 14168 -1 14169 -1 14170 -1 14171 -1 14172 -1 14173 -1 14174 -1 14175 -1 14176 -1 14177 -1 14178 -1 14179 -1 14180 -1 14181 -1 14182 -1 14183 -1 14184 -1 14185 -1 14186 -1 14187 -1 14188 -1 14189 -1 14190 -1 14191 -1 14192 -1 14193 -1 14194 -1 14195 -1 14196 -1 14197 -1 14198 -1 14199 -1 14200 -1 14201 -1 14202 -1 14203 -1 14204 -1 14205 -1 14206 -1 14207 -1 14208 -1 14209 -1 14210 -1 14211 -1 14212 -1 14213 -1 14214 -1 14215 -1 14216 -1 14217 -1 14218 -1 14219 -1 14220 -1 14221 -1 14222 -1 14223 -1 14224 -1 14225 -1 14226 -1 14227 -1 14228 -1 14229 -1 14230 -1 14231 -1 14232 -1 14233 -1 14234 -1 14235 -1 14236 -1 14237 -1 14238 -1 14239 -1 14240 -1 14241 -1 14242 -1 14243 -1 14244 -1 14245 -1 14246 -1 14247 -1 14248 -1 14249 -1 14250 -1 14251 -1 14252 -1 14253 -1 14254 -1 14255 -1 14256 -1 14257 -1 14258 -1 14259 -1 14260 -1 14261 -1 14262 -1 14263 -1 14264 -1 14265 -1 14266 -1 14267 -1 14268 -1 14269 -1 14270 -1 14271 -1 14272 -1 14273 -1 14274 -1 14275 -1 14276 -1 14277 -1 14278 -1 14279 -1 14280 -1 14281 -1 14282 -1 14283 -1 14284 -1 14285 -1 14286 -1 14287 -1 14288 -1 14289 -1 14290 -1 14291 -1 14292 -1 14293 -1 14294 -1 14295 -1 14296 -1 14297 -1 14298 -1 14299 -1 14300 -1 14301 -1 14302 -1 14303 -1 14304 -1 14305 -1 14306 -1 14307 -1 14308 -1 14309 -1 14310 -1 14311 -1 14312 -1 14313 -1 14314 -1 14315 -1 14316 -1 14317 -1 14318 -1 14319 -1 14320 -1 14321 -1 14322 -1 14323 -1 14324 -1 14325 -1 14326 -1 14327 -1 14328 -1 14329 -1 14330 -1 14331 -1 14332 -1 14333 -1 14334 -1 14335 -1 14336 -1 14337 -1 14338 -1 14339 -1 14340 -1 14341 -1 14342 -1 14343 -1 14344 -1 14345 -1 14346 -1 14347 -1 14348 -1 14349 -1 14350 -1 14351 -1 14352 -1 14353 -1 14354 -1 14355 -1 14356 -1 14357 -1 14358 -1 14359 -1 14360 -1 14361 -1 14362 -1 14363 -1 14364 -1 14365 -1 14366 -1 14367 -1 14368 -1 14369 -1 14370 -1 14371 -1 14372 -1 14373 -1 14374 -1 14375 -1 14376 -1 14377 -1 14378 -1 14379 -1 14380 -1 14381 -1 14382 -1 14383 -1 14384 -1 14385 -1 14386 -1 14387 -1 14388 -1 14389 -1 14390 -1 14391 -1 14392 -1 14393 -1 14394 -1 14395 -1 14396 -1 14397 -1 14398 -1 14399 -1 14400 -1 14401 -1 14402 -1 14403 -1 14404 -1 14405 -1 14406 -1 14407 -1 14408 -1 14409 -1 14410 -1 14411 -1 14412 -1 14413 -1 14414 -1 14415 -1 14416 -1 14417 -1 14418 -1 14419 -1 14420 -1 14421 -1 14422 -1 14423 -1 14424 -1 14425 -1 14426 -1 14427 -1 14428 -1 14429 -1 14430 -1 14431 -1 14432 -1 14433 -1 14434 -1 14435 -1 14436 -1 14437 -1 14438 -1 14439 -1 14440 -1 14441 -1 14442 -1 14443 -1 14444 -1 14445 -1 14446 -1 14447 -1 14448 -1 14449 -1 14450 -1 14451 -1 14452 -1 14453 -1 14454 -1 14455 -1 14456 -1 14457 -1 14458 -1 14459 -1 14460 -1 14461 -1 14462 -1 14463 -1 14464 -1 14465 -1 14466 -1 14467 -1 14468 -1 14469 -1 14470 -1 14471 -1 14472 -1 14473 -1 14474 -1 14475 -1 14476 -1 14477 -1 14478 -1 14479 -1 14480 -1 14481 -1 14482 -1 14483 -1 14484 -1 14485 -1 14486 -1 14487 -1 14488 -1 14489 -1 14490 -1 14491 -1 14492 -1 14493 -1 14494 -1 14495 -1 14496 -1 14497 -1 14498 -1 14499 -1 14500 -1 14501 -1 14502 -1 14503 -1 14504 -1 14505 -1 14506 -1 14507 -1 14508 -1 14509 -1 14510 -1 14511 -1 14512 -1 14513 -1 14514 -1 14515 -1 14516 -1 14517 -1 14518 -1 14519 -1 14520 -1 14521 -1 14522 -1 14523 -1 14524 -1 14525 -1 14526 -1 14527 -1 14528 -1 14529 -1 14530 -1 14531 -1 14532 -1 14533 -1 14534 -1 14535 -1 14536 -1 14537 -1 14538 -1 14539 -1 14540 -1 14541 -1 14542 -1 14543 -1 14544 -1 14545 -1 14546 -1 14547 -1 14548 -1 14549 -1 14550 -1 14551 -1 14552 -1 14553 -1 14554 -1 14555 -1 14556 -1 14557 -1 14558 -1 14559 -1 14560 -1 14561 -1 14562 -1 14563 -1 14564 -1 14565 -1 14566 -1 14567 -1 14568 -1 14569 -1 14570 -1 14571 -1 14572 -1 14573 -1 14574 -1 14575 -1 14576 -1 14577 -1 14578 -1 14579 -1 14580 -1 14581 -1 14582 -1 14583 -1 14584 -1 14585 -1 14586 -1 14587 -1 14588 -1 14589 -1 14590 -1 14591 -1 14592 -1 14593 -1 14594 -1 14595 -1 14596 -1 14597 -1 14598 -1 14599 -1 14600 -1 14601 -1 14602 -1 14603 -1 14604 -1 14605 -1 14606 -1 14607 -1 14608 -1 14609 -1 14610 -1 14611 -1 14612 -1 14613 -1 14614 -1 14615 -1 14616 -1 14617 -1 14618 -1 14619 -1 14620 -1 14621 -1 14622 -1 14623 -1 14624 -1 14625 -1 14626 -1 14627 -1 14628 -1 14629 -1 14630 -1 14631 -1 14632 -1 14633 -1 14634 -1 14635 -1 14636 -1 14637 -1 14638 -1 14639 -1 14640 -1 14641 -1 14642 -1 14643 -1 14644 -1 14645 -1 14646 -1 14647 -1 14648 -1 14649 -1 14650 -1 14651 -1 14652 -1 14653 -1 14654 -1 14655 -1 14656 -1 14657 -1 14658 -1 14659 -1 14660 -1 14661 -1 14662 -1 14663 -1 14664 -1 14665 -1 14666 -1 14667 -1 14668 -1 14669 -1 14670 -1 14671 -1 14672 -1 14673 -1 14674 -1 14675 -1 14676 -1 14677 -1 14678 -1 14679 -1 14680 -1 14681 -1 14682 -1 14683 -1 14684 -1 14685 -1 14686 -1 14687 -1 14688 -1 14689 -1 14690 -1 14691 -1 14692 -1 14693 -1 14694 -1 14695 -1 14696 -1 14697 -1 14698 -1 14699 -1 14700 -1 14701 -1 14702 -1 14703 -1 14704 -1 14705 -1 14706 -1 14707 -1 14708 -1 14709 -1 14710 -1 14711 -1 14712 -1 14713 -1 14714 -1 14715 -1 14716 -1 14717 -1 14718 -1 14719 -1 14720 -1 14721 -1 14722 -1 14723 -1 14724 -1 14725 -1 14726 -1 14727 -1 14728 -1 14729 -1 14730 -1 14731 -1 14732 -1 14733 -1 14734 -1 14735 -1 14736 -1 14737 -1 14738 -1 14739 -1 14740 -1 14741 -1 14742 -1 14743 -1 14744 -1 14745 -1 14746 -1 14747 -1 14748 -1 14749 -1 14750 -1 14751 -1 14752 -1 14753 -1 14754 -1 14755 -1 14756 -1 14757 -1 14758 -1 14759 -1 14760 -1 14761 -1 14762 -1 14763 -1 14764 -1 14765 -1 14766 -1 14767 -1 14768 -1 14769 -1 14770 -1 14771 -1 14772 -1 14773 -1 14774 -1 14775 -1 14776 -1 14777 -1 14778 -1 14779 -1 14780 -1 14781 -1 14782 -1 14783 -1 14784 -1 14785 -1 14786 -1 14787 -1 14788 -1 14789 -1 14790 -1 14791 -1 14792 -1 14793 -1 14794 -1 14795 -1 14796 -1 14797 -1 14798 -1 14799 -1 14800 -1 14801 -1 14802 -1 14803 -1 14804 -1 14805 -1 14806 -1 14807 -1 14808 -1 14809 -1 14810 -1 14811 -1 14812 -1 14813 -1 14814 -1 14815 -1 14816 -1 14817 -1 14818 -1 14819 -1 14820 -1 14821 -1 14822 -1 14823 -1 14824 -1 14825 -1 14826 -1 14827 -1 14828 -1 14829 -1 14830 -1 14831 -1 14832 -1 14833 -1 14834 -1 14835 -1 14836 -1 14837 -1 14838 -1 14839 -1 14840 -1 14841 -1 14842 -1 14843 -1 14844 -1 14845 -1 14846 -1 14847 -1 14848 -1 14849 -1 14850 -1 14851 -1 14852 -1 14853 -1 14854 -1 14855 -1 14856 -1 14857 -1 14858 -1 14859 -1 14860 -1 14861 -1 14862 -1 14863 -1 14864 -1 14865 -1 14866 -1 14867 -1 14868 -1 14869 -1 14870 -1 14871 -1 14872 -1 14873 -1 14874 -1 14875 -1 14876 -1 14877 -1 14878 -1 14879 -1 14880 -1 14881 -1 14882 -1 14883 -1 14884 -1 14885 -1 14886 -1 14887 -1 14888 -1 14889 -1 14890 -1 14891 -1 14892 -1 14893 -1 14894 -1 14895 -1 14896 -1 14897 -1 14898 -1 14899 -1 14900 -1 14901 -1 14902 -1 14903 -1 14904 -1 14905 -1 14906 -1 14907 -1 14908 -1 14909 -1 14910 -1 14911 -1 14912 -1 14913 -1 14914 -1 14915 -1 14916 -1 14917 -1 14918 -1 14919 -1 14920 -1 14921 -1 14922 -1 14923 -1 14924 -1 14925 -1 14926 -1 14927 -1 14928 -1 14929 -1 14930 -1 14931 -1 14932 -1 14933 -1 14934 -1 14935 -1 14936 -1 14937 -1 14938 -1 14939 -1 14940 -1 14941 -1 14942 -1 14943 -1 14944 -1 14945 -1 14946 -1 14947 -1 14948 -1 14949 -1 14950 -1 14951 -1 14952 -1 14953 -1 14954 -1 14955 -1 14956 -1 14957 -1 14958 -1 14959 -1 14960 -1 14961 -1 14962 -1 14963 -1 14964 -1 14965 -1 14966 -1 14967 -1 14968 -1 14969 -1 14970 -1 14971 -1 14972 -1 14973 -1 14974 -1 14975 -1 14976 -1 14977 -1 14978 -1 14979 -1 14980 -1 14981 -1 14982 -1 14983 -1 14984 -1 14985 -1 14986 -1 14987 -1 14988 -1 14989 -1 14990 -1 14991 -1 14992 -1 14993 -1 14994 -1 14995 -1 14996 -1 14997 -1 14998 -1 14999 -1 15000 -1 15001 -1 15002 -1 15003 -1 15004 -1 15005 -1 15006 -1 15007 -1 15008 -1 15009 -1 15010 -1 15011 -1 15012 -1 15013 -1 15014 -1 15015 -1 15016 -1 15017 -1 15018 -1 15019 -1 15020 -1 15021 -1 15022 -1 15023 -1 15024 -1 15025 -1 15026 -1 15027 -1 15028 -1 15029 -1 15030 -1 15031 -1 15032 -1 15033 -1 15034 -1 15035 -1 15036 -1 15037 -1 15038 -1 15039 -1 15040 -1 15041 -1 15042 -1 15043 -1 15044 -1 15045 -1 15046 -1 15047 -1 15048 -1 15049 -1 15050 -1 15051 -1 15052 -1 15053 -1 15054 -1 15055 -1 15056 -1 15057 -1 15058 -1 15059 -1 15060 -1 15061 -1 15062 -1 15063 -1 15064 -1 15065 -1 15066 -1 15067 -1 15068 -1 15069 -1 15070 -1 15071 -1 15072 -1 15073 -1 15074 -1 15075 -1 15076 -1 15077 -1 15078 -1 15079 -1 15080 -1 15081 -1 15082 -1 15083 -1 15084 -1 15085 -1 15086 -1 15087 -1 15088 -1 15089 -1 15090 -1 15091 -1 15092 -1 15093 -1 15094 -1 15095 -1 15096 -1 15097 -1 15098 -1 15099 -1 15100 -1 15101 -1 15102 -1 15103 -1 15104 -1 15105 -1 15106 -1 15107 -1 15108 -1 15109 -1 15110 -1 15111 -1 15112 -1 15113 -1 15114 -1 15115 -1 15116 -1 15117 -1 15118 -1 15119 -1 15120 -1 15121 -1 15122 -1 15123 -1 15124 -1 15125 -1 15126 -1 15127 -1 15128 -1 15129 -1 15130 -1 15131 -1 15132 -1 15133 -1 15134 -1 15135 -1 15136 -1 15137 -1 15138 -1 15139 -1 15140 -1 15141 -1 15142 -1 15143 -1 15144 -1 15145 -1 15146 -1 15147 -1 15148 -1 15149 -1 15150 -1 15151 -1 15152 -1 15153 -1 15154 -1 15155 -1 15156 -1 15157 -1 15158 -1 15159 -1 15160 -1 15161 -1 15162 -1 15163 -1 15164 -1 15165 -1 15166 -1 15167 -1 15168 -1 15169 -1 15170 -1 15171 -1 15172 -1 15173 -1 15174 -1 15175 -1 15176 -1 15177 -1 15178 -1 15179 -1 15180 -1 15181 -1 15182 -1 15183 -1 15184 -1 15185 -1 15186 -1 15187 -1 15188 -1 15189 -1 15190 -1 15191 -1 15192 -1 15193 -1 15194 -1 15195 -1 15196 -1 15197 -1 15198 -1 15199 -1 15200 -1 15201 -1 15202 -1 15203 -1 15204 -1 15205 -1 15206 -1 15207 -1 15208 -1 15209 -1 15210 -1 15211 -1 15212 -1 15213 -1 15214 -1 15215 -1 15216 -1 15217 -1 15218 -1 15219 -1 15220 -1 15221 -1 15222 -1 15223 -1 15224 -1 15225 -1 15226 -1 15227 -1 15228 -1 15229 -1 15230 -1 15231 -1 15232 -1 15233 -1 15234 -1 15235 -1 15236 -1 15237 -1 15238 -1 15239 -1 15240 -1 15241 -1 15242 -1 15243 -1 15244 -1 15245 -1 15246 -1 15247 -1 15248 -1 15249 -1 15250 -1 15251 -1 15252 -1 15253 -1 15254 -1 15255 -1 15256 -1 15257 -1 15258 -1 15259 -1 15260 -1 15261 -1 15262 -1 15263 -1 15264 -1 15265 -1 15266 -1 15267 -1 15268 -1 15269 -1 15270 -1 15271 -1 15272 -1 15273 -1 15274 -1 15275 -1 15276 -1 15277 -1 15278 -1 15279 -1 15280 -1 15281 -1 15282 -1 15283 -1 15284 -1 15285 -1 15286 -1 15287 -1 15288 -1 15289 -1 15290 -1 15291 -1 15292 -1 15293 -1 15294 -1 15295 -1 15296 -1 15297 -1 15298 -1 15299 -1 15300 -1 15301 -1 15302 -1 15303 -1 15304 -1 15305 -1 15306 -1 15307 -1 15308 -1 15309 -1 15310 -1 15311 -1 15312 -1 15313 -1 15314 -1 15315 -1 15316 -1 15317 -1 15318 -1 15319 -1 15320 -1 15321 -1 15322 -1 15323 -1 15324 -1 15325 -1 15326 -1 15327 -1 15328 -1 15329 -1 15330 -1 15331 -1 15332 -1 15333 -1 15334 -1 15335 -1 15336 -1 15337 -1 15338 -1 15339 -1 15340 -1 15341 -1 15342 -1 15343 -1 15344 -1 15345 -1 15346 -1 15347 -1 15348 -1 15349 -1 15350 -1 15351 -1 15352 -1 15353 -1 15354 -1 15355 -1 15356 -1 15357 -1 15358 -1 15359 -1 15360 -1 15361 -1 15362 -1 15363 -1 15364 -1 15365 -1 15366 -1 15367 -1 15368 -1 15369 -1 15370 -1 15371 -1 15372 -1 15373 -1 15374 -1 15375 -1 15376 -1 15377 -1 15378 -1 15379 -1 15380 -1 15381 -1 15382 -1 15383 -1 15384 -1 15385 -1 15386 -1 15387 -1 15388 -1 15389 -1 15390 -1 15391 -1 15392 -1 15393 -1 15394 -1 15395 -1 15396 -1 15397 -1 15398 -1 15399 -1 15400 -1 15401 -1 15402 -1 15403 -1 15404 -1 15405 -1 15406 -1 15407 -1 15408 -1 15409 -1 15410 -1 15411 -1 15412 -1 15413 -1 15414 -1 15415 -1 15416 -1 15417 -1 15418 -1 15419 -1 15420 -1 15421 -1 15422 -1 15423 -1 15424 -1 15425 -1 15426 -1 15427 -1 15428 -1 15429 -1 15430 -1 15431 -1 15432 -1 15433 -1 15434 -1 15435 -1 15436 -1 15437 -1 15438 -1 15439 -1 15440 -1 15441 -1 15442 -1 15443 -1 15444 -1 15445 -1 15446 -1 15447 -1 15448 -1 15449 -1 15450 -1 15451 -1 15452 -1 15453 -1 15454 -1 15455 -1 15456 -1 15457 -1 15458 -1 15459 -1 15460 -1 15461 -1 15462 -1 15463 -1 15464 -1 15465 -1 15466 -1 15467 -1 15468 -1 15469 -1 15470 -1 15471 -1 15472 -1 15473 -1 15474 -1 15475 -1 15476 -1 15477 -1 15478 -1 15479 -1 15480 -1 15481 -1 15482 -1 15483 -1 15484 -1 15485 -1 15486 -1 15487 -1 15488 -1 15489 -1 15490 -1 15491 -1 15492 -1 15493 -1 15494 -1 15495 -1 15496 -1 15497 -1 15498 -1 15499 -1 15500 -1 15501 -1 15502 -1 15503 -1 15504 -1 15505 -1 15506 -1 15507 -1 15508 -1 15509 -1 15510 -1 15511 -1 15512 -1 15513 -1 15514 -1 15515 -1 15516 -1 15517 -1 15518 -1 15519 -1 15520 -1 15521 -1 15522 -1 15523 -1 15524 -1 15525 -1 15526 -1 15527 -1 15528 -1 15529 -1 15530 -1 15531 -1 15532 -1 15533 -1 15534 -1 15535 -1 15536 -1 15537 -1 15538 -1 15539 -1 15540 -1 15541 -1 15542 -1 15543 -1 15544 -1 15545 -1 15546 -1 15547 -1 15548 -1 15549 -1 15550 -1 15551 -1 15552 -1 15553 -1 15554 -1 15555 -1 15556 -1 15557 -1 15558 -1 15559 -1 15560 -1 15561 -1 15562 -1 15563 -1 15564 -1 15565 -1 15566 -1 15567 -1 15568 -1 15569 -1 15570 -1 15571 -1 15572 -1 15573 -1 15574 -1 15575 -1 15576 -1 15577 -1 15578 -1 15579 -1 15580 -1 15581 -1 15582 -1 15583 -1 15584 -1 15585 -1 15586 -1 15587 -1 15588 -1 15589 -1 15590 -1 15591 -1 15592 -1 15593 -1 15594 -1 15595 -1 15596 -1 15597 -1 15598 -1 15599 -1 15600 -1 15601 -1 15602 -1 15603 -1 15604 -1 15605 -1 15606 -1 15607 -1 15608 -1 15609 -1 15610 -1 15611 -1 15612 -1 15613 -1 15614 -1 15615 -1 15616 -1 15617 -1 15618 -1 15619 -1 15620 -1 15621 -1 15622 -1 15623 -1 15624 -1 15625 -1 15626 -1 15627 -1 15628 -1 15629 -1 15630 -1 15631 -1 15632 -1 15633 -1 15634 -1 15635 -1 15636 -1 15637 -1 15638 -1 15639 -1 15640 -1 15641 -1 15642 -1 15643 -1 15644 -1 15645 -1 15646 -1 15647 -1 15648 -1 15649 -1 15650 -1 15651 -1 15652 -1 15653 -1 15654 -1 15655 -1 15656 -1 15657 -1 15658 -1 15659 -1 15660 -1 15661 -1 15662 -1 15663 -1 15664 -1 15665 -1 15666 -1 15667 -1 15668 -1 15669 -1 15670 -1 15671 -1 15672 -1 15673 -1 15674 -1 15675 -1 15676 -1 15677 -1 15678 -1 15679 -1 15680 -1 15681 -1 15682 -1 15683 -1 15684 -1 15685 -1 15686 -1 15687 -1 15688 -1 15689 -1 15690 -1 15691 -1 15692 -1 15693 -1 15694 -1 15695 -1 15696 -1 15697 -1 15698 -1 15699 -1 15700 -1 15701 -1 15702 -1 15703 -1 15704 -1 15705 -1 15706 -1 15707 -1 15708 -1 15709 -1 15710 -1 15711 -1 15712 -1 15713 -1 15714 -1 15715 -1 15716 -1 15717 -1 15718 -1 15719 -1 15720 -1 15721 -1 15722 -1 15723 -1 15724 -1 15725 -1 15726 -1 15727 -1 15728 -1 15729 -1 15730 -1 15731 -1 15732 -1 15733 -1 15734 -1 15735 -1 15736 -1 15737 -1 15738 -1 15739 -1 15740 -1 15741 -1 15742 -1 15743 -1 15744 -1 15745 -1 15746 -1 15747 -1 15748 -1 15749 -1 15750 -1 15751 -1 15752 -1 15753 -1 15754 -1 15755 -1 15756 -1 15757 -1 15758 -1 15759 -1 15760 -1 15761 -1 15762 -1 15763 -1 15764 -1 15765 -1 15766 -1 15767 -1 15768 -1 15769 -1 15770 -1 15771 -1 15772 -1 15773 -1 15774 -1 15775 -1 15776 -1 15777 -1 15778 -1 15779 -1 15780 -1 15781 -1 15782 -1 15783 -1 15784 -1 15785 -1 15786 -1 15787 -1 15788 -1 15789 -1 15790 -1 15791 -1 15792 -1 15793 -1 15794 -1 15795 -1 15796 -1 15797 -1 15798 -1 15799 -1 15800 -1 15801 -1 15802 -1 15803 -1 15804 -1 15805 -1 15806 -1 15807 -1 15808 -1 15809 -1 15810 -1 15811 -1 15812 -1 15813 -1 15814 -1 15815 -1 15816 -1 15817 -1 15818 -1 15819 -1 15820 -1 15821 -1 15822 -1 15823 -1 15824 -1 15825 -1 15826 -1 15827 -1 15828 -1 15829 -1 15830 -1 15831 -1 15832 -1 15833 -1 15834 -1 15835 -1 15836 -1 15837 -1 15838 -1 15839 -1 15840 -1 15841 -1 15842 -1 15843 -1 15844 -1 15845 -1 15846 -1 15847 -1 15848 -1 15849 -1 15850 -1 15851 -1 15852 -1 15853 -1 15854 -1 15855 -1 15856 -1 15857 -1 15858 -1 15859 -1 15860 -1 15861 -1 15862 -1 15863 -1 15864 -1 15865 -1 15866 -1 15867 -1 15868 -1 15869 -1 15870 -1 15871 -1 15872 -1 15873 -1 15874 -1 15875 -1 15876 -1 15877 -1 15878 -1 15879 -1 15880 -1 15881 -1 15882 -1 15883 -1 15884 -1 15885 -1 15886 -1 15887 -1 15888 -1 15889 -1 15890 -1 15891 -1 15892 -1 15893 -1 15894 -1 15895 -1 15896 -1 15897 -1 15898 -1 15899 -1 15900 -1 15901 -1 15902 -1 15903 -1 15904 -1 15905 -1 15906 -1 15907 -1 15908 -1 15909 -1 15910 -1 15911 -1 15912 -1 15913 -1 15914 -1 15915 -1 15916 -1 15917 -1 15918 -1 15919 -1 15920 -1 15921 -1 15922 -1 15923 -1 15924 -1 15925 -1 15926 -1 15927 -1 15928 -1 15929 -1 15930 -1 15931 -1 15932 -1 15933 -1 15934 -1 15935 -1 15936 -1 15937 -1 15938 -1 15939 -1 15940 -1 15941 -1 15942 -1 15943 -1 15944 -1 15945 -1 15946 -1 15947 -1 15948 -1 15949 -1 15950 -1 15951 -1 15952 -1 15953 -1 15954 -1 15955 -1 15956 -1 15957 -1 15958 -1 15959 -1 15960 -1 15961 -1 15962 -1 15963 -1 15964 -1 15965 -1 15966 -1 15967 -1 15968 -1 15969 -1 15970 -1 15971 -1 15972 -1 15973 -1 15974 -1 15975 -1 15976 -1 15977 -1 15978 -1 15979 -1 15980 -1 15981 -1 15982 -1 15983 -1 15984 -1 15985 -1 15986 -1 15987 -1 15988 -1 15989 -1 15990 -1 15991 -1 15992 -1 15993 -1 15994 -1 15995 -1 15996 -1 15997 -1 15998 -1 15999 -1 16000 -1 16001 -1 16002 -1 16003 -1 16004 -1 16005 -1 16006 -1 16007 -1 16008 -1 16009 -1 16010 -1 16011 -1 16012 -1 16013 -1 16014 -1 16015 -1 16016 -1 16017 -1 16018 -1 16019 -1 16020 -1 16021 -1 16022 -1 16023 -1 16024 -1 16025 -1 16026 -1 16027 -1 16028 -1 16029 -1 16030 -1 16031 -1 16032 -1 16033 -1 16034 -1 16035 -1 16036 -1 16037 -1 16038 -1 16039 -1 16040 -1 16041 -1 16042 -1 16043 -1 16044 -1 16045 -1 16046 -1 16047 -1 16048 -1 16049 -1 16050 -1 16051 -1 16052 -1 16053 -1 16054 -1 16055 -1 16056 -1 16057 -1 16058 -1 16059 -1 16060 -1 16061 -1 16062 -1 16063 -1 16064 -1 16065 -1 16066 -1 16067 -1 16068 -1 16069 -1 16070 -1 16071 -1 16072 -1 16073 -1 16074 -1 16075 -1 16076 -1 16077 -1 16078 -1 16079 -1 16080 -1 16081 -1 16082 -1 16083 -1 16084 -1 16085 -1 16086 -1 16087 -1 16088 -1 16089 -1 16090 -1 16091 -1 16092 -1 16093 -1 16094 -1 16095 -1 16096 -1 16097 -1 16098 -1 16099 -1 16100 -1 16101 -1 16102 -1 16103 -1 16104 -1 16105 -1 16106 -1 16107 -1 16108 -1 16109 -1 16110 -1 16111 -1 16112 -1 16113 -1 16114 -1 16115 -1 16116 -1 16117 -1 16118 -1 16119 -1 16120 -1 16121 -1 16122 -1 16123 -1 16124 -1 16125 -1 16126 -1 16127 -1 16128 -1 16129 -1 16130 -1 16131 -1 16132 -1 16133 -1 16134 -1 16135 -1 16136 -1 16137 -1 16138 -1 16139 -1 16140 -1 16141 -1 16142 -1 16143 -1 16144 -1 16145 -1 16146 -1 16147 -1 16148 -1 16149 -1 16150 -1 16151 -1 16152 -1 16153 -1 16154 -1 16155 -1 16156 -1 16157 -1 16158 -1 16159 -1 16160 -1 16161 -1 16162 -1 16163 -1 16164 -1 16165 -1 16166 -1 16167 -1 16168 -1 16169 -1 16170 -1 16171 -1 16172 -1 16173 -1 16174 -1 16175 -1 16176 -1 16177 -1 16178 -1 16179 -1 16180 -1 16181 -1 16182 -1 16183 -1 16184 -1 16185 -1 16186 -1 16187 -1 16188 -1 16189 -1 16190 -1 16191 -1 16192 -1 16193 -1 16194 -1 16195 -1 16196 -1 16197 -1 16198 -1 16199 -1 16200 -1 16201 -1 16202 -1 16203 -1 16204 -1 16205 -1 16206 -1 16207 -1 16208 -1 16209 -1 16210 -1 16211 -1 16212 -1 16213 -1 16214 -1 16215 -1 16216 -1 16217 -1 16218 -1 16219 -1 16220 -1 16221 -1 16222 -1 16223 -1 16224 -1 16225 -1 16226 -1 16227 -1 16228 -1 16229 -1 16230 -1 16231 -1 16232 -1 16233 -1 16234 -1 16235 -1 16236 -1 16237 -1 16238 -1 16239 -1 16240 -1 16241 -1 16242 -1 16243 -1 16244 -1 16245 -1 16246 -1 16247 -1 16248 -1 16249 -1 16250 -1 16251 -1 16252 -1 16253 -1 16254 -1 16255 -1 16256 -1 16257 -1 16258 -1 16259 -1 16260 -1 16261 -1 16262 -1 16263 -1 16264 -1 16265 -1 16266 -1 16267 -1 16268 -1 16269 -1 16270 -1 16271 -1 16272 -1 16273 -1 16274 -1 16275 -1 16276 -1 16277 -1 16278 -1 16279 -1 16280 -1 16281 -1 16282 -1 16283 -1 16284 -1 16285 -1 16286 -1 16287 -1 16288 -1 16289 -1 16290 -1 16291 -1 16292 -1 16293 -1 16294 -1 16295 -1 16296 -1 16297 -1 16298 -1 16299 -1 16300 -1 16301 -1 16302 -1 16303 -1 16304 -1 16305 -1 16306 -1 16307 -1 16308 -1 16309 -1 16310 -1 16311 -1 16312 -1 16313 -1 16314 -1 16315 -1 16316 -1 16317 -1 16318 -1 16319 -1 16320 -1 16321 -1 16322 -1 16323 -1 16324 -1 16325 -1 16326 -1 16327 -1 16328 -1 16329 -1 16330 -1 16331 -1 16332 -1 16333 -1 16334 -1 16335 -1 16336 -1 16337 -1 16338 -1 16339 -1 16340 -1 16341 -1 16342 -1 16343 -1 16344 -1 16345 -1 16346 -1 16347 -1 16348 -1 16349 -1 16350 -1 16351 -1 16352 -1 16353 -1 16354 -1 16355 -1 16356 -1 16357 -1 16358 -1 16359 -1 16360 -1 16361 -1 16362 -1 16363 -1 16364 -1 16365 -1 16366 -1 16367 -1 16368 -1 16369 -1 16370 -1 16371 -1 16372 -1 16373 -1 16374 -1 16375 -1 16376 -1 16377 -1 16378 -1 16379 -1 16380 -1 16381 -1 16382 -1 16383 -1 16384 -1 16385 -1 16386 -1 16387 -1 16388 -1 16389 -1 16390 -1 16391 -1 16392 -1 16393 -1 16394 -1 16395 -1 16396 -1 16397 -1 16398 -1 16399 -1 16400 -1 16401 -1 16402 -1 16403 -1 16404 -1 16405 -1 16406 -1 16407 -1 16408 -1 16409 -1 16410 -1 16411 -1 16412 -1 16413 -1 16414 -1 16415 -1 16416 -1 16417 -1 16418 -1 16419 -1 16420 -1 16421 -1 16422 -1 16423 -1 16424 -1 16425 -1 16426 -1 16427 -1 16428 -1 16429 -1 16430 -1 16431 -1 16432 -1 16433 -1 16434 -1 16435 -1 16436 -1 16437 -1 16438 -1 16439 -1 16440 -1 16441 -1 16442 -1 16443 -1 16444 -1 16445 -1 16446 -1 16447 -1 16448 -1 16449 -1 16450 -1 16451 -1 16452 -1 16453 -1 16454 -1 16455 -1 16456 -1 16457 -1 16458 -1 16459 -1 16460 -1 16461 -1 16462 -1 16463 -1 16464 -1 16465 -1 16466 -1 16467 -1 16468 -1 16469 -1 16470 -1 16471 -1 16472 -1 16473 -1 16474 -1 16475 -1 16476 -1 16477 -1 16478 -1 16479 -1 16480 -1 16481 -1 16482 -1 16483 -1 16484 -1 16485 -1 16486 -1 16487 -1 16488 -1 16489 -1 16490 -1 16491 -1 16492 -1 16493 -1 16494 -1 16495 -1 16496 -1 16497 -1 16498 -1 16499 -1 16500 -1 16501 -1 16502 -1 16503 -1 16504 -1 16505 -1 16506 -1 16507 -1 16508 -1 16509 -1 16510 -1 16511 -1 16512 -1 16513 -1 16514 -1 16515 -1 16516 -1 16517 -1 16518 -1 16519 -1 16520 -1 16521 -1 16522 -1 16523 -1 16524 -1 16525 -1 16526 -1 16527 -1 16528 -1 16529 -1 16530 -1 16531 -1 16532 -1 16533 -1 16534 -1 16535 -1 16536 -1 16537 -1 16538 -1 16539 -1 16540 -1 16541 -1 16542 -1 16543 -1 16544 -1 16545 -1 16546 -1 16547 -1 16548 -1 16549 -1 16550 -1 16551 -1 16552 -1 16553 -1 16554 -1 16555 -1 16556 -1 16557 -1 16558 -1 16559 -1 16560 -1 16561 -1 16562 -1 16563 -1 16564 -1 16565 -1 16566 -1 16567 -1 16568 -1 16569 -1 16570 -1 16571 -1 16572 -1 16573 -1 16574 -1 16575 -1 16576 -1 16577 -1 16578 -1 16579 -1 16580 -1 16581 -1 16582 -1 16583 -1 16584 -1 16585 -1 16586 -1 16587 -1 16588 -1 16589 -1 16590 -1 16591 -1 16592 -1 16593 -1 16594 -1 16595 -1 16596 -1 16597 -1 16598 -1 16599 -1 16600 -1 16601 -1 16602 -1 16603 -1 16604 -1 16605 -1 16606 -1 16607 -1 16608 -1 16609 -1 16610 -1 16611 -1 16612 -1 16613 -1 16614 -1 16615 -1 16616 -1 16617 -1 16618 -1 16619 -1 16620 -1 16621 -1 16622 -1 16623 -1 16624 -1 16625 -1 16626 -1 16627 -1 16628 -1 16629 -1 16630 -1 16631 -1 16632 -1 16633 -1 16634 -1 16635 -1 16636 -1 16637 -1 16638 -1 16639 -1 16640 -1 16641 -1 16642 -1 16643 -1 16644 -1 16645 -1 16646 -1 16647 -1 16648 -1 16649 -1 16650 -1 16651 -1 16652 -1 16653 -1 16654 -1 16655 -1 16656 -1 16657 -1 16658 -1 16659 -1 16660 -1 16661 -1 16662 -1 16663 -1 16664 -1 16665 -1 16666 -1 16667 -1 16668 -1 16669 -1 16670 -1 16671 -1 16672 -1 16673 -1 16674 -1 16675 -1 16676 -1 16677 -1 16678 -1 16679 -1 16680 -1 16681 -1 16682 -1 16683 -1 16684 -1 16685 -1 16686 -1 16687 -1 16688 -1 16689 -1 16690 -1 16691 -1 16692 -1 16693 -1 16694 -1 16695 -1 16696 -1 16697 -1 16698 -1 16699 -1 16700 -1 16701 -1 16702 -1 16703 -1 16704 -1 16705 -1 16706 -1 16707 -1 16708 -1 16709 -1 16710 -1 16711 -1 16712 -1 16713 -1 16714 -1 16715 -1 16716 -1 16717 -1 16718 -1 16719 -1 16720 -1 16721 -1 16722 -1 16723 -1 16724 -1 16725 -1 16726 -1 16727 -1 16728 -1 16729 -1 16730 -1 16731 -1 16732 -1 16733 -1 16734 -1 16735 -1 16736 -1 16737 -1 16738 -1 16739 -1 16740 -1 16741 -1 16742 -1 16743 -1 16744 -1 16745 -1 16746 -1 16747 -1 16748 -1 16749 -1 16750 -1 16751 -1 16752 -1 16753 -1 16754 -1 16755 -1 16756 -1 16757 -1 16758 -1 16759 -1 16760 -1 16761 -1 16762 -1 16763 -1 16764 -1 16765 -1 16766 -1 16767 -1 16768 -1 16769 -1 16770 -1 16771 -1 16772 -1 16773 -1 16774 -1 16775 -1 16776 -1 16777 -1 16778 -1 16779 -1 16780 -1 16781 -1 16782 -1 16783 -1 16784 -1 16785 -1 16786 -1 16787 -1 16788 -1 16789 -1 16790 -1 16791 -1 16792 -1 16793 -1 16794 -1 16795 -1 16796 -1 16797 -1 16798 -1 16799 -1 16800 -1 16801 -1 16802 -1 16803 -1 16804 -1 16805 -1 16806 -1 16807 -1 16808 -1 16809 -1 16810 -1 16811 -1 16812 -1 16813 -1 16814 -1 16815 -1 16816 -1 16817 -1 16818 -1 16819 -1 16820 -1 16821 -1 16822 -1 16823 -1 16824 -1 16825 -1 16826 -1 16827 -1 16828 -1 16829 -1 16830 -1 16831 -1 16832 -1 16833 -1 16834 -1 16835 -1 16836 -1 16837 -1 16838 -1 16839 -1 16840 -1 16841 -1 16842 -1 16843 -1 16844 -1 16845 -1 16846 -1 16847 -1 16848 -1 16849 -1 16850 -1 16851 -1 16852 -1 16853 -1 16854 -1 16855 -1 16856 -1 16857 -1 16858 -1 16859 -1 16860 -1 16861 -1 16862 -1 16863 -1 16864 -1 16865 -1 16866 -1 16867 -1 16868 -1 16869 -1 16870 -1 16871 -1 16872 -1 16873 -1 16874 -1 16875 -1 16876 -1 16877 -1 16878 -1 16879 -1 16880 -1 16881 -1 16882 -1 16883 -1 16884 -1 16885 -1 16886 -1 16887 -1 16888 -1 16889 -1 16890 -1 16891 -1 16892 -1 16893 -1 16894 -1 16895 -1 16896 -1 16897 -1 16898 -1 16899 -1 16900 -1 16901 -1 16902 -1 16903 -1 16904 -1 16905 -1 16906 -1 16907 -1 16908 -1 16909 -1 16910 -1 16911 -1 16912 -1 16913 -1 16914 -1 16915 -1 16916 -1 16917 -1 16918 -1 16919 -1 16920 -1 16921 -1 16922 -1 16923 -1 16924 -1 16925 -1 16926 -1 16927 -1 16928 -1 16929 -1 16930 -1 16931 -1 16932 -1 16933 -1 16934 -1 16935 -1 16936 -1 16937 -1 16938 -1 16939 -1 16940 -1 16941 -1 16942 -1 16943 -1 16944 -1 16945 -1 16946 -1 16947 -1 16948 -1 16949 -1 16950 -1 16951 -1 16952 -1 16953 -1 16954 -1 16955 -1 16956 -1 16957 -1 16958 -1 16959 -1 16960 -1 16961 -1 16962 -1 16963 -1 16964 -1 16965 -1 16966 -1 16967 -1 16968 -1 16969 -1 16970 -1 16971 -1 16972 -1 16973 -1 16974 -1 16975 -1 16976 -1 16977 -1 16978 -1 16979 -1 16980 -1 16981 -1 16982 -1 16983 -1 16984 -1 16985 -1 16986 -1 16987 -1 16988 -1 16989 -1 16990 -1 16991 -1 16992 -1 16993 -1 16994 -1 16995 -1 16996 -1 16997 -1 16998 -1 16999 -1 17000 -1 17001 -1 17002 -1 17003 -1 17004 -1 17005 -1 17006 -1 17007 -1 17008 -1 17009 -1 17010 -1 17011 -1 17012 -1 17013 -1 17014 -1 17015 -1 17016 -1 17017 -1 17018 -1 17019 -1 17020 -1 17021 -1 17022 -1 17023 -1 17024 -1 17025 -1 17026 -1 17027 -1 17028 -1 17029 -1 17030 -1 17031 -1 17032 -1 17033 -1 17034 -1 17035 -1 17036 -1 17037 -1 17038 -1 17039 -1 17040 -1 17041 -1 17042 -1 17043 -1 17044 -1 17045 -1 17046 -1 17047 -1 17048 -1 17049 -1 17050 -1 17051 -1 17052 -1 17053 -1 17054 -1 17055 -1 17056 -1 17057 -1 17058 -1 17059 -1 17060 -1 17061 -1 17062 -1 17063 -1 17064 -1 17065 -1 17066 -1 17067 -1 17068 -1 17069 -1 17070 -1 17071 -1 17072 -1 17073 -1 17074 -1 17075 -1 17076 -1 17077 -1 17078 -1 17079 -1 17080 -1 17081 -1 17082 -1 17083 -1 17084 -1 17085 -1 17086 -1 17087 -1 17088 -1 17089 -1 17090 -1 17091 -1 17092 -1 17093 -1 17094 -1 17095 -1 17096 -1 17097 -1 17098 -1 17099 -1 17100 -1 17101 -1 17102 -1 17103 -1 17104 -1 17105 -1 17106 -1 17107 -1 17108 -1 17109 -1 17110 -1 17111 -1 17112 -1 17113 -1 17114 -1 17115 -1 17116 -1 17117 -1 17118 -1 17119 -1 17120 -1 17121 -1 17122 -1 17123 -1 17124 -1 17125 -1 17126 -1 17127 -1 17128 -1 17129 -1 17130 -1 17131 -1 17132 -1 17133 -1 17134 -1 17135 -1 17136 -1 17137 -1 17138 -1 17139 -1 17140 -1 17141 -1 17142 -1 17143 -1 17144 -1 17145 -1 17146 -1 17147 -1 17148 -1 17149 -1 17150 -1 17151 -1 17152 -1 17153 -1 17154 -1 17155 -1 17156 -1 17157 -1 17158 -1 17159 -1 17160 -1 17161 -1 17162 -1 17163 -1 17164 -1 17165 -1 17166 -1 17167 -1 17168 -1 17169 -1 17170 -1 17171 -1 17172 -1 17173 -1 17174 -1 17175 -1 17176 -1 17177 -1 17178 -1 17179 -1 17180 -1 17181 -1 17182 -1 17183 -1 17184 -1 17185 -1 17186 -1 17187 -1 17188 -1 17189 -1 17190 -1 17191 -1 17192 -1 17193 -1 17194 -1 17195 -1 17196 -1 17197 -1 17198 -1 17199 -1 17200 -1 17201 -1 17202 -1 17203 -1 17204 -1 17205 -1 17206 -1 17207 -1 17208 -1 17209 -1 17210 -1 17211 -1 17212 -1 17213 -1 17214 -1 17215 -1 17216 -1 17217 -1 17218 -1 17219 -1 17220 -1 17221 -1 17222 -1 17223 -1 17224 -1 17225 -1 17226 -1 17227 -1 17228 -1 17229 -1 17230 -1 17231 -1 17232 -1 17233 -1 17234 -1 17235 -1 17236 -1 17237 -1 17238 -1 17239 -1 17240 -1 17241 -1 17242 -1 17243 -1 17244 -1 17245 -1 17246 -1 17247 -1 17248 -1 17249 -1 17250 -1 17251 -1 17252 -1 17253 -1 17254 -1 17255 -1 17256 -1 17257 -1 17258 -1 17259 -1 17260 -1 17261 -1 17262 -1 17263 -1 17264 -1 17265 -1 17266 -1 17267 -1 17268 -1 17269 -1 17270 -1 17271 -1 17272 -1 17273 -1 17274 -1 17275 -1 17276 -1 17277 -1 17278 -1 17279 -1 17280 -1 17281 -1 17282 -1 17283 -1 17284 -1 17285 -1 17286 -1 17287 -1 17288 -1 17289 -1 17290 -1 17291 -1 17292 -1 17293 -1 17294 -1 17295 -1 17296 -1 17297 -1 17298 -1 17299 -1 17300 -1 17301 -1 17302 -1 17303 -1 17304 -1 17305 -1 17306 -1 17307 -1 17308 -1 17309 -1 17310 -1 17311 -1 17312 -1 17313 -1 17314 -1 17315 -1 17316 -1 17317 -1 17318 -1 17319 -1 17320 -1 17321 -1 17322 -1 17323 -1 17324 -1 17325 -1 17326 -1 17327 -1 17328 -1 17329 -1 17330 -1 17331 -1 17332 -1 17333 -1 17334 -1 17335 -1 17336 -1 17337 -1 17338 -1 17339 -1 17340 -1 17341 -1 17342 -1 17343 -1 17344 -1 17345 -1 17346 -1 17347 -1 17348 -1 17349 -1 17350 -1 17351 -1 17352 -1 17353 -1 17354 -1 17355 -1 17356 -1 17357 -1 17358 -1 17359 -1 17360 -1 17361 -1 17362 -1 17363 -1 17364 -1 17365 -1 17366 -1 17367 -1 17368 -1 17369 -1 17370 -1 17371 -1 17372 -1 17373 -1 17374 -1 17375 -1 17376 -1 17377 -1 17378 -1 17379 -1 17380 -1 17381 -1 17382 -1 17383 -1 17384 -1 17385 -1 17386 -1 17387 -1 17388 -1 17389 -1 17390 -1 17391 -1 17392 -1 17393 -1 17394 -1 17395 -1 17396 -1 17397 -1 17398 -1 17399 -1 17400 -1 17401 -1 17402 -1 17403 -1 17404 -1 17405 -1 17406 -1 17407 -1 17408 -1 17409 -1 17410 -1 17411 -1 17412 -1 17413 -1 17414 -1 17415 -1 17416 -1 17417 -1 17418 -1 17419 -1 17420 -1 17421 -1 17422 -1 17423 -1 17424 -1 17425 -1 17426 -1 17427 -1 17428 -1 17429 -1 17430 -1 17431 -1 17432 -1 17433 -1 17434 -1 17435 -1 17436 -1 17437 -1 17438 -1 17439 -1 17440 -1 17441 -1 17442 -1 17443 -1 17444 -1 17445 -1 17446 -1 17447 -1 17448 -1 17449 -1 17450 -1 17451 -1 17452 -1 17453 -1 17454 -1 17455 -1 17456 -1 17457 -1 17458 -1 17459 -1 17460 -1 17461 -1 17462 -1 17463 -1 17464 -1 17465 -1 17466 -1 17467 -1 17468 -1 17469 -1 17470 -1 17471 -1 17472 -1 17473 -1 17474 -1 17475 -1 17476 -1 17477 -1 17478 -1 17479 -1 17480 -1 17481 -1 17482 -1 17483 -1 17484 -1 17485 -1 17486 -1 17487 -1 17488 -1 17489 -1 17490 -1 17491 -1 17492 -1 17493 -1 17494 -1 17495 -1 17496 -1 17497 -1 17498 -1 17499 -1 17500 -1 17501 -1 17502 -1 17503 -1 17504 -1 17505 -1 17506 -1 17507 -1 17508 -1 17509 -1 17510 -1 17511 -1 17512 -1 17513 -1 17514 -1 17515 -1 17516 -1 17517 -1 17518 -1 17519 -1 17520 -1 17521 -1 17522 -1 17523 -1 17524 -1 17525 -1 17526 -1 17527 -1 17528 -1 17529 -1 17530 -1 17531 -1 17532 -1 17533 -1 17534 -1 17535 -1 17536 -1 17537 -1 17538 -1 17539 -1 17540 -1 17541 -1 17542 -1 17543 -1 17544 -1 17545 -1 17546 -1 17547 -1 17548 -1 17549 -1 17550 -1 17551 -1 17552 -1 17553 -1 17554 -1 17555 -1 17556 -1 17557 -1 17558 -1 17559 -1 17560 -1 17561 -1 17562 -1 17563 -1 17564 -1 17565 -1 17566 -1 17567 -1 17568 -1 17569 -1 17570 -1 17571 -1 17572 -1 17573 -1 17574 -1 17575 -1 17576 -1 17577 -1 17578 -1 17579 -1 17580 -1 17581 -1 17582 -1 17583 -1 17584 -1 17585 -1 17586 -1 17587 -1 17588 -1 17589 -1 17590 -1 17591 -1 17592 -1 17593 -1 17594 -1 17595 -1 17596 -1 17597 -1 17598 -1 17599 -1 17600 -1 17601 -1 17602 -1 17603 -1 17604 -1 17605 -1 17606 -1 17607 -1 17608 -1 17609 -1 17610 -1 17611 -1 17612 -1 17613 -1 17614 -1 17615 -1 17616 -1 17617 -1 17618 -1 17619 -1 17620 -1 17621 -1 17622 -1 17623 -1 17624 -1 17625 -1 17626 -1 17627 -1 17628 -1 17629 -1 17630 -1 17631 -1 17632 -1 17633 -1 17634 -1 17635 -1 17636 -1 17637 -1 17638 -1 17639 -1 17640 -1 17641 -1 17642 -1 17643 -1 17644 -1 17645 -1 17646 -1 17647 -1 17648 -1 17649 -1 17650 -1 17651 -1 17652 -1 17653 -1 17654 -1 17655 -1 17656 -1 17657 -1 17658 -1 17659 -1 17660 -1 17661 -1 17662 -1 17663 -1 17664 -1 17665 -1 17666 -1 17667 -1 17668 -1 17669 -1 17670 -1 17671 -1 17672 -1 17673 -1 17674 -1 17675 -1 17676 -1 17677 -1 17678 -1 17679 -1 17680 -1 17681 -1 17682 -1 17683 -1 17684 -1 17685 -1 17686 -1 17687 -1 17688 -1 17689 -1 17690 -1 17691 -1 17692 -1 17693 -1 17694 -1 17695 -1 17696 -1 17697 -1 17698 -1 17699 -1 17700 -1 17701 -1 17702 -1 17703 -1 17704 -1 17705 -1 17706 -1 17707 -1 17708 -1 17709 -1 17710 -1 17711 -1 17712 -1 17713 -1 17714 -1 17715 -1 17716 -1 17717 -1 17718 -1 17719 -1 17720 -1 17721 -1 17722 -1 17723 -1 17724 -1 17725 -1 17726 -1 17727 -1 17728 -1 17729 -1 17730 -1 17731 -1 17732 -1 17733 -1 17734 -1 17735 -1 17736 -1 17737 -1 17738 -1 17739 -1 17740 -1 17741 -1 17742 -1 17743 -1 17744 -1 17745 -1 17746 -1 17747 -1 17748 -1 17749 -1 17750 -1 17751 -1 17752 -1 17753 -1 17754 -1 17755 -1 17756 -1 17757 -1 17758 -1 17759 -1 17760 -1 17761 -1 17762 -1 17763 -1 17764 -1 17765 -1 17766 -1 17767 -1 17768 -1 17769 -1 17770 -1 17771 -1 17772 -1 17773 -1 17774 -1 17775 -1 17776 -1 17777 -1 17778 -1 17779 -1 17780 -1 17781 -1 17782 -1 17783 -1 17784 -1 17785 -1 17786 -1 17787 -1 17788 -1 17789 -1 17790 -1 17791 -1 17792 -1 17793 -1 17794 -1 17795 -1 17796 -1 17797 -1 17798 -1 17799 -1 17800 -1 17801 -1 17802 -1 17803 -1 17804 -1 17805 -1 17806 -1 17807 -1 17808 -1 17809 -1 17810 -1 17811 -1 17812 -1 17813 -1 17814 -1 17815 -1 17816 -1 17817 -1 17818 -1 17819 -1 17820 -1 17821 -1 17822 -1 17823 -1 17824 -1 17825 -1 17826 -1 17827 -1 17828 -1 17829 -1 17830 -1 17831 -1 17832 -1 17833 -1 17834 -1 17835 -1 17836 -1 17837 -1 17838 -1 17839 -1 17840 -1 17841 -1 17842 -1 17843 -1 17844 -1 17845 -1 17846 -1 17847 -1 17848 -1 17849 -1 17850 -1 17851 -1 17852 -1 17853 -1 17854 -1 17855 -1 17856 -1 17857 -1 17858 -1 17859 -1 17860 -1 17861 -1 17862 -1 17863 -1 17864 -1 17865 -1 17866 -1 17867 -1 17868 -1 17869 -1 17870 -1 17871 -1 17872 -1 17873 -1 17874 -1 17875 -1 17876 -1 17877 -1 17878 -1 17879 -1 17880 -1 17881 -1 17882 -1 17883 -1 17884 -1 17885 -1 17886 -1 17887 -1 17888 -1 17889 -1 17890 -1 17891 -1 17892 -1 17893 -1 17894 -1 17895 -1 17896 -1 17897 -1 17898 -1 17899 -1 17900 -1 17901 -1 17902 -1 17903 -1 17904 -1 17905 -1 17906 -1 17907 -1 17908 -1 17909 -1 17910 -1 17911 -1 17912 -1 17913 -1 17914 -1 17915 -1 17916 -1 17917 -1 17918 -1 17919 -1 17920 -1 17921 -1 17922 -1 17923 -1 17924 -1 17925 -1 17926 -1 17927 -1 17928 -1 17929 -1 17930 -1 17931 -1 17932 -1 17933 -1 17934 -1 17935 -1 17936 -1 17937 -1 17938 -1 17939 -1 17940 -1 17941 -1 17942 -1 17943 -1 17944 -1 17945 -1 17946 -1 17947 -1 17948 -1 17949 -1 17950 -1 17951 -1 17952 -1 17953 -1 17954 -1 17955 -1 17956 -1 17957 -1 17958 -1 17959 -1 17960 -1 17961 -1 17962 -1 17963 -1 17964 -1 17965 -1 17966 -1 17967 -1 17968 -1 17969 -1 17970 -1 17971 -1 17972 -1 17973 -1 17974 -1 17975 -1 17976 -1 17977 -1 17978 -1 17979 -1 17980 -1 17981 -1 17982 -1 17983 -1 17984 -1 17985 -1 17986 -1 17987 -1 17988 -1 17989 -1 17990 -1 17991 -1 17992 -1 17993 -1 17994 -1 17995 -1 17996 -1 17997 -1 17998 -1 17999 -1 18000 -1 18001 -1 18002 -1 18003 -1 18004 -1 18005 -1 18006 -1 18007 -1 18008 -1 18009 -1 18010 -1 18011 -1 18012 -1 18013 -1 18014 -1 18015 -1 18016 -1 18017 -1 18018 -1 18019 -1 18020 -1 18021 -1 18022 -1 18023 -1 18024 -1 18025 -1 18026 -1 18027 -1 18028 -1 18029 -1 18030 -1 18031 -1 18032 -1 18033 -1 18034 -1 18035 -1 18036 -1 18037 -1 18038 -1 18039 -1 18040 -1 18041 -1 18042 -1 18043 -1 18044 -1 18045 -1 18046 -1 18047 -1 18048 -1 18049 -1 18050 -1 18051 -1 18052 -1 18053 -1 18054 -1 18055 -1 18056 -1 18057 -1 18058 -1 18059 -1 18060 -1 18061 -1 18062 -1 18063 -1 18064 -1 18065 -1 18066 -1 18067 -1 18068 -1 18069 -1 18070 -1 18071 -1 18072 -1 18073 -1 18074 -1 18075 -1 18076 -1 18077 -1 18078 -1 18079 -1 18080 -1 18081 -1 18082 -1 18083 -1 18084 -1 18085 -1 18086 -1 18087 -1 18088 -1 18089 -1 18090 -1 18091 -1 18092 -1 18093 -1 18094 -1 18095 -1 18096 -1 18097 -1 18098 -1 18099 -1 18100 -1 18101 -1 18102 -1 18103 -1 18104 -1 18105 -1 18106 -1 18107 -1 18108 -1 18109 -1 18110 -1 18111 -1 18112 -1 18113 -1 18114 -1 18115 -1 18116 -1 18117 -1 18118 -1 18119 -1 18120 -1 18121 -1 18122 -1 18123 -1 18124 -1 18125 -1 18126 -1 18127 -1 18128 -1 18129 -1 18130 -1 18131 -1 18132 -1 18133 -1 18134 -1 18135 -1 18136 -1 18137 -1 18138 -1 18139 -1 18140 -1 18141 -1 18142 -1 18143 -1 18144 -1 18145 -1 18146 -1 18147 -1 18148 -1 18149 -1 18150 -1 18151 -1 18152 -1 18153 -1 18154 -1 18155 -1 18156 -1 18157 -1 18158 -1 18159 -1 18160 -1 18161 -1 18162 -1 18163 -1 18164 -1 18165 -1 18166 -1 18167 -1 18168 -1 18169 -1 18170 -1 18171 -1 18172 -1 18173 -1 18174 -1 18175 -1 18176 -1 18177 -1 18178 -1 18179 -1 18180 -1 18181 -1 18182 -1 18183 -1 18184 -1 18185 -1 18186 -1 18187 -1 18188 -1 18189 -1 18190 -1 18191 -1 18192 -1 18193 -1 18194 -1 18195 -1 18196 -1 18197 -1 18198 -1 18199 -1 18200 -1 18201 -1 18202 -1 18203 -1 18204 -1 18205 -1 18206 -1 18207 -1 18208 -1 18209 -1 18210 -1 18211 -1 18212 -1 18213 -1 18214 -1 18215 -1 18216 -1 18217 -1 18218 -1 18219 -1 18220 -1 18221 -1 18222 -1 18223 -1 18224 -1 18225 -1 18226 -1 18227 -1 18228 -1 18229 -1 18230 -1 18231 -1 18232 -1 18233 -1 18234 -1 18235 -1 18236 -1 18237 -1 18238 -1 18239 -1 18240 -1 18241 -1 18242 -1 18243 -1 18244 -1 18245 -1 18246 -1 18247 -1 18248 -1 18249 -1 18250 -1 18251 -1 18252 -1 18253 -1 18254 -1 18255 -1 18256 -1 18257 -1 18258 -1 18259 -1 18260 -1 18261 -1 18262 -1 18263 -1 18264 -1 18265 -1 18266 -1 18267 -1 18268 -1 18269 -1 18270 -1 18271 -1 18272 -1 18273 -1 18274 -1 18275 -1 18276 -1 18277 -1 18278 -1 18279 -1 18280 -1 18281 -1 18282 -1 18283 -1 18284 -1 18285 -1 18286 -1 18287 -1 18288 -1 18289 -1 18290 -1 18291 -1 18292 -1 18293 -1 18294 -1 18295 -1 18296 -1 18297 -1 18298 -1 18299 -1 18300 -1 18301 -1 18302 -1 18303 -1 18304 -1 18305 -1 18306 -1 18307 -1 18308 -1 18309 -1 18310 -1 18311 -1 18312 -1 18313 -1 18314 -1 18315 -1 18316 -1 18317 -1 18318 -1 18319 -1 18320 -1 18321 -1 18322 -1 18323 -1 18324 -1 18325 -1 18326 -1 18327 -1 18328 -1 18329 -1 18330 -1 18331 -1 18332 -1 18333 -1 18334 -1 18335 -1 18336 -1 18337 -1 18338 -1 18339 -1 18340 -1 18341 -1 18342 -1 18343 -1 18344 -1 18345 -1 18346 -1 18347 -1 18348 -1 18349 -1 18350 -1 18351 -1 18352 -1 18353 -1 18354 -1 18355 -1 18356 -1 18357 -1 18358 -1 18359 -1 18360 -1 18361 -1 18362 -1 18363 -1 18364 -1 18365 -1 18366 -1 18367 -1 18368 -1 18369 -1 18370 -1 18371 -1 18372 -1 18373 -1 18374 -1 18375 -1 18376 -1 18377 -1 18378 -1 18379 -1 18380 -1 18381 -1 18382 -1 18383 -1 18384 -1 18385 -1 18386 -1 18387 -1 18388 -1 18389 -1 18390 -1 18391 -1 18392 -1 18393 -1 18394 -1 18395 -1 18396 -1 18397 -1 18398 -1 18399 -1 18400 -1 18401 -1 18402 -1 18403 -1 18404 -1 18405 -1 18406 -1 18407 -1 18408 -1 18409 -1 18410 -1 18411 -1 18412 -1 18413 -1 18414 -1 18415 -1 18416 -1 18417 -1 18418 -1 18419 -1 18420 -1 18421 -1 18422 -1 18423 -1 18424 -1 18425 -1 18426 -1 18427 -1 18428 -1 18429 -1 18430 -1 18431 -1 18432 -1 18433 -1 18434 -1 18435 -1 18436 -1 18437 -1 18438 -1 18439 -1 18440 -1 18441 -1 18442 -1 18443 -1 18444 -1 18445 -1 18446 -1 18447 -1 18448 -1 18449 -1 18450 -1 18451 -1 18452 -1 18453 -1 18454 -1 18455 -1 18456 -1 18457 -1 18458 -1 18459 -1 18460 -1 18461 -1 18462 -1 18463 -1 18464 -1 18465 -1 18466 -1 18467 -1 18468 -1 18469 -1 18470 -1 18471 -1 18472 -1 18473 -1 18474 -1 18475 -1 18476 -1 18477 -1 18478 -1 18479 -1 18480 -1 18481 -1 18482 -1 18483 -1 18484 -1 18485 -1 18486 -1 18487 -1 18488 -1 18489 -1 18490 -1 18491 -1 18492 -1 18493 -1 18494 -1 18495 -1 18496 -1 18497 -1 18498 -1 18499 -1 18500 -1 18501 -1 18502 -1 18503 -1 18504 -1 18505 -1 18506 -1 18507 -1 18508 -1 18509 -1 18510 -1 18511 -1 18512 -1 18513 -1 18514 -1 18515 -1 18516 -1 18517 -1 18518 -1 18519 -1 18520 -1 18521 -1 18522 -1 18523 -1 18524 -1 18525 -1 18526 -1 18527 -1 18528 -1 18529 -1 18530 -1 18531 -1 18532 -1 18533 -1 18534 -1 18535 -1 18536 -1 18537 -1 18538 -1 18539 -1 18540 -1 18541 -1 18542 -1 18543 -1 18544 -1 18545 -1 18546 -1 18547 -1 18548 -1 18549 -1 18550 -1 18551 -1 18552 -1 18553 -1 18554 -1 18555 -1 18556 -1 18557 -1 18558 -1 18559 -1 18560 -1 18561 -1 18562 -1 18563 -1 18564 -1 18565 -1 18566 -1 18567 -1 18568 -1 18569 -1 18570 -1 18571 -1 18572 -1 18573 -1 18574 -1 18575 -1 18576 -1 18577 -1 18578 -1 18579 -1 18580 -1 18581 -1 18582 -1 18583 -1 18584 -1 18585 -1 18586 -1 18587 -1 18588 -1 18589 -1 18590 -1 18591 -1 18592 -1 18593 -1 18594 -1 18595 -1 18596 -1 18597 -1 18598 -1 18599 -1 18600 -1 18601 -1 18602 -1 18603 -1 18604 -1 18605 -1 18606 -1 18607 -1 18608 -1 18609 -1 18610 -1 18611 -1 18612 -1 18613 -1 18614 -1 18615 -1 18616 -1 18617 -1 18618 -1 18619 -1 18620 -1 18621 -1 18622 -1 18623 -1 18624 -1 18625 -1 18626 -1 18627 -1 18628 -1 18629 -1 18630 -1 18631 -1 18632 -1 18633 -1 18634 -1 18635 -1 18636 -1 18637 -1 18638 -1 18639 -1 18640 -1 18641 -1 18642 -1 18643 -1 18644 -1 18645 -1 18646 -1 18647 -1 18648 -1 18649 -1 18650 -1 18651 -1 18652 -1 18653 -1 18654 -1 18655 -1 18656 -1 18657 -1 18658 -1 18659 -1 18660 -1 18661 -1 18662 -1 18663 -1 18664 -1 18665 -1 18666 -1 18667 -1 18668 -1 18669 -1 18670 -1 18671 -1 18672 -1 18673 -1 18674 -1 18675 -1 18676 -1 18677 -1 18678 -1 18679 -1 18680 -1 18681 -1 18682 -1 18683 -1 18684 -1 18685 -1 18686 -1 18687 -1 18688 -1 18689 -1 18690 -1 18691 -1 18692 -1 18693 -1 18694 -1 18695 -1 18696 -1 18697 -1 18698 -1 18699 -1 18700 -1 18701 -1 18702 -1 18703 -1 18704 -1 18705 -1 18706 -1 18707 -1 18708 -1 18709 -1 18710 -1 18711 -1 18712 -1 18713 -1 18714 -1 18715 -1 18716 -1 18717 -1 18718 -1 18719 -1 18720 -1 18721 -1 18722 -1 18723 -1 18724 -1 18725 -1 18726 -1 18727 -1 18728 -1 18729 -1 18730 -1 18731 -1 18732 -1 18733 -1 18734 -1 18735 -1 18736 -1 18737 -1 18738 -1 18739 -1 18740 -1 18741 -1 18742 -1 18743 -1 18744 -1 18745 -1 18746 -1 18747 -1 18748 -1 18749 -1 18750 -1 18751 -1 18752 -1 18753 -1 18754 -1 18755 -1 18756 -1 18757 -1 18758 -1 18759 -1 18760 -1 18761 -1 18762 -1 18763 -1 18764 -1 18765 -1 18766 -1 18767 -1 18768 -1 18769 -1 18770 -1 18771 -1 18772 -1 18773 -1 18774 -1 18775 -1 18776 -1 18777 -1 18778 -1 18779 -1 18780 -1 18781 -1 18782 -1 18783 -1 18784 -1 18785 -1 18786 -1 18787 -1 18788 -1 18789 -1 18790 -1 18791 -1 18792 -1 18793 -1 18794 -1 18795 -1 18796 -1 18797 -1 18798 -1 18799 -1 18800 -1 18801 -1 18802 -1 18803 -1 18804 -1 18805 -1 18806 -1 18807 -1 18808 -1 18809 -1 18810 -1 18811 -1 18812 -1 18813 -1 18814 -1 18815 -1 18816 -1 18817 -1 18818 -1 18819 -1 18820 -1 18821 -1 18822 -1 18823 -1 18824 -1 18825 -1 18826 -1 18827 -1 18828 -1 18829 -1 18830 -1 18831 -1 18832 -1 18833 -1 18834 -1 18835 -1 18836 -1 18837 -1 18838 -1 18839 -1 18840 -1 18841 -1 18842 -1 18843 -1 18844 -1 18845 -1 18846 -1 18847 -1 18848 -1 18849 -1 18850 -1 18851 -1 18852 -1 18853 -1 18854 -1 18855 -1 18856 -1 18857 -1 18858 -1 18859 -1 18860 -1 18861 -1 18862 -1 18863 -1 18864 -1 18865 -1 18866 -1 18867 -1 18868 -1 18869 -1 18870 -1 18871 -1 18872 -1 18873 -1 18874 -1 18875 -1 18876 -1 18877 -1 18878 -1 18879 -1 18880 -1 18881 -1 18882 -1 18883 -1 18884 -1 18885 -1 18886 -1 18887 -1 18888 -1 18889 -1 18890 -1 18891 -1 18892 -1 18893 -1 18894 -1 18895 -1 18896 -1 18897 -1 18898 -1 18899 -1 18900 -1 18901 -1 18902 -1 18903 -1 18904 -1 18905 -1 18906 -1 18907 -1 18908 -1 18909 -1 18910 -1 18911 -1 18912 -1 18913 -1 18914 -1 18915 -1 18916 -1 18917 -1 18918 -1 18919 -1 18920 -1 18921 -1 18922 -1 18923 -1 18924 -1 18925 -1 18926 -1 18927 -1 18928 -1 18929 -1 18930 -1 18931 -1 18932 -1 18933 -1 18934 -1 18935 -1 18936 -1 18937 -1 18938 -1 18939 -1 18940 -1 18941 -1 18942 -1 18943 -1 18944 -1 18945 -1 18946 -1 18947 -1 18948 -1 18949 -1 18950 -1 18951 -1 18952 -1 18953 -1 18954 -1 18955 -1 18956 -1 18957 -1 18958 -1 18959 -1 18960 -1 18961 -1 18962 -1 18963 -1 18964 -1 18965 -1 18966 -1 18967 -1 18968 -1 18969 -1 18970 -1 18971 -1 18972 -1 18973 -1 18974 -1 18975 -1 18976 -1 18977 -1 18978 -1 18979 -1 18980 -1 18981 -1 18982 -1 18983 -1 18984 -1 18985 -1 18986 -1 18987 -1 18988 -1 18989 -1 18990 -1 18991 -1 18992 -1 18993 -1 18994 -1 18995 -1 18996 -1 18997 -1 18998 -1 18999 -1 19000 -1 19001 -1 19002 -1 19003 -1 19004 -1 19005 -1 19006 -1 19007 -1 19008 -1 19009 -1 19010 -1 19011 -1 19012 -1 19013 -1 19014 -1 19015 -1 19016 -1 19017 -1 19018 -1 19019 -1 19020 -1 19021 -1 19022 -1 19023 -1 19024 -1 19025 -1 19026 -1 19027 -1 19028 -1 19029 -1 19030 -1 19031 -1 19032 -1 19033 -1 19034 -1 19035 -1 19036 -1 19037 -1 19038 -1 19039 -1 19040 -1 19041 -1 19042 -1 19043 -1 19044 -1 19045 -1 19046 -1 19047 -1 19048 -1 19049 -1 19050 -1 19051 -1 19052 -1 19053 -1 19054 -1 19055 -1 19056 -1 19057 -1 19058 -1 19059 -1 19060 -1 19061 -1 19062 -1 19063 -1 19064 -1 19065 -1 19066 -1 19067 -1 19068 -1 19069 -1 19070 -1 19071 -1 19072 -1 19073 -1 19074 -1 19075 -1 19076 -1 19077 -1 19078 -1 19079 -1 19080 -1 19081 -1 19082 -1 19083 -1 19084 -1 19085 -1 19086 -1 19087 -1 19088 -1 19089 -1 19090 -1 19091 -1 19092 -1 19093 -1 19094 -1 19095 -1 19096 -1 19097 -1 19098 -1 19099 -1 19100 -1 19101 -1 19102 -1 19103 -1 19104 -1 19105 -1 19106 -1 19107 -1 19108 -1 19109 -1 19110 -1 19111 -1 19112 -1 19113 -1 19114 -1 19115 -1 19116 -1 19117 -1 19118 -1 19119 -1 19120 -1 19121 -1 19122 -1 19123 -1 19124 -1 19125 -1 19126 -1 19127 -1 19128 -1 19129 -1 19130 -1 19131 -1 19132 -1 19133 -1 19134 -1 19135 -1 19136 -1 19137 -1 19138 -1 19139 -1 19140 -1 19141 -1 19142 -1 19143 -1 19144 -1 19145 -1 19146 -1 19147 -1 19148 -1 19149 -1 19150 -1 19151 -1 19152 -1 19153 -1 19154 -1 19155 -1 19156 -1 19157 -1 19158 -1 19159 -1 19160 -1 19161 -1 19162 -1 19163 -1 19164 -1 19165 -1 19166 -1 19167 -1 19168 -1 19169 -1 19170 -1 19171 -1 19172 -1 19173 -1 19174 -1 19175 -1 19176 -1 19177 -1 19178 -1 19179 -1 19180 -1 19181 -1 19182 -1 19183 -1 19184 -1 19185 -1 19186 -1 19187 -1 19188 -1 19189 -1 19190 -1 19191 -1 19192 -1 19193 -1 19194 -1 19195 -1 19196 -1 19197 -1 19198 -1 19199 -1 19200 -1 19201 -1 19202 -1 19203 -1 19204 -1 19205 -1 19206 -1 19207 -1 19208 -1 19209 -1 19210 -1 19211 -1 19212 -1 19213 -1 19214 -1 19215 -1 19216 -1 19217 -1 19218 -1 19219 -1 19220 -1 19221 -1 19222 -1 19223 -1 19224 -1 19225 -1 19226 -1 19227 -1 19228 -1 19229 -1 19230 -1 19231 -1 19232 -1 19233 -1 19234 -1 19235 -1 19236 -1 19237 -1 19238 -1 19239 -1 19240 -1 19241 -1 19242 -1 19243 -1 19244 -1 19245 -1 19246 -1 19247 -1 19248 -1 19249 -1 19250 -1 19251 -1 19252 -1 19253 -1 19254 -1 19255 -1 19256 -1 19257 -1 19258 -1 19259 -1 19260 -1 19261 -1 19262 -1 19263 -1 19264 -1 19265 -1 19266 -1 19267 -1 19268 -1 19269 -1 19270 -1 19271 -1 19272 -1 19273 -1 19274 -1 19275 -1 19276 -1 19277 -1 19278 -1 19279 -1 19280 -1 19281 -1 19282 -1 19283 -1 19284 -1 19285 -1 19286 -1 19287 -1 19288 -1 19289 -1 19290 -1 19291 -1 19292 -1 19293 -1 19294 -1 19295 -1 19296 -1 19297 -1 19298 -1 19299 -1 19300 -1 19301 -1 19302 -1 19303 -1 19304 -1 19305 -1 19306 -1 19307 -1 19308 -1 19309 -1 19310 -1 19311 -1 19312 -1 19313 -1 19314 -1 19315 -1 19316 -1 19317 -1 19318 -1 19319 -1 19320 -1 19321 -1 19322 -1 19323 -1 19324 -1 19325 -1 19326 -1 19327 -1 19328 -1 19329 -1 19330 -1 19331 -1 19332 -1 19333 -1 19334 -1 19335 -1 19336 -1 19337 -1 19338 -1 19339 -1 19340 -1 19341 -1 19342 -1 19343 -1 19344 -1 19345 -1 19346 -1 19347 -1 19348 -1 19349 -1 19350 -1 19351 -1 19352 -1 19353 -1 19354 -1 19355 -1 19356 -1 19357 -1 19358 -1 19359 -1 19360 -1 19361 -1 19362 -1 19363 -1 19364 -1 19365 -1 19366 -1 19367 -1 19368 -1 19369 -1 19370 -1 19371 -1 19372 -1 19373 -1 19374 -1 19375 -1 19376 -1 19377 -1 19378 -1 19379 -1 19380 -1 19381 -1 19382 -1 19383 -1 19384 -1 19385 -1 19386 -1 19387 -1 19388 -1 19389 -1 19390 -1 19391 -1 19392 -1 19393 -1 19394 -1 19395 -1 19396 -1 19397 -1 19398 -1 19399 -1 19400 -1 19401 -1 19402 -1 19403 -1 19404 -1 19405 -1 19406 -1 19407 -1 19408 -1 19409 -1 19410 -1 19411 -1 19412 -1 19413 -1 19414 -1 19415 -1 19416 -1 19417 -1 19418 -1 19419 -1 19420 -1 19421 -1 19422 -1 19423 -1 19424 -1 19425 -1 19426 -1 19427 -1 19428 -1 19429 -1 19430 -1 19431 -1 19432 -1 19433 -1 19434 -1 19435 -1 19436 -1 19437 -1 19438 -1 19439 -1 19440 -1 19441 -1 19442 -1 19443 -1 19444 -1 19445 -1 19446 -1 19447 -1 19448 -1 19449 -1 19450 -1 19451 -1 19452 -1 19453 -1 19454 -1 19455 -1 19456 -1 19457 -1 19458 -1 19459 -1 19460 -1 19461 -1 19462 -1 19463 -1 19464 -1 19465 -1 19466 -1 19467 -1 19468 -1 19469 -1 19470 -1 19471 -1 19472 -1 19473 -1 19474 -1 19475 -1 19476 -1 19477 -1 19478 -1 19479 -1 19480 -1 19481 -1 19482 -1 19483 -1 19484 -1 19485 -1 19486 -1 19487 -1 19488 -1 19489 -1 19490 -1 19491 -1 19492 -1 19493 -1 19494 -1 19495 -1 19496 -1 19497 -1 19498 -1 19499 -1 19500 -1 19501 -1 19502 -1 19503 -1 19504 -1 19505 -1 19506 -1 19507 -1 19508 -1 19509 -1 19510 -1 19511 -1 19512 -1 19513 -1 19514 -1 19515 -1 19516 -1 19517 -1 19518 -1 19519 -1 19520 -1 19521 -1 19522 -1 19523 -1 19524 -1 19525 -1 19526 -1 19527 -1 19528 -1 19529 -1 19530 -1 19531 -1 19532 -1 19533 -1 19534 -1 19535 -1 19536 -1 19537 -1 19538 -1 19539 -1 19540 -1 19541 -1 19542 -1 19543 -1 19544 -1 19545 -1 19546 -1 19547 -1 19548 -1 19549 -1 19550 -1 19551 -1 19552 -1 19553 -1 19554 -1 19555 -1 19556 -1 19557 -1 19558 -1 19559 -1 19560 -1 19561 -1 19562 -1 19563 -1 19564 -1 19565 -1 19566 -1 19567 -1 19568 -1 19569 -1 19570 -1 19571 -1 19572 -1 19573 -1 19574 -1 19575 -1 19576 -1 19577 -1 19578 -1 19579 -1 19580 -1 19581 -1 19582 -1 19583 -1 19584 -1 19585 -1 19586 -1 19587 -1 19588 -1 19589 -1 19590 -1 19591 -1 19592 -1 19593 -1 19594 -1 19595 -1 19596 -1 19597 -1 19598 -1 19599 -1 19600 -1 19601 -1 19602 -1 19603 -1 19604 -1 19605 -1 19606 -1 19607 -1 19608 -1 19609 -1 19610 -1 19611 -1 19612 -1 19613 -1 19614 -1 19615 -1 19616 -1 19617 -1 19618 -1 19619 -1 19620 -1 19621 -1 19622 -1 19623 -1 19624 -1 19625 -1 19626 -1 19627 -1 19628 -1 19629 -1 19630 -1 19631 -1 19632 -1 19633 -1 19634 -1 19635 -1 19636 -1 19637 -1 19638 -1 19639 -1 19640 -1 19641 -1 19642 -1 19643 -1 19644 -1 19645 -1 19646 -1 19647 -1 19648 -1 19649 -1 19650 -1 19651 -1 19652 -1 19653 -1 19654 -1 19655 -1 19656 -1 19657 -1 19658 -1 19659 -1 19660 -1 19661 -1 19662 -1 19663 -1 19664 -1 19665 -1 19666 -1 19667 -1 19668 -1 19669 -1 19670 -1 19671 -1 19672 -1 19673 -1 19674 -1 19675 -1 19676 -1 19677 -1 19678 -1 19679 -1 19680 -1 19681 -1 19682 -1 19683 -1 19684 -1 19685 -1 19686 -1 19687 -1 19688 -1 19689 -1 19690 -1 19691 -1 19692 -1 19693 -1 19694 -1 19695 -1 19696 -1 19697 -1 19698 -1 19699 -1 19700 -1 19701 -1 19702 -1 19703 -1 19704 -1 19705 -1 19706 -1 19707 -1 19708 -1 19709 -1 19710 -1 19711 -1 19712 -1 19713 -1 19714 -1 19715 -1 19716 -1 19717 -1 19718 -1 19719 -1 19720 -1 19721 -1 19722 -1 19723 -1 19724 -1 19725 -1 19726 -1 19727 -1 19728 -1 19729 -1 19730 -1 19731 -1 19732 -1 19733 -1 19734 -1 19735 -1 19736 -1 19737 -1 19738 -1 19739 -1 19740 -1 19741 -1 19742 -1 19743 -1 19744 -1 19745 -1 19746 -1 19747 -1 19748 -1 19749 -1 19750 -1 19751 -1 19752 -1 19753 -1 19754 -1 19755 -1 19756 -1 19757 -1 19758 -1 19759 -1 19760 -1 19761 -1 19762 -1 19763 -1 19764 -1 19765 -1 19766 -1 19767 -1 19768 -1 19769 -1 19770 -1 19771 -1 19772 -1 19773 -1 19774 -1 19775 -1 19776 -1 19777 -1 19778 -1 19779 -1 19780 -1 19781 -1 19782 -1 19783 -1 19784 -1 19785 -1 19786 -1 19787 -1 19788 -1 19789 -1 19790 -1 19791 -1 19792 -1 19793 -1 19794 -1 19795 -1 19796 -1 19797 -1 19798 -1 19799 -1 19800 -1 19801 -1 19802 -1 19803 -1 19804 -1 19805 -1 19806 -1 19807 -1 19808 -1 19809 -1 19810 -1 19811 -1 19812 -1 19813 -1 19814 -1 19815 -1 19816 -1 19817 -1 19818 -1 19819 -1 19820 -1 19821 -1 19822 -1 19823 -1 19824 -1 19825 -1 19826 -1 19827 -1 19828 -1 19829 -1 19830 -1 19831 -1 19832 -1 19833 -1 19834 -1 19835 -1 19836 -1 19837 -1 19838 -1 19839 -1 19840 -1 19841 -1 19842 -1 19843 -1 19844 -1 19845 -1 19846 -1 19847 -1 19848 -1 19849 -1 19850 -1 19851 -1 19852 -1 19853 -1 19854 -1 19855 -1 19856 -1 19857 -1 19858 -1 19859 -1 19860 -1 19861 -1 19862 -1 19863 -1 19864 -1 19865 -1 19866 -1 19867 -1 19868 -1 19869 -1 19870 -1 19871 -1 19872 -1 19873 -1 19874 -1 19875 -1 19876 -1 19877 -1 19878 -1 19879 -1 19880 -1 19881 -1 19882 -1 19883 -1 19884 -1 19885 -1 19886 -1 19887 -1 19888 -1 19889 -1 19890 -1 19891 -1 19892 -1 19893 -1 19894 -1 19895 -1 19896 -1 19897 -1 19898 -1 19899 -1 19900 -1 19901 -1 19902 -1 19903 -1 19904 -1 19905 -1 19906 -1 19907 -1 19908 -1 19909 -1 19910 -1 19911 -1 19912 -1 19913 -1 19914 -1 19915 -1 19916 -1 19917 -1 19918 -1 19919 -1 19920 -1 19921 -1 19922 -1 19923 -1 19924 -1 19925 -1 19926 -1 19927 -1 19928 -1 19929 -1 19930 -1 19931 -1 19932 -1 19933 -1 19934 -1 19935 -1 19936 -1 19937 -1 19938 -1 19939 -1 19940 -1 19941 -1 19942 -1 19943 -1 19944 -1 19945 -1 19946 -1 19947 -1 19948 -1 19949 -1 19950 -1 19951 -1 19952 -1 19953 -1 19954 -1 19955 -1 19956 -1 19957 -1 19958 -1 19959 -1 19960 -1 19961 -1 19962 -1 19963 -1 19964 -1 19965 -1 19966 -1 19967 -1 19968 -1 19969 -1 19970 -1 19971 -1 19972 -1 19973 -1 19974 -1 19975 -1 19976 -1 19977 -1 19978 -1 19979 -1 19980 -1 19981 -1 19982 -1 19983 -1 19984 -1 19985 -1 19986 -1 19987 -1 19988 -1 19989 -1 19990 -1 19991 -1 19992 -1 19993 -1 19994 -1 19995 -1 19996 -1 19997 -1 19998 -1 19999 -1 20000 -1 20001 -1 20002 -1 20003 -1 20004 -1 20005 -1 20006 -1 20007 -1 20008 -1 20009 -1 20010 -1 20011 -1 20012 -1 20013 -1 20014 -1 20015 -1 20016 -1 20017 -1 20018 -1 20019 -1 20020 -1 20021 -1 20022 -1 20023 -1 20024 -1 20025 -1 20026 -1 20027 -1 20028 -1 20029 -1 20030 -1 20031 -1 20032 -1 20033 -1 20034 -1 20035 -1 20036 -1 20037 -1 20038 -1 20039 -1 20040 -1 20041 -1 20042 -1 20043 -1 20044 -1 20045 -1 20046 -1 20047 -1 20048 -1 20049 -1 20050 -1 20051 -1 20052 -1 20053 -1 20054 -1 20055 -1 20056 -1 20057 -1 20058 -1 20059 -1 20060 -1 20061 -1 20062 -1 20063 -1 20064 -1 20065 -1 20066 -1 20067 -1 20068 -1 20069 -1 20070 -1 20071 -1 20072 -1 20073 -1 20074 -1 20075 -1 20076 -1 20077 -1 20078 -1 20079 -1 20080 -1 20081 -1 20082 -1 20083 -1 20084 -1 20085 -1 20086 -1 20087 -1 20088 -1 20089 -1 20090 -1 20091 -1 20092 -1 20093 -1 20094 -1 20095 -1 20096 -1 20097 -1 20098 -1 20099 -1 20100 -1 20101 -1 20102 -1 20103 -1 20104 -1 20105 -1 20106 -1 20107 -1 20108 -1 20109 -1 20110 -1 20111 -1 20112 -1 20113 -1 20114 -1 20115 -1 20116 -1 20117 -1 20118 -1 20119 -1 20120 -1 20121 -1 20122 -1 20123 -1 20124 -1 20125 -1 20126 -1 20127 -1 20128 -1 20129 -1 20130 -1 20131 -1 20132 -1 20133 -1 20134 -1 20135 -1 20136 -1 20137 -1 20138 -1 20139 -1 20140 -1 20141 -1 20142 -1 20143 -1 20144 -1 20145 -1 20146 -1 20147 -1 20148 -1 20149 -1 20150 -1 20151 -1 20152 -1 20153 -1 20154 -1 20155 -1 20156 -1 20157 -1 20158 -1 20159 -1 20160 -1 20161 -1 20162 -1 20163 -1 20164 -1 20165 -1 20166 -1 20167 -1 20168 -1 20169 -1 20170 -1 20171 -1 20172 -1 20173 -1 20174 -1 20175 -1 20176 -1 20177 -1 20178 -1 20179 -1 20180 -1 20181 -1 20182 -1 20183 -1 20184 -1 20185 -1 20186 -1 20187 -1 20188 -1 20189 -1 20190 -1 20191 -1 20192 -1 20193 -1 20194 -1 20195 -1 20196 -1 20197 -1 20198 -1 20199 -1 20200 -1 20201 -1 20202 -1 20203 -1 20204 -1 20205 -1 20206 -1 20207 -1 20208 -1 20209 -1 20210 -1 20211 -1 20212 -1 20213 -1 20214 -1 20215 -1 20216 -1 20217 -1 20218 -1 20219 -1 20220 -1 20221 -1 20222 -1 20223 -1 20224 -1 20225 -1 20226 -1 20227 -1 20228 -1 20229 -1 20230 -1 20231 -1 20232 -1 20233 -1 20234 -1 20235 -1 20236 -1 20237 -1 20238 -1 20239 -1 20240 -1 20241 -1 20242 -1 20243 -1 20244 -1 20245 -1 20246 -1 20247 -1 20248 -1 20249 -1 20250 -1 20251 -1 20252 -1 20253 -1 20254 -1 20255 -1 20256 -1 20257 -1 20258 -1 20259 -1 20260 -1 20261 -1 20262 -1 20263 -1 20264 -1 20265 -1 20266 -1 20267 -1 20268 -1 20269 -1 20270 -1 20271 -1 20272 -1 20273 -1 20274 -1 20275 -1 20276 -1 20277 -1 20278 -1 20279 -1 20280 -1 20281 -1 20282 -1 20283 -1 20284 -1 20285 -1 20286 -1 20287 -1 20288 -1 20289 -1 20290 -1 20291 -1 20292 -1 20293 -1 20294 -1 20295 -1 20296 -1 20297 -1 20298 -1 20299 -1 20300 -1 20301 -1 20302 -1 20303 -1 20304 -1 20305 -1 20306 -1 20307 -1 20308 -1 20309 -1 20310 -1 20311 -1 20312 -1 20313 -1 20314 -1 20315 -1 20316 -1 20317 -1 20318 -1 20319 -1 20320 -1 20321 -1 20322 -1 20323 -1 20324 -1 20325 -1 20326 -1 20327 -1 20328 -1 20329 -1 20330 -1 20331 -1 20332 -1 20333 -1 20334 -1 20335 -1 20336 -1 20337 -1 20338 -1 20339 -1 20340 -1 20341 -1 20342 -1 20343 -1 20344 -1 20345 -1 20346 -1 20347 -1 20348 -1 20349 -1 20350 -1 20351 -1 20352 -1 20353 -1 20354 -1 20355 -1 20356 -1 20357 -1 20358 -1 20359 -1 20360 -1 20361 -1 20362 -1 20363 -1 20364 -1 20365 -1 20366 -1 20367 -1 20368 -1 20369 -1 20370 -1 20371 -1 20372 -1 20373 -1 20374 -1 20375 -1 20376 -1 20377 -1 20378 -1 20379 -1 20380 -1 20381 -1 20382 -1 20383 -1 20384 -1 20385 -1 20386 -1 20387 -1 20388 -1 20389 -1 20390 -1 20391 -1 20392 -1 20393 -1 20394 -1 20395 -1 20396 -1 20397 -1 20398 -1 20399 -1 20400 -1 20401 -1 20402 -1 20403 -1 20404 -1 20405 -1 20406 -1 20407 -1 20408 -1 20409 -1 20410 -1 20411 -1 20412 -1 20413 -1 20414 -1 20415 -1 20416 -1 20417 -1 20418 -1 20419 -1 20420 -1 20421 -1 20422 -1 20423 -1 20424 -1 20425 -1 20426 -1 20427 -1 20428 -1 20429 -1 20430 -1 20431 -1 20432 -1 20433 -1 20434 -1 20435 -1 20436 -1 20437 -1 20438 -1 20439 -1 20440 -1 20441 -1 20442 -1 20443 -1 20444 -1 20445 -1 20446 -1 20447 -1 20448 -1 20449 -1 20450 -1 20451 -1 20452 -1 20453 -1 20454 -1 20455 -1 20456 -1 20457 -1 20458 -1 20459 -1 20460 -1 20461 -1 20462 -1 20463 -1 20464 -1 20465 -1 20466 -1 20467 -1 20468 -1 20469 -1 20470 -1 20471 -1 20472 -1 20473 -1 20474 -1 20475 -1 20476 -1 20477 -1 20478 -1 20479 -1 20480 -1 20481 -1 20482 -1 20483 -1 20484 -1 20485 -1 20486 -1 20487 -1 20488 -1 20489 -1 20490 -1 20491 -1 20492 -1 20493 -1 20494 -1 20495 -1 20496 -1 20497 -1 20498 -1 20499 -1 20500 -1 20501 -1 20502 -1 20503 -1 20504 -1 20505 -1 20506 -1 20507 -1 20508 -1 20509 -1 20510 -1 20511 -1 20512 -1 20513 -1 20514 -1 20515 -1 20516 -1 20517 -1 20518 -1 20519 -1 20520 -1 20521 -1 20522 -1 20523 -1 20524 -1 20525 -1 20526 -1 20527 -1 20528 -1 20529 -1 20530 -1 20531 -1 20532 -1 20533 -1 20534 -1 20535 -1 20536 -1 20537 -1 20538 -1 20539 -1 20540 -1 20541 -1 20542 -1 20543 -1 20544 -1 20545 -1 20546 -1 20547 -1 20548 -1 20549 -1 20550 -1 20551 -1 20552 -1 20553 -1 20554 -1 20555 -1 20556 -1 20557 -1 20558 -1 20559 -1 20560 -1 20561 -1 20562 -1 20563 -1 20564 -1 20565 -1 20566 -1 20567 -1 20568 -1 20569 -1 20570 -1 20571 -1 20572 -1 20573 -1 20574 -1 20575 -1 20576 -1 20577 -1 20578 -1 20579 -1 20580 -1 20581 -1 20582 -1 20583 -1 20584 -1 20585 -1 20586 -1 20587 -1 20588 -1 20589 -1 20590 -1 20591 -1 20592 -1 20593 -1 20594 -1 20595 -1 20596 -1 20597 -1 20598 -1 20599 -1 20600 -1 20601 -1 20602 -1 20603 -1 20604 -1 20605 -1 20606 -1 20607 -1 20608 -1 20609 -1 20610 -1 20611 -1 20612 -1 20613 -1 20614 -1 20615 -1 20616 -1 20617 -1 20618 -1 20619 -1 20620 -1 20621 -1 20622 -1 20623 -1 20624 -1 20625 -1 20626 -1 20627 -1 20628 -1 20629 -1 20630 -1 20631 -1 20632 -1 20633 -1 20634 -1 20635 -1 20636 -1 20637 -1 20638 -1 20639 -1 20640 -1 20641 -1 20642 -1 20643 -1 20644 -1 20645 -1 20646 -1 20647 -1 20648 -1 20649 -1 20650 -1 20651 -1 20652 -1 20653 -1 20654 -1 20655 -1 20656 -1 20657 -1 20658 -1 20659 -1 20660 -1 20661 -1 20662 -1 20663 -1 20664 -1 20665 -1 20666 -1 20667 -1 20668 -1 20669 -1 20670 -1 20671 -1 20672 -1 20673 -1 20674 -1 20675 -1 20676 -1 20677 -1 20678 -1 20679 -1 20680 -1 20681 -1 20682 -1 20683 -1 20684 -1 20685 -1 20686 -1 20687 -1 20688 -1 20689 -1 20690 -1 20691 -1 20692 -1 20693 -1 20694 -1 20695 -1 20696 -1 20697 -1 20698 -1 20699 -1 20700 -1 20701 -1 20702 -1 20703 -1 20704 -1 20705 -1 20706 -1 20707 -1 20708 -1 20709 -1 20710 -1 20711 -1 20712 -1 20713 -1 20714 -1 20715 -1 20716 -1 20717 -1 20718 -1 20719 -1 20720 -1 20721 -1 20722 -1 20723 -1 20724 -1 20725 -1 20726 -1 20727 -1 20728 -1 20729 -1 20730 -1 20731 -1 20732 -1 20733 -1 20734 -1 20735 -1 20736 -1 20737 -1 20738 -1 20739 -1 20740 -1 20741 -1 20742 -1 20743 -1 20744 -1 20745 -1 20746 -1 20747 -1 20748 -1 20749 -1 20750 -1 20751 -1 20752 -1 20753 -1 20754 -1 20755 -1 20756 -1 20757 -1 20758 -1 20759 -1 20760 -1 20761 -1 20762 -1 20763 -1 20764 -1 20765 -1 20766 -1 20767 -1 20768 -1 20769 -1 20770 -1 20771 -1 20772 -1 20773 -1 20774 -1 20775 -1 20776 -1 20777 -1 20778 -1 20779 -1 20780 -1 20781 -1 20782 -1 20783 -1 20784 -1 20785 -1 20786 -1 20787 -1 20788 -1 20789 -1 20790 -1 20791 -1 20792 -1 20793 -1 20794 -1 20795 -1 20796 -1 20797 -1 20798 -1 20799 -1 20800 -1 20801 -1 20802 -1 20803 -1 20804 -1 20805 -1 20806 -1 20807 -1 20808 -1 20809 -1 20810 -1 20811 -1 20812 -1 20813 -1 20814 -1 20815 -1 20816 -1 20817 -1 20818 -1 20819 -1 20820 -1 20821 -1 20822 -1 20823 -1 20824 -1 20825 -1 20826 -1 20827 -1 20828 -1 20829 -1 20830 -1 20831 -1 20832 -1 20833 -1 20834 -1 20835 -1 20836 -1 20837 -1 20838 -1 20839 -1 20840 -1 20841 -1 20842 -1 20843 -1 20844 -1 20845 -1 20846 -1 20847 -1 20848 -1 20849 -1 20850 -1 20851 -1 20852 -1 20853 -1 20854 -1 20855 -1 20856 -1 20857 -1 20858 -1 20859 -1 20860 -1 20861 -1 20862 -1 20863 -1 20864 -1 20865 -1 20866 -1 20867 -1 20868 -1 20869 -1 20870 -1 20871 -1 20872 -1 20873 -1 20874 -1 20875 -1 20876 -1 20877 -1 20878 -1 20879 -1 20880 -1 20881 -1 20882 -1 20883 -1 20884 -1 20885 -1 20886 -1 20887 -1 20888 -1 20889 -1 20890 -1 20891 -1 20892 -1 20893 -1 20894 -1 20895 -1 20896 -1 20897 -1 20898 -1 20899 -1 20900 -1 20901 -1 20902 -1 20903 -1 20904 -1 20905 -1 20906 -1 20907 -1 20908 -1 20909 -1 20910 -1 20911 -1 20912 -1 20913 -1 20914 -1 20915 -1 20916 -1 20917 -1 20918 -1 20919 -1 20920 -1 20921 -1 20922 -1 20923 -1 20924 -1 20925 -1 20926 -1 20927 -1 20928 -1 20929 -1 20930 -1 20931 -1 20932 -1 20933 -1 20934 -1 20935 -1 20936 -1 20937 -1 20938 -1 20939 -1 20940 -1 20941 -1 20942 -1 20943 -1 20944 -1 20945 -1 20946 -1 20947 -1 20948 -1 20949 -1 20950 -1 20951 -1 20952 -1 20953 -1 20954 -1 20955 -1 20956 -1 20957 -1 20958 -1 20959 -1 20960 -1 20961 -1 20962 -1 20963 -1 20964 -1 20965 -1 20966 -1 20967 -1 20968 -1 20969 -1 20970 -1 20971 -1 20972 -1 20973 -1 20974 -1 20975 -1 20976 -1 20977 -1 20978 -1 20979 -1 20980 -1 20981 -1 20982 -1 20983 -1 20984 -1 20985 -1 20986 -1 20987 -1 20988 -1 20989 -1 20990 -1 20991 -1 20992 -1 20993 -1 20994 -1 20995 -1 20996 -1 20997 -1 20998 -1 20999 -1 21000 -1 21001 -1 21002 -1 21003 -1 21004 -1 21005 -1 21006 -1 21007 -1 21008 -1 21009 -1 21010 -1 21011 -1 21012 -1 21013 -1 21014 -1 21015 -1 21016 -1 21017 -1 21018 -1 21019 -1 21020 -1 21021 -1 21022 -1 21023 -1 21024 -1 21025 -1 21026 -1 21027 -1 21028 -1 21029 -1 21030 -1 21031 -1 21032 -1 21033 -1 21034 -1 21035 -1 21036 -1 21037 -1 21038 -1 21039 -1 21040 -1 21041 -1 21042 -1 21043 -1 21044 -1 21045 -1 21046 -1 21047 -1 21048 -1 21049 -1 21050 -1 21051 -1 21052 -1 21053 -1 21054 -1 21055 -1 21056 -1 21057 -1 21058 -1 21059 -1 21060 -1 21061 -1 21062 -1 21063 -1 21064 -1 21065 -1 21066 -1 21067 -1 21068 -1 21069 -1 21070 -1 21071 -1 21072 -1 21073 -1 21074 -1 21075 -1 21076 -1 21077 -1 21078 -1 21079 -1 21080 -1 21081 -1 21082 -1 21083 -1 21084 -1 21085 -1 21086 -1 21087 -1 21088 -1 21089 -1 21090 -1 21091 -1 21092 -1 21093 -1 21094 -1 21095 -1 21096 -1 21097 -1 21098 -1 21099 -1 21100 -1 21101 -1 21102 -1 21103 -1 21104 -1 21105 -1 21106 -1 21107 -1 21108 -1 21109 -1 21110 -1 21111 -1 21112 -1 21113 -1 21114 -1 21115 -1 21116 -1 21117 -1 21118 -1 21119 -1 21120 -1 21121 -1 21122 -1 21123 -1 21124 -1 21125 -1 21126 -1 21127 -1 21128 -1 21129 -1 21130 -1 21131 -1 21132 -1 21133 -1 21134 -1 21135 -1 21136 -1 21137 -1 21138 -1 21139 -1 21140 -1 21141 -1 21142 -1 21143 -1 21144 -1 21145 -1 21146 -1 21147 -1 21148 -1 21149 -1 21150 -1 21151 -1 21152 -1 21153 -1 21154 -1 21155 -1 21156 -1 21157 -1 21158 -1 21159 -1 21160 -1 21161 -1 21162 -1 21163 -1 21164 -1 21165 -1 21166 -1 21167 -1 21168 -1 21169 -1 21170 -1 21171 -1 21172 -1 21173 -1 21174 -1 21175 -1 21176 -1 21177 -1 21178 -1 21179 -1 21180 -1 21181 -1 21182 -1 21183 -1 21184 -1 21185 -1 21186 -1 21187 -1 21188 -1 21189 -1 21190 -1 21191 -1 21192 -1 21193 -1 21194 -1 21195 -1 21196 -1 21197 -1 21198 -1 21199 -1 21200 -1 21201 -1 21202 -1 21203 -1 21204 -1 21205 -1 21206 -1 21207 -1 21208 -1 21209 -1 21210 -1 21211 -1 21212 -1 21213 -1 21214 -1 21215 -1 21216 -1 21217 -1 21218 -1 21219 -1 21220 -1 21221 -1 21222 -1 21223 -1 21224 -1 21225 -1 21226 -1 21227 -1 21228 -1 21229 -1 21230 -1 21231 -1 21232 -1 21233 -1 21234 -1 21235 -1 21236 -1 21237 -1 21238 -1 21239 -1 21240 -1 21241 -1 21242 -1 21243 -1 21244 -1 21245 -1 21246 -1 21247 -1 21248 -1 21249 -1 21250 -1 21251 -1 21252 -1 21253 -1 21254 -1 21255 -1 21256 -1 21257 -1 21258 -1 21259 -1 21260 -1 21261 -1 21262 -1 21263 -1 21264 -1 21265 -1 21266 -1 21267 -1 21268 -1 21269 -1 21270 -1 21271 -1 21272 -1 21273 -1 21274 -1 21275 -1 21276 -1 21277 -1 21278 -1 21279 -1 21280 -1 21281 -1 21282 -1 21283 -1 21284 -1 21285 -1 21286 -1 21287 -1 21288 -1 21289 -1 21290 -1 21291 -1 21292 -1 21293 -1 21294 -1 21295 -1 21296 -1 21297 -1 21298 -1 21299 -1 21300 -1 21301 -1 21302 -1 21303 -1 21304 -1 21305 -1 21306 -1 21307 -1 21308 -1 21309 -1 21310 -1 21311 -1 21312 -1 21313 -1 21314 -1 21315 -1 21316 -1 21317 -1 21318 -1 21319 -1 21320 -1 21321 -1 21322 -1 21323 -1 21324 -1 21325 -1 21326 -1 21327 -1 21328 -1 21329 -1 21330 -1 21331 -1 21332 -1 21333 -1 21334 -1 21335 -1 21336 -1 21337 -1 21338 -1 21339 -1 21340 -1 21341 -1 21342 -1 21343 -1 21344 -1 21345 -1 21346 -1 21347 -1 21348 -1 21349 -1 21350 -1 21351 -1 21352 -1 21353 -1 21354 -1 21355 -1 21356 -1 21357 -1 21358 -1 21359 -1 21360 -1 21361 -1 21362 -1 21363 -1 21364 -1 21365 -1 21366 -1 21367 -1 21368 -1 21369 -1 21370 -1 21371 -1 21372 -1 21373 -1 21374 -1 21375 -1 21376 -1 21377 -1 21378 -1 21379 -1 21380 -1 21381 -1 21382 -1 21383 -1 21384 -1 21385 -1 21386 -1 21387 -1 21388 -1 21389 -1 21390 -1 21391 -1 21392 -1 21393 -1 21394 -1 21395 -1 21396 -1 21397 -1 21398 -1 21399 -1 21400 -1 21401 -1 21402 -1 21403 -1 21404 -1 21405 -1 21406 -1 21407 -1 21408 -1 21409 -1 21410 -1 21411 -1 21412 -1 21413 -1 21414 -1 21415 -1 21416 -1 21417 -1 21418 -1 21419 -1 21420 -1 21421 -1 21422 -1 21423 -1 21424 -1 21425 -1 21426 -1 21427 -1 21428 -1 21429 -1 21430 -1 21431 -1 21432 -1 21433 -1 21434 -1 21435 -1 21436 -1 21437 -1 21438 -1 21439 -1 21440 -1 21441 -1 21442 -1 21443 -1 21444 -1 21445 -1 21446 -1 21447 -1 21448 -1 21449 -1 21450 -1 21451 -1 21452 -1 21453 -1 21454 -1 21455 -1 21456 -1 21457 -1 21458 -1 21459 -1 21460 -1 21461 -1 21462 -1 21463 -1 21464 -1 21465 -1 21466 -1 21467 -1 21468 -1 21469 -1 21470 -1 21471 -1 21472 -1 21473 -1 21474 -1 21475 -1 21476 -1 21477 -1 21478 -1 21479 -1 21480 -1 21481 -1 21482 -1 21483 -1 21484 -1 21485 -1 21486 -1 21487 -1 21488 -1 21489 -1 21490 -1 21491 -1 21492 -1 21493 -1 21494 -1 21495 -1 21496 -1 21497 -1 21498 -1 21499 -1 21500 -1 21501 -1 21502 -1 21503 -1 21504 -1 21505 -1 21506 -1 21507 -1 21508 -1 21509 -1 21510 -1 21511 -1 21512 -1 21513 -1 21514 -1 21515 -1 21516 -1 21517 -1 21518 -1 21519 -1 21520 -1 21521 -1 21522 -1 21523 -1 21524 -1 21525 -1 21526 -1 21527 -1 21528 -1 21529 -1 21530 -1 21531 -1 21532 -1 21533 -1 21534 -1 21535 -1 21536 -1 21537 -1 21538 -1 21539 -1 21540 -1 21541 -1 21542 -1 21543 -1 21544 -1 21545 -1 21546 -1 21547 -1 21548 -1 21549 -1 21550 -1 21551 -1 21552 -1 21553 -1 21554 -1 21555 -1 21556 -1 21557 -1 21558 -1 21559 -1 21560 -1 21561 -1 21562 -1 21563 -1 21564 -1 21565 -1 21566 -1 21567 -1 21568 -1 21569 -1 21570 -1 21571 -1 21572 -1 21573 -1 21574 -1 21575 -1 21576 -1 21577 -1 21578 -1 21579 -1 21580 -1 21581 -1 21582 -1 21583 -1 21584 -1 21585 -1 21586 -1 21587 -1 21588 -1 21589 -1 21590 -1 21591 -1 21592 -1 21593 -1 21594 -1 21595 -1 21596 -1 21597 -1 21598 -1 21599 -1 21600 -1 21601 -1 21602 -1 21603 -1 21604 -1 21605 -1 21606 -1 21607 -1 21608 -1 21609 -1 21610 -1 21611 -1 21612 -1 21613 -1 21614 -1 21615 -1 21616 -1 21617 -1 21618 -1 21619 -1 21620 -1 21621 -1 21622 -1 21623 -1 21624 -1 21625 -1 21626 -1 21627 -1 21628 -1 21629 -1 21630 -1 21631 -1 21632 -1 21633 -1 21634 -1 21635 -1 21636 -1 21637 -1 21638 -1 21639 -1 21640 -1 21641 -1 21642 -1 21643 -1 21644 -1 21645 -1 21646 -1 21647 -1 21648 -1 21649 -1 21650 -1 21651 -1 21652 -1 21653 -1 21654 -1 21655 -1 21656 -1 21657 -1 21658 -1 21659 -1 21660 -1 21661 -1 21662 -1 21663 -1 21664 -1 21665 -1 21666 -1 21667 -1 21668 -1 21669 -1 21670 -1 21671 -1 21672 -1 21673 -1 21674 -1 21675 -1 21676 -1 21677 -1 21678 -1 21679 -1 21680 -1 21681 -1 21682 -1 21683 -1 21684 -1 21685 -1 21686 -1 21687 -1 21688 -1 21689 -1 21690 -1 21691 -1 21692 -1 21693 -1 21694 -1 21695 -1 21696 -1 21697 -1 21698 -1 21699 -1 21700 -1 21701 -1 21702 -1 21703 -1 21704 -1 21705 -1 21706 -1 21707 -1 21708 -1 21709 -1 21710 -1 21711 -1 21712 -1 21713 -1 21714 -1 21715 -1 21716 -1 21717 -1 21718 -1 21719 -1 21720 -1 21721 -1 21722 -1 21723 -1 21724 -1 21725 -1 21726 -1 21727 -1 21728 -1 21729 -1 21730 -1 21731 -1 21732 -1 21733 -1 21734 -1 21735 -1 21736 -1 21737 -1 21738 -1 21739 -1 21740 -1 21741 -1 21742 -1 21743 -1 21744 -1 21745 -1 21746 -1 21747 -1 21748 -1 21749 -1 21750 -1 21751 -1 21752 -1 21753 -1 21754 -1 21755 -1 21756 -1 21757 -1 21758 -1 21759 -1 21760 -1 21761 -1 21762 -1 21763 -1 21764 -1 21765 -1 21766 -1 21767 -1 21768 -1 21769 -1 21770 -1 21771 -1 21772 -1 21773 -1 21774 -1 21775 -1 21776 -1 21777 -1 21778 -1 21779 -1 21780 -1 21781 -1 21782 -1 21783 -1 21784 -1 21785 -1 21786 -1 21787 -1 21788 -1 21789 -1 21790 -1 21791 -1 21792 -1 21793 -1 21794 -1 21795 -1 21796 -1 21797 -1 21798 -1 21799 -1 21800 -1 21801 -1 21802 -1 21803 -1 21804 -1 21805 -1 21806 -1 21807 -1 21808 -1 21809 -1 21810 -1 21811 -1 21812 -1 21813 -1 21814 -1 21815 -1 21816 -1 21817 -1 21818 -1 21819 -1 21820 -1 21821 -1 21822 -1 21823 -1 21824 -1 21825 -1 21826 -1 21827 -1 21828 -1 21829 -1 21830 -1 21831 -1 21832 -1 21833 -1 21834 -1 21835 -1 21836 -1 21837 -1 21838 -1 21839 -1 21840 -1 21841 -1 21842 -1 21843 -1 21844 -1 21845 -1 21846 -1 21847 -1 21848 -1 21849 -1 21850 -1 21851 -1 21852 -1 21853 -1 21854 -1 21855 -1 21856 -1 21857 -1 21858 -1 21859 -1 21860 -1 21861 -1 21862 -1 21863 -1 21864 -1 21865 -1 21866 -1 21867 -1 21868 -1 21869 -1 21870 -1 21871 -1 21872 -1 21873 -1 21874 -1 21875 -1 21876 -1 21877 -1 21878 -1 21879 -1 21880 -1 21881 -1 21882 -1 21883 -1 21884 -1 21885 -1 21886 -1 21887 -1 21888 -1 21889 -1 21890 -1 21891 -1 21892 -1 21893 -1 21894 -1 21895 -1 21896 -1 21897 -1 21898 -1 21899 -1 21900 -1 21901 -1 21902 -1 21903 -1 21904 -1 21905 -1 21906 -1 21907 -1 21908 -1 21909 -1 21910 -1 21911 -1 21912 -1 21913 -1 21914 -1 21915 -1 21916 -1 21917 -1 21918 -1 21919 -1 21920 -1 21921 -1 21922 -1 21923 -1 21924 -1 21925 -1 21926 -1 21927 -1 21928 -1 21929 -1 21930 -1 21931 -1 21932 -1 21933 -1 21934 -1 21935 -1 21936 -1 21937 -1 21938 -1 21939 -1 21940 -1 21941 -1 21942 -1 21943 -1 21944 -1 21945 -1 21946 -1 21947 -1 21948 -1 21949 -1 21950 -1 21951 -1 21952 -1 21953 -1 21954 -1 21955 -1 21956 -1 21957 -1 21958 -1 21959 -1 21960 -1 21961 -1 21962 -1 21963 -1 21964 -1 21965 -1 21966 -1 21967 -1 21968 -1 21969 -1 21970 -1 21971 -1 21972 -1 21973 -1 21974 -1 21975 -1 21976 -1 21977 -1 21978 -1 21979 -1 21980 -1 21981 -1 21982 -1 21983 -1 21984 -1 21985 -1 21986 -1 21987 -1 21988 -1 21989 -1 21990 -1 21991 -1 21992 -1 21993 -1 21994 -1 21995 -1 21996 -1 21997 -1 21998 -1 21999 -1 22000 -1 22001 -1 22002 -1 22003 -1 22004 -1 22005 -1 22006 -1 22007 -1 22008 -1 22009 -1 22010 -1 22011 -1 22012 -1 22013 -1 22014 -1 22015 -1 22016 -1 22017 -1 22018 -1 22019 -1 22020 -1 22021 -1 22022 -1 22023 -1 22024 -1 22025 -1 22026 -1 22027 -1 22028 -1 22029 -1 22030 -1 22031 -1 22032 -1 22033 -1 22034 -1 22035 -1 22036 -1 22037 -1 22038 -1 22039 -1 22040 -1 22041 -1 22042 -1 22043 -1 22044 -1 22045 -1 22046 -1 22047 -1 22048 -1 22049 -1 22050 -1 22051 -1 22052 -1 22053 -1 22054 -1 22055 -1 22056 -1 22057 -1 22058 -1 22059 -1 22060 -1 22061 -1 22062 -1 22063 -1 22064 -1 22065 -1 22066 -1 22067 -1 22068 -1 22069 -1 22070 -1 22071 -1 22072 -1 22073 -1 22074 -1 22075 -1 22076 -1 22077 -1 22078 -1 22079 -1 22080 -1 22081 -1 22082 -1 22083 -1 22084 -1 22085 -1 22086 -1 22087 -1 22088 -1 22089 -1 22090 -1 22091 -1 22092 -1 22093 -1 22094 -1 22095 -1 22096 -1 22097 -1 22098 -1 22099 -1 22100 -1 22101 -1 22102 -1 22103 -1 22104 -1 22105 -1 22106 -1 22107 -1 22108 -1 22109 -1 22110 -1 22111 -1 22112 -1 22113 -1 22114 -1 22115 -1 22116 -1 22117 -1 22118 -1 22119 -1 22120 -1 22121 -1 22122 -1 22123 -1 22124 -1 22125 -1 22126 -1 22127 -1 22128 -1 22129 -1 22130 -1 22131 -1 22132 -1 22133 -1 22134 -1 22135 -1 22136 -1 22137 -1 22138 -1 22139 -1 22140 -1 22141 -1 22142 -1 22143 -1 22144 -1 22145 -1 22146 -1 22147 -1 22148 -1 22149 -1 22150 -1 22151 -1 22152 -1 22153 -1 22154 -1 22155 -1 22156 -1 22157 -1 22158 -1 22159 -1 22160 -1 22161 -1 22162 -1 22163 -1 22164 -1 22165 -1 22166 -1 22167 -1 22168 -1 22169 -1 22170 -1 22171 -1 22172 -1 22173 -1 22174 -1 22175 -1 22176 -1 22177 -1 22178 -1 22179 -1 22180 -1 22181 -1 22182 -1 22183 -1 22184 -1 22185 -1 22186 -1 22187 -1 22188 -1 22189 -1 22190 -1 22191 -1 22192 -1 22193 -1 22194 -1 22195 -1 22196 -1 22197 -1 22198 -1 22199 -1 22200 -1 22201 -1 22202 -1 22203 -1 22204 -1 22205 -1 22206 -1 22207 -1 22208 -1 22209 -1 22210 -1 22211 -1 22212 -1 22213 -1 22214 -1 22215 -1 22216 -1 22217 -1 22218 -1 22219 -1 22220 -1 22221 -1 22222 -1 22223 -1 22224 -1 22225 -1 22226 -1 22227 -1 22228 -1 22229 -1 22230 -1 22231 -1 22232 -1 22233 -1 22234 -1 22235 -1 22236 -1 22237 -1 22238 -1 22239 -1 22240 -1 22241 -1 22242 -1 22243 -1 22244 -1 22245 -1 22246 -1 22247 -1 22248 -1 22249 -1 22250 -1 22251 -1 22252 -1 22253 -1 22254 -1 22255 -1 22256 -1 22257 -1 22258 -1 22259 -1 22260 -1 22261 -1 22262 -1 22263 -1 22264 -1 22265 -1 22266 -1 22267 -1 22268 -1 22269 -1 22270 -1 22271 -1 22272 -1 22273 -1 22274 -1 22275 -1 22276 -1 22277 -1 22278 -1 22279 -1 22280 -1 22281 -1 22282 -1 22283 -1 22284 -1 22285 -1 22286 -1 22287 -1 22288 -1 22289 -1 22290 -1 22291 -1 22292 -1 22293 -1 22294 -1 22295 -1 22296 -1 22297 -1 22298 -1 22299 -1 22300 -1 22301 -1 22302 -1 22303 -1 22304 -1 22305 -1 22306 -1 22307 -1 22308 -1 22309 -1 22310 -1 22311 -1 22312 -1 22313 -1 22314 -1 22315 -1 22316 -1 22317 -1 22318 -1 22319 -1 22320 -1 22321 -1 22322 -1 22323 -1 22324 -1 22325 -1 22326 -1 22327 -1 22328 -1 22329 -1 22330 -1 22331 -1 22332 -1 22333 -1 22334 -1 22335 -1 22336 -1 22337 -1 22338 -1 22339 -1 22340 -1 22341 -1 22342 -1 22343 -1 22344 -1 22345 -1 22346 -1 22347 -1 22348 -1 22349 -1 22350 -1 22351 -1 22352 -1 22353 -1 22354 -1 22355 -1 22356 -1 22357 -1 22358 -1 22359 -1 22360 -1 22361 -1 22362 -1 22363 -1 22364 -1 22365 -1 22366 -1 22367 -1 22368 -1 22369 -1 22370 -1 22371 -1 22372 -1 22373 -1 22374 -1 22375 -1 22376 -1 22377 -1 22378 -1 22379 -1 22380 -1 22381 -1 22382 -1 22383 -1 22384 -1 22385 -1 22386 -1 22387 -1 22388 -1 22389 -1 22390 -1 22391 -1 22392 -1 22393 -1 22394 -1 22395 -1 22396 -1 22397 -1 22398 -1 22399 -1 22400 -1 22401 -1 22402 -1 22403 -1 22404 -1 22405 -1 22406 -1 22407 -1 22408 -1 22409 -1 22410 -1 22411 -1 22412 -1 22413 -1 22414 -1 22415 -1 22416 -1 22417 -1 22418 -1 22419 -1 22420 -1 22421 -1 22422 -1 22423 -1 22424 -1 22425 -1 22426 -1 22427 -1 22428 -1 22429 -1 22430 -1 22431 -1 22432 -1 22433 -1 22434 -1 22435 -1 22436 -1 22437 -1 22438 -1 22439 -1 22440 -1 22441 -1 22442 -1 22443 -1 22444 -1 22445 -1 22446 -1 22447 -1 22448 -1 22449 -1 22450 -1 22451 -1 22452 -1 22453 -1 22454 -1 22455 -1 22456 -1 22457 -1 22458 -1 22459 -1 22460 -1 22461 -1 22462 -1 22463 -1 22464 -1 22465 -1 22466 -1 22467 -1 22468 -1 22469 -1 22470 -1 22471 -1 22472 -1 22473 -1 22474 -1 22475 -1 22476 -1 22477 -1 22478 -1 22479 -1 22480 -1 22481 -1 22482 -1 22483 -1 22484 -1 22485 -1 22486 -1 22487 -1 22488 -1 22489 -1 22490 -1 22491 -1 22492 -1 22493 -1 22494 -1 22495 -1 22496 -1 22497 -1 22498 -1 22499 -1 22500 -1 22501 -1 22502 -1 22503 -1 22504 -1 22505 -1 22506 -1 22507 -1 22508 -1 22509 -1 22510 -1 22511 -1 22512 -1 22513 -1 22514 -1 22515 -1 22516 -1 22517 -1 22518 -1 22519 -1 22520 -1 22521 -1 22522 -1 22523 -1 22524 -1 22525 -1 22526 -1 22527 -1 22528 -1 22529 -1 22530 -1 22531 -1 22532 -1 22533 -1 22534 -1 22535 -1 22536 -1 22537 -1 22538 -1 22539 -1 22540 -1 22541 -1 22542 -1 22543 -1 22544 -1 22545 -1 22546 -1 22547 -1 22548 -1 22549 -1 22550 -1 22551 -1 22552 -1 22553 -1 22554 -1 22555 -1 22556 -1 22557 -1 22558 -1 22559 -1 22560 -1 22561 -1 22562 -1 22563 -1 22564 -1 22565 -1 22566 -1 22567 -1 22568 -1 22569 -1 22570 -1 22571 -1 22572 -1 22573 -1 22574 -1 22575 -1 22576 -1 22577 -1 22578 -1 22579 -1 22580 -1 22581 -1 22582 -1 22583 -1 22584 -1 22585 -1 22586 -1 22587 -1 22588 -1 22589 -1 22590 -1 22591 -1 22592 -1 22593 -1 22594 -1 22595 -1 22596 -1 22597 -1 22598 -1 22599 -1 22600 -1 22601 -1 22602 -1 22603 -1 22604 -1 22605 -1 22606 -1 22607 -1 22608 -1 22609 -1 22610 -1 22611 -1 22612 -1 22613 -1 22614 -1 22615 -1 22616 -1 22617 -1 22618 -1 22619 -1 22620 -1 22621 -1 22622 -1 22623 -1 22624 -1 22625 -1 22626 -1 22627 -1 22628 -1 22629 -1 22630 -1 22631 -1 22632 -1 22633 -1 22634 -1 22635 -1 22636 -1 22637 -1 22638 -1 22639 -1 22640 -1 22641 -1 22642 -1 22643 -1 22644 -1 22645 -1 22646 -1 22647 -1 22648 -1 22649 -1 22650 -1 22651 -1 22652 -1 22653 -1 22654 -1 22655 -1 22656 -1 22657 -1 22658 -1 22659 -1 22660 -1 22661 -1 22662 -1 22663 -1 22664 -1 22665 -1 22666 -1 22667 -1 22668 -1 22669 -1 22670 -1 22671 -1 22672 -1 22673 -1 22674 -1 22675 -1 22676 -1 22677 -1 22678 -1 22679 -1 22680 -1 22681 -1 22682 -1 22683 -1 22684 -1 22685 -1 22686 -1 22687 -1 22688 -1 22689 -1 22690 -1 22691 -1 22692 -1 22693 -1 22694 -1 22695 -1 22696 -1 22697 -1 22698 -1 22699 -1 22700 -1 22701 -1 22702 -1 22703 -1 22704 -1 22705 -1 22706 -1 22707 -1 22708 -1 22709 -1 22710 -1 22711 -1 22712 -1 22713 -1 22714 -1 22715 -1 22716 -1 22717 -1 22718 -1 22719 -1 22720 -1 22721 -1 22722 -1 22723 -1 22724 -1 22725 -1 22726 -1 22727 -1 22728 -1 22729 -1 22730 -1 22731 -1 22732 -1 22733 -1 22734 -1 22735 -1 22736 -1 22737 -1 22738 -1 22739 -1 22740 -1 22741 -1 22742 -1 22743 -1 22744 -1 22745 -1 22746 -1 22747 -1 22748 -1 22749 -1 22750 -1 22751 -1 22752 -1 22753 -1 22754 -1 22755 -1 22756 -1 22757 -1 22758 -1 22759 -1 22760 -1 22761 -1 22762 -1 22763 -1 22764 -1 22765 -1 22766 -1 22767 -1 22768 -1 22769 -1 22770 -1 22771 -1 22772 -1 22773 -1 22774 -1 22775 -1 22776 -1 22777 -1 22778 -1 22779 -1 22780 -1 22781 -1 22782 -1 22783 -1 22784 -1 22785 -1 22786 -1 22787 -1 22788 -1 22789 -1 22790 -1 22791 -1 22792 -1 22793 -1 22794 -1 22795 -1 22796 -1 22797 -1 22798 -1 22799 -1 22800 -1 22801 -1 22802 -1 22803 -1 22804 -1 22805 -1 22806 -1 22807 -1 22808 -1 22809 -1 22810 -1 22811 -1 22812 -1 22813 -1 22814 -1 22815 -1 22816 -1 22817 -1 22818 -1 22819 -1 22820 -1 22821 -1 22822 -1 22823 -1 22824 -1 22825 -1 22826 -1 22827 -1 22828 -1 22829 -1 22830 -1 22831 -1 22832 -1 22833 -1 22834 -1 22835 -1 22836 -1 22837 -1 22838 -1 22839 -1 22840 -1 22841 -1 22842 -1 22843 -1 22844 -1 22845 -1 22846 -1 22847 -1 22848 -1 22849 -1 22850 -1 22851 -1 22852 -1 22853 -1 22854 -1 22855 -1 22856 -1 22857 -1 22858 -1 22859 -1 22860 -1 22861 -1 22862 -1 22863 -1 22864 -1 22865 -1 22866 -1 22867 -1 22868 -1 22869 -1 22870 -1 22871 -1 22872 -1 22873 -1 22874 -1 22875 -1 22876 -1 22877 -1 22878 -1 22879 -1 22880 -1 22881 -1 22882 -1 22883 -1 22884 -1 22885 -1 22886 -1 22887 -1 22888 -1 22889 -1 22890 -1 22891 -1 22892 -1 22893 -1 22894 -1 22895 -1 22896 -1 22897 -1 22898 -1 22899 -1 22900 -1 22901 -1 22902 -1 22903 -1 22904 -1 22905 -1 22906 -1 22907 -1 22908 -1 22909 -1 22910 -1 22911 -1 22912 -1 22913 -1 22914 -1 22915 -1 22916 -1 22917 -1 22918 -1 22919 -1 22920 -1 22921 -1 22922 -1 22923 -1 22924 -1 22925 -1 22926 -1 22927 -1 22928 -1 22929 -1 22930 -1 22931 -1 22932 -1 22933 -1 22934 -1 22935 -1 22936 -1 22937 -1 22938 -1 22939 -1 22940 -1 22941 -1 22942 -1 22943 -1 22944 -1 22945 -1 22946 -1 22947 -1 22948 -1 22949 -1 22950 -1 22951 -1 22952 -1 22953 -1 22954 -1 22955 -1 22956 -1 22957 -1 22958 -1 22959 -1 22960 -1 22961 -1 22962 -1 22963 -1 22964 -1 22965 -1 22966 -1 22967 -1 22968 -1 22969 -1 22970 -1 22971 -1 22972 -1 22973 -1 22974 -1 22975 -1 22976 -1 22977 -1 22978 -1 22979 -1 22980 -1 22981 -1 22982 -1 22983 -1 22984 -1 22985 -1 22986 -1 22987 -1 22988 -1 22989 -1 22990 -1 22991 -1 22992 -1 22993 -1 22994 -1 22995 -1 22996 -1 22997 -1 22998 -1 22999 -1 23000 -1 23001 -1 23002 -1 23003 -1 23004 -1 23005 -1 23006 -1 23007 -1 23008 -1 23009 -1 23010 -1 23011 -1 23012 -1 23013 -1 23014 -1 23015 -1 23016 -1 23017 -1 23018 -1 23019 -1 23020 -1 23021 -1 23022 -1 23023 -1 23024 -1 23025 -1 23026 -1 23027 -1 23028 -1 23029 -1 23030 -1 23031 -1 23032 -1 23033 -1 23034 -1 23035 -1 23036 -1 23037 -1 23038 -1 23039 -1 23040 -1 23041 -1 23042 -1 23043 -1 23044 -1 23045 -1 23046 -1 23047 -1 23048 -1 23049 -1 23050 -1 23051 -1 23052 -1 23053 -1 23054 -1 23055 -1 23056 -1 23057 -1 23058 -1 23059 -1 23060 -1 23061 -1 23062 -1 23063 -1 23064 -1 23065 -1 23066 -1 23067 -1 23068 -1 23069 -1 23070 -1 23071 -1 23072 -1 23073 -1 23074 -1 23075 -1 23076 -1 23077 -1 23078 -1 23079 -1 23080 -1 23081 -1 23082 -1 23083 -1 23084 -1 23085 -1 23086 -1 23087 -1 23088 -1 23089 -1 23090 -1 23091 -1 23092 -1 23093 -1 23094 -1 23095 -1 23096 -1 23097 -1 23098 -1 23099 -1 23100 -1 23101 -1 23102 -1 23103 -1 23104 -1 23105 -1 23106 -1 23107 -1 23108 -1 23109 -1 23110 -1 23111 -1 23112 -1 23113 -1 23114 -1 23115 -1 23116 -1 23117 -1 23118 -1 23119 -1 23120 -1 23121 -1 23122 -1 23123 -1 23124 -1 23125 -1 23126 -1 23127 -1 23128 -1 23129 -1 23130 -1 23131 -1 23132 -1 23133 -1 23134 -1 23135 -1 23136 -1 23137 -1 23138 -1 23139 -1 23140 -1 23141 -1 23142 -1 23143 -1 23144 -1 23145 -1 23146 -1 23147 -1 23148 -1 23149 -1 23150 -1 23151 -1 23152 -1 23153 -1 23154 -1 23155 -1 23156 -1 23157 -1 23158 -1 23159 -1 23160 -1 23161 -1 23162 -1 23163 -1 23164 -1 23165 -1 23166 -1 23167 -1 23168 -1 23169 -1 23170 -1 23171 -1 23172 -1 23173 -1 23174 -1 23175 -1 23176 -1 23177 -1 23178 -1 23179 -1 23180 -1 23181 -1 23182 -1 23183 -1 23184 -1 23185 -1 23186 -1 23187 -1 23188 -1 23189 -1 23190 -1 23191 -1 23192 -1 23193 -1 23194 -1 23195 -1 23196 -1 23197 -1 23198 -1 23199 -1 23200 -1 23201 -1 23202 -1 23203 -1 23204 -1 23205 -1 23206 -1 23207 -1 23208 -1 23209 -1 23210 -1 23211 -1 23212 -1 23213 -1 23214 -1 23215 -1 23216 -1 23217 -1 23218 -1 23219 -1 23220 -1 23221 -1 23222 -1 23223 -1 23224 -1 23225 -1 23226 -1 23227 -1 23228 -1 23229 -1 23230 -1 23231 -1 23232 -1 23233 -1 23234 -1 23235 -1 23236 -1 23237 -1 23238 -1 23239 -1 23240 -1 23241 -1 23242 -1 23243 -1 23244 -1 23245 -1 23246 -1 23247 -1 23248 -1 23249 -1 23250 -1 23251 -1 23252 -1 23253 -1 23254 -1 23255 -1 23256 -1 23257 -1 23258 -1 23259 -1 23260 -1 23261 -1 23262 -1 23263 -1 23264 -1 23265 -1 23266 -1 23267 -1 23268 -1 23269 -1 23270 -1 23271 -1 23272 -1 23273 -1 23274 -1 23275 -1 23276 -1 23277 -1 23278 -1 23279 -1 23280 -1 23281 -1 23282 -1 23283 -1 23284 -1 23285 -1 23286 -1 23287 -1 23288 -1 23289 -1 23290 -1 23291 -1 23292 -1 23293 -1 23294 -1 23295 -1 23296 -1 23297 -1 23298 -1 23299 -1 23300 -1 23301 -1 23302 -1 23303 -1 23304 -1 23305 -1 23306 -1 23307 -1 23308 -1 23309 -1 23310 -1 23311 -1 23312 -1 23313 -1 23314 -1 23315 -1 23316 -1 23317 -1 23318 -1 23319 -1 23320 -1 23321 -1 23322 -1 23323 -1 23324 -1 23325 -1 23326 -1 23327 -1 23328 -1 23329 -1 23330 -1 23331 -1 23332 -1 23333 -1 23334 -1 23335 -1 23336 -1 23337 -1 23338 -1 23339 -1 23340 -1 23341 -1 23342 -1 23343 -1 23344 -1 23345 -1 23346 -1 23347 -1 23348 -1 23349 -1 23350 -1 23351 -1 23352 -1 23353 -1 23354 -1 23355 -1 23356 -1 23357 -1 23358 -1 23359 -1 23360 -1 23361 -1 23362 -1 23363 -1 23364 -1 23365 -1 23366 -1 23367 -1 23368 -1 23369 -1 23370 -1 23371 -1 23372 -1 23373 -1 23374 -1 23375 -1 23376 -1 23377 -1 23378 -1 23379 -1 23380 -1 23381 -1 23382 -1 23383 -1 23384 -1 23385 -1 23386 -1 23387 -1 23388 -1 23389 -1 23390 -1 23391 -1 23392 -1 23393 -1 23394 -1 23395 -1 23396 -1 23397 -1 23398 -1 23399 -1 23400 -1 23401 -1 23402 -1 23403 -1 23404 -1 23405 -1 23406 -1 23407 -1 23408 -1 23409 -1 23410 -1 23411 -1 23412 -1 23413 -1 23414 -1 23415 -1 23416 -1 23417 -1 23418 -1 23419 -1 23420 -1 23421 -1 23422 -1 23423 -1 23424 -1 23425 -1 23426 -1 23427 -1 23428 -1 23429 -1 23430 -1 23431 -1 23432 -1 23433 -1 23434 -1 23435 -1 23436 -1 23437 -1 23438 -1 23439 -1 23440 -1 23441 -1 23442 -1 23443 -1 23444 -1 23445 -1 23446 -1 23447 -1 23448 -1 23449 -1 23450 -1 23451 -1 23452 -1 23453 -1 23454 -1 23455 -1 23456 -1 23457 -1 23458 -1 23459 -1 23460 -1 23461 -1 23462 -1 23463 -1 23464 -1 23465 -1 23466 -1 23467 -1 23468 -1 23469 -1 23470 -1 23471 -1 23472 -1 23473 -1 23474 -1 23475 -1 23476 -1 23477 -1 23478 -1 23479 -1 23480 -1 23481 -1 23482 -1 23483 -1 23484 -1 23485 -1 23486 -1 23487 -1 23488 -1 23489 -1 23490 -1 23491 -1 23492 -1 23493 -1 23494 -1 23495 -1 23496 -1 23497 -1 23498 -1 23499 -1 23500 -1 23501 -1 23502 -1 23503 -1 23504 -1 23505 -1 23506 -1 23507 -1 23508 -1 23509 -1 23510 -1 23511 -1 23512 -1 23513 -1 23514 -1 23515 -1 23516 -1 23517 -1 23518 -1 23519 -1 23520 -1 23521 -1 23522 -1 23523 -1 23524 -1 23525 -1 23526 -1 23527 -1 23528 -1 23529 -1 23530 -1 23531 -1 23532 -1 23533 -1 23534 -1 23535 -1 23536 -1 23537 -1 23538 -1 23539 -1 23540 -1 23541 -1 23542 -1 23543 -1 23544 -1 23545 -1 23546 -1 23547 -1 23548 -1 23549 -1 23550 -1 23551 -1 23552 -1 23553 -1 23554 -1 23555 -1 23556 -1 23557 -1 23558 -1 23559 -1 23560 -1 23561 -1 23562 -1 23563 -1 23564 -1 23565 -1 23566 -1 23567 -1 23568 -1 23569 -1 23570 -1 23571 -1 23572 -1 23573 -1 23574 -1 23575 -1 23576 -1 23577 -1 23578 -1 23579 -1 23580 -1 23581 -1 23582 -1 23583 -1 23584 -1 23585 -1 23586 -1 23587 -1 23588 -1 23589 -1 23590 -1 23591 -1 23592 -1 23593 -1 23594 -1 23595 -1 23596 -1 23597 -1 23598 -1 23599 -1 23600 -1 23601 -1 23602 -1 23603 -1 23604 -1 23605 -1 23606 -1 23607 -1 23608 -1 23609 -1 23610 -1 23611 -1 23612 -1 23613 -1 23614 -1 23615 -1 23616 -1 23617 -1 23618 -1 23619 -1 23620 -1 23621 -1 23622 -1 23623 -1 23624 -1 23625 -1 23626 -1 23627 -1 23628 -1 23629 -1 23630 -1 23631 -1 23632 -1 23633 -1 23634 -1 23635 -1 23636 -1 23637 -1 23638 -1 23639 -1 23640 -1 23641 -1 23642 -1 23643 -1 23644 -1 23645 -1 23646 -1 23647 -1 23648 -1 23649 -1 23650 -1 23651 -1 23652 -1 23653 -1 23654 -1 23655 -1 23656 -1 23657 -1 23658 -1 23659 -1 23660 -1 23661 -1 23662 -1 23663 -1 23664 -1 23665 -1 23666 -1 23667 -1 23668 -1 23669 -1 23670 -1 23671 -1 23672 -1 23673 -1 23674 -1 23675 -1 23676 -1 23677 -1 23678 -1 23679 -1 23680 -1 23681 -1 23682 -1 23683 -1 23684 -1 23685 -1 23686 -1 23687 -1 23688 -1 23689 -1 23690 -1 23691 -1 23692 -1 23693 -1 23694 -1 23695 -1 23696 -1 23697 -1 23698 -1 23699 -1 23700 -1 23701 -1 23702 -1 23703 -1 23704 -1 23705 -1 23706 -1 23707 -1 23708 -1 23709 -1 23710 -1 23711 -1 23712 -1 23713 -1 23714 -1 23715 -1 23716 -1 23717 -1 23718 -1 23719 -1 23720 -1 23721 -1 23722 -1 23723 -1 23724 -1 23725 -1 23726 -1 23727 -1 23728 -1 23729 -1 23730 -1 23731 -1 23732 -1 23733 -1 23734 -1 23735 -1 23736 -1 23737 -1 23738 -1 23739 -1 23740 -1 23741 -1 23742 -1 23743 -1 23744 -1 23745 -1 23746 -1 23747 -1 23748 -1 23749 -1 23750 -1 23751 -1 23752 -1 23753 -1 23754 -1 23755 -1 23756 -1 23757 -1 23758 -1 23759 -1 23760 -1 23761 -1 23762 -1 23763 -1 23764 -1 23765 -1 23766 -1 23767 -1 23768 -1 23769 -1 23770 -1 23771 -1 23772 -1 23773 -1 23774 -1 23775 -1 23776 -1 23777 -1 23778 -1 23779 -1 23780 -1 23781 -1 23782 -1 23783 -1 23784 -1 23785 -1 23786 -1 23787 -1 23788 -1 23789 -1 23790 -1 23791 -1 23792 -1 23793 -1 23794 -1 23795 -1 23796 -1 23797 -1 23798 -1 23799 -1 23800 -1 23801 -1 23802 -1 23803 -1 23804 -1 23805 -1 23806 -1 23807 -1 23808 -1 23809 -1 23810 -1 23811 -1 23812 -1 23813 -1 23814 -1 23815 -1 23816 -1 23817 -1 23818 -1 23819 -1 23820 -1 23821 -1 23822 -1 23823 -1 23824 -1 23825 -1 23826 -1 23827 -1 23828 -1 23829 -1 23830 -1 23831 -1 23832 -1 23833 -1 23834 -1 23835 -1 23836 -1 23837 -1 23838 -1 23839 -1 23840 -1 23841 -1 23842 -1 23843 -1 23844 -1 23845 -1 23846 -1 23847 -1 23848 -1 23849 -1 23850 -1 23851 -1 23852 -1 23853 -1 23854 -1 23855 -1 23856 -1 23857 -1 23858 -1 23859 -1 23860 -1 23861 -1 23862 -1 23863 -1 23864 -1 23865 -1 23866 -1 23867 -1 23868 -1 23869 -1 23870 -1 23871 -1 23872 -1 23873 -1 23874 -1 23875 -1 23876 -1 23877 -1 23878 -1 23879 -1 23880 -1 23881 -1 23882 -1 23883 -1 23884 -1 23885 -1 23886 -1 23887 -1 23888 -1 23889 -1 23890 -1 23891 -1 23892 -1 23893 -1 23894 -1 23895 -1 23896 -1 23897 -1 23898 -1 23899 -1 23900 -1 23901 -1 23902 -1 23903 -1 23904 -1 23905 -1 23906 -1 23907 -1 23908 -1 23909 -1 23910 -1 23911 -1 23912 -1 23913 -1 23914 -1 23915 -1 23916 -1 23917 -1 23918 -1 23919 -1 23920 -1 23921 -1 23922 -1 23923 -1 23924 -1 23925 -1 23926 -1 23927 -1 23928 -1 23929 -1 23930 -1 23931 -1 23932 -1 23933 -1 23934 -1 23935 -1 23936 -1 23937 -1 23938 -1 23939 -1 23940 -1 23941 -1 23942 -1 23943 -1 23944 -1 23945 -1 23946 -1 23947 -1 23948 -1 23949 -1 23950 -1 23951 -1 23952 -1 23953 -1 23954 -1 23955 -1 23956 -1 23957 -1 23958 -1 23959 -1 23960 -1 23961 -1 23962 -1 23963 -1 23964 -1 23965 -1 23966 -1 23967 -1 23968 -1 23969 -1 23970 -1 23971 -1 23972 -1 23973 -1 23974 -1 23975 -1 23976 -1 23977 -1 23978 -1 23979 -1 23980 -1 23981 -1 23982 -1 23983 -1 23984 -1 23985 -1 23986 -1 23987 -1 23988 -1 23989 -1 23990 -1 23991 -1 23992 -1 23993 -1 23994 -1 23995 -1 23996 -1 23997 -1 23998 -1 23999 -1 24000 -1 24001 -1 24002 -1 24003 -1 24004 -1 24005 -1 24006 -1 24007 -1 24008 -1 24009 -1 24010 -1 24011 -1 24012 -1 24013 -1 24014 -1 24015 -1 24016 -1 24017 -1 24018 -1 24019 -1 24020 -1 24021 -1 24022 -1 24023 -1 24024 -1 24025 -1 24026 -1 24027 -1 24028 -1 24029 -1 24030 -1 24031 -1 24032 -1 24033 -1 24034 -1 24035 -1 24036 -1 24037 -1 24038 -1 24039 -1 24040 -1 24041 -1 24042 -1 24043 -1 24044 -1 24045 -1 24046 -1 24047 -1 24048 -1 24049 -1 24050 -1 24051 -1 24052 -1 24053 -1 24054 -1 24055 -1 24056 -1 24057 -1 24058 -1 24059 -1 24060 -1 24061 -1 24062 -1 24063 -1 24064 -1 24065 -1 24066 -1 24067 -1 24068 -1 24069 -1 24070 -1 24071 -1 24072 -1 24073 -1 24074 -1 24075 -1 24076 -1 24077 -1 24078 -1 24079 -1 24080 -1 24081 -1 24082 -1 24083 -1 24084 -1 24085 -1 24086 -1 24087 -1 24088 -1 24089 -1 24090 -1 24091 -1 24092 -1 24093 -1 24094 -1 24095 -1 24096 -1 24097 -1 24098 -1 24099 -1 24100 -1 24101 -1 24102 -1 24103 -1 24104 -1 24105 -1 24106 -1 24107 -1 24108 -1 24109 -1 24110 -1 24111 -1 24112 -1 24113 -1 24114 -1 24115 -1 24116 -1 24117 -1 24118 -1 24119 -1 24120 -1 24121 -1 24122 -1 24123 -1 24124 -1 24125 -1 24126 -1 24127 -1 24128 -1 24129 -1 24130 -1 24131 -1 24132 -1 24133 -1 24134 -1 24135 -1 24136 -1 24137 -1 24138 -1 24139 -1 24140 -1 24141 -1 24142 -1 24143 -1 24144 -1 24145 -1 24146 -1 24147 -1 24148 -1 24149 -1 24150 -1 24151 -1 24152 -1 24153 -1 24154 -1 24155 -1 24156 -1 24157 -1 24158 -1 24159 -1 24160 -1 24161 -1 24162 -1 24163 -1 24164 -1 24165 -1 24166 -1 24167 -1 24168 -1 24169 -1 24170 -1 24171 -1 24172 -1 24173 -1 24174 -1 24175 -1 24176 -1 24177 -1 24178 -1 24179 -1 24180 -1 24181 -1 24182 -1 24183 -1 24184 -1 24185 -1 24186 -1 24187 -1 24188 -1 24189 -1 24190 -1 24191 -1 24192 -1 24193 -1 24194 -1 24195 -1 24196 -1 24197 -1 24198 -1 24199 -1 24200 -1 24201 -1 24202 -1 24203 -1 24204 -1 24205 -1 24206 -1 24207 -1 24208 -1 24209 -1 24210 -1 24211 -1 24212 -1 24213 -1 24214 -1 24215 -1 24216 -1 24217 -1 24218 -1 24219 -1 24220 -1 24221 -1 24222 -1 24223 -1 24224 -1 24225 -1 24226 -1 24227 -1 24228 -1 24229 -1 24230 -1 24231 -1 24232 -1 24233 -1 24234 -1 24235 -1 24236 -1 24237 -1 24238 -1 24239 -1 24240 -1 24241 -1 24242 -1 24243 -1 24244 -1 24245 -1 24246 -1 24247 -1 24248 -1 24249 -1 24250 -1 24251 -1 24252 -1 24253 -1 24254 -1 24255 -1 24256 -1 24257 -1 24258 -1 24259 -1 24260 -1 24261 -1 24262 -1 24263 -1 24264 -1 24265 -1 24266 -1 24267 -1 24268 -1 24269 -1 24270 -1 24271 -1 24272 -1 24273 -1 24274 -1 24275 -1 24276 -1 24277 -1 24278 -1 24279 -1 24280 -1 24281 -1 24282 -1 24283 -1 24284 -1 24285 -1 24286 -1 24287 -1 24288 -1 24289 -1 24290 -1 24291 -1 24292 -1 24293 -1 24294 -1 24295 -1 24296 -1 24297 -1 24298 -1 24299 -1 24300 -1 24301 -1 24302 -1 24303 -1 24304 -1 24305 -1 24306 -1 24307 -1 24308 -1 24309 -1 24310 -1 24311 -1 24312 -1 24313 -1 24314 -1 24315 -1 24316 -1 24317 -1 24318 -1 24319 -1 24320 -1 24321 -1 24322 -1 24323 -1 24324 -1 24325 -1 24326 -1 24327 -1 24328 -1 24329 -1 24330 -1 24331 -1 24332 -1 24333 -1 24334 -1 24335 -1 24336 -1 24337 -1 24338 -1 24339 -1 24340 -1 24341 -1 24342 -1 24343 -1 24344 -1 24345 -1 24346 -1 24347 -1 24348 -1 24349 -1 24350 -1 24351 -1 24352 -1 24353 -1 24354 -1 24355 -1 24356 -1 24357 -1 24358 -1 24359 -1 24360 -1 24361 -1 24362 -1 24363 -1 24364 -1 24365 -1 24366 -1 24367 -1 24368 -1 24369 -1 24370 -1 24371 -1 24372 -1 24373 -1 24374 -1 24375 -1 24376 -1 24377 -1 24378 -1 24379 -1 24380 -1 24381 -1 24382 -1 24383 -1 24384 -1 24385 -1 24386 -1 24387 -1 24388 -1 24389 -1 24390 -1 24391 -1 24392 -1 24393 -1 24394 -1 24395 -1 24396 -1 24397 -1 24398 -1 24399 -1 24400 -1 24401 -1 24402 -1 24403 -1 24404 -1 24405 -1 24406 -1 24407 -1 24408 -1 24409 -1 24410 -1 24411 -1 24412 -1 24413 -1 24414 -1 24415 -1 24416 -1 24417 -1 24418 -1 24419 -1 24420 -1 24421 -1 24422 -1 24423 -1 24424 -1 24425 -1 24426 -1 24427 -1 24428 -1 24429 -1 24430 -1 24431 -1 24432 -1 24433 -1 24434 -1 24435 -1 24436 -1 24437 -1 24438 -1 24439 -1 24440 -1 24441 -1 24442 -1 24443 -1 24444 -1 24445 -1 24446 -1 24447 -1 24448 -1 24449 -1 24450 -1 24451 -1 24452 -1 24453 -1 24454 -1 24455 -1 24456 -1 24457 -1 24458 -1 24459 -1 24460 -1 24461 -1 24462 -1 24463 -1 24464 -1 24465 -1 24466 -1 24467 -1 24468 -1 24469 -1 24470 -1 24471 -1 24472 -1 24473 -1 24474 -1 24475 -1 24476 -1 24477 -1 24478 -1 24479 -1 24480 -1 24481 -1 24482 -1 24483 -1 24484 -1 24485 -1 24486 -1 24487 -1 24488 -1 24489 -1 24490 -1 24491 -1 24492 -1 24493 -1 24494 -1 24495 -1 24496 -1 24497 -1 24498 -1 24499 -1 24500 -1 24501 -1 24502 -1 24503 -1 24504 -1 24505 -1 24506 -1 24507 -1 24508 -1 24509 -1 24510 -1 24511 -1 24512 -1 24513 -1 24514 -1 24515 -1 24516 -1 24517 -1 24518 -1 24519 -1 24520 -1 24521 -1 24522 -1 24523 -1 24524 -1 24525 -1 24526 -1 24527 -1 24528 -1 24529 -1 24530 -1 24531 -1 24532 -1 24533 -1 24534 -1 24535 -1 24536 -1 24537 -1 24538 -1 24539 -1 24540 -1 24541 -1 24542 -1 24543 -1 24544 -1 24545 -1 24546 -1 24547 -1 24548 -1 24549 -1 24550 -1 24551 -1 24552 -1 24553 -1 24554 -1 24555 -1 24556 -1 24557 -1 24558 -1 24559 -1 24560 -1 24561 -1 24562 -1 24563 -1 24564 -1 24565 -1 24566 -1 24567 -1 24568 -1 24569 -1 24570 -1 24571 -1 24572 -1 24573 -1 24574 -1 24575 -1 24576 -1 24577 -1 24578 -1 24579 -1 24580 -1 24581 -1 24582 -1 24583 -1 24584 -1 24585 -1 24586 -1 24587 -1 24588 -1 24589 -1 24590 -1 24591 -1 24592 -1 24593 -1 24594 -1 24595 -1 24596 -1 24597 -1 24598 -1 24599 -1 24600 -1 24601 -1 24602 -1 24603 -1 24604 -1 24605 -1 24606 -1 24607 -1 24608 -1 24609 -1 24610 -1 24611 -1 24612 -1 24613 -1 24614 -1 24615 -1 24616 -1 24617 -1 24618 -1 24619 -1 24620 -1 24621 -1 24622 -1 24623 -1 24624 -1 24625 -1 24626 -1 24627 -1 24628 -1 24629 -1 24630 -1 24631 -1 24632 -1 24633 -1 24634 -1 24635 -1 24636 -1 24637 -1 24638 -1 24639 -1 24640 -1 24641 -1 24642 -1 24643 -1 24644 -1 24645 -1 24646 -1 24647 -1 24648 -1 24649 -1 24650 -1 24651 -1 24652 -1 24653 -1 24654 -1 24655 -1 24656 -1 24657 -1 24658 -1 24659 -1 24660 -1 24661 -1 24662 -1 24663 -1 24664 -1 24665 -1 24666 -1 24667 -1 24668 -1 24669 -1 24670 -1 24671 -1 24672 -1 24673 -1 24674 -1 24675 -1 24676 -1 24677 -1 24678 -1 24679 -1 24680 -1 24681 -1 24682 -1 24683 -1 24684 -1 24685 -1 24686 -1 24687 -1 24688 -1 24689 -1 24690 -1 24691 -1 24692 -1 24693 -1 24694 -1 24695 -1 24696 -1 24697 -1 24698 -1 24699 -1 24700 -1 24701 -1 24702 -1 24703 -1 24704 -1 24705 -1 24706 -1 24707 -1 24708 -1 24709 -1 24710 -1 24711 -1 24712 -1 24713 -1 24714 -1 24715 -1 24716 -1 24717 -1 24718 -1 24719 -1 24720 -1 24721 -1 24722 -1 24723 -1 24724 -1 24725 -1 24726 -1 24727 -1 24728 -1 24729 -1 24730 -1 24731 -1 24732 -1 24733 -1 24734 -1 24735 -1 24736 -1 24737 -1 24738 -1 24739 -1 24740 -1 24741 -1 24742 -1 24743 -1 24744 -1 24745 -1 24746 -1 24747 -1 24748 -1 24749 -1 24750 -1 24751 -1 24752 -1 24753 -1 24754 -1 24755 -1 24756 -1 24757 -1 24758 -1 24759 -1 24760 -1 24761 -1 24762 -1 24763 -1 24764 -1 24765 -1 24766 -1 24767 -1 24768 -1 24769 -1 24770 -1 24771 -1 24772 -1 24773 -1 24774 -1 24775 -1 24776 -1 24777 -1 24778 -1 24779 -1 24780 -1 24781 -1 24782 -1 24783 -1 24784 -1 24785 -1 24786 -1 24787 -1 24788 -1 24789 -1 24790 -1 24791 -1 24792 -1 24793 -1 24794 -1 24795 -1 24796 -1 24797 -1 24798 -1 24799 -1 24800 -1 24801 -1 24802 -1 24803 -1 24804 -1 24805 -1 24806 -1 24807 -1 24808 -1 24809 -1 24810 -1 24811 -1 24812 -1 24813 -1 24814 -1 24815 -1 24816 -1 24817 -1 24818 -1 24819 -1 24820 -1 24821 -1 24822 -1 24823 -1 24824 -1 24825 -1 24826 -1 24827 -1 24828 -1 24829 -1 24830 -1 24831 -1 24832 -1 24833 -1 24834 -1 24835 -1 24836 -1 24837 -1 24838 -1 24839 -1 24840 -1 24841 -1 24842 -1 24843 -1 24844 -1 24845 -1 24846 -1 24847 -1 24848 -1 24849 -1 24850 -1 24851 -1 24852 -1 24853 -1 24854 -1 24855 -1 24856 -1 24857 -1 24858 -1 24859 -1 24860 -1 24861 -1 24862 -1 24863 -1 24864 -1 24865 -1 24866 -1 24867 -1 24868 -1 24869 -1 24870 -1 24871 -1 24872 -1 24873 -1 24874 -1 24875 -1 24876 -1 24877 -1 24878 -1 24879 -1 24880 -1 24881 -1 24882 -1 24883 -1 24884 -1 24885 -1 24886 -1 24887 -1 24888 -1 24889 -1 24890 -1 24891 -1 24892 -1 24893 -1 24894 -1 24895 -1 24896 -1 24897 -1 24898 -1 24899 -1 24900 -1 24901 -1 24902 -1 24903 -1 24904 -1 24905 -1 24906 -1 24907 -1 24908 -1 24909 -1 24910 -1 24911 -1 24912 -1 24913 -1 24914 -1 24915 -1 24916 -1 24917 -1 24918 -1 24919 -1 24920 -1 24921 -1 24922 -1 24923 -1 24924 -1 24925 -1 24926 -1 24927 -1 24928 -1 24929 -1 24930 -1 24931 -1 24932 -1 24933 -1 24934 -1 24935 -1 24936 -1 24937 -1 24938 -1 24939 -1 24940 -1 24941 -1 24942 -1 24943 -1 24944 -1 24945 -1 24946 -1 24947 -1 24948 -1 24949 -1 24950 -1 24951 -1 24952 -1 24953 -1 24954 -1 24955 -1 24956 -1 24957 -1 24958 -1 24959 -1 24960 -1 24961 -1 24962 -1 24963 -1 24964 -1 24965 -1 24966 -1 24967 -1 24968 -1 24969 -1 24970 -1 24971 -1 24972 -1 24973 -1 24974 -1 24975 -1 24976 -1 24977 -1 24978 -1 24979 -1 24980 -1 24981 -1 24982 -1 24983 -1 24984 -1 24985 -1 24986 -1 24987 -1 24988 diff --git a/thirdparty/libpointmatcher/examples/data/cloud.00001.vtk b/thirdparty/libpointmatcher/examples/data/cloud.00001.vtk deleted file mode 100644 index 8f00ca3..0000000 --- a/thirdparty/libpointmatcher/examples/data/cloud.00001.vtk +++ /dev/null @@ -1,50392 +0,0 @@ -# vtk DataFile Version 3.0 -data -ASCII -DATASET POLYDATA -POINTS 25193 float -2.7728 -0.334396 -0.70489 -2.84273 -0.343062 -0.693509 -2.91324 -0.352456 -0.679865 -3.00824 -0.366814 -0.681159 -3.0881 -0.376702 -0.668865 -3.16853 -0.387273 -0.654113 -3.24903 -0.396388 -0.63732 -3.34596 -0.41008 -0.628034 -3.45326 -0.424659 -0.620757 -3.56009 -0.439485 -0.610169 -3.67701 -0.455996 -0.60071 -3.79369 -0.471759 -0.587944 -3.9204 -0.489051 -0.575627 -4.04779 -0.505702 -0.559395 -4.20284 -0.527659 -0.550903 -4.35923 -0.54992 -0.537205 -4.52478 -0.572128 -0.522425 -4.69997 -0.59631 -0.50566 -4.88596 -0.621601 -0.486401 -5.08172 -0.647652 -0.464186 -5.30549 -0.679033 -0.444334 -5.53186 -0.708481 -0.417118 -5.76669 -0.739054 -0.385215 -6.05063 -0.778406 -0.357231 -6.33484 -0.815885 -0.319883 -6.65801 -0.858609 -0.281533 -7.01153 -0.905639 -0.23779 -7.43315 -0.962264 -0.194414 -7.86433 -1.01961 -0.138032 -8.42385 -1.09585 -0.0851959 -8.99376 -1.17095 -0.014469 -9.67072 -1.26147 0.0642192 -10.5849 -1.38816 0.145622 -11.6169 -1.52883 0.249857 -13.1324 -1.741 0.364008 -14.7462 -1.96111 0.527163 -16.7742 -2.23605 0.738494 -19.9281 -2.67161 1.0193 -24.0463 -3.16682 1.83563 -24.5628 -3.17482 2.27248 -24.933 -3.15853 2.7175 -24.6143 -3.04505 3.11691 -27.8275 -3.41165 3.87214 -24.9705 -2.95431 4.0055 -22.9996 -2.62863 4.16287 -20.6378 -2.26335 4.19089 -21.5664 -2.32057 4.71067 -19.9567 -2.06428 4.7776 -19.6342 -1.969 5.05934 -19.5113 -1.89789 5.37703 -19.3443 -1.82365 5.68229 -20.4407 -1.88677 6.31849 -21.0519 -1.89214 6.86099 -20.9471 -1.81837 7.21293 -20.3892 -1.70027 7.41976 -20.1512 -1.61519 7.7178 -18.1366 -1.36396 7.37273 -17.7883 -1.27572 7.58454 -17.2253 -1.17081 7.70136 -16.8642 -1.08627 7.88509 -17.6805 -1.09824 8.57501 -20.8348 -1.28665 10.3774 -19.9217 -1.14938 10.3636 -18.7203 -0.997193 10.1733 -18.9548 -0.948371 10.689 -20.3253 -0.970278 11.8413 -19.9244 -0.874429 12.0575 -19.8837 -0.799645 12.4758 -21.0429 -0.78718 13.6376 -19.4037 -0.627697 13.081 -19.4734 -0.556114 13.5854 -19.523 -0.481691 14.0897 -19.625 -0.407434 14.6457 -4.2364 0.174376 3.7916 -4.18047 0.191733 3.84899 -4.08541 0.210049 3.87437 -4.00667 0.228501 3.90977 -4.00216 0.244723 4.00794 -3.91409 0.26255 4.03426 -3.98078 0.279261 4.1996 -3.91939 0.296854 4.2516 -3.84251 0.315095 4.28821 -3.85757 0.333577 4.4156 -3.78495 0.350867 4.45778 -3.84881 0.371741 4.6449 -3.7271 0.389151 4.63406 -3.88077 0.415051 4.93754 -3.84551 0.43511 5.03266 -3.776 0.455501 5.08846 -3.65682 0.471776 5.08022 -3.81614 0.506085 5.43608 -3.52891 0.51158 5.20036 -3.43967 0.528583 5.22636 -3.45616 0.555737 5.4074 -3.41898 0.578868 5.51505 -3.23581 0.587619 5.39407 -3.15481 0.605813 5.43059 -3.05399 0.621462 5.43116 -2.85633 0.622437 5.25535 -2.99904 0.672617 5.69828 -3.07371 0.717737 6.04057 -3.04827 0.748226 6.20787 -2.97152 0.77095 6.27637 -2.92142 0.799971 6.40711 -2.63942 0.778453 6.00684 -2.37609 0.75371 5.60828 -2.37601 0.791746 5.84226 -2.30964 0.814592 5.9187 -2.20504 0.82538 5.89131 -2.12084 0.842369 5.9182 -1.93251 0.821256 5.61157 -1.89133 0.853206 5.76709 -1.86427 0.893474 5.98972 -2.01509 1.02457 6.93387 -1.90795 1.04139 6.9376 -1.55819 0.915117 5.83467 -1.45115 0.915433 5.7336 -1.35485 0.919672 5.66935 -1.3116 0.964846 5.90642 -1.23226 0.984497 5.95703 -1.24684 1.10915 6.73264 -0.982011 0.911826 5.27711 -0.900744 0.914653 5.21388 -0.828428 0.926186 5.21853 -0.759189 0.946839 5.28097 -0.693328 0.990815 5.49031 -0.625247 1.06253 5.86622 -0.540898 1.07998 5.89516 -0.455217 1.10252 5.95214 -0.376694 1.0733 5.70219 -0.297451 1.07544 5.63804 -0.207537 1.11232 5.77935 -0.0179227 1.3569 7.10709 -2.70032 -0.381513 -0.679193 -2.80066 -0.401751 -0.692331 -2.86351 -0.410311 -0.673689 -2.94218 -0.422678 -0.664624 -3.02892 -0.437711 -0.658775 -3.11645 -0.452388 -0.650277 -3.19633 -0.464642 -0.634157 -3.28448 -0.478479 -0.620867 -3.39095 -0.497215 -0.614357 -3.48903 -0.512297 -0.600252 -3.59603 -0.529885 -0.587589 -3.72028 -0.55185 -0.580464 -3.8462 -0.573411 -0.5694 -3.97304 -0.593378 -0.554619 -4.09101 -0.611571 -0.531751 -4.26311 -0.642898 -0.527786 -4.41007 -0.66668 -0.507355 -4.56598 -0.691425 -0.485937 -4.75935 -0.723979 -0.472608 -4.95396 -0.75653 -0.452711 -5.16735 -0.792613 -0.432468 -5.3812 -0.827374 -0.405294 -5.60667 -0.863017 -0.373559 -5.86894 -0.906169 -0.344172 -6.1616 -0.955346 -0.312599 -6.45378 -1.00142 -0.271689 -6.78609 -1.05587 -0.228262 -7.18515 -1.1219 -0.186291 -7.58589 -1.18653 -0.130431 -8.09299 -1.27062 -0.0767453 -8.63083 -1.35742 -0.00956887 -9.27588 -1.46412 0.064436 -9.9692 -1.57603 0.155855 -10.9868 -1.74735 0.247023 -12.1418 -1.93968 0.365612 -13.8258 -2.22562 0.502913 -15.5406 -2.5072 0.698168 -17.9714 -2.91145 0.949795 -20.4782 -3.31573 1.28706 -23.315 -3.76375 1.7217 -23.2512 -3.68883 2.11828 -23.2015 -3.61656 2.51372 -23.1637 -3.54627 2.90886 -23.1485 -3.48015 3.3058 -25.3619 -3.77946 3.96569 -23.0888 -3.34221 4.09714 -22.4177 -3.17187 4.39515 -22.455 -3.11559 4.79217 -22.7273 -3.09404 5.23683 -19.9205 -2.61019 5.05629 -19.528 -2.49608 5.31993 -20.0672 -2.51794 5.79819 -20.7383 -2.55537 6.33357 -21.8944 -2.65393 7.03238 -20.2964 -2.37483 6.95473 -21.665 -2.49587 7.76357 -20.2579 -2.25005 7.69285 -16.8929 -1.76526 6.87516 -18.1645 -1.86996 7.67215 -18.2958 -1.83 8.07245 -17.0864 -1.63313 7.92597 -22.271 -2.16486 10.5198 -21.0355 -1.95733 10.4036 -11.8595 -0.912701 6.45493 -18.4716 -1.55589 9.98948 -18.3043 -1.47644 10.2892 -19.3851 -1.51792 11.2643 -19.5871 -1.46968 11.7992 -20.6283 -1.49239 12.843 -19.3312 -1.30758 12.5182 -20.5198 -1.33277 13.7161 -19.3558 -1.16583 13.4339 -19.3857 -1.09357 13.9194 -4.20337 0.0377973 3.65604 -4.14344 0.0569906 3.70737 -4.17696 0.086336 3.92948 -3.98904 0.112855 3.87835 -3.94881 0.131184 3.94399 -3.95165 0.146915 4.04857 -3.96002 0.163867 4.16059 -3.93567 0.181415 4.2465 -3.88841 0.20032 4.31159 -3.95256 0.217006 4.48899 -3.86688 0.238027 4.51836 -3.86186 0.256862 4.63358 -3.80687 0.277445 4.69751 -3.94151 0.298231 4.97894 -3.89385 0.319442 5.05971 -3.79315 0.340778 5.07771 -3.70514 0.361761 5.10918 -3.75116 0.386512 5.31393 -3.81919 0.41366 5.56162 -3.55093 0.428377 5.34743 -3.57856 0.455473 5.54658 -3.40247 0.47121 5.44747 -3.2895 0.490573 5.43622 -3.19317 0.509577 5.44819 -2.78905 0.500709 4.93256 -2.76639 0.52401 5.04824 -2.76867 0.550049 5.21706 -2.95421 0.601942 5.74986 -2.91836 0.62924 5.87918 -2.9976 0.675019 6.26051 -2.96651 0.707971 6.42786 -2.654 0.690492 5.96499 -2.37709 0.672935 5.53922 -2.2992 0.692125 5.56907 -2.20681 0.707943 5.56026 -2.12271 0.724196 5.56852 -2.03477 0.740147 5.56566 -1.99317 0.769568 5.70342 -1.9235 0.792141 5.76447 -1.81266 0.79918 5.68112 -1.71137 0.808244 5.62404 -1.58453 0.803438 5.44926 -1.53255 0.833317 5.57176 -1.41929 0.829236 5.42177 -1.33621 0.840286 5.39602 -1.25545 0.852448 5.37842 -1.26621 0.940489 5.93742 -1.26919 1.04375 6.58585 -1.01427 0.880826 5.27767 -0.934409 0.886504 5.2248 -0.861538 0.900331 5.22972 -0.791476 0.920309 5.27272 -0.725989 0.956203 5.42327 -0.658762 1.0146 5.71066 -0.581528 1.06099 5.90792 -0.495945 1.07146 5.87636 -0.413575 1.07174 5.78434 -0.33637 1.06136 5.63188 -0.253367 1.08457 5.68511 -0.0404936 1.42017 7.53545 -2.74229 -0.452948 -0.679565 -2.81203 -0.466653 -0.667369 -2.89009 -0.48216 -0.658976 -2.97548 -0.499144 -0.654021 -3.05516 -0.514093 -0.641009 -3.1337 -0.528321 -0.62588 -3.22123 -0.545321 -0.613361 -3.31797 -0.564052 -0.60326 -3.41524 -0.583313 -0.590019 -3.52069 -0.603959 -0.578733 -3.636 -0.62724 -0.56838 -3.76137 -0.652138 -0.558865 -3.87809 -0.674267 -0.541265 -4.01296 -0.700745 -0.528012 -4.13919 -0.724455 -0.506675 -4.30185 -0.757281 -0.495881 -4.45678 -0.787398 -0.4762 -4.63969 -0.824435 -0.461507 -4.82314 -0.860368 -0.440855 -5.01615 -0.898057 -0.417245 -5.22888 -0.939428 -0.392875 -5.46103 -0.985211 -0.366577 -5.71277 -1.03426 -0.33767 -5.97481 -1.08457 -0.302571 -6.25606 -1.13871 -0.262915 -6.58573 -1.20284 -0.223767 -6.91554 -1.26471 -0.173506 -7.30415 -1.33977 -0.121642 -7.76936 -1.43138 -0.068145 -8.30319 -1.53543 -0.00785536 -8.87609 -1.64626 0.0664344 -9.52676 -1.77175 0.152911 -10.4405 -1.95266 0.240871 -11.4819 -2.15811 0.353039 -12.8636 -2.43202 0.486076 -14.5295 -2.76051 0.660006 -16.4575 -3.13613 0.88971 -19.4596 -3.72948 1.19619 -23.6321 -4.48656 2.0461 -24.055 -4.50882 2.47971 -24.1957 -4.47202 2.9064 -26.2151 -4.80643 3.51999 -45.1125 -8.43236 6.13415 -24.9931 -4.42768 4.27087 -25.1809 -4.39468 4.73554 -23.2556 -3.96433 4.85416 -23.0057 -3.85447 5.21696 -20.4154 -3.31953 5.09569 -19.737 -3.14215 5.30739 -19.2886 -3.00771 5.55147 -20.5165 -3.16495 6.21533 -21.871 -3.33726 6.96285 -20.2917 -3.0102 6.89549 -21.3761 -3.12949 7.61132 -19.0769 -2.69611 7.24183 -21.9712 -3.09772 8.62271 -17.5928 -2.35241 7.40908 -17.9506 -2.35462 7.88697 -18.7004 -2.41033 8.5448 -18.7781 -2.36407 8.94699 -18.4238 -2.25488 9.16143 -19.7612 -2.3817 10.1687 -17.9122 -2.06665 9.66033 -18.141 -2.03806 10.1527 -18.3928 -2.01023 10.674 -20.6097 -2.22573 12.315 -20.4741 -2.13715 12.6915 -19.3877 -1.93623 12.4936 -19.459 -1.8745 12.983 -4.29481 -0.124759 3.51866 -4.19953 -0.0699423 3.73498 -4.04274 -0.0396358 3.71399 -4.05347 -0.0260432 3.81769 -4.01435 -0.0066921 3.88452 -3.94394 0.0149647 3.92506 -3.92575 0.0318214 4.00994 -3.98695 0.0432021 4.16837 -3.86811 0.06904 4.16612 -3.93056 0.0820778 4.33404 -3.88984 0.101923 4.40639 -3.85352 0.122011 4.48518 -3.69246 0.147854 4.4325 -4.02549 0.15287 4.91554 -3.86686 0.179518 4.86964 -3.87971 0.199694 5.01776 -3.81299 0.223769 5.07437 -3.81889 0.245956 5.22388 -3.74186 0.269666 5.27148 -3.67022 0.293382 5.32554 -3.64949 0.317326 5.4517 -4.07261 0.349456 6.2289 -3.63666 0.369342 5.7632 -3.33566 0.387302 5.46977 -3.12416 0.405601 5.29508 -3.04114 0.427348 5.32099 -2.76039 0.436263 4.99802 -2.72109 0.458269 5.08757 -2.8386 0.495281 5.47743 -3.18604 0.558357 6.35393 -2.76928 0.548664 5.72294 -2.97032 0.607103 6.36663 -2.66848 0.602237 5.93172 -2.40619 0.597243 5.54348 -2.53448 0.655236 6.08287 -2.25553 0.640419 5.61213 -2.17332 0.661381 5.63016 -2.06595 0.674806 5.57164 -1.97557 0.692275 5.55798 -1.88606 0.708138 5.54269 -1.79492 0.724111 5.51585 -1.70266 0.738031 5.47777 -1.61249 0.751059 5.43789 -1.52542 0.763923 5.40599 -1.44191 0.77857 5.38186 -1.35506 0.789701 5.3368 -1.2757 0.803683 5.31951 -1.20188 0.821012 5.33003 -1.16217 0.86799 5.57498 -1.06584 0.867185 5.4357 -0.967891 0.858302 5.24538 -0.894189 0.871477 5.23096 -0.823305 0.89078 5.25452 -0.761467 0.933005 5.44503 -0.68737 0.957659 5.49561 -0.620289 1.03829 5.92077 -0.536066 1.04963 5.87986 -0.450645 1.08939 6.01511 -0.374876 1.04731 5.64564 -0.293948 1.06711 5.6596 -0.20664 1.10337 5.77062 -0.0165049 1.3562 7.11722 -2.6909 -0.503944 -0.672699 -2.76776 -0.521842 -0.667145 -2.83598 -0.537015 -0.653702 -2.92173 -0.557377 -0.649397 -3.00005 -0.574277 -0.637278 -3.07821 -0.590672 -0.622922 -3.15694 -0.60775 -0.606107 -3.25212 -0.629472 -0.597091 -3.34879 -0.651939 -0.584815 -3.44549 -0.672818 -0.569915 -3.5511 -0.696226 -0.556554 -3.67471 -0.725176 -0.548413 -3.79878 -0.754459 -0.536257 -3.91468 -0.779091 -0.516509 -4.04824 -0.809932 -0.500519 -4.19274 -0.842319 -0.483981 -4.35503 -0.879635 -0.469938 -4.51768 -0.916952 -0.450421 -4.69921 -0.958153 -0.432114 -4.88203 -0.999439 -0.407629 -5.08364 -1.04432 -0.383089 -5.30448 -1.0947 -0.357005 -5.52671 -1.14387 -0.323384 -5.7865 -1.20177 -0.292083 -6.0653 -1.26449 -0.256223 -6.36422 -1.33107 -0.214908 -6.69095 -1.40461 -0.16892 -7.05766 -1.4861 -0.118469 -7.47169 -1.5793 -0.0628744 -7.91552 -1.67674 0.00278521 -8.50401 -1.81146 0.0666724 -9.14027 -1.95486 0.145841 -9.79629 -2.09991 0.245668 -10.7722 -2.32292 0.346951 -11.9125 -2.58125 0.474313 -13.5378 -2.95566 0.62671 -15.2397 -3.3395 0.835252 -20.4373 -4.51155 1.47196 -23.5013 -5.18728 1.94669 -24.2837 -5.30832 2.39958 -27.0107 -5.8784 3.02649 -25.5936 -5.4102 3.81336 -23.9696 -4.97686 4.05315 -23.8036 -4.87461 4.4492 -23.8243 -4.81419 4.87158 -22.856 -4.53922 5.11612 -23.4105 -4.59566 5.63345 -19.8792 -3.78658 5.27871 -19.7293 -3.7008 5.5993 -20.098 -3.721 6.04907 -18.7526 -3.39251 6.04517 -18.8357 -3.35587 6.41241 -19.8972 -3.51076 7.09129 -17.7762 -3.04327 6.75986 -18.8288 -3.19203 7.46281 -21.1197 -3.56547 8.66872 -19.9615 -3.28964 8.62468 -18.2065 -2.91148 8.29473 -16.8939 -2.62251 8.08893 -17.915 -2.74921 8.88589 -19.952 -3.04277 10.209 -17.6924 -2.5988 9.50727 -17.8018 -2.55977 9.93267 -17.9281 -2.52182 10.3781 -17.8451 -2.44846 10.7188 -18.2019 -2.44311 11.318 -19.9443 -2.64368 12.778 -19.2896 -2.47606 12.824 -4.36281 -0.259666 3.55245 -4.18221 -0.219645 3.52451 -20.093 -2.372 14.7675 -4.10726 -0.181076 3.65638 -4.0481 -0.159182 3.70644 -4.05145 -0.145011 3.80412 -4.05182 -0.129952 3.9025 -3.95064 -0.102608 3.9185 -3.91821 -0.0828007 3.99045 -3.93644 -0.0691079 4.10867 -3.85541 -0.0446142 4.14006 -3.86867 -0.0294719 4.25933 -3.82191 -0.00872909 4.32373 -3.76716 0.0133855 4.38014 -3.77347 0.0305612 4.5009 -3.66127 0.0575892 4.49712 -3.81533 0.0654718 4.79021 -3.81764 0.084912 4.92219 -3.84084 0.104697 5.08586 -3.82913 0.127503 5.21223 -3.71036 0.155378 5.2047 -3.64642 0.180857 5.26634 -3.63392 0.20436 5.4002 -3.61747 0.228965 5.53465 -3.35346 0.25808 5.30375 -3.26433 0.282642 5.32579 -3.35132 0.308693 5.62633 -3.06317 0.331601 5.32144 -2.89659 0.353775 5.19886 -2.89852 0.379214 5.36944 -2.86261 0.404582 5.47925 -3.11473 0.448346 6.15884 -2.73397 0.455119 5.59958 -2.66894 0.481165 5.66266 -2.49692 0.495947 5.4878 -2.47635 0.525919 5.64828 -2.55358 0.569896 6.05906 -2.35945 0.57943 5.8122 -2.24759 0.597884 5.75734 -2.31574 0.651385 6.20826 -2.06493 0.641438 5.74397 -1.9305 0.650549 5.59684 -1.86993 0.677781 5.67601 -1.74839 0.687621 5.54272 -1.6722 0.70831 5.56157 -1.56427 0.718789 5.45269 -1.47671 0.732697 5.41003 -1.40012 0.752511 5.41403 -1.3108 0.764195 5.34841 -1.22999 0.779414 5.32014 -1.15445 0.796064 5.31014 -1.07827 0.813573 5.29845 -0.999709 0.826364 5.2561 -0.92446 0.841061 5.23196 -0.854737 0.861233 5.25603 -0.785872 0.88803 5.31813 -0.721589 0.931773 5.49784 -0.648292 0.963227 5.58724 -0.57405 1.02717 5.88283 -0.491121 1.0482 5.8902 -0.409183 1.0555 5.80721 -0.333843 1.04569 5.62424 -0.254392 1.06707 5.63744 --0.098739 1.74519 9.46326 -2.71326 -0.573253 -0.66093 -2.78957 -0.592835 -0.654009 -2.85097 -0.606994 -0.633697 -2.94343 -0.631973 -0.633502 -3.01276 -0.648381 -0.614558 -3.10656 -0.673644 -0.60906 -3.17751 -0.689537 -0.585691 -3.28104 -0.717083 -0.579569 -3.37595 -0.741904 -0.565557 -3.47282 -0.765588 -0.548776 -3.57739 -0.792495 -0.533264 -3.70906 -0.828045 -0.527041 -3.8323 -0.859809 -0.51264 -3.9481 -0.888088 -0.490328 -4.09875 -0.928388 -0.479254 -4.23308 -0.961129 -0.456301 -4.38475 -1.00072 -0.435546 -4.57441 -1.05038 -0.422948 -4.75531 -1.09693 -0.400807 -4.93652 -1.14335 -0.372608 -5.15526 -1.20011 -0.349353 -5.37541 -1.25569 -0.318754 -5.62345 -1.32018 -0.287664 -5.88083 -1.38577 -0.250695 -6.1584 -1.45537 -0.208952 -6.46457 -1.53335 -0.163288 -6.8084 -1.62098 -0.114079 -7.19071 -1.71802 -0.059159 -7.64969 -1.83571 -0.00208533 -8.11883 -1.9549 0.0700635 -8.7123 -2.10747 0.145034 -9.38231 -2.27928 0.233957 -10.1394 -2.4722 0.3403 -11.2136 -2.75122 0.456105 -12.4893 -3.08121 0.602548 -14.2755 -3.54604 0.784887 -16.1084 -4.01552 1.03107 -20.7322 -5.18216 1.75291 -23.2488 -5.8019 2.24873 -23.0767 -5.6952 2.64373 -23.1873 -5.66196 3.05777 -26.5152 -6.46523 3.82077 -24.232 -5.80782 4.0034 -25.0295 -5.94565 4.54539 -22.9617 -5.3576 4.65612 -22.6735 -5.22382 5.01251 -22.475 -5.11352 5.378 -19.9313 -4.43337 5.23224 -19.8506 -4.35968 5.57222 -19.5484 -4.23242 5.85514 -19.6552 -4.20411 6.24093 -18.7997 -3.95078 6.35372 -18.6352 -3.85995 6.65091 -20.5742 -4.24546 7.63648 -18.0951 -3.58099 7.50751 -21.0099 -4.16086 8.98578 -19.6324 -3.80331 8.83541 -19.9068 -3.80313 9.34159 -17.5977 -3.26188 8.70514 -19.1236 -3.52066 9.7778 -11.8908 -2.00145 6.62411 -18.9364 -3.36294 10.4766 -18.8562 -3.28537 10.8359 -18.121 -3.08329 10.8353 -18.3312 -3.06228 11.3552 -17.8689 -2.91394 11.4874 -4.37498 -0.406101 3.45886 -4.2947 -0.377809 3.49933 -4.20521 -0.348839 3.53206 -22.4987 -3.44679 16.4026 -19.8002 -2.9131 15.0109 -4.03361 -0.277425 3.68653 -3.95851 -0.25122 3.72312 -4.00001 -0.243337 3.85127 -3.93141 -0.217804 3.89241 -3.86908 -0.193871 3.93838 -3.83671 -0.17424 4.00955 -3.86109 -0.161796 4.13416 -3.8392 -0.142951 4.21914 -3.82876 -0.125087 4.31815 -3.78248 -0.102463 4.38205 -3.73333 -0.0793032 4.44511 -3.75175 -0.0640765 4.58109 -3.69969 -0.0402936 4.64369 -3.82183 -0.0332017 4.91001 -3.89152 -0.0200485 5.12768 -3.82974 0.00767244 5.19257 -3.81577 0.0301772 5.31987 -3.72659 0.0598794 5.35144 -3.69668 0.08504 5.46235 -3.5772 0.116316 5.45009 -3.27515 0.155497 5.16145 -3.41833 0.173215 5.53456 -3.31659 0.201801 5.54067 -3.27223 0.228895 5.63856 -3.13531 0.258135 5.58043 -2.94246 0.28615 5.41409 -3.22857 0.314145 6.12414 -3.08404 0.343615 6.05296 -2.69918 0.364354 5.4852 -2.59853 0.388591 5.46658 -2.61537 0.419329 5.7008 -2.57656 0.449704 5.82621 -2.59592 0.485817 6.0995 -2.39289 0.501298 5.83521 -2.29828 0.526315 5.82755 -2.35528 0.573834 6.24137 -2.05415 0.565041 5.63636 -2.01321 0.597492 5.7743 -1.96219 0.629478 5.8929 -1.92883 0.667653 6.08778 -1.82282 0.688639 6.03187 -2.14192 0.851852 7.68673 -1.92308 0.844821 7.24431 -1.51721 0.743915 5.84192 -1.42159 0.760641 5.77787 -1.3051 0.764108 5.58442 -1.1838 0.757197 5.31997 -1.10681 0.775084 5.29899 -1.02989 0.791677 5.2668 -0.956279 0.810176 5.25282 -0.885978 0.831655 5.2673 -0.82421 0.870053 5.40903 -0.793927 0.996994 6.19271 -0.680742 0.929703 5.54039 -0.608818 0.984056 5.76719 -0.528839 1.02487 5.89376 -0.445945 1.05186 5.91972 -0.369491 1.03636 5.67762 -0.289729 1.06202 5.70093 -0.204775 1.09569 5.7719 -0.0230194 1.3354 7.01962 -2.66598 -0.623533 -0.660909 -2.71909 -0.636022 -0.637377 -2.79464 -0.658304 -0.629183 -2.86279 -0.677191 -0.613468 -2.95544 -0.70502 -0.611587 -3.03945 -0.730103 -0.601719 -3.11726 -0.751053 -0.584407 -3.20285 -0.775489 -0.569531 -3.2974 -0.802587 -0.556778 -3.39272 -0.829284 -0.54118 -3.49672 -0.859463 -0.526925 -3.61775 -0.894969 -0.51801 -3.7402 -0.931022 -0.504959 -3.85425 -0.963376 -0.484119 -3.9862 -1.00101 -0.46733 -4.12765 -1.04188 -0.449721 -4.28763 -1.08884 -0.434289 -4.43009 -1.12898 -0.4069 -4.61816 -1.18379 -0.390687 -4.79746 -1.23551 -0.364929 -5.00509 -1.2958 -0.341601 -5.22195 -1.35851 -0.313852 -5.44897 -1.42372 -0.280977 -5.6951 -1.49409 -0.245002 -5.96995 -1.5732 -0.20676 -6.25478 -1.65427 -0.160961 -6.56744 -1.7424 -0.110877 -6.94648 -1.85224 -0.0608122 -7.35398 -1.96837 -0.00196463 -7.80987 -2.09897 0.0651943 -8.33173 -2.2484 0.140699 -8.9299 -2.41966 0.227437 -9.61392 -2.61448 0.328562 -10.5829 -2.89727 0.437277 -11.6567 -3.20716 0.576055 -13.2083 -3.65923 0.742254 -14.9317 -4.15719 0.963478 -17.1604 -4.79988 1.25287 -20.2751 -5.69974 1.65001 -23.6632 -6.66444 2.17272 -24.4526 -6.83706 2.64364 -24.8299 -6.81865 3.54829 -24.8127 -6.74758 3.98693 -21.4918 -5.67194 4.3481 -21.8 -5.70159 4.78634 -21.73 -5.62375 5.16411 -21.9664 -5.63055 5.60644 -20.6684 -5.21691 5.70495 -20.8278 -5.20364 6.1217 -19.8941 -4.89661 6.25313 -23.682 -5.84519 7.71146 -23.7044 -5.78474 8.16141 -21.5764 -5.16656 7.91476 -18.5526 -4.33022 7.2794 -25.0728 -5.85728 10.5064 -23.6989 -5.44353 10.4438 -18.16 -4.0194 8.55722 -17.4906 -3.80417 8.6228 -21.5525 -4.71774 10.8764 -18.6482 -3.9694 9.90376 -17.6545 -3.68099 9.78762 -17.7596 -3.64916 10.2186 -18.0528 -3.65796 10.7648 -17.5501 -3.48697 10.8719 -19.1982 -3.78875 12.2533 -19.1708 -3.71766 12.6747 -21.4572 -4.13393 14.6013 -19.8339 -3.72023 14.0225 -20.371 -3.75775 14.8788 -20.0053 -3.60944 15.1214 -20.3093 -3.59306 15.8576 -4.04271 -0.341059 4.07974 -3.9194 -0.30409 4.07515 -3.82621 -0.271883 4.09373 -3.83489 -0.258133 4.20588 -3.91722 -0.255 4.3954 -3.84248 -0.226584 4.43296 -3.73843 -0.194125 4.43977 -3.77096 -0.181453 4.59043 -3.713 -0.155492 4.64634 -3.70603 -0.136205 4.76142 -4.00186 -0.154456 5.24489 -3.88935 -0.119218 5.24993 -3.68581 -0.0738767 5.13407 -3.66593 -0.050848 5.25176 -3.626 -0.0246522 5.34556 -3.43543 0.0167717 5.22631 -3.68543 0.0176336 5.74717 -3.23698 0.0785745 5.23139 -3.16227 0.106902 5.26856 -3.19095 0.128984 5.47519 -3.15813 0.156466 5.58875 -2.9361 0.191613 5.37124 -2.83591 0.221129 5.35834 -2.76407 0.248943 5.39646 -2.85209 0.275329 5.75558 -2.87749 0.305086 6.0105 -2.63329 0.333658 5.69424 -2.76034 0.36936 6.19561 -2.64362 0.398906 6.15804 -2.4068 0.420389 5.81135 -2.49013 0.463547 6.27108 -2.3629 0.490788 6.18956 -2.15354 0.505709 5.85925 -2.01828 0.525859 5.71367 -1.89931 0.546081 5.6031 -1.94741 0.598642 6.05592 -1.77766 0.606573 5.75954 -2.05474 0.733807 7.19069 -1.93294 0.763026 7.13534 -1.768 0.773795 6.86345 -1.4599 0.713801 5.82584 -1.47749 0.791241 6.37737 -1.42499 0.842211 6.61614 -1.13613 0.736305 5.30922 -1.06086 0.756678 5.28708 -0.985459 0.775792 5.26379 -0.914586 0.798556 5.26858 -0.847258 0.826305 5.31177 -0.845657 0.991935 6.42271 -0.718267 0.913135 5.63204 -0.639656 0.93169 5.59208 -0.581902 1.16843 7.06494 -0.484594 1.02632 5.9036 -0.403373 1.04567 5.86943 -0.328922 1.03666 5.65592 -0.247281 1.07074 5.71759 --0.105157 1.74465 9.51378 -2.60967 -0.669278 -0.654875 -2.67671 -0.690885 -0.643459 -2.74459 -0.71229 -0.630073 -2.81136 -0.733062 -0.614959 -2.89541 -0.759931 -0.608591 -2.97083 -0.784097 -0.594431 -3.05526 -0.811056 -0.582978 -3.13228 -0.834641 -0.564101 -3.22624 -0.864945 -0.552312 -3.32 -0.894611 -0.537703 -3.42244 -0.927803 -0.52463 -3.53377 -0.963414 -0.51261 -3.64655 -0.99966 -0.496844 -3.75908 -1.03512 -0.477576 -3.88905 -1.0778 -0.462159 -4.02089 -1.11903 -0.442613 -4.16102 -1.16422 -0.422071 -4.31084 -1.21156 -0.400321 -4.47793 -1.26555 -0.379893 -4.65534 -1.3226 -0.356772 -4.85184 -1.38636 -0.333079 -5.06637 -1.45639 -0.30796 -5.29131 -1.52805 -0.278205 -5.51643 -1.59916 -0.240544 -5.77885 -1.68387 -0.203609 -6.05152 -1.76967 -0.159702 -6.34263 -1.86193 -0.109675 -6.68064 -1.96964 -0.0578038 -7.06536 -2.0922 -0.00146252 -7.49733 -2.23021 0.062197 -7.99492 -2.38928 0.133137 -8.54994 -2.56635 0.216326 -9.20875 -2.77631 0.310566 -9.88554 -2.99027 0.427297 -10.931 -3.32877 0.551416 -12.1177 -3.71001 0.709063 -13.8999 -4.288 0.903512 -15.3217 -4.73541 1.15992 -18.2189 -5.67166 1.50683 -23.2724 -7.19214 2.88579 -23.4465 -7.18755 3.31865 -24.9171 -7.60257 3.9113 -24.8943 -7.52999 4.35566 -26.326 -7.91945 5.02496 -25.6467 -7.63567 5.38381 -20.8117 -6.0554 4.92429 -21.2284 -6.12942 5.38979 -20.9079 -5.97424 5.7043 -20.6107 -5.82778 6.0148 -20.151 -5.6339 6.2735 -25.5107 -7.18101 8.17879 -25.0582 -6.97666 8.52201 -31.2984 -8.73752 11.0216 -21.0486 -5.67282 8.1012 -18.7122 -4.94175 7.65821 -22.5292 -5.97435 9.48615 -23.9999 -6.32414 10.5252 -18.7385 -4.7873 8.77385 -18.9762 -4.79751 9.25714 -18.4718 -4.60393 9.4103 -18.4312 -4.53657 9.7728 -18.1327 -4.40114 10.0082 -17.5295 -4.18527 10.0747 -17.5011 -4.12279 10.4384 -19.7743 -4.65016 12.1326 -18.8722 -4.35602 12.037 -21.5012 -4.87607 14.6073 -21.4677 -4.79335 15.0979 -19.0877 -4.1482 13.9655 -19.3458 -4.1394 14.6256 -19.1944 -4.03289 15.0038 -20.0395 -4.15249 16.1568 -4.06109 -0.470461 4.0909 -3.99012 -0.4409 4.13342 -3.90432 -0.407683 4.16064 -4.07686 -0.426977 4.43092 -3.98737 -0.391794 4.45814 -3.84829 -0.348719 4.43373 -3.77335 -0.317388 4.4699 -3.75183 -0.296957 4.56298 -3.63574 -0.258857 4.5522 -3.64392 -0.242538 4.68121 -3.64908 -0.225222 4.81141 -3.58781 -0.19676 4.86528 -3.78952 -0.207863 5.25552 -3.65487 -0.167363 5.22401 -3.36995 -0.105468 4.97922 -3.2318 -0.0673544 4.92188 -3.21857 -0.0454142 5.04226 -3.1705 -0.0177915 5.11293 -3.16238 0.00436492 5.25061 -3.12547 0.0312623 5.34632 -3.0444 0.0621001 5.37278 -3.22439 0.0720433 5.85883 -2.87809 0.125087 5.41185 -2.98309 0.144449 5.78781 -2.80635 0.181169 5.632 -2.7353 0.212626 5.6785 -2.70147 0.243163 5.80559 -2.65155 0.27411 5.90528 -2.57183 0.306297 5.93987 -2.45322 0.337992 5.87998 -2.53856 0.376566 6.34028 -2.48547 0.412709 6.46631 -2.38652 0.447235 6.46892 -1.93238 0.443722 5.38723 -1.81607 0.465271 5.26597 -1.85532 0.509871 5.6597 -2.10716 0.601531 6.87396 -1.74684 0.577799 5.8728 -1.93744 0.679527 7.0168 -1.72805 0.682014 6.54035 -1.64035 0.716603 6.57699 -1.54485 0.748858 6.57276 -1.44824 0.779016 6.55711 -1.33222 0.79756 6.41158 -1.087 0.716694 5.28768 -1.01445 0.740324 5.27437 -0.943744 0.764238 5.27984 -0.892217 0.814543 5.50136 -0.933271 1.04074 7.14791 -0.790304 0.978329 6.38722 -0.673443 0.906949 5.62465 -0.597409 0.940974 5.68263 -0.52117 1.0063 5.94703 -0.440332 1.02571 5.89335 -0.362451 1.03087 5.74916 -0.286698 1.04849 5.69287 -0.200743 1.09458 5.80228 -0.0249651 1.32783 6.99053 -2.55401 -0.712014 -0.648753 -2.6197 -0.735551 -0.638133 -2.6782 -0.754719 -0.620091 -2.75986 -0.784781 -0.616778 -2.82004 -0.803588 -0.594992 -2.91033 -0.836977 -0.59234 -2.98521 -0.862826 -0.576812 -3.06885 -0.89242 -0.563794 -3.15329 -0.92168 -0.548223 -3.24645 -0.954552 -0.534578 -3.33147 -0.982863 -0.51373 -3.43288 -1.01957 -0.498603 -3.55229 -1.06187 -0.488891 -3.66306 -1.10138 -0.470996 -3.78363 -1.14339 -0.453451 -3.92137 -1.19347 -0.439074 -4.05117 -1.23788 -0.41701 -4.19903 -1.29035 -0.397021 -4.34728 -1.34292 -0.371947 -4.52279 -1.40523 -0.351171 -4.70762 -1.47026 -0.327238 -4.90153 -1.53887 -0.29966 -5.11418 -1.61489 -0.270144 -5.346 -1.69622 -0.238307 -5.58769 -1.78084 -0.200369 -5.84794 -1.87229 -0.157964 -6.13562 -1.97296 -0.112047 -6.433 -2.07638 -0.0576947 -6.78641 -2.2007 -0.00164425 -7.17657 -2.33691 0.0612682 -7.63178 -2.49745 0.130205 -8.14335 -2.67718 0.209424 -8.75797 -2.89417 0.298051 -9.3993 -3.11883 0.406952 -10.238 -3.41391 0.528782 -11.3845 -3.82204 0.670907 -12.6619 -4.27327 0.852976 -14.5003 -4.92704 1.08352 -15.5226 -5.26837 1.36392 -24.4041 -8.36973 2.87753 -26.2937 -8.98676 3.49862 -26.1589 -8.87038 3.95948 -26.2694 -8.84149 4.44882 -27.3521 -9.15443 5.09025 -26.0551 -8.62987 5.37008 -27.1646 -8.94545 6.05626 -21.003 -6.75495 5.28135 -21.7716 -6.96168 5.84168 -24.3368 -7.77242 6.87334 -20.3954 -6.384 6.28813 -20.4602 -6.35056 6.68895 -18.7105 -5.71734 6.54644 -18.8774 -5.72107 6.95597 -22.1216 -6.72248 8.42694 -20.2513 -6.05881 8.18058 -23.3526 -6.99143 9.76177 -25.2807 -7.53384 11.0015 -18.1864 -5.24063 8.51256 -18.8317 -5.38784 9.16682 -18.9463 -5.36812 9.60674 -17.9763 -5.01654 9.52949 -11.9487 -3.14839 6.8486 -22.2442 -6.17763 12.5537 -21.6863 -5.87514 13.2137 -19.4176 -5.15102 12.3469 -19.5322 -5.12051 12.8642 -21.338 -5.56277 14.4861 -19.3493 -4.93768 13.664 -19.33 -4.86529 14.1217 -19.2141 -4.76475 14.5186 -19.5375 -4.78086 15.2481 -19.6262 -4.7316 15.8248 -3.8843 -0.523793 4.13932 -4.30669 -0.609562 4.64613 -4.21435 -0.570578 4.67814 -3.86636 -0.473243 4.44779 -3.80473 -0.443102 4.49919 -3.81044 -0.427456 4.622 -3.76713 -0.400689 4.69424 -3.76104 -0.381332 4.81071 -3.5479 -0.320023 4.68436 -3.60204 -0.312666 4.87576 -3.75485 -0.323596 5.20332 -3.76601 -0.304985 5.36215 -3.66752 -0.265761 5.37782 -3.39777 -0.197378 5.14698 -3.16411 -0.138436 4.94923 -3.05731 -0.101707 4.92774 -3.15983 -0.096597 5.232 -3.40479 -0.108341 5.7874 -3.48541 -0.0934084 6.10272 -3.29041 -0.0424878 5.95304 -2.97143 0.0204646 5.56116 -2.75009 0.0682491 5.31925 -3.17143 0.0554716 6.32879 -2.65927 0.127435 5.49102 -2.62048 0.157294 5.59878 -2.68119 0.182518 5.93485 -2.59014 0.218192 5.94232 -2.60757 0.25078 6.21656 -2.54956 0.286737 6.31554 -2.46681 0.323275 6.35735 -2.05263 0.348959 5.45408 -1.96509 0.378426 5.43073 -1.86948 0.405726 5.37715 -1.76729 0.432392 5.29238 -1.67889 0.457964 5.24415 -1.82015 0.522488 6.06364 -1.7455 0.557324 6.11199 -1.81513 0.630464 6.80127 -1.67158 0.652807 6.5854 -1.60914 0.69991 6.74803 -1.51216 0.734521 6.74327 -1.36037 0.741322 6.39194 -1.11516 0.678122 5.30764 -1.04178 0.702151 5.28513 -0.971733 0.729073 5.29069 -0.904026 0.759191 5.32458 -0.946678 0.953485 6.79385 -0.823461 0.933108 6.33042 -0.720604 0.921468 5.98413 -0.6306 0.907314 5.64614 -0.557208 0.970061 5.89139 -0.476177 1.00895 5.95675 -0.396073 1.02903 5.8818 -0.323741 1.02465 5.66781 -0.249014 1.04899 5.6401 --0.107015 1.73695 9.51497 -2.56117 -0.777751 -0.632859 -2.62632 -0.803016 -0.621066 -2.69959 -0.8311 -0.61317 -2.76543 -0.855722 -0.597462 -2.84711 -0.888129 -0.590225 -2.92161 -0.916145 -0.57547 -2.99667 -0.944843 -0.558257 -3.07978 -0.976121 -0.543871 -3.16342 -1.00799 -0.526638 -3.25482 -1.04324 -0.511354 -3.35491 -1.08202 -0.497607 -3.4644 -1.12537 -0.484593 -3.56595 -1.16312 -0.464184 -3.68379 -1.20899 -0.448231 -3.80307 -1.25541 -0.428142 -3.93114 -1.30398 -0.407939 -4.07706 -1.36162 -0.389808 -4.21501 -1.41354 -0.363796 -4.38741 -1.48186 -0.345288 -4.55251 -1.54545 -0.317802 -4.73575 -1.61564 -0.290253 -4.94536 -1.69788 -0.263978 -5.17391 -1.78641 -0.235282 -5.40358 -1.87454 -0.198267 -5.64191 -1.96672 -0.155171 -5.90872 -2.06855 -0.109416 -6.21119 -2.18502 -0.0611951 -6.51457 -2.30048 -0.00193083 -6.89086 -2.44565 0.0569358 -7.29561 -2.60101 0.125982 -7.78243 -2.78832 0.199927 -8.31612 -2.99386 0.287548 -8.95007 -3.23866 0.386775 -9.63156 -3.49937 0.506704 -10.6356 -3.89002 0.638895 -11.7502 -4.32081 0.805966 -13.4574 -4.9879 1.0132 -14.9779 -5.56997 1.28055 -16.3577 -6.08756 1.59943 -25.2772 -9.48417 3.30066 -26.6111 -9.94276 3.91004 -27.3981 -10.1806 4.49962 -27.8891 -10.2993 5.07615 -28.2959 -10.3844 5.65905 -23.3287 -8.35407 5.69644 -23.8017 -8.4717 6.23683 -23.6066 -8.33642 6.63569 -23.9423 -8.39843 7.1686 -19.9486 -6.86382 6.50125 -20.2184 -6.90969 6.9623 -20.3436 -6.90023 7.39061 -18.7495 -6.27098 7.24261 -18.7951 -6.23659 7.62513 -21.4163 -7.11344 8.99268 -18.1168 -5.89364 8.09815 -17.9888 -5.79853 8.4088 -18.6404 -5.97246 9.06351 -18.9993 -6.04066 9.61456 -19.2008 -6.05408 10.11 -18.4175 -5.73268 10.1204 -18.4771 -5.69753 10.5488 -20.1356 -6.18825 11.8674 -18.8642 -5.70985 11.5855 -19.186 -5.75383 12.2039 -19.5588 -5.81166 12.8773 -19.6881 -5.78897 13.42 -19.4765 -5.65568 13.749 -19.1477 -5.48724 13.996 -19.8238 -5.62821 14.9604 -19.728 -5.52824 15.3939 -5.06732 -1.05217 4.69298 -4.99505 -1.01366 4.76185 -5.10608 -1.00852 5.12205 -4.95647 -0.946821 5.1242 -4.92172 -0.918328 5.2302 -4.78656 -0.861867 5.23955 -4.30702 -0.714603 4.89509 -4.30724 -0.695926 5.02596 -3.99098 -0.596604 4.81776 -3.86625 -0.547266 4.80524 -3.61456 -0.467647 4.64002 -3.91902 -0.524134 5.12681 -3.79294 -0.474468 5.10918 -3.81945 -0.461719 5.28343 -3.80055 -0.437251 5.40416 -3.72653 -0.399318 5.45298 -3.75937 -0.384586 5.65449 -3.19977 -0.248938 4.99617 -3.09354 -0.208937 4.97593 -3.03116 -0.176962 5.02008 -3.45663 -0.233016 5.86136 -3.09126 -0.145233 5.42228 -2.91356 -0.0937901 5.27551 -2.83106 -0.0578258 5.28951 -2.82445 -0.0337289 5.44342 -2.99268 -0.0305037 5.95395 -2.6352 0.0399925 5.42068 -2.59062 0.0706483 5.51014 -2.44578 0.112158 5.3801 -2.7179 0.117198 6.21106 -2.64722 0.155293 6.2748 -2.57369 0.193814 6.3372 -2.47861 0.233134 6.3422 -2.06897 0.276569 5.459 -2.03327 0.308993 5.58789 -1.85352 0.338702 5.27813 -1.88635 0.374942 5.634 -1.72255 0.400318 5.33761 -2.01282 0.47384 6.70798 -1.76013 0.489371 6.08053 -1.68503 0.526194 6.12777 -1.76888 0.602612 6.91574 -1.62182 0.628802 6.66862 -1.52846 0.666674 6.67378 -1.3931 0.686731 6.42121 -1.14863 0.64005 5.37691 -1.06971 0.663657 5.31533 -1.00007 0.692681 5.32137 -0.930529 0.721418 5.32614 -0.941576 0.853541 6.30076 -0.86521 0.904907 6.44197 -0.78279 0.953456 6.55222 -0.662977 0.881849 5.68874 -0.587566 0.914761 5.70663 -0.5115 0.976999 5.93103 -0.430921 1.01363 5.95561 -0.357522 1.01371 5.74156 -0.284359 1.02969 5.64503 -0.207028 1.06464 5.6654 -0.0233114 1.32618 7.00085 -2.51646 -0.824786 -0.639443 -2.56637 -0.842992 -0.616915 -2.63901 -0.874173 -0.609497 -2.69646 -0.896795 -0.58911 -2.76856 -0.928026 -0.577507 -2.8577 -0.966261 -0.574257 -2.93141 -0.996912 -0.557937 -3.00496 -1.02706 -0.53938 -3.07932 -1.05696 -0.518658 -3.17809 -1.09942 -0.50911 -3.26892 -1.13631 -0.492264 -3.36797 -1.17858 -0.476366 -3.47567 -1.22425 -0.461421 -3.59296 -1.27344 -0.446919 -3.70184 -1.3189 -0.424531 -3.82792 -1.3725 -0.405602 -3.95467 -1.42541 -0.382564 -4.10737 -1.49012 -0.365107 -4.25183 -1.54999 -0.339279 -4.41502 -1.61886 -0.314138 -4.60395 -1.6989 -0.291854 -4.77557 -1.77108 -0.257421 -5.00182 -1.86703 -0.231745 -5.21873 -1.95749 -0.195874 -5.46353 -2.06085 -0.158405 -5.7077 -2.16224 -0.112278 -5.98057 -2.27629 -0.0623895 -6.28881 -2.40576 -0.0091567 -6.61536 -2.54124 0.0521427 -6.98741 -2.6963 0.119094 -7.43229 -2.88308 0.19103 -7.93164 -3.0927 0.273722 -8.50326 -3.33237 0.368794 -9.15818 -3.60617 0.479936 -9.90323 -3.91808 0.611335 -10.986 -4.37603 0.76151 -12.215 -4.89251 0.951109 -14.1299 -5.70542 1.19492 -15.3009 -6.18291 1.48807 -24.9897 -10.2346 3.16955 -25.8723 -10.5482 3.72572 -26.4431 -10.7256 4.27734 -27.1154 -10.9415 4.86596 -27.2579 -10.9321 5.39531 -27.473 -10.9514 5.94493 -23.5005 -9.2349 5.66292 -23.6533 -9.23706 6.13909 -23.4176 -9.07958 6.53063 -23.5364 -9.06691 7.00739 -28.7197 -11.0977 8.90312 -19.1884 -7.19829 6.61493 -19.7546 -7.37343 7.16672 -18.1636 -6.69123 7.01418 -18.1785 -6.64812 7.37673 -18.6701 -6.78995 7.92397 -18.382 -6.62689 8.18339 -18.0543 -6.45057 8.419 -18.9691 -6.74799 9.19305 -18.7585 -6.61423 9.49006 -18.9008 -6.61417 9.95436 -19.779 -6.88599 10.8031 -18.3434 -6.296 10.4727 -17.9721 -6.10496 10.6713 -18.1362 -6.11008 11.1671 -22.0874 -7.47587 13.9407 -21.076 -7.0443 13.8247 -20.2902 -6.69908 13.8153 -19.4775 -6.34756 13.7586 -20.2432 -6.54761 14.7682 -19.3262 -6.16319 14.6137 -20.823 -6.60343 16.2259 -5.09565 -1.23017 4.71988 -5.00986 -1.18425 4.77795 -4.85694 -1.11613 4.77666 -4.88753 -1.10924 4.9326 -4.75692 -1.049 4.94534 -4.85227 -1.06088 5.16924 -4.73391 -1.00471 5.19224 -4.70471 -0.976694 5.30256 -4.43633 -0.877779 5.16484 -4.20034 -0.789044 5.04714 -4.30806 -0.801539 5.30314 -3.95998 -0.684055 5.04315 -4.00481 -0.677967 5.2325 -3.94037 -0.640804 5.29413 -3.95383 -0.624324 5.45557 -3.7834 -0.559506 5.38198 -3.8159 -0.546471 5.5749 -3.68818 -0.493342 5.55174 -3.71756 -0.479604 5.75445 -3.10964 -0.314457 4.99819 -3.2289 -0.321859 5.32801 -3.17265 -0.28836 5.3919 -3.29198 -0.291146 5.75419 -3.28199 -0.264954 5.91416 -2.82207 -0.150447 5.26289 -2.90036 -0.142861 5.57548 -3.04166 -0.141768 6.03341 -2.62144 -0.0466133 5.37683 -2.54005 -0.00902484 5.38478 -2.51722 0.019187 5.51887 -2.37936 0.0636056 5.39598 -2.64516 0.0613061 6.23975 -2.57402 0.101388 6.30238 -2.49427 0.142627 6.3451 -2.46072 0.181546 6.51801 -1.98492 0.23857 5.40335 -1.9152 0.272219 5.42653 -1.85153 0.305978 5.46762 -1.83619 0.342326 5.68029 -2.09686 0.39941 6.93601 -1.78454 0.422633 6.09701 -1.69913 0.460447 6.09619 -1.62652 0.499531 6.15226 -1.51753 0.530824 6.03099 -1.46325 0.5756 6.18202 -1.39641 0.619412 6.28299 -1.16955 0.593946 5.36709 -1.09327 0.622082 5.32545 -1.02402 0.652219 5.32212 -0.954888 0.683036 5.32727 -0.974815 0.810911 6.32242 -0.893361 0.854583 6.37485 -0.7753 0.828904 5.81093 -0.698209 0.862681 5.81072 -0.619638 0.885385 5.71987 -0.544302 0.927294 5.7863 -0.46505 1.02064 6.20758 -0.389238 1.00825 5.87478 -0.320693 1.00194 5.61042 -0.246668 1.03732 5.62159 --0.110322 1.72653 9.50639 -2.52048 -0.890829 -0.623714 -2.57691 -0.914781 -0.605877 -2.641 -0.943478 -0.591641 -2.71272 -0.976853 -0.580713 -2.78428 -1.00977 -0.567742 -2.86464 -1.04649 -0.557573 -2.93781 -1.07883 -0.539885 -3.01854 -1.11564 -0.524631 -3.09909 -1.15191 -0.506945 -3.18933 -1.19198 -0.490966 -3.27913 -1.23239 -0.472066 -3.39298 -1.28599 -0.462683 -3.49194 -1.33025 -0.441305 -3.60719 -1.38266 -0.424481 -3.72387 -1.43558 -0.403423 -3.84791 -1.49238 -0.382075 -3.99004 -1.5573 -0.363094 -4.12469 -1.61861 -0.335618 -4.27544 -1.68742 -0.309875 -4.46224 -1.77372 -0.289932 -4.62363 -1.84546 -0.255437 -4.81879 -1.93488 -0.225328 -5.0334 -2.03278 -0.192574 -5.274 -2.1432 -0.158756 -5.50618 -2.24823 -0.114038 -5.76615 -2.36581 -0.0662639 -6.04314 -2.49161 -0.0123866 -6.36586 -2.63763 0.0442238 -6.7148 -2.79585 0.108831 -7.11738 -2.97873 0.179408 -7.59216 -3.19484 0.257212 -8.08494 -3.41831 0.351385 -8.67593 -3.68589 0.456668 -9.3753 -4.0041 0.579096 -10.2821 -4.41801 0.72112 -11.4494 -4.95212 0.893867 -12.941 -5.63575 1.11323 -14.8022 -6.48565 1.39841 -16.0113 -7.01903 1.72592 -24.8458 -10.9994 3.51587 -25.0619 -11.0369 4.00884 -25.234 -11.0524 4.50477 -25.2175 -10.9815 4.97857 -25.2931 -10.951 5.46937 -27.3331 -11.807 6.35432 -22.4527 -9.49144 6.24442 -23.3586 -9.83459 6.90901 -19.9577 -8.27629 6.42078 -18.8282 -7.72896 6.47349 -18.1144 -7.36915 6.61545 -18.2424 -7.37684 7.01516 -18.0836 -7.26043 7.32087 -18.1982 -7.26038 7.72657 -20.4229 -8.15463 8.98227 -18.7149 -7.37896 8.68457 -18.8814 -7.39707 9.14594 -18.9045 -7.35317 9.55239 -18.5649 -7.15987 9.78975 -18.508 -7.08259 10.1603 -18.6445 -7.0839 10.6363 -19.6047 -7.41638 11.5794 -18.7737 -7.02451 11.5433 -21.2445 -7.94947 13.4519 -19.3984 -7.15447 12.7985 -18.9164 -6.90443 12.9467 -21.2786 -7.75979 14.99 -20.9184 -7.55067 15.2638 -21.1042 -7.55106 15.9249 -4.92116 -1.32292 4.71272 -4.86659 -1.28635 4.79342 -4.72363 -1.21785 4.79577 -4.81039 -1.23094 5.00357 -4.76414 -1.19736 5.09502 -4.56496 -1.1098 5.03594 -4.56632 -1.09246 5.17182 -4.71205 -1.12267 5.46384 -4.45385 -1.01678 5.33137 -4.41434 -0.985178 5.43148 -4.52672 -1.00168 5.70918 -4.0926 -0.842573 5.34436 -3.97761 -0.787201 5.34724 -3.87548 -0.736665 5.36245 -3.85062 -0.709843 5.47727 -3.92853 -0.711363 5.73535 -3.77705 -0.646845 5.68297 -3.78967 -0.628418 5.86292 -3.70987 -0.583717 5.91215 -3.1147 -0.402074 5.14931 -3.01038 -0.354549 5.1271 -2.99249 -0.330427 5.24737 -2.87867 -0.281772 5.20405 -2.81448 -0.245829 5.24491 -2.85149 -0.231935 5.47776 -2.81001 -0.199187 5.57088 -2.81018 -0.175093 5.75315 -2.56333 -0.101612 5.42223 -2.46217 -0.0582083 5.38392 -2.40265 -0.0234154 5.43495 -2.77267 -0.0536228 6.52714 -2.55179 0.0111376 6.22069 -2.47143 0.0537715 6.2542 -2.44359 0.0911057 6.43643 -2.39186 0.133112 6.56195 -2.32082 0.177292 6.6394 -2.23918 0.222138 6.68712 -2.11139 0.269301 6.57938 -2.09143 0.314637 6.84508 -2.04249 0.36273 7.03368 -1.76109 0.395684 6.27855 -1.98192 0.47455 7.65251 -1.5087 0.464337 5.8924 -1.53797 0.526595 6.45562 -1.41248 0.557726 6.24292 -1.18807 0.546302 5.35713 -1.11716 0.578292 5.34555 -1.04955 0.612231 5.35237 -0.979833 0.644377 5.34804 -1.00645 0.766473 6.35373 -0.913904 0.796925 6.24806 -0.83369 0.840172 6.28978 -0.728219 0.827447 5.81351 -0.704504 1.06119 7.47984 -0.576061 0.892977 5.76013 -0.499625 1.09139 6.97517 -0.4064 1.12601 6.89893 -0.223004 1.58493 9.66794 -0.281303 1.01412 5.61697 -0.206831 1.05146 5.62694 -0.0199638 1.32694 7.02078 -2.45237 -0.922266 -0.613465 -2.52133 -0.957112 -0.607858 -2.57724 -0.982792 -0.588848 -2.6476 -1.01812 -0.578814 -2.71199 -1.04834 -0.561436 -2.79779 -1.0919 -0.557438 -2.86163 -1.12213 -0.535679 -2.94102 -1.16094 -0.521512 -3.02097 -1.20039 -0.504693 -3.10097 -1.23832 -0.485542 -3.20486 -1.29058 -0.476585 -3.28592 -1.32961 -0.45135 -3.39895 -1.38572 -0.439818 -3.50477 -1.43734 -0.420378 -3.61009 -1.48914 -0.397336 -3.7489 -1.55881 -0.384932 -3.8642 -1.61425 -0.357346 -4.005 -1.68347 -0.335334 -4.14522 -1.75258 -0.308456 -4.312 -1.83431 -0.285284 -4.47884 -1.91685 -0.255856 -4.65477 -2.00306 -0.223074 -4.85684 -2.10224 -0.191272 -5.07615 -2.21032 -0.156383 -5.3051 -2.32266 -0.115292 -5.53514 -2.43455 -0.065688 -5.80776 -2.56858 -0.0162371 -6.10776 -2.7156 0.0388027 -6.42558 -2.87054 0.102304 -6.79594 -3.05123 0.170294 -7.21912 -3.25912 0.246303 -7.67826 -3.4838 0.334955 -8.288 -3.78455 0.429391 -8.87059 -4.06819 0.548571 -9.60448 -4.42791 0.684385 -10.6395 -4.93862 0.842302 -11.8431 -5.53214 1.04052 -13.607 -6.40505 1.29599 -15.0936 -7.12795 1.60897 -24.8802 -11.9206 3.41226 -24.9536 -11.8954 3.89504 -24.7529 -11.7336 4.34404 -24.5976 -11.5956 4.79334 -24.6399 -11.5541 5.27239 -24.9935 -11.6647 5.81544 -28.9142 -13.5071 7.1409 -24.5178 -11.3091 6.67249 -31.022 -14.3725 8.8065 -20.2079 -9.12283 6.44868 -20.1573 -9.0477 6.83149 -19.4846 -8.67714 7.01869 -18.8273 -8.3175 7.1869 -18.0742 -7.91567 7.29701 -18.0608 -7.86164 7.65807 -18.7233 -8.11941 8.29141 -20.9613 -9.09594 9.61725 -18.7248 -8.01894 9.0715 -18.5987 -7.90922 9.40932 -18.7836 -7.941 9.89766 -18.8015 -7.89571 10.3148 -20.6299 -8.65395 11.697 -18.6272 -7.70896 11.0526 -18.5668 -7.6282 11.4408 -20.5571 -8.43902 13.0619 -18.9846 -7.69535 12.564 -18.788 -7.55171 12.8899 -21.7554 -8.75572 15.3436 -24.0516 -9.65563 17.4887 -5.24789 -1.62577 4.99593 -5.06601 -1.53515 4.97733 -4.99412 -1.48885 5.04878 -4.97042 -1.46116 5.16411 -4.74955 -1.35697 5.09339 -4.73791 -1.33441 5.21869 -4.62876 -1.27498 5.24812 -4.64658 -1.26309 5.40783 -4.63439 -1.23885 5.54052 -4.5608 -1.19285 5.60853 -4.56909 -1.17596 5.77082 -4.18067 -1.01655 5.46206 -3.98582 -0.928779 5.36862 -3.90857 -0.883022 5.41585 -3.89064 -0.857114 5.53962 -3.75951 -0.793333 5.51308 -3.997 -0.851046 6.00512 -3.82843 -0.774596 5.92904 -3.79739 -0.742074 6.05383 -3.62749 -0.666415 5.96221 -3.47025 -0.596675 5.88253 -2.90303 -0.407137 5.09994 -2.88138 -0.381905 5.21094 -2.80327 -0.33942 5.22615 -2.80035 -0.317311 5.37996 -2.81079 -0.298331 5.5701 -2.75903 -0.261499 5.6453 -3.06577 -0.309456 6.48505 -2.54409 -0.163338 5.55767 -2.56577 -0.142146 5.80233 -2.70373 -0.141889 6.34345 -2.7101 -0.111787 6.60263 -2.58606 -0.0569455 6.5364 -2.45747 -0.00233571 6.44839 -2.37122 0.0446897 6.47071 -2.30356 0.0901274 6.54812 -2.24549 0.134578 6.66266 -2.1225 0.185805 6.56504 -2.09555 0.230105 6.80219 -2.02662 0.278763 6.90375 -1.9424 0.328274 6.95568 -1.61931 0.364307 5.95273 -1.56303 0.407112 6.06654 -1.56722 0.461938 6.50314 -1.34587 0.478332 5.75006 -1.20644 0.49854 5.35654 -1.1369 0.532415 5.34556 -1.07345 0.569471 5.38252 -1.00634 0.605203 5.38847 -0.954292 0.653032 5.55182 -0.904896 0.712156 5.81334 -0.845183 0.77066 6.02408 -0.7501 0.777844 5.7069 -0.733568 0.98348 7.21586 -0.606754 0.864895 5.8033 -0.532032 0.90466 5.81959 -0.446442 1.09092 6.90429 -0.340989 1.21258 7.42063 -0.316205 0.984662 5.58254 -0.242407 1.02813 5.62283 --0.113393 1.71706 9.49761 -2.5829 -1.05735 -0.576726 -2.64496 -1.08926 -0.560167 -2.70761 -1.12195 -0.541539 -2.78488 -1.16311 -0.531111 -2.87068 -1.20895 -0.522899 -2.94156 -1.24539 -0.5024 -3.01999 -1.28628 -0.484236 -3.10668 -1.33269 -0.467605 -3.19436 -1.37773 -0.448228 -3.30465 -1.43765 -0.438094 -3.40006 -1.48828 -0.41616 -3.51273 -1.54724 -0.398561 -3.62489 -1.60629 -0.376972 -3.75375 -1.67532 -0.358155 -3.88422 -1.74378 -0.33472 -4.02174 -1.81685 -0.309823 -4.16061 -1.89021 -0.27972 -4.32483 -1.9769 -0.25315 -4.48935 -2.06346 -0.220521 -4.67981 -2.16407 -0.189161 -4.88732 -2.27465 -0.1551 -5.10353 -2.38938 -0.115445 -5.34639 -2.51762 -0.0736302 -5.58933 -2.64501 -0.0225466 -5.85853 -2.78641 0.0329376 -6.15388 -2.94148 0.0942814 -6.49196 -3.11976 0.160657 -6.88298 -3.3256 0.2334 -7.32623 -3.56024 0.315918 -7.81258 -3.81647 0.411664 -8.39546 -4.12344 0.52 -9.0308 -4.45709 0.648545 -9.83057 -4.87979 0.797632 -10.9551 -5.47774 0.976267 -12.2533 -6.16484 1.20113 -14.3839 -7.30145 1.50513 -16.1871 -8.24862 1.87529 -25.3209 -13.0367 3.83263 -25.011 -12.8088 4.2825 -24.7728 -12.6207 4.73212 -24.8435 -12.5967 5.22647 -25.2194 -12.733 5.78379 -23.1827 -11.5436 6.30232 -23.3045 -11.5481 6.7911 -20.0597 -9.81185 6.36958 -20.1149 -9.78971 6.78561 -20.0104 -9.68481 7.15645 -20.3271 -9.79408 7.66675 -19.468 -9.30724 7.7764 -19.5763 -9.31097 8.21723 -19.9553 -9.44819 8.77374 -18.6463 -8.74293 8.64368 -18.8119 -8.77526 9.11148 -18.4974 -8.56939 9.36853 -18.558 -8.54775 9.79864 -21.0158 -9.69231 11.4537 -19.7041 -8.99807 11.2267 -18.5645 -8.39264 11.0408 -18.619 -8.36506 11.4974 -19.998 -8.96526 12.7599 -19.402 -8.62318 12.8609 -19.2918 -8.51175 13.2563 -23.1322 -10.2399 16.3239 -23.4381 -10.3075 17.1187 -24.75 -10.8327 18.6727 -25.1224 -10.9206 19.6011 -5.19842 -1.77621 5.10834 -4.99076 -1.66792 5.06307 -4.90502 -1.61257 5.12107 -4.81822 -1.55843 5.177 -4.83349 -1.54697 5.33159 -4.77833 -1.50467 5.41896 -4.6025 -1.41254 5.3794 -4.53223 -1.3651 5.44815 -4.46794 -1.32008 5.52252 -4.45287 -1.29527 5.65456 -4.4841 -1.28838 5.84672 -4.29241 -1.19203 5.76802 -4.15667 -1.11954 5.75264 -3.73021 -0.936844 5.34349 -3.64427 -0.885734 5.37066 -3.65921 -0.872233 5.53977 -3.92802 -0.950526 6.09163 -3.76671 -0.870369 6.02183 -3.4143 -0.724516 5.64008 -3.40274 -0.700066 5.7847 -3.31688 -0.649197 5.81081 -3.33343 -0.631959 6.01506 -2.75523 -0.42393 5.14638 -3.26241 -0.562019 6.26236 -2.82536 -0.404179 5.60414 -3.09673 -0.460795 6.3396 -3.01384 -0.409695 6.37544 -2.75756 -0.312863 6.0293 -2.55226 -0.232402 5.76651 -2.73228 -0.251123 6.40828 -2.64822 -0.200267 6.43648 -2.51354 -0.140048 6.33277 -2.49153 -0.103018 6.52557 -2.37941 -0.04721 6.47316 -2.29092 0.0023727 6.48487 -2.2143 0.0512257 6.53258 -2.1368 0.100031 6.579 -2.0527 0.14932 6.60467 -1.98416 0.198018 6.68663 -1.94615 0.246089 6.90339 -1.65752 0.297716 6.05737 -1.57202 0.3416 6.03503 -1.46847 0.382911 5.91283 -1.31625 0.414551 5.49326 -1.2259 0.448317 5.37581 -1.15701 0.485245 5.36511 -1.1019 0.527393 5.45181 -1.03598 0.566033 5.47826 -0.966634 0.603292 5.46354 -1.03736 0.762733 7.02634 -0.851275 0.703466 5.74789 -0.790872 0.763005 5.95772 -0.708003 0.788343 5.79843 -0.679437 1.01002 7.41594 -0.562389 0.87065 5.8135 -0.484574 1.04907 6.87979 -0.394547 1.10228 6.90208 -0.21138 1.54689 9.60238 -0.277279 0.99876 5.58879 -0.203272 1.04619 5.63783 -0.0166247 1.32873 7.05076 -2.51692 -1.09312 -0.574694 -2.57859 -1.1272 -0.558908 -2.64012 -1.16086 -0.541273 -2.71581 -1.20495 -0.531639 -2.78454 -1.24367 -0.514586 -2.86859 -1.29191 -0.504832 -2.93892 -1.33003 -0.482965 -3.02428 -1.37848 -0.467616 -3.10919 -1.42725 -0.449248 -3.21049 -1.48439 -0.436505 -3.30435 -1.53803 -0.415753 -3.40662 -1.59602 -0.395758 -3.51725 -1.6582 -0.375837 -3.62834 -1.72068 -0.351804 -3.75516 -1.7929 -0.330568 -3.88238 -1.8653 -0.304636 -4.02717 -1.94756 -0.279897 -4.17993 -2.03445 -0.252799 -4.34916 -2.13063 -0.225458 -4.50375 -2.21657 -0.186515 -4.69871 -2.32844 -0.153406 -4.90361 -2.44383 -0.115266 -5.14108 -2.57993 -0.0772195 -5.36402 -2.7045 -0.0263086 -5.63613 -2.85944 0.0230971 -5.90094 -3.00798 0.0844935 -6.23425 -3.19664 0.145768 -6.56737 -3.38366 0.219813 -6.96836 -3.61057 0.299186 -7.43864 -3.87789 0.388121 -7.93431 -4.15654 0.493325 -8.54999 -4.50524 0.611984 -9.26885 -4.91196 0.751537 -10.1075 -5.38683 0.918385 -11.3509 -6.09535 1.1216 -12.8942 -6.97341 1.38246 -14.9628 -8.15068 1.73051 -20.2713 -11.1535 2.77836 -24.8515 -13.7453 3.67032 -25.2747 -13.9276 4.2142 -25.4477 -13.9647 4.73873 -26.9629 -14.7641 5.49738 -26.9714 -14.7031 6.03477 -27.0749 -14.6948 6.5941 -28.1871 -15.2518 7.39133 -30.1464 -16.2769 8.44867 -30.2913 -16.282 9.09883 -21.6018 -11.3922 7.18503 -23.9864 -12.6519 8.36978 -21.4898 -11.2214 8.03186 -19.2834 -9.96153 7.69466 -20.0262 -10.3146 8.37503 -19.6841 -10.0781 8.66042 -19.438 -9.89404 8.97519 -19.7455 -10.007 9.52788 -18.9495 -9.5294 9.58706 -19.064 -9.53882 10.0586 -19.3482 -9.63647 10.6267 -18.2104 -8.98602 10.4573 -18.1163 -8.88536 10.8201 -19.603 -9.6042 12.1004 -18.9746 -9.22322 12.1829 -19.1108 -9.23665 12.7219 -19.1284 -9.18749 13.1979 -26.2587 -12.7374 18.5079 -24.7328 -11.8868 18.0998 -24.3617 -11.6227 18.4684 -24.3192 -11.5224 19.079 -23.7452 -11.1581 19.283 -5.30716 -2.02088 5.22403 -5.19995 -1.95185 5.27168 -5.15378 -1.91187 5.37382 -5.05782 -1.84822 5.42918 -4.98892 -1.79782 5.50878 -4.77246 -1.67927 5.43658 -4.65826 -1.60798 5.46141 -4.56225 -1.54692 5.5043 -4.43505 -1.4714 5.50861 -4.37713 -1.42662 5.58946 -4.51403 -1.46821 5.90725 -4.17953 -1.30207 5.64981 -4.24301 -1.31071 5.88674 -4.31128 -1.31977 6.14252 -4.1978 -1.25066 6.15772 -3.63366 -0.996422 5.52356 -3.5848 -0.956883 5.60515 -3.97735 -1.09512 6.36551 -3.72712 -0.973662 6.15548 -3.37313 -0.813752 5.75348 -3.32374 -0.774264 5.83926 -3.29737 -0.742268 5.96708 -3.38075 -0.750134 6.30245 -2.77079 -0.509219 5.34154 -3.16356 -0.625174 6.28056 -3.07337 -0.569179 6.30087 -2.99565 -0.517437 6.346 -2.66487 -0.387033 5.82945 -2.62525 -0.350112 5.93987 -2.53026 -0.295728 5.92133 -2.64171 -0.300149 6.41836 -2.49879 -0.232005 6.28728 -2.46174 -0.191517 6.43315 -2.45955 -0.158307 6.69202 -2.34437 -0.098533 6.62975 -2.21337 -0.036775 6.50747 -2.1185 0.0172344 6.48728 -2.07747 0.0626506 6.65724 -1.97614 0.116749 6.61455 -1.99392 0.159534 7.04481 -1.67498 0.22841 6.08358 -1.5958 0.274923 6.08146 -1.4592 0.32045 5.79313 -1.31105 0.358351 5.39342 -1.24246 0.397709 5.38467 -1.18344 0.438273 5.43371 -1.1382 0.48511 5.59029 -1.06421 0.524034 5.55779 -0.992288 0.562154 5.52388 -1.06873 0.707888 7.05782 -0.883259 0.669145 5.86893 -0.813196 0.716121 5.91036 -0.735 0.751632 5.83103 -0.710853 0.942843 7.2512 -0.61073 0.963968 6.94962 -0.518084 0.885447 5.87243 -0.43266 1.06154 6.88801 -0.327467 1.1933 7.45337 -0.309321 0.97403 5.59398 -0.238367 1.01887 5.61393 --0.121498 1.71891 9.55764 -2.45722 -1.13159 -0.578163 -2.51752 -1.16758 -0.563076 -2.57768 -1.20315 -0.54614 -2.64522 -1.2443 -0.532121 -2.72035 -1.29003 -0.520925 -2.79531 -1.33523 -0.507394 -2.87178 -1.38124 -0.490894 -2.94035 -1.42174 -0.467389 -3.02394 -1.47254 -0.450304 -3.11575 -1.52878 -0.434361 -3.19965 -1.57945 -0.411218 -3.31574 -1.65016 -0.400579 -3.41597 -1.71134 -0.378164 -3.5169 -1.77195 -0.352125 -3.64963 -1.85301 -0.336059 -3.76674 -1.92364 -0.308608 -3.90024 -2.00496 -0.282761 -4.03436 -2.08543 -0.252025 -4.18456 -2.17729 -0.221529 -4.35122 -2.27839 -0.190595 -4.52648 -2.38499 -0.155621 -4.72713 -2.50733 -0.120548 -4.92818 -2.62816 -0.0777665 -5.16252 -2.77082 -0.0345654 -5.40519 -2.9182 0.016081 -5.66562 -3.07496 0.0731484 -5.95077 -3.24708 0.13635 -6.30288 -3.46071 0.201064 -6.64626 -3.668 0.280862 -7.07432 -3.92775 0.365971 -7.55297 -4.21733 0.464049 -8.08993 -4.5423 0.577653 -8.72867 -4.92875 0.709024 -9.48458 -5.38771 0.863957 -10.5541 -6.03887 1.04969 -11.8502 -6.82761 1.28368 -13.6369 -7.91712 1.59121 -15.7777 -9.21765 1.99364 -18.745 -11.0207 2.55213 -25.1663 -14.8831 4.09412 -25.4738 -15.0113 4.644 -26.5605 -15.6122 5.33596 -26.361 -15.4265 5.83556 -26.3985 -15.3854 6.37756 -26.5539 -15.4145 6.94995 -28.8216 -16.7112 8.05469 -30.3504 -17.5536 9.05841 -29.5345 -16.9925 9.45084 -21.1857 -11.9678 7.46995 -19.6694 -11.0195 7.4076 -19.6753 -10.9739 7.82216 -19.945 -11.0816 8.33951 -20.0928 -11.1156 8.82343 -20.8404 -11.498 9.57051 -20.7408 -11.3862 9.98075 -20.0409 -10.928 10.112 -20.0996 -10.9081 10.5871 -20.874 -11.2941 11.4354 -21.1888 -11.4149 12.0806 -19.2575 -10.2684 11.495 -18.9481 -10.0407 11.767 -22.0716 -11.7275 14.1113 -23.5666 -12.4922 15.5906 -23.1904 -12.2138 15.926 -23.6485 -12.0949 19.3173 -5.08906 -2.06025 5.48803 -4.90048 -1.94578 5.44977 -4.7932 -1.87366 5.48686 -4.66054 -1.78902 5.49322 -4.53482 -1.70862 5.5026 -4.55272 -1.69985 5.67268 -4.72237 -1.7641 6.0268 -4.64552 -1.70685 6.09953 -4.75909 -1.74078 6.41117 -4.37877 -1.53969 6.09515 -4.32997 -1.49655 6.19925 -4.30233 -1.46178 6.33387 -3.99529 -1.30035 6.07132 -3.78314 -1.18412 5.92719 -3.64389 -1.10217 5.88228 -3.36857 -0.961022 5.61053 -3.27798 -0.902593 5.62184 -3.24697 -0.868933 5.73188 -3.35755 -0.895017 6.09806 -3.47277 -0.920058 6.49509 -3.22984 -0.798029 6.23573 -3.1373 -0.737492 6.2498 -3.15251 -0.71907 6.4835 -2.93562 -0.612643 6.23577 -2.82018 -0.545394 6.18896 -2.77306 -0.503565 6.2938 -2.51501 -0.38905 5.89399 -2.69717 -0.423092 6.5658 -2.63475 -0.373276 6.65032 -2.38294 -0.266785 6.21928 -2.42534 -0.248725 6.59014 -2.33828 -0.1918 6.60349 -2.23911 -0.132752 6.57711 -2.13283 -0.0721108 6.51952 -2.07971 -0.0240578 6.64214 -1.99497 0.0306699 6.6578 -1.95631 0.0792155 6.8558 -1.67983 0.158337 6.0606 -1.61603 0.205839 6.12725 -1.53384 0.255133 6.10455 -1.32458 0.30313 5.40176 -1.2564 0.344567 5.39339 -1.20824 0.388485 5.502 -1.21085 0.445047 5.99576 -1.08858 0.476791 5.61756 -1.01355 0.516948 5.55428 -1.05708 0.626386 6.69144 -0.972394 0.677802 6.67599 -0.828385 0.663806 5.80294 -0.775698 0.736686 6.13193 -0.684014 0.744059 5.71331 -0.647952 0.937054 7.13291 -0.545841 0.850986 5.8864 -0.468421 1.0202 6.88346 -0.379118 1.08544 6.95448 -0.195691 1.51995 9.60575 -0.270852 0.989022 5.58989 -0.199703 1.03884 5.62854 -0.0132699 1.32951 7.07079 -2.3916 -1.16117 -0.576268 -2.45053 -1.19909 -0.561977 -2.50933 -1.23659 -0.545838 -2.56896 -1.27386 -0.527632 -2.64155 -1.32235 -0.517544 -2.70839 -1.3647 -0.500018 -2.7891 -1.41828 -0.489613 -2.85633 -1.46077 -0.467196 -2.93859 -1.51362 -0.451393 -3.02138 -1.56699 -0.432452 -3.10396 -1.61973 -0.410688 -3.20867 -1.68923 -0.397676 -3.30761 -1.75254 -0.376933 -3.40605 -1.81603 -0.352587 -3.521 -1.89057 -0.331401 -3.63542 -1.96515 -0.305932 -3.75886 -2.04484 -0.279149 -3.88934 -2.12912 -0.250905 -4.03689 -2.22506 -0.222974 -4.20068 -2.33124 -0.194603 -4.35644 -2.43151 -0.157476 -4.53742 -2.54868 -0.121024 -4.73424 -2.67652 -0.0816011 -4.94684 -2.81484 -0.0384278 -5.17731 -2.9629 0.00960988 -5.42389 -3.12307 0.0640534 -5.71198 -3.30883 0.120787 -6.00773 -3.50057 0.188182 -6.35366 -3.72363 0.260837 -6.72348 -3.96289 0.344787 -7.15999 -4.24513 0.437968 -7.65376 -4.56396 0.544807 -8.21414 -4.92616 0.669078 -8.93212 -5.39083 0.811889 -9.7156 -5.89717 0.984101 -10.8883 -6.66025 1.19436 -12.2763 -7.56064 1.46093 -14.4447 -8.97382 1.82961 -16.3263 -10.1863 2.26592 -18.9108 -11.8543 2.8503 -25.2353 -15.908 4.50485 -25.4165 -15.9656 5.05139 -25.8799 -16.2059 5.65801 -25.8117 -16.1 6.17803 -25.7288 -15.9841 6.69374 -26.0252 -16.1113 7.30106 -36.8864 -23.0041 10.7416 -37.6317 -23.3883 11.7358 -20.1346 -12.1776 7.11761 -24.8656 -15.1216 9.11138 -20.1836 -12.1086 7.99018 -20.3353 -12.1537 8.481 -20.6954 -12.3278 9.0653 -19.8466 -11.7463 9.16195 -20.1608 -11.8894 9.73933 -26.3734 -15.6713 13.0822 -26.2309 -15.5135 13.612 -24.5012 -14.3856 13.3296 -24.3599 -14.2333 13.8242 -24.0687 -13.8544 15.3947 -5.40199 -2.47177 5.51455 -5.3349 -2.4164 5.60508 -5.21323 -2.33027 5.64183 -5.09085 -2.24475 5.67487 -4.78855 -2.06004 5.51504 -4.79713 -2.04796 5.67474 -4.93527 -2.10348 5.9826 -4.88543 -2.05824 6.09048 -4.72496 -1.95291 6.06707 -4.57811 -1.8553 6.0531 -4.55538 -1.82407 6.19175 -4.54212 -1.79723 6.34587 -4.303 -1.65467 6.20017 -4.22663 -1.59492 6.26527 -4.16425 -1.54353 6.35232 -3.82267 -1.35312 6.02104 -3.58554 -1.21645 5.82398 -3.46249 -1.13793 5.79204 -3.26059 -1.02202 5.62315 -3.54336 -1.13611 6.27243 -3.4554 -1.07313 6.30377 -3.29324 -0.976582 6.19546 -3.26607 -0.942148 6.33409 -3.11649 -0.852884 6.23608 -3.03859 -0.796034 6.2752 -2.87735 -0.7044 6.13415 -2.69599 -0.606301 5.93433 -2.60754 -0.547714 5.9287 -2.57209 -0.509824 6.04876 -2.6172 -0.501637 6.38033 -2.5238 -0.439386 6.37123 -2.3565 -0.352457 6.15463 -2.27726 -0.297451 6.16807 -2.20647 -0.245375 6.20787 -2.23726 -0.224197 6.56977 -2.20094 -0.179417 6.74228 -2.05406 -0.104062 6.53988 -2.24218 -0.110776 7.5685 -1.95445 -0.00414459 6.82155 -1.68983 0.0865421 6.07602 -1.64314 0.133585 6.21158 -1.54658 0.187131 6.12126 -1.33677 0.246988 5.41926 -1.26996 0.29031 5.41149 -1.22296 0.335119 5.5207 -1.2967 0.397005 6.47987 -1.11358 0.42914 5.69638 -1.03618 0.471197 5.61409 -1.05194 0.555427 6.42421 -1.00168 0.627435 6.75698 -0.851961 0.62141 5.84459 -0.778972 0.664139 5.78602 -0.756632 0.804244 6.86058 -0.677832 0.882379 7.07728 -0.578555 0.853743 6.25805 -0.501984 0.866699 5.93509 -0.416214 1.03372 6.87107 -0.313912 1.17095 7.45608 -0.114797 1.58049 9.8162 -0.232412 1.01209 5.62478 --0.130343 1.72194 9.61746 -2.38862 -1.23401 -0.566206 -2.43947 -1.26754 -0.54549 -2.50431 -1.31263 -0.533356 -2.56898 -1.3572 -0.518984 -2.62769 -1.3967 -0.497365 -2.69957 -1.44633 -0.483575 -2.77296 -1.49678 -0.466817 -2.85269 -1.55238 -0.452123 -2.94065 -1.61345 -0.438766 -3.02166 -1.66916 -0.417991 -3.10991 -1.73003 -0.398285 -3.20635 -1.79621 -0.379136 -3.30972 -1.8683 -0.359984 -3.40709 -1.9352 -0.333097 -3.51902 -2.01271 -0.309515 -3.64715 -2.10195 -0.287729 -3.76015 -2.1789 -0.255147 -3.90405 -2.27862 -0.229512 -4.05662 -2.38404 -0.200811 -4.20949 -2.48934 -0.166051 -4.37097 -2.60018 -0.127446 -4.54716 -2.72267 -0.0868624 -4.74845 -2.86164 -0.0451067 -4.97351 -3.01752 -0.000740528 -5.19864 -3.17256 0.052797 -5.46465 -3.35629 0.108146 -5.73886 -3.54429 0.172886 -6.06045 -3.76726 0.242267 -6.41542 -4.01128 0.320946 -6.80291 -4.27877 0.411461 -7.25482 -4.58945 0.512622 -7.76292 -4.94017 0.629787 -8.37646 -5.3638 0.764594 -9.13601 -5.8881 0.922943 -9.98508 -6.47395 1.1145 -11.2879 -7.3776 1.3548 -12.9405 -8.52407 1.66828 -15.0714 -9.99972 2.0861 -17.5656 -11.7214 2.62848 -20.3796 -13.6556 3.31382 -25.8393 -17.4272 4.47863 -27.2143 -18.3247 5.23531 -26.1328 -17.5085 5.61335 -25.7844 -17.2049 6.09321 -25.8904 -17.2174 6.66096 -26.1751 -17.3502 7.27841 -37.5049 -24.8659 12.4558 -24.1069 -15.6965 8.84321 -24.6629 -16.0125 9.56484 -24.5565 -15.8799 10.0669 -41.5956 -26.9118 20.2349 -42.6361 -27.4884 21.7133 -42.8624 -27.409 23.8564 -5.15447 -2.51157 5.62475 -5.08733 -2.45379 5.71164 -5.13923 -2.46771 5.92444 -4.84136 -2.27266 5.76404 -4.80876 -2.23522 5.88534 -4.84139 -2.23666 6.08463 -4.7195 -2.14637 6.10573 -4.56231 -2.03721 6.07934 -4.08241 -1.74532 5.63116 -4.07152 -1.72126 5.76964 -4.27593 -1.81868 6.20806 -4.18408 -1.74813 6.25096 -4.03694 -1.64719 6.21217 -3.92998 -1.5686 6.2251 -3.63145 -1.3886 5.93555 -3.51852 -1.30977 5.92229 -3.40682 -1.23191 5.90574 -3.3407 -1.17768 5.96154 -3.27275 -1.12332 6.01575 -3.26395 -1.09865 6.17994 -3.28303 -1.08608 6.40528 -3.16478 -1.00622 6.37031 -2.96427 -0.886482 6.15564 -2.88059 -0.824969 6.17489 -2.79351 -0.761744 6.1831 -2.62963 -0.663868 6.00818 -2.51167 -0.589119 5.92864 -2.65333 -0.625911 6.49825 -2.47641 -0.524603 6.26854 -2.42025 -0.475786 6.35067 -2.31671 -0.407998 6.3004 -2.26832 -0.361097 6.40791 -2.26399 -0.328518 6.66625 -2.1829 -0.268338 6.68722 -2.05183 -0.192063 6.53349 -2.00863 -0.143686 6.68473 -2.62441 -0.268908 9.47735 -1.65421 0.0583866 6.2372 -1.59349 0.111379 6.31373 -1.34356 0.188133 5.41723 -1.28013 0.233787 5.41966 -1.3851 0.275785 6.45709 -1.28738 0.331518 6.33033 -1.14749 0.377901 5.85469 -1.05445 0.42232 5.65363 -1.01735 0.478967 5.92804 -0.996731 0.555433 6.46974 -0.897505 0.594446 6.18454 -0.799771 0.62049 5.79805 -0.738686 0.680316 5.94763 -0.702276 0.818786 6.94174 -0.621212 0.895334 7.10755 -0.528544 0.831479 5.94903 -0.450243 0.985694 6.82709 -0.362051 1.07507 7.05638 -0.176639 1.49987 9.64834 -0.266094 0.974832 5.56139 -0.196136 1.03255 5.62938 -0.00655881 1.33713 7.12994 -2.31517 -1.25436 -0.559577 -2.37709 -1.30043 -0.550624 -2.43399 -1.34157 -0.534011 -2.49732 -1.38812 -0.52063 -2.55466 -1.42955 -0.499806 -2.62495 -1.48209 -0.486713 -2.7028 -1.53911 -0.476052 -2.76041 -1.58027 -0.448588 -2.83186 -1.63256 -0.427856 -2.92457 -1.70169 -0.41726 -3.00382 -1.75977 -0.394846 -3.1052 -1.83462 -0.381183 -3.19217 -1.89826 -0.356115 -3.29449 -1.97384 -0.334713 -3.39652 -2.04855 -0.309518 -3.51382 -2.13492 -0.286822 -3.62413 -2.21582 -0.256222 -3.75799 -2.31398 -0.230041 -3.89123 -2.41193 -0.198508 -4.04861 -2.52789 -0.169228 -4.19818 -2.63697 -0.131291 -4.37864 -2.77104 -0.0958922 -4.54415 -2.8917 -0.0491173 -4.75599 -3.04792 -0.00699401 -4.97695 -3.21015 0.0424062 -5.22133 -3.38985 0.0963656 -5.481 -3.58024 0.15758 -5.75759 -3.78247 0.227559 -6.08854 -4.02568 0.301696 -6.45933 -4.29775 0.385628 -6.85458 -4.5867 0.483314 -7.32019 -4.92841 0.593121 -7.86547 -5.32948 0.719699 -8.5054 -5.79902 0.867356 -9.29665 -6.38023 1.04256 -10.2452 -7.07775 1.25545 -11.7605 -8.19735 1.53434 -13.6079 -9.56084 1.90087 -15.4208 -10.8882 2.34436 -18.8565 -13.4212 3.04431 -30.9556 -22.2467 6.35767 -28.6545 -20.4759 6.57193 -27.4303 -19.509 6.92279 -31.2547 -22.247 8.43624 -16.9401 -11.0338 11.6117 -4.79133 -2.44697 5.75558 -4.60214 -2.30909 5.69771 -4.552 -2.26171 5.79531 -4.90375 -2.46423 6.37935 -4.29213 -2.06378 5.79045 -4.34421 -2.07944 6.01537 -4.10969 -1.91753 5.86718 -4.28294 -2.00456 6.26773 -4.15379 -1.90829 6.25836 -4.00959 -1.80249 6.22115 -3.94091 -1.74258 6.29111 -3.61567 -1.53176 5.95613 -3.53457 -1.46715 5.99336 -3.43836 -1.39287 6.00344 -3.35323 -1.32574 6.02778 -3.26753 -1.25792 6.04966 -3.20386 -1.20295 6.11196 -3.1494 -1.15321 6.19041 -3.07508 -1.09239 6.23271 -2.96289 -1.01061 6.19396 -2.95441 -0.98478 6.37426 -2.7988 -0.882042 6.23267 -3.53445 -1.22956 8.17268 -2.68353 -0.778426 6.38169 -2.62471 -0.725733 6.45905 -2.54075 -0.660481 6.47064 -2.39272 -0.566029 6.30321 -2.2766 -0.487897 6.20671 -2.1904 -0.424472 6.19162 -2.15768 -0.383522 6.34491 -2.06015 -0.315339 6.28853 -2.01253 -0.266384 6.40179 -1.95851 -0.21483 6.50474 -1.89578 -0.158909 6.57779 -1.83319 -0.102354 6.65914 -1.77499 -0.0473183 6.7688 -1.43241 0.0776231 5.51757 -1.33692 0.132822 5.35542 -1.28741 0.177822 5.42709 -1.24174 0.223596 5.52734 -1.31341 0.266472 6.42785 -1.2249 0.324682 6.33924 -1.07282 0.370255 5.70325 -1.01884 0.423398 5.80882 -1.01221 0.498234 6.45061 -0.955098 0.567032 6.68368 -0.865156 0.616745 6.51692 -0.752852 0.626265 5.82049 -0.7277 0.765954 6.92515 -0.64684 0.832544 6.97223 -0.555831 0.819237 6.22159 -0.483601 0.86166 6.10672 -0.399956 1.00384 6.82408 -0.299333 1.14475 7.41876 -0.103344 1.54543 9.72972 -0.225733 1.00751 5.64536 --0.144472 1.73434 9.73633 -2.25924 -1.28883 -0.569632 -2.30832 -1.32637 -0.550096 -2.36313 -1.36827 -0.534597 -2.42509 -1.41675 -0.522012 -2.47356 -1.4541 -0.49722 -2.54274 -1.50768 -0.485412 -2.61225 -1.56286 -0.470753 -2.68181 -1.61653 -0.45386 -2.75096 -1.67061 -0.434337 -2.82813 -1.73117 -0.416245 -2.91255 -1.79695 -0.399416 -2.99002 -1.85736 -0.37517 -3.08217 -1.92873 -0.355783 -3.18103 -2.007 -0.336293 -3.28155 -2.08483 -0.312766 -3.38155 -2.16277 -0.285249 -3.49658 -2.25329 -0.259936 -3.61223 -2.34299 -0.22993 -3.74899 -2.45134 -0.203802 -3.87991 -2.55333 -0.169164 -4.04111 -2.67951 -0.139038 -4.18002 -2.78685 -0.0952985 -4.36427 -2.93106 -0.0586638 -4.54136 -3.06932 -0.0119842 -4.74913 -3.23196 0.0348812 -4.97233 -3.40568 0.0872508 -5.22548 -3.60493 0.143606 -5.4878 -3.80867 0.209472 -5.78785 -4.04367 0.281201 -6.12762 -4.30884 0.361365 -6.50571 -4.60434 0.452571 -6.91422 -4.92235 0.557706 -7.40816 -5.30815 0.676291 -7.94864 -5.7286 0.815114 -8.63579 -6.26583 0.97664 -9.49434 -6.93752 1.17102 -10.6785 -7.86663 1.41533 -12.1109 -8.98834 1.72686 -14.2826 -10.6932 2.16238 -16.2466 -12.2229 2.67276 -34.723 -26.5948 7.64536 -34.5421 -26.3725 8.37449 -36.5901 -27.8916 9.62884 -38.6018 -29.1917 12.707 -40.081 -30.2414 14.0704 -39.1359 -28.4318 24.0735 -16.2805 -11.3504 11.2734 -4.65585 -2.56812 5.65814 -4.55449 -2.48245 5.69672 -4.45336 -2.39748 5.73218 -4.20136 -2.21018 5.57911 -4.3886 -2.32003 5.96745 -4.11153 -2.11823 5.76812 -3.95691 -1.99837 5.71535 -4.05885 -2.04988 6.01447 -3.98406 -1.98265 6.07194 -3.98117 -1.96346 6.23699 -3.91285 -1.90134 6.30791 -3.65862 -1.71952 6.08016 -3.44475 -1.56616 5.90018 -3.32818 -1.47641 5.86927 -3.29289 -1.4361 5.97585 -3.50921 -1.55023 6.54556 -3.18514 -1.33351 6.12895 -3.10033 -1.26338 6.14781 -3.06266 -1.2213 6.26008 -2.99003 -1.15789 6.30171 -2.83185 -1.04595 6.15579 -2.80723 -1.01111 6.29945 -2.68847 -0.922095 6.22691 -3.41582 -1.29872 8.23959 -2.57049 -0.813891 6.36442 -2.4899 -0.747338 6.37617 -2.21686 -0.582333 5.84718 -2.13672 -0.519269 5.83251 -2.02999 -0.443441 5.73106 -2.0905 -0.44798 6.15649 -2.04999 -0.402746 6.28058 -1.99272 -0.348717 6.35611 -1.94184 -0.296835 6.45932 -1.8785 -0.239519 6.52317 -1.59616 -0.101751 5.66423 -1.53262 -0.04848 5.67285 -1.41902 0.0187228 5.44559 -1.34669 0.0717241 5.39174 -1.29131 0.119591 5.4246 -1.23955 0.167192 5.48585 -1.34217 0.198274 6.56412 -1.18474 0.263568 5.98135 -1.08634 0.317205 5.73217 -1.03326 0.370308 5.83864 -1.02785 0.439799 6.46117 -0.945897 0.496132 6.36628 -0.885534 0.563602 6.54853 -0.800255 0.614015 6.37044 -0.74972 0.708773 6.87844 -0.671983 0.77784 6.94627 -0.594038 0.859768 7.12147 -0.509057 0.810443 6.00167 -0.430929 0.961575 6.83974 -0.34303 1.06413 7.1481 -0.160869 1.46579 9.58168 -0.257982 0.968537 5.58215 -0.190882 1.02864 5.63974 --0.00256243 1.3504 7.21846 -2.24509 -1.35383 -0.555387 -2.29949 -1.39783 -0.540369 -2.35256 -1.44217 -0.523524 -2.40743 -1.48652 -0.504588 -2.46094 -1.53117 -0.48363 -2.52838 -1.5872 -0.470475 -2.59637 -1.64382 -0.454472 -2.66418 -1.69989 -0.436037 -2.73905 -1.76226 -0.419252 -2.81468 -1.82423 -0.399622 -2.88987 -1.88651 -0.376973 -2.97206 -1.95491 -0.355195 -3.0694 -2.03628 -0.337276 -3.17366 -2.1235 -0.319061 -3.26398 -2.19765 -0.289932 -3.36912 -2.28543 -0.263201 -3.48135 -2.37793 -0.235592 -3.60089 -2.47808 -0.205712 -3.72842 -2.58296 -0.173861 -3.87033 -2.7018 -0.141485 -4.02796 -2.83265 -0.107692 -4.19296 -2.96965 -0.0693927 -4.3582 -3.1063 -0.0240624 -4.55294 -3.26817 0.0210437 -4.76366 -3.44341 0.0714883 -4.98151 -3.62409 0.129552 -5.23658 -3.83552 0.190241 -5.51511 -4.06685 0.259023 -5.81625 -4.31654 0.337234 -6.16964 -4.61022 0.422899 -6.55306 -4.92857 0.52172 -6.99021 -5.28994 0.634464 -7.48711 -5.70246 0.764546 -8.11264 -6.22154 0.914608 -8.84485 -6.82929 1.09398 -9.75769 -7.5874 1.31152 -10.9888 -8.61304 1.58728 -12.6065 -9.95966 1.948 -14.8991 -11.8692 2.4485 -17.5828 -14.0974 3.1009 -21.0262 -16.9524 3.98527 -38.1282 -30.7135 12.5207 -37.098 -29.5151 15.6848 -4.1779 -2.40147 5.4597 -4.10531 -2.3338 5.51682 -4.09375 -2.31043 5.65119 -4.07403 -2.2812 5.7787 -3.94396 -2.17239 5.75769 -3.8949 -2.12102 5.84543 -3.80257 -2.03928 5.87077 -3.85904 -2.06377 6.11918 -3.72928 -1.9553 6.08676 -3.69944 -1.91809 6.21028 -3.38669 -1.68542 5.86379 -3.31535 -1.61988 5.90709 -3.2163 -1.53606 5.89897 -3.49292 -1.70425 6.58407 -3.42634 -1.63967 6.65374 -3.17726 -1.45664 6.36195 -3.16837 -1.4306 6.53766 -3.00771 -1.30704 6.39921 -2.81533 -1.16485 6.17586 -2.73277 -1.09385 6.18647 -2.66299 -1.0303 6.22201 -2.47955 -0.898396 5.97493 -2.42612 -0.846192 6.04118 -2.36847 -0.790846 6.09727 -2.32139 -0.74229 6.18897 -2.1224 -0.607238 5.83209 -2.00861 -0.522683 5.70348 -1.95686 -0.472825 5.76042 -2.06773 -0.505995 6.37656 -1.97375 -0.431493 6.31943 -1.93991 -0.386513 6.48067 -1.86131 -0.31934 6.47752 -1.64638 -0.194257 5.89136 -1.51173 -0.109781 5.59047 -1.40898 -0.0412844 5.40268 -1.33475 0.0155423 5.32953 -1.30616 0.0569682 5.50019 -1.23895 0.110186 5.46363 -1.16856 0.163983 5.39566 -1.17193 0.206117 5.84103 -1.10329 0.260956 5.81058 -1.04807 0.31588 5.88781 -0.987931 0.372876 5.93367 -0.963548 0.441256 6.41669 -0.9063 0.510173 6.60963 -0.828969 0.570945 6.5518 -0.765596 0.646932 6.78165 -0.69221 0.719146 6.86986 -0.618159 0.803327 7.07578 -0.53247 0.778824 6.10522 -0.463129 0.86112 6.32796 -0.381116 0.982676 6.84647 -0.200704 1.43485 9.81962 -0.0768803 1.55249 9.92978 --0.0360525 1.63656 9.80997 --0.164605 1.75826 9.92391 -2.17547 -1.37429 -0.554823 -2.22754 -1.42 -0.540722 -2.28045 -1.46554 -0.524749 -2.33859 -1.51724 -0.512029 -2.3917 -1.56402 -0.491649 -2.45682 -1.62176 -0.479411 -2.51715 -1.67361 -0.459711 -2.58241 -1.73242 -0.442287 -2.64314 -1.78443 -0.417793 -2.71527 -1.84895 -0.39949 -2.79541 -1.91991 -0.382326 -2.87629 -1.99037 -0.361928 -2.9639 -2.06782 -0.341815 -3.05846 -2.15121 -0.321795 -3.14606 -2.2292 -0.294162 -3.24798 -2.31874 -0.269635 -3.35033 -2.40852 -0.240705 -3.46742 -2.51169 -0.213101 -3.58392 -2.61473 -0.180533 -3.7222 -2.73741 -0.150746 -3.86078 -2.85995 -0.114805 -4.00775 -2.98901 -0.0750142 -4.17532 -3.13684 -0.0352079 -4.35091 -3.29179 0.0102984 -4.54768 -3.46618 0.0582791 -4.75354 -3.64653 0.113731 -4.98723 -3.85305 0.172541 -5.24347 -4.07943 0.238545 -5.55102 -4.35132 0.308577 -5.85903 -4.6225 0.392768 -6.21849 -4.94022 0.48627 -6.60693 -5.28218 0.593877 -7.06903 -5.68887 0.715528 -7.59022 -6.14808 0.857248 -8.25112 -6.73158 1.02275 -8.99255 -7.38508 1.22054 -10.0597 -8.32878 1.46743 -11.5178 -9.62045 1.7909 -13.4568 -11.337 2.22671 -15.6653 -13.2863 2.78422 -29.8422 -25.7205 7.17309 -30.7428 -26.4511 8.07639 -37.3132 -32.0098 12.2385 -4.14104 -2.54944 5.78157 -3.94285 -2.37916 5.67151 -3.81661 -2.26715 5.65027 -3.76956 -2.21644 5.73718 -3.71202 -2.15702 5.80797 -3.60709 -2.06277 5.80765 -3.71131 -2.12609 6.13366 -3.56139 -1.99712 6.05944 -3.55063 -1.97301 6.21355 -3.50551 -1.92162 6.31113 -3.46646 -1.87581 6.42452 -3.52417 -1.9 6.72147 -3.48366 -1.85081 6.84436 -3.37664 -1.75504 6.83871 -3.01561 -1.47888 6.2946 -3.24224 -1.61924 6.98325 -3.18364 -1.55723 7.07538 -2.72785 -1.22391 6.24261 -2.66223 -1.15933 6.2881 -3.10632 -1.43479 7.62406 -2.40111 -0.946859 6.03769 -2.31136 -0.868837 6.00259 -2.11582 -0.724386 5.65968 -1.95221 -0.603006 5.37544 -1.92969 -0.570151 5.50695 -1.84446 -0.498704 5.44047 -1.90053 -0.510685 5.85512 -1.97419 -0.52763 6.36821 -1.93068 -0.477531 6.4919 -1.66055 -0.306986 5.70932 -1.57595 -0.238504 5.62423 -1.46374 -0.158261 5.4007 -1.40661 -0.104773 5.4079 -1.33727 -0.0470492 5.35506 -1.30787 -0.00524555 5.51642 -1.2405 0.0513364 5.47056 -1.19487 0.100461 5.55156 -1.12948 0.155879 5.51258 -1.12798 0.200229 5.96789 -1.02498 0.26153 5.62854 -0.998774 0.317467 5.96323 -0.966471 0.38101 6.32731 -0.916405 0.450218 6.57078 -0.844983 0.515751 6.57338 -0.789099 0.598045 6.9034 -0.709102 0.660116 6.80304 -0.639686 0.745361 7.03991 -0.562964 0.824075 7.12506 -0.487703 0.79385 6.09376 -0.408473 0.93715 6.85221 -0.229198 1.4388 10.3845 -0.1408 1.44185 9.58415 -0.00283311 1.61032 10.0391 --0.0975778 1.67598 9.76945 -0.0116313 1.31359 7.02246 -2.11335 -1.39675 -0.560031 -2.16428 -1.4434 -0.546729 -2.20265 -1.47905 -0.52071 -2.25944 -1.53273 -0.508981 -2.31704 -1.58614 -0.494991 -2.37425 -1.64004 -0.47876 -2.43858 -1.70039 -0.46486 -2.49642 -1.7535 -0.444033 -2.56016 -1.81375 -0.425266 -2.62565 -1.87386 -0.403728 -2.70326 -1.94759 -0.38777 -2.77438 -2.01403 -0.364692 -2.85973 -2.09339 -0.346371 -2.93811 -2.16734 -0.320438 -3.03688 -2.26047 -0.301811 -3.12291 -2.3398 -0.272347 -3.22182 -2.43231 -0.245522 -3.33526 -2.53924 -0.220118 -3.44215 -2.63872 -0.186912 -3.56966 -2.7587 -0.156995 -3.70463 -2.88512 -0.123836 -3.8399 -3.0114 -0.0846198 -3.99559 -3.15756 -0.0458709 -4.16619 -3.31825 -0.00365269 -4.33721 -3.47749 0.0460802 -4.53695 -3.66455 0.0973482 -4.74968 -3.8641 0.154565 -4.98504 -4.08376 0.217906 -5.2563 -4.33846 0.286902 -5.54118 -4.60487 0.366443 -5.88319 -4.92599 0.453141 -6.24025 -5.25931 0.554714 -6.65397 -5.64594 0.66967 -7.12577 -6.0864 0.802242 -7.68226 -6.60754 0.956156 -8.35373 -7.23649 1.13805 -9.23371 -8.06128 1.35967 -10.3513 -9.10873 1.63787 -11.9208 -10.5833 2.00817 -13.9283 -12.4656 2.50154 -16.1897 -14.5814 3.12554 -28.7902 -26.3452 6.85116 -28.8222 -26.3132 7.54509 -35.5301 -31.9827 16.0451 -34.3168 -30.7054 17.2675 -4.68829 -3.35172 5.13631 -4.43048 -3.11448 5.01942 -4.40792 -3.08195 5.13415 -4.55669 -3.11021 6.40708 -4.55066 -3.08804 6.57771 -3.74039 -2.3972 5.6162 -3.68024 -2.33412 5.68124 -3.53374 -2.19902 5.61535 -3.53771 -2.18889 5.77536 -3.44219 -2.09591 5.78013 -3.35643 -2.01216 5.79769 -3.28502 -1.94014 5.83665 -3.19549 -1.85296 5.84092 -3.1278 -1.78529 5.8836 -3.06943 -1.72321 5.94089 -2.99278 -1.6471 5.96291 -2.78314 -1.46883 5.71049 -2.84766 -1.50307 6.01773 -2.66391 -1.34738 5.79886 -2.76703 -1.40783 6.21337 -2.48723 -1.1817 5.74808 -2.50573 -1.17859 5.97777 -2.39202 -1.07824 5.88486 -2.38033 -1.05129 6.05151 -2.0754 -0.816938 5.4134 -2.01805 -0.760062 5.43668 -1.93593 -0.68547 5.38401 -1.91181 -0.650917 5.50659 -1.905 -0.626981 5.69495 -1.76265 -0.51534 5.42971 -1.96348 -0.620805 6.38753 -1.70386 -0.436285 5.66969 -1.66704 -0.391791 5.77942 -1.51393 -0.27893 5.39571 -1.40047 -0.192884 5.14293 -1.3498 -0.142192 5.15957 -1.34678 -0.115999 5.42921 -1.30488 -0.0672732 5.51273 -1.24671 -0.0110941 5.51647 -1.16993 0.0512371 5.3908 -1.1112 0.105972 5.3717 -1.22131 0.117797 6.67012 -1.01679 0.20912 5.51807 -0.958364 0.263985 5.50502 -0.92054 0.319976 5.70953 -0.8598 0.375963 5.68393 -0.857081 0.458369 6.56452 -0.7938 0.529735 6.68605 -0.730004 0.608998 6.87545 -0.656102 0.679491 6.87366 -0.581505 0.745755 6.82024 -0.507665 0.755908 6.1475 -0.433802 0.898054 6.92707 -0.360573 0.962894 6.86843 -0.177025 1.40762 9.81208 -0.0499114 1.55353 10.09 --0.0475451 1.62084 9.79139 --0.178018 1.76742 10.023 -2.08802 -1.45387 -0.54141 -2.13651 -1.50189 -0.527469 -2.19193 -1.55747 -0.516439 -2.2416 -1.60696 -0.498067 -2.29136 -1.65506 -0.477946 -2.34706 -1.71045 -0.460566 -2.40965 -1.77325 -0.445319 -2.47131 -1.83432 -0.427958 -2.53427 -1.89719 -0.407529 -2.60354 -1.96516 -0.38897 -2.67311 -2.03463 -0.367171 -2.74247 -2.10347 -0.342551 -2.82508 -2.18495 -0.322518 -2.91416 -2.27429 -0.30228 -3.00369 -2.36393 -0.277833 -3.08697 -2.44535 -0.24656 -3.18983 -2.54847 -0.220542 -3.30643 -2.66471 -0.195776 -3.41006 -2.76808 -0.15988 -3.53452 -2.89094 -0.127177 -3.67213 -3.02841 -0.0934844 -3.81001 -3.16564 -0.0532472 -3.969 -3.32381 -0.0127704 -4.13408 -3.48865 0.0332619 -4.32107 -3.67413 0.0819896 -4.50109 -3.85254 0.141246 -4.73626 -4.08615 0.197857 -4.97089 -4.3204 0.26598 -5.23382 -4.58121 0.341184 -5.53897 -4.8845 0.424192 -5.87742 -5.22209 0.518454 -6.24535 -5.58606 0.627143 -6.66794 -6.0066 0.751343 -7.15303 -6.48806 0.894678 -7.7354 -7.06644 1.06191 -8.42938 -7.75622 1.26117 -9.40191 -8.72564 1.50919 -10.766 -10.0859 1.83539 -12.2467 -11.5594 2.24149 -14.8668 -14.1739 2.86588 -16.5132 -15.7972 3.47234 -26.1544 -25.3794 6.21434 -26.5545 -25.7231 6.94541 -26.2754 -25.3891 7.528 -34.3938 -33.3332 11.2816 -34.1528 -33.0218 12.0641 -34.1308 -32.9258 12.9164 -33.4618 -32.0442 15.2429 -33.426 -31.707 18.7468 -32.3736 -30.6087 19.0548 -4.38388 -3.31321 5.03925 -4.31505 -3.23709 5.10615 -4.2802 -3.19249 5.2086 -4.32792 -3.22419 5.4067 -4.63421 -3.49173 5.91683 -4.23207 -3.11058 5.59161 -3.95209 -2.84293 5.3922 -3.93941 -2.81827 5.52127 -3.98743 -2.84875 5.73576 -4.24183 -3.06506 6.24844 -4.03924 -2.8681 6.13007 -3.62995 -2.48976 5.69158 -3.49693 -2.35864 5.6429 -3.46769 -2.31869 5.74991 -3.41738 -2.26106 5.82576 -3.33753 -2.17783 5.85292 -3.27203 -2.10634 5.90148 -3.33093 -2.14307 6.17484 -3.25689 -2.06401 6.21417 -2.978 -1.81215 5.85374 -2.96379 -1.78392 5.99319 -2.77436 -1.6105 5.77699 -2.78612 -1.60526 5.97342 -3.04379 -1.80252 6.73387 -2.5698 -1.39626 5.84596 -3.38662 -2.04304 8.00074 -2.34508 -1.18371 5.65972 -2.36934 -1.18689 5.90647 -2.30428 -1.11886 5.92871 -2.2592 -1.0658 6.00403 -2.04279 -0.883233 5.58177 -1.91705 -0.770513 5.39225 -1.85548 -0.707615 5.39391 -1.79221 -0.644409 5.38489 -1.79641 -0.629228 5.61007 -1.69526 -0.538486 5.46558 -1.69024 -0.514715 5.68063 -1.55284 -0.402433 5.36864 -1.49901 -0.345792 5.37979 -1.40631 -0.265543 5.21507 -1.37376 -0.223118 5.31994 -1.29396 -0.153578 5.18995 -1.24137 -0.0996411 5.19461 -1.23999 -0.0720987 5.50313 -1.18077 -0.0136123 5.48633 -1.10944 0.0501813 5.36917 -1.23226 0.0436985 6.75664 -1.11997 0.127911 6.40012 -0.959754 0.212005 5.48408 -0.982304 0.262376 6.33668 -0.859186 0.323884 5.60437 -0.866599 0.399418 6.56528 -0.805647 0.471446 6.67759 -0.745524 0.551967 6.89771 -0.673181 0.623345 6.87671 -0.600394 0.692456 6.81385 -0.527497 0.726929 6.35072 -0.462323 0.783239 6.24537 -0.385559 0.917891 6.89412 -0.20885 1.37219 10.0897 -0.115728 1.43124 9.67533 --0.0158194 1.60131 10.0899 --0.106187 1.66469 9.76047 --0.308225 1.96579 10.8746 -2.02368 -1.47279 -0.547378 -2.06637 -1.51623 -0.528427 -2.1197 -1.5726 -0.518609 -2.16167 -1.61719 -0.495955 -2.21544 -1.67383 -0.48183 -2.26979 -1.73117 -0.465343 -2.32398 -1.78803 -0.446716 -2.38432 -1.85113 -0.430541 -2.43891 -1.90815 -0.407121 -2.49938 -1.97226 -0.385565 -2.57295 -2.05024 -0.369567 -2.64002 -2.12092 -0.346448 -2.72012 -2.20524 -0.327913 -2.78748 -2.27575 -0.298541 -2.87981 -2.37464 -0.279915 -2.96756 -2.46659 -0.253537 -3.06099 -2.56506 -0.226495 -3.16701 -2.67751 -0.201115 -3.26722 -2.78367 -0.167616 -3.37521 -2.89561 -0.132337 -3.50209 -3.03049 -0.0990001 -3.63542 -3.1715 -0.0621538 -3.78277 -3.32705 -0.0229316 -3.92939 -3.48204 0.0232006 -4.10362 -3.66591 0.0694851 -4.28482 -3.85637 0.122711 -4.47856 -4.06132 0.181891 -4.69377 -4.2872 0.246882 -4.93472 -4.54233 0.318138 -5.21022 -4.83285 0.396875 -5.53244 -5.17316 0.483965 -5.86174 -5.51933 0.58668 -6.23691 -5.91607 0.703103 -6.67432 -6.3762 0.836528 -7.19117 -6.92201 0.991314 -7.76928 -7.52992 1.17322 -8.55683 -8.36242 1.39411 -9.54719 -9.40846 1.66899 -10.9305 -10.871 2.03184 -12.705 -12.7455 2.51247 -15.2979 -15.4864 3.2041 -25.4986 -26.2127 6.62176 -25.2715 -25.9198 7.21022 -25.7062 -26.3278 7.97174 -33.2469 -34.2245 10.8983 -32.0763 -32.9239 11.3719 -32.6976 -33.5095 12.4224 -32.9039 -33.6566 13.3532 -32.4918 -33.0183 15.7765 -4.47463 -3.65213 5.20602 -4.39979 -3.56625 5.27222 -4.23027 -3.38699 5.22959 -4.1675 -3.31351 5.30114 -4.18469 -3.31884 5.46829 -4.07688 -3.20051 5.48431 -4.01652 -3.12949 5.557 -3.90304 -3.00743 5.55891 -3.94413 -3.03536 5.76728 -3.66958 -2.75691 5.5352 -3.61352 -2.69198 5.60394 -3.56127 -2.63001 5.67815 -3.79189 -2.83562 6.19373 -3.42725 -2.47651 5.77668 -3.40578 -2.44347 5.90022 -3.30068 -2.33171 5.88277 -3.1959 -2.22089 5.86114 -3.27544 -2.28185 6.17409 -3.32745 -2.31509 6.45098 -2.9788 -1.97889 5.94768 -2.87767 -1.87263 5.91348 -2.84504 -1.82997 6.01941 -2.73347 -1.71397 5.95386 -2.82737 -1.78431 6.35017 -2.4802 -1.45923 5.72409 -2.86503 -1.78439 6.85091 -2.48547 -1.43495 6.1059 -2.39023 -1.33629 6.05227 -2.29265 -1.23644 5.98637 -2.4846 -1.38201 6.74526 -2.18957 -1.11556 6.10146 -1.90631 -0.863775 5.43646 -1.83252 -0.788301 5.39295 -1.7599 -0.713635 5.34693 -1.80182 -0.728838 5.70379 -1.68154 -0.617233 5.48502 -1.59097 -0.52982 5.35738 -1.53819 -0.471959 5.3706 -1.48706 -0.41595 5.39208 -1.38719 -0.324817 5.18006 -1.31924 -0.25721 5.10052 -1.31672 -0.23421 5.36044 -1.23728 -0.160608 5.20992 -1.22676 -0.128325 5.45944 -1.18056 -0.0744092 5.51218 -1.12435 -0.0158015 5.50462 -1.05471 0.0495352 5.37664 -1.02104 0.0989741 5.54439 -0.976819 0.154303 5.64177 -0.908474 0.21633 5.48925 -0.869314 0.272756 5.66385 -0.814745 0.332263 5.6778 -0.760513 0.392413 5.69019 -0.760251 0.494899 6.95939 -0.68949 0.569203 6.93919 -0.617536 0.641397 6.86685 -0.547185 0.709787 6.78315 -0.481907 0.734216 6.19962 -0.409069 0.866026 6.86976 -0.240111 1.33057 10.3774 -0.154 1.37314 9.74496 -0.0307622 1.53241 10.0819 --0.0599826 1.60738 9.79268 --0.189762 1.77214 10.0925 -1.95977 -1.48968 -0.553157 -1.99473 -1.52813 -0.529535 -2.03593 -1.57311 -0.509727 -2.09314 -1.63763 -0.504152 -2.13922 -1.6894 -0.485842 -2.19148 -1.74753 -0.470567 -2.24432 -1.80634 -0.452834 -2.3021 -1.87212 -0.437476 -2.35534 -1.93109 -0.414949 -2.41374 -1.99604 -0.3948 -2.47268 -2.06158 -0.371803 -2.5435 -2.14167 -0.354092 -2.61505 -2.22127 -0.333148 -2.68614 -2.30112 -0.308893 -2.75773 -2.38143 -0.281206 -2.85328 -2.4898 -0.2639 -2.93227 -2.57637 -0.232194 -3.02866 -2.68519 -0.205885 -3.13141 -2.8015 -0.177717 -3.23574 -2.91716 -0.14454 -3.33948 -3.03271 -0.1064 -3.46801 -3.17838 -0.0724549 -3.59802 -3.3231 -0.0321394 -3.74577 -3.49003 0.00844824 -3.90841 -3.67141 0.0528944 -4.07684 -3.86024 0.103774 -4.25102 -4.05639 0.161769 -4.45235 -4.28164 0.223323 -4.67947 -4.5363 0.290461 -4.92641 -4.81298 0.36631 -5.21124 -5.13321 0.449779 -5.52986 -5.48987 0.54492 -5.87436 -5.87512 0.654717 -6.27763 -6.32644 0.779701 -6.70612 -6.80604 0.925182 -7.23318 -7.39562 1.09391 -7.85682 -8.0952 1.29364 -8.65812 -8.9927 1.53681 -9.63461 -10.0867 1.83752 -11.393 -12.0651 2.27905 -13.7664 -14.7327 2.89984 -15.5143 -16.6827 3.54221 -24.3029 -26.5292 6.27123 -24.2623 -26.4359 6.89553 -24.2007 -26.3196 7.5143 -24.1457 -26.2099 8.13445 -24.077 -26.0852 8.75026 -24.0339 -25.989 9.37507 -23.938 -25.8343 9.98137 -23.886 -25.7279 10.6047 -23.8148 -25.6001 11.2216 -23.7543 -25.4853 11.8451 -23.7442 -25.4256 12.4958 -30.4306 -32.6968 17.5037 -32.3177 -34.4964 22.306 -31.6397 -33.6111 23.7677 -31.5877 -33.4068 25.699 -4.13386 -3.55603 5.06447 -4.12801 -3.53923 5.19931 -4.1849 -3.58725 5.41072 -3.98476 -3.36603 5.31594 -4.10371 -3.48078 5.61426 -3.93651 -3.294 5.54986 -3.91727 -3.26291 5.67678 -3.72772 -3.05383 5.56651 -3.65905 -2.97138 5.61852 -3.52211 -2.81787 5.56666 -3.496 -2.77985 5.67825 -3.43581 -2.70645 5.73726 -3.38856 -2.64662 5.81726 -3.29956 -2.54482 5.8268 -3.36526 -2.5989 6.10571 -3.19653 -2.417 5.97034 -3.08729 -2.29385 5.93192 -3.12407 -2.31807 6.17326 -3.13203 -2.31219 6.36823 -3.09995 -2.26741 6.49007 -2.9433 -2.09837 6.34258 -2.83506 -1.97828 6.29063 -2.79106 -1.92135 6.38078 -2.84206 -1.95622 6.70432 -2.46159 -1.57646 5.96258 -2.39914 -1.50256 5.99088 -2.34757 -1.43973 6.0447 -2.34807 -1.42469 6.24959 -2.19407 -1.26673 6.01136 -2.14138 -1.20264 6.05977 -1.95486 -1.0181 5.68277 -1.81064 -0.872992 5.40942 -1.77534 -0.826298 5.48598 -1.69601 -0.742283 5.41114 -1.63208 -0.670692 5.38096 -1.57136 -0.60355 5.35849 -1.53167 -0.552563 5.42008 -1.52606 -0.530945 5.64431 -1.36852 -0.385603 5.16362 -1.32406 -0.333006 5.1918 -1.31818 -0.307846 5.43279 -1.22272 -0.216746 5.18534 -1.24505 -0.209603 5.63159 -1.19107 -0.147965 5.63627 -1.11635 -0.0733671 5.49112 -1.04368 -0.00170003 5.32418 -1.0127 0.0460978 5.49229 -0.956098 0.10727 5.45103 -0.908497 0.164548 5.48789 -0.865623 0.221226 5.5934 -0.812634 0.281552 5.58785 -0.763639 0.342446 5.65062 -0.769268 0.433081 6.95079 -0.700324 0.510208 6.92104 -0.632673 0.589588 6.95944 -0.55658 0.619672 6.20782 -0.497165 0.684085 6.15349 -0.429464 0.812714 6.8347 -0.360675 0.897046 6.91589 -0.292576 0.974782 6.90529 -0.0853791 1.42997 9.82549 --0.0347402 1.58828 10.1108 --0.113852 1.65115 9.7316 --0.311329 1.96037 10.865 -1.90218 -1.50937 -0.564924 -1.93034 -1.54294 -0.536024 -1.97482 -1.59532 -0.522626 -2.02505 -1.65607 -0.512257 -2.06999 -1.70876 -0.494746 -2.11456 -1.76202 -0.475287 -2.16531 -1.82161 -0.458766 -2.21032 -1.87516 -0.435097 -2.27192 -1.94891 -0.423204 -2.32874 -2.01678 -0.403848 -2.38537 -2.08408 -0.381963 -2.44881 -2.1586 -0.361433 -2.51085 -2.23325 -0.338102 -2.57966 -2.31497 -0.315445 -2.64898 -2.39717 -0.289454 -2.74203 -2.50843 -0.27384 -2.81156 -2.59022 -0.240526 -2.89854 -2.69438 -0.213192 -2.99809 -2.81253 -0.187522 -3.09185 -2.92441 -0.153829 -3.19788 -3.051 -0.120628 -3.32302 -3.19955 -0.089372 -3.44155 -3.34047 -0.0495358 -3.5786 -3.5049 -0.00969309 -3.71707 -3.66822 0.0372013 -3.87295 -3.85439 0.0859271 -4.04806 -4.06352 0.138185 -4.23007 -4.27905 0.198163 -4.44236 -4.53292 0.261548 -4.65531 -4.78667 0.336369 -4.90628 -5.08439 0.41696 -5.21421 -5.45149 0.50472 -5.51493 -5.80908 0.609427 -5.88546 -6.24979 0.726184 -6.29987 -6.74272 0.861498 -6.75212 -7.28028 1.01937 -7.36224 -8.0067 1.20525 -7.72801 -8.43709 1.41173 -8.38 -9.20917 1.66058 -10.2655 -11.4662 2.07643 -11.9804 -13.5119 2.57258 -24.3078 -28.1612 6.83497 -24.2801 -28.0834 7.48603 -24.2578 -28.0116 8.13989 -31.5455 -36.5158 12.9327 -30.021 -34.3556 17.488 -25.5136 -28.8549 18.0304 -26.2049 -29.5491 20.131 -26.5342 -29.8137 22.0763 -3.97035 -3.62773 5.1061 -3.88304 -3.51097 5.286 -3.877 -3.48336 5.57411 -3.59956 -3.16213 5.34213 -3.48209 -3.02126 5.31852 -3.58322 -3.12478 5.61422 -3.50709 -3.02901 5.65054 -3.5215 -3.03529 5.83004 -3.43469 -2.92802 5.84827 -3.35655 -2.831 5.8781 -3.33582 -2.79749 6.00477 -3.24787 -2.69055 6.01498 -3.1695 -2.59391 6.03768 -3.00925 -2.40866 5.89818 -2.95642 -2.34141 5.96169 -2.92 -2.28963 6.05634 -3.11548 -2.48618 6.65473 -2.97196 -2.32071 6.53616 -2.8723 -2.20164 6.50472 -2.70653 -2.0134 6.30719 -2.78491 -2.08191 6.69885 -2.66593 -1.94431 6.607 -2.34814 -1.60293 5.97295 -2.32685 -1.56773 6.10711 -2.27186 -1.49758 6.15162 -2.19562 -1.40617 6.13136 -2.15151 -1.34768 6.20861 -2.08618 -1.26805 6.2206 -1.79459 -0.967104 5.45333 -1.73096 -0.891427 5.428 -1.68543 -0.833321 5.46627 -1.64157 -0.777089 5.5127 -1.5604 -0.686566 5.40623 -1.54517 -0.656478 5.57366 -1.49367 -0.592468 5.58765 -1.47913 -0.561891 5.78359 -1.3281 -0.412061 5.29178 -1.25294 -0.330535 5.15418 -1.26661 -0.322852 5.52176 -1.22997 -0.272071 5.61642 -1.19421 -0.220768 5.72983 -1.12204 -0.14243 5.59564 -1.05965 -0.0724645 5.50879 -1.00454 -0.00808148 5.46959 -0.955112 0.0523294 5.46871 -0.985365 0.0756377 6.35205 -0.860031 0.171068 5.53235 -0.816872 0.22983 5.62729 -0.766925 0.292273 5.65079 -0.784056 0.373336 7.13139 -0.709924 0.451292 6.96261 -0.644227 0.530523 6.95195 -0.577866 0.607544 6.90957 -0.510702 0.639286 6.19689 -0.453288 0.716195 6.28122 -0.380876 0.847935 6.93126 -0.315099 0.926355 6.91153 -0.12691 1.3487 9.73664 -0.0151326 1.49928 9.97441 --0.0741223 1.59529 9.79354 --0.207744 1.78743 10.2309 -1.85247 -1.5418 -0.588132 -1.86075 -1.55001 -0.536733 -1.89872 -1.59669 -0.518838 -1.94589 -1.65801 -0.509802 -1.99388 -1.71907 -0.498601 -2.03733 -1.77331 -0.480136 -2.08575 -1.83462 -0.464531 -2.13475 -1.89663 -0.446566 -2.18359 -1.95817 -0.42646 -2.24852 -2.04173 -0.417346 -2.28758 -2.08856 -0.383611 -2.34753 -2.16567 -0.364505 -2.41355 -2.24877 -0.34678 -2.47382 -2.32574 -0.321616 -2.53988 -2.40958 -0.297246 -2.61268 -2.5004 -0.273161 -2.70175 -2.61442 -0.255369 -2.78024 -2.71404 -0.226405 -2.85846 -2.81281 -0.193646 -2.94902 -2.92653 -0.162449 -3.0457 -3.04867 -0.1291 -3.15343 -3.18616 -0.0957779 -3.27998 -3.34645 -0.0637165 -3.39423 -3.4909 -0.0206293 -3.53288 -3.66597 0.0205025 -3.67715 -3.84962 0.067487 -3.83973 -4.05614 0.117299 -4.00241 -4.26192 0.175894 -4.18324 -4.49011 0.239359 -4.40063 -4.76557 0.306051 -4.62423 -5.04865 0.383969 -4.88408 -5.37804 0.469395 -5.17995 -5.75306 0.565343 -5.50026 -6.15839 0.676124 -5.8755 -6.63297 0.802423 -6.30413 -7.17654 0.948693 -6.76396 -7.75637 1.11956 -7.30754 -8.44439 1.31986 -7.64118 -8.86057 1.53616 -8.78985 -10.319 1.85131 -10.7577 -12.8219 2.33522 -12.3398 -14.8253 2.87153 -23.5133 -28.9745 6.56999 -25.0804 -30.9251 7.65192 -23.693 -29.1213 7.94653 -7.63241 -8.73587 3.36854 -7.61278 -8.69786 3.5689 -29.8608 -36.7871 12.3471 -28.8941 -35.5129 12.8108 -29.0004 -35.4884 15.4123 -28.4929 -34.7996 16.0086 -24.0486 -28.9493 18.0995 -24.3816 -29.2137 20.7444 -25.2387 -30.2201 22.308 -25.2197 -30.1424 23.1616 -24.6236 -29.3554 23.4923 -28.5661 -34.0747 29.2303 -3.43992 -3.2252 5.2273 -3.38283 -3.14743 5.28576 -3.38107 -3.1367 5.42659 -3.3451 -3.08461 5.51823 -3.31169 -3.03606 5.6161 -3.6057 -3.3736 6.26559 -3.34881 -3.04937 6.16387 -3.25502 -2.9286 6.16281 -3.1534 -2.79844 6.14198 -2.95244 -2.55525 5.91903 -2.87471 -2.45435 5.92756 -2.85415 -2.41967 6.05501 -2.8952 -2.4563 6.3227 -2.83277 -2.37247 6.3685 -2.79497 -2.31755 6.47159 -2.75886 -2.26462 6.58234 -2.7828 -2.27758 6.84742 -2.52397 -1.97413 6.38473 -2.44941 -1.87798 6.38429 -2.26626 -1.66112 6.07086 -2.20339 -1.58079 6.08915 -2.18322 -1.54519 6.23163 -1.95601 -1.28504 5.71961 -1.83629 -1.14269 5.51798 -1.80454 -1.09645 5.60673 -1.72621 -1.00093 5.52772 -1.66683 -0.924532 5.51098 -1.63751 -0.882021 5.61504 -1.54978 -0.776419 5.4721 -1.50652 -0.71868 5.51637 -1.4882 -0.684494 5.67453 -1.42534 -0.60659 5.63046 -1.43931 -0.602515 5.98099 -1.33234 -0.483691 5.70144 -1.38062 -0.50804 6.30558 -1.21971 -0.34144 5.64972 -1.16462 -0.272761 5.6262 -1.11064 -0.204715 5.60095 -1.04545 -0.127423 5.47513 -0.99883 -0.0662754 5.48621 -0.949813 -0.0037636 5.48581 -0.904741 0.0562896 5.52388 -0.862847 0.115161 5.60059 -0.81051 0.179896 5.55627 -0.769409 0.241033 5.68033 -0.779096 0.307818 6.9717 -0.717699 0.389574 7.01383 -0.652623 0.471923 7.00374 -0.588639 0.553684 6.99212 -0.521654 0.586928 6.13994 -0.466491 0.659456 6.1653 -0.397734 0.796404 6.93604 -0.335263 0.876301 6.91724 -0.271008 0.958273 6.91645 -0.0599834 1.41128 9.84694 --0.0484234 1.56287 10.0429 --0.12177 1.63459 9.68285 --0.18853 1.70025 9.34193 -1.7977 -1.55889 -0.543433 -1.83428 -1.60744 -0.526043 -1.87051 -1.65659 -0.506898 -1.91105 -1.71183 -0.49171 -1.96292 -1.78104 -0.484754 -2.00902 -1.84409 -0.470164 -2.05082 -1.89939 -0.4487 -2.09735 -1.96269 -0.429706 -2.14468 -2.02571 -0.408451 -2.20203 -2.1031 -0.393793 -2.24953 -2.16721 -0.36745 -2.30215 -2.2372 -0.343095 -2.37124 -2.33098 -0.327562 -2.43502 -2.41668 -0.304791 -2.49858 -2.5017 -0.279003 -2.56839 -2.59557 -0.252911 -2.6487 -2.70421 -0.229791 -2.72945 -2.81312 -0.202364 -2.81063 -2.92226 -0.170435 -2.90888 -3.05432 -0.142539 -3.00725 -3.18737 -0.109068 -3.11687 -3.33471 -0.0753349 -3.22654 -3.48284 -0.0352494 -3.34884 -3.64734 0.00690216 -3.48197 -3.82655 0.0518481 -3.62095 -4.01338 0.102547 -3.77701 -4.22379 0.156247 -3.95078 -4.45855 0.215018 -4.13677 -4.70849 0.281108 -4.34587 -4.99013 0.353715 -4.57257 -5.29418 0.435574 -4.834 -5.64597 0.526381 -5.12969 -6.04578 0.629252 -5.4727 -6.50795 0.746442 -5.85068 -7.01586 0.882527 -6.27568 -7.58754 1.04094 -6.7697 -8.25175 1.22591 -7.09636 -8.68762 1.43009 -7.42257 -9.11943 1.65337 -7.40286 -9.08115 1.8549 -7.4105 -9.08054 2.05957 -7.39235 -9.04488 2.26047 -7.3656 -8.99814 2.45895 -7.34384 -8.95683 2.65748 -22.5207 -29.45 6.90627 -22.3922 -29.2391 7.52644 -7.26533 -8.81746 3.24583 -7.24666 -8.78129 3.4435 -7.40577 -8.98407 3.70992 -7.86973 -9.59524 4.11471 -7.84788 -9.55323 4.33169 -7.82431 -9.50978 4.54851 -7.80385 -9.46987 4.76719 -23.0226 -29.6249 16.1699 -23.0354 -29.6007 16.9303 -23.4738 -30.1399 18.016 -23.8662 -30.4794 21.5812 -23.8674 -30.3868 23.3012 -24.1139 -30.611 25.3371 -27.8525 -35.4468 30.2593 -3.76447 -3.88698 5.98149 -3.69311 -3.78603 6.03838 -3.57396 -3.62474 6.01497 -3.48989 -3.50866 6.04345 -3.2754 -3.22618 5.84176 -3.21099 -3.13619 5.88962 -3.32589 -3.27141 6.26679 -3.12892 -3.01441 6.0696 -2.94922 -2.77884 5.88603 -2.97398 -2.80082 6.10356 -2.94593 -2.75508 6.21963 -2.90467 -2.69434 6.31117 -2.76548 -2.51136 6.18084 -2.75548 -2.4891 6.3421 -2.73975 -2.45958 6.49605 -2.67811 -2.37317 6.54009 -2.63932 -2.31401 6.64215 -2.47452 -2.10155 6.40551 -2.41447 -2.01721 6.4414 -2.35048 -1.92894 6.46624 -2.11744 -1.63833 5.9725 -2.11022 -1.61754 6.15023 -1.93809 -1.40273 5.7945 -1.78652 -1.21361 5.47633 -1.71653 -1.12007 5.41802 -1.62993 -1.00911 5.29215 -1.61069 -0.975741 5.41485 -1.58567 -0.936613 5.52801 -1.55317 -0.886881 5.61242 -1.66816 -1.00195 6.38079 -1.4395 -0.735253 5.56919 -1.42742 -0.70729 5.7656 -1.32912 -0.587113 5.51816 -1.53778 -0.789154 7.00276 -1.29491 -0.517769 5.90792 -1.31908 -0.523542 6.41572 -1.19061 -0.374939 5.91455 -1.09911 -0.267184 5.61533 -1.03855 -0.189858 5.5104 -0.987151 -0.121919 5.47252 -0.945649 -0.0624056 5.52239 -0.88852 0.00873674 5.41202 -0.851624 0.0652952 5.51902 -0.802394 0.130446 5.47536 -0.761124 0.191812 5.55977 -0.713441 0.255891 5.54319 -0.718365 0.326618 6.95429 -0.659857 0.412455 7.05502 -0.597448 0.49611 7.03415 -0.535947 0.580176 7.03155 -0.478043 0.612062 6.17861 -0.424623 0.688085 6.21276 -0.350934 0.8282 6.96247 -0.290175 0.909575 6.93258 -0.0934167 1.33896 9.84726 --0.00455382 1.47723 9.93578 --0.095933 1.60025 9.90283 --0.222867 1.798 10.3297 -1.73461 -1.56766 -0.549647 -1.76909 -1.61693 -0.533176 -1.79901 -1.65936 -0.50944 -1.83842 -1.71555 -0.495149 -1.87745 -1.77231 -0.478909 -1.92245 -1.83642 -0.465702 -1.96706 -1.901 -0.450157 -2.01151 -1.9651 -0.432472 -2.05677 -2.02896 -0.412622 -2.11182 -2.10814 -0.399271 -2.15723 -2.17306 -0.374237 -2.21264 -2.25225 -0.355411 -2.26832 -2.33292 -0.333248 -2.33391 -2.4276 -0.316127 -2.38509 -2.49986 -0.284172 -2.45167 -2.59545 -0.260091 -2.52854 -2.70681 -0.238979 -2.59054 -2.79377 -0.204133 -2.67903 -2.92121 -0.180784 -2.76694 -3.04853 -0.15247 -2.85047 -3.16788 -0.11631 -2.94509 -3.30269 -0.080664 -3.05517 -3.46162 -0.0465383 -3.16628 -3.62153 -0.00574458 -3.28825 -3.79625 0.0373572 -3.41587 -3.97966 0.0859225 -3.56062 -4.18678 0.136906 -3.71653 -4.41018 0.193631 -3.88253 -4.64943 0.25695 -4.07734 -4.92859 0.324438 -4.28933 -5.23219 0.400988 -4.51207 -5.5509 0.488533 -4.77918 -5.93451 0.58469 -5.0628 -6.34223 0.695847 -5.4031 -6.83029 0.821767 -5.79876 -7.39742 0.967096 -6.2559 -8.05432 1.13811 -6.77483 -8.79693 1.33965 -7.06439 -9.20761 1.55512 -8.19814 -10.8387 1.88103 -9.35071 -12.4932 2.27919 -11.0937 -14.9981 2.84988 -24.0572 -33.5792 7.98724 -24.6975 -34.4634 8.93319 -24.5815 -34.2612 9.65288 -7.46004 -9.66792 3.96883 -7.43992 -9.62904 4.18294 -7.42366 -9.59491 4.39902 -7.41025 -9.56518 4.61755 -22.9577 -31.7255 13.4123 -22.4969 -30.9634 15.3709 -21.9483 -30.15 15.7491 -23.2719 -31.9912 17.4474 -22.0963 -30.1393 20.5077 -22.2253 -30.2429 22.2858 -23.0548 -31.368 23.9834 -22.9827 -31.224 24.8097 -23.621 -32.0743 26.4283 -3.46815 -3.81247 5.22142 -3.37929 -3.68303 5.23768 -3.37449 -3.66899 5.37569 -3.38024 -3.67 5.53475 -3.3713 -3.65035 5.67458 -3.49517 -3.81237 6.03966 -3.21518 -3.42195 5.72782 -3.12551 -3.29156 5.72746 -3.14072 -3.30376 5.91483 -3.12893 -3.28031 6.05945 -3.14956 -3.30001 6.27286 -2.98249 -3.06521 6.11076 -2.81856 -2.8351 5.93999 -2.78596 -2.78235 6.03882 -2.76199 -2.74263 6.16117 -2.64641 -2.57911 6.07164 -2.63162 -2.55079 6.21586 -2.54857 -2.43079 6.19356 -2.45608 -2.29968 6.14257 -2.45131 -2.28317 6.31785 -2.39955 -2.20629 6.37331 -2.35052 -2.13179 6.43579 -2.33297 -2.09888 6.59377 -2.23617 -1.96254 6.51218 -2.19144 -1.8937 6.58797 -2.04544 -1.69358 6.31933 -1.82035 -1.39463 5.74351 -1.75161 -1.29781 5.6975 -1.61219 -1.10992 5.36252 -1.57444 -1.05257 5.41152 -1.53578 -0.995162 5.45971 -1.48813 -0.925735 5.46895 -1.48285 -0.907835 5.67564 -1.44547 -0.849479 5.74006 -1.37742 -0.755619 5.65016 -1.30746 -0.659589 5.53805 -1.5925 -0.980275 7.51481 -1.38962 -0.725139 6.658 -1.29311 -0.598718 6.40732 -1.25127 -0.532285 6.50535 -1.08037 -0.327751 5.59986 -1.01931 -0.244824 5.47574 -0.978505 -0.182863 5.50784 -0.924406 -0.108958 5.41949 -0.881505 -0.0459305 5.42888 -0.843679 0.0131637 5.50646 -0.800006 0.0768653 5.52326 -0.857978 0.0786793 7.35465 -0.786481 0.173807 7.17047 -0.721034 0.262659 7.03421 -0.662749 0.349817 7.08583 -0.603448 0.435993 7.0859 -0.544476 0.529574 7.25382 -0.483192 0.602683 6.94021 -0.435304 0.635937 6.16664 -0.364263 0.77948 7.01713 -0.302824 0.871363 7.07763 -0.250574 0.937435 6.8777 -0.033113 1.3939 9.8577 --0.0688023 1.5532 10.0733 --0.136169 1.6348 9.7325 --0.188767 1.69113 9.30275 -1.67664 -1.58 -0.56187 -1.70455 -1.62343 -0.540318 -1.73777 -1.67326 -0.522992 -1.77579 -1.73134 -0.509303 -1.80926 -1.78256 -0.488251 -1.84703 -1.83986 -0.471059 -1.88954 -1.9052 -0.456628 -1.93264 -1.97127 -0.439934 -1.97047 -2.02936 -0.41639 -2.02345 -2.10938 -0.404444 -2.07577 -2.19073 -0.389575 -2.11481 -2.24873 -0.359074 -2.16748 -2.33008 -0.33873 -2.22573 -2.4193 -0.319275 -2.27968 -2.50074 -0.292753 -2.33798 -2.59072 -0.266751 -2.40586 -2.6954 -0.244426 -2.47517 -2.80064 -0.218062 -2.54971 -2.91432 -0.190638 -2.62845 -3.0361 -0.16179 -2.71356 -3.16538 -0.131083 -2.7931 -3.28745 -0.0925505 -2.89389 -3.44209 -0.0589572 -2.99424 -3.5954 -0.0195265 -3.11615 -3.78281 0.0181071 -3.23826 -3.9698 0.0630636 -3.36622 -4.16441 0.113773 -3.49879 -4.36725 0.170798 -3.66359 -4.62011 0.22785 -3.83376 -4.88082 0.294063 -4.02048 -5.16513 0.36756 -4.22219 -5.47437 0.450271 -4.4616 -5.84173 0.541002 -4.72317 -6.24129 0.644871 -5.02657 -6.70518 0.762171 -5.3737 -7.23597 0.898041 -5.78949 -7.87277 1.05578 -6.26436 -8.59917 1.24226 -6.79766 -9.41489 1.46314 -7.19324 -10.0167 1.70459 -8.34089 -11.7764 2.07066 -9.48021 -13.519 2.50932 -22.7534 -33.8324 7.5647 -23.3948 -34.7872 8.50088 -23.1247 -34.3438 9.15565 -25.7794 -38.2437 14.3405 -21.2443 -31.2741 13.3838 -21.4967 -31.5994 15.0104 -22.6452 -33.2825 17.3687 -21.7737 -31.8377 19.9139 -21.4417 -31.3031 20.433 -21.8914 -31.9159 22.5557 -22.1164 -32.1848 24.5684 -22.5781 -32.842 26.0104 -3.29208 -3.84932 5.24376 -3.25688 -3.79292 5.33685 -3.19722 -3.69181 5.54023 -3.12725 -3.58322 5.57483 -3.10187 -3.53848 5.68423 -3.05878 -3.46914 5.76435 -3.00705 -3.38735 5.82836 -2.9699 -3.32654 5.9201 -2.87662 -3.18302 5.89759 -2.96174 -3.30099 6.24634 -2.69032 -2.89727 5.83151 -2.68415 -2.88075 5.9849 -2.65796 -2.83686 6.09936 -2.59126 -2.73273 6.11631 -2.48168 -2.56713 6.02376 -2.46381 -2.53475 6.15851 -2.36971 -2.39178 6.09187 -2.35214 -2.35924 6.23287 -2.33303 -2.32414 6.37421 -2.2403 -2.18427 6.29932 -2.26926 -2.21706 6.59639 -2.17926 -2.08124 6.5255 -2.13804 -2.01442 6.61095 -2.0251 -1.84566 6.44344 -1.89641 -1.6565 6.1984 -1.72488 -1.40875 5.76404 -1.63708 -1.27821 5.62472 -1.56775 -1.17425 5.54653 -1.5343 -1.11918 5.61496 -1.46083 -1.01054 5.50375 -1.44773 -0.983711 5.6732 -1.39352 -0.900838 5.64315 -1.49995 -1.03303 6.49101 -1.45605 -0.961066 6.55752 -1.41085 -0.890195 6.63241 -1.40002 -0.860624 6.92928 -1.27904 -0.691438 6.49578 -1.12452 -0.481107 5.7341 -1.09646 -0.432772 5.88802 -1.01611 -0.320539 5.59838 -0.961802 -0.238558 5.49297 -0.921267 -0.175755 5.52438 -0.867745 -0.0978235 5.40545 -0.856314 -0.0643727 5.82167 -0.911991 -0.0885047 7.39345 -0.865987 -0.00677972 7.65146 -0.789666 0.0995739 7.36869 -0.729583 0.19223 7.35346 -0.665504 0.284819 7.19631 -0.605775 0.374619 7.10693 -0.547594 0.464351 7.14575 -0.492365 0.510943 6.12367 -0.441022 0.599796 6.37926 -0.377486 0.721574 6.98175 -0.319314 0.811886 7.01324 -0.264754 0.894912 6.95312 -0.0546533 1.33853 10.0167 --0.0294851 1.46759 9.98616 --0.115122 1.59847 9.96255 --0.262225 1.85582 10.7236 -1.6137 -1.5836 -0.568315 -1.63722 -1.62068 -0.541638 -1.67253 -1.67869 -0.530841 -1.69983 -1.72359 -0.506949 -1.74399 -1.79682 -0.503256 -1.7762 -1.8486 -0.481349 -1.81245 -1.90736 -0.462911 -1.84834 -1.96668 -0.442524 -1.88919 -2.03305 -0.424901 -1.94376 -2.12306 -0.4187 -1.98477 -2.19052 -0.395989 -2.0215 -2.25028 -0.3666 -2.0721 -2.33248 -0.34776 -2.12806 -2.42353 -0.329708 -2.17874 -2.50658 -0.30471 -2.23402 -2.59721 -0.28043 -2.29459 -2.69652 -0.256161 -2.36522 -2.81258 -0.23476 -2.426 -2.91146 -0.203071 -2.50727 -3.04334 -0.179359 -2.57725 -3.1597 -0.144988 -2.6536 -3.2836 -0.108953 -2.73981 -3.42365 -0.0731599 -2.84576 -3.59776 -0.0411565 -2.94628 -3.76343 -0.000260293 -3.05818 -3.94607 0.043362 -3.17403 -4.13601 0.0919117 -3.30556 -4.35134 0.14325 -3.43699 -4.56694 0.203277 -3.5952 -4.82345 0.265287 -3.77737 -5.12274 0.332064 -3.96478 -5.42946 0.409849 -4.17344 -5.76996 0.497055 -4.41192 -6.16091 0.594585 -4.68121 -6.60092 0.705185 -4.99559 -7.11711 0.831722 -5.35159 -7.6993 0.97863 -5.77967 -8.39816 1.15078 -6.29368 -9.23957 1.3565 -6.89397 -10.2219 1.60426 -7.5491 -11.293 1.89941 -8.56936 -12.9633 2.29612 -10.3145 -15.8214 2.89936 -12.5481 -19.4794 3.73094 -23.1256 -36.7761 8.4092 -25.4814 -40.5328 12.6459 -21.053 -33.2069 13.5296 -21.8413 -34.2967 20.538 -21.0009 -32.8834 21.4529 -21.5602 -33.7365 23.8 -3.33073 -4.23858 5.30824 -3.24017 -4.08805 5.31776 -3.13777 -3.92062 5.30336 -3.08827 -3.83682 5.36956 -3.03744 -3.75109 5.43337 -3.05998 -3.78283 5.62652 -3.00092 -3.68255 5.67461 -3.00063 -3.67768 5.83456 -2.92128 -3.54694 5.84311 -2.76645 -3.29703 5.69249 -2.67563 -3.14766 5.66063 -2.61676 -3.05069 5.69303 -2.59255 -3.00675 5.79992 -2.54038 -2.91951 5.84407 -2.5688 -2.95869 6.08436 -2.57452 -2.96268 6.27975 -2.5312 -2.88811 6.35445 -2.41337 -2.69875 6.22972 -2.31898 -2.54641 6.15724 -2.26508 -2.45481 6.1899 -2.22152 -2.38222 6.25475 -2.19443 -2.33275 6.36974 -2.14877 -2.25697 6.43227 -2.12092 -2.20682 6.55465 -2.0462 -2.08573 6.51712 -1.9682 -1.9588 6.45827 -1.90994 -1.86244 6.46815 -1.83278 -1.73575 6.39391 -1.64491 -1.44299 5.84795 -1.57807 -1.33509 5.7816 -1.4709 -1.16686 5.51709 -1.53949 -1.26214 6.07205 -1.38171 -1.01837 5.52851 -1.35689 -0.974249 5.64066 -1.31537 -0.904974 5.66663 -1.41048 -1.03611 6.51619 -1.35744 -0.949839 6.52421 -1.31281 -0.873868 6.57876 -1.1125 -0.576393 5.5035 -1.10563 -0.556264 5.78492 -1.04379 -0.458344 5.63588 -1.01756 -0.410734 5.79863 -0.963039 -0.324161 5.69484 -0.9102 -0.240579 5.58877 -0.869259 -0.172439 5.59983 -0.821272 -0.0951153 5.50992 -0.775466 -0.0218503 5.42839 -0.844067 -0.0750574 7.49873 -0.784888 0.0231915 7.48622 -0.727489 0.118439 7.51203 -0.648172 0.22522 6.71592 -0.605405 0.311376 7.23733 -0.550128 0.404694 7.31719 -0.495223 0.465023 6.27559 -0.447412 0.545378 6.32213 -0.398009 0.627838 6.37692 -0.329074 0.762931 7.08783 -0.271897 0.857947 7.128 -0.225665 0.928776 6.93793 -0.00194249 1.38667 9.9376 --0.0882676 1.53926 10.0639 --0.152482 1.63747 9.80192 --0.194288 1.69137 9.32264 -1.57897 -1.62988 -0.554282 -1.60449 -1.67483 -0.532772 -1.6383 -1.73437 -0.521019 -1.66877 -1.78632 -0.501981 -1.70307 -1.84626 -0.486505 -1.74115 -1.91408 -0.474106 -1.77591 -1.97435 -0.454615 -1.81857 -2.04973 -0.44274 -1.85376 -2.11026 -0.418942 -1.89659 -2.18674 -0.402076 -1.94021 -2.26289 -0.382657 -1.97954 -2.33131 -0.356461 -2.03248 -2.42302 -0.340132 -2.07604 -2.49959 -0.312706 -2.12903 -2.5921 -0.290024 -2.19117 -2.70131 -0.27111 -2.24418 -2.79446 -0.241394 -2.3113 -2.91139 -0.21821 -2.37861 -3.0295 -0.190425 -2.44538 -3.14765 -0.158356 -2.52683 -3.29022 -0.130263 -2.60863 -3.43282 -0.0967935 -2.69055 -3.57638 -0.0576522 -2.78673 -3.74476 -0.0198576 -2.8832 -3.91295 0.0242869 -2.98885 -4.09861 0.0712105 -3.10385 -4.30054 0.121786 -3.23871 -4.53748 0.174244 -3.36922 -4.76486 0.237172 -3.53728 -5.06057 0.299312 -3.70158 -5.3474 0.374382 -3.89407 -5.68517 0.455448 -4.11621 -6.07456 0.546063 -4.34841 -6.48024 0.651182 -4.62829 -6.97076 0.769044 -4.93258 -7.50332 0.905929 -5.30994 -8.16406 1.06446 -5.75524 -8.94378 1.25245 -6.33693 -9.96403 1.48243 -6.84688 -10.8567 1.74536 -7.64085 -12.248 2.08667 -8.76708 -14.2197 2.54507 -12.6161 -20.9637 4.10938 -23.7927 -40.5119 10.3025 -24.0284 -40.8916 12.1232 -20.8008 -35.0318 21.0448 -3.09785 -4.18752 5.25582 -3.00497 -4.02402 5.24908 -2.98412 -3.98498 5.36175 -3.0215 -4.04638 5.58162 -2.94958 -3.91928 5.60686 -2.90345 -3.83648 5.67734 -2.87532 -3.78254 5.94943 -2.68938 -3.45973 5.72298 -2.60292 -3.30768 5.69402 -2.54256 -3.20207 5.72066 -2.47762 -3.08542 5.72916 -2.40181 -2.95376 5.71094 -2.39012 -2.92999 5.84706 -2.36107 -2.87651 5.94352 -2.3424 -2.84213 6.0718 -2.29913 -2.7648 6.13447 -2.24715 -2.67192 6.17058 -2.21676 -2.61708 6.27198 -2.156 -2.51011 6.27937 -2.11118 -2.42961 6.33525 -2.06886 -2.35244 6.39834 -2.0194 -2.26692 6.44246 -1.9715 -2.18007 6.48475 -1.9475 -2.1359 6.62347 -1.88878 -2.03132 6.62683 -1.79056 -1.86302 6.46453 -1.62223 -1.57537 5.96795 -1.77544 -1.8261 6.90826 -1.50183 -1.36644 5.87376 -1.41815 -1.22261 5.69196 -1.34974 -1.10551 5.57181 -1.29987 -1.01701 5.53351 -1.27165 -0.966645 5.62611 -1.35424 -1.09428 6.4168 -1.3315 -1.05215 6.60798 -1.26849 -0.943731 6.52843 -1.21316 -0.845478 6.48506 -1.03604 -0.554798 5.43516 -0.99968 -0.489823 5.46177 -0.992605 -0.472133 5.78186 -0.950163 -0.396389 5.77711 -0.885077 -0.288701 5.5142 -0.844954 -0.218486 5.50584 -0.800851 -0.140993 5.42646 -0.761707 -0.0726907 5.41511 -0.730158 -0.0143405 5.53207 -0.768226 -0.0444088 7.38358 -0.709146 0.0570864 7.26014 -0.640352 0.165151 6.6551 -0.60076 0.246518 7.16735 -0.547019 0.339057 7.06792 -0.495002 0.424914 6.82685 -0.449314 0.496797 6.3942 -0.406561 0.569026 6.22011 -0.340303 0.701398 7.01232 -0.288292 0.791367 6.99378 -0.234355 0.888509 7.05313 -0.0158658 1.33605 10.1662 --0.0687598 1.4846 10.2239 --0.140313 1.60823 10.091 --0.271592 1.85182 10.7337 -1.51598 -1.62939 -0.561346 -1.54132 -1.67547 -0.540416 -1.57303 -1.73573 -0.529584 -1.59792 -1.78213 -0.505636 -1.63012 -1.84283 -0.491275 -1.66218 -1.90309 -0.474968 -1.69877 -1.97243 -0.461516 -1.73128 -2.03302 -0.441194 -1.77636 -2.11814 -0.432899 -1.80907 -2.17993 -0.407976 -1.84576 -2.24852 -0.385743 -1.89175 -2.33431 -0.369418 -1.92859 -2.40396 -0.341999 -1.97782 -2.49761 -0.324272 -2.02852 -2.59194 -0.302994 -2.07877 -2.68654 -0.278502 -2.12877 -2.78042 -0.2508 -2.20104 -2.91619 -0.236337 -2.25102 -3.0106 -0.201114 -2.30982 -3.12241 -0.168295 -2.38786 -3.26784 -0.142794 -2.45603 -3.39598 -0.106615 -2.53737 -3.55005 -0.0732626 -2.62823 -3.72094 -0.0386904 -2.71019 -3.8748 0.00658363 -2.81504 -4.07194 0.0478184 -2.9154 -4.26077 0.0984559 -3.02954 -4.47466 0.151155 -3.15688 -4.71513 0.207963 -3.29314 -4.97226 0.27115 -3.45338 -5.27224 0.338812 -3.61305 -5.57278 0.418277 -3.79526 -5.91616 0.505601 -4.01463 -6.32896 0.601607 -4.25682 -6.78443 0.711724 -4.52673 -7.29168 0.838377 -4.85159 -7.90312 0.984331 -5.23094 -8.61741 1.15562 -5.68907 -9.47887 1.36005 -6.28126 -10.5927 1.61226 -6.83785 -11.6402 1.90416 -7.7465 -13.3494 2.29909 -8.55774 -14.8751 2.74256 -22.2979 -40.7256 8.95007 -22.8043 -41.6637 10.8492 -22.7471 -41.5481 11.6881 -2.93874 -4.25609 5.63196 -2.86638 -4.11915 5.65341 -2.57547 -3.5729 5.37557 -2.50361 -3.43793 5.37293 -2.45171 -3.33968 5.40968 -2.44496 -3.32518 5.54754 -2.43868 -3.31329 5.69364 -2.43404 -3.30321 5.84818 -2.34406 -3.13377 5.78738 -2.23438 -2.92889 5.66623 -2.23393 -2.92579 5.83263 -2.28469 -3.01892 6.15368 -2.22077 -2.89809 6.15319 -2.19216 -2.8432 6.25697 -2.1396 -2.74342 6.2851 -2.07845 -2.6284 6.2852 -2.09708 -2.66197 6.55607 -2.07183 -2.61154 6.6829 -1.97119 -2.42514 6.53915 -1.91519 -2.31898 6.54832 -1.85939 -2.21341 6.55485 -1.80162 -2.10445 6.5501 -1.79512 -2.09012 6.7685 -1.56537 -1.66435 5.96757 -1.53065 -1.598 6.03315 -1.52246 -1.58111 6.23657 -1.4823 -1.50385 6.28243 -1.72301 -1.94468 7.92078 -1.25634 -1.08567 5.52039 -1.22891 -1.0321 5.604 -1.18007 -0.94114 5.5535 -1.16464 -0.911017 5.73098 -1.23561 -1.03764 6.58358 -1.16338 -0.901927 6.38648 -1.15423 -0.881734 6.71109 -0.975884 -0.55629 5.4929 -0.939997 -0.489411 5.51911 -0.911401 -0.434567 5.6227 -0.908685 -0.423969 6.06076 -0.835837 -0.291549 5.63925 -0.788445 -0.202203 5.49147 -0.745796 -0.124118 5.40148 -0.70877 -0.0532911 5.36937 -0.676957 0.00707652 5.47548 -0.682301 0.00893159 6.8185 -0.63721 0.0943232 6.94325 -0.587811 0.187477 6.82664 -0.542323 0.275758 7.20809 -0.49305 0.364052 6.66786 -0.449829 0.442467 6.37609 -0.407268 0.522844 6.32259 -0.36576 0.599584 6.23761 -0.297405 0.735474 6.9784 -0.246546 0.83312 7.0388 -0.195251 0.928477 7.05723 --0.0309217 1.38185 10.0271 --0.115625 1.54136 10.1629 --0.173844 1.65046 9.9302 --0.198613 1.69131 9.33241 -1.47558 -1.66586 -0.542243 -1.50195 -1.71962 -0.526698 -1.52895 -1.77421 -0.509376 -1.55904 -1.83563 -0.495934 -1.58997 -1.8969 -0.480718 -1.6235 -1.96678 -0.468502 -1.66176 -2.0447 -0.45895 -1.68885 -2.0985 -0.432651 -1.72753 -2.17662 -0.4185 -1.75873 -2.2399 -0.392427 -1.80169 -2.32632 -0.377726 -1.84033 -2.40493 -0.35586 -1.87879 -2.48298 -0.331562 -1.92238 -2.57089 -0.30805 -1.96962 -2.66621 -0.285572 -2.01639 -2.76178 -0.259783 -2.07683 -2.88314 -0.240618 -2.12838 -2.98748 -0.210848 -2.1842 -3.1001 -0.180432 -2.25688 -3.24787 -0.157472 -2.31614 -3.36958 -0.12115 -2.3898 -3.51654 -0.0880228 -2.46261 -3.66427 -0.0495393 -2.55273 -3.84745 -0.0143033 -2.6344 -4.01163 0.0315318 -2.72854 -4.20294 0.0779505 -2.82735 -4.40269 0.129809 -2.93847 -4.62906 0.184587 -3.05953 -4.87245 0.245183 -3.19686 -5.15151 0.310321 -3.35154 -5.46507 0.381868 -3.51121 -5.787 0.464622 -3.7048 -6.17998 0.554436 -3.91599 -6.60719 0.657302 -4.15286 -7.08713 0.774811 -4.43304 -7.65516 0.909481 -4.7528 -8.30193 1.06653 -5.12859 -9.06196 1.25117 -5.59486 -10.0069 1.47341 -6.16614 -11.1618 1.74568 -6.81721 -12.482 2.07702 -7.76503 -14.4009 2.5209 -8.52705 -15.9447 2.99593 -23.9781 -47.2408 14.4221 -8.75428 -16.432 11.4485 -2.48734 -3.73305 5.40003 -2.43061 -3.61966 5.42796 -2.34137 -3.43856 5.37363 -2.29575 -3.34588 5.41632 -2.23772 -3.22946 5.42692 -2.2675 -3.28914 5.66125 -2.23944 -3.23366 5.75332 -2.52644 -3.8174 6.73256 -2.21898 -3.19423 6.04571 -2.51917 -3.80415 7.1374 -2.12799 -3.00861 6.13773 -2.10325 -2.95914 6.25042 -2.05007 -2.85229 6.27136 -2 -2.75125 6.29836 -1.96857 -2.68749 6.39088 -2.00111 -2.75426 6.73115 -1.90432 -2.55846 6.58155 -1.8436 -2.43629 6.56598 -1.76188 -2.26979 6.45024 -1.75389 -2.25349 6.65102 -1.68151 -2.10735 6.56483 -1.70812 -2.16325 6.95544 -1.47964 -1.69642 6.06011 -1.43512 -1.60756 6.07054 -1.38291 -1.50165 6.03235 -1.33027 -1.39489 5.98253 -1.32116 -1.37749 6.20251 -1.18082 -1.09082 5.56238 -1.15743 -1.04498 5.67436 -1.14215 -1.01365 5.85281 -1.09553 -0.91836 5.80047 -1.06498 -0.857258 5.88122 -1.2 -1.13618 7.50505 -0.967493 -0.65965 5.69899 -0.906767 -0.537014 5.45256 -0.872791 -0.467597 5.46796 -0.866948 -0.457023 5.85656 -0.833622 -0.389459 5.92968 -0.768973 -0.258446 5.50612 -0.73188 -0.182864 5.46644 -0.70019 -0.119815 5.53495 -0.664642 -0.0463571 5.51222 -0.661259 -0.0425703 6.60582 -0.62158 0.036201 6.79126 -0.575074 0.129806 6.68535 -0.534833 0.208819 7.34765 -0.488317 0.306196 6.76836 -0.445493 0.392746 6.58723 -0.408431 0.470492 6.29451 -0.36531 0.556744 6.38016 -0.300473 0.684859 7.06232 -0.25656 0.774053 6.99399 -0.209516 0.868633 6.99348 --0.0478816 1.37587 10.6824 --0.108286 1.49964 10.4519 --0.159526 1.60441 10.1307 --0.28073 1.84775 10.7335 -1.44174 -1.72439 -0.54059 -1.46684 -1.77869 -0.524093 -1.48837 -1.82638 -0.500308 -1.52437 -1.90393 -0.496763 -1.55282 -1.96643 -0.480324 -1.58579 -2.03797 -0.466643 -1.61765 -2.10884 -0.451039 -1.63931 -2.15588 -0.418861 -1.67551 -2.23527 -0.403681 -1.70837 -2.30706 -0.381215 -1.74495 -2.38654 -0.36095 -1.78112 -2.46643 -0.338056 -1.82168 -2.55499 -0.316265 -1.86952 -2.66002 -0.299361 -1.91039 -2.74843 -0.271415 -1.95824 -2.85411 -0.247477 -2.02234 -2.99418 -0.233064 -2.07013 -3.10029 -0.201119 -2.11864 -3.20584 -0.165648 -2.18754 -3.35532 -0.140222 -2.24755 -3.4878 -0.104288 -2.32071 -3.64616 -0.0709858 -2.39652 -3.81392 -0.0342339 -2.47264 -3.98155 0.00857598 -2.55799 -4.16677 0.0535814 -2.64611 -4.36009 0.103396 -2.7473 -4.58133 0.155864 -2.85556 -4.81905 0.213302 -2.97671 -5.08411 0.275922 -3.10205 -5.35781 0.347487 -3.25112 -5.6848 0.423601 -3.41686 -6.04761 0.50905 -3.60665 -6.46363 0.604815 -3.8169 -6.92393 0.71426 -4.06432 -7.46383 0.839006 -4.34376 -8.07573 0.984248 -4.66357 -8.7756 1.15391 -5.06028 -9.64544 1.35597 -5.49306 -10.5922 1.59534 -6.14735 -12.0256 1.90596 -6.87415 -13.614 2.28616 -7.91378 -15.8915 2.80365 -8.87364 -17.9934 3.38792 -22.204 -47.3958 22.9156 -2.27353 -3.63566 5.15293 -2.20756 -3.49205 5.14323 -2.17985 -3.43308 5.22221 -2.14586 -3.36001 5.28561 -2.1226 -3.31107 5.37726 -2.12562 -3.32048 5.54325 -2.12169 -3.31315 5.69549 -2.40788 -3.95712 6.7229 -2.36551 -3.86584 6.80325 -2.13512 -3.35338 6.2777 -1.97764 -3.00463 5.95191 -1.95749 -2.96331 6.07131 -1.98698 -3.03322 6.37248 -1.97437 -3.00789 6.53532 -1.85745 -2.74984 6.30202 -1.64145 -2.26675 5.64191 -1.61745 -2.21662 5.73333 -1.77517 -2.57609 6.62597 -1.73753 -2.4962 6.69763 -1.60322 -2.19628 6.30597 -1.59844 -2.18901 6.52281 -1.68928 -2.3999 7.25633 -1.39848 -1.74259 5.95841 -1.33828 -1.60964 5.85863 -1.30899 -1.54737 5.9313 -1.29208 -1.51304 6.08675 -1.29109 -1.51519 6.36407 -1.15365 -1.20592 5.69953 -1.10764 -1.10232 5.6323 -1.08641 -1.0594 5.76319 -1.0412 -0.958834 5.69239 -0.999955 -0.867455 5.64792 -1.20077 -1.34836 8.02339 -0.952381 -0.770192 5.9131 -0.912614 -0.682394 5.88352 -0.866043 -0.578875 5.7544 -0.827855 -0.495417 5.72098 -0.784674 -0.397948 5.587 -0.75636 -0.338351 5.68851 -0.714392 -0.24395 5.53105 -0.683407 -0.175594 5.57025 -0.648083 -0.09871 5.5187 -0.614875 -0.0270648 5.51536 -0.60629 -0.0312664 6.86827 -0.562625 0.067224 6.72343 -0.52085 0.157001 6.74661 -0.477223 0.242266 7.29818 -0.439104 0.337518 6.64774 -0.397722 0.427161 6.6758 -0.363655 0.505051 6.39243 -0.322681 0.594792 6.46707 -0.260206 0.721403 7.02825 -0.219706 0.80964 6.93911 -0.165734 0.922898 7.1268 --0.0750101 1.39484 10.2549 --0.142763 1.5434 10.2518 --0.205044 1.67993 10.1668 --0.202229 1.68805 9.32249 -1.38016 -1.7182 -0.548838 -1.39968 -1.7669 -0.527237 -1.42354 -1.82182 -0.510177 -1.45325 -1.89269 -0.502235 -1.47341 -1.94062 -0.476135 -1.50752 -2.02015 -0.469201 -1.53729 -2.09182 -0.454907 -1.56469 -2.15614 -0.433303 -1.59465 -2.22899 -0.41431 -1.62176 -2.29242 -0.388815 -1.66284 -2.38983 -0.378659 -1.69691 -2.47048 -0.356879 -1.73056 -2.5515 -0.332372 -1.77513 -2.65813 -0.316894 -1.81369 -2.74834 -0.290255 -1.85467 -2.84664 -0.26428 -1.89998 -2.9534 -0.238438 -1.95196 -3.07815 -0.215334 -2.00533 -3.20335 -0.187706 -2.0572 -3.32837 -0.155915 -2.11755 -3.47145 -0.125066 -2.17755 -3.61345 -0.0894489 -2.24219 -3.76546 -0.0509189 -2.321 -3.95324 -0.0158985 -2.39209 -4.12317 0.030039 -2.47491 -4.31909 0.0762421 -2.56542 -4.53393 0.126471 -2.66281 -4.76635 0.181284 -2.76451 -5.0078 0.24329 -2.88131 -5.28573 0.309622 -3.00915 -5.58915 0.382741 -3.15671 -5.93901 0.463294 -3.32307 -6.33359 0.553394 -3.51534 -6.79112 0.654707 -3.73495 -7.31218 0.771174 -3.96911 -7.86866 0.906589 -4.25613 -8.55152 1.06328 -4.57779 -9.314 1.24743 -4.99469 -10.3044 1.47019 -5.43655 -11.3544 1.73419 -6.05042 -12.8114 2.07045 -6.95879 -14.9682 2.53129 -9.77649 -21.6599 4.02701 -20.5555 -47.5266 18.0339 -2.47693 -4.51292 5.74191 -2.16106 -3.74824 5.13441 -2.09931 -3.6032 5.12656 -2.06808 -3.53032 5.19236 -2.10932 -3.63667 5.45854 -2.0674 -3.54042 5.50265 -2.05149 -3.50501 5.61888 -2.32898 -4.19484 6.64274 -2.28249 -4.08666 6.70345 -2.55324 -4.76334 7.81306 -2.3033 -4.15336 7.21242 -1.93205 -3.2418 6.12707 -1.89178 -3.14903 6.17661 -1.84322 -3.0341 6.19134 -1.86696 -3.10122 6.49402 -1.83882 -3.03882 6.59913 -1.74194 -2.80258 6.40626 -1.67557 -2.64437 6.33475 -1.50821 -2.23061 5.77348 -1.48708 -2.18615 5.88151 -1.45346 -2.10739 5.92721 -1.56187 -2.39052 6.7388 -1.37092 -1.91329 5.93345 -1.31421 -1.77607 5.8381 -1.2737 -1.67937 5.83031 -1.24306 -1.60997 5.88512 -1.21888 -1.55595 5.98491 -1.21779 -1.5634 6.26188 -1.20132 -1.52951 6.44614 -1.07281 -1.20339 5.73168 -1.04055 -1.12873 5.75919 -0.992413 -1.01196 5.64145 -0.96819 -0.957812 5.74182 -0.941779 -0.896707 5.82247 -1.05792 -1.23255 7.62056 -0.88108 -0.75918 5.94179 -0.982778 -1.06273 7.88847 -0.785752 -0.520086 5.52637 -0.753246 -0.442683 5.51109 -0.719186 -0.361907 5.46462 -0.689801 -0.294625 5.50561 -0.728394 -0.451472 7.49135 -0.627746 -0.148058 5.49461 -0.599698 -0.0842655 5.60146 -0.583118 -0.0823691 6.66511 -0.54506 0.00703056 6.69091 -0.506433 0.0949373 6.78484 -0.46854 0.189214 6.67726 -0.428452 0.279883 6.78783 -0.382855 0.377158 7.13651 -0.364476 0.447894 6.23436 -0.319214 0.545537 6.53961 -0.259115 0.667671 7.08204 -0.220032 0.761894 7.03359 -0.187017 0.846217 6.89398 -0.133827 0.964214 7.1004 --0.133826 1.484 10.422 --0.223277 1.68407 10.7427 --0.288443 1.83829 10.704 -1.33416 -1.75236 -0.530365 -1.36214 -1.82344 -0.525487 -1.3803 -1.87241 -0.501766 -1.40553 -1.93665 -0.487435 -1.4336 -2.00859 -0.476495 -1.46128 -2.08103 -0.463315 -1.48658 -2.14611 -0.442826 -1.51078 -2.21056 -0.420609 -1.54241 -2.29196 -0.405418 -1.57069 -2.3658 -0.383038 -1.60562 -2.45525 -0.367223 -1.6372 -2.53713 -0.344219 -1.67585 -2.63654 -0.32639 -1.70656 -2.71911 -0.297642 -1.7556 -2.84418 -0.284656 -1.79405 -2.94358 -0.256874 -1.84637 -3.07892 -0.238855 -1.88838 -3.18778 -0.206822 -1.93345 -3.30566 -0.174066 -1.9792 -3.42288 -0.137297 -2.03838 -3.57633 -0.107174 -2.10473 -3.74825 -0.0764573 -2.16338 -3.90237 -0.035018 -2.23387 -4.08278 0.00532532 -2.3067 -4.27334 0.0501915 -2.38327 -4.47221 0.0999879 -2.47097 -4.69856 0.152196 -2.56553 -4.94239 0.209376 -2.66637 -5.20532 0.273188 -2.78568 -5.51304 0.340782 -2.91524 -5.84882 0.41702 -3.051 -6.20181 0.503875 -3.21552 -6.62947 0.599461 -3.39857 -7.10098 0.708486 -3.61591 -7.66506 0.832751 -3.85803 -8.29198 0.977476 -4.1499 -9.04795 1.14724 -4.48305 -9.91167 1.34853 -4.9053 -11.0049 1.59358 -5.46894 -12.4651 1.90493 -6.02935 -13.9185 2.27102 -19.8103 -49.9178 16.0778 -2.24909 -4.42405 5.83222 -2.22214 -4.35859 5.93322 -2.18424 -4.26605 6.00478 -1.99225 -3.75341 5.602 -2.17092 -4.24865 6.34133 -2.19202 -4.31746 6.61243 -2.13563 -4.17188 6.6288 -2.15709 -4.24196 6.91955 -2.24057 -4.48425 7.45743 -1.79708 -3.27276 6.00395 -1.79393 -3.27542 6.19006 -1.7876 -3.26811 6.36977 -1.77346 -3.23962 6.52572 -1.69995 -3.04712 6.42352 -1.42568 -2.32051 5.96094 -1.379 -2.19988 5.92939 -1.35185 -2.13305 6.00129 -1.28858 -1.96436 5.85733 -1.26098 -1.8972 5.92522 -1.22691 -1.81069 5.94693 -1.18806 -1.71128 5.93896 -1.34492 -2.18824 7.39915 -1.15391 -1.63873 6.24289 -1.11521 -1.54041 6.24 -1.10273 -1.51868 6.46164 -1.07554 -1.45477 6.57007 -0.963141 -1.12858 5.8093 -0.940571 -1.07461 5.92094 -0.898663 -0.962226 5.81987 -0.862299 -0.868077 5.77431 -0.851546 -0.857406 6.08656 -0.815065 -0.760626 6.03834 -0.751785 -0.568953 5.48831 -0.721181 -0.49187 5.47376 -0.689878 -0.408397 5.41825 -0.660824 -0.334514 5.4104 -0.691321 -0.51498 7.39419 -0.60682 -0.198506 5.48985 -0.577621 -0.121129 5.448 -0.570416 -0.214547 7.55816 -0.526411 -0.0564268 6.72749 -0.489729 0.036687 6.7323 -0.453493 0.128286 6.75568 -0.413059 0.217633 7.0571 -0.373324 0.315613 7.0868 -0.343628 0.407528 6.78506 -0.315194 0.493292 6.56159 -0.261203 0.607071 7.01529 -0.221487 0.706661 7.04771 -0.184674 0.803225 7.01833 -0.143762 0.906441 7.0668 --0.110577 1.3896 10.324 --0.175666 1.55081 10.38 --0.253043 1.73972 10.6004 --0.0107171 1.30233 7.03269 -1.23899 -1.64495 -0.577234 -1.25581 -1.69367 -0.558914 -1.27652 -1.75053 -0.544837 -1.29615 -1.80684 -0.529422 -1.31842 -1.87196 -0.517786 -1.34154 -1.93691 -0.504374 -1.3613 -1.99425 -0.483579 -1.38689 -2.06745 -0.471514 -1.4133 -2.14042 -0.457382 -1.43341 -2.19776 -0.431113 -1.45904 -2.27172 -0.4125 -1.48159 -2.33721 -0.387188 -1.51422 -2.42849 -0.372777 -1.54641 -2.5201 -0.355444 -1.5784 -2.6111 -0.335388 -1.61357 -2.71146 -0.316165 -1.6466 -2.80352 -0.289829 -1.68469 -2.91244 -0.267839 -1.72661 -3.03166 -0.245295 -1.77542 -3.16784 -0.225395 -1.81369 -3.27854 -0.191478 -1.84837 -3.37864 -0.15128 -1.9034 -3.53374 -0.12397 -1.95757 -3.68959 -0.0911096 -2.00881 -3.83576 -0.0505792 -2.06722 -4.00038 -0.00935686 -2.13176 -4.18301 0.0334093 -2.20561 -4.39305 0.0767888 -2.28615 -4.62174 0.124365 -2.36337 -4.84126 0.181755 -2.45711 -5.10673 0.24006 -2.55291 -5.38149 0.306682 -2.66569 -5.70255 0.378139 -2.7857 -6.0412 0.459555 -2.92755 -6.44467 0.548399 -3.08537 -6.89474 0.649573 -3.27037 -7.41906 0.764711 -3.47718 -8.00707 0.897809 -3.72382 -8.70551 1.05275 -4.00121 -9.49622 1.23535 -4.31091 -10.3784 1.45109 -4.69918 -11.4809 1.71216 -5.28796 -13.1526 2.05781 -5.99326 -15.1532 2.49723 -9.96634 -26.4443 5.06713 -2.31645 -5.10709 5.66474 -2.28149 -5.01653 5.75053 -2.13684 -4.59611 5.53225 -2.15034 -4.67643 6.10872 -1.8455 -3.76849 5.32856 -2.02333 -4.31683 6.0794 -1.79981 -3.65234 5.5046 -1.89064 -3.9409 6.00044 -1.80422 -3.69049 5.87321 -1.80745 -3.71542 6.07612 -1.94877 -4.16454 6.84121 -1.73658 -3.5253 6.18857 -1.68602 -3.3826 6.17775 -1.68297 -3.38842 6.37404 -1.64616 -3.28905 6.42409 -1.63322 -3.26436 6.58849 -1.54937 -3.01764 6.40092 -1.48131 -2.81897 6.27419 -1.45313 -2.74216 6.34736 -1.45952 -2.78373 6.63599 -1.25751 -2.14601 5.65881 -1.20443 -1.98963 5.54368 -1.17872 -1.92382 5.60224 -1.19812 -2.00377 5.97472 -1.18468 -1.97924 6.14282 -1.14731 -1.87204 6.12857 -1.09754 -1.72543 6.01085 -1.10271 -1.76528 6.36201 -1.06422 -1.65681 6.34246 -1.05895 -1.66204 6.64031 -1.00346 -1.49483 6.44783 -0.976266 -1.42347 6.53648 -0.896092 -1.16104 5.98309 -0.862861 -1.06384 5.95095 -0.822001 -0.940965 5.81048 -0.808066 -0.9206 6.07446 -0.776611 -0.83366 6.07602 -0.732181 -0.690314 5.80197 -0.78084 -0.960328 7.65439 -0.658547 -0.451313 5.36136 -0.632044 -0.375772 5.34428 -0.655045 -0.586564 7.37558 -0.618409 -0.490751 7.45935 -0.581524 -0.399675 7.61118 -0.529202 -0.096982 5.44069 -0.503895 -0.130038 6.89292 -0.470174 -0.0243006 6.73917 -0.425407 0.0322352 7.66266 -0.394165 0.151043 7.25565 -0.356007 0.253022 7.29638 -0.326548 0.353279 7.06556 -0.315668 0.434185 6.35316 -0.256048 0.550988 7.04782 -0.218685 0.65328 7.09101 -0.187464 0.745778 6.99296 -0.1546 0.841262 6.96309 -0.104294 0.964739 7.18925 --0.170102 1.48908 10.54 --0.234167 1.66202 10.6335 -0.00481728 1.25314 7.05226 -1.17928 -1.62607 -0.577826 -1.19725 -1.68281 -0.566447 -1.21511 -1.73923 -0.553609 -1.23359 -1.79646 -0.538896 -1.25173 -1.85431 -0.522526 -1.275 -1.92699 -0.515787 -1.29065 -1.97713 -0.490551 -1.31711 -2.05922 -0.484841 -1.33548 -2.11672 -0.46144 -1.35646 -2.18291 -0.441331 -1.38001 -2.25765 -0.42393 -1.39752 -2.31589 -0.394978 -1.42735 -2.40685 -0.382389 -1.45651 -2.4991 -0.366681 -1.47988 -2.57394 -0.339814 -1.51568 -2.68408 -0.326456 -1.54207 -2.76778 -0.298185 -1.58053 -2.88739 -0.281668 -1.60962 -2.98066 -0.250725 -1.65092 -3.10859 -0.230373 -1.69478 -3.24734 -0.208513 -1.7272 -3.34935 -0.170107 -1.77708 -3.50581 -0.145342 -1.82145 -3.64398 -0.109906 -1.86501 -3.78306 -0.0696987 -1.91505 -3.93951 -0.0295063 -1.97003 -4.11482 0.0118201 -2.03535 -4.31786 0.0533943 -2.10871 -4.54884 0.0965339 -2.17324 -4.75179 0.15283 -2.24992 -4.99213 0.210563 -2.33743 -5.27021 0.27156 -2.43235 -5.56641 0.340183 -2.53783 -5.89955 0.415573 -2.65567 -6.26965 0.49982 -2.79498 -6.70518 0.593247 -2.94169 -7.16895 0.701211 -3.11648 -7.71652 0.823818 -3.31369 -8.33817 0.965651 -3.54699 -9.07207 1.13131 -3.82908 -9.95453 1.32809 -4.14073 -10.9385 1.56214 -4.53429 -12.1746 1.84905 -5.06186 -13.8308 2.21675 -5.82486 -16.2272 2.72161 -2.14816 -5.1896 5.43565 -2.11757 -5.102 5.52254 -2.09448 -5.04191 5.63266 -2.02571 -4.82761 5.60576 -1.9998 -4.75863 5.70471 -1.99887 -4.77378 5.88393 -1.73221 -3.88546 5.17642 -1.69376 -3.76955 5.20288 -1.69479 -3.78792 5.3689 -1.66498 -3.70314 5.42791 -1.63758 -3.62309 5.49229 -1.61653 -3.56813 5.5852 -1.58938 -3.49339 5.6547 -1.59624 -3.53255 5.86933 -1.85192 -4.45294 7.24522 -1.80669 -4.3199 7.29044 -1.66776 -3.84958 6.85851 -1.54536 -3.43451 6.46876 -1.45173 -3.12076 6.19748 -1.41707 -3.01955 6.23361 -1.36609 -2.85488 6.166 -1.33648 -2.77069 6.22238 -1.30841 -2.68968 6.28556 -1.27607 -2.59232 6.32109 -1.23979 -2.48195 6.32851 -1.08835 -1.93425 5.46424 -1.06894 -1.88154 5.54823 -1.08626 -1.97425 5.9479 -1.0496 -1.85615 5.90596 -1.02934 -1.80602 6.01709 -1.00855 -1.75367 6.12809 -0.994778 -1.72998 6.32215 -0.948224 -1.57008 6.16087 -0.926045 -1.51169 6.26897 -0.913119 -1.49893 6.52785 -0.873909 -1.36973 6.4351 -0.811993 -1.13219 5.95582 -0.779945 -1.0278 5.89388 -0.755496 -0.958698 5.96475 -0.732711 -0.897858 6.07379 -0.709674 -0.843862 6.23061 -0.683401 -0.769675 6.30862 -0.694482 -0.946059 7.75173 -0.601233 -0.419819 5.29776 -0.621552 -0.725536 7.81069 -0.580211 -0.567282 7.48047 -0.544581 -0.45231 7.42471 -0.509906 -0.37958 7.77451 -0.474799 -0.241498 7.46595 -0.439801 -0.134547 7.47362 -0.414159 0.0042146 6.85026 -0.374497 0.0872278 7.23355 -0.341862 0.190347 7.21543 -0.313714 0.293414 7.04533 -0.295159 0.386997 6.67374 -0.26307 0.482359 6.72022 -0.216228 0.592681 7.04418 -0.184618 0.692529 7.03685 -0.150051 0.794679 7.05735 -0.135022 0.868696 6.7882 --0.139995 1.37377 10.2834 --0.198788 1.54479 10.3892 --0.262223 1.72443 10.5309 --0.0140804 1.30208 7.04267 -1.13827 -1.66114 -0.567924 -1.15402 -1.71828 -0.556005 -1.1704 -1.77625 -0.542309 -1.18666 -1.83386 -0.527056 -1.20881 -1.90752 -0.521311 -1.22235 -1.95838 -0.496995 -1.24398 -2.03216 -0.487356 -1.26323 -2.09855 -0.47031 -1.28114 -2.16526 -0.451339 -1.30085 -2.23199 -0.430278 -1.32215 -2.30705 -0.412045 -1.34306 -2.38259 -0.391475 -1.37015 -2.47569 -0.377271 -1.39413 -2.56024 -0.355977 -1.41792 -2.64422 -0.332154 -1.44758 -2.74647 -0.31343 -1.47676 -2.84897 -0.291394 -1.50548 -2.95172 -0.266048 -1.53995 -3.0724 -0.244243 -1.57748 -3.20209 -0.221715 -1.60928 -3.31448 -0.188515 -1.64413 -3.43589 -0.154591 -1.68929 -3.59391 -0.127771 -1.72893 -3.73363 -0.0902814 -1.77129 -3.88301 -0.0505089 -1.82471 -4.06856 -0.0148003 -1.88375 -4.27391 0.0233334 -1.93976 -4.4693 0.0704014 -2.00033 -4.68401 0.120941 -2.05884 -4.88899 0.180536 -2.14696 -5.19761 0.231826 -2.21869 -5.44897 0.301443 -2.31175 -5.77593 0.371531 -2.41602 -6.14074 0.449871 -2.52842 -6.53267 0.538948 -2.65346 -6.97259 0.639707 -2.80358 -7.49706 0.752998 -2.96394 -8.05813 0.884467 -3.16446 -8.76157 1.03618 -3.38639 -9.53934 1.21491 -3.66545 -10.5142 1.42873 -3.99205 -11.6586 1.68768 -4.43526 -13.2091 2.01794 -4.9196 -14.9064 2.41897 -18.2042 -61.5111 13.512 -5.20405 -16.5022 7.37809 -5.22175 -16.613 7.76736 -5.45118 -17.6362 9.70066 -5.44247 -17.7113 10.5391 -1.92676 -5.1194 5.5653 -1.87558 -4.94733 5.57875 -1.85483 -4.89347 5.69208 -1.64934 -4.12406 5.14304 -1.59122 -3.92148 5.09264 -1.54571 -3.76301 5.07772 -1.54274 -3.77106 5.22795 -1.53151 -3.74807 5.35072 -1.51532 -3.70893 5.45929 -1.49436 -3.64804 5.54543 -1.48256 -3.62331 5.67588 -1.46062 -3.5582 5.76089 -1.45218 -3.55204 5.92241 -1.40982 -3.40451 5.90413 -1.38784 -3.34155 5.99394 -1.35657 -3.24141 6.03405 -1.51733 -3.93969 7.24252 -1.33405 -3.20362 6.35657 -1.273 -2.97601 6.2004 -1.24274 -2.88015 6.24135 -1.19628 -2.71207 6.16015 -1.19515 -2.73836 6.41208 -1.10456 -2.37381 5.95861 -1.09827 -2.37923 6.17327 -1.06347 -2.25692 6.14881 -1.01916 -2.09023 6.02296 -0.962909 -1.86562 5.75671 -0.943102 -1.81003 5.84906 -0.924857 -1.76056 5.95936 -0.919403 -1.78206 6.2546 -0.889361 -1.67696 6.24405 -0.848967 -1.52229 6.09026 -0.822253 -1.43111 6.10273 -0.891848 -1.88233 7.79555 -0.850401 -1.72813 7.69904 -0.733372 -1.10938 5.95663 -0.704775 -1.00395 5.89368 -0.688152 -0.978439 6.13872 -0.661466 -0.888399 6.14066 -0.639122 -0.831505 6.29708 -0.64781 -1.08221 8.03269 -0.610118 -0.940159 7.91752 -0.571401 -0.755873 7.51326 -0.538696 -0.653033 7.56972 -0.50668 -0.53768 7.53532 -0.472611 -0.456129 7.79662 -0.44067 -0.324241 7.60894 -0.409125 -0.210317 7.56821 -0.391875 -0.0528461 6.78666 -0.351471 0.0228157 7.27043 -0.325084 0.130211 7.14358 -0.298963 0.233913 7.02457 -0.280546 0.33264 6.74383 -0.252379 0.428388 6.75125 -0.205391 0.538824 7.12625 -0.177711 0.639035 7.07977 -0.150894 0.736631 7.0217 -0.118582 0.841166 7.06147 -0.10751 0.914081 6.79173 --0.202567 1.48821 10.6085 --0.246734 1.64445 10.554 --4.90993e-06 1.24809 7.03227 -1.10278 -1.72681 -0.582359 -1.1139 -1.76955 -0.557281 -1.12804 -1.82784 -0.542754 -1.14304 -1.88602 -0.526646 -1.15971 -1.95276 -0.514341 -1.17425 -2.01119 -0.494923 -1.1934 -2.08621 -0.484157 -1.21017 -2.15388 -0.466082 -1.2268 -2.22111 -0.446062 -1.24427 -2.28816 -0.42417 -1.26309 -2.36446 -0.404714 -1.28737 -2.4572 -0.392136 -1.30367 -2.52569 -0.363426 -1.3271 -2.61922 -0.345492 -1.35372 -2.72211 -0.328391 -1.37988 -2.82527 -0.308077 -1.40654 -2.92889 -0.284332 -1.43177 -3.03255 -0.257397 -1.46108 -3.14559 -0.230299 -1.49415 -3.27597 -0.206303 -1.52741 -3.40753 -0.177608 -1.56345 -3.5489 -0.147312 -1.60149 -3.69881 -0.115245 -1.63895 -3.8486 -0.0782139 -1.68215 -4.01857 -0.0404117 -1.73417 -4.22504 -0.00593942 -1.7851 -4.42196 0.0378063 -1.84493 -4.65795 0.0811724 -1.88863 -4.83579 0.142377 -1.96087 -5.11844 0.193504 -2.03291 -5.40108 0.254584 -2.09537 -5.65444 0.328794 -2.19169 -6.03151 0.399341 -2.26964 -6.34122 0.488971 -2.38764 -6.80462 0.579603 -2.51712 -7.3152 0.684519 -2.65813 -7.87145 0.805955 -2.81581 -8.49504 0.946925 -3.00714 -9.25139 1.11124 -3.24214 -10.1791 1.30713 -3.47498 -11.1026 1.53632 -3.82601 -12.4859 1.82762 -4.28123 -14.2782 2.20199 -4.86731 -16.5917 2.69281 -5.00905 -17.8744 7.26827 -4.95919 -17.7332 7.5804 -4.99012 -17.9243 8.01842 -4.8707 -17.5674 8.61883 -4.85877 -17.5827 9.00183 -4.57534 -16.4835 8.8709 -4.85952 -17.7223 9.84009 -4.61382 -16.7725 9.75273 -4.54568 -16.5571 10.0207 -4.25779 -15.4218 9.77453 -4.20961 -15.2834 10.0599 -4.7009 -17.6639 13.1953 -4.68959 -17.7005 13.6845 -1.78494 -5.32963 5.60838 -1.72634 -5.10211 5.58141 -1.701 -5.01743 5.67059 -1.66655 -4.89565 5.72511 -1.5071 -4.21143 5.25105 -1.48166 -4.12627 5.31709 -1.65749 -4.95441 6.2975 -1.45798 -4.076 5.57174 -1.39825 -3.8315 5.46818 -1.37901 -3.77657 5.56309 -1.36448 -3.7393 5.67981 -1.34102 -3.66092 5.75102 -1.30671 -3.53196 5.75922 -1.30112 -3.53706 5.93573 -1.28359 -3.49097 6.05086 -1.47793 -4.48239 7.59374 -1.44558 -4.37183 7.67768 -1.12134 -2.79933 5.60421 -1.17026 -3.08602 6.21605 -1.14873 -3.01942 6.30877 -1.10855 -2.85363 6.23924 -1.09476 -2.83137 6.40608 -0.990855 -2.32191 5.71321 -1.00745 -2.45537 6.15369 -0.967945 -2.28689 6.04218 -0.925185 -2.09605 5.87244 -0.893761 -1.96777 5.81492 -0.867403 -1.8669 5.80867 -0.852303 -1.83368 5.95588 -0.844203 -1.8456 6.22316 -0.819936 -1.76173 6.26922 -0.783873 -1.59685 6.09886 -0.761058 -1.51754 6.14997 -0.82302 -2.06792 8.07512 -0.777658 -1.84971 7.80116 -0.708759 -1.42037 6.78403 -0.666619 -1.18622 6.3222 -0.638592 -1.05914 6.20218 -0.614093 -0.964063 6.19554 -0.619538 -1.27925 7.99131 -0.587613 -1.15539 7.98789 -0.556679 -1.05508 8.10016 -0.523606 -0.880726 7.80679 -0.493247 -0.712931 7.47995 -0.462871 -0.620698 7.61474 -0.433552 -0.503075 7.57931 -0.403697 -0.395545 7.62126 -0.38482 -0.237509 7.09386 -0.362081 -0.121455 6.91177 -0.313665 -0.0655914 7.70604 -0.293723 0.058861 7.40056 -0.282606 0.175834 6.953 -0.262795 0.27585 6.79336 -0.23356 0.374952 6.88156 -0.195592 0.480647 7.1178 -0.169817 0.582642 7.09233 -0.146283 0.68073 7.02535 -0.118223 0.784487 7.04618 -0.0966814 0.880314 6.97576 --0.174901 1.36836 10.322 --0.228361 1.54938 10.4773 --0.278128 1.72392 10.55 --0.0138454 1.29487 7.0031 -1.04451 -1.70228 -0.584428 -1.05579 -1.7528 -0.566217 -1.07107 -1.8191 -0.558533 -1.08191 -1.86995 -0.537401 -1.09445 -1.92944 -0.520459 -1.10889 -1.99653 -0.50742 -1.12417 -2.06343 -0.492508 -1.13908 -2.13089 -0.475647 -1.15361 -2.19888 -0.456741 -1.17073 -2.27547 -0.440738 -1.18595 -2.3428 -0.417819 -1.20252 -2.41942 -0.397532 -1.2231 -2.5141 -0.383558 -1.24274 -2.59972 -0.36245 -1.26099 -2.68552 -0.338834 -1.28679 -2.7982 -0.324312 -1.30945 -2.90227 -0.302409 -1.33262 -3.0068 -0.277075 -1.36057 -3.12906 -0.2555 -1.38777 -3.25236 -0.229737 -1.41445 -3.37576 -0.199982 -1.44654 -3.51771 -0.172111 -1.47805 -3.6596 -0.139568 -1.509 -3.80143 -0.102352 -1.54403 -3.96218 -0.0653883 -1.58403 -4.14185 -0.0274848 -1.631 -4.35056 0.010407 -1.67724 -4.55871 0.0552087 -1.72249 -4.76723 0.107215 -1.7823 -5.03241 0.156761 -1.84074 -5.29844 0.215751 -1.8898 -5.52458 0.288673 -1.97277 -5.89534 0.353408 -2.04371 -6.21741 0.435853 -2.14111 -6.65584 0.520953 -2.2269 -7.04351 0.62405 -2.35666 -7.6247 0.733421 -2.48713 -8.21444 0.863179 -2.64303 -8.91966 1.01382 -2.82223 -9.72817 1.19086 -3.02268 -10.6319 1.40034 -3.27305 -11.7648 1.6538 -3.60355 -13.2529 1.97288 -4.06634 -15.3363 2.39749 -4.64911 -17.962 2.95478 -5.39794 -22.1411 7.55082 -5.3556 -22.0409 7.95314 -4.53252 -18.4137 7.56437 -4.44378 -18.0822 7.8155 -4.4216 -18.1474 8.58922 -4.35658 -17.9296 8.87797 -4.22895 -17.4118 9.02772 -3.913 -15.9884 8.73319 -3.86728 -15.8488 9.0176 -3.91621 -16.168 9.53832 -4.02418 -16.7773 10.2361 -3.73013 -15.4376 9.87344 -3.66835 -15.2194 10.1121 -3.75072 -15.7137 10.7811 -4.21144 -18.0894 12.672 -4.17675 -18.0237 13.0838 -4.20155 -18.2588 13.7078 -4.02742 -17.4967 13.6475 -3.94723 -17.2032 13.9032 -3.95696 -17.3697 14.5055 -1.61166 -5.41344 5.54954 -1.55606 -5.16881 5.51235 -1.56162 -5.2354 5.72999 -1.52861 -5.10404 5.78174 -1.50631 -5.03117 5.88347 -1.49516 -5.01313 6.0382 -1.46735 -4.90712 6.11076 -1.44304 -4.82118 6.20219 -1.28222 -3.98619 5.51092 -1.40984 -4.73908 6.48235 -1.4004 -4.739 6.67415 -1.36155 -4.57167 6.67952 -1.16636 -3.55013 5.81804 -1.16456 -3.59044 6.04215 -1.13026 -3.43994 6.02246 -1.29364 -4.47516 7.63635 -1.01726 -2.85413 5.55507 -0.981495 -2.68231 5.4692 -0.980422 -2.72665 5.70516 -0.939645 -2.52077 5.55459 -1.06055 -3.37156 7.15059 -0.891883 -2.31664 5.56454 -0.872434 -2.24392 5.61831 -0.94859 -2.84637 6.93945 -0.844833 -2.17809 5.88252 -0.921192 -2.82873 7.4225 -0.900366 -2.77099 7.58481 -0.757874 -1.74961 5.60483 -0.773216 -1.96251 6.31952 -0.746248 -1.83124 6.25641 -0.781532 -2.27694 7.67139 -0.692341 -1.5703 6.10228 -0.673013 -1.4975 6.17177 -0.694112 -1.90531 7.70182 -0.64048 -1.46518 6.68905 -0.619195 -1.40483 6.84313 -0.58702 -1.16911 6.37037 -0.564837 -1.07867 6.39486 -0.54018 -0.924757 6.15484 -0.524708 -1.22049 7.913 -0.496439 -1.09561 7.89863 -0.467342 -1.0123 8.09833 -0.443716 -0.795996 7.54724 -0.41778 -0.681846 7.54471 -0.38621 -0.611255 7.8575 -0.364868 -0.458896 7.56329 -0.333586 -0.366521 7.76356 -0.332547 -0.180312 6.88658 -0.304579 -0.089488 7.03266 -0.260517 -0.014124 7.58664 -0.260482 0.116738 6.95072 -0.242188 0.219551 6.84185 -0.215244 0.318373 6.91117 -0.178745 0.423839 7.16833 -0.157421 0.526119 7.12421 -0.13506 0.62821 7.08808 -0.111456 0.731178 7.08003 -0.092245 0.828719 7.01052 -0.0827014 0.910448 6.81044 --0.231983 1.48055 10.6073 --0.263625 1.63498 10.5236 --0.00722875 1.24971 7.05172 -0.999089 -1.73426 -0.575037 -1.01021 -1.79324 -0.562329 -1.02098 -1.85281 -0.547867 -1.03058 -1.90429 -0.526171 -1.04517 -1.97912 -0.519901 -1.05835 -2.04676 -0.506006 -1.07114 -2.11492 -0.489969 -1.08381 -2.1827 -0.472277 -1.09785 -2.25979 -0.457314 -1.109 -2.32006 -0.430538 -1.12372 -2.39649 -0.411563 -1.1378 -2.47432 -0.389956 -1.15635 -2.56833 -0.375152 -1.17253 -2.65496 -0.352942 -1.19265 -2.75946 -0.336169 -1.21229 -2.86421 -0.316085 -1.231 -2.9599 -0.288966 -1.24973 -3.06521 -0.262553 -1.27419 -3.18838 -0.239389 -1.29955 -3.32111 -0.215644 -1.32274 -3.44541 -0.1843 -1.35173 -3.59736 -0.15769 -1.37738 -3.73054 -0.120561 -1.40827 -3.89298 -0.0865066 -1.44222 -4.07396 -0.0520464 -1.47878 -4.26422 -0.0136494 -1.5167 -4.4644 0.0292469 -1.55716 -4.67367 0.0769554 -1.60226 -4.91203 0.126748 -1.64953 -5.16004 0.183302 -1.70327 -5.44683 0.243031 -1.76329 -5.76223 0.309075 -1.82325 -6.07641 0.386041 -1.89207 -6.43967 0.470026 -1.98012 -6.89895 0.55996 -2.06434 -7.34752 0.666517 -2.17556 -7.93276 0.78488 -2.28796 -8.52461 0.923429 -2.43408 -9.29155 1.08399 -2.59562 -10.1445 1.27377 -2.81463 -11.2868 1.50551 -3.08808 -12.7186 1.79498 -3.35639 -14.1448 2.13543 -3.63891 -15.6506 2.5348 -4.15346 -18.357 3.12312 -4.17332 -18.7382 4.19716 -4.18675 -18.9069 4.57537 -4.39496 -20.3066 5.97519 -4.41895 -20.5464 6.42348 -4.43639 -20.7495 6.87389 -4.68572 -22.2074 7.70762 -3.53737 -16.1212 6.22014 -3.38298 -15.466 6.63064 -3.33579 -15.2962 6.8812 -2.98788 -13.4631 6.47181 -3.22112 -14.8463 7.32764 -3.14839 -14.531 7.50409 -3.01215 -13.8556 7.50699 -2.94451 -13.5662 7.67096 -3.10012 -14.5492 8.46332 -3.08226 -14.5446 8.78873 -2.88729 -13.5184 8.56291 -2.81277 -13.1838 8.68889 -2.82212 -13.3337 9.09195 -2.77821 -13.1796 9.32124 -2.69793 -12.8042 9.40871 -2.64734 -12.6037 9.6005 -3.08581 -15.3704 11.8344 -2.98079 -14.8551 11.8729 -3.35357 -17.29 14.0821 -3.29997 -17.1149 14.4268 -3.30618 -17.3208 15.0781 -3.24219 -17.0883 15.3929 -1.31037 -5.05293 6.11699 -1.27371 -4.86709 6.11289 -1.28687 -5.09604 6.71714 -1.26935 -5.04682 6.86261 -2.36412 -13.0689 16.6573 -1.02561 -3.65051 6.16409 -1.06726 -4.05072 6.8888 -0.972497 -3.3989 6.19396 -0.943471 -3.24228 6.15941 -0.868111 -2.70723 5.54799 -0.870804 -2.80779 5.87711 -0.889849 -3.0607 6.47427 -0.801778 -2.37584 5.53625 -0.780632 -2.26988 5.53038 -0.768618 -2.24968 5.67931 -0.757832 -2.24536 5.86461 -0.740683 -2.18055 5.94377 -0.778603 -2.72278 7.28156 -0.754659 -2.61577 7.33311 -0.737 -2.60062 7.59285 -0.671828 -1.9573 6.38058 -0.68573 -2.36114 7.65253 -0.627508 -1.72356 6.32459 -0.60545 -1.58491 6.22698 -0.60022 -1.81793 7.19507 -0.573038 -1.58622 6.84067 -0.55143 -1.50362 6.92936 -0.530111 -1.45305 7.13252 -0.507665 -1.45498 7.55755 -0.483728 -1.3214 7.49907 -0.462559 -1.14973 7.26271 -0.437979 -1.06601 7.39379 -0.415707 -0.954963 7.40601 -0.383617 -0.936433 7.92828 -0.368322 -0.746423 7.5036 -0.343906 -0.637213 7.52974 -0.311694 -0.57 7.89135 -0.299355 -0.409165 7.50689 -0.283587 -0.27941 7.31811 -0.276622 -0.143245 6.93766 -0.245101 -0.0573062 7.20289 -0.234108 0.0584192 6.96738 -0.216629 0.161153 6.90978 -0.187314 0.260448 7.09002 -0.160164 0.365344 7.18838 -0.146733 0.467189 7.05532 -0.119561 0.575481 7.15989 -0.108405 0.670878 7.01365 -0.100999 0.758848 6.81582 -0.0675251 0.875638 6.99438 --0.00580414 1.13617 7.39273 --0.290427 1.71748 10.5296 --0.0196273 1.29923 7.03242 -0.943557 -1.71489 -0.583448 -0.951709 -1.76575 -0.565597 -0.959538 -1.81731 -0.54638 -0.970368 -1.88434 -0.537423 -0.97978 -1.94419 -0.520841 -0.991906 -2.02032 -0.51364 -0.999056 -2.07148 -0.488292 -1.01341 -2.15681 -0.482239 -1.02481 -2.22513 -0.463596 -1.03487 -2.29377 -0.443027 -1.04749 -2.37096 -0.425166 -1.06146 -2.45738 -0.409645 -1.07328 -2.53549 -0.387011 -1.08665 -2.62176 -0.366428 -1.10227 -2.71731 -0.347383 -1.11576 -2.80456 -0.321226 -1.13627 -2.92772 -0.307814 -1.1491 -3.01465 -0.275817 -1.16937 -3.13934 -0.254882 -1.18771 -3.25468 -0.226643 -1.21097 -3.39769 -0.204329 -1.22852 -3.51232 -0.1685 -1.25514 -3.67541 -0.142735 -1.27905 -3.82784 -0.109303 -1.30542 -3.99079 -0.0730027 -1.33362 -4.17296 -0.0359275 -1.36672 -4.37383 0.00296259 -1.39791 -4.57493 0.0485477 -1.43368 -4.79541 0.0974097 -1.46974 -5.02526 0.15211 -1.51129 -5.2841 0.210377 -1.55606 -5.57214 0.273626 -1.6081 -5.89864 0.342507 -1.66829 -6.27311 0.417894 -1.73299 -6.67692 0.504149 -1.80626 -7.13847 0.600899 -1.87083 -7.54992 0.716007 -1.94863 -8.0483 0.843306 -2.00644 -8.43605 0.988635 -2.15649 -9.36374 1.15414 -2.3326 -10.4551 1.3572 -2.50827 -11.5633 1.59993 -2.72849 -12.9409 1.8996 -2.99305 -14.6074 2.27258 -3.27646 -16.4126 2.71928 -3.77981 -19.5686 3.39134 -3.59169 -18.5511 3.60853 -3.55213 -18.4287 3.92874 -3.53692 -18.4577 4.27234 -3.59357 -18.9359 4.70455 -3.6667 -19.6524 5.57366 -3.76693 -20.4289 6.13497 -3.3301 -17.7803 5.82186 -3.04771 -16.09 5.68385 -3.05758 -16.2756 6.05225 -2.97909 -15.888 6.24656 -2.95917 -15.8734 6.55652 -2.67648 -14.1209 6.24213 -2.5895 -13.6522 6.35079 -2.55811 -13.5513 6.5919 -2.58838 -13.8763 7.012 -2.56561 -13.8375 7.28872 -2.51381 -13.5949 7.474 -2.49539 -13.5911 7.76925 -2.47538 -13.5728 8.0619 -2.46844 -13.6541 8.41145 -2.43525 -13.5449 8.66534 -2.43901 -13.7066 9.07558 -2.5263 -14.4893 9.87054 -2.50462 -14.4802 10.218 -2.37085 -13.638 10.0344 -2.32506 -13.4505 10.2557 -2.42888 -14.393 11.2624 -2.43946 -14.6524 11.833 -2.33917 -14.0535 11.7838 -2.31631 -14.0488 12.1743 -2.324 -14.3074 12.7861 -2.48349 -15.8031 14.4555 -2.6218 -17.1775 16.1216 -2.03991 -13.7324 15.9488 -1.07946 -5.07127 6.94341 -1.04598 -4.87051 6.92384 -1.0246 -4.78255 7.0285 -0.993752 -4.60357 7.02361 -0.901058 -3.7825 6.19973 -0.882834 -3.69971 6.27814 -0.894434 -3.94634 6.80548 -0.806132 -3.10821 5.83602 -0.787183 -3.00256 5.86163 -0.765888 -2.88099 5.85993 -0.764062 -2.98557 6.20987 -0.709477 -2.42245 5.49005 -0.697487 -2.40171 5.63146 -0.684394 -2.37641 5.7733 -0.700706 -2.80441 6.75938 -0.659999 -2.3601 6.14709 -0.664765 -2.6958 7.04249 -0.643355 -2.57054 7.04828 -0.605764 -2.08131 6.25092 -0.58737 -1.97613 6.25468 -0.569681 -1.89375 6.31154 -0.551133 -1.76289 6.24638 -0.533919 -1.68028 6.29983 -0.51658 -1.60246 6.37059 -0.498831 -1.46886 6.27907 -0.477813 -1.65493 7.17596 -0.458482 -1.54008 7.17963 -0.438961 -1.41249 7.13301 -0.418947 -1.32017 7.20966 -0.399225 -1.20975 7.21686 -0.379309 -1.1074 7.26092 -0.357836 -1.01049 7.33262 -0.335108 -0.929987 7.50105 -0.306353 -0.865816 7.79638 -0.292807 -0.711252 7.56774 -0.262016 -0.640907 7.8904 -0.242827 -0.518436 7.86512 -0.236457 -0.364686 7.5195 -0.22318 -0.239034 7.36966 -0.217983 -0.110106 7.07804 -0.203559 -0.00224535 7.01334 -0.185728 0.100615 7.01674 -0.169651 0.203769 6.99831 -0.133688 0.307283 7.29737 -0.118412 0.413782 7.24535 -0.108206 0.516744 7.12153 -0.0897906 0.621987 7.12558 -0.078344 0.721268 7.03827 -0.0727529 0.810684 6.86985 -0.0481269 0.921258 6.95806 --0.00386437 1.07841 7.39019 --0.0200451 1.18538 7.35455 --0.012783 1.24688 7.04156 -0.875751 -1.58283 -0.615549 -0.880132 -1.62588 -0.594913 -0.888577 -1.68491 -0.585681 -0.897759 -1.75239 -0.580856 -0.903686 -1.80362 -0.562368 -0.911333 -1.86357 -0.548363 -0.919924 -1.93093 -0.538574 -0.927096 -1.9911 -0.521161 -0.935122 -2.05113 -0.50207 -0.944635 -2.12812 -0.491992 -0.952178 -2.18836 -0.469396 -0.962134 -2.26563 -0.455108 -0.972671 -2.34361 -0.438459 -0.98208 -2.42089 -0.41979 -0.992063 -2.49885 -0.398663 -1.00336 -2.58598 -0.379584 -1.01424 -2.67348 -0.357778 -1.02662 -2.76906 -0.337633 -1.04002 -2.87452 -0.318366 -1.05392 -2.98046 -0.295667 -1.06877 -3.09612 -0.273165 -1.08479 -3.22049 -0.250667 -1.09962 -3.33669 -0.220645 -1.11698 -3.47089 -0.193259 -1.13867 -3.63434 -0.170041 -1.15355 -3.75917 -0.130873 -1.17504 -3.92261 -0.0977031 -1.19703 -4.09607 -0.0615163 -1.22409 -4.29827 -0.0261666 -1.24815 -4.4906 0.0177282 -1.27356 -4.69281 0.0663171 -1.30363 -4.92417 0.116698 -1.3342 -5.1639 0.172915 -1.36983 -5.44417 0.23229 -1.40982 -5.7527 0.297445 -1.46212 -6.14914 0.363845 -1.51171 -6.53556 0.444946 -1.5359 -6.75288 0.550925 -1.57327 -7.06757 0.659217 -1.63486 -7.54901 0.772847 -1.69863 -8.05812 0.902552 -1.78213 -8.71442 1.05052 -1.92934 -9.83288 1.23022 -2.06975 -10.9186 1.44817 -2.22928 -12.157 1.71272 -2.41907 -13.6382 2.03887 -2.62258 -15.2492 2.4293 -2.89912 -17.4224 2.93793 -3.00586 -18.5294 3.72772 -2.98808 -18.561 4.0706 -2.9892 -18.7334 4.44163 -3.12087 -20.2883 5.84788 -3.1498 -20.7153 6.33716 -2.72484 -17.5096 5.86158 -2.41628 -15.1848 5.52385 -2.31119 -14.4806 5.60131 -2.2982 -14.5247 5.90016 -2.1854 -13.737 5.91492 -2.17734 -13.8196 6.2216 -2.17163 -13.9248 6.54374 -2.12404 -13.6729 6.72845 -2.12066 -13.8029 7.07026 -2.13897 -14.1255 7.50784 -2.06637 -13.6533 7.59035 -2.05886 -13.7632 7.94333 -2.01922 -13.5734 8.15232 -2.0332 -13.8889 8.6289 -2.00281 -13.7924 8.89554 -2.00206 -13.9836 9.331 -1.96049 -13.7884 9.5486 -1.95012 -13.9027 9.95797 -1.88721 -13.4977 10.0416 -1.95733 -14.4315 11.0197 -1.92175 -14.3078 11.3102 -1.47223 -9.8609 8.44902 -1.88854 -14.4885 12.2235 -1.85627 -14.4205 12.5787 -1.79996 -14.0889 12.7269 -0.787719 -3.45501 4.92723 -1.5278 -13.6464 16.0051 -0.864592 -4.97954 7.10866 -0.80637 -4.3093 6.52607 -0.727273 -3.25218 5.41748 -0.719064 -3.28694 5.62012 -0.709997 -3.30999 5.81738 -0.689419 -3.13854 5.75801 -0.675231 -3.08593 5.85793 -0.648376 -2.75606 5.55159 -0.634607 -2.70016 5.63744 -0.615052 -2.4925 5.48537 -0.601059 -2.4262 5.55015 -0.587823 -2.35265 5.60522 -0.577228 -2.40522 5.88633 -0.564918 -2.46732 6.20565 -0.549067 -2.36457 6.22608 -0.532494 -2.14211 6.00192 -0.517313 -2.11609 6.17006 -0.502581 -1.93748 6.01031 -0.487658 -1.80384 5.93759 -0.472284 -1.83615 6.26003 -0.458065 -1.7133 6.2121 -0.440282 -1.69244 6.43333 -0.414141 -1.8761 7.25972 -0.411723 -1.46748 6.38431 -0.382255 -1.60324 7.14884 -0.361116 -1.55049 7.36272 -0.349629 -1.37261 7.14253 -0.335371 -1.25025 7.10232 -0.311805 -1.19803 7.3513 -0.297816 -1.06905 7.28762 -0.280126 -0.963448 7.3196 -0.261023 -0.865559 7.39886 -0.232471 -0.803832 7.71305 -0.196326 -0.753688 8.17515 -0.159001 -0.680978 8.58756 -0.158413 -0.50687 8.21526 -0.187879 -0.293526 7.28261 -0.17774 -0.177436 7.18163 -0.162736 -0.0704216 7.17803 -0.135442 0.0280278 7.38195 -0.111277 0.133989 7.52449 -0.107084 0.247215 7.34586 -0.0855716 0.357131 7.42448 -0.0757981 0.466338 7.34142 -0.0652711 0.57222 7.26677 -0.0667211 0.665899 7.04117 -0.0689116 0.752778 6.81408 -0.0409744 0.870339 6.9827 --0.0171893 1.12545 7.33252 --0.00976297 1.19629 7.05969 --0.0220456 1.29672 7.02253 -0.827031 -1.55944 -0.62179 -0.83295 -1.61731 -0.615062 -0.838155 -1.66907 -0.600003 -0.842067 -1.72131 -0.583699 -0.848172 -1.78036 -0.572273 -0.853932 -1.84003 -0.55919 -0.860316 -1.90053 -0.544329 -0.865623 -1.96049 -0.528131 -0.873644 -2.03673 -0.521312 -0.87943 -2.09709 -0.50139 -0.887665 -2.17459 -0.490263 -0.893756 -2.24376 -0.471925 -0.900679 -2.31273 -0.451619 -0.907993 -2.39077 -0.434065 -0.91492 -2.46931 -0.41427 -0.923399 -2.55605 -0.39672 -0.932431 -2.6434 -0.37642 -0.9447 -2.75879 -0.36579 -0.953576 -2.85523 -0.343861 -0.961306 -2.94364 -0.314992 -0.97337 -3.05902 -0.294409 -0.984951 -3.1746 -0.27032 -0.997211 -3.30073 -0.245648 -1.0078 -3.41663 -0.21416 -1.02441 -3.5704 -0.190837 -1.03923 -3.72478 -0.162473 -1.05443 -3.87927 -0.129121 -1.07016 -4.04385 -0.0931417 -1.08893 -4.22693 -0.0565618 -1.10789 -4.42075 -0.0157948 -1.12748 -4.62332 0.0291537 -1.1484 -4.83567 0.0791852 -1.1694 -5.05845 0.134766 -1.19738 -5.33898 0.188799 -1.22652 -5.63836 0.249641 -1.26559 -6.01762 0.3121 -1.27679 -6.17804 0.408372 -1.30257 -6.46602 0.499899 -1.34121 -6.86162 0.594591 -1.38012 -7.27668 0.702129 -1.43106 -7.79853 0.821007 -1.48741 -8.37899 0.957638 -1.57286 -9.23424 1.11646 -1.68803 -10.3759 1.313 -1.79777 -11.4925 1.54827 -1.92938 -12.843 1.83728 -2.07208 -14.3156 2.18389 -2.23977 -16.068 2.60985 -2.47774 -18.5208 3.17826 -2.46115 -18.8134 3.89129 -2.45442 -18.9798 4.26151 -2.46426 -19.3146 4.67079 -2.01683 -15.8666 5.51897 -1.93999 -15.2633 5.64537 -1.86795 -14.6985 5.76398 -1.85531 -14.786 6.08211 -1.89993 -15.5159 6.63441 -1.80769 -14.708 6.64449 -1.80337 -14.8983 7.01905 -1.75224 -14.5453 7.18055 -1.73642 -14.6032 7.5105 -1.70047 -14.4268 7.74067 -1.62796 -13.7873 7.74779 -1.63108 -14.0901 8.20158 -1.61405 -14.1602 8.55287 -1.58454 -14.0558 8.81829 -1.53793 -13.7376 8.96435 -1.51439 -13.7117 9.27386 -1.46719 -13.3718 9.39699 -1.5059 -14.2717 10.2983 -1.47778 -14.2102 10.6169 -1.44674 -14.126 10.9248 -1.4599 -14.7347 11.7302 -1.42115 -14.5491 11.9907 -1.36901 -14.1521 12.0898 -1.35791 -14.4291 12.712 -1.35891 -14.967 13.5755 -1.32737 -14.9615 14.0205 -1.44499 -18.6388 18.3158 -1.24433 -15.3094 15.7807 -1.19926 -15.096 16.0919 -0.66743 -3.53988 4.9215 -0.651925 -3.38902 4.90066 -1.04206 -13.9639 16.5135 -0.990967 -13.5888 16.6395 -0.619291 -3.28865 5.20881 -0.609728 -3.33098 5.40884 -0.596745 -3.24241 5.45551 -0.587365 -3.30639 5.69827 -0.575148 -3.29119 5.84821 -0.56034 -3.13167 5.80409 -0.548237 -3.16796 6.03526 -0.534541 -3.10334 6.12778 -0.518659 -2.54442 5.45425 -0.505916 -2.40421 5.40056 -0.494707 -2.31315 5.42089 -0.481084 -2.46473 5.86455 -0.467637 -2.40025 5.94653 -0.453567 -2.40387 6.16061 -0.442776 -2.22481 6.02799 -0.428613 -2.19005 6.17872 -0.426677 -1.78164 5.53086 -0.415878 -1.70776 5.57525 -0.398097 -1.75627 5.91298 -0.378889 -1.78329 6.22592 -0.365283 -1.71045 6.30754 -0.332859 -1.87391 7.04646 -0.309516 -1.87246 7.38534 -0.306442 -1.64593 7.06012 -0.269666 -1.73578 7.73326 -0.285275 -1.38167 6.93071 -0.266406 -1.31486 7.09348 -0.249617 -1.22598 7.1878 -0.226081 -1.1728 7.44652 -0.218968 -1.02828 7.31396 -0.205014 -0.917337 7.32548 -0.18467 -0.832395 7.48271 -0.126533 -0.856989 8.36895 -0.101384 -0.753373 8.56487 -0.0973469 -0.596629 8.36317 -0.140502 -0.363731 7.36381 -0.129141 -0.250488 7.33379 -0.0874172 -0.174158 7.82934 -0.088564 -0.0440679 7.59652 -0.0753059 0.0703742 7.60042 -0.096385 0.19236 7.0939 -0.0122074 0.298076 8.13142 -0.0461452 0.410186 7.47103 -0.0358068 0.520331 7.42729 -0.0524631 0.612016 7.04303 -0.0447268 0.713498 6.9961 -0.0430591 0.805079 6.85801 --0.0200709 1.07081 7.34938 --0.0302013 1.17744 7.31426 --0.0200225 1.24749 7.05106 -0.783526 -1.59284 -0.62201 -0.786844 -1.64433 -0.607873 -0.791169 -1.70343 -0.598828 -0.794062 -1.75529 -0.581965 -0.798675 -1.81587 -0.569583 -0.801372 -1.86715 -0.550093 -0.807665 -1.9436 -0.546338 -0.809673 -1.99611 -0.523534 -0.814417 -2.06498 -0.510402 -0.820794 -2.14229 -0.500586 -0.82502 -2.21125 -0.483464 -0.828871 -2.28075 -0.464295 -0.834335 -2.35862 -0.44815 -0.839403 -2.43697 -0.429667 -0.845795 -2.52449 -0.413329 -0.850294 -2.60278 -0.390174 -0.857573 -2.69982 -0.373059 -0.862943 -2.78758 -0.348933 -0.871507 -2.90323 -0.333892 -0.877676 -3.00025 -0.307822 -0.884833 -3.10708 -0.282337 -0.893376 -3.23284 -0.260288 -0.904224 -3.37758 -0.240872 -0.913114 -3.51288 -0.213763 -0.923578 -3.65874 -0.184975 -0.932741 -3.80337 -0.151834 -0.943428 -3.9584 -0.116333 -0.953673 -4.12331 -0.0783248 -0.970627 -4.3462 -0.0484089 -0.98198 -4.5298 -0.00291121 -0.997959 -4.75368 0.0413404 -1.01006 -4.95655 0.0961794 -1.02899 -5.21835 0.148598 -1.04801 -5.50974 0.205445 -1.06256 -5.74173 0.27989 -1.07226 -5.94293 0.365218 -1.09464 -6.28091 0.444657 -1.11945 -6.64901 0.533753 -1.14682 -7.06512 0.632649 -1.17903 -7.55992 0.742996 -1.21411 -8.09302 0.869711 -1.25996 -8.76273 1.01441 -1.32721 -9.72939 1.18696 -1.40447 -10.8523 1.39833 -1.48548 -12.0502 1.65292 -1.5786 -13.4414 1.96286 -1.67667 -14.9447 2.33147 -1.80966 -16.9652 2.80675 -1.89841 -18.4682 3.29199 -2.4229 -25.9769 4.65964 -1.75845 -19.4454 6.2673 -1.52362 -16.0972 5.68737 -1.61502 -17.9844 6.56805 -1.55007 -17.3261 6.70542 -1.42956 -15.6864 6.48667 -1.39183 -15.4307 6.70672 -1.34217 -14.9386 6.83077 -1.53083 -18.898 8.7208 -1.25364 -14.1323 7.10636 -1.2287 -14.0624 7.37294 -1.29751 -15.9372 8.53973 -1.1978 -14.3577 8.1214 -1.15089 -13.8587 8.1862 -1.11658 -13.61 8.36636 -1.06825 -12.9997 8.34272 -1.05566 -13.2619 8.79623 -1.03576 -13.3321 9.15381 -1.00367 -13.1388 9.35806 -0.996916 -13.6071 9.98559 -0.962059 -13.3336 10.1482 -0.927168 -13.0593 10.304 -0.917766 -13.6191 11.0547 -0.908858 -14.2931 11.9291 -0.87072 -13.9681 12.077 -0.877722 -15.4833 13.6933 -0.834101 -15.0464 13.7866 -0.823948 -16.2864 15.3102 -0.760958 -14.8201 14.5115 -0.740642 -15.7964 15.8911 -0.696089 -15.3629 16.0023 -0.542577 -3.72133 5.01218 -0.529921 -3.49796 4.92379 -0.519507 -3.42935 4.98882 -0.509752 -3.48853 5.19347 -0.498397 -3.35014 5.18336 -0.487589 -3.30977 5.28404 -0.47615 -3.31164 5.43872 -0.465266 -3.27165 5.5476 -0.449828 -3.47822 5.98237 -0.438692 -3.38026 6.03095 -0.426374 -3.27005 6.06117 -0.41345 -3.26636 6.24593 -0.416015 -2.65276 5.51352 -0.408402 -2.51572 5.47101 -0.397772 -2.44356 5.52751 -0.384263 -2.45615 5.72938 -0.372348 -2.39421 5.81112 -0.352979 -2.48689 6.18225 -0.342382 -2.39224 6.22063 -0.334547 -2.24419 6.14981 -0.331949 -2.04709 5.96706 -0.339141 -1.74676 5.53363 -0.329655 -1.66791 5.56805 -0.308269 -1.72216 5.92449 -0.29408 -1.68109 6.07009 -0.252719 -1.86229 6.82427 -0.229652 -1.85756 7.13365 -0.224389 -1.70382 7.02751 -0.223389 -1.53311 6.85114 -0.204886 -1.48002 7.04448 -0.201534 -1.33268 6.91989 -0.185871 -1.25482 7.0435 -0.141253 -1.30096 7.70012 -0.150195 -1.10458 7.36554 -0.136969 -1.00011 7.41764 -0.125355 -0.890984 7.44856 -0.113054 -0.784325 7.49715 -0.105576 -0.664076 7.46501 -0.0930239 -0.556046 7.50978 -0.095599 -0.420616 7.32469 -0.0829312 -0.314513 7.37523 -0.0398367 -0.242973 7.88153 -0.0359123 -0.11711 7.78949 -0.0352435 0.00555022 7.66563 -0.0403281 0.126541 7.45952 --0.00649097 0.234421 7.96936 --0.0180416 0.355798 7.98847 -0.00698499 0.465158 7.52714 -0.0336888 0.558048 7.06441 -0.0280542 0.66027 7.01849 -0.0289767 0.756556 6.90112 --0.320719 1.25877 11.0484 --0.359682 1.46785 11.336 --0.0338438 1.1251 7.34133 --0.0201384 1.19658 7.06893 --0.0225355 1.29171 6.99268 -0.737772 -1.61031 -0.608932 -0.741321 -1.67706 -0.607264 -0.74209 -1.7296 -0.591126 -0.745059 -1.78897 -0.579962 -0.746602 -1.84114 -0.561076 -0.747919 -1.90156 -0.546817 -0.75115 -1.96962 -0.536654 -0.752969 -2.03051 -0.518963 -0.755709 -2.09874 -0.505198 -0.757847 -2.16849 -0.489287 -0.76184 -2.24568 -0.476694 -0.76424 -2.32411 -0.461784 -0.766677 -2.3937 -0.439717 -0.769506 -2.47237 -0.420403 -0.772683 -2.55998 -0.403257 -0.775443 -2.64799 -0.383482 -0.780221 -2.75351 -0.369677 -0.783809 -2.85086 -0.348347 -0.787927 -2.94877 -0.323975 -0.791324 -3.0551 -0.30053 -0.796869 -3.1816 -0.280591 -0.80072 -3.2978 -0.253546 -0.805478 -3.42359 -0.226016 -0.811293 -3.56896 -0.20046 -0.817686 -3.72458 -0.172957 -0.821963 -3.86074 -0.135205 -0.828942 -4.03452 -0.103352 -0.836153 -4.21917 -0.0678946 -0.844167 -4.42265 -0.0310057 -0.849667 -4.59755 0.0189806 -0.85961 -4.84025 0.0615839 -0.868502 -5.0831 0.112365 -0.879737 -5.3552 0.166742 -0.88116 -5.49848 0.247827 -0.888457 -5.74999 0.320798 -0.899024 -6.04995 0.397144 -0.911255 -6.40912 0.478864 -0.925115 -6.79704 0.570799 -0.9432 -7.26287 0.672214 -0.96014 -7.75783 0.788862 -0.982279 -8.35064 0.921314 -1.01197 -9.12064 1.07492 -1.05036 -10.108 1.26007 -1.09321 -11.2113 1.48429 -1.13936 -12.4686 1.75565 -1.18929 -13.8595 2.08142 -1.24482 -15.4521 2.47495 -1.27889 -16.6766 2.88499 -1.27976 -17.2276 3.25425 -1.38569 -20.2926 4.0067 -1.27352 -22.2043 6.72548 -1.24165 -22.2381 7.15279 -1.18896 -21.6306 7.39927 -1.16562 -21.9372 7.90961 -1.14066 -22.2621 8.44191 -1.1028 -22.1217 8.83006 -1.05651 -21.6738 9.10516 -0.870983 -15.2941 7.07198 -0.816228 -13.9366 6.83314 -0.792443 -13.899 7.10741 -0.769556 -13.9015 7.4025 -0.74347 -13.8066 7.65666 -0.728729 -14.3637 8.23139 -0.70086 -14.1922 8.46236 -0.700318 -16.3185 9.91977 -0.638906 -13.1047 8.50395 -0.613028 -13.0167 8.7608 -0.586942 -12.8207 8.95482 -0.563912 -13.248 9.53754 -0.53719 -13.1659 9.8154 -0.511035 -13.8886 10.642 -0.48242 -13.9414 11.0425 -0.452545 -13.8219 11.3294 -0.423098 -13.7847 11.6817 -0.394736 -13.4632 11.8196 -0.351665 -14.6556 13.1789 -0.296219 -16.3473 15.0396 -0.271674 -15.3027 14.6301 -0.241673 -14.8107 14.6708 -0.207606 -14.5718 14.931 -0.128291 -16.368 17.1614 -0.406475 -3.55427 4.89493 -0.397357 -3.4937 4.96835 -0.384724 -3.52683 5.14316 -0.36785 -3.67468 5.45395 -0.357831 -3.61759 5.54495 -0.353869 -3.40957 5.45882 -0.344011 -3.34448 5.53795 -0.310574 -3.77615 6.25431 -0.315616 -3.36621 5.90092 -0.314343 -3.13419 5.76146 -0.291872 -3.26946 6.13129 -0.279634 -3.22992 6.26679 -0.267714 -3.16585 6.36892 -0.247819 -3.21473 6.65673 -0.279161 -2.58693 5.83465 -0.275892 -2.43744 5.77115 -0.21112 -2.99434 6.97118 -0.236434 -2.51528 6.32163 -0.236846 -2.32674 6.18225 -0.237349 -2.15776 6.06528 -0.24771 -1.91323 5.77195 -0.240723 -1.82241 5.7911 -0.235925 -1.72366 5.79023 -0.222148 -1.68156 5.92607 -0.211849 -1.61741 6.01535 -0.195449 -1.5883 6.20707 -0.146042 -1.73229 6.91822 -0.140956 -1.614 6.9048 -0.150182 -1.42642 6.6599 -0.149873 -1.29501 6.57357 -0.119821 -1.29428 6.95673 -0.140031 -1.08373 6.55698 -0.131417 -0.991908 6.59923 -0.0627612 -1.09026 7.53783 -0.110208 -0.818199 6.74765 -0.0545025 -0.843116 7.47307 -0.0446545 -0.735117 7.52093 -0.0414609 -0.611799 7.46817 -0.0374579 -0.495135 7.44316 -0.0291431 -0.384507 7.47512 --0.00320264 -0.302173 7.82333 -0.000337638 -0.173496 7.69298 -0.000504948 -0.0520339 7.60995 -0.00500182 0.0681328 7.46504 -0.0121131 0.183097 7.29817 --0.0569483 0.292141 8.09616 --0.0515594 0.412936 7.94521 --0.0224471 0.518969 7.50313 -0.0106687 0.60709 7.03013 -0.0127478 0.706372 6.93365 --0.0217747 0.838848 7.27274 --0.368835 1.37028 11.2853 --0.0398768 1.06912 7.34797 --0.0427592 1.17617 7.31341 --0.0262942 1.24684 7.05054 -0.691672 -1.64962 -0.615411 -0.691759 -1.70115 -0.600272 -0.692612 -1.76122 -0.58993 -0.691193 -1.8053 -0.565999 -0.693747 -1.88131 -0.564575 -0.693795 -1.94227 -0.549364 -0.693969 -2.00196 -0.53289 -0.693556 -2.06319 -0.514466 -0.694065 -2.13177 -0.499967 -0.694994 -2.20952 -0.488609 -0.694938 -2.27077 -0.464807 -0.695341 -2.34859 -0.44936 -0.69535 -2.42688 -0.431576 -0.695932 -2.50585 -0.411333 -0.697614 -2.60226 -0.397862 -0.698849 -2.69898 -0.381372 -0.699417 -2.79702 -0.361861 -0.699776 -2.89442 -0.339529 -0.70086 -3.00979 -0.321923 -0.701273 -3.10796 -0.293141 -0.702582 -3.23418 -0.271834 -0.703817 -3.36973 -0.249969 -0.705479 -3.50552 -0.2237 -0.705219 -3.63198 -0.190224 -0.706948 -3.77813 -0.158114 -0.70793 -3.94218 -0.127054 -0.709025 -4.10719 -0.0903226 -0.710873 -4.30208 -0.0549058 -0.712398 -4.50555 -0.0156228 -0.715129 -4.72967 0.0268721 -0.716021 -4.94305 0.0784196 -0.717175 -5.18649 0.132255 -0.712699 -5.28045 0.216049 -0.713779 -5.55128 0.27966 -0.716618 -5.86248 0.348307 -0.717531 -6.18179 0.426248 -0.720821 -6.58051 0.509246 -0.722444 -6.98873 0.605263 -0.726258 -7.47413 0.711784 -0.728617 -7.99894 0.834292 -0.732623 -8.64144 0.974047 -0.739603 -9.46148 1.13798 -0.749901 -10.5074 1.33653 -0.757258 -11.6096 1.5743 -0.764423 -12.8668 1.8606 -0.771854 -14.3258 2.20733 -0.7733 -15.677 2.59537 -0.758308 -16.2734 2.94481 -0.74051 -16.7532 3.301 -0.755752 -20.0735 4.10289 -0.541008 -22.6651 7.41864 -0.504706 -22.0514 7.66876 -0.468775 -21.5796 7.94468 -0.430249 -22.462 8.66069 -0.395016 -22.0149 8.94492 -0.357262 -22.1167 9.42251 -0.376086 -15.288 7.17887 -0.364482 -13.7464 6.85542 -0.338961 -13.8545 7.19052 -0.313684 -13.8726 7.49349 -0.2876 -13.8837 7.79883 -0.25451 -14.3276 8.32513 -0.239709 -13.6933 8.31533 -0.202659 -14.1785 8.89077 -0.192913 -13.3873 8.77229 -0.172792 -13.1294 8.93775 -0.145575 -13.1433 9.26379 -0.0927598 -14.0266 10.1507 -0.0807645 -13.4566 10.128 -0.0373584 -13.856 10.7501 -0.00158111 -14.01 11.2263 --0.0326966 -14.0638 11.6457 --0.0636182 -14.0107 11.9967 --0.180069 -15.9702 13.9525 --0.16874 -14.8241 13.4775 --0.191492 -14.5126 13.6602 --0.245779 -14.8298 14.3917 --0.275489 -14.6311 14.686 -0.245331 -4.4061 5.49006 -0.23882 -4.27805 5.52202 -0.2601 -3.70132 5.09537 -0.253358 -3.62278 5.15689 -0.245969 -3.54334 5.21693 -0.238918 -3.46326 5.27541 -0.232957 -3.36904 5.31721 -0.218961 -3.38271 5.48793 -0.196642 -3.49779 5.79318 -0.204363 -3.22498 5.61281 -0.196372 -3.16238 5.69737 -0.195238 -3.01697 5.66742 -0.182599 -2.99137 5.80615 -0.138928 -3.26662 6.40306 -0.114969 -3.3288 6.70806 -0.110818 -3.19729 6.71896 -0.121447 -2.94014 6.51221 -0.0625151 -3.26238 7.30516 -0.0809046 -2.95232 6.99793 -0.0656646 -2.90245 7.15935 -0.0701023 -2.71434 7.05316 -0.120358 -2.22988 6.31246 -0.18803 -1.6763 5.34816 -0.170407 -1.68065 5.56461 -0.125824 -1.82299 6.13236 -0.133282 -1.66375 5.9919 -0.115369 -1.64067 6.1933 -0.108287 -1.56337 6.26361 -0.059291 -1.66579 6.87166 -0.0517279 -1.57232 6.93325 -0.0734038 -1.36293 6.61076 -0.0604316 -1.29522 6.74437 -0.0690191 -1.15246 6.60689 -0.0570143 -1.07813 6.72797 -0.0558824 -0.967613 6.70211 -0.0460909 -0.882555 6.79143 -0.0510193 -0.761303 6.70295 --0.0840423 -0.936522 8.352 --0.11563 -0.857098 8.69723 --0.1193 -0.720833 8.69619 --0.040509 -0.469291 7.6925 --0.0665881 -0.378515 7.97236 --0.0711627 -0.25756 7.9927 --0.0472015 -0.115467 7.67274 --0.0283612 0.0124348 7.40997 --0.0153726 0.129415 7.22437 --0.0924993 0.228803 8.10298 --0.0987376 0.353135 8.14269 --0.0917264 0.474293 8.02077 --0.0190267 0.558509 7.14045 --0.012268 0.659049 7.02522 --0.0150151 0.764299 7.02776 --0.0316769 0.885514 7.18694 --0.162345 1.16048 8.65057 --0.0505066 1.12372 7.34009 --0.030278 1.19781 7.07797 --0.0273639 1.29484 7.01217 -0.644396 -1.62061 -0.623225 -0.643572 -1.6721 -0.608984 -0.642538 -1.73189 -0.599566 -0.640313 -1.78353 -0.582622 -0.638727 -1.83604 -0.564095 -0.637983 -1.90461 -0.556067 -0.636285 -1.96406 -0.540711 -0.633999 -2.02506 -0.523403 -0.632641 -2.09343 -0.510118 -0.631712 -2.17099 -0.500072 -0.630395 -2.24903 -0.487785 -0.62791 -2.31898 -0.468266 -0.626053 -2.39706 -0.451696 -0.624011 -2.4673 -0.427967 -0.622873 -2.56333 -0.416026 -0.620559 -2.65124 -0.396754 -0.617828 -2.73955 -0.374853 -0.61685 -2.84623 -0.358336 -0.613963 -2.94363 -0.334807 -0.61156 -3.05993 -0.315709 -0.609635 -3.17663 -0.292888 -0.606695 -3.30252 -0.270019 -0.604398 -3.43886 -0.246079 -0.599993 -3.55576 -0.211988 -0.597635 -3.72058 -0.18861 -0.593539 -3.84691 -0.148973 -0.590006 -4.0115 -0.115764 -0.585752 -4.18679 -0.0792671 -0.582954 -4.40987 -0.0485191 -0.577711 -4.61416 -0.0060612 -0.573151 -4.85767 0.0355431 -0.566725 -4.99211 0.104281 -0.560072 -5.16573 0.171266 -0.553178 -5.42794 0.231412 -0.546433 -5.69911 0.299244 -0.538747 -6.00897 0.371943 -0.530545 -6.37852 0.450068 -0.520791 -6.77704 0.53873 -0.510145 -7.23411 0.637878 -0.498622 -7.72902 0.751159 -0.484808 -8.32313 0.879993 -0.468575 -9.01438 1.02905 -0.449452 -9.90312 1.20552 -0.426107 -10.9577 1.41852 -0.399047 -12.1077 1.67337 -0.366489 -13.4119 1.97936 -0.328385 -14.8571 2.34352 -0.29693 -15.4385 2.66964 -0.269355 -15.6659 2.97427 -0.209407 -17.7785 3.55013 -0.148936 -19.559 4.15037 --0.345829 -43.3758 8.66367 --0.401785 -42.7148 9.32142 --0.461378 -42.2399 9.99975 --0.138847 -22.9492 7.21753 --0.206776 -22.6125 7.98977 --0.241749 -21.324 8.42947 --0.307015 -22.0936 9.13045 --0.0855868 -15.2057 6.94796 --0.111239 -15.1461 7.23509 --0.125898 -14.8238 7.41346 --0.149138 -14.7188 7.67941 --0.178687 -14.7541 8.01082 --0.177111 -14.0991 8.0142 --0.201773 -14.0454 8.29945 --0.232614 -14.0835 8.63633 --0.258552 -14.0269 8.92856 --0.290536 -14.0773 9.28581 --0.308756 -13.8616 9.49333 --0.341296 -13.8985 9.85427 --0.357434 -13.6656 10.0509 --0.400629 -13.8539 10.5258 --0.430664 -13.8084 10.856 --0.52902 -14.7598 11.9125 --0.521654 -14.1512 11.8613 --0.570869 -14.3374 12.4046 --0.567973 -13.8095 12.3945 --0.610153 -13.8766 12.8618 -0.115151 -4.4844 5.16974 -0.114246 -4.32986 5.17907 -0.0749907 -4.63011 5.60495 -0.0862555 -4.34749 5.49643 -0.0724673 -4.33918 5.64668 -0.111451 -3.77788 5.23264 -0.119078 -3.56733 5.15739 -0.115274 -3.48103 5.20916 -0.11482 -3.35485 5.21403 -0.0988807 -3.37824 5.39132 -0.0817877 -3.40146 5.57816 -0.00823215 -3.90128 6.37908 -0.0850431 -3.13155 5.56092 -0.0738022 -3.09897 5.6843 --3.46825e-05 -3.54001 6.48456 --0.01249 -3.4942 6.6247 --0.00902524 -3.33562 6.59788 --0.00549909 -3.1789 6.56727 -0.004118 -2.98393 6.46485 --0.0684746 -3.31865 7.26237 --0.0725187 -3.20463 7.31578 --0.089642 -3.16483 7.50749 --0.0193536 -2.6275 6.74164 --0.0271877 -2.54915 6.83643 -0.115408 -1.69368 5.27894 -0.107178 -1.64385 5.3675 -0.0862145 -1.65306 5.60207 -0.0513461 -1.71944 5.99539 -0.0378064 -1.67534 6.14118 -0.0305308 -1.60657 6.23098 -0.0325833 -1.49876 6.21614 --0.0317585 -1.63042 6.92833 --0.0329293 -1.52117 6.94191 --0.0131379 -1.34538 6.72369 -0.0059082 -1.18311 6.52051 --0.00154518 -1.10424 6.61315 --0.00277006 -1.00438 6.627 --0.0259761 -0.956143 6.88255 --0.00565325 -0.807902 6.66895 --0.141879 -0.974049 8.17793 --0.141172 -0.844719 8.1791 --0.188108 -0.791086 8.70087 --0.194331 -0.664242 8.77804 --0.115867 -0.434526 7.91195 --0.164774 -0.361418 8.4594 --0.106069 -0.185059 7.8141 --0.0816702 -0.0508435 7.54281 --0.0623978 0.0702539 7.33897 --0.11189 0.170463 7.88971 --0.114967 0.291102 7.93059 --0.122618 0.413332 8.01928 --0.0833569 0.520214 7.58835 --0.0543134 0.618355 7.26523 --0.0550123 0.729508 7.27841 --0.0524776 0.837524 7.26006 --0.0498281 0.944136 7.23001 --0.0584863 1.06714 7.33645 --0.0560503 1.17607 7.31223 --0.0323374 1.24715 7.04991 -0.598533 -1.58982 -0.630923 -0.595955 -1.64872 -0.624083 -0.592906 -1.70057 -0.609206 -0.589528 -1.7531 -0.592867 -0.587135 -1.81317 -0.581329 -0.583666 -1.87269 -0.568452 -0.579851 -1.93284 -0.553918 -0.576654 -1.9938 -0.53751 -0.573348 -2.05443 -0.519642 -0.569425 -2.14002 -0.516434 -0.565622 -2.20082 -0.494866 -0.561514 -2.26963 -0.476856 -0.55835 -2.35707 -0.46649 -0.55327 -2.43521 -0.449015 -0.548771 -2.51406 -0.429179 -0.545128 -2.61127 -0.41582 -0.540045 -2.69002 -0.391117 -0.5353 -2.79617 -0.376542 -0.529615 -2.89324 -0.354834 -0.52442 -3.00925 -0.337655 -0.518278 -3.11617 -0.313246 -0.512333 -3.24278 -0.292391 -0.506104 -3.36855 -0.267741 -0.499129 -3.49538 -0.238999 -0.491864 -3.62133 -0.206366 -0.484029 -3.78649 -0.181057 -0.475575 -3.95144 -0.150395 -0.466508 -4.11619 -0.114477 -0.456396 -4.32039 -0.0824751 -0.44569 -4.534 -0.0459235 -0.434244 -4.76781 -0.00630403 -0.424457 -4.86368 0.0670402 -0.411492 -5.08666 0.121575 -0.398884 -5.29845 0.184915 -0.384346 -5.55033 0.250279 -0.367851 -5.86132 0.317128 -0.349274 -6.20072 0.391472 -0.32907 -6.58961 0.473482 -0.306281 -7.00705 0.566784 -0.280353 -7.50246 0.670573 -0.251008 -8.03679 0.790402 -0.216059 -8.67966 0.927439 -0.176256 -9.43851 1.08723 -0.125192 -10.4255 1.27869 -0.0705617 -11.4275 1.50523 -0.00308581 -12.6736 1.78081 --0.0739532 -14.0532 2.11051 --0.130427 -14.837 2.43412 --0.167373 -15.107 2.72969 --0.225114 -15.8276 3.09339 --0.371157 -18.3589 3.74662 --0.402794 -18.3568 4.07868 --0.432223 -18.3194 4.40622 --0.460702 -18.2568 4.72958 --0.490124 -18.1981 5.05374 --0.518596 -18.1434 5.3795 --0.547634 -18.0825 5.70443 --0.575584 -17.9968 6.02333 --0.60304 -17.9251 6.34655 --0.63104 -17.8472 6.66864 --0.658846 -17.7642 6.98981 --0.688467 -17.7032 7.3196 --0.718516 -17.6544 7.65592 --0.746582 -17.5627 7.97809 --0.779363 -17.5482 8.33317 --0.616358 -14.8773 7.55243 --0.634147 -14.7143 7.79502 --1.21081 -21.7398 11.4235 --0.676842 -14.4851 8.32237 --0.697664 -14.3628 8.58306 --0.728102 -14.3594 8.90791 --0.754946 -14.3057 9.21059 --0.772772 -14.1426 9.45366 --0.764405 -13.6942 9.52302 --0.784909 -13.5673 9.78115 --0.835437 -13.7528 10.2452 --0.91032 -14.1822 10.8924 --0.942881 -14.1532 11.2467 --1.03165 -14.6626 12.0036 --1.36377 -17.4497 14.5302 --0.0461426 -4.79128 5.04787 --0.0476735 -4.68854 5.11069 --0.0416299 -4.51007 5.10691 --0.0310732 -4.29539 5.06518 --0.0469707 -4.31996 5.23174 --0.0563884 -4.27442 5.33876 --0.0908469 -4.43313 5.6471 --0.0723144 -4.16987 5.54513 --0.011344 -3.59438 5.10414 --0.00986805 -3.48166 5.12751 --0.0373005 -3.58102 5.38586 --0.0141322 -3.31559 5.234 --0.0499504 -3.45835 5.55683 --0.0434529 -3.31552 5.54387 --0.11166 -3.64966 6.14166 --0.131415 -3.66132 6.34563 --0.112698 -3.43394 6.22793 --0.126269 -3.40385 6.38212 --0.250031 -3.99967 7.48108 --0.115534 -3.12301 6.36575 --0.129576 -3.09149 6.52626 --0.153438 -3.10692 6.77301 --0.217253 -3.31595 7.37629 --0.131766 -2.77919 6.66134 --0.106318 -2.55038 6.46735 --0.107706 -2.45475 6.51637 --0.00136378 -1.89344 5.59504 --0.00259223 -1.81284 5.63256 --0.00349068 -1.73157 5.66862 --0.0697854 -1.90276 6.30952 --0.0705605 -1.81065 6.34735 --0.0487486 -1.63981 6.17862 --0.0598907 -1.58571 6.31471 --0.103304 -1.63251 6.76178 --0.107026 -1.54435 6.83277 --0.100215 -1.42203 6.79732 --0.0758113 -1.25738 6.59677 --0.0725074 -1.15475 6.60406 --0.10686 -1.13821 6.96708 --0.0949587 -1.01009 6.88456 --0.0714574 -0.863483 6.69223 --0.137708 -0.88894 7.3771 --0.221781 -0.921303 8.25062 --0.234484 -0.818194 8.42858 --0.24932 -0.71073 8.61484 --0.160388 -0.477802 7.76156 --0.171522 -0.373227 7.91298 --0.131659 -0.222562 7.54693 --0.119914 -0.103528 7.46603 --0.111655 0.0115233 7.42257 --0.126487 0.118363 7.61597 --0.150184 0.230861 7.90714 --0.143503 0.351304 7.87766 --0.133132 0.469505 7.8063 --0.10322 0.575904 7.52403 --0.085522 0.681283 7.37933 --0.0666724 0.779836 7.21324 --0.0652147 0.890952 7.23389 --0.186801 1.15672 8.60827 --0.0676583 1.12549 7.34839 --0.0394642 1.19782 7.07718 --0.0278611 1.28985 6.98243 -0.551177 -1.60955 -0.625575 -0.546375 -1.66881 -0.618098 -0.542204 -1.72894 -0.608942 -0.536836 -1.78088 -0.592163 -0.532456 -1.84036 -0.580185 -0.526761 -1.90026 -0.566671 -0.521684 -1.96096 -0.551283 -0.516345 -2.02982 -0.540035 -0.511028 -2.0898 -0.521436 -0.505025 -2.16726 -0.511894 -0.498809 -2.23679 -0.494803 -0.49281 -2.32381 -0.485773 -0.486507 -2.38413 -0.459872 -0.478977 -2.4709 -0.446387 -0.47177 -2.55926 -0.430052 -0.464844 -2.63786 -0.406855 -0.457299 -2.74369 -0.394101 -0.449295 -2.84979 -0.378135 -0.440122 -2.9478 -0.354936 -0.431196 -3.05445 -0.332543 -0.421741 -3.17965 -0.314119 -0.4123 -3.29595 -0.288247 -0.40106 -3.43135 -0.265391 -0.390797 -3.55805 -0.234868 -0.378654 -3.7036 -0.206292 -0.365949 -3.84911 -0.173141 -0.351974 -4.04232 -0.148533 -0.337528 -4.21727 -0.112461 -0.320419 -4.44009 -0.0823253 -0.305118 -4.59562 -0.0296311 -0.288697 -4.76958 0.0240589 -0.271035 -4.98239 0.0764591 -0.253348 -5.1654 0.140733 -0.230234 -5.427 0.199636 -0.206141 -5.70808 0.264817 -0.181218 -6.00741 0.337247 -0.149588 -6.38645 0.412582 -0.116812 -6.77324 0.499862 -0.0788355 -7.22931 0.596541 -0.036601 -7.73401 0.706971 --0.0149701 -8.34684 0.832182 --0.0716067 -9.02662 0.978102 --0.140644 -9.86407 1.14966 --0.219546 -10.807 1.35324 --0.314758 -11.9348 1.5984 --0.420138 -13.1661 1.88982 --0.513154 -14.1517 2.20509 --0.563241 -14.4948 2.49254 --0.629867 -15.0406 2.81653 --0.727474 -15.9736 3.21261 --2.01658 -32.257 5.96786 --2.08661 -32.4078 6.57562 --2.78257 -39.3829 9.18948 --2.98077 -40.8636 10.2449 --1.61859 -23.2222 7.60869 --1.65141 -23.091 8.0146 --1.54955 -21.5299 7.96636 --1.56665 -21.2702 8.30115 --1.59688 -21.1475 8.67955 --1.70469 -21.8003 9.35028 --1.72762 -21.5934 9.71239 --1.66835 -20.5902 9.74052 --1.09584 -14.7876 7.63481 --1.10994 -14.6227 7.8762 --1.1553 -14.7416 8.25174 --1.18523 -14.7183 8.56658 --1.16523 -14.2569 8.65679 --1.20382 -14.3024 9.00956 --1.68936 -18.0928 11.5015 --1.27562 -14.3364 9.70707 --1.21165 -13.5379 9.56479 --1.26103 -13.6609 9.98205 --1.3298 -13.923 10.5056 --1.38268 -14.0477 10.9561 --1.43509 -14.1615 11.414 --1.44499 -13.9438 11.6411 --0.207404 -4.79498 4.96906 --0.200586 -4.64723 4.9954 --0.190956 -4.47662 4.9985 --0.190092 -4.3757 5.05543 --0.209708 -4.40838 5.2291 --0.20436 -4.27573 5.2569 --0.222239 -4.29413 5.42552 --0.222281 -4.20168 5.49119 --0.133837 -3.56772 5.00018 --0.1399 -3.51734 5.08888 --0.157731 -3.53983 5.25812 --0.241029 -3.92349 5.84737 --0.254774 -3.90182 5.99625 --0.252808 -3.7953 6.04604 --0.259618 -3.73144 6.14819 --0.222083 -3.44201 5.95692 --0.202583 -3.24994 5.87768 --0.216238 -3.22688 6.02831 --0.269071 -3.39033 6.45909 --0.204305 -2.98943 6.0575 --0.225439 -2.99568 6.26558 --0.404344 -3.69037 7.62258 --0.374993 -3.44934 7.47699 --0.201918 -2.62388 6.26724 --0.194474 -2.50319 6.26521 --0.231151 -2.55676 6.59651 --0.137578 -2.11254 5.94162 --0.072292 -1.79386 5.48874 --0.0867265 -1.76782 5.64265 --0.182861 -2.01903 6.45492 --0.160945 -1.85612 6.3292 --0.296364 -2.19271 7.47842 --0.282031 -2.04485 7.42811 --0.156637 -1.58433 6.46415 --0.15312 -1.48584 6.48719 --0.162953 -1.42176 6.62227 --0.162061 -1.32987 6.67117 --0.176925 -1.27176 6.85254 --0.173041 -1.16938 6.87956 --0.177434 -1.08496 6.98239 --0.143331 -0.922162 6.73384 --0.13761 -0.820358 6.74509 --0.234171 -0.882134 7.67469 --0.280509 -0.839093 8.15624 --0.311873 -0.762178 8.52004 --0.22805 -0.541858 7.81775 --0.216912 -0.418423 7.78268 --0.176061 -0.163152 7.53709 --0.173128 -0.0500074 7.57436 --0.160279 0.0659633 7.52055 --0.161257 0.178076 7.6039 --0.192384 0.292934 7.98372 --0.153808 0.409569 7.67501 --0.135638 0.521684 7.56336 --0.11917 0.630624 7.45971 --0.0967841 0.732681 7.3046 --0.0848972 0.837625 7.24714 --0.454419 1.36997 11.2677 --0.0902809 1.08241 7.45315 --0.0684037 1.17373 7.29128 --0.0403174 1.24895 7.05919 -0.506881 -1.58473 -0.639927 -0.501027 -1.63625 -0.626775 -0.494951 -1.67983 -0.605976 -0.48783 -1.73917 -0.596599 -0.481576 -1.79843 -0.585738 -0.475109 -1.84976 -0.567329 -0.468263 -1.91782 -0.559147 -0.461052 -1.98645 -0.549016 -0.452747 -2.05449 -0.537352 -0.445206 -2.11484 -0.518116 -0.437131 -2.18418 -0.502337 -0.428744 -2.26152 -0.490018 -0.421127 -2.33119 -0.470224 -0.411753 -2.41781 -0.458245 -0.402187 -2.49658 -0.43901 -0.391775 -2.59233 -0.426691 -0.382126 -2.6804 -0.406801 -0.370844 -2.77685 -0.388737 -0.359112 -2.89209 -0.375711 -0.347395 -2.99844 -0.355237 -0.334698 -3.1141 -0.335201 -0.321276 -3.23089 -0.311366 -0.307601 -3.34691 -0.284126 -0.29362 -3.47323 -0.256227 -0.278381 -3.59846 -0.224557 -0.260634 -3.76246 -0.200454 -0.242202 -3.93728 -0.173549 -0.222537 -4.12063 -0.143677 -0.198049 -4.35241 -0.119981 -0.180624 -4.47828 -0.0636584 -0.159353 -4.65282 -0.0134881 -0.135934 -4.84541 0.0383354 -0.111671 -5.04832 0.0951007 -0.0849076 -5.26986 0.155273 -0.0553839 -5.52048 0.218928 -0.0200261 -5.82935 0.283585 --0.0156427 -6.12834 0.360068 --0.0596996 -6.52482 0.437801 --0.107594 -6.94089 0.527996 --0.161543 -7.41515 0.629341 --0.222975 -7.94765 0.744929 --0.294605 -8.57717 0.877145 --0.379504 -9.32394 1.03115 --0.475877 -10.1672 1.21298 --0.584328 -11.1068 1.4278 --0.722792 -12.3088 1.68906 --0.860149 -13.4651 1.98983 --0.922953 -13.8403 2.26407 --0.984339 -14.1802 2.54861 --1.1573 -15.5708 2.97427 --1.47028 -18.2308 3.6282 --3.12185 -33.1477 6.31098 --3.17563 -33.0653 6.89759 --3.23038 -32.9905 7.48658 --3.73345 -36.8337 8.90751 --6.76014 -61.273 16.3575 --2.39408 -23.8577 7.49924 --2.39714 -23.489 7.84932 --2.16894 -21.2637 7.62295 --2.35397 -22.3885 8.40367 --2.26853 -21.3516 8.48894 --2.28416 -21.1297 8.83567 --2.23 -20.3755 8.97455 --2.31827 -20.7086 9.52836 --2.32345 -20.4077 9.83254 --1.57808 -14.7102 7.72591 --2.15722 -18.5798 9.85083 --1.64129 -14.6761 8.35153 --2.14714 -17.9185 10.3351 --1.72264 -14.7575 9.05807 --1.68511 -14.2657 9.12794 --2.28123 -17.9378 11.5918 --1.70178 -13.9099 9.59739 --1.74989 -13.9821 9.98715 --1.77297 -13.8958 10.2848 --1.80965 -13.8859 10.6379 --2.55501 -18.1478 14.0021 --2.01084 -14.6174 11.9179 --1.81082 -13.1983 11.2512 --1.8345 -13.1085 11.5599 --0.35208 -4.52261 4.95916 --0.35561 -4.45992 5.04948 --0.377451 -4.49297 5.22379 --0.434355 -4.71119 5.57309 --2.08229 -13.2694 13.7662 --0.47428 -4.74019 5.93283 --0.297439 -3.7526 5.11414 --0.268145 -3.52978 5.02765 --0.396997 -4.08371 5.77017 --0.417089 -4.0919 5.94989 --0.439146 -4.10869 6.14662 --0.429657 -3.97375 6.1701 --0.402027 -3.76438 6.09784 --0.351843 -3.45697 5.8868 --0.33009 -3.28222 5.83313 --0.294887 -3.05276 5.6945 --0.349987 -3.20157 6.08675 --0.370697 -3.20517 6.28789 --0.497915 -3.61535 7.13262 --0.363777 -3.00879 6.39176 --0.432314 -3.17597 6.89221 --0.297173 -2.59761 6.11791 --0.263216 -2.39848 5.96836 --0.264345 -2.32518 6.04177 --0.174315 -1.94775 5.51158 --0.159736 -1.83508 5.4794 --0.1714 -1.80183 5.61565 --0.162373 -1.70521 5.61598 --0.25581 -1.90739 6.32837 --0.274195 -1.87604 6.52344 --0.396977 -2.1243 7.48025 --0.232025 -1.59905 6.3639 --0.265337 -1.60005 6.67906 --0.251937 -1.48319 6.65552 --0.238348 -1.36691 6.62944 --0.242762 -1.29031 6.73506 --0.243767 -1.20511 6.82038 --0.257871 -1.14324 7.01063 --0.227437 -0.997699 6.85185 --0.210253 -0.877761 6.78688 --0.249505 -0.847869 7.18815 --0.374567 -0.923683 8.30484 --0.369551 -0.802017 8.36542 --0.31231 -0.620591 7.98097 --0.275868 -0.472652 7.76998 --0.25851 -0.347632 7.70439 --0.240643 -0.225375 7.64635 --0.216812 -0.101643 7.52654 --0.195295 0.0168267 7.42419 --0.200653 0.124778 7.5684 --0.196584 0.238705 7.63106 --0.17927 0.352638 7.56262 --0.170481 0.467864 7.58145 --0.170787 0.586723 7.68801 --0.130957 0.685282 7.39499 --0.109358 0.787281 7.2792 --0.0975787 0.89511 7.26086 --0.218913 1.16389 8.65514 --0.0857937 1.12752 7.35675 --0.0486661 1.19683 7.06644 --0.032698 1.29196 6.99187 -0.425665 -1.82234 -0.585428 -0.416835 -1.88256 -0.572177 -0.407986 -1.95 -0.56336 -0.398841 -2.00199 -0.541199 -0.389114 -2.07904 -0.534182 -0.379576 -2.13879 -0.51441 -0.369331 -2.21594 -0.503402 -0.358879 -2.28518 -0.484944 -0.346684 -2.37143 -0.474495 -0.3357 -2.44072 -0.45185 -0.323451 -2.53636 -0.441135 -0.311232 -2.62313 -0.423166 -0.296676 -2.72843 -0.411158 -0.283358 -2.81688 -0.387344 -0.266908 -2.94099 -0.377088 -0.252429 -3.03819 -0.351279 -0.236481 -3.15382 -0.329949 -0.220798 -3.25965 -0.301563 -0.202132 -3.38538 -0.276408 -0.184152 -3.51046 -0.247339 -0.16095 -3.68382 -0.229239 -0.140256 -3.82856 -0.196857 -0.115008 -4.01133 -0.170823 -0.0880262 -4.20444 -0.141038 -0.0646814 -4.35843 -0.0955629 -0.0398893 -4.52196 -0.0472151 -0.0106737 -4.71497 0.000676036 --0.0180294 -4.90682 0.054817 --0.0512935 -5.12772 0.11035 --0.0873583 -5.36801 0.170363 --0.126242 -5.6372 0.234636 --0.170219 -5.9355 0.304487 --0.221475 -6.29206 0.378628 --0.276216 -6.6676 0.463478 --0.340976 -7.11144 0.556735 --0.412874 -7.61289 0.662577 --0.495519 -8.18209 0.783638 --0.591899 -8.84908 0.923501 --0.703157 -9.62101 1.08688 --0.825642 -10.4598 1.27913 --0.978636 -11.5123 1.50944 --1.15503 -12.7186 1.786 --1.26824 -13.3924 2.06524 --1.33532 -13.7054 2.33568 --1.44068 -14.2882 2.64787 --1.91161 -17.5577 3.32603 --4.17011 -33.2769 6.5433 --4.22208 -33.1675 7.13022 --3.69693 -29.0292 6.91064 --4.30308 -32.7942 8.27127 --4.90631 -36.4313 9.7452 --4.95824 -36.2752 10.3902 --2.72598 -21.031 6.89346 --2.77263 -21.0438 7.30271 --2.81185 -21.0022 7.69979 --2.45755 -18.4665 7.27128 --2.70611 -19.7677 8.09841 --2.47662 -18.081 7.87086 --2.91888 -20.5219 9.19897 --2.93689 -20.3443 9.55203 --2.73264 -18.5949 9.62205 --2.69561 -18.1259 9.80434 --2.5143 -16.6087 9.82702 --2.22852 -14.7911 9.2236 --2.3108 -15.0299 9.70672 --2.16621 -14.039 9.48392 --2.16649 -13.844 9.70937 --2.45725 -15.1609 10.8968 --2.77273 -16.5623 12.2148 --2.66233 -15.7599 12.0961 --2.56969 -15.0637 12.0217 --2.6149 -15.0557 12.4318 --2.72754 -15.3759 13.1045 --2.49889 -14.0483 12.4925 --2.61984 -14.3984 13.2034 --0.586393 -4.7524 5.37002 --0.582196 -4.65297 5.43894 --0.553121 -4.44332 5.40527 --0.551064 -4.35862 5.48168 --0.615599 -4.55927 5.84074 --0.60796 -4.44633 5.89782 --0.589197 -4.28512 5.90198 --0.618142 -4.32497 6.12118 --0.589924 -4.1306 6.0837 --0.528676 -3.80495 5.88263 --0.513232 -3.66884 5.89354 --0.523449 -3.63165 6.0252 --0.631447 -3.9609 6.64462 --0.42377 -3.1097 5.69159 --0.437944 -3.09006 5.84028 --0.506267 -3.26028 6.27564 --0.548938 -3.32929 6.58614 --0.59233 -3.39445 6.90928 --0.54619 -3.15742 6.75434 --0.581524 -3.18562 7.03725 --0.50951 -2.87261 6.72728 --0.36749 -2.35825 6.00732 --0.306304 -2.1044 5.72852 --0.253589 -1.88625 5.49548 --0.296346 -1.94272 5.82072 --0.219423 -1.66414 5.42659 --0.562773 -2.50544 7.61822 --0.37733 -1.93996 6.55815 --0.359549 -1.81822 6.53301 --0.498664 -2.06797 7.51885 --0.341493 -1.61804 6.58741 --0.359472 -1.57565 6.7906 --0.302956 -1.3763 6.50186 --0.319669 -1.32941 6.7029 --0.308057 -1.22518 6.71261 --0.344969 -1.20677 7.06639 --0.294521 -1.03419 6.80349 --0.289335 -0.939423 6.85617 --0.264982 -0.816995 6.77123 --0.347803 -0.839888 7.49428 --0.443248 -0.856787 8.33756 --0.435039 -0.734969 8.39761 --0.321682 -0.508512 7.61833 --0.31124 -0.395739 7.65264 --0.281727 -0.268345 7.52687 --0.266144 -0.153268 7.50749 --0.245025 -0.036645 7.44644 --0.236559 0.0737866 7.49244 --0.216753 0.187724 7.43714 --0.204757 0.299728 7.44933 --0.207468 0.413435 7.59911 --0.190978 0.526817 7.57771 --0.186439 0.646429 7.66328 --0.133593 0.734753 7.28072 --0.119926 0.843358 7.27346 --0.4903 1.36773 11.2038 --0.0995963 1.0712 7.34234 --0.0860191 1.18174 7.33925 --0.0454071 1.24805 7.04874 -0.367788 -1.84573 -0.584971 -0.357197 -1.90439 -0.57138 -0.346116 -1.97218 -0.561829 -0.3337 -2.04031 -0.550451 -0.323015 -2.10096 -0.531381 -0.308784 -2.18586 -0.52704 -0.296681 -2.25388 -0.509701 -0.283975 -2.32341 -0.490216 -0.270928 -2.40085 -0.473802 -0.256517 -2.47854 -0.455171 -0.241485 -2.56495 -0.438829 -0.225568 -2.66096 -0.42419 -0.207284 -2.77541 -0.415123 -0.19046 -2.872 -0.394252 -0.171967 -2.97687 -0.374721 -0.154244 -3.07407 -0.347716 -0.133541 -3.19846 -0.328669 -0.11286 -3.31397 -0.302271 -0.0893958 -3.44831 -0.278816 -0.0686689 -3.56429 -0.244607 -0.0404473 -3.73605 -0.224776 -0.00957336 -3.91809 -0.201996 --0.0235974 -4.11939 -0.178533 --0.045752 -4.22544 -0.123444 --0.0786528 -4.41756 -0.0857937 --0.109684 -4.58018 -0.035444 --0.146887 -4.79153 0.0107518 --0.184834 -5.0023 0.0639549 --0.2274 -5.24195 0.119328 --0.270796 -5.48074 0.182876 --0.320106 -5.75844 0.249424 --0.376466 -6.07431 0.321088 --0.441382 -6.44896 0.398091 --0.513924 -6.8617 0.484981 --0.596626 -7.33275 0.582637 --0.686333 -7.84106 0.69497 --0.795644 -8.46647 0.822218 --0.917135 -9.15801 0.97079 --1.05823 -9.95604 1.14493 --1.2214 -10.8776 1.35058 --1.41239 -11.9533 1.59604 --1.57359 -12.8157 1.86649 --1.64935 -13.12 2.12271 --1.75084 -13.5764 2.40551 --2.12139 -15.6542 2.89426 --2.62029 -18.4507 3.55488 --4.39105 -28.7156 5.45452 --4.43277 -28.6056 5.96036 --4.46339 -28.4296 6.45333 --4.5187 -28.4004 6.97394 --4.57521 -28.3703 7.49743 --4.61823 -28.2647 8.00581 --4.66655 -28.1876 8.52259 --3.38466 -20.8695 7.00156 --2.70745 -16.9756 6.2359 --2.75433 -17.0188 6.58475 --2.82881 -17.2027 6.98719 --2.97321 -17.7399 7.52814 --3.0595 -17.9689 7.9783 --3.10945 -18.0044 8.3654 --3.22393 -18.3583 8.8935 --2.74162 -15.7489 8.13214 --3.06471 -17.1344 9.11738 --3.15539 -17.3577 9.6044 --3.59097 -19.2169 10.9381 --3.07 -16.527 9.95199 --2.82989 -15.2027 9.60623 --2.80247 -14.8853 9.78615 --2.81673 -14.7601 10.0739 --2.95875 -15.2048 10.7191 --3.32178 -16.6117 12.0199 --3.11566 -15.4928 11.6968 --4.0288 -19.218 14.7222 --2.67626 -13.2133 10.8742 --2.62659 -12.8247 10.9526 --2.66964 -12.8244 11.3235 --2.68489 -12.7085 11.6109 --0.757469 -4.77451 5.31231 --0.746694 -4.66125 5.36966 --0.737979 -4.55507 5.43092 --0.741496 -4.49758 5.53671 --0.737893 -4.40985 5.6144 --0.73299 -4.32166 5.69075 --0.76369 -4.36103 5.90005 --0.76873 -4.30786 6.01862 --0.661786 -3.85303 5.6893 --0.646764 -3.73203 5.71809 --0.661555 -3.71158 5.8649 --0.645572 -3.58849 5.88969 --0.921265 -4.43472 7.16546 --0.650966 -3.46849 6.09706 --0.530183 -3.01167 5.65196 --0.532475 -2.95228 5.74302 --0.586904 -3.05503 6.07948 --0.61557 -3.07162 6.30476 --0.625267 -3.02994 6.4485 --0.58905 -2.84954 6.36338 --0.820934 -3.43095 7.61035 --0.406488 -2.20421 5.63423 --0.470827 -2.31419 6.04559 --0.42898 -2.13814 5.91582 --0.327419 -1.8152 5.46098 --0.305804 -1.70024 5.41782 --0.678882 -2.53549 7.55242 --0.65627 -2.39462 7.53915 --0.660436 -2.31622 7.67912 --0.623966 -2.1478 7.58716 --0.482977 -1.76347 6.8674 --0.550575 -1.82068 7.38235 --0.414274 -1.47001 6.65679 --0.40865 -1.38235 6.72642 --0.387933 -1.26695 6.69954 --0.402226 -1.21012 6.8906 --0.404061 -1.13045 7.01412 --0.357815 -0.976678 6.81765 --0.338314 -0.865925 6.79224 --0.389165 -0.846311 7.25171 --0.559484 -0.954865 8.58212 --0.506506 -0.785889 8.35044 --0.398169 -0.569874 7.69217 --0.368991 -0.442846 7.60984 --0.357713 -0.330496 7.65325 --0.333718 -0.211701 7.60611 --0.300724 -0.0889667 7.47723 --0.285206 0.0232533 7.49467 --0.256235 0.137571 7.39135 --0.241837 0.248188 7.41493 --0.234174 0.359832 7.48609 --0.225922 0.474081 7.56543 --0.238639 0.599625 7.84142 --0.168295 0.687454 7.3507 --0.148247 0.794883 7.31498 --0.524534 1.28068 11.1993 --0.234791 1.15413 8.53333 --0.107278 1.13636 7.40414 --0.0595461 1.19925 7.07526 --0.038244 1.29727 7.02099 -0.320138 -1.80708 -0.597455 -0.307536 -1.87404 -0.590775 -0.295682 -1.93326 -0.57633 -0.282508 -1.99287 -0.560251 -0.269057 -2.06058 -0.548118 -0.254271 -2.12864 -0.534158 -0.240142 -2.20491 -0.523536 -0.224412 -2.28238 -0.5105 -0.208963 -2.35009 -0.490602 -0.193662 -2.4278 -0.473162 -0.174387 -2.52286 -0.462997 -0.157073 -2.60947 -0.445241 -0.136695 -2.71345 -0.43386 -0.117072 -2.80973 -0.414811 -0.0972395 -2.90537 -0.392941 -0.0752585 -3.01117 -0.371918 -0.0530383 -3.11624 -0.347685 -0.0280927 -3.24032 -0.327173 -0.00413841 -3.35574 -0.299189 --0.0241238 -3.49871 -0.277433 --0.0547084 -3.6513 -0.254191 --0.0900035 -3.83189 -0.234742 --0.125457 -4.01428 -0.208937 --0.151086 -4.11901 -0.156767 --0.189591 -4.31048 -0.122662 --0.225264 -4.47264 -0.0756405 --0.265974 -4.67303 -0.0314619 --0.308382 -4.87267 0.0194088 --0.354724 -5.09265 0.0738633 --0.40646 -5.34022 0.130754 --0.462068 -5.60666 0.193365 --0.522825 -5.89249 0.262747 --0.593731 -6.23604 0.335571 --0.674318 -6.62813 0.416168 --0.764517 -7.0673 0.506579 --0.867171 -7.56492 0.609366 --0.981295 -8.11959 0.727371 --1.11568 -8.76966 0.862843 --1.27019 -9.51616 1.02116 --1.43034 -10.2778 1.20593 --1.64392 -11.3109 1.42703 --1.85182 -12.2899 1.6823 --1.96228 -12.7333 1.936 --2.03828 -12.9846 2.18928 --2.24511 -13.9056 2.52261 --2.91988 -17.1942 3.17951 --6.12669 -32.8419 6.2922 --6.21743 -32.9265 6.91099 --6.27225 -32.8363 7.50308 --6.30979 -32.6595 8.0778 --6.61676 -33.4068 9.49932 --6.6536 -33.2148 10.0871 --3.57648 -18.6016 6.50345 --3.21287 -16.7294 6.29189 --3.29457 -16.9172 6.68736 --3.31838 -16.8388 7.00153 --3.39195 -16.984 7.39939 --3.43441 -16.9825 7.75093 --3.17436 -15.663 7.56789 --3.14446 -15.362 7.77309 --3.61728 -17.1971 8.93526 --3.23213 -15.3903 8.45917 --3.12549 -14.7717 8.49845 --3.19044 -14.8695 8.88686 --3.28757 -15.095 9.3554 --3.30985 -15.0113 9.66673 --3.33968 -14.9553 9.99763 --3.42188 -15.1003 10.4567 --3.89376 -16.7512 11.8896 --3.91812 -16.6439 12.2515 --4.00096 -16.7547 12.7683 --3.7626 -15.6606 12.4406 --3.06731 -12.8963 10.8259 --3.03035 -12.596 10.965 --3.18243 -12.9825 11.6456 --3.18319 -12.8149 11.9005 --3.2178 -12.7683 12.2613 --3.53284 -13.6842 13.4885 --0.928748 -4.59675 5.5543 --0.901288 -4.43801 5.56706 --0.888425 -4.32958 5.62391 --0.896037 -4.28922 5.74857 --1.03251 -4.66023 6.31507 --0.885755 -4.11947 5.91051 --0.788608 -3.74986 5.66529 --0.770549 -3.6299 5.69268 --0.758083 -3.52859 5.74001 --0.767407 -3.49305 5.86985 --0.76015 -3.40822 5.93788 --0.728045 -3.2519 5.90908 --0.69823 -3.10364 5.88429 --0.672885 -2.9685 5.872 --0.693431 -2.96348 6.05405 --0.708413 -2.93745 6.21234 --0.725708 -2.91669 6.38809 --0.669883 -2.70545 6.24196 --0.520591 -2.2665 5.66878 --0.523009 -2.21295 5.76701 --0.574747 -2.27687 6.10137 --0.511374 -2.06291 5.89125 --0.487723 -1.94884 5.87157 --0.565904 -2.0588 6.35262 --0.529004 -1.91202 6.26835 --0.505133 -1.79468 6.24445 --0.71563 -2.14914 7.45091 --0.700526 -2.03749 7.49549 --0.686623 -1.92721 7.54727 --0.514953 -1.53277 6.71527 --0.394473 -1.25012 6.14451 --0.4229 -1.22894 6.41031 --0.495947 -1.27158 6.95352 --0.409612 -1.06224 6.55096 --0.420495 -1.00136 6.73015 --0.411075 -0.909755 6.79291 --0.385366 -0.796319 6.74732 --0.624381 -0.986269 8.4342 --0.441463 -0.688366 7.37311 --0.455889 -0.607801 7.60752 --0.421741 -0.481621 7.51691 --0.419133 -0.381036 7.65032 --0.399069 -0.265486 7.65378 --0.359044 -0.139845 7.50679 --0.350065 -0.031299 7.59498 --0.308662 0.0878888 7.43372 --0.286495 0.198119 7.41911 --0.267274 0.309555 7.42199 --0.267489 0.422643 7.59205 --0.254404 0.538741 7.66075 --0.249516 0.661356 7.80683 --0.172057 0.741232 7.28626 --0.570466 1.20215 11.2623 --0.151584 0.977974 7.46919 --0.12016 1.07575 7.34985 --0.103398 1.1907 7.38702 --0.0541047 1.25202 7.06765 -0.261258 -1.82622 -0.597931 -0.246555 -1.88497 -0.584626 -0.231598 -1.9519 -0.575559 -0.216274 -2.01938 -0.564543 -0.199851 -2.08625 -0.551897 -0.182644 -2.16302 -0.542316 -0.167823 -2.22202 -0.520226 -0.15009 -2.29887 -0.506556 -0.12982 -2.38408 -0.495709 -0.110102 -2.4699 -0.482111 -0.0899746 -2.55615 -0.465981 -0.0696585 -2.64183 -0.447322 -0.0445839 -2.75474 -0.439003 -0.0233975 -2.84112 -0.414599 -0.00032033 -2.93676 -0.391531 --0.0261577 -3.05042 -0.373281 --0.0533682 -3.16519 -0.351134 --0.0790939 -3.26947 -0.322201 --0.111073 -3.41206 -0.303069 --0.146108 -3.56311 -0.282768 --0.184528 -3.73451 -0.263264 --0.226911 -3.92389 -0.244003 --0.253748 -4.01979 -0.191243 --0.29499 -4.19036 -0.155897 --0.335905 -4.36085 -0.114784 --0.375879 -4.52254 -0.0655186 --0.429332 -4.75002 -0.0253186 --0.480113 -4.95894 0.0265117 --0.535367 -5.18596 0.081994 --0.596297 -5.44139 0.140693 --0.666342 -5.73584 0.203005 --0.739496 -6.0392 0.274395 --0.825794 -6.39937 0.350031 --0.922807 -6.80767 0.434195 --1.03289 -7.2736 0.528861 --1.15507 -7.78621 0.637383 --1.29951 -8.39524 0.761089 --1.46021 -9.0706 0.905348 --1.6446 -9.83915 1.07362 --1.84957 -10.6932 1.27137 --2.10039 -11.7371 1.50697 --2.23344 -12.2195 1.74836 --2.29748 -12.3849 1.98405 --2.40341 -12.7305 2.24305 --3.21172 -16.1838 2.85852 --3.85009 -18.8224 3.49521 --6.44221 -29.9018 5.46714 --6.50539 -29.8747 6.01413 --7.1625 -32.377 7.02752 --6.62885 -29.8002 7.11243 --7.25899 -32.1403 8.19017 --7.28555 -31.9313 8.75063 --7.35404 -31.8924 9.35277 --7.38509 -31.7015 9.91718 --3.87278 -17.2815 6.25651 --4.42251 -19.2947 7.23824 --6.35106 -26.6956 10.1158 --4.03186 -17.3853 7.33967 --3.55894 -15.3836 6.94534 --3.60588 -15.408 7.27853 --3.63048 -15.3445 7.58079 --3.64267 -15.2313 7.86361 --3.67712 -15.2012 8.18524 --3.52908 -14.5008 8.18713 --3.61318 -14.6548 8.59586 --3.58393 -14.395 8.7992 --3.74011 -14.7966 9.36169 --3.7706 -14.7452 9.68949 --5.00846 -18.893 12.5389 --4.47856 -16.863 11.7461 --4.39734 -16.3996 11.8786 --4.47233 -16.4689 12.3568 --4.41908 -16.1046 12.5454 --3.77898 -13.8086 11.3175 --3.68782 -13.3526 11.3654 --3.67513 -13.1509 11.5979 --3.75803 -13.2546 12.0784 --3.60716 -12.6183 11.9516 --3.67742 -12.6787 12.4077 --4.24851 -14.2667 14.2685 --1.09005 -4.52455 5.57789 --0.954155 -3.99854 5.38318 --0.92632 -3.86066 5.39718 --0.92421 -3.79645 5.48634 --0.914434 -3.71048 5.55276 --0.902235 -3.61853 5.61041 --0.92159 -3.6109 5.77099 --0.964683 -3.66692 6.01695 --0.943802 -3.54962 6.05009 --0.882653 -3.32714 5.93923 --0.925636 -3.37682 6.19558 --0.792028 -2.97675 5.81144 --0.772883 -2.87086 5.83818 --0.801806 -2.88089 6.04408 --0.794602 -2.80212 6.11831 --0.794849 -2.74305 6.22552 --0.703676 -2.46931 5.95679 --0.631961 -2.24886 5.75754 --0.771195 -2.49794 6.4475 --0.652587 -2.17739 6.04206 --0.704076 -2.22462 6.37104 --0.685918 -2.1224 6.39915 --0.636117 -1.95945 6.28157 --0.611228 -1.84536 6.26855 --0.617016 -1.79282 6.40859 --0.623124 -1.73702 6.54869 --0.807955 -1.99058 7.58821 --0.582176 -1.52829 6.57542 --0.541699 -1.39146 6.47784 --0.527368 -1.29931 6.51874 --0.553933 -1.26877 6.78626 --0.588404 -1.24199 7.10225 --0.612069 -1.19296 7.37116 --0.526585 -0.999259 7.0138 --0.458676 -0.837877 6.74816 --0.568498 -0.879306 7.54718 --0.467334 -0.685416 7.07263 --0.475116 -0.606216 7.26787 --0.481512 -0.52122 7.4623 --0.494678 -0.435087 7.7048 --0.441988 -0.300894 7.51283 --0.420961 -0.189043 7.53508 --0.409383 -0.0818742 7.6248 --0.361163 0.0392026 7.44533 --0.324431 0.151777 7.34287 --0.253329 0.26287 6.97031 --0.28763 0.369746 7.41932 --0.285156 0.485126 7.58844 --0.293768 0.610783 7.8648 --0.210423 0.694759 7.34571 --0.17929 0.798698 7.28107 --0.177118 0.924995 7.47206 --0.256404 1.1528 8.48083 --0.129479 1.14844 7.4713 --0.0692213 1.20241 7.084 --0.04379 1.30258 7.05011 -0.199768 -1.85121 -0.604472 -0.18491 -1.90222 -0.584397 -0.165865 -1.97659 -0.580635 -0.148531 -2.04342 -0.568888 -0.133111 -2.09439 -0.544237 -0.111788 -2.17852 -0.539572 -0.0924177 -2.25418 -0.527216 -0.0716907 -2.33011 -0.512741 -0.0505683 -2.40651 -0.495928 -0.0288326 -2.49167 -0.481502 -0.00427333 -2.58598 -0.46902 --0.0207175 -2.68066 -0.453714 --0.0447025 -2.76671 -0.431131 --0.0732608 -2.8789 -0.418405 --0.0978875 -2.96468 -0.390177 --0.127632 -3.07827 -0.370438 --0.157096 -3.18211 -0.343837 --0.191061 -3.31457 -0.323851 --0.229555 -3.46436 -0.306663 --0.271605 -3.62442 -0.287522 --0.318616 -3.81338 -0.271783 --0.348941 -3.90794 -0.221747 --0.39206 -4.06871 -0.187006 --0.438336 -4.23762 -0.149733 --0.482703 -4.39794 -0.104188 --0.537822 -4.60504 -0.0639868 --0.594882 -4.81231 -0.0167992 --0.655668 -5.0389 0.0341642 --0.720087 -5.27386 0.0910662 --0.792162 -5.53667 0.151527 --0.873404 -5.83835 0.216282 --0.960886 -6.15883 0.28934 --1.06257 -6.53565 0.367692 --1.17915 -6.97 0.454844 --1.31062 -7.46028 0.553518 --1.45888 -8.00844 0.667202 --1.62151 -8.61136 0.798657 --1.81316 -9.31945 0.950778 --2.0286 -10.1108 1.12888 --2.27711 -11.0241 1.33862 --2.46169 -11.6609 1.56923 --2.57282 -11.9924 1.80418 --2.68898 -12.3387 2.053 --3.2806 -14.5401 2.49739 --3.92653 -16.9111 3.04242 --6.73369 -27.5561 4.78962 --6.78729 -27.5018 5.29152 --6.8756 -27.581 5.8176 --6.91401 -27.4706 6.31413 --6.92807 -27.2663 6.79086 --7.02863 -27.3844 7.33756 --7.06344 -27.2583 7.83317 --7.10065 -27.1415 8.33144 --7.14058 -27.0349 8.83353 --4.95575 -19.0418 6.93317 --4.97362 -18.9277 7.2799 --4.1456 -15.8706 6.61198 --4.13651 -15.6911 6.87544 --4.12871 -15.5176 7.13833 --4.16492 -15.4917 7.45858 --4.1073 -15.1494 7.64738 --4.04206 -14.7876 7.81814 --3.96224 -14.3822 7.95784 --4.12849 -14.7808 8.48221 --4.14394 -14.6856 8.77574 --4.16079 -14.5945 9.07317 --4.20766 -14.5979 9.42661 --4.46108 -15.2419 10.1637 --4.84485 -16.2752 11.1786 --4.86903 -16.1796 11.5346 --4.92817 -16.1901 11.9654 --4.21114 -13.8632 10.7964 --4.27275 -13.8979 11.204 --4.1283 -13.3192 11.1669 --4.13704 -13.1983 11.4607 --4.13439 -13.0403 11.7292 --4.17953 -13.0189 12.1128 --4.619 -14.0992 13.4578 --8.29752 -24.1485 22.9093 --1.15699 -4.25894 5.26344 --1.15184 -4.19019 5.35284 --1.13109 -4.07933 5.40037 --1.12506 -4.00822 5.48693 --1.10099 -3.88907 5.52267 --1.03165 -3.65405 5.42634 --1.04436 -3.63384 5.56432 --1.01501 -3.50406 5.57657 --1.05702 -3.5515 5.80433 --1.04271 -3.46113 5.86701 --1.03349 -3.38136 5.94342 --1.03392 -3.32339 6.05015 --1.02603 -3.24626 6.13251 --1.05605 -3.25403 6.34295 --0.99452 -3.0553 6.24468 --0.915191 -2.82115 6.07497 --0.897329 -2.72259 6.11551 --0.90992 -2.69109 6.27264 --0.799857 -2.40301 5.96898 --0.900273 -2.54762 6.45908 --0.961056 -2.6065 6.81702 --0.910637 -2.44182 6.73897 --0.797331 -2.15963 6.39053 --0.737398 -1.98773 6.25728 --0.688186 -1.8371 6.1556 --0.68006 -1.76235 6.23183 --0.66941 -1.68192 6.29792 --0.714262 -1.69305 6.62139 --0.640371 -1.50847 6.39875 --0.651381 -1.46009 6.57326 --0.623193 -1.35011 6.55956 --0.637554 -1.30158 6.76123 --0.673436 -1.27657 7.07711 --0.690969 -1.22114 7.30823 --0.703923 -1.1552 7.52961 --0.57593 -0.924815 6.97933 --0.661572 -0.936057 7.6133 --0.600655 -0.78653 7.42402 --0.536181 -0.639451 7.20185 --0.549717 -0.563418 7.44588 --0.532843 -0.459137 7.51281 --0.499367 -0.341857 7.4697 --0.466365 -0.227082 7.43421 --0.499415 -0.142943 7.84096 --0.447731 -0.0181432 7.67344 --0.37789 0.105389 7.37455 --0.256406 0.222792 6.66696 --0.249066 0.319924 6.78937 --0.305753 0.431334 7.42606 --0.299857 0.54784 7.59456 --0.302698 0.673114 7.8405 --0.208884 0.748355 7.27153 --0.621812 1.21351 11.2557 --0.176788 0.982537 7.45601 --0.262781 1.23007 8.562 --0.126071 1.20799 7.4838 --0.0599192 1.25331 7.06692 -0.156114 -1.8009 -0.611686 -0.13764 -1.86639 -0.604953 -0.1208 -1.91684 -0.584536 -0.100874 -1.98231 -0.574419 -0.0813151 -2.04951 -0.562035 -0.0595057 -2.12428 -0.553353 -0.0361574 -2.20771 -0.547761 -0.0147229 -2.27528 -0.529266 --0.0058876 -2.34262 -0.508705 --0.0311695 -2.42625 -0.496224 --0.0573225 -2.51951 -0.48564 --0.0851263 -2.61383 -0.471962 --0.111681 -2.69859 -0.4513 --0.14012 -2.79265 -0.432073 --0.170463 -2.89593 -0.413989 --0.199565 -2.98964 -0.388825 --0.233302 -3.10202 -0.368012 --0.269023 -3.22339 -0.347272 --0.312203 -3.37258 -0.332828 --0.357727 -3.53134 -0.316606 --0.404092 -3.69087 -0.295027 --0.438697 -3.79396 -0.250682 --0.486223 -3.95331 -0.219466 --0.535338 -4.11223 -0.183017 --0.58689 -4.28043 -0.143525 --0.638116 -4.44857 -0.0982668 --0.703289 -4.66364 -0.0578369 --0.76641 -4.86888 -0.00806618 --0.834233 -5.09319 0.0454567 --0.913485 -5.35435 0.100182 --1.00096 -5.64498 0.160125 --1.09726 -5.96261 0.22623 --1.19987 -6.29885 0.301515 --1.31293 -6.6728 0.385156 --1.4383 -7.08257 0.478952 --1.60082 -7.62772 0.579995 --1.78155 -8.22689 0.697744 --1.97213 -8.85391 0.836671 --2.19335 -9.58331 0.997672 --2.45002 -10.4243 1.18647 --2.71164 -11.2703 1.40594 --2.8166 -11.5439 1.6281 --2.88684 -11.6882 1.85188 --3.20288 -12.6903 2.1553 --3.86549 -14.8794 2.61998 --4.68707 -17.5784 3.22836 --7.33856 -26.4759 4.81101 --7.61918 -27.1971 5.42162 --7.6865 -27.186 5.93185 --7.72259 -27.0716 6.42518 --7.76581 -26.9777 6.92271 --7.83676 -26.9773 7.44309 --7.87738 -26.8752 7.94247 --7.91832 -26.7738 8.44321 --7.95381 -26.6545 8.94042 --7.98719 -26.5267 9.43605 --5.42617 -18.273 7.22546 --5.37509 -17.9541 7.49122 --8.09736 -26.1721 10.9433 --5.11077 -16.8289 7.80537 --5.24703 -17.0892 8.2776 --5.21184 -16.8304 8.53917 --5.45888 -17.4104 9.18155 --8.38139 -25.8539 13.6481 --4.89973 -15.4618 8.99444 --4.96938 -15.5174 9.38799 --4.6393 -14.4247 9.15808 --4.9501 -15.171 9.94148 --5.04984 -15.3023 10.4002 --4.8779 -14.6765 10.4003 --5.0319 -14.9551 10.9657 --4.99772 -14.7109 11.201 --4.8079 -14.0488 11.1388 --4.85162 -14.0211 11.5141 --4.81836 -13.7858 11.741 --8.92543 -24.3906 20.5201 --8.80021 -23.8028 20.7777 --9.10198 -24.0428 22.4981 --1.59346 -4.9567 5.84171 --1.72705 -5.22675 6.27513 --1.29021 -4.09271 5.35341 --1.34674 -4.17706 5.5987 --1.21457 -3.8056 5.37386 --1.22555 -3.78066 5.50638 --1.24708 -3.77749 5.66821 --1.27576 -3.7887 5.85352 --1.2578 -3.69227 5.91429 --1.25264 -3.62414 6.01081 --1.24578 -3.55346 6.10647 --1.16882 -3.32745 5.99096 --1.15925 -3.25164 6.07405 --1.11552 -3.10409 6.05231 --1.08227 -2.97856 6.05881 --0.995441 -2.74705 5.89047 --0.960339 -2.62214 5.88101 --1.15574 -2.95051 6.64852 --0.938271 -2.47105 6.02276 --0.95363 -2.44388 6.18611 --1.06765 -2.59631 6.71345 --1.05031 -2.50132 6.77665 --1.04894 -2.43505 6.90024 --1.07862 -2.42051 7.14771 --1.10663 -2.3977 7.39651 --0.830647 -1.87597 6.42626 --0.74926 -1.68506 6.21271 --0.751747 -1.62813 6.34234 --0.772323 -1.59681 6.55494 --0.74711 -1.4963 6.57307 --0.668313 -1.32026 6.34553 --0.673939 -1.26382 6.4995 --0.821497 -1.38501 7.335 --0.831328 -1.31915 7.53947 --0.83958 -1.24641 7.74352 --0.816088 -1.1357 7.79366 --0.63108 -0.858993 6.99263 --0.721131 -0.866094 7.63623 --0.600094 -0.671164 7.14484 --0.613361 -0.598222 7.38949 --0.600421 -0.499291 7.48673 --0.588524 -0.399475 7.60219 --0.537321 -0.274603 7.48005 --0.538802 -0.178006 7.68056 --0.532285 -0.0729325 7.84028 --0.497507 0.0446245 7.82033 --0.316763 0.181094 6.77888 --0.279704 0.278405 6.70457 --0.360253 0.385658 7.50046 --0.334233 0.497047 7.53152 --0.286715 0.60037 7.39228 --0.249692 0.704453 7.33031 --0.212027 0.804926 7.25677 --0.204034 0.92991 7.44839 --0.183549 1.04975 7.5389 --0.145953 1.15209 7.46924 --0.0870643 1.21761 7.17144 --0.0440585 1.29856 7.02027 -0.202781 -1.4947 -0.680757 -0.0936223 -1.82165 -0.619161 -0.0729014 -1.88743 -0.611499 -0.0508451 -1.95356 -0.60201 -0.0307565 -2.01127 -0.585026 -0.0103234 -2.0696 -0.566385 --0.0135038 -2.14369 -0.556874 --0.0365537 -2.21014 -0.539985 --0.0611498 -2.28524 -0.52609 --0.0882902 -2.36868 -0.514921 --0.11584 -2.45254 -0.50122 --0.143808 -2.5368 -0.484889 --0.17437 -2.62926 -0.470602 --0.202957 -2.71331 -0.448918 --0.23852 -2.82499 -0.437035 --0.270428 -2.91836 -0.413595 --0.305224 -3.0207 -0.391224 --0.341992 -3.13206 -0.36912 --0.388652 -3.27993 -0.357497 --0.43438 -3.41896 -0.337623 --0.486684 -3.58577 -0.322758 --0.523815 -3.6877 -0.280919 --0.57398 -3.836 -0.250237 --0.624978 -3.9851 -0.214296 --0.67815 -4.14262 -0.175899 --0.740305 -4.32773 -0.13944 --0.805213 -4.52284 -0.0986701 --0.868774 -4.70702 -0.0492667 --0.945679 -4.93891 -0.00262249 --1.02744 -5.17988 0.0502314 --1.11689 -5.44857 0.107131 --1.21132 -5.72594 0.171991 --1.32269 -6.05951 0.239544 --1.44642 -6.43042 0.31492 --1.58075 -6.82907 0.401013 --1.73594 -7.29307 0.496713 --1.91856 -7.84128 0.604557 --2.11749 -8.43428 0.730347 --2.33951 -9.09193 0.876524 --2.59548 -9.85177 1.04685 --2.9048 -10.7696 1.24776 --3.03261 -11.0911 1.4605 --3.09838 -11.2071 1.67391 --3.26653 -11.6428 1.91572 --3.891 -13.507 2.30553 --4.78534 -16.1813 2.85422 --7.379 -24.0602 4.17299 --7.71433 -24.8898 4.74817 --8.58718 -27.3383 5.62613 --8.63486 -27.2553 6.13175 --8.66285 -27.1172 6.62703 --8.8673 -27.5001 7.2376 --8.91314 -27.4082 7.75256 --8.949 -27.2884 8.26186 --8.98637 -27.1701 8.77242 --9.02966 -27.07 9.28981 --9.06653 -26.9521 9.80389 --9.10134 -26.8255 10.3169 --5.85865 -17.519 7.50143 --5.69511 -16.9162 7.64382 --5.79677 -17.0537 8.06559 --9.26484 -26.3776 12.4182 --5.92613 -17.1099 8.84604 --9.3466 -26.1447 13.489 --9.39008 -26.0306 14.0328 --9.42665 -25.897 14.5725 --9.46966 -25.78 15.126 --9.51261 -25.6598 15.6847 --9.55316 -25.5285 16.2439 --5.60406 -15.2447 10.578 --9.64176 -25.2816 17.3945 --5.64406 -15.0569 11.2582 --9.73048 -25.021 18.5706 --9.77567 -24.8873 19.1713 --9.79895 -24.6964 19.7394 --1.48299 -4.47456 4.74626 --1.47528 -4.40873 4.83475 --1.95192 -5.41904 6.00649 --1.8042 -5.01892 5.83205 --1.71375 -4.75323 5.76182 --1.69478 -4.65502 5.84251 --1.41353 -3.97183 5.33285 --1.43414 -3.96812 5.48826 --1.56771 -4.20668 5.91137 --1.45298 -3.90435 5.75296 --1.51176 -3.97671 6.01285 --1.40945 -3.70654 5.87198 --1.40264 -3.63964 5.96963 --1.31583 -3.40672 5.85359 --1.3565 -3.43642 6.07734 --1.28273 -3.23608 5.99134 --1.2862 -3.18782 6.11349 --1.12754 -2.82856 5.77024 --1.1051 -2.7359 5.81317 --1.16082 -2.78812 6.0927 --1.05936 -2.54978 5.89368 --0.999205 -2.38905 5.81324 --1.19768 -2.68637 6.56971 --1.275 -2.75902 6.95297 --1.20336 -2.57494 6.84683 --1.19598 -2.49976 6.95468 --1.28871 -2.58446 7.42359 --1.1699 -2.32889 7.14087 --0.878139 -1.81555 6.19465 --0.847448 -1.71182 6.19941 --0.87055 -1.68723 6.412 --0.854382 -1.60491 6.4786 --1.15643 -1.95012 7.84822 --1.10651 -1.80774 7.80899 --1.04935 -1.65565 7.72894 --0.917184 -1.41785 7.31566 --0.883183 -1.3031 7.32177 --0.922133 -1.26985 7.66866 --0.908959 -1.17285 7.77714 --0.836752 -1.01821 7.60575 --0.699223 -0.807722 7.09254 --0.757303 -0.777974 7.56183 --0.664799 -0.617758 7.25408 --0.723902 -0.575521 7.7621 --0.72705 -0.482811 7.97734 --0.625416 -0.328165 7.60297 --0.575871 -0.208429 7.50982 --0.60117 -0.120677 7.87738 --0.587789 -0.00991361 8.017 --0.375277 0.138974 6.85044 --0.34202 0.238255 6.82669 --0.296077 0.334524 6.71237 --0.361039 0.446633 7.40841 --0.313036 0.549987 7.29017 --0.327588 0.676657 7.66568 --0.248349 0.760145 7.28628 --0.406196 1.01585 8.93365 --0.201749 0.989083 7.45267 --0.195299 1.12919 7.70017 --0.130281 1.19869 7.39339 --0.0710112 1.26394 7.12517 -0.149653 -1.50872 -0.685148 -0.0515069 -1.77722 -0.63264 -0.0320969 -1.82637 -0.614145 -0.00753196 -1.89868 -0.612083 --0.0144222 -1.95617 -0.596313 --0.0386052 -2.0213 -0.584536 --0.0610417 -2.079 -0.565261 --0.0889923 -2.16043 -0.560568 --0.114053 -2.22623 -0.542948 --0.143044 -2.3095 -0.533188 --0.17103 -2.38416 -0.51615 --0.203738 -2.47494 -0.506512 --0.233745 -2.55847 -0.489061 --0.269965 -2.65965 -0.478054 --0.30399 -2.75145 -0.459652 --0.338696 -2.8445 -0.438034 --0.372643 -2.93714 -0.413474 --0.415385 -3.05567 -0.397597 --0.464038 -3.19339 -0.385023 --0.513261 -3.33104 -0.367776 --0.565768 -3.47813 -0.34926 --0.610892 -3.59777 -0.316247 --0.656535 -3.71751 -0.279242 --0.71075 -3.86442 -0.246709 --0.772071 -4.02962 -0.214583 --0.833064 -4.19476 -0.17669 --0.895911 -4.36034 -0.132979 --0.978073 -4.59036 -0.0987653 --1.05356 -4.79182 -0.050665 --1.13853 -5.02105 -0.000803709 --1.23024 -5.26864 0.0538328 --1.33754 -5.56254 0.109749 --1.44396 -5.84581 0.177415 --1.57266 -6.19557 0.247539 --1.70851 -6.56241 0.328081 --1.86995 -7.00346 0.415461 --2.04928 -7.48996 0.515679 --2.25006 -8.03215 0.630884 --2.48354 -8.66572 0.762955 --2.74223 -9.36302 0.91741 --3.05148 -10.1989 1.09836 --3.25285 -10.7078 1.30242 --3.37624 -10.9767 1.51534 --3.45822 -11.127 1.73149 --3.79819 -12.0082 2.01187 --4.60317 -14.1962 2.45327 --7.42388 -22.0276 3.63338 --7.76331 -22.803 4.15574 --9.59405 -27.7001 5.34378 --9.68413 -27.7305 5.87979 --9.72731 -27.6307 6.39582 --9.74668 -27.4679 6.89921 --9.85592 -27.545 7.45614 --9.89342 -27.4285 7.97275 --9.93123 -27.3128 8.49044 --9.96237 -27.1786 9.00413 --9.9972 -27.0542 9.52172 --10.047 -26.9664 10.0529 --6.42147 -17.4565 7.27673 --6.35358 -17.1418 7.53274 --10.095 -26.4438 11.5677 --10.2047 -26.5018 12.1706 --10.2275 -26.3413 12.6894 --10.2845 -26.2646 13.2496 --10.3258 -26.1443 13.7952 --10.373 -26.0389 14.3538 --10.4103 -25.907 14.9047 --10.4544 -25.7885 15.469 --10.4953 -25.66 16.0344 --10.5319 -25.521 16.6004 --10.5786 -25.4025 17.1867 --10.6195 -25.2642 17.7691 --10.6685 -25.1456 18.3737 --10.715 -25.0147 18.9798 --10.7432 -24.8411 19.5651 --10.7816 -24.6865 20.1735 --1.6753 -4.4803 4.83838 --1.66505 -4.41171 4.92799 --1.65204 -4.33482 5.01027 --1.69405 -4.37695 5.19777 --1.61252 -4.15669 5.15122 --1.86562 -4.63616 5.76477 --1.58151 -3.99595 5.30461 --1.82674 -4.44774 5.92925 --1.81034 -4.36069 6.01895 --1.74025 -4.16495 5.98746 --1.74876 -4.1281 6.12961 --1.60459 -3.7948 5.92261 --1.63416 -3.79878 6.11136 --1.5851 -3.65062 6.11414 --1.51443 -3.46497 6.06 --1.4222 -3.24338 5.94652 --1.28081 -2.93481 5.69298 --1.27095 -2.87002 5.779 --1.26468 -2.80815 5.87198 --1.37314 -2.94571 6.29019 --1.44061 -3.00595 6.60827 --1.23542 -2.6056 6.13873 --1.32338 -2.6973 6.52386 --1.30327 -2.6065 6.59047 --1.32883 -2.58885 6.80208 --1.32962 -2.53056 6.94541 --1.31987 -2.45377 7.05368 --1.31411 -2.38097 7.17849 --1.25257 -2.2275 7.11541 --1.233 -2.13337 7.19234 --1.1919 -2.01153 7.19553 --0.976383 -1.6602 6.54757 --0.912476 -1.51662 6.43963 --1.13545 -1.73128 7.44882 --1.18583 -1.71928 7.8164 --1.11862 -1.56526 7.71714 --1.01871 -1.378 7.4726 --1.14238 -1.43067 8.18062 --1.06146 -1.26505 8.01685 --0.896975 -1.02484 7.45618 --0.790924 -0.851193 7.13818 --0.863961 -0.833047 7.66541 --0.798096 -0.697675 7.53541 --0.827328 -0.631777 7.87904 --0.777024 -0.506785 7.82228 --0.69258 -0.36624 7.57727 --0.706481 -0.279266 7.86856 --0.648355 -0.155265 7.75556 --0.670892 -0.0598305 8.12292 --0.423484 0.101826 6.8316 --0.39376 0.198932 6.84888 --0.345937 0.295999 6.74572 --0.389801 0.400649 7.28406 --0.3738 0.509969 7.42492 --0.321131 0.610067 7.29656 --0.358732 0.752837 7.8691 --0.244048 0.815039 7.24193 --0.240528 0.946141 7.51344 --0.202263 1.05386 7.50594 --0.166744 1.16384 7.51623 --0.114525 1.24925 7.35703 --0.0443197 1.29452 6.99032 -0.117908 -1.46578 -0.693407 -0.0975676 -1.51423 -0.682747 --0.0103967 -1.78747 -0.634424 --0.0336506 -1.84314 -0.621527 --0.0583638 -1.90771 -0.612793 --0.0844197 -1.97261 -0.602133 --0.110606 -2.03711 -0.589722 --0.137166 -2.10214 -0.575265 --0.16313 -2.16793 -0.558642 --0.19447 -2.24891 -0.550806 --0.224086 -2.32241 -0.53518 --0.257451 -2.40498 -0.522204 --0.290027 -2.48721 -0.506674 --0.326404 -2.57838 -0.493112 --0.362022 -2.66912 -0.476608 --0.401712 -2.76962 -0.461388 --0.439198 -2.86075 -0.438871 --0.47713 -2.9522 -0.413334 --0.525596 -3.07927 -0.399862 --0.581719 -3.22401 -0.389546 --0.640179 -3.37833 -0.37755 --0.695226 -3.51528 -0.353702 --0.735421 -3.60653 -0.30967 --0.796823 -3.76132 -0.28319 --0.856071 -3.90659 -0.248731 --0.918698 -4.061 -0.211739 --0.992246 -4.24258 -0.176927 --1.06832 -4.43318 -0.137904 --1.14913 -4.63319 -0.0942277 --1.23729 -4.85073 -0.0475537 --1.33217 -5.08671 0.00350636 --1.43883 -5.35056 0.0581314 --1.55214 -5.63138 0.11928 --1.68055 -5.94942 0.185555 --1.823 -6.30349 0.259018 --1.98374 -6.70284 0.340528 --2.17336 -7.17626 0.430753 --2.38195 -7.69453 0.53535 --2.60288 -8.23963 0.658036 --2.86661 -8.89353 0.797792 --3.17502 -9.6566 0.960827 --3.51724 -10.4998 1.15311 --3.63421 -10.7297 1.35914 --3.7157 -10.8624 1.56969 --3.91086 -11.2885 1.80507 --4.31301 -12.2495 2.10275 --7.45417 -20.2771 3.16949 --7.80908 -21.0343 3.64987 --8.91395 -23.6906 4.42979 --10.5128 -27.554 5.50744 --10.543 -27.4216 6.01873 --10.5583 -27.2545 6.52236 --10.5965 -27.1427 7.03607 --10.6208 -26.996 7.54191 --10.6407 -26.8405 8.04495 --10.6642 -26.6952 8.55033 --10.689 -26.5506 9.05598 --10.7171 -26.4149 9.56514 --10.7356 -26.2537 10.0668 --10.7498 -26.0836 10.5659 --10.7642 -25.9144 11.0659 --10.7644 -25.7114 11.553 --10.8316 -25.6621 12.1056 --10.8504 -25.5023 12.6153 --10.8768 -25.3575 13.1351 --10.9002 -25.2041 13.6541 --10.9171 -25.0335 14.1677 --10.9287 -24.854 14.68 --10.9637 -24.7213 15.2224 --10.988 -24.5636 15.7559 --10.9964 -24.3711 16.274 --11.0129 -24.1937 16.8056 --10.7612 -23.4499 16.9632 --11.1798 -24.1142 18.079 --11.7091 -24.9888 19.4012 --11.7106 -24.7612 19.9598 --1.83635 -4.45889 4.76943 --1.81419 -4.36945 4.84206 --1.83199 -4.35864 4.97932 --1.86933 -4.38662 5.15451 --1.83484 -4.27201 5.20613 --1.75004 -4.06199 5.16481 --1.79577 -4.10269 5.35983 --1.8352 -4.13096 5.55138 --1.90912 -4.21903 5.81369 --1.94259 -4.22996 6.00475 --1.86577 -4.03723 5.97188 --1.82607 -3.91465 6.01243 --1.8163 -3.84521 6.11568 --1.81901 -3.79717 6.24781 --1.59801 -3.35907 5.86775 --1.61651 -3.34174 6.03052 --1.71757 -3.46158 6.39605 --1.45976 -2.97618 5.88769 --1.44097 -2.89759 5.95974 --1.61823 -3.13404 6.53844 --1.4155 -2.75565 6.13238 --1.45241 -2.76281 6.35779 --1.43139 -2.67598 6.42661 --1.59231 -2.86456 7.01751 --1.57613 -2.77911 7.11444 --1.44923 -2.53285 6.88264 --1.40683 -2.41344 6.89593 --1.34132 -2.26339 6.83629 --1.34275 -2.20481 6.98526 --1.3269 -2.1217 7.08064 --1.3016 -2.02574 7.14791 --1.29399 -1.95144 7.27714 --1.25706 -1.83921 7.30502 --1.22178 -1.73035 7.34 --1.31466 -1.76653 7.8552 --1.25981 -1.63006 7.82374 --1.15423 -1.44259 7.59211 --1.24006 -1.45366 8.12025 --0.919952 -1.06517 6.98088 --0.895579 -0.973063 7.04875 --0.912442 -0.914219 7.29714 --0.842193 -0.781245 7.16081 --0.906706 -0.751221 7.64909 --0.907761 -0.666689 7.8578 --0.792434 -0.505435 7.50126 --0.753957 -0.396251 7.51122 --0.791491 -0.325183 7.93067 --0.755193 -0.211063 7.96691 --0.6317 -0.0695639 7.50966 --0.59356 0.0389753 7.52119 --0.438214 0.163125 6.81059 --0.417797 0.257838 6.90656 --0.410558 0.357057 7.09973 --0.404002 0.46335 7.31098 --0.358916 0.565217 7.26317 --0.336036 0.674574 7.38202 --0.255661 0.882569 7.35604 --0.233193 1.00317 7.49823 --0.188357 1.10413 7.45081 --0.135925 1.19479 7.33238 --0.0838044 1.277 7.19311 -0.0645112 -1.4767 -0.698413 --0.0747719 -1.79506 -0.636477 --0.0990457 -1.85036 -0.623021 --0.12883 -1.92212 -0.619517 --0.156896 -1.98636 -0.608126 --0.185093 -2.05021 -0.594984 --0.215791 -2.12254 -0.58515 --0.244742 -2.18743 -0.567819 --0.275973 -2.25981 -0.5538 --0.308568 -2.33244 -0.537564 --0.348521 -2.43092 -0.533201 --0.384114 -2.51219 -0.516575 --0.423514 -2.60235 -0.501818 --0.462383 -2.69307 -0.48402 --0.502432 -2.78293 -0.463522 --0.543163 -2.87406 -0.439807 --0.592452 -2.99013 -0.424973 --0.64863 -3.12516 -0.413465 --0.706103 -3.25897 -0.3977 --0.773281 -3.42093 -0.387302 --0.81353 -3.50246 -0.342077 --0.879367 -3.65575 -0.318733 --0.939331 -3.79035 -0.284373 --1.00361 -3.93397 -0.247988 --1.07757 -4.10416 -0.214445 --1.1534 -4.27471 -0.17479 --1.24586 -4.49056 -0.140329 --1.33349 -4.68728 -0.0939986 --1.43559 -4.92149 -0.0480909 --1.54518 -5.17281 0.00266308 --1.67046 -5.46061 0.0563763 --1.7929 -5.73823 0.121983 --1.93792 -6.06964 0.190139 --2.09948 -6.43831 0.266611 --2.29125 -6.8791 0.34941 --2.4997 -7.35502 0.445582 --2.72112 -7.85695 0.557968 --2.9739 -8.43083 0.686222 --3.30019 -9.17728 0.83194 --3.67369 -10.0323 1.00566 --3.86157 -10.4186 1.20409 --3.99421 -10.662 1.41251 --4.14501 -10.9477 1.63315 --4.57601 -11.9 1.91285 --7.42977 -18.6168 2.75212 --7.8191 -19.4001 3.19719 --9.0323 -22.1102 3.9224 --9.92542 -24.0305 4.63721 --10.029 -24.0962 5.11911 --10.052 -23.9734 5.57206 --9.97719 -23.6272 5.97792 --10.8865 -25.5152 6.87993 --10.8412 -25.2279 7.3262 --11.2772 -26.0169 8.05307 --11.3136 -25.906 8.55951 --11.3742 -25.8474 9.08377 --10.2752 -23.2531 8.77871 --10.2916 -23.1154 9.23023 --10.3216 -23.0048 9.69268 --10.3311 -22.8516 10.1409 --10.242 -22.4887 10.5028 --10.9606 -23.8262 11.6012 --10.4496 -22.575 11.5763 --11.327 -24.2159 12.9027 --11.3549 -24.0816 13.4154 --11.3831 -23.9465 13.932 --11.1045 -22.9982 14.5861 --11.1134 -22.8263 15.0796 --11.1436 -22.6928 15.6014 --10.6783 -21.589 15.4899 --10.8544 -21.7434 16.1972 --10.5972 -21.0563 16.3262 --11.3303 -22.2655 17.8441 --2.14921 -4.71493 4.91928 --1.99404 -4.37945 4.80183 --2.00409 -4.354 4.92773 --1.99072 -4.28502 5.01789 --2.00997 -4.2765 5.16265 --2.08553 -4.36549 5.40336 --2.07936 -4.30846 5.51346 --2.14685 -4.37935 5.75479 --2.12852 -4.29664 5.84612 --2.10866 -4.21253 5.93592 --2.05121 -4.06425 5.9544 --2.09215 -4.08176 6.16058 --1.96608 -3.8201 6.03748 --1.95435 -3.75116 6.14069 --1.90329 -3.6167 6.16089 --1.87666 -3.52264 6.23075 --1.67422 -3.1501 5.9076 --1.52176 -2.86503 5.68065 --1.48269 -2.75946 5.70433 --1.67898 -3.01132 6.2924 --1.53188 -2.73984 6.05939 --1.94086 -3.29064 7.21698 --1.6349 -2.7877 6.57709 --1.96317 -3.19816 7.58554 --1.9012 -3.04753 7.58019 --1.66468 -2.66047 7.08403 --1.43657 -2.29544 6.58306 --1.40684 -2.20141 6.6362 --1.40046 -2.13672 6.75815 --1.48402 -2.18327 7.16353 --1.43932 -2.06601 7.17933 --1.43856 -2.00198 7.33699 --1.39791 -1.89015 7.36739 --1.35663 -1.77692 7.39516 --1.27913 -1.62521 7.29194 --1.40719 -1.69181 7.92754 --1.31189 -1.52106 7.76512 --1.32696 -1.45991 8.01158 --1.024 -1.10266 7.02035 --1.03021 -1.04022 7.22277 --0.943592 -0.895099 7.04298 --0.956435 -0.832997 7.28148 --0.86397 -0.690152 7.06728 --0.986419 -0.695763 7.81616 --0.971534 -0.599889 7.96686 --0.900618 -0.469713 7.85332 --0.866298 -0.360815 7.91269 --0.736942 -0.211368 7.4805 --0.706913 -0.108848 7.55466 --0.667593 -0.00238721 7.57785 --0.538903 0.120303 7.0868 --0.444308 0.223528 6.76011 --0.482747 0.320059 7.24044 --0.450376 0.422145 7.29504 --0.425015 0.529424 7.40684 --0.365057 0.625876 7.27975 --0.325882 0.729445 7.29895 --0.255516 0.945343 7.40047 --0.224821 1.0619 7.50255 --0.17988 1.16571 7.4842 --0.12854 1.25951 7.40496 --0.0479517 1.29736 6.99969 -0.0103525 -1.48637 -0.703348 --0.138712 -1.80063 -0.63844 --0.168278 -1.86411 -0.630211 --0.194907 -1.91938 -0.614367 --0.226832 -1.9901 -0.608381 --0.257039 -2.0533 -0.594507 --0.290709 -2.12478 -0.584161 --0.326902 -2.20467 -0.576831 --0.358024 -2.26843 -0.556629 --0.395029 -2.34919 -0.544333 --0.433192 -2.42916 -0.529628 --0.477561 -2.52682 -0.521465 --0.516579 -2.60753 -0.501209 --0.561619 -2.70482 -0.487011 --0.601272 -2.78528 -0.461207 --0.653331 -2.90112 -0.448584 --0.710075 -3.02426 -0.436204 --0.773737 -3.16626 -0.426761 --0.829333 -3.28183 -0.401821 --0.884471 -3.39773 -0.372866 --0.947325 -3.53112 -0.346291 --1.01423 -3.67267 -0.318278 --1.07921 -3.80569 -0.282283 --1.16131 -3.98357 -0.255011 --1.23853 -4.14246 -0.216551 --1.32977 -4.33853 -0.181532 --1.42248 -4.53285 -0.139823 --1.52377 -4.74541 -0.0949432 --1.63272 -4.97622 -0.0458951 --1.75802 -5.24258 0.00472391 --1.88523 -5.50753 0.0649534 --2.03904 -5.83618 0.125767 --2.19518 -6.16384 0.198724 --2.38719 -6.57235 0.274729 --2.59676 -7.01608 0.362622 --2.82794 -7.50318 0.463842 --3.08137 -8.03504 0.581117 --3.37999 -8.66372 0.714633 --3.7411 -9.42693 0.869763 --4.15419 -10.2962 1.05423 --4.29835 -10.5469 1.25923 --4.44699 -10.8028 1.47442 --4.63565 -11.1463 1.7055 --7.29116 -16.9372 2.37179 --7.85054 -18.0446 2.80904 --8.16778 -18.6064 3.22755 --9.95763 -22.3484 4.1001 --10.1363 -22.5741 4.57698 --10.1659 -22.478 5.01008 --10.1414 -22.2676 5.42065 --10.2913 -22.4242 5.90534 --10.3705 -22.43 6.36526 --10.3916 -22.3138 6.79888 --10.4262 -22.2263 7.24052 --10.4577 -22.1302 7.68128 --10.4823 -22.0187 8.11867 --10.5109 -21.9178 8.56092 --10.5411 -21.8181 9.00559 --10.5683 -21.7098 9.44948 --10.5953 -21.6041 9.89662 --10.5093 -21.2735 10.2506 --10.6996 -21.4833 10.8409 --10.692 -21.3037 11.2649 --10.7571 -21.264 11.7589 --10.7755 -21.1335 12.2136 --10.799 -21.0118 12.6764 --10.8185 -20.8816 13.1393 --10.8437 -20.7586 13.6108 --10.8598 -20.6199 14.078 --10.8564 -20.4419 14.5249 --10.8818 -20.3159 15.0108 --10.8089 -20.0101 15.3765 --2.322 -4.73253 4.73431 --2.25226 -4.56472 4.75526 --2.26737 -4.54768 4.89028 --10.9662 -19.5775 17.4672 --2.27353 -4.47162 5.13312 --2.21302 -4.32342 5.15997 --2.22417 -4.29794 5.29482 --2.1943 -4.20222 5.36639 --2.19148 -4.15274 5.48165 --2.22344 -4.15705 5.65581 --2.23353 -4.12704 5.79856 --2.27721 -4.14834 6.00343 --2.13549 -3.87481 5.87522 --2.12029 -3.80262 5.97291 --2.14517 -3.79248 6.14917 --2.05654 -3.60789 6.10637 --2.13438 -3.67603 6.39421 --1.75781 -3.06401 5.74645 --1.65828 -2.87264 5.65308 --1.68029 -2.86016 5.81874 --1.77154 -2.94456 6.14389 --1.69929 -2.79378 6.10597 --2.02543 -3.1961 7.0042 --1.94803 -3.03442 6.96924 --1.86566 -2.86673 6.91345 --1.9712 -2.94934 7.3315 --1.92616 -2.82992 7.37336 --1.54354 -2.28656 6.51326 --1.50624 -2.18624 6.55002 --1.59807 -2.24409 6.95188 --1.60611 -2.19485 7.12898 --1.48601 -1.99618 6.93323 --1.46018 -1.90699 7.00906 --1.57698 -1.97482 7.53558 --1.54033 -1.86982 7.59416 --1.40866 -1.6664 7.33888 --1.39418 -1.58597 7.46528 --1.45288 -1.57339 7.85103 --1.44466 -1.49109 8.01448 --1.10444 -1.11541 6.96409 --1.05497 -1.00775 6.94942 --1.03807 -0.926926 7.06544 --0.999975 -0.82737 7.09441 --0.942117 -0.715328 7.04505 --0.855095 -0.585535 6.86783 --0.98307 -0.588005 7.62525 --1.02376 -0.526163 8.03698 --0.88245 -0.365714 7.61132 --0.820624 -0.251313 7.5426 --0.765193 -0.141302 7.50081 --0.84396 -0.0685081 8.16308 --0.685902 0.0682635 7.57739 --0.549832 0.184917 7.06604 --0.503813 0.282572 7.04464 --0.526889 0.386143 7.45566 --0.466895 0.487319 7.36153 --0.3998 0.582415 7.21615 --0.356105 0.682115 7.21704 --0.396247 0.832423 7.84823 --0.286453 0.895458 7.36112 --0.242384 0.999023 7.36588 --0.225959 1.1349 7.62516 --0.184283 1.24844 7.67518 --0.0982757 1.29348 7.28062 --0.0362715 -1.49555 -0.76786 --0.0437404 -1.4873 -0.701515 --0.177202 -1.75009 -0.653545 --0.207207 -1.81162 -0.646611 --0.238784 -1.87445 -0.637651 --0.264341 -1.92131 -0.615405 --0.302328 -1.99892 -0.614479 --0.336666 -2.06944 -0.605326 --0.367131 -2.12458 -0.583321 --0.405106 -2.20285 -0.57536 --0.444702 -2.28225 -0.564694 --0.48448 -2.3611 -0.551595 --0.52588 -2.4411 -0.535791 --0.57303 -2.53683 -0.526728 --0.614088 -2.6168 -0.505352 --0.663113 -2.7129 -0.490178 --0.708225 -2.80103 -0.467365 --0.768457 -2.92282 -0.457708 --0.828497 -3.0458 -0.44345 --0.896935 -3.18527 -0.43257 --0.963706 -3.31708 -0.413122 --1.01201 -3.40491 -0.372421 --1.09055 -3.56238 -0.354012 --1.15803 -3.69431 -0.320815 --1.23056 -3.83409 -0.285912 --1.31944 -4.00882 -0.256667 --1.40074 -4.16624 -0.215966 --1.50606 -4.37621 -0.183691 --1.60961 -4.5772 -0.141488 --1.72055 -4.79558 -0.0957035 --1.83734 -5.02277 -0.0436356 --1.97624 -5.29388 0.00837737 --2.11899 -5.57273 0.0691501 --2.27956 -5.88706 0.13517 --2.48293 -6.29155 0.201814 --2.68474 -6.68468 0.284511 --2.92085 -7.14846 0.375777 --3.17963 -7.65511 0.481513 --3.46249 -8.20475 0.604519 --3.80703 -8.8785 0.744587 --4.21377 -9.6747 0.909013 --4.63234 -10.4837 1.10422 --4.82856 -10.8192 1.31906 --4.98206 -11.0595 1.5431 --7.08644 -15.3084 2.03266 --7.79987 -16.6578 2.44698 --8.09829 -17.1471 2.82718 --10.0311 -20.9217 3.62984 --10.1833 -21.0806 4.07058 --10.2118 -20.9927 4.48072 --10.224 -20.8722 4.88483 --10.1395 -20.5612 5.249 --10.6384 -21.3885 5.85744 --10.6455 -21.2538 6.27053 --10.8885 -21.5711 6.80164 --10.8886 -21.4216 7.21839 --10.9137 -21.3169 7.64771 --10.9256 -21.1884 8.0706 --10.9518 -21.0869 8.50344 --10.9755 -20.9787 8.93569 --10.7562 -20.4226 9.19369 --10.718 -20.2039 9.57434 --10.6232 -19.883 9.90723 --10.7804 -20.0194 10.445 --10.7914 -19.8882 10.867 --11.9245 -21.7464 12.3091 --11.9557 -21.6363 12.7976 --11.9841 -21.5174 13.2864 --12.0304 -21.4292 13.7984 --12.0421 -21.2772 14.279 --10.8806 -19.1241 13.4819 --10.9483 -19.0826 13.9913 --10.9688 -18.9576 14.4529 --10.9247 -18.7221 14.8409 --10.9156 -18.5452 15.2738 --10.8509 -18.2765 15.6385 --10.6273 -17.7503 15.7925 --11.1686 -18.4579 16.9787 --10.9802 -17.9853 17.187 --2.42594 -4.324 5.27765 --2.38393 -4.07912 5.70797 --2.88307 -4.78166 6.66462 --2.34504 -3.92746 5.89792 --2.21966 -3.6965 5.80843 --2.25031 -3.69537 5.99009 --2.39742 -3.85835 6.39153 --2.50918 -3.9649 6.74247 --2.65103 -4.10961 7.16741 --1.78578 -2.85824 5.60055 --1.76353 -2.78654 5.6739 --2.01645 -3.08185 6.3243 --1.96401 -2.96294 6.3472 --1.99472 -2.95387 6.55183 --1.98049 -2.88435 6.66085 --1.93986 -2.77991 6.71131 --1.93454 -2.71925 6.84294 --1.89226 -2.61376 6.89031 --1.71061 -2.34228 6.5871 --1.68628 -2.26083 6.6694 --1.66435 -2.18146 6.75908 --1.86047 -2.34624 7.44293 --1.70252 -2.11121 7.17384 --1.60396 -1.94642 7.05752 --1.60465 -1.88861 7.22398 --1.56411 -1.78559 7.2726 --1.69713 -1.85209 7.85713 --1.4452 -1.5444 7.24497 --1.48211 -1.51384 7.54585 --1.43597 -1.40398 7.57834 --1.19519 -1.13153 6.93497 --1.13402 -1.01863 6.89367 --1.49954 -1.23143 8.42057 --1.37847 -1.06085 8.19186 --1.06167 -0.762921 7.17435 --0.933027 -0.608641 6.85583 --0.885725 -0.510042 6.85065 --0.983397 -0.489269 7.47259 --1.07568 -0.450608 8.11627 --0.886793 -0.278297 7.49555 --0.868772 -0.184374 7.65073 --0.787237 -0.0685535 7.50093 --0.787187 0.0262401 7.76045 --0.693496 0.140653 7.52717 --0.607086 0.246694 7.32083 --0.592287 0.348718 7.51629 --0.522805 0.449134 7.39436 --0.461463 0.547726 7.30964 --0.433283 0.655074 7.44034 --0.360417 0.744176 7.26283 --0.327934 0.853924 7.37984 --0.279336 0.954652 7.37634 --0.230365 1.05591 7.37079 --0.204035 1.18432 7.5704 --0.140405 1.26825 7.43294 --0.0482202 1.29334 6.96984 --0.0784714 -1.46075 -0.731581 --0.0989518 -1.49255 -0.706702 --0.241418 -1.75255 -0.656026 --0.273419 -1.81348 -0.648554 --0.303689 -1.86694 -0.633391 --0.337392 -1.92877 -0.622143 --0.374314 -1.99795 -0.614718 --0.411625 -2.06761 -0.605052 --0.449095 -2.1368 -0.593246 --0.488166 -2.20719 -0.579025 --0.526426 -2.27731 -0.562544 --0.572324 -2.36289 -0.553727 --0.622036 -2.45736 -0.546683 --0.665671 -2.53602 -0.527131 --0.71629 -2.63107 -0.513856 --0.76494 -2.71769 -0.493085 --0.824295 -2.82987 -0.481628 --0.880734 -2.93377 -0.462264 --0.960504 -3.08839 -0.461964 --1.02587 -3.20882 -0.441791 --1.07696 -3.2964 -0.403203 --1.14782 -3.42503 -0.378404 --1.22321 -3.56372 -0.351773 --1.29895 -3.7013 -0.320277 --1.38376 -3.8567 -0.289236 --1.47394 -4.02067 -0.255222 --1.57683 -4.21014 -0.222563 --1.68167 -4.39976 -0.182819 --1.79081 -4.59679 -0.138331 --1.92191 -4.83822 -0.0960376 --2.05415 -5.07955 -0.0444966 --2.19688 -5.33708 0.0126957 --2.36601 -5.64768 0.071273 --2.55406 -5.99318 0.13663 --2.7619 -6.37193 0.210493 --2.99307 -6.7943 0.294521 --3.25674 -7.27775 0.38972 --3.52419 -7.75852 0.503459 --3.86844 -8.38807 0.62894 --4.2612 -9.10301 0.776259 --4.73845 -9.97432 0.950339 --5.29176 -10.9823 1.1601 --6.07885 -12.4278 1.4229 --6.93636 -13.9879 1.74848 --7.79392 -15.528 2.135 --8.1062 -16.0149 2.48989 --8.36249 -16.3889 2.85344 --10.1554 -19.6281 3.60266 --10.6443 -20.4027 4.11749 --10.6194 -20.2173 4.50435 --10.3114 -19.5157 4.78946 --10.6418 -19.9857 5.2954 --10.7199 -19.9892 5.71706 --10.6758 -19.773 6.0878 --11.0132 -20.239 6.64013 --11.052 -20.1687 7.05965 --11.0935 -20.1002 7.48186 --11.1111 -19.9906 7.89315 --11.1733 -19.9585 8.33343 --11.1604 -19.7947 8.7283 --10.8388 -19.1044 8.90895 --10.7857 -18.876 9.26301 --10.7152 -18.6195 9.60093 --10.5467 -18.2005 9.85681 --10.877 -18.6152 10.5181 --10.7492 -18.2635 10.8057 --11.3914 -19.1766 11.7823 --11.4345 -19.0976 12.2432 --11.4536 -18.9807 12.6877 --11.4559 -18.8332 13.1179 --11.4675 -18.7014 13.5621 --11.3966 -18.4366 13.9203 --11.1093 -17.8355 14.0356 --11.0419 -17.5806 14.3872 --10.9478 -17.2845 14.7062 --11.0197 -17.2419 15.2262 --10.8325 -16.8059 15.4287 --11.2731 -17.3105 16.4423 --11.2075 -17.052 16.8145 --2.95929 -4.58586 6.4079 --2.98993 -4.57641 6.60434 --3.02614 -4.57388 6.81651 --2.30228 -3.53158 5.75496 --2.65278 -3.96016 6.48729 --2.47305 -3.67064 6.31441 --2.61702 -3.81023 6.71584 --2.74407 -3.92331 7.10319 --2.21516 -3.18843 6.24682 --2.16346 -3.07517 6.28214 --2.10747 -2.95781 6.30688 --2.14036 -2.94926 6.51147 --2.11724 -2.87141 6.60539 --2.05898 -2.75151 6.62479 --2.03108 -2.66772 6.70745 --2.10285 -2.6982 7.02198 --1.8383 -2.34429 6.55656 --1.74604 -2.19104 6.47845 --1.82061 -2.22075 6.80853 --1.97169 -2.32729 7.35071 --1.96321 -2.25805 7.49708 --1.88907 -2.12227 7.47522 --1.79377 -1.9655 7.3873 --1.73018 -1.84299 7.38513 --1.60268 -1.6618 7.18996 --1.77779 -1.75849 7.89279 --1.50052 -1.44694 7.23323 --1.8657 -1.68992 8.57948 --1.47996 -1.29955 7.5378 --1.23567 -1.04326 6.91191 --1.53727 -1.20004 8.14167 --1.42952 -1.04681 7.98064 --1.41164 -0.956379 8.13907 --1.02946 -0.64077 6.90997 --0.969035 -0.53623 6.86804 --1.00296 -0.483217 7.20981 --1.19763 -0.496989 8.25868 --1.15174 -0.384908 8.3219 --0.898188 -0.199055 7.43837 --0.867056 -0.101877 7.54383 --0.922052 -0.0214825 8.07859 --0.764569 0.10593 7.56364 --0.721282 0.208813 7.61486 --0.641586 0.312934 7.46725 --0.580901 0.413352 7.41589 --0.626341 0.53489 8.01351 --0.45546 0.606848 7.26744 --0.400702 0.703125 7.2397 --0.43699 0.851585 7.86152 --0.322776 0.914667 7.40526 --0.270236 1.01434 7.40136 --0.240568 1.13912 7.59258 --0.18491 1.23933 7.56464 --0.104588 1.29689 7.27938 --0.129831 -1.45057 -0.723623 --0.156871 -1.4961 -0.711963 --0.309953 -1.75947 -0.664912 --0.341867 -1.81173 -0.650966 --0.377207 -1.87237 -0.641033 --0.412921 -1.93355 -0.629054 --0.454715 -2.00885 -0.626571 --0.490954 -2.0701 -0.610503 --0.534758 -2.14703 -0.603073 --0.575625 -2.21575 -0.588027 --0.620012 -2.29258 -0.575729 --0.668926 -2.37719 -0.565816 --0.717316 -2.46232 -0.552762 --0.768084 -2.54737 -0.537029 --0.82174 -2.64137 -0.522364 --0.876826 -2.73543 -0.504608 --0.935577 -2.83716 -0.487654 --1.01171 -2.97281 -0.482734 --1.09188 -3.11667 -0.476669 --1.14183 -3.19373 -0.436672 --1.20828 -3.30468 -0.407519 --1.28666 -3.44018 -0.384298 --1.37154 -3.5852 -0.359 --1.45209 -3.72016 -0.325679 --1.54995 -3.88989 -0.298234 --1.64145 -4.04302 -0.259159 --1.75942 -4.24612 -0.229169 --1.8701 -4.43268 -0.186748 --1.99843 -4.65298 -0.14563 --2.1336 -4.88178 -0.0979603 --2.28709 -5.14558 -0.0483775 --2.4471 -5.41551 0.00940549 --2.63576 -5.73881 0.0695995 --2.84898 -6.10409 0.136113 --3.08717 -6.5118 0.211477 --3.3367 -6.93479 0.300959 --3.61174 -7.4002 0.403673 --3.93637 -7.95153 0.519323 --4.32978 -8.62218 0.651351 --4.79763 -9.41983 0.806719 --5.33605 -10.3364 0.993554 --6.03836 -11.5359 1.2214 --6.81773 -12.8579 1.50158 --7.74795 -14.4312 1.84887 --8.0954 -14.9498 2.18115 --8.36304 -15.3224 2.52209 --10.1956 -18.426 3.19422 --10.3674 -18.6013 3.59785 --10.3775 -18.4948 3.96755 --10.38 -18.3752 4.33361 --10.2882 -18.0956 4.66647 --10.523 -18.3726 5.11272 --10.5796 -18.3442 5.50132 --10.5984 -18.2512 5.87621 --10.619 -18.1608 6.25215 --10.636 -18.0641 6.62714 --10.6592 -17.9786 7.00668 --10.6747 -17.8789 7.38276 --10.6963 -17.7903 7.76415 --10.7196 -17.7028 8.14806 --10.7393 -17.6088 8.5318 --10.7356 -17.4775 8.90123 --10.7292 -17.3398 9.26872 --10.8182 -17.3531 9.7111 --10.8939 -17.3412 10.1496 --10.8611 -17.1611 10.5047 --10.9726 -17.2029 10.9858 --10.9975 -17.1073 11.3968 --11.0222 -17.0127 11.8134 --11.0389 -16.903 12.2257 --11.0656 -16.8068 12.6527 --11.0783 -16.6896 13.0709 --11.1073 -16.5924 13.5099 --11.1262 -16.4797 13.9446 --11.136 -16.3524 14.3747 --11.0656 -16.1091 14.7149 --11.0298 -15.9147 15.0969 --10.7876 -15.4317 15.2224 --11.3101 -16.0087 16.3253 --11.1854 -15.686 16.6116 --3.08846 -4.42202 6.39489 --3.08821 -4.37039 6.54278 --3.01518 -4.22534 6.5795 --2.75408 -3.84288 6.30843 --2.65682 -3.67133 6.28906 --2.65738 -3.62558 6.43297 --2.53071 -3.42007 6.35405 --2.57983 -3.43244 6.58539 --2.37802 -3.14234 6.36057 --2.30689 -3.00969 6.36562 --2.31536 -2.97253 6.52455 --2.62996 -3.28185 7.29718 --2.17792 -2.71805 6.53755 --2.25324 -2.75199 6.84129 --2.27461 -2.72206 7.04119 --2.14544 -2.53079 6.91685 --2.13779 -2.46904 7.05653 --2.16497 -2.44194 7.28141 --2.36692 -2.58776 7.93823 --2.09931 -2.26135 7.46548 --2.18772 -2.28546 7.86686 --1.92735 -1.97739 7.37808 --2.08036 -2.05685 7.96744 --1.89889 -1.82865 7.6631 --1.68005 -1.57685 7.23347 --1.5993 -1.44853 7.17844 --1.70524 -1.47144 7.68123 --1.65775 -1.36707 7.73449 --1.55678 -1.22388 7.61829 --1.515 -1.12369 7.68512 --1.53006 -1.06215 7.94866 --1.50562 -0.970738 8.08926 --1.1824 -0.700716 7.15264 --1.03556 -0.549089 6.8076 --0.98944 -0.457677 6.83223 --1.0612 -0.41913 7.3276 --1.24725 -0.41572 8.33788 --1.15431 -0.288453 8.21635 --1.19161 -0.203711 8.66655 --1.04639 -0.0642912 8.29619 --0.880428 0.0669176 7.79448 --0.863253 0.169298 8.00463 --0.722225 0.27949 7.57446 --0.874088 0.3961 8.73564 --0.672334 0.493471 7.93618 --0.549091 0.583073 7.53751 --0.453171 0.667675 7.27464 --0.392321 0.761376 7.22655 --0.403009 0.899003 7.68991 --0.316815 0.977202 7.46055 --0.26299 1.07842 7.46565 --0.223172 1.19771 7.60706 --0.15227 1.27699 7.46092 --0.0508916 1.29493 6.96928 --0.182788 -1.44661 -0.722194 --0.379999 -1.76393 -0.673852 --0.410115 -1.80891 -0.653088 --0.450305 -1.87575 -0.648389 --0.490875 -1.94309 -0.641547 --0.532817 -2.01067 -0.63239 --0.570831 -2.07031 -0.615789 --0.617393 -2.14538 -0.607751 --0.663404 -2.22107 -0.596963 --0.710793 -2.29697 -0.583763 --0.761753 -2.38081 -0.572631 --0.814129 -2.46476 -0.558602 --0.874478 -2.56481 -0.550677 --0.931898 -2.65663 -0.53504 --0.989793 -2.74868 -0.515994 --1.0648 -2.8738 -0.509666 --1.14059 -2.99986 -0.498662 --1.21327 -3.11661 -0.479559 --1.27415 -3.209 -0.445446 --1.35699 -3.34291 -0.424972 --1.43226 -3.4595 -0.393043 --1.52074 -3.60116 -0.365996 --1.60634 -3.73446 -0.330652 --1.71922 -3.91799 -0.306655 --1.82857 -4.09405 -0.272778 --1.94412 -4.27719 -0.234885 --2.06519 -4.46846 -0.192072 --2.21543 -4.71026 -0.154203 --2.36228 -4.94422 -0.1048 --2.52418 -5.20202 -0.0515459 --2.71712 -5.51079 0.00258422 --2.9213 -5.83683 0.0664573 --3.16049 -6.22057 0.134586 --3.41239 -6.62149 0.216134 --3.70479 -7.08828 0.306662 --3.99928 -7.55377 0.416169 --2.49339 -4.89414 0.729945 --2.50036 -4.87193 0.833776 --2.49189 -4.82206 0.937444 --2.51702 -4.83143 1.03955 --2.47451 -4.72758 1.14014 --2.50288 -4.74256 1.24174 --8.06838 -13.976 1.90238 --8.42536 -14.4738 2.23215 --10.2486 -17.3739 2.82736 --10.3909 -17.4916 3.20474 --10.6556 -17.8059 3.61763 --10.5576 -17.531 3.95027 --10.4504 -17.2439 4.27227 --10.7646 -17.6293 4.72375 --10.8293 -17.6142 5.10447 --10.8431 -17.5185 5.46851 --10.8702 -17.4425 5.83788 --10.8928 -17.3604 6.20681 --10.9067 -17.2643 6.5725 --10.9278 -17.1792 6.94272 --10.9516 -17.096 7.31522 --10.9712 -17.0076 7.68769 --10.9872 -16.9128 8.05969 --10.9567 -16.7491 8.40409 --10.9238 -16.5814 8.74528 --10.8664 -16.3783 9.06849 --10.9674 -16.4064 9.50652 --11.0072 -16.3433 9.90528 --10.9761 -16.1762 10.2513 --11.1949 -16.3663 10.8067 --11.2178 -16.2721 11.208 --11.2408 -16.1799 11.6151 --11.2662 -16.086 12.0274 --11.2862 -15.9858 12.4407 --11.3182 -15.8984 12.8697 --11.2644 -15.6937 13.2168 --11.1669 -15.4296 13.5173 --11.1712 -15.3024 13.9278 --11.0906 -15.0616 14.2479 --11.1466 -14.999 14.7258 --10.9367 -14.5878 14.892 --11.4307 -15.0882 15.9274 --11.3478 -14.8372 16.2639 --3.2702 -4.38093 6.32006 --3.23294 -4.28539 6.41484 --2.68434 -3.57058 5.7538 --2.93275 -3.82674 6.26392 --2.99383 -3.85129 6.50329 --3.08826 -3.91269 6.80379 --2.92092 -3.61795 6.83891 --2.52504 -3.11928 6.30618 --2.43643 -2.97527 6.29063 --2.81945 -3.34866 7.13369 --2.83004 -3.30672 7.31822 --2.75697 -3.1724 7.34379 --3.02834 -3.4015 8.05321 --2.98931 -3.2992 8.16243 --2.28869 -2.52752 6.88807 --2.24183 -2.42853 6.94506 --2.23885 -2.37367 7.10167 --2.46016 -2.52998 7.77094 --2.15827 -2.18717 7.25099 --2.09583 -2.07362 7.27522 --2.10828 -2.0277 7.48173 --2.02388 -1.89353 7.44919 --2.16866 -1.95522 8.01243 --2.27809 -1.97841 8.50969 --1.72312 -1.46688 7.19535 --1.62954 -1.33401 7.11177 --1.74957 -1.36264 7.6512 --1.71845 -1.2733 7.75936 --1.65125 -1.15875 7.76368 --1.52105 -1.00333 7.55891 --1.57812 -0.96845 7.96297 --1.51771 -0.85813 7.98943 --1.15742 -0.587844 6.94635 --1.12332 -0.503179 7.0305 --1.09338 -0.418001 7.13242 --1.34418 -0.444331 8.35264 --1.28424 -0.33095 8.38824 --1.20833 -0.212935 8.35378 --1.22912 -0.11921 8.7454 --1.0363 0.0224844 8.17938 --0.939634 0.136607 8.02934 --0.847961 0.246033 7.88616 --0.917753 0.356894 8.58562 --0.840786 0.47168 8.53686 --0.70888 0.571192 8.16085 --0.635054 0.677333 8.09705 --0.446969 0.727533 7.28183 --0.516669 0.897617 8.16055 --0.361729 0.938521 7.47879 --0.290691 1.02495 7.3774 --0.229789 1.11727 7.343 --0.189372 1.23519 7.4937 --0.111859 1.30259 7.29821 --0.24074 -1.44612 -0.728267 --0.447753 -1.75928 -0.676661 --0.486513 -1.81712 -0.667411 --0.525638 -1.87551 -0.656213 --0.568234 -1.94216 -0.648445 --0.608847 -2.00043 -0.633376 --0.652952 -2.0669 -0.621445 --0.701539 -2.14127 -0.612481 --0.754645 -2.22345 -0.605998 --0.807947 -2.30503 -0.596888 --0.866054 -2.39522 -0.589381 --0.921452 -2.47817 -0.574157 --0.977069 -2.56046 -0.556014 --1.04508 -2.66694 -0.547722 --1.10698 -2.75773 -0.527409 --1.1902 -2.88869 -0.523561 --1.26981 -3.01241 -0.510903 --1.32954 -3.09434 -0.475674 --1.41119 -3.21793 -0.454667 --1.48873 -3.33248 -0.425732 --1.5814 -3.47171 -0.402116 --1.67023 -3.60277 -0.369985 --1.77903 -3.76699 -0.344289 --1.8793 -3.9141 -0.30692 --2.01368 -4.11933 -0.281476 --2.13961 -4.3072 -0.243288 --2.27681 -4.51159 -0.202001 --2.43015 -4.74099 -0.158635 --2.59973 -4.99503 -0.111632 --2.6153 -4.98535 -0.00252622 --2.57356 -4.88039 0.122736 --2.56174 -4.82418 0.235606 --2.5677 -4.80066 0.34189 --2.57315 -4.77535 0.447293 --2.58782 -4.76512 0.550069 --2.60128 -4.75412 0.652867 --2.60354 -4.72472 0.756454 --2.5933 -4.67645 0.859588 --2.60946 -4.6694 0.960404 --2.38864 -4.28847 1.0595 --2.66462 -4.69251 1.16308 --2.68273 -4.68895 1.26505 --2.69967 -4.68451 1.36753 --2.71097 -4.66904 1.46917 --2.69894 -4.62011 1.56746 --10.4882 -16.4671 3.1941 --10.4991 -16.3758 3.53481 --10.518 -16.2971 3.87671 --10.4066 -16.0241 4.18096 --10.8915 -16.6386 4.66693 --10.9442 -16.6068 5.03089 --10.8773 -16.3992 5.35203 --11.1772 -16.7263 5.81831 --11.1979 -16.6441 6.17977 --11.2088 -16.5481 6.53812 --11.2228 -16.4553 6.89818 --11.2385 -16.3647 7.26046 --11.2549 -16.2756 7.62508 --11.2306 -16.1277 7.96672 --11.0152 -15.7155 8.18972 --11.0005 -15.5832 8.53098 --10.927 -15.3707 8.8329 --10.9209 -15.2508 9.18012 --11.081 -15.354 9.65158 --11.0507 -15.2002 9.98863 --11.4229 -15.5803 10.6499 --11.4337 -15.4739 11.0339 --11.4611 -15.3898 11.4367 --11.4789 -15.2921 11.836 --11.5086 -15.2072 12.2506 --11.4813 -15.0469 12.6152 --11.23 -14.479 13.1505 --11.2383 -14.3638 13.5545 --11.1551 -14.1324 13.8623 --11.2051 -14.0665 14.323 --11.1346 -13.8492 14.6493 --10.8969 -13.4319 14.7768 --11.4523 -13.9635 15.8772 --11.3114 -13.6581 16.135 --3.36885 -4.1378 6.42689 --2.87589 -3.52997 5.87272 --2.73692 -3.33259 5.80478 --3.14651 -3.74268 6.55568 --3.05709 -3.5485 6.72221 --3.00201 -3.44034 6.78761 --3.47686 -3.88927 7.7445 --3.39999 -3.75181 7.79483 --3.36309 -3.65471 7.91185 --3.26338 -3.49549 7.91703 --3.24435 -3.41707 8.06962 --3.23261 -3.34409 8.2379 --3.12669 -3.18054 8.22582 --2.42265 -2.45522 6.99045 --2.39146 -2.37503 7.0901 --2.3556 -2.28857 7.17994 --2.3717 -2.24871 7.38837 --2.24443 -2.08143 7.27784 --2.11863 -1.91904 7.16224 --2.12058 -1.86469 7.3409 --2.13637 -1.81972 7.56424 --2.5505 -2.0801 8.8086 --2.35118 -1.85658 8.51825 --1.72575 -1.329 7.0564 --1.65861 -1.22321 7.05385 --1.68131 -1.17879 7.30681 --1.90143 -1.25738 8.15463 --1.89778 -1.18199 8.37552 --1.58512 -0.922412 7.6293 --1.62607 -0.874004 7.98607 --1.29869 -0.629241 7.12013 --1.2233 -0.525269 7.07307 --1.14891 -0.422692 7.02317 --1.46902 -0.476909 8.45174 --1.33885 -0.340987 8.22897 --1.30301 -0.239633 8.37033 --1.3888 -0.164608 9.03496 --1.13334 -0.00840084 8.24892 --1.02723 0.106124 8.08172 --0.960705 0.213801 8.08753 --0.874793 0.320082 7.99325 --0.940818 0.438302 8.69215 --0.799208 0.540176 8.30873 --0.701844 0.641571 8.13869 --0.523123 0.703329 7.44403 --0.466036 0.800995 7.46631 --0.411444 0.901835 7.50599 --0.3457 0.994756 7.4752 --0.295386 1.1019 7.56042 --0.246162 1.21401 7.66324 --0.160307 1.2808 7.44939 --0.0545393 1.29677 6.9687 --0.512005 -1.74481 -0.673513 --0.552761 -1.80204 -0.663727 --0.600794 -1.87415 -0.663456 --0.643037 -1.93126 -0.649799 --0.692844 -2.00405 -0.644779 --0.734651 -2.06142 -0.626815 --0.790091 -2.14136 -0.622451 --0.840899 -2.21445 -0.609935 --0.89721 -2.29508 -0.599825 --0.959287 -2.38411 -0.591536 --1.02476 -2.47998 -0.584734 --1.07902 -2.55305 -0.561068 --1.14664 -2.6501 -0.547373 --1.21989 -2.75432 -0.534432 --1.30811 -2.88374 -0.529145 --1.39127 -3.00424 -0.515322 --1.45846 -3.09322 -0.482449 --1.53924 -3.20551 -0.456629 --1.63069 -3.33452 -0.432967 --1.72816 -3.47113 -0.407526 --1.83074 -3.61546 -0.379796 --1.93517 -3.76021 -0.346149 --2.0642 -3.94563 -0.320153 --2.19022 -4.12139 -0.2845 --2.32771 -4.31474 -0.246039 --2.48179 -4.5311 -0.206596 --2.61135 -4.70551 -0.148386 --2.7359 -4.8709 -0.0812508 --3.04097 -5.31904 -0.0628963 --3.26919 -5.64025 -0.00447518 --3.52594 -6.00233 0.0609493 --3.80653 -6.39629 0.13673 --4.09924 -6.80422 0.226895 --4.43284 -7.26897 0.328695 --4.86127 -7.87231 0.439415 --5.21528 -8.35516 0.581607 --5.22266 -8.31083 0.761205 --5.07145 -8.03021 0.942013 --4.80634 -7.58283 1.1104 --4.83869 -7.58077 1.27425 --4.8427 -7.53561 1.43654 --5.31854 -8.17994 1.64765 --5.29232 -8.08698 1.81815 --10.5339 -15.5683 2.85191 --10.5617 -15.5072 3.18399 --10.5752 -15.4252 3.51281 --10.5793 -15.3303 3.83871 --10.5566 -15.1986 4.15633 --10.749 -15.3669 4.53856 --10.7547 -15.2731 4.86746 --10.7735 -15.1982 5.20129 --10.778 -15.1036 5.53021 --10.7964 -15.0266 5.86472 --10.7995 -14.9302 6.19385 --10.8166 -14.851 6.52983 --10.8245 -14.7601 6.86281 --10.8403 -14.6787 7.20095 --10.8518 -14.592 7.53895 --10.8664 -14.5082 7.88013 --10.8486 -14.3816 8.20295 --10.8556 -14.2873 8.54285 --10.7347 -14.0283 8.79607 --11.0123 -14.2762 9.33145 --10.997 -14.1497 9.66554 --11.1292 -14.2083 10.117 --11.1623 -14.139 10.4977 --11.1848 -14.0562 10.8752 --11.1923 -13.9527 11.2438 --11.2122 -13.8639 11.6278 --11.217 -13.7545 12.0023 --11.2278 -13.652 12.3876 --11.2456 -13.5558 12.7845 --11.2693 -13.4651 13.1935 --11.2083 -13.2732 13.5181 --11.233 -13.1807 13.9394 --11.254 -13.0795 14.362 --11.0429 -12.7169 14.5229 --11.5588 -13.1675 15.5498 --11.4166 -12.8767 15.8042 --11.2 -12.5059 15.961 --3.53302 -4.02595 6.48622 --3.31413 -3.74639 6.33742 --3.71038 -3.7824 8.12769 --3.39627 -3.42267 7.77998 --3.25323 -3.23067 7.7112 --3.22977 -3.1525 7.85266 --3.21726 -3.08248 8.01776 --2.65273 -2.51983 7.12349 --2.53577 -2.36339 7.05986 --2.51024 -2.28983 7.17651 --2.616 -2.32551 7.57233 --2.45288 -2.13429 7.40726 --2.23103 -1.89943 7.09712 --2.11382 -1.75313 7.00517 --2.25807 -1.80882 7.51694 --2.21654 -1.71928 7.60815 --1.90296 -1.43333 7.02564 --1.63196 -1.18865 6.5125 --1.74522 -1.21263 6.98107 --1.67175 -1.10742 6.96813 --1.67174 -1.04854 7.15578 --1.91033 -1.12882 8.04938 --1.83137 -1.01266 8.04506 --1.63755 -0.836677 7.68106 --1.62381 -0.758268 7.8678 --1.55058 -0.648975 7.86409 --1.22369 -0.434121 6.99016 --1.49847 -0.470391 8.1946 --1.46868 -0.374481 8.35822 --1.35237 -0.249675 8.20209 --1.46011 -0.184732 8.93377 --1.2117 -0.0329398 8.22951 --1.13924 0.0753294 8.23009 --1.0538 0.184542 8.16964 --0.895963 0.290515 7.75443 --0.889429 0.394546 8.06117 --0.925249 0.51553 8.62201 --0.777685 0.609635 8.21838 --0.711618 0.71747 8.24468 --0.50188 0.75892 7.37262 --0.557956 0.922984 8.17271 --0.383241 0.950385 7.42414 --0.314983 1.03946 7.3829 --0.262886 1.14498 7.46749 --0.198174 1.23814 7.46196 --0.124196 1.31655 7.35581 --0.508529 -1.64298 -0.710437 --0.547012 -1.69271 -0.697241 --0.589412 -1.74873 -0.688672 --0.624084 -1.79018 -0.666475 --0.674861 -1.86048 -0.665791 --0.718145 -1.91715 -0.651282 --0.769727 -1.98834 -0.645728 --0.822695 -2.05971 -0.637666 --0.871743 -2.12314 -0.622061 --0.934725 -2.20988 -0.618984 --0.993809 -2.28861 -0.608072 --1.0577 -2.37591 -0.598665 --1.12279 -2.46232 -0.586363 --1.18859 -2.54993 -0.570553 --1.25878 -2.64403 -0.555864 --1.35 -2.77022 -0.553792 --1.44181 -2.89631 -0.546853 --1.50592 -2.97524 -0.512526 --1.58033 -3.07031 -0.482207 --1.68019 -3.20395 -0.46553 --1.77076 -3.32167 -0.437054 --1.87206 -3.45592 -0.409862 --1.98488 -3.60535 -0.383491 --2.09838 -3.75438 -0.350988 --2.23968 -3.94421 -0.325426 --2.37702 -4.12455 -0.289892 --2.52087 -4.3127 -0.249171 --2.6873 -4.53322 -0.209092 --2.87169 -4.77699 -0.165718 --3.07339 -5.04488 -0.117467 --3.30484 -5.35205 -0.0661565 --3.55967 -5.6908 -0.00760514 --3.84507 -6.06969 0.0590701 --4.13283 -6.44581 0.141387 --4.44437 -6.85233 0.236102 --4.85511 -7.39615 0.335725 --5.00507 -7.56033 0.484773 --5.03355 -7.54956 0.649616 --5.16997 -7.69256 0.810516 --5.13175 -7.58814 0.979632 --5.04387 -7.41611 1.14396 --5.04218 -7.364 1.30603 --5.01996 -7.286 1.46543 --5.02612 -7.24706 1.62557 --5.01817 -7.18804 1.78285 --10.7349 -14.8392 2.87385 --10.7545 -14.7695 3.19648 --10.6278 -14.5054 3.48659 --10.5447 -14.3013 3.77932 --10.9064 -14.6826 4.1892 --10.96 -14.6564 4.52498 --10.9617 -14.5631 4.84616 --10.9909 -14.5041 5.17666 --11.0167 -14.4397 5.5071 --11.0385 -14.371 5.83769 --11.051 -14.2895 6.16536 --11.0654 -14.2111 6.49546 --11.0766 -14.1274 6.825 --11.0959 -14.0541 7.16059 --11.112 -13.9752 7.49611 --11.0888 -13.8474 7.81075 --11.1036 -13.7663 8.14891 --11.0493 -13.6016 8.44541 --10.9793 -13.419 8.7305 --11.1656 -13.5389 9.19175 --11.1529 -13.422 9.52195 --11.2826 -13.471 9.96166 --11.3026 -13.3896 10.3255 --11.3307 -13.3155 10.6996 --11.3472 -13.2283 11.0702 --11.3717 -13.1473 11.4516 --11.3866 -13.0538 11.8291 --11.3908 -12.947 12.2021 --11.3502 -12.7899 12.5371 --11.3064 -12.6286 12.8705 --11.3085 -12.516 13.2537 --11.2115 -12.2962 13.5374 --11.2919 -12.2645 14.0152 --11.1877 -12.0338 14.2943 --10.9718 -11.6885 14.4435 --11.5493 -12.1643 15.5385 --11.4026 -11.8857 15.7853 --4.35241 -4.21528 8.56689 --4.28499 -4.09081 8.66992 --4.21596 -3.96519 8.77035 --4.18299 -3.87076 8.93064 --3.34679 -3.07177 7.70175 --4.14731 -3.70473 9.31271 --3.92489 -3.44727 9.13761 --2.73387 -2.3908 7.12674 --2.86542 -2.44623 7.55357 --2.71988 -2.27304 7.44779 --2.66672 -2.17696 7.52359 --2.41323 -1.92709 7.17675 --2.25793 -1.75757 7.01929 --2.16055 -1.63461 6.97862 --2.0792 -1.52422 6.96962 --1.98393 -1.4053 6.92211 --1.71666 -1.17343 6.4492 --1.70611 -1.11623 6.59063 --1.67168 -1.0427 6.67722 --1.71833 -1.01607 6.98299 --1.66203 -0.926181 7.02259 --1.95719 -1.02479 8.06423 --1.74147 -0.843303 7.6668 --1.40501 -0.613272 6.86735 --1.68317 -0.67362 7.95671 --1.64861 -0.584002 8.09569 --1.64791 -0.503632 8.35739 --1.47589 -0.361039 8.03436 --1.44687 -0.26841 8.20658 --1.33619 -0.153204 8.07852 --1.30599 -0.0563969 8.25708 --1.22287 0.0519583 8.23027 --1.16185 0.156129 8.29876 --0.971764 0.265008 7.77901 --0.873745 0.362423 7.64631 --0.981575 0.481099 8.54069 --0.955515 0.600272 8.81709 --1.06461 0.770608 9.88812 --0.692676 0.783982 8.20291 --0.61865 0.887354 8.20708 --0.502615 0.961652 7.91349 --0.367173 1.00862 7.44035 --0.303111 1.10253 7.45794 --0.341871 1.3231 8.36878 --0.170022 1.28802 7.45741 --0.0564931 1.29619 6.95851 --0.53216 -1.57814 -0.719954 --0.571068 -1.62597 -0.708247 --0.614136 -1.68103 -0.700872 --0.658546 -1.7364 -0.691571 --0.703087 -1.79138 -0.68052 --0.755661 -1.86 -0.67901 --0.805776 -1.92231 -0.669392 --0.855318 -1.98529 -0.657316 --0.911059 -2.05476 -0.648451 --0.966241 -2.12487 -0.636934 --1.0279 -2.20228 -0.627846 --1.09412 -2.28737 -0.620655 --1.15644 -2.36446 -0.605728 --1.2287 -2.45714 -0.596758 --1.30242 -2.54976 -0.584209 --1.37663 -2.64259 -0.568155 --1.48122 -2.78152 -0.57253 --1.56285 -2.88213 -0.552188 --1.62976 -2.95909 -0.516766 --1.72744 -3.08263 -0.499532 --1.82126 -3.19806 -0.473978 --1.92109 -3.32116 -0.447033 --2.03241 -3.45953 -0.4213 --2.15008 -3.6062 -0.39252 --2.29031 -3.78306 -0.368987 --2.42703 -3.95238 -0.335379 --2.57573 -4.13718 -0.299477 --2.74197 -4.34478 -0.262715 --2.92157 -4.56806 -0.221248 --3.12493 -4.82287 -0.177819 --3.35293 -5.1076 -0.130705 --3.60618 -5.42372 -0.0776623 --3.88968 -5.77926 -0.0177629 --4.19853 -6.16424 0.0523432 --4.49838 -6.53077 0.141054 --4.85901 -6.97631 0.237322 --5.32909 -7.56259 0.339958 --5.84916 -8.20882 0.463715 --6.47461 -8.9872 0.609775 --7.12144 -9.78282 0.789073 --7.92892 -10.7805 1.00316 --8.1691 -11.0234 1.24726 --8.47468 -11.3479 1.50645 --9.09731 -12.0782 1.80663 --10.4893 -13.7824 2.22249 --10.8078 -14.0984 2.5682 --11.1238 -14.4075 2.92963 --10.8015 -13.9089 3.18567 --10.69 -13.6802 3.46889 --10.6815 -13.5799 3.77004 --11.0596 -13.9581 4.17524 --11.0937 -13.9081 4.4973 --11.0249 -13.7325 4.7874 --11.7045 -14.4631 5.33729 --11.7346 -14.403 5.67743 --11.7541 -14.3292 6.01506 --11.7827 -14.2657 6.35793 --11.5273 -13.8683 6.57276 --11.803 -14.0945 7.03265 --11.8444 -14.0441 7.38823 --11.3081 -13.3267 7.43443 --11.164 -13.0675 7.67606 --11.1708 -12.9805 8.00109 --11.0947 -12.7994 8.27627 --11.051 -12.6556 8.57084 --11.2113 -12.7394 9.00369 --11.2084 -12.6394 9.33263 --11.643 -13.0173 9.98579 --11.6605 -12.9346 10.3481 --11.6563 -12.8265 10.697 --11.6712 -12.7381 11.0652 --11.6756 -12.6373 11.4292 --11.6642 -12.5174 11.783 --12.6536 -13.4428 13.0552 --11.7607 -12.4006 12.6159 --11.4701 -11.9901 12.7128 --11.3613 -11.7682 12.9804 --11.3005 -11.5958 13.2966 --11.32 -11.5029 13.7011 --11.2891 -11.3588 14.0577 --11.0661 -11.0233 14.1989 --11.61 -11.4341 15.232 --11.5181 -11.2222 15.5425 --4.55977 -4.16108 8.48914 --4.4751 -4.02625 8.57159 --4.68106 -3.861 10.0547 --3.97477 -3.22969 9.04775 --4.01807 -3.19609 9.35569 --3.77376 -2.94141 9.13248 --3.954 -3.00668 9.71722 --3.98412 -2.95353 10.0287 --2.50723 -1.83254 7.24666 --2.28116 -1.62219 6.95008 --2.20489 -1.51912 6.96054 --2.0977 -1.39685 6.89785 --1.9487 -1.25037 6.73329 --1.7667 -1.08764 6.47368 --1.80516 -1.05931 6.74164 --1.73935 -0.968592 6.75607 --1.75604 -0.922547 6.98855 --1.6907 -0.830398 7.00931 --2.00856 -0.925434 8.10693 --1.58494 -0.659293 7.11957 --1.4493 -0.537258 6.92757 --1.78366 -0.606033 8.18785 --1.34496 -0.369541 7.035 --1.52225 -0.358535 7.86434 --1.50735 -0.274425 8.08502 --1.39569 -0.162358 7.96833 --1.58943 -0.113124 8.9978 --1.30224 0.0316995 8.21002 --1.27517 0.130689 8.42578 --1.03739 0.242436 7.74376 --0.946026 0.338358 7.66178 --0.994622 0.445684 8.24284 --0.996631 0.561671 8.6477 --1.08256 0.714802 9.55196 --0.988691 0.834454 9.54179 --0.677685 0.851249 8.21073 --0.594683 0.949359 8.17491 --0.407141 0.967824 7.39859 --0.317951 1.039 7.24032 --0.254715 1.12981 7.26728 --0.21416 1.25288 7.50883 --0.137478 1.33275 7.43329 --0.641735 -1.62005 -0.718549 --0.682769 -1.66688 -0.704554 --0.728947 -1.72067 -0.694817 --0.779321 -1.78158 -0.688925 --0.829847 -1.84203 -0.68099 --0.881737 -1.90273 -0.670839 --0.943174 -1.97854 -0.668982 --1.00071 -2.04635 -0.659292 --1.06375 -2.12169 -0.652008 --1.12722 -2.1974 -0.6419 --1.19625 -2.28049 -0.633518 --1.26669 -2.36366 -0.622141 --1.33762 -2.44705 -0.607356 --1.43417 -2.56782 -0.610813 --1.51734 -2.66525 -0.597266 --1.61622 -2.78665 -0.591399 --1.6749 -2.8466 -0.550264 --1.77043 -2.96001 -0.532279 --1.8675 -3.07316 -0.509743 --1.97034 -3.19303 -0.486014 --2.08041 -3.32123 -0.460429 --2.20725 -3.47129 -0.43866 --2.33598 -3.62167 -0.410584 --2.47112 -3.78017 -0.378587 --2.62992 -3.96822 -0.350205 --2.79074 -4.15621 -0.313767 --2.97013 -4.36663 -0.275909 --3.17493 -4.60735 -0.237209 --3.39228 -4.86349 -0.191543 --3.64759 -5.16471 -0.145103 --3.92923 -5.49677 -0.0913962 --4.07946 -5.6536 0.00663322 --3.8769 -5.35446 0.181019 --3.8607 -5.29683 0.311058 --3.81761 -5.20569 0.442216 --3.80946 -5.16001 0.565823 --3.81151 -5.12912 0.686975 --3.8003 -5.08059 0.807699 --3.82561 -5.07715 0.925813 --3.88003 -5.11155 1.04455 --3.89669 -5.09634 1.16384 --3.93686 -5.11172 1.28489 --3.87377 -5.00079 1.39857 --3.88531 -4.98187 1.51658 --10.7111 -13.1062 2.55781 --10.7217 -13.0334 2.85543 --10.7354 -12.9651 3.15331 --10.6421 -12.7715 3.4279 --11.0224 -13.1307 3.81074 --11.0643 -13.0935 4.12268 --11.0701 -13.0144 4.42602 --11.0667 -12.9236 4.72605 --11.1177 -12.8953 5.04479 --11.1456 -12.8403 5.35788 --11.1572 -12.7661 5.6661 --11.1525 -12.673 5.9684 --11.1692 -12.6051 6.28124 --11.1828 -12.5326 6.59412 --11.2054 -12.4692 6.91331 --11.2117 -12.387 7.22618 --11.2078 -12.2934 7.53519 --11.2322 -12.2291 7.86195 --11.1388 -12.0399 8.12037 --11.161 -11.9735 8.4499 --11.281 -12.0075 8.84694 --11.2645 -11.8975 9.15893 --11.3619 -11.9046 9.5551 --11.4051 -11.8532 9.91874 --11.4005 -11.7528 10.2514 --11.4098 -11.6648 10.5985 --11.4028 -11.5597 10.9364 --11.3913 -11.4484 11.274 --11.3879 -11.3445 11.6221 --11.4034 -11.2575 11.9926 --11.4206 -11.1697 12.3699 --11.4254 -11.0702 12.7429 --11.3971 -10.9355 13.0867 --11.3807 -10.812 13.4483 --11.4004 -10.72 13.8533 --11.1797 -10.4057 14.0005 --11.6593 -10.7279 14.9397 --11.6195 -10.574 15.3086 --4.29068 -3.34654 8.97331 --4.08831 -3.12918 8.85449 --4.09734 -3.07168 9.09565 --4.00167 -2.93676 9.15618 --4.15295 -2.97504 9.67254 --2.89699 -2.04002 7.52865 --2.75592 -1.89011 7.44209 --2.10568 -1.41021 6.31715 --2.02021 -1.31035 6.29777 --2.3754 -1.48443 7.22298 --2.17822 -1.3113 6.97593 --1.96585 -1.13575 6.67766 --2.28726 -1.26357 7.61292 --1.78444 -0.932514 6.60251 --1.70644 -0.840282 6.58811 --1.7411 -0.80366 6.86517 --1.71546 -0.735607 6.99592 --1.72104 -0.677514 7.2187 --1.57527 -0.555016 7.02077 --1.51638 -0.470433 7.06321 --1.38613 -0.359754 6.88602 --1.64394 -0.375481 7.94122 --1.55371 -0.271921 7.915 --1.48671 -0.175563 7.96309 --1.44466 -0.0829206 8.10534 --1.51675 -0.00459151 8.69079 --1.48152 0.0993354 8.89957 --1.10874 0.222974 7.7268 --1.03402 0.317422 7.73437 --0.957006 0.410965 7.73019 --1.07492 0.533879 8.66335 --1.2424 0.698317 9.96048 --1.04243 0.790524 9.42282 --0.735778 0.816845 8.1933 --0.649232 0.912377 8.14929 --0.590494 1.02377 8.2904 --0.400376 1.03426 7.50404 --0.309616 1.1049 7.36533 --0.239349 1.19195 7.36232 --0.175169 1.28912 7.42615 --0.0382442 1.26148 6.74198 --0.764579 -1.67107 -0.726252 --0.807762 -1.71683 -0.709677 --0.859926 -1.77609 -0.703057 --0.913453 -1.83561 -0.69422 --0.96714 -1.89464 -0.683242 --1.03135 -1.96855 -0.680583 --1.09069 -2.03467 -0.66997 --1.15674 -2.10906 -0.661686 --1.22809 -2.18993 -0.65552 --1.2948 -2.26398 -0.6413 --1.36804 -2.3452 -0.628926 --1.452 -2.44067 -0.622049 --1.54161 -2.54326 -0.61573 --1.64447 -2.66123 -0.613297 --1.74177 -2.77242 -0.601909 --1.80867 -2.83821 -0.563255 --1.90777 -2.94833 -0.543813 --2.00842 -3.05816 -0.519723 --2.12693 -3.19091 -0.50083 --2.24063 -3.31569 -0.473204 --2.37851 -3.46951 -0.452334 --2.52378 -3.63119 -0.427565 --2.66431 -3.7847 -0.393188 --2.82972 -3.96843 -0.36196 --3.01466 -4.17441 -0.329628 --3.21371 -4.39486 -0.292714 --3.42574 -4.62879 -0.250128 --3.67685 -4.90879 -0.207858 --3.94819 -5.21059 -0.15806 --4.25875 -5.55637 -0.103718 --4.58426 -5.91575 -0.0365219 --4.05246 -5.23043 0.204377 --3.99003 -5.11875 0.341175 --3.9756 -5.06683 0.466923 --3.98477 -5.04462 0.588374 --3.9866 -5.01274 0.709523 --3.98106 -4.97126 0.829981 --4.04427 -5.01307 0.948091 --4.00261 -4.93031 1.06757 --4.07003 -4.97588 1.18786 --9.61826 -11.2969 1.63237 --10.6221 -12.3655 1.97882 --11.1111 -12.839 2.31894 --11.4485 -13.134 2.66202 --10.8462 -12.3774 2.86987 --10.7844 -12.2271 3.14653 --10.7521 -12.111 3.42573 --11.1613 -12.48 3.80762 --11.1953 -12.4349 4.11118 --11.1463 -12.2984 4.39196 --11.4532 -12.5461 4.78182 --11.4824 -12.4932 5.09353 --11.5026 -12.4292 5.40321 --11.5179 -12.3612 5.71296 --11.5298 -12.2877 6.02245 --11.5049 -12.177 6.31744 --11.5832 -12.1708 6.65937 --11.5902 -12.0915 6.97234 --11.3631 -11.7735 7.16597 --11.2709 -11.5949 7.42288 --11.2744 -11.5123 7.73073 --11.1829 -11.3342 7.98412 --11.2179 -11.2834 8.31397 --11.3264 -11.3025 8.69544 --11.3206 -11.2076 9.00799 --11.7915 -11.5739 9.6583 --11.8079 -11.4948 10.0049 --11.8251 -11.4164 10.3573 --11.8369 -11.3318 10.7108 --11.8579 -11.2541 11.0755 --11.8672 -11.1634 11.4359 --11.8592 -11.0558 11.7867 --11.8277 -10.926 12.1211 --11.6394 -10.6534 12.3127 --11.4307 -10.3638 12.4789 --11.4478 -10.2768 12.8626 --11.3952 -10.1261 13.181 --11.4558 -10.0721 13.6221 --11.2688 -9.80487 13.8066 --11.0744 -9.53082 13.977 --11.6882 -9.93755 15.0727 --11.5157 -9.67747 15.2863 --4.28944 -3.21383 8.38837 --4.12251 -3.03467 8.33691 --4.31171 -3.10862 8.85387 --4.28702 -3.02784 9.03975 --4.19293 -2.89873 9.11094 --4.03198 -2.72571 9.06329 --3.07839 -2.03838 7.56297 --2.94519 -1.89837 7.5054 --2.77254 -1.73765 7.36684 --2.7382 -1.66298 7.48924 --2.11978 -1.24488 6.41845 --2.51695 -1.42337 7.42427 --2.47842 -1.34657 7.54167 --1.89079 -0.97654 6.42527 --1.83793 -0.900175 6.47661 --1.80299 -0.833342 6.57205 --1.77362 -0.767838 6.68485 --1.73781 -0.697603 6.7876 --1.66973 -0.612859 6.80632 --1.6853 -0.561452 7.05587 --1.38038 -0.389125 6.40669 --1.47517 -0.36458 6.88809 --1.49482 -0.306841 7.17342 --1.65395 -0.280621 7.92553 --1.58104 -0.185238 7.96585 --1.48005 -0.0835549 7.90796 --1.76618 -0.0414154 9.24381 --1.41909 0.0984313 8.30599 --1.21834 0.205046 7.85395 --1.1042 0.298829 7.71792 --1.01126 0.390259 7.65671 --1.06653 0.497986 8.2672 --1.09304 0.618136 8.8098 --1.08095 0.746314 9.21429 --1.02127 0.870148 9.41145 --0.714775 0.881777 8.18185 --0.631899 0.978883 8.18665 --0.435831 0.990394 7.41232 --0.314191 1.03298 7.05868 --0.275815 1.14871 7.31293 --0.233525 1.27347 7.58497 --0.145238 1.34161 7.46165 --0.879009 -1.69565 -0.712984 --0.932947 -1.75331 -0.705829 --0.993299 -1.81848 -0.701981 --1.05383 -1.88309 -0.695701 --1.11575 -1.94789 -0.686911 --1.17786 -2.01212 -0.675593 --1.25056 -2.09102 -0.67162 --1.32469 -2.16996 -0.664554 --1.39929 -2.24916 -0.654179 --1.48045 -2.3354 -0.645065 --1.57333 -2.43562 -0.641376 --1.66796 -2.5366 -0.633327 --1.76804 -2.64361 -0.625352 --1.85319 -2.72989 -0.600904 --1.93246 -2.80868 -0.568866 --2.04671 -2.92996 -0.555434 --2.15759 -3.04498 -0.533092 --2.27427 -3.16659 -0.508974 --2.41061 -3.30946 -0.489228 --2.54764 -3.4519 -0.463155 --2.69206 -3.60223 -0.433281 --2.86184 -3.78074 -0.407462 --3.03364 -3.95916 -0.373489 --3.23147 -4.16708 -0.34055 --3.44417 -4.38819 -0.30286 --3.67014 -4.62359 -0.258717 --3.94903 -4.91805 -0.218027 --4.07654 -5.03107 -0.124907 --4.09277 -5.01609 -0.0011161 --4.21848 -5.1258 0.100023 --5.28763 -6.30991 0.0448109 --5.77329 -6.8182 0.129905 --6.30923 -7.3754 0.233294 --6.93977 -8.03261 0.354488 --7.66172 -8.78071 0.500808 --8.11828 -9.22765 0.693551 --8.27853 -9.34332 0.912183 --8.57972 -9.61047 1.13901 --9.27308 -10.299 1.39376 --10.6132 -11.6749 1.72175 --10.8054 -11.8038 2.01601 --10.7964 -11.7174 2.29629 --10.804 -11.6498 2.57742 --10.8095 -11.5779 2.857 --10.7559 -11.4461 3.12552 --11.0962 -11.7237 3.47348 --11.2357 -11.7884 3.79019 --11.2469 -11.7222 4.08072 --11.1655 -11.5604 4.34504 --11.8238 -12.1462 4.83308 --11.8306 -12.0709 5.1375 --11.615 -11.7729 5.36275 --11.6586 -11.6526 5.97682 --11.5491 -11.4633 6.23003 --11.5986 -11.346 6.85268 --11.4033 -11.0767 7.0571 --11.3132 -10.9101 7.30948 --11.302 -10.8164 7.60215 --11.1382 -10.581 7.80818 --10.9784 -10.3516 8.01066 --11.3633 -10.6242 8.55195 --11.3691 -10.544 8.86582 --11.1124 -10.226 9.00348 --11.8796 -10.8303 9.85991 --11.8963 -10.7534 10.2057 --11.914 -10.6771 10.5577 --11.9211 -10.5885 10.9055 --11.9163 -10.49 11.2492 --11.8688 -10.3521 11.5605 --12.1647 -10.5074 12.1762 --11.7231 -10.0328 12.1444 --11.5133 -9.75727 12.3098 --11.5173 -9.6624 12.6764 --11.4005 -9.46481 12.9275 --11.4798 -9.42784 13.381 --11.3895 -9.25125 13.6665 --11.1593 -8.9623 13.7995 --11.7163 -9.294 14.813 --11.6252 -9.11076 15.1212 --4.40502 -3.04778 8.42757 --4.20762 -2.85611 8.33608 --4.26796 -2.83794 8.64551 --4.27731 -2.78279 8.88502 --4.22026 -2.68296 9.01905 --2.29731 -1.43215 5.91137 --2.22805 -1.35056 5.93151 --2.2075 -1.29796 6.04245 --2.76158 -1.57374 7.248 --2.65141 -1.45933 7.22194 --2.14907 -1.13644 6.39958 --2.06561 -1.04672 6.39479 --2.05764 -0.995053 6.54705 --1.98913 -0.912852 6.57429 --1.89677 -0.819816 6.54546 --1.8822 -0.762869 6.69558 --1.82715 -0.68663 6.754 --1.7567 -0.604258 6.77426 --1.67526 -0.517179 6.76446 --1.66981 -0.458487 6.9577 --1.31743 -0.285644 6.18531 --1.53858 -0.294669 7.03286 --1.44263 -0.204815 6.97777 --1.51899 -0.15575 7.46261 --1.7696 -0.128498 8.56138 --1.74942 -0.0352627 8.82223 --1.64687 0.0719667 8.80308 --1.39614 0.186453 8.2207 --1.21104 0.283554 7.83584 --1.12766 0.37521 7.83522 --1.02125 0.463638 7.73509 --1.16806 0.592685 8.79506 --1.05289 0.690911 8.69182 --1.1078 0.841443 9.45846 --1.15944 1.01884 10.3129 --0.689844 0.945695 8.1702 --0.606612 1.0405 8.18459 --0.402422 1.03767 7.36096 --0.306053 1.09992 7.2037 --0.240732 1.19014 7.27083 --0.180804 1.29442 7.41456 --0.0416404 1.26527 6.75115 --0.902874 -1.62889 -0.733747 --0.954619 -1.6788 -0.722113 --1.01132 -1.7346 -0.714351 --1.07346 -1.79812 -0.709774 --1.14182 -1.86806 -0.708117 --1.20554 -1.93117 -0.698405 --1.26944 -1.99374 -0.68626 --1.35099 -2.07758 -0.68635 --1.42185 -2.14768 -0.673228 --1.49924 -2.22493 -0.661855 --1.58296 -2.30824 -0.651846 --1.68476 -2.41322 -0.651343 --1.7827 -2.51005 -0.642423 --1.8981 -2.62934 -0.641039 --1.97453 -2.69902 -0.607252 --2.06252 -2.78152 -0.578113 --2.1754 -2.89362 -0.559352 --2.30122 -3.01871 -0.542633 --2.42866 -3.1433 -0.52039 --2.56317 -3.27505 -0.495515 --2.71768 -3.42866 -0.473259 --2.87915 -3.58813 -0.447012 --3.05554 -3.76233 -0.418445 --3.25218 -3.95762 -0.38909 --3.45718 -4.15891 -0.353042 --3.68261 -4.38078 -0.31397 --3.94305 -4.63897 -0.27393 --4.23821 -4.93099 -0.230789 --4.57554 -5.26628 -0.183174 --4.92856 -5.61391 -0.122633 --5.29738 -5.97361 -0.0479037 --5.70979 -6.37493 0.0375029 --6.23922 -6.89673 0.126805 --6.81884 -7.46601 0.236249 --7.51302 -8.14608 0.363723 --8.14664 -8.75574 0.528117 --8.27118 -8.82601 0.739773 --8.4623 -8.96614 0.955566 --8.99394 -9.45215 1.18433 --10.1629 -10.5822 1.46326 --10.7175 -11.074 1.75824 --10.8281 -11.1122 2.03956 --10.8583 -11.0695 2.31618 --10.8707 -11.0084 2.59062 --10.8655 -10.9303 2.86199 --10.7354 -10.7304 3.10963 --10.9573 -10.8751 3.42375 --11.0201 -10.862 3.71081 --11.0426 -10.811 3.99096 --11.0553 -10.7491 4.26909 --11.0651 -10.6838 4.54687 --11.0779 -10.6216 4.82656 --11.08 -10.5499 5.10378 --11.092 -10.4874 5.38573 --11.109 -10.4273 5.67032 --11.1072 -10.351 5.94935 --11.1225 -10.2906 6.2373 --11.1345 -10.2248 6.52537 --11.1429 -10.1565 6.81399 --11.1473 -10.084 7.10277 --11.1695 -10.0247 7.40258 --11.111 -9.8954 7.6602 --10.9865 -9.70966 7.87853 --11.2777 -9.88225 8.35036 --11.2893 -9.81211 8.65949 --11.2286 -9.67883 8.92367 --11.3878 -9.72947 9.34057 --11.3922 -9.64986 9.65838 --11.4132 -9.58081 9.99153 --11.4214 -9.502 10.3213 --11.4263 -9.41753 10.6518 --11.445 -9.34392 10.9995 --11.4525 -9.25923 11.3432 --11.4608 -9.17397 11.6938 --11.4837 -9.098 12.063 --11.4815 -9.00114 12.4162 --11.4549 -8.88347 12.7519 --11.4726 -8.79805 13.1375 --11.4722 -8.69729 13.5124 --11.2284 -8.41413 13.6337 --11.6092 -8.59009 14.4382 --11.5891 -8.4667 14.8191 --11.4451 -8.25329 15.0624 --4.60904 -3.21536 7.58854 --4.5579 -3.12848 7.71386 --4.40589 -2.97498 7.70326 --4.33053 -2.873 7.79356 --4.60222 -2.99462 8.38237 --4.54026 -2.89709 8.50609 --4.4758 -2.79838 8.62839 --3.34256 -2.04808 7.07379 --4.36686 -2.61079 8.90806 --2.36304 -1.37748 5.80757 --2.3398 -1.32594 5.91156 --2.29622 -1.26231 5.98163 --2.23689 -1.18923 6.02485 --2.21291 -1.13553 6.13508 --2.17908 -1.07533 6.22762 --2.11685 -1.0006 6.26708 --2.1648 -0.978635 6.53361 --3.81888 -1.69149 10.2307 --3.80891 -1.60529 10.5113 --3.53435 -1.40461 10.2058 --3.27501 -1.21604 9.90981 --1.73797 -0.552267 6.48484 --1.68586 -0.481506 6.5488 --1.73295 -0.442918 6.87116 --1.69631 -0.373729 6.99014 --1.32316 -0.208609 6.16984 --1.57312 -0.215975 7.10245 --1.54898 -0.145202 7.27493 --1.62854 -0.0891762 7.78952 --1.81259 -0.0367555 8.68886 --1.75534 0.0612783 8.83473 --1.45711 0.176773 8.12141 --1.3212 0.270823 7.9519 --1.23407 0.361993 7.95342 --1.0977 0.447546 7.74855 --1.03593 0.537908 7.8527 --1.11602 0.66409 8.62893 --1.11267 0.789989 9.08293 --1.08275 0.921215 9.45753 --0.436323 0.759962 6.37661 --0.656438 1.00359 8.12949 --0.358372 0.937507 6.73806 --0.299379 1.0204 6.81809 --0.265477 1.13409 7.11287 --0.227912 1.26195 7.44491 --0.0936171 1.2545 6.90061 --0.868982 -1.50742 -0.756188 --0.921022 -1.55584 -0.747794 --0.982789 -1.61654 -0.749478 --1.03054 -1.65873 -0.731275 --1.09505 -1.71992 -0.728428 --1.15875 -1.7808 -0.723125 --1.22482 -1.84165 -0.715434 --1.29541 -1.91026 -0.71003 --1.37324 -1.98494 -0.707082 --1.44644 -2.05277 -0.695982 --1.52592 -2.12685 -0.687022 --1.60587 -2.20115 -0.674656 --1.70973 -2.30304 -0.676956 --1.79775 -2.38422 -0.661787 --1.91002 -2.49362 -0.659629 --2.02458 -2.60151 -0.652945 --2.09648 -2.66178 -0.613956 --2.21854 -2.77723 -0.602011 --2.33578 -2.88472 -0.58143 --2.45906 -2.99979 -0.558973 --2.59109 -3.12072 -0.534712 --2.74285 -3.26269 -0.513851 --2.90274 -3.41134 -0.489312 --3.08253 -3.5805 -0.465838 --3.27155 -3.75573 -0.437055 --3.4679 -3.93735 -0.402235 --3.69956 -4.1538 -0.369785 --3.96668 -4.40455 -0.337371 --4.07938 -4.49069 -0.248913 --4.00804 -4.38377 -0.109244 --3.78928 -4.12675 0.0587979 --3.75884 -4.06796 0.175965 --3.74845 -4.02862 0.286883 --3.75724 -4.00865 0.392937 --3.74284 -3.96661 0.501384 --3.7423 -3.93755 0.606696 --3.75253 -3.92092 0.710108 --3.74165 -3.88305 0.814507 --8.7035 -8.70838 0.775051 --8.79189 -8.73635 0.995676 --3.87128 -3.9268 1.12258 --3.88301 -3.91171 1.22695 --10.8862 -10.5576 1.79649 --10.8879 -10.4891 2.06417 --10.8801 -10.4118 2.32976 --10.8895 -10.3509 2.59655 --10.8666 -10.2594 2.85767 --10.9496 -10.2671 3.13693 --11.0727 -10.3097 3.42767 --11.0904 -10.2552 3.69969 --11.0897 -10.185 3.9682 --11.1084 -10.13 4.24147 --11.1078 -10.0596 4.51066 --11.1257 -10.0044 4.78599 --11.133 -9.93963 5.05914 --11.1511 -9.88375 5.3373 --11.1517 -9.8123 5.61016 --11.1691 -9.75589 5.89175 --11.1838 -9.69589 6.17376 --11.1655 -9.60683 6.4426 --11.194 -9.55699 6.73502 --11.197 -9.48605 7.01779 --11.2098 -9.42264 7.30821 --11.1272 -9.27893 7.54751 --11.0478 -9.13952 7.78765 --11.3379 -9.29838 8.2509 --11.3339 -9.21724 8.54556 --11.2843 -9.09945 8.81303 --11.4244 -9.13036 9.21107 --11.4422 -9.06243 9.53258 --11.455 -8.99015 9.85563 --11.4627 -8.91264 10.1796 --11.4791 -8.84001 10.5153 --11.4836 -8.75749 10.847 --11.5037 -8.68425 11.1965 --11.4978 -8.59123 11.5304 --11.5194 -8.51666 11.8945 --11.5217 -8.42589 12.2484 --11.4942 -8.31163 12.5789 --11.5177 -8.23285 12.9661 --11.5219 -8.138 13.3425 --11.2969 -7.88163 13.4844 --11.1432 -7.67767 13.6989 --4.53826 -3.11147 6.6842 --4.68264 -3.16336 7.0216 --4.68485 -3.11776 7.20335 --4.12722 -2.7077 6.70525 --4.49466 -2.8978 7.3359 --4.64263 -2.94212 7.71561 --3.98061 -2.47947 7.02829 --3.87114 -2.36658 7.05484 --3.79895 -2.27706 7.1319 --4.79426 -2.81313 8.76444 --3.50469 -2.01125 7.0576 --4.17992 -2.34354 8.28169 --2.43058 -1.32172 5.71193 --2.39751 -1.26757 5.79971 --2.33455 -1.19566 5.83658 --2.30314 -1.14087 5.93056 --3.12617 -1.51087 7.56136 --3.12588 -1.45637 7.7637 --2.16896 -0.953483 6.14822 --2.80571 -1.19808 7.56753 --2.63026 -1.06572 7.42222 --2.61388 -1.00337 7.60054 --2.54505 -0.918507 7.67141 --3.51496 -1.22536 10.0798 --1.83742 -0.54262 6.48851 --1.69624 -0.443807 6.34319 --1.85486 -0.442222 6.9315 --1.68037 -0.334965 6.69949 --1.43279 -0.212625 6.24749 --1.56767 -0.190699 6.83051 --1.76314 -0.168848 7.63467 --1.68981 -0.0838768 7.68611 --1.94571 -0.0440191 8.78358 --1.84222 0.0573213 8.78783 --1.72834 0.159132 8.75101 --1.50297 0.260212 8.30678 --1.37237 0.352057 8.17602 --1.19275 0.436216 7.82862 --1.14246 0.527168 7.99284 --1.18442 0.64237 8.58433 --1.09082 0.737964 8.59973 --1.1366 0.884429 9.32727 --1.07602 1.0079 9.57444 --0.413291 0.805694 6.35608 --0.66175 1.08619 8.34408 --0.341406 0.990409 6.79552 --0.288089 1.08157 6.94409 --0.240193 1.18688 7.16964 --0.176585 1.28424 7.30462 --0.0301259 1.24431 6.61315 --0.834095 -1.3958 -0.779312 --0.88166 -1.43629 -0.767853 --0.935329 -1.48354 -0.760871 --0.993692 -1.53579 -0.758249 --1.05748 -1.5958 -0.759007 --1.11279 -1.64247 -0.746111 --1.17887 -1.70102 -0.742539 --1.23954 -1.75398 -0.730885 --1.31248 -1.82032 -0.727502 --1.39144 -1.89202 -0.726749 --1.46623 -1.9588 -0.717547 --1.54804 -2.03064 -0.710707 --1.62936 -2.10292 -0.700339 --1.71821 -2.18204 -0.691451 --1.83174 -2.28744 -0.696868 --1.92235 -2.36561 -0.680413 --2.03305 -2.46475 -0.672539 --2.15022 -2.56959 -0.664375 --2.24338 -2.64774 -0.635677 --2.35649 -2.74564 -0.61459 --2.4899 -2.86388 -0.599264 --2.61232 -2.96761 -0.571799 --2.7668 -3.10555 -0.555032 --2.93038 -3.24998 -0.534805 --3.1019 -3.4 -0.510513 --3.29552 -3.57095 -0.486844 --3.48975 -3.74005 -0.455002 --3.72646 -3.95025 -0.428863 --3.89692 -4.09029 -0.370361 --3.90038 -4.06453 -0.255351 --3.89484 -4.03032 -0.139523 --3.94469 -4.04963 -0.0388615 --4.38362 -4.44587 -0.0214382 --5.72398 -5.70647 -0.156465 --4.01469 -4.03062 0.283331 --3.87154 -3.86558 0.414091 --3.84954 -3.81695 0.522852 --3.83919 -3.78081 0.628424 --3.86457 -3.77762 0.730041 --3.85908 -3.74596 0.833491 --3.84448 -3.70623 0.936104 --3.96946 -3.79402 1.03738 --3.98213 -3.77878 1.14134 --11.0346 -10.1172 1.56899 --11.0896 -10.0983 1.83743 --11.141 -10.0759 2.10691 --11.1674 -10.0306 2.37491 --11.1756 -9.96923 2.64085 --10.9845 -9.73477 2.87483 --11.2617 -9.90757 3.18492 --11.3636 -9.9269 3.47156 --11.3866 -9.87719 3.74458 --11.4138 -9.83125 4.01978 --11.4224 -9.76861 4.29126 --11.4274 -9.70373 4.56271 --11.4507 -9.65294 4.84049 --11.4559 -9.5876 5.11398 --11.4863 -9.54218 5.3979 --11.4836 -9.46932 5.67141 --11.5075 -9.41689 5.95649 --11.5119 -9.3494 6.23613 --11.5349 -9.2952 6.52571 --11.5463 -9.23178 6.81284 --11.5321 -9.14747 7.08935 --11.5573 -9.09294 7.38815 --11.3238 -8.839 7.54874 --11.703 -9.05576 8.05204 --11.7075 -8.98188 8.35222 --11.6152 -8.83458 8.59503 --11.8809 -8.95614 9.06966 --11.8923 -8.88389 9.38923 --11.8998 -8.80715 9.70983 --11.9152 -8.73661 10.0417 --11.9332 -8.66516 10.3799 --11.9451 -8.58857 10.7197 --11.959 -8.51216 11.0665 --11.9744 -8.43397 11.4201 --12.0035 -8.3652 11.7929 --12.0274 -8.28992 12.1679 --11.9455 -8.1415 12.4544 --11.9635 -8.05867 12.8374 --11.9883 -7.97946 13.2353 --11.7504 -7.72514 13.3777 --11.5174 -7.47522 13.5184 --4.64789 -2.99209 6.55112 --4.61935 -2.9309 6.68775 --4.60084 -2.87499 6.83757 --4.37418 -2.69036 6.74707 --4.32845 -2.6186 6.86399 --4.27543 -2.54199 6.97245 --4.22571 -2.46746 7.08719 --4.00967 -2.2968 6.98251 --3.93608 -2.20944 7.06098 --3.90066 -2.1438 7.19177 --3.79747 -2.04004 7.22762 --4.07437 -2.13872 7.82453 --4.01698 -2.05611 7.94182 --2.53957 -1.25098 5.8265 --2.44299 -1.16562 5.81637 --2.42143 -1.1173 5.92815 --2.40311 -1.06963 6.04816 --2.30562 -0.983711 6.0317 --2.26484 -0.92492 6.11561 --2.85475 -1.13435 7.3956 --2.6353 -0.990972 7.17358 --2.69661 -0.962547 7.50087 --2.64001 -0.884694 7.59934 --2.54325 -0.792771 7.61601 --1.92083 -0.523724 6.45459 --1.79592 -0.43406 6.3572 --1.71912 -0.361848 6.36645 --1.85001 -0.345794 6.89046 --1.45378 -0.190471 6.09105 --1.64923 -0.18276 6.81185 --1.41573 -0.0774092 6.39286 --1.48871 -0.0323925 6.82675 --1.72357 0.000609592 7.78457 --1.90658 0.0600779 8.66338 --1.74325 0.160296 8.4753 --1.63006 0.253576 8.43707 --1.56046 0.346982 8.55005 --1.30304 0.428867 7.95528 --1.18845 0.510771 7.86895 --1.28815 0.631016 8.68433 --1.16665 0.71893 8.59468 --1.07265 0.813164 8.62933 --1.10621 0.959977 9.31741 --1.19846 1.16235 10.4262 --0.390892 0.850456 6.35545 --0.378876 0.958264 6.73256 --0.307096 1.02918 6.75489 --0.252012 1.11876 6.90302 --0.226853 1.25756 7.35408 --0.0799756 1.23103 6.7328 --0.902708 -1.37717 -0.791716 --0.952283 -1.417 -0.779527 --1.00653 -1.46189 -0.77199 --1.06691 -1.51347 -0.768539 --1.12842 -1.56435 -0.76307 --1.19514 -1.62199 -0.760983 --1.26301 -1.67887 -0.756584 --1.33226 -1.73594 -0.749677 --1.40193 -1.79341 -0.74014 --1.48391 -1.86412 -0.738193 --1.56612 -1.93414 -0.733231 --1.64976 -2.00422 -0.725176 --1.74069 -2.08018 -0.718702 --1.84409 -2.16891 -0.717775 --1.94312 -2.25168 -0.708207 --2.04976 -2.34103 -0.698952 --2.18221 -2.45598 -0.702079 --2.27768 -2.53195 -0.675792 --2.38056 -2.6135 -0.649724 --2.50342 -2.71466 -0.630683 --2.62786 -2.81544 -0.606605 --2.78699 -2.94895 -0.59427 --2.94041 -3.07449 -0.572206 --3.11461 -3.22062 -0.552592 --3.30518 -3.37917 -0.531391 --3.49753 -3.5367 -0.50233 --3.71932 -3.72094 -0.475083 --3.97022 -3.92953 -0.448003 --4.18763 -4.1051 -0.399055 --4.21238 -4.09776 -0.286815 --4.20737 -4.0636 -0.166801 --4.57838 -4.37401 -0.135744 --5.71831 -5.38289 -0.246494 --6.17078 -5.75577 -0.178205 --6.67756 -6.17166 -0.0984902 --7.2616 -6.65001 -0.00683081 --7.94457 -7.21204 0.100166 --8.25727 -7.4378 0.269602 --8.56877 -7.6601 0.452021 --9.33991 -8.27847 0.627974 --10.5968 -9.30938 0.828636 --11.6387 -10.1405 1.08397 --11.6622 -10.0925 1.35836 --11.9042 -10.2279 1.64269 --11.883 -10.1403 1.91825 --11.9116 -10.0944 2.19645 --11.9142 -10.0261 2.47182 --11.8889 -9.93622 2.74307 --11.9834 -9.94436 3.03174 --12.1576 -10.0172 3.33885 --12.1673 -9.95443 3.61978 --12.1809 -9.8946 3.9021 --12.183 -9.82548 4.18227 --12.2123 -9.77746 4.47 --12.222 -9.71303 4.75384 --12.2428 -9.65851 5.04259 --12.2518 -9.59373 5.32908 --12.2569 -9.52567 5.61563 --12.2582 -9.45437 5.90214 --12.2938 -9.40823 6.20371 --12.2942 -9.33538 6.49374 --12.3132 -9.27577 6.79391 --12.2911 -9.18466 7.07718 --12.3093 -9.12328 7.38184 --12.0622 -8.86755 7.55219 --12.488 -9.10063 8.0781 --12.4993 -9.03051 8.39262 --12.3738 -8.8621 8.62995 --12.7126 -9.02243 9.14962 --12.7226 -8.94728 9.47974 --12.7425 -8.87797 9.82062 --12.7494 -8.7989 10.1581 --12.7515 -8.71553 10.4968 --12.7837 -8.65064 10.8625 --12.782 -8.56037 11.2085 --12.8089 -8.4896 11.5835 --12.8168 -8.4034 11.9492 --12.7967 -8.29799 12.299 --12.6569 -8.11387 12.5482 --12.741 -8.07194 12.9996 --12.6643 -7.92715 13.313 --12.3586 -7.6393 13.4094 --13.0628 -7.96954 14.4972 --4.88376 -2.94443 6.54971 --4.79025 -2.84554 6.62141 --4.7459 -2.77627 6.74495 --4.75646 -2.73837 6.93029 --4.7378 -2.68187 7.08821 --4.58361 -2.54988 7.08798 --4.54936 -2.48402 7.22861 --4.2004 -2.2489 6.97537 --4.21839 -2.2121 7.17695 --4.14567 -2.12769 7.26547 --4.13933 -2.07729 7.44513 --3.91989 -1.91771 7.32656 --3.85545 -1.83787 7.42372 --3.92293 -1.8215 7.721 --2.4957 -1.10322 5.7046 --2.45962 -1.05002 5.79139 --3.30478 -1.3858 7.33777 --3.1485 -1.26834 7.27005 --3.12503 -1.20884 7.42786 --2.8815 -1.05904 7.18963 --2.75465 -0.959488 7.15234 --2.84539 -0.941312 7.53187 --2.73401 -0.847096 7.52639 --2.67469 -0.770972 7.62483 --3.83593 -1.08135 10.345 --1.94183 -0.433527 6.46915 --1.81814 -0.349091 6.38055 --1.75445 -0.282885 6.42626 --1.55187 -0.183582 6.12865 --1.4689 -0.115886 6.11338 --1.66593 -0.100483 6.84404 --1.96946 -0.0872373 7.92855 --2.64732 -0.0978777 10.1937 --1.9878 0.0650305 8.59526 --2.32346 0.133127 10.0021 --1.71701 0.251965 8.41153 --1.56866 0.340799 8.25707 --1.32191 0.417932 7.72291 --1.25377 0.501378 7.82159 --1.26974 0.601076 8.26804 --1.23509 0.701275 8.54937 --1.14615 0.79477 8.61495 --1.09029 0.901059 8.84458 --1.28083 1.1318 10.4035 --0.44058 0.834018 6.36882 --0.426668 0.935467 6.72768 --0.355167 1.00661 6.76093 --0.272017 1.06667 6.71409 --0.224515 1.16696 6.95041 --0.181259 1.28829 7.28311 --0.0275112 1.2376 6.56367 --0.960613 -1.34482 -0.791104 --1.02128 -1.39492 -0.79099 --1.07827 -1.43799 -0.78304 --1.14044 -1.48793 -0.778861 --1.20276 -1.5374 -0.77264 --1.27201 -1.59221 -0.770045 --1.34287 -1.64818 -0.764841 --1.41295 -1.70382 -0.757085 --1.49679 -1.77038 -0.757652 --1.57453 -1.83245 -0.749528 --1.6605 -1.90031 -0.743689 --1.75255 -1.97333 -0.739605 --1.85824 -2.05993 -0.741284 --1.95226 -2.13304 -0.729824 --2.06708 -2.22605 -0.727751 --2.16309 -2.29918 -0.708623 --2.28684 -2.39749 -0.702217 --2.41118 -2.4957 -0.690944 --2.52995 -2.58717 -0.670912 --2.65741 -2.68469 -0.649952 --2.79142 -2.78763 -0.627436 --2.95495 -2.91641 -0.612795 --3.12017 -3.04448 -0.591656 --3.31414 -3.19799 -0.575548 --3.50989 -3.35048 -0.55158 --3.72114 -3.51535 -0.524737 --3.9636 -3.70532 -0.499174 --4.22898 -3.91316 -0.470565 --4.37994 -4.01692 -0.396292 --4.4048 -4.00923 -0.282496 --4.62889 -4.17361 -0.217969 --4.78641 -4.28006 -0.128982 --6.15194 -5.42155 -0.272124 --6.63131 -5.79199 -0.198887 --7.19044 -6.2238 -0.1166 --7.82019 -6.7096 -0.0192593 --8.36873 -7.12086 0.113963 --8.42715 -7.12026 0.310531 --9.12266 -7.64407 0.470351 --10.0903 -8.38323 0.649902 --11.5729 -9.53101 0.863538 --12.4617 -10.183 1.1369 --12.5162 -10.1564 1.42326 --12.7236 -10.2508 1.71848 --12.7481 -10.1983 2.00824 --12.7521 -10.1292 2.29598 --12.7602 -10.0644 2.58386 --12.5913 -9.86246 2.84707 --13.3057 -10.343 3.24374 --13.3567 -10.3077 3.55051 --13.2852 -10.1793 3.83469 --13.6891 -10.4097 4.22236 --13.704 -10.3449 4.53215 --13.7061 -10.27 4.8398 --13.7354 -10.2151 5.15588 --13.7443 -10.145 5.468 --13.7648 -10.0825 5.7852 --13.7803 -10.016 6.10287 --13.7921 -9.94601 6.42108 --13.5736 -9.71204 6.64991 --13.3911 -9.50551 6.88597 --13.412 -9.4433 7.20648 --13.3071 -9.29156 7.47071 --12.8691 -8.91281 7.57055 --13.4946 -9.26366 8.197 --13.4599 -9.15968 8.50163 --13.9168 -9.38523 9.08254 --13.922 -9.30436 9.42571 --13.9435 -9.2333 9.78313 --13.9532 -9.15219 10.1374 --13.9715 -9.07612 10.5026 --13.9839 -8.99589 10.8695 --13.9761 -8.89945 11.2273 --14.0417 -8.84936 11.6438 --13.7356 -8.5652 11.7887 --13.6052 -8.39179 12.0612 --13.576 -8.28046 12.4149 --13.5282 -8.15621 12.7571 --13.5705 -8.08489 13.1822 --13.3116 -7.83397 13.3485 --13.0301 -7.57121 13.4874 --13.8659 -7.95247 14.6788 --4.95824 -2.75692 6.55403 --4.84854 -2.65342 6.6116 --4.83431 -2.60333 6.76879 --4.8242 -2.55389 6.93312 --4.90945 -2.55387 7.21139 --5.00131 -2.55468 7.50816 --4.56683 -2.28413 7.17836 --4.22442 -2.06687 6.9376 --4.16509 -1.99303 7.04026 --4.0339 -1.88489 7.04957 --3.96022 -1.80401 7.13238 --4.25998 -1.89659 7.74153 --3.95806 -1.70872 7.5083 --4.10432 -1.72321 7.92746 --4.10915 -1.67196 8.14854 --3.22403 -1.24975 6.96532 --3.27278 -1.22246 7.23121 --3.1748 -1.13503 7.26316 --2.91466 -0.988027 7.01098 --2.83449 -0.910347 7.06077 --3.00991 -0.921672 7.58702 --2.85316 -0.814574 7.50534 --2.78796 -0.739314 7.5965 --2.77308 -0.678029 7.79325 --3.80564 -0.907037 10.2386 --3.83404 -0.83172 10.6337 --1.85559 -0.269752 6.44979 --1.77764 -0.201229 6.46797 --1.73999 -0.141909 6.58618 --1.70063 -0.0800374 6.70352 --2.00631 -0.0666248 7.75587 --2.06932 -0.00400488 8.21562 --2.60159 0.0283271 10.0765 --1.90405 0.16721 8.36205 --1.80397 0.25431 8.38478 --1.7082 0.340752 8.42451 --1.46677 0.419418 7.95221 --1.35391 0.498083 7.89885 --1.35559 0.592919 8.28826 --1.22715 0.670504 8.18245 --1.21462 0.777225 8.57013 --1.11909 0.866025 8.61588 --1.17656 1.02309 9.43123 --1.13446 1.15653 9.83615 --0.42342 0.882995 6.41773 --0.402981 0.983881 6.75633 --0.323227 1.04696 6.75039 --0.247896 1.11572 6.7818 --0.222674 1.25144 7.24343 --0.0805212 1.22907 6.69229 --1.03486 -1.32712 -0.809678 --1.08124 -1.35783 -0.790265 --1.15489 -1.41626 -0.800234 --1.21982 -1.46431 -0.795351 --1.27815 -1.50605 -0.78256 --1.35016 -1.559 -0.779357 --1.42161 -1.61257 -0.773404 --1.50027 -1.6723 -0.770297 --1.58011 -1.73118 -0.764489 --1.66719 -1.79611 -0.761041 --1.76058 -1.86717 -0.759247 --2.18554 -2.18726 -0.743077 --2.29125 -2.26384 -0.726871 --2.4385 -2.37642 -0.731224 --2.53916 -2.44634 -0.702171 --2.6615 -2.53453 -0.680778 --2.80564 -2.64066 -0.665491 --2.95832 -2.75162 -0.648208 --3.11908 -2.86943 -0.628026 --3.31645 -3.0179 -0.617011 --3.49379 -3.14582 -0.589407 --3.71754 -3.31153 -0.571425 --3.9494 -3.48229 -0.546946 --4.20509 -3.67089 -0.520419 --4.47723 -3.87 -0.488221 --4.73712 -4.0563 -0.440426 --4.74129 -4.02838 -0.315882 --4.76507 -4.01791 -0.197495 --5.00972 -4.1873 -0.125967 --5.0249 -4.16716 -0.00141171 --5.03693 -4.14676 0.123114 --5.01673 -4.09993 0.25147 --5.03336 -4.08314 0.373383 --5.0412 -4.05891 0.496019 --5.04636 -4.03237 0.617819 --5.04195 -3.99975 0.739882 --5.05105 -3.97776 0.86036 --5.04366 -3.94204 0.98061 --5.06515 -3.92974 1.1004 --5.07013 -3.90375 1.21977 --5.07269 -3.87633 1.33879 --5.06535 -3.84211 1.4568 --5.05677 -3.80729 1.57416 --5.07058 -3.7886 1.69339 --5.07427 -3.76214 1.81151 --5.14862 -3.78723 1.94115 --14.2898 -10.3149 3.71318 --14.2546 -10.2131 4.01794 --14.3667 -10.2174 4.3548 --14.3785 -10.1487 4.67194 --14.3854 -10.076 4.98888 --14.4041 -10.012 5.3104 --14.4099 -9.93808 5.62969 --14.4273 -9.87172 5.95414 --14.4391 -9.80241 6.27939 --14.4389 -9.723 6.6017 --14.3155 -9.56091 6.8771 --14.3453 -9.50166 7.21335 --14.1885 -9.31983 7.47177 --14.2639 -9.28946 7.83222 --14.3962 -9.29277 8.22563 --14.3354 -9.17299 8.5312 --14.5942 -9.25424 9.00577 --14.6079 -9.17737 9.36011 --14.6225 -9.10119 9.72018 --14.6319 -9.01974 10.0814 --14.6429 -8.93773 10.4484 --14.6558 -8.85605 10.8218 --14.6695 -8.7739 11.2017 --14.5963 -8.63846 11.5266 --14.5024 -8.49072 11.8395 --14.5133 -8.40363 12.2312 --14.344 -8.21096 12.4909 --14.4423 -8.17081 12.9623 --14.3415 -8.01613 13.2814 --14.0106 -7.73375 13.4067 --14.8114 -8.07212 14.5173 --14.6119 -7.85726 14.7732 --5.11242 -2.61073 6.64397 --5.13534 -2.49011 7.20832 --5.08465 -2.41932 7.34166 --5.01317 -2.33739 7.45224 --4.46769 -2.03359 6.99481 --4.2118 -1.87131 6.86189 --4.28853 -1.86244 7.13726 --4.04126 -1.70812 7.00128 --4.24807 -1.75204 7.46461 --4.07107 -1.62852 7.41537 --3.98977 -1.54668 7.49668 --3.78663 -1.41673 7.39818 --3.43235 -1.2308 7.05602 --3.2131 -1.10186 6.90097 --3.25029 -1.0695 7.14941 --2.97436 -0.923934 6.88382 --4.54799 -1.40769 9.80543 --3.70169 -1.06358 8.57929 --2.88432 -0.749201 7.31711 --2.77854 -0.665725 7.32916 --2.77112 -0.610455 7.5336 --2.57209 -0.502539 7.35435 --2.60745 -0.455446 7.65571 --1.92276 -0.243512 6.38962 --1.82704 -0.175098 6.37277 --1.8211 -0.124091 6.56501 --1.72821 -0.0558966 6.55385 --1.71578 0.000695661 6.74531 --2.02978 0.0253021 7.82649 --2.21368 0.0829203 8.63452 --2.00408 0.175907 8.36045 --1.91589 0.260467 8.43272 --1.76449 0.34413 8.30258 --1.5745 0.421316 8.02516 --1.44308 0.497434 7.92597 --1.31406 0.570403 7.82392 --1.31353 0.665628 8.21279 --1.2124 0.745631 8.22281 --1.20411 0.855168 8.64942 --1.12521 0.951413 8.79226 --1.16638 1.109 9.56883 --0.793042 1.0547 8.18229 --0.42227 0.943567 6.57436 --0.3766 1.03063 6.78526 --0.292172 1.09043 6.7691 --0.242226 1.1892 7.01622 --0.183049 1.28966 7.24196 --0.0325928 1.24484 6.59249 --1.22172 -1.38074 -0.805115 --1.2759 -1.41524 -0.787895 --2.19635 -2.0707 -0.771646 --2.29726 -2.13864 -0.753644 --2.41242 -2.21773 -0.740557 --2.57016 -2.33241 -0.747274 --2.68031 -2.40472 -0.720853 --2.80603 -2.48858 -0.697812 --2.9607 -2.59665 -0.684208 --3.12492 -2.70924 -0.66834 --3.30419 -2.83388 -0.652519 --3.49237 -2.9639 -0.632753 --3.69669 -3.10537 -0.611501 --3.92543 -3.26395 -0.590464 --4.17771 -3.43956 -0.568158 --4.44834 -3.62535 -0.54091 --4.77317 -3.85332 -0.518249 --5.05441 -4.04268 -0.470221 --5.05085 -4.00912 -0.339594 --5.05186 -3.97929 -0.212164 --5.0516 -3.9489 -0.085588 --5.05715 -3.92285 0.0384519 --5.06855 -3.90101 0.16054 --5.07041 -3.87297 0.283377 --5.06982 -3.84362 0.40538 --5.0751 -3.81838 0.525821 --5.08748 -3.79794 0.645067 --5.08172 -3.76503 0.76501 --5.08948 -3.74273 0.883563 --5.10441 -3.72502 1.0018 --5.09346 -3.68859 1.11958 --5.08868 -3.65708 1.23668 --5.09851 -3.6356 1.35383 --5.09751 -3.60746 1.47048 --5.10372 -3.58379 1.5873 --5.10873 -3.55939 1.70405 --5.10261 -3.52754 1.81932 --5.10375 -3.50005 1.93535 --15.2324 -10.2787 3.88087 --16.0217 -10.7267 4.36523 --16.1488 -10.7287 4.73571 --16.1562 -10.6506 5.08295 --16.2403 -10.6227 5.45162 --15.8707 -10.2991 5.69532 --16.2621 -10.4687 6.15786 --16.2814 -10.3959 6.5164 --15.5325 -9.83785 6.61072 --15.3405 -9.63509 6.8804 --15.3549 -9.56232 7.2243 --15.1549 -9.35749 7.48311 --15.3823 -9.41519 7.9213 --15.405 -9.34502 8.27812 --15.2623 -9.1757 8.56073 --16.4025 -9.77002 9.48073 --16.4666 -9.62432 10.279 --16.4702 -9.53281 10.6703 --16.4821 -9.44456 11.0715 --16.2418 -9.11678 11.723 --15.7661 -8.75469 11.813 --15.5088 -8.51697 12.0353 --15.4797 -8.40581 12.4135 --15.4219 -8.27679 12.7754 --15.446 -8.19142 13.2038 --15.0921 -7.9046 13.3426 --14.8087 -7.65783 13.5284 --15.7266 -8.02833 14.7191 --5.14875 -2.18293 7.54849 --4.277 -1.75956 6.71472 --4.2952 -1.72545 6.91319 --4.45406 -1.74761 7.29552 --4.33189 -1.65194 7.3302 --4.1043 -1.51561 7.22077 --3.92099 -1.39823 7.1596 --3.62706 -1.24275 6.93289 --3.43454 -1.12803 6.83447 --3.33587 -1.04949 6.86993 --3.21688 -0.964492 6.86967 --3.00933 -0.850807 6.72336 --2.97369 -0.795394 6.85072 --2.19776 -0.515444 5.70239 --2.11099 -0.453526 5.70433 --2.86445 -0.619661 7.25603 --2.25105 -0.410985 6.29948 --2.65565 -0.462716 7.28434 --2.76232 -0.433464 7.72864 --2.10689 -0.240026 6.58162 --1.928 -0.156925 6.39547 --1.90673 -0.1035 6.55182 --1.88517 -0.0482469 6.71733 --1.82918 0.0135909 6.80878 --1.78494 0.0753516 6.93648 --2.10139 0.114177 8.0377 --1.62092 0.208824 7.00079 --1.43798 0.275882 6.73706 --1.79102 0.349633 8.09471 --1.69509 0.427681 8.13469 --1.55372 0.502083 8.01885 --1.43955 0.575393 7.98685 --1.41496 0.665794 8.28999 --1.33154 0.748779 8.3895 --1.20042 0.82021 8.29269 --0.84659 0.803652 7.17124 --1.22967 1.08344 9.47635 --1.17816 1.21077 9.85292 --0.48546 0.93628 6.64612 --0.398298 0.989898 6.61358 --0.325422 1.05549 6.6673 --0.258905 1.12931 6.77842 --0.187483 1.20475 6.87792 --0.0897153 1.24333 6.75006 --2.18941 -1.94271 -0.789757 --2.30633 -2.01961 -0.783462 --2.42946 -2.10131 -0.777268 --2.56198 -2.18801 -0.770951 --2.70318 -2.28075 -0.763609 --2.81595 -2.34998 -0.73561 --2.97338 -2.45392 -0.725613 --3.13222 -2.55631 -0.7099 --3.29987 -2.6644 -0.691605 --3.49867 -2.79551 -0.679681 --3.69899 -2.92472 -0.660387 --3.91671 -3.06598 -0.638946 --4.1584 -3.22235 -0.617627 --4.42489 -3.39632 -0.594283 --4.73225 -3.59729 -0.572614 --5.08935 -3.83243 -0.552176 --5.19597 -3.87974 -0.45168 --5.19024 -3.84565 -0.321009 --5.19125 -3.8158 -0.193481 --5.1971 -3.79051 -0.0683682 --5.20147 -3.76366 0.0558869 --5.18799 -3.72506 0.182107 --5.20429 -3.7076 0.302558 --5.20347 -3.67725 0.424559 --5.20779 -3.6522 0.545217 --5.21922 -3.63193 0.664778 --5.22061 -3.60367 0.784208 --5.2284 -3.58127 0.90315 --5.23376 -3.55745 1.02174 --5.22928 -3.52672 1.13982 --5.23171 -3.49965 1.25728 --5.23196 -3.47213 1.3745 --5.23845 -3.44928 1.4921 --5.2447 -3.42551 1.60941 --5.23887 -3.39446 1.72556 --5.27465 -3.38982 1.84704 --16.3105 -10.3471 3.73232 --16.3301 -10.2791 4.07721 --16.3868 -10.2338 4.43044 --16.413 -10.1695 4.78001 --16.4093 -10.0855 5.12383 --16.4169 -10.0083 5.47146 --16.4271 -9.93218 5.82139 --16.4164 -9.84329 6.1666 --16.4332 -9.77068 6.52197 --16.4276 -9.68368 6.87216 --16.4662 -9.62296 7.24041 --16.1542 -9.358 7.47714 --16.5093 -9.4788 7.97526 --16.506 -9.39087 8.3373 --16.4083 -9.24848 8.65934 --16.5384 -9.23535 9.08908 --16.5662 -9.16175 9.47661 --16.5795 -9.07959 9.86195 --16.6021 -9.00148 10.2572 --16.6099 -8.91393 10.6497 --16.5636 -8.79685 11.0163 --16.5824 -8.71274 11.4247 --16.5942 -8.62365 11.8351 --16.5986 -8.5287 12.2471 --16.3748 -8.31617 12.5107 --16.57 -8.31668 13.0655 --16.2685 -8.06448 13.2737 --15.9191 -7.7921 13.4389 --16.9006 -8.16822 14.6329 --4.37007 -1.61675 6.78028 --4.55108 -1.59871 7.37051 --4.43665 -1.51046 7.42098 --4.00478 -1.30959 7.04597 --3.93505 -1.24007 7.14021 --4.54357 -1.39889 8.19605 --3.41505 -0.977633 6.77214 --3.49996 -0.960916 7.08573 --2.29913 -0.551197 5.40883 --3.29234 -0.806151 7.15279 --2.28038 -0.477126 5.67185 --2.29157 -0.443352 5.84667 --2.45359 -0.444884 6.29934 --2.33826 -0.374662 6.26905 --2.33956 -0.33136 6.45601 --1.93998 -0.203637 5.86199 --2.14427 -0.200079 6.45592 --2.01312 -0.130586 6.3802 --1.97931 -0.0773298 6.51018 --2.20207 -0.0557809 7.23466 --1.96393 0.0293276 6.91617 --1.79162 0.101497 6.73026 --1.65655 0.166839 6.62401 --2.09529 0.210281 8.05232 --1.54753 0.287831 6.82591 --1.42313 0.348748 6.73117 --1.79593 0.437011 8.16557 --1.34754 0.478711 7.06813 --1.6187 0.592165 8.31981 --1.39702 0.647124 7.92242 --1.14395 0.683362 7.35572 --1.25749 0.808333 8.20776 --1.23838 0.912486 8.59599 --1.29202 1.06065 9.37303 --1.19022 1.15587 9.48759 --1.07772 1.24828 9.56093 --0.443523 0.971595 6.58782 --0.368507 1.03281 6.63314 --0.313076 1.1154 6.82399 --0.252486 1.20263 7.02311 --0.144195 1.23398 6.84761 --0.0340665 1.24719 6.59195 --2.08926 -1.76658 -0.824132 --2.17158 -1.81278 -0.800711 --2.30966 -1.90166 -0.811583 --2.42111 -1.96926 -0.799479 --2.56254 -2.05844 -0.800564 --2.69769 -2.14198 -0.79228 --2.84917 -2.2358 -0.787208 --2.97245 -2.30706 -0.761281 --3.13403 -2.40536 -0.74937 --3.29653 -2.50425 -0.731227 --3.49038 -2.62324 -0.720848 --3.6862 -2.74233 -0.703094 --3.89891 -2.87165 -0.683976 --4.13675 -3.01695 -0.665489 --4.39986 -3.17786 -0.646075 --4.69654 -3.35987 -0.626658 --5.04314 -3.57323 -0.610255 --5.4159 -3.80278 -0.586693 --5.53358 -3.85211 -0.483792 --5.52719 -3.81732 -0.348914 --5.48741 -3.75917 -0.208497 --5.47695 -3.72187 -0.0769645 --5.47252 -3.68989 0.052132 --5.49958 -3.67765 0.175118 --5.49121 -3.64279 0.302522 --5.40561 -3.55843 0.436629 --5.42651 -3.54292 0.557383 --5.46293 -3.5374 0.677284 --5.49628 -3.53136 0.798323 --5.4873 -3.49667 0.920569 --5.49168 -3.47145 1.04201 --5.49483 -3.44556 1.16307 --5.49653 -3.41803 1.28367 --5.48759 -3.38489 1.40349 --5.51095 -3.3707 1.52508 --5.50681 -3.34059 1.64481 --5.50966 -3.31392 1.7649 --5.53579 -3.30178 1.8885 --17.6948 -10.4616 3.96301 --17.9747 -10.5418 4.37678 --17.9942 -10.467 4.74964 --18.008 -10.3893 5.1229 --18.0244 -10.3126 5.49836 --18.0272 -10.2272 5.8717 --18.0487 -10.1524 6.25214 --17.8707 -9.96463 6.57463 --17.6533 -9.7577 6.87959 --17.6758 -9.68286 7.25922 --17.2818 -9.38138 7.49133 --17.7432 -9.54461 8.03789 --17.722 -9.44408 8.41116 --18.1914 -9.60379 8.99549 --18.2215 -9.52677 9.40695 --18.2286 -9.43768 9.81287 --18.2532 -9.35526 10.2315 --18.2557 -9.26069 10.644 --18.2502 -9.16157 11.0576 --18.1982 -9.03743 11.4497 --17.917 -8.79946 11.7121 --17.6709 -8.58126 11.9891 --17.6341 -8.46404 12.3906 --17.6981 -8.39433 12.863 --17.538 -8.21719 13.194 --17.143 -7.92966 13.3601 --18.1282 -8.28088 14.5125 --17.8384 -8.03999 14.7688 --9.41774 -3.47874 11.6234 --9.01482 -3.25054 11.5127 --4.6845 -1.50838 7.30203 --4.61731 -1.43949 7.41555 --4.44536 -1.33581 7.39631 --4.02038 -1.15346 7.03525 --3.97326 -1.09394 7.16068 --6.1206 -1.69345 10.3891 --2.50683 -0.576391 5.42423 --2.42325 -0.519807 5.44225 --2.32965 -0.461183 5.44153 --2.33687 -0.429006 5.59819 --2.22087 -0.36476 5.56015 --2.41725 -0.373953 6.05136 --2.41482 -0.3332 6.22037 --2.92186 -0.392654 7.33441 --2.12378 -0.192649 6.03988 --2.04753 -0.137469 6.07278 --2.19454 -0.116382 6.56125 --2.09027 -0.0533323 6.54902 --2.53019 -0.053495 7.73526 --2.42598 0.0178966 7.76318 --1.87325 0.122552 6.71901 --1.82134 0.180706 6.82836 --1.65809 0.243398 6.65687 --1.99129 0.30322 7.81397 --1.54439 0.36212 6.85849 --1.5766 0.429784 7.23748 --1.49824 0.494472 7.30353 --1.40998 0.558824 7.33926 --1.2817 0.615527 7.23898 --1.39715 0.725561 8.02177 --0.944234 0.697998 6.6819 --0.933753 0.778958 6.99867 --0.873921 0.849263 7.14061 --0.653963 0.847991 6.54096 --0.570339 0.900059 6.54231 --0.490193 0.95556 6.56114 --0.408963 1.01049 6.57853 --0.35931 1.09349 6.7999 --0.277854 1.15486 6.8435 --0.177758 1.19332 6.73814 --0.0854555 1.23725 6.68021 --1.78758 -1.48208 -0.850183 --1.86818 -1.52681 -0.837863 --1.98333 -1.5962 -0.848963 --2.07241 -1.64597 -0.835621 --2.1761 -1.70515 -0.829364 --2.29497 -1.77539 -0.828728 --2.42293 -1.84984 -0.828847 --2.54361 -1.91896 -0.819865 --2.68841 -2.00383 -0.819398 --2.82692 -2.08308 -0.80966 --2.98177 -2.17256 -0.802938 --3.11531 -2.24492 -0.779379 --3.29511 -2.3493 -0.772901 --3.4766 -2.45293 -0.759829 --3.67488 -2.5671 -0.746657 --3.87588 -2.68016 -0.726331 --4.10051 -2.80768 -0.707688 --4.3595 -2.95668 -0.691788 --4.66047 -3.12974 -0.679954 --4.98716 -3.31868 -0.663883 --5.36583 -3.53816 -0.649511 --5.78847 -3.78176 -0.631635 --6.30333 -4.08147 -0.61957 --6.73939 -4.32552 -0.569286 --6.60302 -4.2038 -0.386899 --7.97725 -5.03284 -0.483151 --6.56143 -4.10967 -0.0809652 --9.36196 -5.8096 -0.319499 --9.68098 -5.95883 -0.153527 --9.88808 -6.03764 0.0347885 --10.777 -6.5264 0.178037 --11.9159 -7.15804 0.341926 --13.7695 -8.20459 0.524389 --16.627 -9.8281 0.763494 --17.9569 -10.5302 1.10926 --18.214 -10.5964 1.48106 --18.224 -10.5173 1.85088 --18.2638 -10.4556 2.22212 --18.2358 -10.356 2.58882 --18.4024 -10.3653 2.97351 --18.5552 -10.3655 3.36264 --18.5706 -10.2889 3.73861 --18.599 -10.2181 4.11706 --18.6121 -10.1397 4.49453 --18.6278 -10.0625 4.87371 --18.646 -9.98627 5.25489 --18.6509 -9.90214 5.63444 --18.6571 -9.81831 6.01603 --18.6841 -9.74461 6.40503 --18.67 -9.64936 6.78483 --18.7099 -9.58202 7.18346 --18.513 -9.39277 7.50538 --18.8042 -9.45176 7.9979 --18.7823 -9.34944 8.38563 --18.9316 -9.33188 8.8443 --18.9465 -9.24695 9.25623 --18.9466 -9.15261 9.66539 --18.9647 -9.06693 10.0873 --18.9832 -8.97998 10.5149 --18.9949 -8.88908 10.9443 --18.9917 -8.78881 11.3708 --10.5866 -4.81507 7.16264 --10.407 -4.67671 7.30964 --10.4893 -4.65634 7.60851 --10.2167 -4.47701 7.6944 --10.1487 -4.38859 7.90296 --19.1327 -8.23258 14.1631 --19.1192 -8.11759 14.6323 --8.31219 -3.38256 7.58591 --8.43705 -3.38229 7.90928 --8.00405 -3.15301 7.7993 --8.06203 -3.12452 8.07512 --7.64718 -2.9071 7.95721 --7.57586 -2.82729 8.12325 --9.60662 -3.4092 10.7954 --9.27006 -3.14516 11.0824 --9.25181 -3.06641 11.3826 --9.18169 -2.96767 11.6334 --6.2309 -1.55986 10.2122 --3.84464 -0.858469 7.15255 --2.55095 -0.482826 5.473 --2.41034 -0.415384 5.40883 --2.31517 -0.359445 5.4072 --2.36283 -0.336954 5.63097 --2.28136 -0.283368 5.65228 --2.17498 -0.226284 5.62902 --2.16734 -0.188133 5.77649 --2.14646 -0.146267 5.90704 --2.39512 -0.142889 6.55856 --2.1566 -0.0637838 6.29265 --2.04064 -0.00501613 6.25348 --2.10038 0.0359213 6.58217 --2.08524 0.087453 6.76768 --2.07194 0.141257 6.97207 --1.80445 0.208377 6.57658 --1.70367 0.264867 6.56403 --1.62533 0.320251 6.60546 --1.64281 0.378961 6.90821 --1.56476 0.437931 6.96659 --1.50235 0.498738 7.07089 --1.39091 0.555336 7.03105 --1.30389 0.613429 7.06552 --1.17566 0.663623 6.95406 --0.998941 0.696987 6.64711 --0.897325 0.745515 6.59716 --0.829794 0.803982 6.68109 --0.751384 0.860801 6.72446 --0.616513 0.888741 6.5035 --0.534235 0.939888 6.51401 --0.454708 0.993324 6.5424 --0.369056 1.04302 6.53982 --0.323164 1.13181 6.80997 --0.244739 1.19675 6.89252 --0.13781 1.22434 6.73782 --0.0336262 1.24708 6.57166 --1.77066 -1.37744 -0.857447 --1.85142 -1.41942 -0.8473 --1.94792 -1.47179 -0.845231 --2.05125 -1.52813 -0.845138 --2.15603 -1.58444 -0.841563 --2.26913 -1.64628 -0.839107 --2.40477 -1.72256 -0.847094 --2.53511 -1.79298 -0.845832 --2.66624 -1.86432 -0.839798 --2.81416 -1.94393 -0.837977 --2.95506 -2.01911 -0.826664 --3.13572 -2.11904 -0.830197 --3.27982 -2.19329 -0.808126 --3.45588 -2.28687 -0.795792 --3.64945 -2.38989 -0.784066 --3.85169 -2.49735 -0.768594 --4.07276 -2.61461 -0.752 --4.32645 -2.7509 -0.7394 --4.59023 -2.89169 -0.720058 --4.90595 -3.06089 -0.707215 --5.27213 -3.2592 -0.697415 --5.6914 -3.48739 -0.687391 --6.1635 -3.74292 -0.674718 --6.52998 -3.93047 -0.618445 --6.56772 -3.9193 -0.477921 --6.52705 -3.86235 -0.321954 --8.51443 -4.99552 -0.519573 --6.43768 -3.74479 -0.0181664 --9.94195 -5.73711 -0.338888 --10.0679 -5.76171 -0.141869 --10.5987 -6.01557 0.0215768 --11.5375 -6.49503 0.175459 --12.9834 -7.25032 0.338952 --15.2461 -8.44653 0.532034 --18.496 -10.1664 0.800169 --18.5322 -10.1025 1.17148 --18.8793 -10.2068 1.55114 --18.895 -10.131 1.92818 --18.888 -10.0424 2.30328 --18.6537 -9.83345 2.65829 --19.2249 -10.0505 3.08783 --19.2265 -9.96477 3.46872 --19.2214 -9.87667 3.84905 --19.2459 -9.80335 4.23412 --19.2466 -9.71756 4.61649 --19.2677 -9.64153 5.00356 --19.2744 -9.55777 5.38923 --19.2745 -9.47142 5.77513 --19.2685 -9.38138 6.16074 --19.2913 -9.3043 6.55577 --19.2724 -9.20693 6.94151 --18.9529 -8.96615 7.23276 --19.4502 -9.11292 7.7904 --19.4552 -9.02479 8.19423 --19.6425 -9.02044 8.67032 --19.6763 -8.9427 9.09604 --19.6935 -8.85676 9.52022 --19.7124 -8.77036 9.94972 --19.7157 -8.67568 10.377 --19.7207 -8.58054 10.8095 --19.7338 -8.48867 11.2521 --19.7396 -8.39094 11.6962 --10.8621 -4.52519 7.27338 --7.92664 -3.23766 5.85187 --8.0117 -3.22955 6.09337 --8.00195 -3.18088 6.28396 --7.76643 -3.04111 6.33233 --8.62211 -3.33768 7.09743 --8.65951 -3.30242 7.34438 --8.22596 -3.08346 7.26133 --8.4201 -3.10835 7.62377 --8.42218 -3.05787 7.85459 --8.21671 -2.92903 7.9258 --7.95888 -2.78232 7.94816 --7.88657 -2.70507 8.11824 --7.25054 -2.42794 7.79755 --7.82571 -2.5763 8.53826 --9.91192 -3.22694 10.7216 --9.86051 -3.13959 10.9863 --9.55524 -2.96779 11.0039 --9.38812 -2.84284 11.1524 --8.79398 -2.5863 10.8496 --3.88658 -0.76478 7.00183 --3.81738 -0.704878 7.09974 --3.73487 -0.641412 7.18006 --2.35391 -0.305373 5.31757 --2.36767 -0.275296 5.48162 --2.30219 -0.22819 5.52859 --2.52426 -0.232747 6.052 --2.27479 -0.152504 5.7996 --2.24778 -0.110594 5.92248 --2.19449 -0.0632993 6.00139 --2.82565 -0.0963228 7.38844 --2.28092 0.0128295 6.54896 --2.3126 0.0581305 6.82582 --1.91183 0.135737 6.19932 --2.42896 0.158986 7.5582 --1.93101 0.232874 6.6752 --1.77347 0.287884 6.53585 --2.09674 0.349437 7.59154 --1.74218 0.399885 6.95621 --1.5908 0.451609 6.819 --1.57868 0.51443 7.06546 --1.46822 0.568384 7.03704 --1.3798 0.624364 7.07313 --1.26497 0.675513 7.0212 --1.07756 0.70595 6.69772 --0.968563 0.750117 6.63049 --0.899388 0.807378 6.71563 --0.813573 0.859749 6.74134 --0.678276 0.886844 6.53201 --0.593619 0.935617 6.54406 --0.503577 0.981841 6.52491 --0.42155 1.03253 6.55319 --0.367996 1.10959 6.7658 --0.28936 1.17162 6.84975 --0.182708 1.20049 6.71611 --0.0893719 1.24217 6.67901 --1.75771 -1.27895 -0.868755 --1.84639 -1.3237 -0.866181 --1.94282 -1.37233 -0.866287 --2.04092 -1.42195 -0.863006 --2.13925 -1.47088 -0.856709 --2.25321 -1.5289 -0.857132 --2.37623 -1.59122 -0.858699 --2.52208 -1.66877 -0.869831 --2.64719 -1.73082 -0.862466 --2.78929 -1.8022 -0.859603 --2.93173 -1.87252 -0.852071 --3.0915 -1.95284 -0.847579 --3.26768 -2.04316 -0.845035 --3.43046 -2.12146 -0.829302 --3.61762 -2.2147 -0.818485 --3.82329 -2.31705 -0.807814 --4.02948 -2.41779 -0.790042 --4.27041 -2.53825 -0.777085 --4.54574 -2.67609 -0.767492 --4.84016 -2.82299 -0.753371 --5.17744 -2.99232 -0.741591 --5.57691 -3.19348 -0.734656 --6.00412 -3.40816 -0.719641 --6.55224 -3.68718 -0.718529 --7.17384 -4.00163 -0.712527 --7.72113 -4.27059 -0.666961 --8.29771 -4.55111 -0.605751 --6.36675 -3.45577 -0.105602 --6.41298 -3.45062 0.0260914 --10.4327 -5.57971 -0.343771 --10.4807 -5.55648 -0.132115 --11.3008 -5.94313 0.013144 --12.4146 -6.47543 0.16921 --14.1867 -7.34051 0.335878 --16.9929 -8.72432 0.540498 --20.1626 -10.2698 0.848798 --20.3047 -10.2539 1.24721 --21.3533 -10.6921 1.67626 --20.8667 -10.3569 2.07035 --20.5177 -10.0937 2.45424 --21.4144 -10.4439 2.93186 --21.4984 -10.3925 3.35794 --21.4334 -10.2688 3.76861 --21.6035 -10.2569 4.21056 --21.6317 -10.1773 4.63669 --21.6454 -10.089 5.06151 --21.6515 -9.99822 5.48677 --21.6681 -9.91144 5.91574 --21.6602 -9.81361 6.34116 --21.3619 -9.58343 6.69274 --21.3416 -9.47947 7.11195 --20.6172 -9.06345 7.32328 --21.4819 -9.35032 8.01284 --21.4305 -9.23219 8.43117 --21.8969 -9.33501 9.03493 --21.8994 -9.23658 9.48638 --21.9212 -9.14468 9.94906 --21.9255 -9.04488 10.4099 --21.9481 -8.95059 10.8832 --9.6562 -3.84089 5.70528 --21.5441 -8.57898 11.6326 --9.87222 -3.83184 6.2458 --11.1767 -4.29441 7.15372 --7.7824 -2.92029 5.55801 --7.79756 -2.88496 5.75078 --8.16848 -2.98398 6.1577 --7.89769 -2.83842 6.19002 --7.7395 -2.73699 6.28539 --7.84433 -2.73081 6.5497 --7.66622 -2.62287 6.62935 --7.76223 -2.61166 6.89802 --7.65834 -2.53041 7.02885 --8.32772 -2.71171 7.74644 --8.07443 -2.57562 7.77805 --7.64934 -2.38568 7.66147 --7.40765 -2.25769 7.68068 --7.93056 -2.37483 8.35574 --7.83422 -2.29094 8.51049 --7.5767 -2.15889 8.51753 --7.37863 -2.04562 8.57074 --8.90867 -2.43556 10.3245 --7.42088 -1.9477 9.10897 --7.32384 -1.86324 9.26734 --8.7852 -2.19671 11.1171 --6.05676 -0.936371 10.5383 --5.8824 -0.834003 10.5967 --2.75575 -0.24451 6.08346 --2.56393 -0.175667 5.95042 --2.34656 -0.106978 5.76105 --2.27491 -0.060563 5.80699 --3.06494 -0.112722 7.38316 --2.9397 -0.0483646 7.3871 --2.79272 0.0176193 7.34378 --2.72374 0.0759019 7.44882 --1.92868 0.17182 6.05927 --1.86537 0.218878 6.12366 --2.48191 0.257497 7.71148 --1.85088 0.314289 6.52504 --1.78972 0.366195 6.61532 --2.1032 0.439412 7.66294 --1.72691 0.476912 6.97089 --1.59444 0.526026 6.8897 --1.54029 0.584352 7.02282 --1.44116 0.636286 7.03194 --1.32827 0.684985 6.99122 --1.25775 0.743015 7.09181 --1.0264 0.754817 6.61443 --0.92948 0.799249 6.59486 --0.872903 0.860034 6.73768 --0.786525 0.910089 6.76303 --0.644143 0.929318 6.52425 --0.55987 0.976978 6.54566 --0.468525 1.0197 6.52637 --0.380161 1.06373 6.52507 --0.330368 1.14659 6.78646 --0.238898 1.19331 6.78159 --0.142238 1.23143 6.7363 --0.0396755 1.25558 6.61051 --1.76712 -1.20042 -0.901685 --1.8368 -1.22984 -0.883579 --1.92706 -1.2719 -0.880085 --2.02604 -1.31764 -0.879391 --2.12573 -1.36457 -0.87519 --2.24715 -1.4234 -0.883386 --2.36371 -1.47836 -0.882329 --2.48934 -1.5376 -0.882318 --2.61528 -1.59591 -0.878221 --2.76604 -1.66887 -0.883153 --2.90266 -1.73096 -0.874579 --3.06299 -1.80667 -0.873845 --3.22614 -1.88262 -0.867509 --3.42943 -1.9799 -0.875177 --3.59587 -2.05466 -0.856917 --3.79489 -2.14627 -0.847353 --4.00355 -2.2421 -0.834163 --4.23851 -2.35083 -0.823409 --4.48324 -2.46338 -0.807279 --4.781 -2.60147 -0.800329 --5.10588 -2.75329 -0.790654 --5.46649 -2.9212 -0.779598 --5.8981 -3.12432 -0.774923 --6.39301 -3.35694 -0.770254 --7.07255 -3.68258 -0.791223 --6.31275 -3.25312 -0.467636 --6.3209 -3.2269 -0.330673 --6.3266 -3.19934 -0.194446 --6.33009 -3.17136 -0.0586608 --10.4789 -5.22915 -0.507592 --10.8314 -5.35812 -0.334613 --11.129 -5.45711 -0.143952 --12.114 -5.89033 0.000151359 --13.5495 -6.53495 0.152481 --15.9612 -7.63835 0.315865 --19.9749 -9.487 0.530065 --22.037 -10.3785 0.906817 --22.5247 -10.5146 1.33993 --23.305 -10.7829 1.79939 --22.4656 -10.2973 2.20504 --22.1081 -10.0388 2.6118 --23.45 -10.5541 3.15518 --23.2956 -10.3868 3.58859 --23.5156 -10.3863 4.0631 --23.5288 -10.2932 4.5165 --23.5518 -10.2054 4.97304 --23.5593 -10.1092 5.4282 --23.5857 -10.0208 5.88875 --23.5242 -9.89462 6.33242 --23.2662 -9.68621 6.72848 --23.0195 -9.48441 7.11984 --23.4213 -9.55053 7.68395 --23.3835 -9.43361 8.13576 --23.7749 -9.48974 8.72502 --23.7915 -9.39198 9.2069 --23.7994 -9.29078 9.69052 --9.84593 -3.74149 4.92913 --9.7722 -3.66702 5.10776 --9.80743 -3.635 5.33154 --9.9436 -3.64067 5.60257 --8.64437 -3.10892 5.22464 --8.94985 -3.17958 5.5627 --8.49823 -2.97188 5.53813 --8.37066 -2.88359 5.66533 --8.26692 -2.80416 5.80241 --8.30997 -2.77748 6.02148 --8.25 -2.71336 6.18445 --8.35182 -2.70424 6.44627 --8.15465 -2.5934 6.52721 --8.06197 -2.51826 6.67091 --7.87978 -2.41409 6.75244 --7.90207 -2.37634 6.97373 --7.9665 -2.35008 7.23108 --7.81617 -2.25676 7.33376 --7.78023 -2.19821 7.52221 --7.73226 -2.13554 7.70436 --7.62041 -2.05497 7.83634 --7.84025 -2.06745 8.25327 --7.6038 -1.94902 8.28093 --7.37577 -1.83581 8.30884 --7.21214 -1.74057 8.391 --7.81182 -1.84228 9.22101 --8.0787 -1.85094 9.75722 --8.62286 -1.92148 10.6113 --7.27777 -1.14566 11.2522 --4.7421 -0.520155 8.63859 --4.63232 -0.446926 8.73271 --3.44469 -0.230516 7.15688 --3.27654 -0.163666 7.1025 --4.44009 -0.243186 9.25063 --4.91638 -0.223785 10.3661 --3.05797 0.00318559 7.39296 --2.87502 0.0680189 7.2908 --2.82481 0.122802 7.43255 --2.01761 0.205935 6.07187 --1.94032 0.250557 6.11082 --2.57926 0.296109 7.70023 --1.87122 0.343879 6.38497 --1.84693 0.392801 6.55869 --1.75996 0.441505 6.59344 --1.90255 0.509771 7.21332 --1.70486 0.551403 6.97637 --1.61187 0.602134 7.00782 --1.56839 0.662501 7.18871 --1.42928 0.705112 7.0841 --1.32536 0.753439 7.08154 --1.1146 0.769833 6.70304 --0.986384 0.803843 6.57941 --0.928636 0.860466 6.71369 --0.85906 0.916345 6.81799 --0.70712 0.931714 6.56188 --0.61545 0.973894 6.55558 --0.52365 1.01568 6.54753 --0.444457 1.06602 6.60621 --0.370663 1.12334 6.71234 --0.292917 1.18351 6.81669 --0.186444 1.20942 6.70405 --0.0904052 1.24441 6.65818 --1.91575 -1.17554 -0.898538 --2.01513 -1.21946 -0.899722 --2.11571 -1.26247 -0.897914 --2.23188 -1.31464 -0.903214 --2.34197 -1.36228 -0.899629 --2.4599 -1.41352 -0.897459 --2.57908 -1.46371 -0.891713 --2.72378 -1.52748 -0.8958 --2.89193 -1.60399 -0.908314 --3.03881 -1.66721 -0.902204 --3.20328 -1.73733 -0.89975 --3.37627 -1.81234 -0.895593 --3.58374 -1.90391 -0.900957 --3.76871 -1.9815 -0.888065 --3.97985 -2.07236 -0.879263 --4.19249 -2.16141 -0.863481 --4.44013 -2.26708 -0.85313 --4.70627 -2.38024 -0.840204 --5.02553 -2.51866 -0.835193 --5.34683 -2.65529 -0.818918 --5.79157 -2.85049 -0.827188 --6.16979 -3.00963 -0.799995 --6.23504 -3.0125 -0.67901 --6.26321 -2.99629 -0.548368 --6.21952 -2.94533 -0.402439 --6.33183 -2.96987 -0.290141 --6.32642 -2.93877 -0.153987 --6.3376 -2.91488 -0.0217583 --6.34538 -2.8898 0.110147 --6.36099 -2.86835 0.240539 --11.9643 -5.40077 -0.171423 --13.0637 -5.84715 -0.0196038 --15.0397 -6.67865 0.120997 --18.0338 -7.94578 0.293801 --24.2012 -10.5885 0.510242 --24.261 -10.5146 0.972416 --24.6801 -10.5962 1.44119 --24.7065 -10.507 1.91091 --24.5053 -10.3201 2.36854 --24.9578 -10.4107 2.86524 --24.9983 -10.3261 3.34113 --25.0031 -10.2257 3.81458 --24.9733 -10.1116 4.28409 --25.0083 -10.0236 4.76271 --25.018 -9.92551 5.23928 --25.0186 -9.82338 5.71583 --25.0401 -9.7286 6.19783 --25.0072 -9.61246 6.67052 --24.5661 -9.33912 7.04612 --26.8631 -10.1097 8.11537 --25.0611 -9.32015 8.13718 --27.1819 -10.003 9.2571 --8.03621 -2.84489 3.73817 --9.62556 -3.38725 4.43783 --8.02086 -2.76798 4.0666 --9.58169 -3.28615 4.82069 --9.39976 -3.17924 4.95061 --7.78288 -2.57539 4.47902 --8.99732 -2.9546 5.17696 --8.15043 -2.62601 4.98647 --8.46049 -2.6902 5.31481 --7.93818 -2.47802 5.24434 --8.53653 -2.63331 5.73644 --8.10733 -2.45393 5.70056 --7.95026 -2.36365 5.80165 --8.4831 -2.48797 6.30347 --8.20135 -2.35752 6.33683 --8.22447 -2.32164 6.55314 --8.1786 -2.26307 6.72824 --8.38544 -2.278 7.07792 --7.24707 -1.90778 6.49404 --7.16722 -1.84369 6.62993 --7.17988 -1.80442 6.83454 --7.60338 -1.87507 7.36609 --7.52506 -1.80802 7.5195 --7.4601 -1.74375 7.68405 --7.45012 -1.69426 7.89913 --7.67122 -1.69839 8.32446 --7.68607 -1.65036 8.57883 --8.65226 -1.8194 9.74571 --8.38725 -1.69905 9.77116 --8.88002 -1.74405 10.5564 --8.92795 -1.68791 10.9168 --7.44591 -0.993315 11.1422 --7.27226 -0.894106 11.2504 --7.02624 -0.785213 11.2588 --7.1464 -0.72667 11.7724 --4.85175 -0.365069 8.8094 --5.26814 -0.354102 9.70244 --3.35052 -0.0941096 7.02516 --3.25138 -0.040244 7.07907 --5.19783 -0.142955 10.5411 --4.9592 -0.0526506 10.4763 --3.00896 0.12044 7.33282 --2.92466 0.174349 7.41481 --2.8388 0.229594 7.49497 --1.9887 0.287343 6.04289 --1.89607 0.329803 6.05428 --1.93007 0.376699 6.33606 --1.86225 0.42139 6.40965 --1.78455 0.466886 6.46345 --1.79635 0.521543 6.73824 --1.74519 0.572845 6.87447 --1.69038 0.626269 7.01009 --1.57841 0.670921 6.99436 --1.50212 0.723409 7.08019 --1.35783 0.759527 6.95553 --1.24563 0.800747 6.92354 --1.16487 0.851175 6.99464 --0.978383 0.862586 6.66953 --0.92056 0.921095 6.82313 --0.810154 0.95687 6.76273 --0.66432 0.969248 6.52544 --0.581188 1.01415 6.56765 --0.483286 1.04832 6.53022 --0.397749 1.09199 6.55921 --0.36353 1.19055 6.9487 --0.231126 1.18947 6.671 --0.145463 1.2382 6.72456 --0.0348954 1.24837 6.55103 --2.02203 -1.13584 -0.935467 --2.1016 -1.16415 -0.918761 --2.20378 -1.20442 -0.915838 --2.3223 -1.25266 -0.920147 --2.43375 -1.29659 -0.915547 --2.57018 -1.35244 -0.922244 --2.691 -1.39977 -0.9148 --2.83808 -1.45947 -0.917312 --3.00175 -1.52642 -0.923943 --3.16702 -1.5929 -0.925146 --3.3339 -1.65886 -0.920728 --3.52634 -1.73664 -0.922741 --3.72912 -1.81759 -0.92203 --3.95858 -1.90965 -0.925633 --4.15615 -1.98504 -0.907083 --4.38939 -2.07611 -0.895256 --4.64082 -2.17392 -0.881927 --4.93709 -2.29134 -0.874908 --5.26967 -2.42417 -0.868967 --5.6484 -2.57536 -0.864885 --6.08342 -2.74872 -0.862662 --6.1754 -2.76196 -0.752635 --7.51013 -3.3387 -0.948256 --7.43687 -3.27177 -0.771045 --6.19236 -2.68469 -0.354745 --9.4341 -4.08558 -0.834096 --6.35281 -2.69921 -0.119912 --6.34384 -2.66741 0.0137776 --6.3694 -2.65032 0.14164 --11.8585 -4.9533 -0.339839 --12.8145 -5.30626 -0.194636 --14.3247 -5.88161 -0.0561158 --17.2131 -7.01498 0.0619699 --16.2699 -6.55952 0.426033 --16.6255 -6.63735 0.73053 --28.3087 -11.2529 1.05264 --28.7057 -11.2982 1.59103 --28.6196 -11.15 2.12478 --29.6236 -11.4271 2.71533 --29.7246 -11.3489 3.27554 --30.5153 -11.5325 3.90279 --30.5332 -11.4181 4.47374 --30.5595 -11.3074 5.04717 --30.5581 -11.1851 5.6182 --29.4523 -10.5417 6.56095 --29.0913 -10.2947 7.04333 --29.5895 -10.3545 7.70512 --29.3492 -10.1506 8.21034 --30.7347 -10.5106 9.13071 --8.45623 -2.76741 3.52872 --8.30739 -2.6814 3.65514 --8.40132 -2.67679 3.85392 --8.33818 -2.61911 4.00481 --8.06484 -2.49361 4.0803 --7.9172 -2.41108 4.19354 --7.87549 -2.36184 4.34402 --7.91014 -2.33641 4.52658 --8.12657 -2.36753 4.79183 --8.25052 -2.36722 5.02521 --8.07304 -2.27543 5.12254 --8.14489 -2.25891 5.33929 --8.25599 -2.25157 5.58139 --7.89201 -2.10771 5.57499 --8.01305 -2.10204 5.82762 --7.96923 -2.04934 5.99219 --7.91367 -1.99337 6.15113 --7.39357 -1.81263 6.01759 --7.18967 -1.71983 6.0703 --6.87238 -1.59982 6.04001 --7.1983 -1.64314 6.45003 --7.18932 -1.60048 6.63606 --7.30159 -1.58581 6.91723 --7.6939 -1.63506 7.42705 --7.58241 -1.56235 7.55616 --7.37093 -1.46784 7.60083 --7.32297 -1.41076 7.78136 --7.51535 -1.4037 8.17834 --8.16383 -1.4863 9.0117 --8.701 -1.5371 9.78686 --8.35468 -1.40977 9.73539 --8.60425 -1.39491 10.2739 --8.40016 -1.29451 10.3635 --8.83554 -1.30385 11.141 --7.63124 -1.03588 10.1276 --7.13774 -0.769571 10.4509 --7.24374 -0.716569 10.8991 --7.11892 -0.631774 11.0669 --7.0144 -0.547302 11.2647 --6.86016 -0.457397 11.3961 --5.41332 -0.248497 9.64794 --3.4589 -0.0260436 7.00592 --3.30569 0.0299145 6.97746 --3.19551 0.0814971 7.01328 --5.15622 0.0387604 10.5144 --5.03056 0.117269 10.6478 --4.86772 0.197597 10.718 --4.71315 0.276672 10.8026 --2.79761 0.335095 7.46002 --1.93327 0.365522 5.96923 --2.02172 0.413595 6.35883 --1.93584 0.454999 6.39761 --1.85771 0.498574 6.4528 --1.8283 0.547263 6.62644 --1.65747 0.580109 6.4569 --1.74739 0.650025 6.95514 --1.63425 0.691568 6.94103 --1.5783 0.745302 7.08458 --1.52941 0.802277 7.26572 --1.3348 0.821741 6.98914 --1.1854 0.84888 6.83235 --1.16176 0.918216 7.11387 --0.993576 0.932307 6.86593 --0.845804 0.949089 6.66233 --0.743412 0.983269 6.63027 --0.625273 1.00649 6.5186 --0.539649 1.04761 6.55064 --0.459431 1.09468 6.6201 --0.386314 1.15116 6.74673 --0.294796 1.19303 6.7742 --0.195703 1.22571 6.74111 --0.085169 1.23809 6.58835 --2.19549 -1.10812 -0.943241 --2.29171 -1.14116 -0.933799 --2.42015 -1.18989 -0.942229 --2.54154 -1.23426 -0.941458 --2.66322 -1.27777 -0.936892 --2.80354 -1.32936 -0.937852 --2.95181 -1.38425 -0.938866 --3.11765 -1.44613 -0.943925 --3.30208 -1.51458 -0.952177 --3.47978 -1.57937 -0.94996 --3.69245 -1.65861 -0.957877 --3.89845 -1.73402 -0.954547 --4.14825 -1.82721 -0.962595 --4.33149 -1.88837 -0.934271 --4.59475 -1.98403 -0.92981 --4.85868 -2.07767 -0.9164 --5.18565 -2.19705 -0.914928 --5.53233 -2.32298 -0.907791 --5.93468 -2.46956 -0.90466 --6.44587 -2.65972 -0.917372 --7.44529 -3.05087 -1.03855 --7.36263 -2.9829 -0.860359 --7.36672 -2.95205 -0.706355 --6.25114 -2.43763 -0.196496 --6.24315 -2.40722 -0.065649 --6.25941 -2.38654 0.0602445 --12.3751 -4.76185 -0.581401 --12.6481 -4.81726 -0.369153 --13.8583 -5.23162 -0.230975 --16.2357 -6.08131 -0.130871 --16.1894 -5.99986 0.18044 --16.1941 -5.93724 0.486956 --16.4365 -5.96269 0.78897 --16.6371 -5.97163 1.09901 --31.7819 -11.3865 1.74043 --32.2321 -11.3004 2.93963 --32.2355 -11.1774 3.53407 --32.2388 -11.0533 4.12841 --32.2128 -10.9202 4.7202 --32.1868 -10.7871 5.31189 --32.1779 -10.6597 5.90638 --32.1223 -10.5159 6.49396 --31.5417 -10.2008 6.98421 --32.3542 -10.3409 7.7396 --35.4548 -11.2057 9.03627 --35.4336 -11.0588 9.69881 --8.70743 -2.57848 3.43003 --8.49237 -2.47591 3.54315 --8.2213 -2.35747 3.63249 --8.14121 -2.29869 3.77351 --8.3051 -2.31304 3.99489 --8.28308 -2.27102 4.15798 --8.15891 -2.19907 4.28337 --8.11351 -2.15014 4.43677 --8.28953 -2.1639 4.68199 --8.06952 -2.06589 4.76382 --8.05119 -2.02418 4.93113 --8.02121 -1.97888 5.09417 --7.91043 -1.91234 5.21804 --7.87475 -1.8657 5.37915 --7.98283 -1.85543 5.61876 --8.25653 -1.88421 5.95857 --8.19142 -1.82768 6.11645 --7.36227 -1.58796 5.81068 --7.5316 -1.58919 6.099 --7.2001 -1.4731 6.07188 --7.00217 -1.38974 6.12258 --7.11819 -1.37732 6.38836 --7.24339 -1.36447 6.67062 --7.26751 -1.32829 6.8872 --7.21733 -1.27523 7.05102 --7.60895 -1.30926 7.57421 --7.53853 -1.24857 7.73823 --7.59214 -1.21122 8.01135 --7.45465 -1.13803 8.12317 --8.09658 -1.19942 8.95007 --8.33244 -1.18376 9.43797 --8.09477 -1.08725 9.48301 --7.91315 -1.00104 9.57863 --8.10235 -0.970193 10.0587 --7.48697 -0.821658 9.69116 --7.45681 -0.757849 9.94367 --7.73267 -0.730018 10.559 --7.28138 -0.611596 10.3366 --7.07098 -0.522769 10.388 --7.03929 -0.453754 10.6624 --6.69884 -0.35541 10.5402 --6.38193 -0.261816 10.4328 --6.83201 -0.225368 11.3932 --6.18617 -0.110901 10.8117 --3.42214 0.0994203 6.9758 --3.26257 0.150785 6.93785 --5.92489 0.124159 11.477 --3.34199 0.241383 7.51289 --5.02505 0.291414 10.6986 --4.83117 0.36572 10.716 --3.04855 0.395354 7.73444 --2.83994 0.442721 7.59394 --2.08744 0.452569 6.32632 --2.01017 0.493751 6.38414 --1.9392 0.534793 6.4591 --1.86266 0.576496 6.52364 --1.78481 0.618627 6.58673 --2.06732 0.719875 7.56835 --1.71087 0.719359 6.94292 --1.69867 0.780111 7.20991 --1.59392 0.822856 7.23211 --1.4431 0.852628 7.10998 --1.29447 0.879214 6.97495 --1.1866 0.915843 6.96125 --1.0836 0.954086 6.9647 --0.930605 0.968026 6.76378 --0.815786 0.995705 6.69495 --0.682331 1.00972 6.52678 --0.593375 1.04725 6.55053 --0.496607 1.07864 6.53379 --0.42135 1.12969 6.64186 --0.380354 1.21966 7.00306 --0.232477 1.19784 6.63879 --0.136895 1.23011 6.62485 --0.0354085 1.24948 6.54056 --2.30319 -1.05501 -0.97806 --2.37878 -1.07387 -0.951576 --2.50029 -1.11561 -0.953464 --2.63138 -1.15948 -0.956816 --2.76397 -1.20316 -0.956006 --2.90547 -1.24999 -0.955662 --3.07187 -1.30726 -0.964479 --3.24945 -1.36784 -0.972249 --3.42771 -1.42806 -0.973985 --3.62462 -1.49468 -0.978232 --3.84891 -1.57137 -0.987696 --4.05765 -1.63935 -0.982239 --4.33696 -1.73538 -0.99873 --4.5408 -1.79856 -0.974361 --4.7893 -1.87797 -0.960034 --5.06572 -1.96744 -0.946543 --5.38834 -2.07293 -0.938737 --5.72193 -2.18129 -0.922464 --6.19105 -2.33973 -0.934682 --7.15269 -2.68628 -1.06425 --7.76743 -2.89222 -1.06908 --7.3724 -2.70817 -0.814178 --6.02732 -2.16878 -0.370776 --5.98311 -2.12669 -0.236579 --6.07572 -2.13511 -0.129434 --6.17639 -2.14652 -0.0209806 --12.774 -4.50716 -0.818302 --13.0518 -4.55582 -0.604652 --13.5623 -4.68448 -0.406091 --15.1807 -5.19848 -0.283527 --16.3873 -5.55732 -0.0758992 --16.2425 -5.44386 0.238914 --16.1783 -5.3595 0.545033 --16.5157 -5.41055 0.843184 --42.5041 -13.9631 1.32138 --39.5892 -12.6991 2.74639 --35.4441 -11.2225 3.21632 --38.9409 -12.1962 4.13721 --39.0311 -12.0785 4.8554 --36.8588 -10.9811 6.66759 --37.4611 -11.0212 7.44669 --34.5384 -10.0186 7.59062 --34.2536 -9.80353 8.1723 --34.2227 -9.66351 8.80329 --32.8221 -9.13472 9.1049 --34.4545 -9.46355 10.1493 --10.5577 -2.7497 4.12767 --10.5438 -2.70247 4.33154 --10.6184 -2.67971 4.56497 --8.68444 -2.12536 4.12725 --8.57613 -2.06132 4.26651 --8.20274 -1.92972 4.30346 --9.00757 -2.09648 4.79244 --7.96271 -1.79862 4.5485 --8.14328 -1.8072 4.79807 --8.12422 -1.76665 4.96569 --8.0215 -1.70534 5.09528 --8.40847 -1.75739 5.46623 --8.00235 -1.62691 5.44564 --8.4194 -1.68147 5.8547 --8.41478 -1.64039 6.04816 --7.66806 -1.44066 5.81085 --7.74581 -1.41819 6.04421 --6.98593 -1.2249 5.7561 --7.0536 -1.20122 5.97688 --7.03463 -1.16037 6.14587 --7.48048 -1.20601 6.64461 --7.39303 -1.14881 6.7817 --7.12205 -1.05871 6.7799 --7.11052 -1.0156 6.97115 --7.88178 -1.10166 7.7982 --7.64533 -1.01641 7.83305 --7.40288 -0.930175 7.85456 --7.25774 -0.861134 7.95555 --7.30218 -0.819796 8.22845 --7.22386 -0.759582 8.3945 --7.21992 -0.708295 8.63638 --7.57397 -0.699448 9.2491 --7.6965 -0.658087 9.65176 --7.4975 -0.577076 9.72281 --7.35836 -0.502993 9.85614 --7.29474 -0.436063 10.0775 --7.43752 -0.385359 10.5517 --7.17061 -0.298794 10.5432 --6.85755 -0.210813 10.465 --6.60841 -0.128952 10.4581 --6.89735 -0.0767621 11.1803 --3.46055 0.134893 6.66006 --3.44277 0.17662 6.83184 --3.36978 0.22075 6.92917 --3.29029 0.265478 7.01689 --3.12961 0.310579 6.9754 --3.3223 0.359752 7.52443 --3.03372 0.402262 7.26352 --4.75427 0.528037 10.6531 --2.97289 0.501545 7.64774 --2.82776 0.546135 7.6308 --2.06946 0.533522 6.34289 --1.96923 0.56909 6.35548 --1.97157 0.618067 6.59392 --1.79696 0.643501 6.43877 --1.79462 0.69526 6.68608 --1.75884 0.745372 6.86913 --1.72491 0.797734 7.07096 --1.65362 0.845373 7.18824 --1.55546 0.887225 7.22866 --1.37434 0.902298 7.01107 --1.22387 0.922099 6.86578 --1.13768 0.964039 6.9278 --1.06238 1.01102 7.03658 --0.88239 1.00776 6.7292 --0.800821 1.05056 6.80507 --0.636768 1.04249 6.50108 --0.547478 1.07673 6.52457 --0.411923 1.07287 6.28288 --0.38776 1.16665 6.70313 --0.298116 1.20692 6.75108 --0.206419 1.24536 6.78757 --0.0792153 1.2296 6.50889 --2.50365 -1.01941 -0.995279 --2.60332 -1.04622 -0.980202 --2.72845 -1.08286 -0.977035 --2.87079 -1.12591 -0.979765 --3.0304 -1.17514 -0.987322 --3.18323 -1.22087 -0.985091 --3.363 -1.27637 -0.991191 --3.56021 -1.33751 -0.999783 --3.76007 -1.39775 -1.0021 --4.00415 -1.47388 -1.01737 --4.20746 -1.53245 -1.00562 --4.51606 -1.63029 -1.03036 --4.72267 -1.68597 -1.00357 --4.99233 -1.76507 -0.992745 --5.28952 -1.85212 -0.982271 --5.58114 -1.93472 -0.958822 --5.86377 -2.0117 -0.922918 --6.05674 -2.05516 -0.851311 --5.82114 -1.94531 -0.658235 --7.21507 -2.40904 -0.881324 --5.99881 -1.95648 -0.453192 --5.97355 -1.92321 -0.32335 --5.96531 -1.89522 -0.198824 --6.04858 -1.89855 -0.0914135 --6.08182 -1.88494 0.025665 --11.9774 -3.79007 -0.649961 --13.8519 -4.34897 -0.63943 --11.9765 -3.69631 -0.191768 --11.9893 -3.65464 0.0344896 --12.0359 -3.62304 0.257828 --12.098 -3.59602 0.481151 --16.3739 -4.85497 0.595469 --16.6824 -4.88652 0.895477 --42.6127 -12.5484 1.45058 --36.3711 -10.5548 2.04916 --36.414 -10.4337 2.70872 --36.2816 -10.2623 3.35871 --36.3979 -10.1618 4.02394 --36.6662 -10.1025 4.70865 --36.2522 -9.85353 5.32456 --36.1424 -9.69053 5.96806 --34.1503 -9.02011 6.32173 --33.5739 -8.74073 6.84769 --33.6946 -8.64672 7.48622 --32.9574 -8.33075 7.95504 --33.228 -8.27576 8.62646 --33.7503 -8.28058 9.37251 --34.399 -8.31173 10.175 --10.5736 -2.35152 4.3514 --10.6932 -2.33776 4.59903 --10.0405 -2.14362 4.5924 --10.4128 -2.18672 4.92779 --10.4373 -2.14937 5.14952 --10.3679 -2.08991 5.33666 --10.1945 -2.00841 5.48094 --10.1275 -1.95064 5.66726 --8.56425 -1.58337 5.17151 --8.44833 -1.52169 5.30344 --8.63818 -1.52118 5.58572 --8.41142 -1.43751 5.66225 --8.3834 -1.39292 5.8398 --8.08491 -1.29727 5.86726 --7.98356 -1.24014 6.00037 --7.86438 -1.17957 6.12066 --7.03146 -0.997563 5.78945 --7.28761 -1.00415 6.13563 --7.19079 -0.950246 6.25792 --7.18919 -0.911523 6.44655 --7.23973 -0.879534 6.67721 --7.5545 -0.885335 7.11423 --7.81789 -0.879368 7.53258 --7.95365 -0.851908 7.8676 --7.73706 -0.775637 7.9216 --7.53671 -0.703271 7.98299 --7.28328 -0.625374 7.9926 --7.21498 -0.569887 8.16442 --6.31321 -0.42605 7.54394 --7.75628 -0.52456 9.18533 --7.72864 -0.466879 9.43062 --6.40423 -0.296042 8.31541 --7.48734 -0.331209 9.73979 --7.16653 -0.249463 9.67111 --7.00632 -0.180267 9.77566 --7.32259 -0.13689 10.4531 --7.09966 -0.0612357 10.4965 --6.91366 0.0113341 10.5823 --3.41271 0.1811 6.25087 --3.6381 0.214102 6.74365 --3.19348 0.259192 6.31175 --3.23061 0.297594 6.55389 --3.11688 0.33701 6.58091 --3.1113 0.377896 6.77459 --3.10427 0.421477 6.97794 --3.08155 0.466205 7.16503 --4.97174 0.629965 10.7579 --3.07207 0.564999 7.63753 --2.97219 0.610237 7.71154 --2.75411 0.642809 7.55155 --2.04498 0.611075 6.35084 --2.02304 0.655468 6.53538 --1.94359 0.692592 6.60158 --2.00861 0.757842 7.01587 --1.797 0.772365 6.77631 --1.68737 0.804534 6.77362 --1.75086 0.881501 7.24623 --1.60802 0.908363 7.16642 --1.58511 0.971601 7.44298 --1.3105 0.94978 6.9312 --1.18409 0.973332 6.86139 --1.0985 1.01318 6.93288 --0.9917 1.0441 6.92583 --0.849472 1.05375 6.76228 --0.714509 1.06242 6.60561 --0.607241 1.08377 6.55296 --0.509447 1.11189 6.54701 --0.391095 1.1178 6.40278 --0.347634 1.19802 6.73512 --0.24105 1.21599 6.6654 --0.132895 1.22815 6.56443 --0.0376069 1.25403 6.54975 --2.56384 -0.933257 -0.996401 --2.68885 -0.966312 -0.99609 --2.83204 -1.00555 -1.0017 --2.97579 -1.04477 -1.00283 --3.13757 -1.08893 -1.00882 --3.30093 -1.13269 -1.00966 --3.49965 -1.18911 -1.02262 --3.69982 -1.24384 -1.02918 --3.9281 -1.30749 -1.04137 --4.14011 -1.36359 -1.03823 --4.39815 -1.43385 -1.04693 --4.71977 -1.52534 -1.07181 --4.93811 -1.57813 -1.04511 --5.2104 -1.64847 -1.0307 --5.48554 -1.71731 -1.00738 --5.82439 -1.80529 -0.995384 --6.36657 -1.95812 -1.0324 --7.32606 -2.2422 -1.16729 --7.21207 -2.17485 -0.984975 --7.13209 -2.11984 -0.816699 --7.10434 -2.08155 -0.664779 --6.01445 -1.71643 -0.297446 --6.02356 -1.69444 -0.176968 --6.0111 -1.66669 -0.0536154 --13.3402 -3.82365 -1.02689 --14.8425 -4.21398 -0.969858 --14.8509 -4.16043 -0.691273 --11.9045 -3.26091 -0.134566 --11.9723 -3.2346 0.0835597 --12.1322 -3.23459 0.29799 --16.9608 -4.52131 0.327136 --16.8514 -4.42877 0.64064 --37.3352 -9.87123 0.843467 --37.3178 -9.73225 1.51419 --36.506 -9.38559 2.15936 --36.9874 -9.37894 2.83741 --37.4005 -9.35091 3.52774 --36.6693 -9.03357 4.13797 --37.0301 -8.99023 4.83295 --37.8512 -9.05707 5.59686 --33.7846 -7.82056 6.33534 --33.028 -7.40017 7.4221 --36.9294 -8.15981 8.84094 --32.562 -7.05339 8.53138 --11.4406 -2.31485 3.96318 --33.0525 -6.91522 9.87317 --11.4759 -2.23456 4.41452 --10.6938 -2.02722 4.40324 --10.1304 -1.87041 4.43416 --9.93115 -1.78993 4.56877 --9.87751 -1.73933 4.75016 --9.82138 -1.68753 4.93023 --10.0459 -1.68909 5.22192 --10.1907 -1.67394 5.49182 --11.9267 -1.89308 6.71833 --7.2102 -1.03055 4.7225 --10.2414 -1.50654 6.39548 --9.87609 -1.40093 6.43431 --10.0607 -1.38555 6.75906 --8.09702 -1.03527 5.8847 --8.25863 -1.02066 6.17248 --7.80453 -0.914815 6.09555 --7.84862 -0.882095 6.31718 --7.38185 -0.77847 6.20921 --6.96246 -0.685569 6.11452 --8.42521 -0.832799 7.33024 --7.56734 -0.683789 6.93053 --7.59922 -0.645437 7.16352 --8.59815 -0.713385 8.1605 --7.77001 -0.576554 7.73748 --7.88217 -0.541167 8.0629 --7.70668 -0.476816 8.1522 --8.03655 -0.456962 8.68982 --6.20482 -0.254793 7.25266 --6.02354 -0.198627 7.28915 --7.66667 -0.269847 9.12708 --6.42312 -0.138007 8.12752 --7.55498 -0.153154 9.56481 --7.42106 -0.0887188 9.7062 --7.44376 -0.0306716 10.0248 --7.37286 0.032656 10.2477 --7.2768 0.0985399 10.4471 --3.67404 0.2244 6.26387 --3.51377 0.26224 6.23756 --3.39744 0.298646 6.26329 --3.26343 0.33454 6.26208 --3.48521 0.376436 6.76659 --3.20536 0.408757 6.5576 --3.15693 0.44728 6.68469 --3.16769 0.490006 6.91333 --3.10013 0.530801 7.02355 --3.00493 0.569323 7.08999 --3.17645 0.632281 7.6345 --3.03238 0.670512 7.63126 --2.88001 0.706579 7.60722 --2.59693 0.723235 7.31135 --2.38448 0.744232 7.13444 --1.99292 0.730603 6.54347 --2.07132 0.796487 6.97523 --1.77596 0.788602 6.5453 --1.74919 0.836347 6.74672 --1.83397 0.917634 7.26539 --1.695 0.943506 7.20658 --1.60944 0.983875 7.29573 --1.3552 0.965558 6.86263 --1.3395 1.02975 7.16558 --1.13007 1.01635 6.81921 --1.03696 1.05033 6.86123 --0.924035 1.0736 6.82461 --0.796557 1.08618 6.7184 --0.648986 1.08069 6.4933 --0.5702 1.12026 6.58572 --0.39346 1.07584 6.13177 --0.403891 1.19865 6.7571 --0.294937 1.21428 6.68901 --0.229636 1.28412 6.95183 --0.0747112 1.2255 6.44889 --2.55259 -0.833194 -1.03255 --2.65498 -0.854325 -1.01865 --2.79806 -0.889957 -1.02702 --2.93432 -0.922197 -1.02609 --3.09671 -0.961655 -1.03544 --3.25157 -0.998802 -1.03479 --3.43386 -1.04355 -1.04278 --3.61756 -1.08679 -1.04516 --3.82908 -1.13815 -1.05405 --4.0685 -1.19733 -1.06818 --4.32754 -1.26108 -1.08213 --4.57998 -1.32077 -1.08385 --4.8871 -1.39689 -1.09838 --5.14325 -1.45412 -1.08254 --5.41914 -1.51552 -1.06476 --5.70515 -1.5774 -1.04116 --6.13964 -1.68259 -1.05419 --7.06707 -1.92898 -1.19704 --7.34205 -1.9795 -1.12574 --7.21617 -1.91384 -0.942468 --7.22751 -1.88842 -0.797955 --5.86927 -1.48062 -0.3551 --5.85024 -1.45146 -0.232295 --5.86665 -1.43303 -0.117419 --13.1331 -3.35608 -1.1852 --14.434 -3.6506 -1.12474 --16.2579 -4.072 -1.08495 --16.2477 -4.0095 -0.781623 --17.477 -4.26252 -0.592594 --17.12 -4.10983 -0.245554 --17.1141 -4.04628 0.0680249 --17.4337 -4.06246 0.368158 --18.9443 -4.361 0.655158 --42.7683 -9.91521 0.948402 --41.3462 -9.4344 1.68789 --41.3905 -9.29891 2.42512 --41.4414 -9.16463 3.16377 --40.5739 -8.82706 3.84197 --41.1152 -8.80241 4.61109 --35.7263 -7.37225 5.42624 --35.5855 -7.21622 6.04793 --35.2017 -7.01122 6.62866 --35.2623 -6.89772 7.27579 --34.0291 -6.52705 7.67896 --10.8609 -1.90947 3.42841 --11.0377 -1.90289 3.67453 --11.0182 -1.85776 3.88 --10.9484 -1.80256 4.07246 --11.0349 -1.77621 4.30891 --10.363 -1.61557 4.32073 --10.2377 -1.55372 4.48498 --10.259 -1.51721 4.69635 --9.68173 -1.38097 4.69532 --9.92085 -1.38074 4.98325 --9.68414 -1.30304 5.09353 --9.51929 -1.23839 5.2273 --7.92855 -0.960916 4.73178 --7.23913 -0.827484 4.58772 --7.057 -0.770259 4.66073 --9.87572 -1.12411 6.22904 --9.51028 -1.03172 6.25997 --9.69649 -1.01304 6.57851 --8.1264 -0.773443 5.91619 --8.10717 -0.732952 6.09895 --8.05949 -0.688964 6.26669 --8.15004 -0.659292 6.5245 --8.0612 -0.608765 6.67163 --8.37153 -0.599063 7.09242 --7.74378 -0.495192 6.86893 --7.92095 -0.47004 7.2092 --8.05745 -0.438488 7.53265 --8.17848 -0.40238 7.85602 --6.87257 -0.257819 7.03287 --7.62941 -0.269285 7.87704 --7.45586 -0.21179 7.96137 --6.21846 -0.0936271 7.08615 --6.08854 -0.0460954 7.17164 --6.5846 0.0189396 8.08827 --6.18805 0.0790634 7.91972 --6.31198 0.121682 8.28622 --5.81376 0.179585 7.98524 --7.35537 0.209248 9.97488 --7.02363 0.271564 9.89147 --7.16702 0.332004 10.3713 --3.61433 0.349172 6.22235 --3.4418 0.381466 6.17888 --3.35584 0.414565 6.2436 --3.27869 0.44866 6.32285 --3.19552 0.481451 6.39287 --3.29924 0.527407 6.74388 --3.08406 0.553614 6.62067 --3.26801 0.61003 7.12894 --3.07766 0.638708 7.04372 --3.04007 0.680446 7.21389 --3.11373 0.738624 7.59388 --2.99804 0.775737 7.64253 --2.85385 0.807985 7.63592 --2.43569 0.793289 7.06146 --2.08802 0.78041 6.58383 --1.97323 0.806625 6.57886 --1.99267 0.861897 6.88296 --1.86641 0.886165 6.85697 --2.27798 1.05666 8.21081 --1.74277 0.970559 7.13298 --1.69792 1.02146 7.33574 --1.66472 1.07967 7.5953 --1.54305 1.1091 7.59885 --1.32728 1.09597 7.27653 --1.10212 1.06985 6.87242 --0.987074 1.08984 6.83773 --0.882677 1.11473 6.83927 --0.740439 1.11374 6.66496 --0.614125 1.11774 6.53625 --0.431895 1.07029 6.07424 --0.344705 1.09316 6.08606 --0.349301 1.21356 6.70167 --0.247466 1.23366 6.68211 --0.137797 1.23939 6.58239 --0.0371509 1.25493 6.53941 --2.75191 -0.775889 -1.04513 --2.88806 -0.804525 -1.04696 --3.04292 -0.837113 -1.05473 --3.19838 -0.869555 -1.05744 --3.37287 -0.906614 -1.06464 --3.56553 -0.948266 -1.07514 --3.76896 -0.991111 -1.08401 --3.96495 -1.03142 -1.0819 --4.21532 -1.08511 -1.09778 --4.47715 -1.14129 -1.10902 --4.76784 -1.20348 -1.1229 --5.0781 -1.26871 -1.13426 --5.40095 -1.33568 -1.13867 --5.58819 -1.36318 -1.08463 --5.90443 -1.42511 -1.06696 --6.7595 -1.62644 -1.20504 --7.37057 -1.75873 -1.24053 --8.10785 -1.91802 -1.28847 --8.75551 -2.05044 -1.28728 --8.28993 -1.90018 -1.00458 --8.27296 -1.86434 -0.836771 --8.31956 -1.84413 -0.683532 --9.89758 -2.1898 -0.800628 --14.0526 -3.1301 -1.27052 --16.1365 -3.56238 -1.30007 --18.5774 -4.06184 -1.29993 --18.5302 -3.98499 -0.954013 --18.8763 -3.99499 -0.645633 --18.8968 -3.93268 -0.303836 --42.8081 -8.84759 -0.432426 --42.8663 -8.71152 0.326449 --42.8424 -8.55889 1.08585 --41.9033 -8.22194 1.82627 --41.0875 -7.91714 2.53804 --40.5925 -7.67917 3.23822 --42.2128 -7.84875 4.07176 --40.7228 -7.42409 4.68756 --34.4492 -6.12969 4.745 --34.4608 -6.01273 5.36097 --35.3498 -6.04948 6.10264 --35.8156 -6.00679 6.81092 --35.3162 -5.79647 7.36792 --35.7474 -5.74347 8.09114 --10.8282 -1.55235 3.4463 --10.888 -1.52266 3.66487 --10.4641 -1.41541 3.76638 --10.5471 -1.3896 3.98935 --10.2911 -1.3113 4.12045 --10.1302 -1.24931 4.27221 --10.2387 -1.22515 4.50732 --9.63996 -1.10364 4.50649 --7.91485 -0.834043 4.07786 --7.82859 -0.7905 4.20849 --7.18725 -0.677635 4.11555 --7.77935 -0.720853 4.51702 --7.37747 -0.640761 4.50688 --7.23963 -0.592727 4.60426 --7.21699 -0.559856 4.75435 --9.52282 -0.773771 6.07496 --8.50444 -0.627741 5.75644 --8.12073 -0.552175 5.74329 --6.26671 -0.340269 4.88142 --6.10053 -0.295542 4.93591 --8.12737 -0.438127 6.33089 --5.98556 -0.227097 5.17027 --5.75889 -0.17916 5.17571 --5.6489 -0.141905 5.25371 --8.01247 -0.267825 7.08671 --7.872 -0.216894 7.20121 --6.83876 -0.115605 6.63405 --6.89402 -0.0802055 6.87552 --6.5873 -0.0260227 6.82939 --6.71899 0.0074224 7.14239 --6.81915 0.0448905 7.44152 --6.23719 0.10505 7.13496 --6.06884 0.148644 7.18658 --7.99112 0.159151 9.25724 --6.13465 0.231611 7.68028 --6.04318 0.276289 7.81248 --6.03044 0.321617 8.03107 --5.77133 0.365306 7.98387 --6.88397 0.432444 9.49632 --7.02369 0.492811 9.95487 --7.40924 0.566793 10.7376 --3.54472 0.467802 6.1732 --3.39658 0.495639 6.16017 --3.30313 0.525101 6.21629 --5.59049 0.722389 9.62793 --3.53155 0.618907 6.93276 --3.27121 0.637696 6.75683 --3.43106 0.695108 7.22267 --3.36667 0.733813 7.35451 --3.02058 0.739 7.01278 --2.95794 0.775931 7.13903 --3.06772 0.840706 7.58874 --2.97905 0.878609 7.68999 --2.67223 0.877561 7.36247 --2.46014 0.889489 7.19714 --2.02089 0.847297 6.52038 --1.96325 0.882411 6.64204 --1.96642 0.935418 6.91919 --1.76955 0.93723 6.71728 --1.82303 1.01018 7.15207 --1.71482 1.03818 7.17827 --1.6663 1.08716 7.38123 --1.60622 1.13561 7.56503 --1.51607 1.17447 7.67265 --1.19701 1.1067 6.98737 --1.05131 1.10926 6.84952 --0.955358 1.1372 6.89117 --0.806911 1.13206 6.70932 --0.682086 1.13663 6.60185 --0.48427 1.07793 6.09411 --0.389164 1.09209 6.06829 --0.409435 1.22218 6.7524 --0.298014 1.23015 6.67574 --0.218461 1.27647 6.83197 --0.0747597 1.22853 6.43813 --2.69409 -0.66116 -1.05625 --2.83919 -0.688231 -1.06629 --2.97747 -0.71191 -1.06703 --3.1409 -0.743023 -1.07794 --3.29014 -0.767368 -1.07472 --3.47398 -0.801676 -1.08488 --3.67771 -0.839084 -1.09829 --3.89152 -0.878765 -1.10937 --4.10681 -0.91667 -1.11366 --4.37778 -0.968419 -1.1347 --4.62434 -1.01051 -1.13575 --4.92678 -1.06579 -1.15062 --5.27592 -1.13101 -1.1729 --5.70196 -1.2118 -1.21024 --5.81862 -1.21587 -1.12602 --6.53701 -1.36061 -1.23329 --7.07484 -1.45966 -1.25911 --7.77539 -1.59132 -1.3124 --8.30168 -1.67887 -1.29432 --8.23251 -1.6318 -1.11138 --8.08298 -1.56811 -0.914396 --8.20707 -1.56446 -0.781589 --8.15605 -1.52306 -0.612191 --9.94607 -1.86216 -0.763524 --9.79762 -1.7952 -0.55204 --10.0627 -1.81322 -0.403354 --23.4866 -4.32807 -1.38197 --29.4997 -5.28426 -0.931354 --37.7413 -6.68895 -0.802035 --42.9051 -7.48602 -0.292016 --42.9268 -7.34473 0.464702 --41.2306 -6.90676 1.21373 --37.5379 -6.14216 1.85979 --37.6075 -6.02709 2.52398 --36.8588 -5.77816 3.14459 --35.4478 -5.42822 3.69069 --35.3569 -5.29412 4.30919 --37.4375 -5.49071 5.16162 --38.9118 -5.58362 6.01227 --34.3742 -4.7884 6.05229 --34.4864 -4.687 6.68587 --35.3378 -4.68571 7.45834 --10.867 -1.24564 3.27751 --10.9199 -1.21418 3.49271 --10.7844 -1.15692 3.66718 --10.3866 -1.06768 3.77225 --10.5928 -1.05413 4.02694 --9.65689 -0.904379 3.96232 --9.77171 -0.881919 4.18675 --10.0801 -0.879153 4.48015 --8.0764 -0.624835 3.99154 --7.93476 -0.578668 4.10473 --7.16919 -0.470546 3.97525 --7.73954 -0.49718 4.35599 --7.38198 -0.4318 4.36889 --7.50901 -0.413362 4.58469 --7.29653 -0.363128 4.65013 --7.4611 -0.345733 4.89204 --6.78184 -0.261294 4.71748 --8.28362 -0.339999 5.66463 --6.79668 -0.201966 5.04156 --6.38259 -0.144395 4.96783 --6.35125 -0.112147 5.10504 --6.1379 -0.0700298 5.13239 --5.89319 -0.0277898 5.13193 --5.79891 0.00673045 5.22356 --5.69462 0.0403673 5.30771 --6.02095 0.058061 5.69725 --5.77376 0.0988249 5.6825 --7.28973 0.0911166 7.01077 --6.95355 0.13826 6.95578 --6.72107 0.182025 6.97339 --6.643 0.222396 7.11441 --6.44202 0.263726 7.14852 --6.21932 0.304898 7.15715 --6.12928 0.344535 7.28359 --7.7564 0.407453 9.08307 --6.20291 0.42985 7.79447 --6.04564 0.47027 7.86315 --5.94256 0.51138 7.98695 --7.45234 0.619206 9.91012 --7.29336 0.670771 10.0346 --7.0616 0.717763 10.072 --3.72061 0.564871 6.25875 --3.59364 0.591668 6.28127 --3.43143 0.613946 6.25317 --3.39478 0.646999 6.39049 --3.38317 0.683227 6.56891 --3.31579 0.715587 6.67373 --3.26752 0.750058 6.81149 --3.31653 0.79875 7.10932 --3.18618 0.825128 7.1288 --3.19142 0.871847 7.37823 --2.84852 0.862955 7.02052 --2.93852 0.926928 7.43427 --2.91876 0.97443 7.66667 --2.66295 0.974567 7.43592 --2.07878 0.893873 6.48828 --1.97654 0.916345 6.51107 --2.0361 0.981555 6.90635 --1.88849 0.99346 6.83613 --1.67517 0.98244 6.58695 --1.82838 1.09173 7.29062 --1.77634 1.13822 7.48578 --1.71799 1.18524 7.68087 --0.865739 0.891758 5.37896 --1.39886 1.19738 7.45192 --1.12034 1.13568 6.87922 --1.00379 1.14927 6.84588 --0.895963 1.16632 6.83906 --0.728178 1.1425 6.55988 --0.615967 1.14959 6.50013 --0.431712 1.09356 6.03971 --0.34471 1.11139 6.05234 --0.352638 1.23356 6.69783 --0.252912 1.25111 6.69894 --0.14054 1.25015 6.59045 --0.0391051 1.26146 6.55845 --2.65768 -0.557662 -1.08123 --2.78648 -0.576621 -1.08336 --2.91557 -0.594723 -1.08169 --3.07147 -0.618988 -1.09111 --3.2378 -0.643868 -1.10077 --3.41385 -0.670463 -1.11003 --3.59967 -0.698599 -1.11814 --3.80442 -0.730029 -1.12927 --4.02024 -0.763449 -1.13791 --4.25584 -0.798622 -1.14823 --4.50238 -0.834549 -1.15499 --4.79513 -0.880159 -1.17246 --5.09077 -0.924136 -1.18044 --5.47089 -0.984205 -1.20989 --5.87278 -1.04607 -1.23347 --6.31521 -1.11348 -1.25624 --6.84403 -1.1956 -1.29107 --7.44301 -1.28805 -1.32776 --8.20621 -1.40902 -1.38916 --7.9759 -1.33346 -1.16509 --9.84356 -1.65528 -1.45758 --10.1787 -1.68148 -1.34085 --8.02475 -1.2532 -0.704679 --8.07663 -1.23334 -0.559461 --8.05913 -1.20075 -0.401672 --16.794 -2.66848 -1.56101 --19.4947 -3.06447 -1.61059 --42.9795 -6.28721 -0.904329 --43.0066 -6.14805 -0.149179 --38.8745 -5.40662 0.646896 --37.8739 -5.13628 1.32203 --38.029 -5.03174 1.99046 --36.0047 -4.63193 2.57263 --35.9391 -4.50411 3.20146 --35.695 -4.35231 3.81474 --35.7759 -4.2433 4.45139 --35.8154 -4.12883 5.08795 --35.7753 -4.00404 5.71731 --35.5863 -3.86165 6.32573 --11.2669 -1.02106 2.97025 --11.1788 -0.971589 3.16217 --11.1741 -0.931935 3.36912 --10.9231 -0.867509 3.52364 --10.8344 -0.819597 3.70866 --10.8382 -0.780966 3.91572 --10.3972 -0.701862 4.00338 --10.2911 -0.653945 4.17366 --9.76353 -0.570899 4.21148 --8.40344 -0.424467 3.95872 --8.32617 -0.386665 4.10159 --7.81634 -0.316895 4.08455 --7.17844 -0.242256 4.00081 --7.10121 -0.208148 4.12077 --7.23285 -0.187058 4.32863 --7.20466 -0.155718 4.4729 --7.35525 -0.134074 4.70133 --7.40095 -0.105114 4.88771 --6.66738 -0.0393669 4.68288 --6.77281 -0.0146748 4.89384 --6.68979 0.0188762 5.00787 --6.31872 0.0621858 4.95584 --6.27769 0.0928847 5.08703 --5.86106 0.13262 4.98605 --5.91068 0.160918 5.16962 --6.04812 0.187487 5.41724 --5.99716 0.219243 5.54513 --5.87151 0.250939 5.6201 --7.4367 0.27936 6.95226 --6.72572 0.318121 6.61564 --6.75534 0.3557 6.83746 --6.79383 0.39443 7.07449 --6.65211 0.432618 7.16451 --6.1646 0.46101 6.9466 --6.40219 0.506697 7.36941 --6.24183 0.541945 7.43713 --6.70192 0.604272 8.11004 --6.35514 0.632721 8.00292 --6.17967 0.66924 8.05934 --6.76892 0.751609 8.94312 --7.25578 0.838004 9.76598 --6.93565 0.8707 9.69815 --3.79527 0.661061 6.21779 --3.63026 0.6807 6.19553 --3.51612 0.704182 6.23234 --3.516 0.73965 6.41871 --3.51584 0.77606 6.61474 --3.33896 0.792566 6.56622 --3.35928 0.834188 6.80344 --3.24902 0.859562 6.84981 --3.00074 0.861487 6.67442 --2.8413 0.875632 6.62914 --3.23034 0.990636 7.52951 --2.68888 0.93208 6.81493 --2.69542 0.980026 7.06871 --2.76583 1.04424 7.46649 --2.21849 0.964235 6.62511 --2.02848 0.961837 6.47071 --2.1 1.02941 6.88338 --1.98207 1.04744 6.8883 --1.73128 1.02118 6.55973 --1.98045 1.16201 7.49336 --1.83705 1.17394 7.44862 --1.78017 1.21938 7.64447 --0.920553 0.917125 5.40029 --0.835723 0.92838 5.39379 --1.38202 1.26262 7.57381 --1.06901 1.17396 6.86669 --0.962908 1.18957 6.87117 --0.819912 1.18157 6.71968 --0.709915 1.19142 6.69091 --0.494692 1.11368 6.11722 --0.390405 1.11468 6.04398 --0.40294 1.23387 6.67973 --0.301074 1.24704 6.67242 --0.218818 1.28666 6.81988 --0.0779518 1.23837 6.45644 --2.73021 -0.466603 -1.09877 --2.86039 -0.481838 -1.09979 --3.00782 -0.499403 -1.10732 --3.16491 -0.518838 -1.11514 --3.33146 -0.539103 -1.12308 --3.50849 -0.559852 -1.13065 --3.71353 -0.585823 -1.14623 --3.93855 -0.614652 -1.16399 --4.16505 -0.641685 -1.17486 --4.42006 -0.674165 -1.19032 --4.68678 -0.70608 -1.20186 --4.97275 -0.740321 -1.21214 --5.31675 -0.782745 -1.23497 --5.69988 -0.83064 -1.25999 --6.13246 -0.884907 -1.2887 --6.57751 -0.937999 -1.30637 --7.15792 -1.01135 -1.35041 --7.86494 -1.10198 -1.41119 --8.5576 -1.18592 -1.44281 --9.34034 -1.27986 -1.47322 --10.0028 -1.34895 -1.44776 --9.81637 -1.28475 -1.21443 --9.76135 -1.24141 -1.01567 --9.7415 -1.20399 -0.826728 --15.7561 -2.03005 -1.63055 --18.5515 -2.36663 -1.75005 --41.1502 -4.03667 2.91622 --36.3863 -3.30334 3.97736 --35.771 -3.00815 5.18845 --37.3254 -3.02711 6.0264 --11.1774 -0.653739 2.98873 --11.1942 -0.616558 3.19853 --11.4912 -0.599808 3.4666 --10.336 -0.367206 4.01788 --10.8509 -0.360056 4.36943 --10.2322 -0.286718 4.38816 --10.0322 -0.238603 4.52479 --8.43643 -0.126122 4.16703 --8.27991 -0.0865155 4.28158 --8.13107 -0.049319 4.39558 --7.41677 0.00911041 4.27433 --7.49919 0.0351697 4.4687 --7.51356 0.0653933 4.63781 --7.58771 0.0948338 4.8381 --7.52214 0.128151 4.97577 --10.1062 0.115974 6.47041 --6.50205 0.205059 4.77701 --6.06147 0.237993 4.68706 --5.83417 0.266992 4.70331 --5.99357 0.293565 4.94497 --6.61222 0.32444 5.48449 --6.33398 0.354254 5.47433 --6.19075 0.383939 5.54542 --5.94038 0.41082 5.53847 --6.18684 0.446486 5.88209 --6.58278 0.490358 6.35519 --6.4665 0.522441 6.45631 --6.76933 0.570462 6.89348 --6.51399 0.597526 6.8883 --6.19244 0.620735 6.81697 --6.53886 0.677248 7.32914 --6.31228 0.704061 7.33904 --6.1517 0.734716 7.40513 --6.48788 0.800581 7.95944 --6.60432 0.854716 8.31947 --6.65507 0.905952 8.62749 --6.40207 0.931948 8.61436 --6.34874 0.976029 8.81971 --6.23929 1.01568 8.96436 --3.63822 0.769862 6.07879 --3.58657 0.797854 6.19442 --3.48415 0.819022 6.24661 --3.46429 0.850961 6.40914 --3.39316 0.877847 6.50725 --3.32596 0.905145 6.61279 --3.34414 0.947377 6.85044 --3.24777 0.970989 6.92239 --2.72325 0.914096 6.29694 --2.74695 0.957168 6.54725 --2.83662 1.01867 6.9292 --2.69054 1.03108 6.90521 --1.29533 0.735592 4.48241 --2.70666 1.13059 7.45191 --2.07468 1.00914 6.42061 --2.04306 1.0464 6.59752 --2.02402 1.09003 6.82056 --1.89615 1.09973 6.79717 --1.81741 1.12594 6.89096 --1.96932 1.24232 7.60505 --1.81384 1.24652 7.53243 --0.959559 0.940129 5.37338 --0.883378 0.952325 5.39655 --0.801106 0.961944 5.39938 --0.427795 0.810941 4.36238 --1.03946 1.22288 6.94028 --0.865507 1.19321 6.67573 --0.732472 1.18301 6.54229 --0.630779 1.19442 6.54153 --0.436098 1.1219 6.03432 --0.352892 1.13958 6.07712 --0.355974 1.25356 6.69399 --0.260037 1.27198 6.73532 --0.14953 1.27046 6.65735 --0.042989 1.26946 6.58729 --2.68012 -0.363116 -1.11759 --2.79231 -0.37162 -1.11025 --2.94748 -0.386884 -1.12608 --3.08821 -0.398427 -1.12696 --3.25437 -0.414247 -1.13834 --3.44011 -0.432479 -1.15433 --3.61044 -0.447183 -1.15516 --3.82538 -0.468086 -1.17334 --4.04204 -0.488188 -1.18464 --4.30573 -0.514307 -1.2102 --4.56329 -0.538278 -1.22315 --4.84972 -0.564254 -1.23976 --5.16564 -0.593787 -1.25806 --5.53027 -0.62858 -1.28395 --5.9256 -0.665924 -1.30815 --6.36076 -0.706004 -1.33234 --6.86481 -0.753588 -1.36356 --7.51471 -0.817916 -1.42181 --8.26396 -0.891369 -1.48571 --9.01869 -0.961383 -1.52438 --9.93169 -1.04542 -1.5766 --9.70782 -0.983065 -1.33266 --12.4992 -1.28868 -1.74398 --9.62505 -0.904483 -0.946033 --15.4036 -1.53733 -1.79277 --17.605 -1.73117 -1.86201 --43.4264 -4.05335 -2.91007 --44.0168 -3.9698 -2.18916 --11.0034 -0.181131 3.61067 --10.3861 -0.119164 3.66929 --10.1282 -0.073899 3.80049 --10.7354 -0.057022 4.16466 --8.12216 0.0541526 3.59775 --8.03043 0.0861959 3.73015 --8.16354 0.113574 3.93617 --8.1987 0.143444 4.11419 --8.09861 0.175296 4.24551 --8.02415 0.207803 4.38485 --7.91934 0.239576 4.51129 --7.59277 0.271729 4.53977 --7.31333 0.301975 4.57873 --6.85365 0.329011 4.52372 --7.527 0.363992 5.01259 --10.0882 0.427089 6.50736 --6.32964 0.408203 4.71601 --5.82892 0.425647 4.58779 --6.06968 0.458013 4.87163 --6.07121 0.485941 5.02474 --6.10304 0.515524 5.2003 --6.06288 0.543852 5.33422 --5.93029 0.567949 5.40618 --5.72254 0.58828 5.42313 --6.1139 0.638254 5.87032 --5.97289 0.661939 5.94024 --6.64119 0.736528 6.64133 --6.73759 0.779249 6.91961 --6.15998 0.776352 6.64331 --5.97167 0.797657 6.6772 --6.10948 0.846234 7.0001 --6.12202 0.885597 7.22052 --6.63033 0.97341 7.92829 --6.83313 1.03909 8.37252 --6.63473 1.06474 8.42426 --6.51226 1.09757 8.55158 --6.44648 1.13887 8.74317 --6.26596 1.16518 8.80711 --6.65492 1.26867 9.54562 --5.70782 1.18832 8.68373 --5.56065 1.21737 8.7717 --5.38267 1.24053 8.81735 --3.76772 1.01857 6.89018 --3.46439 1.0052 6.6764 --3.46506 1.04351 6.89075 --3.72143 1.13586 7.50597 --2.78182 0.984749 6.26356 --2.69469 1.00352 6.32646 --3.15073 1.14997 7.32369 --2.8369 1.11956 7.02007 --1.35818 0.780367 4.51171 --1.27895 0.786041 4.50708 --1.20843 0.794059 4.51855 --2.03791 1.07861 6.43973 --2.32426 1.21885 7.33115 --1.9484 1.14447 6.75788 --1.79863 1.14239 6.67854 --2.12862 1.32606 7.82353 --1.86855 1.28498 7.48523 --1.77761 1.31127 7.58896 --0.933181 0.980668 5.40782 --0.546982 0.832326 4.42946 --0.469996 0.831189 4.3893 --1.09893 1.24832 6.9412 --0.937291 1.22463 6.73637 --0.791553 1.20481 6.56668 --0.67066 1.19902 6.48058 --0.5133 1.15836 6.1888 --0.403419 1.15101 6.09719 --0.330001 1.17686 6.20825 --0.30029 1.26105 6.64968 --0.219183 1.29687 6.80788 --0.0840256 1.25195 6.50452 --2.75547 -0.269419 -1.14097 --2.8602 -0.273134 -1.12697 --3.00866 -0.282397 -1.13624 --3.19118 -0.295985 -1.16147 --3.35066 -0.305739 -1.16601 --3.53738 -0.318102 -1.18021 --3.72671 -0.329645 -1.18852 --3.94245 -0.343596 -1.20453 --4.1881 -0.360838 -1.22654 --4.42613 -0.374376 -1.2368 --4.7123 -0.393276 -1.2595 --5.01851 -0.413183 -1.28059 --5.37315 -0.437551 -1.31014 --5.749 -0.462051 -1.33528 --6.15611 -0.486808 -1.35848 --6.64077 -0.519027 -1.39378 --7.21422 -0.55785 -1.44038 --7.84828 -0.599184 -1.48537 --8.61151 -0.649284 -1.54459 --9.32089 -0.689526 -1.56286 --10.3238 -0.754127 -1.62884 --11.6442 -0.842314 -1.73186 --13.3209 -0.953311 -1.86408 --15.1528 -1.06816 -1.96722 --16.6207 -1.14075 -1.94331 --19.5497 -1.32218 -2.09761 --59.6425 -3.416 -2.07505 --10.6845 0.133541 3.37577 --10.3996 0.173177 3.51211 --10.3263 0.209093 3.6918 --10.4343 0.244892 3.91785 --10.5952 0.281305 4.16458 --10.5782 0.317835 4.36615 --8.07101 0.341897 3.77442 --7.98514 0.371429 3.90798 --10.119 0.427084 4.83372 --10.1641 0.465739 5.05743 --10.0098 0.500445 5.20642 --8.29311 0.498871 4.7017 --8.64089 0.540075 5.032 --7.63303 0.543798 4.75964 --6.67501 0.541863 4.47138 --6.73887 0.571886 4.65637 --6.54197 0.592099 4.71047 --7.84686 0.679635 5.57461 --7.34906 0.689125 5.48055 --7.86427 0.749942 5.96376 --6.41462 0.700108 5.272 --6.12923 0.712164 5.2557 --6.07969 0.738232 5.38486 --6.09343 0.769274 5.55866 --6.32232 0.817072 5.89058 --5.99545 0.823052 5.82867 --6.61565 0.908621 6.47804 --7.37264 1.01322 7.27358 --7.51678 1.06738 7.61582 --7.37741 1.09585 7.73222 --6.2187 1.01437 6.9506 --6.10657 1.04029 7.05753 --6.17395 1.08685 7.3333 --6.96706 1.22527 8.32984 --6.66994 1.23294 8.28611 --6.52863 1.25995 8.3927 --6.40477 1.28901 8.51871 --6.19988 1.30635 8.55329 --1.37958 0.593284 3.22424 --5.78535 1.33646 8.60102 --5.58257 1.35035 8.62152 --5.47288 1.38032 8.75521 --7.03728 1.72925 11.1322 --5.58115 1.50709 9.48542 --3.42735 1.11538 6.6996 --3.34315 1.13641 6.79014 --3.66614 1.24989 7.51383 --3.48893 1.25404 7.48211 --3.13578 1.21183 7.14832 --2.96344 1.21106 7.09719 --2.86645 1.2299 7.17222 --1.33061 0.829727 4.51917 --1.25965 0.835802 4.53192 --1.17187 0.836307 4.50751 --2.66198 1.37264 7.89714 --2.01808 1.2006 6.76283 --1.91716 1.21361 6.80431 --1.01162 0.903895 4.83239 --0.93703 0.908804 4.83879 --1.8525 1.36003 7.59776 --0.961153 1.00034 5.35268 --0.565876 0.844424 4.37906 --0.537625 0.867852 4.50046 --0.450506 0.858388 4.42213 --1.13736 1.34125 7.28256 --0.842222 1.22367 6.55145 --0.731471 1.22335 6.51506 --0.587853 1.19407 6.31241 --0.436623 1.14838 6.01946 --0.353613 1.16104 6.06318 --0.358113 1.27432 6.69017 --0.255133 1.27894 6.68354 --0.154194 1.28371 6.68526 --0.0434935 1.2716 6.58687 --2.70593 -0.170946 -1.16435 --2.81155 -0.170732 -1.15274 --2.94222 -0.174305 -1.15386 --3.09089 -0.178997 -1.16161 --3.27559 -0.187497 -1.18517 --3.45281 -0.193529 -1.19804 --3.62275 -0.1982 -1.2007 --3.82988 -0.205847 -1.21656 --4.06544 -0.215229 -1.23929 --4.32157 -0.225021 -1.26325 --4.57951 -0.233704 -1.27897 --4.86612 -0.24342 -1.29843 --5.2018 -0.256672 -1.32775 --5.56739 -0.269905 -1.35723 --5.95424 -0.283161 -1.38183 --6.40058 -0.298958 -1.41377 --6.90663 -0.316659 -1.45025 --7.50111 -0.33873 -1.49695 --8.18632 -0.363709 -1.54955 --9.00019 -0.393986 -1.61424 --9.90554 -0.42482 -1.67442 --11.1267 -0.471756 -1.77926 --12.3443 -0.510574 -1.84064 --14.1544 -0.57675 -1.98203 --15.8351 -0.624317 -2.03606 --15.8003 -0.570411 -1.73953 --16.1339 -0.536272 -1.50237 --56.2332 -1.83225 -3.6657 --23.8473 -0.467687 -0.1392 --23.8363 -0.39182 0.28031 --9.95282 0.454767 3.26039 --10.0104 0.489808 3.46188 --10.0537 0.524537 3.6638 --9.51332 0.54586 3.71311 --9.5997 0.581382 3.92304 --9.60566 0.614998 4.11349 --9.64492 0.650192 4.31734 --12.0069 0.776053 5.31908 --10.4359 0.753066 4.99305 --9.93494 0.768294 5.01655 --8.65814 0.742784 4.71182 --8.62921 0.774438 4.88383 --7.94829 0.770073 4.76954 --7.41966 0.769701 4.70026 --7.12849 0.780852 4.72703 --6.80497 0.787867 4.72694 --6.76484 0.814026 4.86556 --7.08185 0.866503 5.20085 --6.87712 0.880821 5.25614 --7.63337 0.974139 5.87656 --7.30999 0.980542 5.86827 --6.41845 0.932129 5.4842 --6.446 0.965703 5.67398 --4.92206 0.842656 4.79399 --6.52153 1.03684 6.08379 --6.12773 1.02644 5.97733 --6.48937 1.10104 6.4369 --7.37256 1.24134 7.33986 --7.32971 1.27662 7.5308 --7.22912 1.3051 7.67689 --6.18812 1.20594 6.98855 --7.34809 1.40775 8.26785 --7.10432 1.41736 8.29134 --6.84743 1.42377 8.29485 --6.67015 1.4416 8.36971 --1.51006 0.62994 3.16903 --1.4656 0.63602 3.19574 --1.42697 0.642811 3.22905 --1.36298 0.644279 3.23153 --5.7195 1.50742 8.61727 --6.45872 1.70611 9.82696 --7.13988 1.90794 11.0401 --7.0443 1.95311 11.2809 --3.15946 1.1325 6.19527 --3.04566 1.14079 6.22429 --2.95332 1.15343 6.28412 --3.025 1.20866 6.60161 --2.9977 1.24088 6.77943 --2.94082 1.26648 6.91511 --2.96276 1.31676 7.19723 --2.9191 1.3496 7.37737 --1.30631 0.878574 4.53544 --1.19589 0.868801 4.46827 --2.07497 1.20865 6.48027 --2.6175 1.45615 7.93741 --1.92754 1.24688 6.67361 --2.405 1.49425 8.12174 --0.987238 0.943988 4.85722 --0.922892 0.95089 4.8914 --1.00399 1.03011 5.34369 --0.915803 1.02981 5.3311 --0.546942 0.873918 4.41215 --0.478554 0.873567 4.40099 --1.36286 1.47509 7.88136 --0.967388 1.29602 6.83179 --0.797315 1.25371 6.56754 --0.678035 1.24221 6.49248 --0.493176 1.17113 6.06664 --0.414524 1.18595 6.1409 --0.301565 1.16638 6.01939 --0.308415 1.28723 6.69528 --0.18825 1.26443 6.5516 --0.0958889 1.27703 6.61124 --2.75171 -0.0695933 -1.17123 --2.8646 -0.0674538 -1.16409 --3.01313 -0.0686086 -1.17489 --3.17063 -0.0687786 -1.18659 --3.34743 -0.0704753 -1.20338 --3.52584 -0.0716779 -1.21466 --3.72319 -0.0722185 -1.23016 --3.94024 -0.074754 -1.24843 --4.17637 -0.0761658 -1.26889 --4.43309 -0.0779444 -1.29039 --4.70952 -0.0800632 -1.31174 --4.98853 -0.0797742 -1.32457 --5.36222 -0.0850723 -1.36601 --5.74773 -0.0878196 -1.39915 --6.16452 -0.0907575 -1.43005 --6.62221 -0.0919326 -1.4608 --7.1767 -0.0966189 -1.50763 --7.79301 -0.100619 -1.55408 --8.54657 -0.106074 -1.61957 --9.4012 -0.111941 -1.68623 --10.474 -0.120632 -1.779 --11.5821 -0.122996 -1.84282 --13.1831 -0.135379 -1.97656 --15.0367 -0.144145 -2.10589 --17.4001 -0.155573 -2.26447 --16.2128 -0.07291 -1.7492 --16.0628 0.0327033 -1.14176 --10.5213 0.72532 3.02917 --10.0823 0.742161 3.13845 --9.96472 0.76932 3.30348 --9.94224 0.80192 3.48754 --9.79989 0.828154 3.64229 --9.4632 0.842882 3.74073 --9.39483 0.871776 3.90602 --9.151 0.889004 4.01702 --9.18174 0.924103 4.21033 --9.19925 0.957802 4.40257 --9.98178 1.04644 4.87777 --9.95835 1.08159 5.0753 --11.0772 1.2064 5.73849 --10.9825 1.24007 5.93293 --8.29041 1.05028 4.96683 --8.26484 1.08058 5.13848 --6.87414 0.983536 4.64522 --6.61366 0.986504 4.67186 --6.3201 0.98417 4.67196 --6.34146 1.01321 4.83711 --6.77283 1.08771 5.2433 --7.2681 1.17407 5.71133 --6.55992 1.12381 5.45391 --6.80587 1.18328 5.78624 --6.66285 1.1972 5.87228 --4.97872 1.01052 4.87695 --4.82157 1.01446 4.90637 --7.18895 1.37031 6.83329 --7.32756 1.42817 7.15434 --7.61153 1.50938 7.60689 --3.30184 0.884089 4.22929 --6.1524 1.36088 6.82064 --6.43952 1.44454 7.28628 --7.08262 1.59369 8.10841 --6.69936 1.57073 7.98961 --6.6381 1.60255 8.17571 --1.54318 0.682815 3.15637 --1.50585 0.689177 3.19112 --1.45402 0.691949 3.21069 --1.39523 0.693312 3.22165 --1.32477 0.691512 3.21611 --4.30757 1.37483 6.9797 --4.1768 1.38338 7.03027 --1.70069 0.826178 3.96345 --1.6366 0.829465 3.98496 --1.50446 0.814396 3.90806 --1.39831 0.805443 3.86001 --1.32601 0.805196 3.85908 --1.25006 0.802018 3.8484 --2.97345 1.34017 6.83621 --1.40049 0.890526 4.34368 --1.33656 0.894296 4.36733 --1.27731 0.899712 4.39838 --1.15997 0.883631 4.31413 --1.16168 0.910432 4.46666 --2.3137 1.38356 7.10931 --1.14307 0.961704 4.7564 --1.07652 0.965708 4.7843 --1.01755 0.973032 4.82929 --0.957309 0.980874 4.87322 --0.928864 1.00416 5.00936 --0.97592 1.06931 5.37876 --0.598003 0.90591 4.46485 --0.522445 0.90016 4.43622 --0.454485 0.897774 4.42486 --1.1548 1.41395 7.32847 --0.879505 1.29867 6.68612 --0.735261 1.26778 6.51698 --0.580035 1.22175 6.2576 --0.43956 1.17944 6.02384 --0.344936 1.17428 6.0006 --0.303657 1.23156 6.32614 --0.238663 1.27113 6.55404 --0.15934 1.30008 6.7226 --0.0437696 1.27471 6.58635 --2.80202 0.0319119 -1.18279 --2.9318 0.0362104 -1.18541 --3.0803 0.0405558 -1.19499 --3.25671 0.0432826 -1.21533 --3.42464 0.0481294 -1.22544 --3.62156 0.0519246 -1.24487 --3.83675 0.0554128 -1.26734 --4.03678 0.061521 -1.27427 --4.30123 0.0659333 -1.30556 --4.55857 0.0722345 -1.3243 --4.85499 0.0791674 -1.35124 --5.15355 0.0865436 -1.36846 --5.53699 0.0931382 -1.40983 --5.93325 0.102587 -1.44261 --6.37934 0.113019 -1.47954 --6.90343 0.123607 -1.52786 --7.45998 0.136555 -1.56813 --8.12576 0.151548 -1.62266 --8.94809 0.16917 -1.69962 --9.85318 0.18982 -1.76966 --10.9952 0.214914 -1.86832 --12.28 0.246298 -1.96043 --14.0892 0.285125 -2.12135 --16.0837 0.335446 -2.25592 --16.403 0.388163 -2.0184 --16.3345 0.438748 -1.70782 --10.719 1.03256 2.91113 --10.3391 1.04094 3.04074 --10.4082 1.07922 3.24917 --10.5901 1.12722 3.48617 --10.0884 1.12285 3.56811 --9.65425 1.1217 3.65078 --9.48103 1.13939 3.79105 --9.52467 1.17588 3.9909 --9.4983 1.20592 4.17233 --9.18538 1.20947 4.25939 --9.10683 1.23472 4.41927 --10.8457 1.44255 5.25362 --10.9905 1.49702 5.53571 --10.6133 1.4961 5.61223 --10.4473 1.51766 5.76764 --9.10136 1.40227 5.38578 --7.58447 1.25663 4.86982 --6.38363 1.13958 4.44844 --6.1978 1.14262 4.50282 --6.26595 1.17706 4.68875 --6.64098 1.25417 5.05322 --5.6248 1.14246 4.62438 --6.93367 1.35321 5.56606 --6.95211 1.38699 5.7576 --5.20103 1.15475 4.78978 --5.31291 1.19782 5.0107 --4.92561 1.1623 4.88682 --4.92805 1.18694 5.03309 --4.93493 1.21413 5.18638 --7.50994 1.6885 7.37583 --3.29712 0.974423 4.15363 --3.1959 0.975875 4.18027 --6.35746 1.59397 7.0762 --6.13899 1.58872 7.09407 --6.69143 1.73706 7.83319 --6.65475 1.77183 8.03961 --4.36769 1.32921 5.97336 --3.84225 1.24529 5.59872 --1.46539 0.738366 3.17768 --1.40023 0.736746 3.18187 --1.3814 0.74561 3.23698 --1.30449 0.740584 3.2236 --1.25258 0.741461 3.23919 --1.27318 0.760648 3.34762 --1.22022 0.761067 3.36227 --1.62044 0.888485 4.01014 --1.46683 0.863364 3.90031 --1.38343 0.858336 3.88454 --1.27893 0.845045 3.83385 --1.09501 0.805633 3.64574 --0.953495 0.77741 3.51156 --1.38481 0.943107 4.37779 --1.32035 0.944671 4.40157 --1.20161 0.926477 4.31893 --0.972103 0.863116 4.00394 --1.13099 0.95062 4.47415 --1.19125 1.00408 4.7714 --1.12116 1.00553 4.7912 --1.05025 1.00552 4.81006 --0.990515 1.01157 4.85487 --0.915344 1.01017 4.86192 --0.854474 1.01549 4.90462 --0.936773 1.10109 5.38622 --0.854203 1.09964 5.39177 --0.481099 0.914663 4.40354 --0.936981 1.26137 6.31087 --1.07853 1.43152 7.26111 --0.794636 1.29775 6.54998 --0.726076 1.32272 6.70672 --0.489147 1.19863 6.04192 --0.41984 1.21756 6.16533 --0.300812 1.18548 6.00598 --0.302809 1.29812 6.65315 --0.178004 1.26003 6.46156 --0.107745 1.30208 6.71787 --2.75209 0.129198 -1.21143 --2.86554 0.137587 -1.20522 --3.01297 0.145343 -1.21734 --3.1629 0.153589 -1.22503 --3.34698 0.161729 -1.2487 --3.51687 0.172682 -1.25705 --3.72249 0.182281 -1.27916 --3.92957 0.193567 -1.29487 --4.17451 0.204523 -1.32197 --4.42197 0.217667 -1.34152 --4.67969 0.233021 -1.35761 --5.00412 0.248187 -1.39353 --5.34024 0.265508 -1.4229 --5.71576 0.284427 -1.45617 --6.15028 0.306554 -1.49888 --6.62454 0.331334 -1.54084 --7.15063 0.35938 -1.58339 --7.78437 0.390765 -1.64221 --8.50785 0.428569 -1.7064 --9.36053 0.47287 -1.78219 --10.373 0.524764 -1.87046 --11.6133 0.58873 -1.98029 --13.1236 0.667337 -2.10902 --14.7189 0.758437 -2.20322 --17.3713 0.893257 -2.44802 --19.0397 1.00868 -2.42611 --18.9856 1.06555 -2.07197 --12.0872 1.50267 3.19302 --11.8494 1.51784 3.37311 --11.2974 1.49911 3.48137 --10.726 1.4761 3.56686 --10.1946 1.45367 3.64286 --9.8657 1.44996 3.75454 --8.15823 1.28799 3.46873 --9.23598 1.44254 3.95454 --9.33271 1.48615 4.17082 --9.07627 1.48601 4.27393 --8.88502 1.49365 4.39243 --12.5842 2.05496 6.23509 --9.15316 1.66091 5.26862 --6.22787 1.27105 4.12836 --6.55558 1.34423 4.42909 --6.28027 1.32852 4.4442 --6.85879 1.44494 4.89688 --5.9799 1.33211 4.58233 --5.82001 1.33181 4.64026 --7.75503 1.68183 5.93586 --7.61513 1.69129 6.04735 --5.50943 1.3539 4.89503 --5.25783 1.33427 4.87811 --5.09067 1.32888 4.90998 --5.00341 1.33753 4.99522 --4.9876 1.35979 5.13157 --7.05416 1.79583 6.88239 --6.90247 1.80178 6.97581 --3.21041 1.0699 4.12475 --3.11753 1.06924 4.15659 --3.02448 1.0681 4.18629 --5.84411 1.71956 6.90681 --4.5623 1.46114 5.89042 --4.4542 1.46501 5.95721 --4.39267 1.48074 6.07111 --1.42731 0.77465 3.0941 --1.42416 0.786257 3.16397 --1.41788 0.798236 3.2343 --1.3147 0.783914 3.19229 --1.33228 0.802707 3.2923 --1.2915 0.804497 3.32433 --1.25709 0.809248 3.36303 --1.17463 0.799339 3.3378 --1.17856 0.815502 3.4313 --1.42746 0.910863 3.89262 --1.32827 0.897732 3.85158 --1.2156 0.878738 3.78317 --1.0289 0.832413 3.58531 --0.939248 0.817663 3.53519 --0.932979 0.833445 3.62892 --1.09476 0.914612 4.04484 --0.965302 0.88571 3.92338 --1.17148 0.994356 4.47956 --1.1024 0.99112 4.49078 --1.16029 1.04617 4.78836 --1.09372 1.04617 4.81727 --1.02202 1.04484 4.83576 --1.03917 1.08774 5.0829 --0.876685 1.03903 4.85982 --0.938846 1.1123 5.26553 --1.56764 1.53235 7.482 --0.526198 0.945527 4.44779 --1.31132 1.51099 7.4573 --0.84621 1.25844 6.15692 --0.888641 1.35841 6.72509 --0.755403 1.32894 6.60538 --0.582532 1.25981 6.27092 --0.482206 1.24976 6.25116 --0.244734 1.09197 5.41434 --0.324072 1.27473 6.45918 --0.23037 1.27432 6.49319 --0.159192 1.30919 6.72107 --0.0440456 1.27782 6.58584 --2.81264 0.234053 -1.23427 --2.9179 0.246043 -1.22118 --3.08275 0.25823 -1.2429 --3.2576 0.271814 -1.26475 --3.41773 0.286028 -1.27105 --3.61308 0.300659 -1.29209 --3.81082 0.317105 -1.30725 --4.03604 0.3356 -1.33015 --4.28157 0.354569 -1.35479 --4.53834 0.375965 -1.37607 --4.82403 0.399442 -1.40163 --5.14869 0.424854 -1.43403 --5.50327 0.454284 -1.4676 --5.89829 0.485747 -1.50424 --6.3237 0.521001 -1.53865 --6.84636 0.562597 -1.59284 --7.4198 0.608657 -1.64566 --8.10993 0.663237 -1.71577 --8.88169 0.726426 -1.7862 --9.80296 0.800541 -1.87116 --10.8829 0.888816 -1.966 --12.2689 1.00003 -2.09808 --13.9443 1.13634 -2.24741 --16.0673 1.3101 -2.43176 --18.4151 1.51131 -2.58519 --11.9218 1.82287 2.99899 --11.7739 1.84162 3.19521 --11.7797 1.87963 3.41716 --11.5482 1.88562 3.59094 --8.3573 1.49155 3.07725 --8.2506 1.50497 3.21374 --8.31351 1.54106 3.39363 --8.15416 1.5454 3.51379 --7.70908 1.50724 3.54251 --9.01754 1.7315 4.12418 --4.01639 1.00684 2.67999 --9.10531 1.87311 4.91497 --6.66786 1.49697 4.07868 --6.52982 1.49888 4.16676 --6.0602 1.44155 4.09689 --5.99367 1.45409 4.20643 --6.79767 1.62385 4.75833 --5.936 1.491 4.46348 --5.89822 1.50882 4.58952 --5.7223 1.50015 4.63634 --5.67298 1.51461 4.75486 --5.7141 1.54849 4.92988 --5.82452 1.59653 5.15627 --6.25517 1.71402 5.60841 --4.46326 1.35955 4.52569 --5.3696 1.58071 5.31965 --4.15389 1.33632 4.56046 --6.81492 1.96546 6.78019 --3.29893 1.18148 4.1313 --3.21249 1.18007 4.17208 --3.05947 1.16126 4.15278 --3.01065 1.16859 4.22116 --4.62309 1.5972 5.85053 --4.4794 1.58971 5.88482 --4.42055 1.6031 5.99946 --4.28331 1.59551 6.03565 --4.03302 1.55684 5.94565 --2.75384 1.2222 4.69033 --1.33034 0.830099 3.16825 --3.51297 1.49443 5.87607 --2.49265 1.21293 4.78044 --3.73332 1.62534 6.52771 --1.22025 0.850015 3.35533 --1.20214 0.8594 3.41716 --1.44414 0.956409 3.8592 --1.22431 0.898438 3.63971 --1.13636 0.883865 3.60361 --1.07497 0.878843 3.60716 --1.00396 0.86974 3.59241 --0.929025 0.858614 3.56751 --0.88382 0.857874 3.59263 --1.0017 0.925647 3.93056 --0.958873 0.929385 3.97443 --0.918841 0.934491 4.02663 --2.53357 1.71105 7.72636 --1.1204 1.08131 4.78761 --1.04561 1.07546 4.7981 --0.989679 1.07925 4.85281 --0.918315 1.0756 4.86984 --0.873484 1.08627 4.95968 --0.94262 1.16813 5.40353 --1.54789 1.59906 7.62454 --2.44499 2.2746 11.1324 --0.907448 1.29861 6.2065 --0.821244 1.29793 6.25049 --0.800855 1.35181 6.58028 --0.689878 1.33503 6.54587 --0.52171 1.26261 6.21016 --0.407562 1.23306 6.10272 --0.322443 1.23294 6.14814 --0.282015 1.29036 6.51388 --0.173777 1.26616 6.43027 --0.100578 1.29535 6.64838 --2.99283 0.359875 -1.2534 --3.15793 0.376743 -1.2731 --3.33278 0.395959 -1.29314 --3.50156 0.415823 -1.3028 --3.68902 0.437257 -1.31709 --3.91258 0.460736 -1.34439 --4.13862 0.486271 -1.36473 --4.39345 0.51347 -1.3912 --4.65931 0.544157 -1.41403 --4.96286 0.577317 -1.44465 --5.29722 0.614468 -1.47764 --5.67052 0.655165 -1.51474 --6.08365 0.701013 -1.55433 --6.54671 0.752108 -1.5979 --7.08796 0.811818 -1.65284 --7.72745 0.881461 -1.72156 --8.42743 0.959462 -1.7868 --9.27547 1.05231 -1.87125 --10.2631 1.16213 -1.9647 --11.4676 1.29595 -2.08003 --12.9591 1.46064 -2.22228 --14.827 1.66886 -2.39674 --17.0064 1.91577 -2.56944 --11.7143 2.20675 3.24331 --9.11057 1.82798 2.94782 --9.30382 1.88841 3.16534 --8.79098 1.83361 3.22518 --8.27884 1.77545 3.26804 --7.70241 1.70351 3.27563 --7.49778 1.69369 3.37152 --4.09216 1.1127 2.46645 --3.96142 1.10453 2.51236 --3.96101 1.1184 2.60002 --6.97038 1.69834 3.80128 --6.91848 1.71253 3.93177 --6.8362 1.72191 4.04998 --6.96031 1.77121 4.25594 --6.98991 1.80344 4.42664 --6.04689 1.63751 4.14048 --6.10381 1.6724 4.31164 --6.10435 1.69672 4.45864 --5.86724 1.67088 4.4806 --5.98378 1.72071 4.69307 --5.90785 1.72859 4.80159 --5.75453 1.71898 4.86246 --5.69295 1.73062 4.97698 --5.61994 1.73921 5.08542 --4.32478 1.45461 4.35398 --4.18463 1.44134 4.3815 --3.6584 1.33115 4.11933 --3.5325 1.3186 4.13833 --6.90286 2.20744 6.93988 --6.7878 2.21396 7.06323 --3.15067 1.27551 4.16901 --6.13445 2.10912 6.93319 --2.78448 1.2113 4.06401 --3.07663 1.31287 4.45287 --3.62781 1.49258 5.12178 --4.12892 1.66561 5.78288 --4.17068 1.70624 5.99982 --3.8442 1.63554 5.82106 --2.64735 1.2876 4.63127 --2.61416 1.29862 4.72408 --2.56645 1.30603 4.80161 --2.45054 1.28941 4.79416 --3.31143 1.60997 6.07108 --3.15259 1.58484 6.04346 --1.16474 0.897851 3.4091 --1.18746 0.922402 3.5358 --1.13831 0.918927 3.55751 --1.09264 0.917833 3.58655 --1.02214 0.906959 3.57278 --1.04074 0.932631 3.70981 --0.91232 0.896253 3.5916 --0.89383 0.906599 3.66866 --1.00723 0.976675 4.00785 --0.967491 0.981005 4.06102 --2.55985 1.77294 7.63354 --1.13702 1.11439 4.73974 --1.08262 1.11677 4.79598 --1.00825 1.10886 4.80619 --0.952499 1.11154 4.86041 --1.06101 1.20959 5.37579 --0.984052 1.20471 5.4037 --1.62583 1.661 7.673 --0.516726 0.983029 4.42204 --0.465527 0.98423 4.46875 --0.879162 1.33848 6.29067 --0.837146 1.37158 6.52582 --0.731505 1.35615 6.51179 --0.628618 1.34195 6.5055 --0.441548 1.24173 6.04313 --0.219385 1.08629 5.27535 --0.169343 1.10989 5.45404 --0.230751 1.29063 6.50047 --0.149395 1.30387 6.64128 --0.0416598 1.27726 6.56569 --3.43931 0.525895 -1.34122 --3.59106 0.550425 -1.33843 --3.76893 0.577302 -1.34542 --4.00173 0.608835 -1.37533 --4.23703 0.642489 -1.39799 --4.49127 0.678505 -1.42178 --4.78365 0.718981 -1.45445 --5.09711 0.762818 -1.48596 --5.42201 0.809741 -1.5112 --5.84033 0.866835 -1.56358 --6.26283 0.926764 -1.60222 --6.77168 0.997187 -1.65799 --7.33132 1.07607 -1.71338 --7.99839 1.16888 -1.78445 --8.77427 1.27703 -1.86596 --9.69735 1.40578 -1.96329 --10.7314 1.55199 -2.05834 --12.0104 1.73238 -2.18008 --13.6635 1.96475 -2.34615 --15.7892 2.26378 -2.55818 --38.1158 5.5197 -4.0417 --45.3482 6.62975 -4.18631 --9.29906 2.09775 2.68043 --11.3432 2.50879 3.2379 --10.267 2.33918 3.23498 --8.41881 2.01563 3.02235 --8.17879 1.99532 3.13024 --7.79518 1.94587 3.19322 --7.54438 1.92074 3.28058 --3.9927 1.21769 2.37706 --3.92976 1.21808 2.44405 --8.06519 2.10647 3.92358 --8.19428 2.16225 4.13963 --7.39259 2.01595 4.01232 --6.82567 1.91684 3.94845 --6.84342 1.94475 4.10745 --6.89246 1.98086 4.28374 --6.67184 1.95568 4.33989 --6.55672 1.95431 4.44046 --6.82505 2.04341 4.73184 --5.81319 1.82563 4.36405 --5.72586 1.82725 4.46106 --6.08604 1.94129 4.81356 --6.302 2.02159 5.09973 --6.13582 2.00609 5.16279 --4.23934 1.53585 4.10291 --4.19845 1.5453 4.19736 --3.83633 1.46757 4.06787 --3.05387 1.2716 3.61721 --3.51374 1.41571 4.06147 --3.0357 1.29909 3.8019 --2.94677 1.28997 3.83381 --2.93377 1.30274 3.92615 --2.9101 1.31371 4.0124 --2.84231 1.3109 4.05961 --2.894 1.34416 4.21898 --2.94836 1.38004 4.38784 --2.90188 1.3851 4.46273 --2.75269 1.35638 4.43161 --3.67852 1.68453 5.55601 --2.77873 1.40655 4.71334 --2.62315 1.3754 4.66803 --2.60819 1.39146 4.78362 --2.54026 1.38929 4.83913 --1.25041 0.939408 3.30946 --1.19787 0.933815 3.32502 --1.57225 1.09102 3.93458 --1.531 1.09289 3.98781 --1.17594 0.969414 3.56849 --1.09387 0.951772 3.54097 --1.1316 0.984136 3.70261 --1.16242 1.0163 3.86646 --1.04055 0.980548 3.76879 --0.926873 0.947861 3.6761 --0.992498 0.997622 3.91869 --2.59767 1.79552 7.28169 --0.947857 1.01898 4.09533 --0.946069 1.04168 4.23732 --1.12198 1.16149 4.80238 --1.03688 1.14551 4.78653 --0.948774 1.12757 4.75973 --0.931095 1.15005 4.91457 --1.01058 1.23606 5.36606 --1.69629 1.72223 7.70161 --0.555112 1.01444 4.44652 --0.511626 1.02041 4.52221 --0.501505 1.05262 4.73021 --0.814477 1.34713 6.24245 --0.796704 1.39955 6.58234 --0.678697 1.37008 6.51032 --0.555487 1.33194 6.39767 --0.268807 1.11587 5.34373 --0.23109 1.15051 5.59127 --0.279048 1.30592 6.50123 --0.170265 1.27551 6.41876 --0.097499 1.29768 6.62784 --3.47198 0.658851 -1.34726 --3.65787 0.691121 -1.36316 --3.86228 0.726153 -1.3828 --4.0947 0.765485 -1.41013 --4.33832 0.807154 -1.43451 --4.61036 0.852677 -1.46413 --4.90295 0.903311 -1.49366 --5.23386 0.958955 -1.52965 --5.60374 1.02216 -1.57066 --6.00349 1.09089 -1.61061 --6.47171 1.16995 -1.66232 --6.9989 1.25942 -1.71913 --7.60362 1.36217 -1.78431 --8.31697 1.48371 -1.86336 --9.1379 1.62292 -1.9503 --10.0781 1.78423 -2.0428 --11.2524 1.98465 -2.16579 --12.6146 2.21884 -2.29466 --14.378 2.52079 -2.46997 --16.5852 2.90051 -2.67916 --37.3471 6.50026 -4.48075 --41.2346 7.25591 -4.30774 --13.4876 3.22018 2.94974 --9.51863 2.41895 2.58845 --8.91584 2.31932 2.66634 --8.64185 2.28677 2.78621 --8.56688 2.2968 2.93939 --8.23276 2.2499 3.03151 --8.12588 2.25093 3.16927 --8.69671 2.40837 3.48435 --8.61963 2.41912 3.63846 --3.90205 1.33439 2.37925 --4.92456 1.59242 2.79657 --4.8074 1.58152 2.86378 --4.74445 1.60015 3.05421 --4.59713 1.58011 3.10323 --4.51298 1.5761 3.17434 --6.65895 2.14828 4.2401 --6.42215 2.11035 4.2845 --4.42225 1.60356 3.45571 --6.42785 2.16149 4.59518 --6.29254 2.15 4.68125 --5.73346 2.02031 4.52646 --6.65095 2.3012 5.20999 --4.23989 1.64395 3.91913 --4.11249 1.62545 3.95685 --3.45854 1.45307 3.64373 --3.20173 1.39337 3.5716 --3.6388 1.5413 3.98041 --2.99883 1.36396 3.62162 --3.56771 1.55599 4.15651 --2.97161 1.38685 3.80001 --2.94381 1.39453 3.88042 --2.86271 1.3851 3.91665 --2.90476 1.4159 4.06054 --5.80246 2.4018 6.8359 --3.73597 1.73439 5.07915 --2.90994 1.47302 4.41082 --2.8965 1.48821 4.52043 --2.84754 1.49059 4.59549 --2.88159 1.52437 4.76325 --2.77611 1.50699 4.78018 --2.77714 1.53007 4.92064 --2.64699 1.50279 4.90412 --2.89006 1.62046 5.35837 --3.40519 1.85174 6.20253 --3.11775 1.76699 6.00564 --1.22385 1.01206 3.49896 --1.1857 1.01076 3.53828 --1.08818 0.98439 3.48715 --1.05438 0.985399 3.53241 --1.16053 1.04956 3.81118 --1.10217 1.04097 3.82436 --1.01003 1.01563 3.77681 --0.85662 0.960071 3.60611 --1.04844 1.07548 4.10056 --0.982395 1.06267 4.10252 --0.947841 1.06788 4.17402 --1.16446 1.21077 4.81697 --1.10502 1.20818 4.86536 --1.01578 1.18722 4.84056 --0.931934 1.16903 4.82265 --0.888297 1.17499 4.91367 --0.691633 1.08119 4.55963 --0.626167 1.07181 4.57238 --0.546907 1.05118 4.5372 --0.472361 1.03227 4.50982 --0.401324 1.01584 4.49014 --0.757676 1.3594 6.22253 --0.715999 1.39125 6.46647 --0.625592 1.38083 6.50907 --0.315088 1.14366 5.39198 --0.20921 1.09922 5.23331 --0.106604 1.05109 5.05293 --0.234488 1.31379 6.54687 --0.138636 1.29837 6.56171 --0.040242 1.27796 6.55556 --3.53624 0.796647 -1.37279 --3.73805 0.836514 -1.39642 --3.95169 0.8796 -1.41867 --4.20066 0.929022 -1.4526 --4.46185 0.98115 -1.48301 --4.70694 1.03182 -1.49616 --5.02542 1.09533 -1.53505 --5.39231 1.1678 -1.58358 --5.76131 1.24228 -1.61988 --6.18846 1.32802 -1.66633 --6.67302 1.42549 -1.71972 --7.25451 1.54122 -1.79082 --7.89516 1.6696 -1.86148 --8.66228 1.82241 -1.95026 --9.56593 2.00296 -2.05332 --10.5597 2.204 -2.15005 --11.7969 2.45386 -2.27696 --13.346 2.76659 -2.43812 --15.285 3.15809 -2.63471 --17.7808 3.66251 -2.88143 --38.0356 7.72022 -5.13721 --36.7052 7.56843 -4.25881 --12.8185 3.45622 2.68828 --11.9327 3.28161 2.80378 --12.1431 3.3678 3.06416 --9.47735 2.74894 2.82022 --9.33414 2.74268 2.97642 --9.46448 2.80411 3.18781 --4.12816 1.47415 2.12413 --3.94552 1.44171 2.16572 --3.89552 1.442 2.23702 --3.88992 1.45377 2.32071 --4.16045 1.53933 2.49102 --4.13208 1.54633 2.57389 --7.49227 2.47831 3.84733 --8.17272 2.69115 4.26303 --4.7409 1.76027 3.09572 --4.58516 1.7342 3.14096 --3.74728 1.51121 2.88473 --4.39866 1.71441 3.27352 --4.02448 1.62167 3.20259 --4.39034 1.74604 3.48666 --6.64792 2.44023 4.77928 --3.96663 1.65226 3.48009 --6.80007 2.5402 5.20113 --6.83891 2.57971 5.40096 --4.12184 1.75169 3.90071 --3.40298 1.54164 3.55447 --3.3725 1.54768 3.63524 --3.10357 1.47497 3.55031 --3.76922 1.71189 4.13024 --3.35746 1.59143 3.9402 --5.63424 2.38432 5.82768 --5.68261 2.42928 6.04746 --2.92217 1.49315 3.91557 --2.89168 1.49917 3.99625 --3.81285 1.84828 4.93844 --3.81241 1.87066 5.08236 --3.82967 1.89983 5.24799 --2.65064 1.48057 4.21494 --2.95445 1.61541 4.64897 --2.96159 1.63901 4.78968 --2.95926 1.66008 4.92448 --2.87678 1.64963 4.97266 --2.6516 1.58052 4.84778 --2.80754 1.66704 5.18501 --2.63875 1.62064 5.12245 --2.62919 1.64155 5.26512 --2.53209 1.62385 5.29074 --2.54929 1.65828 5.48181 --1.1608 1.05325 3.555 --1.11612 1.04848 3.58541 --1.13121 1.07166 3.71463 --1.14249 1.0942 3.84531 --1.13588 1.10938 3.95174 --0.872447 0.994983 3.58831 --1.04562 1.10363 4.03696 --1.16924 1.19125 4.42323 --1.1231 1.18961 4.48059 --0.953551 1.11991 4.27111 --2.21969 1.88375 7.37852 --0.950668 1.17057 4.59487 --0.979288 1.21767 4.85871 --0.831784 1.15595 4.66644 --0.765254 1.14379 4.68226 --0.658752 1.1038 4.57619 --0.587456 1.08703 4.57039 --0.482649 1.04461 4.44048 --0.48405 1.08332 4.68624 --0.401428 1.05627 4.62922 --0.752823 1.4143 6.42214 --0.695915 1.43265 6.61917 --0.317045 1.12908 5.20784 --0.247326 1.1192 5.24353 --0.168602 1.09791 5.21977 --0.0524201 1.02724 4.93171 --0.168683 1.28633 6.41705 --0.0936955 1.29782 6.59756 --3.26325 0.861396 -1.37787 --3.41178 0.897813 -1.37979 --3.60329 0.942647 -1.40264 --3.81336 0.990309 -1.42895 --4.03506 1.04225 -1.4536 --4.27542 1.09737 -1.48015 --4.54352 1.15927 -1.51226 --4.84162 1.22773 -1.54859 --5.16766 1.3036 -1.58765 --5.54289 1.38975 -1.63588 --5.9288 1.47935 -1.67521 --6.38199 1.58402 -1.72737 --6.90175 1.70429 -1.78893 --7.50837 1.84452 -1.86313 --8.21198 2.00651 -1.94833 --9.02324 2.1943 -2.04285 --9.97055 2.41335 -2.14923 --11.0827 2.67258 -2.26904 --12.4277 2.98604 -2.41074 --14.112 3.37825 -2.58831 --16.3097 3.88901 -2.82309 --38.4211 9.37535 -2.97855 --38.4588 9.49107 -2.28818 --11.7665 3.56273 2.40185 --11.7433 3.59104 2.62189 --11.726 3.62111 2.84324 --10.0377 3.19124 2.78837 --10.0566 3.22667 2.9872 --9.67466 3.15046 3.10667 --9.18809 3.04201 3.19064 --9.49979 3.15938 3.4499 --3.88681 1.56586 2.18081 --3.82629 1.56085 2.24926 --3.82065 1.57248 2.33236 --4.09773 1.66781 2.50646 --4.16009 1.7015 2.61971 --4.82525 1.91884 2.95381 --4.77944 1.92139 3.04618 --3.82237 1.6401 2.77293 --4.04558 1.72457 2.95905 --3.83362 1.67283 2.96288 --4.02338 1.74846 3.14639 --3.92327 1.73131 3.19853 --3.73783 1.68645 3.20387 --3.96801 1.77783 3.42511 --3.90673 1.77324 3.4965 --3.99355 1.81889 3.65343 --4.11793 1.87875 3.839 --3.78226 1.77992 3.74335 --3.33939 1.64212 3.56262 --3.21361 1.61311 3.57813 --3.18317 1.61761 3.65648 --4.40125 2.0758 4.6583 --4.41933 2.10365 4.81153 --4.38117 2.11139 4.92487 --4.31042 2.10804 5.01354 --4.07836 2.04226 4.96356 --3.97868 2.0264 5.02144 --4.09025 2.09249 5.27265 --3.04081 1.701 4.42636 --2.83021 1.63551 4.34203 --2.67011 1.58912 4.29957 --2.67731 1.61017 4.42791 --2.93316 1.73716 4.83583 --3.01163 1.79167 5.0657 --2.92676 1.77883 5.11532 --2.78719 1.74127 5.09597 --1.24898 1.07794 3.27982 --1.37206 1.14623 3.52793 --1.32146 1.13819 3.55469 --1.28293 1.13514 3.59617 --2.77243 1.86339 5.91533 --1.2021 1.1268 3.67788 --1.24205 1.1638 3.8491 --1.19307 1.15627 3.88149 --1.06021 1.10655 3.77012 --0.933158 1.05644 3.65501 --0.829129 1.01728 3.57026 --1.04588 1.15563 4.11513 --1.01307 1.15841 4.18798 --1.06711 1.21345 4.4547 --0.992331 1.19367 4.44871 --0.977601 1.21087 4.58469 --0.919187 1.20198 4.62178 --0.877258 1.20433 4.70352 --0.809319 1.19002 4.72076 --0.717276 1.1583 4.66262 --0.68689 1.17053 4.78835 --0.499179 1.06332 4.39945 --0.466918 1.0726 4.51314 --0.477438 1.12033 4.80676 --0.747726 1.40484 6.21537 --0.706986 1.43287 6.46001 --0.636758 1.437 6.59937 --0.237958 1.09101 5.00226 --0.207464 1.12015 5.24002 --0.096129 1.05584 5.00217 --0.22161 1.31292 6.46683 --0.14449 1.319 6.62888 --0.0412355 1.28325 6.56467 --2.69197 0.83388 -1.32437 --2.81868 0.867981 -1.33164 --2.97037 0.907663 -1.35201 --3.12338 0.948636 -1.36773 --3.30274 0.994894 -1.39452 --3.49192 1.0437 -1.42076 --3.6835 1.09434 -1.44102 --3.89317 1.14976 -1.46495 --4.13987 1.21291 -1.50088 --4.38814 1.27811 -1.52886 --4.66492 1.35137 -1.56212 --4.9698 1.4309 -1.59878 --5.31387 1.52091 -1.64187 --5.67753 1.61754 -1.68153 --6.08013 1.72328 -1.72379 --6.59455 1.85678 -1.79627 --7.13961 2.0004 -1.86161 --7.76287 2.16388 -1.93479 --8.51833 2.36074 -2.03039 --9.39985 2.59143 -2.13881 --10.3976 2.85448 -2.25045 --11.608 3.17372 -2.38579 --13.1252 3.5729 -2.55814 --14.9894 4.06544 -2.76087 --17.5817 4.74661 -3.06117 --37.6689 10.01 -5.51572 --38.1606 10.3472 -4.19872 --43.7614 11.9234 -4.1591 --44.8316 12.3285 -3.46957 --46.5412 13.0376 -1.952 --50.9744 14.3775 -1.31163 --45.4584 12.9935 -0.236797 --48.3787 13.9326 0.557975 --48.3352 14.0532 1.43441 --44.6503 13.2613 3.02884 --12.9483 4.19501 1.87436 --12.7698 4.17945 2.10384 --12.5967 4.16523 2.32841 --12.6499 4.21677 2.57409 --12.5558 4.22518 2.80308 --12.4478 4.2293 3.02811 --11.261 3.90177 3.06488 --10.0892 3.57277 3.06151 --9.88613 3.53942 3.21934 --7.24988 2.7388 2.81372 --3.93003 1.70554 2.13885 --3.81541 1.68129 2.19439 --4.09472 1.78474 2.35939 --4.41498 1.90346 2.54904 --4.26771 1.87004 2.59943 --4.02113 1.80182 2.6108 --4.16877 1.86594 2.75872 --3.83358 1.76761 2.72572 --4.59487 2.04229 3.13017 --4.62491 2.06892 3.25308 --3.59386 1.72591 2.89732 --3.75599 1.79689 3.06605 --3.79506 1.82532 3.18181 --3.91485 1.88337 3.34387 --4.09021 1.96286 3.5429 --3.92757 1.91993 3.5607 --4.1431 2.01609 3.79717 --3.82447 1.91411 3.71668 --3.83942 1.93748 3.83683 --3.78799 1.93492 3.91637 --3.64985 1.89823 3.93495 --3.61149 1.90155 4.02217 --4.84553 2.40533 5.0676 --4.4267 2.26159 4.89537 --4.40051 2.274 5.02198 --4.25627 2.23784 5.05045 --3.23482 1.83912 4.30815 --3.22529 1.85303 4.42207 --3.84656 2.13547 5.13267 --3.02754 1.80758 4.48489 --2.95964 1.79759 4.54319 --2.99545 1.83292 4.7113 --3.17005 1.93113 5.037 --3.08638 1.91525 5.09081 --2.97648 1.88852 5.11357 --2.83156 1.84442 5.0893 --1.63845 1.30518 3.73779 --1.29302 1.15453 3.38875 --1.35985 1.20115 3.56916 --1.32088 1.19616 3.61194 --1.04286 1.07183 3.30416 --1.15558 1.14367 3.56653 --1.1016 1.13022 3.5814 --1.06111 1.125 3.61982 --1.11844 1.17217 3.82435 --0.970921 1.1084 3.67798 --0.864765 1.06596 3.59515 --0.860107 1.07996 3.69862 --0.898495 1.12144 3.89835 --1.08343 1.25336 4.42494 --1.04436 1.25288 4.49971 --0.987255 1.24356 4.53824 --0.930304 1.23305 4.5759 --0.875915 1.22486 4.62169 --0.82433 1.21806 4.67589 --0.840397 1.26144 4.93174 --0.75432 1.23298 4.90243 --0.616933 1.16303 4.6939 --0.526277 1.12674 4.6222 --0.505071 1.14653 4.79364 --0.433496 1.12497 4.78534 --0.728405 1.44645 6.358 --0.650978 1.43798 6.45028 --0.216297 1.05506 4.72305 --0.242217 1.14037 5.24026 --0.151887 1.10024 5.13949 --0.0619306 1.05579 5.01747 --0.16685 1.2991 6.4251 --0.0930268 1.30579 6.6064 --2.71373 0.948525 -1.33471 --2.84681 0.988512 -1.34657 --3.00589 1.03443 -1.37105 --3.1745 1.08366 -1.39597 --3.34546 1.13456 -1.41567 --3.54188 1.19084 -1.44497 --3.74049 1.24994 -1.46828 --3.96643 1.31627 -1.49958 --4.22922 1.39148 -1.54221 --4.47692 1.46556 -1.56722 --4.75218 1.54756 -1.5971 --5.08231 1.643 -1.64294 --5.442 1.74863 -1.6902 --5.81307 1.85882 -1.72906 --6.2578 1.98994 -1.78543 --6.76938 2.1398 -1.85163 --7.36643 2.3154 -1.93135 --8.03114 2.51054 -2.01292 --8.82904 2.74492 -2.11512 --9.73264 3.01191 -2.22187 --10.8358 3.33655 -2.35507 --12.1778 3.73273 -2.51482 --13.825 4.21924 -2.70527 --15.9405 4.84439 -2.94896 --19.2023 5.80156 -3.37227 --41.8366 12.4742 -6.09434 --44.3323 13.3144 -5.69488 --44.7573 13.5607 -4.93397 --45.7504 13.9761 -4.22435 --44.0117 13.5822 -3.21953 --44.5109 13.8514 -2.45244 --45.7035 14.3347 -1.70951 --44.0354 13.9479 -0.80559 --43.9782 14.0494 0.000823021 --42.6465 13.7542 0.812229 --48.6486 15.7584 1.67095 --49.8797 16.2806 2.60121 --47.1619 15.5476 3.3841 --45.8442 15.2516 4.16513 --43.0382 14.4647 4.7736 --12.9615 4.71416 2.44132 --12.6809 4.65758 2.65591 --11.1276 4.17598 2.68171 --11.5016 4.33462 2.95918 --10.8698 4.1532 3.07261 --3.80351 1.76873 1.89039 --5.82244 2.47698 2.41108 --4.70548 2.10665 2.26946 --3.96465 1.86169 2.18149 --3.94173 1.8666 2.26298 --3.86227 1.85198 2.32801 --3.84532 1.85865 2.41083 --3.93458 1.90434 2.52954 --3.87887 1.89802 2.60111 --4.39677 2.10178 2.8886 --4.45785 2.14037 3.01688 --4.59452 2.20726 3.18113 --3.85314 1.944 2.96504 --3.49999 1.82357 2.89767 --3.66027 1.89834 3.06661 --3.79909 1.9663 3.23345 --4.35013 2.19745 3.62864 --4.19436 2.15341 3.65821 --4.032 2.10573 3.67809 --4.03943 2.12477 3.79648 --3.89274 2.08269 3.81959 --3.89794 2.10205 3.93715 --3.81345 2.08414 3.99734 --3.74407 2.07284 4.06632 --3.68911 2.06714 4.14509 --4.20328 2.30494 4.662 --4.28643 2.36189 4.86764 --4.51612 2.48356 5.20512 --4.18998 2.36348 5.0818 --4.13096 2.36016 5.18192 --3.88351 2.27067 5.10698 --3.24974 2.00485 4.64859 --3.06408 1.93888 4.59797 --3.09976 1.97549 4.76733 --1.55482 1.26666 3.24659 --2.99854 1.96868 4.93655 --3.0669 2.02372 5.16079 --1.41066 1.23375 3.33116 --1.38849 1.23611 3.38933 --1.54037 1.32551 3.67431 --1.27104 1.20267 3.41406 --1.21751 1.18893 3.43204 --1.03945 1.10864 3.26784 --1.01142 1.10685 3.31298 --1.01264 1.12128 3.40646 --1.00194 1.12953 3.48434 --1.00767 1.14779 3.59594 --1.11059 1.22258 3.88427 --0.919035 1.12818 3.65292 --0.86851 1.11537 3.67181 --1.1545 1.30755 4.36311 --0.772756 1.09218 3.71501 --1.03937 1.28052 4.4261 --0.9691 1.25958 4.42939 --0.947407 1.27033 4.54771 --0.904556 1.26761 4.62131 --0.829474 1.24298 4.61252 --0.719706 1.1917 4.50153 --0.795073 1.27961 4.93163 --0.707723 1.24668 4.89243 --0.570475 1.17049 4.67389 --0.594064 1.22728 5.0057 --0.467408 1.15765 4.80103 --0.780884 1.49306 6.39845 --0.666154 1.4452 6.31996 --0.226675 1.05662 4.62695 --0.194044 1.07111 4.79664 --0.203537 1.14157 5.24668 --0.0890256 1.06641 4.98057 --0.214735 1.32252 6.44533 --0.146011 1.33256 6.65695 --0.0431812 1.29081 6.59376 --2.62363 1.02658 -1.34728 --2.74749 1.06812 -1.35581 --2.89612 1.11622 -1.37754 --3.0624 1.16947 -1.40566 --3.22285 1.22242 -1.4232 --3.40827 1.28254 -1.4512 --3.60428 1.3465 -1.4784 --3.80198 1.41118 -1.4991 --4.04398 1.48947 -1.53749 --4.27034 1.56436 -1.55842 --4.56788 1.6604 -1.60803 --4.85013 1.75243 -1.63843 --5.1966 1.86459 -1.68906 --5.56246 1.98443 -1.73598 --5.95828 2.11403 -1.78179 --6.40983 2.26192 -1.83639 --6.95353 2.43903 -1.91094 --7.5743 2.64091 -1.99363 --8.29821 2.87704 -2.0902 --9.13526 3.15046 -2.19787 --10.1242 3.4738 -2.32247 --11.2753 3.85073 -2.4584 --12.764 4.33742 -2.64592 --14.5021 4.90824 -2.84256 --17.01 5.72779 -3.16011 --29.3552 9.80027 -4.44514 --40.9206 13.594 -5.80248 --41.1831 13.7906 -5.0772 --42.087 14.3104 -3.6462 --42.7148 14.7478 -2.13512 --43.5653 15.2667 -0.588906 --42.2447 14.9316 0.240328 --46.9724 16.8027 1.88899 --47.204 17.0109 2.76841 --13.239 5.18386 2.04351 --12.9837 5.12966 2.2748 --12.9039 5.13702 2.51714 --13.3326 5.32993 2.82339 --11.0661 4.53726 2.74901 --10.3133 4.29025 2.84279 --3.93892 1.9482 1.86423 --3.82836 1.91915 1.92724 --4.40443 2.14928 2.14061 --4.23569 2.09887 2.19551 --4.139 2.07541 2.26382 --4.18648 2.1071 2.37 --3.76476 1.95678 2.33669 --3.65007 1.92502 2.38653 --4.1189 2.12316 2.63465 --4.1146 2.13553 2.72983 --4.55379 2.32531 2.99839 --4.29907 2.23903 3.00334 --4.7514 2.43869 3.30384 --4.81169 2.48034 3.44782 --3.57341 1.98476 2.97904 --3.61284 2.0149 3.09244 --3.63269 2.03679 3.1996 --3.64948 2.05924 3.30809 --3.68894 2.09052 3.43202 --3.8873 2.19104 3.65429 --3.80732 2.17256 3.71654 --3.85299 2.20907 3.85825 --3.73127 2.17235 3.89257 --3.64901 2.15239 3.95039 --3.79366 2.23426 4.17223 --3.48206 2.11059 4.05984 --4.50746 2.59853 4.9844 --4.47294 2.60518 5.1084 --4.27034 2.53276 5.09257 --4.25461 2.54738 5.2325 --4.15884 2.52565 5.30302 --4.04236 2.49225 5.35214 --3.9193 2.45525 5.39176 --3.18027 2.11471 4.8002 --1.56889 1.33034 3.2328 --1.53012 1.32261 3.27228 --1.49129 1.31469 3.31088 --1.44502 1.3033 3.34167 --1.39868 1.29167 3.37139 --1.30502 1.25471 3.34057 --1.22499 1.2237 3.32218 --1.03355 1.13265 3.14742 --1.0077 1.13034 3.19252 --1.06109 1.17224 3.35609 --0.973968 1.13666 3.31398 --0.939894 1.12954 3.35081 --1.03317 1.19811 3.60035 --0.950354 1.16471 3.5636 --0.924999 1.16497 3.62556 --0.898645 1.16492 3.68725 --0.861238 1.1586 3.73187 --0.807517 1.14093 3.7413 --0.719691 1.10216 3.67961 --0.982802 1.29804 4.40087 --0.974314 1.31555 4.54608 --0.914467 1.29943 4.57535 --0.857175 1.2856 4.61265 --0.85815 1.31485 4.8133 --0.694517 1.21902 4.54679 --0.741284 1.28784 4.90386 --0.659157 1.25485 4.87333 --0.561512 1.2081 4.78488 --0.55066 1.23627 5.00464 --0.996876 1.69545 7.10099 --0.891404 1.66232 7.12302 --0.263561 1.08831 4.66474 --0.189261 1.05516 4.61393 --0.23855 1.16592 5.25635 --0.152268 1.12367 5.17601 --0.0526371 1.06078 4.97664 --0.168631 1.31678 6.4626 --0.0933189 1.31501 6.62516 --2.94818 1.252 -1.41342 --3.09814 1.30704 -1.4286 --3.26483 1.36713 -1.44955 --3.44111 1.4307 -1.47026 --3.64415 1.50315 -1.50041 --3.86609 1.58174 -1.53367 --4.10554 1.66838 -1.56932 --4.35604 1.75853 -1.60125 --4.64384 1.86121 -1.6427 --4.94988 1.97078 -1.68284 --5.29325 2.09462 -1.7292 --5.67456 2.23122 -1.77962 --6.09348 2.38295 -1.83245 --6.56803 2.55433 -1.89253 --7.14371 2.75992 -1.97435 --7.80401 2.99701 -2.06629 --8.56719 3.27088 -2.16969 --9.4521 3.58922 -2.2852 --10.5242 3.97494 -2.42629 --11.7752 4.42655 -2.57995 --13.3619 4.99917 -2.77949 --15.535 5.78022 -3.06998 --26.5546 9.76814 -4.35403 --29.3955 10.8432 -4.35939 --37.7536 13.8936 -5.15366 --37.8489 14.1309 -3.74333 --40.9961 15.4844 -2.6001 --41.0878 15.6279 -1.84037 --41.5799 15.9196 -1.09779 --46.1222 17.7289 -0.468051 --41.9906 16.2962 0.450204 --44.3129 17.2892 1.24661 --44.3672 17.4278 2.07808 --44.415 17.5656 2.91351 --12.4773 5.32015 1.82216 --12.4129 5.33034 2.05984 --12.3831 5.35269 2.29949 --12.2848 5.34904 2.5311 --11.6288 5.12271 2.68495 --5.10251 2.54065 1.90627 --3.97458 2.10086 1.81785 --3.87457 2.07324 1.88529 --3.96538 2.12272 1.98998 --4.10815 2.19376 2.11122 --4.10352 2.20509 2.20182 --4.41972 2.34997 2.38062 --4.24101 2.28929 2.4283 --4.46091 2.39617 2.59469 --4.36909 2.3716 2.66701 --9.23735 4.47546 4.49994 --4.12187 2.29391 2.78047 --4.19968 2.34254 2.91182 --4.30061 2.40199 3.05759 --4.45774 2.486 3.23434 --4.38251 2.46875 3.31199 --4.49001 2.53283 3.47731 --3.82552 2.24936 3.2543 --3.89854 2.29814 3.39717 --3.6362 2.19341 3.35772 --3.68273 2.22872 3.48761 --3.66912 2.23843 3.58614 --3.43438 2.1434 3.54533 --3.38933 2.13719 3.61988 --4.02441 2.45487 4.16463 --4.68726 2.79136 4.7669 --3.94 2.4509 4.35786 --4.55884 2.77197 4.96874 --4.78681 2.9057 5.30568 --4.4963 2.78469 5.22647 --4.16027 2.63943 5.09487 --4.16546 2.66302 5.25311 --4.18009 2.69401 5.42562 --4.21026 2.73236 5.62008 --5.1536 3.25067 6.74351 --1.57438 1.3915 3.212 --1.54324 1.38615 3.25891 --1.51724 1.38445 3.31221 --1.4651 1.36824 3.33692 --1.41929 1.35489 3.36781 --1.12577 1.20394 3.08703 --1.25116 1.28621 3.32883 --1.15537 1.24326 3.28687 --1.13343 1.243 3.34222 --1.02907 1.19478 3.28009 --1.00153 1.19114 3.32583 --0.997513 1.20163 3.41164 --0.941728 1.18149 3.41665 --1.00187 1.23295 3.61825 --0.929744 1.20245 3.59793 --0.904617 1.20174 3.65999 --1.13125 1.36693 4.21606 --0.856593 1.20435 3.80092 --0.757101 1.1535 3.71518 --0.683347 1.12138 3.6789 --0.961412 1.33659 4.45522 --0.939229 1.34525 4.57416 --0.872605 1.32159 4.58529 --0.8131 1.30317 4.6132 --0.691994 1.23641 4.46647 --0.634203 1.21774 4.49113 --0.544582 1.17293 4.41254 --0.61823 1.26757 4.88225 --0.586953 1.27633 5.02774 --1.00549 1.71093 6.95758 --1.00775 1.7773 7.41679 --0.775926 1.61211 6.87704 --0.226153 1.08792 4.66196 --0.174461 1.07791 4.72615 --0.203218 1.16788 5.2827 --0.0961346 1.0954 5.05614 --0.0340533 1.07946 5.10918 --0.154275 1.35883 6.7535 --0.0465765 1.30277 6.6423 --2.82558 1.32575 -1.41293 --2.97248 1.38364 -1.43099 --3.12071 1.44282 -1.4444 --3.29463 1.5103 -1.46879 --3.48685 1.58549 -1.49814 --3.70374 1.67028 -1.53602 --3.92433 1.75645 -1.56657 --4.16245 1.85072 -1.59933 --4.42765 1.95479 -1.63745 --4.71275 2.06698 -1.67539 --5.02511 2.18955 -1.71617 --5.39192 2.3332 -1.77101 --5.778 2.48584 -1.82078 --6.21104 2.65635 -1.87592 --6.73385 2.86158 -1.95207 --7.3144 3.08908 -2.03036 --8.02194 3.36689 -2.13441 --8.51081 3.56798 -2.13422 --9.11788 3.81493 -2.15545 --10.2129 4.24521 -2.30666 --11.5934 4.78797 -2.50002 --13.2898 5.45559 -2.72723 --16.8142 6.82129 -3.35425 --25.3952 10.1932 -4.53695 --37.7407 15.1136 -5.74204 --37.8007 15.2383 -5.02988 --38.0889 15.4519 -4.34953 --38.0896 15.5528 -3.62552 --40.5294 16.6256 -3.15252 --40.4981 16.7197 -2.38284 --41.5093 17.2343 -1.6825 --41.7223 17.4299 -0.907994 --43.4479 18.2447 -0.166571 --43.7536 18.485 0.652387 --43.7584 18.6034 1.48101 --12.4547 5.6886 1.41129 --12.2877 5.65299 1.64702 --12.2268 5.66091 1.88464 --12.2543 5.70666 2.12821 --12.242 5.7348 2.36977 --12.1877 5.74539 2.60732 --12.2309 5.79853 2.85761 --5.19425 2.77268 1.96277 --5.05502 2.72764 2.04879 --3.82641 2.20211 1.91056 --4.05856 2.31652 2.04792 --4.03763 2.31974 2.13407 --4.12106 2.37029 2.2477 --4.10508 2.37659 2.33771 --4.22815 2.44509 2.47024 --4.18228 2.43849 2.55409 --4.33426 2.52234 2.70576 --4.25958 2.50174 2.78187 --4.25123 2.51212 2.88242 --4.24193 2.5223 2.98319 --4.33969 2.58363 3.13166 --4.29145 2.57636 3.22015 --4.21748 2.55689 3.29574 --4.63559 2.77329 3.6165 --3.50706 2.24256 3.14604 --3.45142 2.22919 3.21395 --3.74668 2.38847 3.48213 --3.70257 2.3818 3.5635 --3.49285 2.29167 3.54171 --3.50952 2.3148 3.6587 --3.2643 2.20629 3.60084 --3.45203 2.31684 3.83859 --5.20223 3.23376 5.24072 --3.53478 2.39163 4.13069 --4.44212 2.88315 4.97545 --4.25863 2.80844 4.97639 --5.96183 3.73575 6.59122 --4.36102 2.90612 5.37574 --4.22339 2.85459 5.41336 --4.16063 2.84292 5.51822 --3.91081 2.72862 5.43797 --5.40981 3.58619 7.15313 --1.54753 1.44804 3.23803 --1.50309 1.43445 3.27124 --1.43984 1.40951 3.2823 --1.37721 1.38538 3.29149 --1.15592 1.26702 3.10179 --1.09226 1.23979 3.09726 --1.1585 1.29087 3.26437 --1.17535 1.3135 3.37364 --1.06559 1.25859 3.30593 --0.984487 1.22035 3.27425 --0.936402 1.20283 3.28775 --0.937832 1.21622 3.38103 --0.903231 1.2069 3.41799 --0.867611 1.19722 3.45439 --0.885942 1.22373 3.59073 --0.961662 1.29142 3.84692 --0.884354 1.25549 3.8167 --0.767426 1.19034 3.69807 --0.7385 1.18733 3.75868 --1.06449 1.4441 4.63758 --0.959894 1.39016 4.5633 --0.911786 1.37845 4.6201 --0.827582 1.339 4.58625 --0.723577 1.28203 4.4865 --0.634571 1.2368 4.42039 --0.772228 1.38119 5.05347 --0.488216 1.16713 4.35565 --0.572207 1.27407 4.87229 --0.543051 1.2832 5.02719 --1.06576 1.83893 7.46218 --0.838808 1.67515 6.96399 --0.253646 1.11248 4.66136 --0.184625 1.08049 4.63014 --0.196291 1.14332 5.05091 --0.167366 1.16766 5.30927 --0.0515357 1.07577 4.99451 -0.0195291 1.04137 4.95916 --0.0996216 1.33472 6.70257 --2.45588 1.28736 -1.38422 --2.5739 1.33937 -1.39612 --2.70231 1.39458 -1.41004 --2.84689 1.45649 -1.4313 --2.99206 1.51852 -1.44759 --3.16316 1.59185 -1.47587 --3.3429 1.66852 -1.50339 --3.53324 1.74907 -1.53001 --3.74973 1.84161 -1.56549 --3.984 1.9413 -1.60299 --4.21984 2.04302 -1.63254 --4.49153 2.15894 -1.67197 --4.7912 2.28629 -1.71504 --5.11772 2.42611 -1.76046 --5.48953 2.5848 -1.81465 --5.8198 2.73053 -1.83609 --6.1624 2.88097 -1.84954 --6.41865 3.00101 -1.81515 --6.95463 3.23156 -1.88125 --7.64442 3.52533 -1.98336 --8.39908 3.84958 -2.08198 --9.37066 4.26493 -2.2235 --10.6326 4.80233 -2.4175 --12.134 5.44408 -2.63266 --13.4711 6.02733 -2.74611 --25.1242 10.9435 -4.90249 --37.7827 16.4041 -6.35981 --37.8687 16.5408 -5.64129 --38.0058 16.6992 -4.93002 --38.2136 16.8884 -4.22544 --13.0284 6.12938 -0.544199 --13.039 6.16919 -0.288887 --13.0357 6.20268 -0.0322416 --13.0566 6.24703 0.222514 --13.0543 6.28075 0.479136 --40.0127 18.2877 0.133483 --40.256 18.5008 0.900443 --40.3215 18.7421 2.45197 --12.3099 6.1185 1.72669 --12.3386 6.16539 1.97422 --12.3278 6.19378 2.22024 --12.1409 6.14098 2.44756 --10.87 5.58395 2.52711 --11.6589 5.98267 2.8684 --5.02469 2.89482 1.97906 --3.91673 2.38591 1.87804 --3.95974 2.41891 1.97562 --3.86902 2.38766 2.04484 --3.98899 2.4578 2.16366 --4.16729 2.5564 2.30439 --4.38488 2.6752 2.46518 --4.21838 2.60764 2.51576 --4.89314 2.95395 2.84202 --4.81612 2.93219 2.93048 --8.73048 4.89936 4.52481 --4.11875 2.61346 2.88585 --4.15905 2.64851 3.00671 --4.23795 2.70271 3.14842 --4.23993 2.71885 3.25934 --4.06855 2.64634 3.28684 --4.12365 2.6898 3.42546 --4.0806 2.68298 3.51501 --3.94 2.62498 3.5503 --3.65959 2.49204 3.49781 --3.49094 2.41752 3.50223 --3.63082 2.50655 3.69845 --3.4098 2.4032 3.66189 --3.4747 2.45352 3.81683 --3.33689 2.3937 3.82992 --3.45582 2.47355 4.03224 --3.4677 2.49683 4.16075 --3.40641 2.47872 4.23283 --3.94618 2.80049 4.8149 --5.95022 3.95774 6.72789 --6.19864 4.12931 7.17214 --6.03857 4.06867 7.25347 --8.4111 5.48076 9.82821 --5.6081 3.88156 7.29141 --3.67117 2.76625 5.47003 --4.92996 3.54118 7.02317 --3.42647 2.66531 5.52915 --1.33369 1.41363 3.2162 --1.31438 1.41255 3.27462 --1.19602 1.35046 3.20793 --1.06843 1.28218 3.12236 --1.18153 1.36548 3.35846 --1.00855 1.2656 3.20015 --0.909113 1.2131 3.13677 --1.00609 1.28883 3.37086 --1.62964 1.7169 4.46674 --0.922475 1.25795 3.42322 --0.872801 1.23772 3.43571 --0.778395 1.18579 3.36401 --1.12512 1.44343 4.12102 --0.850606 1.26551 3.71283 --0.776532 1.22788 3.68069 --0.768463 1.23909 3.78494 --0.715805 1.21632 3.7938 --0.710295 1.2309 3.91632 --0.945665 1.43514 4.64517 --0.864861 1.39555 4.62179 --0.710461 1.29515 4.3881 --0.664252 1.28209 4.44115 --0.567233 1.2239 4.33735 --0.51027 1.20002 4.3511 --0.651085 1.35943 5.05281 --0.579354 1.32829 5.05933 --0.49693 1.28546 5.01717 --0.856864 1.69792 6.85965 --0.282105 1.14223 4.66948 --0.221052 1.11518 4.67787 --0.17029 1.10132 4.74265 --0.184328 1.17178 5.21261 --0.0979408 1.11816 5.10287 --0.0237664 1.07916 5.05923 --0.163989 1.3895 6.8695 --0.0586358 1.32994 6.77917 --2.46039 1.40103 -1.39388 --2.58674 1.45937 -1.41051 --2.72035 1.5213 -1.4287 --2.87114 1.59024 -1.45385 --3.02305 1.66151 -1.47418 --3.19246 1.73913 -1.50001 --3.37899 1.82522 -1.53078 --3.58391 1.9193 -1.56534 --3.79736 2.01804 -1.59769 --4.03005 2.12628 -1.63258 --4.27161 2.23858 -1.6636 --4.54861 2.36712 -1.70423 --4.83657 2.50059 -1.73927 --5.1182 2.63336 -1.76002 --5.40058 2.76836 -1.77084 --5.7187 2.92054 -1.78718 --6.09032 3.09534 -1.81415 --6.54123 3.30697 -1.85967 --7.12336 3.57765 -1.9394 --7.83133 3.90514 -2.04257 --8.68267 4.29921 -2.16837 --9.70462 4.77179 -2.31711 --11.0756 5.40502 -2.53399 --12.4448 6.0438 -2.6968 --13.8012 6.68373 -2.8032 --13.8368 6.73782 -2.52913 --13.8597 6.78516 -2.25228 --13.8413 6.81443 -1.96745 --37.9179 17.8561 -6.26487 --38.0078 17.9961 -5.53494 --13.9754 6.9882 -1.15305 --13.3366 6.72767 -0.789446 --13.1063 6.65548 -0.497368 --13.1063 6.69074 -0.236124 --13.1194 6.73115 0.0241051 --13.1287 6.7707 0.284817 --39.9472 19.6138 -0.422432 --44.8275 22.0604 0.271521 --45.0207 22.2702 1.14348 --45.0569 22.4045 2.02127 --39.4655 19.7937 2.67274 --12.2461 6.54812 1.80689 --45.8124 23.1306 4.7311 --39.1137 19.931 4.97154 --10.6321 5.84294 2.36269 --11.0057 6.06024 2.63454 --10.8877 6.03145 2.84463 --5.35678 3.26183 2.08493 --5.24584 3.22067 2.18122 --3.71797 2.45522 1.96333 --3.82851 2.52295 2.07672 --3.91065 2.57792 2.1879 --8.42428 4.93664 3.55027 --10.702 6.15311 4.42842 --8.50013 5.0268 3.95515 --9.82187 5.75131 4.60715 --5.20853 3.33107 3.13824 --4.11008 2.75986 2.83698 --4.14253 2.79123 2.95453 --4.08131 2.77274 3.03481 --4.21604 2.85996 3.20314 --4.27272 2.90608 3.34259 --4.3989 2.99127 3.52148 --3.68711 2.61325 3.26394 --3.97747 2.78873 3.52995 --5.43398 3.61934 4.49189 --4.07109 2.87275 3.81813 --3.77757 2.72256 3.75386 --3.90277 2.80962 3.95306 --3.8664 2.80506 4.05054 --3.45364 2.58299 3.87848 --3.35967 2.54402 3.9245 --3.45333 2.61363 4.11273 --4.16375 3.04853 4.80836 --3.87491 2.89745 4.71392 --4.38181 3.22001 5.29858 --5.99298 4.21359 6.92235 --5.81215 4.13388 6.97706 --8.20795 5.63047 9.54125 --7.73991 5.38526 9.38954 --5.20408 3.84869 7.03814 --3.37856 2.73278 5.27326 --3.25856 2.67733 5.29626 --3.03642 2.5574 5.1963 --3.04306 2.58266 5.36083 --2.87807 2.49682 5.31645 --1.05012 1.31694 3.07876 --1.04411 1.32245 3.14797 --1.84777 1.87344 4.36796 --1.74968 1.82423 4.35431 --1.70456 1.81113 4.41603 --1.68343 1.81423 4.51702 --0.916398 1.29318 3.38755 --2.16782 2.1967 5.64046 --1.94485 2.06142 5.43199 --1.30642 1.61948 4.42381 --0.895999 1.33487 3.77005 --0.796865 1.27556 3.68866 --1.1528 1.56508 4.56811 --0.744828 1.26795 3.82058 --1.07045 1.54481 4.71574 --0.988627 1.50257 4.69601 --0.929009 1.47759 4.72789 --0.779234 1.37744 4.51518 --0.677569 1.31483 4.41591 --0.610399 1.28118 4.40487 --0.532548 1.23693 4.3555 --0.479388 1.21475 4.37793 --0.605532 1.36508 5.05339 --0.530849 1.3271 5.0406 --0.929363 1.78001 6.99143 --0.78834 1.68944 6.82463 --0.246877 1.1424 4.67689 --0.177326 1.10319 4.63686 --0.140985 1.10461 4.77832 --0.155938 1.17829 5.27791 --0.0475355 1.08909 5.00269 -0.0226003 1.05084 4.96794 --0.10063 1.34717 6.74111 --2.36054 1.46489 -1.40241 --2.47596 1.5234 -1.41528 --2.59264 1.58302 -1.42438 --2.7411 1.65595 -1.45284 --2.88995 1.73005 -1.47614 --3.04786 1.80942 -1.50008 --3.20813 1.89047 -1.51871 --3.4162 1.99277 -1.56297 --3.62604 2.096 -1.59976 --3.80637 2.18903 -1.60994 --4.0032 2.28974 -1.62309 --4.23434 2.40603 -1.64777 --4.51556 2.54663 -1.69101 --4.82438 2.70088 -1.73693 --5.15088 2.86536 -1.78001 --5.43862 3.01317 -1.79124 --5.74523 3.17043 -1.79975 --6.12827 3.36626 -1.83017 --6.62364 3.61503 -1.8916 --7.27636 3.94038 -1.99479 --8.00109 4.30336 -2.0989 --8.97879 4.79025 -2.26258 --10.1796 5.38741 -2.46018 --11.4903 6.04506 -2.64448 --13.2869 6.94266 -2.91629 --19.983 10.2235 -4.42358 --21.8316 11.2935 -3.58163 --21.9035 11.3863 -3.15423 --30.3013 15.6216 -4.12008 --38.3696 19.7346 -4.70936 --39.3871 20.4459 -3.30177 --39.3982 20.5528 -2.52552 --37.8688 19.8736 -1.64185 --38.9581 20.5289 -0.949597 --39.4401 20.8772 -0.195908 --44.7739 23.8547 1.40656 --40.0097 21.4798 2.16094 --40.8904 22.0452 2.9983 --44.8441 24.2393 4.07908 --44.7075 24.2829 4.96472 --11.7264 6.81544 2.34379 --11.2359 6.58455 2.52611 --10.2294 6.07379 2.61429 --10.775 6.39701 2.9228 --5.1068 3.3449 2.09003 --5.05743 3.33343 2.19508 --3.90685 2.71598 2.04733 --4.01421 2.78723 2.16632 --10.6628 6.48682 4.06251 --10.289 6.30957 4.19176 --9.82281 6.07857 4.27866 --5.02596 3.40759 2.89434 --4.99854 3.40837 3.00691 --4.98655 3.41737 3.12542 --5.03705 3.46217 3.27096 --4.76791 3.32461 3.28405 --4.81565 3.36753 3.42889 --4.58775 3.25189 3.44772 --4.45671 3.19153 3.50586 --3.71991 2.77481 3.24361 --4.21006 3.07799 3.61803 --4.0945 3.02494 3.67264 --4.12476 3.05889 3.81033 --3.90147 2.94041 3.79472 --3.94273 2.98111 3.94167 --3.85567 2.94445 4.00578 --3.62163 2.81787 3.96402 --3.44111 2.72217 3.95139 --3.52541 2.78958 4.13515 --3.38089 2.71558 4.14362 --4.1663 3.22442 4.91862 --3.98361 3.12861 4.91316 --5.27073 3.96613 6.21734 --9.27676 6.55852 10.1493 --8.5486 6.13397 9.79338 --5.39235 4.12662 6.95734 --5.19812 4.02836 6.9792 --5.07973 3.97912 7.07582 --3.19079 2.75157 5.18288 --3.12132 2.72589 5.25862 --3.05101 2.69873 5.33331 --1.95295 1.97071 4.11839 --1.92982 1.97045 4.20559 --1.78877 1.88869 4.13702 --1.82894 1.93197 4.31287 --1.7854 1.9176 4.37671 --2.36091 2.347 5.37936 --1.735 1.91586 4.56537 --0.947984 1.3573 3.41574 --0.899096 1.33446 3.42989 --0.897187 1.34529 3.52493 --0.851758 1.32476 3.5461 --1.11448 1.54149 4.16062 --0.858085 1.35811 3.78047 --1.0572 1.53249 4.32254 --1.64726 2.02681 5.77281 --0.659076 1.24718 3.71654 --0.586862 1.20307 3.67123 --0.862791 1.45453 4.50326 --0.769931 1.39728 4.4345 --0.769692 1.42118 4.61589 --0.626143 1.31751 4.38892 --0.569249 1.28989 4.40484 --0.496391 1.24656 4.36404 --1.23363 1.99659 7.18566 --1.13539 1.94995 7.2251 --0.968831 1.83352 6.98946 --0.37755 1.24943 4.8645 --0.296076 1.19797 4.78978 --0.218363 1.14703 4.71302 --0.152621 1.11059 4.69192 --0.143724 1.14647 5.00734 --0.0845581 1.12225 5.05248 --0.0115654 1.07639 4.98953 --0.160934 1.39796 6.86833 --0.0894897 1.38987 7.09206 --2.26095 1.52395 -1.40905 --2.35996 1.57841 -1.41176 --2.48153 1.64376 -1.42941 --2.60317 1.71101 -1.44308 --2.75762 1.79198 -1.47544 --2.89753 1.86851 -1.49153 --3.06146 1.956 -1.51898 --3.24226 2.05291 -1.55156 --3.38555 2.13255 -1.55165 --3.54592 2.22059 -1.55696 --3.77034 2.3407 -1.59567 --3.99635 2.4629 -1.62623 --4.23197 2.59034 -1.65314 --4.50163 2.73587 -1.68924 --4.78963 2.89251 -1.72407 --5.10432 3.0628 -1.76048 --5.37945 3.21508 -1.76552 --5.7385 3.41079 -1.79823 --6.21645 3.6682 -1.86813 --6.78922 3.97551 -1.9577 --7.44095 4.32699 -2.05531 --8.3168 4.79492 -2.20897 --9.35965 5.35316 -2.38519 --10.5356 5.98507 -2.56289 --12.2406 6.89775 -2.85524 --18.6569 10.2715 -4.42165 --19.4385 10.7818 -3.83225 --27.9882 15.3502 -5.34503 --28.0952 15.4795 -4.79403 --28.2204 15.6191 -4.24469 --29.2606 16.2494 -3.84225 --46.017 25.3478 -5.66468 --40.6364 22.6563 -3.25782 --38.315 21.4928 -2.24731 --38.4146 21.6439 -1.48576 --38.7915 21.9492 -0.732821 --44.813 25.6091 1.69136 --38.1751 21.9987 2.36605 --39.9867 23.1172 3.23745 --11.4208 7.04593 1.92523 --11.4785 7.11012 2.17092 --10.1074 6.35708 2.25617 --10.7915 6.7766 2.56447 --10.7967 6.80926 2.79682 --10.1316 6.454 2.91253 --9.84271 6.31348 3.0768 --10.4346 6.68645 3.42294 --5.10556 3.58756 2.37987 --5.03618 3.56199 2.48137 --4.90733 3.501 2.56426 --4.89326 3.50749 2.67824 --4.85374 3.49863 2.78413 --4.89358 3.53834 2.91784 --4.93208 3.57611 3.05395 --5.11311 3.70255 3.24965 --4.7344 3.48743 3.22243 --5.45257 3.94376 3.66245 --4.83509 3.5811 3.51828 --4.75076 3.54606 3.6072 --4.54166 3.4317 3.63 --4.48756 3.41452 3.72837 --4.18837 3.24254 3.68743 --4.13374 3.22374 3.77859 --4.10144 3.21835 3.88244 --4.11088 3.24075 4.01462 --4.00865 3.19104 4.07447 --3.73206 3.02908 4.00924 --3.51616 2.90455 3.97594 --3.45926 2.88327 4.05283 --3.4431 2.8872 4.162 --3.2865 2.80031 4.15824 --4.0949 3.35365 4.97338 --4.10928 3.38222 5.13957 --3.9485 3.29402 5.14968 --3.47085 2.99054 4.85015 --5.50623 4.39848 7.02232 --5.12444 4.16515 6.85522 --3.44978 3.03322 5.27873 --3.28246 2.93605 5.25342 --3.10587 2.83257 5.20875 --3.0432 2.80785 5.29115 --1.97881 2.06826 4.12712 --1.92203 2.04248 4.17202 --1.86612 2.01663 4.21553 --1.78727 1.97448 4.22815 --1.78799 1.98993 4.35247 --1.94414 2.12302 4.71639 --0.98036 1.41492 3.35591 --1.6439 1.93248 4.52636 --0.956674 1.42036 3.50672 --0.903011 1.39165 3.51351 --0.859066 1.36957 3.53554 --0.823649 1.35488 3.57295 --1.04794 1.55042 4.13118 --0.998452 1.52725 4.16477 --1.65832 2.0947 5.74236 --0.684971 1.29917 3.74368 --0.616646 1.25701 3.70823 --0.53166 1.19913 3.627 --0.784854 1.44112 4.42534 --0.757741 1.43844 4.52592 --0.631049 1.34548 4.34564 --0.560709 1.30205 4.31659 --0.528777 1.29566 4.40501 --0.449357 1.24271 4.33582 --1.26318 2.10378 7.55571 --0.547313 1.40344 5.17621 --0.482385 1.37037 5.20075 --0.319227 1.22647 4.77792 --0.281335 1.2209 4.90278 --0.177748 1.13675 4.69175 --0.117746 1.10349 4.68924 --0.128823 1.16815 5.14993 --0.0478837 1.10848 5.04002 --0.236666 1.47752 7.12091 --0.0934544 1.34147 6.68167 --2.25645 1.63648 -1.4185 --2.36039 1.69846 -1.42627 --2.48789 1.7717 -1.4485 --2.61693 1.84518 -1.46628 --2.76823 1.93206 -1.49677 --2.88424 2.0013 -1.49412 --3.00054 2.07142 -1.48758 --3.17135 2.17026 -1.51409 --3.35837 2.27756 -1.54455 --3.5544 2.39163 -1.5734 --3.72883 2.49435 -1.58051 --3.93587 2.61517 -1.60009 --4.1669 2.75019 -1.62549 --4.40855 2.89082 -1.64668 --4.69172 3.056 -1.68021 --5.03273 3.25289 -1.73127 --5.37666 3.45318 -1.76944 --5.77189 3.68214 -1.81688 --6.29125 3.98122 -1.90256 --6.88893 4.32585 -1.99902 --7.68987 4.78422 -2.14978 --8.56153 5.2857 -2.29374 --9.66334 5.92014 -2.48211 --11.1674 6.78166 -2.75564 --18.8017 11.1254 -4.4296 --26.2541 15.4421 -5.43404 --26.4042 15.5946 -4.91845 --26.7085 15.8364 -4.4304 --26.6548 15.8737 -3.86722 --28.1804 16.8198 -3.56125 --28.0251 16.802 -2.95976 --28.0588 16.8921 -2.3882 --39.7432 23.7821 -2.9794 --37.796 23.3119 2.62439 --37.8011 23.4109 3.40445 --11.3908 7.50191 2.01629 --9.86244 6.6031 2.10352 --9.92722 6.66835 2.32551 --10.4112 6.99168 2.61186 --10.3396 6.97573 2.82833 --4.83952 3.60097 2.03278 --4.7929 3.58571 2.13653 --4.76926 3.58541 2.24444 --4.76167 3.59412 2.35631 --4.76798 3.61248 2.47278 --4.77998 3.63507 2.5927 --4.80744 3.66598 2.71905 --4.85636 3.71265 2.85524 --5.77302 4.3146 3.30916 --5.60314 4.2228 3.3888 --4.86028 3.76063 3.22885 --4.63887 3.63253 3.26092 --4.67758 3.67257 3.40266 --4.58049 3.62531 3.48337 --4.52229 3.60263 3.5804 --4.22539 3.42199 3.55071 --4.25756 3.45794 3.69067 --3.92735 3.25285 3.62345 --4.14881 3.41628 3.8782 --4.61354 3.74547 4.30198 --3.83969 3.23909 3.93045 --3.87631 3.27934 4.08073 --3.93174 3.33319 4.24884 --4.09416 3.46127 4.50508 --4.15328 3.5192 4.69348 --6.00755 4.82897 6.3554 --4.00974 3.45613 4.87003 --3.99915 3.46711 5.01163 --3.57437 3.18492 4.77685 --3.41621 3.0898 4.77075 --3.38588 3.08598 4.88488 --5.60368 4.70585 7.30858 --3.3139 3.07003 5.10683 --3.22965 3.02812 5.16759 --3.25079 3.06253 5.34881 --3.02464 2.91495 5.24193 --2.60961 2.62409 4.88781 --2.54199 2.59025 4.94736 --1.90582 2.12572 4.24817 --1.8166 2.07209 4.24822 --1.73915 2.0281 4.26043 --1.02401 1.48512 3.31789 --0.982262 1.46423 3.34309 --1.69923 2.04463 4.59055 --0.984145 1.48851 3.5339 --0.889255 1.42433 3.46963 --0.882341 1.43027 3.5572 --0.833334 1.40312 3.571 --1.47779 1.95749 4.95195 --1.73947 2.20016 5.66234 --0.724432 1.35193 3.68236 --0.686405 1.33417 3.71819 --0.63369 1.30228 3.71863 --2.20082 2.72928 7.72316 --0.880433 1.5616 4.62856 --1.11642 1.8042 5.45549 --0.620552 1.36215 4.26628 --0.567309 1.33244 4.28292 --0.533962 1.32281 4.36251 --0.452638 1.26453 4.28511 --0.414803 1.25053 4.354 --0.581949 1.4562 5.21691 --0.454153 1.35005 4.97945 --0.345983 1.26379 4.79412 --0.279906 1.22178 4.77697 --0.251858 1.22639 4.94927 --0.139515 1.12491 4.67024 --0.138086 1.16755 5.02448 --0.0704422 1.12518 5.0024 --0.00899031 1.08903 5.00794 --0.176665 1.43915 7.04308 --0.0818095 1.38203 7.03304 --2.2412 1.74573 -1.42077 --2.35895 1.81829 -1.43966 --2.47701 1.89179 -1.45436 --2.58962 1.96283 -1.45926 --2.6948 2.03085 -1.45461 --2.84564 2.12301 -1.47936 --3.01117 2.22507 -1.5094 --3.1493 2.31225 -1.51255 --3.31086 2.41359 -1.52609 --3.48063 2.52034 -1.53859 --3.68298 2.64511 -1.56396 --3.87104 2.76451 -1.57277 --4.09109 2.9012 -1.59218 --4.35138 3.06298 -1.62487 --4.62978 3.23687 -1.65631 --4.93349 3.42626 -1.68882 --5.33483 3.67271 -1.75547 --5.7956 3.95694 -1.83261 --6.39688 4.32419 -1.95099 --7.03395 4.71711 -2.05934 --7.86236 5.22531 -2.21548 --8.7533 5.77459 -2.35976 --10.2841 6.70815 -2.68783 --13.7661 8.8156 -3.58437 --16.648 10.5798 -4.15199 --17.12 10.9075 -3.92124 --24.6798 15.523 -5.51852 --24.7453 15.6265 -5.00682 --25.1139 15.9133 -4.56076 --25.1819 16.0187 -4.04259 --39.4965 25.7646 1.34625 --37.9505 24.875 2.12727 --38.9109 25.5863 2.97004 --4.70111 3.64702 1.40167 --4.71407 3.66877 1.51133 --4.70895 3.67848 1.62002 --4.67745 3.6705 1.72562 --4.66039 3.67275 1.83287 --4.64984 3.67898 1.94141 --4.66306 3.70152 2.05457 --4.66661 3.71633 2.16732 --4.67555 3.73615 2.28264 --4.70771 3.77163 2.40514 --4.75318 3.81601 2.5344 --10.7228 7.84446 4.48667 --7.89934 5.96928 3.81079 --7.75259 5.89194 3.95277 --5.74085 4.5459 3.38862 --5.58074 4.45419 3.47225 --4.38497 3.65102 3.1113 --4.59495 3.81037 3.32465 --6.52355 5.16071 4.36367 --4.46684 3.75094 3.51558 --4.40159 3.72036 3.60824 --4.20036 3.5952 3.62529 --4.0747 3.52131 3.67765 --4.09553 3.55059 3.81421 --3.93978 3.45488 3.84291 --3.81313 3.37968 3.88505 --3.79364 3.38104 3.99598 --3.82162 3.41626 4.14249 --3.85968 3.4598 4.30189 --3.71031 3.36667 4.32017 --3.97347 3.57534 4.66727 --3.96748 3.58828 4.80777 --5.24584 4.55327 6.07826 --3.88113 3.56006 5.03335 --3.30607 3.14765 4.64419 --3.27268 3.1394 4.75071 --3.33669 3.20459 4.95817 --8.43586 7.11065 10.5127 --3.35263 3.25329 5.28036 --3.00294 3.00259 5.04182 --2.70831 2.79196 4.8445 --2.60279 2.72666 4.85847 --2.52551 2.68244 4.90485 --2.13243 2.38881 4.53142 --1.84299 2.1729 4.26696 --1.78725 2.14194 4.311 --1.73544 2.11535 4.36126 --1.68354 2.0885 4.41036 --2.02296 2.3857 5.08814 --2.0403 2.41888 5.27805 --0.901469 1.47874 3.47411 --0.854723 1.45133 3.48903 --0.821026 1.43413 3.52749 --1.50403 2.04209 4.97375 --1.7224 2.25418 5.5885 --2.71072 3.1584 7.90084 --0.678953 1.36235 3.67548 --0.642323 1.34277 3.711 --1.16117 1.83999 5.10836 --0.786336 1.50981 4.34434 --0.761419 1.50668 4.44517 --0.694162 1.46155 4.42954 --0.581589 1.37144 4.27655 --0.537431 1.34854 4.32026 --0.77098 1.61293 5.29068 --0.427005 1.28034 4.33115 --0.618733 1.51335 5.26612 --0.509782 1.42667 5.11517 --0.345479 1.27186 4.69684 --0.306683 1.25917 4.79347 --0.23065 1.20165 4.71848 --0.182276 1.17731 4.77548 --0.135265 1.1571 4.85077 --0.118568 1.18006 5.13854 --0.0412206 1.11917 5.03872 --0.20444 1.44583 6.90526 --0.0826552 1.3319 6.60282 --2.13499 1.79816 -1.42613 --2.23558 1.86542 -1.43484 --2.31002 1.91723 -1.4159 --2.42626 1.99461 -1.43001 --2.56474 2.08528 -1.45731 --2.69708 2.17246 -1.47381 --2.83728 2.26565 -1.49101 --2.98636 2.36517 -1.50856 --3.13682 2.46616 -1.52068 --3.28794 2.56747 -1.52697 --3.44044 2.67025 -1.52783 --3.62406 2.79271 -1.54193 --3.80797 2.91768 -1.54931 --4.02464 3.06125 -1.56704 --4.28013 3.23165 -1.59804 --4.58392 3.43205 -1.64343 --4.84315 3.60668 -1.65345 --5.31612 3.91507 -1.75536 --5.88728 4.28787 -1.8819 --6.50996 4.69498 -2.00595 --7.25579 5.18428 -2.15455 --8.12801 5.75508 -2.31966 --9.37505 6.57021 -2.58566 --10.6938 7.43639 -2.823 --15.5708 10.5878 -4.15371 --17.0287 11.5651 -4.24418 --17.1078 11.6596 -3.88821 --23.2842 15.705 -5.10639 --23.5161 15.9141 -4.65405 --23.84 16.1844 -4.21419 --24.3564 16.5822 -3.80009 --18.9048 13.0577 -2.33016 --18.9206 13.1162 -1.92507 --50.7764 34.3913 -4.63752 --51.5161 35.5137 0.721369 --4.56016 3.74791 1.22051 --4.51818 3.73085 1.32524 --4.51559 3.74174 1.43152 --4.52844 3.76312 1.53952 --4.53865 3.78301 1.64857 --4.53993 3.79641 1.75728 --4.55503 3.81919 1.86932 --4.57747 3.84742 1.98369 --4.60558 3.87985 2.10142 --10.7855 8.2472 3.63749 --10.5576 8.1145 3.83256 --10.7735 8.29628 4.14187 --9.29668 7.27442 3.95938 --9.45395 7.41385 4.23595 --9.56711 7.52129 4.5073 --9.58908 7.56517 4.75345 --8.44852 6.76801 4.54809 --4.22956 3.73097 3.00861 --4.20191 3.72379 3.11343 --4.18906 3.72789 3.22458 --4.28594 3.81278 3.39143 --4.00796 3.62199 3.37125 --4.1664 3.75318 3.57631 --4.153 3.75834 3.69322 --4.18077 3.7929 3.83681 --4.0125 3.68176 3.8618 --3.7247 3.48027 3.8018 --3.9732 3.68234 4.09402 --3.81135 3.57554 4.11201 --3.75461 3.54623 4.20066 --4.07522 3.80751 4.58073 --3.60385 3.46138 4.3467 --5.41515 4.88051 5.99945 --5.26302 4.78518 6.06623 --5.1318 4.70501 6.14561 --5.02453 4.64439 6.245 --3.27399 3.28245 4.73454 --3.26468 3.29185 4.86705 --3.08909 3.16897 4.82894 --2.77522 2.93198 4.62893 --2.70671 2.89256 4.68796 --2.64896 2.86246 4.75878 --2.59654 2.83492 4.83562 --2.54283 2.80786 4.91121 --2.44986 2.74796 4.93618 --1.7608 2.18814 4.13972 --1.71739 2.16523 4.19767 --1.69937 2.16456 4.29199 --1.60442 2.09821 4.27303 --1.59337 2.10234 4.38219 --1.9467 2.42526 5.10144 --3.16055 3.50943 7.35818 --1.7314 2.27408 5.05038 --1.86151 2.4099 5.45858 --1.79888 2.37364 5.52077 --1.73065 2.33401 5.57336 --2.72546 3.2754 7.87979 --0.66957 1.39012 3.63311 --0.671065 1.40522 3.75478 --0.562475 1.31507 3.61712 --1.10284 1.85518 5.11452 --0.759756 1.54002 4.40015 --0.68603 1.48661 4.36754 --0.599453 1.41814 4.2878 --0.583247 1.42235 4.41366 --0.49021 1.34685 4.30268 --0.502519 1.38201 4.53856 --0.432659 1.33004 4.49815 --0.570704 1.51238 5.26817 --0.423083 1.37365 4.93779 --0.308843 1.26987 4.70568 --0.271199 1.25733 4.81184 --0.200899 1.20297 4.75535 --0.12978 1.14507 4.67772 --0.121088 1.17491 4.984 --0.0633145 1.1378 5.0008 --0.00376072 1.09801 5.00682 --0.190475 1.4789 7.20813 --0.0693089 1.36291 6.91525 --2.02281 1.84034 -1.42309 --2.0811 1.88553 -1.39652 --2.1736 1.95111 -1.39859 --2.28581 2.0311 -1.41556 --2.40701 2.11613 -1.43423 --2.53602 2.207 -1.4543 --2.66541 2.29899 -1.4694 --2.81136 2.40117 -1.4907 --2.93592 2.49092 -1.49055 --3.07588 2.59168 -1.49629 --3.20989 2.68788 -1.49161 --3.39544 2.81924 -1.51577 --3.56055 2.93833 -1.51889 --3.77109 3.08753 -1.54268 --4.03583 3.27286 -1.58874 --4.24987 3.42555 -1.59477 --4.58585 3.6619 -1.65734 --4.85614 3.85422 -1.67127 --5.40461 4.23495 -1.8085 --6.09828 4.71451 -1.9873 --6.72562 5.15414 -2.10711 --7.55401 5.73099 -2.28184 --8.59185 6.45435 -2.50218 --9.97586 7.41787 -2.80419 --14.5303 10.5518 -4.13747 --15.0231 10.9269 -3.96172 --15.0987 11.0174 -3.64128 --21.9344 15.7696 -5.19884 --22.0914 15.9332 -4.74918 --22.3621 16.1762 -4.32169 --22.3934 16.2536 -3.83383 --40.0737 28.6746 -6.72199 --47.6373 34.1963 -6.10312 --47.9301 34.6334 -4.07641 --4.41352 3.84002 1.04431 --4.35862 3.81129 1.14874 --4.35862 3.82351 1.25329 --4.38197 3.8524 1.35964 --4.41911 3.8906 1.46902 --4.44622 3.92333 1.57925 --4.49712 3.97238 1.6941 --11.0771 8.84089 2.81222 --10.7745 8.64526 3.01607 --10.6681 8.59429 3.24715 --10.7009 8.64768 3.50597 --10.3917 8.44435 3.68552 --10.6767 8.68649 4.01078 --9.92711 8.15007 4.05323 --9.51444 7.86567 4.16835 --9.24971 7.69093 4.31614 --8.01172 6.77575 4.1041 --8.59506 7.24408 4.53512 --5.552 4.93705 3.51397 --5.52407 4.93159 3.65276 --5.56092 4.97687 3.82203 --3.97812 3.76828 3.2103 --4.34312 4.06576 3.51423 --4.15711 3.93408 3.54251 --4.01415 3.8366 3.58793 --3.80797 3.68824 3.59023 --3.73054 3.64109 3.66318 --3.68793 3.62044 3.75644 --3.80314 3.72521 3.9567 --3.80344 3.74046 4.08563 --3.70726 3.67763 4.14594 --4.36529 4.22314 4.78379 --3.69857 3.69991 4.40562 --5.96341 5.55921 6.43274 --3.32063 3.4227 4.3568 --3.27416 3.39958 4.44781 --3.22785 3.37527 4.53796 --2.94441 3.15643 4.39922 --2.84366 3.08684 4.42728 --2.78566 3.05203 4.49599 --2.73151 3.02137 4.56996 --2.69404 3.00498 4.66239 --2.66171 2.99219 4.76101 --3.39985 3.64172 5.80472 --7.98625 7.61825 11.8001 --1.52769 2.05808 3.71014 --2.17978 2.63892 4.70279 --1.83087 2.34757 4.34837 --2.04283 2.54983 4.78656 --1.62711 2.19473 4.2958 --1.54399 2.1343 4.29128 --1.93529 2.50343 5.06634 --3.07245 3.55996 7.18013 --1.83537 2.44798 5.21736 --1.62174 2.26889 4.98921 --1.79362 2.4485 5.48771 --1.72377 2.40274 5.53296 --1.63657 2.34125 5.54337 --1.31624 2.05358 5.03572 --1.25253 2.01132 5.07026 --1.17483 1.95597 5.06851 --1.11186 1.91322 5.09981 --0.748215 1.56625 4.33773 --0.69926 1.53409 4.36786 --0.641583 1.49289 4.36985 --0.580438 1.44766 4.36169 --0.500183 1.38202 4.28803 --0.487721 1.38881 4.43195 --0.656843 1.60263 5.25073 --0.604849 1.57199 5.31713 --0.448597 1.42053 4.96107 --0.355131 1.33767 4.82527 --0.284714 1.28068 4.77143 --0.203818 1.20992 4.65868 --0.199106 1.23882 4.94556 --0.14652 1.20427 4.9837 --0.10205 1.18449 5.08841 --0.031903 1.1262 5.01789 --0.196808 1.4563 6.90408 --0.0723294 1.32649 6.54344 --1.95426 1.91725 -1.38077 --2.05043 1.98932 -1.39147 --2.16634 2.07584 -1.41687 --2.27151 2.15461 -1.42625 --2.3965 2.24811 -1.44907 --2.52282 2.34293 -1.46715 --2.65024 2.44004 -1.48059 --2.77268 2.53278 -1.48383 --2.90202 2.6313 -1.48766 --3.04584 2.74077 -1.49657 --3.17691 2.84183 -1.49021 --3.35178 2.97407 -1.50751 --3.54328 3.11834 -1.52722 --3.74954 3.2744 -1.54823 --4.02382 3.47886 -1.59963 --4.30753 3.69132 -1.64397 --4.6083 3.91713 -1.6849 --4.94817 4.17226 -1.73248 --5.62358 4.66913 -1.9276 --6.28896 5.16145 -2.08713 --7.03484 5.71566 -2.25214 --7.8638 6.33243 -2.41752 --9.30651 7.39871 -2.78577 --12.2243 9.54319 -3.63014 --14.0715 10.9207 -3.97443 --14.0606 10.9484 -3.64016 --14.0596 10.9837 -3.31173 --20.7277 15.9288 -4.82801 --21.0973 16.2525 -4.44873 --21.1064 16.3116 -3.97195 --21.7818 16.865 -3.63637 --30.8866 23.7084 -4.85561 --22.3961 17.4304 -2.75902 --31.0949 24.0139 -3.50991 --31.2131 24.1771 -2.83389 --31.2896 24.3096 -2.14939 --31.3646 24.4414 -1.46172 --31.4776 24.6028 -0.772979 --4.28323 3.94433 0.87196 --4.22365 3.90942 0.977514 --4.19459 3.8984 1.08074 --4.21927 3.92921 1.1846 --4.25942 3.97062 1.29067 --4.32089 4.02965 1.40053 --11.6715 9.75082 2.22261 --11.6239 9.74268 2.48856 --11.5093 9.68225 2.7446 --11.3531 9.58935 2.99009 --11.0074 9.34646 3.19487 --10.9004 9.29009 3.43616 --10.1657 8.73717 3.52809 --10.1785 8.77467 3.77986 --9.63759 8.37122 3.87951 --12.9063 11.0086 5.1141 --10.4892 9.10538 4.6433 --7.95189 7.09382 4.01678 --5.34537 5.0134 3.2423 --5.28425 4.98034 3.36368 --3.96978 3.92839 2.94842 --5.37863 5.08831 3.70056 --7.55479 6.88436 4.89522 --4.25749 4.202 3.44246 --5.75978 5.4529 4.36958 --3.88615 3.92282 3.49278 --3.875 3.92602 3.6077 --3.81176 3.88714 3.69345 --3.75587 3.85374 3.78164 --3.72523 3.8417 3.88686 --3.42417 3.60236 3.80207 --3.32057 3.52713 3.84692 --3.26358 3.49205 3.92323 --3.20572 3.45542 3.99821 --3.15919 3.42877 4.08242 --3.06772 3.36388 4.12712 --2.9885 3.30902 4.18026 --2.92156 3.26435 4.24251 --2.86599 3.22983 4.31479 --2.81033 3.19501 4.38569 --2.77126 3.17421 4.47399 --2.74199 3.16256 4.5744 --7.11838 7.06354 9.66089 --3.4816 3.85199 5.71753 --1.63636 2.21561 3.6456 --1.5858 2.18008 3.68165 --3.21311 3.66855 5.91906 --1.4697 2.09675 3.72772 --3.14274 3.64487 6.19814 --1.75298 2.38095 4.35414 --1.67014 2.31743 4.35461 --1.54906 2.21871 4.29188 --1.74807 2.4192 4.74716 --1.52077 2.21893 4.50414 --2.87843 3.5358 7.06241 --1.63792 2.36371 5.00647 --1.65575 2.39837 5.20299 --1.6602 2.42058 5.38585 --1.54071 2.32291 5.32122 --1.4366 2.23768 5.27792 --1.25566 2.07574 5.0528 --1.1756 2.01307 5.04394 --1.12516 1.98003 5.10203 --0.758514 1.61696 4.33681 --0.736256 1.61145 4.43819 --0.637529 1.52381 4.32616 --0.587236 1.48698 4.34552 --0.557308 1.47227 4.42693 --0.448838 1.37038 4.25275 --0.456805 1.40054 4.46974 --0.516796 1.49434 4.91116 --0.406351 1.38813 4.71343 --0.401409 1.40939 4.94346 --0.287363 1.29453 4.69317 --0.249695 1.27692 4.7901 --0.196981 1.23759 4.81042 --0.139587 1.19391 4.81027 --0.0966032 1.17046 4.89555 --0.0561785 1.15144 5.00925 --0.222166 1.47155 6.79524 --0.0784363 1.30198 6.25074 -0.00362981 1.23234 6.18028 --1.77397 1.89473 -1.38538 --1.84109 1.95127 -1.3754 --1.94096 2.02986 -1.39452 --2.03537 2.10596 -1.40394 --2.14325 2.19101 -1.42173 --2.24569 2.2736 -1.42972 --2.36869 2.37215 -1.45117 --2.49882 2.4755 -1.47321 --2.61723 2.57085 -1.47931 --2.72288 2.65773 -1.47041 --2.85678 2.76602 -1.47822 --2.9913 2.87454 -1.48058 --3.15404 3.00601 -1.49721 --3.34655 3.15914 -1.5261 --3.5404 3.31524 -1.54732 --3.77918 3.50492 -1.58698 --4.07712 3.74002 -1.65066 --4.30419 3.92442 -1.66122 --4.45214 4.04869 -1.6189 --5.07935 4.53848 -1.81592 --5.93486 5.20462 -2.09424 --6.58768 5.72001 -2.23893 --7.32806 6.30587 -2.39176 --8.51572 7.24113 -2.69671 --11.0199 9.19782 -3.46066 --13.2752 10.974 -4.01739 --13.8752 11.4735 -3.9019 --19.5288 15.9648 -4.91931 --19.6845 16.1338 -4.50343 --19.7411 16.2265 -4.05822 --19.7 16.2419 -3.59014 --29.5664 24.0996 -5.17176 --29.5893 24.188 -4.49949 --29.5018 24.1884 -3.81023 --29.4286 24.1992 -3.1283 --29.5392 24.3574 -2.47208 --29.8211 24.6534 -1.82786 --4.44301 4.27967 0.681429 --4.11477 4.02599 0.8083 --4.08102 4.00877 0.912558 --4.06105 4.00307 1.01535 --4.07847 4.02867 1.11794 --4.14886 4.09647 1.22392 --11.2872 9.95665 1.77417 --11.2538 9.95798 2.03837 --11.2937 10.019 2.31044 --11.2846 10.0389 2.57922 --11.2481 10.0366 2.84508 --11.0944 9.93691 3.09008 --10.1859 9.20779 3.17874 --5.88609 5.63844 2.46806 --5.94148 5.70008 2.63319 --5.99367 5.75954 2.80181 --6.06564 5.83742 2.97982 --6.13469 5.91232 3.1622 --5.11612 5.06411 2.97533 --5.07525 5.04418 3.10036 --3.7586 3.93402 2.72123 --3.67946 3.8776 2.79712 --3.66461 3.87611 2.89888 --6.35698 6.20917 4.28226 --5.32047 5.33119 3.94802 --5.38603 5.40417 4.14046 --3.51257 3.79029 3.26479 --3.45004 3.74747 3.34079 --3.39287 3.7096 3.41908 --3.34883 3.68172 3.50452 --3.29623 3.64742 3.58443 --3.26288 3.63094 3.67657 --3.20935 3.59486 3.75408 --3.16783 3.56979 3.83993 --3.12452 3.5431 3.92514 --3.08113 3.51615 4.00919 --3.02257 3.47674 4.08176 --2.95825 3.43126 4.14709 --2.92338 3.41229 4.23918 --2.97146 3.46957 4.41231 --3.05088 3.55643 4.62473 --4.84937 5.22819 6.6495 --5.04731 5.43394 7.08075 --7.72665 7.95042 10.3421 --7.74991 8.00921 10.7245 --6.94268 7.28842 10.109 --6.75027 7.14299 10.2103 --4.3302 4.88263 7.38244 --4.31009 4.88815 7.59526 --1.4622 2.18068 3.81705 --1.75779 2.47746 4.35768 --1.70997 2.4442 4.41152 --1.57522 2.32655 4.32961 --1.5607 2.32437 4.43274 --1.44798 2.22754 4.3742 --1.45331 2.24549 4.51519 --1.69532 2.50288 5.10223 --1.53629 2.35987 4.96248 --1.50461 2.34406 5.06093 --1.50633 2.36346 5.23352 --1.42404 2.2966 5.23245 --3.51624 4.5087 10.1704 --1.19935 2.09766 5.07888 --1.1317 2.04433 5.09514 --1.05122 1.97705 5.0747 --0.994365 1.93424 5.11358 --0.75312 1.68867 4.62825 --0.598822 1.53326 4.34706 --0.543668 1.48925 4.34774 --0.456408 1.40704 4.23805 --0.429227 1.39355 4.3271 --0.395972 1.37359 4.3973 --0.404832 1.40691 4.64363 --0.383273 1.4044 4.78908 --0.318465 1.34791 4.7563 --0.295797 1.34688 4.92032 --0.20184 1.25103 4.7326 --0.224878 1.3155 5.17302 --0.139181 1.23002 5.02037 --0.0857512 1.18897 5.04842 --0.0295725 1.14397 5.05568 --0.153719 1.4059 6.60106 --0.0692336 1.33088 6.54299 --1.66312 1.92471 -1.3769 --1.73538 1.98611 -1.37498 --1.81931 2.05873 -1.38355 --1.90469 2.13134 -1.38884 --2.0213 2.22913 -1.42156 --2.10819 2.30361 -1.41967 --2.22717 2.40477 -1.44399 --2.34771 2.5063 -1.46336 --2.45652 2.59976 -1.46708 --2.57219 2.69892 -1.47178 --2.70205 2.80979 -1.48254 --2.83961 2.92785 -1.49324 --2.97782 3.0462 -1.4982 --3.13769 3.18277 -1.51217 --3.35383 3.36475 -1.55683 --3.55008 3.53285 -1.57879 --3.83282 3.77001 -1.64478 --3.94115 3.86835 -1.59396 --4.05547 3.97247 -1.54273 --4.72985 4.52889 -1.78905 --5.38001 5.07066 -1.99089 --6.18175 5.73791 -2.23503 --6.82842 6.28238 -2.36897 --7.76546 7.0678 -2.60033 --9.98105 8.90873 -3.31911 --12.1897 10.7536 -3.92961 --12.3956 10.9542 -3.69998 --12.4567 11.0351 -3.41311 --12.6865 11.2562 -3.17939 --18.5681 16.1889 -4.61125 --18.8891 16.5016 -4.25218 --18.7465 16.4275 -3.76476 --27.4989 23.8266 -5.29908 --27.5621 23.9444 -4.66463 --4.35568 4.40067 0.16321 --4.32331 4.3843 0.280023 --4.07674 4.1859 0.423788 --4.00344 4.13341 0.537006 --3.97447 4.11872 0.6427 --3.9659 4.12218 0.745655 --3.95655 4.12435 0.848343 --3.94545 4.125 0.950887 --3.94919 4.13766 1.05311 --4.07963 4.26026 1.15899 --3.74006 3.97598 1.24808 --3.71615 3.96591 1.34465 --3.7064 3.96686 1.44198 --3.71139 3.9812 1.54065 --3.74377 4.01919 1.64457 --3.70779 3.99731 1.73916 --3.69359 3.99504 1.83642 --3.68494 3.99661 1.93539 --3.66726 3.99136 2.03256 --3.65564 3.9921 2.13112 --3.64352 3.99068 2.22999 --3.62231 3.9823 2.32638 --3.60743 3.97904 2.42475 --3.59083 3.97434 2.52326 --3.55893 3.95621 2.61586 --3.53241 3.94306 2.71085 --3.49792 3.92193 2.80217 --3.47601 3.91246 2.89928 --3.43224 3.88376 2.98549 --3.40131 3.86585 3.07798 --3.3631 3.84098 3.1659 --3.32911 3.82196 3.25671 --3.29552 3.80082 3.34694 --3.25993 3.77905 3.43653 --3.2298 3.76252 3.52967 --3.19139 3.73872 3.61788 --3.16524 3.72501 3.71482 --3.14463 3.71677 3.81627 --3.10262 3.68961 3.90273 --3.07173 3.67349 3.99872 --3.0281 3.64353 4.08377 --2.98342 3.61311 4.16787 --2.98484 3.62738 4.29581 --2.95549 3.61153 4.39634 --2.92906 3.5997 4.50264 --2.89622 3.58085 4.60299 --2.88353 3.58255 4.72772 --2.88072 3.59366 4.86573 --8.05707 8.67776 11.0929 --7.92265 8.58387 11.3127 --6.87192 7.58296 10.3722 --1.53748 2.32076 3.71844 --1.49921 2.29316 3.76792 --4.23737 5.0497 7.74664 --1.75797 2.57581 4.36043 --1.68292 2.51124 4.37187 --1.62149 2.46148 4.403 --1.45502 2.30314 4.25905 --1.50828 2.37069 4.47552 --1.46891 2.34291 4.54065 --1.39366 2.27835 4.54223 --1.54002 2.44627 4.96417 --1.50123 2.4213 5.04723 --1.47215 2.40794 5.15438 --1.33942 2.28054 5.03824 --1.36855 2.32995 5.27715 --2.34782 3.4239 7.78033 --1.09481 2.06485 4.98481 --1.08033 2.06702 5.1291 --0.891019 1.87225 4.8115 --0.841971 1.83465 4.85602 --0.625287 1.60258 4.40138 --0.559353 1.54146 4.36788 --0.51643 1.50897 4.40442 --0.460409 1.45839 4.39473 --0.387195 1.38776 4.319 --0.456097 1.49346 4.78688 --0.377434 1.41825 4.70067 --0.319163 1.3663 4.68703 --0.299653 1.36501 4.85108 --0.28322 1.37138 5.05347 --0.159503 1.22932 4.69368 --0.149654 1.24687 4.95226 --0.0807937 1.17809 4.86509 --0.0524145 1.17092 5.04686 -0.0117885 1.10977 4.98579 --0.0649829 1.29586 6.18159 --0.0175668 1.27888 6.42496 --1.48564 1.88554 -1.36378 --1.5485 1.94401 -1.35967 --1.62347 2.01168 -1.36625 --1.69412 2.07593 -1.36382 --1.79371 2.16551 -1.39045 --1.88305 2.24546 -1.40056 --1.98517 2.33727 -1.41945 --2.07677 2.42029 -1.42251 --2.19303 2.52531 -1.44523 --2.31085 2.6307 -1.46301 --2.42347 2.73271 -1.47059 --2.54906 2.84715 -1.48441 --2.68257 2.96777 -1.49817 --2.83039 3.10046 -1.51643 --2.95182 3.21303 -1.50896 --3.14185 3.38315 -1.54417 --3.33346 3.55537 -1.57113 --3.56716 3.76466 -1.61659 --3.74705 3.92988 -1.61766 --3.75486 3.94733 -1.50736 --3.7831 3.98199 -1.40947 --3.80967 4.01536 -1.31075 --3.82045 4.03595 -1.20406 --3.82231 4.04776 -1.09359 --3.83059 4.06559 -0.98712 --3.83714 4.08195 -0.880599 --3.85616 4.10859 -0.7799 --3.86674 4.12855 -0.676034 --3.87657 4.1473 -0.572044 --3.89243 4.17026 -0.470173 --3.89883 4.18617 -0.365597 --3.91202 4.20753 -0.263167 --3.91572 4.22177 -0.15842 --3.92549 4.24032 -0.0553062 --3.92695 4.25092 0.0498106 --3.88927 4.2281 0.162204 --3.82887 4.18327 0.276638 --3.81121 4.17748 0.38133 --3.79963 4.17604 0.484486 --3.79367 4.18092 0.586102 --3.78717 4.18358 0.687748 --3.76411 4.17274 0.789767 --3.72488 4.14628 0.891485 --3.67685 4.11205 0.991604 --3.64331 4.09044 1.08964 --3.60023 4.05987 1.18631 --3.55603 4.02865 1.28114 --3.54791 4.03074 1.37697 --3.53804 4.03135 1.47275 --3.54219 4.04421 1.57037 --3.53786 4.04858 1.66756 --3.53861 4.05871 1.76616 --3.52452 4.05512 1.86197 --3.53064 4.07016 1.96265 --3.52017 4.07001 2.0606 --3.51581 4.07597 2.16042 --3.51096 4.07981 2.26075 --3.48992 4.07027 2.35647 --3.48235 4.0724 2.45687 --3.46594 4.0666 2.5549 --3.44778 4.05929 2.65287 --3.42146 4.04509 2.74757 --3.40175 4.03519 2.84502 --3.36667 4.01162 2.9355 --3.33052 3.98758 3.02492 --3.2998 3.96863 3.11722 --3.27475 3.95388 3.21287 --3.26746 3.9585 3.31989 --3.25341 3.95442 3.42341 --3.50124 4.20844 3.70343 --3.34031 4.06183 3.71585 --3.28183 4.01648 3.7951 --4.26163 4.99432 4.6635 --4.2707 5.01818 4.82847 --4.28302 5.04534 5.00048 --4.28007 5.05753 5.16416 --4.28573 5.07965 5.34006 --4.28903 5.09942 5.51759 --4.31811 5.14552 5.7254 --4.45765 5.30461 6.05209 --4.33582 5.19928 6.12052 --2.81609 3.67155 4.65981 --2.78666 3.65486 4.7665 --2.73921 3.62026 4.85402 --2.71291 3.60657 4.96638 --4.3627 5.32651 7.20864 --1.50016 2.37603 3.67481 --1.49341 2.37852 3.76582 --1.45086 2.34322 3.80863 --3.3031 4.30495 6.64038 --3.20289 4.21772 6.69931 --1.38536 2.30418 4.03314 --1.55293 2.49411 4.42438 --1.40923 2.35156 4.30909 --1.30362 2.24996 4.24945 --1.40736 2.37545 4.56841 --1.49096 2.4798 4.87032 --1.59926 2.61415 5.24173 --1.46374 2.48023 5.13292 --1.36267 2.38314 5.08457 --1.25639 2.27952 5.01598 --1.24165 2.27923 5.15385 --1.1516 2.19292 5.11385 --1.06381 2.10861 5.07067 --0.93194 1.97183 4.90324 --0.826998 1.86592 4.79159 --0.612302 1.62654 4.33989 --0.562757 1.58199 4.35148 --0.540315 1.57197 4.45163 --0.479044 1.51243 4.42524 --0.434064 1.47415 4.45152 --0.582057 1.68248 5.22346 --0.433545 1.51299 4.87255 --0.354828 1.43262 4.77671 --0.271158 1.34268 4.64065 --0.303019 1.41122 5.05975 --0.212171 1.31207 4.88282 --0.184248 1.30145 5.03726 --0.169765 1.31295 5.29755 --0.0585807 1.17577 4.93111 --0.0337646 1.1744 5.15179 --0.112787 1.35599 6.30794 --0.068548 1.34091 6.57192 --1.37882 1.90502 -1.34994 --1.44559 1.96902 -1.35426 --1.51877 2.03899 -1.36277 --1.59216 2.1096 -1.36846 --1.67103 2.18608 -1.37773 --1.7691 2.27878 -1.40268 --1.86316 2.36732 -1.41756 --1.94451 2.44755 -1.41676 --2.05795 2.5545 -1.44207 --2.17177 2.66256 -1.46241 --2.28037 2.76722 -1.47266 --2.39659 2.87882 -1.48391 --2.5195 2.99726 -1.49555 --2.66205 3.1332 -1.51714 --2.79407 3.26035 -1.52301 --2.9319 3.39439 -1.52788 --3.14954 3.6008 -1.58321 --3.32346 3.76718 -1.59694 --3.43822 3.88235 -1.56387 --3.49964 3.94824 -1.49185 --3.54025 3.99516 -1.40535 --3.55278 4.0156 -1.30153 --3.56335 4.03551 -1.19786 --3.57315 4.05417 -1.09426 --3.58769 4.07753 -0.993925 --3.60149 4.09971 -0.893369 --3.60709 4.11424 -0.789448 --3.63868 4.15376 -0.697425 --3.64182 4.16566 -0.593136 --3.65725 4.189 -0.493992 --3.67074 4.2119 -0.394606 --3.67696 4.22725 -0.292559 --3.67414 4.23348 -0.188192 --3.6703 4.23936 -0.0842881 --3.66495 4.24276 0.0195713 --3.65857 4.24577 0.122773 --3.65803 4.25407 0.224243 --3.65551 4.26182 0.325468 --3.6591 4.27405 0.425742 --3.65505 4.2793 0.526825 --3.64186 4.2751 0.628769 --3.61998 4.26344 0.730476 --3.59727 4.25034 0.831236 --3.57373 4.23577 0.93105 --3.53374 4.20642 1.02988 --3.51405 4.19657 1.12752 --3.49451 4.18552 1.22429 --3.47199 4.17359 1.32035 --3.47113 4.18094 1.41764 --3.49012 4.2075 1.51795 --3.47205 4.19879 1.61408 --3.49523 4.23111 1.71689 --3.48854 4.23319 1.816 --3.49477 4.24856 1.91815 --3.52812 4.29011 2.02798 --3.57971 4.35144 2.14545 --3.67879 4.45969 2.28045 --4.06516 4.85417 2.51473 --4.06171 4.86227 2.63393 --4.05582 4.8678 2.7538 --4.05635 4.87875 2.87689 --4.0473 4.88061 2.99803 --4.04348 4.88864 3.12241 --4.04538 4.90103 3.25084 --4.04465 4.91194 3.38031 --4.04224 4.92153 3.51051 --4.04439 4.93634 3.64525 --4.04438 4.94777 3.78144 --4.04874 4.96548 3.92246 --3.46903 4.38128 3.67841 --3.4878 4.4114 3.81638 --4.04966 5.00369 4.3539 --4.04422 5.01269 4.50009 --4.0502 5.03199 4.65697 --4.05916 5.05549 4.82039 --4.07039 5.08211 4.99106 --4.07391 5.09983 5.15845 --4.07946 5.12162 5.33289 --4.08852 5.14586 5.51495 --4.09401 5.16853 5.69876 --4.1023 5.19254 5.89079 --4.10606 5.21479 6.0848 --4.1013 5.22677 6.27497 --1.78544 2.75455 3.74014 --2.64621 3.69281 4.89945 --2.59365 3.64908 4.97944 --2.56507 3.6316 5.09149 --4.0216 5.23624 7.2419 --3.96721 5.19752 7.39891 --1.51081 2.51267 4.01186 --1.39087 2.3906 3.94157 --1.38899 2.39861 4.04834 --1.33025 2.34388 4.06745 --1.46075 2.50047 4.40812 --1.33959 2.37468 4.32139 --1.24057 2.27507 4.26852 --1.78118 2.90358 5.43684 --1.73508 2.86536 5.52045 --2.82866 4.14609 7.98197 --1.32966 2.42784 5.01526 --1.25884 2.3602 5.02204 --1.27097 2.38832 5.21913 --1.16473 2.27814 5.13917 --1.0408 2.14684 5.00382 --1.05894 2.18561 5.23496 --0.886201 1.99236 4.94539 --0.755242 1.84686 4.74491 --0.55459 1.613 4.30808 --0.520379 1.58453 4.36373 --0.458655 1.52195 4.32829 --0.464029 1.54469 4.52782 --0.397077 1.47548 4.47176 --0.428154 1.53486 4.80202 --0.364652 1.469 4.76303 --0.31408 1.42178 4.77819 --0.271641 1.3862 4.82968 --0.242622 1.36953 4.95628 --0.147831 1.2551 4.72049 --0.126864 1.25195 4.90265 --0.0676387 1.18938 4.85417 --0.0474455 1.19114 5.0844 --0.182063 1.46047 6.62763 --0.0580351 1.29736 6.16162 -0.00842664 1.2343 6.17012 --1.23143 1.87386 -1.35443 --1.28487 1.92934 -1.34843 --1.34392 1.98943 -1.34718 --1.4091 2.05633 -1.3508 --1.48521 2.13322 -1.3649 --1.56252 2.21106 -1.3759 --1.65134 2.30127 -1.39673 --1.73614 2.38728 -1.40767 --1.82119 2.47408 -1.41511 --1.91279 2.56727 -1.42489 --2.02787 2.68328 -1.45401 --2.13995 2.79549 -1.47259 --2.25749 2.9152 -1.49194 --2.36473 3.02512 -1.49546 --2.49033 3.15308 -1.50997 --2.61828 3.28273 -1.51918 --2.75816 3.42602 -1.53257 --2.95016 3.61869 -1.57795 --3.10553 3.77825 -1.58712 --3.24272 3.91975 -1.57554 --3.2762 3.96183 -1.48865 --3.30899 4.0029 -1.40077 --3.34754 4.04902 -1.31568 --3.37158 4.08182 -1.22168 --3.3949 4.11353 -1.12707 --3.42278 4.15103 -1.03534 --3.43749 4.17324 -0.935687 --3.45025 4.19498 -0.835983 --3.4678 4.22157 -0.738863 --3.47811 4.24072 -0.638596 --3.48042 4.25116 -0.535254 --3.48826 4.26765 -0.434717 --3.50069 4.29005 -0.336475 --3.49973 4.29649 -0.233322 --3.50337 4.30885 -0.132465 --3.5126 4.32743 -0.0336341 --3.52769 4.35141 0.063951 --3.52811 4.3599 0.165203 --3.52679 4.36692 0.266504 --3.52447 4.37362 0.36744 --3.52065 4.37787 0.468526 --3.51581 4.38177 0.569148 --3.52356 4.398 0.668518 --3.5239 4.40625 0.7687 --3.57089 4.46346 0.866785 --3.62426 4.52595 0.967518 --3.65495 4.56651 1.07068 --3.74639 4.67024 1.17777 --3.76094 4.693 1.28533 --3.78711 4.72956 1.39487 --3.79909 4.75103 1.50436 --3.81545 4.77718 1.61596 --3.83113 4.80233 1.72865 --3.8442 4.82607 1.84268 --3.84975 4.84152 1.95616 --3.84679 4.84839 2.06883 --3.84922 4.86024 2.18387 --3.85091 4.87094 2.29933 --3.85683 4.88749 2.41767 --3.86819 4.90922 2.53927 --3.87791 4.92974 2.66209 --3.87907 4.94153 2.78341 --3.89188 4.96492 2.91131 --3.90901 4.99447 3.04346 --3.92476 5.02193 3.17732 --3.94534 5.05376 3.31631 --3.95614 5.07755 3.45362 --3.97274 5.10595 3.59604 --3.99829 5.14591 3.74804 --3.9977 5.15661 3.88649 --3.99469 5.16484 4.02608 --3.99533 5.17822 4.17093 --3.98196 5.17606 4.3082 --3.97876 5.18473 4.45521 --3.97314 5.19094 4.60337 --3.9712 5.20241 4.75727 --3.97783 5.22367 4.92281 --3.99402 5.25505 5.10036 --4.01254 5.28968 5.28574 --4.01136 5.30285 5.45708 --4.0568 5.36786 5.68077 --4.04358 5.36931 5.85052 --4.05425 5.39677 6.05126 --1.552 2.60329 3.38609 --1.78178 2.869 3.7491 --1.51996 2.58214 3.53017 --2.56162 3.77238 4.9586 --2.50006 3.71527 5.02533 --1.56499 2.65905 3.88771 --1.53238 2.63103 3.94868 --1.48074 2.5798 3.98126 --1.35903 2.44883 3.90571 --1.34837 2.44642 3.99802 --1.34124 2.44656 4.09843 --1.28392 2.39003 4.11732 --1.18961 2.28879 4.06621 --1.19582 2.30564 4.19577 --1.32455 2.46945 4.56826 --1.42461 2.60073 4.90942 --1.6542 2.89042 5.54538 --1.26507 2.43457 4.88163 --1.18711 2.35265 4.8636 --1.20878 2.39247 5.07532 --1.12629 2.30604 5.04599 --1.1014 2.29057 5.15824 --0.867295 2.01192 4.71264 --0.885333 2.04933 4.93228 --0.767164 1.91371 4.76922 --0.556023 1.658 4.30038 --0.518242 1.62188 4.33859 --0.479419 1.58532 4.37595 --0.444609 1.55443 4.43075 --0.597195 1.77657 5.1979 --0.522317 1.69389 5.13704 --0.370373 1.50444 4.7396 --0.319591 1.45325 4.746 --0.259791 1.38772 4.7042 --0.243601 1.38605 4.87764 --0.193519 1.33531 4.89047 --0.152295 1.29842 4.94936 --0.105419 1.25195 4.97897 --0.0490263 1.19192 4.94945 --0.160825 1.41435 6.21779 --0.0879973 1.33411 6.16116 --0.0384498 1.29645 6.31747 --1.12935 1.88394 -1.33585 --1.18548 1.94564 -1.33854 --1.24822 2.01223 -1.34582 --1.30567 2.07519 -1.34397 --1.37901 2.15416 -1.35997 --1.44855 2.22793 -1.36608 --1.52836 2.3147 -1.38258 --1.61491 2.40681 -1.40171 --1.70247 2.50093 -1.41736 --1.79636 2.60244 -1.43536 --1.88017 2.6932 -1.43743 --1.99354 2.8134 -1.4646 --2.10704 2.9357 -1.4869 --2.21025 3.04826 -1.49318 --2.30869 3.15538 -1.48956 --2.44938 3.30526 -1.51775 --2.57884 3.44526 -1.52951 --2.71487 3.59339 -1.54031 --2.9328 3.82495 -1.60648 --3.08982 3.99531 -1.61626 --3.17299 4.09047 -1.56593 --3.22533 4.15271 -1.49055 --3.2699 4.20696 -1.40889 --3.29453 4.2422 -1.31404 --3.31152 4.26813 -1.21437 --3.32131 4.28677 -1.11087 --3.31569 4.29041 -1.00046 --3.33593 4.31864 -0.903707 --3.34149 4.33306 -0.800272 --3.34531 4.34597 -0.696983 --3.35488 4.36393 -0.596495 --3.36347 4.38163 -0.496081 --3.37056 4.39693 -0.395323 --3.36306 4.39696 -0.289926 --3.37398 4.41692 -0.191534 --3.38419 4.43573 -0.0927269 --3.39268 4.45314 0.00642204 --3.40778 4.47715 0.104104 --3.4001 4.47665 0.207167 --3.38572 4.4693 0.310529 --3.3698 4.45937 0.413457 --3.33875 4.43429 0.51713 --3.33306 4.43664 0.616319 --3.36052 4.47393 0.712649 --3.42776 4.55448 0.807859 --3.54174 4.68589 0.904958 --3.62629 4.78611 1.00842 --3.64206 4.81213 1.11505 --3.66315 4.84294 1.22319 --3.68334 4.87375 1.33242 --3.68858 4.88825 1.44172 --3.69891 4.90852 1.55242 --3.70101 4.9194 1.66318 --3.71576 4.94445 1.77648 --3.72814 4.96713 1.89132 --3.72616 4.97426 2.00406 --3.74301 5.00187 2.12217 --3.75845 5.02736 2.2418 --3.77225 5.05164 2.36264 --3.80334 5.09553 2.49154 --3.82003 5.12377 2.61786 --4.00905 5.34483 2.81431 --7.95446 9.78049 4.60904 --4.69983 6.14204 3.38517 --5.67768 7.25542 4.00745 --4.90039 6.39322 3.79414 --5.12961 6.66497 4.08059 --5.10601 6.65096 4.23888 --5.20245 6.77451 4.47104 --5.47823 7.10234 4.82523 --4.84059 6.39061 4.59293 --5.49153 7.14907 5.22217 --5.74326 7.4528 5.60549 --5.20043 6.84626 5.40219 --4.94473 6.567 5.39498 --4.82915 6.44896 5.491 --1.81057 2.97141 3.05313 --4.09182 5.62481 5.21072 --4.34794 5.93638 5.62658 --4.16141 5.73353 5.63151 --4.11246 5.69057 5.76666 --4.07252 5.65935 5.91216 --3.98239 5.56907 6.00515 --1.52175 2.68216 3.36672 --1.45533 2.61133 3.37821 --1.45566 2.6185 3.46815 --1.43475 2.60057 3.53338 --4.29252 6.01876 7.44812 --1.53304 2.73318 3.86276 --1.51113 2.716 3.93786 --1.49343 2.70234 4.01986 --1.46427 2.67664 4.08787 --1.39949 2.60702 4.09814 --1.35211 2.55781 4.1354 --1.35119 2.56709 4.2522 --1.2152 2.40928 4.13012 --1.19293 2.3904 4.20758 --1.30043 2.5343 4.53989 --1.16395 2.37398 4.40124 --1.34125 2.6081 4.90779 --1.19809 2.43885 4.74926 --1.10175 2.32856 4.68225 --1.07745 2.30944 4.77616 --1.24464 2.5363 5.34596 --0.8859 2.08868 4.60953 --0.86467 2.07234 4.70814 --0.847224 2.06263 4.82408 --0.797299 2.01115 4.85341 --0.75064 1.96307 4.89015 --0.599044 1.77462 4.58835 --0.561029 1.73657 4.63781 --0.460808 1.61485 4.46966 --0.53583 1.73294 4.93418 --0.536888 1.75105 5.15707 --0.422379 1.60824 4.9195 --0.319057 1.47834 4.69535 --0.301044 1.46948 4.84136 --0.23901 1.39929 4.78989 --0.196214 1.3543 4.82174 --0.148973 1.30401 4.83332 --0.107445 1.26286 4.8822 --0.0585732 1.20868 4.88204 --0.0369133 1.20099 5.08368 --0.147393 1.42726 6.42279 --0.050843 1.30083 6.1515 -0.0125147 1.23235 6.15041 --1.09349 1.96259 -1.33439 --1.14851 2.02528 -1.336 --1.20868 2.09454 -1.34255 --1.26904 2.16438 -1.34648 --1.34106 2.24539 -1.3612 --1.41308 2.32805 -1.373 --1.50715 2.43362 -1.40714 --1.57538 2.5128 -1.40585 --1.67705 2.62689 -1.43837 --1.74676 2.70785 -1.43029 --1.84981 2.82509 -1.45437 --1.9479 2.93799 -1.46806 --2.07012 3.0763 -1.49956 --2.17087 3.19186 -1.50367 --2.28343 3.32067 -1.5137 --2.40249 3.45741 -1.52364 --2.52808 3.60218 -1.53311 --2.69581 3.79267 -1.57013 --2.90125 4.02512 -1.62724 --3.05426 4.20149 -1.63366 --3.154 4.31862 -1.59343 --3.18016 4.35637 -1.49844 --3.18607 4.37184 -1.39034 --3.19764 4.39208 -1.2863 --3.202 4.40496 -1.17873 --3.21107 4.42246 -1.07481 --3.22465 4.44563 -0.974257 --3.23123 4.46042 -0.870262 --3.24234 4.48093 -0.769438 --3.25271 4.50025 -0.668393 --3.27394 4.53272 -0.572669 --3.28186 4.54947 -0.470965 --3.29559 4.5714 -0.371479 --3.30738 4.59293 -0.271654 --3.3177 4.61211 -0.171193 --3.32706 4.63109 -0.0706109 --3.33591 4.64792 0.0303893 --3.33006 4.6492 0.134764 --3.30327 4.62611 0.242916 --3.24974 4.57182 0.354244 --3.19404 4.5164 0.462701 --3.15786 4.48148 0.565588 --3.14583 4.47474 0.664012 --3.14591 4.48221 0.760788 --3.15194 4.49534 0.857389 --3.21508 4.57598 0.952885 --10.0842 12.5056 1.07584 --10.0065 12.4362 1.35562 --9.78809 12.2044 1.62407 --9.14423 11.4781 1.84583 --8.70724 10.9901 2.05707 --8.58189 10.862 2.28858 --8.36927 10.6325 2.50046 --8.10984 10.3475 2.6931 --8.16494 10.4296 2.94193 --8.23661 10.5302 3.19942 --8.17658 10.4773 3.42665 --8.26652 10.6011 3.6981 --5.4984 7.36006 3.02869 --5.46875 7.33782 3.19001 --5.44916 7.3284 3.35549 --7.93332 10.2809 4.56915 --5.65334 7.59573 3.79744 --7.44284 9.73567 4.83716 --4.85344 6.67018 3.76181 --4.9252 6.76803 3.96544 --4.77718 6.6039 4.05023 --4.79072 6.63205 4.22552 --4.45782 6.24468 4.18455 --5.3514 7.33074 4.94304 --5.15417 7.10763 4.9999 --5.81817 7.92394 5.67965 --5.30092 7.3128 5.49964 --4.86324 6.79858 5.35235 --1.87483 3.18336 3.03552 --1.7995 3.0976 3.0566 --1.77901 3.07929 3.12455 --1.74163 3.03984 3.17664 --4.10402 5.9413 5.60736 --3.9937 5.8185 5.67918 --3.96158 5.79253 5.83053 --5.12154 7.23928 7.31557 --1.46862 2.7347 3.32377 --1.49442 2.77452 3.44442 --1.43534 2.70689 3.46255 --1.41472 2.68818 3.52876 --1.38959 2.66273 3.58808 --1.42311 2.71358 3.73239 --1.44536 2.74895 3.86624 --1.47024 2.78688 4.00928 --2.19441 3.71413 5.25342 --1.40135 2.71607 4.12518 --1.32562 2.62762 4.11349 --1.48047 2.83575 4.50125 --1.19695 2.48 4.11797 --1.17973 2.46614 4.20348 --1.14103 2.4254 4.25093 --1.12916 2.41917 4.35159 --2.66268 4.43364 7.71724 --1.33709 2.71093 5.07412 --1.10382 2.41584 4.70535 --1.01887 2.31347 4.65278 --0.975626 2.26757 4.69597 --0.944494 2.23677 4.77216 --0.856489 2.12953 4.6947 --0.840277 2.11917 4.81111 --0.851134 2.14721 5.01438 --0.704872 1.95888 4.74731 --0.770405 2.06303 5.13572 --0.521322 1.72882 4.49584 --0.599754 1.85257 4.94814 --0.59683 1.86405 5.14384 --0.460566 1.68308 4.82934 --0.499677 1.75654 5.20774 --0.340212 1.53729 4.74655 --0.296168 1.48958 4.77181 --0.246487 1.43233 4.76799 --0.25999 1.47061 5.09353 --0.162542 1.33963 4.83177 --0.121766 1.29471 4.87168 --0.0724483 1.23751 4.86258 --0.0561432 1.23516 5.08357 --0.147401 1.42255 6.20748 --0.0808212 1.34369 6.17032 --0.0411205 1.31332 6.38551 --1.10723 2.10608 -1.33287 --1.18053 2.19343 -1.35909 --1.23433 2.26015 -1.35504 --1.30383 2.34395 -1.36845 --1.36829 2.42323 -1.37235 --1.45458 2.52636 -1.39878 --1.55128 2.64294 -1.43365 --1.62978 2.73682 -1.43963 --1.71243 2.8386 -1.44801 --1.81279 2.95978 -1.47011 --1.90842 3.07568 -1.48162 --2.02069 3.21212 -1.50517 --2.13532 3.35027 -1.52333 --2.26062 3.50265 -1.54642 --2.37096 3.63686 -1.54805 --2.48781 3.77902 -1.54949 --2.70169 4.03682 -1.62622 --2.88361 4.25587 -1.66406 --3.01416 4.41767 -1.65308 --3.0465 4.46236 -1.56238 --3.05936 4.48606 -1.4584 --3.0779 4.51461 -1.35809 --3.10619 4.55564 -1.26503 --3.12232 4.58171 -1.16368 --3.14922 4.62062 -1.06901 --3.1807 4.66544 -0.976636 --3.20527 4.70211 -0.879847 --3.23443 4.74474 -0.785158 --3.26293 4.78641 -0.689276 --3.2784 4.81151 -0.58673 --3.31086 4.85825 -0.491365 --3.31761 4.87354 -0.385133 --3.34896 4.91733 -0.287476 --3.3281 4.89925 -0.172369 --3.31791 4.89536 -0.0623908 --3.31449 4.89689 0.0453448 --3.32088 4.91276 0.149726 --3.32035 4.91885 0.255703 --3.3319 4.939 0.359351 --3.06905 4.62851 0.504048 --3.00754 4.56058 0.609802 --2.95793 4.50623 0.711087 --2.92653 4.47445 0.808182 --2.90646 4.45558 0.903363 --2.9168 4.47544 0.996888 --2.95194 4.52378 1.09169 --3.81291 5.58647 1.22409 --3.88221 5.67885 1.34854 --3.95562 5.77843 1.47744 --4.02809 5.87557 1.61097 --4.07967 5.94685 1.74603 --4.15432 6.04852 1.88865 --8.05325 10.8816 2.84272 --21.1593 27.1378 6.22412 --7.97468 10.8153 3.31129 --7.82876 10.6519 3.51356 --7.65181 10.4468 3.69898 --8.38315 11.375 4.1993 --7.56718 10.3741 4.1488 --7.47635 10.2753 4.35345 --5.34478 7.62234 3.64595 --4.65346 6.76613 3.4956 --5.06513 7.29489 3.86573 --4.63351 6.7619 3.80816 --4.79099 6.97129 4.06203 --4.19963 6.23563 3.8769 --4.42225 6.52889 4.17358 --4.18762 6.2422 4.18139 --4.81745 7.05297 4.78405 --5.27045 7.64174 5.30293 --5.09442 7.43133 5.37035 --1.89179 3.35309 2.97722 --1.80704 3.25143 2.99375 --3.91233 5.95621 4.94048 --1.75825 3.20002 3.1234 --1.70119 3.13185 3.15682 --1.68111 3.11144 3.22429 --1.63871 3.0631 3.26992 --3.93388 6.0438 5.84892 --4.5798 6.89481 6.76827 --1.42146 2.79962 3.29288 --1.39446 2.77063 3.34749 --1.35775 2.72714 3.38944 --4.17709 6.42928 7.17878 --1.3709 2.7573 3.59011 --1.30827 2.68146 3.59823 --1.32337 2.70759 3.7163 --6.0439 8.96841 10.9986 --5.77408 8.63411 10.9456 --2.10906 3.77504 5.31468 --1.3578 2.78145 4.19856 --1.27517 2.67885 4.17249 --1.19475 2.57811 4.14264 --1.12625 2.49476 4.13172 --1.11805 2.49042 4.23209 --1.16338 2.56131 4.44881 --1.26692 2.71183 4.80253 --1.32794 2.80429 5.08424 --1.29877 2.77444 5.17785 --1.03652 2.42377 4.71762 --0.928057 2.28276 4.59802 --0.87994 2.2257 4.62364 --0.820714 2.15219 4.61361 --0.806196 2.14319 4.72949 --0.860993 2.23113 5.05256 --0.820491 2.18582 5.11052 --0.705868 2.03385 4.93023 --0.642753 1.95505 4.90442 --0.586013 1.88424 4.89431 --0.573727 1.87973 5.04437 --0.479693 1.75421 4.88596 --0.495684 1.79159 5.16363 --0.453753 1.743 5.21257 --0.319285 1.55509 4.84215 --0.247662 1.45988 4.72714 --0.217476 1.42695 4.80714 --0.186011 1.39559 4.89622 --0.141645 1.3419 4.90826 --0.0947724 1.28439 4.90994 --0.0485387 1.22776 4.91004 --0.0278234 1.21521 5.10231 -0.0202938 1.15665 5.10042 --0.0453373 1.3067 6.1509 -0.0122628 1.23751 6.16989 --1.2051 2.36634 -1.37561 --1.27305 2.4532 -1.38765 --1.3506 2.55205 -1.40907 --1.41906 2.64045 -1.4143 --1.49861 2.74329 -1.42906 --1.58377 2.85238 -1.44565 --1.67431 2.96876 -1.46398 --1.77102 3.0937 -1.48388 --1.87927 3.2328 -1.5101 --1.99914 3.38625 -1.54177 --2.09895 3.51518 -1.54615 --2.2214 3.6727 -1.56638 --2.34359 3.83046 -1.58007 --2.47311 3.99763 -1.59263 --2.68587 4.26993 -1.66906 --2.87379 4.51056 -1.7114 --2.94472 4.60565 -1.65181 --3.00353 4.68756 -1.58054 --3.25595 5.01108 -1.64486 --4.16414 6.15905 -2.14078 --4.82193 6.99611 -2.41769 --5.64903 8.04786 -2.75868 --6.57614 9.22976 -3.10856 --7.88085 10.8927 -3.61227 --8.86573 12.1542 -3.87013 --9.09826 12.4669 -3.69946 --9.03833 12.4087 -3.38159 --12.2895 16.558 -4.5041 --12.5332 16.8923 -4.22226 --12.5532 16.9399 -3.84442 --12.7609 17.2294 -3.53303 --18.7237 24.8755 -5.02705 --18.7639 24.9599 -4.48009 --18.7669 24.9982 -3.92403 --3.33751 5.22488 0.160226 --3.27065 5.14464 0.28396 --3.24431 5.11732 0.396526 --3.23519 5.1123 0.504829 --2.99287 4.8058 0.639181 --2.81599 4.58398 0.753954 --2.77324 4.53364 0.851151 --2.74756 4.50681 0.945054 --2.71477 4.4696 1.03793 --2.69291 4.44742 1.12937 --2.68881 4.44748 1.22073 --2.67838 4.43848 1.31142 --2.69601 4.4676 1.4054 --2.69523 4.47186 1.49783 --3.86565 6.00755 1.79288 --3.9069 6.0702 1.92912 --3.9593 6.14626 2.07106 --4.00383 6.21235 2.21491 --4.04022 6.2693 2.3599 --4.09272 6.34674 2.51344 --4.14422 6.42155 2.67074 --4.19251 6.49419 2.83154 --4.25018 6.58034 3.00062 --4.45773 6.86348 3.24119 --5.13511 7.77179 3.72022 --5.19344 7.85916 3.92989 --5.02528 7.64671 4.0237 --3.72174 5.92211 3.45827 --3.75416 5.97278 3.61823 --3.95114 6.24576 3.8883 --4.27243 6.68352 4.25703 --4.65119 7.20186 4.6923 --4.67822 7.24948 4.89467 --3.69559 5.93987 4.31501 --1.87237 3.49258 2.97882 --1.83288 3.44594 3.03423 --1.75706 3.34851 3.05541 --2.09217 3.80673 3.4556 --1.71343 3.3008 3.19165 --1.62286 3.18225 3.1894 --1.59247 3.14658 3.24629 --4.53391 7.16221 6.56184 --2.15818 3.92996 4.07227 --4.26897 6.82671 6.69487 --1.69575 3.31048 3.74595 --1.52852 3.08655 3.6363 --4.1526 6.70727 7.22082 --1.34552 2.84563 3.58521 --1.39229 2.91744 3.74888 --1.79023 3.47481 4.44064 --1.34374 2.86114 3.88003 --1.2689 2.76309 3.86663 --1.11961 2.56108 3.72469 --1.09688 2.53581 3.78708 --1.10255 2.54996 3.8992 --1.16894 2.64996 4.12977 --1.24637 2.76622 4.39512 --1.15609 2.64554 4.34173 --1.5037 3.14876 5.18721 --2.13064 4.05129 6.69189 --1.19926 2.73201 4.83375 --1.24641 2.80889 5.09236 --1.10112 2.60846 4.90258 --0.897421 2.32405 4.54997 --0.852476 2.26677 4.57581 --0.832579 2.24508 4.6673 --0.801342 2.20897 4.73319 --0.905081 2.3717 5.20131 --1.1278 2.71424 6.07501 --0.653097 2.01916 4.77045 --0.656131 2.03525 4.95592 --0.59633 1.955 4.92927 --0.565538 1.91962 5.00832 --0.54479 1.90125 5.13201 --0.460803 1.78274 5.00047 --0.447118 1.77549 5.15926 --0.324749 1.59747 4.83731 --0.308707 1.58519 4.98477 --0.256356 1.51636 4.96372 --0.176603 1.40073 4.78023 --0.135898 1.34997 4.80202 --0.0943661 1.29776 4.82287 --0.0513118 1.24094 4.82329 --0.037402 1.23707 5.04424 --0.0180599 1.22474 5.25621 --0.0745984 1.3545 6.18932 --0.0211443 1.28743 6.2288 --1.23704 2.56352 -1.40556 --1.29794 2.64681 -1.40609 --1.38312 2.76281 -1.43504 --1.46429 2.87467 -1.45381 --1.54699 2.98677 -1.46822 --1.62468 3.0944 -1.47283 --1.72815 3.2349 -1.50178 --1.83278 3.37784 -1.52542 --1.94879 3.53613 -1.55449 --2.06014 3.68932 -1.5722 --2.1881 3.86464 -1.59934 --2.31755 4.04176 -1.61958 --2.46375 4.24145 -1.64731 --2.67545 4.52842 -1.72265 --2.86134 4.78347 -1.76398 --3.05512 5.04798 -1.79951 --3.29842 5.38121 -1.86186 --3.72544 5.95933 -2.04233 --4.41527 6.89287 -2.37878 --5.06248 7.77102 -2.64259 --5.8893 8.89214 -2.97816 --6.97501 10.3651 -3.41648 --8.57263 12.5319 -4.07524 --8.78785 12.8372 -3.89934 --11.2978 16.2468 -4.8603 --11.4685 16.4965 -4.56955 --11.5558 16.6348 -4.23509 --11.5929 16.7055 -3.87772 --11.6908 16.857 -3.54301 --12.6036 18.1176 -3.48621 --13.0047 18.6851 -3.21513 --17.6905 25.0951 -4.1419 --17.5813 24.9749 -3.56739 --17.5483 24.9576 -3.01851 --17.6143 25.0766 -2.49268 --3.17759 5.33493 0.430983 --3.11046 5.24826 0.549404 --3.09457 5.23221 0.658235 --2.85388 4.90838 0.78302 --2.80134 4.83982 0.885163 --2.66997 4.66514 0.985384 --2.5857 4.55324 1.07861 --2.54111 4.49777 1.16847 --2.49026 4.43178 1.25562 --2.43919 4.3651 1.33975 --2.38596 4.29732 1.42111 --2.35049 4.25183 1.50259 --2.30902 4.19886 1.58055 --2.27153 4.15102 1.65818 --2.23365 4.10365 1.73348 --2.20736 4.06999 1.81037 --2.17976 4.03674 1.88572 --2.15155 4.00102 1.96003 --2.11068 3.94943 2.02869 --2.08694 3.92093 2.10206 --2.07973 3.91473 2.18212 --4.10681 6.76481 3.23042 --4.13052 6.80567 3.39406 --4.16287 6.85885 3.5662 --3.69912 6.21356 3.45652 --3.91564 6.52726 3.73239 --3.73307 6.27698 3.76736 --3.94224 6.58168 4.05927 --4.17431 6.91775 4.38382 --4.09371 6.81213 4.49282 --4.39431 7.24856 4.9002 --1.7839 3.54615 2.92736 --2.19515 4.1361 3.37005 --1.77547 3.54457 3.09703 --2.04053 3.92673 3.43718 --1.97355 3.836 3.47499 --1.65036 3.37844 3.24614 --3.71422 6.34507 5.54222 --1.74921 3.53157 3.54206 --2.07949 4.01069 4.02351 --1.81128 3.63072 3.8193 --1.67377 3.43854 3.75628 --1.57553 3.30123 3.73356 --1.53193 3.24409 3.7787 --1.41375 3.07684 3.71652 --1.36204 3.00858 3.74309 --1.32411 2.95787 3.78718 --1.75645 3.59398 4.56406 --1.25145 2.86201 3.87797 --1.21201 2.81112 3.91789 --1.02012 2.53463 3.69069 --1.0433 2.57346 3.82995 --1.07099 2.62007 3.98614 --1.22877 2.85909 4.4028 --1.53008 3.31298 5.13674 --1.47507 3.23936 5.17689 --1.36709 3.08718 5.09915 --1.17093 2.80168 4.81334 --1.25317 2.9319 5.15042 --1.11661 2.73557 4.98013 --0.898313 2.41318 4.58342 --0.807036 2.28236 4.48738 --0.785717 2.25742 4.56994 --0.845542 2.35715 4.88813 --1.12221 2.79031 5.8759 --1.0799 2.73585 5.95272 --0.679112 2.12666 4.87261 --0.644464 2.0811 4.92742 --0.605636 2.03042 4.9727 --0.546974 1.94923 4.94525 --0.49012 1.86808 4.9158 --0.435802 1.79311 4.89289 --0.440218 1.8099 5.11552 --0.38113 1.72636 5.07218 --0.32579 1.6483 5.03555 --0.255847 1.54653 4.92231 --0.186516 1.44344 4.78681 --0.141006 1.37961 4.77162 --0.138911 1.38995 5.02158 --0.0567263 1.26378 4.77497 --0.0351237 1.24204 4.91891 --0.0218696 1.23622 5.14992 -0.00912295 1.19885 5.26521 --0.0489919 1.33095 6.24824 -0.018029 1.23214 6.13062 --0.657314 1.88764 -1.31632 --0.698082 1.94859 -1.31945 --1.25946 2.76632 -1.42744 --1.34626 2.89134 -1.4604 --1.41605 2.99286 -1.46478 --1.49506 3.10862 -1.47738 --1.58944 3.24543 -1.50308 --1.67496 3.37081 -1.51258 --1.79009 3.53762 -1.5502 --1.90154 3.69965 -1.57608 --2.02424 3.87826 -1.60644 --2.15262 4.065 -1.63475 --2.28816 4.2623 -1.66124 --2.42354 4.46017 -1.67973 --2.62701 4.75458 -1.74987 --2.8269 5.04614 -1.80419 --3.02886 5.33959 -1.84677 --3.37416 5.83831 -1.98811 --3.95869 6.68235 -2.2857 --4.51799 7.49109 -2.52575 --5.26454 8.56848 -2.85461 --6.11871 9.80488 -3.20417 --7.18016 11.342 -3.62351 --7.58373 11.9332 -3.59622 --7.67732 12.0805 -3.37775 --7.7766 12.2477 -2.88769 --11.5164 17.6652 -4.27193 --11.5758 17.7687 -3.90945 --11.4432 17.593 -3.4731 --11.8568 18.2101 -3.23675 --12.101 18.5827 -2.9232 --12.5452 19.2439 -2.65224 --16.4583 24.9528 -3.22855 --16.5262 25.0752 -2.71451 --16.5897 25.1909 -2.197 --16.6525 25.307 -1.67675 --3.02715 5.44608 0.58936 --2.73007 5.0164 0.727244 --2.58374 4.80735 0.836652 --2.59419 4.82754 0.931636 --2.60394 4.84664 1.02733 --2.64672 4.91318 1.12475 --2.9643 5.38381 1.24088 --2.78551 5.12524 1.33274 --2.47105 4.66768 1.39753 --2.38693 4.54788 1.47782 --2.25152 4.35353 1.54373 --2.17753 4.24801 1.61491 --2.1365 4.19138 1.68986 --2.09552 4.13325 1.76258 --2.05808 4.08221 1.83487 --2.02047 4.03069 1.90501 --1.98272 3.9787 1.97312 --1.94407 3.92507 2.03941 --1.91096 3.87918 2.106 --1.87698 3.83168 2.17096 --1.85808 3.80819 2.24243 --1.85007 3.79896 2.31901 --1.83533 3.78112 2.3925 --1.82555 3.77032 2.46864 --3.5615 6.36877 3.68026 --4.18701 7.30959 4.25644 --4.04827 7.11044 4.32851 --3.93577 6.94868 4.41269 --3.9187 6.93145 4.56793 --4.11685 7.23632 4.9042 --2.09744 4.20694 3.31661 --2.03873 4.12286 3.36649 --1.99929 4.06786 3.43222 --1.96921 4.02632 3.50603 --3.65959 6.58831 5.37161 --1.59319 3.46825 3.31173 --1.68675 3.6134 3.50963 --1.75788 3.72572 3.69256 --1.7245 3.68065 3.75837 --3.80442 6.85068 6.5042 --1.61813 3.52798 3.83346 --1.49275 3.34052 3.76857 --1.47707 3.32197 3.84989 --1.37511 3.17094 3.80598 --1.31287 3.07945 3.81421 --1.26814 3.01494 3.84548 --1.18976 2.89917 3.82175 --1.12514 2.80485 3.81415 --1.72313 3.73288 4.97469 --1.00979 2.6348 3.81109 --0.992262 2.61336 3.88066 --1.53655 3.46354 5.05939 --1.53517 3.46838 5.20601 --1.4 3.26484 5.07528 --1.40485 3.27723 5.23566 --1.28705 3.10023 5.12601 --1.12275 2.8492 4.89233 --0.863149 2.44685 4.40267 --0.872828 2.46814 4.55965 --0.843802 2.42828 4.62005 --0.752708 2.29135 4.51458 --0.909268 2.54674 5.10792 --0.83744 2.4392 5.06036 --1.15453 2.95688 6.22493 --1.07094 2.83122 6.17494 --1.03931 2.79069 6.29603 --0.590852 2.07165 4.93581 --0.50841 1.94555 4.81142 --0.473255 1.89512 4.85349 --0.445483 1.85906 4.93072 --0.391341 1.77796 4.89828 --0.397414 1.79705 5.13004 --0.344534 1.71872 5.10438 --0.261355 1.58905 4.91805 --0.214528 1.51834 4.8966 --0.159388 1.43438 4.82623 --0.113582 1.36633 4.80112 --0.0826781 1.32561 4.86977 --0.0366918 1.25595 4.83209 --0.0280751 1.2533 5.07283 -0.00432966 1.21059 5.159 --0.0710373 1.36898 6.22794 --0.0141804 1.28282 6.18955 --0.573062 1.88821 -1.3041 --0.612553 1.94968 -1.30829 --0.649172 2.00605 -1.30319 --0.703914 2.09113 -1.33337 --0.736593 2.14357 -1.31722 --0.792696 2.23005 -1.34227 --0.850732 2.31861 -1.36464 --0.90401 2.40181 -1.37681 --1.14595 2.77851 -1.43058 --1.21601 2.88605 -1.44682 --1.27721 2.98206 -1.44717 --1.35752 3.10586 -1.46816 --1.43793 3.23162 -1.48487 --1.52378 3.36482 -1.50264 --1.61998 3.51296 -1.52661 --1.7303 3.68442 -1.56143 --1.84697 3.86502 -1.59518 --1.97889 4.06969 -1.63757 --2.10745 4.26883 -1.66714 --2.23731 4.47084 -1.68944 --2.39175 4.7115 -1.72714 --2.55305 4.96114 -1.76007 --2.72575 5.22951 -1.79233 --3.00366 5.65928 -1.90178 --3.53968 6.48515 -2.19864 --4.03157 7.24358 -2.42333 --4.7569 8.36175 -2.78357 --5.43778 9.41423 -3.06284 --6.39139 10.8884 -3.47433 --6.97165 11.7893 -3.58894 --7.65436 12.8488 -3.72502 --7.67253 12.8879 -3.45161 --7.59906 12.7846 -3.13222 --10.9271 17.9298 -4.45554 --11.3296 18.5664 -4.24848 --11.5731 18.9564 -3.95106 --11.6699 19.1215 -3.5847 --11.5619 18.9678 -3.14292 --11.7477 19.2704 -2.80293 --11.9635 19.6196 -2.46114 --15.483 25.0953 -2.92638 --15.5583 25.2302 -2.42138 --15.5908 25.2991 -1.90526 --15.661 25.4278 -1.39396 --8.13003 13.7284 0.0188236 --2.39596 4.80894 0.790047 --2.38569 4.79649 0.884181 --2.396 4.81624 0.977219 --2.41113 4.84261 1.07108 --2.60225 5.14565 1.17383 --2.8474 5.53066 1.2931 --2.84755 5.53546 1.4022 --2.8523 5.54785 1.51201 --2.86752 5.57493 1.6244 --2.9023 5.63326 1.74247 --2.94116 5.69865 1.86439 --2.97331 5.75321 1.98772 --3.00954 5.81486 2.115 --1.99433 4.22242 1.88781 --1.9481 4.15239 1.95508 --1.89053 4.06448 2.01551 --1.82776 3.96881 2.07006 --1.77989 3.89654 2.12849 --1.74701 3.848 2.19217 --1.714 3.79906 2.25409 --1.68108 3.74876 2.31437 --1.65281 3.70618 2.37594 --1.62825 3.67124 2.43953 --1.60382 3.63504 2.50194 --1.60788 3.64491 2.58524 --1.6074 3.64567 2.66548 --1.60521 3.64507 2.74627 --4.06008 7.55487 4.91687 --3.91859 7.33765 4.97606 --1.49334 3.4764 2.89775 --1.62079 3.68342 3.10515 --1.8523 4.05537 3.43109 --1.86968 4.08689 3.55219 --1.55598 3.58932 3.31163 --3.50889 6.72257 5.65184 --1.55894 3.60064 3.50456 --1.65769 3.76353 3.72602 --1.86638 4.10327 4.10133 --1.80611 4.00989 4.13863 --1.30358 3.20453 3.55682 --1.31219 3.22169 3.66475 --1.35645 3.29634 3.82992 --1.24716 3.12427 3.76427 --1.29657 3.2076 3.94488 --1.2168 3.08245 3.91814 --1.14906 2.97729 3.90756 --1.16256 3.00339 4.03758 --1.11465 2.92844 4.05777 --1.57452 3.68158 5.05697 --1.4703 3.51688 4.99544 --1.39591 3.40108 4.98715 --2.07118 4.51228 6.58891 --1.3661 3.36271 5.2178 --1.35527 3.35048 5.34914 --0.882157 2.57666 4.37245 --0.646882 2.19271 3.91207 --1.4472 3.52055 6.09987 --1.04547 2.86214 5.21433 --0.776827 2.421 4.62442 --0.710327 2.31661 4.57555 --0.661869 2.24124 4.57409 --1.43595 3.54236 7.16613 --1.03425 2.87793 6.10453 --0.988255 2.80758 6.16486 --0.92892 2.71613 6.17996 --0.539845 2.06466 4.95291 --0.452279 1.92224 4.79147 --0.456338 1.93417 4.98603 --0.402968 1.85042 4.95506 --0.406191 1.86298 5.16887 --0.358909 1.78906 5.16287 --0.324801 1.73786 5.22025 --0.218126 1.56052 4.89297 --0.201932 1.53884 5.03075 --0.118216 1.39892 4.78047 --0.105466 1.38662 4.95431 --0.0263945 1.25401 4.68805 --0.0260498 1.26237 4.95683 --0.0243682 1.27135 5.26566 -0.023555 1.1946 5.21636 --0.041075 1.33222 6.2284 -0.0329397 1.20738 5.98345 --0.566105 2.01037 -1.29962 --0.607604 2.0787 -1.30859 --0.657013 2.16001 -1.33032 --0.7036 2.23637 -1.3421 --0.750141 2.31426 -1.35154 --0.797832 2.39291 -1.35867 --0.848786 2.47784 -1.36983 --0.904735 2.57053 -1.38506 --0.973589 2.68393 -1.41714 --1.03079 2.77934 -1.42578 --1.09326 2.8817 -1.43762 --1.15963 2.99283 -1.45235 --1.22726 3.10508 -1.46321 --1.30801 3.23873 -1.4879 --1.37236 3.34571 -1.48478 --1.46355 3.49617 -1.51179 --1.55491 3.64885 -1.53344 --1.67435 3.84606 -1.58164 --1.79532 4.04521 -1.62237 --1.93041 4.26937 -1.67083 --2.06808 4.49588 -1.71107 --2.20615 4.72529 -1.74284 --2.34982 4.9643 -1.77052 --2.52797 5.25878 -1.82019 --2.76432 5.64978 -1.90986 --3.19283 6.35605 -2.14817 --3.59709 7.02393 -2.33478 --4.15481 7.94436 -2.61206 --4.74192 8.91483 -2.87067 --5.49597 10.1601 -3.2046 --6.32094 11.5222 -3.53134 --7.25115 13.0611 -3.86628 --7.27103 13.1017 -3.59312 --9.66407 17.0543 -4.64898 --10.0497 17.7011 -4.48428 --10.4507 18.3721 -4.30215 --10.8865 19.1011 -4.1103 --11.5941 20.2821 -4.0044 --11.7543 20.5587 -3.64247 --11.6424 20.3847 -3.1774 --12.7402 22.2134 -3.10049 --12.744 22.2329 -2.64593 --13.0116 22.6868 -2.25689 --13.2439 23.0853 -1.8442 --15.5343 26.8983 -1.7786 --15.5713 26.9742 -1.23892 --15.6091 27.0516 -0.697997 --2.19767 4.78156 0.839271 --2.20857 4.80206 0.930143 --2.21779 4.82124 1.02175 --2.2169 4.82121 1.11392 --2.80159 5.7967 1.24218 --2.77172 5.75104 1.35165 --2.75187 5.72039 1.46068 --2.74627 5.71455 1.57096 --2.74452 5.71509 1.68209 --2.75767 5.73905 1.79709 --2.76915 5.76175 1.91312 --2.80033 5.81608 2.03647 --2.83462 5.8773 2.16399 --2.86314 5.9278 2.29231 --2.88561 5.96841 2.42074 --2.93574 6.05592 2.56489 --2.9799 6.13379 2.71023 --3.5816 7.14622 3.14835 --1.66 3.92465 2.23499 --1.6134 3.84851 2.28845 --1.5721 3.78108 2.34201 --1.53921 3.72918 2.39966 --1.5074 3.67615 2.45564 --1.47928 3.6307 2.51333 --1.45008 3.58471 2.56968 --1.42582 3.5457 2.62851 --1.39641 3.49905 2.68194 --1.36227 3.44275 2.72999 --1.33697 3.40164 2.78495 --1.3106 3.36 2.83866 --1.28925 3.32558 2.89582 --1.26685 3.2907 2.95204 --1.24462 3.25464 3.00747 --1.22133 3.21814 3.06196 --1.19821 3.18043 3.11558 --1.18264 3.15613 3.17917 --1.16605 3.13149 3.2423 --1.1541 3.11226 3.31085 --1.16519 3.13438 3.4144 --1.19571 3.18884 3.54928 --1.32419 3.41032 3.8404 --1.25431 3.29397 3.83416 --1.51183 3.73623 4.36164 --1.06411 2.97477 3.71824 --1.05478 2.95974 3.7988 --1.12859 3.09018 4.03552 --1.38453 3.53153 4.63146 --1.32914 3.44054 4.65418 --1.33488 3.45246 4.796 --1.33371 3.45519 4.93218 --2.44059 5.36697 7.50685 --2.42044 5.33765 7.69866 --0.81075 2.56331 4.14005 --0.826245 2.59378 4.29381 --1.35215 3.50838 5.75446 --1.37512 3.55317 5.99365 --1.34129 3.49977 6.09077 --0.752793 2.4793 4.60996 --0.692114 2.37728 4.57061 --0.634868 2.28144 4.5367 --1.20031 3.2751 6.48844 --1.37099 3.57998 7.28325 --0.985205 2.9102 6.20728 --0.578485 2.20042 4.95833 --0.529127 2.11671 4.94308 --0.491455 2.05515 4.96997 --0.463542 2.01139 5.04062 --0.392401 1.88793 4.92055 --0.362606 1.84119 4.97907 --0.332233 1.79208 5.03703 --0.348864 1.82851 5.3347 --0.233299 1.62433 4.95452 --0.195393 1.56267 4.97106 --0.15353 1.49279 4.95779 --0.087876 1.3789 4.79115 --0.0542848 1.32338 4.81185 --0.0237501 1.27439 4.86044 --0.0255093 1.28624 5.16888 -0.013444 1.21974 5.1684 --0.0698792 1.38908 6.29585 --0.00938239 1.28583 6.18954 --0.710357 2.41115 -1.37395 --0.758836 2.49736 -1.38614 --0.808259 2.58537 -1.39582 --0.858868 2.67425 -1.40271 --0.931194 2.80307 -1.44572 --0.985912 2.9014 -1.45247 --1.03822 2.99272 -1.44965 --1.1062 3.11286 -1.46849 --1.17813 3.24197 -1.48934 --1.24772 3.36428 -1.49963 --1.32128 3.49562 -1.51165 --1.41277 3.65718 -1.54128 --1.42143 3.67465 -1.45727 --1.58896 3.97071 -1.5728 --1.73836 4.23413 -1.65175 --1.88037 4.48614 -1.71102 --2.02481 4.74173 -1.761 --2.16996 4.99947 -1.80145 --2.32551 5.27564 -1.8415 --2.54473 5.66431 -1.93204 --2.85966 6.22242 -2.09532 --3.24691 6.90701 -2.2976 --3.68723 7.68768 -2.51556 --4.22481 8.63791 -2.7771 --4.81343 9.67998 -3.03688 --5.74174 11.3234 -3.4988 --6.75257 13.1142 -3.94699 --7.94638 15.2285 -4.43707 --8.92827 16.9699 -4.70863 --9.27162 17.5841 -4.54391 --9.62484 18.215 -4.36148 --10.0303 18.9392 -4.18151 --11.6057 21.7353 -4.51059 --11.7739 22.0403 -4.13284 --11.7979 22.0918 -3.69069 --11.9931 22.4453 -3.30875 --13.4967 25.1187 -3.32271 --12.0398 22.5414 -2.4146 --13.6147 25.3435 -2.33938 --13.6623 25.4364 -1.84204 --13.7002 25.5139 -1.34143 --13.7446 25.6005 -0.83987 --2.01116 4.76122 0.796907 --2.00276 4.74733 0.886911 --2.01783 4.77578 0.975677 --2.02714 4.79357 1.06553 --2.0454 4.82748 1.15653 --1.93979 4.64285 1.23878 --1.93798 4.63941 1.32572 --1.94854 4.66053 1.41494 --1.97352 4.70699 1.50774 --1.98296 4.72515 1.59925 --1.97749 4.71591 1.68788 --2.67273 5.95777 1.9854 --2.66792 5.951 2.10035 --2.67222 5.9608 2.2185 --2.68519 5.9853 2.34141 --2.71512 6.04131 2.47434 --2.73998 6.08764 2.60726 --2.76275 6.13083 2.7427 --2.79365 6.18811 2.88565 --2.82895 6.25178 3.03393 --2.85173 6.29604 3.1796 --4.99013 10.1253 4.76229 --1.4722 3.83048 2.4564 --1.42266 3.743 2.49918 --1.39092 3.68853 2.55321 --1.35544 3.62467 2.60183 --1.32752 3.5765 2.65632 --1.29561 3.51985 2.7051 --1.26648 3.47075 2.7565 --1.24743 3.43618 2.81527 --1.21833 3.38548 2.86404 --1.19302 3.34267 2.91589 --1.16785 3.29862 2.96667 --1.14259 3.25426 3.01609 --1.12067 3.21584 3.06988 --1.09868 3.17719 3.1226 --1.07982 3.14549 3.17978 --1.05694 3.1052 3.23077 --1.03397 3.06465 3.2806 --1.00672 3.01638 3.32365 --0.990336 2.98902 3.38357 --0.96567 2.94543 3.43092 --0.948433 2.91653 3.48951 --0.967263 2.95199 3.6127 --0.995288 3.00478 3.7577 --1.3936 3.72699 4.60535 --1.37319 3.69192 4.69373 --1.27503 3.51636 4.62835 --0.781571 2.62454 3.72526 --1.26221 3.49668 4.86297 --1.96424 4.77495 6.5796 --0.793146 2.65059 4.05494 --0.770712 2.60999 4.10895 --1.34051 3.64929 5.64714 --0.590177 2.28581 3.87132 --1.25345 3.49704 5.76201 --0.74381 2.57049 4.51819 --0.708642 2.50774 4.54649 --0.666657 2.43338 4.55737 --0.654467 2.41433 4.65745 --0.866628 2.80458 5.49002 --3.23987 7.16223 13.6981 --0.574129 2.27369 4.83037 --0.539092 2.21134 4.86042 --0.494093 2.13162 4.85413 --0.459579 2.06979 4.88105 --0.449512 2.0549 5.01385 --0.399151 1.96316 4.97624 --0.340462 1.85917 4.89967 --0.293959 1.7755 4.86601 --0.342713 1.87019 5.30991 --0.2731 1.7438 5.16376 --0.200688 1.61227 4.98599 --0.180614 1.57866 5.09622 --0.0934741 1.41775 4.78936 --0.0756382 1.38715 4.90635 --0.0243349 1.29515 4.80278 --0.0200963 1.29049 5.03367 -0.0171111 1.2255 5.03334 -0.0411377 1.18352 5.13835 --0.027353 1.32302 6.15986 -0.0360671 1.20668 5.97366 --0.877854 2.90986 -1.4599 --0.930543 3.00916 -1.46467 --0.993836 3.13098 -1.48497 --1.05842 3.25399 -1.50112 --1.12792 3.3862 -1.5193 --1.19411 3.51136 -1.52701 --1.27576 3.66805 -1.55316 --1.3512 3.81085 -1.56287 --1.36784 3.84316 -1.48774 --1.46403 4.02614 -1.51598 --1.51625 4.12597 -1.48218 --1.83375 4.72771 -1.76241 --1.97513 4.99737 -1.81185 --2.13019 5.29175 -1.86481 --2.32853 5.66977 -1.95139 --2.57575 6.1393 -2.07061 --2.89717 6.75199 -2.24198 --3.28298 7.4844 -2.44508 --3.80677 8.47945 -2.73751 --4.34881 9.50995 -3.00241 --5.04008 10.8258 -3.34184 --5.90085 12.4632 -3.75203 --7.02234 14.5954 -4.27706 --8.18878 16.8142 -4.74275 --8.50631 17.4193 -4.58627 --8.83319 18.0427 -4.41315 --9.19999 18.7425 -4.23917 --9.50787 19.3299 -4.00942 --11.8525 23.7907 -4.70548 --11.9691 24.0155 -4.27248 --12.5087 25.044 -3.99719 --12.551 25.1271 -3.51 --12.6122 25.2474 -3.0284 --12.6603 25.3416 -2.54065 --12.7285 25.4737 -2.05627 --7.73361 15.9702 -0.575852 --6.37657 13.3888 -0.0500381 --6.35573 13.3507 0.211648 --1.83061 4.73696 0.84503 --1.8266 4.73002 0.93293 --1.83215 4.74004 1.02019 --1.87316 4.8191 1.10917 --1.95619 4.97703 1.20392 --1.77315 4.62945 1.27704 --1.82278 4.72744 1.63451 --4.15683 9.17453 2.41027 --2.661 6.32577 2.09147 --2.63382 6.27391 2.20327 --2.60033 6.21135 2.31158 --2.59395 6.19966 2.43002 --2.59152 6.19463 2.55058 --2.59561 6.20487 2.67614 --2.60494 6.22132 2.80515 --2.61638 6.24435 2.93796 --2.64047 6.29046 3.08086 --2.66224 6.3344 3.22617 --2.68387 6.37562 3.37375 --2.7204 6.44696 3.53726 --2.7914 6.58074 3.73262 --2.82904 6.65377 3.90801 --1.28581 3.70939 2.65778 --1.25548 3.65148 2.70869 --1.24173 3.62495 2.7746 --1.29782 3.73393 2.91377 --1.406 3.94151 3.11652 --1.51222 4.14408 3.32784 --1.41977 3.96855 3.31661 --1.20419 3.55587 3.14515 --1.10327 3.36312 3.10154 --1.05384 3.27053 3.11955 --1.02909 3.22275 3.16703 --1.00401 3.17563 3.21305 --0.978096 3.12704 3.25803 --0.952323 3.07721 3.30193 --0.926221 3.02805 3.34438 --0.900017 2.97858 3.38546 --0.876248 2.93499 3.43172 --0.85711 2.89682 3.48339 --0.833188 2.85277 3.52761 --0.81647 2.82044 3.58426 --0.795427 2.78028 3.63365 --0.79105 2.77224 3.71669 --0.748619 2.69259 3.72283 --0.75618 2.70701 3.83403 --0.698179 2.59644 3.80093 --0.694494 2.58884 3.89029 --3.08618 7.17734 9.90063 --0.602239 2.41346 3.86431 --0.637332 2.48177 4.06058 --1.19848 3.5596 5.71385 --1.16067 3.48668 5.77733 --0.692593 2.59013 4.57276 --0.639966 2.49013 4.54366 --0.62901 2.47043 4.64421 --0.822162 2.84162 5.42278 --0.592338 2.39986 4.80381 --0.511421 2.24488 4.66506 --0.50472 2.23325 4.78927 --0.478264 2.18346 4.84432 --0.442829 2.11657 4.8631 --0.457835 2.14612 5.09408 --0.443197 2.11932 5.21039 --0.31276 1.86891 4.80239 --0.286795 1.81788 4.8509 --0.24215 1.73441 4.81593 --0.275901 1.79962 5.18631 --0.175746 1.60677 4.84231 --0.142892 1.54514 4.85806 --0.101722 1.46525 4.81595 --0.0677191 1.4018 4.81924 --0.0370022 1.34288 4.84039 --0.0194991 1.31101 4.96607 -0.00486169 1.26423 5.04331 -0.0228026 1.23087 5.18766 -0.100237 1.08115 4.79645 -0.0120592 1.25655 6.02331 --1.06671 3.52411 -1.54126 --1.13218 3.65999 -1.55216 --1.21046 3.81964 -1.57524 --1.28228 3.9663 -1.58226 --1.30201 4.00604 -1.51047 --1.33612 4.07676 -1.45857 --1.36315 4.13034 -1.39467 --1.37388 4.15259 -1.31035 --1.38034 4.1643 -1.22107 --1.38978 4.18308 -1.13669 --1.39847 4.20064 -1.05229 --1.40663 4.21599 -0.967759 --1.41782 4.23859 -0.887355 --1.42447 4.25147 -0.802773 --1.43418 4.27168 -0.722024 --1.43954 4.2811 -0.637387 --1.4528 4.30678 -0.559786 --1.46436 4.33111 -0.481648 --1.46843 4.33705 -0.397053 --1.48337 4.36801 -0.321384 --1.48885 4.38008 -0.239308 --1.49869 4.399 -0.159822 --1.5078 4.4168 -0.0798224 --1.51201 4.42544 0.00240636 --1.52874 4.45804 0.0788032 --1.54059 4.48157 0.157819 --1.55098 4.50281 0.237666 --1.54825 4.49763 0.3224 --1.57135 4.54338 0.398847 --1.57656 4.55234 0.481441 --1.59309 4.58768 0.561141 --7.22547 16.1199 -0.412078 --5.90979 13.4233 0.0913522 --6.27624 14.1717 0.307725 --1.67024 4.74141 0.890922 --1.67982 4.76061 0.977147 --1.68436 4.77026 1.06385 --1.71907 4.84036 1.15264 --1.73627 4.87377 1.24249 --3.99163 9.47871 2.71127 --2.73713 6.91455 2.37672 --2.74844 6.93655 2.51492 --2.81831 7.07933 2.68407 --2.53638 6.50122 2.67087 --2.50695 6.44009 2.78123 --2.49772 6.41999 2.90312 --2.496 6.41546 3.03029 --2.49733 6.41763 3.16076 --2.51034 6.44267 3.30143 --2.52194 6.46558 3.44362 --2.5482 6.51951 3.60134 --2.60654 6.63738 3.79086 --1.38418 4.1426 2.79468 --1.38233 4.13905 2.88114 --1.37223 4.11712 2.95973 --1.4254 4.22478 3.10619 --1.21599 3.79686 2.96537 --1.39724 4.16504 3.26229 --1.44916 4.27208 3.42246 --1.4352 4.24146 3.50432 --1.41213 4.19482 3.57557 --4.04108 9.5466 7.30214 --3.45643 8.3534 6.71187 --3.44563 8.33126 6.91698 --1.26534 3.8921 3.77103 --0.999617 3.35036 3.44764 --0.913234 3.17494 3.3942 --0.863877 3.07257 3.3954 --0.83813 3.02116 3.43668 --0.809989 2.96231 3.47037 --0.784032 2.91026 3.50883 --0.759193 2.8572 3.5462 --0.739133 2.8173 3.59566 --0.716442 2.77092 3.63733 --0.700022 2.73616 3.69204 --0.660625 2.65587 3.69656 --0.664572 2.66356 3.79989 --0.667318 2.66806 3.90444 --1.14636 3.63745 5.21909 --1.1198 3.58325 5.29859 --0.721989 2.77602 4.36978 --0.691445 2.71306 4.4017 --0.629577 2.58833 4.34546 --0.610223 2.54662 4.40566 --0.557837 2.44068 4.36791 --0.580803 2.48519 4.56522 --0.6081 2.53966 4.79018 --0.545624 2.41203 4.71563 --0.494255 2.30706 4.67121 --0.447284 2.21348 4.64095 --0.486172 2.28903 4.93851 --0.453701 2.22401 4.96784 --0.425932 2.16568 5.01372 --0.39567 2.10358 5.04942 --0.413264 2.13765 5.30921 --0.276472 1.86053 4.83577 --0.268796 1.8435 4.97566 --0.294628 1.89604 5.30961 --0.200814 1.70591 4.99649 --0.141171 1.58313 4.8457 --0.113577 1.52656 4.87954 --0.0897664 1.47768 4.94087 --0.0528012 1.40237 4.91582 --0.0297769 1.35421 4.98474 --0.0184999 1.33077 5.15883 -0.0477413 1.19832 4.88819 -0.0693483 1.15278 4.97317 --0.014583 1.31608 6.11129 -0.0418417 1.20234 5.94444 --1.23784 4.18528 -1.44112 --1.24956 4.20781 -1.35663 --1.25582 4.22056 -1.26716 --1.26226 4.2322 -1.17817 --1.26696 4.24233 -1.08932 --1.27987 4.26636 -1.00916 --1.28326 4.27296 -0.920556 --1.29063 4.28699 -0.836389 --1.29651 4.29858 -0.752073 --1.30258 4.3091 -0.668045 --1.31075 4.32677 -0.587536 --1.31916 4.34347 -0.506927 --1.32681 4.35896 -0.426194 --1.33395 4.37226 -0.345238 --1.33645 4.37556 -0.261368 --1.34598 4.39524 -0.182955 --1.35086 4.40487 -0.101822 --1.35988 4.42238 -0.0230877 --1.37114 4.44746 0.0539768 --1.37499 4.45274 0.135654 --1.38577 4.47575 0.213428 --1.3921 4.48766 0.29373 --1.39768 4.49837 0.374155 --1.4035 4.5081 0.45468 --1.41161 4.52558 0.534313 --1.42021 4.54121 0.614633 --1.42785 4.55666 0.695172 --1.43403 4.56979 0.776443 --1.44046 4.58199 0.85801 --1.45121 4.60263 0.93961 --1.45619 4.61256 1.0221 --1.46067 4.62038 1.10511 --1.46854 4.63651 1.18867 --1.55298 4.80599 1.89487 --1.55073 4.80062 1.98311 --1.5691 4.83818 2.08149 --1.58161 4.86478 2.1796 --1.59017 4.88074 2.27671 --1.60156 4.90439 2.37711 --1.61252 4.92611 2.47891 --1.62207 4.94566 2.58202 --1.63951 4.98024 2.69245 --1.64339 4.98773 2.79491 --1.20487 4.02657 2.51539 --1.18605 3.98481 2.57978 --1.1758 3.95908 2.65039 --1.2335 4.08433 2.79008 --1.20589 4.02191 2.84643 --1.3895 4.4217 3.13583 --1.39057 4.41987 3.23217 --1.27763 4.17271 3.19392 --1.15901 3.91299 3.13735 --1.27654 4.16579 3.37976 --1.2452 4.09571 3.43401 --1.17803 3.94788 3.43488 --3.29672 8.54826 6.67174 --1.18938 3.96784 3.64425 --1.19549 3.97832 3.75337 --1.24769 4.09163 3.94344 --2.889 7.64572 6.87625 --2.88502 7.63078 7.08262 --2.86785 7.5911 7.27161 --0.73777 2.97673 3.41339 --0.788563 3.08458 3.59905 --0.725477 2.94749 3.5607 --0.695002 2.87974 3.58464 --0.673803 2.83183 3.62726 --0.648976 2.77714 3.66182 --0.627595 2.72868 3.70201 --0.608958 2.68537 3.74854 --0.591867 2.64796 3.80143 --0.569521 2.59763 3.83882 --0.560819 2.57616 3.91288 --0.551355 2.55342 3.98687 --0.642034 2.74689 4.35529 --0.610961 2.67671 4.37838 --0.561445 2.56903 4.344 --0.524868 2.48912 4.34699 --0.545701 2.52928 4.53598 --0.501305 2.43245 4.51234 --0.532625 2.49656 4.75363 --0.496661 2.41684 4.76187 --0.434936 2.2827 4.6652 --0.453921 2.32026 4.88442 --0.418371 2.24074 4.88806 --0.390157 2.1794 4.92499 --0.397475 2.19138 5.12094 --0.425477 2.24582 5.42603 --0.316516 2.01423 5.08311 --0.281163 1.93425 5.07924 --0.485237 2.35746 6.36926 --0.199514 1.75685 5.01057 --0.134598 1.61898 4.8237 --0.109458 1.56107 4.85828 --0.0680265 1.471 4.78766 --0.056736 1.44496 4.9239 --0.0211619 1.36675 4.88829 --0.0244438 1.36794 5.14856 -0.0200107 1.27204 5.04329 -0.0529441 1.19972 5.02282 -0.0975591 1.10516 4.89383 -0.0142099 1.2632 6.04273 --1.7613 5.80986 -1.95599 --1.9466 6.25579 -2.0593 --2.17236 6.8001 -2.19268 --2.44302 7.45156 -2.35453 --2.86104 8.46055 -2.65097 --3.25879 9.41984 -2.8841 --3.76582 10.6393 -3.18443 --4.34286 12.0273 -3.5004 --5.22919 14.1636 -4.03391 --6.26723 16.6635 -4.60658 --6.60141 17.4577 -4.52612 --1.27057 4.57468 -0.261344 --1.26489 4.55856 -0.170114 --1.26622 4.55877 -0.0845352 --1.26773 4.55786 0.00046283 --1.27143 4.56438 0.083207 --1.2637 4.54189 0.171505 --1.27379 4.56386 0.250181 --1.28015 4.57586 0.330872 --1.29 4.59485 0.41065 --1.29489 4.6045 0.49188 --1.30329 4.6212 0.572489 --1.30694 4.62752 0.654358 --1.31793 4.65118 0.735051 --1.3213 4.65441 0.817535 --1.3268 4.66651 0.899709 --1.33276 4.6767 0.982277 --1.34209 4.69516 1.06519 --1.34684 4.70211 1.14879 --1.41764 4.83852 2.02599 --1.43855 4.88458 2.12679 --1.4433 4.89258 2.22053 --1.44732 4.89947 2.31478 --1.45892 4.92207 2.41499 --1.46533 4.93466 2.51364 --1.4715 4.94427 2.61339 --1.47957 4.96146 2.71704 --1.48816 4.97688 2.82167 --1.11669 4.10116 2.56998 --1.07049 3.98989 2.60554 --1.16305 4.20174 2.78166 --1.5336 5.06848 3.27495 --1.44791 4.86389 3.28272 --1.23137 4.35199 3.12553 --0.99177 3.79039 2.91837 --0.916883 3.61182 2.90188 --0.898862 3.56476 2.95497 --0.885686 3.53333 3.01681 --1.63251 5.26981 4.20354 --0.785824 3.29463 3.02399 --0.76011 3.23043 3.05932 --1.66529 5.33097 4.64171 --1.0633 3.92891 3.73901 --1.70244 5.40533 4.98119 --1.72136 5.44407 5.16058 --0.71323 3.10615 3.37252 --1.10611 4.01142 4.23771 --1.03255 3.83827 4.20017 --1.80721 5.61898 5.96217 --1.83132 5.66969 6.18801 --0.665691 2.98138 3.70439 --0.636813 2.91076 3.72773 --0.586868 2.79494 3.70025 --0.56432 2.73839 3.73321 --0.544257 2.68786 3.77201 --0.515127 2.61875 3.78774 --0.496515 2.57385 3.83165 --0.480669 2.53416 3.88218 --0.477805 2.52238 3.97068 --0.496268 2.56096 4.12958 --0.534482 2.64496 4.36227 --0.493969 2.54673 4.34245 --0.481681 2.51405 4.41745 --0.512538 2.57903 4.6483 --0.659356 2.90577 5.32369 --0.547558 2.64854 5.05308 --0.406931 2.32864 4.64653 --0.391655 2.28946 4.71911 --0.389977 2.27883 4.85228 --0.368304 2.22599 4.90715 --0.340279 2.15855 4.93475 --0.366345 2.21047 5.21979 --0.338417 2.14272 5.25588 --0.270817 1.98683 5.0816 --0.243859 1.92157 5.11335 --0.237332 1.90075 5.26399 --0.127049 1.65459 4.80173 --0.101456 1.59364 4.82727 --0.0946399 1.57194 4.97401 --0.0495213 1.4678 4.86531 --0.0331003 1.42438 4.95426 -0.00276903 1.34088 4.89859 --0.0495476 1.44127 5.56338 -0.0549256 1.21604 4.93663 -0.0881532 1.13739 4.88595 -0.112998 1.07765 4.91137 -0.0456939 1.19944 5.92493 --1.88417 6.66134 -2.15241 --2.11803 7.27547 -2.3034 --2.46076 8.18013 -2.56193 --2.78605 9.0339 -2.7612 --3.13881 9.95762 -2.95499 --3.72679 11.504 -3.35628 --4.38483 13.2338 -3.76317 --5.27221 15.5657 -4.31227 --5.92653 17.2744 -4.56302 --6.16409 17.8817 -4.40674 --6.41265 18.5165 -4.23734 --6.67846 19.1955 -4.05783 --8.84271 24.8355 -4.61412 --9.24118 25.8556 -4.35223 --9.70789 27.0487 -4.08743 --10.445 28.9504 -3.90175 --10.9448 30.2244 -3.55006 --10.9785 30.2808 -2.98888 --5.48299 15.9115 -0.763429 --5.51647 15.9826 -0.475775 --5.69192 16.4217 -0.214999 --5.75806 16.5768 0.0785067 --5.32045 15.4219 0.43 --5.17415 15.0268 0.721433 --5.10536 14.8316 0.9975 --1.30696 4.92663 2.08146 --2.75828 8.63142 3.07952 --2.78646 8.69511 3.26173 --1.37853 5.09224 2.40424 --1.38862 5.11405 2.50752 --1.39138 5.11526 2.60633 --1.39364 5.11436 2.70566 --1.3978 5.12101 2.8088 --1.40603 5.13475 2.91589 --1.41283 5.14627 3.0241 --1.0737 4.28391 2.75763 --1.4306 5.17996 3.25148 --1.43773 5.19412 3.36699 --0.819901 3.6275 2.69814 --0.816807 3.61624 2.76916 --0.793691 3.55446 2.81311 --0.835518 3.65602 2.94874 --0.88936 3.78648 3.1081 --1.505 5.32248 4.14368 --0.712461 3.33286 2.99194 --0.704064 3.30792 3.05401 --1.53647 5.38072 4.57439 --1.53991 5.38319 4.71399 --1.55883 5.4209 4.88332 --1.57493 5.45425 5.0553 --1.58785 5.4766 5.22362 --1.60117 5.50183 5.4003 --1.61915 5.53756 5.59164 --1.63879 5.57559 5.7921 --1.65232 5.60189 5.98888 --1.0369 4.07732 4.69393 --1.00393 3.98986 4.73731 --0.962367 3.88189 4.75791 --0.529003 2.81638 3.74608 --0.505279 2.7517 3.7717 --0.480242 2.68744 3.79579 --0.453463 2.61667 3.81089 --0.434381 2.56473 3.84676 --0.41782 2.51894 3.88897 --0.403306 2.47723 3.93832 --0.387765 2.43514 3.98702 --0.397352 2.45404 4.12245 --0.456482 2.5876 4.43736 --0.475435 2.6275 4.62738 --0.57798 2.86377 5.1424 --0.497838 2.66476 4.97284 --0.437789 2.51677 4.8732 --0.398166 2.41518 4.84627 --0.334188 2.25633 4.70405 --0.325021 2.22706 4.8019 --0.303281 2.16901 4.84695 --0.364981 2.30348 5.30002 --0.273755 2.08421 5.00542 --0.256334 2.03442 5.07501 --0.236665 1.97992 5.13473 --0.225591 1.94515 5.24887 --0.179881 1.83117 5.1593 --0.0956086 1.63168 4.815 --0.0721392 1.57006 4.83981 --0.0606811 1.53412 4.9488 --0.0726052 1.54973 5.23785 -5.69969e-06 1.37931 4.89814 --0.028664 1.42979 5.35054 -0.0404944 1.2685 5.00512 -0.084315 1.16424 4.84866 -0.110329 1.09823 4.84526 -0.0286727 1.24569 5.94518 --1.45497 6.08012 -2.0198 --1.61682 6.54727 -2.12451 --1.81545 7.12271 -2.2628 --2.07994 7.88621 -2.46491 --2.37098 8.72808 -2.67046 --2.70843 9.70207 -2.89749 --3.13469 10.9329 -3.18801 --3.67295 12.4874 -3.55165 --4.41238 14.6209 -4.06001 --5.27081 17.098 -4.59943 --5.49775 17.7296 -4.46028 --5.71864 18.3432 -4.29391 --5.94319 18.9648 -4.10884 --6.1648 19.576 -3.89981 --7.91297 24.594 -4.71315 --8.26088 25.5608 -4.455 --8.66725 26.6927 -4.19561 --10.9917 33.2824 -4.25049 --5.0923 16.3264 -1.22993 --5.06259 16.2181 -0.916065 --5.09371 16.2829 -0.625478 --5.21828 16.6166 -0.356318 --5.17347 16.4645 -0.0430446 --5.16315 16.4111 0.25933 --5.09391 16.1924 0.564287 --3.04515 10.1683 3.34166 --2.52145 8.69938 3.16323 --2.4866 8.58856 3.29888 --2.50923 8.63887 3.47898 --1.92704 6.99568 3.40676 --1.9263 6.98122 3.54062 --0.949148 4.28674 2.6161 --3.61663 11.5994 5.7485 --1.83054 6.68871 3.84088 --0.77117 3.77819 2.64183 --0.763612 3.7508 2.70625 --0.73266 3.66294 2.74022 --0.718574 3.61692 2.7936 --1.0226 4.43707 3.32415 --0.821399 3.88691 3.106 --2.1396 7.44843 5.33078 --0.636182 3.37041 2.96015 --0.678781 3.48158 3.11083 --0.726847 3.60465 3.27691 --0.771219 3.7162 3.44247 --0.755186 3.66745 3.50021 --2.64336 8.71241 7.41818 --2.53958 8.41707 7.42549 --2.45815 8.1828 7.47255 --2.31072 7.77277 7.36418 --1.56211 5.77155 5.84051 --1.57137 5.78293 6.02618 --0.949654 4.12796 4.64716 --0.92733 4.06009 4.71143 --0.909792 4.00539 4.78789 --0.879028 3.91583 4.82861 --0.923951 4.02233 5.08069 --0.452298 2.78266 3.83229 --0.422834 2.69798 3.83418 --0.402664 2.63819 3.86388 --0.377671 2.56739 3.8767 --0.357054 2.50792 3.90339 --0.341819 2.46008 3.94431 --0.327431 2.41709 3.9924 --0.31131 2.36763 4.0316 --0.31227 2.36094 4.13501 --0.376396 2.51542 4.49416 --0.398392 2.56077 4.70174 --0.456041 2.69496 5.07213 --0.386148 2.51102 4.91227 --0.340255 2.38509 4.84134 --0.303812 2.28559 4.81051 --0.277571 2.20979 4.82095 --0.291871 2.2322 5.03356 --0.271001 2.17013 5.07843 --0.233392 2.06709 5.03193 --0.208685 1.99655 5.05577 --0.200304 1.96344 5.16964 --0.160675 1.85594 5.09901 --0.113917 1.73439 4.97926 --0.0638933 1.60461 4.81864 --0.0655326 1.59387 5.00309 --0.0428907 1.52809 5.02714 --0.0141096 1.44853 5.00223 -0.017909 1.36188 4.94699 -0.0420301 1.29495 4.95712 -0.0684125 1.22116 4.93689 -0.0972992 1.14144 4.88602 -0.112022 1.09317 4.97995 -0.0464183 1.20435 5.94443 --4.6506 16.5421 -0.771486 --4.71393 16.7093 -0.487186 --4.7394 16.7575 -0.188635 --4.79668 16.9063 0.105312 --4.60956 16.2879 0.433344 --1.76865 7.11727 3.50334 --0.83666 4.30859 2.57215 --3.30573 11.6882 5.63114 --3.24284 11.4762 5.78391 --3.31124 11.6556 6.10568 --1.61413 6.58561 3.98246 --1.60715 6.55173 4.10616 --2.85527 10.2308 6.13538 --0.934148 4.53544 3.3113 --0.733528 3.93549 3.07536 --0.70458 3.84265 3.10825 --0.652973 3.68387 3.09852 --0.666626 3.71286 3.20176 --0.592948 3.49113 3.14292 --0.610756 3.53472 3.25581 --0.670467 3.7012 3.46015 --0.613878 3.52759 3.42546 --2.3068 8.40831 7.25609 --2.35411 8.52067 7.57914 --2.22487 8.12677 7.49641 --1.60161 6.31921 6.18918 --2.13049 7.80998 7.69823 --2.06845 7.61142 7.75747 --1.32857 5.48961 5.98141 --2.10804 7.67728 8.3166 --0.801437 3.96957 4.79028 --0.81164 3.98579 4.94241 --0.801656 3.94554 5.039 --0.798658 3.92302 5.15696 --0.417185 2.8504 4.04379 --0.34875 2.65116 3.90979 --0.321883 2.56618 3.90713 --0.303397 2.50605 3.93319 --0.284823 2.44566 3.95808 --0.268039 2.39024 3.98963 --0.253805 2.34105 4.02791 --0.24067 2.29581 4.07375 --0.239148 2.28142 4.16839 --0.280594 2.38189 4.45632 --0.357528 2.57342 4.91799 --0.328732 2.4841 4.91697 --0.293103 2.37706 4.87925 --0.255878 2.26625 4.83027 --0.245219 2.22456 4.91058 --0.215467 2.13462 4.89251 --0.218369 2.12743 5.052 --0.186 2.02833 5.01317 --0.171864 1.977 5.08153 --0.149178 1.90547 5.10328 --0.124459 1.82717 5.10492 --0.0536874 1.63867 4.79742 --0.0381851 1.58486 4.85041 --0.0431687 1.57882 5.05349 --0.0664624 1.61422 5.41935 -0.00690929 1.42544 5.03255 --0.0173851 1.45977 5.43763 -0.0484104 1.29112 5.07297 -0.0956351 1.16881 4.84878 -0.118759 1.0984 4.83588 -0.0358967 1.24407 5.92573 --0.19842 2.63259 1.66886 --0.196749 2.62203 1.71115 --0.191963 2.60064 1.75056 --2.15795 9.10711 3.93708 --2.6338 10.6529 4.65502 --1.59755 7.21495 3.5961 --1.59021 7.16983 3.72175 --1.60819 7.21197 3.88317 --2.83064 11.1909 5.75212 --2.74788 10.8892 5.85038 --1.4273 6.56817 4.0254 --1.41436 6.50682 4.1352 --3.44836 13.0635 7.69358 --0.610369 3.8799 2.98999 --3.17328 12.1055 7.74573 --0.569555 3.72778 3.07045 --0.584729 3.76655 3.17846 --0.632098 3.90873 3.35642 --0.588421 3.75615 3.34685 --0.543953 3.6045 3.33261 --0.50973 3.4864 3.33613 --2.35961 9.29157 7.76284 --2.35492 9.244 7.97993 --1.65777 7.03853 6.46391 --1.59752 6.82558 6.4871 --1.70782 7.14366 6.96169 --1.88472 7.66431 7.64429 --1.85029 7.5302 7.75835 --1.16975 5.41556 5.96618 --1.92675 7.70428 8.42525 --1.84241 7.41479 8.39197 --0.539911 3.44637 4.40936 --0.475426 3.23849 4.29994 --0.688513 3.86266 5.1344 --0.297185 2.66747 3.96391 --0.276947 2.59353 3.97615 --0.25185 2.50848 3.97102 --0.232784 2.44098 3.98758 --0.21624 2.37962 4.01049 --0.200537 2.32309 4.04046 --0.187385 2.2728 4.07716 --0.175575 2.22551 4.12171 --0.180431 2.22413 4.241 --0.240771 2.38225 4.64248 --0.280151 2.47385 4.95601 --0.216878 2.28214 4.76092 --0.211298 2.25057 4.85861 --0.208539 2.22544 4.97386 --0.201372 2.18723 5.07183 --0.178714 2.10746 5.0791 --0.151111 2.01525 5.05768 --0.135714 1.95449 5.1074 --0.122156 1.8999 5.1746 --0.0884398 1.79233 5.1016 --0.0575208 1.69507 5.04456 --0.0402817 1.62978 5.07971 --0.0716059 1.68319 5.4924 --0.057324 1.62125 5.56553 -0.0204642 1.41408 5.11054 -0.0550205 1.31035 4.99624 -0.0802139 1.22972 4.95681 -0.105729 1.14873 4.90587 -0.122626 1.08569 4.93124 -0.0485852 1.2049 5.94457 --0.159814 2.74927 1.67457 --0.158501 2.73813 1.71871 --2.26242 10.4791 4.07305 --2.03341 9.60334 3.99566 --1.82303 8.80775 3.91246 --2.3415 10.6708 4.75089 --1.86425 8.90125 4.29378 --1.41911 7.25965 3.81711 --1.42225 7.24545 3.95771 --2.18739 9.9785 5.31148 --2.07589 9.54154 5.31918 --1.24078 6.52593 4.05983 --1.2316 6.47235 4.17222 --3.00994 12.7622 7.64648 --2.60608 11.2874 7.11928 --0.557784 4.03088 3.19303 --0.527123 3.90919 3.21046 --0.524845 3.88752 3.28604 --0.480541 3.71787 3.26588 --0.473034 3.67941 3.32755 --0.444556 3.56739 3.33832 --0.432767 3.51228 3.38567 --2.01017 8.9065 7.56018 --1.38393 6.73147 6.09604 --1.57563 7.35502 6.7909 --1.70748 7.76905 7.35271 --1.80971 8.07806 7.85401 --1.65844 7.53329 7.60728 --1.67306 7.54801 7.8584 --1.71805 7.66134 8.21429 --0.988667 5.21711 6.00609 --1.71276 7.56664 8.64065 --0.636872 4.0156 5.06701 --0.607711 3.90029 5.08299 --2.69312 10.5501 13.3925 --0.464986 3.3807 4.89171 --0.378603 3.08679 4.65205 --0.214239 2.54897 4.06428 --0.184055 2.43983 4.02509 --0.16512 2.36606 4.03154 --0.151312 2.30983 4.06069 --0.138622 2.2526 4.08874 --0.126787 2.20024 4.12406 --0.117985 2.15724 4.17555 --0.132802 2.18655 4.3549 --0.216201 2.41451 4.90849 --0.169171 2.25681 4.77184 --0.154897 2.19234 4.80741 --0.151849 2.163 4.91283 --0.156192 2.15412 5.0726 --0.14047 2.08571 5.10609 --0.105572 1.96667 5.01973 --0.109928 1.95328 5.18812 --0.0931832 1.88281 5.21803 --0.0722276 1.80109 5.21893 --0.0359178 1.68232 5.10517 --0.0622024 1.72257 5.47054 --0.0513601 1.66456 5.55342 --0.014747 1.54381 5.42543 -0.00623418 1.46368 5.42895 -0.00118951 1.44188 5.66241 -0.0917355 1.2053 4.99474 -0.1313 1.09049 4.78741 -0.0327626 1.26007 6.00422 --3.07797 16.303 -0.212383 --3.09104 16.2986 0.0750387 --0.0810033 2.72438 1.64372 --0.0819776 2.72262 1.68978 --2.19427 11.4446 4.24439 --1.88521 10.1291 4.05786 --1.73688 9.48128 4.04018 --1.82723 9.81358 4.33862 --1.7977 9.65417 4.4718 --2.42412 12.155 5.63188 --1.24438 7.34374 3.91454 --1.24105 7.30155 4.04447 --1.81461 9.56762 5.21496 --1.78026 9.38766 5.33083 --1.05652 6.47782 4.09368 --1.05822 6.45864 4.22215 --1.21022 7.02965 4.67054 --0.465038 4.08163 3.16854 --0.416252 3.87502 3.13763 --0.398421 3.78821 3.17111 --0.405461 3.8 3.26516 --0.37079 3.64688 3.25237 --1.64186 8.49186 6.66489 --1.49501 7.89153 6.45402 --1.30618 7.13576 6.10129 --1.34343 7.24123 6.37278 --1.16057 6.52002 5.99711 --1.29849 7.00007 6.57615 --1.2743 6.87391 6.67068 --1.31747 6.99476 6.9839 --1.89754 9.07795 9.11444 --1.72909 8.41219 8.77102 --1.49453 7.51593 8.16541 --0.848348 5.14846 5.99988 --1.56937 7.69144 8.87159 --1.62756 7.84587 9.32371 --1.60495 7.71583 9.47369 --1.8916 8.66405 10.896 --2.37534 10.2822 13.2301 --0.378631 3.32878 4.87636 --0.298386 3.02881 4.62548 --0.295068 2.99594 4.71415 --0.154505 2.49965 4.15121 --0.118985 2.36234 4.06871 --0.103734 2.29384 4.081 --0.0919696 2.2367 4.10835 --0.0803539 2.17834 4.13473 --0.0727135 2.13447 4.18571 --0.0681274 2.10002 4.25314 --0.117195 2.23209 4.63369 --0.113264 2.19674 4.72132 --0.175421 2.36216 5.21661 --0.130266 2.19697 5.05684 --0.10229 2.08697 5.00072 --0.0831245 2.00356 4.99642 --0.079786 1.96546 5.10045 --0.0746844 1.92079 5.19521 --0.0559391 1.83865 5.19655 --0.0409801 1.76816 5.22417 --0.0183983 1.6765 5.19434 --0.0368941 1.69175 5.49408 --0.018718 1.60968 5.5001 --0.0210243 1.57852 5.68664 -0.0167236 1.44889 5.51715 -0.0951587 1.23147 4.94766 -0.116333 1.14942 4.89654 -0.143611 1.05552 4.77536 -0.0442534 1.22014 6.02304 --1.37911 10.9694 -3.06762 --1.58044 12.037 -3.24314 --1.85166 13.4864 -3.51063 --2.30318 15.9215 -4.04479 --2.76034 18.3589 -4.48812 --3.23954 20.8906 -4.86814 --6.24287 36.7972 -7.36962 --6.29663 36.8909 -6.7134 --6.36936 37.0788 -6.07668 --6.45053 37.3139 -5.44549 --6.51343 37.4519 -4.79431 --6.57047 37.5592 -4.13729 --6.63353 37.6938 -3.48267 --6.69344 37.8168 -2.82437 --6.75841 37.959 -2.16566 --6.81676 38.0692 -1.50118 --2.60992 16.2763 0.248618 --2.62692 16.2847 0.532436 --7.03098 38.5986 0.506363 --1.7778 11.1178 3.63238 --1.45275 9.53386 3.42729 --1.36711 9.08402 3.47874 --1.35066 8.96374 3.61269 --1.42445 9.26259 3.87602 --1.46513 9.40551 4.10098 --1.4888 9.4696 4.30574 --1.69227 10.3548 4.82426 --1.69506 10.3139 5.01389 --1.06099 7.38512 3.99882 --1.06077 7.3498 4.13283 --1.52479 9.39589 5.22486 --1.53904 9.40921 5.42914 --0.875717 6.41579 4.12218 --0.87851 6.39555 4.24927 --1.74993 10.1887 6.47291 --1.00991 6.90084 4.82094 --0.320554 3.86839 3.16939 --0.320112 3.84684 3.24336 --0.308295 3.77481 3.28518 --1.12966 7.25577 5.7102 --1.11002 7.13309 5.80598 --1.1302 7.17612 6.01976 --1.21338 7.48189 6.43697 --0.968998 6.41795 5.80994 --1.17325 7.22091 6.6353 --1.16431 7.13757 6.77115 --1.13074 6.95486 6.82211 --1.23093 7.31407 7.35508 --1.09468 6.71447 7.02361 --1.50925 8.32224 8.7926 --1.517 8.29136 9.03983 --0.714181 5.07485 5.99278 --1.71086 8.92179 10.3024 --1.46736 7.91007 9.51058 --1.67119 8.62756 10.6439 --0.25429 3.16878 4.47134 --0.266457 3.18944 4.62231 --0.242639 3.07249 4.60373 --0.239404 3.03487 4.68463 --0.27319 3.13345 4.95742 --0.230585 2.94672 4.83769 --0.0733005 2.35664 4.10599 --0.0573398 2.27705 4.1011 --0.0469725 2.21809 4.12814 --0.0374873 2.15907 4.15389 --0.0298224 2.11013 4.19563 --0.0232855 2.06522 4.24533 --0.0461823 2.11602 4.47812 --0.109239 2.29432 4.97876 --0.133891 2.343 5.25497 --0.0877172 2.1614 5.05777 --0.0664346 2.06368 5.02756 --0.0481773 1.9753 5.01342 --0.0573585 1.96898 5.2 --0.0408452 1.8865 5.20208 --0.0235056 1.80151 5.19307 --0.377656 2.75416 8.20799 --0.0296676 1.74273 5.51034 --0.187104 2.11782 7.01936 --0.0121879 1.61523 5.65629 -0.0741619 1.35621 5.00714 -0.017576 1.45349 5.69236 -0.106696 1.20095 4.96631 -0.134909 1.10089 4.82665 -0.0431372 1.25162 5.95561 --0.802514 9.44652 -2.72338 --0.548033 7.59816 -1.81516 --0.559101 7.61716 -1.67596 --1.29991 12.6243 -3.28859 --0.584901 7.67509 -1.40717 --0.597759 7.7059 -1.27396 -0.106375 2.84513 0.529329 -0.0855121 2.96068 0.554819 -0.0855554 2.93884 0.606628 -0.083979 2.93557 0.654841 -0.0989544 2.82376 0.716363 -0.0792509 2.92607 0.750376 --6.26984 41.8753 -2.04034 --1.10114 9.14238 3.07976 --1.16385 9.4299 3.31688 --1.37925 10.5472 3.78981 --1.17383 9.37055 3.64716 --1.17426 9.31294 3.80466 --1.17426 9.26296 3.96396 --1.23114 9.50679 4.22546 --1.17507 9.15319 4.28 --1.3276 9.89381 4.74493 --1.18493 9.08728 4.61423 --0.887405 7.49345 4.11547 --0.880935 7.41064 4.23066 --0.895227 7.43336 4.39406 --0.918401 7.5061 4.58539 --0.701585 6.36554 4.15894 --0.708958 6.36179 4.2942 --0.232198 3.94843 3.08327 --0.216294 3.84353 3.10825 --0.219275 3.83207 3.18627 --0.231864 3.86951 3.296 --0.227264 3.82047 3.35388 --0.910231 7.06807 5.6603 --0.972379 7.31648 6.01359 --0.97753 7.28367 6.17861 --0.849531 6.62813 5.87159 --0.818385 6.43459 5.89789 --0.994118 7.19535 6.70078 --1.57637 9.80003 9.12372 --1.38756 8.86563 8.59373 --0.886918 6.53943 6.74209 --0.871521 6.41768 6.8322 --1.35472 8.49399 9.07574 --1.43474 8.76809 9.64301 --0.588131 5.01801 6.00617 --1.34536 8.22348 9.6778 --1.25797 7.77046 9.47784 --0.85112 5.98505 7.69444 --0.221183 3.30236 4.68375 --0.186287 3.12767 4.59763 --0.178668 3.06476 4.64797 --0.182737 3.04916 4.76045 --0.184175 3.01815 4.85749 --0.186716 2.99608 4.97104 --0.0418574 2.39828 4.21765 --0.0135358 2.26267 4.12971 --0.00412037 2.19887 4.14749 -0.00420336 2.13898 4.17274 -0.0128427 2.07981 4.19672 -0.016299 2.0394 4.25431 -0.00494031 2.05184 4.41727 --0.0811628 2.31495 5.09656 --0.0725896 2.24853 5.14128 --0.0453649 2.11975 5.04946 --0.047679 2.09017 5.17264 --0.61158 3.85033 9.63644 --0.0223334 1.93049 5.19815 --0.0151998 1.86905 5.25501 --0.023702 1.85217 5.44218 --0.318339 2.65404 8.10016 --0.187916 2.21788 7.14616 -0.0128824 1.61283 5.49228 --0.00514444 1.61255 5.79371 -0.0965077 1.30926 4.95949 -0.103832 1.24785 5.00659 -0.129845 1.14235 4.85833 -0.0280606 1.31876 6.0637 -0.0432925 1.2285 6.06219 --0.463598 9.02637 -2.60612 --0.571866 9.89108 -2.77196 --0.71032 10.996 -2.99626 -0.189015 3.02934 0.0619624 -0.185778 3.02672 0.116381 -0.180161 3.04224 0.164262 -0.17527 3.05662 0.212558 -0.170144 3.07005 0.261051 -0.168779 3.05369 0.317375 -0.164179 3.06492 0.365994 -0.157818 3.08559 0.412452 -0.154743 3.08641 0.463431 -0.151225 3.08525 0.514416 -0.146316 3.10363 0.561705 -0.139937 3.12041 0.609656 -0.13696 3.11699 0.660573 -0.132269 3.13243 0.709158 --1.74629 16.2637 1.71711 --1.08762 10.8023 3.17943 --0.965888 9.92256 3.17739 --1.33407 12.2379 3.91395 --1.10584 10.6722 3.73137 --0.890914 9.2123 3.52122 --0.889453 9.12862 3.66676 --0.94209 9.39186 3.92049 --1.02472 9.83538 4.24752 --1.10287 10.2424 4.58118 --1.29628 11.3536 5.19795 --1.08929 10.0006 4.88596 --0.994142 9.34711 4.81307 --1.00315 9.32343 4.99218 --0.711516 7.51843 4.35492 --0.710018 7.44997 4.4776 --0.72363 7.46774 4.64331 --0.535046 6.30864 4.19509 --0.121972 3.88483 3.0046 --0.112195 3.79899 3.03818 --0.118615 3.80496 3.12516 --0.116186 3.75933 3.1817 --0.73835 7.18098 5.46762 --0.763756 7.25821 5.69312 --0.917024 8.02869 6.40761 --0.772158 7.17894 6.00016 --0.87797 7.6764 6.55957 --0.678722 6.54734 5.88889 --0.673279 6.46159 5.99881 --0.685079 6.45732 6.17693 --0.761896 6.79285 6.65408 --0.738776 6.60521 6.68904 --0.728925 6.4906 6.78668 --1.20421 8.78616 9.19993 --1.38316 9.57535 10.278 --1.17533 8.45426 9.45332 --0.468439 4.9641 6.02613 --1.11179 7.96254 9.52471 --0.709436 5.97769 7.55463 --0.694404 5.8381 7.62418 --0.116789 3.12428 4.52247 --0.116498 3.08741 4.60349 --0.897825 6.52436 9.28645 --0.101622 2.94436 4.67638 --0.0862199 2.84069 4.66619 --0.0732963 2.74304 4.66177 --0.0834587 2.74957 4.8129 -0.0262303 2.25797 4.17485 -0.0373199 2.17787 4.16673 -0.044475 2.11714 4.19157 -0.0500338 2.06247 4.22345 -0.054236 2.01086 4.26338 -0.0529804 1.98218 4.34654 --0.120674 2.58193 5.72354 --0.0466543 2.26459 5.25985 --0.0268551 2.15032 5.20377 --0.550959 3.89851 9.52564 --0.526596 3.72408 9.5245 -0.0141757 1.8775 5.15857 --0.00840115 1.90106 5.4479 --0.299693 2.74006 8.13691 --0.28802 2.62282 8.19869 --0.155069 2.16038 7.1362 -0.0145741 1.62655 5.677 -0.0903038 1.37295 5.05647 -0.0997766 1.30003 5.06584 -0.134948 1.1672 4.81198 -0.136832 1.11473 4.88554 -0.0419329 1.26617 6.02429 --0.154351 8.64269 -2.50043 --0.226386 9.39577 -2.63425 --0.314891 10.3225 -2.80677 --0.427578 11.5107 -3.03993 --0.510471 12.314 -3.09648 --0.66985 13.9755 -3.40324 --0.90938 16.5167 -3.9177 --1.1851 19.3951 -4.43508 --1.4848 22.4491 -4.8944 --1.00935 14.3731 0.798623 --1.04055 14.4918 1.04525 --1.05509 14.4681 1.29345 --1.07531 14.4891 1.54274 --1.08469 14.4172 1.78801 --1.12342 14.6083 2.05002 --0.931265 12.1258 3.13999 --0.845681 11.3056 3.19468 --0.576677 9.01296 2.90518 --0.948744 11.8986 3.73662 --0.672968 9.59542 3.37404 --0.663409 9.42754 3.50333 --0.685796 9.50624 3.69892 --0.72831 9.73174 3.94497 --0.739336 9.71663 4.1224 --0.828433 10.2879 4.50532 --0.808199 10.0391 4.61174 --0.71896 9.27993 4.51396 --0.722194 9.20748 4.66751 --0.798417 9.66213 5.04575 --0.777892 9.41758 5.13263 --0.823521 9.64009 5.43144 --0.533844 7.52267 4.59282 --0.377535 6.36474 4.15726 --0.372818 6.26514 4.24003 --0.326452 5.88816 4.16519 --0.0343823 3.87762 3.1252 --0.0243117 3.7724 3.14674 --0.0173441 3.68524 3.17568 --0.643961 7.69358 5.88834 --0.729798 8.1566 6.39174 --0.705128 7.90737 6.42047 --0.703762 7.81171 6.55371 --0.51692 6.5695 5.81412 --0.5405 6.64042 6.04684 --0.531181 6.50515 6.12023 --0.599884 6.8312 6.58163 --0.589294 6.68858 6.65657 --0.567229 6.47852 6.66834 --1.1057 9.46758 9.68963 --1.04862 9.02317 9.56596 --1.31341 10.3715 11.2358 --1.0115 8.58245 9.725 --1.05487 8.69748 10.1619 --1.25814 9.65092 11.5621 --0.581004 5.96907 7.65136 --0.568402 5.81413 7.70476 --0.0495534 3.09527 4.544 --0.0497463 3.05153 4.61667 --0.0592759 3.04782 4.74446 --0.04829 2.94832 4.74401 --0.0437526 2.88325 4.79039 --0.0296846 2.76757 4.76124 --0.0194753 2.67498 4.76276 -0.056958 2.28783 4.27956 -0.0792603 2.14975 4.17754 -0.0835589 2.08951 4.20134 -0.0879562 2.03398 4.23271 -0.0902638 1.98266 4.27181 -0.088804 1.94793 4.34585 -0.0614131 2.01464 4.63474 -0.00220729 2.19455 5.19842 -0.00396971 2.13411 5.25876 --0.46868 3.77501 9.42377 --0.304415 3.0988 8.14321 -0.0112866 1.94588 5.44428 -0.0148963 1.87801 5.50141 --0.270617 2.71427 8.25509 --0.186888 2.36844 7.6048 --0.134757 2.13288 7.23058 -0.010987 1.64855 5.91054 -0.126227 1.28134 4.84517 -0.132093 1.21513 4.86231 -0.137321 1.15085 4.88801 -0.153018 1.06362 4.80537 -0.041371 1.2381 6.11128 -0.124945 8.34261 -2.42778 -0.0783882 9.04814 -2.55267 -0.0215927 9.91855 -2.71566 --0.0467685 10.9647 -2.91159 --0.105224 11.7751 -2.9861 --0.190106 13.0279 -3.17804 --0.318073 14.9758 -3.54147 --0.509458 17.9461 -4.13294 --0.709694 20.9389 -4.62171 --3.39898 58.5039 -8.54228 --0.637299 14.4794 1.19877 --0.621657 14.0546 1.43424 --0.84633 16.5424 1.79009 --0.710089 14.4476 2.18968 --0.594729 12.9068 2.28661 --0.589169 12.6448 2.47891 --0.586674 12.4283 2.66933 --0.605053 12.4555 2.89011 --0.546158 11.6353 2.96841 --0.545288 11.4617 3.1406 --0.598511 11.8609 3.42597 --0.336731 8.97955 2.99032 --0.362398 9.1275 3.18657 --0.355409 8.92392 3.29773 --0.425886 9.50491 3.62309 --0.533689 10.4304 4.075 --0.684889 11.7493 4.69022 --0.586041 10.6458 4.53927 --0.55545 10.2166 4.58904 --0.519497 9.74274 4.60736 --0.501476 9.44652 4.68023 --0.515615 9.44556 4.86647 --0.707028 11.0153 5.74604 --0.396886 8.15663 4.65638 --0.372531 7.83149 4.66831 --0.353236 7.5625 4.69668 --0.217274 6.32509 4.20827 --0.1916 6.02477 4.17933 --0.195643 5.9771 4.28416 -0.071155 3.75636 3.09734 --0.184536 5.72355 4.39745 --0.177786 5.597 4.44904 --0.227736 5.89965 4.78452 --0.514594 7.98915 6.37868 --0.533459 8.01451 6.60005 --0.515308 7.76432 6.62141 --0.661869 8.71023 7.56146 --0.81063 9.64021 8.54873 --0.422218 6.77228 6.43384 --0.505542 7.24869 7.04028 --0.435516 6.66058 6.73068 --0.446171 6.62523 6.90223 --0.477303 6.72877 7.21223 --0.676686 7.91017 8.60643 --0.829204 8.74579 9.73726 --0.450181 6.23211 7.36836 --0.439224 6.06049 7.40527 --0.970372 9.15322 11.1734 --0.446263 5.89067 7.67252 --0.435082 5.72398 7.70812 --0.0167941 3.24263 4.79203 --0.0215283 3.21177 4.89095 --0.000719123 3.03894 4.79698 -0.00530336 2.94921 4.81235 --0.00293117 2.93307 4.93246 -0.00423706 2.83758 4.93667 -0.0264879 2.66827 4.82084 -0.079142 2.35515 4.45329 -0.114036 2.14096 4.22231 -0.118123 2.07469 4.23707 -0.121576 2.0143 4.25909 -0.124872 1.95271 4.28023 -0.122483 1.91308 4.34472 -0.0994505 1.96079 4.59793 -0.0395302 2.15393 5.19917 --0.0238479 2.33738 5.83574 --0.427402 3.78185 9.64291 -0.0370506 1.97922 5.41287 -0.0396492 1.90564 5.45137 -0.0384626 1.84475 5.5263 --0.213134 2.5861 8.07061 -0.0315737 1.73334 5.73083 -0.0326509 1.66209 5.79398 -0.120023 1.35214 4.97139 -0.138926 1.24457 4.8351 -0.154273 1.15068 4.73513 -0.124764 1.16326 5.1102 -0.0414533 1.27851 6.08324 -0.44189 4.91281 -1.07901 -0.434286 4.92131 -0.986314 -0.426151 4.94614 -0.901662 -0.383722 6.82849 -1.55475 -0.384459 6.25495 -1.20797 -0.3715 6.46264 -1.16457 -0.355715 6.71744 -1.13047 -0.34153 6.88774 -1.06103 -0.18316 12.5922 -2.64385 -0.161094 12.7312 -2.45106 -0.0417228 16.1929 -3.12585 --0.329883 27.5863 -5.60566 --1.92787 72.9661 -13.9981 -0.027308 12.851 -0.882735 -0.00812609 12.8914 -0.665103 --0.0079811 12.8491 -0.437394 --0.0282813 12.902 -0.221641 --0.295434 16.0651 1.11487 --0.318055 16.0709 1.38951 --0.349672 16.2402 1.67156 --0.35024 15.8372 1.9269 --0.204213 12.8507 1.97601 --0.246624 13.2894 2.23672 --0.194892 12.0946 2.33435 --0.212756 12.109 2.54479 --0.195921 11.5559 2.67448 --0.286017 12.7272 3.06631 --0.216616 11.3729 3.04442 --0.234568 11.4034 3.25103 --0.247943 11.3528 3.44206 --0.10935 9.12336 3.1194 --0.123772 9.13298 3.28535 --0.14306 9.21666 3.47326 --0.185398 9.61283 3.75694 --0.263881 10.4592 4.19703 --0.242802 9.97491 4.23325 --0.254383 9.92614 4.40488 --0.239509 9.54714 4.45489 --0.24556 9.44868 4.60126 --0.391531 11.0175 5.42914 --0.369845 10.5438 5.44625 --0.153272 7.8473 4.44414 --0.163757 7.82282 4.59228 --0.366933 9.9303 5.79544 --0.174473 7.6478 4.83011 --0.0481237 6.15807 4.19291 --0.153707 7.15369 4.88446 --0.0696133 6.1559 4.4608 --0.0437009 5.78831 4.37635 --0.0501178 5.74466 4.48256 --0.0823937 5.95042 4.75202 --0.0802523 5.81802 4.80532 --0.114395 6.02777 5.09686 --0.332139 7.89803 6.62357 --0.135668 5.99278 5.37907 --0.344689 7.71218 6.89825 --0.32736 7.41599 6.86909 --0.342749 7.40366 7.06994 --0.313861 7.01188 6.94338 --0.324292 6.95903 7.10677 --0.336148 6.91671 7.28381 --0.551397 8.44399 8.99918 --0.520211 8.02992 8.86415 --0.316322 6.35157 7.38476 --0.310101 6.17842 7.42382 --0.125423 4.73597 6.03033 --0.298798 5.83406 7.48969 --0.309254 5.77734 7.65467 --0.310839 5.66078 7.74954 -0.0499806 3.20773 4.81506 -0.062438 3.05738 4.75363 -0.0592219 3.00904 4.82578 -0.0600674 2.93699 4.86452 -0.0555962 2.89139 4.94335 -0.0821514 2.67204 4.75352 -0.0850414 2.59152 4.76905 -0.0267117 2.83505 5.33137 -0.151226 2.11468 4.2414 -0.153419 2.04871 4.25533 -0.155934 1.98344 4.2679 -0.154947 1.93561 4.31481 -0.153785 1.88165 4.35219 -0.145717 1.865 4.47006 -0.0293538 2.29806 5.62861 --0.351802 3.78063 9.4233 -0.0584945 2.03354 5.43694 -0.0622442 1.94981 5.44812 -0.0588402 1.88853 5.52358 --0.195243 2.68758 8.16579 -0.0511268 1.76645 5.69089 -0.0536042 1.6849 5.71617 -0.128134 1.38922 4.97236 -0.150627 1.26576 4.77897 -0.153113 1.19724 4.78599 -0.155922 1.12941 4.79166 -0.0526715 1.30105 5.96715 -0.0425771 1.23989 6.12134 -0.62647 6.85691 -2.01941 -0.623419 7.40232 -2.12452 -0.626166 8.43232 -2.41471 -0.622738 9.17755 -2.54998 -0.617496 10.0511 -2.70696 -0.611403 11.1295 -2.90635 -0.600261 11.896 -2.95839 -0.588948 13.162 -3.14587 -0.578146 15.2413 -3.53641 -0.566238 18.6538 -4.23371 -0.406973 12.857 -0.962501 -0.387886 12.8893 -0.743633 -0.368784 12.8692 -0.518408 -0.349569 12.9137 -0.301589 -0.1845 15.313 1.01623 -0.158808 15.4802 1.28019 -0.135742 15.483 1.54468 -0.11352 15.4708 1.80883 -0.0783057 15.934 2.10513 -0.0695247 15.4045 2.33344 -0.148601 12.0084 2.24805 -0.13236 11.9745 2.45051 -0.0772861 13.0963 2.81255 --0.039162 15.8968 3.47814 --0.0638774 15.9108 3.7593 -0.112161 10.6098 3.02129 -0.095082 10.6416 3.21493 --0.0299949 13.3001 4.01134 -0.0580931 10.733 3.61656 -0.0370081 10.8311 3.83624 -0.0597039 9.97293 3.78967 -0.034851 10.1524 4.02719 -0.0290513 9.95487 4.15246 --0.00355556 10.2767 4.44923 --0.00529137 9.99033 4.54082 --0.000504099 9.58162 4.57746 --0.0944437 10.9824 5.32599 --0.0860162 10.5101 5.34446 -0.0540728 7.84753 4.37885 --0.0900377 9.98012 5.52544 --0.112854 10.0621 5.77166 --0.348447 13.415 7.68179 -0.111285 6.15609 4.13575 -0.103213 6.10975 4.24213 -0.0875852 6.16473 4.4075 -0.0815411 6.07902 4.49374 -0.0899489 5.81403 4.46756 -0.0637582 5.99585 4.72007 -0.0381748 6.17066 4.98006 -0.0436221 5.94513 4.97342 -0.0307771 5.94041 5.11775 -0.0146217 5.97895 5.29944 -0.0107576 5.86463 5.36691 -0.00539256 5.77958 5.45715 --0.460409 10.6251 9.66233 --0.178067 7.40149 7.18538 --0.144433 6.86146 6.92223 --0.167447 6.91078 7.17817 --0.348045 8.46987 8.89572 --0.16231 6.50769 7.222 --0.164653 6.3566 7.28628 --0.352279 7.84145 9.09356 --0.297277 7.15683 8.62496 --0.0182054 4.63583 6.01005 --0.177041 5.80084 7.57132 --0.185306 5.70442 7.68942 --0.202809 5.67895 7.90037 -0.131423 3.03828 4.66286 -0.135791 2.9275 4.64576 -0.13027 2.88131 4.7154 -0.100739 3.0006 5.03234 -0.0738846 3.08812 5.3209 -0.125765 2.67368 4.82876 -0.132669 2.54961 4.77589 -0.123806 2.52371 4.88366 -0.179115 2.13209 4.33843 -0.186562 2.02215 4.27326 -0.186954 1.9562 4.2851 -0.184799 1.90752 4.3316 -0.181503 1.85791 4.3773 -0.173698 1.83214 4.47679 -0.0334027 2.39613 5.96951 --0.408158 4.19174 10.6491 -0.088014 1.98918 5.4357 -0.0852955 1.91478 5.47399 -0.077101 1.86652 5.58624 -0.0534958 1.86698 5.85924 -0.0668376 1.73567 5.73355 -0.0526586 1.69723 5.91129 -0.157748 1.30417 4.79025 -0.16116 1.22846 4.76875 -0.161034 1.16241 4.78458 -0.059351 1.33779 5.92934 -0.0595472 1.24999 5.93695 -0.833282 6.67824 -1.98514 -0.852621 7.33064 -2.14553 -0.876498 8.1006 -2.33163 -0.89395 8.79633 -2.45765 -0.914878 9.61966 -2.60781 -0.936492 10.5443 -2.76509 -0.964514 11.6837 -2.9639 -1.00212 13.1652 -3.23444 -1.04027 14.7934 -3.49653 -1.08696 16.8462 -3.82419 -1.14875 19.5215 -4.24865 -0.54379 15.1272 1.95886 -0.520886 15.4976 2.24757 -0.497049 13.7527 2.34434 -0.47174 16.0529 2.84449 -0.456744 12.9154 2.70777 -0.437555 12.7957 2.91346 -0.415222 13.0278 3.17493 -0.394007 13.0279 3.40318 -0.369098 13.4352 3.71596 -0.376506 10.9558 3.40442 -0.358713 10.9522 3.5986 -0.353487 10.1405 3.58561 -0.335711 10.1621 3.77501 -0.325117 9.83423 3.86379 -0.309467 9.79314 4.03205 -0.296407 9.63515 4.16174 -0.248305 10.9362 4.80379 -0.233665 10.7662 4.94955 -0.212768 10.826 5.18222 -0.198633 10.6505 5.32246 -0.194842 10.1524 5.31851 -0.189621 9.75763 5.34428 -0.18499 9.35603 5.35322 -0.114098 10.8001 6.26719 -0.272253 6.1935 4.10311 -0.264701 6.0772 4.17178 -0.188411 7.58766 5.15628 -0.235626 6.18767 4.50247 -0.222513 6.20287 4.65132 -0.218732 6.00431 4.66741 -0.202525 6.07333 4.85414 -0.186758 6.12918 5.03873 -0.183358 5.92781 5.04675 -0.180001 5.75207 5.06697 -0.157824 5.90273 5.33112 -0.147553 5.83516 5.43391 -0.136296 5.78741 5.55508 --0.293878 11.7811 10.8242 --0.180138 9.7593 9.39009 --0.0177555 7.22361 7.37061 --0.0578816 7.47451 7.83312 --0.0406497 6.9978 7.60739 --0.0168789 6.46077 7.29627 --0.122007 7.42378 8.53044 --0.00238874 5.84695 7.08012 --0.0086958 5.70716 7.13836 -0.0837817 4.56082 6.01856 --0.252251 7.69019 9.9837 --0.0568897 5.56581 7.6458 -0.201908 3.02173 4.58119 -0.194569 2.97727 4.65195 -0.189413 2.91936 4.70607 -0.173873 2.9392 4.87435 -0.159016 2.94908 5.03599 -0.133627 3.03426 5.32518 -0.143233 2.855 5.20202 -0.177221 2.51718 4.79949 -0.167189 2.49044 4.90685 -0.217985 2.0795 4.31373 -0.219256 1.99361 4.29128 -0.216553 1.93221 4.31122 -0.213698 1.8746 4.33913 -0.208269 1.82934 4.39315 -0.200268 1.7975 4.48341 -0.0678926 2.34909 5.98157 -0.117448 2.02063 5.40458 -0.111531 1.95713 5.47141 -0.108376 1.87966 5.49947 -0.0820675 1.88681 5.78123 -0.0730654 1.82434 5.87464 -0.083801 1.69443 5.74752 -0.148412 1.40097 5.01274 -0.169717 1.26357 4.77092 -0.164466 1.20489 4.81615 -0.167762 1.12574 4.77291 -0.0616133 1.29906 5.9581 -0.0423494 1.24709 6.16082 -1.02239 6.34214 -2.00646 -1.0434 6.74528 -2.06953 -1.06912 7.21641 -2.14873 -1.09997 7.77347 -2.2484 -1.13779 8.45569 -2.37972 -1.17518 9.16329 -2.49563 -1.21641 9.94326 -2.61269 -1.27753 11.0587 -2.82161 -1.34619 12.3158 -3.03732 -1.42701 13.8304 -3.28939 -1.53811 15.8741 -3.64512 -1.68583 18.6058 -4.12034 -0.883788 13.6153 2.25042 -0.820882 13.7927 2.98007 -0.751269 11.7047 2.88247 -0.729494 11.573 3.06271 -0.684392 10.2127 2.99674 -0.661464 9.84515 3.09717 -0.650152 10.2362 3.36294 -0.628555 9.93358 3.46905 -0.608999 9.74529 3.59687 -0.596507 10.141 3.88864 -0.581535 10.5398 4.1976 -0.56314 10.6356 4.42478 -0.545134 11.0667 4.77414 -0.524419 10.8875 4.91924 -0.50404 10.6126 5.0235 -0.485928 9.87487 4.93098 -0.467035 9.66835 5.03758 -0.448345 9.6703 5.23238 -0.429553 9.76837 5.47505 -0.380303 12.7342 7.12952 -0.389555 9.75898 5.87857 -0.422048 6.04798 4.10746 -0.408647 6.07255 4.25047 -0.395979 6.08473 4.39037 -0.380723 6.17997 4.58306 -0.373606 5.87982 4.53602 -0.358852 5.96899 4.73044 -0.338313 6.21822 5.04112 -0.331809 5.93471 4.99396 -0.314259 6.03524 5.21448 -0.301862 5.96867 5.31956 -0.285857 5.97203 5.47878 -0.167563 8.50315 7.69109 -0.187128 7.53577 7.11904 -0.172011 7.40574 7.22397 -0.139318 7.63089 7.64721 -0.160218 6.80638 7.11197 -0.141495 6.76415 7.28632 -0.111447 6.90835 7.65177 -0.128914 6.27816 7.23356 -0.128384 5.9641 7.11717 -0.118112 5.80421 7.15488 -0.112343 5.60474 7.14389 -0.176773 4.49524 6.04153 -0.0718127 5.57058 7.54895 -0.0645922 5.38233 7.54477 -0.260982 2.96552 4.57835 -0.249733 2.94429 4.68047 -0.233307 2.98303 4.87299 -0.225313 2.92162 4.92707 -0.221412 2.8314 4.93842 -0.203802 2.85251 5.12558 -0.195127 2.79649 5.19474 -0.223407 2.44859 4.76209 -0.221952 2.34929 4.73764 -0.243516 2.09634 4.42037 -0.248835 1.96468 4.30876 -0.245202 1.89838 4.31915 -0.240221 1.8451 4.35527 -0.233624 1.799 4.40888 -0.225174 1.75912 4.48016 --0.172957 3.65576 9.33901 -0.142639 1.98122 5.42204 -0.134355 1.91507 5.4783 -0.129565 1.83377 5.4961 -0.079065 1.92809 6.05271 -0.0980031 1.75209 5.79424 -0.0981393 1.64964 5.7514 -0.159163 1.36072 5.00382 -0.173726 1.23787 4.80888 -0.165864 1.18272 4.87307 -0.173064 1.08629 4.75117 -0.0549878 1.27243 6.05489 -1.16625 5.77648 -1.89153 -1.19739 6.13731 -1.95394 -1.22534 6.49278 -2.00038 -1.26167 6.92455 -2.06919 -1.31445 7.52294 -2.1967 -1.36282 8.10059 -2.29262 -1.42335 8.80465 -2.41824 -1.48929 9.59808 -2.55233 -1.57354 10.5854 -2.72803 -1.66422 11.6763 -2.90311 -1.78098 13.0701 -3.13715 -1.93137 14.8553 -3.44062 -2.14409 17.3536 -3.88458 -2.36093 19.9972 -4.27656 -2.59204 23.3777 -4.33147 -1.11023 11.072 2.14562 -1.07871 10.8444 2.30774 -1.31801 15.7284 3.168 -1.20794 14.1211 3.19171 -1.01103 10.6294 2.8321 -1.00642 10.9311 3.07527 -0.946185 10.0347 3.07948 -0.96412 10.865 3.44598 -0.914967 10.1627 3.4669 -0.885109 9.87912 3.57385 -0.863757 9.79575 3.72913 -0.873839 10.5705 4.14236 -0.842288 10.2304 4.22862 -0.858203 11.3193 4.79037 -0.828755 11.0652 4.9135 -0.888599 13.9509 6.22046 -0.755403 9.94181 4.89173 -0.718866 9.25597 4.79938 -0.712497 9.79359 5.22031 -0.694326 9.92055 5.47634 -0.672351 9.83347 5.63828 -0.644915 9.39472 5.62328 -0.57827 5.99534 4.03529 -0.566382 6.02138 4.17705 -0.554947 6.21008 4.4145 -0.539432 6.08158 4.47567 -0.527446 6.42976 4.82775 -0.512743 6.83439 5.23596 -0.496787 6.54487 5.20426 -0.481256 6.35593 5.23241 -0.467109 6.02287 5.15003 -0.453058 5.86188 5.18298 -0.377411 11.0615 9.34762 -0.349639 10.846 9.47634 -0.360844 8.42654 7.77563 -0.282298 11.1001 10.3119 -0.254789 10.8329 10.4043 -0.323868 6.96797 7.17966 -0.309926 6.71539 7.15621 -0.284872 6.78606 7.44171 -0.277465 6.37314 7.24579 -0.268257 6.0586 7.13194 -0.248675 5.99898 7.2822 -0.23717 5.77707 7.25242 -0.218276 5.70081 7.38408 -0.267854 4.42107 6.05623 -0.188612 5.40768 7.48076 -0.178993 5.19793 7.44097 -0.316084 2.91878 4.59116 -0.308031 2.85649 4.63587 -0.28862 2.91838 4.86046 -0.254932 3.13727 5.3385 -0.243807 3.07262 5.40366 -0.250042 2.83481 5.18668 -0.273037 2.4637 4.72198 -0.265319 2.38872 4.74142 -0.254634 2.3479 4.82067 -0.276672 2.0508 4.41267 -0.277007 1.93896 4.33496 -0.271236 1.87202 4.34482 -0.264118 1.81811 4.38041 -0.256826 1.76806 4.42427 -0.244785 1.73591 4.51328 -0.179103 1.98496 5.32657 -0.166902 1.93085 5.41086 -0.155767 1.87123 5.48506 -0.139398 1.8287 5.61515 -0.101311 1.86567 6.01142 -0.116191 1.69336 5.75069 -0.0890134 1.67693 6.01397 -0.176957 1.29246 4.88848 -0.17147 1.22572 4.90469 -0.170182 1.14458 4.86155 -0.0679008 1.30072 5.96857 -0.042838 1.25105 6.18052 -0.891027 1.83141 -1.22167 -0.897275 1.89401 -1.22651 -1.25815 5.04691 -1.7676 -1.28779 5.31218 -1.80608 -1.32036 5.60599 -1.85038 -1.35965 5.94583 -1.90796 -1.39916 6.29956 -1.95911 -1.45548 6.78101 -2.05841 -1.51415 7.28657 -2.15013 -1.57669 7.83343 -2.24081 -1.65118 8.48595 -2.35499 -1.73864 9.24708 -2.48738 -1.83745 10.1173 -2.63237 -1.9655 11.2289 -2.8305 -2.10565 12.4646 -3.02883 -2.28321 14.0308 -3.28618 -2.5329 16.2103 -3.66731 -3.30756 23.3684 -4.48371 -3.28863 23.5919 -4.10759 -1.4337 10.9421 1.88555 -1.42095 11.0267 2.08053 -1.40281 11.0477 2.27188 -1.40078 11.2735 2.49168 -1.36035 11.0316 2.65001 -1.33433 10.9542 2.82847 -1.3207 11.0415 3.03542 -1.28485 10.8403 3.18826 -1.2869 11.1436 3.44719 -1.29281 11.5392 3.74015 -1.24365 11.1444 3.84528 -1.22154 11.1334 4.04441 -1.17029 10.6701 4.11039 -1.35921 14.0346 5.36723 -1.32821 13.9875 5.61485 -1.29287 13.8703 5.83871 -1.25708 13.7495 6.05975 -1.23593 13.8853 6.38027 -0.995638 9.81365 4.97137 -1.19313 14.1992 7.06754 -0.960553 9.94657 5.42338 -0.929185 9.72565 5.52162 -0.89754 9.50451 5.6134 -0.746176 6.30184 4.15311 -0.715313 5.8693 4.05248 -0.700258 5.82568 4.15352 -0.716854 6.72907 4.80993 -0.699047 6.67985 4.93135 -0.688742 6.89951 5.22316 -0.663293 6.56726 5.16668 -0.634821 6.0576 4.97572 -0.617423 5.9568 5.05167 -0.605952 6.24094 5.40972 -0.676403 12.2411 10.1427 -0.636848 11.8623 10.1745 -0.612251 13.0569 11.4814 -0.561983 11.2507 10.3231 -0.52017 8.07473 7.86593 -0.489934 11.7743 11.4695 -0.469515 7.53532 7.84963 -0.449713 6.8149 7.38756 -0.42845 6.60517 7.39983 -0.403965 6.65334 7.6738 -0.389672 6.10281 7.31284 -0.371158 5.87413 7.27758 -0.351088 5.73233 7.33504 -0.328463 5.69271 7.51222 -0.311571 5.47307 7.47176 -0.292216 5.34304 7.53617 -0.277362 5.12722 7.48616 -0.287334 4.44702 6.78234 -0.259241 4.53524 7.12348 -0.238321 4.46756 7.25356 -0.307974 3.09572 5.36879 -0.297288 3.00414 5.39074 -0.198306 3.98456 7.20271 -0.31068 2.43255 4.75361 -0.298951 2.38217 4.81592 -0.275214 2.44264 5.08923 -0.300517 2.05502 4.5021 -0.302784 1.91173 4.36113 -0.295118 1.84509 4.37016 -0.286098 1.7915 4.40502 -0.276433 1.73986 4.44855 -0.264666 1.70354 4.52793 -0.194875 1.97778 5.42732 -0.174003 1.95573 5.60518 -0.175036 1.82072 5.47231 -0.12235 1.92561 6.05701 -0.128947 1.76752 5.85494 -0.207615 1.36178 4.75772 -0.100039 1.62463 5.99792 -0.183393 1.25607 4.88793 -0.182306 1.16888 4.81585 -0.182005 1.0843 4.74211 -0.0631968 1.26449 6.01628 -0.942531 1.79424 -1.21263 -0.950782 1.85622 -1.2181 -0.959879 1.91836 -1.22179 -1.32487 4.43876 -1.65581 -1.36166 4.68683 -1.70786 -1.3937 4.91252 -1.73671 -1.42979 5.16608 -1.7733 -1.47164 5.45792 -1.82108 -1.5173 5.77839 -1.8732 -1.57332 6.1549 -1.94173 -1.6321 6.56214 -2.01083 -1.70609 7.06376 -2.10833 -1.78188 7.58782 -2.19678 -1.86572 8.17276 -2.29119 -1.96975 8.89113 -2.41742 -2.08514 9.69096 -2.54773 -2.23392 10.7107 -2.728 -2.3882 11.7964 -2.89294 -2.60157 13.2682 -3.14213 -2.87566 15.1587 -3.46398 -3.2426 17.6921 -3.89873 -4.9011 29.7882 -5.12971 -1.76348 11.0423 1.83577 -1.73511 10.9801 2.01875 -1.7442 11.2404 2.23551 -1.69511 10.994 2.39748 -1.67392 11.0009 2.58819 -1.69986 11.4365 2.84966 -1.61144 10.808 2.9362 -1.58321 10.7476 3.11311 -1.67875 11.8985 3.55218 -1.62646 11.6037 3.69493 -1.60063 11.5773 3.89653 -1.56367 11.4425 4.06895 -1.42684 10.2241 3.92351 -1.381 9.95553 4.02823 -1.32621 9.56346 4.08402 -1.27283 9.18165 4.1302 -1.25641 9.22268 4.3185 -1.23279 9.16608 4.47343 -1.00646 6.59429 3.60412 -0.990887 6.57799 3.72485 -0.988511 6.74146 3.92746 -0.976192 6.78169 4.0814 -0.946743 6.57711 4.11883 -0.927718 6.52446 4.22737 -0.933599 6.83854 4.53267 -0.848325 5.75748 4.07767 -0.827056 5.63631 4.13182 -0.837871 6.06153 4.51271 -0.843697 6.45004 4.89309 -0.83325 6.55932 5.11361 -0.785991 5.96755 4.86917 -0.763965 5.85263 4.93224 -0.761223 6.15724 5.29814 -0.834839 8.36624 7.11901 -0.724173 6.10241 5.57224 -0.787898 8.45644 7.63972 -0.757605 8.32641 7.76705 -0.729123 8.25561 7.94394 -0.632749 5.50983 5.72208 -0.658922 7.57397 7.80629 -0.588047 5.08657 5.64968 -0.593458 6.79203 7.50992 -0.567064 6.67973 7.62099 -0.538031 6.22397 7.36498 -0.513382 5.97968 7.318 -0.488501 5.77914 7.30943 -0.464533 5.67676 7.41042 -0.440652 5.50274 7.42451 -0.421057 5.18841 7.25362 -0.395769 5.18324 7.47215 -0.388776 4.46241 6.72444 -0.405143 3.24487 5.21088 -0.389088 3.2005 5.30204 -0.374666 3.12601 5.3513 -0.360326 3.04627 5.39054 -0.281067 4.07107 7.24751 -0.265135 3.88795 7.1816 -0.346181 2.40578 4.79365 -0.299672 2.76748 5.62065 -0.321635 2.27894 4.87227 -0.326287 2.04386 4.56523 -0.326647 1.87984 4.37781 -0.318056 1.81329 4.38614 -0.306659 1.76313 4.42962 -0.295099 1.71179 4.47232 -0.277562 1.6998 4.61649 -0.237805 1.80443 5.08873 -0.200273 1.87049 5.49924 -0.151901 1.96336 6.03619 -0.140988 1.86096 6.01585 -0.149581 1.68699 5.74464 -0.215687 1.32316 4.74834 -0.109156 1.57267 5.98125 -0.193246 1.20054 4.80931 -0.180827 1.1412 4.85293 -0.0734718 1.30561 5.99882 -0.0589866 1.22298 6.03408 -1.00185 1.81705 -1.20915 -1.01197 1.87879 -1.2135 -1.02435 1.94703 -1.22439 -1.37335 3.93712 -1.56408 -1.403 4.11288 -1.58821 -1.437 4.30545 -1.61734 -1.47546 4.52632 -1.65665 -1.51361 4.7498 -1.68886 -1.56174 5.01757 -1.73877 -1.61008 5.29761 -1.78505 -1.66444 5.60667 -1.83621 -1.72373 5.9453 -1.8909 -1.79462 6.34851 -1.96496 -1.87289 6.79223 -2.04259 -1.95872 7.28547 -2.1258 -2.05408 7.82933 -2.21193 -2.16873 8.48691 -2.32466 -2.3031 9.25168 -2.45438 -2.45334 10.1159 -2.59233 -2.63308 11.1452 -2.75568 -2.8639 12.465 -2.97676 -3.14128 14.0581 -3.23376 -3.52338 16.2408 -3.60359 -4.67795 22.8622 -4.67361 -5.14006 25.6588 -4.90641 -5.15631 26.0552 -4.52108 -5.19384 26.5809 -4.15062 -2.08929 11.7165 2.63319 -2.05199 11.622 2.82207 -2.09457 12.1106 3.11064 -2.07171 12.1243 3.32664 -2.05549 12.1936 3.55553 -2.00653 12.0164 3.73191 -1.93868 11.6725 3.8624 -1.70596 10.1706 3.8573 -1.66448 10.0096 3.99448 -1.63266 9.92182 4.15132 -1.54321 9.3332 4.13513 -1.51032 9.22469 4.2719 -1.50261 9.34735 4.49432 -1.53953 9.8793 4.88903 -1.50206 9.74013 5.02447 -1.44778 9.43585 5.08359 -1.42342 9.41285 5.26284 -1.21065 7.4854 4.52182 -1.11076 6.63429 4.24601 -1.08386 6.52657 4.32785 -1.22031 8.20048 5.38687 -0.973725 5.64301 4.10125 -0.949897 5.53037 4.15802 -0.984021 6.12158 4.64757 -0.953591 5.95047 4.67799 -0.931569 5.87191 4.7644 -0.941553 6.23444 5.1562 -0.877244 5.57275 4.83295 -0.847176 5.37099 4.82242 -0.829091 5.34626 4.94003 -0.802265 5.17756 4.94581 -0.786194 5.18795 5.09327 -0.80721 5.87633 5.82797 -0.773092 5.59213 5.74448 -0.746206 5.43755 5.76762 -0.723014 5.36315 5.86257 -0.767955 6.98296 7.62565 -0.737151 6.86254 7.73279 -0.696815 6.4652 7.54734 -0.658122 6.00878 7.27657 -0.630942 5.93419 7.41145 -0.600676 5.71408 7.37811 -0.570614 5.45214 7.28517 -0.534694 4.29082 6.05115 -0.514702 4.65634 6.70534 -0.490822 4.55781 6.77937 -0.462286 5.02394 7.63993 -0.459653 3.21099 5.2596 -0.442523 3.13821 5.30878 -0.426568 3.03231 5.30612 -0.367153 4.18234 7.33457 -0.410307 2.47044 4.70067 -0.387154 2.58535 5.04971 -0.38141 2.35318 4.78986 -0.366401 2.30624 4.85978 -0.351912 2.24107 4.89306 -0.359203 1.93027 4.42168 -0.349327 1.84716 4.39428 -0.337633 1.78518 4.4108 -0.325068 1.73417 4.45387 -0.312575 1.68294 4.49596 -0.294353 1.66196 4.62135 -0.27838 1.62023 4.7 -0.213013 1.84161 5.55255 -0.164935 1.92026 6.06181 -0.153356 1.81276 6.02118 -0.224062 1.38349 4.84656 -0.205853 1.34125 4.95054 -0.197913 1.25895 4.90902 -0.20093 1.14948 4.73949 -0.189751 1.0826 4.74318 -0.0723748 1.25634 5.9778 -1.05169 1.7772 -1.19983 -1.06381 1.83834 -1.20471 -1.07936 1.91137 -1.22416 -1.09146 1.97423 -1.22584 -1.10368 2.0384 -1.22616 -1.12137 2.11993 -1.24768 -1.43618 3.65231 -1.49919 -1.47179 3.82299 -1.53056 -1.50483 3.98814 -1.55111 -1.54392 4.1789 -1.58285 -1.58539 4.38075 -1.61404 -1.63558 4.61846 -1.65947 -1.68916 4.87483 -1.70721 -1.74419 5.14408 -1.7519 -1.80737 5.44922 -1.80634 -1.86795 5.7506 -1.84656 -1.94159 6.10631 -1.90312 -2.03046 6.53662 -1.98207 -2.12603 6.99828 -2.05896 -2.23482 7.52668 -2.14789 -2.3605 8.13344 -2.24925 -2.50683 8.8456 -2.37 -2.66541 9.61961 -2.48705 -2.85523 10.5475 -2.63037 -3.0911 11.6974 -2.814 -3.39087 13.1552 -3.05277 -3.76589 14.9811 -3.34728 -4.33701 17.7359 -3.83358 -4.84837 20.2777 -4.16211 -5.52261 23.626 -4.59252 -5.52007 23.8629 -4.20813 -5.54951 24.2566 -3.8507 -2.45265 11.8294 2.59304 -2.08943 9.80568 2.49027 -2.40926 11.8748 3.01392 -2.05814 9.87341 2.84536 -2.03571 9.86415 3.01713 -2.50129 12.9461 3.88567 -2.33159 12.045 3.8988 -2.49679 13.2897 4.44285 -2.51265 13.5967 4.77136 -1.95516 10.0547 3.96144 -1.91755 9.95861 4.11685 -1.88264 9.87033 4.27274 -1.83614 9.70433 4.3998 -1.92505 10.5029 4.88536 -1.77734 9.60849 4.73396 -1.82774 10.1517 5.1481 -1.67886 9.20959 4.9377 -1.66029 9.24317 5.13821 -1.39773 7.35631 4.42193 -1.37653 7.33498 4.56229 -1.26084 6.53533 4.29784 -1.40745 7.91278 5.1861 -1.19173 6.23318 4.40523 -1.12159 5.7644 4.26535 -1.06803 5.42116 4.18305 -1.04765 5.37733 4.27675 -1.1439 6.44412 5.10675 -1.11135 6.30081 5.16228 -1.02767 5.64611 4.84959 -0.986242 5.38956 4.79949 -0.969004 5.38849 4.93588 -0.936222 5.20529 4.93051 -0.920121 5.21577 5.07836 -0.905663 5.25354 5.25336 -0.921978 5.69988 5.79332 -0.886806 5.50058 5.77846 -0.862395 5.43443 5.88131 -0.826134 5.20116 5.82296 -0.803464 5.16929 5.95634 -0.857682 6.47441 7.49012 -0.818436 6.26247 7.48541 -0.782584 6.09251 7.52 -0.723707 5.36746 6.90783 -0.696948 5.33799 7.07829 -0.657863 4.93962 6.79819 -0.616684 4.38685 6.29295 -0.598365 4.59104 6.75397 -0.579463 4.99792 7.52276 -0.549604 4.92162 7.65124 -0.512737 3.17537 5.30839 -0.493155 3.08625 5.33159 -0.461905 4.19562 7.26862 -0.420198 4.86819 8.62739 -0.447192 2.4216 4.70684 -0.429658 2.38248 4.78612 -0.417046 2.24767 4.68858 -0.394559 2.30373 4.95228 -0.360472 2.51406 5.55074 -0.37639 1.96879 4.5925 -0.369623 1.81793 4.41946 -0.356761 1.7551 4.43557 -0.341325 1.70462 4.47779 -0.326448 1.65684 4.52859 -0.308992 1.62354 4.62588 -0.283602 1.63219 4.84499 -0.197653 1.95324 6.03192 -0.170004 1.90918 6.19183 -0.1905 1.64551 5.62395 -0.237953 1.31722 4.74127 -0.205508 1.31559 4.99866 -0.21043 1.18656 4.76246 -0.192928 1.13341 4.82476 -0.0773563 1.3129 6.03858 -0.0469671 1.2532 6.2009 -1.11225 1.79669 -1.19561 -1.12862 1.86372 -1.20757 -1.14389 1.93135 -1.21791 -1.15788 1.99394 -1.21866 -1.17547 2.06957 -1.2333 -1.19386 2.14546 -1.24568 -1.21025 2.21745 -1.2489 -1.22991 2.30178 -1.26473 -1.2483 2.38103 -1.27109 -1.27037 2.47471 -1.28957 -1.29571 2.5762 -1.31215 -1.39625 3.00487 -1.37999 -1.42851 3.13539 -1.40634 -1.45974 3.26797 -1.42903 -1.49089 3.40247 -1.44763 -1.52682 3.55413 -1.47406 -1.56337 3.70665 -1.49561 -1.60387 3.87779 -1.52395 -1.6442 4.05113 -1.54704 -1.6965 4.26648 -1.59137 -1.75015 4.49339 -1.6341 -1.8068 4.73057 -1.6744 -1.86803 4.9872 -1.7168 -1.93303 5.26466 -1.76064 -2.00343 5.56182 -1.80442 -2.08717 5.91412 -1.86531 -2.18017 6.30504 -1.93166 -2.27877 6.72625 -1.99725 -2.40238 7.241 -2.08867 -2.5362 7.80543 -2.18172 -2.67505 8.40187 -2.2664 -2.85444 9.15873 -2.39057 -3.05401 10.0044 -2.51859 -3.30067 11.0502 -2.68429 -3.61915 12.3921 -2.90711 -3.98068 13.9315 -3.14016 -4.51348 16.175 -3.51784 -5.08261 18.6056 -3.862 -6.25709 23.7572 -4.34861 -6.30808 24.2001 -4.00191 -2.34238 9.75169 2.60827 -2.30652 9.67875 2.76608 -2.33294 9.93152 2.98777 -2.29201 9.83395 3.14234 -2.25267 9.74323 3.2964 -2.24465 9.82148 3.49183 -2.18405 9.61128 3.61188 -2.16413 9.62727 3.7919 -2.21164 10.025 4.09446 -2.15343 9.82593 4.21506 -2.11608 9.74585 4.37211 -2.05367 9.51612 4.47187 -1.98707 9.25744 4.5537 -1.94078 9.11778 4.67626 -1.92548 9.16646 4.87751 -1.88862 9.07592 5.02021 -1.9713 9.76223 5.52973 -1.56863 7.29052 4.50657 -1.52835 7.15432 4.58717 -1.52105 7.23538 4.78181 -1.64947 8.26254 5.51492 -1.32296 6.11447 4.44068 -1.20727 5.40387 4.1445 -1.17859 5.3019 4.20126 -1.4629 7.57639 5.81438 -1.36475 6.99487 5.5991 -1.31168 6.74852 5.59436 -1.23031 6.25446 5.40025 -1.14354 5.69678 5.13613 -1.10505 5.52621 5.14938 -1.04997 5.19472 5.02566 -1.02625 5.1506 5.12914 -1.05184 5.57042 5.63848 -1.02651 5.52221 5.75582 -1.00897 5.55935 5.95447 -0.984479 5.52693 6.09319 -0.938586 5.25819 5.99926 -1.01452 6.43691 7.39032 -0.991696 6.50004 7.67759 -0.911324 5.81176 7.14607 -0.81479 4.80899 6.20888 -0.783935 4.69588 6.25494 -0.762656 4.72039 6.46933 -0.767084 5.27787 7.36887 -0.694609 4.35383 6.37889 -0.677647 4.54707 6.83436 -0.66159 4.8359 7.45281 -0.584857 3.19326 5.28321 -0.56231 3.10495 5.30682 -0.540477 3.03782 5.36239 -0.531434 5.01749 8.77084 -0.497827 2.4185 4.65108 -0.479788 2.38152 4.72994 -0.432599 3.82155 7.53286 -0.432558 2.64381 5.54294 -0.410878 2.55788 5.56382 -0.38791 2.51085 5.66431 -0.402621 1.8614 4.45569 -0.388732 1.7829 4.43558 -0.373003 1.72559 4.45969 -0.356398 1.67427 4.50149 -0.338656 1.63306 4.57043 -0.319537 1.59603 4.65786 -0.300019 1.55687 4.7447 -0.208278 1.90866 6.05768 -0.200346 1.75377 5.85371 -0.250449 1.37156 4.82059 -0.241209 1.28064 4.74104 -0.212198 1.26087 4.93031 -0.209409 1.15372 4.77011 -0.0753803 1.39538 6.2262 -0.0805838 1.2484 5.93919 -1.16161 1.75952 -1.19422 -1.1776 1.81982 -1.19853 -1.19487 1.88685 -1.2094 -1.21321 1.95501 -1.2186 -1.23141 2.02362 -1.22585 -1.25416 2.10509 -1.24667 -1.2723 2.17554 -1.25013 -1.28933 2.24663 -1.25186 -1.31204 2.33155 -1.26626 -1.33807 2.42413 -1.28534 -1.36063 2.51116 -1.29478 -1.38877 2.61235 -1.31544 -1.41367 2.70894 -1.32666 -1.44183 2.81342 -1.34158 -1.47222 2.92609 -1.35993 -1.50754 3.05552 -1.38787 -1.54033 3.17927 -1.40566 -1.57869 3.31886 -1.43166 -1.61135 3.44634 -1.44178 -1.65196 3.59743 -1.46537 -1.69727 3.76593 -1.49563 -1.74818 3.95184 -1.53157 -1.79911 4.14106 -1.56167 -1.85718 4.35693 -1.60168 -1.92088 4.59179 -1.64473 -1.98756 4.83701 -1.68497 -2.05805 5.10295 -1.72714 -2.13727 5.3962 -1.77411 -2.22598 5.72737 -1.82965 -2.32363 6.0885 -1.88708 -2.43761 6.51349 -1.96172 -2.55769 6.96039 -2.02976 -2.70016 7.49218 -2.11787 -2.85089 8.05599 -2.19872 -3.03636 8.74994 -2.30987 -3.25128 9.55048 -2.43437 -3.50853 10.5125 -2.58592 -3.82037 11.6754 -2.76807 -4.20058 13.0972 -2.98779 -4.70692 14.9844 -3.29117 -5.26122 17.0731 -3.57914 -5.76528 19.0182 -3.7527 -5.71893 19.0238 -3.39562 -5.62704 18.8617 -3.00516 -5.57026 18.8246 -2.64876 -5.57906 19.0284 -2.33981 -13.4534 50.8088 -2.5396 -13.5603 51.7037 -1.67954 -3.42726 13.2761 3.13777 -2.62207 9.80296 2.74889 -2.6078 9.84517 2.93031 -2.55952 9.73067 3.08064 -2.50644 9.59464 3.22274 -3.2146 13.0256 4.26529 -2.56324 10.0825 3.70237 -2.54533 10.1158 3.89695 -2.51014 10.062 4.06702 -2.45425 9.91117 4.20527 -2.41904 9.86143 4.37433 -2.32812 9.53093 4.44056 -2.21853 9.091 4.45343 -2.23554 9.3009 4.71565 -2.1807 9.14188 4.83095 -2.22854 9.52985 5.18796 -2.08861 8.90933 5.08938 -2.01808 8.65745 5.14862 -1.77727 7.43953 4.70422 -1.73487 7.31885 4.79626 -1.72448 7.37868 4.98621 -1.57176 6.60319 4.69771 -1.88184 8.58601 6.03993 -1.30752 5.23042 4.13234 -1.28696 5.19669 4.22889 -1.55026 6.98441 5.55752 -1.51072 6.86944 5.64509 -1.39867 6.27153 5.37974 -1.36878 6.21564 5.49509 -1.26847 5.66318 5.22477 -1.32311 6.19762 5.80463 -1.17538 5.27092 5.19839 -1.23069 5.84166 5.83754 -1.19059 5.69508 5.87331 -1.14184 5.48259 5.84449 -1.07073 5.07144 5.61648 -1.04128 5.00256 5.70519 -1.04147 5.19576 6.0644 -1.00223 5.04383 6.07544 -0.962373 4.87879 6.06812 -0.937302 4.86102 6.22105 -0.919586 4.92306 6.47369 -0.89187 4.89498 6.62948 -0.899949 5.32968 7.3721 -0.864784 5.2598 7.50491 -0.789453 4.586 6.82629 -0.757087 4.51762 6.93933 -0.72673 4.48089 7.10089 -0.632112 3.09882 5.24916 -0.609113 3.04977 5.32976 -0.61426 3.88756 6.84701 -0.603562 4.77128 8.55665 -0.560107 4.4311 8.25795 -0.511414 2.33167 4.73512 -0.483791 3.65818 7.3941 -0.465041 2.64058 5.65741 -0.421554 3.2495 7.10751 -0.404349 2.77974 6.3674 -0.421947 1.82238 4.46295 -0.404716 1.75252 4.46018 -0.387826 1.69434 4.48378 -0.369319 1.64334 4.52486 -0.350163 1.60536 4.60263 -0.329388 1.56457 4.68009 -0.297294 1.58976 4.96588 -0.157803 2.18507 7.11231 -0.223681 1.62704 5.58978 -0.26193 1.29671 4.68622 -0.23868 1.25948 4.79815 -0.222052 1.19112 4.79323 -0.213238 1.10345 4.69951 -0.085109 1.31117 6.03955 -0.0472199 1.25621 6.22079 -1.1883 1.65643 -1.178 -1.20327 1.71087 -1.17633 -1.22341 1.77571 -1.18927 -1.24031 1.83597 -1.19268 -1.26042 1.90253 -1.20241 -1.28276 1.97572 -1.21809 -1.30613 2.05012 -1.23172 -1.32532 2.12012 -1.23613 -1.35095 2.20269 -1.25328 -1.37103 2.27434 -1.25368 -1.39655 2.35892 -1.26635 -1.42189 2.44405 -1.2766 -1.45556 2.55162 -1.30548 -1.48324 2.64633 -1.31741 -1.51786 2.75708 -1.33994 -1.5421 2.84781 -1.33972 -1.57872 2.9675 -1.36238 -1.61873 3.09631 -1.38767 -1.65769 3.22724 -1.40909 -1.7 3.36742 -1.43256 -1.74439 3.51626 -1.45742 -1.78987 3.66788 -1.47769 -1.84679 3.85193 -1.51543 -1.90012 4.03078 -1.54198 -1.96161 4.23597 -1.57871 -2.02951 4.45884 -1.61884 -2.09731 4.68532 -1.65179 -2.17303 4.93885 -1.69179 -2.25778 5.22048 -1.73757 -2.35983 5.5561 -1.80125 -2.45896 5.8873 -1.84924 -2.57741 6.28138 -1.91554 -2.69859 6.68828 -1.97251 -2.84616 7.17875 -2.05101 -3.01608 7.74401 -2.14248 -3.18477 8.31469 -2.21439 -3.42003 9.09617 -2.34561 -3.66869 9.93022 -2.46581 -3.99558 11.0162 -2.64069 -4.41015 12.3933 -2.86808 -4.87463 13.948 -3.09682 -5.38471 15.6722 -3.31472 -6.10145 18.085 -3.6497 -17.1871 55.1535 -9.22472 -14.7523 50.0748 -1.86621 -14.6617 51.5509 1.73808 -2.87585 9.64981 2.68367 -2.82382 9.54139 2.83348 -2.7963 9.52497 3.00012 -3.54665 12.6695 3.89773 -3.52045 12.6935 4.13407 -2.8042 9.85323 3.60425 -2.77377 9.83294 3.77915 -2.70352 9.64158 3.90256 -2.74185 9.91365 4.17073 -2.68733 9.79112 4.31543 -2.65251 9.74911 4.48678 -3.26523 12.591 5.76741 -2.52084 9.39404 4.72029 -2.57196 9.74156 5.05338 -2.35781 8.88001 4.86433 -2.45353 9.44284 5.30588 -2.27231 8.71217 5.14369 -2.33328 9.12858 5.53699 -1.96761 7.46616 4.84724 -1.80598 6.77592 4.62475 -1.7909 6.80392 4.78732 -2.03207 8.1477 5.74276 -1.44405 5.21424 4.10094 -1.40781 5.10611 4.14939 -1.61254 6.3036 5.0704 -1.6004 6.35207 5.25416 -1.48356 5.81723 5.02365 -1.46117 5.79965 5.15537 -1.50305 6.16413 5.58456 -1.397 5.66364 5.34515 -1.33851 5.43332 5.30482 -1.40179 5.96589 5.91135 -1.34547 5.75169 5.89057 -1.23243 5.15261 5.5069 -1.19149 5.0216 5.5357 -1.16294 4.96895 5.63787 -1.19045 5.3332 6.16534 -1.14407 5.16599 6.16511 -1.26509 6.30778 7.58401 -1.06251 4.90244 6.22586 -0.991133 4.50484 5.94122 -0.971424 4.53854 6.15108 -1.03719 5.3958 7.39885 -0.990294 5.23513 7.41437 -0.869168 4.26228 6.33866 -0.87373 4.62399 7.02915 -0.828533 4.4388 6.97911 -0.795742 4.39066 7.12332 -0.732177 3.89228 6.57998 -0.697652 3.78896 6.62325 -0.672608 3.89155 7.00691 -0.667296 4.57496 8.41589 -0.616837 4.2565 8.13756 -0.568479 3.77852 7.53338 -0.523807 2.9011 6.09706 -0.494331 2.85624 6.22053 -0.462614 2.86757 6.47032 -0.433189 2.71939 6.38452 -0.438888 1.78682 4.47893 -0.419525 1.7213 4.48447 -0.400487 1.66752 4.51658 -0.379602 1.62601 4.58536 -0.358059 1.58043 4.6439 -0.336115 1.5388 4.72094 -0.235386 1.98961 6.34866 -0.246629 1.68481 5.65759 -0.277098 1.34945 4.7661 -0.262042 1.26588 4.70491 -0.240767 1.21388 4.75814 -0.210166 1.1841 4.91748 -0.0867577 1.39084 6.2179 -0.0796554 1.25982 6.00839 -1.21085 1.55498 -1.15885 -1.23299 1.61753 -1.17534 -1.24658 1.66555 -1.16574 -1.2656 1.72483 -1.17134 -1.28976 1.79458 -1.19126 -1.31187 1.86056 -1.20143 -1.33074 1.92193 -1.20217 -1.35282 1.98967 -1.20893 -1.38018 2.06912 -1.22895 -1.40549 2.14477 -1.23932 -1.43296 2.2272 -1.25496 -1.45818 2.30481 -1.26106 -1.48673 2.39 -1.27221 -1.51413 2.476 -1.28085 -1.55132 2.58214 -1.3074 -1.58201 2.67752 -1.31751 -1.61596 2.78078 -1.33141 -1.65312 2.89201 -1.34862 -1.69369 3.01227 -1.36886 -1.73987 3.14826 -1.39777 -1.78009 3.27128 -1.41023 -1.8295 3.41854 -1.43672 -1.87539 3.56039 -1.4529 -1.93471 3.73411 -1.4869 -1.99046 3.90259 -1.5099 -2.04842 4.08102 -1.53293 -2.12316 4.30055 -1.57591 -2.20375 4.54006 -1.62195 -2.28468 4.78123 -1.65959 -2.37492 5.05131 -1.70379 -2.47717 5.35649 -1.75698 -2.58262 5.67467 -1.80444 -2.70361 6.03831 -1.86244 -2.84114 6.44872 -1.92854 -2.98012 6.87143 -1.98426 -3.15405 7.39434 -2.06741 -3.34068 7.95795 -2.14688 -3.56729 8.6409 -2.25176 -3.83581 9.44615 -2.37559 -4.15287 10.4019 -2.52147 -4.55294 11.6002 -2.71081 -5.0489 13.0893 -2.94478 -5.60812 14.7828 -3.18127 -6.04211 16.1432 -3.26286 -19.8083 58.2889 -8.02028 -19.7138 58.476 -6.96243 -19.6282 58.6918 -5.90773 -19.5331 58.8815 -4.84835 -19.4521 59.1104 -3.79043 -16.2237 50.7411 0.571579 -3.09555 9.5568 2.97411 -3.19008 10.0815 3.44843 -3.0673 9.7283 3.53931 -3.03918 9.71934 3.71583 -3.00511 9.68964 3.88662 -2.96038 9.61908 4.04529 -2.88113 9.41825 4.15783 -2.87876 9.50798 4.36979 -2.94147 9.85653 4.68624 -2.39535 7.80412 4.05406 -2.84987 9.71583 5.01318 -2.40064 8.00365 4.44985 -2.26467 7.54304 4.39737 -2.62961 9.15329 5.33125 -2.50742 8.75452 5.3198 -2.40437 8.42737 5.33195 -1.96053 6.61631 4.51618 -1.95582 6.68935 4.70059 -1.87062 6.404 4.67718 -2.02205 7.18127 5.30213 -1.54451 5.09443 4.12469 -1.52136 5.06207 4.2197 -1.74383 6.20202 5.12769 -1.65354 5.87226 5.04116 -1.52943 5.36403 4.80872 -1.60216 5.82851 5.30089 -1.49921 5.41188 5.11986 -1.46067 5.31589 5.18359 -1.5571 5.94906 5.86885 -1.52823 5.92299 6.01269 -1.46702 5.71729 5.99661 -1.34756 5.16891 5.64706 -1.1934 4.39158 5.04392 -1.2005 4.55683 5.34756 -1.15355 4.39046 5.32028 -1.13485 4.40835 5.48558 -1.15226 4.67368 5.93442 -1.0987 4.46418 5.85851 -1.06002 4.35924 5.89917 -1.03443 4.34927 6.05359 -0.99756 4.25487 6.1067 -1.03263 4.77205 6.97014 -0.983002 4.59272 6.93293 -0.940362 4.47871 6.98089 -0.889091 4.26893 6.8861 -0.83444 4.00791 6.7023 -0.790741 3.84001 6.64621 -0.753392 3.74207 6.69689 -0.733518 3.9276 7.22821 -0.701466 3.98266 7.56687 -0.649891 3.66019 7.23241 -0.59204 3.01093 6.242 -0.558405 2.88069 6.19707 -0.52576 2.79955 6.24821 -0.492373 2.79215 6.46151 -0.459414 2.66653 6.41938 -0.453678 1.75066 4.49457 -0.432419 1.68545 4.49929 -0.410998 1.63512 4.5401 -0.388211 1.59392 4.60815 -0.365254 1.55158 4.67552 -0.341172 1.50931 4.75203 -0.201417 2.19565 7.19519 -0.250333 1.63837 5.66106 -0.273083 1.3328 4.84316 -0.256612 1.25246 4.79079 -0.234658 1.18935 4.80485 -0.101944 1.44597 6.26877 -0.0904514 1.31509 6.06989 -0.0501271 1.25557 6.22116 -1.24725 1.51156 -1.14736 -1.26801 1.56767 -1.15602 -1.28889 1.62509 -1.16332 -1.3099 1.68378 -1.16936 -1.33055 1.74188 -1.17364 -1.35467 1.80721 -1.18455 -1.37865 1.87295 -1.1936 -1.40153 1.93931 -1.20102 -1.42878 2.01285 -1.21416 -1.45258 2.08082 -1.21777 -1.48282 2.16136 -1.23412 -1.51007 2.23826 -1.24123 -1.54369 2.32793 -1.26021 -1.57156 2.40566 -1.26254 -1.6108 2.51101 -1.2904 -1.64849 2.61049 -1.3079 -1.68197 2.70559 -1.31609 -1.7187 2.80857 -1.32798 -1.76305 2.92661 -1.34938 -1.80296 3.03935 -1.36108 -1.85628 3.1823 -1.3935 -1.90023 3.3049 -1.40352 -1.95431 3.45158 -1.42718 -2.02183 3.63013 -1.46864 -2.07899 3.78854 -1.48782 -2.14274 3.96411 -1.51265 -2.21323 4.15802 -1.54236 -2.30137 4.39308 -1.59073 -2.38581 4.62328 -1.62636 -2.48009 4.88018 -1.66851 -2.58456 5.16601 -1.71603 -2.69609 5.47027 -1.76257 -2.81761 5.80408 -1.81174 -2.95301 6.17441 -1.86586 -3.09793 6.57407 -1.91922 -3.26713 7.03855 -1.98572 -3.47374 7.60224 -2.07636 -3.69019 8.19703 -2.15736 -3.96433 8.94757 -2.27479 -4.27246 9.79274 -2.39697 -4.6628 10.8588 -2.5617 -5.15487 12.203 -2.77404 -5.71044 13.7296 -2.98882 -6.18848 15.0792 -3.09551 -18.7428 49.6002 -7.92881 -16.8288 50.4495 6.72981 -3.41466 9.90311 3.55583 -3.32718 9.70087 3.68215 -3.27771 9.62712 3.84005 -3.2087 9.48525 3.9755 -3.18546 9.49754 4.15899 -3.15755 9.49685 4.34024 -2.63642 7.7679 3.86856 -2.58403 7.66259 3.97715 -2.56633 7.6808 4.13505 -2.57065 7.77673 4.32915 -2.41004 7.27685 4.25545 -2.34606 7.12302 4.32911 -2.33838 7.17676 4.50306 -2.0501 6.16675 4.12267 -2.09546 6.41913 4.39047 -2.24259 7.0706 4.90032 -2.21445 7.05294 5.04499 -2.12803 6.7993 5.0464 -1.70696 5.18629 4.16888 -1.67163 5.11285 4.23876 -1.64269 5.07045 4.32913 -1.66918 5.2587 4.58441 -1.61307 5.10042 4.59532 -1.60998 5.16903 4.77551 -1.65575 5.46499 5.14245 -1.58796 5.25517 5.11386 -1.54485 5.15214 5.16856 -1.70363 6.00641 6.06211 -1.56301 5.45091 5.72894 -1.45292 5.02324 5.48614 -1.324 4.48375 5.11239 -1.30995 4.51636 5.28324 -1.24876 4.30426 5.20592 -1.22255 4.27739 5.31868 -1.25152 4.56778 5.78564 -1.23107 4.58931 5.97147 -1.18494 4.45835 5.98415 -1.16402 4.49133 6.19418 -1.11126 4.31623 6.14829 -1.07336 4.2395 6.22457 -1.0817 4.49717 6.75742 -1.06268 4.58361 7.08051 -1.00035 4.33951 6.93878 -0.928071 3.99048 6.62379 -0.885065 3.87775 6.65211 -0.84247 3.76545 6.6779 -0.802523 3.66889 6.72705 -0.835209 4.50284 8.40563 -0.742766 3.79022 7.39776 -0.689086 3.52324 7.1459 -0.620743 2.86161 6.09346 -0.587633 2.81855 6.21615 -0.55758 2.96221 6.74629 -0.517543 2.69265 6.39694 -0.481357 2.66058 6.5639 -0.466315 1.71392 4.50988 -0.443639 1.65695 4.53236 -0.419596 1.61412 4.59102 -0.395391 1.56511 4.63996 -0.370296 1.52214 4.7068 -0.34407 1.47926 4.78288 -0.26868 1.73764 5.87282 -0.251883 1.59029 5.65404 -0.281677 1.25747 4.69799 -0.254343 1.2119 4.76987 -0.226633 1.16518 4.85103 -0.0995919 1.38188 6.19004 -0.0876286 1.25093 5.96998 -1.3042 1.52319 -1.14482 -1.32371 1.57416 -1.14429 -1.34961 1.63619 -1.15884 -1.37153 1.69484 -1.16398 -1.39717 1.75766 -1.17502 -1.42316 1.82278 -1.18471 -1.44901 1.88829 -1.19264 -1.47472 1.95424 -1.19863 -1.50384 2.02757 -1.21056 -1.53376 2.10119 -1.22013 -1.56608 2.18254 -1.23517 -1.59263 2.25201 -1.23336 -1.63137 2.34765 -1.25793 -1.66434 2.43143 -1.26556 -1.70408 2.53011 -1.28447 -1.74456 2.62927 -1.30015 -1.78085 2.72403 -1.30662 -1.8248 2.83375 -1.32298 -1.87512 2.9579 -1.3483 -1.92977 3.09105 -1.37574 -1.97676 3.21258 -1.38725 -2.03124 3.34959 -1.40643 -2.09338 3.50322 -1.43259 -2.15851 3.66548 -1.45914 -2.22034 3.82336 -1.47529 -2.30074 4.02067 -1.51222 -2.38804 4.23749 -1.55324 -2.47575 4.45583 -1.58646 -2.57786 4.70909 -1.63174 -2.68738 4.98138 -1.67767 -2.79641 5.25683 -1.71408 -2.92077 5.56883 -1.75863 -3.05557 5.90838 -1.80482 -3.21664 6.3105 -1.8675 -3.38012 6.72472 -1.91968 -3.57742 7.22012 -1.99097 -3.81164 7.8067 -2.0802 -4.07111 8.45897 -2.17211 -4.38228 9.23894 -2.28582 -4.77053 10.2108 -2.436 -5.22045 11.3411 -2.60009 -5.82291 12.8445 -2.83503 -6.46579 14.4689 -3.04609 -7.08231 16.0532 -3.18343 -8.87733 20.5031 -3.97084 -15.1007 36.3192 -5.76749 -16.2565 39.7547 -4.89748 -16.2045 39.921 -4.16789 -18.5946 46.6409 -3.30147 -18.9752 48.3352 -1.66485 -20.8805 54.513 0.999633 -20.7757 54.6501 2.00161 -20.6567 54.7523 3.00597 -17.4604 49.1623 10.0244 -17.7768 50.9289 12.2474 -3.64475 9.66831 3.46893 -3.61426 9.66335 3.64674 -3.58033 9.64611 3.82203 -3.59306 9.77187 4.04332 -3.46911 9.47575 4.12944 -2.89259 7.76313 3.70072 -2.84567 7.68954 3.82188 -3.36083 9.40719 4.65254 -3.30498 9.31855 4.80193 -3.17774 8.99926 4.84842 -3.09204 8.81133 4.94451 -2.45688 6.79622 4.15769 -2.37769 6.60298 4.20047 -2.41811 6.81244 4.448 -2.36581 6.71032 4.53665 -2.4157 6.96134 4.8236 -2.39619 6.97901 4.98683 -2.29524 6.70283 4.97364 -1.87188 5.25532 4.20227 -1.82803 5.16638 4.26319 -1.76395 4.99592 4.2667 -1.78886 5.16167 4.50279 -1.75795 5.11588 4.5947 -1.74794 5.15396 4.75116 -1.75183 5.2506 4.95832 -1.66754 4.9998 4.88976 -1.67993 5.13431 5.13763 -1.65485 5.12233 5.26778 -1.98995 6.64747 6.79448 -1.55731 4.89505 5.34751 -1.46979 4.60756 5.21473 -1.43761 4.56289 5.31051 -1.36118 4.31038 5.19245 -1.30897 4.16317 5.17525 -1.2839 4.1445 5.29344 -1.3677 4.68394 6.05392 -1.41282 5.05952 6.66721 -1.3576 4.91977 6.68746 -1.22406 4.34241 6.15088 -1.24479 4.62429 6.69368 -1.17262 4.36823 6.54333 -1.08476 4.00211 6.22353 -1.08007 4.16294 6.63872 -1.03239 4.04517 6.66248 -0.99169 3.97649 6.75904 -0.957208 3.96425 6.94765 -0.922595 3.9618 7.16303 -0.97602 4.81566 8.87627 -0.836693 3.84145 7.42259 -0.768073 3.48393 7.00514 -0.689863 2.92148 6.15057 -0.679893 3.30854 7.14354 -0.616992 2.80312 6.33397 -0.589544 3.07217 7.15761 -0.540165 2.64254 6.44078 -0.501693 1.75001 4.53869 -0.477275 1.68954 4.55238 -0.451492 1.63215 4.57421 -0.426518 1.58442 4.62332 -0.400654 1.54272 4.69033 -0.374148 1.49191 4.73797 -0.345538 1.45248 4.82276 -0.277734 1.64243 5.71337 -0.246441 1.56297 5.72354 -0.275278 1.23715 4.75452 -0.250653 1.17565 4.76802 -0.142319 1.36063 5.90045 -0.0916983 1.3281 6.14928 -0.0694022 1.21864 6.02556 -1.31735 1.42698 -1.13188 -1.34209 1.48192 -1.14142 -1.36575 1.53741 -1.14962 -1.38639 1.58932 -1.14829 -1.41081 1.64526 -1.15345 -1.43437 1.70271 -1.15737 -1.46213 1.76622 -1.16759 -1.48998 1.83111 -1.17616 -1.51747 1.89543 -1.18278 -1.55266 1.97294 -1.20281 -1.58031 2.04009 -1.20574 -1.6088 2.10745 -1.2067 -1.647 2.19352 -1.2274 -1.68219 2.27601 -1.23858 -1.71793 2.35789 -1.24701 -1.76046 2.45462 -1.26692 -1.80299 2.55302 -1.28382 -1.84303 2.64563 -1.29106 -1.88953 2.75244 -1.30833 -1.93624 2.86195 -1.32239 -1.99789 2.99915 -1.35741 -2.04524 3.11111 -1.36396 -2.10011 3.23842 -1.37876 -2.16607 3.38966 -1.40677 -2.23262 3.54186 -1.4295 -2.30698 3.71189 -1.45825 -2.38451 3.89168 -1.48681 -2.47045 4.08853 -1.51932 -2.56832 4.31116 -1.56025 -2.67013 4.54395 -1.59815 -2.78393 4.80399 -1.64234 -2.89728 5.06709 -1.67739 -3.02246 5.3579 -1.71668 -3.16338 5.68341 -1.76243 -3.31612 6.03835 -1.80921 -3.49229 6.44618 -1.86692 -3.68839 6.89973 -1.92864 -3.92005 7.43462 -2.00659 -4.1909 8.05867 -2.0994 -4.48579 8.74147 -2.18929 -4.85028 9.5855 -2.31041 -5.31538 10.6543 -2.47398 -5.8697 11.9345 -2.66229 -6.53804 13.48 -2.87882 -7.12625 14.8714 -2.99187 -8.90448 18.9191 -3.73165 -18.9718 42.438 -6.40405 -20.0984 46.6563 -2.69695 -15.1633 35.2335 -1.11672 -15.1426 35.6986 0.183978 -19.788 49.8259 7.21928 -3.92599 9.60185 3.42883 -3.87908 9.55323 3.59441 -3.8316 9.50134 3.75873 -3.81582 9.53752 3.94982 -3.73996 9.40854 4.08853 -3.64257 9.21429 4.201 -3.07338 7.66637 3.79988 -3.51273 9.00891 4.47947 -3.47049 8.96993 4.64137 -3.41537 8.89197 4.78736 -3.32693 8.71709 4.88739 -2.87824 7.45148 4.46119 -2.56579 6.57808 4.17858 -2.54525 6.58282 4.31876 -2.54834 6.66187 4.50096 -2.54115 6.71185 4.67251 -2.49478 6.64116 4.77794 -2.45833 6.60232 4.90179 -2.35703 6.34861 4.89008 -1.98729 5.20652 4.28223 -2.02533 5.39862 4.53442 -1.89078 5.01294 4.38886 -2.32508 6.57752 5.66181 -2.02558 5.62398 5.09945 -1.88629 5.2095 4.91575 -1.78237 4.91508 4.81106 -1.82078 5.13486 5.12621 -1.74785 4.94613 5.10193 -1.6974 4.84026 5.14429 -1.71028 4.97869 5.41166 -1.62459 4.73354 5.32311 -1.58647 4.67433 5.40755 -1.48739 4.36025 5.22904 -1.44379 4.27509 5.27812 -1.43045 4.31492 5.46435 -1.40087 4.29176 5.5859 -1.35148 4.17601 5.60219 -1.5131 5.05574 6.82458 -1.43759 4.84167 6.75104 -1.37375 4.67961 6.73448 -1.33062 4.61952 6.84927 -1.22824 4.23807 6.51931 -1.16611 4.06641 6.46361 -1.12958 4.03056 6.60179 -1.07606 3.89413 6.58945 -1.10237 4.28766 7.4188 -1.01625 3.94431 7.08422 -0.965732 3.84362 7.13629 -0.929852 3.85501 7.38648 -0.848895 3.47888 6.93552 -0.801106 3.37099 6.96116 -0.728778 2.9737 6.40327 -0.684802 2.85758 6.38367 -0.642471 2.76857 6.41572 -0.611989 2.94049 7.04101 -0.560971 2.68488 6.70526 -0.512157 1.71275 4.55395 -0.485843 1.65258 4.56681 -0.458889 1.59935 4.59718 -0.431043 1.55822 4.66453 -0.403522 1.51276 4.72157 -0.374633 1.4654 4.77791 -0.329568 1.5328 5.2264 -0.275897 1.59917 5.72557 -0.297686 1.259 4.72957 -0.269865 1.2034 4.76267 -0.241414 1.14971 4.80423 -0.122564 1.34113 6.01594 -0.0883856 1.25892 6.01952 -1.37462 1.43536 -1.1294 -1.40004 1.48932 -1.13784 -1.42244 1.53967 -1.13686 -1.44811 1.59619 -1.14277 -1.47441 1.65187 -1.14691 -1.50728 1.7197 -1.16565 -1.53259 1.7773 -1.1668 -1.55899 1.836 -1.16637 -1.60001 1.91671 -1.19439 -1.62636 1.9772 -1.19047 -1.65993 2.04899 -1.19945 -1.69686 2.12831 -1.21369 -1.73056 2.20303 -1.2185 -1.77257 2.2901 -1.23493 -1.81764 2.38399 -1.25535 -1.8597 2.47426 -1.26643 -1.90575 2.5712 -1.28109 -1.95203 2.67077 -1.29294 -2.00131 2.77735 -1.30799 -2.0601 2.89867 -1.33173 -2.11785 3.02209 -1.35171 -2.17234 3.141 -1.36186 -2.24285 3.28876 -1.39111 -2.30981 3.43121 -1.40966 -2.38123 3.58389 -1.42926 -2.46866 3.76713 -1.46485 -2.56016 3.96011 -1.49926 -2.65595 4.16389 -1.53218 -2.76125 4.38577 -1.56787 -2.87381 4.62547 -1.60519 -2.99123 4.87529 -1.63858 -3.12052 5.15272 -1.6767 -3.2668 5.46543 -1.72204 -3.41769 5.78898 -1.76023 -3.60625 6.18964 -1.82249 -3.79937 6.60295 -1.874 -4.03413 7.10342 -1.94704 -4.30691 7.68428 -2.03292 -4.61321 8.33876 -2.1241 -4.95247 9.06686 -2.21619 -5.40255 10.0239 -2.35893 -5.93663 11.1618 -2.52238 -6.60034 12.5778 -2.72542 -7.46269 14.4159 -2.99221 -8.25642 16.138 -3.15499 -10.0149 19.8675 -3.74037 -19.2077 39.6071 -6.18644 -28.911 60.8433 -7.7033 -28.8451 61.1285 -6.55869 -16.0992 34.4861 -1.25574 -16.1568 35.1037 0.027658 -16.1387 35.3117 0.684468 -15.9367 35.1066 1.3439 -15.3668 36.1325 7.42898 -15.0934 35.7477 8.03403 -15.0031 35.8069 8.72348 -4.25509 9.55913 3.22093 -4.19021 9.55013 3.57635 -4.12331 9.45552 3.72934 -3.87448 9.1258 4.33529 -3.74076 8.85243 4.40794 -3.73306 8.91166 4.6083 -3.27162 7.75205 4.28272 -3.46712 8.35428 4.71427 -3.50969 8.55126 4.98019 -3.46008 8.49601 5.13082 -2.7511 6.59511 4.32001 -2.70191 6.52313 4.4209 -2.72786 6.66663 4.64215 -2.62325 6.43267 4.65081 -2.56705 6.33937 4.73677 -2.48074 6.15608 4.76331 -2.20504 5.40234 4.40738 -2.1186 5.20172 4.39578 -2.17379 5.43618 4.68522 -2.16862 5.49109 4.85766 -2.12604 5.42723 4.94477 -2.27514 5.97881 5.51752 -2.20756 5.84432 5.56352 -1.92573 5.00253 5.00881 -1.859 4.85439 5.0154 -1.96775 5.30281 5.55427 -1.92841 5.25625 5.6628 -2.29724 6.65432 7.16438 -1.7194 4.69106 5.41398 -1.7251 4.8025 5.67438 -1.55847 4.27359 5.26603 -1.51633 4.20234 5.32822 -1.51951 4.30703 5.58851 -1.45908 4.16692 5.57546 -1.74791 5.47585 7.31171 -1.58008 4.90971 6.81362 -1.52764 4.82045 6.89319 -1.46759 4.70127 6.93085 -1.41553 4.61588 7.0143 -1.24243 3.932 6.24114 -1.31113 4.44095 7.17606 -1.26134 4.37243 7.28784 -1.2064 4.27034 7.34812 -1.14942 4.1623 7.39757 -1.07263 3.92199 7.22133 -1.00831 3.75108 7.15142 -0.969057 3.75119 7.38376 -0.891402 3.45716 7.0691 -0.783175 2.84587 6.09514 -0.750638 2.86651 6.34328 -0.707282 2.78789 6.39378 -0.664813 2.7237 6.47943 -0.620258 2.63766 6.51805 -0.549503 1.74938 4.59276 -0.520222 1.67898 4.57811 -0.492006 1.61913 4.59025 -0.463392 1.57321 4.63868 -0.433162 1.53552 4.71473 -0.403498 1.4834 4.75225 -0.372951 1.43834 4.81771 -0.305871 1.6332 5.72783 -0.274083 1.53557 5.65994 -0.291527 1.22752 4.74774 -0.262535 1.16896 4.76014 -0.155651 1.34955 5.87311 -0.102099 1.31563 6.10158 -0.0706082 1.22042 6.03563 -1.43141 1.44191 -1.12624 -1.45871 1.49559 -1.13376 -1.48613 1.55057 -1.13992 -1.51753 1.6106 -1.15247 -1.54496 1.66723 -1.15572 -1.57227 1.72422 -1.15741 -1.60376 1.78731 -1.1652 -1.63179 1.84483 -1.16346 -1.67158 1.92031 -1.18268 -1.70692 1.9905 -1.1922 -1.74257 2.06309 -1.19987 -1.78305 2.14089 -1.21217 -1.8226 2.22043 -1.22225 -1.86644 2.30742 -1.23688 -1.9155 2.40175 -1.25546 -1.96011 2.49077 -1.26443 -2.00918 2.58839 -1.27727 -2.06221 2.6928 -1.2932 -2.1194 2.80506 -1.31193 -2.17677 2.92008 -1.32726 -2.24336 3.04907 -1.3503 -2.30573 3.1738 -1.36354 -2.37651 3.31388 -1.38385 -2.46 3.47677 -1.41585 -2.54451 3.64264 -1.44239 -2.63748 3.8254 -1.47366 -2.73982 4.02503 -1.50865 -2.84186 4.22725 -1.53655 -2.95316 4.44666 -1.56681 -3.08173 4.70049 -1.60809 -3.21082 4.95717 -1.6401 -3.35344 5.24018 -1.67592 -3.51726 5.56616 -1.72243 -3.69531 5.91913 -1.76874 -3.90062 6.32419 -1.82519 -4.12804 6.77554 -1.88541 -4.39514 7.30438 -1.96039 -4.72145 7.94703 -2.05933 -5.05896 8.62041 -2.14371 -5.49235 9.4765 -2.26623 -6.02448 10.5277 -2.41949 -6.66257 11.7913 -2.59732 -7.41683 13.2895 -2.79283 -8.66707 15.7462 -3.1902 -9.96575 18.329 -3.51982 -19.4633 37.1818 -6.0169 -19.3455 37.2054 -5.2785 -30.8299 60.1097 -8.00461 -16.5514 32.3873 -2.54559 -16.431 32.3659 -1.91593 -16.377 32.4775 -1.30027 -16.3215 32.5877 -0.683269 -16.8786 33.9562 -0.107564 -16.6064 33.6259 0.543756 -16.9057 34.4836 1.18552 -17.097 35.1253 1.8533 -16.6349 34.3937 2.48612 -16.4275 34.1936 3.12274 -16.1698 33.8826 3.74261 -16.7921 35.4689 4.53928 -16.7056 35.5341 5.21666 -16.6628 35.6981 5.91055 -16.7481 36.1481 6.65682 -16.0298 35.0776 7.82239 -15.958 35.18 8.51426 -4.48521 9.35503 3.15538 -4.44045 9.32215 3.32342 -4.43278 9.3763 3.51455 -4.39253 9.35688 3.68698 -4.35866 9.35066 3.86481 -4.27578 9.22786 4.00468 -4.29091 9.33994 4.2237 -4.19809 9.19429 4.35298 -3.80861 8.32669 4.19376 -3.6959 8.12031 4.27505 -3.59475 7.94024 4.36019 -3.58596 7.99006 4.5443 -3.50816 7.86626 4.64993 -3.67242 8.357 5.05891 -3.10779 6.98578 4.522 -2.854 6.39736 4.35096 -2.8632 6.48319 4.53763 -2.77032 6.3035 4.57366 -2.73884 6.28567 4.70342 -2.68657 6.20983 4.79724 -2.52805 5.84525 4.6994 -2.27431 5.20807 4.39968 -2.4392 5.73114 4.89432 -2.29481 5.38943 4.78179 -2.25782 5.35073 4.88542 -2.23333 5.34758 5.01834 -2.26811 5.52214 5.29861 -2.08575 5.05311 5.04867 -1.98062 4.80391 4.96802 -1.88485 4.57999 4.8988 -1.83767 4.50145 4.95527 -1.82948 4.54945 5.13131 -1.78079 4.46779 5.18611 -1.77551 4.52847 5.38622 -1.67777 4.2823 5.26822 -1.65036 4.27256 5.39625 -1.59191 4.15478 5.40709 -1.60367 4.28752 5.7065 -1.81647 5.17946 6.93744 -1.73986 5.01614 6.92997 -1.65066 4.80047 6.84756 -1.57483 4.63538 6.82235 -1.54262 4.64127 7.02512 -1.47117 4.48776 7.01028 -1.40894 4.36868 7.04076 -1.35089 4.26677 7.09316 -1.29528 4.17958 7.16874 -1.18846 3.8268 6.80957 -1.16087 3.87501 7.10026 -1.09855 3.73743 7.08198 -1.06398 3.76923 7.3663 -0.994061 3.58292 7.25597 -0.852509 2.85782 6.07345 -0.82463 2.92128 6.4019 -0.897126 3.93491 8.77657 -0.727408 2.72157 6.41221 -0.681098 2.64208 6.46002 -0.621854 2.34784 5.989 -0.557308 1.70367 4.58948 -0.526616 1.6415 4.5925 -0.496506 1.58194 4.60381 -0.464538 1.56891 4.74602 -0.433857 1.50504 4.74592 -0.402778 1.45614 4.79227 -0.364761 1.44706 4.98175 -0.234725 2.01901 7.30047 -0.313217 1.25865 4.76164 -0.284899 1.19094 4.73577 -0.250145 1.14986 4.82551 -0.119715 1.37033 6.17359 -0.0831102 1.27747 6.12801 -1.48657 1.42293 -1.17211 -1.48963 1.44619 -1.12215 -1.51882 1.49962 -1.12865 -1.54403 1.54963 -1.12594 -1.58141 1.61409 -1.14542 -1.61048 1.66952 -1.14745 -1.64373 1.73104 -1.15568 -1.67279 1.78816 -1.15459 -1.71437 1.86202 -1.17445 -1.74841 1.92554 -1.17711 -1.78987 2.00141 -1.19249 -1.8281 2.07267 -1.19844 -1.87066 2.15127 -1.20942 -1.91302 2.23045 -1.21788 -1.96463 2.32188 -1.23725 -2.01105 2.40921 -1.24715 -2.06291 2.50489 -1.26099 -2.1143 2.60034 -1.27142 -2.17108 2.70426 -1.28521 -2.24058 2.82928 -1.31382 -2.30143 2.94297 -1.32633 -2.36735 3.06446 -1.34074 -2.43758 3.19502 -1.35697 -2.53122 3.36226 -1.3964 -2.61593 3.51732 -1.41905 -2.70047 3.67459 -1.43635 -2.80818 3.86929 -1.47353 -2.91583 4.06751 -1.5039 -3.03396 4.2836 -1.53692 -3.16106 4.51614 -1.57113 -3.29227 4.75997 -1.60172 -3.43804 5.02981 -1.63649 -3.58852 5.31016 -1.66557 -3.78246 5.66472 -1.72072 -3.97988 6.03085 -1.7666 -4.21583 6.46402 -1.82825 -4.47989 6.95112 -1.89526 -4.79175 7.52409 -1.97758 -5.15546 8.19275 -2.07365 -5.55152 8.92569 -2.16569 -6.03823 9.8239 -2.2849 -6.63798 10.9304 -2.43504 -7.38071 12.2992 -2.61936 -8.38368 14.1452 -2.88261 -9.98269 17.068 -3.35198 -11.4106 19.7277 -3.63783 -19.5408 34.904 -5.14064 -17.6641 32.1293 -2.71794 -17.7354 32.4756 -2.1184 -17.5458 32.3383 -1.47122 -17.4325 32.3395 -0.840897 -17.7831 33.2247 -0.247988 -17.8611 33.5977 0.386841 -17.8262 33.7573 1.03399 -17.0077 32.3952 1.65624 -17.1984 32.9879 2.29959 -17.2253 33.2678 2.94689 -17.1883 33.4229 3.59451 -16.8682 33.0149 4.19373 -16.6791 32.8652 4.80684 -17.8231 35.6666 6.49658 -16.3047 32.7996 6.68354 -16.2655 32.9569 7.34447 -16.2496 33.165 8.02456 -15.8152 32.4951 8.51188 -15.7434 32.5857 9.16693 -4.66674 9.1866 3.45209 -4.6053 9.12436 3.61062 -4.66887 9.33187 3.85105 -4.56921 9.18562 3.98448 -4.47693 9.05452 4.11874 -4.45559 9.07771 4.30639 -4.44296 9.12314 4.50529 -4.38638 9.07098 4.66756 -3.7236 7.6384 4.2293 -3.68486 7.61501 4.37426 -3.76828 7.87439 4.65545 -3.81088 8.04385 4.90528 -3.75116 7.9764 5.04075 -2.99347 6.2408 4.26946 -3.03839 6.40992 4.50011 -3.09112 6.59833 4.75207 -2.71268 5.73431 4.36992 -2.70264 5.76914 4.52083 -2.69132 5.79951 4.67399 -2.43998 5.22373 4.41476 -2.48649 5.40179 4.66509 -2.47972 5.44322 4.82638 -2.39126 5.27633 4.83312 -2.33546 5.19261 4.89988 -2.29648 5.15282 5.00094 -2.06709 4.58835 4.6603 -2.04452 4.58769 4.78222 -1.94114 4.3617 4.70406 -1.90536 4.32329 4.79024 -1.90736 4.39444 4.9837 -1.87222 4.3585 5.0775 -1.81442 4.25933 5.10793 -1.72175 4.04552 5.01517 -1.76936 4.27158 5.39187 -1.6791 4.06488 5.30078 -1.70694 4.2382 5.64279 -1.72336 4.38376 5.96905 -1.77298 4.65614 6.4701 -1.71768 4.57528 6.54622 -1.72879 4.73693 6.94369 -1.66218 4.62025 6.9805 -1.6173 4.58897 7.13583 -1.36413 3.72968 6.07994 -1.42159 4.09577 6.80915 -1.36551 4.00955 6.87368 -1.24715 3.64574 6.48808 -1.20615 3.61984 6.63848 -1.14317 3.49107 6.61631 -1.15298 3.73995 7.27069 -1.09791 3.66448 7.36288 -0.916925 2.83106 5.98089 -0.862813 2.7036 5.91478 -0.848565 2.86036 6.44077 -0.7984 2.77832 6.48188 -0.743427 2.64409 6.40233 -0.69574 2.57771 6.47627 -0.595887 1.73095 4.61004 -0.563939 1.66819 4.61382 -0.530858 1.60342 4.60656 -0.498849 1.57841 4.71117 -0.466427 1.52814 4.7493 -0.433605 1.46864 4.75762 -0.399907 1.42224 4.81287 -0.335979 1.61133 5.70397 -0.338814 1.27567 4.72733 -0.306821 1.21805 4.74063 -0.27515 1.16111 4.75257 -0.168754 1.3375 5.84587 -0.11468 1.29654 6.0246 -0.0723106 1.21904 6.03607 -1.54857 1.44938 -1.11745 -1.57964 1.50252 -1.12303 -1.60553 1.55154 -1.11922 -1.63662 1.6063 -1.12207 -1.67574 1.67093 -1.13869 -1.71063 1.73126 -1.1456 -1.7509 1.79847 -1.1585 -1.79003 1.86641 -1.16929 -1.82593 1.92972 -1.17073 -1.86596 1.99931 -1.17751 -1.90583 2.06941 -1.18204 -1.95522 2.15257 -1.19838 -1.9992 2.23063 -1.20523 -2.05361 2.32173 -1.22288 -2.10803 2.41448 -1.23762 -2.15705 2.50211 -1.24296 -2.22179 2.60988 -1.26413 -2.27597 2.70671 -1.26962 -2.34995 2.8301 -1.29568 -2.41871 2.94947 -1.31186 -2.49786 3.08369 -1.33525 -2.58199 3.22599 -1.35938 -2.67033 3.37763 -1.38406 -2.76478 3.5383 -1.40858 -2.86868 3.71562 -1.43781 -2.97208 3.89444 -1.46042 -3.09131 4.0981 -1.49126 -3.21451 4.31183 -1.51946 -3.35839 4.55723 -1.55779 -3.50205 4.80661 -1.58727 -3.66095 5.08096 -1.62003 -3.83521 5.38157 -1.65479 -4.03841 5.73134 -1.70169 -4.26657 6.12522 -1.75433 -4.52963 6.57776 -1.81689 -4.82853 7.09048 -1.88596 -5.18144 7.69779 -1.97154 -5.57397 8.37594 -2.05835 -6.052 9.19829 -2.16859 -6.62463 10.1842 -2.29946 -7.28165 11.3193 -2.43585 -8.17348 12.8547 -2.64216 -9.40502 14.9706 -2.94195 -11.1824 18.0184 -3.38626 -19.605 32.6355 -4.98575 -19.5708 32.7924 -4.341 -19.7786 33.5841 -3.10803 -18.5493 31.876 -1.61933 -18.3465 31.7273 -0.977441 -18.5017 32.2125 -0.372903 -18.6944 32.7682 0.246469 -18.4249 32.7189 1.52609 -18.3839 32.8621 2.16767 -18.0889 32.7609 3.43521 -17.6342 32.1378 4.01172 -18.1219 33.2685 4.76177 -18.5268 34.4991 6.23851 -15.9455 29.8059 6.10377 -15.8897 29.9093 6.70305 -4.9493 8.97906 3.04246 -4.9343 9.01288 3.22304 -4.86846 8.94809 3.37924 -4.89268 9.06168 3.58595 -17.6609 34.8118 11.764 -4.95921 9.33165 4.02979 -4.71555 8.90419 4.06419 -3.91545 7.32444 3.65418 -3.90936 7.37045 3.81808 -3.96313 7.54012 4.03663 -3.97671 7.63023 4.22893 -3.9052 7.54067 4.34507 -3.9877 7.78163 4.6174 -3.94756 7.76143 4.771 -3.75962 7.41841 4.75717 -3.46023 6.82391 4.59345 -3.43709 6.83438 4.74807 -3.07938 6.09445 4.46206 -2.85433 5.6427 4.32047 -2.90805 5.82022 4.5616 -2.97142 6.02423 4.83057 -2.65051 5.33613 4.4989 -2.5809 5.22704 4.54847 -2.57905 5.27838 4.71271 -2.53389 5.22872 4.80444 -2.54908 5.32608 5.01332 -2.48599 5.23476 5.07529 -2.29567 4.82065 4.86282 -2.15485 4.52133 4.7309 -2.07912 4.38448 4.73047 -1.98814 4.20557 4.68639 -1.98758 4.26571 4.86426 -1.95225 4.2326 4.95627 -1.90035 4.15702 5.00617 -1.81369 3.98047 4.94821 -1.81999 4.06947 5.17209 -1.78136 4.02925 5.26135 -1.69879 3.86074 5.20146 -1.72405 4.01416 5.52044 -1.90248 4.65553 6.46487 -1.92168 4.82399 6.85925 -1.46991 3.46129 5.24163 -1.80357 4.67207 7.03956 -1.7344 4.56164 7.0832 -1.67416 4.48486 7.17304 -1.5194 4.05685 6.73334 -1.45287 3.94176 6.74749 -1.33957 3.63912 6.45514 -1.27519 3.51918 6.44341 -1.22166 3.44356 6.50635 -1.15514 3.31027 6.46315 -1.08161 3.13144 6.32886 -0.995696 2.87934 6.03927 -0.92727 2.69778 5.86744 -0.902347 2.75939 6.18543 -0.863982 2.76636 6.40631 -0.810961 2.67876 6.42728 -0.758573 2.59364 6.45587 -0.70974 2.5424 6.56597 -0.602004 1.68764 4.61627 -0.568163 1.64123 4.6561 -0.550571 2.23797 6.51422 -0.499554 2.06602 6.27779 -0.465672 1.49494 4.77072 -0.430718 1.44084 4.7975 -0.394629 1.39792 4.86156 -0.267273 2.01486 7.35482 -0.331434 1.24244 4.73562 -0.298995 1.18072 4.72864 -0.260105 1.14462 4.82733 -0.147517 1.31222 5.92154 -0.0884445 1.27324 6.11908 -1.60896 1.45027 -1.11192 -1.6366 1.49775 -1.10835 -1.67354 1.55567 -1.1194 -1.71034 1.614 -1.1286 -1.74725 1.67368 -1.13624 -1.78401 1.73377 -1.14204 -1.82088 1.79524 -1.14619 -1.86261 1.86178 -1.15553 -1.90039 1.92486 -1.15587 -1.94205 1.99329 -1.16123 -1.99823 2.07947 -1.18524 -2.04098 2.15067 -1.18611 -2.09297 2.23411 -1.198 -2.14898 2.32415 -1.21375 -2.20596 2.41564 -1.22647 -2.26392 2.50856 -1.23615 -2.3312 2.61513 -1.255 -2.39844 2.72352 -1.27026 -2.46564 2.83371 -1.28191 -2.54399 2.95747 -1.30095 -2.62661 3.09038 -1.32142 -2.72465 3.24441 -1.35342 -2.82369 3.40144 -1.37986 -2.92687 3.56804 -1.4059 -3.03683 3.7427 -1.43058 -3.15615 3.93428 -1.45879 -3.28043 4.13562 -1.48462 -3.42138 4.36199 -1.51682 -3.56791 4.59734 -1.54466 -3.72352 4.85046 -1.57225 -3.90622 5.14498 -1.61108 -4.09948 5.45657 -1.64618 -4.32919 5.82647 -1.69607 -4.57883 6.2303 -1.74606 -4.89279 6.7326 -1.82203 -5.22737 7.27112 -1.89129 -5.59834 7.87083 -1.96147 -6.07443 8.6357 -2.0674 -6.61216 9.50441 -2.17667 -7.23419 10.5114 -2.29382 -8.07251 11.8589 -2.47166 -9.11392 13.5384 -2.68562 -10.9891 16.5308 -3.16872 -12.7415 19.3691 -3.4878 -19.7469 30.6829 -4.8668 -19.6973 30.8044 -4.24409 -19.8909 31.5176 -3.06178 -19.8601 31.6713 -2.43324 -19.6409 31.5185 -1.77518 -19.5826 31.6278 -1.14574 -20.0673 32.6338 -0.55967 -20.0729 32.8548 0.0868309 -15.0014 24.737 1.30508 -14.9473 24.8058 1.79525 -19.2183 32.264 2.66229 -14.944 25.1282 2.79346 -14.8245 25.088 3.28291 -14.8545 25.3085 3.79915 -14.7852 25.3574 4.30162 -14.9408 25.8037 4.86625 -14.9233 25.9488 5.39783 -14.7273 25.7759 5.87567 -14.9948 26.4377 6.52331 -14.7888 26.2488 7.00311 -16.0456 28.7353 8.14575 -15.7644 28.4221 8.63528 -5.27138 9.14926 3.60959 -5.14092 8.97105 3.73448 -4.8074 8.53454 4.10939 -4.12597 7.28474 3.79036 -4.14988 7.3876 3.98045 -4.11157 7.37017 4.1243 -4.92799 9.04398 5.04282 -4.26088 7.78831 4.63151 -4.36138 8.05553 4.93039 -3.9477 7.28534 4.70009 -3.89956 7.24804 4.83773 -3.63165 6.76016 4.71899 -3.45473 6.45144 4.68611 -3.37756 6.34997 4.76845 -3.3416 6.33316 4.90288 -3.27491 6.25234 4.99593 -2.77589 5.23071 4.43944 -2.7246 5.17102 4.52105 -2.7099 5.19347 4.66239 -2.63999 5.09319 4.71354 -2.63287 5.13233 4.87347 -2.53749 4.97194 4.87288 -2.34637 4.58662 4.67666 -2.24993 4.41564 4.6491 -2.20868 4.37355 4.73128 -2.12714 4.23293 4.72099 -2.13842 4.32002 4.92635 -2.23742 4.62813 5.35978 -2.08623 4.31319 5.17563 -1.93173 3.98407 4.95969 -1.89451 3.94955 5.04776 -1.87709 3.97087 5.20067 -1.78077 3.7797 5.11137 -1.82607 3.97759 5.4812 -1.78748 3.94557 5.58475 -2.03677 4.7526 6.76913 -1.58083 3.50425 5.29755 -1.52625 3.42092 5.32207 -1.83661 4.48284 6.96727 -1.76089 4.35987 6.98314 -1.6344 4.06772 6.74078 -1.58699 4.03487 6.88046 -1.43945 3.6483 6.4566 -1.3701 3.52482 6.43708 -1.2982 3.38756 6.38861 -1.23738 3.29062 6.40587 -1.16213 3.13321 6.30692 -1.03007 2.70365 5.67406 -0.983111 2.64024 5.7226 -0.952742 2.66325 5.9493 -0.929098 2.74249 6.31325 -0.881202 2.70174 6.43452 -0.825575 2.61554 6.45406 -0.771073 2.53971 6.49961 -0.641572 1.70465 4.61887 -0.606698 1.65259 4.64037 -0.606136 2.27626 6.5423 -0.54995 2.11076 6.32571 -0.498988 1.52289 4.79331 -0.462765 1.46115 4.79181 -0.426145 1.40833 4.81766 -0.386703 1.37617 4.91953 -0.298207 1.66319 6.24841 -0.324069 1.20205 4.71449 -0.288269 1.15007 4.73528 -0.180407 1.32985 5.83808 -0.121968 1.2929 6.02586 -0.0759426 1.2162 6.0267 -1.63608 1.39758 -1.10046 -1.66982 1.44913 -1.10548 -1.70754 1.50572 -1.11689 -1.74104 1.558 -1.1187 -1.77564 1.61134 -1.11912 -1.80915 1.66527 -1.11801 -1.85785 1.73428 -1.13748 -1.9016 1.80017 -1.14756 -1.93994 1.86093 -1.14825 -1.98861 1.93339 -1.16129 -2.03331 2.00244 -1.16513 -2.07762 2.07101 -1.16663 -2.13143 2.15272 -1.17963 -2.19119 2.24062 -1.19616 -2.2559 2.33501 -1.21605 -2.31049 2.42039 -1.22048 -2.37518 2.51818 -1.23414 -2.44082 2.61749 -1.24439 -2.52722 2.74319 -1.27487 -2.59276 2.84612 -1.27792 -2.68504 2.98152 -1.30522 -2.77719 3.11902 -1.32767 -2.87451 3.26566 -1.35055 -2.98326 3.42838 -1.37848 -3.09758 3.59841 -1.40508 -3.21718 3.77896 -1.43037 -3.33749 3.96176 -1.44902 -3.47835 4.17492 -1.47916 -3.63128 4.40492 -1.50995 -3.79023 4.64589 -1.53639 -3.96943 4.91816 -1.57015 -4.17209 5.22347 -1.6091 -4.40111 5.56909 -1.65529 -4.6523 5.94895 -1.70243 -4.94746 6.39401 -1.76266 -5.27593 6.89027 -1.82509 -5.64782 7.4534 -1.89322 -6.11274 8.15466 -1.98983 -6.62242 8.92587 -2.08081 -7.22408 9.83842 -2.18606 -8.03009 11.0545 -2.34711 -9.02136 12.5536 -2.53814 -10.4376 14.6854 -2.83464 -12.6915 18.0654 -3.34717 -19.4831 28.3304 -4.64757 -19.8968 29.1288 -4.18486 -28.6163 42.6351 -4.82191 -28.5297 42.7795 -3.94493 -28.425 42.8944 -3.06549 -28.4322 43.1803 -2.20011 -16.229 24.6003 -0.293786 -16.0861 24.5361 0.208704 -16.0318 24.6071 0.704407 -15.9817 24.6878 1.20081 -15.9177 24.7438 1.69837 -15.7897 24.7002 2.19176 -15.7359 24.775 2.69047 -15.6627 24.8176 3.18841 -15.6519 24.9628 3.69866 -15.6711 25.161 4.22098 -15.4074 24.8923 4.68264 -15.3449 24.9561 5.18944 -15.4396 25.2831 5.74934 -15.0691 24.8308 6.16104 -15.6251 25.9453 6.9141 -15.607 26.0942 7.47365 -16.7334 28.4166 9.20466 -16.1259 27.5626 9.51912 -16.0698 27.6651 10.1188 -16.1004 27.9243 10.7818 -4.31481 7.20596 3.91493 -5.22641 8.92739 4.81704 -4.43034 7.53208 4.36373 -4.36093 7.46178 4.48905 -4.3759 7.55083 4.6931 -4.20567 7.29167 4.71973 -4.17196 7.28845 4.87675 -4.20951 7.42432 5.1156 -3.9243 6.93423 4.99093 -3.58006 6.32439 4.7706 -3.52034 6.26333 4.87605 -3.52817 6.33878 5.07185 -3.41984 6.18084 5.11323 -3.35021 6.09909 5.20339 -2.94202 5.32093 4.77403 -2.80644 5.09571 4.73205 -2.7995 5.13597 4.89256 -3.03271 5.68856 5.47947 -2.41031 4.46329 4.70568 -2.25282 4.16942 4.55988 -2.19 4.08144 4.59265 -2.2184 4.19868 4.82197 -2.41479 4.70906 5.45525 -2.29476 4.49679 5.37779 -2.17302 4.27431 5.27938 -2.02338 3.97648 5.08839 -2.00865 4.0051 5.2493 -1.89353 3.78402 5.12506 -1.93015 3.94521 5.4495 -1.85751 3.83021 5.44663 -1.79883 3.75115 5.48684 -1.66982 3.47907 5.26731 -1.64371 3.48373 5.41058 -2.83088 6.96361 10.4794 -1.86646 4.30967 6.90777 -1.80042 4.22809 6.97771 -1.8833 4.61272 7.77607 -1.5974 3.8374 6.7515 -1.6345 4.09239 7.37169 -1.39412 3.40785 6.40854 -1.33352 3.3269 6.45253 -1.25602 3.17923 6.37249 -1.13629 2.85539 5.94486 -1.03999 2.59834 5.61388 -1.08857 2.9799 6.57433 -1.09305 3.21357 7.28582 -0.955421 2.7396 6.47776 -0.909799 2.73724 6.69054 -0.832453 2.53293 6.43386 -0.683831 1.725 4.63069 -0.645039 1.66893 4.64334 -0.662721 2.29813 6.53294 -0.601841 2.12991 6.30778 -0.546957 2.03828 6.28687 -0.495824 1.48821 4.81488 -0.457941 1.42772 4.81236 -0.419418 1.38128 4.85657 -0.285816 2.12839 7.86362 -0.215389 2.043 7.9454 -0.310665 1.18224 4.77018 -0.257042 1.18808 5.0535 -0.151206 1.3216 5.99144 -0.10824 1.23518 5.93385 -1.70061 1.3991 -1.10217 -1.72609 1.44146 -1.09041 -1.77052 1.50132 -1.10843 -1.80688 1.55311 -1.10919 -1.85126 1.61478 -1.12362 -1.8876 1.66831 -1.12108 -1.92787 1.72699 -1.12444 -1.97326 1.79169 -1.13321 -2.02469 1.86228 -1.14686 -2.06997 1.92895 -1.15135 -2.12128 2.00157 -1.16044 -2.17264 2.07572 -1.16719 -2.22997 2.15596 -1.17796 -2.29229 2.2426 -1.19247 -2.35461 2.33091 -1.20397 -2.41693 2.42088 -1.21255 -2.49545 2.52898 -1.23595 -2.56898 2.634 -1.24977 -2.65467 2.75228 -1.27123 -2.72882 2.85984 -1.27715 -2.82456 2.99401 -1.30125 -2.93155 3.14311 -1.33106 -3.0289 3.28117 -1.34461 -3.15316 3.45455 -1.37862 -3.27281 3.62311 -1.40089 -3.40375 3.80817 -1.42635 -3.54568 4.00898 -1.45394 -3.69971 4.22652 -1.48265 -3.85957 4.45398 -1.50731 -4.04189 4.71312 -1.53982 -4.22964 4.9817 -1.56593 -4.46363 5.31237 -1.61239 -4.72058 5.67594 -1.66025 -5.00553 6.08028 -1.71112 -5.34238 6.55715 -1.77595 -5.70279 7.06946 -1.83427 -6.15449 7.70794 -1.92005 -6.62842 8.38487 -1.99148 -7.21148 9.21482 -2.08646 -7.96139 10.277 -2.22052 -8.92899 11.6476 -2.40094 -10.2127 13.4626 -2.64512 -12.8234 17.1123 -3.28047 -20.1691 27.6657 -4.14928 -20.0597 27.6896 -3.55165 -28.85 40.5161 -3.95609 -18.9479 26.6355 -1.66779 -17.5652 24.8164 -0.958873 -17.5647 24.9746 -0.450053 -17.4971 25.0343 0.0664287 -17.5154 25.2194 0.580337 -17.437 25.2645 1.09933 -17.3758 25.3358 1.6185 -17.4925 25.6727 2.1508 -16.5297 24.3905 2.59099 -16.5179 24.5291 3.09824 -16.4335 24.5603 3.59914 -16.2086 24.3761 4.0736 -16.3669 24.9439 5.15609 -16.1181 24.7204 5.62046 -15.9775 24.6647 6.11113 -15.9161 24.7348 6.62923 -15.8278 24.7641 7.14139 -16.7392 26.3997 8.09052 -16.4833 26.17 8.56718 -17.7248 28.3811 9.79741 -16.7133 26.9237 9.90246 -16.7491 27.1774 10.5554 -16.8382 27.5272 11.2587 -4.63882 7.40829 4.32509 -4.66408 7.50791 4.53164 -4.8439 7.88303 4.88308 -4.61847 7.54791 4.87773 -4.44316 7.30008 4.90728 -4.35021 7.19381 5.00844 -4.47455 7.48137 5.34264 -3.85005 6.4064 4.84517 -3.72867 6.23975 4.88466 -3.68559 6.21652 5.01508 -3.59276 6.10107 5.08224 -3.53167 6.04373 5.18881 -3.01156 5.10591 4.63618 -3.02969 5.19417 4.83006 -2.92301 5.03805 4.83661 -2.88988 5.02598 4.95672 -3.04076 5.44568 5.59495 -3.02464 5.4785 5.77445 -2.43537 4.31897 4.83533 -2.72704 4.98972 5.61083 -2.69374 4.98421 5.75227 -2.79283 5.26612 6.19625 -2.78096 5.31631 6.41397 -2.2314 4.16603 5.31353 -2.17809 4.10991 5.38462 -2.36117 4.6017 6.09984 -2.52853 5.075 6.83379 -1.94791 3.77102 5.38583 -1.91697 3.76609 5.51765 -1.82796 3.6182 5.46332 -1.71721 3.40951 5.3179 -1.67495 3.37501 5.40509 -1.62981 3.33213 5.48387 -1.6064 3.35341 5.65988 -1.54485 3.26885 5.68025 -1.85424 4.27386 7.45531 -1.45084 3.18228 5.84976 -1.70426 4.09247 7.58214 -1.42771 3.33973 6.46477 -1.35535 3.22674 6.44666 -1.27404 3.07868 6.35512 -1.16092 2.80343 6.00243 -1.08715 2.66006 5.89188 -1.1123 2.93504 6.66003 -1.05274 2.86866 6.72989 -1.02395 2.95956 7.16422 -0.913933 2.63145 6.62624 -0.725649 1.73835 4.63356 -0.686555 1.68047 4.63714 -0.654149 1.6921 4.82678 -0.666939 2.28675 6.68579 -0.601995 2.12329 6.46861 -0.542794 1.99419 6.3328 -0.49146 1.45173 4.82629 -0.450705 1.39783 4.84201 -0.409081 1.36412 4.93379 -0.328097 1.61398 6.12792 -0.338173 1.19285 4.71741 -0.228938 1.43901 6.03228 -0.185317 1.34202 5.928 -0.126602 1.29291 6.04666 -0.0807799 1.20698 5.98803 -1.72825 1.34878 -1.09892 -1.7557 1.3906 -1.08741 -1.79274 1.43972 -1.09009 -1.83904 1.49937 -1.1069 -1.8763 1.55114 -1.10666 -1.9132 1.60233 -1.10458 -1.95549 1.66036 -1.10868 -2.0084 1.7269 -1.1249 -2.05563 1.79143 -1.13226 -2.09844 1.85061 -1.1302 -2.15156 1.92155 -1.14021 -2.20545 1.99284 -1.14757 -2.26363 2.07158 -1.15948 -2.32354 2.15053 -1.16832 -2.38842 2.2359 -1.18082 -2.45353 2.3239 -1.19049 -2.52431 2.4173 -1.20282 -2.6056 2.52515 -1.22411 -2.68851 2.63352 -1.24096 -2.77672 2.75069 -1.25973 -2.86556 2.86864 -1.27399 -2.96571 3.00137 -1.29466 -3.07808 3.14885 -1.32083 -3.19001 3.29765 -1.34116 -3.30899 3.45537 -1.36072 -3.44435 3.63564 -1.38878 -3.5864 3.82426 -1.41422 -3.74059 4.0295 -1.44128 -3.9016 4.24434 -1.46454 -4.07845 4.48175 -1.49183 -4.27463 4.74427 -1.52191 -4.50594 5.05121 -1.56434 -4.75012 5.37701 -1.60184 -5.03549 5.75644 -1.65076 -5.35611 6.18493 -1.70473 -5.71863 6.6693 -1.76348 -6.11763 7.20283 -1.82033 -6.60548 7.85489 -1.89878 -7.15281 8.58887 -1.97731 -7.83769 9.5036 -2.08405 -8.75647 10.7252 -2.24586 -9.84654 12.1811 -2.4207 -11.3976 14.2456 -2.6928 -13.8598 17.5089 -3.16486 -20.2892 26.1272 -4.08672 -20.2599 26.2537 -3.52666 -23.9478 31.2979 -3.72178 -28.7858 37.9347 -3.90794 -20.0212 26.4371 -1.82312 -18.9746 25.1946 -1.14477 -18.9659 25.3411 -0.615837 -18.5262 24.9006 -0.057879 -19.1128 25.8643 0.445657 -19.0736 25.9741 0.989033 -16.9861 23.2336 1.48012 -19.2731 26.5847 2.09895 -18.9661 26.3212 2.63545 -17.5069 24.5775 3.54562 -17.4971 24.7214 4.07094 -16.5428 23.5011 4.40424 -16.4635 23.5406 4.89505 -15.9396 22.9277 5.26612 -15.9422 23.0834 5.7717 -15.8785 23.1421 6.26261 -15.8355 23.235 6.76522 -15.8623 23.4342 7.30196 -17.5127 26.099 8.56861 -18.05 27.1019 9.43008 -17.7877 26.8891 9.93029 -17.0904 26.0007 10.1841 -17.349 26.5939 10.962 -18.0165 27.8384 12.0293 -17.9396 27.9248 12.6682 -4.95519 7.46036 4.37154 -4.86511 7.37142 4.48873 -4.35875 6.60046 4.2555 -4.2165 6.41854 4.30285 -4.24774 6.52261 4.50246 -4.27218 6.61475 4.70231 -4.20211 6.55222 4.81369 -4.14847 6.51755 4.94221 -4.36136 6.94014 5.36948 -3.9915 6.35918 5.14123 -3.85031 6.1713 5.16112 -3.71994 5.99738 5.18524 -3.28949 5.28566 4.79627 -3.23632 5.24017 4.89345 -3.02163 4.90053 4.75249 -3.02381 4.95555 4.92412 -3.29706 5.51899 5.54024 -3.15815 5.31815 5.51049 -3.11496 5.29751 5.63806 -3.10999 5.34937 5.83659 -3.07257 5.3432 5.98506 -2.88023 5.02891 5.82586 -2.78477 4.90346 5.84667 -2.93114 5.26927 6.392 -2.81229 5.09906 6.37173 -2.2206 3.92563 5.19546 -2.57065 4.73862 6.28578 -2.6103 4.90306 6.6497 -2.58514 4.93236 6.86231 -2.03047 3.76531 5.53296 -1.91523 3.56764 5.41001 -1.8202 3.41392 5.33558 -1.74359 3.30189 5.3119 -1.73574 3.35474 5.52695 -1.66832 3.26328 5.53241 -1.63231 3.25119 5.65909 -1.57632 3.19063 5.71064 -1.54247 3.18848 5.86248 -1.49535 3.15387 5.96361 -1.43031 3.06896 5.97815 -1.72829 4.11033 8.06691 -1.34897 3.04982 6.29033 -1.2319 2.79065 5.96486 -1.20899 2.84618 6.2559 -1.15127 2.78754 6.32477 -1.10641 2.77743 6.50112 -1.03641 2.67124 6.46788 -0.974651 2.60062 6.51469 -0.775296 1.77686 4.70123 -0.728359 1.69387 4.64021 -0.688585 1.64805 4.67072 -0.693541 2.01088 5.84852 -0.636851 1.91173 5.77901 -0.594642 2.0377 6.3917 -0.526224 1.49557 4.90697 -0.484211 1.41582 4.83705 -0.442529 1.36807 4.87115 -0.39827 1.3369 4.97202 -0.329928 1.44898 5.65374 -0.25834 1.49383 6.13413 -0.217546 1.36588 5.89408 -0.15996 1.31562 5.99334 -0.115024 1.22656 5.90547 -1.78893 1.34256 -1.09186 -1.81201 1.37887 -1.07162 -1.85503 1.43242 -1.08123 -1.90394 1.49066 -1.0967 -1.94284 1.54122 -1.09525 -1.98065 1.59236 -1.09227 -2.0356 1.65819 -1.10952 -2.07937 1.71552 -1.11016 -2.12897 1.7777 -1.11588 -2.18484 1.84678 -1.1265 -2.23932 1.91569 -1.13451 -2.29506 1.98681 -1.14046 -2.35678 2.06405 -1.15032 -2.42421 2.14654 -1.16352 -2.48574 2.22603 -1.16784 -2.55318 2.31181 -1.1753 -2.63899 2.41622 -1.19763 -2.72451 2.52156 -1.21587 -2.80384 2.62305 -1.22456 -2.89628 2.73768 -1.24038 -3.00612 2.87282 -1.26827 -3.11652 3.00897 -1.29059 -3.22699 3.14826 -1.30785 -3.3443 3.29543 -1.32454 -3.4725 3.45697 -1.3451 -3.61995 3.64054 -1.37321 -3.77429 3.83349 -1.39851 -3.93428 4.03523 -1.42033 -4.10706 4.25268 -1.44228 -4.30401 4.50042 -1.47174 -4.52595 4.77867 -1.50664 -4.77297 5.08887 -1.54503 -5.05062 5.4367 -1.58831 -5.35301 5.81748 -1.63061 -5.71147 6.26673 -1.68625 -6.09522 6.74996 -1.73524 -6.55213 7.32651 -1.79924 -7.05898 7.96691 -1.86048 -7.72133 8.79846 -1.95947 -8.51291 9.79445 -2.07385 -9.4917 11.0247 -2.21311 -11.0616 12.981 -2.4982 -19.9629 24.1356 -3.91481 -18.7101 22.7442 -3.10595 -18.6315 22.7911 -2.59889 -18.8539 23.5069 -1.14644 -18.5002 23.2046 -0.610093 -18.5053 23.3578 -0.113411 -18.4561 23.4416 0.388847 -17.4979 22.3452 0.89955 -17.5135 22.5081 1.37931 -17.4513 22.5677 1.86067 -17.4985 22.7722 2.35115 -17.3831 22.7639 2.83176 -17.3881 22.9158 3.32718 -17.3443 23.0048 3.82044 -17.1726 22.9192 4.2919 -16.9961 22.8274 4.75813 -16.9899 22.9675 5.26404 -16.4636 22.3902 5.62687 -16.5057 22.5967 6.14553 -16.4375 22.6532 6.63587 -16.4319 22.7978 7.15395 -16.3582 22.8479 7.65192 -16.4885 23.1922 8.24655 -18.2233 25.8568 9.63867 -17.954 25.6483 10.12 -17.8375 25.6608 10.6796 -17.8259 25.8303 11.3061 -17.5845 25.6617 11.8005 -5.13286 7.22497 4.13296 -5.09387 7.21916 4.28638 -5.22667 7.47391 4.56879 -4.52424 6.45521 4.20895 -4.38633 6.29284 4.26454 -4.42714 6.40469 4.46753 -4.31389 6.27822 4.53823 -4.20633 6.15873 4.6088 -4.27609 6.32268 4.8544 -4.25387 6.34038 5.01454 -4.15714 6.23818 5.09528 -3.99335 6.02541 5.09484 -3.76583 5.7041 5.00666 -3.6684 5.59524 5.06459 -3.44948 5.27817 4.95646 -3.31413 5.09923 4.94536 -3.29451 5.11676 5.09259 -3.40337 5.36038 5.43966 -3.38755 5.39064 5.61225 -3.30101 5.29553 5.67354 -3.27705 5.3141 5.84086 -3.01947 4.90561 5.59025 -2.83024 4.61418 5.43855 -2.96664 4.93009 5.90868 -3.02136 5.10104 6.24604 -2.4439 4.05356 5.23799 -2.353 3.93259 5.23017 -2.25804 3.8014 5.20369 -2.16984 3.68333 5.18771 -2.19144 3.78619 5.44598 -2.09729 3.6542 5.41153 -2.03073 3.5762 5.44238 -1.95064 3.46986 5.43185 -1.81479 3.23586 5.2357 -1.80068 3.2697 5.41747 -1.76778 3.26692 5.55226 -1.69801 3.17775 5.55579 -1.66431 3.17576 5.69846 -1.59479 3.08582 5.69858 -1.56967 3.109 5.89181 -1.49178 2.99765 5.85472 -1.41259 2.87817 5.79707 -1.35005 2.80173 5.81492 -1.30709 2.78374 5.9454 -1.25022 2.72817 6.0047 -1.20843 2.72144 6.17065 -1.16356 2.71529 6.3458 -1.10652 2.66899 6.43948 -1.06846 2.70487 6.73424 -0.983014 2.54273 6.55974 -0.772617 1.70965 4.65269 -0.729637 1.65767 4.66482 -0.745298 2.02088 5.83192 -0.687577 1.93319 5.7911 -0.646534 2.03473 6.3178 -0.585867 1.95431 6.31356 -0.518233 1.44375 4.87049 -0.475533 1.38319 4.85683 -0.431215 1.34403 4.91911 -0.366929 1.46637 5.61968 -0.312908 1.41697 5.69188 -0.232195 1.47904 6.25959 -0.184927 1.36966 6.09627 -0.131244 1.29395 6.0775 -0.0851439 1.20192 5.96884 -1.84406 1.33002 -1.07629 -1.87893 1.37404 -1.07068 -1.92359 1.42638 -1.07908 -1.96834 1.4801 -1.08582 -2.01393 1.53402 -1.09059 -2.05938 1.58836 -1.09351 -2.10492 1.64406 -1.09479 -2.15655 1.70557 -1.10134 -2.20777 1.76662 -1.10555 -2.26526 1.83457 -1.11456 -2.3176 1.89832 -1.11458 -2.38066 1.97192 -1.12517 -2.45511 2.05839 -1.14624 -2.51918 2.13502 -1.15117 -2.58424 2.21301 -1.15345 -2.6665 2.3088 -1.17091 -2.75461 2.4111 -1.19053 -2.84264 2.5153 -1.20617 -2.93254 2.62095 -1.21768 -3.03333 2.7393 -1.23598 -3.14735 2.87206 -1.26024 -3.26217 3.00678 -1.27914 -3.37053 3.13685 -1.28759 -3.51036 3.30034 -1.31523 -3.6509 3.4661 -1.33613 -3.79814 3.64014 -1.3547 -3.96332 3.83579 -1.37939 -4.1363 4.04083 -1.40017 -4.33422 4.27483 -1.42882 -4.54479 4.52504 -1.45546 -4.78819 4.81164 -1.49033 -5.06252 5.13662 -1.53117 -5.37647 5.50611 -1.57868 -5.69656 5.88721 -1.61347 -6.07459 6.33659 -1.66028 -6.52297 6.86777 -1.72012 -6.99601 7.43318 -1.76786 -7.59266 8.14132 -1.8411 -8.33633 9.02312 -1.94004 -9.29957 10.1608 -2.07805 -10.5124 11.5956 -2.24874 -20.6523 23.6411 -3.48873 -20.5426 23.6629 -2.94204 -22.2046 25.7644 -2.70552 -20.2335 23.7483 -1.32882 -19.69 23.2482 -0.756213 -19.7368 23.4511 -0.249032 -19.294 23.0617 0.283475 -18.4233 22.1449 0.801276 -18.4369 22.3022 1.28747 -18.3944 22.39 1.77628 -18.3772 22.51 2.26872 -18.4298 22.7179 2.7714 -18.251 22.6383 3.2531 -18.2345 22.7622 3.755 -18.0586 22.6841 4.23256 -17.9026 22.6306 4.71017 -17.9061 22.7813 5.22333 -18.0285 23.0894 5.7758 -18.1537 23.4053 6.34408 -17.2867 22.4183 6.59884 -17.3019 22.5883 7.12783 -17.2917 22.7278 7.65639 -18.5051 24.5162 8.7154 -18.6074 24.8238 9.35294 -18.2842 24.5571 9.7989 -18.8529 25.5119 10.7042 -6.59393 8.72753 4.45906 -6.45254 8.59234 4.59089 -5.94576 7.9427 4.48606 -6.13639 8.27073 4.81595 -5.91599 8.01675 4.87344 -4.5782 6.15436 4.08459 -4.53102 6.13328 4.21031 -4.52353 6.1702 4.36927 -4.41374 6.05597 4.44229 -4.58629 6.36174 4.7699 -4.41875 6.16279 4.79105 -4.33958 6.09502 4.89163 -4.31749 6.11231 5.04993 -4.32025 6.17101 5.23998 -3.61272 5.1267 4.61881 -3.7473 5.38574 4.94428 -3.64922 5.28005 4.99651 -3.54662 5.16719 5.03912 -3.45315 5.06735 5.08956 -3.35231 4.95354 5.12461 -3.41575 5.11065 5.40057 -2.88412 4.27791 4.76322 -3.14366 4.76462 5.35278 -3.14796 4.82573 5.55125 -3.01368 4.6504 5.51321 -3.00914 4.70097 5.70601 -2.89043 4.55108 5.68764 -2.80981 4.46515 5.73434 -2.40959 3.79392 5.10042 -2.38074 3.79433 5.22502 -2.32074 3.73838 5.28386 -2.23939 3.6398 5.28896 -2.14355 3.51312 5.25277 -2.09073 3.46673 5.32068 -2.06443 3.47592 5.46528 -1.90269 3.20669 5.21533 -1.8327 3.12216 5.22067 -1.90749 3.35261 5.70171 -1.80692 3.20558 5.61744 -1.74417 3.13814 5.65308 -1.68701 3.0857 5.71195 -1.6285 3.03127 5.76974 -1.57329 2.9817 5.83469 -1.52882 2.96285 5.95919 -1.46474 2.89503 5.99646 -1.40868 2.84971 6.07581 -1.37213 2.86405 6.27861 -1.28556 2.72911 6.17816 -1.22591 2.67481 6.24539 -1.20929 2.77561 6.66595 -1.11383 2.60156 6.46769 -1.0127 2.38814 6.15384 -0.816679 1.71937 4.65593 -0.772678 1.66776 4.66863 -0.800018 2.03613 5.83399 -0.739559 1.95629 5.81257 -0.681166 1.88064 5.79858 -0.632623 1.90924 6.10654 -0.571055 1.83277 6.1 -0.509047 1.40221 4.86192 -0.464206 1.35314 4.8859 -0.417268 1.32254 4.97617 -0.348918 1.43464 5.65798 -0.274178 1.48527 6.15739 -0.21428 1.41857 6.17971 -0.173062 1.2954 5.92672 -0.118436 1.22377 5.90625 -1.99261 1.41834 -1.07592 -2.03396 1.46633 -1.07381 -2.08622 1.52363 -1.08471 -2.13353 1.57775 -1.08642 -2.18669 1.63671 -1.09331 -2.23969 1.69615 -1.09805 -2.29277 1.75703 -1.10086 -2.35284 1.82366 -1.10814 -2.41273 1.89085 -1.1129 -2.47859 1.96414 -1.12166 -2.54448 2.03901 -1.12781 -2.61704 2.11895 -1.13706 -2.69573 2.20617 -1.14946 -2.78642 2.30548 -1.17027 -2.87801 2.40646 -1.18708 -2.96438 2.5034 -1.19411 -3.06875 2.61846 -1.21386 -3.16789 2.72955 -1.22355 -3.29216 2.86572 -1.24946 -3.41116 2.99805 -1.26473 -3.54908 3.15006 -1.2892 -3.68772 3.3043 -1.30712 -3.84538 3.47958 -1.3326 -3.99744 3.65035 -1.34597 -4.18257 3.85516 -1.3736 -4.37446 4.06975 -1.39667 -4.59293 4.31216 -1.4261 -4.82397 4.57093 -1.45283 -5.09493 4.8733 -1.49025 -5.38704 5.19838 -1.52454 -5.70468 5.55513 -1.55811 -6.08869 5.98358 -1.60746 -6.52668 6.47126 -1.66143 -6.99657 6.99984 -1.70808 -7.5541 7.62427 -1.76553 -8.26316 8.41727 -1.85265 -9.1399 9.3953 -1.96197 -10.2621 10.6456 -2.10679 -11.7707 12.325 -2.31038 -14.3079 15.1301 -2.71799 -20.6998 22.2821 -3.44254 -21.6938 23.5142 -3.12951 -21.6233 23.5872 -2.58264 -20.6151 22.7605 -1.38907 -20.3887 22.6501 -0.854012 -20.2705 22.6598 -0.335728 -20.041 22.5408 0.184395 -20.0099 22.6485 0.691947 -20.0711 22.8621 1.20239 -20.3017 23.274 1.7257 -19.7118 22.7324 2.21512 -19.5216 22.6527 2.71287 -19.5324 22.8094 3.2282 -19.5236 22.9443 3.74668 -18.4905 21.995 4.59829 -18.5369 22.1931 5.11712 -18.4878 22.2782 5.62074 -18.4638 22.394 6.13561 -18.3587 22.4125 6.63098 -18.6751 22.9569 7.273 -18.6276 23.052 7.80654 -19.0553 23.7482 8.53801 -19.7411 24.7845 9.41853 -19.9357 25.3846 10.7562 -19.7565 25.3316 11.3047 -19.3804 25.0228 11.7433 -6.17931 7.78671 4.45389 -6.21183 7.8855 4.67524 -6.27837 8.03364 4.92685 -4.82238 6.12783 4.10661 -4.70911 6.01993 4.18576 -4.64435 5.97735 4.29827 -4.53139 5.86683 4.37022 -4.58964 5.99497 4.58646 -4.56193 6.00404 4.73386 -4.59833 6.10488 4.94435 -4.52516 6.05146 5.0554 -4.46618 6.01831 5.17978 -3.93378 5.29654 4.78774 -3.64867 4.92386 4.63132 -3.63418 4.94902 4.77587 -3.66402 5.03946 4.97907 -3.65815 5.0786 5.14556 -3.23173 4.47746 4.74734 -3.50791 4.94952 5.30136 -3.07359 4.32282 4.84644 -3.00978 4.26861 4.91417 -2.92122 4.17328 4.94154 -3.171 4.62745 5.53485 -3.04908 4.48309 5.519 -2.9661 4.40114 5.56689 -2.68637 3.98643 5.23452 -2.54939 3.80522 5.14971 -2.46748 3.71563 5.16713 -2.44344 3.72733 5.30629 -2.36183 3.63685 5.31972 -2.34047 3.65526 5.47422 -2.2706 3.58639 5.51469 -2.16557 3.44973 5.45991 -1.96482 3.12412 5.12451 -1.87149 3.00041 5.06511 -1.84285 3.00517 5.19574 -1.81549 3.01151 5.33545 -1.87039 3.19811 5.77383 -2.22562 4.0512 7.3576 -1.72318 3.03352 5.79242 -1.65264 2.95623 5.80668 -1.59062 2.89824 5.85329 -1.54426 2.87968 5.97696 -1.47682 2.80951 6.00393 -1.45131 2.85199 6.25938 -1.35657 2.7073 6.13256 -1.35284 2.82895 6.57784 -1.28513 2.76672 6.63773 -1.19916 2.64659 6.55876 -1.09601 2.45595 6.30169 -0.863197 1.72648 4.65965 -0.815988 1.6737 4.66291 -0.773008 1.63777 4.71192 -0.870115 2.41329 7.07765 -0.733615 1.90671 5.82991 -0.676248 1.85383 5.88136 -0.621191 1.85057 6.09375 -0.545282 1.43265 4.9152 -0.498195 1.36906 4.88165 -0.451679 1.32734 4.92389 -0.386668 1.45188 5.63419 -0.310164 1.53041 6.23057 -0.251885 1.44519 6.1655 -0.189366 1.37993 6.18658 -0.146244 1.26209 5.94181 -0.090217 1.19365 5.92997 -2.06186 1.40731 -1.07166 -2.10411 1.45528 -1.06856 -2.15897 1.5112 -1.07792 -2.21294 1.56878 -1.08546 -2.26869 1.6264 -1.09063 -2.31757 1.68122 -1.08713 -2.37324 1.74074 -1.08831 -2.44087 1.81077 -1.10052 -2.5083 1.88142 -1.11002 -2.57672 1.95346 -1.11667 -2.65109 2.03168 -1.12694 -2.72619 2.11041 -1.13389 -2.81332 2.20113 -1.14974 -2.90137 2.29344 -1.16187 -3.00232 2.39782 -1.18152 -3.09219 2.49338 -1.18592 -3.20684 2.61178 -1.20772 -3.32232 2.73205 -1.22453 -3.43765 2.85444 -1.23638 -3.56687 2.99028 -1.25292 -3.71572 3.14474 -1.27784 -3.86549 3.30245 -1.29614 -4.02294 3.46822 -1.31198 -4.19307 3.64839 -1.32941 -4.40388 3.86752 -1.36371 -4.60917 4.08353 -1.38415 -4.84124 4.32843 -1.41066 -5.10758 4.60748 -1.44438 -5.38728 4.90328 -1.47257 -5.70931 5.24183 -1.50756 -6.07149 5.62426 -1.5465 -6.49566 6.07126 -1.59519 -6.95431 6.55621 -1.63766 -7.49442 7.12814 -1.69031 -8.13825 7.80758 -1.75437 -8.96732 8.68027 -1.85095 -10.0431 9.81068 -1.98592 -11.4089 11.2441 -2.15272 -21.8174 22.2632 -3.12044 -21.7717 22.359 -2.59125 -24.3208 25.1631 -2.44208 -22.8695 23.7998 -1.67982 -21.3495 22.3428 -0.979863 -20.6565 21.7473 -0.412764 -20.6497 21.8785 0.0900717 -20.5679 21.9293 0.597228 -20.5687 22.0689 1.10388 -20.6847 22.3358 1.61727 -20.9001 22.7147 2.14597 -21.4351 23.4506 2.71581 -20.2191 22.2462 3.13221 -19.7701 21.8853 3.59163 -19.5562 21.7852 4.06969 -19.6796 22.0652 4.60463 -19.6179 22.1376 5.11294 -19.3296 21.9506 5.56952 -19.2173 21.9645 6.06447 -19.4578 22.3898 6.66472 -19.1792 22.2123 7.11764 -19.3065 22.512 7.70639 -20.1237 23.6364 8.57626 -20.1874 23.8745 9.19268 -20.1427 23.9864 9.77516 -21.046 25.2511 10.8164 -20.9937 25.3665 11.442 -20.9626 25.5104 12.0884 -21.0159 25.7615 12.7952 -6.72143 8.07359 4.81289 -20.7238 25.7773 14.0074 -6.90558 8.4265 5.37155 -6.73746 8.27594 5.48348 -4.88934 5.95444 4.32859 -4.75538 5.8269 4.38966 -4.72453 5.83231 4.53087 -4.71999 5.87181 4.69563 -4.63709 5.81003 4.7953 -4.67984 5.91462 5.01117 -3.62337 4.53166 4.14404 -3.55373 4.47481 4.21234 -4.0709 5.22964 4.91791 -4.03395 5.22494 5.04872 -3.37417 4.34459 4.44413 -3.34925 4.35018 4.56292 -3.25417 4.25496 4.59317 -3.23149 4.2642 4.71705 -3.14034 4.17358 4.74882 -3.13101 4.20564 4.89733 -3.16289 4.29808 5.11257 -3.04805 4.17312 5.10757 -3.21731 4.4832 5.56861 -3.11243 4.3726 5.58393 -2.87733 4.05622 5.35839 -2.78131 3.95504 5.36894 -2.68578 3.85409 5.3761 -2.60991 3.78147 5.41665 -2.51975 3.68679 5.42495 -2.50078 3.71173 5.58843 -2.38803 3.57606 5.53934 -2.08625 3.1017 5.00448 -2.13288 3.24067 5.32492 -1.99874 3.0533 5.17325 -1.91076 2.94762 5.13619 -1.86034 2.91063 5.20164 -1.79048 2.8369 5.20856 -1.98905 3.30593 6.13154 -2.27566 3.98582 7.47714 -2.07162 3.65898 7.0914 -1.66999 2.87773 5.83403 -1.60314 2.81575 5.8708 -1.54822 2.78029 5.95849 -1.50054 2.76467 6.08973 -1.47997 2.82187 6.38148 -1.44595 2.85549 6.63974 -1.39314 2.84771 6.81785 -1.27941 2.66068 6.58581 -1.20775 2.59679 6.63293 -0.908778 1.7287 4.6539 -0.859816 1.67746 4.65741 -0.816067 1.6428 4.70659 -0.920982 2.33771 6.82468 -0.796345 1.97456 5.99389 -0.728927 1.88193 5.92273 -0.674058 1.89188 6.17368 -0.607855 1.79828 6.09933 -0.53367 1.38863 4.89683 -0.485418 1.34235 4.92003 -0.436038 1.30826 4.99056 -0.366726 1.42767 5.70138 -0.287362 1.48748 6.22942 -0.225501 1.41206 6.20227 -0.177484 1.2965 5.96772 -0.11776 1.2311 5.96611 -2.07698 1.34089 -1.05461 -2.12655 1.38969 -1.05906 -2.17044 1.43647 -1.05464 -2.23196 1.49582 -1.06993 -2.27655 1.54318 -1.06189 -2.33992 1.60404 -1.07277 -2.39641 1.66213 -1.07479 -2.45966 1.72502 -1.08109 -2.52369 1.78826 -1.08475 -2.59963 1.86217 -1.09876 -2.67654 1.93751 -1.10974 -2.75347 2.01449 -1.1179 -2.83726 2.0976 -1.12879 -2.93474 2.19142 -1.14775 -3.02508 2.28164 -1.15708 -3.1234 2.37899 -1.16814 -3.22141 2.47725 -1.17512 -3.34026 2.5932 -1.19358 -3.46601 2.71685 -1.21224 -3.59934 2.84717 -1.2302 -3.73271 2.98072 -1.24272 -3.87965 3.12703 -1.25855 -4.05503 3.2976 -1.28555 -4.22333 3.46604 -1.30087 -4.41316 3.65442 -1.32105 -4.62444 3.86302 -1.34472 -4.84241 4.08161 -1.36294 -5.10936 4.34471 -1.39682 -5.38472 4.61804 -1.42201 -5.68749 4.9211 -1.44847 -6.03988 5.27109 -1.48317 -6.45586 5.68292 -1.52885 -6.89269 6.12014 -1.56401 -7.42243 6.64686 -1.61401 -8.02187 7.24551 -1.66457 -8.77673 7.99609 -1.73931 -9.67374 8.88933 -1.82283 -11.0744 10.269 -2.00932 -12.865 12.0363 -2.23271 -21.7446 20.8743 -3.07327 -23.0253 22.258 -2.78629 -23.0745 22.451 -2.25779 -29.3335 28.7778 -2.48372 -29.2645 28.8953 -1.78673 -29.2381 29.0541 -1.09332 -29.138 29.1398 -0.394333 -23.125 23.2304 0.455851 -21.6122 21.836 1.01033 -21.5818 21.9437 1.52873 -21.816 22.3262 2.06182 -21.9295 22.5877 2.60205 -21.5746 22.3599 3.10646 -21.509 22.4351 3.63371 -22.5357 23.6693 4.32562 -21.0672 22.255 4.63933 -22.4145 23.8473 5.44961 -21.1894 22.6771 5.75153 -20.9505 22.5667 6.24609 -20.4553 22.1737 6.66277 -22.4908 24.5675 7.84283 -20.99 23.0651 7.95171 -20.9335 23.1588 8.51338 -22.0956 24.6269 9.5623 -23.5736 26.4745 10.8228 -22.0496 25.094 11.4761 -22.9677 26.338 12.6176 -4.86399 5.71829 4.64944 -4.85187 5.74942 4.81039 -4.91257 5.87376 5.04164 -4.95233 5.973 5.26365 -3.70866 4.42453 4.22095 -4.1815 5.12207 5.02291 -3.50515 4.27306 4.43314 -3.49029 4.29328 4.56356 -3.52094 4.37566 4.75415 -3.23182 4.02429 4.54369 -3.31156 4.17449 4.80074 -3.3162 4.22519 4.96972 -3.09663 3.96045 4.81919 -3.04421 3.92845 4.90125 -3.09532 4.0472 5.14981 -3.2393 4.3072 5.56714 -3.12789 4.19398 5.57218 -2.84444 3.82165 5.26234 -2.74441 3.71905 5.2612 -2.81536 3.88045 5.59216 -2.71635 3.7808 5.59639 -2.62575 3.69305 5.61224 -2.51269 3.56559 5.57196 -2.14231 3.01162 4.91583 -2.06175 2.92644 4.90542 -2.05506 2.96804 5.08281 -2.004 2.93361 5.14969 -1.94836 2.89216 5.20764 -1.89505 2.85578 5.27253 -1.97065 3.06178 5.75319 -2.33484 3.83793 7.26044 -2.18142 3.63502 7.08679 -2.03713 3.44177 6.91494 -1.69703 2.82538 5.91293 -1.60613 2.71661 5.8524 -1.56875 2.7253 6.02702 -1.52359 2.72188 6.18457 -1.51656 2.81658 6.56693 -1.42272 2.7002 6.49156 -1.33936 2.60867 6.46747 -1.22996 2.43898 6.24818 -0.9583 1.73593 4.66686 -0.906847 1.6824 4.66144 -0.85915 1.64277 4.69202 -0.810079 1.59518 4.70292 -0.859378 2.02105 6.10085 -0.786771 1.92282 6.01165 -0.725502 1.88905 6.12017 -0.65997 1.83581 6.17028 -0.572593 1.44271 5.03687 -0.520384 1.35197 4.89672 -0.470465 1.31407 4.94823 -0.405454 1.43861 5.65852 -0.33207 1.48696 6.11815 -0.265786 1.42995 6.15929 -0.202256 1.3608 6.14016 -0.152823 1.25454 5.93352 -0.0950542 1.18443 5.89129 -2.08795 1.27449 -1.03736 -2.13856 1.32285 -1.04266 -2.19 1.37141 -1.04599 -2.24803 1.4236 -1.05438 -2.29942 1.47399 -1.05402 -2.35165 1.52457 -1.05178 -2.41663 1.58431 -1.06105 -2.47474 1.64126 -1.06157 -2.54034 1.70186 -1.06595 -2.61217 1.76946 -1.07473 -2.69044 1.84112 -1.08663 -2.76992 1.9152 -1.09559 -2.85508 1.99461 -1.10749 -2.94828 2.08097 -1.1219 -3.04218 2.16795 -1.13249 -3.14285 2.26131 -1.14474 -3.24347 2.35653 -1.1532 -3.3518 2.45804 -1.16261 -3.47387 2.57177 -1.17776 -3.61061 2.69767 -1.19776 -3.7331 2.81453 -1.20238 -3.89919 2.96632 -1.22974 -4.05003 3.1094 -1.24125 -4.22328 3.27085 -1.25906 -4.41832 3.45309 -1.28229 -4.6137 3.63708 -1.29675 -4.83146 3.84112 -1.31438 -5.09134 4.08357 -1.34484 -5.36637 4.34105 -1.37079 -5.66365 4.62074 -1.39485 -5.99661 4.9341 -1.4217 -6.39503 5.3074 -1.46132 -6.809 5.69729 -1.48852 -7.3166 6.17392 -1.53286 -7.87501 6.70102 -1.57207 -8.57964 7.36265 -1.63406 -9.40684 8.14089 -1.70184 -10.5479 9.20693 -1.8209 -12.0535 10.6129 -1.98311 -18.1739 16.2935 -2.76931 -22.2404 20.2397 -2.64221 -23.0875 21.1541 -2.26303 -24.4429 22.5516 -1.90586 -29.5592 27.4862 -1.85943 -29.494 27.6041 -1.17622 -29.2613 27.5625 -0.484177 -24.0083 22.7284 0.347744 -23.7748 22.6498 0.906024 -23.5998 22.6268 1.45747 -25.3237 24.4502 2.08426 -24.4358 23.739 2.62548 -23.9028 23.3672 3.16024 -22.4396 22.0665 3.56681 -28.9383 28.7013 5.02128 -28.8975 28.8483 5.72687 -28.8118 28.9502 6.42995 -28.8759 29.2073 7.16874 -28.7498 29.2723 7.87365 -22.864 23.3882 7.03662 -22.677 23.351 7.57638 -22.3634 23.1798 8.07357 -22.2853 23.2557 8.64494 -5.27813 5.88706 4.82309 -5.155 5.78969 4.90066 -5.09444 5.76483 5.02768 -3.73598 4.32817 4.53389 -3.67978 4.29615 4.62143 -3.58212 4.21286 4.66051 -3.48469 4.12887 4.69648 -3.59492 4.31344 4.99358 -3.29654 3.96583 4.76482 -3.22938 3.91814 4.82959 -3.16114 3.86932 4.89269 -3.14523 3.89105 5.0342 -3.11406 3.89366 5.15648 -3.11001 3.93439 5.32779 -3.00796 3.83913 5.33934 -2.91088 3.74969 5.35456 -2.91629 3.80789 5.55552 -2.5049 3.2534 4.95423 -2.42829 3.18547 4.97599 -2.37323 3.1506 5.04102 -2.27255 3.04406 5.00496 -2.13754 2.88115 4.87895 -2.10152 2.87151 4.97691 -2.05344 2.84513 5.05073 -2.1588 3.07733 5.54629 -1.98506 2.84171 5.28693 -2.13898 3.17281 5.98303 -1.88137 2.78153 5.44041 -2.19258 3.42702 6.75089 -2.18837 3.51046 7.08235 -2.3209 3.87217 7.9714 -1.72686 2.78609 6.01757 -1.56792 2.54194 5.67397 -1.50508 2.49493 5.72184 -1.5489 2.69039 6.30623 -1.46046 2.59458 6.26557 -1.41334 2.59711 6.44948 -1.34843 2.56182 6.5514 -1.00664 1.73735 4.67065 -0.954165 1.6892 4.67474 -0.910087 1.66387 4.74317 -0.99426 2.11903 6.16185 -0.795099 1.51943 4.61366 -0.832221 1.88699 5.87295 -0.691932 1.39411 4.51442 -0.707735 1.81675 6.05943 -0.642501 1.77639 6.14663 -0.556615 1.37137 4.92207 -0.505661 1.32572 4.93496 -0.454084 1.28907 4.98544 -0.38139 1.43461 5.80308 -0.308039 1.44125 6.09708 -0.236241 1.40156 6.20503 -0.187207 1.28214 5.93036 -0.121897 1.22612 5.95716 -2.10877 1.21622 -1.03498 -2.15512 1.25872 -1.03311 -2.20809 1.30475 -1.03668 -2.26116 1.35215 -1.0386 -2.31433 1.40092 -1.03887 -2.37984 1.4568 -1.05093 -2.43368 1.50626 -1.04709 -2.48761 1.5571 -1.0415 -2.56073 1.61957 -1.05324 -2.62721 1.68022 -1.05633 -2.70827 1.74993 -1.06923 -2.78909 1.82037 -1.07891 -2.87681 1.89687 -1.09171 -2.95957 1.97021 -1.09522 -3.05509 2.05439 -1.10722 -3.15813 2.14375 -1.12075 -3.25427 2.23044 -1.12495 -3.37886 2.33803 -1.14644 -3.48337 2.43174 -1.14738 -3.61644 2.54768 -1.16406 -3.75735 2.67122 -1.18034 -3.91161 2.80649 -1.20011 -4.0538 2.93325 -1.20438 -4.23822 3.09469 -1.22915 -4.42425 3.2584 -1.2461 -4.62459 3.43533 -1.26332 -4.84038 3.62641 -1.27992 -5.09213 3.84866 -1.30601 -5.35292 4.07861 -1.32465 -5.63506 4.33075 -1.34258 -5.95567 4.6146 -1.36431 -6.33548 4.94981 -1.39702 -6.75184 5.32047 -1.42792 -7.21387 5.73069 -1.45675 -7.75827 6.21435 -1.49408 -8.4362 6.81428 -1.55111 -9.20403 7.49556 -1.60502 -10.2191 8.39199 -1.69424 -11.5483 9.56356 -1.81931 -13.2519 11.0662 -1.97318 -22.0926 18.9115 -2.60538 -23.1939 19.9924 -2.27992 -23.1974 20.1281 -1.7682 -29.3122 26.1479 0.0980415 -29.383 26.3832 0.760325 -24.519 22.2778 1.92218 -29.1086 26.8268 3.43772 -29.1836 27.0731 4.12715 -29.094 27.5261 6.19944 -28.9126 27.5369 6.87055 -28.9585 27.7636 7.59336 -28.8808 28.0641 9.02507 -28.7821 28.1567 9.73398 -28.6722 28.242 10.4447 -3.88389 4.26327 4.53963 -3.7835 4.18343 4.58194 -3.76804 4.24437 4.87252 -3.72171 4.22921 4.97713 -3.4372 3.92069 4.78118 -3.33361 3.83299 4.80201 -3.29723 3.82778 4.91077 -3.40704 4.01014 5.23218 -3.26427 3.87198 5.19601 -3.18133 3.80899 5.24414 -3.15903 3.82648 5.38799 -3.05015 3.72789 5.39053 -3.02382 3.74109 5.53421 -2.59851 3.20354 4.94224 -2.62371 3.28472 5.1662 -2.46103 3.09868 5.02229 -2.41502 3.07984 5.10956 -2.29804 2.9558 5.04056 -2.25128 2.9365 5.1247 -2.12575 2.7939 5.01681 -2.15429 2.89129 5.29246 -2.14021 2.92504 5.47384 -2.0023 2.75958 5.31694 -1.93701 2.71018 5.35541 -1.89233 2.69772 5.45984 -1.83294 2.66009 5.52158 -1.77142 2.6168 5.57375 -1.65983 2.48146 5.44151 -1.61335 2.46839 5.55098 -1.53327 2.38692 5.5185 -1.59161 2.5965 6.1275 -1.54066 2.58927 6.275 -1.50967 2.6319 6.54995 -1.11179 1.7874 4.67787 -1.05551 1.73656 4.67457 -1.00225 1.68973 4.67902 -0.96204 1.67961 4.7849 -0.880137 1.54177 4.53415 -0.837414 1.52172 4.6094 -0.894055 1.92273 5.9621 -0.720273 1.35659 4.3775 -0.694863 1.43768 4.78377 -0.680498 1.67887 5.76742 -0.60359 1.49032 5.30349 -0.542116 1.34005 4.94122 -0.488298 1.29491 4.95316 -0.424004 1.41727 5.65383 -0.35204 1.43787 5.98641 -0.273896 1.44042 6.27019 -0.209846 1.35714 6.17208 -0.158678 1.24918 5.93496 -0.0984419 1.17961 5.87208 -2.16874 1.19533 -1.02353 -2.21673 1.23664 -1.02034 -2.27736 1.28579 -1.03012 -2.33782 1.33545 -1.03765 -2.39239 1.38211 -1.03631 -2.44704 1.43015 -1.03322 -2.50252 1.47843 -1.02807 -2.57051 1.53493 -1.03412 -2.64644 1.59704 -1.04424 -2.72787 1.66337 -1.05778 -2.81148 1.73187 -1.06846 -2.88797 1.79668 -1.06989 -2.98487 1.87542 -1.08621 -3.06994 1.94661 -1.08722 -3.1746 2.03319 -1.10206 -3.27405 2.11572 -1.10722 -3.38052 2.2056 -1.11414 -3.50129 2.3054 -1.12707 -3.6229 2.40703 -1.13521 -3.75895 2.51983 -1.14829 -3.91058 2.64474 -1.16541 -4.06973 2.77654 -1.18085 -4.24433 2.92084 -1.19869 -4.41983 3.06844 -1.20959 -4.61021 3.22694 -1.22114 -4.8387 3.41555 -1.24465 -5.07463 3.61293 -1.26261 -5.33451 3.82943 -1.28135 -5.61629 4.06581 -1.29967 -5.92945 4.32679 -1.31894 -6.29502 4.63281 -1.34725 -6.68492 4.9595 -1.36844 -7.13539 5.33721 -1.39552 -7.67035 5.78347 -1.43199 -8.28203 6.29549 -1.4701 -9.02351 6.91563 -1.52089 -9.87955 7.63354 -1.57146 -11.1743 8.7054 -1.69663 -12.8294 10.0783 -1.8499 -18.4354 14.7265 -2.37609 -21.9802 17.6993 -2.57969 -23.06 18.7001 -2.2658 -23.3005 19.0231 -1.79898 -23.4337 19.2608 -1.30957 -29.6951 24.6028 -1.3049 -29.672 24.7475 -0.655323 -29.4626 24.7361 0.00235093 -29.4143 24.8596 0.651528 -29.4255 25.0338 1.30251 -29.5176 25.2788 1.96051 -29.4861 25.4192 2.62028 -29.3104 25.4351 3.27195 -29.1865 25.4953 3.92599 -29.2327 25.7058 4.601 -29.3208 25.9552 5.2906 -29.323 26.1315 5.97631 -29.0889 26.0955 6.62279 -28.9915 26.1836 7.29595 -29.002 26.3699 7.99886 -29.174 26.7088 8.75435 -28.9817 26.7139 9.42067 -28.8092 26.7375 10.0935 -3.8288 4.08283 4.78443 -3.77172 4.05802 4.8753 -3.76502 4.09027 5.02787 -3.69031 4.04476 5.09919 -3.60975 3.99167 5.16244 -3.54792 3.96207 5.24983 -3.31646 3.72434 5.09376 -3.24729 3.68291 5.16097 -3.35571 3.86326 5.50647 -3.16358 3.66785 5.38355 -3.11201 3.64996 5.48397 -2.4811 2.87614 4.55599 -2.61925 3.0976 4.96802 -2.58153 3.09265 5.07138 -2.49643 3.02262 5.08301 -2.41618 2.95877 5.09978 -2.34031 2.89922 5.12228 -2.27846 2.85919 5.17461 -2.20833 2.80916 5.20936 -2.15192 2.77795 5.27522 -2.04542 2.66955 5.20799 -2.00976 2.66988 5.32912 -1.92061 2.58579 5.29851 -2.40847 3.45686 7.09204 -1.89582 2.67379 5.72865 -1.83091 2.63429 5.78999 -1.64358 2.37179 5.38479 -1.58415 2.33489 5.43989 -1.57124 2.38975 5.69913 -1.60007 2.5371 6.18565 -1.56659 2.57137 6.43249 -1.5099 2.56233 6.58973 -1.1044 1.73069 4.66926 -1.05086 1.68803 4.68334 -1.00156 1.65615 4.72407 -1.12728 2.14411 6.22387 -0.877594 1.51838 4.59568 -0.830266 1.48929 4.6421 -0.778148 1.444 4.64012 -0.722224 1.38118 4.57952 -0.725859 1.67253 5.71508 -0.674747 1.74087 6.15582 -0.579569 1.35513 4.95736 -0.524479 1.30735 4.94997 -0.469733 1.27547 5.00952 -0.397765 1.41882 5.81743 -0.327502 1.39325 5.95478 -0.2494 1.37935 6.15922 -0.198624 1.25826 5.85417 -0.130854 1.20986 5.88945 -2.18692 1.13464 -1.02081 -2.2299 1.17127 -1.01066 -2.28532 1.21473 -1.01358 -2.34661 1.26294 -1.02206 -2.40295 1.308 -1.02125 -2.45914 1.35349 -1.0185 -2.52789 1.40711 -1.02744 -2.59169 1.45753 -1.02729 -2.66225 1.51275 -1.03142 -2.73286 1.56949 -1.03322 -2.81686 1.63454 -1.04484 -2.90945 1.70424 -1.05924 -2.98753 1.768 -1.05877 -3.08084 1.83993 -1.06663 -3.18099 1.91807 -1.07692 -3.28206 1.9978 -1.08349 -3.39065 2.08274 -1.0914 -3.51476 2.1783 -1.10558 -3.63876 2.27589 -1.1152 -3.77914 2.38418 -1.12961 -3.91935 2.49466 -1.13877 -4.07488 2.61634 -1.15158 -4.22996 2.73943 -1.15817 -4.43187 2.89521 -1.18427 -4.6274 3.04777 -1.19799 -4.83725 3.21353 -1.21209 -5.07194 3.39678 -1.22869 -5.32175 3.59353 -1.24321 -5.60217 3.81448 -1.26153 -5.89968 4.05009 -1.2749 -6.24379 4.32014 -1.29453 -6.635 4.62815 -1.31809 -7.0807 4.97972 -1.34517 -7.57351 5.36858 -1.36925 -8.15258 5.82606 -1.40024 -8.83364 6.36322 -1.4369 -9.61642 6.98254 -1.47272 -10.7926 7.90041 -1.57502 -12.2437 9.03529 -1.69096 -14.2619 10.6104 -1.86437 -23.436 17.8562 -2.32328 -24.8456 19.0658 -2.00651 -24.7259 19.1028 -1.46953 -30.4295 23.8537 -0.765937 -30.4564 24.0374 -0.116529 -29.4658 23.4099 0.553835 -29.5315 23.6211 1.18944 -29.5564 23.8004 1.83045 -30.2642 24.7035 3.17498 -29.2812 24.058 3.75224 -29.3375 24.268 4.41156 -29.2773 24.3813 5.06309 -30.1398 25.274 5.86849 -30.1242 25.4322 6.55698 -29.0981 24.7306 7.0401 -29.134 24.931 7.73038 -29.077 25.0539 8.4067 -28.8514 25.3835 10.4558 -4.12037 3.9565 4.08288 -3.99198 4.03645 4.81662 -3.93405 4.01316 4.90873 -3.99611 4.12198 5.14277 -3.76787 3.91101 5.03342 -3.70641 3.88359 5.12168 -3.67436 3.88949 5.24861 -3.40609 3.6264 5.05296 -3.48846 3.76312 5.33936 -3.47499 3.79227 5.49932 -3.37098 3.7154 5.52631 -2.72538 2.98194 4.66387 -2.53401 2.78726 4.49469 -2.47049 2.74582 4.53313 -2.51352 2.83815 4.76629 -2.52196 2.89097 4.94998 -2.29995 2.6448 4.67831 -2.39541 2.81369 5.04939 -2.24655 2.65982 4.90992 -2.2629 2.72982 5.13524 -2.25994 2.77542 5.33133 -2.15287 2.67437 5.2735 -2.04772 2.57521 5.2119 -1.94228 2.47256 5.13821 -1.97709 2.58315 5.46983 -2.07769 2.80717 6.04696 -2.09218 2.90688 6.39813 -1.8601 2.59693 5.90318 -1.73141 2.45167 5.73306 -1.62873 2.34503 5.63837 -1.53114 2.24554 5.54873 -1.63753 2.54127 6.39749 -1.54917 2.46918 6.39023 -1.15357 1.72169 4.66437 -1.10023 1.68512 4.68778 -1.31161 2.30385 6.49488 -1.20083 2.16533 6.29249 -0.928777 1.54251 4.66681 -0.86823 1.47949 4.60983 -0.823868 1.46669 4.70285 -0.768133 1.41708 4.68081 -0.714924 1.37571 4.68629 -0.652769 1.27156 4.46959 -0.624136 1.42916 5.19528 -0.561423 1.31958 4.95684 -0.50565 1.27993 4.97768 -0.443252 1.34403 5.43518 -0.369101 1.39654 5.88354 -0.302001 1.33961 5.87341 -0.238623 1.26928 5.79299 -0.167888 1.22882 5.85791 -0.102319 1.17163 5.84333 -2.24593 1.10997 -1.00837 -2.29637 1.14872 -1.00452 -2.34667 1.18783 -0.999024 -2.41609 1.23713 -1.0128 -2.47406 1.281 -1.01068 -2.53764 1.3288 -1.01335 -2.60225 1.37781 -1.01395 -2.67437 1.43041 -1.01871 -2.75322 1.48789 -1.02736 -2.83284 1.54578 -1.03316 -2.91249 1.60522 -1.03644 -2.99978 1.66951 -1.04271 -3.09468 1.73873 -1.05158 -3.18956 1.80968 -1.05725 -3.29297 1.88549 -1.06471 -3.40415 1.9674 -1.074 -3.51599 2.05004 -1.07899 -3.64213 2.14263 -1.08989 -3.77032 2.23776 -1.09617 -3.92826 2.352 -1.11668 -4.07895 2.46294 -1.1263 -4.23839 2.58139 -1.1348 -4.41405 2.71111 -1.14566 -4.61258 2.85711 -1.1621 -4.81945 3.01026 -1.1747 -5.0512 3.18074 -1.19049 -5.29885 3.36345 -1.20436 -5.56254 3.55957 -1.21545 -5.86542 3.78461 -1.23281 -6.19371 4.02812 -1.24731 -6.57734 4.312 -1.26959 -7.00058 4.62627 -1.29054 -7.47324 4.97794 -1.31028 -8.04093 5.39843 -1.34065 -8.68165 5.87481 -1.36896 -9.42656 6.42905 -1.39896 -10.4285 7.16897 -1.46296 -11.7353 8.13214 -1.55559 -13.5647 9.47561 -1.70329 -18.7252 13.2897 -2.02052 -24.2706 17.3652 -2.45159 -25.7641 18.5688 -2.13975 -26.065 18.9176 -1.63898 -26.0278 19.0225 -1.0964 -29.8533 21.981 -0.795232 -29.8094 22.1015 -0.170338 -29.6447 22.1307 0.457656 -29.5191 22.1892 1.08121 -29.5923 22.3966 1.70755 -29.6877 22.6242 2.34125 -29.6454 22.747 2.97417 -29.5945 22.8649 3.60869 -29.3305 22.815 4.22259 -29.4105 23.0356 4.87544 -29.5032 23.2681 5.53979 -29.4681 23.4015 6.19182 -29.4545 23.5536 6.85326 -29.1397 23.463 7.45386 -29.214 23.6875 8.14383 -29.2076 23.85 8.8237 -28.9245 24.1263 10.8258 -4.21005 3.82913 4.0472 -4.17525 3.82747 4.14962 -5.30987 5.05269 5.65694 -4.1222 3.91318 4.66164 -4.05361 3.88166 4.74187 -3.85665 3.71832 4.68165 -3.99217 3.89475 4.98493 -3.88253 3.81966 5.0188 -3.6209 3.58506 4.86203 -3.82572 3.84065 5.28017 -3.5987 3.63946 5.15358 -3.57468 3.65505 5.29125 -3.26863 3.35974 5.02678 -2.77541 2.84687 4.45244 -2.61453 2.69826 4.3442 -2.5474 2.65519 4.37554 -2.50231 2.63812 4.44203 -2.52796 2.70457 4.63605 -2.45414 2.65378 4.65765 -2.36458 2.58322 4.64615 -2.31066 2.55778 4.70225 -2.42865 2.74935 5.12344 -2.3178 2.65222 5.0699 -2.32793 2.71412 5.28928 -2.27104 2.68995 5.36317 -2.17817 2.6146 5.3449 -2.102 2.56216 5.36587 -1.98699 2.45295 5.27445 -2.17856 2.79725 6.0893 -2.14128 2.81292 6.26728 -1.89561 2.50169 5.75496 -1.79934 2.41801 5.70769 -1.70447 2.33445 5.65761 -1.62965 2.28231 5.67656 -1.62291 2.35464 5.99194 -1.66131 2.52383 6.56479 -1.20059 1.70714 4.6504 -1.14646 1.67187 4.67407 -1.37062 2.2691 6.42315 -1.36783 2.40559 6.98675 -1.16227 2.03783 6.11808 -0.913295 1.48706 4.63429 -0.849863 1.41751 4.54742 -0.810914 1.42947 4.71564 -0.748143 1.35519 4.60675 -0.690335 1.28947 4.5147 -0.63212 1.20638 4.35357 -0.599144 1.33763 4.99268 -0.541359 1.29046 4.97487 -0.484171 1.26115 5.03377 -0.414112 1.37466 5.71524 -0.346462 1.32606 5.72436 -0.270722 1.30954 5.88866 -0.19895 1.26844 5.9442 -0.1321 1.20758 5.90023 -2.30545 1.0832 -0.995423 -2.35632 1.12 -0.990282 -2.41404 1.1613 -0.990686 -2.47932 1.20602 -0.996024 -2.54468 1.25217 -0.99942 -2.61733 1.30091 -1.00697 -2.68357 1.34878 -1.00606 -2.75037 1.396 -1.0026 -2.83752 1.45572 -1.01587 -2.9185 1.51158 -1.01967 -3.00072 1.56973 -1.02103 -3.09699 1.63525 -1.03092 -3.19421 1.70228 -1.03748 -3.29237 1.77083 -1.04061 -3.40591 1.84878 -1.05099 -3.51914 1.92763 -1.05738 -3.64083 2.01159 -1.0645 -3.76242 2.09752 -1.06735 -3.90797 2.19754 -1.08002 -4.05431 2.29954 -1.08722 -4.23997 2.42511 -1.1112 -4.39557 2.5358 -1.11104 -4.58239 2.66494 -1.12146 -4.80194 2.81565 -1.14079 -5.02977 2.97365 -1.15559 -5.26679 3.13888 -1.16508 -5.5197 3.31636 -1.17255 -5.81238 3.52039 -1.18685 -6.1315 3.74248 -1.19905 -6.48266 3.98822 -1.21092 -6.89078 4.27321 -1.22895 -7.35656 4.59802 -1.24962 -7.87117 4.9587 -1.26694 -8.49187 5.39188 -1.29438 -9.22037 5.89955 -1.32536 -10.104 6.51502 -1.36565 -11.2581 7.3165 -1.43221 -12.9542 8.48597 -1.56484 -14.6242 9.65425 -1.62287 -18.6479 12.41 -2.00706 -25.8613 17.4775 -2.17291 -29.6874 20.2149 -2.05549 -27.5296 18.8763 -1.26811 -29.7286 20.5334 -0.850483 -29.6823 20.648 -0.241606 -29.6442 20.767 0.367614 -29.6124 20.8919 0.977418 -29.5719 21.0108 1.58864 -29.5394 21.1345 2.20195 -29.5216 21.2699 2.81833 -29.4696 21.3823 3.4351 -29.4257 21.4997 4.05504 -29.4035 21.6349 4.68069 -29.3557 21.7525 5.30689 -29.3147 21.8757 5.93798 -29.2875 22.0095 6.57642 -29.2433 22.1322 7.21632 -29.1805 22.2418 7.85728 -29.169 22.393 8.51673 -29.1254 22.5192 9.17448 -29.0924 22.6575 9.84263 -29.0503 22.7895 10.5151 -28.973 22.8958 11.1836 -14.7128 11.9234 7.54481 -14.3057 11.678 7.72461 -4.50486 3.85275 4.04214 -4.43129 3.81937 4.11759 -4.26816 3.70348 4.11886 -4.1938 3.66809 4.18874 -4.14456 3.6548 4.27863 -5.25573 4.7228 5.44577 -5.27996 4.79025 5.65303 -4.21533 3.82407 4.77401 -4.13369 3.78278 4.84222 -3.92112 3.61485 4.76656 -4.12931 3.85506 5.15511 -3.66771 3.43726 4.77792 -3.54062 3.34605 4.77405 -4.03072 3.88133 5.55412 -3.80656 3.69586 5.44085 -3.33897 3.25127 4.97295 -2.92736 2.85594 4.54096 -2.69709 2.64574 4.34165 -2.66181 2.64009 4.42428 -2.92762 2.96728 5.00213 -2.66886 2.71889 4.73161 -2.5614 2.63628 4.70146 -2.46059 2.5582 4.67571 -2.38576 2.51003 4.69355 -2.44471 2.61981 4.97915 -2.43769 2.65575 5.14916 -2.38685 2.64021 5.23132 -2.65147 3.02457 6.05304 -2.7071 3.15864 6.44166 -2.30554 2.69141 5.68509 -2.43292 2.92335 6.27671 -2.11952 2.55547 5.66873 -2.03548 2.49842 5.67834 -1.93535 2.41723 5.6334 -1.86636 2.38041 5.68252 -1.79453 2.33904 5.72146 -1.73364 2.31552 5.80385 -1.59527 2.16044 5.56975 -1.73331 2.48932 6.53005 -1.26552 1.72208 4.71898 -1.19078 1.65397 4.65088 -1.14259 1.63313 4.71069 -1.46062 2.43171 7.09188 -1.28916 2.18566 6.57212 -0.946438 1.45721 4.55531 -0.885884 1.40315 4.50606 -0.850807 1.42532 4.70279 -0.789445 1.36494 4.63219 -0.73233 1.31635 4.59821 -0.67822 1.27892 4.6014 -0.626134 1.24687 4.62274 -0.579785 1.30032 4.98219 -0.521317 1.26128 4.99262 -0.455329 1.38605 5.70289 -0.383035 1.37014 5.84891 -0.31468 1.30735 5.78872 -0.248363 1.24987 5.7465 -0.173971 1.21732 5.83002 -0.103777 1.16827 5.83392 -2.36978 1.05605 -0.988612 -2.41601 1.09039 -0.97555 -2.48188 1.13274 -0.981444 -2.54855 1.17535 -0.985173 -2.62203 1.22263 -0.993668 -2.68214 1.26485 -0.986802 -2.74977 1.31062 -0.984287 -2.83255 1.36313 -0.991933 -2.9218 1.41966 -1.00288 -3.00536 1.4742 -1.00486 -3.09559 1.53378 -1.01006 -3.18754 1.59363 -1.01189 -3.29394 1.66293 -1.02188 -3.40201 1.73262 -1.02792 -3.5176 1.80749 -1.0355 -3.62532 1.87992 -1.03386 -3.75783 1.96496 -1.0431 -3.898 2.05646 -1.0526 -4.04652 2.15336 -1.06157 -4.21209 2.26003 -1.07394 -4.37065 2.36432 -1.07582 -4.55296 2.48338 -1.0845 -4.75985 2.61733 -1.09841 -4.97507 2.75843 -1.10839 -5.20823 2.911 -1.11767 -5.44937 3.07009 -1.12145 -5.72367 3.25051 -1.12973 -6.03959 3.45729 -1.14354 -6.39696 3.69101 -1.16035 -6.77171 3.93786 -1.16907 -7.20479 4.2219 -1.18214 -7.705 4.55053 -1.19895 -8.28869 4.93225 -1.21979 -8.94645 5.36551 -1.23801 -9.6635 5.84015 -1.2443 -10.7572 6.55206 -1.30829 -12.0684 7.40639 -1.37323 -14.0829 8.71081 -1.51848 -19.0207 11.9474 -1.69895 -22.3928 14.174 -1.75479 -27.5534 17.5747 -1.86579 -29.8554 19.1864 -1.51826 -29.8739 19.3388 -0.923462 -29.8415 19.4596 -0.324279 -29.8334 19.5963 0.274731 -29.8078 19.721 0.875986 -29.7486 19.8248 1.47802 -29.7543 19.972 2.08312 -29.7188 20.0918 2.68936 -29.7059 20.2279 3.2997 -29.6843 20.3583 3.9129 -29.6528 20.4833 4.52848 -29.6439 20.6251 5.15105 -29.626 20.7615 5.77709 -29.5898 20.886 6.40505 -29.576 21.0279 7.04236 -29.5355 21.1523 7.67979 -29.5169 21.2935 8.32842 -29.4798 21.4219 8.97918 -29.4945 21.5914 9.65185 -29.4279 21.702 10.3083 -29.4424 21.8763 10.9991 -29.3535 21.974 11.6629 -4.44978 3.62673 4.03172 -4.45407 3.66081 4.16568 -4.42984 3.67159 4.27996 -4.29519 3.58865 4.30182 -4.20568 3.54275 4.35866 -4.38658 3.7349 4.66527 -4.21369 3.61532 4.64722 -4.05617 3.50785 4.63499 -4.01606 3.507 4.74002 -3.86588 3.40364 4.72596 -3.74629 3.32768 4.73873 -3.63347 3.25591 4.75445 -3.58666 3.24568 4.84681 -3.99659 3.68055 5.52826 -3.77597 3.50707 5.41625 -3.41471 3.18999 5.09234 -2.75953 2.57021 4.31053 -2.73419 2.57559 4.40754 -3.53585 3.44113 5.80961 -2.65758 2.56459 4.57207 -2.59466 2.5336 4.61601 -2.54427 2.51564 4.68199 -2.4468 2.44618 4.66133 -2.66047 2.72424 5.23889 -2.93056 3.07916 5.98092 -3.17746 3.42205 6.73853 -2.74364 2.96909 6.04263 -2.62743 2.88625 6.01609 -2.25405 2.48 5.34909 -2.28923 2.57888 5.66519 -2.58009 3.0176 6.70437 -2.1411 2.50211 5.7565 -2.00344 2.37518 5.60829 -1.93859 2.34836 5.6751 -1.92229 2.39262 5.90955 -1.92665 2.47459 6.24414 -1.65358 2.12538 5.53627 -1.57228 2.06837 5.52397 -1.71375 2.39758 6.51529 -1.23978 1.63989 4.64661 -1.18176 1.60451 4.66004 -1.4999 2.34038 6.8707 -1.36039 2.1791 6.58507 -0.976182 1.42011 4.45757 -0.943189 1.44096 4.63522 -0.891463 1.41992 4.68987 -0.832989 1.37712 4.67709 -0.777032 1.34152 4.68179 -0.710196 1.25672 4.51227 -0.655626 1.21419 4.48523 -0.611405 1.25197 4.76656 -0.553344 1.19263 4.67963 -0.498381 1.23875 5.02889 -0.427588 1.35342 5.71004 -0.360363 1.28948 5.63046 -0.285794 1.26958 5.7545 -0.210122 1.24152 5.84801 -0.135276 1.20384 5.90121 -2.37453 0.989444 -0.979793 -2.42156 1.02244 -0.967192 -2.47475 1.05704 -0.959737 -2.55645 1.10343 -0.977903 -2.61706 1.14188 -0.973437 -2.68543 1.18478 -0.973714 -2.75462 1.22795 -0.97173 -2.83033 1.27493 -0.973926 -2.91449 1.32539 -0.979671 -3.0063 1.38063 -0.988699 -3.09123 1.43315 -0.988683 -3.19903 1.49698 -1.00308 -3.29231 1.55489 -1.00253 -3.39415 1.61757 -1.00427 -3.51114 1.68867 -1.01315 -3.62219 1.75687 -1.01268 -3.75611 1.83811 -1.02341 -3.88309 1.91675 -1.02452 -4.02601 2.00411 -1.03042 -4.19475 2.10539 -1.04473 -4.36303 2.20806 -1.05291 -4.52456 2.30927 -1.05089 -4.73446 2.43668 -1.06742 -4.95439 2.56984 -1.07967 -5.16624 2.70116 -1.08008 -5.41985 2.85679 -1.09068 -5.68236 3.01888 -1.09499 -5.98733 3.20589 -1.10577 -6.32689 3.41363 -1.11711 -6.70018 3.64368 -1.12749 -7.09918 3.89073 -1.13166 -7.56551 4.17777 -1.14119 -8.10911 4.51311 -1.15485 -8.76224 4.91418 -1.17673 -9.45082 5.34053 -1.18132 -10.4365 5.94321 -1.22715 -11.5757 6.64177 -1.26572 -13.2951 7.68655 -1.36866 -15.108 8.80103 -1.41901 -18.8765 11.0806 -1.68795 -25.6792 15.3072 -1.69692 -32.0464 19.3949 -1.1325 -32.0425 19.5401 -0.502807 -32.038 19.6838 0.128836 -32.0059 19.8116 0.762527 -31.9726 19.9389 1.39746 -31.9389 20.0656 2.03396 -31.9364 20.2137 2.67391 -31.9167 20.3507 3.3163 -31.8863 20.4825 3.96083 -31.8625 20.6187 4.60967 -31.8868 20.7872 5.269 -31.8173 20.8954 5.92036 -31.7949 21.0363 6.58296 -31.7706 21.1766 7.2507 -31.7684 21.3335 7.92896 -31.7138 21.4563 8.60231 -31.7044 21.6113 9.2932 -31.6839 21.7607 9.98887 -31.6754 21.9201 10.6966 -31.6314 22.0572 11.4016 -4.55162 3.56691 4.27546 -4.42119 3.49267 4.30379 -4.33667 3.45422 4.36703 -4.32132 3.47318 4.49081 -4.2537 3.44934 4.56866 -4.16638 3.40953 4.62706 -4.08549 3.37322 4.68978 -4.14458 3.46 4.9001 -4.06015 3.42126 4.96208 -3.76523 3.19519 4.78127 -3.71137 3.18229 4.86754 -3.59659 3.11328 4.87899 -3.93028 3.4579 5.46496 -3.86499 3.43848 5.55678 -3.48278 3.11894 5.20608 -3.42723 3.10512 5.29603 -3.37902 3.09976 5.40003 -3.64638 3.40679 6.00414 -3.38802 3.19612 5.78928 -2.65062 2.49027 4.72731 -2.59428 2.469 4.78547 -2.5274 2.43746 4.82709 -3.75279 3.79665 7.39298 -3.63262 3.73188 7.43874 -2.93116 3.01653 6.23707 -2.66773 2.77418 5.89885 -2.35748 2.46759 5.40781 -2.29731 2.44583 5.47927 -2.26438 2.45937 5.62681 -2.27169 2.52694 5.89548 -2.08491 2.3484 5.6272 -2.0109 2.31215 5.668 -1.96134 2.30922 5.78719 -1.86468 2.24126 5.75443 -1.71119 2.0874 5.50309 -1.65634 2.07584 5.59967 -1.77059 2.33878 6.42641 -1.29006 1.62738 4.65144 -1.23125 1.59332 4.66523 -1.17498 1.5664 4.69621 -1.53954 2.38394 7.23457 -1.2788 1.97775 6.18556 -0.993958 1.45407 4.69833 -0.93753 1.42323 4.71527 -0.865575 1.34851 4.58823 -0.811294 1.32266 4.62168 -0.759525 1.30509 4.68285 -0.704429 1.28005 4.72428 -0.644038 1.22566 4.64829 -0.58837 1.18813 4.63895 -0.533032 1.15837 4.65738 -0.470288 1.36349 5.70828 -0.397221 1.33859 5.7948 -0.32617 1.28247 5.74329 -0.253542 1.24368 5.76843 -0.180787 1.20361 5.79231 -0.106211 1.16467 5.82453 -2.43816 0.959403 -0.972585 -2.48562 0.990475 -0.958592 -2.55466 1.02909 -0.963508 -2.62377 1.06915 -0.96648 -2.69249 1.10873 -0.967114 -2.75579 1.1472 -0.959368 -2.83306 1.19156 -0.962192 -2.91781 1.23962 -0.968686 -3.00331 1.2881 -0.972238 -3.09745 1.34113 -0.979049 -3.18397 1.39259 -0.977135 -3.28623 1.45006 -0.983215 -3.39705 1.5123 -0.991485 -3.51637 1.57949 -1.00126 -3.62048 1.64182 -0.996895 -3.74896 1.71469 -1.00378 -3.86954 1.78516 -1.00126 -4.0319 1.87492 -1.01797 -4.16928 1.95592 -1.01554 -4.33322 2.04964 -1.02141 -4.52142 2.15592 -1.03396 -4.71033 2.26446 -1.03988 -4.91708 2.38307 -1.04685 -5.16499 2.52281 -1.06487 -5.3985 2.65792 -1.06668 -5.64003 2.79947 -1.06339 -5.9246 2.9635 -1.06742 -6.26956 3.16063 -1.08295 -6.61451 3.36049 -1.08533 -7.01925 3.59356 -1.09425 -7.46873 3.85279 -1.10091 -7.98634 4.15232 -1.11057 -8.59993 4.50477 -1.12534 -9.27458 4.89533 -1.13163 -10.1295 5.38727 -1.15325 -11.2286 6.01684 -1.19227 -12.7431 6.87967 -1.26712 -14.553 7.91609 -1.33265 -22.5572 12.5538 -1.38948 -34.4479 19.4671 -1.36986 -34.4659 19.629 -0.704671 -34.4462 19.7715 -0.0362614 -34.4606 19.933 0.63305 -34.4121 20.0591 1.30475 -34.4308 20.2248 1.97921 -34.3785 20.3494 2.65425 -34.3836 20.5082 3.3349 -34.3366 20.6367 4.01521 -34.3119 20.7798 4.70058 -34.3018 20.9319 5.39197 -34.2716 21.0738 6.08544 -34.256 21.2251 6.78618 -34.2204 21.366 7.4889 -34.2061 21.5205 8.20195 -34.1891 21.676 8.92098 -34.1679 21.8296 9.64657 -34.1416 21.9827 10.3787 -34.1363 22.1504 11.1252 -34.0853 22.2906 11.8668 -5.81972 4.37116 5.33645 -4.49738 3.38908 4.40214 -4.44994 3.38307 4.49885 -4.36188 3.34612 4.56004 -4.29259 3.32353 4.63687 -3.93237 3.0654 4.42616 -3.90229 3.07258 4.53126 -4.11423 3.27987 4.8973 -3.90622 3.14102 4.82035 -4.13858 3.37192 5.2385 -3.73414 3.06364 4.9206 -3.66672 3.04146 4.99151 -3.56598 2.9892 5.01945 -4.39665 3.76501 6.3022 -4.30124 3.72838 6.38148 -4.24985 3.73101 6.52528 -4.44492 3.96461 7.04869 -3.4382 3.07096 5.70184 -3.34047 3.02275 5.73772 -2.5947 2.34042 4.65245 -2.56477 2.34714 4.7555 -2.48631 2.3047 4.77126 -3.82378 3.72339 7.57054 -2.47933 2.37821 5.10722 -2.58466 2.53455 5.52586 -2.44395 2.42973 5.42486 -2.29335 2.30996 5.28558 -2.2782 2.34256 5.46519 -2.28726 2.40756 5.72358 -2.20046 2.36131 5.74143 -2.09976 2.29639 5.71344 -2.06712 2.31619 5.88642 -2.10486 2.43558 6.3096 -2.03691 2.42044 6.41383 -1.9234 2.34062 6.35443 -2.14425 2.76028 7.62336 -1.845 2.40453 6.83237 -1.27614 1.57416 4.65183 -1.22029 1.54928 4.683 -1.5943 2.32181 7.10683 -1.33489 1.95079 6.14289 -1.24447 1.88816 6.10271 -0.98119 1.419 4.72174 -0.916024 1.37198 4.68063 -0.843871 1.30014 4.552 -0.789367 1.27119 4.56517 -0.734705 1.2471 4.59655 -0.676716 1.20738 4.56882 -0.621246 1.17697 4.57886 -0.565115 1.1404 4.55837 -0.512132 1.22863 5.08267 -0.440119 1.33444 5.72472 -0.369718 1.28135 5.67339 -0.294612 1.2534 5.73773 -0.219609 1.21909 5.78163 -0.13653 1.20154 5.9119 -2.48804 0.922175 -0.950593 -2.54366 0.954229 -0.942382 -2.62059 0.992966 -0.952492 -2.68365 1.02882 -0.947464 -2.75401 1.06722 -0.946784 -2.8393 1.11134 -0.956456 -2.91891 1.15346 -0.957161 -2.99093 1.19394 -0.94953 -3.08569 1.24447 -0.95748 -3.18095 1.29454 -0.961999 -3.27719 1.34604 -0.963481 -3.38938 1.40457 -0.972863 -3.49392 1.46162 -0.97313 -3.61532 1.52568 -0.9803 -3.73004 1.58805 -0.978234 -3.87667 1.66448 -0.991871 -4.00049 1.7327 -0.986232 -4.16462 1.81858 -0.99926 -4.31348 1.89971 -0.997655 -4.48863 1.99275 -1.00356 -4.6805 2.09485 -1.01161 -4.88153 2.20264 -1.01676 -5.10762 2.32332 -1.02615 -5.34468 2.44962 -1.03074 -5.60709 2.59123 -1.03762 -5.8611 2.73031 -1.0313 -6.19391 2.90688 -1.04392 -6.53563 3.09154 -1.04742 -6.9133 3.29493 -1.04939 -7.34302 3.52702 -1.05345 -7.83484 3.79179 -1.05883 -8.414 4.10327 -1.06907 -9.08109 4.46235 -1.07909 -9.7756 4.83972 -1.06951 -10.8301 5.4025 -1.10901 -12.0787 6.07036 -1.14453 -13.9894 7.08202 -1.24433 -19.1501 9.84 -1.39889 -22.5911 11.6976 -1.42351 -25.3705 13.2401 -1.25452 -37.0877 19.6578 -0.924024 -42.2136 22.5519 -0.392299 -41.8785 22.7362 1.22582 -35.2927 19.317 1.87551 -35.2096 19.4258 2.55399 -42.0208 23.3643 3.66964 -41.8445 23.4516 4.47781 -41.8811 23.6585 5.30628 -35.0941 19.9832 5.3012 -35.0436 20.1121 5.99412 -41.7451 24.1467 7.79693 -40.3278 23.5122 8.38457 -40.2081 23.6286 9.18791 -34.9245 20.6869 8.82633 -34.8674 20.8181 9.54261 -5.7799 4.12712 5.35365 -5.66087 4.07993 5.42976 -4.475 3.24092 4.5579 -4.07658 2.97451 4.33255 -3.9793 2.92995 4.37134 -4.0004 2.97659 4.52519 -4.4219 3.33389 5.09983 -4.1816 3.18187 5.00186 -4.38804 3.38144 5.39 -4.14969 3.22953 5.28475 -4.28463 3.37724 5.61606 -4.62036 3.69458 6.21985 -4.79468 3.88785 6.65575 -4.687 3.8468 6.7345 -4.48537 3.72555 6.67912 -4.42323 3.72354 6.81813 -4.30449 3.67108 6.87428 -4.10444 3.54503 6.7976 -4.1225 3.61725 7.07116 -2.67192 2.32146 4.8104 -2.62539 2.31497 4.89073 -2.48849 2.2201 4.80174 -2.51943 2.29005 5.03411 -2.43209 2.24337 5.03908 -2.4692 2.3247 5.3084 -2.39044 2.28817 5.3371 -2.25824 2.19391 5.2364 -2.28362 2.27132 5.51838 -2.26139 2.30072 5.69942 -2.17812 2.26027 5.72414 -2.08315 2.2066 5.71161 -2.05697 2.23753 5.91052 -1.91236 2.11897 5.73359 -2.01286 2.32414 6.40213 -2.16574 2.62082 7.35158 -2.09646 2.62395 7.53218 -1.32399 1.55521 4.64806 -1.26321 1.52563 4.6608 -1.62512 2.21934 6.86748 -1.64818 2.39 7.56591 -1.29981 1.86346 6.07006 -1.00461 1.36928 4.58598 -0.968228 1.38891 4.76386 -0.901137 1.34123 4.71217 -0.826564 1.26477 4.55335 -0.773084 1.24755 4.60404 -0.718221 1.22847 4.65422 -0.655372 1.16853 4.53839 -0.599448 1.14011 4.54732 -0.544845 1.14157 4.68169 -0.483567 1.3433 5.72308 -0.408034 1.31287 5.76986 -0.335737 1.26614 5.73679 -0.257287 1.24289 5.81977 -0.185917 1.19333 5.77424 --0.0366911 1.47818 7.57087 -2.49402 0.856817 -0.949468 -2.54272 0.884583 -0.93474 -2.61397 0.91968 -0.938798 -2.68506 0.955237 -0.940813 -2.74951 0.988981 -0.934176 -2.82126 1.02527 -0.931887 -2.90817 1.06826 -0.939953 -2.98917 1.1083 -0.938952 -3.08527 1.15521 -0.947527 -3.1661 1.1974 -0.941373 -3.26371 1.24521 -0.94387 -3.37727 1.30003 -0.954267 -3.47582 1.35103 -0.950325 -3.60596 1.41369 -0.963928 -3.72206 1.47234 -0.962975 -3.84641 1.53502 -0.963138 -3.97898 1.60183 -0.963932 -4.12921 1.67593 -0.96927 -4.28877 1.75522 -0.973954 -4.45738 1.83884 -0.977298 -4.62579 1.92471 -0.975101 -4.84652 2.03179 -0.99055 -5.05943 2.13793 -0.994549 -5.28141 2.24998 -0.994683 -5.53872 2.37828 -1.00089 -5.78814 2.50587 -0.994681 -6.09048 2.65717 -0.998312 -6.43714 2.82923 -1.006 -6.80205 3.01288 -1.00693 -7.21218 3.21896 -1.00781 -7.68406 3.45544 -1.01126 -8.20933 3.72034 -1.0115 -8.84188 4.03713 -1.01845 -9.50202 4.37172 -1.00794 -10.4297 4.8343 -1.0284 -11.5445 5.39115 -1.04963 -13.2154 6.21554 -1.12295 -14.7683 6.99972 -1.11571 -22.7218 11.0174 -1.05057 -45.6334 22.6459 -0.630753 -45.5406 22.9825 1.09427 -45.5358 23.1725 1.95914 -45.4819 23.3371 2.82557 -24.9537 12.927 2.48382 -24.4784 12.7848 2.92282 -24.1914 12.7394 3.36427 -43.9315 23.8777 8.76817 -48.9547 26.825 10.6494 -4.8465 3.31479 4.78043 -4.23756 2.92023 4.38486 -4.07962 2.83773 4.37086 -3.99303 2.80524 4.41985 -4.26517 3.03235 4.82671 -4.27177 3.07029 4.98207 -4.51502 3.28628 5.40214 -4.42015 3.25258 5.4658 -4.36449 3.24909 5.57499 -4.23923 3.19189 5.60047 -4.96065 3.7984 6.69643 -4.92668 3.82114 6.87698 -4.77791 3.75246 6.90515 -4.44694 3.53357 6.67028 -4.35433 3.50726 6.76214 -4.24024 3.46387 6.82193 -3.40655 2.79862 5.71905 -3.19041 2.65312 5.5547 -2.66834 2.23073 4.83484 -2.56857 2.17632 4.8181 -2.54228 2.18959 4.9368 -2.57119 2.25628 5.17131 -2.49303 2.22293 5.20087 -2.4024 2.17864 5.2033 -2.40645 2.2281 5.41621 -2.26841 2.13414 5.30493 -2.24793 2.16095 5.47558 -2.33095 2.30515 5.9357 -2.18271 2.19883 5.79315 -2.11585 2.18162 5.86843 -1.9901 2.09536 5.76331 -2.09574 2.2952 6.42245 -2.08193 2.35704 6.73453 -2.05613 2.41192 7.03927 -1.36626 1.52853 4.62568 -1.30471 1.50022 4.63859 -1.71547 2.21952 6.94592 -1.7084 2.33038 7.45681 -1.36645 1.85704 6.10351 -1.02414 1.31547 4.44109 -1.00288 1.36266 4.70401 -0.923524 1.28981 4.55687 -0.876017 1.29065 4.66632 -0.800258 1.21024 4.47685 -0.753162 1.21967 4.62314 -0.693439 1.18037 4.58522 -0.632577 1.13196 4.50712 -0.583577 1.1859 4.85557 -0.523466 1.20889 5.09732 -0.452413 1.31346 5.72945 -0.377143 1.27468 5.72613 -0.301509 1.23972 5.74082 -0.225251 1.20666 5.76389 -0.0162833 1.50282 7.57059 -2.54102 0.816192 -0.927026 -2.61285 0.848928 -0.931639 -2.67704 0.88011 -0.927526 -2.73461 0.909433 -0.914955 -2.81537 0.945206 -0.919589 -2.89618 0.982458 -0.922084 -2.97681 1.02028 -0.92205 -3.06587 1.06158 -0.925565 -3.16407 1.1053 -0.931825 -3.25488 1.14842 -0.929555 -3.35383 1.19427 -0.929762 -3.45278 1.24176 -0.927054 -3.56936 1.29499 -0.931416 -3.68567 1.34904 -0.932082 -3.8112 1.40691 -0.933744 -3.95446 1.47189 -0.940729 -4.0976 1.53888 -0.943242 -4.25059 1.60885 -0.944973 -4.42044 1.68751 -0.950497 -4.60876 1.77371 -0.958403 -4.78086 1.85538 -0.951796 -5.005 1.9574 -0.962249 -5.22131 2.05847 -0.961253 -5.46433 2.17122 -0.963268 -5.7161 2.28921 -0.959955 -5.99584 2.42107 -0.957691 -6.32051 2.57127 -0.960232 -6.66326 2.73185 -0.956985 -7.06047 2.91698 -0.957795 -7.49395 3.11926 -0.954125 -8.01805 3.36253 -0.958716 -8.58753 3.6288 -0.955254 -9.2563 3.94156 -0.953558 -9.98824 4.28525 -0.940057 -11.11 4.80106 -0.973604 -12.4046 5.40055 -0.994979 -14.1074 6.18607 -1.03 -16.4641 7.27225 -1.08885 -19.3107 8.59363 -1.11561 -22.7166 10.1867 -1.08938 -24.5325 11.0939 -0.813095 -49.7916 22.8498 -0.910572 -49.7566 23.0362 0.0173075 -49.6961 23.2112 0.946175 -49.6126 23.3752 1.8753 -24.0102 11.4414 1.88541 -23.4509 11.2715 2.30303 -23.812 11.5425 2.76952 -24.6135 12.0306 3.29359 -24.4092 12.0336 3.73788 -23.3273 11.5996 4.06141 -23.7169 11.8922 4.56974 -22.9489 11.6062 4.89793 -23.9806 12.2287 5.54498 -23.8145 12.2474 5.98374 -4.95169 3.12558 4.48532 -4.90268 3.12386 4.58567 -4.90543 3.15758 4.73131 -5.09427 3.31423 5.04345 -4.17084 2.73401 4.3649 -4.07111 2.696 4.40193 -4.65905 3.12478 5.10973 -4.54809 3.08296 5.15552 -4.41831 3.0275 5.17894 -4.43539 3.07529 5.35885 -4.24497 2.97578 5.3102 -4.46128 3.1696 5.73306 -4.28045 3.07721 5.69472 -4.64534 3.38976 6.34575 -4.56833 3.37759 6.45347 -4.48376 3.35929 6.55296 -4.47122 3.3982 6.75601 -4.32997 3.33695 6.77834 -2.78648 2.14118 4.60504 -2.7098 2.11169 4.62963 -2.73171 2.16343 4.81919 -2.74864 2.21274 5.0113 -2.52978 2.06099 4.78319 -2.47408 2.04837 4.84325 -2.56169 2.16549 5.19347 -2.50658 2.15655 5.27197 -2.45723 2.15481 5.36675 -2.37959 2.12654 5.40117 -2.34103 2.13644 5.52948 -2.4482 2.2982 6.04232 -2.22348 2.1205 5.70739 -2.13222 2.07872 5.71105 -2.06497 2.0633 5.78436 -1.96609 2.0118 5.75737 -2.06438 2.19762 6.40093 -2.18637 2.43309 7.21595 -1.41569 1.50799 4.63133 -1.34845 1.47622 4.62578 -1.29722 1.46429 4.68438 -1.67268 2.1197 6.87965 -1.69602 2.28225 7.56975 -1.34484 1.80455 6.1337 -1.25495 1.75862 6.11898 -0.977474 1.31234 4.66918 -0.910607 1.26958 4.61619 -0.839437 1.21142 4.50407 -0.788385 1.20773 4.59248 -0.730814 1.18219 4.60321 -0.680677 1.19917 4.78734 -0.61176 1.11407 4.54291 -0.561392 1.20377 5.05711 -0.495191 1.3428 5.83589 -0.417184 1.30581 5.83288 -0.342658 1.25449 5.75988 -0.264875 1.22394 5.78308 -0.189361 1.18545 5.76569 --0.0344926 1.47363 7.56168 -2.59405 0.775916 -0.910896 -2.67354 0.807798 -0.920603 -2.73937 0.837795 -0.915176 -2.80603 0.868016 -0.907682 -2.8872 0.901935 -0.910632 -2.96938 0.937139 -0.911227 -3.04397 0.970722 -0.903387 -3.14279 1.01193 -0.910882 -3.23399 1.05161 -0.909554 -3.3343 1.09377 -0.910679 -3.42626 1.1355 -0.90359 -3.5516 1.1873 -0.914483 -3.66928 1.23763 -0.916261 -3.78885 1.28936 -0.914104 -3.91547 1.34439 -0.912986 -4.06054 1.40536 -0.916874 -4.22326 1.47368 -0.925014 -4.36999 1.53839 -0.919035 -4.54235 1.61201 -0.920559 -4.73341 1.69411 -0.924663 -4.9424 1.78213 -0.929488 -5.16172 1.87665 -0.931205 -5.38966 1.97514 -0.928759 -5.64523 2.08524 -0.928523 -5.9105 2.20042 -0.922644 -6.22078 2.33368 -0.922738 -6.54897 2.47616 -0.917723 -6.9147 2.63472 -0.911998 -7.33553 2.81693 -0.908747 -7.81098 3.02255 -0.904757 -8.36047 3.25905 -0.901509 -8.99224 3.5321 -0.897302 -9.63258 3.8137 -0.87208 -10.6034 4.22802 -0.886132 -11.7773 4.72988 -0.899281 -13.4101 5.42437 -0.94004 -15.1254 6.16435 -0.931587 -21.8029 9.09862 -0.647744 -24.7818 10.4265 -0.434008 -49.9621 21.3295 -0.127014 -49.893 21.4976 0.793417 -49.8539 21.6803 1.71391 -25.155 11.0773 1.83758 -24.0423 10.686 2.24385 -23.2554 10.432 2.63287 -23.0922 10.4518 3.05011 -23.1678 10.5788 3.4895 -24.8976 11.4642 4.14524 -23.4664 10.9053 4.40721 -23.4277 10.9833 4.84864 -23.7833 11.2483 5.36542 -24.5362 11.7046 5.98228 -25.6269 12.3313 6.70987 -25.5722 12.4139 7.20518 -5.24014 3.0763 4.4759 -5.05256 3.02568 4.61572 -5.06351 3.063 4.76825 -5.24345 3.20589 5.06927 -5.12889 3.1685 5.12705 -4.11194 2.56435 4.35309 -4.03847 2.54541 4.41213 -3.90599 2.48788 4.41217 -3.81306 2.45618 4.44725 -4.40524 2.87584 5.21242 -4.2936 2.83564 5.24998 -4.1824 2.79577 5.28462 -4.82713 3.27509 6.22289 -4.47723 3.07368 5.98894 -4.82639 3.36401 6.6356 -4.48083 3.16262 6.39168 -4.58505 3.28463 6.74985 -3.44645 2.52432 5.49812 -3.35833 2.49665 5.54313 -2.75945 2.0672 4.74812 -2.83044 2.15797 5.0274 -2.62555 2.02758 4.83282 -2.58963 2.03448 4.93466 -2.62004 2.09875 5.16941 -2.63139 2.14847 5.38218 -2.5444 2.11631 5.40188 -2.49558 2.11735 5.50563 -2.43029 2.10371 5.57466 -2.38482 2.1105 5.69494 -2.31505 2.09454 5.76263 -2.32491 2.16134 6.05089 -2.20807 2.10029 6.00201 -2.04784 1.98902 5.80603 -2.13875 2.15771 6.40377 -2.04488 2.12278 6.43231 -1.45952 1.47975 4.61846 -1.39173 1.45025 4.61308 -1.33581 1.43455 4.65296 -1.75355 2.10308 6.9215 -1.76609 2.23919 7.52693 -1.56425 2.04512 7.02893 -1.32206 1.75622 6.17242 -0.991361 1.2478 4.47593 -0.947187 1.25504 4.59486 -1.05313 1.63078 6.12788 -0.848081 1.26263 4.83225 -0.765542 1.17343 4.58218 -0.793368 1.51208 6.09638 -0.650058 1.1361 4.63916 -0.599868 1.20453 5.0561 -0.534815 1.19017 5.12193 -0.461824 1.30228 5.78304 -0.38434 1.26704 5.77896 -0.306956 1.23044 5.76337 -0.231611 1.19205 5.73652 -0.0180414 1.49839 7.58169 -2.58825 0.707412 -0.903566 -2.66107 0.73589 -0.907245 -2.72724 0.762576 -0.902175 -2.79448 0.790438 -0.895235 -2.87647 0.822904 -0.899132 -2.95901 0.854753 -0.900279 -3.04258 0.887887 -0.89907 -3.12619 0.922544 -0.895528 -3.22711 0.960604 -0.900513 -3.31966 0.998276 -0.897089 -3.42133 1.03844 -0.896118 -3.52276 1.0793 -0.892034 -3.64183 1.12588 -0.895021 -3.7699 1.17528 -0.899002 -3.89056 1.22413 -0.894259 -4.0368 1.28033 -0.899451 -4.17464 1.33631 -0.895554 -4.34011 1.40049 -0.900087 -4.49691 1.46361 -0.894848 -4.68971 1.53861 -0.900713 -4.88324 1.61582 -0.900136 -5.10412 1.70212 -0.904098 -5.33482 1.79312 -0.904071 -5.57533 1.88893 -0.899569 -5.83379 1.9922 -0.893359 -6.12986 2.10964 -0.890425 -6.46243 2.24186 -0.889138 -6.80521 2.37871 -0.878679 -7.20297 2.53792 -0.872054 -7.65597 2.71803 -0.865827 -8.19319 2.931 -0.864036 -8.77703 3.16364 -0.853553 -9.42491 3.42397 -0.835712 -10.2786 3.76139 -0.833516 -11.3076 4.16794 -0.830795 -12.7554 4.73503 -0.855742 -14.3989 5.38513 -0.854532 -16.8427 6.34362 -0.887818 -19.5174 7.40784 -0.854904 -21.8898 8.37797 -0.69961 -22.4649 8.68109 -0.344495 -54.7433 21.4258 -0.389148 -54.7426 21.6378 0.607139 -54.799 21.8721 1.60667 -24.1216 9.77413 1.72219 -24.0384 9.83324 2.15604 -24.2704 10.0221 2.60946 -24.1351 10.0604 3.0427 -23.6357 9.94617 3.43546 -24.2113 10.282 3.94379 -23.7075 10.1642 4.32417 -24.1006 10.4266 4.83292 -24.6442 10.7599 5.38741 -24.816 10.9346 5.893 -24.2952 10.8063 6.25786 -26.1906 11.8622 7.70139 -25.459 11.6408 8.01933 -5.33926 2.93616 4.46591 -5.20872 2.89364 4.51029 -5.15173 2.89099 4.60676 -5.09287 2.8886 4.70221 -4.17262 2.39362 4.08379 -4.19267 2.43073 4.22081 -4.107 2.40609 4.2682 -4.13491 2.44949 4.41959 -4.7269 2.83306 5.12198 -3.90681 2.36751 4.45606 -3.80623 2.3339 4.48289 -4.32511 2.68548 5.17677 -4.25086 2.6722 5.25205 -4.34956 2.77036 5.52915 -3.7814 2.43652 5.01395 -3.64674 2.3797 4.99959 -4.52061 3.00087 6.29776 -4.56365 3.07495 6.56454 -3.54134 2.44783 5.51126 -3.46756 2.43315 5.58031 -3.08585 2.19235 5.15892 -2.85478 2.05554 4.9477 -2.62656 1.91783 4.72035 -2.60793 1.93691 4.84581 -2.54976 1.92694 4.90561 -2.71626 2.09921 5.40826 -2.6727 2.10626 5.52194 -2.61068 2.0992 5.60125 -2.63442 2.16659 5.87859 -2.47806 2.07767 5.74939 -2.44864 2.10311 5.92308 -2.45523 2.16499 6.20398 -2.30919 2.08199 6.08532 -2.23766 2.072 6.16951 -2.2995 2.20439 6.67913 -2.12146 2.08436 6.44495 -1.49751 1.44289 4.58747 -1.43164 1.41799 4.59138 -1.37787 1.40788 4.64053 -1.81661 2.05661 6.87923 -1.71373 2.01845 6.8915 -1.60146 1.9661 6.85456 -1.48639 1.90696 6.78657 -1.32964 1.76687 6.42035 -0.984049 1.23736 4.57395 -1.12374 1.65121 6.26009 -0.857712 1.17893 4.53138 -0.802984 1.17004 4.59036 -0.853002 1.53371 6.21116 -0.712381 1.25565 5.16344 -0.63935 1.20602 5.06487 -0.572277 1.18311 5.08201 -0.506038 1.29881 5.7533 -0.427036 1.27317 5.77849 -0.349806 1.23566 5.74349 -0.271495 1.20521 5.74628 -0.190402 1.18424 5.79657 --0.0339796 1.47252 7.57215 -2.6384 0.663717 -0.887083 -2.72011 0.692054 -0.89603 -2.77948 0.715755 -0.883083 -2.84715 0.741674 -0.87485 -2.93055 0.772004 -0.877235 -3.02192 0.803866 -0.882969 -3.11503 0.835912 -0.885737 -3.20002 0.8685 -0.880392 -3.30109 0.903798 -0.883302 -3.40337 0.941487 -0.883372 -3.50616 0.97869 -0.880108 -3.62659 1.0216 -0.884013 -3.73841 1.06318 -0.879216 -3.87685 1.1117 -0.885204 -3.99957 1.1575 -0.877464 -4.13859 1.20867 -0.875066 -4.30502 1.26705 -0.881095 -4.46398 1.3251 -0.877428 -4.63179 1.38644 -0.872614 -4.83556 1.45981 -0.878321 -5.05917 1.53873 -0.884215 -5.274 1.61686 -0.879072 -5.48853 1.69757 -0.866928 -5.75995 1.79529 -0.866928 -6.03068 1.89508 -0.857782 -6.33876 2.00819 -0.85123 -6.69388 2.13633 -0.847752 -7.06777 2.27387 -0.837291 -7.48964 2.42805 -0.826089 -7.99419 2.61197 -0.820992 -8.53714 2.81144 -0.806475 -9.19237 3.04946 -0.796206 -9.88573 3.30553 -0.769904 -10.9265 3.67931 -0.779358 -12.0425 4.08595 -0.763283 -13.8349 4.72488 -0.800268 -15.5336 5.347 -0.761597 -18.7576 6.49863 -0.816146 -21.8658 7.63574 -0.744789 -22.3373 7.8817 -0.3888 -22.9353 8.17437 -0.0211864 -24.554 9.20151 2.09271 -24.1862 9.15581 2.51206 -24.3333 9.3039 2.96118 -25.2172 9.73388 3.49124 -25.1051 9.78736 3.93943 -24.0248 9.46252 4.25414 -23.5514 9.36996 4.62544 -29.9636 12.1299 6.75156 -27.828 11.3833 6.86736 -27.4301 11.332 7.31011 -27.2607 11.3736 7.80007 -27.1187 11.4267 8.29679 -26.2049 11.1535 8.56776 -26.5557 11.413 9.20444 -26.3474 11.4362 9.67572 -28.6341 12.5463 11.0317 -23.5453 11.0882 12.8427 -22.8203 10.9761 13.5587 -24.5992 12.0837 15.7811 -23.2287 11.5391 15.5404 -23.2079 11.6557 16.1385 -5.47269 2.81186 4.48213 -5.3937 2.80041 4.56558 -5.22418 2.74257 4.58072 -5.17284 2.74477 4.68196 -5.11231 2.74364 4.77648 -4.28256 2.35389 4.34796 -4.13289 2.29779 4.33941 -4.10638 2.30961 4.44073 -4.1303 2.35026 4.59441 -3.95466 2.27878 4.55162 -3.96168 2.31044 4.69239 -3.87073 2.28549 4.73196 -3.89561 2.33033 4.90192 -3.63942 2.20525 4.74765 -3.64974 2.24114 4.90262 -3.55141 2.21176 4.92721 -4.41506 2.79512 6.2234 -4.2728 2.74498 6.23225 -4.19713 2.73769 6.32961 -3.53394 2.33683 5.555 -3.20472 2.1491 5.22925 -3.03205 2.06483 5.12328 -2.94073 2.03552 5.14139 -2.83593 1.99565 5.13302 -2.83156 2.03007 5.30388 -2.77426 2.02626 5.38425 -2.69358 2.00466 5.42186 -2.78843 2.12354 5.82465 -2.60639 2.02229 5.65603 -2.55265 2.02462 5.76014 -2.67705 2.183 6.30258 -2.47405 2.05996 6.06464 -2.34371 1.99793 5.9898 -2.2773 1.99268 6.08276 -2.19009 1.96955 6.12034 -2.16446 2.01028 6.35706 -1.53678 1.4076 4.56558 -1.47552 1.39066 4.58807 -1.41777 1.37566 4.61902 -1.83315 1.9514 6.65013 -1.76552 1.96074 6.81197 -1.68549 1.95789 6.93565 -1.61611 1.97527 7.13419 -1.07645 1.2326 4.51952 -1.02389 1.22593 4.58166 -0.958903 1.19792 4.55642 -0.89353 1.16669 4.52026 -0.855623 1.20139 4.75372 -0.902427 1.51517 6.17072 -0.809223 1.45997 6.06677 -0.678123 1.19649 5.03486 -0.611006 1.17977 5.07167 -0.545256 1.19597 5.26376 -0.470763 1.28919 5.83703 -0.392703 1.23575 5.71408 -0.311922 1.21717 5.76612 -0.234598 1.18327 5.73831 -0.0190747 1.49614 7.60253 -2.70353 0.620056 -0.882958 -2.77094 0.643435 -0.877151 -2.83918 0.667016 -0.869375 -2.92292 0.694035 -0.872118 -3.00744 0.721388 -0.872307 -3.09298 0.750027 -0.870141 -3.17834 0.779237 -0.865445 -3.28003 0.812044 -0.869493 -3.37507 0.84308 -0.864694 -3.47848 0.877791 -0.862569 -3.59097 0.915078 -0.862506 -3.70417 0.952941 -0.858821 -3.83546 0.994519 -0.861206 -3.96668 1.03799 -0.859604 -4.11613 1.08642 -0.863005 -4.24889 1.13235 -0.852798 -4.40883 1.18452 -0.850919 -4.58686 1.24209 -0.852097 -4.79238 1.30836 -0.859564 -4.97168 1.36919 -0.848536 -5.20696 1.4454 -0.853565 -5.43342 1.52093 -0.847071 -5.66948 1.60022 -0.836292 -5.95198 1.69368 -0.833475 -6.25401 1.79361 -0.82676 -6.56562 1.89898 -0.812748 -6.93413 2.02074 -0.80375 -7.34969 2.1592 -0.794811 -7.8035 2.31033 -0.780436 -8.33323 2.48644 -0.767692 -8.94742 2.69008 -0.754359 -9.6004 2.90916 -0.726618 -10.5183 3.21107 -0.722725 -11.5505 3.5529 -0.703912 -13.1142 4.05999 -0.722504 -14.7453 4.60016 -0.693584 -17.0405 5.35503 -0.675202 -19.6571 6.22651 -0.602264 -22.0988 7.06235 -0.423699 -22.4972 7.269 -0.0558525 -23.3448 7.62181 0.312251 -23.7946 7.85273 0.71668 -23.7133 7.91254 1.13593 -23.2467 7.84391 1.54468 -28.0744 10.071 4.68061 -27.0183 9.79911 5.03617 -30.2134 11.0589 6.07677 -26.9925 9.99641 6.03279 -26.866 10.0538 6.51304 -29.9011 11.2944 7.71062 -28.7297 10.9701 7.995 -27.4798 10.6063 8.2185 -28.7835 11.2214 9.12906 -26.8814 10.7069 9.65532 -23.4318 9.44354 9.00278 -24.1194 9.8205 9.73702 -23.811 9.79874 10.1198 -23.0319 9.58116 10.3034 -27.3456 11.4813 12.6672 -25.1516 10.6802 12.268 -25.478 10.9349 12.9845 -19.4882 8.4739 10.5597 -19.2537 8.4649 10.8847 -19.3733 8.61096 11.4025 -22.4019 10.0562 13.6046 -22.4972 10.2133 14.2123 -22.7917 10.4639 14.9621 -23.7945 11.0472 16.2013 -23.2917 10.9425 16.4888 -21.7736 10.3551 16.0482 -5.30721 2.59706 4.56611 -5.22683 2.58604 4.64495 -5.13027 2.56883 4.7101 -4.3686 2.2444 4.34847 -4.27985 2.22487 4.39653 -4.17697 2.19839 4.42969 -4.93132 2.62109 5.2817 -4.10404 2.21395 4.62025 -4.04541 2.2104 4.69522 -4.34975 2.40572 5.15956 -3.86176 2.16593 4.77309 -3.71389 2.11164 4.74504 -3.73141 2.15143 4.90717 -3.68463 2.15461 4.99836 -3.98172 2.36255 5.53516 -4.48575 2.70318 6.38655 -3.6659 2.24209 5.45353 -3.53881 2.19926 5.44479 -3.36671 2.126 5.36217 -3.14819 2.01941 5.19512 -2.94094 1.91759 5.02907 -2.87974 1.91032 5.09317 -2.90557 1.96425 5.31316 -2.82074 1.94328 5.34375 -2.79713 1.96596 5.49074 -2.70632 1.9401 5.51089 -2.7167 1.99216 5.74393 -2.61894 1.96167 5.75371 -2.54007 1.94666 5.80498 -2.52815 1.98749 6.02306 -2.52315 2.03847 6.27812 -2.32981 1.92687 6.04099 -2.24573 1.90905 6.08768 -2.14038 1.8704 6.06934 -1.58346 1.37933 4.57123 -1.51477 1.35543 4.56647 -1.46043 1.34764 4.61598 -1.82274 1.82186 6.33736 -1.87939 1.97783 7.00511 -1.79632 1.97601 7.13018 -1.6519 1.8945 6.9598 -1.55588 1.87402 7.01484 -1.06572 1.21497 4.59907 -1.02148 1.22742 4.72782 -0.922799 1.13981 4.46108 -0.860624 1.11372 4.43325 -0.953858 1.49812 6.14993 -0.864025 1.46553 6.13374 -0.722104 1.21096 5.12173 -0.650764 1.17815 5.08096 -0.581964 1.1617 5.10689 -0.514756 1.28473 5.80729 -0.433769 1.25649 5.8024 -0.355766 1.2171 5.73713 -0.275712 1.19209 5.73876 -0.191925 1.17885 5.80788 --0.0327346 1.46919 7.57279 -2.6905 0.551045 -0.876565 -2.75149 0.571972 -0.864927 -2.82754 0.594281 -0.864095 -2.89645 0.616893 -0.855125 -2.97316 0.639931 -0.849988 -3.05908 0.665149 -0.848665 -3.16136 0.693896 -0.856378 -3.25624 0.722062 -0.855466 -3.34278 0.749796 -0.846339 -3.44755 0.780827 -0.845132 -3.56021 0.813675 -0.846008 -3.67382 0.848029 -0.843555 -3.79743 0.884896 -0.842365 -3.92981 0.923628 -0.84197 -4.05381 0.962038 -0.832876 -4.19582 1.0044 -0.828781 -4.35697 1.05171 -0.828692 -4.52698 1.10224 -0.827748 -4.70678 1.15595 -0.825147 -4.89731 1.21271 -0.820379 -5.1242 1.27967 -0.824254 -5.34329 1.34563 -0.81697 -5.57198 1.41529 -0.805695 -5.84768 1.49682 -0.802644 -6.14198 1.58491 -0.7964 -6.43771 1.67576 -0.780188 -6.78106 1.77934 -0.767313 -7.15285 1.89248 -0.750366 -7.60023 2.0266 -0.739516 -8.0968 2.17577 -0.723982 -8.6493 2.34258 -0.703534 -9.30795 2.54063 -0.68429 -10.0812 2.77286 -0.662279 -11.113 3.07888 -0.654424 -12.269 3.42527 -0.627723 -13.9816 3.92954 -0.628932 -15.6356 4.43065 -0.563377 -19.4584 5.54379 -0.630109 -21.992 6.32251 -0.470249 -22.6659 6.59213 -0.123127 -23.7263 6.97732 0.234807 -23.5693 7.01539 0.651368 -23.1182 6.96655 1.06246 -68.3182 20.7913 3.53819 -23.7263 7.3998 2.31245 -29.3762 9.23413 3.14365 -23.1952 7.40458 3.1045 -28.8601 9.28436 4.13716 -22.1957 7.25254 3.80683 -30.8956 10.156 5.47755 -27.6873 9.21847 5.514 -21.9881 7.43022 4.97791 -21.4407 7.32859 5.27277 -22.0295 7.60977 5.80192 -22.5879 7.8856 6.35006 -26.4715 9.32309 7.78831 -26.7643 9.52882 8.38029 -20.8595 7.53597 7.13388 -19.1012 6.98595 6.98146 -19.0495 7.04429 7.3429 -20.2008 7.54653 8.14074 -20.0747 7.58298 8.50528 -22.5077 8.58416 9.90142 -22.9483 8.84869 10.5634 -19.8995 7.7735 9.69593 -19.9598 7.8858 10.1574 -25.1624 10.0284 13.1566 -19.1369 7.73855 10.6277 -19.4167 7.94096 11.2186 -18.7443 7.75919 11.2969 -22.9829 9.60558 14.2341 -22.5791 9.55115 14.5532 -22.7826 9.75394 15.2523 -21.4947 9.31987 14.9848 -21.79 9.5634 15.7569 -5.43986 2.47344 4.58973 -5.32789 2.45213 4.64705 -5.25339 2.44691 4.73046 -5.17705 2.44181 4.81227 -4.3251 2.1001 4.36589 -4.22894 2.07958 4.4054 -4.13295 2.05856 4.44267 -4.07072 2.05336 4.51045 -4.1328 2.1118 4.70427 -4.10571 2.12535 4.81328 -4.18973 2.19825 5.0473 -4.11748 2.1906 5.11663 -4.01916 2.16952 5.1559 -3.98013 2.18097 5.26584 -3.88085 2.15843 5.30198 -3.77002 2.12986 5.32063 -3.63652 2.08745 5.30618 -3.65837 2.13481 5.50495 -3.55648 2.11034 5.53372 -3.39835 2.05177 5.47278 -3.42062 2.10166 5.6893 -3.4062 2.13206 5.85919 -2.86369 1.82302 5.12433 -2.77219 1.79885 5.13654 -2.73502 1.81013 5.24789 -2.81213 1.90272 5.58889 -2.732 1.8878 5.63398 -2.60606 1.84 5.58236 -2.54592 1.83994 5.66732 -2.46765 1.82649 5.71664 -2.62341 2.00159 6.35189 -2.56738 2.01422 6.49278 -2.45258 1.97801 6.47996 -1.90373 1.5515 5.18116 -2.25546 1.93186 6.53871 -1.56784 1.33456 4.60022 -1.49772 1.31289 4.59434 -1.89677 1.79342 6.37992 -1.97058 1.96015 7.09474 -1.8678 1.93837 7.13548 -1.70293 1.83805 6.88035 -1.60389 1.81644 6.91619 -1.10295 1.19497 4.58765 -1.04766 1.189 4.63977 -0.984866 1.17357 4.65246 -0.896709 1.10445 4.44184 -0.8561 1.13266 4.63576 -0.917156 1.46026 6.16171 -0.824169 1.41712 6.08579 -0.690559 1.17747 5.09991 -0.621197 1.15622 5.09697 -0.553707 1.17181 5.26882 -0.477536 1.27556 5.89088 -0.397969 1.2214 5.73735 -0.315927 1.20514 5.7788 -0.239271 1.17106 5.72045 -0.0222752 1.48733 7.59427 -2.73006 0.50105 -0.852459 -2.79872 0.521078 -0.846111 -2.87618 0.541229 -0.843863 -2.95347 0.561885 -0.839378 -3.03901 0.584935 -0.838828 -3.11718 0.607317 -0.830042 -3.21246 0.632018 -0.830167 -3.31687 0.65914 -0.833037 -3.41293 0.685851 -0.827597 -3.51786 0.71412 -0.824314 -3.63261 0.743798 -0.822776 -3.7564 0.77616 -0.822816 -3.87991 0.80938 -0.819061 -4.00532 0.843977 -0.811468 -4.13948 0.880484 -0.804476 -4.30086 0.923127 -0.806299 -4.47282 0.967622 -0.806827 -4.63536 1.01219 -0.797998 -4.84489 1.06535 -0.803031 -5.02794 1.11616 -0.790281 -5.26603 1.17851 -0.792895 -5.48733 1.23864 -0.780637 -5.73636 1.30611 -0.770845 -6.01398 1.38104 -0.761844 -6.32105 1.46352 -0.752149 -6.61942 1.54665 -0.729474 -6.99399 1.64664 -0.716854 -7.40701 1.75871 -0.701424 -7.85881 1.8812 -0.680528 -8.38733 2.02339 -0.66052 -8.99347 2.18689 -0.63749 -9.648 2.36619 -0.602086 -10.6004 2.61774 -0.592061 -11.6409 2.89696 -0.561159 -13.1922 3.30439 -0.558271 -14.7443 3.72292 -0.500883 -17.0405 4.33478 -0.456287 -19.7696 5.06929 -0.362127 -22.2053 5.74952 -0.155652 -23.6465 6.19319 0.174165 -23.8827 6.41989 0.992275 -23.2894 6.34518 1.39748 -23.1053 6.37681 1.79621 -20.8916 5.85466 2.08524 -20.1601 5.72488 2.39936 -20.1074 5.78076 2.74772 -20.699 6.01991 3.16363 -20.3936 6.00508 3.49238 -20.4067 6.08273 3.85706 -19.8073 5.9793 4.12676 -20.1971 6.16668 4.55362 -20.1815 6.2356 4.91793 -19.6825 6.15729 5.18039 -21.82 6.89164 6.04646 -21.461 6.86147 6.36388 -19.3735 6.28119 6.19912 -19.1834 6.2936 6.51313 -19.2797 6.39903 6.91361 -18.9682 6.37215 7.18707 -19.1852 6.52037 7.63919 -19.3381 6.64889 8.08185 -20.8736 7.25235 9.08208 -19.7289 6.94282 9.03885 -19.0474 6.78819 9.15601 -19.2523 6.94224 9.65732 -20.4473 7.45464 10.6526 -18.8177 6.95399 10.284 -18.9163 7.07588 10.7616 -19.0962 7.22954 11.297 -19.5436 7.48904 12.0035 -22.3324 8.6499 14.149 -24.2979 9.52329 15.9309 -20.1736 8.02647 13.8583 -22.275 8.96751 15.8045 -21.4161 8.73922 15.7902 -5.19324 2.42256 5.50908 -5.01631 2.37453 5.50181 -4.86217 2.33566 5.51021 -4.44824 2.17252 5.23725 -4.30182 2.13324 5.23264 -4.13192 2.08145 5.19539 -4.71185 2.40333 6.04197 -3.96152 2.05948 5.30638 -3.83144 2.02485 5.30318 -3.67514 1.9745 5.25871 -3.52038 1.92389 5.20978 -3.44538 1.91533 5.26636 -3.42791 1.9397 5.4086 -3.40103 1.95971 5.54393 -3.02415 1.77584 5.11898 -3.21927 1.92679 5.61892 -2.70258 1.64833 4.90529 -2.73946 1.7048 5.14054 -2.65261 1.6857 5.15751 -2.6905 1.74893 5.42152 -2.67941 1.78177 5.6021 -2.61848 1.78308 5.68762 -2.53964 1.77194 5.7373 -2.48654 1.7807 5.84783 -2.60804 1.92603 6.41509 -2.00009 1.49819 5.07477 -2.03189 1.57046 5.39539 -1.92422 1.52978 5.33406 -1.64802 1.33365 4.717 -1.55644 1.29564 4.64722 -2.11723 1.90523 6.95453 -1.84858 1.71193 6.33985 -1.92048 1.87614 7.06557 -1.80478 1.84225 7.04765 -1.71104 1.83466 7.13211 -1.13949 1.17205 4.57654 -1.0822 1.16566 4.61914 -1.01984 1.15224 4.63192 -0.929408 1.08684 4.42132 -0.889244 1.11098 4.59615 -0.845745 1.1419 4.8098 -0.874107 1.40459 6.08504 -0.732109 1.17631 5.12876 -0.660491 1.15267 5.10656 -0.590446 1.13955 5.13185 -0.5233 1.28795 5.95974 -0.438871 1.26865 5.97354 -0.359795 1.20711 5.7698 -0.279938 1.18001 5.74129 -0.195613 1.16584 5.77994 --0.0314967 1.46588 7.57352 -2.78336 0.450374 -0.840537 -2.84523 0.467395 -0.82641 -2.93034 0.486756 -0.828965 -3.00927 0.506228 -0.823165 -3.09499 0.526451 -0.820833 -3.18271 0.547722 -0.816121 -3.2875 0.571401 -0.819932 -3.38393 0.594713 -0.815238 -3.48112 0.618447 -0.807602 -3.59627 0.644637 -0.8072 -3.7114 0.672548 -0.80359 -3.82723 0.701035 -0.796358 -3.97094 0.7331 -0.79937 -4.09623 0.764094 -0.789018 -4.2505 0.799688 -0.787722 -4.40442 0.83636 -0.78166 -4.5862 0.878286 -0.782829 -4.76949 0.921078 -0.778016 -4.96157 0.967369 -0.771181 -5.18325 1.01908 -0.768709 -5.39617 1.06995 -0.755394 -5.63686 1.12802 -0.745129 -5.91684 1.19336 -0.739027 -6.19733 1.26152 -0.72376 -6.49811 1.33492 -0.704569 -6.84579 1.4182 -0.688121 -7.24238 1.5124 -0.67204 -7.68694 1.61928 -0.654014 -8.18076 1.73708 -0.63088 -8.75189 1.87382 -0.606468 -9.36322 2.02215 -0.569344 -10.1868 2.21695 -0.546024 -11.2149 2.45854 -0.523893 -12.4179 2.74258 -0.488347 -14.1852 3.15363 -0.473371 -15.8253 3.54945 -0.384763 -19.5307 4.40295 -0.394505 -22.739 5.24972 0.144798 -25.0843 5.85656 0.482299 -24.1456 5.72683 0.918919 -23.9026 5.75188 1.33201 -22.8154 5.57671 1.7116 -22.6964 5.62588 2.10032 -23.8886 5.99461 2.57191 -22.9309 5.83939 2.90854 -22.357 5.7753 3.25132 -23.5986 6.1682 3.79205 -20.16 5.36449 3.73734 -22.8799 6.14579 4.51758 -19.9679 5.45513 4.42126 -20.4322 5.65061 4.86973 -20.1394 5.64434 5.17878 -20.4266 5.79667 5.613 -21.5368 6.18144 6.26656 -20.9886 6.10557 6.52254 -20.5694 6.06385 6.7983 -19.4014 5.80043 6.83307 -18.9906 5.75346 7.07334 -19.4323 5.95965 7.59726 -19.1209 5.94064 7.86812 -19.4609 6.12095 8.38384 -29.4123 9.29808 12.8447 -19.5715 6.31453 9.23163 -19.8759 6.49287 9.78142 -19.7406 6.53326 10.1439 -24.456 8.16856 12.9117 -20.3207 6.89812 11.3144 -20.276 6.97459 11.7513 -19.4793 6.79459 11.7707 -18.3597 6.49676 11.5707 -18.4955 6.63213 12.0969 -18.2626 6.63912 12.4046 -20.1935 7.42972 14.1514 -19.7744 7.37939 14.3858 -21.8556 8.2597 16.4104 -21.6616 8.30516 16.8639 -5.42799 2.30946 5.47738 -5.26993 2.27659 5.49482 -5.00967 2.19913 5.40823 -5.03704 2.2434 5.59865 -4.8627 2.23398 5.75534 -4.85393 2.26417 5.92086 -4.83399 2.29163 6.0801 -4.1556 2.0109 5.45105 -3.92063 1.93124 5.32326 -3.75528 1.88278 5.27203 -3.62202 1.84916 5.25469 -3.56285 1.85119 5.33565 -3.44166 1.82199 5.32869 -3.13211 1.69182 5.03037 -3.15834 1.73788 5.23315 -3.73692 2.09357 6.35774 -2.92494 1.67526 5.1894 -2.80319 1.63958 5.15056 -2.76649 1.65275 5.26142 -2.63413 1.60824 5.19264 -2.67032 1.66889 5.45742 -2.64074 1.69167 5.60282 -2.59913 1.70658 5.73141 -2.50453 1.68755 5.74449 -2.2069 1.52203 5.2545 -2.12896 1.50942 5.27785 -1.97502 1.43634 5.09119 -1.94411 1.45878 5.23841 -1.70541 1.30936 4.75965 -1.6258 1.28652 4.73678 -2.18954 1.85763 6.96851 -1.88854 1.64788 6.26119 -2.04759 1.89148 7.30666 -1.84319 1.76758 6.921 -1.74743 1.7586 6.9862 -1.67629 1.78145 7.18368 -1.55701 1.74539 7.1409 -1.05729 1.13426 4.63055 -0.989817 1.11291 4.60403 -0.921213 1.08952 4.56637 -0.878637 1.11825 4.76044 -0.932906 1.41314 6.19151 -0.783016 1.20123 5.29457 -0.699342 1.14714 5.11615 -0.629222 1.13213 5.12213 -0.57133 1.31193 6.09729 -0.483897 1.28434 6.06247 -0.402992 1.20612 5.76091 -0.320649 1.18989 5.7717 -0.241298 1.16352 5.73217 -0.0230643 1.48311 7.60525 -2.75732 0.381501 -0.828773 -2.83496 0.397147 -0.827756 -2.8975 0.413199 -0.812434 -2.98376 0.429495 -0.813183 -3.07104 0.447099 -0.811479 -3.15838 0.466181 -0.807637 -3.2554 0.485457 -0.806511 -3.36011 0.505444 -0.807952 -3.4579 0.526752 -0.801163 -3.55644 0.548483 -0.791431 -3.6727 0.571739 -0.788639 -3.79778 0.59673 -0.787227 -3.92378 0.623291 -0.782194 -4.05927 0.650595 -0.777444 -4.21277 0.681856 -0.777695 -4.3498 0.711615 -0.76434 -4.52354 0.746576 -0.763095 -4.70685 0.783715 -0.760191 -4.90965 0.824109 -0.758831 -5.09521 0.864256 -0.743796 -5.31814 0.910335 -0.736567 -5.56136 0.959982 -0.728427 -5.8139 1.01253 -0.715416 -6.10471 1.0727 -0.706106 -6.38783 1.13318 -0.68418 -6.70903 1.20184 -0.663425 -7.08863 1.28048 -0.646429 -7.5168 1.36939 -0.628239 -7.97439 1.46534 -0.601738 -8.51091 1.57743 -0.575366 -9.13468 1.70724 -0.546804 -9.80709 1.84981 -0.504961 -10.7725 2.04591 -0.483187 -11.8662 2.27147 -0.444736 -13.4581 2.5925 -0.424857 -14.9332 2.9037 -0.338479 -17.2798 3.38431 -0.268717 -19.9279 3.9388 -0.135919 -22.3771 4.47218 0.0981499 -23.3173 4.72948 0.455866 -24.447 5.03045 0.845174 -25.7082 5.5369 2.15957 -26.225 5.73336 2.63506 -30.9056 6.93218 4.00167 -30.0141 6.83961 4.44071 -20.1598 4.72359 3.65687 -19.3657 4.61062 3.89098 -19.8873 4.79863 4.32135 -19.9096 4.8727 4.67982 -19.8777 4.93546 5.03054 -20.1633 5.07451 5.45449 -20.7598 5.2938 5.96818 -22.3498 5.76562 6.76867 -19.5304 5.1307 6.39304 -19.2356 5.12616 6.67245 -26.5235 7.10513 9.37331 -19.5261 5.34746 7.50909 -31.1623 8.55795 12.082 -20.5138 5.7678 8.65398 -19.2414 5.49454 8.55707 -19.2552 5.57595 8.9559 -19.9161 5.84166 9.64872 -19.6097 5.83554 9.927 -19.5265 5.89309 10.3078 -20.727 6.33444 11.3472 -20.1129 6.2385 11.4834 -19.045 6.00009 11.3479 -18.8422 6.02203 11.6725 -22.3755 7.22965 14.2541 -22.1111 7.25075 14.6327 -21.1145 7.03219 14.5313 -20.6385 6.97935 14.7463 -19.7693 6.79134 14.6708 -21.2245 7.39292 16.2704 -21.5091 7.6055 17.0731 -5.29549 2.13986 5.60089 -5.08916 2.09216 5.56515 -4.59539 1.92799 5.22727 -4.42674 1.88908 5.20293 -4.30512 1.86889 5.22372 -4.2104 1.859 5.2706 -4.10214 1.84372 5.30063 -4.22572 1.92921 5.61225 -4.01174 1.86704 5.51281 -3.75123 1.78084 5.33813 -3.53767 1.71363 5.20983 -3.57237 1.76186 5.42304 -3.40223 1.71278 5.34281 -3.1154 1.60261 5.07178 -3.18558 1.67004 5.34907 -2.90479 1.55745 5.05837 -2.88559 1.57993 5.19453 -2.97439 1.66418 5.53459 -2.69955 1.5467 5.21224 -2.76439 1.62156 5.52908 -2.68061 1.61135 5.56215 -2.60759 1.60783 5.6201 -2.49839 1.58179 5.59709 -2.57435 1.67694 6.00989 -2.11426 1.41024 5.11146 -2.09356 1.43833 5.27791 -1.96284 1.38797 5.15249 -1.76977 1.28513 4.82111 -1.69353 1.26961 4.81729 -2.26662 1.80962 7.00143 -2.15116 1.78498 6.99799 -1.87551 1.60856 6.37024 -1.90402 1.71834 6.90828 -1.83146 1.73793 7.07823 -1.71783 1.71216 7.06644 -1.61488 1.70043 7.10983 -1.4861 1.65236 6.99772 -1.36237 1.60755 6.89223 -0.96227 1.08197 4.60434 -0.894676 1.06324 4.57516 -0.845274 1.07939 4.71051 -0.880054 1.34257 6.0262 -0.739688 1.13918 5.12599 -0.667548 1.12273 5.11251 -0.597998 1.12672 5.20572 -0.529883 1.27639 6.04363 -0.44391 1.24016 5.94859 -0.3631 1.19221 5.78297 -0.282941 1.16513 5.72381 -0.19641 1.16265 5.80097 --0.0305032 1.46059 7.56441 -2.80797 0.328423 -0.816404 -2.88603 0.342193 -0.813801 -2.95696 0.356266 -0.803061 -3.04363 0.370708 -0.802127 -3.13229 0.386242 -0.798619 -3.21164 0.401536 -0.787116 -3.31795 0.418794 -0.789673 -3.41516 0.436875 -0.783945 -3.52198 0.455302 -0.780252 -3.63863 0.475093 -0.778498 -3.75526 0.496628 -0.773439 -3.8824 0.518513 -0.769321 -4.00925 0.541278 -0.761312 -4.14584 0.565715 -0.753881 -4.28212 0.591074 -0.742363 -4.44781 0.619114 -0.738511 -4.63114 0.650554 -0.737709 -4.80723 0.68265 -0.727215 -5.00257 0.717029 -0.718165 -5.23505 0.756388 -0.716725 -5.46019 0.796666 -0.704423 -5.70464 0.840771 -0.691137 -5.97799 0.889073 -0.678804 -6.27143 0.941537 -0.662932 -6.57503 0.997127 -0.640124 -6.927 1.06024 -0.619522 -7.32838 1.13213 -0.598866 -7.7689 1.21112 -0.573199 -8.2779 1.30173 -0.546492 -8.84652 1.40409 -0.513476 -9.48313 1.51958 -0.472707 -10.3555 1.67157 -0.445435 -11.3761 1.85096 -0.40786 -12.6524 2.07429 -0.364655 -14.3615 2.37039 -0.319724 -16.0897 2.68203 -0.217678 -19.4538 3.25918 -0.158774 -22.3423 3.78424 0.0382534 -22.8773 3.94469 0.402463 -24.3024 4.25629 0.775501 -24.5178 4.37204 1.19075 -26.0831 4.98114 2.98854 -23.5104 4.66621 3.60449 -28.4159 5.69285 4.64786 -19.3121 3.99697 3.80716 -18.9021 3.98025 4.07776 -19.6068 4.18837 4.54016 -23.5868 5.07994 5.69073 -19.988 4.40257 5.32419 -23.0889 5.13708 6.42532 -22.6561 5.12413 6.73737 -19.0433 4.40422 6.15911 -18.5851 4.36887 6.37842 -19.0281 4.53819 6.8679 -18.8852 4.57384 7.18328 -18.8572 4.6375 7.53788 -19.1685 4.78302 8.02375 -24.3572 6.1244 10.452 -11.6546 3.0646 5.6707 -19.6385 5.12407 9.38882 -19.4605 5.15735 9.7167 -19.1982 5.16836 10.0034 -21.1076 5.754 11.3748 -21.0756 5.83389 11.8232 -20.3602 5.72973 11.905 -18.7877 5.38171 11.4741 -20.2541 5.88062 12.7845 -20.0509 5.91495 13.143 -20.2909 6.07948 13.7874 -20.1182 6.1259 14.1798 -19.8013 6.12929 14.4762 -19.8828 6.25455 15.0559 -22.0363 7.03138 17.2101 -5.11668 1.90312 5.35539 -5.07934 1.91992 5.47792 -4.73181 1.82549 5.29132 -4.41238 1.73775 5.11485 -4.39096 1.75878 5.24131 -4.34663 1.77166 5.34673 -4.2055 1.7468 5.34193 -4.12699 1.74632 5.40794 -4.01169 1.73058 5.42737 -4.26356 1.86803 5.91989 -3.87503 1.73679 5.58282 -3.64055 1.66869 5.43025 -3.46832 1.62449 5.35082 -3.09634 1.48633 4.9596 -3.17154 1.55218 5.23526 -3.51064 1.74911 5.96178 -2.92719 1.49857 5.17119 -2.82376 1.47971 5.16436 -2.87447 1.54049 5.43698 -2.82245 1.54991 5.53171 -2.78113 1.56622 5.6522 -2.6319 1.52172 5.55317 -2.54684 1.51327 5.58307 -2.47349 1.51139 5.63837 -2.46142 1.54993 5.84524 -2.09537 1.35482 5.15608 -1.93428 1.28848 4.94773 -1.8241 1.25135 4.85488 -1.77093 1.25607 4.92561 -2.1111 1.57361 6.28056 -2.20856 1.72399 6.97523 -1.92412 1.55427 6.33884 -1.95509 1.66038 6.86721 -1.90921 1.70561 7.142 -1.77855 1.66821 7.06393 -1.67992 1.66368 7.12688 -1.54393 1.61357 6.98622 -1.42035 1.57499 6.89065 -0.99407 1.06041 4.58403 -0.930573 1.04894 4.58456 -0.867407 1.03813 4.58363 -0.80898 1.03912 4.64022 -0.780826 1.13804 5.17475 -0.705691 1.11434 5.12269 -0.633838 1.10581 5.13757 -0.576977 1.29654 6.18187 -0.487023 1.25937 6.06741 -0.404162 1.20086 5.83321 -0.322953 1.17318 5.76485 -0.240419 1.15769 5.75367 -0.0250428 1.4715 7.57698 -2.70044 0.250265 -0.804912 -2.77804 0.260433 -0.805025 -2.84873 0.2719 -0.797004 -2.91927 0.283785 -0.787134 -3.01449 0.295765 -0.792922 -3.10254 0.308158 -0.790087 -3.19161 0.321838 -0.784897 -3.27234 0.335063 -0.77159 -3.37881 0.349559 -0.772072 -3.47715 0.36464 -0.764245 -3.58511 0.380067 -0.758454 -3.70192 0.397119 -0.754528 -3.8285 0.415688 -0.751861 -3.95554 0.433948 -0.745082 -4.09232 0.453858 -0.738978 -4.22999 0.475427 -0.728864 -4.38591 0.497993 -0.722551 -4.5612 0.522491 -0.719239 -4.73729 0.548954 -0.710556 -4.93339 0.576469 -0.703291 -5.13825 0.607568 -0.693615 -5.35427 0.639771 -0.680477 -5.60901 0.675924 -0.672953 -5.85444 0.713558 -0.654227 -6.13939 0.755433 -0.638755 -6.41496 0.798964 -0.611303 -6.74941 0.848755 -0.589718 -7.1319 0.905398 -0.568876 -7.5642 0.969013 -0.546103 -8.0269 1.03945 -0.5149 -8.58752 1.12182 -0.486495 -9.1585 1.20941 -0.440817 -9.87761 1.31639 -0.398249 -10.852 1.45673 -0.365986 -11.8871 1.61065 -0.307297 -13.515 1.84168 -0.272942 -14.9738 2.06191 -0.16836 -17.4125 2.41561 -0.0784912 -19.9977 2.8036 0.0884581 -22.51 3.1982 0.34706 -23.2322 3.36824 0.717593 -24.4831 3.61565 1.11518 -25.081 3.77897 1.54304 -26.5362 4.24328 2.93167 -22.4613 3.69837 3.01985 -19.7031 3.3348 3.10854 -20.4971 3.52744 3.54726 -20.5387 3.60144 3.90821 -20.8949 3.72855 4.32357 -18.9329 3.46136 4.33879 -23.6788 4.35585 5.60816 -23.7969 4.45636 6.0566 -27.8369 5.27406 7.4296 -27.2098 5.3484 8.28009 -18.7658 3.81628 6.33691 -18.802 3.88959 6.69823 -18.9621 3.98903 7.10564 -18.8163 4.02783 7.41741 -17.8368 3.89405 7.4209 -17.7782 3.94801 7.74776 -17.2325 3.89698 7.87827 -17.6158 4.04694 8.3905 -18.4943 4.31102 9.148 -19.6691 4.65115 10.0892 -17.5409 4.23827 9.45666 -17.7046 4.34848 9.92029 -18.1929 4.53947 10.5735 -18.2104 4.62108 10.993 -24.6218 6.29565 15.1665 -21.6552 5.6541 13.9395 -18.7177 4.99524 12.5978 -18.8952 5.1287 13.1748 -18.8801 5.21531 13.6403 -19.6649 5.52163 14.687 -18.6206 5.33027 14.4368 -19.2096 5.59335 15.3958 -18.4657 5.47956 15.3414 -18.0903 5.47045 15.5633 -5.28494 1.78879 5.44103 -5.14816 1.77539 5.47138 -4.84599 1.70826 5.3338 -4.67202 1.67976 5.31278 -4.58087 1.6789 5.37197 -4.32611 1.61993 5.24934 -4.26862 1.62959 5.33868 -4.07745 1.59046 5.27118 -4.11155 1.63275 5.47027 -4.17555 1.68822 5.71794 -3.93234 1.62708 5.57332 -3.7191 1.57512 5.45302 -3.5221 1.52749 5.34261 -3.29755 1.46502 5.1784 -3.21171 1.45955 5.21159 -3.14187 1.46021 5.26811 -2.94537 1.40455 5.11453 -2.8483 1.39106 5.1159 -2.80316 1.4026 5.20881 -3.08415 1.57641 5.92163 -2.69725 1.41952 5.37667 -2.69537 1.45667 5.57382 -2.56597 1.42654 5.50695 -2.50937 1.4362 5.59738 -2.48863 1.46713 5.77747 -2.09327 1.27223 5.03407 -1.96685 1.23197 4.91687 -1.88125 1.21658 4.89742 -1.80953 1.20928 4.91336 -2.10731 1.47317 6.0907 -2.25425 1.6498 6.91532 -2.16358 1.65292 6.9943 -1.8733 1.48428 6.3156 -1.90063 1.58822 6.84439 -1.90809 1.68736 7.36683 -1.71734 1.59432 7.00945 -1.66022 1.63977 7.29209 -1.54732 1.62615 7.30433 -1.41812 1.58889 7.19828 -0.958438 1.02131 4.53532 -0.899384 1.0177 4.5639 -0.847287 1.03446 4.68884 -0.885565 1.29276 6.02573 -0.744856 1.10663 5.14246 -0.671722 1.09548 5.13809 -0.602132 1.10353 5.23059 -0.533522 1.24926 6.0489 -0.443505 1.26068 6.17879 -0.364222 1.17576 5.78605 -0.285686 1.14831 5.69666 -0.196712 1.15551 5.8024 --0.0302429 1.45647 7.55498 -2.75483 0.195692 -0.800355 -2.81714 0.20516 -0.786648 -2.88803 0.213733 -0.777136 -2.97492 0.22356 -0.777918 -3.06357 0.233505 -0.776027 -3.1518 0.243071 -0.771409 -3.24106 0.2539 -0.764533 -3.33037 0.266253 -0.755324 -3.42909 0.27789 -0.748439 -3.53647 0.290068 -0.743806 -3.64483 0.303685 -0.736137 -3.77136 0.316799 -0.734503 -3.88116 0.33148 -0.719977 -4.02697 0.346854 -0.719885 -4.15507 0.364011 -0.707021 -4.31121 0.381918 -0.702619 -4.47773 0.400639 -0.697115 -4.65457 0.42026 -0.690119 -4.83124 0.442085 -0.677776 -5.03666 0.465237 -0.67027 -5.2535 0.490421 -0.659599 -5.47975 0.518222 -0.645322 -5.71588 0.546632 -0.626437 -6.0015 0.580251 -0.614499 -6.28718 0.614769 -0.593098 -6.59363 0.652413 -0.567257 -6.94778 0.694655 -0.543322 -7.34294 0.742069 -0.516368 -7.76719 0.794227 -0.48246 -8.29026 0.856662 -0.453174 -8.8533 0.924081 -0.412886 -9.47506 1.00099 -0.36307 -10.3055 1.09822 -0.32059 -11.343 1.21832 -0.275156 -12.6195 1.3665 -0.218969 -14.3023 1.55974 -0.154209 -15.995 1.76452 -0.0322126 -19.2066 2.12969 0.0689671 -23.1747 2.66455 0.645894 -24.7515 2.90761 1.03698 -24.7191 2.98237 1.45505 -24.7097 3.05889 1.87361 -25.1812 3.3529 3.17583 -24.7362 3.37705 3.56101 -22.8198 3.20577 3.75368 -20.345 2.9487 3.80283 -19.0531 2.83749 3.95219 -18.6212 2.8389 4.20791 -17.9926 2.80909 4.41256 -18.0014 2.86987 4.73139 -18.1976 2.95887 5.09605 -24.2332 3.94861 6.91693 -17.7069 3.00432 5.62053 -18.7389 3.23073 6.23803 -18.7048 3.28892 6.57409 -17.6204 3.17287 6.57317 -17.2908 3.17824 6.79297 -17.0223 3.19239 7.02675 -17.6831 3.37213 7.60894 -17.8324 3.46495 8.01704 -17.4651 3.46204 8.21781 -18.2836 3.68444 8.93564 -20.1004 4.1087 10.158 -23.3545 4.83353 12.1657 -16.9109 3.62164 9.38905 -17.3986 3.7904 10.0155 -17.9366 3.97651 10.6996 -21.3587 4.78982 13.0814 -18.7611 4.31103 12.016 -18.941 4.43447 12.5728 -18.7947 4.48619 12.9362 -18.827 4.58052 13.4245 -18.8086 4.66578 13.8897 -20.4204 5.14963 15.5547 -19.3248 4.97939 15.274 -18.9176 4.97517 15.4865 -18.7138 5.02256 15.8566 -6.30756 1.8346 5.93653 -6.24729 1.85269 6.06322 -6.14823 1.85885 6.15693 -6.10528 1.88176 6.30223 -5.97495 1.87893 6.36593 -4.94058 1.60908 5.51589 -4.81816 1.60254 5.5509 -5.41426 1.81798 6.35962 -4.51715 1.56913 5.54692 -4.05342 1.44969 5.17178 -3.95331 1.44438 5.20386 -3.8718 1.44605 5.25641 -4.12438 1.56391 5.74148 -4.06808 1.57708 5.84409 -3.97553 1.57667 5.89876 -3.64434 1.48649 5.6052 -3.36854 1.41193 5.36703 -3.14854 1.3561 5.19468 -3.29273 1.44743 5.59965 -2.97314 1.34678 5.24416 -2.91698 1.35572 5.32152 -3.1106 1.47679 5.86305 -3.09136 1.50757 6.03917 -2.94498 1.47926 5.97093 -2.99116 1.54485 6.2968 -2.65924 1.41999 5.81491 -2.59742 1.43024 5.90697 -2.12131 1.20859 4.99379 -2.02933 1.19345 4.96795 -2.02968 1.23472 5.18767 -2.21036 1.3953 5.94482 -2.25077 1.47884 6.36551 -2.22225 1.52124 6.61191 -2.1992 1.57323 6.906 -1.90627 1.41674 6.2371 -1.9525 1.52997 6.813 -1.89608 1.56573 7.0396 -1.79753 1.56656 7.1032 -1.71555 1.5881 7.26111 -1.58144 1.55272 7.1481 -1.43033 1.4887 6.897 -1.35318 1.52011 7.10824 -1.18863 1.41788 6.65683 -0.868206 0.991434 4.55199 -0.807787 0.989855 4.57858 -0.784066 1.09378 5.15271 -0.710362 1.08391 5.13865 -0.638491 1.08043 5.16266 -0.583151 1.28606 6.29581 -0.491354 1.22697 6.03291 -0.405813 1.18431 5.8567 -0.326217 1.15418 5.73793 -0.241241 1.14943 5.76546 -0.0279978 1.45966 7.54873 -2.7207 0.131829 -0.789297 -2.79133 0.137862 -0.782212 -2.86204 0.145286 -0.773378 -2.94156 0.152811 -0.768742 -3.02959 0.159638 -0.767426 -3.10951 0.167007 -0.757997 -3.1984 0.175625 -0.752088 -3.29673 0.183464 -0.748795 -3.39485 0.191917 -0.742777 -3.49493 0.201551 -0.733796 -3.59481 0.2118 -0.722092 -3.71194 0.221672 -0.716932 -3.82977 0.232099 -0.708247 -3.96695 0.242911 -0.704992 -4.10502 0.255405 -0.697631 -4.25231 0.267756 -0.690064 -4.39073 0.281924 -0.674215 -4.56662 0.296106 -0.669248 -4.74428 0.312019 -0.658887 -4.93127 0.329179 -0.646571 -5.1477 0.34663 -0.638191 -5.37453 0.366461 -0.626183 -5.6018 0.387682 -0.606952 -5.86823 0.410931 -0.591943 -6.15433 0.436264 -0.573781 -6.44095 0.46442 -0.546452 -6.77777 0.494405 -0.521245 -7.14389 0.528475 -0.492002 -7.55916 0.566508 -0.460918 -8.02436 0.608839 -0.42544 -8.5777 0.657711 -0.38991 -9.1817 0.713045 -0.343739 -9.90512 0.778421 -0.293921 -10.847 0.859546 -0.246598 -11.888 0.953095 -0.17794 -13.4655 1.08553 -0.121784 -14.9443 1.2215 -0.00439548 -17.3775 1.43054 0.111166 -20.0588 1.67333 0.300791 -22.6372 1.9244 0.58481 -24.1317 2.10909 0.960954 -26.1075 2.3421 1.39534 -24.9055 2.32341 1.79929 -26.6338 2.55043 2.30427 -22.7497 2.3572 2.88724 -23.4215 2.49206 3.34225 -23.2631 2.55063 3.72416 -22.6345 2.55942 4.03891 -21.5311 2.51526 4.26056 -20.1327 2.43159 4.39503 -22.1358 2.72105 5.1242 -17.6275 2.2725 4.58127 -17.8197 2.3519 4.93547 -18.2653 2.46419 5.36083 -18.6232 2.57012 5.78254 -18.0259 2.55493 5.95311 -17.8368 2.59126 6.22665 -18.2017 2.70065 6.67328 -18.9684 2.87046 7.27342 -17.6181 2.74382 7.15188 -17.3185 2.76185 7.37732 -18.4514 2.9942 8.16434 -18.912 3.13228 8.72191 -19.2037 3.24842 9.23012 -20.5172 3.53284 10.2256 -17.1196 3.04901 9.02091 -17.0952 3.11164 9.36974 -17.3878 3.23005 9.89016 -18.421 3.48328 10.836 -17.9739 3.4776 10.9938 -22.3089 4.36138 13.9755 -16.9064 3.42647 11.1639 -20.0253 4.10944 13.5684 -19.788 4.15196 13.9003 -18.9203 4.06576 13.7955 -19.928 4.36648 15.0057 -19.7526 4.4256 15.4004 -6.68785 1.65446 5.82648 -6.50869 1.64686 5.85947 -6.49668 1.67705 6.02618 -4.51247 1.24223 4.49712 -4.3981 1.23764 4.52068 -4.32106 1.24166 4.57468 -5.88234 1.66149 6.19999 -5.76126 1.66409 6.26542 -5.55724 1.64394 6.24367 -5.39537 1.63477 6.25938 -4.51698 1.42228 5.47708 -4.04925 1.31759 5.10242 -4.03874 1.34218 5.23885 -3.91369 1.33228 5.23928 -3.826 1.33364 5.28291 -3.73173 1.33255 5.31704 -3.71829 1.35724 5.46054 -3.43587 1.29262 5.22693 -3.39954 1.31029 5.33463 -3.38569 1.33623 5.48367 -3.25981 1.32234 5.45883 -3.21035 1.33611 5.55729 -3.0027 1.28842 5.3832 -3.22813 1.4144 5.97635 -3.14812 1.42032 6.041 -2.99269 1.39282 5.95577 -2.81029 1.35106 5.80493 -2.67632 1.3284 5.73829 -2.60802 1.33648 5.81217 -2.50378 1.32691 5.80358 -2.11242 1.16217 5.07351 -2.06461 1.1753 5.16586 -2.27595 1.34262 5.9871 -2.18157 1.33809 5.99939 -2.18237 1.39478 6.3092 -2.20953 1.47688 6.74258 -1.92775 1.34197 6.13029 -2.05609 1.51064 6.99057 -1.91481 1.47855 6.87474 -1.86481 1.52267 7.1392 -1.78546 1.54777 7.30729 -1.61538 1.48028 7.01168 -1.48796 1.45096 6.9055 -1.41441 1.48569 7.12695 -1.33511 1.52364 7.36718 -1.08249 1.27875 6.14286 -0.822079 0.935306 4.38331 -0.828737 1.09372 5.24126 -0.748346 1.07039 5.14926 -0.67566 1.06622 5.15373 -0.606289 1.08133 5.26531 -0.536443 1.21719 6.03457 -0.446843 1.22645 6.12417 -0.370126 1.13786 5.67119 -0.288209 1.1305 5.66952 -0.197982 1.14711 5.79381 --0.0126541 1.41481 7.33966 -2.75552 0.0752937 -0.771981 -2.83456 0.0792825 -0.76977 -2.9057 0.084786 -0.759545 -2.98541 0.0894605 -0.753223 -3.06616 0.0953768 -0.744741 -3.16311 0.0996527 -0.745062 -3.25218 0.105465 -0.737273 -3.35091 0.111471 -0.732199 -3.45017 0.116925 -0.724083 -3.54945 0.12399 -0.713245 -3.65811 0.13045 -0.704245 -3.78519 0.137358 -0.701477 -3.90414 0.144873 -0.690305 -4.04143 0.153055 -0.684392 -4.18012 0.160779 -0.673954 -4.33707 0.169433 -0.667608 -4.49462 0.178971 -0.656277 -4.67229 0.189273 -0.647629 -4.85052 0.20059 -0.633413 -5.05726 0.212304 -0.62374 -5.26449 0.225254 -0.607525 -5.50108 0.238802 -0.593885 -5.73904 0.253612 -0.572513 -6.01612 0.270584 -0.554779 -6.29326 0.28841 -0.527776 -6.61971 0.308061 -0.503989 -6.96658 0.330239 -0.474008 -7.36344 0.354928 -0.443132 -7.78987 0.382242 -0.404787 -8.3147 0.413843 -0.370049 -8.87065 0.448825 -0.322347 -9.52539 0.489638 -0.27035 -10.2594 0.536399 -0.206389 -11.3817 0.597828 -0.159985 -12.7133 0.673254 -0.094987 -14.3043 0.765428 -0.00395668 -16.0846 0.874354 0.130484 -19.2204 1.04975 0.269906 -23.2968 1.35584 0.886632 -25.1495 1.51893 1.29793 -24.4287 1.55758 1.70217 -24.031 1.60975 2.09658 -24.8059 1.88206 3.3933 -30.0118 2.4086 4.92806 -24.9033 2.12035 4.68402 -22.6481 2.02333 4.73867 -19.0377 1.80118 4.46539 -17.6524 1.74428 4.51669 -17.8681 1.81951 4.87378 -18.2984 1.91537 5.29288 -18.3438 1.97951 5.63105 -18.2081 2.02567 5.92453 -18.8897 2.15519 6.45672 -19.13 2.24333 6.88005 -21.0314 2.51316 7.86921 -17.5274 2.19418 7.03326 -17.696 2.27455 7.42978 -17.707 2.33738 7.77627 -17.9685 2.43201 8.23097 -19.1853 2.64994 9.11455 -18.4305 2.62283 9.16106 -17.5815 2.57826 9.13749 -18.0557 2.70963 9.73973 -20.1078 3.0695 11.1862 -17.1459 2.71787 10.0248 -16.8176 2.73747 10.2185 -17.2665 2.8748 10.8598 -17.0023 2.90527 11.0964 -19.1121 3.32049 12.8331 -18.8319 3.35691 13.1096 -18.563 3.39576 13.391 -18.9283 3.54464 14.1198 -18.8664 3.62301 14.5656 -18.9199 3.72358 15.1096 -6.69536 1.48068 5.94513 -6.45384 1.46516 5.92622 -4.48328 1.09942 4.42729 -4.45228 1.11515 4.52186 -4.3669 1.11997 4.56971 -5.72354 1.44082 5.9799 -5.72687 1.47307 6.15963 -4.62985 1.25262 5.22973 -4.41796 1.22926 5.15775 -4.31774 1.23156 5.19602 -4.25548 1.24266 5.27645 -4.24354 1.2672 5.41598 -4.27759 1.30571 5.61704 -3.8455 1.21738 5.24226 -3.78854 1.22937 5.3232 -3.72944 1.24072 5.4036 -3.59949 1.23162 5.38683 -3.60535 1.26333 5.56193 -3.46924 1.25217 5.53294 -3.46326 1.28207 5.70038 -3.246 1.24128 5.53285 -2.98635 1.18165 5.27452 -3.01673 1.22524 5.50582 -3.21689 1.33645 6.06846 -3.15422 1.35153 6.16759 -2.93198 1.30133 5.94878 -2.72216 1.2528 5.73257 -2.62264 1.24751 5.73509 -2.53044 1.24683 5.75335 -2.20795 1.13233 5.20598 -2.12674 1.13055 5.21688 -2.26318 1.24532 5.81683 -2.20673 1.26395 5.93043 -2.21834 1.32388 6.25861 -2.10217 1.30961 6.21309 -1.95762 1.27505 6.06118 -2.13301 1.46567 7.0633 -1.6872 1.20555 5.74744 -1.89091 1.44269 7.00266 -1.79967 1.4548 7.09386 -1.67125 1.43352 7.01006 -1.54396 1.41044 6.91389 -1.45954 1.43185 7.05808 -1.36763 1.44977 7.18163 -1.11364 1.22679 6.01568 -1.01608 1.20861 5.9381 -0.800248 0.930932 4.46788 -0.787092 1.05562 5.1598 -0.713606 1.05175 5.15469 -0.642947 1.06321 5.23698 -0.585111 1.24101 6.23295 -0.492548 1.19424 5.99814 -0.407456 1.16672 5.87015 -0.328741 1.12925 5.68156 -0.245897 1.12803 5.69828 -0.0316618 1.4446 7.5008 -2.71894 0.0140238 -0.761485 -2.78961 0.0159695 -0.753782 -2.87609 0.0181294 -0.756564 -2.94743 0.0207608 -0.744751 -3.03648 0.023286 -0.742696 -3.11644 0.0265893 -0.732552 -3.20587 0.0290025 -0.725509 -3.304 0.0318239 -0.721302 -3.40268 0.0340719 -0.714151 -3.51121 0.0375964 -0.709328 -3.61162 0.0416839 -0.696295 -3.72042 0.045426 -0.685026 -3.84742 0.0486642 -0.679791 -3.98465 0.0514121 -0.674814 -4.1142 0.0567141 -0.661631 -4.25278 0.0608335 -0.648435 -4.41057 0.0657127 -0.639015 -4.56897 0.0714534 -0.624707 -4.75577 0.0763098 -0.616206 -4.97182 0.0803746 -0.612027 -5.15965 0.0875254 -0.59122 -5.39705 0.0940334 -0.580143 -5.61547 0.101808 -0.555245 -5.87284 0.110572 -0.534762 -6.16008 0.119406 -0.513713 -6.45703 0.129376 -0.485723 -6.77425 0.140658 -0.452509 -7.15193 0.153235 -0.421867 -7.58742 0.166359 -0.390435 -8.0637 0.181404 -0.35167 -8.59021 0.199265 -0.305173 -9.21593 0.219402 -0.255808 -10.0001 0.242375 -0.206071 -10.8948 0.26932 -0.141904 -11.929 0.301955 -0.0609201 -13.5411 0.342643 0.00969386 -15.1935 0.394713 0.132755 -17.414 0.461725 0.28715 -20.1325 0.548535 0.503992 -22.788 0.650509 0.814884 -24.2368 0.74605 1.20827 -25.2382 0.841793 1.64044 -24.4834 0.898403 2.0349 -24.77 0.980657 2.46497 -25.108 1.06586 2.90992 -24.9507 1.13659 3.32134 -24.885 1.21007 3.73907 -24.8223 1.2828 4.15667 -23.3682 1.29569 4.37107 -22.1706 1.31186 4.57844 -24.5408 1.4984 5.39191 -18.5924 1.25887 4.63745 -17.9976 1.28307 4.83364 -18.5002 1.36956 5.26867 -24.2264 1.78839 7.04794 -21.6405 1.69542 6.78255 -18.8225 1.56918 6.35803 -18.8767 1.6349 6.71942 -19.4452 1.74069 7.25543 -18.8033 1.75473 7.39706 -17.3957 1.70156 7.23698 -21.8098 2.14349 9.27726 -17.9119 1.86781 8.11849 -19.2392 2.05552 9.03901 -18.2204 2.02463 8.96968 -18.5367 2.12323 9.48873 -18.7857 2.21799 9.99488 -18.8712 2.29756 10.4353 -17.0409 2.16415 9.86442 -17.1945 2.24827 10.3219 -21.7684 2.86994 13.354 -19.9367 2.72965 12.7484 -18.5961 2.63959 12.374 -18.7829 2.74299 12.9387 -18.7736 2.8243 13.3905 -18.6898 2.8954 13.8004 -19.3507 3.07881 14.7603 -18.4534 3.03308 14.5924 -18.366 3.10811 15.0219 -6.55708 1.27988 5.95181 -4.53323 0.971586 4.42802 -4.47249 0.983073 4.49697 -4.42521 0.996907 4.5781 -4.61487 1.05492 4.88184 -4.47475 1.05213 4.88334 -4.3286 1.04858 4.87397 -4.39671 1.08641 5.08204 -4.35902 1.10446 5.18483 -4.15808 1.08742 5.11081 -4.10518 1.10133 5.19572 -3.90372 1.08209 5.1054 -3.84914 1.09563 5.18657 -4.2248 1.21503 5.82108 -3.70609 1.11414 5.30751 -3.51425 1.09251 5.202 -3.48458 1.11241 5.31823 -3.52362 1.15319 5.54125 -3.48653 1.17318 5.65917 -3.40902 1.18258 5.71829 -3.20348 1.15119 5.56452 -3.04014 1.13108 5.4649 -2.96512 1.13837 5.51677 -3.22651 1.26558 6.20442 -3.00509 1.22457 5.99541 -2.78816 1.18144 5.77139 -2.66184 1.16967 5.72074 -2.57892 1.17472 5.75752 -2.28165 1.08499 5.28373 -2.23887 1.10422 5.39626 -2.33585 1.19341 5.88649 -2.26944 1.20788 5.97315 -2.14051 1.18934 5.8817 -1.91368 1.1115 5.46835 -2.03462 1.23695 6.16207 -1.97622 1.26145 6.30164 -1.77501 1.18947 5.91673 -1.68345 1.18743 5.91911 -1.86385 1.40655 7.13051 -1.72525 1.38301 7.00842 -1.61282 1.37768 6.99025 -1.50669 1.37944 7.00867 -1.41494 1.39748 7.12286 -1.15589 1.19229 5.9961 -1.22939 1.44632 7.41531 -0.823638 0.899477 4.38977 -0.825402 1.03883 5.17025 -0.75014 1.03552 5.15553 -0.678911 1.04115 5.1989 -0.653768 1.38389 7.12051 -0.538755 1.21569 6.18721 -0.450793 1.15953 5.8822 -0.370539 1.12461 5.69395 -0.28929 1.11706 5.66175 -0.197581 1.14316 5.81482 -0.00565932 1.37096 7.11462 -2.75814 -0.0449104 -0.750497 -2.82924 -0.0448632 -0.741305 -2.90045 -0.0434689 -0.730559 -2.98792 -0.0438908 -0.729395 -3.06824 -0.0439649 -0.719899 -3.1573 -0.0437625 -0.713824 -3.24619 -0.0430107 -0.705316 -3.35315 -0.0441319 -0.704495 -3.44455 -0.0428391 -0.690372 -3.56164 -0.0440989 -0.688251 -3.66125 -0.0425803 -0.673361 -3.7712 -0.0418376 -0.659993 -3.90789 -0.0424716 -0.656758 -4.04527 -0.0424199 -0.649414 -4.17449 -0.0417172 -0.63347 -4.32273 -0.0413381 -0.62169 -4.48016 -0.0409703 -0.60912 -4.65746 -0.0407897 -0.599035 -4.83606 -0.0407605 -0.583064 -5.0517 -0.0410754 -0.575151 -5.26952 -0.0414712 -0.559965 -5.49629 -0.0411752 -0.540877 -5.73512 -0.0397717 -0.517234 -6.02083 -0.0396484 -0.499471 -6.29911 -0.0382984 -0.469486 -6.6168 -0.0363339 -0.440094 -6.96388 -0.0345043 -0.406633 -7.36025 -0.0330405 -0.371782 -7.78669 -0.0311136 -0.32914 -8.29261 -0.0287729 -0.285812 -8.87819 -0.0272581 -0.237389 -9.4849 -0.0232208 -0.171825 -10.2199 -0.0194281 -0.101068 -11.373 -0.0239409 -0.0469311 -12.6659 -0.0247805 0.0348798 -14.3081 -0.0258003 0.137915 -16.0805 -0.0203273 0.291235 -19.2494 -0.0274114 0.461789 -23.2502 0.041401 1.12113 -24.4651 0.0998744 1.53753 -24.1438 0.17419 1.93757 -28.0431 0.488799 3.99015 -25.2012 0.620565 4.54806 -27.3386 0.731856 5.32346 -26.8161 0.805013 5.70538 -26.2402 0.8744 6.06115 -19.4018 0.780231 5.06539 -22.5323 0.930241 6.13 -20.0821 0.922327 5.92017 -18.082 0.915008 5.74424 -18.3039 0.980666 6.13357 -22.6277 1.22035 7.78489 -17.9337 1.08143 6.68372 -18.0012 1.14395 7.04045 -19.0392 1.25668 7.75541 -23.7127 1.58007 9.90408 -21.0605 1.50477 9.30001 -17.5733 1.36064 8.24286 -17.973 1.44849 8.7692 -18.0787 1.51935 9.18148 -18.9198 1.64584 9.96059 -19.0445 1.72588 10.4195 -19.476 1.8313 11.0533 -19.6892 1.92413 11.5937 -17.8483 1.83705 10.9751 -19.4932 2.06089 12.3584 -18.7237 2.06521 12.331 -18.4879 2.11856 12.6207 -20.2842 2.38688 14.2676 -18.8535 2.31797 13.776 -18.528 2.36402 14.0194 -19.3971 2.55302 15.1486 -19.3373 2.72923 16.1497 -4.56375 0.841548 4.41516 -4.49566 0.853547 4.47778 -4.22673 0.835996 4.36057 -4.02837 0.826562 4.29591 -3.89839 0.826512 4.28727 -3.83991 0.837226 4.34504 -4.4545 0.961601 5.09151 -4.00059 0.907424 4.75396 -3.74089 0.883218 4.60049 -4.09587 0.972854 5.13266 -4.00402 0.980464 5.17108 -3.84912 0.975782 5.13058 -3.81258 0.9947 5.23388 -3.7923 1.01668 5.36123 -3.54495 0.988944 5.18523 -3.45965 0.996376 5.22047 -3.50246 1.03495 5.44242 -3.39122 1.03648 5.44355 -3.29753 1.04153 5.46739 -3.20847 1.04782 5.49768 -3.1841 1.07235 5.63752 -2.98159 1.04512 5.46689 -2.88427 1.04755 5.47379 -2.88577 1.08203 5.67221 -2.76908 1.07827 5.64134 -2.69962 1.09006 5.70638 -2.57234 1.08135 5.64398 -2.34683 1.03066 5.3429 -2.50167 1.13413 5.94071 -2.52473 1.18931 6.25971 -2.39818 1.18113 6.20074 -2.24147 1.15529 6.04596 -1.98681 1.07422 5.56856 -1.8887 1.06985 5.53664 -1.91828 1.14063 5.93864 -1.84646 1.15518 6.01923 -1.70851 1.12603 5.84048 -1.66987 1.16477 6.06219 -1.7707 1.32347 6.96821 -1.54267 1.2192 6.36009 -1.44755 1.22314 6.37689 -1.31249 1.18312 6.13904 -1.19893 1.1575 5.98619 -1.1152 1.16562 6.02663 -1.16871 1.40431 7.38852 -0.867472 1.03015 5.23949 -0.788186 1.01786 5.16656 -0.714912 1.02003 5.17048 -0.645709 1.0413 5.29168 -0.581119 1.16789 6.00227 -0.493491 1.15955 5.95363 -0.407429 1.15358 5.9132 -0.33128 1.10534 5.63514 -0.245506 1.118 5.70011 -0.0319707 1.43745 7.50213 -2.7092 -0.103034 -0.73454 -2.79541 -0.107348 -0.73845 -2.86718 -0.108291 -0.728162 -2.9463 -0.110778 -0.721603 -3.02624 -0.113019 -0.71288 -3.11492 -0.115005 -0.707675 -3.19549 -0.116451 -0.694357 -3.29419 -0.119879 -0.689211 -3.38402 -0.121577 -0.676173 -3.49192 -0.12506 -0.670432 -3.60055 -0.128055 -0.661457 -3.70894 -0.130348 -0.649369 -3.83625 -0.134289 -0.642901 -3.97381 -0.138763 -0.636884 -4.10249 -0.141399 -0.622488 -4.24972 -0.146305 -0.612056 -4.38927 -0.148635 -0.593322 -4.56635 -0.155038 -0.584851 -4.74325 -0.159259 -0.57113 -4.93095 -0.164587 -0.554915 -5.13815 -0.170637 -0.539141 -5.35531 -0.17632 -0.519829 -5.59282 -0.182566 -0.499183 -5.84963 -0.18894 -0.47635 -6.13682 -0.197406 -0.452631 -6.41389 -0.203027 -0.417152 -6.75066 -0.211707 -0.385888 -7.1375 -0.222096 -0.353695 -7.53351 -0.231422 -0.310471 -8.0094 -0.243843 -0.267793 -8.54515 -0.257101 -0.218411 -9.1403 -0.271465 -0.159111 -9.86486 -0.290706 -0.0953388 -10.7885 -0.31745 -0.027481 -11.8607 -0.347751 0.0589311 -13.4223 -0.397849 0.148455 -15.0639 -0.441803 0.287049 -17.163 -0.498287 0.466157 -20.0791 -0.579193 0.70332 -22.8723 -0.637238 1.04056 -23.451 -0.592646 1.43553 -24.0126 -0.54497 1.8501 -23.9476 -0.472817 2.25204 -27.2406 -0.340546 3.81054 -27.5182 -0.264895 4.30947 -27.1528 -0.177254 4.73118 -27.1557 -0.0965693 5.19967 -27.0225 -0.0128679 5.64686 -44.0292 -0.0774827 9.3748 -19.2057 0.193293 4.95526 -18.648 0.25316 5.16518 -18.4292 0.309878 5.44063 -18.5438 0.367334 5.79893 -18.2373 0.421998 6.04581 -18.0054 0.476793 6.30653 -20.0451 0.561617 7.28857 -20.7953 0.639076 7.91513 -18.0754 0.652158 7.3321 -18.7205 0.726428 7.91896 -18.766 0.790408 8.29706 -18.7663 0.853683 8.66342 -17.3025 0.867531 8.39449 -17.8723 0.949061 9.00237 -18.2619 1.02888 9.55393 -18.3346 1.097 9.96931 -18.4497 1.16974 10.4171 -19.7579 1.3077 11.526 -19.8579 1.38794 12.0173 -21.9 1.5886 13.667 -19.5984 1.52698 12.7576 -22.767 1.82398 15.2353 -20.3344 1.74065 14.1709 -18.9906 1.7238 13.7454 -18.7008 1.78197 14.0139 -19.674 1.94918 15.2131 -19.3033 2.0057 15.448 -4.22609 0.68999 4.2132 -4.38729 0.726997 4.46776 -4.12073 0.717262 4.34546 -3.98932 0.721068 4.33852 -3.88777 0.728769 4.35563 -3.87869 0.747961 4.46266 -3.84464 0.763727 4.54866 -3.77603 0.775204 4.598 -3.89762 0.815499 4.86162 -3.90768 0.841557 5.00943 -3.73623 0.83697 4.94455 -3.8039 0.873257 5.17 -3.79136 0.896892 5.30444 -3.59673 0.886782 5.20044 -3.47069 0.888533 5.17986 -3.42605 0.905843 5.27079 -3.44475 0.938416 5.46033 -3.24869 0.923396 5.32587 -3.12007 0.922096 5.28749 -3.17177 0.964734 5.54475 -2.96417 0.942212 5.36539 -2.83479 0.937761 5.31091 -2.7914 0.95675 5.41142 -2.72328 0.969462 5.46731 -2.60646 0.967331 5.42383 -2.51234 0.970518 5.42298 -2.41092 0.971313 5.40189 -2.66449 1.10402 6.22833 -2.62369 1.13358 6.39305 -2.56369 1.15813 6.52077 -2.32086 1.10356 6.14476 -2.00284 1.00553 5.49975 -1.94828 1.02509 5.59981 -1.87854 1.03832 5.66132 -1.8281 1.06444 5.79793 -1.76888 1.08661 5.91515 -1.65756 1.0766 5.83007 -1.60027 1.10382 5.97394 -1.53446 1.12796 6.09783 -1.59511 1.26761 6.91974 -1.34562 1.1313 6.07067 -1.26491 1.14724 6.14226 -1.17987 1.15994 6.19309 -1.23361 1.37934 7.47742 -0.933684 1.05808 5.54453 -0.824834 0.998394 5.17729 -0.750746 1.00091 5.17182 -0.679972 1.01455 5.23408 -0.626377 1.15893 6.05371 -0.54561 1.36552 7.227 -0.451003 1.13312 5.86659 -0.365234 1.13504 5.85443 -0.289395 1.10385 5.65394 -0.199812 1.1264 5.76707 -0.00256453 1.37473 7.15445 -2.75328 -0.166485 -0.729363 -2.8237 -0.169358 -0.719871 -2.8947 -0.172981 -0.708212 -2.97426 -0.17741 -0.700359 -3.06234 -0.182559 -0.695924 -3.15122 -0.187395 -0.689033 -3.24064 -0.192827 -0.679294 -3.33876 -0.197872 -0.672489 -3.43741 -0.203447 -0.662544 -3.53683 -0.208622 -0.649755 -3.64562 -0.21438 -0.638706 -3.75515 -0.219649 -0.624422 -3.88237 -0.227282 -0.615584 -4.01887 -0.235211 -0.607221 -4.14843 -0.241754 -0.590336 -4.31344 -0.253198 -0.58512 -4.46239 -0.260132 -0.567215 -4.63909 -0.271002 -0.5554 -4.81634 -0.280835 -0.537918 -5.0224 -0.293407 -0.524559 -5.24886 -0.30674 -0.510741 -5.46606 -0.318767 -0.486499 -5.7036 -0.331335 -0.460825 -5.96965 -0.345763 -0.435382 -6.24739 -0.359639 -0.403436 -6.56362 -0.376729 -0.371392 -6.90975 -0.396116 -0.334957 -7.31506 -0.418657 -0.298746 -7.73046 -0.440175 -0.250605 -8.22516 -0.466405 -0.20135 -8.77991 -0.4963 -0.143609 -9.42349 -0.530922 -0.0784895 -10.226 -0.57656 -0.00829309 -11.2871 -0.640278 0.0659291 -12.4977 -0.709496 0.165473 -14.1558 -0.807435 0.281522 -15.8538 -0.899522 0.453074 -20.579 -1.14986 0.966277 -23.1754 -1.26973 1.34795 -23.5198 -1.22656 1.74983 -23.4791 -1.15552 2.14509 -27.3656 -1.32269 2.79669 -22.9277 -0.85617 3.67446 -23.0213 -0.793377 4.07891 -23.048 -0.727649 4.47845 -28.6615 -0.897832 5.83171 -25.1614 -0.674733 5.67342 -25.0026 -0.59394 6.08102 -18.3113 -0.296871 5.0243 -18.339 -0.242813 5.35357 -18.4092 -0.188929 5.69735 -18.1356 -0.126295 5.95104 -19.516 -0.0989058 6.6891 -21.1718 -0.0672021 7.56921 -20.3273 0.0114455 7.67901 -18.5801 0.0956423 7.44102 -18.6278 0.155114 7.81012 -21.7474 0.203162 9.39363 -18.2369 0.278218 8.36726 -22.3568 0.350169 10.5116 -19.487 0.409369 9.65755 -18.1698 0.464523 9.42855 -18.9907 0.538754 10.2103 -18.2167 0.593657 10.2088 -17.6422 0.648423 10.2878 -22.1518 0.823043 13.2056 -22.2567 0.910197 13.7613 -19.2665 0.900055 12.4493 -20.7049 1.02847 13.8046 -19.7285 1.07339 13.6548 -19.5735 1.14698 14.0272 -20.9609 1.29831 15.4929 -20.0775 1.34151 15.3801 -20.0088 1.42688 15.8516 -4.20224 0.563518 4.16269 -4.17744 0.580752 4.25162 -4.21666 0.604047 4.40069 -3.97588 0.602542 4.29315 -3.92552 0.617099 4.35889 -3.80319 0.625178 4.35299 -3.85569 0.650724 4.52371 -3.77446 0.662312 4.55852 -3.77862 0.683887 4.68779 -3.83884 0.713257 4.88619 -3.75164 0.724943 4.9194 -3.75834 0.7497 5.06705 -3.67583 0.76247 5.10602 -3.7473 0.798567 5.3503 -3.59535 0.801598 5.29985 -3.57777 0.825224 5.43331 -3.3614 0.814184 5.27855 -3.31318 0.833131 5.36802 -3.17893 0.834829 5.32218 -3.07818 0.84237 5.32427 -3.01215 0.857521 5.38429 -2.95042 0.873244 5.4522 -2.80267 0.867915 5.3614 -2.70797 0.875139 5.36412 -2.64463 0.890303 5.42742 -2.61383 0.915285 5.56174 -2.61478 0.952458 5.7776 -2.57046 0.976989 5.90372 -2.62192 1.03756 6.27758 -2.55447 1.05915 6.37705 -2.20255 0.96878 5.70311 -2.0841 0.964632 5.62769 -1.99169 0.969296 5.61575 -1.91596 0.982237 5.65858 -1.86448 1.00774 5.7859 -1.7968 1.02622 5.86508 -1.72825 1.04567 5.95292 -1.62337 1.04289 5.89527 -1.53756 1.05206 5.91291 -1.63809 1.21178 6.8894 -1.56573 1.24972 7.08215 -1.49769 1.29848 7.34236 -1.25125 1.15447 6.38887 -1.14488 1.14703 6.30184 -1.17071 1.34087 7.44987 -0.861292 0.978892 5.19777 -0.786397 0.981743 5.18281 -0.715532 0.992489 5.21581 -0.707345 1.32917 7.18929 -0.578966 1.12881 5.9582 -0.492274 1.13141 5.9381 -0.406196 1.13866 5.94619 -0.330211 1.09341 5.64731 -0.246799 1.10347 5.67213 -0.030593 1.43268 7.51298 -2.78718 -0.230224 -0.717478 -2.86552 -0.237022 -0.712368 -2.93695 -0.242521 -0.699124 -3.01596 -0.248612 -0.689806 -3.09674 -0.25465 -0.678107 -3.18483 -0.262099 -0.669554 -3.2831 -0.271518 -0.663395 -3.37274 -0.278233 -0.649444 -3.48021 -0.287706 -0.64269 -3.58818 -0.297643 -0.632505 -3.69713 -0.306163 -0.619381 -3.81517 -0.316085 -0.607215 -3.96022 -0.330388 -0.604178 -4.07034 -0.337009 -0.5805 -4.21767 -0.350111 -0.568928 -4.37398 -0.36422 -0.556564 -4.54041 -0.37849 -0.542997 -4.72695 -0.395907 -0.530718 -4.9133 -0.411076 -0.512895 -5.13815 -0.432856 -0.501196 -5.33572 -0.447721 -0.47356 -5.56269 -0.466075 -0.447881 -5.80949 -0.486763 -0.419888 -6.10412 -0.512836 -0.396161 -6.38137 -0.534762 -0.358015 -6.71664 -0.562409 -0.323709 -7.08152 -0.593106 -0.28394 -7.50501 -0.628598 -0.242833 -7.94962 -0.664899 -0.190513 -8.48282 -0.710143 -0.136255 -9.08578 -0.76129 -0.0726911 -9.76782 -0.817072 0.00223053 -10.7265 -0.902064 0.0743414 -11.7552 -0.990276 0.174195 -13.2903 -1.12832 0.279132 -14.9638 -1.27206 0.430821 -16.9952 -1.44491 0.631677 -20.1375 -1.71958 0.894099 -22.9984 -1.94777 1.26217 -23.515 -1.93228 1.66545 -23.458 -1.86023 2.06123 -24.7553 -1.91141 2.53907 -29.4891 -2.25767 3.33473 -23.04 -1.55859 3.60905 -23.0176 -1.49079 4.00045 -22.2779 -1.36706 4.28559 -21.3291 -1.23315 4.51174 -23.0753 -1.29445 5.20364 -26.8489 -1.48135 6.37006 -24.5169 -1.25219 6.3298 -19.6501 -0.880501 5.6041 -18.6245 -0.761906 5.69005 -18.3719 -0.691862 5.95391 -20.3477 -0.739215 6.86575 -20.8101 -0.699442 7.38225 -19.4877 -0.574027 7.32869 -19.3799 -0.509165 7.65457 -18.8626 -0.426734 7.829 -18.2798 -0.346015 7.96255 -18.1981 -0.283642 8.28219 -17.6595 -0.208194 8.40769 -18.9174 -0.181642 9.3246 -11.7272 0.0437868 6.32279 -19.289 -0.0591412 10.2784 -19.0315 0.0114858 10.5494 -21.4584 0.051164 12.2528 -17.4035 0.161858 10.4587 -21.401 0.209414 13.1602 -21.2667 0.290492 13.5628 -20.9052 0.371675 13.8262 -20.5402 0.450855 14.0809 -20.8437 0.53742 14.78 -20.5232 0.617881 15.0688 -20.6755 0.70827 15.6968 -20.2845 0.78779 15.9372 -4.41985 0.429243 4.20605 -4.22628 0.440748 4.15685 -4.13484 0.455017 4.18732 -4.10181 0.472714 4.26864 -4.06003 0.489061 4.34314 -4.01634 0.505772 4.41711 -3.9438 0.520542 4.46244 -4.00226 0.54541 4.64209 -3.97382 0.563853 4.73756 -3.74155 0.566811 4.61105 -3.77756 0.59047 4.7783 -3.71885 0.607475 4.8408 -3.73385 0.63157 4.99518 -3.62178 0.642425 4.99466 -3.66708 0.672232 5.1976 -3.55877 0.684276 5.20223 -3.49203 0.700506 5.26154 -3.65933 0.751196 5.66538 -3.38706 0.73869 5.42662 -3.25165 0.745131 5.38198 -3.1645 0.758985 5.41049 -3.04311 0.765413 5.37749 -3.03526 0.793891 5.54089 -2.91863 0.801183 5.51267 -2.90468 0.830133 5.67614 -2.84068 0.848973 5.7513 -2.81321 0.877472 5.90656 -2.59673 0.857869 5.65464 -2.57072 0.887365 5.81646 -2.53214 0.915209 5.96035 -2.60243 0.980735 6.39073 -2.28607 0.918573 5.82943 -2.18552 0.925071 5.81153 -2.10806 0.941136 5.85722 -1.98185 0.935595 5.7506 -1.84272 0.92185 5.58391 -1.85587 0.980748 5.93937 -1.77911 0.998464 5.99893 -1.68496 1.00627 5.98995 -1.56876 0.998218 5.87302 -1.49136 1.01518 5.92818 -1.3481 0.979774 5.63184 -1.55928 1.25536 7.40058 -1.44111 1.26294 7.37701 -1.21481 1.14095 6.50814 -1.09541 1.12036 6.31178 -0.899267 0.957956 5.22835 -0.821352 0.958624 5.18406 -0.749688 0.969682 5.20747 -0.682102 0.999828 5.34806 -0.623311 1.12412 6.04942 -0.534829 1.12732 6.0199 -0.448549 1.10934 5.86048 -0.36348 1.12125 5.87704 -0.288546 1.09187 5.65597 -0.199403 1.12142 5.77803 -0.00547937 1.36695 7.12548 -2.74068 -0.28636 -0.709292 -2.81863 -0.295326 -0.704955 -2.88218 -0.300987 -0.68671 -2.96057 -0.310218 -0.678066 -3.04846 -0.320405 -0.672815 -3.13691 -0.33121 -0.664814 -3.2254 -0.340514 -0.654578 -3.32287 -0.352501 -0.646562 -3.42133 -0.363115 -0.635802 -3.52032 -0.374258 -0.621902 -3.62845 -0.386979 -0.60974 -3.74497 -0.39998 -0.599048 -3.86316 -0.41262 -0.584613 -3.99951 -0.429632 -0.574622 -4.13675 -0.444962 -0.560524 -4.28299 -0.46141 -0.54612 -4.44941 -0.481245 -0.534073 -4.61523 -0.500912 -0.516867 -4.7921 -0.520801 -0.497657 -4.9973 -0.545354 -0.482272 -5.20299 -0.568649 -0.460248 -5.4286 -0.594565 -0.437176 -5.66387 -0.620845 -0.409397 -5.92935 -0.650389 -0.381507 -6.21429 -0.682802 -0.349258 -6.51886 -0.716933 -0.311973 -6.85335 -0.753427 -0.270588 -7.23648 -0.797295 -0.226896 -7.67986 -0.847119 -0.180453 -8.17148 -0.903108 -0.126352 -8.74191 -0.967904 -0.0661388 -9.37237 -1.03864 0.00677705 -10.1314 -1.12472 0.0885229 -11.2054 -1.25197 0.170645 -12.3787 -1.38803 0.283546 -14.0471 -1.58533 0.414058 -15.7941 -1.78333 0.599717 -18.1046 -2.04773 0.839788 -20.4727 -2.30557 1.15996 -23.2321 -2.59944 1.57139 -24.1197 -2.64496 2.00231 -24.455 -2.61788 2.43223 -24.2771 -2.52797 2.83562 -27.8022 -2.86837 3.57805 -27.8521 -2.79536 4.06073 -21.6226 -2.02976 3.74268 -22.0715 -2.01674 4.17981 -21.0791 -1.85035 4.39908 -20.3097 -1.71253 4.62537 -19.7141 -1.59494 4.86065 -20.196 -1.58427 5.31064 -20.7745 -1.57926 5.80323 -20.2127 -1.46749 6.03053 -20.832 -1.46158 6.56111 -21.8014 -1.48015 7.21972 -20.8881 -1.34098 7.33631 -20.8111 -1.27136 7.69661 -19.4448 -1.106 7.61093 -22.5198 -1.26336 9.10336 -17.718 -0.868203 7.68185 -19.8248 -0.946887 8.87788 -18.2495 -0.78732 8.59559 -18.7318 -0.754677 9.17232 -10.5474 -0.249352 5.72887 -19.2293 -0.655202 10.1758 -19.0823 -0.581828 10.5008 -20.509 -0.57793 11.6623 -20.6069 -0.508644 12.159 -9.90882 -0.0457824 6.45404 -19.5511 -0.322805 12.4418 -19.4565 -0.247176 12.8303 -20.236 -0.191294 13.7881 -19.8261 -0.10327 13.9963 -20.2185 -0.0298875 14.7534 -20.2176 0.054038 15.2582 -20.0844 0.140302 15.6772 -19.8239 0.228431 16.0036 -4.31587 0.300321 4.09862 -4.14792 0.316606 4.06763 -4.08802 0.333454 4.12289 -3.81017 0.347259 3.98405 -3.94339 0.367241 4.20922 -3.93194 0.385453 4.30869 -3.93211 0.403833 4.42286 -3.84534 0.419855 4.45215 -3.76622 0.436117 4.48668 -3.78063 0.456556 4.62272 -3.76445 0.476544 4.73017 -3.76535 0.498164 4.86083 -3.68588 0.515481 4.90003 -3.66259 0.536309 5.0081 -3.66062 0.559517 5.14805 -3.66715 0.584177 5.30517 -3.45895 0.589076 5.17117 -3.32514 0.600052 5.13004 -3.35341 0.628546 5.32657 -3.38091 0.65937 5.5334 -3.17677 0.660754 5.37716 -3.22876 0.69628 5.63594 -3.03023 0.695913 5.47291 -3.33041 0.776533 6.20522 -3.15344 0.780551 6.08403 -2.90848 0.767857 5.81619 -2.79858 0.780503 5.80155 -2.71186 0.796349 5.83006 -2.63595 0.814825 5.88417 -2.50192 0.818919 5.79945 -2.41884 0.834651 5.83175 -2.42987 0.87983 6.11347 -2.23002 0.860215 5.83576 -2.16581 0.883002 5.91957 -2.00416 0.869022 5.70963 -1.87355 0.863347 5.57177 -1.85708 0.905852 5.81278 -1.73832 0.902372 5.69967 -1.92537 1.0604 6.80684 -1.88636 1.11388 7.0992 -1.50852 0.953813 5.83015 -1.40972 0.956844 5.76721 -1.31843 0.96266 5.73176 -1.48251 1.20269 7.31836 -1.24545 1.08474 6.41056 -1.16534 1.11641 6.53847 -0.935846 0.9352 5.25863 -0.856124 0.935452 5.19496 -0.783402 0.944884 5.19913 -0.714229 0.966392 5.27084 -0.673196 1.13832 6.27884 -0.57531 1.084 5.87461 -0.490341 1.1065 5.94235 -0.40538 1.10736 5.88042 -0.327228 1.08396 5.67924 -0.24784 1.08698 5.63441 -0.0292165 1.42897 7.53396 -VERTICES 25193 50386 -1 0 -1 1 -1 2 -1 3 -1 4 -1 5 -1 6 -1 7 -1 8 -1 9 -1 10 -1 11 -1 12 -1 13 -1 14 -1 15 -1 16 -1 17 -1 18 -1 19 -1 20 -1 21 -1 22 -1 23 -1 24 -1 25 -1 26 -1 27 -1 28 -1 29 -1 30 -1 31 -1 32 -1 33 -1 34 -1 35 -1 36 -1 37 -1 38 -1 39 -1 40 -1 41 -1 42 -1 43 -1 44 -1 45 -1 46 -1 47 -1 48 -1 49 -1 50 -1 51 -1 52 -1 53 -1 54 -1 55 -1 56 -1 57 -1 58 -1 59 -1 60 -1 61 -1 62 -1 63 -1 64 -1 65 -1 66 -1 67 -1 68 -1 69 -1 70 -1 71 -1 72 -1 73 -1 74 -1 75 -1 76 -1 77 -1 78 -1 79 -1 80 -1 81 -1 82 -1 83 -1 84 -1 85 -1 86 -1 87 -1 88 -1 89 -1 90 -1 91 -1 92 -1 93 -1 94 -1 95 -1 96 -1 97 -1 98 -1 99 -1 100 -1 101 -1 102 -1 103 -1 104 -1 105 -1 106 -1 107 -1 108 -1 109 -1 110 -1 111 -1 112 -1 113 -1 114 -1 115 -1 116 -1 117 -1 118 -1 119 -1 120 -1 121 -1 122 -1 123 -1 124 -1 125 -1 126 -1 127 -1 128 -1 129 -1 130 -1 131 -1 132 -1 133 -1 134 -1 135 -1 136 -1 137 -1 138 -1 139 -1 140 -1 141 -1 142 -1 143 -1 144 -1 145 -1 146 -1 147 -1 148 -1 149 -1 150 -1 151 -1 152 -1 153 -1 154 -1 155 -1 156 -1 157 -1 158 -1 159 -1 160 -1 161 -1 162 -1 163 -1 164 -1 165 -1 166 -1 167 -1 168 -1 169 -1 170 -1 171 -1 172 -1 173 -1 174 -1 175 -1 176 -1 177 -1 178 -1 179 -1 180 -1 181 -1 182 -1 183 -1 184 -1 185 -1 186 -1 187 -1 188 -1 189 -1 190 -1 191 -1 192 -1 193 -1 194 -1 195 -1 196 -1 197 -1 198 -1 199 -1 200 -1 201 -1 202 -1 203 -1 204 -1 205 -1 206 -1 207 -1 208 -1 209 -1 210 -1 211 -1 212 -1 213 -1 214 -1 215 -1 216 -1 217 -1 218 -1 219 -1 220 -1 221 -1 222 -1 223 -1 224 -1 225 -1 226 -1 227 -1 228 -1 229 -1 230 -1 231 -1 232 -1 233 -1 234 -1 235 -1 236 -1 237 -1 238 -1 239 -1 240 -1 241 -1 242 -1 243 -1 244 -1 245 -1 246 -1 247 -1 248 -1 249 -1 250 -1 251 -1 252 -1 253 -1 254 -1 255 -1 256 -1 257 -1 258 -1 259 -1 260 -1 261 -1 262 -1 263 -1 264 -1 265 -1 266 -1 267 -1 268 -1 269 -1 270 -1 271 -1 272 -1 273 -1 274 -1 275 -1 276 -1 277 -1 278 -1 279 -1 280 -1 281 -1 282 -1 283 -1 284 -1 285 -1 286 -1 287 -1 288 -1 289 -1 290 -1 291 -1 292 -1 293 -1 294 -1 295 -1 296 -1 297 -1 298 -1 299 -1 300 -1 301 -1 302 -1 303 -1 304 -1 305 -1 306 -1 307 -1 308 -1 309 -1 310 -1 311 -1 312 -1 313 -1 314 -1 315 -1 316 -1 317 -1 318 -1 319 -1 320 -1 321 -1 322 -1 323 -1 324 -1 325 -1 326 -1 327 -1 328 -1 329 -1 330 -1 331 -1 332 -1 333 -1 334 -1 335 -1 336 -1 337 -1 338 -1 339 -1 340 -1 341 -1 342 -1 343 -1 344 -1 345 -1 346 -1 347 -1 348 -1 349 -1 350 -1 351 -1 352 -1 353 -1 354 -1 355 -1 356 -1 357 -1 358 -1 359 -1 360 -1 361 -1 362 -1 363 -1 364 -1 365 -1 366 -1 367 -1 368 -1 369 -1 370 -1 371 -1 372 -1 373 -1 374 -1 375 -1 376 -1 377 -1 378 -1 379 -1 380 -1 381 -1 382 -1 383 -1 384 -1 385 -1 386 -1 387 -1 388 -1 389 -1 390 -1 391 -1 392 -1 393 -1 394 -1 395 -1 396 -1 397 -1 398 -1 399 -1 400 -1 401 -1 402 -1 403 -1 404 -1 405 -1 406 -1 407 -1 408 -1 409 -1 410 -1 411 -1 412 -1 413 -1 414 -1 415 -1 416 -1 417 -1 418 -1 419 -1 420 -1 421 -1 422 -1 423 -1 424 -1 425 -1 426 -1 427 -1 428 -1 429 -1 430 -1 431 -1 432 -1 433 -1 434 -1 435 -1 436 -1 437 -1 438 -1 439 -1 440 -1 441 -1 442 -1 443 -1 444 -1 445 -1 446 -1 447 -1 448 -1 449 -1 450 -1 451 -1 452 -1 453 -1 454 -1 455 -1 456 -1 457 -1 458 -1 459 -1 460 -1 461 -1 462 -1 463 -1 464 -1 465 -1 466 -1 467 -1 468 -1 469 -1 470 -1 471 -1 472 -1 473 -1 474 -1 475 -1 476 -1 477 -1 478 -1 479 -1 480 -1 481 -1 482 -1 483 -1 484 -1 485 -1 486 -1 487 -1 488 -1 489 -1 490 -1 491 -1 492 -1 493 -1 494 -1 495 -1 496 -1 497 -1 498 -1 499 -1 500 -1 501 -1 502 -1 503 -1 504 -1 505 -1 506 -1 507 -1 508 -1 509 -1 510 -1 511 -1 512 -1 513 -1 514 -1 515 -1 516 -1 517 -1 518 -1 519 -1 520 -1 521 -1 522 -1 523 -1 524 -1 525 -1 526 -1 527 -1 528 -1 529 -1 530 -1 531 -1 532 -1 533 -1 534 -1 535 -1 536 -1 537 -1 538 -1 539 -1 540 -1 541 -1 542 -1 543 -1 544 -1 545 -1 546 -1 547 -1 548 -1 549 -1 550 -1 551 -1 552 -1 553 -1 554 -1 555 -1 556 -1 557 -1 558 -1 559 -1 560 -1 561 -1 562 -1 563 -1 564 -1 565 -1 566 -1 567 -1 568 -1 569 -1 570 -1 571 -1 572 -1 573 -1 574 -1 575 -1 576 -1 577 -1 578 -1 579 -1 580 -1 581 -1 582 -1 583 -1 584 -1 585 -1 586 -1 587 -1 588 -1 589 -1 590 -1 591 -1 592 -1 593 -1 594 -1 595 -1 596 -1 597 -1 598 -1 599 -1 600 -1 601 -1 602 -1 603 -1 604 -1 605 -1 606 -1 607 -1 608 -1 609 -1 610 -1 611 -1 612 -1 613 -1 614 -1 615 -1 616 -1 617 -1 618 -1 619 -1 620 -1 621 -1 622 -1 623 -1 624 -1 625 -1 626 -1 627 -1 628 -1 629 -1 630 -1 631 -1 632 -1 633 -1 634 -1 635 -1 636 -1 637 -1 638 -1 639 -1 640 -1 641 -1 642 -1 643 -1 644 -1 645 -1 646 -1 647 -1 648 -1 649 -1 650 -1 651 -1 652 -1 653 -1 654 -1 655 -1 656 -1 657 -1 658 -1 659 -1 660 -1 661 -1 662 -1 663 -1 664 -1 665 -1 666 -1 667 -1 668 -1 669 -1 670 -1 671 -1 672 -1 673 -1 674 -1 675 -1 676 -1 677 -1 678 -1 679 -1 680 -1 681 -1 682 -1 683 -1 684 -1 685 -1 686 -1 687 -1 688 -1 689 -1 690 -1 691 -1 692 -1 693 -1 694 -1 695 -1 696 -1 697 -1 698 -1 699 -1 700 -1 701 -1 702 -1 703 -1 704 -1 705 -1 706 -1 707 -1 708 -1 709 -1 710 -1 711 -1 712 -1 713 -1 714 -1 715 -1 716 -1 717 -1 718 -1 719 -1 720 -1 721 -1 722 -1 723 -1 724 -1 725 -1 726 -1 727 -1 728 -1 729 -1 730 -1 731 -1 732 -1 733 -1 734 -1 735 -1 736 -1 737 -1 738 -1 739 -1 740 -1 741 -1 742 -1 743 -1 744 -1 745 -1 746 -1 747 -1 748 -1 749 -1 750 -1 751 -1 752 -1 753 -1 754 -1 755 -1 756 -1 757 -1 758 -1 759 -1 760 -1 761 -1 762 -1 763 -1 764 -1 765 -1 766 -1 767 -1 768 -1 769 -1 770 -1 771 -1 772 -1 773 -1 774 -1 775 -1 776 -1 777 -1 778 -1 779 -1 780 -1 781 -1 782 -1 783 -1 784 -1 785 -1 786 -1 787 -1 788 -1 789 -1 790 -1 791 -1 792 -1 793 -1 794 -1 795 -1 796 -1 797 -1 798 -1 799 -1 800 -1 801 -1 802 -1 803 -1 804 -1 805 -1 806 -1 807 -1 808 -1 809 -1 810 -1 811 -1 812 -1 813 -1 814 -1 815 -1 816 -1 817 -1 818 -1 819 -1 820 -1 821 -1 822 -1 823 -1 824 -1 825 -1 826 -1 827 -1 828 -1 829 -1 830 -1 831 -1 832 -1 833 -1 834 -1 835 -1 836 -1 837 -1 838 -1 839 -1 840 -1 841 -1 842 -1 843 -1 844 -1 845 -1 846 -1 847 -1 848 -1 849 -1 850 -1 851 -1 852 -1 853 -1 854 -1 855 -1 856 -1 857 -1 858 -1 859 -1 860 -1 861 -1 862 -1 863 -1 864 -1 865 -1 866 -1 867 -1 868 -1 869 -1 870 -1 871 -1 872 -1 873 -1 874 -1 875 -1 876 -1 877 -1 878 -1 879 -1 880 -1 881 -1 882 -1 883 -1 884 -1 885 -1 886 -1 887 -1 888 -1 889 -1 890 -1 891 -1 892 -1 893 -1 894 -1 895 -1 896 -1 897 -1 898 -1 899 -1 900 -1 901 -1 902 -1 903 -1 904 -1 905 -1 906 -1 907 -1 908 -1 909 -1 910 -1 911 -1 912 -1 913 -1 914 -1 915 -1 916 -1 917 -1 918 -1 919 -1 920 -1 921 -1 922 -1 923 -1 924 -1 925 -1 926 -1 927 -1 928 -1 929 -1 930 -1 931 -1 932 -1 933 -1 934 -1 935 -1 936 -1 937 -1 938 -1 939 -1 940 -1 941 -1 942 -1 943 -1 944 -1 945 -1 946 -1 947 -1 948 -1 949 -1 950 -1 951 -1 952 -1 953 -1 954 -1 955 -1 956 -1 957 -1 958 -1 959 -1 960 -1 961 -1 962 -1 963 -1 964 -1 965 -1 966 -1 967 -1 968 -1 969 -1 970 -1 971 -1 972 -1 973 -1 974 -1 975 -1 976 -1 977 -1 978 -1 979 -1 980 -1 981 -1 982 -1 983 -1 984 -1 985 -1 986 -1 987 -1 988 -1 989 -1 990 -1 991 -1 992 -1 993 -1 994 -1 995 -1 996 -1 997 -1 998 -1 999 -1 1000 -1 1001 -1 1002 -1 1003 -1 1004 -1 1005 -1 1006 -1 1007 -1 1008 -1 1009 -1 1010 -1 1011 -1 1012 -1 1013 -1 1014 -1 1015 -1 1016 -1 1017 -1 1018 -1 1019 -1 1020 -1 1021 -1 1022 -1 1023 -1 1024 -1 1025 -1 1026 -1 1027 -1 1028 -1 1029 -1 1030 -1 1031 -1 1032 -1 1033 -1 1034 -1 1035 -1 1036 -1 1037 -1 1038 -1 1039 -1 1040 -1 1041 -1 1042 -1 1043 -1 1044 -1 1045 -1 1046 -1 1047 -1 1048 -1 1049 -1 1050 -1 1051 -1 1052 -1 1053 -1 1054 -1 1055 -1 1056 -1 1057 -1 1058 -1 1059 -1 1060 -1 1061 -1 1062 -1 1063 -1 1064 -1 1065 -1 1066 -1 1067 -1 1068 -1 1069 -1 1070 -1 1071 -1 1072 -1 1073 -1 1074 -1 1075 -1 1076 -1 1077 -1 1078 -1 1079 -1 1080 -1 1081 -1 1082 -1 1083 -1 1084 -1 1085 -1 1086 -1 1087 -1 1088 -1 1089 -1 1090 -1 1091 -1 1092 -1 1093 -1 1094 -1 1095 -1 1096 -1 1097 -1 1098 -1 1099 -1 1100 -1 1101 -1 1102 -1 1103 -1 1104 -1 1105 -1 1106 -1 1107 -1 1108 -1 1109 -1 1110 -1 1111 -1 1112 -1 1113 -1 1114 -1 1115 -1 1116 -1 1117 -1 1118 -1 1119 -1 1120 -1 1121 -1 1122 -1 1123 -1 1124 -1 1125 -1 1126 -1 1127 -1 1128 -1 1129 -1 1130 -1 1131 -1 1132 -1 1133 -1 1134 -1 1135 -1 1136 -1 1137 -1 1138 -1 1139 -1 1140 -1 1141 -1 1142 -1 1143 -1 1144 -1 1145 -1 1146 -1 1147 -1 1148 -1 1149 -1 1150 -1 1151 -1 1152 -1 1153 -1 1154 -1 1155 -1 1156 -1 1157 -1 1158 -1 1159 -1 1160 -1 1161 -1 1162 -1 1163 -1 1164 -1 1165 -1 1166 -1 1167 -1 1168 -1 1169 -1 1170 -1 1171 -1 1172 -1 1173 -1 1174 -1 1175 -1 1176 -1 1177 -1 1178 -1 1179 -1 1180 -1 1181 -1 1182 -1 1183 -1 1184 -1 1185 -1 1186 -1 1187 -1 1188 -1 1189 -1 1190 -1 1191 -1 1192 -1 1193 -1 1194 -1 1195 -1 1196 -1 1197 -1 1198 -1 1199 -1 1200 -1 1201 -1 1202 -1 1203 -1 1204 -1 1205 -1 1206 -1 1207 -1 1208 -1 1209 -1 1210 -1 1211 -1 1212 -1 1213 -1 1214 -1 1215 -1 1216 -1 1217 -1 1218 -1 1219 -1 1220 -1 1221 -1 1222 -1 1223 -1 1224 -1 1225 -1 1226 -1 1227 -1 1228 -1 1229 -1 1230 -1 1231 -1 1232 -1 1233 -1 1234 -1 1235 -1 1236 -1 1237 -1 1238 -1 1239 -1 1240 -1 1241 -1 1242 -1 1243 -1 1244 -1 1245 -1 1246 -1 1247 -1 1248 -1 1249 -1 1250 -1 1251 -1 1252 -1 1253 -1 1254 -1 1255 -1 1256 -1 1257 -1 1258 -1 1259 -1 1260 -1 1261 -1 1262 -1 1263 -1 1264 -1 1265 -1 1266 -1 1267 -1 1268 -1 1269 -1 1270 -1 1271 -1 1272 -1 1273 -1 1274 -1 1275 -1 1276 -1 1277 -1 1278 -1 1279 -1 1280 -1 1281 -1 1282 -1 1283 -1 1284 -1 1285 -1 1286 -1 1287 -1 1288 -1 1289 -1 1290 -1 1291 -1 1292 -1 1293 -1 1294 -1 1295 -1 1296 -1 1297 -1 1298 -1 1299 -1 1300 -1 1301 -1 1302 -1 1303 -1 1304 -1 1305 -1 1306 -1 1307 -1 1308 -1 1309 -1 1310 -1 1311 -1 1312 -1 1313 -1 1314 -1 1315 -1 1316 -1 1317 -1 1318 -1 1319 -1 1320 -1 1321 -1 1322 -1 1323 -1 1324 -1 1325 -1 1326 -1 1327 -1 1328 -1 1329 -1 1330 -1 1331 -1 1332 -1 1333 -1 1334 -1 1335 -1 1336 -1 1337 -1 1338 -1 1339 -1 1340 -1 1341 -1 1342 -1 1343 -1 1344 -1 1345 -1 1346 -1 1347 -1 1348 -1 1349 -1 1350 -1 1351 -1 1352 -1 1353 -1 1354 -1 1355 -1 1356 -1 1357 -1 1358 -1 1359 -1 1360 -1 1361 -1 1362 -1 1363 -1 1364 -1 1365 -1 1366 -1 1367 -1 1368 -1 1369 -1 1370 -1 1371 -1 1372 -1 1373 -1 1374 -1 1375 -1 1376 -1 1377 -1 1378 -1 1379 -1 1380 -1 1381 -1 1382 -1 1383 -1 1384 -1 1385 -1 1386 -1 1387 -1 1388 -1 1389 -1 1390 -1 1391 -1 1392 -1 1393 -1 1394 -1 1395 -1 1396 -1 1397 -1 1398 -1 1399 -1 1400 -1 1401 -1 1402 -1 1403 -1 1404 -1 1405 -1 1406 -1 1407 -1 1408 -1 1409 -1 1410 -1 1411 -1 1412 -1 1413 -1 1414 -1 1415 -1 1416 -1 1417 -1 1418 -1 1419 -1 1420 -1 1421 -1 1422 -1 1423 -1 1424 -1 1425 -1 1426 -1 1427 -1 1428 -1 1429 -1 1430 -1 1431 -1 1432 -1 1433 -1 1434 -1 1435 -1 1436 -1 1437 -1 1438 -1 1439 -1 1440 -1 1441 -1 1442 -1 1443 -1 1444 -1 1445 -1 1446 -1 1447 -1 1448 -1 1449 -1 1450 -1 1451 -1 1452 -1 1453 -1 1454 -1 1455 -1 1456 -1 1457 -1 1458 -1 1459 -1 1460 -1 1461 -1 1462 -1 1463 -1 1464 -1 1465 -1 1466 -1 1467 -1 1468 -1 1469 -1 1470 -1 1471 -1 1472 -1 1473 -1 1474 -1 1475 -1 1476 -1 1477 -1 1478 -1 1479 -1 1480 -1 1481 -1 1482 -1 1483 -1 1484 -1 1485 -1 1486 -1 1487 -1 1488 -1 1489 -1 1490 -1 1491 -1 1492 -1 1493 -1 1494 -1 1495 -1 1496 -1 1497 -1 1498 -1 1499 -1 1500 -1 1501 -1 1502 -1 1503 -1 1504 -1 1505 -1 1506 -1 1507 -1 1508 -1 1509 -1 1510 -1 1511 -1 1512 -1 1513 -1 1514 -1 1515 -1 1516 -1 1517 -1 1518 -1 1519 -1 1520 -1 1521 -1 1522 -1 1523 -1 1524 -1 1525 -1 1526 -1 1527 -1 1528 -1 1529 -1 1530 -1 1531 -1 1532 -1 1533 -1 1534 -1 1535 -1 1536 -1 1537 -1 1538 -1 1539 -1 1540 -1 1541 -1 1542 -1 1543 -1 1544 -1 1545 -1 1546 -1 1547 -1 1548 -1 1549 -1 1550 -1 1551 -1 1552 -1 1553 -1 1554 -1 1555 -1 1556 -1 1557 -1 1558 -1 1559 -1 1560 -1 1561 -1 1562 -1 1563 -1 1564 -1 1565 -1 1566 -1 1567 -1 1568 -1 1569 -1 1570 -1 1571 -1 1572 -1 1573 -1 1574 -1 1575 -1 1576 -1 1577 -1 1578 -1 1579 -1 1580 -1 1581 -1 1582 -1 1583 -1 1584 -1 1585 -1 1586 -1 1587 -1 1588 -1 1589 -1 1590 -1 1591 -1 1592 -1 1593 -1 1594 -1 1595 -1 1596 -1 1597 -1 1598 -1 1599 -1 1600 -1 1601 -1 1602 -1 1603 -1 1604 -1 1605 -1 1606 -1 1607 -1 1608 -1 1609 -1 1610 -1 1611 -1 1612 -1 1613 -1 1614 -1 1615 -1 1616 -1 1617 -1 1618 -1 1619 -1 1620 -1 1621 -1 1622 -1 1623 -1 1624 -1 1625 -1 1626 -1 1627 -1 1628 -1 1629 -1 1630 -1 1631 -1 1632 -1 1633 -1 1634 -1 1635 -1 1636 -1 1637 -1 1638 -1 1639 -1 1640 -1 1641 -1 1642 -1 1643 -1 1644 -1 1645 -1 1646 -1 1647 -1 1648 -1 1649 -1 1650 -1 1651 -1 1652 -1 1653 -1 1654 -1 1655 -1 1656 -1 1657 -1 1658 -1 1659 -1 1660 -1 1661 -1 1662 -1 1663 -1 1664 -1 1665 -1 1666 -1 1667 -1 1668 -1 1669 -1 1670 -1 1671 -1 1672 -1 1673 -1 1674 -1 1675 -1 1676 -1 1677 -1 1678 -1 1679 -1 1680 -1 1681 -1 1682 -1 1683 -1 1684 -1 1685 -1 1686 -1 1687 -1 1688 -1 1689 -1 1690 -1 1691 -1 1692 -1 1693 -1 1694 -1 1695 -1 1696 -1 1697 -1 1698 -1 1699 -1 1700 -1 1701 -1 1702 -1 1703 -1 1704 -1 1705 -1 1706 -1 1707 -1 1708 -1 1709 -1 1710 -1 1711 -1 1712 -1 1713 -1 1714 -1 1715 -1 1716 -1 1717 -1 1718 -1 1719 -1 1720 -1 1721 -1 1722 -1 1723 -1 1724 -1 1725 -1 1726 -1 1727 -1 1728 -1 1729 -1 1730 -1 1731 -1 1732 -1 1733 -1 1734 -1 1735 -1 1736 -1 1737 -1 1738 -1 1739 -1 1740 -1 1741 -1 1742 -1 1743 -1 1744 -1 1745 -1 1746 -1 1747 -1 1748 -1 1749 -1 1750 -1 1751 -1 1752 -1 1753 -1 1754 -1 1755 -1 1756 -1 1757 -1 1758 -1 1759 -1 1760 -1 1761 -1 1762 -1 1763 -1 1764 -1 1765 -1 1766 -1 1767 -1 1768 -1 1769 -1 1770 -1 1771 -1 1772 -1 1773 -1 1774 -1 1775 -1 1776 -1 1777 -1 1778 -1 1779 -1 1780 -1 1781 -1 1782 -1 1783 -1 1784 -1 1785 -1 1786 -1 1787 -1 1788 -1 1789 -1 1790 -1 1791 -1 1792 -1 1793 -1 1794 -1 1795 -1 1796 -1 1797 -1 1798 -1 1799 -1 1800 -1 1801 -1 1802 -1 1803 -1 1804 -1 1805 -1 1806 -1 1807 -1 1808 -1 1809 -1 1810 -1 1811 -1 1812 -1 1813 -1 1814 -1 1815 -1 1816 -1 1817 -1 1818 -1 1819 -1 1820 -1 1821 -1 1822 -1 1823 -1 1824 -1 1825 -1 1826 -1 1827 -1 1828 -1 1829 -1 1830 -1 1831 -1 1832 -1 1833 -1 1834 -1 1835 -1 1836 -1 1837 -1 1838 -1 1839 -1 1840 -1 1841 -1 1842 -1 1843 -1 1844 -1 1845 -1 1846 -1 1847 -1 1848 -1 1849 -1 1850 -1 1851 -1 1852 -1 1853 -1 1854 -1 1855 -1 1856 -1 1857 -1 1858 -1 1859 -1 1860 -1 1861 -1 1862 -1 1863 -1 1864 -1 1865 -1 1866 -1 1867 -1 1868 -1 1869 -1 1870 -1 1871 -1 1872 -1 1873 -1 1874 -1 1875 -1 1876 -1 1877 -1 1878 -1 1879 -1 1880 -1 1881 -1 1882 -1 1883 -1 1884 -1 1885 -1 1886 -1 1887 -1 1888 -1 1889 -1 1890 -1 1891 -1 1892 -1 1893 -1 1894 -1 1895 -1 1896 -1 1897 -1 1898 -1 1899 -1 1900 -1 1901 -1 1902 -1 1903 -1 1904 -1 1905 -1 1906 -1 1907 -1 1908 -1 1909 -1 1910 -1 1911 -1 1912 -1 1913 -1 1914 -1 1915 -1 1916 -1 1917 -1 1918 -1 1919 -1 1920 -1 1921 -1 1922 -1 1923 -1 1924 -1 1925 -1 1926 -1 1927 -1 1928 -1 1929 -1 1930 -1 1931 -1 1932 -1 1933 -1 1934 -1 1935 -1 1936 -1 1937 -1 1938 -1 1939 -1 1940 -1 1941 -1 1942 -1 1943 -1 1944 -1 1945 -1 1946 -1 1947 -1 1948 -1 1949 -1 1950 -1 1951 -1 1952 -1 1953 -1 1954 -1 1955 -1 1956 -1 1957 -1 1958 -1 1959 -1 1960 -1 1961 -1 1962 -1 1963 -1 1964 -1 1965 -1 1966 -1 1967 -1 1968 -1 1969 -1 1970 -1 1971 -1 1972 -1 1973 -1 1974 -1 1975 -1 1976 -1 1977 -1 1978 -1 1979 -1 1980 -1 1981 -1 1982 -1 1983 -1 1984 -1 1985 -1 1986 -1 1987 -1 1988 -1 1989 -1 1990 -1 1991 -1 1992 -1 1993 -1 1994 -1 1995 -1 1996 -1 1997 -1 1998 -1 1999 -1 2000 -1 2001 -1 2002 -1 2003 -1 2004 -1 2005 -1 2006 -1 2007 -1 2008 -1 2009 -1 2010 -1 2011 -1 2012 -1 2013 -1 2014 -1 2015 -1 2016 -1 2017 -1 2018 -1 2019 -1 2020 -1 2021 -1 2022 -1 2023 -1 2024 -1 2025 -1 2026 -1 2027 -1 2028 -1 2029 -1 2030 -1 2031 -1 2032 -1 2033 -1 2034 -1 2035 -1 2036 -1 2037 -1 2038 -1 2039 -1 2040 -1 2041 -1 2042 -1 2043 -1 2044 -1 2045 -1 2046 -1 2047 -1 2048 -1 2049 -1 2050 -1 2051 -1 2052 -1 2053 -1 2054 -1 2055 -1 2056 -1 2057 -1 2058 -1 2059 -1 2060 -1 2061 -1 2062 -1 2063 -1 2064 -1 2065 -1 2066 -1 2067 -1 2068 -1 2069 -1 2070 -1 2071 -1 2072 -1 2073 -1 2074 -1 2075 -1 2076 -1 2077 -1 2078 -1 2079 -1 2080 -1 2081 -1 2082 -1 2083 -1 2084 -1 2085 -1 2086 -1 2087 -1 2088 -1 2089 -1 2090 -1 2091 -1 2092 -1 2093 -1 2094 -1 2095 -1 2096 -1 2097 -1 2098 -1 2099 -1 2100 -1 2101 -1 2102 -1 2103 -1 2104 -1 2105 -1 2106 -1 2107 -1 2108 -1 2109 -1 2110 -1 2111 -1 2112 -1 2113 -1 2114 -1 2115 -1 2116 -1 2117 -1 2118 -1 2119 -1 2120 -1 2121 -1 2122 -1 2123 -1 2124 -1 2125 -1 2126 -1 2127 -1 2128 -1 2129 -1 2130 -1 2131 -1 2132 -1 2133 -1 2134 -1 2135 -1 2136 -1 2137 -1 2138 -1 2139 -1 2140 -1 2141 -1 2142 -1 2143 -1 2144 -1 2145 -1 2146 -1 2147 -1 2148 -1 2149 -1 2150 -1 2151 -1 2152 -1 2153 -1 2154 -1 2155 -1 2156 -1 2157 -1 2158 -1 2159 -1 2160 -1 2161 -1 2162 -1 2163 -1 2164 -1 2165 -1 2166 -1 2167 -1 2168 -1 2169 -1 2170 -1 2171 -1 2172 -1 2173 -1 2174 -1 2175 -1 2176 -1 2177 -1 2178 -1 2179 -1 2180 -1 2181 -1 2182 -1 2183 -1 2184 -1 2185 -1 2186 -1 2187 -1 2188 -1 2189 -1 2190 -1 2191 -1 2192 -1 2193 -1 2194 -1 2195 -1 2196 -1 2197 -1 2198 -1 2199 -1 2200 -1 2201 -1 2202 -1 2203 -1 2204 -1 2205 -1 2206 -1 2207 -1 2208 -1 2209 -1 2210 -1 2211 -1 2212 -1 2213 -1 2214 -1 2215 -1 2216 -1 2217 -1 2218 -1 2219 -1 2220 -1 2221 -1 2222 -1 2223 -1 2224 -1 2225 -1 2226 -1 2227 -1 2228 -1 2229 -1 2230 -1 2231 -1 2232 -1 2233 -1 2234 -1 2235 -1 2236 -1 2237 -1 2238 -1 2239 -1 2240 -1 2241 -1 2242 -1 2243 -1 2244 -1 2245 -1 2246 -1 2247 -1 2248 -1 2249 -1 2250 -1 2251 -1 2252 -1 2253 -1 2254 -1 2255 -1 2256 -1 2257 -1 2258 -1 2259 -1 2260 -1 2261 -1 2262 -1 2263 -1 2264 -1 2265 -1 2266 -1 2267 -1 2268 -1 2269 -1 2270 -1 2271 -1 2272 -1 2273 -1 2274 -1 2275 -1 2276 -1 2277 -1 2278 -1 2279 -1 2280 -1 2281 -1 2282 -1 2283 -1 2284 -1 2285 -1 2286 -1 2287 -1 2288 -1 2289 -1 2290 -1 2291 -1 2292 -1 2293 -1 2294 -1 2295 -1 2296 -1 2297 -1 2298 -1 2299 -1 2300 -1 2301 -1 2302 -1 2303 -1 2304 -1 2305 -1 2306 -1 2307 -1 2308 -1 2309 -1 2310 -1 2311 -1 2312 -1 2313 -1 2314 -1 2315 -1 2316 -1 2317 -1 2318 -1 2319 -1 2320 -1 2321 -1 2322 -1 2323 -1 2324 -1 2325 -1 2326 -1 2327 -1 2328 -1 2329 -1 2330 -1 2331 -1 2332 -1 2333 -1 2334 -1 2335 -1 2336 -1 2337 -1 2338 -1 2339 -1 2340 -1 2341 -1 2342 -1 2343 -1 2344 -1 2345 -1 2346 -1 2347 -1 2348 -1 2349 -1 2350 -1 2351 -1 2352 -1 2353 -1 2354 -1 2355 -1 2356 -1 2357 -1 2358 -1 2359 -1 2360 -1 2361 -1 2362 -1 2363 -1 2364 -1 2365 -1 2366 -1 2367 -1 2368 -1 2369 -1 2370 -1 2371 -1 2372 -1 2373 -1 2374 -1 2375 -1 2376 -1 2377 -1 2378 -1 2379 -1 2380 -1 2381 -1 2382 -1 2383 -1 2384 -1 2385 -1 2386 -1 2387 -1 2388 -1 2389 -1 2390 -1 2391 -1 2392 -1 2393 -1 2394 -1 2395 -1 2396 -1 2397 -1 2398 -1 2399 -1 2400 -1 2401 -1 2402 -1 2403 -1 2404 -1 2405 -1 2406 -1 2407 -1 2408 -1 2409 -1 2410 -1 2411 -1 2412 -1 2413 -1 2414 -1 2415 -1 2416 -1 2417 -1 2418 -1 2419 -1 2420 -1 2421 -1 2422 -1 2423 -1 2424 -1 2425 -1 2426 -1 2427 -1 2428 -1 2429 -1 2430 -1 2431 -1 2432 -1 2433 -1 2434 -1 2435 -1 2436 -1 2437 -1 2438 -1 2439 -1 2440 -1 2441 -1 2442 -1 2443 -1 2444 -1 2445 -1 2446 -1 2447 -1 2448 -1 2449 -1 2450 -1 2451 -1 2452 -1 2453 -1 2454 -1 2455 -1 2456 -1 2457 -1 2458 -1 2459 -1 2460 -1 2461 -1 2462 -1 2463 -1 2464 -1 2465 -1 2466 -1 2467 -1 2468 -1 2469 -1 2470 -1 2471 -1 2472 -1 2473 -1 2474 -1 2475 -1 2476 -1 2477 -1 2478 -1 2479 -1 2480 -1 2481 -1 2482 -1 2483 -1 2484 -1 2485 -1 2486 -1 2487 -1 2488 -1 2489 -1 2490 -1 2491 -1 2492 -1 2493 -1 2494 -1 2495 -1 2496 -1 2497 -1 2498 -1 2499 -1 2500 -1 2501 -1 2502 -1 2503 -1 2504 -1 2505 -1 2506 -1 2507 -1 2508 -1 2509 -1 2510 -1 2511 -1 2512 -1 2513 -1 2514 -1 2515 -1 2516 -1 2517 -1 2518 -1 2519 -1 2520 -1 2521 -1 2522 -1 2523 -1 2524 -1 2525 -1 2526 -1 2527 -1 2528 -1 2529 -1 2530 -1 2531 -1 2532 -1 2533 -1 2534 -1 2535 -1 2536 -1 2537 -1 2538 -1 2539 -1 2540 -1 2541 -1 2542 -1 2543 -1 2544 -1 2545 -1 2546 -1 2547 -1 2548 -1 2549 -1 2550 -1 2551 -1 2552 -1 2553 -1 2554 -1 2555 -1 2556 -1 2557 -1 2558 -1 2559 -1 2560 -1 2561 -1 2562 -1 2563 -1 2564 -1 2565 -1 2566 -1 2567 -1 2568 -1 2569 -1 2570 -1 2571 -1 2572 -1 2573 -1 2574 -1 2575 -1 2576 -1 2577 -1 2578 -1 2579 -1 2580 -1 2581 -1 2582 -1 2583 -1 2584 -1 2585 -1 2586 -1 2587 -1 2588 -1 2589 -1 2590 -1 2591 -1 2592 -1 2593 -1 2594 -1 2595 -1 2596 -1 2597 -1 2598 -1 2599 -1 2600 -1 2601 -1 2602 -1 2603 -1 2604 -1 2605 -1 2606 -1 2607 -1 2608 -1 2609 -1 2610 -1 2611 -1 2612 -1 2613 -1 2614 -1 2615 -1 2616 -1 2617 -1 2618 -1 2619 -1 2620 -1 2621 -1 2622 -1 2623 -1 2624 -1 2625 -1 2626 -1 2627 -1 2628 -1 2629 -1 2630 -1 2631 -1 2632 -1 2633 -1 2634 -1 2635 -1 2636 -1 2637 -1 2638 -1 2639 -1 2640 -1 2641 -1 2642 -1 2643 -1 2644 -1 2645 -1 2646 -1 2647 -1 2648 -1 2649 -1 2650 -1 2651 -1 2652 -1 2653 -1 2654 -1 2655 -1 2656 -1 2657 -1 2658 -1 2659 -1 2660 -1 2661 -1 2662 -1 2663 -1 2664 -1 2665 -1 2666 -1 2667 -1 2668 -1 2669 -1 2670 -1 2671 -1 2672 -1 2673 -1 2674 -1 2675 -1 2676 -1 2677 -1 2678 -1 2679 -1 2680 -1 2681 -1 2682 -1 2683 -1 2684 -1 2685 -1 2686 -1 2687 -1 2688 -1 2689 -1 2690 -1 2691 -1 2692 -1 2693 -1 2694 -1 2695 -1 2696 -1 2697 -1 2698 -1 2699 -1 2700 -1 2701 -1 2702 -1 2703 -1 2704 -1 2705 -1 2706 -1 2707 -1 2708 -1 2709 -1 2710 -1 2711 -1 2712 -1 2713 -1 2714 -1 2715 -1 2716 -1 2717 -1 2718 -1 2719 -1 2720 -1 2721 -1 2722 -1 2723 -1 2724 -1 2725 -1 2726 -1 2727 -1 2728 -1 2729 -1 2730 -1 2731 -1 2732 -1 2733 -1 2734 -1 2735 -1 2736 -1 2737 -1 2738 -1 2739 -1 2740 -1 2741 -1 2742 -1 2743 -1 2744 -1 2745 -1 2746 -1 2747 -1 2748 -1 2749 -1 2750 -1 2751 -1 2752 -1 2753 -1 2754 -1 2755 -1 2756 -1 2757 -1 2758 -1 2759 -1 2760 -1 2761 -1 2762 -1 2763 -1 2764 -1 2765 -1 2766 -1 2767 -1 2768 -1 2769 -1 2770 -1 2771 -1 2772 -1 2773 -1 2774 -1 2775 -1 2776 -1 2777 -1 2778 -1 2779 -1 2780 -1 2781 -1 2782 -1 2783 -1 2784 -1 2785 -1 2786 -1 2787 -1 2788 -1 2789 -1 2790 -1 2791 -1 2792 -1 2793 -1 2794 -1 2795 -1 2796 -1 2797 -1 2798 -1 2799 -1 2800 -1 2801 -1 2802 -1 2803 -1 2804 -1 2805 -1 2806 -1 2807 -1 2808 -1 2809 -1 2810 -1 2811 -1 2812 -1 2813 -1 2814 -1 2815 -1 2816 -1 2817 -1 2818 -1 2819 -1 2820 -1 2821 -1 2822 -1 2823 -1 2824 -1 2825 -1 2826 -1 2827 -1 2828 -1 2829 -1 2830 -1 2831 -1 2832 -1 2833 -1 2834 -1 2835 -1 2836 -1 2837 -1 2838 -1 2839 -1 2840 -1 2841 -1 2842 -1 2843 -1 2844 -1 2845 -1 2846 -1 2847 -1 2848 -1 2849 -1 2850 -1 2851 -1 2852 -1 2853 -1 2854 -1 2855 -1 2856 -1 2857 -1 2858 -1 2859 -1 2860 -1 2861 -1 2862 -1 2863 -1 2864 -1 2865 -1 2866 -1 2867 -1 2868 -1 2869 -1 2870 -1 2871 -1 2872 -1 2873 -1 2874 -1 2875 -1 2876 -1 2877 -1 2878 -1 2879 -1 2880 -1 2881 -1 2882 -1 2883 -1 2884 -1 2885 -1 2886 -1 2887 -1 2888 -1 2889 -1 2890 -1 2891 -1 2892 -1 2893 -1 2894 -1 2895 -1 2896 -1 2897 -1 2898 -1 2899 -1 2900 -1 2901 -1 2902 -1 2903 -1 2904 -1 2905 -1 2906 -1 2907 -1 2908 -1 2909 -1 2910 -1 2911 -1 2912 -1 2913 -1 2914 -1 2915 -1 2916 -1 2917 -1 2918 -1 2919 -1 2920 -1 2921 -1 2922 -1 2923 -1 2924 -1 2925 -1 2926 -1 2927 -1 2928 -1 2929 -1 2930 -1 2931 -1 2932 -1 2933 -1 2934 -1 2935 -1 2936 -1 2937 -1 2938 -1 2939 -1 2940 -1 2941 -1 2942 -1 2943 -1 2944 -1 2945 -1 2946 -1 2947 -1 2948 -1 2949 -1 2950 -1 2951 -1 2952 -1 2953 -1 2954 -1 2955 -1 2956 -1 2957 -1 2958 -1 2959 -1 2960 -1 2961 -1 2962 -1 2963 -1 2964 -1 2965 -1 2966 -1 2967 -1 2968 -1 2969 -1 2970 -1 2971 -1 2972 -1 2973 -1 2974 -1 2975 -1 2976 -1 2977 -1 2978 -1 2979 -1 2980 -1 2981 -1 2982 -1 2983 -1 2984 -1 2985 -1 2986 -1 2987 -1 2988 -1 2989 -1 2990 -1 2991 -1 2992 -1 2993 -1 2994 -1 2995 -1 2996 -1 2997 -1 2998 -1 2999 -1 3000 -1 3001 -1 3002 -1 3003 -1 3004 -1 3005 -1 3006 -1 3007 -1 3008 -1 3009 -1 3010 -1 3011 -1 3012 -1 3013 -1 3014 -1 3015 -1 3016 -1 3017 -1 3018 -1 3019 -1 3020 -1 3021 -1 3022 -1 3023 -1 3024 -1 3025 -1 3026 -1 3027 -1 3028 -1 3029 -1 3030 -1 3031 -1 3032 -1 3033 -1 3034 -1 3035 -1 3036 -1 3037 -1 3038 -1 3039 -1 3040 -1 3041 -1 3042 -1 3043 -1 3044 -1 3045 -1 3046 -1 3047 -1 3048 -1 3049 -1 3050 -1 3051 -1 3052 -1 3053 -1 3054 -1 3055 -1 3056 -1 3057 -1 3058 -1 3059 -1 3060 -1 3061 -1 3062 -1 3063 -1 3064 -1 3065 -1 3066 -1 3067 -1 3068 -1 3069 -1 3070 -1 3071 -1 3072 -1 3073 -1 3074 -1 3075 -1 3076 -1 3077 -1 3078 -1 3079 -1 3080 -1 3081 -1 3082 -1 3083 -1 3084 -1 3085 -1 3086 -1 3087 -1 3088 -1 3089 -1 3090 -1 3091 -1 3092 -1 3093 -1 3094 -1 3095 -1 3096 -1 3097 -1 3098 -1 3099 -1 3100 -1 3101 -1 3102 -1 3103 -1 3104 -1 3105 -1 3106 -1 3107 -1 3108 -1 3109 -1 3110 -1 3111 -1 3112 -1 3113 -1 3114 -1 3115 -1 3116 -1 3117 -1 3118 -1 3119 -1 3120 -1 3121 -1 3122 -1 3123 -1 3124 -1 3125 -1 3126 -1 3127 -1 3128 -1 3129 -1 3130 -1 3131 -1 3132 -1 3133 -1 3134 -1 3135 -1 3136 -1 3137 -1 3138 -1 3139 -1 3140 -1 3141 -1 3142 -1 3143 -1 3144 -1 3145 -1 3146 -1 3147 -1 3148 -1 3149 -1 3150 -1 3151 -1 3152 -1 3153 -1 3154 -1 3155 -1 3156 -1 3157 -1 3158 -1 3159 -1 3160 -1 3161 -1 3162 -1 3163 -1 3164 -1 3165 -1 3166 -1 3167 -1 3168 -1 3169 -1 3170 -1 3171 -1 3172 -1 3173 -1 3174 -1 3175 -1 3176 -1 3177 -1 3178 -1 3179 -1 3180 -1 3181 -1 3182 -1 3183 -1 3184 -1 3185 -1 3186 -1 3187 -1 3188 -1 3189 -1 3190 -1 3191 -1 3192 -1 3193 -1 3194 -1 3195 -1 3196 -1 3197 -1 3198 -1 3199 -1 3200 -1 3201 -1 3202 -1 3203 -1 3204 -1 3205 -1 3206 -1 3207 -1 3208 -1 3209 -1 3210 -1 3211 -1 3212 -1 3213 -1 3214 -1 3215 -1 3216 -1 3217 -1 3218 -1 3219 -1 3220 -1 3221 -1 3222 -1 3223 -1 3224 -1 3225 -1 3226 -1 3227 -1 3228 -1 3229 -1 3230 -1 3231 -1 3232 -1 3233 -1 3234 -1 3235 -1 3236 -1 3237 -1 3238 -1 3239 -1 3240 -1 3241 -1 3242 -1 3243 -1 3244 -1 3245 -1 3246 -1 3247 -1 3248 -1 3249 -1 3250 -1 3251 -1 3252 -1 3253 -1 3254 -1 3255 -1 3256 -1 3257 -1 3258 -1 3259 -1 3260 -1 3261 -1 3262 -1 3263 -1 3264 -1 3265 -1 3266 -1 3267 -1 3268 -1 3269 -1 3270 -1 3271 -1 3272 -1 3273 -1 3274 -1 3275 -1 3276 -1 3277 -1 3278 -1 3279 -1 3280 -1 3281 -1 3282 -1 3283 -1 3284 -1 3285 -1 3286 -1 3287 -1 3288 -1 3289 -1 3290 -1 3291 -1 3292 -1 3293 -1 3294 -1 3295 -1 3296 -1 3297 -1 3298 -1 3299 -1 3300 -1 3301 -1 3302 -1 3303 -1 3304 -1 3305 -1 3306 -1 3307 -1 3308 -1 3309 -1 3310 -1 3311 -1 3312 -1 3313 -1 3314 -1 3315 -1 3316 -1 3317 -1 3318 -1 3319 -1 3320 -1 3321 -1 3322 -1 3323 -1 3324 -1 3325 -1 3326 -1 3327 -1 3328 -1 3329 -1 3330 -1 3331 -1 3332 -1 3333 -1 3334 -1 3335 -1 3336 -1 3337 -1 3338 -1 3339 -1 3340 -1 3341 -1 3342 -1 3343 -1 3344 -1 3345 -1 3346 -1 3347 -1 3348 -1 3349 -1 3350 -1 3351 -1 3352 -1 3353 -1 3354 -1 3355 -1 3356 -1 3357 -1 3358 -1 3359 -1 3360 -1 3361 -1 3362 -1 3363 -1 3364 -1 3365 -1 3366 -1 3367 -1 3368 -1 3369 -1 3370 -1 3371 -1 3372 -1 3373 -1 3374 -1 3375 -1 3376 -1 3377 -1 3378 -1 3379 -1 3380 -1 3381 -1 3382 -1 3383 -1 3384 -1 3385 -1 3386 -1 3387 -1 3388 -1 3389 -1 3390 -1 3391 -1 3392 -1 3393 -1 3394 -1 3395 -1 3396 -1 3397 -1 3398 -1 3399 -1 3400 -1 3401 -1 3402 -1 3403 -1 3404 -1 3405 -1 3406 -1 3407 -1 3408 -1 3409 -1 3410 -1 3411 -1 3412 -1 3413 -1 3414 -1 3415 -1 3416 -1 3417 -1 3418 -1 3419 -1 3420 -1 3421 -1 3422 -1 3423 -1 3424 -1 3425 -1 3426 -1 3427 -1 3428 -1 3429 -1 3430 -1 3431 -1 3432 -1 3433 -1 3434 -1 3435 -1 3436 -1 3437 -1 3438 -1 3439 -1 3440 -1 3441 -1 3442 -1 3443 -1 3444 -1 3445 -1 3446 -1 3447 -1 3448 -1 3449 -1 3450 -1 3451 -1 3452 -1 3453 -1 3454 -1 3455 -1 3456 -1 3457 -1 3458 -1 3459 -1 3460 -1 3461 -1 3462 -1 3463 -1 3464 -1 3465 -1 3466 -1 3467 -1 3468 -1 3469 -1 3470 -1 3471 -1 3472 -1 3473 -1 3474 -1 3475 -1 3476 -1 3477 -1 3478 -1 3479 -1 3480 -1 3481 -1 3482 -1 3483 -1 3484 -1 3485 -1 3486 -1 3487 -1 3488 -1 3489 -1 3490 -1 3491 -1 3492 -1 3493 -1 3494 -1 3495 -1 3496 -1 3497 -1 3498 -1 3499 -1 3500 -1 3501 -1 3502 -1 3503 -1 3504 -1 3505 -1 3506 -1 3507 -1 3508 -1 3509 -1 3510 -1 3511 -1 3512 -1 3513 -1 3514 -1 3515 -1 3516 -1 3517 -1 3518 -1 3519 -1 3520 -1 3521 -1 3522 -1 3523 -1 3524 -1 3525 -1 3526 -1 3527 -1 3528 -1 3529 -1 3530 -1 3531 -1 3532 -1 3533 -1 3534 -1 3535 -1 3536 -1 3537 -1 3538 -1 3539 -1 3540 -1 3541 -1 3542 -1 3543 -1 3544 -1 3545 -1 3546 -1 3547 -1 3548 -1 3549 -1 3550 -1 3551 -1 3552 -1 3553 -1 3554 -1 3555 -1 3556 -1 3557 -1 3558 -1 3559 -1 3560 -1 3561 -1 3562 -1 3563 -1 3564 -1 3565 -1 3566 -1 3567 -1 3568 -1 3569 -1 3570 -1 3571 -1 3572 -1 3573 -1 3574 -1 3575 -1 3576 -1 3577 -1 3578 -1 3579 -1 3580 -1 3581 -1 3582 -1 3583 -1 3584 -1 3585 -1 3586 -1 3587 -1 3588 -1 3589 -1 3590 -1 3591 -1 3592 -1 3593 -1 3594 -1 3595 -1 3596 -1 3597 -1 3598 -1 3599 -1 3600 -1 3601 -1 3602 -1 3603 -1 3604 -1 3605 -1 3606 -1 3607 -1 3608 -1 3609 -1 3610 -1 3611 -1 3612 -1 3613 -1 3614 -1 3615 -1 3616 -1 3617 -1 3618 -1 3619 -1 3620 -1 3621 -1 3622 -1 3623 -1 3624 -1 3625 -1 3626 -1 3627 -1 3628 -1 3629 -1 3630 -1 3631 -1 3632 -1 3633 -1 3634 -1 3635 -1 3636 -1 3637 -1 3638 -1 3639 -1 3640 -1 3641 -1 3642 -1 3643 -1 3644 -1 3645 -1 3646 -1 3647 -1 3648 -1 3649 -1 3650 -1 3651 -1 3652 -1 3653 -1 3654 -1 3655 -1 3656 -1 3657 -1 3658 -1 3659 -1 3660 -1 3661 -1 3662 -1 3663 -1 3664 -1 3665 -1 3666 -1 3667 -1 3668 -1 3669 -1 3670 -1 3671 -1 3672 -1 3673 -1 3674 -1 3675 -1 3676 -1 3677 -1 3678 -1 3679 -1 3680 -1 3681 -1 3682 -1 3683 -1 3684 -1 3685 -1 3686 -1 3687 -1 3688 -1 3689 -1 3690 -1 3691 -1 3692 -1 3693 -1 3694 -1 3695 -1 3696 -1 3697 -1 3698 -1 3699 -1 3700 -1 3701 -1 3702 -1 3703 -1 3704 -1 3705 -1 3706 -1 3707 -1 3708 -1 3709 -1 3710 -1 3711 -1 3712 -1 3713 -1 3714 -1 3715 -1 3716 -1 3717 -1 3718 -1 3719 -1 3720 -1 3721 -1 3722 -1 3723 -1 3724 -1 3725 -1 3726 -1 3727 -1 3728 -1 3729 -1 3730 -1 3731 -1 3732 -1 3733 -1 3734 -1 3735 -1 3736 -1 3737 -1 3738 -1 3739 -1 3740 -1 3741 -1 3742 -1 3743 -1 3744 -1 3745 -1 3746 -1 3747 -1 3748 -1 3749 -1 3750 -1 3751 -1 3752 -1 3753 -1 3754 -1 3755 -1 3756 -1 3757 -1 3758 -1 3759 -1 3760 -1 3761 -1 3762 -1 3763 -1 3764 -1 3765 -1 3766 -1 3767 -1 3768 -1 3769 -1 3770 -1 3771 -1 3772 -1 3773 -1 3774 -1 3775 -1 3776 -1 3777 -1 3778 -1 3779 -1 3780 -1 3781 -1 3782 -1 3783 -1 3784 -1 3785 -1 3786 -1 3787 -1 3788 -1 3789 -1 3790 -1 3791 -1 3792 -1 3793 -1 3794 -1 3795 -1 3796 -1 3797 -1 3798 -1 3799 -1 3800 -1 3801 -1 3802 -1 3803 -1 3804 -1 3805 -1 3806 -1 3807 -1 3808 -1 3809 -1 3810 -1 3811 -1 3812 -1 3813 -1 3814 -1 3815 -1 3816 -1 3817 -1 3818 -1 3819 -1 3820 -1 3821 -1 3822 -1 3823 -1 3824 -1 3825 -1 3826 -1 3827 -1 3828 -1 3829 -1 3830 -1 3831 -1 3832 -1 3833 -1 3834 -1 3835 -1 3836 -1 3837 -1 3838 -1 3839 -1 3840 -1 3841 -1 3842 -1 3843 -1 3844 -1 3845 -1 3846 -1 3847 -1 3848 -1 3849 -1 3850 -1 3851 -1 3852 -1 3853 -1 3854 -1 3855 -1 3856 -1 3857 -1 3858 -1 3859 -1 3860 -1 3861 -1 3862 -1 3863 -1 3864 -1 3865 -1 3866 -1 3867 -1 3868 -1 3869 -1 3870 -1 3871 -1 3872 -1 3873 -1 3874 -1 3875 -1 3876 -1 3877 -1 3878 -1 3879 -1 3880 -1 3881 -1 3882 -1 3883 -1 3884 -1 3885 -1 3886 -1 3887 -1 3888 -1 3889 -1 3890 -1 3891 -1 3892 -1 3893 -1 3894 -1 3895 -1 3896 -1 3897 -1 3898 -1 3899 -1 3900 -1 3901 -1 3902 -1 3903 -1 3904 -1 3905 -1 3906 -1 3907 -1 3908 -1 3909 -1 3910 -1 3911 -1 3912 -1 3913 -1 3914 -1 3915 -1 3916 -1 3917 -1 3918 -1 3919 -1 3920 -1 3921 -1 3922 -1 3923 -1 3924 -1 3925 -1 3926 -1 3927 -1 3928 -1 3929 -1 3930 -1 3931 -1 3932 -1 3933 -1 3934 -1 3935 -1 3936 -1 3937 -1 3938 -1 3939 -1 3940 -1 3941 -1 3942 -1 3943 -1 3944 -1 3945 -1 3946 -1 3947 -1 3948 -1 3949 -1 3950 -1 3951 -1 3952 -1 3953 -1 3954 -1 3955 -1 3956 -1 3957 -1 3958 -1 3959 -1 3960 -1 3961 -1 3962 -1 3963 -1 3964 -1 3965 -1 3966 -1 3967 -1 3968 -1 3969 -1 3970 -1 3971 -1 3972 -1 3973 -1 3974 -1 3975 -1 3976 -1 3977 -1 3978 -1 3979 -1 3980 -1 3981 -1 3982 -1 3983 -1 3984 -1 3985 -1 3986 -1 3987 -1 3988 -1 3989 -1 3990 -1 3991 -1 3992 -1 3993 -1 3994 -1 3995 -1 3996 -1 3997 -1 3998 -1 3999 -1 4000 -1 4001 -1 4002 -1 4003 -1 4004 -1 4005 -1 4006 -1 4007 -1 4008 -1 4009 -1 4010 -1 4011 -1 4012 -1 4013 -1 4014 -1 4015 -1 4016 -1 4017 -1 4018 -1 4019 -1 4020 -1 4021 -1 4022 -1 4023 -1 4024 -1 4025 -1 4026 -1 4027 -1 4028 -1 4029 -1 4030 -1 4031 -1 4032 -1 4033 -1 4034 -1 4035 -1 4036 -1 4037 -1 4038 -1 4039 -1 4040 -1 4041 -1 4042 -1 4043 -1 4044 -1 4045 -1 4046 -1 4047 -1 4048 -1 4049 -1 4050 -1 4051 -1 4052 -1 4053 -1 4054 -1 4055 -1 4056 -1 4057 -1 4058 -1 4059 -1 4060 -1 4061 -1 4062 -1 4063 -1 4064 -1 4065 -1 4066 -1 4067 -1 4068 -1 4069 -1 4070 -1 4071 -1 4072 -1 4073 -1 4074 -1 4075 -1 4076 -1 4077 -1 4078 -1 4079 -1 4080 -1 4081 -1 4082 -1 4083 -1 4084 -1 4085 -1 4086 -1 4087 -1 4088 -1 4089 -1 4090 -1 4091 -1 4092 -1 4093 -1 4094 -1 4095 -1 4096 -1 4097 -1 4098 -1 4099 -1 4100 -1 4101 -1 4102 -1 4103 -1 4104 -1 4105 -1 4106 -1 4107 -1 4108 -1 4109 -1 4110 -1 4111 -1 4112 -1 4113 -1 4114 -1 4115 -1 4116 -1 4117 -1 4118 -1 4119 -1 4120 -1 4121 -1 4122 -1 4123 -1 4124 -1 4125 -1 4126 -1 4127 -1 4128 -1 4129 -1 4130 -1 4131 -1 4132 -1 4133 -1 4134 -1 4135 -1 4136 -1 4137 -1 4138 -1 4139 -1 4140 -1 4141 -1 4142 -1 4143 -1 4144 -1 4145 -1 4146 -1 4147 -1 4148 -1 4149 -1 4150 -1 4151 -1 4152 -1 4153 -1 4154 -1 4155 -1 4156 -1 4157 -1 4158 -1 4159 -1 4160 -1 4161 -1 4162 -1 4163 -1 4164 -1 4165 -1 4166 -1 4167 -1 4168 -1 4169 -1 4170 -1 4171 -1 4172 -1 4173 -1 4174 -1 4175 -1 4176 -1 4177 -1 4178 -1 4179 -1 4180 -1 4181 -1 4182 -1 4183 -1 4184 -1 4185 -1 4186 -1 4187 -1 4188 -1 4189 -1 4190 -1 4191 -1 4192 -1 4193 -1 4194 -1 4195 -1 4196 -1 4197 -1 4198 -1 4199 -1 4200 -1 4201 -1 4202 -1 4203 -1 4204 -1 4205 -1 4206 -1 4207 -1 4208 -1 4209 -1 4210 -1 4211 -1 4212 -1 4213 -1 4214 -1 4215 -1 4216 -1 4217 -1 4218 -1 4219 -1 4220 -1 4221 -1 4222 -1 4223 -1 4224 -1 4225 -1 4226 -1 4227 -1 4228 -1 4229 -1 4230 -1 4231 -1 4232 -1 4233 -1 4234 -1 4235 -1 4236 -1 4237 -1 4238 -1 4239 -1 4240 -1 4241 -1 4242 -1 4243 -1 4244 -1 4245 -1 4246 -1 4247 -1 4248 -1 4249 -1 4250 -1 4251 -1 4252 -1 4253 -1 4254 -1 4255 -1 4256 -1 4257 -1 4258 -1 4259 -1 4260 -1 4261 -1 4262 -1 4263 -1 4264 -1 4265 -1 4266 -1 4267 -1 4268 -1 4269 -1 4270 -1 4271 -1 4272 -1 4273 -1 4274 -1 4275 -1 4276 -1 4277 -1 4278 -1 4279 -1 4280 -1 4281 -1 4282 -1 4283 -1 4284 -1 4285 -1 4286 -1 4287 -1 4288 -1 4289 -1 4290 -1 4291 -1 4292 -1 4293 -1 4294 -1 4295 -1 4296 -1 4297 -1 4298 -1 4299 -1 4300 -1 4301 -1 4302 -1 4303 -1 4304 -1 4305 -1 4306 -1 4307 -1 4308 -1 4309 -1 4310 -1 4311 -1 4312 -1 4313 -1 4314 -1 4315 -1 4316 -1 4317 -1 4318 -1 4319 -1 4320 -1 4321 -1 4322 -1 4323 -1 4324 -1 4325 -1 4326 -1 4327 -1 4328 -1 4329 -1 4330 -1 4331 -1 4332 -1 4333 -1 4334 -1 4335 -1 4336 -1 4337 -1 4338 -1 4339 -1 4340 -1 4341 -1 4342 -1 4343 -1 4344 -1 4345 -1 4346 -1 4347 -1 4348 -1 4349 -1 4350 -1 4351 -1 4352 -1 4353 -1 4354 -1 4355 -1 4356 -1 4357 -1 4358 -1 4359 -1 4360 -1 4361 -1 4362 -1 4363 -1 4364 -1 4365 -1 4366 -1 4367 -1 4368 -1 4369 -1 4370 -1 4371 -1 4372 -1 4373 -1 4374 -1 4375 -1 4376 -1 4377 -1 4378 -1 4379 -1 4380 -1 4381 -1 4382 -1 4383 -1 4384 -1 4385 -1 4386 -1 4387 -1 4388 -1 4389 -1 4390 -1 4391 -1 4392 -1 4393 -1 4394 -1 4395 -1 4396 -1 4397 -1 4398 -1 4399 -1 4400 -1 4401 -1 4402 -1 4403 -1 4404 -1 4405 -1 4406 -1 4407 -1 4408 -1 4409 -1 4410 -1 4411 -1 4412 -1 4413 -1 4414 -1 4415 -1 4416 -1 4417 -1 4418 -1 4419 -1 4420 -1 4421 -1 4422 -1 4423 -1 4424 -1 4425 -1 4426 -1 4427 -1 4428 -1 4429 -1 4430 -1 4431 -1 4432 -1 4433 -1 4434 -1 4435 -1 4436 -1 4437 -1 4438 -1 4439 -1 4440 -1 4441 -1 4442 -1 4443 -1 4444 -1 4445 -1 4446 -1 4447 -1 4448 -1 4449 -1 4450 -1 4451 -1 4452 -1 4453 -1 4454 -1 4455 -1 4456 -1 4457 -1 4458 -1 4459 -1 4460 -1 4461 -1 4462 -1 4463 -1 4464 -1 4465 -1 4466 -1 4467 -1 4468 -1 4469 -1 4470 -1 4471 -1 4472 -1 4473 -1 4474 -1 4475 -1 4476 -1 4477 -1 4478 -1 4479 -1 4480 -1 4481 -1 4482 -1 4483 -1 4484 -1 4485 -1 4486 -1 4487 -1 4488 -1 4489 -1 4490 -1 4491 -1 4492 -1 4493 -1 4494 -1 4495 -1 4496 -1 4497 -1 4498 -1 4499 -1 4500 -1 4501 -1 4502 -1 4503 -1 4504 -1 4505 -1 4506 -1 4507 -1 4508 -1 4509 -1 4510 -1 4511 -1 4512 -1 4513 -1 4514 -1 4515 -1 4516 -1 4517 -1 4518 -1 4519 -1 4520 -1 4521 -1 4522 -1 4523 -1 4524 -1 4525 -1 4526 -1 4527 -1 4528 -1 4529 -1 4530 -1 4531 -1 4532 -1 4533 -1 4534 -1 4535 -1 4536 -1 4537 -1 4538 -1 4539 -1 4540 -1 4541 -1 4542 -1 4543 -1 4544 -1 4545 -1 4546 -1 4547 -1 4548 -1 4549 -1 4550 -1 4551 -1 4552 -1 4553 -1 4554 -1 4555 -1 4556 -1 4557 -1 4558 -1 4559 -1 4560 -1 4561 -1 4562 -1 4563 -1 4564 -1 4565 -1 4566 -1 4567 -1 4568 -1 4569 -1 4570 -1 4571 -1 4572 -1 4573 -1 4574 -1 4575 -1 4576 -1 4577 -1 4578 -1 4579 -1 4580 -1 4581 -1 4582 -1 4583 -1 4584 -1 4585 -1 4586 -1 4587 -1 4588 -1 4589 -1 4590 -1 4591 -1 4592 -1 4593 -1 4594 -1 4595 -1 4596 -1 4597 -1 4598 -1 4599 -1 4600 -1 4601 -1 4602 -1 4603 -1 4604 -1 4605 -1 4606 -1 4607 -1 4608 -1 4609 -1 4610 -1 4611 -1 4612 -1 4613 -1 4614 -1 4615 -1 4616 -1 4617 -1 4618 -1 4619 -1 4620 -1 4621 -1 4622 -1 4623 -1 4624 -1 4625 -1 4626 -1 4627 -1 4628 -1 4629 -1 4630 -1 4631 -1 4632 -1 4633 -1 4634 -1 4635 -1 4636 -1 4637 -1 4638 -1 4639 -1 4640 -1 4641 -1 4642 -1 4643 -1 4644 -1 4645 -1 4646 -1 4647 -1 4648 -1 4649 -1 4650 -1 4651 -1 4652 -1 4653 -1 4654 -1 4655 -1 4656 -1 4657 -1 4658 -1 4659 -1 4660 -1 4661 -1 4662 -1 4663 -1 4664 -1 4665 -1 4666 -1 4667 -1 4668 -1 4669 -1 4670 -1 4671 -1 4672 -1 4673 -1 4674 -1 4675 -1 4676 -1 4677 -1 4678 -1 4679 -1 4680 -1 4681 -1 4682 -1 4683 -1 4684 -1 4685 -1 4686 -1 4687 -1 4688 -1 4689 -1 4690 -1 4691 -1 4692 -1 4693 -1 4694 -1 4695 -1 4696 -1 4697 -1 4698 -1 4699 -1 4700 -1 4701 -1 4702 -1 4703 -1 4704 -1 4705 -1 4706 -1 4707 -1 4708 -1 4709 -1 4710 -1 4711 -1 4712 -1 4713 -1 4714 -1 4715 -1 4716 -1 4717 -1 4718 -1 4719 -1 4720 -1 4721 -1 4722 -1 4723 -1 4724 -1 4725 -1 4726 -1 4727 -1 4728 -1 4729 -1 4730 -1 4731 -1 4732 -1 4733 -1 4734 -1 4735 -1 4736 -1 4737 -1 4738 -1 4739 -1 4740 -1 4741 -1 4742 -1 4743 -1 4744 -1 4745 -1 4746 -1 4747 -1 4748 -1 4749 -1 4750 -1 4751 -1 4752 -1 4753 -1 4754 -1 4755 -1 4756 -1 4757 -1 4758 -1 4759 -1 4760 -1 4761 -1 4762 -1 4763 -1 4764 -1 4765 -1 4766 -1 4767 -1 4768 -1 4769 -1 4770 -1 4771 -1 4772 -1 4773 -1 4774 -1 4775 -1 4776 -1 4777 -1 4778 -1 4779 -1 4780 -1 4781 -1 4782 -1 4783 -1 4784 -1 4785 -1 4786 -1 4787 -1 4788 -1 4789 -1 4790 -1 4791 -1 4792 -1 4793 -1 4794 -1 4795 -1 4796 -1 4797 -1 4798 -1 4799 -1 4800 -1 4801 -1 4802 -1 4803 -1 4804 -1 4805 -1 4806 -1 4807 -1 4808 -1 4809 -1 4810 -1 4811 -1 4812 -1 4813 -1 4814 -1 4815 -1 4816 -1 4817 -1 4818 -1 4819 -1 4820 -1 4821 -1 4822 -1 4823 -1 4824 -1 4825 -1 4826 -1 4827 -1 4828 -1 4829 -1 4830 -1 4831 -1 4832 -1 4833 -1 4834 -1 4835 -1 4836 -1 4837 -1 4838 -1 4839 -1 4840 -1 4841 -1 4842 -1 4843 -1 4844 -1 4845 -1 4846 -1 4847 -1 4848 -1 4849 -1 4850 -1 4851 -1 4852 -1 4853 -1 4854 -1 4855 -1 4856 -1 4857 -1 4858 -1 4859 -1 4860 -1 4861 -1 4862 -1 4863 -1 4864 -1 4865 -1 4866 -1 4867 -1 4868 -1 4869 -1 4870 -1 4871 -1 4872 -1 4873 -1 4874 -1 4875 -1 4876 -1 4877 -1 4878 -1 4879 -1 4880 -1 4881 -1 4882 -1 4883 -1 4884 -1 4885 -1 4886 -1 4887 -1 4888 -1 4889 -1 4890 -1 4891 -1 4892 -1 4893 -1 4894 -1 4895 -1 4896 -1 4897 -1 4898 -1 4899 -1 4900 -1 4901 -1 4902 -1 4903 -1 4904 -1 4905 -1 4906 -1 4907 -1 4908 -1 4909 -1 4910 -1 4911 -1 4912 -1 4913 -1 4914 -1 4915 -1 4916 -1 4917 -1 4918 -1 4919 -1 4920 -1 4921 -1 4922 -1 4923 -1 4924 -1 4925 -1 4926 -1 4927 -1 4928 -1 4929 -1 4930 -1 4931 -1 4932 -1 4933 -1 4934 -1 4935 -1 4936 -1 4937 -1 4938 -1 4939 -1 4940 -1 4941 -1 4942 -1 4943 -1 4944 -1 4945 -1 4946 -1 4947 -1 4948 -1 4949 -1 4950 -1 4951 -1 4952 -1 4953 -1 4954 -1 4955 -1 4956 -1 4957 -1 4958 -1 4959 -1 4960 -1 4961 -1 4962 -1 4963 -1 4964 -1 4965 -1 4966 -1 4967 -1 4968 -1 4969 -1 4970 -1 4971 -1 4972 -1 4973 -1 4974 -1 4975 -1 4976 -1 4977 -1 4978 -1 4979 -1 4980 -1 4981 -1 4982 -1 4983 -1 4984 -1 4985 -1 4986 -1 4987 -1 4988 -1 4989 -1 4990 -1 4991 -1 4992 -1 4993 -1 4994 -1 4995 -1 4996 -1 4997 -1 4998 -1 4999 -1 5000 -1 5001 -1 5002 -1 5003 -1 5004 -1 5005 -1 5006 -1 5007 -1 5008 -1 5009 -1 5010 -1 5011 -1 5012 -1 5013 -1 5014 -1 5015 -1 5016 -1 5017 -1 5018 -1 5019 -1 5020 -1 5021 -1 5022 -1 5023 -1 5024 -1 5025 -1 5026 -1 5027 -1 5028 -1 5029 -1 5030 -1 5031 -1 5032 -1 5033 -1 5034 -1 5035 -1 5036 -1 5037 -1 5038 -1 5039 -1 5040 -1 5041 -1 5042 -1 5043 -1 5044 -1 5045 -1 5046 -1 5047 -1 5048 -1 5049 -1 5050 -1 5051 -1 5052 -1 5053 -1 5054 -1 5055 -1 5056 -1 5057 -1 5058 -1 5059 -1 5060 -1 5061 -1 5062 -1 5063 -1 5064 -1 5065 -1 5066 -1 5067 -1 5068 -1 5069 -1 5070 -1 5071 -1 5072 -1 5073 -1 5074 -1 5075 -1 5076 -1 5077 -1 5078 -1 5079 -1 5080 -1 5081 -1 5082 -1 5083 -1 5084 -1 5085 -1 5086 -1 5087 -1 5088 -1 5089 -1 5090 -1 5091 -1 5092 -1 5093 -1 5094 -1 5095 -1 5096 -1 5097 -1 5098 -1 5099 -1 5100 -1 5101 -1 5102 -1 5103 -1 5104 -1 5105 -1 5106 -1 5107 -1 5108 -1 5109 -1 5110 -1 5111 -1 5112 -1 5113 -1 5114 -1 5115 -1 5116 -1 5117 -1 5118 -1 5119 -1 5120 -1 5121 -1 5122 -1 5123 -1 5124 -1 5125 -1 5126 -1 5127 -1 5128 -1 5129 -1 5130 -1 5131 -1 5132 -1 5133 -1 5134 -1 5135 -1 5136 -1 5137 -1 5138 -1 5139 -1 5140 -1 5141 -1 5142 -1 5143 -1 5144 -1 5145 -1 5146 -1 5147 -1 5148 -1 5149 -1 5150 -1 5151 -1 5152 -1 5153 -1 5154 -1 5155 -1 5156 -1 5157 -1 5158 -1 5159 -1 5160 -1 5161 -1 5162 -1 5163 -1 5164 -1 5165 -1 5166 -1 5167 -1 5168 -1 5169 -1 5170 -1 5171 -1 5172 -1 5173 -1 5174 -1 5175 -1 5176 -1 5177 -1 5178 -1 5179 -1 5180 -1 5181 -1 5182 -1 5183 -1 5184 -1 5185 -1 5186 -1 5187 -1 5188 -1 5189 -1 5190 -1 5191 -1 5192 -1 5193 -1 5194 -1 5195 -1 5196 -1 5197 -1 5198 -1 5199 -1 5200 -1 5201 -1 5202 -1 5203 -1 5204 -1 5205 -1 5206 -1 5207 -1 5208 -1 5209 -1 5210 -1 5211 -1 5212 -1 5213 -1 5214 -1 5215 -1 5216 -1 5217 -1 5218 -1 5219 -1 5220 -1 5221 -1 5222 -1 5223 -1 5224 -1 5225 -1 5226 -1 5227 -1 5228 -1 5229 -1 5230 -1 5231 -1 5232 -1 5233 -1 5234 -1 5235 -1 5236 -1 5237 -1 5238 -1 5239 -1 5240 -1 5241 -1 5242 -1 5243 -1 5244 -1 5245 -1 5246 -1 5247 -1 5248 -1 5249 -1 5250 -1 5251 -1 5252 -1 5253 -1 5254 -1 5255 -1 5256 -1 5257 -1 5258 -1 5259 -1 5260 -1 5261 -1 5262 -1 5263 -1 5264 -1 5265 -1 5266 -1 5267 -1 5268 -1 5269 -1 5270 -1 5271 -1 5272 -1 5273 -1 5274 -1 5275 -1 5276 -1 5277 -1 5278 -1 5279 -1 5280 -1 5281 -1 5282 -1 5283 -1 5284 -1 5285 -1 5286 -1 5287 -1 5288 -1 5289 -1 5290 -1 5291 -1 5292 -1 5293 -1 5294 -1 5295 -1 5296 -1 5297 -1 5298 -1 5299 -1 5300 -1 5301 -1 5302 -1 5303 -1 5304 -1 5305 -1 5306 -1 5307 -1 5308 -1 5309 -1 5310 -1 5311 -1 5312 -1 5313 -1 5314 -1 5315 -1 5316 -1 5317 -1 5318 -1 5319 -1 5320 -1 5321 -1 5322 -1 5323 -1 5324 -1 5325 -1 5326 -1 5327 -1 5328 -1 5329 -1 5330 -1 5331 -1 5332 -1 5333 -1 5334 -1 5335 -1 5336 -1 5337 -1 5338 -1 5339 -1 5340 -1 5341 -1 5342 -1 5343 -1 5344 -1 5345 -1 5346 -1 5347 -1 5348 -1 5349 -1 5350 -1 5351 -1 5352 -1 5353 -1 5354 -1 5355 -1 5356 -1 5357 -1 5358 -1 5359 -1 5360 -1 5361 -1 5362 -1 5363 -1 5364 -1 5365 -1 5366 -1 5367 -1 5368 -1 5369 -1 5370 -1 5371 -1 5372 -1 5373 -1 5374 -1 5375 -1 5376 -1 5377 -1 5378 -1 5379 -1 5380 -1 5381 -1 5382 -1 5383 -1 5384 -1 5385 -1 5386 -1 5387 -1 5388 -1 5389 -1 5390 -1 5391 -1 5392 -1 5393 -1 5394 -1 5395 -1 5396 -1 5397 -1 5398 -1 5399 -1 5400 -1 5401 -1 5402 -1 5403 -1 5404 -1 5405 -1 5406 -1 5407 -1 5408 -1 5409 -1 5410 -1 5411 -1 5412 -1 5413 -1 5414 -1 5415 -1 5416 -1 5417 -1 5418 -1 5419 -1 5420 -1 5421 -1 5422 -1 5423 -1 5424 -1 5425 -1 5426 -1 5427 -1 5428 -1 5429 -1 5430 -1 5431 -1 5432 -1 5433 -1 5434 -1 5435 -1 5436 -1 5437 -1 5438 -1 5439 -1 5440 -1 5441 -1 5442 -1 5443 -1 5444 -1 5445 -1 5446 -1 5447 -1 5448 -1 5449 -1 5450 -1 5451 -1 5452 -1 5453 -1 5454 -1 5455 -1 5456 -1 5457 -1 5458 -1 5459 -1 5460 -1 5461 -1 5462 -1 5463 -1 5464 -1 5465 -1 5466 -1 5467 -1 5468 -1 5469 -1 5470 -1 5471 -1 5472 -1 5473 -1 5474 -1 5475 -1 5476 -1 5477 -1 5478 -1 5479 -1 5480 -1 5481 -1 5482 -1 5483 -1 5484 -1 5485 -1 5486 -1 5487 -1 5488 -1 5489 -1 5490 -1 5491 -1 5492 -1 5493 -1 5494 -1 5495 -1 5496 -1 5497 -1 5498 -1 5499 -1 5500 -1 5501 -1 5502 -1 5503 -1 5504 -1 5505 -1 5506 -1 5507 -1 5508 -1 5509 -1 5510 -1 5511 -1 5512 -1 5513 -1 5514 -1 5515 -1 5516 -1 5517 -1 5518 -1 5519 -1 5520 -1 5521 -1 5522 -1 5523 -1 5524 -1 5525 -1 5526 -1 5527 -1 5528 -1 5529 -1 5530 -1 5531 -1 5532 -1 5533 -1 5534 -1 5535 -1 5536 -1 5537 -1 5538 -1 5539 -1 5540 -1 5541 -1 5542 -1 5543 -1 5544 -1 5545 -1 5546 -1 5547 -1 5548 -1 5549 -1 5550 -1 5551 -1 5552 -1 5553 -1 5554 -1 5555 -1 5556 -1 5557 -1 5558 -1 5559 -1 5560 -1 5561 -1 5562 -1 5563 -1 5564 -1 5565 -1 5566 -1 5567 -1 5568 -1 5569 -1 5570 -1 5571 -1 5572 -1 5573 -1 5574 -1 5575 -1 5576 -1 5577 -1 5578 -1 5579 -1 5580 -1 5581 -1 5582 -1 5583 -1 5584 -1 5585 -1 5586 -1 5587 -1 5588 -1 5589 -1 5590 -1 5591 -1 5592 -1 5593 -1 5594 -1 5595 -1 5596 -1 5597 -1 5598 -1 5599 -1 5600 -1 5601 -1 5602 -1 5603 -1 5604 -1 5605 -1 5606 -1 5607 -1 5608 -1 5609 -1 5610 -1 5611 -1 5612 -1 5613 -1 5614 -1 5615 -1 5616 -1 5617 -1 5618 -1 5619 -1 5620 -1 5621 -1 5622 -1 5623 -1 5624 -1 5625 -1 5626 -1 5627 -1 5628 -1 5629 -1 5630 -1 5631 -1 5632 -1 5633 -1 5634 -1 5635 -1 5636 -1 5637 -1 5638 -1 5639 -1 5640 -1 5641 -1 5642 -1 5643 -1 5644 -1 5645 -1 5646 -1 5647 -1 5648 -1 5649 -1 5650 -1 5651 -1 5652 -1 5653 -1 5654 -1 5655 -1 5656 -1 5657 -1 5658 -1 5659 -1 5660 -1 5661 -1 5662 -1 5663 -1 5664 -1 5665 -1 5666 -1 5667 -1 5668 -1 5669 -1 5670 -1 5671 -1 5672 -1 5673 -1 5674 -1 5675 -1 5676 -1 5677 -1 5678 -1 5679 -1 5680 -1 5681 -1 5682 -1 5683 -1 5684 -1 5685 -1 5686 -1 5687 -1 5688 -1 5689 -1 5690 -1 5691 -1 5692 -1 5693 -1 5694 -1 5695 -1 5696 -1 5697 -1 5698 -1 5699 -1 5700 -1 5701 -1 5702 -1 5703 -1 5704 -1 5705 -1 5706 -1 5707 -1 5708 -1 5709 -1 5710 -1 5711 -1 5712 -1 5713 -1 5714 -1 5715 -1 5716 -1 5717 -1 5718 -1 5719 -1 5720 -1 5721 -1 5722 -1 5723 -1 5724 -1 5725 -1 5726 -1 5727 -1 5728 -1 5729 -1 5730 -1 5731 -1 5732 -1 5733 -1 5734 -1 5735 -1 5736 -1 5737 -1 5738 -1 5739 -1 5740 -1 5741 -1 5742 -1 5743 -1 5744 -1 5745 -1 5746 -1 5747 -1 5748 -1 5749 -1 5750 -1 5751 -1 5752 -1 5753 -1 5754 -1 5755 -1 5756 -1 5757 -1 5758 -1 5759 -1 5760 -1 5761 -1 5762 -1 5763 -1 5764 -1 5765 -1 5766 -1 5767 -1 5768 -1 5769 -1 5770 -1 5771 -1 5772 -1 5773 -1 5774 -1 5775 -1 5776 -1 5777 -1 5778 -1 5779 -1 5780 -1 5781 -1 5782 -1 5783 -1 5784 -1 5785 -1 5786 -1 5787 -1 5788 -1 5789 -1 5790 -1 5791 -1 5792 -1 5793 -1 5794 -1 5795 -1 5796 -1 5797 -1 5798 -1 5799 -1 5800 -1 5801 -1 5802 -1 5803 -1 5804 -1 5805 -1 5806 -1 5807 -1 5808 -1 5809 -1 5810 -1 5811 -1 5812 -1 5813 -1 5814 -1 5815 -1 5816 -1 5817 -1 5818 -1 5819 -1 5820 -1 5821 -1 5822 -1 5823 -1 5824 -1 5825 -1 5826 -1 5827 -1 5828 -1 5829 -1 5830 -1 5831 -1 5832 -1 5833 -1 5834 -1 5835 -1 5836 -1 5837 -1 5838 -1 5839 -1 5840 -1 5841 -1 5842 -1 5843 -1 5844 -1 5845 -1 5846 -1 5847 -1 5848 -1 5849 -1 5850 -1 5851 -1 5852 -1 5853 -1 5854 -1 5855 -1 5856 -1 5857 -1 5858 -1 5859 -1 5860 -1 5861 -1 5862 -1 5863 -1 5864 -1 5865 -1 5866 -1 5867 -1 5868 -1 5869 -1 5870 -1 5871 -1 5872 -1 5873 -1 5874 -1 5875 -1 5876 -1 5877 -1 5878 -1 5879 -1 5880 -1 5881 -1 5882 -1 5883 -1 5884 -1 5885 -1 5886 -1 5887 -1 5888 -1 5889 -1 5890 -1 5891 -1 5892 -1 5893 -1 5894 -1 5895 -1 5896 -1 5897 -1 5898 -1 5899 -1 5900 -1 5901 -1 5902 -1 5903 -1 5904 -1 5905 -1 5906 -1 5907 -1 5908 -1 5909 -1 5910 -1 5911 -1 5912 -1 5913 -1 5914 -1 5915 -1 5916 -1 5917 -1 5918 -1 5919 -1 5920 -1 5921 -1 5922 -1 5923 -1 5924 -1 5925 -1 5926 -1 5927 -1 5928 -1 5929 -1 5930 -1 5931 -1 5932 -1 5933 -1 5934 -1 5935 -1 5936 -1 5937 -1 5938 -1 5939 -1 5940 -1 5941 -1 5942 -1 5943 -1 5944 -1 5945 -1 5946 -1 5947 -1 5948 -1 5949 -1 5950 -1 5951 -1 5952 -1 5953 -1 5954 -1 5955 -1 5956 -1 5957 -1 5958 -1 5959 -1 5960 -1 5961 -1 5962 -1 5963 -1 5964 -1 5965 -1 5966 -1 5967 -1 5968 -1 5969 -1 5970 -1 5971 -1 5972 -1 5973 -1 5974 -1 5975 -1 5976 -1 5977 -1 5978 -1 5979 -1 5980 -1 5981 -1 5982 -1 5983 -1 5984 -1 5985 -1 5986 -1 5987 -1 5988 -1 5989 -1 5990 -1 5991 -1 5992 -1 5993 -1 5994 -1 5995 -1 5996 -1 5997 -1 5998 -1 5999 -1 6000 -1 6001 -1 6002 -1 6003 -1 6004 -1 6005 -1 6006 -1 6007 -1 6008 -1 6009 -1 6010 -1 6011 -1 6012 -1 6013 -1 6014 -1 6015 -1 6016 -1 6017 -1 6018 -1 6019 -1 6020 -1 6021 -1 6022 -1 6023 -1 6024 -1 6025 -1 6026 -1 6027 -1 6028 -1 6029 -1 6030 -1 6031 -1 6032 -1 6033 -1 6034 -1 6035 -1 6036 -1 6037 -1 6038 -1 6039 -1 6040 -1 6041 -1 6042 -1 6043 -1 6044 -1 6045 -1 6046 -1 6047 -1 6048 -1 6049 -1 6050 -1 6051 -1 6052 -1 6053 -1 6054 -1 6055 -1 6056 -1 6057 -1 6058 -1 6059 -1 6060 -1 6061 -1 6062 -1 6063 -1 6064 -1 6065 -1 6066 -1 6067 -1 6068 -1 6069 -1 6070 -1 6071 -1 6072 -1 6073 -1 6074 -1 6075 -1 6076 -1 6077 -1 6078 -1 6079 -1 6080 -1 6081 -1 6082 -1 6083 -1 6084 -1 6085 -1 6086 -1 6087 -1 6088 -1 6089 -1 6090 -1 6091 -1 6092 -1 6093 -1 6094 -1 6095 -1 6096 -1 6097 -1 6098 -1 6099 -1 6100 -1 6101 -1 6102 -1 6103 -1 6104 -1 6105 -1 6106 -1 6107 -1 6108 -1 6109 -1 6110 -1 6111 -1 6112 -1 6113 -1 6114 -1 6115 -1 6116 -1 6117 -1 6118 -1 6119 -1 6120 -1 6121 -1 6122 -1 6123 -1 6124 -1 6125 -1 6126 -1 6127 -1 6128 -1 6129 -1 6130 -1 6131 -1 6132 -1 6133 -1 6134 -1 6135 -1 6136 -1 6137 -1 6138 -1 6139 -1 6140 -1 6141 -1 6142 -1 6143 -1 6144 -1 6145 -1 6146 -1 6147 -1 6148 -1 6149 -1 6150 -1 6151 -1 6152 -1 6153 -1 6154 -1 6155 -1 6156 -1 6157 -1 6158 -1 6159 -1 6160 -1 6161 -1 6162 -1 6163 -1 6164 -1 6165 -1 6166 -1 6167 -1 6168 -1 6169 -1 6170 -1 6171 -1 6172 -1 6173 -1 6174 -1 6175 -1 6176 -1 6177 -1 6178 -1 6179 -1 6180 -1 6181 -1 6182 -1 6183 -1 6184 -1 6185 -1 6186 -1 6187 -1 6188 -1 6189 -1 6190 -1 6191 -1 6192 -1 6193 -1 6194 -1 6195 -1 6196 -1 6197 -1 6198 -1 6199 -1 6200 -1 6201 -1 6202 -1 6203 -1 6204 -1 6205 -1 6206 -1 6207 -1 6208 -1 6209 -1 6210 -1 6211 -1 6212 -1 6213 -1 6214 -1 6215 -1 6216 -1 6217 -1 6218 -1 6219 -1 6220 -1 6221 -1 6222 -1 6223 -1 6224 -1 6225 -1 6226 -1 6227 -1 6228 -1 6229 -1 6230 -1 6231 -1 6232 -1 6233 -1 6234 -1 6235 -1 6236 -1 6237 -1 6238 -1 6239 -1 6240 -1 6241 -1 6242 -1 6243 -1 6244 -1 6245 -1 6246 -1 6247 -1 6248 -1 6249 -1 6250 -1 6251 -1 6252 -1 6253 -1 6254 -1 6255 -1 6256 -1 6257 -1 6258 -1 6259 -1 6260 -1 6261 -1 6262 -1 6263 -1 6264 -1 6265 -1 6266 -1 6267 -1 6268 -1 6269 -1 6270 -1 6271 -1 6272 -1 6273 -1 6274 -1 6275 -1 6276 -1 6277 -1 6278 -1 6279 -1 6280 -1 6281 -1 6282 -1 6283 -1 6284 -1 6285 -1 6286 -1 6287 -1 6288 -1 6289 -1 6290 -1 6291 -1 6292 -1 6293 -1 6294 -1 6295 -1 6296 -1 6297 -1 6298 -1 6299 -1 6300 -1 6301 -1 6302 -1 6303 -1 6304 -1 6305 -1 6306 -1 6307 -1 6308 -1 6309 -1 6310 -1 6311 -1 6312 -1 6313 -1 6314 -1 6315 -1 6316 -1 6317 -1 6318 -1 6319 -1 6320 -1 6321 -1 6322 -1 6323 -1 6324 -1 6325 -1 6326 -1 6327 -1 6328 -1 6329 -1 6330 -1 6331 -1 6332 -1 6333 -1 6334 -1 6335 -1 6336 -1 6337 -1 6338 -1 6339 -1 6340 -1 6341 -1 6342 -1 6343 -1 6344 -1 6345 -1 6346 -1 6347 -1 6348 -1 6349 -1 6350 -1 6351 -1 6352 -1 6353 -1 6354 -1 6355 -1 6356 -1 6357 -1 6358 -1 6359 -1 6360 -1 6361 -1 6362 -1 6363 -1 6364 -1 6365 -1 6366 -1 6367 -1 6368 -1 6369 -1 6370 -1 6371 -1 6372 -1 6373 -1 6374 -1 6375 -1 6376 -1 6377 -1 6378 -1 6379 -1 6380 -1 6381 -1 6382 -1 6383 -1 6384 -1 6385 -1 6386 -1 6387 -1 6388 -1 6389 -1 6390 -1 6391 -1 6392 -1 6393 -1 6394 -1 6395 -1 6396 -1 6397 -1 6398 -1 6399 -1 6400 -1 6401 -1 6402 -1 6403 -1 6404 -1 6405 -1 6406 -1 6407 -1 6408 -1 6409 -1 6410 -1 6411 -1 6412 -1 6413 -1 6414 -1 6415 -1 6416 -1 6417 -1 6418 -1 6419 -1 6420 -1 6421 -1 6422 -1 6423 -1 6424 -1 6425 -1 6426 -1 6427 -1 6428 -1 6429 -1 6430 -1 6431 -1 6432 -1 6433 -1 6434 -1 6435 -1 6436 -1 6437 -1 6438 -1 6439 -1 6440 -1 6441 -1 6442 -1 6443 -1 6444 -1 6445 -1 6446 -1 6447 -1 6448 -1 6449 -1 6450 -1 6451 -1 6452 -1 6453 -1 6454 -1 6455 -1 6456 -1 6457 -1 6458 -1 6459 -1 6460 -1 6461 -1 6462 -1 6463 -1 6464 -1 6465 -1 6466 -1 6467 -1 6468 -1 6469 -1 6470 -1 6471 -1 6472 -1 6473 -1 6474 -1 6475 -1 6476 -1 6477 -1 6478 -1 6479 -1 6480 -1 6481 -1 6482 -1 6483 -1 6484 -1 6485 -1 6486 -1 6487 -1 6488 -1 6489 -1 6490 -1 6491 -1 6492 -1 6493 -1 6494 -1 6495 -1 6496 -1 6497 -1 6498 -1 6499 -1 6500 -1 6501 -1 6502 -1 6503 -1 6504 -1 6505 -1 6506 -1 6507 -1 6508 -1 6509 -1 6510 -1 6511 -1 6512 -1 6513 -1 6514 -1 6515 -1 6516 -1 6517 -1 6518 -1 6519 -1 6520 -1 6521 -1 6522 -1 6523 -1 6524 -1 6525 -1 6526 -1 6527 -1 6528 -1 6529 -1 6530 -1 6531 -1 6532 -1 6533 -1 6534 -1 6535 -1 6536 -1 6537 -1 6538 -1 6539 -1 6540 -1 6541 -1 6542 -1 6543 -1 6544 -1 6545 -1 6546 -1 6547 -1 6548 -1 6549 -1 6550 -1 6551 -1 6552 -1 6553 -1 6554 -1 6555 -1 6556 -1 6557 -1 6558 -1 6559 -1 6560 -1 6561 -1 6562 -1 6563 -1 6564 -1 6565 -1 6566 -1 6567 -1 6568 -1 6569 -1 6570 -1 6571 -1 6572 -1 6573 -1 6574 -1 6575 -1 6576 -1 6577 -1 6578 -1 6579 -1 6580 -1 6581 -1 6582 -1 6583 -1 6584 -1 6585 -1 6586 -1 6587 -1 6588 -1 6589 -1 6590 -1 6591 -1 6592 -1 6593 -1 6594 -1 6595 -1 6596 -1 6597 -1 6598 -1 6599 -1 6600 -1 6601 -1 6602 -1 6603 -1 6604 -1 6605 -1 6606 -1 6607 -1 6608 -1 6609 -1 6610 -1 6611 -1 6612 -1 6613 -1 6614 -1 6615 -1 6616 -1 6617 -1 6618 -1 6619 -1 6620 -1 6621 -1 6622 -1 6623 -1 6624 -1 6625 -1 6626 -1 6627 -1 6628 -1 6629 -1 6630 -1 6631 -1 6632 -1 6633 -1 6634 -1 6635 -1 6636 -1 6637 -1 6638 -1 6639 -1 6640 -1 6641 -1 6642 -1 6643 -1 6644 -1 6645 -1 6646 -1 6647 -1 6648 -1 6649 -1 6650 -1 6651 -1 6652 -1 6653 -1 6654 -1 6655 -1 6656 -1 6657 -1 6658 -1 6659 -1 6660 -1 6661 -1 6662 -1 6663 -1 6664 -1 6665 -1 6666 -1 6667 -1 6668 -1 6669 -1 6670 -1 6671 -1 6672 -1 6673 -1 6674 -1 6675 -1 6676 -1 6677 -1 6678 -1 6679 -1 6680 -1 6681 -1 6682 -1 6683 -1 6684 -1 6685 -1 6686 -1 6687 -1 6688 -1 6689 -1 6690 -1 6691 -1 6692 -1 6693 -1 6694 -1 6695 -1 6696 -1 6697 -1 6698 -1 6699 -1 6700 -1 6701 -1 6702 -1 6703 -1 6704 -1 6705 -1 6706 -1 6707 -1 6708 -1 6709 -1 6710 -1 6711 -1 6712 -1 6713 -1 6714 -1 6715 -1 6716 -1 6717 -1 6718 -1 6719 -1 6720 -1 6721 -1 6722 -1 6723 -1 6724 -1 6725 -1 6726 -1 6727 -1 6728 -1 6729 -1 6730 -1 6731 -1 6732 -1 6733 -1 6734 -1 6735 -1 6736 -1 6737 -1 6738 -1 6739 -1 6740 -1 6741 -1 6742 -1 6743 -1 6744 -1 6745 -1 6746 -1 6747 -1 6748 -1 6749 -1 6750 -1 6751 -1 6752 -1 6753 -1 6754 -1 6755 -1 6756 -1 6757 -1 6758 -1 6759 -1 6760 -1 6761 -1 6762 -1 6763 -1 6764 -1 6765 -1 6766 -1 6767 -1 6768 -1 6769 -1 6770 -1 6771 -1 6772 -1 6773 -1 6774 -1 6775 -1 6776 -1 6777 -1 6778 -1 6779 -1 6780 -1 6781 -1 6782 -1 6783 -1 6784 -1 6785 -1 6786 -1 6787 -1 6788 -1 6789 -1 6790 -1 6791 -1 6792 -1 6793 -1 6794 -1 6795 -1 6796 -1 6797 -1 6798 -1 6799 -1 6800 -1 6801 -1 6802 -1 6803 -1 6804 -1 6805 -1 6806 -1 6807 -1 6808 -1 6809 -1 6810 -1 6811 -1 6812 -1 6813 -1 6814 -1 6815 -1 6816 -1 6817 -1 6818 -1 6819 -1 6820 -1 6821 -1 6822 -1 6823 -1 6824 -1 6825 -1 6826 -1 6827 -1 6828 -1 6829 -1 6830 -1 6831 -1 6832 -1 6833 -1 6834 -1 6835 -1 6836 -1 6837 -1 6838 -1 6839 -1 6840 -1 6841 -1 6842 -1 6843 -1 6844 -1 6845 -1 6846 -1 6847 -1 6848 -1 6849 -1 6850 -1 6851 -1 6852 -1 6853 -1 6854 -1 6855 -1 6856 -1 6857 -1 6858 -1 6859 -1 6860 -1 6861 -1 6862 -1 6863 -1 6864 -1 6865 -1 6866 -1 6867 -1 6868 -1 6869 -1 6870 -1 6871 -1 6872 -1 6873 -1 6874 -1 6875 -1 6876 -1 6877 -1 6878 -1 6879 -1 6880 -1 6881 -1 6882 -1 6883 -1 6884 -1 6885 -1 6886 -1 6887 -1 6888 -1 6889 -1 6890 -1 6891 -1 6892 -1 6893 -1 6894 -1 6895 -1 6896 -1 6897 -1 6898 -1 6899 -1 6900 -1 6901 -1 6902 -1 6903 -1 6904 -1 6905 -1 6906 -1 6907 -1 6908 -1 6909 -1 6910 -1 6911 -1 6912 -1 6913 -1 6914 -1 6915 -1 6916 -1 6917 -1 6918 -1 6919 -1 6920 -1 6921 -1 6922 -1 6923 -1 6924 -1 6925 -1 6926 -1 6927 -1 6928 -1 6929 -1 6930 -1 6931 -1 6932 -1 6933 -1 6934 -1 6935 -1 6936 -1 6937 -1 6938 -1 6939 -1 6940 -1 6941 -1 6942 -1 6943 -1 6944 -1 6945 -1 6946 -1 6947 -1 6948 -1 6949 -1 6950 -1 6951 -1 6952 -1 6953 -1 6954 -1 6955 -1 6956 -1 6957 -1 6958 -1 6959 -1 6960 -1 6961 -1 6962 -1 6963 -1 6964 -1 6965 -1 6966 -1 6967 -1 6968 -1 6969 -1 6970 -1 6971 -1 6972 -1 6973 -1 6974 -1 6975 -1 6976 -1 6977 -1 6978 -1 6979 -1 6980 -1 6981 -1 6982 -1 6983 -1 6984 -1 6985 -1 6986 -1 6987 -1 6988 -1 6989 -1 6990 -1 6991 -1 6992 -1 6993 -1 6994 -1 6995 -1 6996 -1 6997 -1 6998 -1 6999 -1 7000 -1 7001 -1 7002 -1 7003 -1 7004 -1 7005 -1 7006 -1 7007 -1 7008 -1 7009 -1 7010 -1 7011 -1 7012 -1 7013 -1 7014 -1 7015 -1 7016 -1 7017 -1 7018 -1 7019 -1 7020 -1 7021 -1 7022 -1 7023 -1 7024 -1 7025 -1 7026 -1 7027 -1 7028 -1 7029 -1 7030 -1 7031 -1 7032 -1 7033 -1 7034 -1 7035 -1 7036 -1 7037 -1 7038 -1 7039 -1 7040 -1 7041 -1 7042 -1 7043 -1 7044 -1 7045 -1 7046 -1 7047 -1 7048 -1 7049 -1 7050 -1 7051 -1 7052 -1 7053 -1 7054 -1 7055 -1 7056 -1 7057 -1 7058 -1 7059 -1 7060 -1 7061 -1 7062 -1 7063 -1 7064 -1 7065 -1 7066 -1 7067 -1 7068 -1 7069 -1 7070 -1 7071 -1 7072 -1 7073 -1 7074 -1 7075 -1 7076 -1 7077 -1 7078 -1 7079 -1 7080 -1 7081 -1 7082 -1 7083 -1 7084 -1 7085 -1 7086 -1 7087 -1 7088 -1 7089 -1 7090 -1 7091 -1 7092 -1 7093 -1 7094 -1 7095 -1 7096 -1 7097 -1 7098 -1 7099 -1 7100 -1 7101 -1 7102 -1 7103 -1 7104 -1 7105 -1 7106 -1 7107 -1 7108 -1 7109 -1 7110 -1 7111 -1 7112 -1 7113 -1 7114 -1 7115 -1 7116 -1 7117 -1 7118 -1 7119 -1 7120 -1 7121 -1 7122 -1 7123 -1 7124 -1 7125 -1 7126 -1 7127 -1 7128 -1 7129 -1 7130 -1 7131 -1 7132 -1 7133 -1 7134 -1 7135 -1 7136 -1 7137 -1 7138 -1 7139 -1 7140 -1 7141 -1 7142 -1 7143 -1 7144 -1 7145 -1 7146 -1 7147 -1 7148 -1 7149 -1 7150 -1 7151 -1 7152 -1 7153 -1 7154 -1 7155 -1 7156 -1 7157 -1 7158 -1 7159 -1 7160 -1 7161 -1 7162 -1 7163 -1 7164 -1 7165 -1 7166 -1 7167 -1 7168 -1 7169 -1 7170 -1 7171 -1 7172 -1 7173 -1 7174 -1 7175 -1 7176 -1 7177 -1 7178 -1 7179 -1 7180 -1 7181 -1 7182 -1 7183 -1 7184 -1 7185 -1 7186 -1 7187 -1 7188 -1 7189 -1 7190 -1 7191 -1 7192 -1 7193 -1 7194 -1 7195 -1 7196 -1 7197 -1 7198 -1 7199 -1 7200 -1 7201 -1 7202 -1 7203 -1 7204 -1 7205 -1 7206 -1 7207 -1 7208 -1 7209 -1 7210 -1 7211 -1 7212 -1 7213 -1 7214 -1 7215 -1 7216 -1 7217 -1 7218 -1 7219 -1 7220 -1 7221 -1 7222 -1 7223 -1 7224 -1 7225 -1 7226 -1 7227 -1 7228 -1 7229 -1 7230 -1 7231 -1 7232 -1 7233 -1 7234 -1 7235 -1 7236 -1 7237 -1 7238 -1 7239 -1 7240 -1 7241 -1 7242 -1 7243 -1 7244 -1 7245 -1 7246 -1 7247 -1 7248 -1 7249 -1 7250 -1 7251 -1 7252 -1 7253 -1 7254 -1 7255 -1 7256 -1 7257 -1 7258 -1 7259 -1 7260 -1 7261 -1 7262 -1 7263 -1 7264 -1 7265 -1 7266 -1 7267 -1 7268 -1 7269 -1 7270 -1 7271 -1 7272 -1 7273 -1 7274 -1 7275 -1 7276 -1 7277 -1 7278 -1 7279 -1 7280 -1 7281 -1 7282 -1 7283 -1 7284 -1 7285 -1 7286 -1 7287 -1 7288 -1 7289 -1 7290 -1 7291 -1 7292 -1 7293 -1 7294 -1 7295 -1 7296 -1 7297 -1 7298 -1 7299 -1 7300 -1 7301 -1 7302 -1 7303 -1 7304 -1 7305 -1 7306 -1 7307 -1 7308 -1 7309 -1 7310 -1 7311 -1 7312 -1 7313 -1 7314 -1 7315 -1 7316 -1 7317 -1 7318 -1 7319 -1 7320 -1 7321 -1 7322 -1 7323 -1 7324 -1 7325 -1 7326 -1 7327 -1 7328 -1 7329 -1 7330 -1 7331 -1 7332 -1 7333 -1 7334 -1 7335 -1 7336 -1 7337 -1 7338 -1 7339 -1 7340 -1 7341 -1 7342 -1 7343 -1 7344 -1 7345 -1 7346 -1 7347 -1 7348 -1 7349 -1 7350 -1 7351 -1 7352 -1 7353 -1 7354 -1 7355 -1 7356 -1 7357 -1 7358 -1 7359 -1 7360 -1 7361 -1 7362 -1 7363 -1 7364 -1 7365 -1 7366 -1 7367 -1 7368 -1 7369 -1 7370 -1 7371 -1 7372 -1 7373 -1 7374 -1 7375 -1 7376 -1 7377 -1 7378 -1 7379 -1 7380 -1 7381 -1 7382 -1 7383 -1 7384 -1 7385 -1 7386 -1 7387 -1 7388 -1 7389 -1 7390 -1 7391 -1 7392 -1 7393 -1 7394 -1 7395 -1 7396 -1 7397 -1 7398 -1 7399 -1 7400 -1 7401 -1 7402 -1 7403 -1 7404 -1 7405 -1 7406 -1 7407 -1 7408 -1 7409 -1 7410 -1 7411 -1 7412 -1 7413 -1 7414 -1 7415 -1 7416 -1 7417 -1 7418 -1 7419 -1 7420 -1 7421 -1 7422 -1 7423 -1 7424 -1 7425 -1 7426 -1 7427 -1 7428 -1 7429 -1 7430 -1 7431 -1 7432 -1 7433 -1 7434 -1 7435 -1 7436 -1 7437 -1 7438 -1 7439 -1 7440 -1 7441 -1 7442 -1 7443 -1 7444 -1 7445 -1 7446 -1 7447 -1 7448 -1 7449 -1 7450 -1 7451 -1 7452 -1 7453 -1 7454 -1 7455 -1 7456 -1 7457 -1 7458 -1 7459 -1 7460 -1 7461 -1 7462 -1 7463 -1 7464 -1 7465 -1 7466 -1 7467 -1 7468 -1 7469 -1 7470 -1 7471 -1 7472 -1 7473 -1 7474 -1 7475 -1 7476 -1 7477 -1 7478 -1 7479 -1 7480 -1 7481 -1 7482 -1 7483 -1 7484 -1 7485 -1 7486 -1 7487 -1 7488 -1 7489 -1 7490 -1 7491 -1 7492 -1 7493 -1 7494 -1 7495 -1 7496 -1 7497 -1 7498 -1 7499 -1 7500 -1 7501 -1 7502 -1 7503 -1 7504 -1 7505 -1 7506 -1 7507 -1 7508 -1 7509 -1 7510 -1 7511 -1 7512 -1 7513 -1 7514 -1 7515 -1 7516 -1 7517 -1 7518 -1 7519 -1 7520 -1 7521 -1 7522 -1 7523 -1 7524 -1 7525 -1 7526 -1 7527 -1 7528 -1 7529 -1 7530 -1 7531 -1 7532 -1 7533 -1 7534 -1 7535 -1 7536 -1 7537 -1 7538 -1 7539 -1 7540 -1 7541 -1 7542 -1 7543 -1 7544 -1 7545 -1 7546 -1 7547 -1 7548 -1 7549 -1 7550 -1 7551 -1 7552 -1 7553 -1 7554 -1 7555 -1 7556 -1 7557 -1 7558 -1 7559 -1 7560 -1 7561 -1 7562 -1 7563 -1 7564 -1 7565 -1 7566 -1 7567 -1 7568 -1 7569 -1 7570 -1 7571 -1 7572 -1 7573 -1 7574 -1 7575 -1 7576 -1 7577 -1 7578 -1 7579 -1 7580 -1 7581 -1 7582 -1 7583 -1 7584 -1 7585 -1 7586 -1 7587 -1 7588 -1 7589 -1 7590 -1 7591 -1 7592 -1 7593 -1 7594 -1 7595 -1 7596 -1 7597 -1 7598 -1 7599 -1 7600 -1 7601 -1 7602 -1 7603 -1 7604 -1 7605 -1 7606 -1 7607 -1 7608 -1 7609 -1 7610 -1 7611 -1 7612 -1 7613 -1 7614 -1 7615 -1 7616 -1 7617 -1 7618 -1 7619 -1 7620 -1 7621 -1 7622 -1 7623 -1 7624 -1 7625 -1 7626 -1 7627 -1 7628 -1 7629 -1 7630 -1 7631 -1 7632 -1 7633 -1 7634 -1 7635 -1 7636 -1 7637 -1 7638 -1 7639 -1 7640 -1 7641 -1 7642 -1 7643 -1 7644 -1 7645 -1 7646 -1 7647 -1 7648 -1 7649 -1 7650 -1 7651 -1 7652 -1 7653 -1 7654 -1 7655 -1 7656 -1 7657 -1 7658 -1 7659 -1 7660 -1 7661 -1 7662 -1 7663 -1 7664 -1 7665 -1 7666 -1 7667 -1 7668 -1 7669 -1 7670 -1 7671 -1 7672 -1 7673 -1 7674 -1 7675 -1 7676 -1 7677 -1 7678 -1 7679 -1 7680 -1 7681 -1 7682 -1 7683 -1 7684 -1 7685 -1 7686 -1 7687 -1 7688 -1 7689 -1 7690 -1 7691 -1 7692 -1 7693 -1 7694 -1 7695 -1 7696 -1 7697 -1 7698 -1 7699 -1 7700 -1 7701 -1 7702 -1 7703 -1 7704 -1 7705 -1 7706 -1 7707 -1 7708 -1 7709 -1 7710 -1 7711 -1 7712 -1 7713 -1 7714 -1 7715 -1 7716 -1 7717 -1 7718 -1 7719 -1 7720 -1 7721 -1 7722 -1 7723 -1 7724 -1 7725 -1 7726 -1 7727 -1 7728 -1 7729 -1 7730 -1 7731 -1 7732 -1 7733 -1 7734 -1 7735 -1 7736 -1 7737 -1 7738 -1 7739 -1 7740 -1 7741 -1 7742 -1 7743 -1 7744 -1 7745 -1 7746 -1 7747 -1 7748 -1 7749 -1 7750 -1 7751 -1 7752 -1 7753 -1 7754 -1 7755 -1 7756 -1 7757 -1 7758 -1 7759 -1 7760 -1 7761 -1 7762 -1 7763 -1 7764 -1 7765 -1 7766 -1 7767 -1 7768 -1 7769 -1 7770 -1 7771 -1 7772 -1 7773 -1 7774 -1 7775 -1 7776 -1 7777 -1 7778 -1 7779 -1 7780 -1 7781 -1 7782 -1 7783 -1 7784 -1 7785 -1 7786 -1 7787 -1 7788 -1 7789 -1 7790 -1 7791 -1 7792 -1 7793 -1 7794 -1 7795 -1 7796 -1 7797 -1 7798 -1 7799 -1 7800 -1 7801 -1 7802 -1 7803 -1 7804 -1 7805 -1 7806 -1 7807 -1 7808 -1 7809 -1 7810 -1 7811 -1 7812 -1 7813 -1 7814 -1 7815 -1 7816 -1 7817 -1 7818 -1 7819 -1 7820 -1 7821 -1 7822 -1 7823 -1 7824 -1 7825 -1 7826 -1 7827 -1 7828 -1 7829 -1 7830 -1 7831 -1 7832 -1 7833 -1 7834 -1 7835 -1 7836 -1 7837 -1 7838 -1 7839 -1 7840 -1 7841 -1 7842 -1 7843 -1 7844 -1 7845 -1 7846 -1 7847 -1 7848 -1 7849 -1 7850 -1 7851 -1 7852 -1 7853 -1 7854 -1 7855 -1 7856 -1 7857 -1 7858 -1 7859 -1 7860 -1 7861 -1 7862 -1 7863 -1 7864 -1 7865 -1 7866 -1 7867 -1 7868 -1 7869 -1 7870 -1 7871 -1 7872 -1 7873 -1 7874 -1 7875 -1 7876 -1 7877 -1 7878 -1 7879 -1 7880 -1 7881 -1 7882 -1 7883 -1 7884 -1 7885 -1 7886 -1 7887 -1 7888 -1 7889 -1 7890 -1 7891 -1 7892 -1 7893 -1 7894 -1 7895 -1 7896 -1 7897 -1 7898 -1 7899 -1 7900 -1 7901 -1 7902 -1 7903 -1 7904 -1 7905 -1 7906 -1 7907 -1 7908 -1 7909 -1 7910 -1 7911 -1 7912 -1 7913 -1 7914 -1 7915 -1 7916 -1 7917 -1 7918 -1 7919 -1 7920 -1 7921 -1 7922 -1 7923 -1 7924 -1 7925 -1 7926 -1 7927 -1 7928 -1 7929 -1 7930 -1 7931 -1 7932 -1 7933 -1 7934 -1 7935 -1 7936 -1 7937 -1 7938 -1 7939 -1 7940 -1 7941 -1 7942 -1 7943 -1 7944 -1 7945 -1 7946 -1 7947 -1 7948 -1 7949 -1 7950 -1 7951 -1 7952 -1 7953 -1 7954 -1 7955 -1 7956 -1 7957 -1 7958 -1 7959 -1 7960 -1 7961 -1 7962 -1 7963 -1 7964 -1 7965 -1 7966 -1 7967 -1 7968 -1 7969 -1 7970 -1 7971 -1 7972 -1 7973 -1 7974 -1 7975 -1 7976 -1 7977 -1 7978 -1 7979 -1 7980 -1 7981 -1 7982 -1 7983 -1 7984 -1 7985 -1 7986 -1 7987 -1 7988 -1 7989 -1 7990 -1 7991 -1 7992 -1 7993 -1 7994 -1 7995 -1 7996 -1 7997 -1 7998 -1 7999 -1 8000 -1 8001 -1 8002 -1 8003 -1 8004 -1 8005 -1 8006 -1 8007 -1 8008 -1 8009 -1 8010 -1 8011 -1 8012 -1 8013 -1 8014 -1 8015 -1 8016 -1 8017 -1 8018 -1 8019 -1 8020 -1 8021 -1 8022 -1 8023 -1 8024 -1 8025 -1 8026 -1 8027 -1 8028 -1 8029 -1 8030 -1 8031 -1 8032 -1 8033 -1 8034 -1 8035 -1 8036 -1 8037 -1 8038 -1 8039 -1 8040 -1 8041 -1 8042 -1 8043 -1 8044 -1 8045 -1 8046 -1 8047 -1 8048 -1 8049 -1 8050 -1 8051 -1 8052 -1 8053 -1 8054 -1 8055 -1 8056 -1 8057 -1 8058 -1 8059 -1 8060 -1 8061 -1 8062 -1 8063 -1 8064 -1 8065 -1 8066 -1 8067 -1 8068 -1 8069 -1 8070 -1 8071 -1 8072 -1 8073 -1 8074 -1 8075 -1 8076 -1 8077 -1 8078 -1 8079 -1 8080 -1 8081 -1 8082 -1 8083 -1 8084 -1 8085 -1 8086 -1 8087 -1 8088 -1 8089 -1 8090 -1 8091 -1 8092 -1 8093 -1 8094 -1 8095 -1 8096 -1 8097 -1 8098 -1 8099 -1 8100 -1 8101 -1 8102 -1 8103 -1 8104 -1 8105 -1 8106 -1 8107 -1 8108 -1 8109 -1 8110 -1 8111 -1 8112 -1 8113 -1 8114 -1 8115 -1 8116 -1 8117 -1 8118 -1 8119 -1 8120 -1 8121 -1 8122 -1 8123 -1 8124 -1 8125 -1 8126 -1 8127 -1 8128 -1 8129 -1 8130 -1 8131 -1 8132 -1 8133 -1 8134 -1 8135 -1 8136 -1 8137 -1 8138 -1 8139 -1 8140 -1 8141 -1 8142 -1 8143 -1 8144 -1 8145 -1 8146 -1 8147 -1 8148 -1 8149 -1 8150 -1 8151 -1 8152 -1 8153 -1 8154 -1 8155 -1 8156 -1 8157 -1 8158 -1 8159 -1 8160 -1 8161 -1 8162 -1 8163 -1 8164 -1 8165 -1 8166 -1 8167 -1 8168 -1 8169 -1 8170 -1 8171 -1 8172 -1 8173 -1 8174 -1 8175 -1 8176 -1 8177 -1 8178 -1 8179 -1 8180 -1 8181 -1 8182 -1 8183 -1 8184 -1 8185 -1 8186 -1 8187 -1 8188 -1 8189 -1 8190 -1 8191 -1 8192 -1 8193 -1 8194 -1 8195 -1 8196 -1 8197 -1 8198 -1 8199 -1 8200 -1 8201 -1 8202 -1 8203 -1 8204 -1 8205 -1 8206 -1 8207 -1 8208 -1 8209 -1 8210 -1 8211 -1 8212 -1 8213 -1 8214 -1 8215 -1 8216 -1 8217 -1 8218 -1 8219 -1 8220 -1 8221 -1 8222 -1 8223 -1 8224 -1 8225 -1 8226 -1 8227 -1 8228 -1 8229 -1 8230 -1 8231 -1 8232 -1 8233 -1 8234 -1 8235 -1 8236 -1 8237 -1 8238 -1 8239 -1 8240 -1 8241 -1 8242 -1 8243 -1 8244 -1 8245 -1 8246 -1 8247 -1 8248 -1 8249 -1 8250 -1 8251 -1 8252 -1 8253 -1 8254 -1 8255 -1 8256 -1 8257 -1 8258 -1 8259 -1 8260 -1 8261 -1 8262 -1 8263 -1 8264 -1 8265 -1 8266 -1 8267 -1 8268 -1 8269 -1 8270 -1 8271 -1 8272 -1 8273 -1 8274 -1 8275 -1 8276 -1 8277 -1 8278 -1 8279 -1 8280 -1 8281 -1 8282 -1 8283 -1 8284 -1 8285 -1 8286 -1 8287 -1 8288 -1 8289 -1 8290 -1 8291 -1 8292 -1 8293 -1 8294 -1 8295 -1 8296 -1 8297 -1 8298 -1 8299 -1 8300 -1 8301 -1 8302 -1 8303 -1 8304 -1 8305 -1 8306 -1 8307 -1 8308 -1 8309 -1 8310 -1 8311 -1 8312 -1 8313 -1 8314 -1 8315 -1 8316 -1 8317 -1 8318 -1 8319 -1 8320 -1 8321 -1 8322 -1 8323 -1 8324 -1 8325 -1 8326 -1 8327 -1 8328 -1 8329 -1 8330 -1 8331 -1 8332 -1 8333 -1 8334 -1 8335 -1 8336 -1 8337 -1 8338 -1 8339 -1 8340 -1 8341 -1 8342 -1 8343 -1 8344 -1 8345 -1 8346 -1 8347 -1 8348 -1 8349 -1 8350 -1 8351 -1 8352 -1 8353 -1 8354 -1 8355 -1 8356 -1 8357 -1 8358 -1 8359 -1 8360 -1 8361 -1 8362 -1 8363 -1 8364 -1 8365 -1 8366 -1 8367 -1 8368 -1 8369 -1 8370 -1 8371 -1 8372 -1 8373 -1 8374 -1 8375 -1 8376 -1 8377 -1 8378 -1 8379 -1 8380 -1 8381 -1 8382 -1 8383 -1 8384 -1 8385 -1 8386 -1 8387 -1 8388 -1 8389 -1 8390 -1 8391 -1 8392 -1 8393 -1 8394 -1 8395 -1 8396 -1 8397 -1 8398 -1 8399 -1 8400 -1 8401 -1 8402 -1 8403 -1 8404 -1 8405 -1 8406 -1 8407 -1 8408 -1 8409 -1 8410 -1 8411 -1 8412 -1 8413 -1 8414 -1 8415 -1 8416 -1 8417 -1 8418 -1 8419 -1 8420 -1 8421 -1 8422 -1 8423 -1 8424 -1 8425 -1 8426 -1 8427 -1 8428 -1 8429 -1 8430 -1 8431 -1 8432 -1 8433 -1 8434 -1 8435 -1 8436 -1 8437 -1 8438 -1 8439 -1 8440 -1 8441 -1 8442 -1 8443 -1 8444 -1 8445 -1 8446 -1 8447 -1 8448 -1 8449 -1 8450 -1 8451 -1 8452 -1 8453 -1 8454 -1 8455 -1 8456 -1 8457 -1 8458 -1 8459 -1 8460 -1 8461 -1 8462 -1 8463 -1 8464 -1 8465 -1 8466 -1 8467 -1 8468 -1 8469 -1 8470 -1 8471 -1 8472 -1 8473 -1 8474 -1 8475 -1 8476 -1 8477 -1 8478 -1 8479 -1 8480 -1 8481 -1 8482 -1 8483 -1 8484 -1 8485 -1 8486 -1 8487 -1 8488 -1 8489 -1 8490 -1 8491 -1 8492 -1 8493 -1 8494 -1 8495 -1 8496 -1 8497 -1 8498 -1 8499 -1 8500 -1 8501 -1 8502 -1 8503 -1 8504 -1 8505 -1 8506 -1 8507 -1 8508 -1 8509 -1 8510 -1 8511 -1 8512 -1 8513 -1 8514 -1 8515 -1 8516 -1 8517 -1 8518 -1 8519 -1 8520 -1 8521 -1 8522 -1 8523 -1 8524 -1 8525 -1 8526 -1 8527 -1 8528 -1 8529 -1 8530 -1 8531 -1 8532 -1 8533 -1 8534 -1 8535 -1 8536 -1 8537 -1 8538 -1 8539 -1 8540 -1 8541 -1 8542 -1 8543 -1 8544 -1 8545 -1 8546 -1 8547 -1 8548 -1 8549 -1 8550 -1 8551 -1 8552 -1 8553 -1 8554 -1 8555 -1 8556 -1 8557 -1 8558 -1 8559 -1 8560 -1 8561 -1 8562 -1 8563 -1 8564 -1 8565 -1 8566 -1 8567 -1 8568 -1 8569 -1 8570 -1 8571 -1 8572 -1 8573 -1 8574 -1 8575 -1 8576 -1 8577 -1 8578 -1 8579 -1 8580 -1 8581 -1 8582 -1 8583 -1 8584 -1 8585 -1 8586 -1 8587 -1 8588 -1 8589 -1 8590 -1 8591 -1 8592 -1 8593 -1 8594 -1 8595 -1 8596 -1 8597 -1 8598 -1 8599 -1 8600 -1 8601 -1 8602 -1 8603 -1 8604 -1 8605 -1 8606 -1 8607 -1 8608 -1 8609 -1 8610 -1 8611 -1 8612 -1 8613 -1 8614 -1 8615 -1 8616 -1 8617 -1 8618 -1 8619 -1 8620 -1 8621 -1 8622 -1 8623 -1 8624 -1 8625 -1 8626 -1 8627 -1 8628 -1 8629 -1 8630 -1 8631 -1 8632 -1 8633 -1 8634 -1 8635 -1 8636 -1 8637 -1 8638 -1 8639 -1 8640 -1 8641 -1 8642 -1 8643 -1 8644 -1 8645 -1 8646 -1 8647 -1 8648 -1 8649 -1 8650 -1 8651 -1 8652 -1 8653 -1 8654 -1 8655 -1 8656 -1 8657 -1 8658 -1 8659 -1 8660 -1 8661 -1 8662 -1 8663 -1 8664 -1 8665 -1 8666 -1 8667 -1 8668 -1 8669 -1 8670 -1 8671 -1 8672 -1 8673 -1 8674 -1 8675 -1 8676 -1 8677 -1 8678 -1 8679 -1 8680 -1 8681 -1 8682 -1 8683 -1 8684 -1 8685 -1 8686 -1 8687 -1 8688 -1 8689 -1 8690 -1 8691 -1 8692 -1 8693 -1 8694 -1 8695 -1 8696 -1 8697 -1 8698 -1 8699 -1 8700 -1 8701 -1 8702 -1 8703 -1 8704 -1 8705 -1 8706 -1 8707 -1 8708 -1 8709 -1 8710 -1 8711 -1 8712 -1 8713 -1 8714 -1 8715 -1 8716 -1 8717 -1 8718 -1 8719 -1 8720 -1 8721 -1 8722 -1 8723 -1 8724 -1 8725 -1 8726 -1 8727 -1 8728 -1 8729 -1 8730 -1 8731 -1 8732 -1 8733 -1 8734 -1 8735 -1 8736 -1 8737 -1 8738 -1 8739 -1 8740 -1 8741 -1 8742 -1 8743 -1 8744 -1 8745 -1 8746 -1 8747 -1 8748 -1 8749 -1 8750 -1 8751 -1 8752 -1 8753 -1 8754 -1 8755 -1 8756 -1 8757 -1 8758 -1 8759 -1 8760 -1 8761 -1 8762 -1 8763 -1 8764 -1 8765 -1 8766 -1 8767 -1 8768 -1 8769 -1 8770 -1 8771 -1 8772 -1 8773 -1 8774 -1 8775 -1 8776 -1 8777 -1 8778 -1 8779 -1 8780 -1 8781 -1 8782 -1 8783 -1 8784 -1 8785 -1 8786 -1 8787 -1 8788 -1 8789 -1 8790 -1 8791 -1 8792 -1 8793 -1 8794 -1 8795 -1 8796 -1 8797 -1 8798 -1 8799 -1 8800 -1 8801 -1 8802 -1 8803 -1 8804 -1 8805 -1 8806 -1 8807 -1 8808 -1 8809 -1 8810 -1 8811 -1 8812 -1 8813 -1 8814 -1 8815 -1 8816 -1 8817 -1 8818 -1 8819 -1 8820 -1 8821 -1 8822 -1 8823 -1 8824 -1 8825 -1 8826 -1 8827 -1 8828 -1 8829 -1 8830 -1 8831 -1 8832 -1 8833 -1 8834 -1 8835 -1 8836 -1 8837 -1 8838 -1 8839 -1 8840 -1 8841 -1 8842 -1 8843 -1 8844 -1 8845 -1 8846 -1 8847 -1 8848 -1 8849 -1 8850 -1 8851 -1 8852 -1 8853 -1 8854 -1 8855 -1 8856 -1 8857 -1 8858 -1 8859 -1 8860 -1 8861 -1 8862 -1 8863 -1 8864 -1 8865 -1 8866 -1 8867 -1 8868 -1 8869 -1 8870 -1 8871 -1 8872 -1 8873 -1 8874 -1 8875 -1 8876 -1 8877 -1 8878 -1 8879 -1 8880 -1 8881 -1 8882 -1 8883 -1 8884 -1 8885 -1 8886 -1 8887 -1 8888 -1 8889 -1 8890 -1 8891 -1 8892 -1 8893 -1 8894 -1 8895 -1 8896 -1 8897 -1 8898 -1 8899 -1 8900 -1 8901 -1 8902 -1 8903 -1 8904 -1 8905 -1 8906 -1 8907 -1 8908 -1 8909 -1 8910 -1 8911 -1 8912 -1 8913 -1 8914 -1 8915 -1 8916 -1 8917 -1 8918 -1 8919 -1 8920 -1 8921 -1 8922 -1 8923 -1 8924 -1 8925 -1 8926 -1 8927 -1 8928 -1 8929 -1 8930 -1 8931 -1 8932 -1 8933 -1 8934 -1 8935 -1 8936 -1 8937 -1 8938 -1 8939 -1 8940 -1 8941 -1 8942 -1 8943 -1 8944 -1 8945 -1 8946 -1 8947 -1 8948 -1 8949 -1 8950 -1 8951 -1 8952 -1 8953 -1 8954 -1 8955 -1 8956 -1 8957 -1 8958 -1 8959 -1 8960 -1 8961 -1 8962 -1 8963 -1 8964 -1 8965 -1 8966 -1 8967 -1 8968 -1 8969 -1 8970 -1 8971 -1 8972 -1 8973 -1 8974 -1 8975 -1 8976 -1 8977 -1 8978 -1 8979 -1 8980 -1 8981 -1 8982 -1 8983 -1 8984 -1 8985 -1 8986 -1 8987 -1 8988 -1 8989 -1 8990 -1 8991 -1 8992 -1 8993 -1 8994 -1 8995 -1 8996 -1 8997 -1 8998 -1 8999 -1 9000 -1 9001 -1 9002 -1 9003 -1 9004 -1 9005 -1 9006 -1 9007 -1 9008 -1 9009 -1 9010 -1 9011 -1 9012 -1 9013 -1 9014 -1 9015 -1 9016 -1 9017 -1 9018 -1 9019 -1 9020 -1 9021 -1 9022 -1 9023 -1 9024 -1 9025 -1 9026 -1 9027 -1 9028 -1 9029 -1 9030 -1 9031 -1 9032 -1 9033 -1 9034 -1 9035 -1 9036 -1 9037 -1 9038 -1 9039 -1 9040 -1 9041 -1 9042 -1 9043 -1 9044 -1 9045 -1 9046 -1 9047 -1 9048 -1 9049 -1 9050 -1 9051 -1 9052 -1 9053 -1 9054 -1 9055 -1 9056 -1 9057 -1 9058 -1 9059 -1 9060 -1 9061 -1 9062 -1 9063 -1 9064 -1 9065 -1 9066 -1 9067 -1 9068 -1 9069 -1 9070 -1 9071 -1 9072 -1 9073 -1 9074 -1 9075 -1 9076 -1 9077 -1 9078 -1 9079 -1 9080 -1 9081 -1 9082 -1 9083 -1 9084 -1 9085 -1 9086 -1 9087 -1 9088 -1 9089 -1 9090 -1 9091 -1 9092 -1 9093 -1 9094 -1 9095 -1 9096 -1 9097 -1 9098 -1 9099 -1 9100 -1 9101 -1 9102 -1 9103 -1 9104 -1 9105 -1 9106 -1 9107 -1 9108 -1 9109 -1 9110 -1 9111 -1 9112 -1 9113 -1 9114 -1 9115 -1 9116 -1 9117 -1 9118 -1 9119 -1 9120 -1 9121 -1 9122 -1 9123 -1 9124 -1 9125 -1 9126 -1 9127 -1 9128 -1 9129 -1 9130 -1 9131 -1 9132 -1 9133 -1 9134 -1 9135 -1 9136 -1 9137 -1 9138 -1 9139 -1 9140 -1 9141 -1 9142 -1 9143 -1 9144 -1 9145 -1 9146 -1 9147 -1 9148 -1 9149 -1 9150 -1 9151 -1 9152 -1 9153 -1 9154 -1 9155 -1 9156 -1 9157 -1 9158 -1 9159 -1 9160 -1 9161 -1 9162 -1 9163 -1 9164 -1 9165 -1 9166 -1 9167 -1 9168 -1 9169 -1 9170 -1 9171 -1 9172 -1 9173 -1 9174 -1 9175 -1 9176 -1 9177 -1 9178 -1 9179 -1 9180 -1 9181 -1 9182 -1 9183 -1 9184 -1 9185 -1 9186 -1 9187 -1 9188 -1 9189 -1 9190 -1 9191 -1 9192 -1 9193 -1 9194 -1 9195 -1 9196 -1 9197 -1 9198 -1 9199 -1 9200 -1 9201 -1 9202 -1 9203 -1 9204 -1 9205 -1 9206 -1 9207 -1 9208 -1 9209 -1 9210 -1 9211 -1 9212 -1 9213 -1 9214 -1 9215 -1 9216 -1 9217 -1 9218 -1 9219 -1 9220 -1 9221 -1 9222 -1 9223 -1 9224 -1 9225 -1 9226 -1 9227 -1 9228 -1 9229 -1 9230 -1 9231 -1 9232 -1 9233 -1 9234 -1 9235 -1 9236 -1 9237 -1 9238 -1 9239 -1 9240 -1 9241 -1 9242 -1 9243 -1 9244 -1 9245 -1 9246 -1 9247 -1 9248 -1 9249 -1 9250 -1 9251 -1 9252 -1 9253 -1 9254 -1 9255 -1 9256 -1 9257 -1 9258 -1 9259 -1 9260 -1 9261 -1 9262 -1 9263 -1 9264 -1 9265 -1 9266 -1 9267 -1 9268 -1 9269 -1 9270 -1 9271 -1 9272 -1 9273 -1 9274 -1 9275 -1 9276 -1 9277 -1 9278 -1 9279 -1 9280 -1 9281 -1 9282 -1 9283 -1 9284 -1 9285 -1 9286 -1 9287 -1 9288 -1 9289 -1 9290 -1 9291 -1 9292 -1 9293 -1 9294 -1 9295 -1 9296 -1 9297 -1 9298 -1 9299 -1 9300 -1 9301 -1 9302 -1 9303 -1 9304 -1 9305 -1 9306 -1 9307 -1 9308 -1 9309 -1 9310 -1 9311 -1 9312 -1 9313 -1 9314 -1 9315 -1 9316 -1 9317 -1 9318 -1 9319 -1 9320 -1 9321 -1 9322 -1 9323 -1 9324 -1 9325 -1 9326 -1 9327 -1 9328 -1 9329 -1 9330 -1 9331 -1 9332 -1 9333 -1 9334 -1 9335 -1 9336 -1 9337 -1 9338 -1 9339 -1 9340 -1 9341 -1 9342 -1 9343 -1 9344 -1 9345 -1 9346 -1 9347 -1 9348 -1 9349 -1 9350 -1 9351 -1 9352 -1 9353 -1 9354 -1 9355 -1 9356 -1 9357 -1 9358 -1 9359 -1 9360 -1 9361 -1 9362 -1 9363 -1 9364 -1 9365 -1 9366 -1 9367 -1 9368 -1 9369 -1 9370 -1 9371 -1 9372 -1 9373 -1 9374 -1 9375 -1 9376 -1 9377 -1 9378 -1 9379 -1 9380 -1 9381 -1 9382 -1 9383 -1 9384 -1 9385 -1 9386 -1 9387 -1 9388 -1 9389 -1 9390 -1 9391 -1 9392 -1 9393 -1 9394 -1 9395 -1 9396 -1 9397 -1 9398 -1 9399 -1 9400 -1 9401 -1 9402 -1 9403 -1 9404 -1 9405 -1 9406 -1 9407 -1 9408 -1 9409 -1 9410 -1 9411 -1 9412 -1 9413 -1 9414 -1 9415 -1 9416 -1 9417 -1 9418 -1 9419 -1 9420 -1 9421 -1 9422 -1 9423 -1 9424 -1 9425 -1 9426 -1 9427 -1 9428 -1 9429 -1 9430 -1 9431 -1 9432 -1 9433 -1 9434 -1 9435 -1 9436 -1 9437 -1 9438 -1 9439 -1 9440 -1 9441 -1 9442 -1 9443 -1 9444 -1 9445 -1 9446 -1 9447 -1 9448 -1 9449 -1 9450 -1 9451 -1 9452 -1 9453 -1 9454 -1 9455 -1 9456 -1 9457 -1 9458 -1 9459 -1 9460 -1 9461 -1 9462 -1 9463 -1 9464 -1 9465 -1 9466 -1 9467 -1 9468 -1 9469 -1 9470 -1 9471 -1 9472 -1 9473 -1 9474 -1 9475 -1 9476 -1 9477 -1 9478 -1 9479 -1 9480 -1 9481 -1 9482 -1 9483 -1 9484 -1 9485 -1 9486 -1 9487 -1 9488 -1 9489 -1 9490 -1 9491 -1 9492 -1 9493 -1 9494 -1 9495 -1 9496 -1 9497 -1 9498 -1 9499 -1 9500 -1 9501 -1 9502 -1 9503 -1 9504 -1 9505 -1 9506 -1 9507 -1 9508 -1 9509 -1 9510 -1 9511 -1 9512 -1 9513 -1 9514 -1 9515 -1 9516 -1 9517 -1 9518 -1 9519 -1 9520 -1 9521 -1 9522 -1 9523 -1 9524 -1 9525 -1 9526 -1 9527 -1 9528 -1 9529 -1 9530 -1 9531 -1 9532 -1 9533 -1 9534 -1 9535 -1 9536 -1 9537 -1 9538 -1 9539 -1 9540 -1 9541 -1 9542 -1 9543 -1 9544 -1 9545 -1 9546 -1 9547 -1 9548 -1 9549 -1 9550 -1 9551 -1 9552 -1 9553 -1 9554 -1 9555 -1 9556 -1 9557 -1 9558 -1 9559 -1 9560 -1 9561 -1 9562 -1 9563 -1 9564 -1 9565 -1 9566 -1 9567 -1 9568 -1 9569 -1 9570 -1 9571 -1 9572 -1 9573 -1 9574 -1 9575 -1 9576 -1 9577 -1 9578 -1 9579 -1 9580 -1 9581 -1 9582 -1 9583 -1 9584 -1 9585 -1 9586 -1 9587 -1 9588 -1 9589 -1 9590 -1 9591 -1 9592 -1 9593 -1 9594 -1 9595 -1 9596 -1 9597 -1 9598 -1 9599 -1 9600 -1 9601 -1 9602 -1 9603 -1 9604 -1 9605 -1 9606 -1 9607 -1 9608 -1 9609 -1 9610 -1 9611 -1 9612 -1 9613 -1 9614 -1 9615 -1 9616 -1 9617 -1 9618 -1 9619 -1 9620 -1 9621 -1 9622 -1 9623 -1 9624 -1 9625 -1 9626 -1 9627 -1 9628 -1 9629 -1 9630 -1 9631 -1 9632 -1 9633 -1 9634 -1 9635 -1 9636 -1 9637 -1 9638 -1 9639 -1 9640 -1 9641 -1 9642 -1 9643 -1 9644 -1 9645 -1 9646 -1 9647 -1 9648 -1 9649 -1 9650 -1 9651 -1 9652 -1 9653 -1 9654 -1 9655 -1 9656 -1 9657 -1 9658 -1 9659 -1 9660 -1 9661 -1 9662 -1 9663 -1 9664 -1 9665 -1 9666 -1 9667 -1 9668 -1 9669 -1 9670 -1 9671 -1 9672 -1 9673 -1 9674 -1 9675 -1 9676 -1 9677 -1 9678 -1 9679 -1 9680 -1 9681 -1 9682 -1 9683 -1 9684 -1 9685 -1 9686 -1 9687 -1 9688 -1 9689 -1 9690 -1 9691 -1 9692 -1 9693 -1 9694 -1 9695 -1 9696 -1 9697 -1 9698 -1 9699 -1 9700 -1 9701 -1 9702 -1 9703 -1 9704 -1 9705 -1 9706 -1 9707 -1 9708 -1 9709 -1 9710 -1 9711 -1 9712 -1 9713 -1 9714 -1 9715 -1 9716 -1 9717 -1 9718 -1 9719 -1 9720 -1 9721 -1 9722 -1 9723 -1 9724 -1 9725 -1 9726 -1 9727 -1 9728 -1 9729 -1 9730 -1 9731 -1 9732 -1 9733 -1 9734 -1 9735 -1 9736 -1 9737 -1 9738 -1 9739 -1 9740 -1 9741 -1 9742 -1 9743 -1 9744 -1 9745 -1 9746 -1 9747 -1 9748 -1 9749 -1 9750 -1 9751 -1 9752 -1 9753 -1 9754 -1 9755 -1 9756 -1 9757 -1 9758 -1 9759 -1 9760 -1 9761 -1 9762 -1 9763 -1 9764 -1 9765 -1 9766 -1 9767 -1 9768 -1 9769 -1 9770 -1 9771 -1 9772 -1 9773 -1 9774 -1 9775 -1 9776 -1 9777 -1 9778 -1 9779 -1 9780 -1 9781 -1 9782 -1 9783 -1 9784 -1 9785 -1 9786 -1 9787 -1 9788 -1 9789 -1 9790 -1 9791 -1 9792 -1 9793 -1 9794 -1 9795 -1 9796 -1 9797 -1 9798 -1 9799 -1 9800 -1 9801 -1 9802 -1 9803 -1 9804 -1 9805 -1 9806 -1 9807 -1 9808 -1 9809 -1 9810 -1 9811 -1 9812 -1 9813 -1 9814 -1 9815 -1 9816 -1 9817 -1 9818 -1 9819 -1 9820 -1 9821 -1 9822 -1 9823 -1 9824 -1 9825 -1 9826 -1 9827 -1 9828 -1 9829 -1 9830 -1 9831 -1 9832 -1 9833 -1 9834 -1 9835 -1 9836 -1 9837 -1 9838 -1 9839 -1 9840 -1 9841 -1 9842 -1 9843 -1 9844 -1 9845 -1 9846 -1 9847 -1 9848 -1 9849 -1 9850 -1 9851 -1 9852 -1 9853 -1 9854 -1 9855 -1 9856 -1 9857 -1 9858 -1 9859 -1 9860 -1 9861 -1 9862 -1 9863 -1 9864 -1 9865 -1 9866 -1 9867 -1 9868 -1 9869 -1 9870 -1 9871 -1 9872 -1 9873 -1 9874 -1 9875 -1 9876 -1 9877 -1 9878 -1 9879 -1 9880 -1 9881 -1 9882 -1 9883 -1 9884 -1 9885 -1 9886 -1 9887 -1 9888 -1 9889 -1 9890 -1 9891 -1 9892 -1 9893 -1 9894 -1 9895 -1 9896 -1 9897 -1 9898 -1 9899 -1 9900 -1 9901 -1 9902 -1 9903 -1 9904 -1 9905 -1 9906 -1 9907 -1 9908 -1 9909 -1 9910 -1 9911 -1 9912 -1 9913 -1 9914 -1 9915 -1 9916 -1 9917 -1 9918 -1 9919 -1 9920 -1 9921 -1 9922 -1 9923 -1 9924 -1 9925 -1 9926 -1 9927 -1 9928 -1 9929 -1 9930 -1 9931 -1 9932 -1 9933 -1 9934 -1 9935 -1 9936 -1 9937 -1 9938 -1 9939 -1 9940 -1 9941 -1 9942 -1 9943 -1 9944 -1 9945 -1 9946 -1 9947 -1 9948 -1 9949 -1 9950 -1 9951 -1 9952 -1 9953 -1 9954 -1 9955 -1 9956 -1 9957 -1 9958 -1 9959 -1 9960 -1 9961 -1 9962 -1 9963 -1 9964 -1 9965 -1 9966 -1 9967 -1 9968 -1 9969 -1 9970 -1 9971 -1 9972 -1 9973 -1 9974 -1 9975 -1 9976 -1 9977 -1 9978 -1 9979 -1 9980 -1 9981 -1 9982 -1 9983 -1 9984 -1 9985 -1 9986 -1 9987 -1 9988 -1 9989 -1 9990 -1 9991 -1 9992 -1 9993 -1 9994 -1 9995 -1 9996 -1 9997 -1 9998 -1 9999 -1 10000 -1 10001 -1 10002 -1 10003 -1 10004 -1 10005 -1 10006 -1 10007 -1 10008 -1 10009 -1 10010 -1 10011 -1 10012 -1 10013 -1 10014 -1 10015 -1 10016 -1 10017 -1 10018 -1 10019 -1 10020 -1 10021 -1 10022 -1 10023 -1 10024 -1 10025 -1 10026 -1 10027 -1 10028 -1 10029 -1 10030 -1 10031 -1 10032 -1 10033 -1 10034 -1 10035 -1 10036 -1 10037 -1 10038 -1 10039 -1 10040 -1 10041 -1 10042 -1 10043 -1 10044 -1 10045 -1 10046 -1 10047 -1 10048 -1 10049 -1 10050 -1 10051 -1 10052 -1 10053 -1 10054 -1 10055 -1 10056 -1 10057 -1 10058 -1 10059 -1 10060 -1 10061 -1 10062 -1 10063 -1 10064 -1 10065 -1 10066 -1 10067 -1 10068 -1 10069 -1 10070 -1 10071 -1 10072 -1 10073 -1 10074 -1 10075 -1 10076 -1 10077 -1 10078 -1 10079 -1 10080 -1 10081 -1 10082 -1 10083 -1 10084 -1 10085 -1 10086 -1 10087 -1 10088 -1 10089 -1 10090 -1 10091 -1 10092 -1 10093 -1 10094 -1 10095 -1 10096 -1 10097 -1 10098 -1 10099 -1 10100 -1 10101 -1 10102 -1 10103 -1 10104 -1 10105 -1 10106 -1 10107 -1 10108 -1 10109 -1 10110 -1 10111 -1 10112 -1 10113 -1 10114 -1 10115 -1 10116 -1 10117 -1 10118 -1 10119 -1 10120 -1 10121 -1 10122 -1 10123 -1 10124 -1 10125 -1 10126 -1 10127 -1 10128 -1 10129 -1 10130 -1 10131 -1 10132 -1 10133 -1 10134 -1 10135 -1 10136 -1 10137 -1 10138 -1 10139 -1 10140 -1 10141 -1 10142 -1 10143 -1 10144 -1 10145 -1 10146 -1 10147 -1 10148 -1 10149 -1 10150 -1 10151 -1 10152 -1 10153 -1 10154 -1 10155 -1 10156 -1 10157 -1 10158 -1 10159 -1 10160 -1 10161 -1 10162 -1 10163 -1 10164 -1 10165 -1 10166 -1 10167 -1 10168 -1 10169 -1 10170 -1 10171 -1 10172 -1 10173 -1 10174 -1 10175 -1 10176 -1 10177 -1 10178 -1 10179 -1 10180 -1 10181 -1 10182 -1 10183 -1 10184 -1 10185 -1 10186 -1 10187 -1 10188 -1 10189 -1 10190 -1 10191 -1 10192 -1 10193 -1 10194 -1 10195 -1 10196 -1 10197 -1 10198 -1 10199 -1 10200 -1 10201 -1 10202 -1 10203 -1 10204 -1 10205 -1 10206 -1 10207 -1 10208 -1 10209 -1 10210 -1 10211 -1 10212 -1 10213 -1 10214 -1 10215 -1 10216 -1 10217 -1 10218 -1 10219 -1 10220 -1 10221 -1 10222 -1 10223 -1 10224 -1 10225 -1 10226 -1 10227 -1 10228 -1 10229 -1 10230 -1 10231 -1 10232 -1 10233 -1 10234 -1 10235 -1 10236 -1 10237 -1 10238 -1 10239 -1 10240 -1 10241 -1 10242 -1 10243 -1 10244 -1 10245 -1 10246 -1 10247 -1 10248 -1 10249 -1 10250 -1 10251 -1 10252 -1 10253 -1 10254 -1 10255 -1 10256 -1 10257 -1 10258 -1 10259 -1 10260 -1 10261 -1 10262 -1 10263 -1 10264 -1 10265 -1 10266 -1 10267 -1 10268 -1 10269 -1 10270 -1 10271 -1 10272 -1 10273 -1 10274 -1 10275 -1 10276 -1 10277 -1 10278 -1 10279 -1 10280 -1 10281 -1 10282 -1 10283 -1 10284 -1 10285 -1 10286 -1 10287 -1 10288 -1 10289 -1 10290 -1 10291 -1 10292 -1 10293 -1 10294 -1 10295 -1 10296 -1 10297 -1 10298 -1 10299 -1 10300 -1 10301 -1 10302 -1 10303 -1 10304 -1 10305 -1 10306 -1 10307 -1 10308 -1 10309 -1 10310 -1 10311 -1 10312 -1 10313 -1 10314 -1 10315 -1 10316 -1 10317 -1 10318 -1 10319 -1 10320 -1 10321 -1 10322 -1 10323 -1 10324 -1 10325 -1 10326 -1 10327 -1 10328 -1 10329 -1 10330 -1 10331 -1 10332 -1 10333 -1 10334 -1 10335 -1 10336 -1 10337 -1 10338 -1 10339 -1 10340 -1 10341 -1 10342 -1 10343 -1 10344 -1 10345 -1 10346 -1 10347 -1 10348 -1 10349 -1 10350 -1 10351 -1 10352 -1 10353 -1 10354 -1 10355 -1 10356 -1 10357 -1 10358 -1 10359 -1 10360 -1 10361 -1 10362 -1 10363 -1 10364 -1 10365 -1 10366 -1 10367 -1 10368 -1 10369 -1 10370 -1 10371 -1 10372 -1 10373 -1 10374 -1 10375 -1 10376 -1 10377 -1 10378 -1 10379 -1 10380 -1 10381 -1 10382 -1 10383 -1 10384 -1 10385 -1 10386 -1 10387 -1 10388 -1 10389 -1 10390 -1 10391 -1 10392 -1 10393 -1 10394 -1 10395 -1 10396 -1 10397 -1 10398 -1 10399 -1 10400 -1 10401 -1 10402 -1 10403 -1 10404 -1 10405 -1 10406 -1 10407 -1 10408 -1 10409 -1 10410 -1 10411 -1 10412 -1 10413 -1 10414 -1 10415 -1 10416 -1 10417 -1 10418 -1 10419 -1 10420 -1 10421 -1 10422 -1 10423 -1 10424 -1 10425 -1 10426 -1 10427 -1 10428 -1 10429 -1 10430 -1 10431 -1 10432 -1 10433 -1 10434 -1 10435 -1 10436 -1 10437 -1 10438 -1 10439 -1 10440 -1 10441 -1 10442 -1 10443 -1 10444 -1 10445 -1 10446 -1 10447 -1 10448 -1 10449 -1 10450 -1 10451 -1 10452 -1 10453 -1 10454 -1 10455 -1 10456 -1 10457 -1 10458 -1 10459 -1 10460 -1 10461 -1 10462 -1 10463 -1 10464 -1 10465 -1 10466 -1 10467 -1 10468 -1 10469 -1 10470 -1 10471 -1 10472 -1 10473 -1 10474 -1 10475 -1 10476 -1 10477 -1 10478 -1 10479 -1 10480 -1 10481 -1 10482 -1 10483 -1 10484 -1 10485 -1 10486 -1 10487 -1 10488 -1 10489 -1 10490 -1 10491 -1 10492 -1 10493 -1 10494 -1 10495 -1 10496 -1 10497 -1 10498 -1 10499 -1 10500 -1 10501 -1 10502 -1 10503 -1 10504 -1 10505 -1 10506 -1 10507 -1 10508 -1 10509 -1 10510 -1 10511 -1 10512 -1 10513 -1 10514 -1 10515 -1 10516 -1 10517 -1 10518 -1 10519 -1 10520 -1 10521 -1 10522 -1 10523 -1 10524 -1 10525 -1 10526 -1 10527 -1 10528 -1 10529 -1 10530 -1 10531 -1 10532 -1 10533 -1 10534 -1 10535 -1 10536 -1 10537 -1 10538 -1 10539 -1 10540 -1 10541 -1 10542 -1 10543 -1 10544 -1 10545 -1 10546 -1 10547 -1 10548 -1 10549 -1 10550 -1 10551 -1 10552 -1 10553 -1 10554 -1 10555 -1 10556 -1 10557 -1 10558 -1 10559 -1 10560 -1 10561 -1 10562 -1 10563 -1 10564 -1 10565 -1 10566 -1 10567 -1 10568 -1 10569 -1 10570 -1 10571 -1 10572 -1 10573 -1 10574 -1 10575 -1 10576 -1 10577 -1 10578 -1 10579 -1 10580 -1 10581 -1 10582 -1 10583 -1 10584 -1 10585 -1 10586 -1 10587 -1 10588 -1 10589 -1 10590 -1 10591 -1 10592 -1 10593 -1 10594 -1 10595 -1 10596 -1 10597 -1 10598 -1 10599 -1 10600 -1 10601 -1 10602 -1 10603 -1 10604 -1 10605 -1 10606 -1 10607 -1 10608 -1 10609 -1 10610 -1 10611 -1 10612 -1 10613 -1 10614 -1 10615 -1 10616 -1 10617 -1 10618 -1 10619 -1 10620 -1 10621 -1 10622 -1 10623 -1 10624 -1 10625 -1 10626 -1 10627 -1 10628 -1 10629 -1 10630 -1 10631 -1 10632 -1 10633 -1 10634 -1 10635 -1 10636 -1 10637 -1 10638 -1 10639 -1 10640 -1 10641 -1 10642 -1 10643 -1 10644 -1 10645 -1 10646 -1 10647 -1 10648 -1 10649 -1 10650 -1 10651 -1 10652 -1 10653 -1 10654 -1 10655 -1 10656 -1 10657 -1 10658 -1 10659 -1 10660 -1 10661 -1 10662 -1 10663 -1 10664 -1 10665 -1 10666 -1 10667 -1 10668 -1 10669 -1 10670 -1 10671 -1 10672 -1 10673 -1 10674 -1 10675 -1 10676 -1 10677 -1 10678 -1 10679 -1 10680 -1 10681 -1 10682 -1 10683 -1 10684 -1 10685 -1 10686 -1 10687 -1 10688 -1 10689 -1 10690 -1 10691 -1 10692 -1 10693 -1 10694 -1 10695 -1 10696 -1 10697 -1 10698 -1 10699 -1 10700 -1 10701 -1 10702 -1 10703 -1 10704 -1 10705 -1 10706 -1 10707 -1 10708 -1 10709 -1 10710 -1 10711 -1 10712 -1 10713 -1 10714 -1 10715 -1 10716 -1 10717 -1 10718 -1 10719 -1 10720 -1 10721 -1 10722 -1 10723 -1 10724 -1 10725 -1 10726 -1 10727 -1 10728 -1 10729 -1 10730 -1 10731 -1 10732 -1 10733 -1 10734 -1 10735 -1 10736 -1 10737 -1 10738 -1 10739 -1 10740 -1 10741 -1 10742 -1 10743 -1 10744 -1 10745 -1 10746 -1 10747 -1 10748 -1 10749 -1 10750 -1 10751 -1 10752 -1 10753 -1 10754 -1 10755 -1 10756 -1 10757 -1 10758 -1 10759 -1 10760 -1 10761 -1 10762 -1 10763 -1 10764 -1 10765 -1 10766 -1 10767 -1 10768 -1 10769 -1 10770 -1 10771 -1 10772 -1 10773 -1 10774 -1 10775 -1 10776 -1 10777 -1 10778 -1 10779 -1 10780 -1 10781 -1 10782 -1 10783 -1 10784 -1 10785 -1 10786 -1 10787 -1 10788 -1 10789 -1 10790 -1 10791 -1 10792 -1 10793 -1 10794 -1 10795 -1 10796 -1 10797 -1 10798 -1 10799 -1 10800 -1 10801 -1 10802 -1 10803 -1 10804 -1 10805 -1 10806 -1 10807 -1 10808 -1 10809 -1 10810 -1 10811 -1 10812 -1 10813 -1 10814 -1 10815 -1 10816 -1 10817 -1 10818 -1 10819 -1 10820 -1 10821 -1 10822 -1 10823 -1 10824 -1 10825 -1 10826 -1 10827 -1 10828 -1 10829 -1 10830 -1 10831 -1 10832 -1 10833 -1 10834 -1 10835 -1 10836 -1 10837 -1 10838 -1 10839 -1 10840 -1 10841 -1 10842 -1 10843 -1 10844 -1 10845 -1 10846 -1 10847 -1 10848 -1 10849 -1 10850 -1 10851 -1 10852 -1 10853 -1 10854 -1 10855 -1 10856 -1 10857 -1 10858 -1 10859 -1 10860 -1 10861 -1 10862 -1 10863 -1 10864 -1 10865 -1 10866 -1 10867 -1 10868 -1 10869 -1 10870 -1 10871 -1 10872 -1 10873 -1 10874 -1 10875 -1 10876 -1 10877 -1 10878 -1 10879 -1 10880 -1 10881 -1 10882 -1 10883 -1 10884 -1 10885 -1 10886 -1 10887 -1 10888 -1 10889 -1 10890 -1 10891 -1 10892 -1 10893 -1 10894 -1 10895 -1 10896 -1 10897 -1 10898 -1 10899 -1 10900 -1 10901 -1 10902 -1 10903 -1 10904 -1 10905 -1 10906 -1 10907 -1 10908 -1 10909 -1 10910 -1 10911 -1 10912 -1 10913 -1 10914 -1 10915 -1 10916 -1 10917 -1 10918 -1 10919 -1 10920 -1 10921 -1 10922 -1 10923 -1 10924 -1 10925 -1 10926 -1 10927 -1 10928 -1 10929 -1 10930 -1 10931 -1 10932 -1 10933 -1 10934 -1 10935 -1 10936 -1 10937 -1 10938 -1 10939 -1 10940 -1 10941 -1 10942 -1 10943 -1 10944 -1 10945 -1 10946 -1 10947 -1 10948 -1 10949 -1 10950 -1 10951 -1 10952 -1 10953 -1 10954 -1 10955 -1 10956 -1 10957 -1 10958 -1 10959 -1 10960 -1 10961 -1 10962 -1 10963 -1 10964 -1 10965 -1 10966 -1 10967 -1 10968 -1 10969 -1 10970 -1 10971 -1 10972 -1 10973 -1 10974 -1 10975 -1 10976 -1 10977 -1 10978 -1 10979 -1 10980 -1 10981 -1 10982 -1 10983 -1 10984 -1 10985 -1 10986 -1 10987 -1 10988 -1 10989 -1 10990 -1 10991 -1 10992 -1 10993 -1 10994 -1 10995 -1 10996 -1 10997 -1 10998 -1 10999 -1 11000 -1 11001 -1 11002 -1 11003 -1 11004 -1 11005 -1 11006 -1 11007 -1 11008 -1 11009 -1 11010 -1 11011 -1 11012 -1 11013 -1 11014 -1 11015 -1 11016 -1 11017 -1 11018 -1 11019 -1 11020 -1 11021 -1 11022 -1 11023 -1 11024 -1 11025 -1 11026 -1 11027 -1 11028 -1 11029 -1 11030 -1 11031 -1 11032 -1 11033 -1 11034 -1 11035 -1 11036 -1 11037 -1 11038 -1 11039 -1 11040 -1 11041 -1 11042 -1 11043 -1 11044 -1 11045 -1 11046 -1 11047 -1 11048 -1 11049 -1 11050 -1 11051 -1 11052 -1 11053 -1 11054 -1 11055 -1 11056 -1 11057 -1 11058 -1 11059 -1 11060 -1 11061 -1 11062 -1 11063 -1 11064 -1 11065 -1 11066 -1 11067 -1 11068 -1 11069 -1 11070 -1 11071 -1 11072 -1 11073 -1 11074 -1 11075 -1 11076 -1 11077 -1 11078 -1 11079 -1 11080 -1 11081 -1 11082 -1 11083 -1 11084 -1 11085 -1 11086 -1 11087 -1 11088 -1 11089 -1 11090 -1 11091 -1 11092 -1 11093 -1 11094 -1 11095 -1 11096 -1 11097 -1 11098 -1 11099 -1 11100 -1 11101 -1 11102 -1 11103 -1 11104 -1 11105 -1 11106 -1 11107 -1 11108 -1 11109 -1 11110 -1 11111 -1 11112 -1 11113 -1 11114 -1 11115 -1 11116 -1 11117 -1 11118 -1 11119 -1 11120 -1 11121 -1 11122 -1 11123 -1 11124 -1 11125 -1 11126 -1 11127 -1 11128 -1 11129 -1 11130 -1 11131 -1 11132 -1 11133 -1 11134 -1 11135 -1 11136 -1 11137 -1 11138 -1 11139 -1 11140 -1 11141 -1 11142 -1 11143 -1 11144 -1 11145 -1 11146 -1 11147 -1 11148 -1 11149 -1 11150 -1 11151 -1 11152 -1 11153 -1 11154 -1 11155 -1 11156 -1 11157 -1 11158 -1 11159 -1 11160 -1 11161 -1 11162 -1 11163 -1 11164 -1 11165 -1 11166 -1 11167 -1 11168 -1 11169 -1 11170 -1 11171 -1 11172 -1 11173 -1 11174 -1 11175 -1 11176 -1 11177 -1 11178 -1 11179 -1 11180 -1 11181 -1 11182 -1 11183 -1 11184 -1 11185 -1 11186 -1 11187 -1 11188 -1 11189 -1 11190 -1 11191 -1 11192 -1 11193 -1 11194 -1 11195 -1 11196 -1 11197 -1 11198 -1 11199 -1 11200 -1 11201 -1 11202 -1 11203 -1 11204 -1 11205 -1 11206 -1 11207 -1 11208 -1 11209 -1 11210 -1 11211 -1 11212 -1 11213 -1 11214 -1 11215 -1 11216 -1 11217 -1 11218 -1 11219 -1 11220 -1 11221 -1 11222 -1 11223 -1 11224 -1 11225 -1 11226 -1 11227 -1 11228 -1 11229 -1 11230 -1 11231 -1 11232 -1 11233 -1 11234 -1 11235 -1 11236 -1 11237 -1 11238 -1 11239 -1 11240 -1 11241 -1 11242 -1 11243 -1 11244 -1 11245 -1 11246 -1 11247 -1 11248 -1 11249 -1 11250 -1 11251 -1 11252 -1 11253 -1 11254 -1 11255 -1 11256 -1 11257 -1 11258 -1 11259 -1 11260 -1 11261 -1 11262 -1 11263 -1 11264 -1 11265 -1 11266 -1 11267 -1 11268 -1 11269 -1 11270 -1 11271 -1 11272 -1 11273 -1 11274 -1 11275 -1 11276 -1 11277 -1 11278 -1 11279 -1 11280 -1 11281 -1 11282 -1 11283 -1 11284 -1 11285 -1 11286 -1 11287 -1 11288 -1 11289 -1 11290 -1 11291 -1 11292 -1 11293 -1 11294 -1 11295 -1 11296 -1 11297 -1 11298 -1 11299 -1 11300 -1 11301 -1 11302 -1 11303 -1 11304 -1 11305 -1 11306 -1 11307 -1 11308 -1 11309 -1 11310 -1 11311 -1 11312 -1 11313 -1 11314 -1 11315 -1 11316 -1 11317 -1 11318 -1 11319 -1 11320 -1 11321 -1 11322 -1 11323 -1 11324 -1 11325 -1 11326 -1 11327 -1 11328 -1 11329 -1 11330 -1 11331 -1 11332 -1 11333 -1 11334 -1 11335 -1 11336 -1 11337 -1 11338 -1 11339 -1 11340 -1 11341 -1 11342 -1 11343 -1 11344 -1 11345 -1 11346 -1 11347 -1 11348 -1 11349 -1 11350 -1 11351 -1 11352 -1 11353 -1 11354 -1 11355 -1 11356 -1 11357 -1 11358 -1 11359 -1 11360 -1 11361 -1 11362 -1 11363 -1 11364 -1 11365 -1 11366 -1 11367 -1 11368 -1 11369 -1 11370 -1 11371 -1 11372 -1 11373 -1 11374 -1 11375 -1 11376 -1 11377 -1 11378 -1 11379 -1 11380 -1 11381 -1 11382 -1 11383 -1 11384 -1 11385 -1 11386 -1 11387 -1 11388 -1 11389 -1 11390 -1 11391 -1 11392 -1 11393 -1 11394 -1 11395 -1 11396 -1 11397 -1 11398 -1 11399 -1 11400 -1 11401 -1 11402 -1 11403 -1 11404 -1 11405 -1 11406 -1 11407 -1 11408 -1 11409 -1 11410 -1 11411 -1 11412 -1 11413 -1 11414 -1 11415 -1 11416 -1 11417 -1 11418 -1 11419 -1 11420 -1 11421 -1 11422 -1 11423 -1 11424 -1 11425 -1 11426 -1 11427 -1 11428 -1 11429 -1 11430 -1 11431 -1 11432 -1 11433 -1 11434 -1 11435 -1 11436 -1 11437 -1 11438 -1 11439 -1 11440 -1 11441 -1 11442 -1 11443 -1 11444 -1 11445 -1 11446 -1 11447 -1 11448 -1 11449 -1 11450 -1 11451 -1 11452 -1 11453 -1 11454 -1 11455 -1 11456 -1 11457 -1 11458 -1 11459 -1 11460 -1 11461 -1 11462 -1 11463 -1 11464 -1 11465 -1 11466 -1 11467 -1 11468 -1 11469 -1 11470 -1 11471 -1 11472 -1 11473 -1 11474 -1 11475 -1 11476 -1 11477 -1 11478 -1 11479 -1 11480 -1 11481 -1 11482 -1 11483 -1 11484 -1 11485 -1 11486 -1 11487 -1 11488 -1 11489 -1 11490 -1 11491 -1 11492 -1 11493 -1 11494 -1 11495 -1 11496 -1 11497 -1 11498 -1 11499 -1 11500 -1 11501 -1 11502 -1 11503 -1 11504 -1 11505 -1 11506 -1 11507 -1 11508 -1 11509 -1 11510 -1 11511 -1 11512 -1 11513 -1 11514 -1 11515 -1 11516 -1 11517 -1 11518 -1 11519 -1 11520 -1 11521 -1 11522 -1 11523 -1 11524 -1 11525 -1 11526 -1 11527 -1 11528 -1 11529 -1 11530 -1 11531 -1 11532 -1 11533 -1 11534 -1 11535 -1 11536 -1 11537 -1 11538 -1 11539 -1 11540 -1 11541 -1 11542 -1 11543 -1 11544 -1 11545 -1 11546 -1 11547 -1 11548 -1 11549 -1 11550 -1 11551 -1 11552 -1 11553 -1 11554 -1 11555 -1 11556 -1 11557 -1 11558 -1 11559 -1 11560 -1 11561 -1 11562 -1 11563 -1 11564 -1 11565 -1 11566 -1 11567 -1 11568 -1 11569 -1 11570 -1 11571 -1 11572 -1 11573 -1 11574 -1 11575 -1 11576 -1 11577 -1 11578 -1 11579 -1 11580 -1 11581 -1 11582 -1 11583 -1 11584 -1 11585 -1 11586 -1 11587 -1 11588 -1 11589 -1 11590 -1 11591 -1 11592 -1 11593 -1 11594 -1 11595 -1 11596 -1 11597 -1 11598 -1 11599 -1 11600 -1 11601 -1 11602 -1 11603 -1 11604 -1 11605 -1 11606 -1 11607 -1 11608 -1 11609 -1 11610 -1 11611 -1 11612 -1 11613 -1 11614 -1 11615 -1 11616 -1 11617 -1 11618 -1 11619 -1 11620 -1 11621 -1 11622 -1 11623 -1 11624 -1 11625 -1 11626 -1 11627 -1 11628 -1 11629 -1 11630 -1 11631 -1 11632 -1 11633 -1 11634 -1 11635 -1 11636 -1 11637 -1 11638 -1 11639 -1 11640 -1 11641 -1 11642 -1 11643 -1 11644 -1 11645 -1 11646 -1 11647 -1 11648 -1 11649 -1 11650 -1 11651 -1 11652 -1 11653 -1 11654 -1 11655 -1 11656 -1 11657 -1 11658 -1 11659 -1 11660 -1 11661 -1 11662 -1 11663 -1 11664 -1 11665 -1 11666 -1 11667 -1 11668 -1 11669 -1 11670 -1 11671 -1 11672 -1 11673 -1 11674 -1 11675 -1 11676 -1 11677 -1 11678 -1 11679 -1 11680 -1 11681 -1 11682 -1 11683 -1 11684 -1 11685 -1 11686 -1 11687 -1 11688 -1 11689 -1 11690 -1 11691 -1 11692 -1 11693 -1 11694 -1 11695 -1 11696 -1 11697 -1 11698 -1 11699 -1 11700 -1 11701 -1 11702 -1 11703 -1 11704 -1 11705 -1 11706 -1 11707 -1 11708 -1 11709 -1 11710 -1 11711 -1 11712 -1 11713 -1 11714 -1 11715 -1 11716 -1 11717 -1 11718 -1 11719 -1 11720 -1 11721 -1 11722 -1 11723 -1 11724 -1 11725 -1 11726 -1 11727 -1 11728 -1 11729 -1 11730 -1 11731 -1 11732 -1 11733 -1 11734 -1 11735 -1 11736 -1 11737 -1 11738 -1 11739 -1 11740 -1 11741 -1 11742 -1 11743 -1 11744 -1 11745 -1 11746 -1 11747 -1 11748 -1 11749 -1 11750 -1 11751 -1 11752 -1 11753 -1 11754 -1 11755 -1 11756 -1 11757 -1 11758 -1 11759 -1 11760 -1 11761 -1 11762 -1 11763 -1 11764 -1 11765 -1 11766 -1 11767 -1 11768 -1 11769 -1 11770 -1 11771 -1 11772 -1 11773 -1 11774 -1 11775 -1 11776 -1 11777 -1 11778 -1 11779 -1 11780 -1 11781 -1 11782 -1 11783 -1 11784 -1 11785 -1 11786 -1 11787 -1 11788 -1 11789 -1 11790 -1 11791 -1 11792 -1 11793 -1 11794 -1 11795 -1 11796 -1 11797 -1 11798 -1 11799 -1 11800 -1 11801 -1 11802 -1 11803 -1 11804 -1 11805 -1 11806 -1 11807 -1 11808 -1 11809 -1 11810 -1 11811 -1 11812 -1 11813 -1 11814 -1 11815 -1 11816 -1 11817 -1 11818 -1 11819 -1 11820 -1 11821 -1 11822 -1 11823 -1 11824 -1 11825 -1 11826 -1 11827 -1 11828 -1 11829 -1 11830 -1 11831 -1 11832 -1 11833 -1 11834 -1 11835 -1 11836 -1 11837 -1 11838 -1 11839 -1 11840 -1 11841 -1 11842 -1 11843 -1 11844 -1 11845 -1 11846 -1 11847 -1 11848 -1 11849 -1 11850 -1 11851 -1 11852 -1 11853 -1 11854 -1 11855 -1 11856 -1 11857 -1 11858 -1 11859 -1 11860 -1 11861 -1 11862 -1 11863 -1 11864 -1 11865 -1 11866 -1 11867 -1 11868 -1 11869 -1 11870 -1 11871 -1 11872 -1 11873 -1 11874 -1 11875 -1 11876 -1 11877 -1 11878 -1 11879 -1 11880 -1 11881 -1 11882 -1 11883 -1 11884 -1 11885 -1 11886 -1 11887 -1 11888 -1 11889 -1 11890 -1 11891 -1 11892 -1 11893 -1 11894 -1 11895 -1 11896 -1 11897 -1 11898 -1 11899 -1 11900 -1 11901 -1 11902 -1 11903 -1 11904 -1 11905 -1 11906 -1 11907 -1 11908 -1 11909 -1 11910 -1 11911 -1 11912 -1 11913 -1 11914 -1 11915 -1 11916 -1 11917 -1 11918 -1 11919 -1 11920 -1 11921 -1 11922 -1 11923 -1 11924 -1 11925 -1 11926 -1 11927 -1 11928 -1 11929 -1 11930 -1 11931 -1 11932 -1 11933 -1 11934 -1 11935 -1 11936 -1 11937 -1 11938 -1 11939 -1 11940 -1 11941 -1 11942 -1 11943 -1 11944 -1 11945 -1 11946 -1 11947 -1 11948 -1 11949 -1 11950 -1 11951 -1 11952 -1 11953 -1 11954 -1 11955 -1 11956 -1 11957 -1 11958 -1 11959 -1 11960 -1 11961 -1 11962 -1 11963 -1 11964 -1 11965 -1 11966 -1 11967 -1 11968 -1 11969 -1 11970 -1 11971 -1 11972 -1 11973 -1 11974 -1 11975 -1 11976 -1 11977 -1 11978 -1 11979 -1 11980 -1 11981 -1 11982 -1 11983 -1 11984 -1 11985 -1 11986 -1 11987 -1 11988 -1 11989 -1 11990 -1 11991 -1 11992 -1 11993 -1 11994 -1 11995 -1 11996 -1 11997 -1 11998 -1 11999 -1 12000 -1 12001 -1 12002 -1 12003 -1 12004 -1 12005 -1 12006 -1 12007 -1 12008 -1 12009 -1 12010 -1 12011 -1 12012 -1 12013 -1 12014 -1 12015 -1 12016 -1 12017 -1 12018 -1 12019 -1 12020 -1 12021 -1 12022 -1 12023 -1 12024 -1 12025 -1 12026 -1 12027 -1 12028 -1 12029 -1 12030 -1 12031 -1 12032 -1 12033 -1 12034 -1 12035 -1 12036 -1 12037 -1 12038 -1 12039 -1 12040 -1 12041 -1 12042 -1 12043 -1 12044 -1 12045 -1 12046 -1 12047 -1 12048 -1 12049 -1 12050 -1 12051 -1 12052 -1 12053 -1 12054 -1 12055 -1 12056 -1 12057 -1 12058 -1 12059 -1 12060 -1 12061 -1 12062 -1 12063 -1 12064 -1 12065 -1 12066 -1 12067 -1 12068 -1 12069 -1 12070 -1 12071 -1 12072 -1 12073 -1 12074 -1 12075 -1 12076 -1 12077 -1 12078 -1 12079 -1 12080 -1 12081 -1 12082 -1 12083 -1 12084 -1 12085 -1 12086 -1 12087 -1 12088 -1 12089 -1 12090 -1 12091 -1 12092 -1 12093 -1 12094 -1 12095 -1 12096 -1 12097 -1 12098 -1 12099 -1 12100 -1 12101 -1 12102 -1 12103 -1 12104 -1 12105 -1 12106 -1 12107 -1 12108 -1 12109 -1 12110 -1 12111 -1 12112 -1 12113 -1 12114 -1 12115 -1 12116 -1 12117 -1 12118 -1 12119 -1 12120 -1 12121 -1 12122 -1 12123 -1 12124 -1 12125 -1 12126 -1 12127 -1 12128 -1 12129 -1 12130 -1 12131 -1 12132 -1 12133 -1 12134 -1 12135 -1 12136 -1 12137 -1 12138 -1 12139 -1 12140 -1 12141 -1 12142 -1 12143 -1 12144 -1 12145 -1 12146 -1 12147 -1 12148 -1 12149 -1 12150 -1 12151 -1 12152 -1 12153 -1 12154 -1 12155 -1 12156 -1 12157 -1 12158 -1 12159 -1 12160 -1 12161 -1 12162 -1 12163 -1 12164 -1 12165 -1 12166 -1 12167 -1 12168 -1 12169 -1 12170 -1 12171 -1 12172 -1 12173 -1 12174 -1 12175 -1 12176 -1 12177 -1 12178 -1 12179 -1 12180 -1 12181 -1 12182 -1 12183 -1 12184 -1 12185 -1 12186 -1 12187 -1 12188 -1 12189 -1 12190 -1 12191 -1 12192 -1 12193 -1 12194 -1 12195 -1 12196 -1 12197 -1 12198 -1 12199 -1 12200 -1 12201 -1 12202 -1 12203 -1 12204 -1 12205 -1 12206 -1 12207 -1 12208 -1 12209 -1 12210 -1 12211 -1 12212 -1 12213 -1 12214 -1 12215 -1 12216 -1 12217 -1 12218 -1 12219 -1 12220 -1 12221 -1 12222 -1 12223 -1 12224 -1 12225 -1 12226 -1 12227 -1 12228 -1 12229 -1 12230 -1 12231 -1 12232 -1 12233 -1 12234 -1 12235 -1 12236 -1 12237 -1 12238 -1 12239 -1 12240 -1 12241 -1 12242 -1 12243 -1 12244 -1 12245 -1 12246 -1 12247 -1 12248 -1 12249 -1 12250 -1 12251 -1 12252 -1 12253 -1 12254 -1 12255 -1 12256 -1 12257 -1 12258 -1 12259 -1 12260 -1 12261 -1 12262 -1 12263 -1 12264 -1 12265 -1 12266 -1 12267 -1 12268 -1 12269 -1 12270 -1 12271 -1 12272 -1 12273 -1 12274 -1 12275 -1 12276 -1 12277 -1 12278 -1 12279 -1 12280 -1 12281 -1 12282 -1 12283 -1 12284 -1 12285 -1 12286 -1 12287 -1 12288 -1 12289 -1 12290 -1 12291 -1 12292 -1 12293 -1 12294 -1 12295 -1 12296 -1 12297 -1 12298 -1 12299 -1 12300 -1 12301 -1 12302 -1 12303 -1 12304 -1 12305 -1 12306 -1 12307 -1 12308 -1 12309 -1 12310 -1 12311 -1 12312 -1 12313 -1 12314 -1 12315 -1 12316 -1 12317 -1 12318 -1 12319 -1 12320 -1 12321 -1 12322 -1 12323 -1 12324 -1 12325 -1 12326 -1 12327 -1 12328 -1 12329 -1 12330 -1 12331 -1 12332 -1 12333 -1 12334 -1 12335 -1 12336 -1 12337 -1 12338 -1 12339 -1 12340 -1 12341 -1 12342 -1 12343 -1 12344 -1 12345 -1 12346 -1 12347 -1 12348 -1 12349 -1 12350 -1 12351 -1 12352 -1 12353 -1 12354 -1 12355 -1 12356 -1 12357 -1 12358 -1 12359 -1 12360 -1 12361 -1 12362 -1 12363 -1 12364 -1 12365 -1 12366 -1 12367 -1 12368 -1 12369 -1 12370 -1 12371 -1 12372 -1 12373 -1 12374 -1 12375 -1 12376 -1 12377 -1 12378 -1 12379 -1 12380 -1 12381 -1 12382 -1 12383 -1 12384 -1 12385 -1 12386 -1 12387 -1 12388 -1 12389 -1 12390 -1 12391 -1 12392 -1 12393 -1 12394 -1 12395 -1 12396 -1 12397 -1 12398 -1 12399 -1 12400 -1 12401 -1 12402 -1 12403 -1 12404 -1 12405 -1 12406 -1 12407 -1 12408 -1 12409 -1 12410 -1 12411 -1 12412 -1 12413 -1 12414 -1 12415 -1 12416 -1 12417 -1 12418 -1 12419 -1 12420 -1 12421 -1 12422 -1 12423 -1 12424 -1 12425 -1 12426 -1 12427 -1 12428 -1 12429 -1 12430 -1 12431 -1 12432 -1 12433 -1 12434 -1 12435 -1 12436 -1 12437 -1 12438 -1 12439 -1 12440 -1 12441 -1 12442 -1 12443 -1 12444 -1 12445 -1 12446 -1 12447 -1 12448 -1 12449 -1 12450 -1 12451 -1 12452 -1 12453 -1 12454 -1 12455 -1 12456 -1 12457 -1 12458 -1 12459 -1 12460 -1 12461 -1 12462 -1 12463 -1 12464 -1 12465 -1 12466 -1 12467 -1 12468 -1 12469 -1 12470 -1 12471 -1 12472 -1 12473 -1 12474 -1 12475 -1 12476 -1 12477 -1 12478 -1 12479 -1 12480 -1 12481 -1 12482 -1 12483 -1 12484 -1 12485 -1 12486 -1 12487 -1 12488 -1 12489 -1 12490 -1 12491 -1 12492 -1 12493 -1 12494 -1 12495 -1 12496 -1 12497 -1 12498 -1 12499 -1 12500 -1 12501 -1 12502 -1 12503 -1 12504 -1 12505 -1 12506 -1 12507 -1 12508 -1 12509 -1 12510 -1 12511 -1 12512 -1 12513 -1 12514 -1 12515 -1 12516 -1 12517 -1 12518 -1 12519 -1 12520 -1 12521 -1 12522 -1 12523 -1 12524 -1 12525 -1 12526 -1 12527 -1 12528 -1 12529 -1 12530 -1 12531 -1 12532 -1 12533 -1 12534 -1 12535 -1 12536 -1 12537 -1 12538 -1 12539 -1 12540 -1 12541 -1 12542 -1 12543 -1 12544 -1 12545 -1 12546 -1 12547 -1 12548 -1 12549 -1 12550 -1 12551 -1 12552 -1 12553 -1 12554 -1 12555 -1 12556 -1 12557 -1 12558 -1 12559 -1 12560 -1 12561 -1 12562 -1 12563 -1 12564 -1 12565 -1 12566 -1 12567 -1 12568 -1 12569 -1 12570 -1 12571 -1 12572 -1 12573 -1 12574 -1 12575 -1 12576 -1 12577 -1 12578 -1 12579 -1 12580 -1 12581 -1 12582 -1 12583 -1 12584 -1 12585 -1 12586 -1 12587 -1 12588 -1 12589 -1 12590 -1 12591 -1 12592 -1 12593 -1 12594 -1 12595 -1 12596 -1 12597 -1 12598 -1 12599 -1 12600 -1 12601 -1 12602 -1 12603 -1 12604 -1 12605 -1 12606 -1 12607 -1 12608 -1 12609 -1 12610 -1 12611 -1 12612 -1 12613 -1 12614 -1 12615 -1 12616 -1 12617 -1 12618 -1 12619 -1 12620 -1 12621 -1 12622 -1 12623 -1 12624 -1 12625 -1 12626 -1 12627 -1 12628 -1 12629 -1 12630 -1 12631 -1 12632 -1 12633 -1 12634 -1 12635 -1 12636 -1 12637 -1 12638 -1 12639 -1 12640 -1 12641 -1 12642 -1 12643 -1 12644 -1 12645 -1 12646 -1 12647 -1 12648 -1 12649 -1 12650 -1 12651 -1 12652 -1 12653 -1 12654 -1 12655 -1 12656 -1 12657 -1 12658 -1 12659 -1 12660 -1 12661 -1 12662 -1 12663 -1 12664 -1 12665 -1 12666 -1 12667 -1 12668 -1 12669 -1 12670 -1 12671 -1 12672 -1 12673 -1 12674 -1 12675 -1 12676 -1 12677 -1 12678 -1 12679 -1 12680 -1 12681 -1 12682 -1 12683 -1 12684 -1 12685 -1 12686 -1 12687 -1 12688 -1 12689 -1 12690 -1 12691 -1 12692 -1 12693 -1 12694 -1 12695 -1 12696 -1 12697 -1 12698 -1 12699 -1 12700 -1 12701 -1 12702 -1 12703 -1 12704 -1 12705 -1 12706 -1 12707 -1 12708 -1 12709 -1 12710 -1 12711 -1 12712 -1 12713 -1 12714 -1 12715 -1 12716 -1 12717 -1 12718 -1 12719 -1 12720 -1 12721 -1 12722 -1 12723 -1 12724 -1 12725 -1 12726 -1 12727 -1 12728 -1 12729 -1 12730 -1 12731 -1 12732 -1 12733 -1 12734 -1 12735 -1 12736 -1 12737 -1 12738 -1 12739 -1 12740 -1 12741 -1 12742 -1 12743 -1 12744 -1 12745 -1 12746 -1 12747 -1 12748 -1 12749 -1 12750 -1 12751 -1 12752 -1 12753 -1 12754 -1 12755 -1 12756 -1 12757 -1 12758 -1 12759 -1 12760 -1 12761 -1 12762 -1 12763 -1 12764 -1 12765 -1 12766 -1 12767 -1 12768 -1 12769 -1 12770 -1 12771 -1 12772 -1 12773 -1 12774 -1 12775 -1 12776 -1 12777 -1 12778 -1 12779 -1 12780 -1 12781 -1 12782 -1 12783 -1 12784 -1 12785 -1 12786 -1 12787 -1 12788 -1 12789 -1 12790 -1 12791 -1 12792 -1 12793 -1 12794 -1 12795 -1 12796 -1 12797 -1 12798 -1 12799 -1 12800 -1 12801 -1 12802 -1 12803 -1 12804 -1 12805 -1 12806 -1 12807 -1 12808 -1 12809 -1 12810 -1 12811 -1 12812 -1 12813 -1 12814 -1 12815 -1 12816 -1 12817 -1 12818 -1 12819 -1 12820 -1 12821 -1 12822 -1 12823 -1 12824 -1 12825 -1 12826 -1 12827 -1 12828 -1 12829 -1 12830 -1 12831 -1 12832 -1 12833 -1 12834 -1 12835 -1 12836 -1 12837 -1 12838 -1 12839 -1 12840 -1 12841 -1 12842 -1 12843 -1 12844 -1 12845 -1 12846 -1 12847 -1 12848 -1 12849 -1 12850 -1 12851 -1 12852 -1 12853 -1 12854 -1 12855 -1 12856 -1 12857 -1 12858 -1 12859 -1 12860 -1 12861 -1 12862 -1 12863 -1 12864 -1 12865 -1 12866 -1 12867 -1 12868 -1 12869 -1 12870 -1 12871 -1 12872 -1 12873 -1 12874 -1 12875 -1 12876 -1 12877 -1 12878 -1 12879 -1 12880 -1 12881 -1 12882 -1 12883 -1 12884 -1 12885 -1 12886 -1 12887 -1 12888 -1 12889 -1 12890 -1 12891 -1 12892 -1 12893 -1 12894 -1 12895 -1 12896 -1 12897 -1 12898 -1 12899 -1 12900 -1 12901 -1 12902 -1 12903 -1 12904 -1 12905 -1 12906 -1 12907 -1 12908 -1 12909 -1 12910 -1 12911 -1 12912 -1 12913 -1 12914 -1 12915 -1 12916 -1 12917 -1 12918 -1 12919 -1 12920 -1 12921 -1 12922 -1 12923 -1 12924 -1 12925 -1 12926 -1 12927 -1 12928 -1 12929 -1 12930 -1 12931 -1 12932 -1 12933 -1 12934 -1 12935 -1 12936 -1 12937 -1 12938 -1 12939 -1 12940 -1 12941 -1 12942 -1 12943 -1 12944 -1 12945 -1 12946 -1 12947 -1 12948 -1 12949 -1 12950 -1 12951 -1 12952 -1 12953 -1 12954 -1 12955 -1 12956 -1 12957 -1 12958 -1 12959 -1 12960 -1 12961 -1 12962 -1 12963 -1 12964 -1 12965 -1 12966 -1 12967 -1 12968 -1 12969 -1 12970 -1 12971 -1 12972 -1 12973 -1 12974 -1 12975 -1 12976 -1 12977 -1 12978 -1 12979 -1 12980 -1 12981 -1 12982 -1 12983 -1 12984 -1 12985 -1 12986 -1 12987 -1 12988 -1 12989 -1 12990 -1 12991 -1 12992 -1 12993 -1 12994 -1 12995 -1 12996 -1 12997 -1 12998 -1 12999 -1 13000 -1 13001 -1 13002 -1 13003 -1 13004 -1 13005 -1 13006 -1 13007 -1 13008 -1 13009 -1 13010 -1 13011 -1 13012 -1 13013 -1 13014 -1 13015 -1 13016 -1 13017 -1 13018 -1 13019 -1 13020 -1 13021 -1 13022 -1 13023 -1 13024 -1 13025 -1 13026 -1 13027 -1 13028 -1 13029 -1 13030 -1 13031 -1 13032 -1 13033 -1 13034 -1 13035 -1 13036 -1 13037 -1 13038 -1 13039 -1 13040 -1 13041 -1 13042 -1 13043 -1 13044 -1 13045 -1 13046 -1 13047 -1 13048 -1 13049 -1 13050 -1 13051 -1 13052 -1 13053 -1 13054 -1 13055 -1 13056 -1 13057 -1 13058 -1 13059 -1 13060 -1 13061 -1 13062 -1 13063 -1 13064 -1 13065 -1 13066 -1 13067 -1 13068 -1 13069 -1 13070 -1 13071 -1 13072 -1 13073 -1 13074 -1 13075 -1 13076 -1 13077 -1 13078 -1 13079 -1 13080 -1 13081 -1 13082 -1 13083 -1 13084 -1 13085 -1 13086 -1 13087 -1 13088 -1 13089 -1 13090 -1 13091 -1 13092 -1 13093 -1 13094 -1 13095 -1 13096 -1 13097 -1 13098 -1 13099 -1 13100 -1 13101 -1 13102 -1 13103 -1 13104 -1 13105 -1 13106 -1 13107 -1 13108 -1 13109 -1 13110 -1 13111 -1 13112 -1 13113 -1 13114 -1 13115 -1 13116 -1 13117 -1 13118 -1 13119 -1 13120 -1 13121 -1 13122 -1 13123 -1 13124 -1 13125 -1 13126 -1 13127 -1 13128 -1 13129 -1 13130 -1 13131 -1 13132 -1 13133 -1 13134 -1 13135 -1 13136 -1 13137 -1 13138 -1 13139 -1 13140 -1 13141 -1 13142 -1 13143 -1 13144 -1 13145 -1 13146 -1 13147 -1 13148 -1 13149 -1 13150 -1 13151 -1 13152 -1 13153 -1 13154 -1 13155 -1 13156 -1 13157 -1 13158 -1 13159 -1 13160 -1 13161 -1 13162 -1 13163 -1 13164 -1 13165 -1 13166 -1 13167 -1 13168 -1 13169 -1 13170 -1 13171 -1 13172 -1 13173 -1 13174 -1 13175 -1 13176 -1 13177 -1 13178 -1 13179 -1 13180 -1 13181 -1 13182 -1 13183 -1 13184 -1 13185 -1 13186 -1 13187 -1 13188 -1 13189 -1 13190 -1 13191 -1 13192 -1 13193 -1 13194 -1 13195 -1 13196 -1 13197 -1 13198 -1 13199 -1 13200 -1 13201 -1 13202 -1 13203 -1 13204 -1 13205 -1 13206 -1 13207 -1 13208 -1 13209 -1 13210 -1 13211 -1 13212 -1 13213 -1 13214 -1 13215 -1 13216 -1 13217 -1 13218 -1 13219 -1 13220 -1 13221 -1 13222 -1 13223 -1 13224 -1 13225 -1 13226 -1 13227 -1 13228 -1 13229 -1 13230 -1 13231 -1 13232 -1 13233 -1 13234 -1 13235 -1 13236 -1 13237 -1 13238 -1 13239 -1 13240 -1 13241 -1 13242 -1 13243 -1 13244 -1 13245 -1 13246 -1 13247 -1 13248 -1 13249 -1 13250 -1 13251 -1 13252 -1 13253 -1 13254 -1 13255 -1 13256 -1 13257 -1 13258 -1 13259 -1 13260 -1 13261 -1 13262 -1 13263 -1 13264 -1 13265 -1 13266 -1 13267 -1 13268 -1 13269 -1 13270 -1 13271 -1 13272 -1 13273 -1 13274 -1 13275 -1 13276 -1 13277 -1 13278 -1 13279 -1 13280 -1 13281 -1 13282 -1 13283 -1 13284 -1 13285 -1 13286 -1 13287 -1 13288 -1 13289 -1 13290 -1 13291 -1 13292 -1 13293 -1 13294 -1 13295 -1 13296 -1 13297 -1 13298 -1 13299 -1 13300 -1 13301 -1 13302 -1 13303 -1 13304 -1 13305 -1 13306 -1 13307 -1 13308 -1 13309 -1 13310 -1 13311 -1 13312 -1 13313 -1 13314 -1 13315 -1 13316 -1 13317 -1 13318 -1 13319 -1 13320 -1 13321 -1 13322 -1 13323 -1 13324 -1 13325 -1 13326 -1 13327 -1 13328 -1 13329 -1 13330 -1 13331 -1 13332 -1 13333 -1 13334 -1 13335 -1 13336 -1 13337 -1 13338 -1 13339 -1 13340 -1 13341 -1 13342 -1 13343 -1 13344 -1 13345 -1 13346 -1 13347 -1 13348 -1 13349 -1 13350 -1 13351 -1 13352 -1 13353 -1 13354 -1 13355 -1 13356 -1 13357 -1 13358 -1 13359 -1 13360 -1 13361 -1 13362 -1 13363 -1 13364 -1 13365 -1 13366 -1 13367 -1 13368 -1 13369 -1 13370 -1 13371 -1 13372 -1 13373 -1 13374 -1 13375 -1 13376 -1 13377 -1 13378 -1 13379 -1 13380 -1 13381 -1 13382 -1 13383 -1 13384 -1 13385 -1 13386 -1 13387 -1 13388 -1 13389 -1 13390 -1 13391 -1 13392 -1 13393 -1 13394 -1 13395 -1 13396 -1 13397 -1 13398 -1 13399 -1 13400 -1 13401 -1 13402 -1 13403 -1 13404 -1 13405 -1 13406 -1 13407 -1 13408 -1 13409 -1 13410 -1 13411 -1 13412 -1 13413 -1 13414 -1 13415 -1 13416 -1 13417 -1 13418 -1 13419 -1 13420 -1 13421 -1 13422 -1 13423 -1 13424 -1 13425 -1 13426 -1 13427 -1 13428 -1 13429 -1 13430 -1 13431 -1 13432 -1 13433 -1 13434 -1 13435 -1 13436 -1 13437 -1 13438 -1 13439 -1 13440 -1 13441 -1 13442 -1 13443 -1 13444 -1 13445 -1 13446 -1 13447 -1 13448 -1 13449 -1 13450 -1 13451 -1 13452 -1 13453 -1 13454 -1 13455 -1 13456 -1 13457 -1 13458 -1 13459 -1 13460 -1 13461 -1 13462 -1 13463 -1 13464 -1 13465 -1 13466 -1 13467 -1 13468 -1 13469 -1 13470 -1 13471 -1 13472 -1 13473 -1 13474 -1 13475 -1 13476 -1 13477 -1 13478 -1 13479 -1 13480 -1 13481 -1 13482 -1 13483 -1 13484 -1 13485 -1 13486 -1 13487 -1 13488 -1 13489 -1 13490 -1 13491 -1 13492 -1 13493 -1 13494 -1 13495 -1 13496 -1 13497 -1 13498 -1 13499 -1 13500 -1 13501 -1 13502 -1 13503 -1 13504 -1 13505 -1 13506 -1 13507 -1 13508 -1 13509 -1 13510 -1 13511 -1 13512 -1 13513 -1 13514 -1 13515 -1 13516 -1 13517 -1 13518 -1 13519 -1 13520 -1 13521 -1 13522 -1 13523 -1 13524 -1 13525 -1 13526 -1 13527 -1 13528 -1 13529 -1 13530 -1 13531 -1 13532 -1 13533 -1 13534 -1 13535 -1 13536 -1 13537 -1 13538 -1 13539 -1 13540 -1 13541 -1 13542 -1 13543 -1 13544 -1 13545 -1 13546 -1 13547 -1 13548 -1 13549 -1 13550 -1 13551 -1 13552 -1 13553 -1 13554 -1 13555 -1 13556 -1 13557 -1 13558 -1 13559 -1 13560 -1 13561 -1 13562 -1 13563 -1 13564 -1 13565 -1 13566 -1 13567 -1 13568 -1 13569 -1 13570 -1 13571 -1 13572 -1 13573 -1 13574 -1 13575 -1 13576 -1 13577 -1 13578 -1 13579 -1 13580 -1 13581 -1 13582 -1 13583 -1 13584 -1 13585 -1 13586 -1 13587 -1 13588 -1 13589 -1 13590 -1 13591 -1 13592 -1 13593 -1 13594 -1 13595 -1 13596 -1 13597 -1 13598 -1 13599 -1 13600 -1 13601 -1 13602 -1 13603 -1 13604 -1 13605 -1 13606 -1 13607 -1 13608 -1 13609 -1 13610 -1 13611 -1 13612 -1 13613 -1 13614 -1 13615 -1 13616 -1 13617 -1 13618 -1 13619 -1 13620 -1 13621 -1 13622 -1 13623 -1 13624 -1 13625 -1 13626 -1 13627 -1 13628 -1 13629 -1 13630 -1 13631 -1 13632 -1 13633 -1 13634 -1 13635 -1 13636 -1 13637 -1 13638 -1 13639 -1 13640 -1 13641 -1 13642 -1 13643 -1 13644 -1 13645 -1 13646 -1 13647 -1 13648 -1 13649 -1 13650 -1 13651 -1 13652 -1 13653 -1 13654 -1 13655 -1 13656 -1 13657 -1 13658 -1 13659 -1 13660 -1 13661 -1 13662 -1 13663 -1 13664 -1 13665 -1 13666 -1 13667 -1 13668 -1 13669 -1 13670 -1 13671 -1 13672 -1 13673 -1 13674 -1 13675 -1 13676 -1 13677 -1 13678 -1 13679 -1 13680 -1 13681 -1 13682 -1 13683 -1 13684 -1 13685 -1 13686 -1 13687 -1 13688 -1 13689 -1 13690 -1 13691 -1 13692 -1 13693 -1 13694 -1 13695 -1 13696 -1 13697 -1 13698 -1 13699 -1 13700 -1 13701 -1 13702 -1 13703 -1 13704 -1 13705 -1 13706 -1 13707 -1 13708 -1 13709 -1 13710 -1 13711 -1 13712 -1 13713 -1 13714 -1 13715 -1 13716 -1 13717 -1 13718 -1 13719 -1 13720 -1 13721 -1 13722 -1 13723 -1 13724 -1 13725 -1 13726 -1 13727 -1 13728 -1 13729 -1 13730 -1 13731 -1 13732 -1 13733 -1 13734 -1 13735 -1 13736 -1 13737 -1 13738 -1 13739 -1 13740 -1 13741 -1 13742 -1 13743 -1 13744 -1 13745 -1 13746 -1 13747 -1 13748 -1 13749 -1 13750 -1 13751 -1 13752 -1 13753 -1 13754 -1 13755 -1 13756 -1 13757 -1 13758 -1 13759 -1 13760 -1 13761 -1 13762 -1 13763 -1 13764 -1 13765 -1 13766 -1 13767 -1 13768 -1 13769 -1 13770 -1 13771 -1 13772 -1 13773 -1 13774 -1 13775 -1 13776 -1 13777 -1 13778 -1 13779 -1 13780 -1 13781 -1 13782 -1 13783 -1 13784 -1 13785 -1 13786 -1 13787 -1 13788 -1 13789 -1 13790 -1 13791 -1 13792 -1 13793 -1 13794 -1 13795 -1 13796 -1 13797 -1 13798 -1 13799 -1 13800 -1 13801 -1 13802 -1 13803 -1 13804 -1 13805 -1 13806 -1 13807 -1 13808 -1 13809 -1 13810 -1 13811 -1 13812 -1 13813 -1 13814 -1 13815 -1 13816 -1 13817 -1 13818 -1 13819 -1 13820 -1 13821 -1 13822 -1 13823 -1 13824 -1 13825 -1 13826 -1 13827 -1 13828 -1 13829 -1 13830 -1 13831 -1 13832 -1 13833 -1 13834 -1 13835 -1 13836 -1 13837 -1 13838 -1 13839 -1 13840 -1 13841 -1 13842 -1 13843 -1 13844 -1 13845 -1 13846 -1 13847 -1 13848 -1 13849 -1 13850 -1 13851 -1 13852 -1 13853 -1 13854 -1 13855 -1 13856 -1 13857 -1 13858 -1 13859 -1 13860 -1 13861 -1 13862 -1 13863 -1 13864 -1 13865 -1 13866 -1 13867 -1 13868 -1 13869 -1 13870 -1 13871 -1 13872 -1 13873 -1 13874 -1 13875 -1 13876 -1 13877 -1 13878 -1 13879 -1 13880 -1 13881 -1 13882 -1 13883 -1 13884 -1 13885 -1 13886 -1 13887 -1 13888 -1 13889 -1 13890 -1 13891 -1 13892 -1 13893 -1 13894 -1 13895 -1 13896 -1 13897 -1 13898 -1 13899 -1 13900 -1 13901 -1 13902 -1 13903 -1 13904 -1 13905 -1 13906 -1 13907 -1 13908 -1 13909 -1 13910 -1 13911 -1 13912 -1 13913 -1 13914 -1 13915 -1 13916 -1 13917 -1 13918 -1 13919 -1 13920 -1 13921 -1 13922 -1 13923 -1 13924 -1 13925 -1 13926 -1 13927 -1 13928 -1 13929 -1 13930 -1 13931 -1 13932 -1 13933 -1 13934 -1 13935 -1 13936 -1 13937 -1 13938 -1 13939 -1 13940 -1 13941 -1 13942 -1 13943 -1 13944 -1 13945 -1 13946 -1 13947 -1 13948 -1 13949 -1 13950 -1 13951 -1 13952 -1 13953 -1 13954 -1 13955 -1 13956 -1 13957 -1 13958 -1 13959 -1 13960 -1 13961 -1 13962 -1 13963 -1 13964 -1 13965 -1 13966 -1 13967 -1 13968 -1 13969 -1 13970 -1 13971 -1 13972 -1 13973 -1 13974 -1 13975 -1 13976 -1 13977 -1 13978 -1 13979 -1 13980 -1 13981 -1 13982 -1 13983 -1 13984 -1 13985 -1 13986 -1 13987 -1 13988 -1 13989 -1 13990 -1 13991 -1 13992 -1 13993 -1 13994 -1 13995 -1 13996 -1 13997 -1 13998 -1 13999 -1 14000 -1 14001 -1 14002 -1 14003 -1 14004 -1 14005 -1 14006 -1 14007 -1 14008 -1 14009 -1 14010 -1 14011 -1 14012 -1 14013 -1 14014 -1 14015 -1 14016 -1 14017 -1 14018 -1 14019 -1 14020 -1 14021 -1 14022 -1 14023 -1 14024 -1 14025 -1 14026 -1 14027 -1 14028 -1 14029 -1 14030 -1 14031 -1 14032 -1 14033 -1 14034 -1 14035 -1 14036 -1 14037 -1 14038 -1 14039 -1 14040 -1 14041 -1 14042 -1 14043 -1 14044 -1 14045 -1 14046 -1 14047 -1 14048 -1 14049 -1 14050 -1 14051 -1 14052 -1 14053 -1 14054 -1 14055 -1 14056 -1 14057 -1 14058 -1 14059 -1 14060 -1 14061 -1 14062 -1 14063 -1 14064 -1 14065 -1 14066 -1 14067 -1 14068 -1 14069 -1 14070 -1 14071 -1 14072 -1 14073 -1 14074 -1 14075 -1 14076 -1 14077 -1 14078 -1 14079 -1 14080 -1 14081 -1 14082 -1 14083 -1 14084 -1 14085 -1 14086 -1 14087 -1 14088 -1 14089 -1 14090 -1 14091 -1 14092 -1 14093 -1 14094 -1 14095 -1 14096 -1 14097 -1 14098 -1 14099 -1 14100 -1 14101 -1 14102 -1 14103 -1 14104 -1 14105 -1 14106 -1 14107 -1 14108 -1 14109 -1 14110 -1 14111 -1 14112 -1 14113 -1 14114 -1 14115 -1 14116 -1 14117 -1 14118 -1 14119 -1 14120 -1 14121 -1 14122 -1 14123 -1 14124 -1 14125 -1 14126 -1 14127 -1 14128 -1 14129 -1 14130 -1 14131 -1 14132 -1 14133 -1 14134 -1 14135 -1 14136 -1 14137 -1 14138 -1 14139 -1 14140 -1 14141 -1 14142 -1 14143 -1 14144 -1 14145 -1 14146 -1 14147 -1 14148 -1 14149 -1 14150 -1 14151 -1 14152 -1 14153 -1 14154 -1 14155 -1 14156 -1 14157 -1 14158 -1 14159 -1 14160 -1 14161 -1 14162 -1 14163 -1 14164 -1 14165 -1 14166 -1 14167 -1 14168 -1 14169 -1 14170 -1 14171 -1 14172 -1 14173 -1 14174 -1 14175 -1 14176 -1 14177 -1 14178 -1 14179 -1 14180 -1 14181 -1 14182 -1 14183 -1 14184 -1 14185 -1 14186 -1 14187 -1 14188 -1 14189 -1 14190 -1 14191 -1 14192 -1 14193 -1 14194 -1 14195 -1 14196 -1 14197 -1 14198 -1 14199 -1 14200 -1 14201 -1 14202 -1 14203 -1 14204 -1 14205 -1 14206 -1 14207 -1 14208 -1 14209 -1 14210 -1 14211 -1 14212 -1 14213 -1 14214 -1 14215 -1 14216 -1 14217 -1 14218 -1 14219 -1 14220 -1 14221 -1 14222 -1 14223 -1 14224 -1 14225 -1 14226 -1 14227 -1 14228 -1 14229 -1 14230 -1 14231 -1 14232 -1 14233 -1 14234 -1 14235 -1 14236 -1 14237 -1 14238 -1 14239 -1 14240 -1 14241 -1 14242 -1 14243 -1 14244 -1 14245 -1 14246 -1 14247 -1 14248 -1 14249 -1 14250 -1 14251 -1 14252 -1 14253 -1 14254 -1 14255 -1 14256 -1 14257 -1 14258 -1 14259 -1 14260 -1 14261 -1 14262 -1 14263 -1 14264 -1 14265 -1 14266 -1 14267 -1 14268 -1 14269 -1 14270 -1 14271 -1 14272 -1 14273 -1 14274 -1 14275 -1 14276 -1 14277 -1 14278 -1 14279 -1 14280 -1 14281 -1 14282 -1 14283 -1 14284 -1 14285 -1 14286 -1 14287 -1 14288 -1 14289 -1 14290 -1 14291 -1 14292 -1 14293 -1 14294 -1 14295 -1 14296 -1 14297 -1 14298 -1 14299 -1 14300 -1 14301 -1 14302 -1 14303 -1 14304 -1 14305 -1 14306 -1 14307 -1 14308 -1 14309 -1 14310 -1 14311 -1 14312 -1 14313 -1 14314 -1 14315 -1 14316 -1 14317 -1 14318 -1 14319 -1 14320 -1 14321 -1 14322 -1 14323 -1 14324 -1 14325 -1 14326 -1 14327 -1 14328 -1 14329 -1 14330 -1 14331 -1 14332 -1 14333 -1 14334 -1 14335 -1 14336 -1 14337 -1 14338 -1 14339 -1 14340 -1 14341 -1 14342 -1 14343 -1 14344 -1 14345 -1 14346 -1 14347 -1 14348 -1 14349 -1 14350 -1 14351 -1 14352 -1 14353 -1 14354 -1 14355 -1 14356 -1 14357 -1 14358 -1 14359 -1 14360 -1 14361 -1 14362 -1 14363 -1 14364 -1 14365 -1 14366 -1 14367 -1 14368 -1 14369 -1 14370 -1 14371 -1 14372 -1 14373 -1 14374 -1 14375 -1 14376 -1 14377 -1 14378 -1 14379 -1 14380 -1 14381 -1 14382 -1 14383 -1 14384 -1 14385 -1 14386 -1 14387 -1 14388 -1 14389 -1 14390 -1 14391 -1 14392 -1 14393 -1 14394 -1 14395 -1 14396 -1 14397 -1 14398 -1 14399 -1 14400 -1 14401 -1 14402 -1 14403 -1 14404 -1 14405 -1 14406 -1 14407 -1 14408 -1 14409 -1 14410 -1 14411 -1 14412 -1 14413 -1 14414 -1 14415 -1 14416 -1 14417 -1 14418 -1 14419 -1 14420 -1 14421 -1 14422 -1 14423 -1 14424 -1 14425 -1 14426 -1 14427 -1 14428 -1 14429 -1 14430 -1 14431 -1 14432 -1 14433 -1 14434 -1 14435 -1 14436 -1 14437 -1 14438 -1 14439 -1 14440 -1 14441 -1 14442 -1 14443 -1 14444 -1 14445 -1 14446 -1 14447 -1 14448 -1 14449 -1 14450 -1 14451 -1 14452 -1 14453 -1 14454 -1 14455 -1 14456 -1 14457 -1 14458 -1 14459 -1 14460 -1 14461 -1 14462 -1 14463 -1 14464 -1 14465 -1 14466 -1 14467 -1 14468 -1 14469 -1 14470 -1 14471 -1 14472 -1 14473 -1 14474 -1 14475 -1 14476 -1 14477 -1 14478 -1 14479 -1 14480 -1 14481 -1 14482 -1 14483 -1 14484 -1 14485 -1 14486 -1 14487 -1 14488 -1 14489 -1 14490 -1 14491 -1 14492 -1 14493 -1 14494 -1 14495 -1 14496 -1 14497 -1 14498 -1 14499 -1 14500 -1 14501 -1 14502 -1 14503 -1 14504 -1 14505 -1 14506 -1 14507 -1 14508 -1 14509 -1 14510 -1 14511 -1 14512 -1 14513 -1 14514 -1 14515 -1 14516 -1 14517 -1 14518 -1 14519 -1 14520 -1 14521 -1 14522 -1 14523 -1 14524 -1 14525 -1 14526 -1 14527 -1 14528 -1 14529 -1 14530 -1 14531 -1 14532 -1 14533 -1 14534 -1 14535 -1 14536 -1 14537 -1 14538 -1 14539 -1 14540 -1 14541 -1 14542 -1 14543 -1 14544 -1 14545 -1 14546 -1 14547 -1 14548 -1 14549 -1 14550 -1 14551 -1 14552 -1 14553 -1 14554 -1 14555 -1 14556 -1 14557 -1 14558 -1 14559 -1 14560 -1 14561 -1 14562 -1 14563 -1 14564 -1 14565 -1 14566 -1 14567 -1 14568 -1 14569 -1 14570 -1 14571 -1 14572 -1 14573 -1 14574 -1 14575 -1 14576 -1 14577 -1 14578 -1 14579 -1 14580 -1 14581 -1 14582 -1 14583 -1 14584 -1 14585 -1 14586 -1 14587 -1 14588 -1 14589 -1 14590 -1 14591 -1 14592 -1 14593 -1 14594 -1 14595 -1 14596 -1 14597 -1 14598 -1 14599 -1 14600 -1 14601 -1 14602 -1 14603 -1 14604 -1 14605 -1 14606 -1 14607 -1 14608 -1 14609 -1 14610 -1 14611 -1 14612 -1 14613 -1 14614 -1 14615 -1 14616 -1 14617 -1 14618 -1 14619 -1 14620 -1 14621 -1 14622 -1 14623 -1 14624 -1 14625 -1 14626 -1 14627 -1 14628 -1 14629 -1 14630 -1 14631 -1 14632 -1 14633 -1 14634 -1 14635 -1 14636 -1 14637 -1 14638 -1 14639 -1 14640 -1 14641 -1 14642 -1 14643 -1 14644 -1 14645 -1 14646 -1 14647 -1 14648 -1 14649 -1 14650 -1 14651 -1 14652 -1 14653 -1 14654 -1 14655 -1 14656 -1 14657 -1 14658 -1 14659 -1 14660 -1 14661 -1 14662 -1 14663 -1 14664 -1 14665 -1 14666 -1 14667 -1 14668 -1 14669 -1 14670 -1 14671 -1 14672 -1 14673 -1 14674 -1 14675 -1 14676 -1 14677 -1 14678 -1 14679 -1 14680 -1 14681 -1 14682 -1 14683 -1 14684 -1 14685 -1 14686 -1 14687 -1 14688 -1 14689 -1 14690 -1 14691 -1 14692 -1 14693 -1 14694 -1 14695 -1 14696 -1 14697 -1 14698 -1 14699 -1 14700 -1 14701 -1 14702 -1 14703 -1 14704 -1 14705 -1 14706 -1 14707 -1 14708 -1 14709 -1 14710 -1 14711 -1 14712 -1 14713 -1 14714 -1 14715 -1 14716 -1 14717 -1 14718 -1 14719 -1 14720 -1 14721 -1 14722 -1 14723 -1 14724 -1 14725 -1 14726 -1 14727 -1 14728 -1 14729 -1 14730 -1 14731 -1 14732 -1 14733 -1 14734 -1 14735 -1 14736 -1 14737 -1 14738 -1 14739 -1 14740 -1 14741 -1 14742 -1 14743 -1 14744 -1 14745 -1 14746 -1 14747 -1 14748 -1 14749 -1 14750 -1 14751 -1 14752 -1 14753 -1 14754 -1 14755 -1 14756 -1 14757 -1 14758 -1 14759 -1 14760 -1 14761 -1 14762 -1 14763 -1 14764 -1 14765 -1 14766 -1 14767 -1 14768 -1 14769 -1 14770 -1 14771 -1 14772 -1 14773 -1 14774 -1 14775 -1 14776 -1 14777 -1 14778 -1 14779 -1 14780 -1 14781 -1 14782 -1 14783 -1 14784 -1 14785 -1 14786 -1 14787 -1 14788 -1 14789 -1 14790 -1 14791 -1 14792 -1 14793 -1 14794 -1 14795 -1 14796 -1 14797 -1 14798 -1 14799 -1 14800 -1 14801 -1 14802 -1 14803 -1 14804 -1 14805 -1 14806 -1 14807 -1 14808 -1 14809 -1 14810 -1 14811 -1 14812 -1 14813 -1 14814 -1 14815 -1 14816 -1 14817 -1 14818 -1 14819 -1 14820 -1 14821 -1 14822 -1 14823 -1 14824 -1 14825 -1 14826 -1 14827 -1 14828 -1 14829 -1 14830 -1 14831 -1 14832 -1 14833 -1 14834 -1 14835 -1 14836 -1 14837 -1 14838 -1 14839 -1 14840 -1 14841 -1 14842 -1 14843 -1 14844 -1 14845 -1 14846 -1 14847 -1 14848 -1 14849 -1 14850 -1 14851 -1 14852 -1 14853 -1 14854 -1 14855 -1 14856 -1 14857 -1 14858 -1 14859 -1 14860 -1 14861 -1 14862 -1 14863 -1 14864 -1 14865 -1 14866 -1 14867 -1 14868 -1 14869 -1 14870 -1 14871 -1 14872 -1 14873 -1 14874 -1 14875 -1 14876 -1 14877 -1 14878 -1 14879 -1 14880 -1 14881 -1 14882 -1 14883 -1 14884 -1 14885 -1 14886 -1 14887 -1 14888 -1 14889 -1 14890 -1 14891 -1 14892 -1 14893 -1 14894 -1 14895 -1 14896 -1 14897 -1 14898 -1 14899 -1 14900 -1 14901 -1 14902 -1 14903 -1 14904 -1 14905 -1 14906 -1 14907 -1 14908 -1 14909 -1 14910 -1 14911 -1 14912 -1 14913 -1 14914 -1 14915 -1 14916 -1 14917 -1 14918 -1 14919 -1 14920 -1 14921 -1 14922 -1 14923 -1 14924 -1 14925 -1 14926 -1 14927 -1 14928 -1 14929 -1 14930 -1 14931 -1 14932 -1 14933 -1 14934 -1 14935 -1 14936 -1 14937 -1 14938 -1 14939 -1 14940 -1 14941 -1 14942 -1 14943 -1 14944 -1 14945 -1 14946 -1 14947 -1 14948 -1 14949 -1 14950 -1 14951 -1 14952 -1 14953 -1 14954 -1 14955 -1 14956 -1 14957 -1 14958 -1 14959 -1 14960 -1 14961 -1 14962 -1 14963 -1 14964 -1 14965 -1 14966 -1 14967 -1 14968 -1 14969 -1 14970 -1 14971 -1 14972 -1 14973 -1 14974 -1 14975 -1 14976 -1 14977 -1 14978 -1 14979 -1 14980 -1 14981 -1 14982 -1 14983 -1 14984 -1 14985 -1 14986 -1 14987 -1 14988 -1 14989 -1 14990 -1 14991 -1 14992 -1 14993 -1 14994 -1 14995 -1 14996 -1 14997 -1 14998 -1 14999 -1 15000 -1 15001 -1 15002 -1 15003 -1 15004 -1 15005 -1 15006 -1 15007 -1 15008 -1 15009 -1 15010 -1 15011 -1 15012 -1 15013 -1 15014 -1 15015 -1 15016 -1 15017 -1 15018 -1 15019 -1 15020 -1 15021 -1 15022 -1 15023 -1 15024 -1 15025 -1 15026 -1 15027 -1 15028 -1 15029 -1 15030 -1 15031 -1 15032 -1 15033 -1 15034 -1 15035 -1 15036 -1 15037 -1 15038 -1 15039 -1 15040 -1 15041 -1 15042 -1 15043 -1 15044 -1 15045 -1 15046 -1 15047 -1 15048 -1 15049 -1 15050 -1 15051 -1 15052 -1 15053 -1 15054 -1 15055 -1 15056 -1 15057 -1 15058 -1 15059 -1 15060 -1 15061 -1 15062 -1 15063 -1 15064 -1 15065 -1 15066 -1 15067 -1 15068 -1 15069 -1 15070 -1 15071 -1 15072 -1 15073 -1 15074 -1 15075 -1 15076 -1 15077 -1 15078 -1 15079 -1 15080 -1 15081 -1 15082 -1 15083 -1 15084 -1 15085 -1 15086 -1 15087 -1 15088 -1 15089 -1 15090 -1 15091 -1 15092 -1 15093 -1 15094 -1 15095 -1 15096 -1 15097 -1 15098 -1 15099 -1 15100 -1 15101 -1 15102 -1 15103 -1 15104 -1 15105 -1 15106 -1 15107 -1 15108 -1 15109 -1 15110 -1 15111 -1 15112 -1 15113 -1 15114 -1 15115 -1 15116 -1 15117 -1 15118 -1 15119 -1 15120 -1 15121 -1 15122 -1 15123 -1 15124 -1 15125 -1 15126 -1 15127 -1 15128 -1 15129 -1 15130 -1 15131 -1 15132 -1 15133 -1 15134 -1 15135 -1 15136 -1 15137 -1 15138 -1 15139 -1 15140 -1 15141 -1 15142 -1 15143 -1 15144 -1 15145 -1 15146 -1 15147 -1 15148 -1 15149 -1 15150 -1 15151 -1 15152 -1 15153 -1 15154 -1 15155 -1 15156 -1 15157 -1 15158 -1 15159 -1 15160 -1 15161 -1 15162 -1 15163 -1 15164 -1 15165 -1 15166 -1 15167 -1 15168 -1 15169 -1 15170 -1 15171 -1 15172 -1 15173 -1 15174 -1 15175 -1 15176 -1 15177 -1 15178 -1 15179 -1 15180 -1 15181 -1 15182 -1 15183 -1 15184 -1 15185 -1 15186 -1 15187 -1 15188 -1 15189 -1 15190 -1 15191 -1 15192 -1 15193 -1 15194 -1 15195 -1 15196 -1 15197 -1 15198 -1 15199 -1 15200 -1 15201 -1 15202 -1 15203 -1 15204 -1 15205 -1 15206 -1 15207 -1 15208 -1 15209 -1 15210 -1 15211 -1 15212 -1 15213 -1 15214 -1 15215 -1 15216 -1 15217 -1 15218 -1 15219 -1 15220 -1 15221 -1 15222 -1 15223 -1 15224 -1 15225 -1 15226 -1 15227 -1 15228 -1 15229 -1 15230 -1 15231 -1 15232 -1 15233 -1 15234 -1 15235 -1 15236 -1 15237 -1 15238 -1 15239 -1 15240 -1 15241 -1 15242 -1 15243 -1 15244 -1 15245 -1 15246 -1 15247 -1 15248 -1 15249 -1 15250 -1 15251 -1 15252 -1 15253 -1 15254 -1 15255 -1 15256 -1 15257 -1 15258 -1 15259 -1 15260 -1 15261 -1 15262 -1 15263 -1 15264 -1 15265 -1 15266 -1 15267 -1 15268 -1 15269 -1 15270 -1 15271 -1 15272 -1 15273 -1 15274 -1 15275 -1 15276 -1 15277 -1 15278 -1 15279 -1 15280 -1 15281 -1 15282 -1 15283 -1 15284 -1 15285 -1 15286 -1 15287 -1 15288 -1 15289 -1 15290 -1 15291 -1 15292 -1 15293 -1 15294 -1 15295 -1 15296 -1 15297 -1 15298 -1 15299 -1 15300 -1 15301 -1 15302 -1 15303 -1 15304 -1 15305 -1 15306 -1 15307 -1 15308 -1 15309 -1 15310 -1 15311 -1 15312 -1 15313 -1 15314 -1 15315 -1 15316 -1 15317 -1 15318 -1 15319 -1 15320 -1 15321 -1 15322 -1 15323 -1 15324 -1 15325 -1 15326 -1 15327 -1 15328 -1 15329 -1 15330 -1 15331 -1 15332 -1 15333 -1 15334 -1 15335 -1 15336 -1 15337 -1 15338 -1 15339 -1 15340 -1 15341 -1 15342 -1 15343 -1 15344 -1 15345 -1 15346 -1 15347 -1 15348 -1 15349 -1 15350 -1 15351 -1 15352 -1 15353 -1 15354 -1 15355 -1 15356 -1 15357 -1 15358 -1 15359 -1 15360 -1 15361 -1 15362 -1 15363 -1 15364 -1 15365 -1 15366 -1 15367 -1 15368 -1 15369 -1 15370 -1 15371 -1 15372 -1 15373 -1 15374 -1 15375 -1 15376 -1 15377 -1 15378 -1 15379 -1 15380 -1 15381 -1 15382 -1 15383 -1 15384 -1 15385 -1 15386 -1 15387 -1 15388 -1 15389 -1 15390 -1 15391 -1 15392 -1 15393 -1 15394 -1 15395 -1 15396 -1 15397 -1 15398 -1 15399 -1 15400 -1 15401 -1 15402 -1 15403 -1 15404 -1 15405 -1 15406 -1 15407 -1 15408 -1 15409 -1 15410 -1 15411 -1 15412 -1 15413 -1 15414 -1 15415 -1 15416 -1 15417 -1 15418 -1 15419 -1 15420 -1 15421 -1 15422 -1 15423 -1 15424 -1 15425 -1 15426 -1 15427 -1 15428 -1 15429 -1 15430 -1 15431 -1 15432 -1 15433 -1 15434 -1 15435 -1 15436 -1 15437 -1 15438 -1 15439 -1 15440 -1 15441 -1 15442 -1 15443 -1 15444 -1 15445 -1 15446 -1 15447 -1 15448 -1 15449 -1 15450 -1 15451 -1 15452 -1 15453 -1 15454 -1 15455 -1 15456 -1 15457 -1 15458 -1 15459 -1 15460 -1 15461 -1 15462 -1 15463 -1 15464 -1 15465 -1 15466 -1 15467 -1 15468 -1 15469 -1 15470 -1 15471 -1 15472 -1 15473 -1 15474 -1 15475 -1 15476 -1 15477 -1 15478 -1 15479 -1 15480 -1 15481 -1 15482 -1 15483 -1 15484 -1 15485 -1 15486 -1 15487 -1 15488 -1 15489 -1 15490 -1 15491 -1 15492 -1 15493 -1 15494 -1 15495 -1 15496 -1 15497 -1 15498 -1 15499 -1 15500 -1 15501 -1 15502 -1 15503 -1 15504 -1 15505 -1 15506 -1 15507 -1 15508 -1 15509 -1 15510 -1 15511 -1 15512 -1 15513 -1 15514 -1 15515 -1 15516 -1 15517 -1 15518 -1 15519 -1 15520 -1 15521 -1 15522 -1 15523 -1 15524 -1 15525 -1 15526 -1 15527 -1 15528 -1 15529 -1 15530 -1 15531 -1 15532 -1 15533 -1 15534 -1 15535 -1 15536 -1 15537 -1 15538 -1 15539 -1 15540 -1 15541 -1 15542 -1 15543 -1 15544 -1 15545 -1 15546 -1 15547 -1 15548 -1 15549 -1 15550 -1 15551 -1 15552 -1 15553 -1 15554 -1 15555 -1 15556 -1 15557 -1 15558 -1 15559 -1 15560 -1 15561 -1 15562 -1 15563 -1 15564 -1 15565 -1 15566 -1 15567 -1 15568 -1 15569 -1 15570 -1 15571 -1 15572 -1 15573 -1 15574 -1 15575 -1 15576 -1 15577 -1 15578 -1 15579 -1 15580 -1 15581 -1 15582 -1 15583 -1 15584 -1 15585 -1 15586 -1 15587 -1 15588 -1 15589 -1 15590 -1 15591 -1 15592 -1 15593 -1 15594 -1 15595 -1 15596 -1 15597 -1 15598 -1 15599 -1 15600 -1 15601 -1 15602 -1 15603 -1 15604 -1 15605 -1 15606 -1 15607 -1 15608 -1 15609 -1 15610 -1 15611 -1 15612 -1 15613 -1 15614 -1 15615 -1 15616 -1 15617 -1 15618 -1 15619 -1 15620 -1 15621 -1 15622 -1 15623 -1 15624 -1 15625 -1 15626 -1 15627 -1 15628 -1 15629 -1 15630 -1 15631 -1 15632 -1 15633 -1 15634 -1 15635 -1 15636 -1 15637 -1 15638 -1 15639 -1 15640 -1 15641 -1 15642 -1 15643 -1 15644 -1 15645 -1 15646 -1 15647 -1 15648 -1 15649 -1 15650 -1 15651 -1 15652 -1 15653 -1 15654 -1 15655 -1 15656 -1 15657 -1 15658 -1 15659 -1 15660 -1 15661 -1 15662 -1 15663 -1 15664 -1 15665 -1 15666 -1 15667 -1 15668 -1 15669 -1 15670 -1 15671 -1 15672 -1 15673 -1 15674 -1 15675 -1 15676 -1 15677 -1 15678 -1 15679 -1 15680 -1 15681 -1 15682 -1 15683 -1 15684 -1 15685 -1 15686 -1 15687 -1 15688 -1 15689 -1 15690 -1 15691 -1 15692 -1 15693 -1 15694 -1 15695 -1 15696 -1 15697 -1 15698 -1 15699 -1 15700 -1 15701 -1 15702 -1 15703 -1 15704 -1 15705 -1 15706 -1 15707 -1 15708 -1 15709 -1 15710 -1 15711 -1 15712 -1 15713 -1 15714 -1 15715 -1 15716 -1 15717 -1 15718 -1 15719 -1 15720 -1 15721 -1 15722 -1 15723 -1 15724 -1 15725 -1 15726 -1 15727 -1 15728 -1 15729 -1 15730 -1 15731 -1 15732 -1 15733 -1 15734 -1 15735 -1 15736 -1 15737 -1 15738 -1 15739 -1 15740 -1 15741 -1 15742 -1 15743 -1 15744 -1 15745 -1 15746 -1 15747 -1 15748 -1 15749 -1 15750 -1 15751 -1 15752 -1 15753 -1 15754 -1 15755 -1 15756 -1 15757 -1 15758 -1 15759 -1 15760 -1 15761 -1 15762 -1 15763 -1 15764 -1 15765 -1 15766 -1 15767 -1 15768 -1 15769 -1 15770 -1 15771 -1 15772 -1 15773 -1 15774 -1 15775 -1 15776 -1 15777 -1 15778 -1 15779 -1 15780 -1 15781 -1 15782 -1 15783 -1 15784 -1 15785 -1 15786 -1 15787 -1 15788 -1 15789 -1 15790 -1 15791 -1 15792 -1 15793 -1 15794 -1 15795 -1 15796 -1 15797 -1 15798 -1 15799 -1 15800 -1 15801 -1 15802 -1 15803 -1 15804 -1 15805 -1 15806 -1 15807 -1 15808 -1 15809 -1 15810 -1 15811 -1 15812 -1 15813 -1 15814 -1 15815 -1 15816 -1 15817 -1 15818 -1 15819 -1 15820 -1 15821 -1 15822 -1 15823 -1 15824 -1 15825 -1 15826 -1 15827 -1 15828 -1 15829 -1 15830 -1 15831 -1 15832 -1 15833 -1 15834 -1 15835 -1 15836 -1 15837 -1 15838 -1 15839 -1 15840 -1 15841 -1 15842 -1 15843 -1 15844 -1 15845 -1 15846 -1 15847 -1 15848 -1 15849 -1 15850 -1 15851 -1 15852 -1 15853 -1 15854 -1 15855 -1 15856 -1 15857 -1 15858 -1 15859 -1 15860 -1 15861 -1 15862 -1 15863 -1 15864 -1 15865 -1 15866 -1 15867 -1 15868 -1 15869 -1 15870 -1 15871 -1 15872 -1 15873 -1 15874 -1 15875 -1 15876 -1 15877 -1 15878 -1 15879 -1 15880 -1 15881 -1 15882 -1 15883 -1 15884 -1 15885 -1 15886 -1 15887 -1 15888 -1 15889 -1 15890 -1 15891 -1 15892 -1 15893 -1 15894 -1 15895 -1 15896 -1 15897 -1 15898 -1 15899 -1 15900 -1 15901 -1 15902 -1 15903 -1 15904 -1 15905 -1 15906 -1 15907 -1 15908 -1 15909 -1 15910 -1 15911 -1 15912 -1 15913 -1 15914 -1 15915 -1 15916 -1 15917 -1 15918 -1 15919 -1 15920 -1 15921 -1 15922 -1 15923 -1 15924 -1 15925 -1 15926 -1 15927 -1 15928 -1 15929 -1 15930 -1 15931 -1 15932 -1 15933 -1 15934 -1 15935 -1 15936 -1 15937 -1 15938 -1 15939 -1 15940 -1 15941 -1 15942 -1 15943 -1 15944 -1 15945 -1 15946 -1 15947 -1 15948 -1 15949 -1 15950 -1 15951 -1 15952 -1 15953 -1 15954 -1 15955 -1 15956 -1 15957 -1 15958 -1 15959 -1 15960 -1 15961 -1 15962 -1 15963 -1 15964 -1 15965 -1 15966 -1 15967 -1 15968 -1 15969 -1 15970 -1 15971 -1 15972 -1 15973 -1 15974 -1 15975 -1 15976 -1 15977 -1 15978 -1 15979 -1 15980 -1 15981 -1 15982 -1 15983 -1 15984 -1 15985 -1 15986 -1 15987 -1 15988 -1 15989 -1 15990 -1 15991 -1 15992 -1 15993 -1 15994 -1 15995 -1 15996 -1 15997 -1 15998 -1 15999 -1 16000 -1 16001 -1 16002 -1 16003 -1 16004 -1 16005 -1 16006 -1 16007 -1 16008 -1 16009 -1 16010 -1 16011 -1 16012 -1 16013 -1 16014 -1 16015 -1 16016 -1 16017 -1 16018 -1 16019 -1 16020 -1 16021 -1 16022 -1 16023 -1 16024 -1 16025 -1 16026 -1 16027 -1 16028 -1 16029 -1 16030 -1 16031 -1 16032 -1 16033 -1 16034 -1 16035 -1 16036 -1 16037 -1 16038 -1 16039 -1 16040 -1 16041 -1 16042 -1 16043 -1 16044 -1 16045 -1 16046 -1 16047 -1 16048 -1 16049 -1 16050 -1 16051 -1 16052 -1 16053 -1 16054 -1 16055 -1 16056 -1 16057 -1 16058 -1 16059 -1 16060 -1 16061 -1 16062 -1 16063 -1 16064 -1 16065 -1 16066 -1 16067 -1 16068 -1 16069 -1 16070 -1 16071 -1 16072 -1 16073 -1 16074 -1 16075 -1 16076 -1 16077 -1 16078 -1 16079 -1 16080 -1 16081 -1 16082 -1 16083 -1 16084 -1 16085 -1 16086 -1 16087 -1 16088 -1 16089 -1 16090 -1 16091 -1 16092 -1 16093 -1 16094 -1 16095 -1 16096 -1 16097 -1 16098 -1 16099 -1 16100 -1 16101 -1 16102 -1 16103 -1 16104 -1 16105 -1 16106 -1 16107 -1 16108 -1 16109 -1 16110 -1 16111 -1 16112 -1 16113 -1 16114 -1 16115 -1 16116 -1 16117 -1 16118 -1 16119 -1 16120 -1 16121 -1 16122 -1 16123 -1 16124 -1 16125 -1 16126 -1 16127 -1 16128 -1 16129 -1 16130 -1 16131 -1 16132 -1 16133 -1 16134 -1 16135 -1 16136 -1 16137 -1 16138 -1 16139 -1 16140 -1 16141 -1 16142 -1 16143 -1 16144 -1 16145 -1 16146 -1 16147 -1 16148 -1 16149 -1 16150 -1 16151 -1 16152 -1 16153 -1 16154 -1 16155 -1 16156 -1 16157 -1 16158 -1 16159 -1 16160 -1 16161 -1 16162 -1 16163 -1 16164 -1 16165 -1 16166 -1 16167 -1 16168 -1 16169 -1 16170 -1 16171 -1 16172 -1 16173 -1 16174 -1 16175 -1 16176 -1 16177 -1 16178 -1 16179 -1 16180 -1 16181 -1 16182 -1 16183 -1 16184 -1 16185 -1 16186 -1 16187 -1 16188 -1 16189 -1 16190 -1 16191 -1 16192 -1 16193 -1 16194 -1 16195 -1 16196 -1 16197 -1 16198 -1 16199 -1 16200 -1 16201 -1 16202 -1 16203 -1 16204 -1 16205 -1 16206 -1 16207 -1 16208 -1 16209 -1 16210 -1 16211 -1 16212 -1 16213 -1 16214 -1 16215 -1 16216 -1 16217 -1 16218 -1 16219 -1 16220 -1 16221 -1 16222 -1 16223 -1 16224 -1 16225 -1 16226 -1 16227 -1 16228 -1 16229 -1 16230 -1 16231 -1 16232 -1 16233 -1 16234 -1 16235 -1 16236 -1 16237 -1 16238 -1 16239 -1 16240 -1 16241 -1 16242 -1 16243 -1 16244 -1 16245 -1 16246 -1 16247 -1 16248 -1 16249 -1 16250 -1 16251 -1 16252 -1 16253 -1 16254 -1 16255 -1 16256 -1 16257 -1 16258 -1 16259 -1 16260 -1 16261 -1 16262 -1 16263 -1 16264 -1 16265 -1 16266 -1 16267 -1 16268 -1 16269 -1 16270 -1 16271 -1 16272 -1 16273 -1 16274 -1 16275 -1 16276 -1 16277 -1 16278 -1 16279 -1 16280 -1 16281 -1 16282 -1 16283 -1 16284 -1 16285 -1 16286 -1 16287 -1 16288 -1 16289 -1 16290 -1 16291 -1 16292 -1 16293 -1 16294 -1 16295 -1 16296 -1 16297 -1 16298 -1 16299 -1 16300 -1 16301 -1 16302 -1 16303 -1 16304 -1 16305 -1 16306 -1 16307 -1 16308 -1 16309 -1 16310 -1 16311 -1 16312 -1 16313 -1 16314 -1 16315 -1 16316 -1 16317 -1 16318 -1 16319 -1 16320 -1 16321 -1 16322 -1 16323 -1 16324 -1 16325 -1 16326 -1 16327 -1 16328 -1 16329 -1 16330 -1 16331 -1 16332 -1 16333 -1 16334 -1 16335 -1 16336 -1 16337 -1 16338 -1 16339 -1 16340 -1 16341 -1 16342 -1 16343 -1 16344 -1 16345 -1 16346 -1 16347 -1 16348 -1 16349 -1 16350 -1 16351 -1 16352 -1 16353 -1 16354 -1 16355 -1 16356 -1 16357 -1 16358 -1 16359 -1 16360 -1 16361 -1 16362 -1 16363 -1 16364 -1 16365 -1 16366 -1 16367 -1 16368 -1 16369 -1 16370 -1 16371 -1 16372 -1 16373 -1 16374 -1 16375 -1 16376 -1 16377 -1 16378 -1 16379 -1 16380 -1 16381 -1 16382 -1 16383 -1 16384 -1 16385 -1 16386 -1 16387 -1 16388 -1 16389 -1 16390 -1 16391 -1 16392 -1 16393 -1 16394 -1 16395 -1 16396 -1 16397 -1 16398 -1 16399 -1 16400 -1 16401 -1 16402 -1 16403 -1 16404 -1 16405 -1 16406 -1 16407 -1 16408 -1 16409 -1 16410 -1 16411 -1 16412 -1 16413 -1 16414 -1 16415 -1 16416 -1 16417 -1 16418 -1 16419 -1 16420 -1 16421 -1 16422 -1 16423 -1 16424 -1 16425 -1 16426 -1 16427 -1 16428 -1 16429 -1 16430 -1 16431 -1 16432 -1 16433 -1 16434 -1 16435 -1 16436 -1 16437 -1 16438 -1 16439 -1 16440 -1 16441 -1 16442 -1 16443 -1 16444 -1 16445 -1 16446 -1 16447 -1 16448 -1 16449 -1 16450 -1 16451 -1 16452 -1 16453 -1 16454 -1 16455 -1 16456 -1 16457 -1 16458 -1 16459 -1 16460 -1 16461 -1 16462 -1 16463 -1 16464 -1 16465 -1 16466 -1 16467 -1 16468 -1 16469 -1 16470 -1 16471 -1 16472 -1 16473 -1 16474 -1 16475 -1 16476 -1 16477 -1 16478 -1 16479 -1 16480 -1 16481 -1 16482 -1 16483 -1 16484 -1 16485 -1 16486 -1 16487 -1 16488 -1 16489 -1 16490 -1 16491 -1 16492 -1 16493 -1 16494 -1 16495 -1 16496 -1 16497 -1 16498 -1 16499 -1 16500 -1 16501 -1 16502 -1 16503 -1 16504 -1 16505 -1 16506 -1 16507 -1 16508 -1 16509 -1 16510 -1 16511 -1 16512 -1 16513 -1 16514 -1 16515 -1 16516 -1 16517 -1 16518 -1 16519 -1 16520 -1 16521 -1 16522 -1 16523 -1 16524 -1 16525 -1 16526 -1 16527 -1 16528 -1 16529 -1 16530 -1 16531 -1 16532 -1 16533 -1 16534 -1 16535 -1 16536 -1 16537 -1 16538 -1 16539 -1 16540 -1 16541 -1 16542 -1 16543 -1 16544 -1 16545 -1 16546 -1 16547 -1 16548 -1 16549 -1 16550 -1 16551 -1 16552 -1 16553 -1 16554 -1 16555 -1 16556 -1 16557 -1 16558 -1 16559 -1 16560 -1 16561 -1 16562 -1 16563 -1 16564 -1 16565 -1 16566 -1 16567 -1 16568 -1 16569 -1 16570 -1 16571 -1 16572 -1 16573 -1 16574 -1 16575 -1 16576 -1 16577 -1 16578 -1 16579 -1 16580 -1 16581 -1 16582 -1 16583 -1 16584 -1 16585 -1 16586 -1 16587 -1 16588 -1 16589 -1 16590 -1 16591 -1 16592 -1 16593 -1 16594 -1 16595 -1 16596 -1 16597 -1 16598 -1 16599 -1 16600 -1 16601 -1 16602 -1 16603 -1 16604 -1 16605 -1 16606 -1 16607 -1 16608 -1 16609 -1 16610 -1 16611 -1 16612 -1 16613 -1 16614 -1 16615 -1 16616 -1 16617 -1 16618 -1 16619 -1 16620 -1 16621 -1 16622 -1 16623 -1 16624 -1 16625 -1 16626 -1 16627 -1 16628 -1 16629 -1 16630 -1 16631 -1 16632 -1 16633 -1 16634 -1 16635 -1 16636 -1 16637 -1 16638 -1 16639 -1 16640 -1 16641 -1 16642 -1 16643 -1 16644 -1 16645 -1 16646 -1 16647 -1 16648 -1 16649 -1 16650 -1 16651 -1 16652 -1 16653 -1 16654 -1 16655 -1 16656 -1 16657 -1 16658 -1 16659 -1 16660 -1 16661 -1 16662 -1 16663 -1 16664 -1 16665 -1 16666 -1 16667 -1 16668 -1 16669 -1 16670 -1 16671 -1 16672 -1 16673 -1 16674 -1 16675 -1 16676 -1 16677 -1 16678 -1 16679 -1 16680 -1 16681 -1 16682 -1 16683 -1 16684 -1 16685 -1 16686 -1 16687 -1 16688 -1 16689 -1 16690 -1 16691 -1 16692 -1 16693 -1 16694 -1 16695 -1 16696 -1 16697 -1 16698 -1 16699 -1 16700 -1 16701 -1 16702 -1 16703 -1 16704 -1 16705 -1 16706 -1 16707 -1 16708 -1 16709 -1 16710 -1 16711 -1 16712 -1 16713 -1 16714 -1 16715 -1 16716 -1 16717 -1 16718 -1 16719 -1 16720 -1 16721 -1 16722 -1 16723 -1 16724 -1 16725 -1 16726 -1 16727 -1 16728 -1 16729 -1 16730 -1 16731 -1 16732 -1 16733 -1 16734 -1 16735 -1 16736 -1 16737 -1 16738 -1 16739 -1 16740 -1 16741 -1 16742 -1 16743 -1 16744 -1 16745 -1 16746 -1 16747 -1 16748 -1 16749 -1 16750 -1 16751 -1 16752 -1 16753 -1 16754 -1 16755 -1 16756 -1 16757 -1 16758 -1 16759 -1 16760 -1 16761 -1 16762 -1 16763 -1 16764 -1 16765 -1 16766 -1 16767 -1 16768 -1 16769 -1 16770 -1 16771 -1 16772 -1 16773 -1 16774 -1 16775 -1 16776 -1 16777 -1 16778 -1 16779 -1 16780 -1 16781 -1 16782 -1 16783 -1 16784 -1 16785 -1 16786 -1 16787 -1 16788 -1 16789 -1 16790 -1 16791 -1 16792 -1 16793 -1 16794 -1 16795 -1 16796 -1 16797 -1 16798 -1 16799 -1 16800 -1 16801 -1 16802 -1 16803 -1 16804 -1 16805 -1 16806 -1 16807 -1 16808 -1 16809 -1 16810 -1 16811 -1 16812 -1 16813 -1 16814 -1 16815 -1 16816 -1 16817 -1 16818 -1 16819 -1 16820 -1 16821 -1 16822 -1 16823 -1 16824 -1 16825 -1 16826 -1 16827 -1 16828 -1 16829 -1 16830 -1 16831 -1 16832 -1 16833 -1 16834 -1 16835 -1 16836 -1 16837 -1 16838 -1 16839 -1 16840 -1 16841 -1 16842 -1 16843 -1 16844 -1 16845 -1 16846 -1 16847 -1 16848 -1 16849 -1 16850 -1 16851 -1 16852 -1 16853 -1 16854 -1 16855 -1 16856 -1 16857 -1 16858 -1 16859 -1 16860 -1 16861 -1 16862 -1 16863 -1 16864 -1 16865 -1 16866 -1 16867 -1 16868 -1 16869 -1 16870 -1 16871 -1 16872 -1 16873 -1 16874 -1 16875 -1 16876 -1 16877 -1 16878 -1 16879 -1 16880 -1 16881 -1 16882 -1 16883 -1 16884 -1 16885 -1 16886 -1 16887 -1 16888 -1 16889 -1 16890 -1 16891 -1 16892 -1 16893 -1 16894 -1 16895 -1 16896 -1 16897 -1 16898 -1 16899 -1 16900 -1 16901 -1 16902 -1 16903 -1 16904 -1 16905 -1 16906 -1 16907 -1 16908 -1 16909 -1 16910 -1 16911 -1 16912 -1 16913 -1 16914 -1 16915 -1 16916 -1 16917 -1 16918 -1 16919 -1 16920 -1 16921 -1 16922 -1 16923 -1 16924 -1 16925 -1 16926 -1 16927 -1 16928 -1 16929 -1 16930 -1 16931 -1 16932 -1 16933 -1 16934 -1 16935 -1 16936 -1 16937 -1 16938 -1 16939 -1 16940 -1 16941 -1 16942 -1 16943 -1 16944 -1 16945 -1 16946 -1 16947 -1 16948 -1 16949 -1 16950 -1 16951 -1 16952 -1 16953 -1 16954 -1 16955 -1 16956 -1 16957 -1 16958 -1 16959 -1 16960 -1 16961 -1 16962 -1 16963 -1 16964 -1 16965 -1 16966 -1 16967 -1 16968 -1 16969 -1 16970 -1 16971 -1 16972 -1 16973 -1 16974 -1 16975 -1 16976 -1 16977 -1 16978 -1 16979 -1 16980 -1 16981 -1 16982 -1 16983 -1 16984 -1 16985 -1 16986 -1 16987 -1 16988 -1 16989 -1 16990 -1 16991 -1 16992 -1 16993 -1 16994 -1 16995 -1 16996 -1 16997 -1 16998 -1 16999 -1 17000 -1 17001 -1 17002 -1 17003 -1 17004 -1 17005 -1 17006 -1 17007 -1 17008 -1 17009 -1 17010 -1 17011 -1 17012 -1 17013 -1 17014 -1 17015 -1 17016 -1 17017 -1 17018 -1 17019 -1 17020 -1 17021 -1 17022 -1 17023 -1 17024 -1 17025 -1 17026 -1 17027 -1 17028 -1 17029 -1 17030 -1 17031 -1 17032 -1 17033 -1 17034 -1 17035 -1 17036 -1 17037 -1 17038 -1 17039 -1 17040 -1 17041 -1 17042 -1 17043 -1 17044 -1 17045 -1 17046 -1 17047 -1 17048 -1 17049 -1 17050 -1 17051 -1 17052 -1 17053 -1 17054 -1 17055 -1 17056 -1 17057 -1 17058 -1 17059 -1 17060 -1 17061 -1 17062 -1 17063 -1 17064 -1 17065 -1 17066 -1 17067 -1 17068 -1 17069 -1 17070 -1 17071 -1 17072 -1 17073 -1 17074 -1 17075 -1 17076 -1 17077 -1 17078 -1 17079 -1 17080 -1 17081 -1 17082 -1 17083 -1 17084 -1 17085 -1 17086 -1 17087 -1 17088 -1 17089 -1 17090 -1 17091 -1 17092 -1 17093 -1 17094 -1 17095 -1 17096 -1 17097 -1 17098 -1 17099 -1 17100 -1 17101 -1 17102 -1 17103 -1 17104 -1 17105 -1 17106 -1 17107 -1 17108 -1 17109 -1 17110 -1 17111 -1 17112 -1 17113 -1 17114 -1 17115 -1 17116 -1 17117 -1 17118 -1 17119 -1 17120 -1 17121 -1 17122 -1 17123 -1 17124 -1 17125 -1 17126 -1 17127 -1 17128 -1 17129 -1 17130 -1 17131 -1 17132 -1 17133 -1 17134 -1 17135 -1 17136 -1 17137 -1 17138 -1 17139 -1 17140 -1 17141 -1 17142 -1 17143 -1 17144 -1 17145 -1 17146 -1 17147 -1 17148 -1 17149 -1 17150 -1 17151 -1 17152 -1 17153 -1 17154 -1 17155 -1 17156 -1 17157 -1 17158 -1 17159 -1 17160 -1 17161 -1 17162 -1 17163 -1 17164 -1 17165 -1 17166 -1 17167 -1 17168 -1 17169 -1 17170 -1 17171 -1 17172 -1 17173 -1 17174 -1 17175 -1 17176 -1 17177 -1 17178 -1 17179 -1 17180 -1 17181 -1 17182 -1 17183 -1 17184 -1 17185 -1 17186 -1 17187 -1 17188 -1 17189 -1 17190 -1 17191 -1 17192 -1 17193 -1 17194 -1 17195 -1 17196 -1 17197 -1 17198 -1 17199 -1 17200 -1 17201 -1 17202 -1 17203 -1 17204 -1 17205 -1 17206 -1 17207 -1 17208 -1 17209 -1 17210 -1 17211 -1 17212 -1 17213 -1 17214 -1 17215 -1 17216 -1 17217 -1 17218 -1 17219 -1 17220 -1 17221 -1 17222 -1 17223 -1 17224 -1 17225 -1 17226 -1 17227 -1 17228 -1 17229 -1 17230 -1 17231 -1 17232 -1 17233 -1 17234 -1 17235 -1 17236 -1 17237 -1 17238 -1 17239 -1 17240 -1 17241 -1 17242 -1 17243 -1 17244 -1 17245 -1 17246 -1 17247 -1 17248 -1 17249 -1 17250 -1 17251 -1 17252 -1 17253 -1 17254 -1 17255 -1 17256 -1 17257 -1 17258 -1 17259 -1 17260 -1 17261 -1 17262 -1 17263 -1 17264 -1 17265 -1 17266 -1 17267 -1 17268 -1 17269 -1 17270 -1 17271 -1 17272 -1 17273 -1 17274 -1 17275 -1 17276 -1 17277 -1 17278 -1 17279 -1 17280 -1 17281 -1 17282 -1 17283 -1 17284 -1 17285 -1 17286 -1 17287 -1 17288 -1 17289 -1 17290 -1 17291 -1 17292 -1 17293 -1 17294 -1 17295 -1 17296 -1 17297 -1 17298 -1 17299 -1 17300 -1 17301 -1 17302 -1 17303 -1 17304 -1 17305 -1 17306 -1 17307 -1 17308 -1 17309 -1 17310 -1 17311 -1 17312 -1 17313 -1 17314 -1 17315 -1 17316 -1 17317 -1 17318 -1 17319 -1 17320 -1 17321 -1 17322 -1 17323 -1 17324 -1 17325 -1 17326 -1 17327 -1 17328 -1 17329 -1 17330 -1 17331 -1 17332 -1 17333 -1 17334 -1 17335 -1 17336 -1 17337 -1 17338 -1 17339 -1 17340 -1 17341 -1 17342 -1 17343 -1 17344 -1 17345 -1 17346 -1 17347 -1 17348 -1 17349 -1 17350 -1 17351 -1 17352 -1 17353 -1 17354 -1 17355 -1 17356 -1 17357 -1 17358 -1 17359 -1 17360 -1 17361 -1 17362 -1 17363 -1 17364 -1 17365 -1 17366 -1 17367 -1 17368 -1 17369 -1 17370 -1 17371 -1 17372 -1 17373 -1 17374 -1 17375 -1 17376 -1 17377 -1 17378 -1 17379 -1 17380 -1 17381 -1 17382 -1 17383 -1 17384 -1 17385 -1 17386 -1 17387 -1 17388 -1 17389 -1 17390 -1 17391 -1 17392 -1 17393 -1 17394 -1 17395 -1 17396 -1 17397 -1 17398 -1 17399 -1 17400 -1 17401 -1 17402 -1 17403 -1 17404 -1 17405 -1 17406 -1 17407 -1 17408 -1 17409 -1 17410 -1 17411 -1 17412 -1 17413 -1 17414 -1 17415 -1 17416 -1 17417 -1 17418 -1 17419 -1 17420 -1 17421 -1 17422 -1 17423 -1 17424 -1 17425 -1 17426 -1 17427 -1 17428 -1 17429 -1 17430 -1 17431 -1 17432 -1 17433 -1 17434 -1 17435 -1 17436 -1 17437 -1 17438 -1 17439 -1 17440 -1 17441 -1 17442 -1 17443 -1 17444 -1 17445 -1 17446 -1 17447 -1 17448 -1 17449 -1 17450 -1 17451 -1 17452 -1 17453 -1 17454 -1 17455 -1 17456 -1 17457 -1 17458 -1 17459 -1 17460 -1 17461 -1 17462 -1 17463 -1 17464 -1 17465 -1 17466 -1 17467 -1 17468 -1 17469 -1 17470 -1 17471 -1 17472 -1 17473 -1 17474 -1 17475 -1 17476 -1 17477 -1 17478 -1 17479 -1 17480 -1 17481 -1 17482 -1 17483 -1 17484 -1 17485 -1 17486 -1 17487 -1 17488 -1 17489 -1 17490 -1 17491 -1 17492 -1 17493 -1 17494 -1 17495 -1 17496 -1 17497 -1 17498 -1 17499 -1 17500 -1 17501 -1 17502 -1 17503 -1 17504 -1 17505 -1 17506 -1 17507 -1 17508 -1 17509 -1 17510 -1 17511 -1 17512 -1 17513 -1 17514 -1 17515 -1 17516 -1 17517 -1 17518 -1 17519 -1 17520 -1 17521 -1 17522 -1 17523 -1 17524 -1 17525 -1 17526 -1 17527 -1 17528 -1 17529 -1 17530 -1 17531 -1 17532 -1 17533 -1 17534 -1 17535 -1 17536 -1 17537 -1 17538 -1 17539 -1 17540 -1 17541 -1 17542 -1 17543 -1 17544 -1 17545 -1 17546 -1 17547 -1 17548 -1 17549 -1 17550 -1 17551 -1 17552 -1 17553 -1 17554 -1 17555 -1 17556 -1 17557 -1 17558 -1 17559 -1 17560 -1 17561 -1 17562 -1 17563 -1 17564 -1 17565 -1 17566 -1 17567 -1 17568 -1 17569 -1 17570 -1 17571 -1 17572 -1 17573 -1 17574 -1 17575 -1 17576 -1 17577 -1 17578 -1 17579 -1 17580 -1 17581 -1 17582 -1 17583 -1 17584 -1 17585 -1 17586 -1 17587 -1 17588 -1 17589 -1 17590 -1 17591 -1 17592 -1 17593 -1 17594 -1 17595 -1 17596 -1 17597 -1 17598 -1 17599 -1 17600 -1 17601 -1 17602 -1 17603 -1 17604 -1 17605 -1 17606 -1 17607 -1 17608 -1 17609 -1 17610 -1 17611 -1 17612 -1 17613 -1 17614 -1 17615 -1 17616 -1 17617 -1 17618 -1 17619 -1 17620 -1 17621 -1 17622 -1 17623 -1 17624 -1 17625 -1 17626 -1 17627 -1 17628 -1 17629 -1 17630 -1 17631 -1 17632 -1 17633 -1 17634 -1 17635 -1 17636 -1 17637 -1 17638 -1 17639 -1 17640 -1 17641 -1 17642 -1 17643 -1 17644 -1 17645 -1 17646 -1 17647 -1 17648 -1 17649 -1 17650 -1 17651 -1 17652 -1 17653 -1 17654 -1 17655 -1 17656 -1 17657 -1 17658 -1 17659 -1 17660 -1 17661 -1 17662 -1 17663 -1 17664 -1 17665 -1 17666 -1 17667 -1 17668 -1 17669 -1 17670 -1 17671 -1 17672 -1 17673 -1 17674 -1 17675 -1 17676 -1 17677 -1 17678 -1 17679 -1 17680 -1 17681 -1 17682 -1 17683 -1 17684 -1 17685 -1 17686 -1 17687 -1 17688 -1 17689 -1 17690 -1 17691 -1 17692 -1 17693 -1 17694 -1 17695 -1 17696 -1 17697 -1 17698 -1 17699 -1 17700 -1 17701 -1 17702 -1 17703 -1 17704 -1 17705 -1 17706 -1 17707 -1 17708 -1 17709 -1 17710 -1 17711 -1 17712 -1 17713 -1 17714 -1 17715 -1 17716 -1 17717 -1 17718 -1 17719 -1 17720 -1 17721 -1 17722 -1 17723 -1 17724 -1 17725 -1 17726 -1 17727 -1 17728 -1 17729 -1 17730 -1 17731 -1 17732 -1 17733 -1 17734 -1 17735 -1 17736 -1 17737 -1 17738 -1 17739 -1 17740 -1 17741 -1 17742 -1 17743 -1 17744 -1 17745 -1 17746 -1 17747 -1 17748 -1 17749 -1 17750 -1 17751 -1 17752 -1 17753 -1 17754 -1 17755 -1 17756 -1 17757 -1 17758 -1 17759 -1 17760 -1 17761 -1 17762 -1 17763 -1 17764 -1 17765 -1 17766 -1 17767 -1 17768 -1 17769 -1 17770 -1 17771 -1 17772 -1 17773 -1 17774 -1 17775 -1 17776 -1 17777 -1 17778 -1 17779 -1 17780 -1 17781 -1 17782 -1 17783 -1 17784 -1 17785 -1 17786 -1 17787 -1 17788 -1 17789 -1 17790 -1 17791 -1 17792 -1 17793 -1 17794 -1 17795 -1 17796 -1 17797 -1 17798 -1 17799 -1 17800 -1 17801 -1 17802 -1 17803 -1 17804 -1 17805 -1 17806 -1 17807 -1 17808 -1 17809 -1 17810 -1 17811 -1 17812 -1 17813 -1 17814 -1 17815 -1 17816 -1 17817 -1 17818 -1 17819 -1 17820 -1 17821 -1 17822 -1 17823 -1 17824 -1 17825 -1 17826 -1 17827 -1 17828 -1 17829 -1 17830 -1 17831 -1 17832 -1 17833 -1 17834 -1 17835 -1 17836 -1 17837 -1 17838 -1 17839 -1 17840 -1 17841 -1 17842 -1 17843 -1 17844 -1 17845 -1 17846 -1 17847 -1 17848 -1 17849 -1 17850 -1 17851 -1 17852 -1 17853 -1 17854 -1 17855 -1 17856 -1 17857 -1 17858 -1 17859 -1 17860 -1 17861 -1 17862 -1 17863 -1 17864 -1 17865 -1 17866 -1 17867 -1 17868 -1 17869 -1 17870 -1 17871 -1 17872 -1 17873 -1 17874 -1 17875 -1 17876 -1 17877 -1 17878 -1 17879 -1 17880 -1 17881 -1 17882 -1 17883 -1 17884 -1 17885 -1 17886 -1 17887 -1 17888 -1 17889 -1 17890 -1 17891 -1 17892 -1 17893 -1 17894 -1 17895 -1 17896 -1 17897 -1 17898 -1 17899 -1 17900 -1 17901 -1 17902 -1 17903 -1 17904 -1 17905 -1 17906 -1 17907 -1 17908 -1 17909 -1 17910 -1 17911 -1 17912 -1 17913 -1 17914 -1 17915 -1 17916 -1 17917 -1 17918 -1 17919 -1 17920 -1 17921 -1 17922 -1 17923 -1 17924 -1 17925 -1 17926 -1 17927 -1 17928 -1 17929 -1 17930 -1 17931 -1 17932 -1 17933 -1 17934 -1 17935 -1 17936 -1 17937 -1 17938 -1 17939 -1 17940 -1 17941 -1 17942 -1 17943 -1 17944 -1 17945 -1 17946 -1 17947 -1 17948 -1 17949 -1 17950 -1 17951 -1 17952 -1 17953 -1 17954 -1 17955 -1 17956 -1 17957 -1 17958 -1 17959 -1 17960 -1 17961 -1 17962 -1 17963 -1 17964 -1 17965 -1 17966 -1 17967 -1 17968 -1 17969 -1 17970 -1 17971 -1 17972 -1 17973 -1 17974 -1 17975 -1 17976 -1 17977 -1 17978 -1 17979 -1 17980 -1 17981 -1 17982 -1 17983 -1 17984 -1 17985 -1 17986 -1 17987 -1 17988 -1 17989 -1 17990 -1 17991 -1 17992 -1 17993 -1 17994 -1 17995 -1 17996 -1 17997 -1 17998 -1 17999 -1 18000 -1 18001 -1 18002 -1 18003 -1 18004 -1 18005 -1 18006 -1 18007 -1 18008 -1 18009 -1 18010 -1 18011 -1 18012 -1 18013 -1 18014 -1 18015 -1 18016 -1 18017 -1 18018 -1 18019 -1 18020 -1 18021 -1 18022 -1 18023 -1 18024 -1 18025 -1 18026 -1 18027 -1 18028 -1 18029 -1 18030 -1 18031 -1 18032 -1 18033 -1 18034 -1 18035 -1 18036 -1 18037 -1 18038 -1 18039 -1 18040 -1 18041 -1 18042 -1 18043 -1 18044 -1 18045 -1 18046 -1 18047 -1 18048 -1 18049 -1 18050 -1 18051 -1 18052 -1 18053 -1 18054 -1 18055 -1 18056 -1 18057 -1 18058 -1 18059 -1 18060 -1 18061 -1 18062 -1 18063 -1 18064 -1 18065 -1 18066 -1 18067 -1 18068 -1 18069 -1 18070 -1 18071 -1 18072 -1 18073 -1 18074 -1 18075 -1 18076 -1 18077 -1 18078 -1 18079 -1 18080 -1 18081 -1 18082 -1 18083 -1 18084 -1 18085 -1 18086 -1 18087 -1 18088 -1 18089 -1 18090 -1 18091 -1 18092 -1 18093 -1 18094 -1 18095 -1 18096 -1 18097 -1 18098 -1 18099 -1 18100 -1 18101 -1 18102 -1 18103 -1 18104 -1 18105 -1 18106 -1 18107 -1 18108 -1 18109 -1 18110 -1 18111 -1 18112 -1 18113 -1 18114 -1 18115 -1 18116 -1 18117 -1 18118 -1 18119 -1 18120 -1 18121 -1 18122 -1 18123 -1 18124 -1 18125 -1 18126 -1 18127 -1 18128 -1 18129 -1 18130 -1 18131 -1 18132 -1 18133 -1 18134 -1 18135 -1 18136 -1 18137 -1 18138 -1 18139 -1 18140 -1 18141 -1 18142 -1 18143 -1 18144 -1 18145 -1 18146 -1 18147 -1 18148 -1 18149 -1 18150 -1 18151 -1 18152 -1 18153 -1 18154 -1 18155 -1 18156 -1 18157 -1 18158 -1 18159 -1 18160 -1 18161 -1 18162 -1 18163 -1 18164 -1 18165 -1 18166 -1 18167 -1 18168 -1 18169 -1 18170 -1 18171 -1 18172 -1 18173 -1 18174 -1 18175 -1 18176 -1 18177 -1 18178 -1 18179 -1 18180 -1 18181 -1 18182 -1 18183 -1 18184 -1 18185 -1 18186 -1 18187 -1 18188 -1 18189 -1 18190 -1 18191 -1 18192 -1 18193 -1 18194 -1 18195 -1 18196 -1 18197 -1 18198 -1 18199 -1 18200 -1 18201 -1 18202 -1 18203 -1 18204 -1 18205 -1 18206 -1 18207 -1 18208 -1 18209 -1 18210 -1 18211 -1 18212 -1 18213 -1 18214 -1 18215 -1 18216 -1 18217 -1 18218 -1 18219 -1 18220 -1 18221 -1 18222 -1 18223 -1 18224 -1 18225 -1 18226 -1 18227 -1 18228 -1 18229 -1 18230 -1 18231 -1 18232 -1 18233 -1 18234 -1 18235 -1 18236 -1 18237 -1 18238 -1 18239 -1 18240 -1 18241 -1 18242 -1 18243 -1 18244 -1 18245 -1 18246 -1 18247 -1 18248 -1 18249 -1 18250 -1 18251 -1 18252 -1 18253 -1 18254 -1 18255 -1 18256 -1 18257 -1 18258 -1 18259 -1 18260 -1 18261 -1 18262 -1 18263 -1 18264 -1 18265 -1 18266 -1 18267 -1 18268 -1 18269 -1 18270 -1 18271 -1 18272 -1 18273 -1 18274 -1 18275 -1 18276 -1 18277 -1 18278 -1 18279 -1 18280 -1 18281 -1 18282 -1 18283 -1 18284 -1 18285 -1 18286 -1 18287 -1 18288 -1 18289 -1 18290 -1 18291 -1 18292 -1 18293 -1 18294 -1 18295 -1 18296 -1 18297 -1 18298 -1 18299 -1 18300 -1 18301 -1 18302 -1 18303 -1 18304 -1 18305 -1 18306 -1 18307 -1 18308 -1 18309 -1 18310 -1 18311 -1 18312 -1 18313 -1 18314 -1 18315 -1 18316 -1 18317 -1 18318 -1 18319 -1 18320 -1 18321 -1 18322 -1 18323 -1 18324 -1 18325 -1 18326 -1 18327 -1 18328 -1 18329 -1 18330 -1 18331 -1 18332 -1 18333 -1 18334 -1 18335 -1 18336 -1 18337 -1 18338 -1 18339 -1 18340 -1 18341 -1 18342 -1 18343 -1 18344 -1 18345 -1 18346 -1 18347 -1 18348 -1 18349 -1 18350 -1 18351 -1 18352 -1 18353 -1 18354 -1 18355 -1 18356 -1 18357 -1 18358 -1 18359 -1 18360 -1 18361 -1 18362 -1 18363 -1 18364 -1 18365 -1 18366 -1 18367 -1 18368 -1 18369 -1 18370 -1 18371 -1 18372 -1 18373 -1 18374 -1 18375 -1 18376 -1 18377 -1 18378 -1 18379 -1 18380 -1 18381 -1 18382 -1 18383 -1 18384 -1 18385 -1 18386 -1 18387 -1 18388 -1 18389 -1 18390 -1 18391 -1 18392 -1 18393 -1 18394 -1 18395 -1 18396 -1 18397 -1 18398 -1 18399 -1 18400 -1 18401 -1 18402 -1 18403 -1 18404 -1 18405 -1 18406 -1 18407 -1 18408 -1 18409 -1 18410 -1 18411 -1 18412 -1 18413 -1 18414 -1 18415 -1 18416 -1 18417 -1 18418 -1 18419 -1 18420 -1 18421 -1 18422 -1 18423 -1 18424 -1 18425 -1 18426 -1 18427 -1 18428 -1 18429 -1 18430 -1 18431 -1 18432 -1 18433 -1 18434 -1 18435 -1 18436 -1 18437 -1 18438 -1 18439 -1 18440 -1 18441 -1 18442 -1 18443 -1 18444 -1 18445 -1 18446 -1 18447 -1 18448 -1 18449 -1 18450 -1 18451 -1 18452 -1 18453 -1 18454 -1 18455 -1 18456 -1 18457 -1 18458 -1 18459 -1 18460 -1 18461 -1 18462 -1 18463 -1 18464 -1 18465 -1 18466 -1 18467 -1 18468 -1 18469 -1 18470 -1 18471 -1 18472 -1 18473 -1 18474 -1 18475 -1 18476 -1 18477 -1 18478 -1 18479 -1 18480 -1 18481 -1 18482 -1 18483 -1 18484 -1 18485 -1 18486 -1 18487 -1 18488 -1 18489 -1 18490 -1 18491 -1 18492 -1 18493 -1 18494 -1 18495 -1 18496 -1 18497 -1 18498 -1 18499 -1 18500 -1 18501 -1 18502 -1 18503 -1 18504 -1 18505 -1 18506 -1 18507 -1 18508 -1 18509 -1 18510 -1 18511 -1 18512 -1 18513 -1 18514 -1 18515 -1 18516 -1 18517 -1 18518 -1 18519 -1 18520 -1 18521 -1 18522 -1 18523 -1 18524 -1 18525 -1 18526 -1 18527 -1 18528 -1 18529 -1 18530 -1 18531 -1 18532 -1 18533 -1 18534 -1 18535 -1 18536 -1 18537 -1 18538 -1 18539 -1 18540 -1 18541 -1 18542 -1 18543 -1 18544 -1 18545 -1 18546 -1 18547 -1 18548 -1 18549 -1 18550 -1 18551 -1 18552 -1 18553 -1 18554 -1 18555 -1 18556 -1 18557 -1 18558 -1 18559 -1 18560 -1 18561 -1 18562 -1 18563 -1 18564 -1 18565 -1 18566 -1 18567 -1 18568 -1 18569 -1 18570 -1 18571 -1 18572 -1 18573 -1 18574 -1 18575 -1 18576 -1 18577 -1 18578 -1 18579 -1 18580 -1 18581 -1 18582 -1 18583 -1 18584 -1 18585 -1 18586 -1 18587 -1 18588 -1 18589 -1 18590 -1 18591 -1 18592 -1 18593 -1 18594 -1 18595 -1 18596 -1 18597 -1 18598 -1 18599 -1 18600 -1 18601 -1 18602 -1 18603 -1 18604 -1 18605 -1 18606 -1 18607 -1 18608 -1 18609 -1 18610 -1 18611 -1 18612 -1 18613 -1 18614 -1 18615 -1 18616 -1 18617 -1 18618 -1 18619 -1 18620 -1 18621 -1 18622 -1 18623 -1 18624 -1 18625 -1 18626 -1 18627 -1 18628 -1 18629 -1 18630 -1 18631 -1 18632 -1 18633 -1 18634 -1 18635 -1 18636 -1 18637 -1 18638 -1 18639 -1 18640 -1 18641 -1 18642 -1 18643 -1 18644 -1 18645 -1 18646 -1 18647 -1 18648 -1 18649 -1 18650 -1 18651 -1 18652 -1 18653 -1 18654 -1 18655 -1 18656 -1 18657 -1 18658 -1 18659 -1 18660 -1 18661 -1 18662 -1 18663 -1 18664 -1 18665 -1 18666 -1 18667 -1 18668 -1 18669 -1 18670 -1 18671 -1 18672 -1 18673 -1 18674 -1 18675 -1 18676 -1 18677 -1 18678 -1 18679 -1 18680 -1 18681 -1 18682 -1 18683 -1 18684 -1 18685 -1 18686 -1 18687 -1 18688 -1 18689 -1 18690 -1 18691 -1 18692 -1 18693 -1 18694 -1 18695 -1 18696 -1 18697 -1 18698 -1 18699 -1 18700 -1 18701 -1 18702 -1 18703 -1 18704 -1 18705 -1 18706 -1 18707 -1 18708 -1 18709 -1 18710 -1 18711 -1 18712 -1 18713 -1 18714 -1 18715 -1 18716 -1 18717 -1 18718 -1 18719 -1 18720 -1 18721 -1 18722 -1 18723 -1 18724 -1 18725 -1 18726 -1 18727 -1 18728 -1 18729 -1 18730 -1 18731 -1 18732 -1 18733 -1 18734 -1 18735 -1 18736 -1 18737 -1 18738 -1 18739 -1 18740 -1 18741 -1 18742 -1 18743 -1 18744 -1 18745 -1 18746 -1 18747 -1 18748 -1 18749 -1 18750 -1 18751 -1 18752 -1 18753 -1 18754 -1 18755 -1 18756 -1 18757 -1 18758 -1 18759 -1 18760 -1 18761 -1 18762 -1 18763 -1 18764 -1 18765 -1 18766 -1 18767 -1 18768 -1 18769 -1 18770 -1 18771 -1 18772 -1 18773 -1 18774 -1 18775 -1 18776 -1 18777 -1 18778 -1 18779 -1 18780 -1 18781 -1 18782 -1 18783 -1 18784 -1 18785 -1 18786 -1 18787 -1 18788 -1 18789 -1 18790 -1 18791 -1 18792 -1 18793 -1 18794 -1 18795 -1 18796 -1 18797 -1 18798 -1 18799 -1 18800 -1 18801 -1 18802 -1 18803 -1 18804 -1 18805 -1 18806 -1 18807 -1 18808 -1 18809 -1 18810 -1 18811 -1 18812 -1 18813 -1 18814 -1 18815 -1 18816 -1 18817 -1 18818 -1 18819 -1 18820 -1 18821 -1 18822 -1 18823 -1 18824 -1 18825 -1 18826 -1 18827 -1 18828 -1 18829 -1 18830 -1 18831 -1 18832 -1 18833 -1 18834 -1 18835 -1 18836 -1 18837 -1 18838 -1 18839 -1 18840 -1 18841 -1 18842 -1 18843 -1 18844 -1 18845 -1 18846 -1 18847 -1 18848 -1 18849 -1 18850 -1 18851 -1 18852 -1 18853 -1 18854 -1 18855 -1 18856 -1 18857 -1 18858 -1 18859 -1 18860 -1 18861 -1 18862 -1 18863 -1 18864 -1 18865 -1 18866 -1 18867 -1 18868 -1 18869 -1 18870 -1 18871 -1 18872 -1 18873 -1 18874 -1 18875 -1 18876 -1 18877 -1 18878 -1 18879 -1 18880 -1 18881 -1 18882 -1 18883 -1 18884 -1 18885 -1 18886 -1 18887 -1 18888 -1 18889 -1 18890 -1 18891 -1 18892 -1 18893 -1 18894 -1 18895 -1 18896 -1 18897 -1 18898 -1 18899 -1 18900 -1 18901 -1 18902 -1 18903 -1 18904 -1 18905 -1 18906 -1 18907 -1 18908 -1 18909 -1 18910 -1 18911 -1 18912 -1 18913 -1 18914 -1 18915 -1 18916 -1 18917 -1 18918 -1 18919 -1 18920 -1 18921 -1 18922 -1 18923 -1 18924 -1 18925 -1 18926 -1 18927 -1 18928 -1 18929 -1 18930 -1 18931 -1 18932 -1 18933 -1 18934 -1 18935 -1 18936 -1 18937 -1 18938 -1 18939 -1 18940 -1 18941 -1 18942 -1 18943 -1 18944 -1 18945 -1 18946 -1 18947 -1 18948 -1 18949 -1 18950 -1 18951 -1 18952 -1 18953 -1 18954 -1 18955 -1 18956 -1 18957 -1 18958 -1 18959 -1 18960 -1 18961 -1 18962 -1 18963 -1 18964 -1 18965 -1 18966 -1 18967 -1 18968 -1 18969 -1 18970 -1 18971 -1 18972 -1 18973 -1 18974 -1 18975 -1 18976 -1 18977 -1 18978 -1 18979 -1 18980 -1 18981 -1 18982 -1 18983 -1 18984 -1 18985 -1 18986 -1 18987 -1 18988 -1 18989 -1 18990 -1 18991 -1 18992 -1 18993 -1 18994 -1 18995 -1 18996 -1 18997 -1 18998 -1 18999 -1 19000 -1 19001 -1 19002 -1 19003 -1 19004 -1 19005 -1 19006 -1 19007 -1 19008 -1 19009 -1 19010 -1 19011 -1 19012 -1 19013 -1 19014 -1 19015 -1 19016 -1 19017 -1 19018 -1 19019 -1 19020 -1 19021 -1 19022 -1 19023 -1 19024 -1 19025 -1 19026 -1 19027 -1 19028 -1 19029 -1 19030 -1 19031 -1 19032 -1 19033 -1 19034 -1 19035 -1 19036 -1 19037 -1 19038 -1 19039 -1 19040 -1 19041 -1 19042 -1 19043 -1 19044 -1 19045 -1 19046 -1 19047 -1 19048 -1 19049 -1 19050 -1 19051 -1 19052 -1 19053 -1 19054 -1 19055 -1 19056 -1 19057 -1 19058 -1 19059 -1 19060 -1 19061 -1 19062 -1 19063 -1 19064 -1 19065 -1 19066 -1 19067 -1 19068 -1 19069 -1 19070 -1 19071 -1 19072 -1 19073 -1 19074 -1 19075 -1 19076 -1 19077 -1 19078 -1 19079 -1 19080 -1 19081 -1 19082 -1 19083 -1 19084 -1 19085 -1 19086 -1 19087 -1 19088 -1 19089 -1 19090 -1 19091 -1 19092 -1 19093 -1 19094 -1 19095 -1 19096 -1 19097 -1 19098 -1 19099 -1 19100 -1 19101 -1 19102 -1 19103 -1 19104 -1 19105 -1 19106 -1 19107 -1 19108 -1 19109 -1 19110 -1 19111 -1 19112 -1 19113 -1 19114 -1 19115 -1 19116 -1 19117 -1 19118 -1 19119 -1 19120 -1 19121 -1 19122 -1 19123 -1 19124 -1 19125 -1 19126 -1 19127 -1 19128 -1 19129 -1 19130 -1 19131 -1 19132 -1 19133 -1 19134 -1 19135 -1 19136 -1 19137 -1 19138 -1 19139 -1 19140 -1 19141 -1 19142 -1 19143 -1 19144 -1 19145 -1 19146 -1 19147 -1 19148 -1 19149 -1 19150 -1 19151 -1 19152 -1 19153 -1 19154 -1 19155 -1 19156 -1 19157 -1 19158 -1 19159 -1 19160 -1 19161 -1 19162 -1 19163 -1 19164 -1 19165 -1 19166 -1 19167 -1 19168 -1 19169 -1 19170 -1 19171 -1 19172 -1 19173 -1 19174 -1 19175 -1 19176 -1 19177 -1 19178 -1 19179 -1 19180 -1 19181 -1 19182 -1 19183 -1 19184 -1 19185 -1 19186 -1 19187 -1 19188 -1 19189 -1 19190 -1 19191 -1 19192 -1 19193 -1 19194 -1 19195 -1 19196 -1 19197 -1 19198 -1 19199 -1 19200 -1 19201 -1 19202 -1 19203 -1 19204 -1 19205 -1 19206 -1 19207 -1 19208 -1 19209 -1 19210 -1 19211 -1 19212 -1 19213 -1 19214 -1 19215 -1 19216 -1 19217 -1 19218 -1 19219 -1 19220 -1 19221 -1 19222 -1 19223 -1 19224 -1 19225 -1 19226 -1 19227 -1 19228 -1 19229 -1 19230 -1 19231 -1 19232 -1 19233 -1 19234 -1 19235 -1 19236 -1 19237 -1 19238 -1 19239 -1 19240 -1 19241 -1 19242 -1 19243 -1 19244 -1 19245 -1 19246 -1 19247 -1 19248 -1 19249 -1 19250 -1 19251 -1 19252 -1 19253 -1 19254 -1 19255 -1 19256 -1 19257 -1 19258 -1 19259 -1 19260 -1 19261 -1 19262 -1 19263 -1 19264 -1 19265 -1 19266 -1 19267 -1 19268 -1 19269 -1 19270 -1 19271 -1 19272 -1 19273 -1 19274 -1 19275 -1 19276 -1 19277 -1 19278 -1 19279 -1 19280 -1 19281 -1 19282 -1 19283 -1 19284 -1 19285 -1 19286 -1 19287 -1 19288 -1 19289 -1 19290 -1 19291 -1 19292 -1 19293 -1 19294 -1 19295 -1 19296 -1 19297 -1 19298 -1 19299 -1 19300 -1 19301 -1 19302 -1 19303 -1 19304 -1 19305 -1 19306 -1 19307 -1 19308 -1 19309 -1 19310 -1 19311 -1 19312 -1 19313 -1 19314 -1 19315 -1 19316 -1 19317 -1 19318 -1 19319 -1 19320 -1 19321 -1 19322 -1 19323 -1 19324 -1 19325 -1 19326 -1 19327 -1 19328 -1 19329 -1 19330 -1 19331 -1 19332 -1 19333 -1 19334 -1 19335 -1 19336 -1 19337 -1 19338 -1 19339 -1 19340 -1 19341 -1 19342 -1 19343 -1 19344 -1 19345 -1 19346 -1 19347 -1 19348 -1 19349 -1 19350 -1 19351 -1 19352 -1 19353 -1 19354 -1 19355 -1 19356 -1 19357 -1 19358 -1 19359 -1 19360 -1 19361 -1 19362 -1 19363 -1 19364 -1 19365 -1 19366 -1 19367 -1 19368 -1 19369 -1 19370 -1 19371 -1 19372 -1 19373 -1 19374 -1 19375 -1 19376 -1 19377 -1 19378 -1 19379 -1 19380 -1 19381 -1 19382 -1 19383 -1 19384 -1 19385 -1 19386 -1 19387 -1 19388 -1 19389 -1 19390 -1 19391 -1 19392 -1 19393 -1 19394 -1 19395 -1 19396 -1 19397 -1 19398 -1 19399 -1 19400 -1 19401 -1 19402 -1 19403 -1 19404 -1 19405 -1 19406 -1 19407 -1 19408 -1 19409 -1 19410 -1 19411 -1 19412 -1 19413 -1 19414 -1 19415 -1 19416 -1 19417 -1 19418 -1 19419 -1 19420 -1 19421 -1 19422 -1 19423 -1 19424 -1 19425 -1 19426 -1 19427 -1 19428 -1 19429 -1 19430 -1 19431 -1 19432 -1 19433 -1 19434 -1 19435 -1 19436 -1 19437 -1 19438 -1 19439 -1 19440 -1 19441 -1 19442 -1 19443 -1 19444 -1 19445 -1 19446 -1 19447 -1 19448 -1 19449 -1 19450 -1 19451 -1 19452 -1 19453 -1 19454 -1 19455 -1 19456 -1 19457 -1 19458 -1 19459 -1 19460 -1 19461 -1 19462 -1 19463 -1 19464 -1 19465 -1 19466 -1 19467 -1 19468 -1 19469 -1 19470 -1 19471 -1 19472 -1 19473 -1 19474 -1 19475 -1 19476 -1 19477 -1 19478 -1 19479 -1 19480 -1 19481 -1 19482 -1 19483 -1 19484 -1 19485 -1 19486 -1 19487 -1 19488 -1 19489 -1 19490 -1 19491 -1 19492 -1 19493 -1 19494 -1 19495 -1 19496 -1 19497 -1 19498 -1 19499 -1 19500 -1 19501 -1 19502 -1 19503 -1 19504 -1 19505 -1 19506 -1 19507 -1 19508 -1 19509 -1 19510 -1 19511 -1 19512 -1 19513 -1 19514 -1 19515 -1 19516 -1 19517 -1 19518 -1 19519 -1 19520 -1 19521 -1 19522 -1 19523 -1 19524 -1 19525 -1 19526 -1 19527 -1 19528 -1 19529 -1 19530 -1 19531 -1 19532 -1 19533 -1 19534 -1 19535 -1 19536 -1 19537 -1 19538 -1 19539 -1 19540 -1 19541 -1 19542 -1 19543 -1 19544 -1 19545 -1 19546 -1 19547 -1 19548 -1 19549 -1 19550 -1 19551 -1 19552 -1 19553 -1 19554 -1 19555 -1 19556 -1 19557 -1 19558 -1 19559 -1 19560 -1 19561 -1 19562 -1 19563 -1 19564 -1 19565 -1 19566 -1 19567 -1 19568 -1 19569 -1 19570 -1 19571 -1 19572 -1 19573 -1 19574 -1 19575 -1 19576 -1 19577 -1 19578 -1 19579 -1 19580 -1 19581 -1 19582 -1 19583 -1 19584 -1 19585 -1 19586 -1 19587 -1 19588 -1 19589 -1 19590 -1 19591 -1 19592 -1 19593 -1 19594 -1 19595 -1 19596 -1 19597 -1 19598 -1 19599 -1 19600 -1 19601 -1 19602 -1 19603 -1 19604 -1 19605 -1 19606 -1 19607 -1 19608 -1 19609 -1 19610 -1 19611 -1 19612 -1 19613 -1 19614 -1 19615 -1 19616 -1 19617 -1 19618 -1 19619 -1 19620 -1 19621 -1 19622 -1 19623 -1 19624 -1 19625 -1 19626 -1 19627 -1 19628 -1 19629 -1 19630 -1 19631 -1 19632 -1 19633 -1 19634 -1 19635 -1 19636 -1 19637 -1 19638 -1 19639 -1 19640 -1 19641 -1 19642 -1 19643 -1 19644 -1 19645 -1 19646 -1 19647 -1 19648 -1 19649 -1 19650 -1 19651 -1 19652 -1 19653 -1 19654 -1 19655 -1 19656 -1 19657 -1 19658 -1 19659 -1 19660 -1 19661 -1 19662 -1 19663 -1 19664 -1 19665 -1 19666 -1 19667 -1 19668 -1 19669 -1 19670 -1 19671 -1 19672 -1 19673 -1 19674 -1 19675 -1 19676 -1 19677 -1 19678 -1 19679 -1 19680 -1 19681 -1 19682 -1 19683 -1 19684 -1 19685 -1 19686 -1 19687 -1 19688 -1 19689 -1 19690 -1 19691 -1 19692 -1 19693 -1 19694 -1 19695 -1 19696 -1 19697 -1 19698 -1 19699 -1 19700 -1 19701 -1 19702 -1 19703 -1 19704 -1 19705 -1 19706 -1 19707 -1 19708 -1 19709 -1 19710 -1 19711 -1 19712 -1 19713 -1 19714 -1 19715 -1 19716 -1 19717 -1 19718 -1 19719 -1 19720 -1 19721 -1 19722 -1 19723 -1 19724 -1 19725 -1 19726 -1 19727 -1 19728 -1 19729 -1 19730 -1 19731 -1 19732 -1 19733 -1 19734 -1 19735 -1 19736 -1 19737 -1 19738 -1 19739 -1 19740 -1 19741 -1 19742 -1 19743 -1 19744 -1 19745 -1 19746 -1 19747 -1 19748 -1 19749 -1 19750 -1 19751 -1 19752 -1 19753 -1 19754 -1 19755 -1 19756 -1 19757 -1 19758 -1 19759 -1 19760 -1 19761 -1 19762 -1 19763 -1 19764 -1 19765 -1 19766 -1 19767 -1 19768 -1 19769 -1 19770 -1 19771 -1 19772 -1 19773 -1 19774 -1 19775 -1 19776 -1 19777 -1 19778 -1 19779 -1 19780 -1 19781 -1 19782 -1 19783 -1 19784 -1 19785 -1 19786 -1 19787 -1 19788 -1 19789 -1 19790 -1 19791 -1 19792 -1 19793 -1 19794 -1 19795 -1 19796 -1 19797 -1 19798 -1 19799 -1 19800 -1 19801 -1 19802 -1 19803 -1 19804 -1 19805 -1 19806 -1 19807 -1 19808 -1 19809 -1 19810 -1 19811 -1 19812 -1 19813 -1 19814 -1 19815 -1 19816 -1 19817 -1 19818 -1 19819 -1 19820 -1 19821 -1 19822 -1 19823 -1 19824 -1 19825 -1 19826 -1 19827 -1 19828 -1 19829 -1 19830 -1 19831 -1 19832 -1 19833 -1 19834 -1 19835 -1 19836 -1 19837 -1 19838 -1 19839 -1 19840 -1 19841 -1 19842 -1 19843 -1 19844 -1 19845 -1 19846 -1 19847 -1 19848 -1 19849 -1 19850 -1 19851 -1 19852 -1 19853 -1 19854 -1 19855 -1 19856 -1 19857 -1 19858 -1 19859 -1 19860 -1 19861 -1 19862 -1 19863 -1 19864 -1 19865 -1 19866 -1 19867 -1 19868 -1 19869 -1 19870 -1 19871 -1 19872 -1 19873 -1 19874 -1 19875 -1 19876 -1 19877 -1 19878 -1 19879 -1 19880 -1 19881 -1 19882 -1 19883 -1 19884 -1 19885 -1 19886 -1 19887 -1 19888 -1 19889 -1 19890 -1 19891 -1 19892 -1 19893 -1 19894 -1 19895 -1 19896 -1 19897 -1 19898 -1 19899 -1 19900 -1 19901 -1 19902 -1 19903 -1 19904 -1 19905 -1 19906 -1 19907 -1 19908 -1 19909 -1 19910 -1 19911 -1 19912 -1 19913 -1 19914 -1 19915 -1 19916 -1 19917 -1 19918 -1 19919 -1 19920 -1 19921 -1 19922 -1 19923 -1 19924 -1 19925 -1 19926 -1 19927 -1 19928 -1 19929 -1 19930 -1 19931 -1 19932 -1 19933 -1 19934 -1 19935 -1 19936 -1 19937 -1 19938 -1 19939 -1 19940 -1 19941 -1 19942 -1 19943 -1 19944 -1 19945 -1 19946 -1 19947 -1 19948 -1 19949 -1 19950 -1 19951 -1 19952 -1 19953 -1 19954 -1 19955 -1 19956 -1 19957 -1 19958 -1 19959 -1 19960 -1 19961 -1 19962 -1 19963 -1 19964 -1 19965 -1 19966 -1 19967 -1 19968 -1 19969 -1 19970 -1 19971 -1 19972 -1 19973 -1 19974 -1 19975 -1 19976 -1 19977 -1 19978 -1 19979 -1 19980 -1 19981 -1 19982 -1 19983 -1 19984 -1 19985 -1 19986 -1 19987 -1 19988 -1 19989 -1 19990 -1 19991 -1 19992 -1 19993 -1 19994 -1 19995 -1 19996 -1 19997 -1 19998 -1 19999 -1 20000 -1 20001 -1 20002 -1 20003 -1 20004 -1 20005 -1 20006 -1 20007 -1 20008 -1 20009 -1 20010 -1 20011 -1 20012 -1 20013 -1 20014 -1 20015 -1 20016 -1 20017 -1 20018 -1 20019 -1 20020 -1 20021 -1 20022 -1 20023 -1 20024 -1 20025 -1 20026 -1 20027 -1 20028 -1 20029 -1 20030 -1 20031 -1 20032 -1 20033 -1 20034 -1 20035 -1 20036 -1 20037 -1 20038 -1 20039 -1 20040 -1 20041 -1 20042 -1 20043 -1 20044 -1 20045 -1 20046 -1 20047 -1 20048 -1 20049 -1 20050 -1 20051 -1 20052 -1 20053 -1 20054 -1 20055 -1 20056 -1 20057 -1 20058 -1 20059 -1 20060 -1 20061 -1 20062 -1 20063 -1 20064 -1 20065 -1 20066 -1 20067 -1 20068 -1 20069 -1 20070 -1 20071 -1 20072 -1 20073 -1 20074 -1 20075 -1 20076 -1 20077 -1 20078 -1 20079 -1 20080 -1 20081 -1 20082 -1 20083 -1 20084 -1 20085 -1 20086 -1 20087 -1 20088 -1 20089 -1 20090 -1 20091 -1 20092 -1 20093 -1 20094 -1 20095 -1 20096 -1 20097 -1 20098 -1 20099 -1 20100 -1 20101 -1 20102 -1 20103 -1 20104 -1 20105 -1 20106 -1 20107 -1 20108 -1 20109 -1 20110 -1 20111 -1 20112 -1 20113 -1 20114 -1 20115 -1 20116 -1 20117 -1 20118 -1 20119 -1 20120 -1 20121 -1 20122 -1 20123 -1 20124 -1 20125 -1 20126 -1 20127 -1 20128 -1 20129 -1 20130 -1 20131 -1 20132 -1 20133 -1 20134 -1 20135 -1 20136 -1 20137 -1 20138 -1 20139 -1 20140 -1 20141 -1 20142 -1 20143 -1 20144 -1 20145 -1 20146 -1 20147 -1 20148 -1 20149 -1 20150 -1 20151 -1 20152 -1 20153 -1 20154 -1 20155 -1 20156 -1 20157 -1 20158 -1 20159 -1 20160 -1 20161 -1 20162 -1 20163 -1 20164 -1 20165 -1 20166 -1 20167 -1 20168 -1 20169 -1 20170 -1 20171 -1 20172 -1 20173 -1 20174 -1 20175 -1 20176 -1 20177 -1 20178 -1 20179 -1 20180 -1 20181 -1 20182 -1 20183 -1 20184 -1 20185 -1 20186 -1 20187 -1 20188 -1 20189 -1 20190 -1 20191 -1 20192 -1 20193 -1 20194 -1 20195 -1 20196 -1 20197 -1 20198 -1 20199 -1 20200 -1 20201 -1 20202 -1 20203 -1 20204 -1 20205 -1 20206 -1 20207 -1 20208 -1 20209 -1 20210 -1 20211 -1 20212 -1 20213 -1 20214 -1 20215 -1 20216 -1 20217 -1 20218 -1 20219 -1 20220 -1 20221 -1 20222 -1 20223 -1 20224 -1 20225 -1 20226 -1 20227 -1 20228 -1 20229 -1 20230 -1 20231 -1 20232 -1 20233 -1 20234 -1 20235 -1 20236 -1 20237 -1 20238 -1 20239 -1 20240 -1 20241 -1 20242 -1 20243 -1 20244 -1 20245 -1 20246 -1 20247 -1 20248 -1 20249 -1 20250 -1 20251 -1 20252 -1 20253 -1 20254 -1 20255 -1 20256 -1 20257 -1 20258 -1 20259 -1 20260 -1 20261 -1 20262 -1 20263 -1 20264 -1 20265 -1 20266 -1 20267 -1 20268 -1 20269 -1 20270 -1 20271 -1 20272 -1 20273 -1 20274 -1 20275 -1 20276 -1 20277 -1 20278 -1 20279 -1 20280 -1 20281 -1 20282 -1 20283 -1 20284 -1 20285 -1 20286 -1 20287 -1 20288 -1 20289 -1 20290 -1 20291 -1 20292 -1 20293 -1 20294 -1 20295 -1 20296 -1 20297 -1 20298 -1 20299 -1 20300 -1 20301 -1 20302 -1 20303 -1 20304 -1 20305 -1 20306 -1 20307 -1 20308 -1 20309 -1 20310 -1 20311 -1 20312 -1 20313 -1 20314 -1 20315 -1 20316 -1 20317 -1 20318 -1 20319 -1 20320 -1 20321 -1 20322 -1 20323 -1 20324 -1 20325 -1 20326 -1 20327 -1 20328 -1 20329 -1 20330 -1 20331 -1 20332 -1 20333 -1 20334 -1 20335 -1 20336 -1 20337 -1 20338 -1 20339 -1 20340 -1 20341 -1 20342 -1 20343 -1 20344 -1 20345 -1 20346 -1 20347 -1 20348 -1 20349 -1 20350 -1 20351 -1 20352 -1 20353 -1 20354 -1 20355 -1 20356 -1 20357 -1 20358 -1 20359 -1 20360 -1 20361 -1 20362 -1 20363 -1 20364 -1 20365 -1 20366 -1 20367 -1 20368 -1 20369 -1 20370 -1 20371 -1 20372 -1 20373 -1 20374 -1 20375 -1 20376 -1 20377 -1 20378 -1 20379 -1 20380 -1 20381 -1 20382 -1 20383 -1 20384 -1 20385 -1 20386 -1 20387 -1 20388 -1 20389 -1 20390 -1 20391 -1 20392 -1 20393 -1 20394 -1 20395 -1 20396 -1 20397 -1 20398 -1 20399 -1 20400 -1 20401 -1 20402 -1 20403 -1 20404 -1 20405 -1 20406 -1 20407 -1 20408 -1 20409 -1 20410 -1 20411 -1 20412 -1 20413 -1 20414 -1 20415 -1 20416 -1 20417 -1 20418 -1 20419 -1 20420 -1 20421 -1 20422 -1 20423 -1 20424 -1 20425 -1 20426 -1 20427 -1 20428 -1 20429 -1 20430 -1 20431 -1 20432 -1 20433 -1 20434 -1 20435 -1 20436 -1 20437 -1 20438 -1 20439 -1 20440 -1 20441 -1 20442 -1 20443 -1 20444 -1 20445 -1 20446 -1 20447 -1 20448 -1 20449 -1 20450 -1 20451 -1 20452 -1 20453 -1 20454 -1 20455 -1 20456 -1 20457 -1 20458 -1 20459 -1 20460 -1 20461 -1 20462 -1 20463 -1 20464 -1 20465 -1 20466 -1 20467 -1 20468 -1 20469 -1 20470 -1 20471 -1 20472 -1 20473 -1 20474 -1 20475 -1 20476 -1 20477 -1 20478 -1 20479 -1 20480 -1 20481 -1 20482 -1 20483 -1 20484 -1 20485 -1 20486 -1 20487 -1 20488 -1 20489 -1 20490 -1 20491 -1 20492 -1 20493 -1 20494 -1 20495 -1 20496 -1 20497 -1 20498 -1 20499 -1 20500 -1 20501 -1 20502 -1 20503 -1 20504 -1 20505 -1 20506 -1 20507 -1 20508 -1 20509 -1 20510 -1 20511 -1 20512 -1 20513 -1 20514 -1 20515 -1 20516 -1 20517 -1 20518 -1 20519 -1 20520 -1 20521 -1 20522 -1 20523 -1 20524 -1 20525 -1 20526 -1 20527 -1 20528 -1 20529 -1 20530 -1 20531 -1 20532 -1 20533 -1 20534 -1 20535 -1 20536 -1 20537 -1 20538 -1 20539 -1 20540 -1 20541 -1 20542 -1 20543 -1 20544 -1 20545 -1 20546 -1 20547 -1 20548 -1 20549 -1 20550 -1 20551 -1 20552 -1 20553 -1 20554 -1 20555 -1 20556 -1 20557 -1 20558 -1 20559 -1 20560 -1 20561 -1 20562 -1 20563 -1 20564 -1 20565 -1 20566 -1 20567 -1 20568 -1 20569 -1 20570 -1 20571 -1 20572 -1 20573 -1 20574 -1 20575 -1 20576 -1 20577 -1 20578 -1 20579 -1 20580 -1 20581 -1 20582 -1 20583 -1 20584 -1 20585 -1 20586 -1 20587 -1 20588 -1 20589 -1 20590 -1 20591 -1 20592 -1 20593 -1 20594 -1 20595 -1 20596 -1 20597 -1 20598 -1 20599 -1 20600 -1 20601 -1 20602 -1 20603 -1 20604 -1 20605 -1 20606 -1 20607 -1 20608 -1 20609 -1 20610 -1 20611 -1 20612 -1 20613 -1 20614 -1 20615 -1 20616 -1 20617 -1 20618 -1 20619 -1 20620 -1 20621 -1 20622 -1 20623 -1 20624 -1 20625 -1 20626 -1 20627 -1 20628 -1 20629 -1 20630 -1 20631 -1 20632 -1 20633 -1 20634 -1 20635 -1 20636 -1 20637 -1 20638 -1 20639 -1 20640 -1 20641 -1 20642 -1 20643 -1 20644 -1 20645 -1 20646 -1 20647 -1 20648 -1 20649 -1 20650 -1 20651 -1 20652 -1 20653 -1 20654 -1 20655 -1 20656 -1 20657 -1 20658 -1 20659 -1 20660 -1 20661 -1 20662 -1 20663 -1 20664 -1 20665 -1 20666 -1 20667 -1 20668 -1 20669 -1 20670 -1 20671 -1 20672 -1 20673 -1 20674 -1 20675 -1 20676 -1 20677 -1 20678 -1 20679 -1 20680 -1 20681 -1 20682 -1 20683 -1 20684 -1 20685 -1 20686 -1 20687 -1 20688 -1 20689 -1 20690 -1 20691 -1 20692 -1 20693 -1 20694 -1 20695 -1 20696 -1 20697 -1 20698 -1 20699 -1 20700 -1 20701 -1 20702 -1 20703 -1 20704 -1 20705 -1 20706 -1 20707 -1 20708 -1 20709 -1 20710 -1 20711 -1 20712 -1 20713 -1 20714 -1 20715 -1 20716 -1 20717 -1 20718 -1 20719 -1 20720 -1 20721 -1 20722 -1 20723 -1 20724 -1 20725 -1 20726 -1 20727 -1 20728 -1 20729 -1 20730 -1 20731 -1 20732 -1 20733 -1 20734 -1 20735 -1 20736 -1 20737 -1 20738 -1 20739 -1 20740 -1 20741 -1 20742 -1 20743 -1 20744 -1 20745 -1 20746 -1 20747 -1 20748 -1 20749 -1 20750 -1 20751 -1 20752 -1 20753 -1 20754 -1 20755 -1 20756 -1 20757 -1 20758 -1 20759 -1 20760 -1 20761 -1 20762 -1 20763 -1 20764 -1 20765 -1 20766 -1 20767 -1 20768 -1 20769 -1 20770 -1 20771 -1 20772 -1 20773 -1 20774 -1 20775 -1 20776 -1 20777 -1 20778 -1 20779 -1 20780 -1 20781 -1 20782 -1 20783 -1 20784 -1 20785 -1 20786 -1 20787 -1 20788 -1 20789 -1 20790 -1 20791 -1 20792 -1 20793 -1 20794 -1 20795 -1 20796 -1 20797 -1 20798 -1 20799 -1 20800 -1 20801 -1 20802 -1 20803 -1 20804 -1 20805 -1 20806 -1 20807 -1 20808 -1 20809 -1 20810 -1 20811 -1 20812 -1 20813 -1 20814 -1 20815 -1 20816 -1 20817 -1 20818 -1 20819 -1 20820 -1 20821 -1 20822 -1 20823 -1 20824 -1 20825 -1 20826 -1 20827 -1 20828 -1 20829 -1 20830 -1 20831 -1 20832 -1 20833 -1 20834 -1 20835 -1 20836 -1 20837 -1 20838 -1 20839 -1 20840 -1 20841 -1 20842 -1 20843 -1 20844 -1 20845 -1 20846 -1 20847 -1 20848 -1 20849 -1 20850 -1 20851 -1 20852 -1 20853 -1 20854 -1 20855 -1 20856 -1 20857 -1 20858 -1 20859 -1 20860 -1 20861 -1 20862 -1 20863 -1 20864 -1 20865 -1 20866 -1 20867 -1 20868 -1 20869 -1 20870 -1 20871 -1 20872 -1 20873 -1 20874 -1 20875 -1 20876 -1 20877 -1 20878 -1 20879 -1 20880 -1 20881 -1 20882 -1 20883 -1 20884 -1 20885 -1 20886 -1 20887 -1 20888 -1 20889 -1 20890 -1 20891 -1 20892 -1 20893 -1 20894 -1 20895 -1 20896 -1 20897 -1 20898 -1 20899 -1 20900 -1 20901 -1 20902 -1 20903 -1 20904 -1 20905 -1 20906 -1 20907 -1 20908 -1 20909 -1 20910 -1 20911 -1 20912 -1 20913 -1 20914 -1 20915 -1 20916 -1 20917 -1 20918 -1 20919 -1 20920 -1 20921 -1 20922 -1 20923 -1 20924 -1 20925 -1 20926 -1 20927 -1 20928 -1 20929 -1 20930 -1 20931 -1 20932 -1 20933 -1 20934 -1 20935 -1 20936 -1 20937 -1 20938 -1 20939 -1 20940 -1 20941 -1 20942 -1 20943 -1 20944 -1 20945 -1 20946 -1 20947 -1 20948 -1 20949 -1 20950 -1 20951 -1 20952 -1 20953 -1 20954 -1 20955 -1 20956 -1 20957 -1 20958 -1 20959 -1 20960 -1 20961 -1 20962 -1 20963 -1 20964 -1 20965 -1 20966 -1 20967 -1 20968 -1 20969 -1 20970 -1 20971 -1 20972 -1 20973 -1 20974 -1 20975 -1 20976 -1 20977 -1 20978 -1 20979 -1 20980 -1 20981 -1 20982 -1 20983 -1 20984 -1 20985 -1 20986 -1 20987 -1 20988 -1 20989 -1 20990 -1 20991 -1 20992 -1 20993 -1 20994 -1 20995 -1 20996 -1 20997 -1 20998 -1 20999 -1 21000 -1 21001 -1 21002 -1 21003 -1 21004 -1 21005 -1 21006 -1 21007 -1 21008 -1 21009 -1 21010 -1 21011 -1 21012 -1 21013 -1 21014 -1 21015 -1 21016 -1 21017 -1 21018 -1 21019 -1 21020 -1 21021 -1 21022 -1 21023 -1 21024 -1 21025 -1 21026 -1 21027 -1 21028 -1 21029 -1 21030 -1 21031 -1 21032 -1 21033 -1 21034 -1 21035 -1 21036 -1 21037 -1 21038 -1 21039 -1 21040 -1 21041 -1 21042 -1 21043 -1 21044 -1 21045 -1 21046 -1 21047 -1 21048 -1 21049 -1 21050 -1 21051 -1 21052 -1 21053 -1 21054 -1 21055 -1 21056 -1 21057 -1 21058 -1 21059 -1 21060 -1 21061 -1 21062 -1 21063 -1 21064 -1 21065 -1 21066 -1 21067 -1 21068 -1 21069 -1 21070 -1 21071 -1 21072 -1 21073 -1 21074 -1 21075 -1 21076 -1 21077 -1 21078 -1 21079 -1 21080 -1 21081 -1 21082 -1 21083 -1 21084 -1 21085 -1 21086 -1 21087 -1 21088 -1 21089 -1 21090 -1 21091 -1 21092 -1 21093 -1 21094 -1 21095 -1 21096 -1 21097 -1 21098 -1 21099 -1 21100 -1 21101 -1 21102 -1 21103 -1 21104 -1 21105 -1 21106 -1 21107 -1 21108 -1 21109 -1 21110 -1 21111 -1 21112 -1 21113 -1 21114 -1 21115 -1 21116 -1 21117 -1 21118 -1 21119 -1 21120 -1 21121 -1 21122 -1 21123 -1 21124 -1 21125 -1 21126 -1 21127 -1 21128 -1 21129 -1 21130 -1 21131 -1 21132 -1 21133 -1 21134 -1 21135 -1 21136 -1 21137 -1 21138 -1 21139 -1 21140 -1 21141 -1 21142 -1 21143 -1 21144 -1 21145 -1 21146 -1 21147 -1 21148 -1 21149 -1 21150 -1 21151 -1 21152 -1 21153 -1 21154 -1 21155 -1 21156 -1 21157 -1 21158 -1 21159 -1 21160 -1 21161 -1 21162 -1 21163 -1 21164 -1 21165 -1 21166 -1 21167 -1 21168 -1 21169 -1 21170 -1 21171 -1 21172 -1 21173 -1 21174 -1 21175 -1 21176 -1 21177 -1 21178 -1 21179 -1 21180 -1 21181 -1 21182 -1 21183 -1 21184 -1 21185 -1 21186 -1 21187 -1 21188 -1 21189 -1 21190 -1 21191 -1 21192 -1 21193 -1 21194 -1 21195 -1 21196 -1 21197 -1 21198 -1 21199 -1 21200 -1 21201 -1 21202 -1 21203 -1 21204 -1 21205 -1 21206 -1 21207 -1 21208 -1 21209 -1 21210 -1 21211 -1 21212 -1 21213 -1 21214 -1 21215 -1 21216 -1 21217 -1 21218 -1 21219 -1 21220 -1 21221 -1 21222 -1 21223 -1 21224 -1 21225 -1 21226 -1 21227 -1 21228 -1 21229 -1 21230 -1 21231 -1 21232 -1 21233 -1 21234 -1 21235 -1 21236 -1 21237 -1 21238 -1 21239 -1 21240 -1 21241 -1 21242 -1 21243 -1 21244 -1 21245 -1 21246 -1 21247 -1 21248 -1 21249 -1 21250 -1 21251 -1 21252 -1 21253 -1 21254 -1 21255 -1 21256 -1 21257 -1 21258 -1 21259 -1 21260 -1 21261 -1 21262 -1 21263 -1 21264 -1 21265 -1 21266 -1 21267 -1 21268 -1 21269 -1 21270 -1 21271 -1 21272 -1 21273 -1 21274 -1 21275 -1 21276 -1 21277 -1 21278 -1 21279 -1 21280 -1 21281 -1 21282 -1 21283 -1 21284 -1 21285 -1 21286 -1 21287 -1 21288 -1 21289 -1 21290 -1 21291 -1 21292 -1 21293 -1 21294 -1 21295 -1 21296 -1 21297 -1 21298 -1 21299 -1 21300 -1 21301 -1 21302 -1 21303 -1 21304 -1 21305 -1 21306 -1 21307 -1 21308 -1 21309 -1 21310 -1 21311 -1 21312 -1 21313 -1 21314 -1 21315 -1 21316 -1 21317 -1 21318 -1 21319 -1 21320 -1 21321 -1 21322 -1 21323 -1 21324 -1 21325 -1 21326 -1 21327 -1 21328 -1 21329 -1 21330 -1 21331 -1 21332 -1 21333 -1 21334 -1 21335 -1 21336 -1 21337 -1 21338 -1 21339 -1 21340 -1 21341 -1 21342 -1 21343 -1 21344 -1 21345 -1 21346 -1 21347 -1 21348 -1 21349 -1 21350 -1 21351 -1 21352 -1 21353 -1 21354 -1 21355 -1 21356 -1 21357 -1 21358 -1 21359 -1 21360 -1 21361 -1 21362 -1 21363 -1 21364 -1 21365 -1 21366 -1 21367 -1 21368 -1 21369 -1 21370 -1 21371 -1 21372 -1 21373 -1 21374 -1 21375 -1 21376 -1 21377 -1 21378 -1 21379 -1 21380 -1 21381 -1 21382 -1 21383 -1 21384 -1 21385 -1 21386 -1 21387 -1 21388 -1 21389 -1 21390 -1 21391 -1 21392 -1 21393 -1 21394 -1 21395 -1 21396 -1 21397 -1 21398 -1 21399 -1 21400 -1 21401 -1 21402 -1 21403 -1 21404 -1 21405 -1 21406 -1 21407 -1 21408 -1 21409 -1 21410 -1 21411 -1 21412 -1 21413 -1 21414 -1 21415 -1 21416 -1 21417 -1 21418 -1 21419 -1 21420 -1 21421 -1 21422 -1 21423 -1 21424 -1 21425 -1 21426 -1 21427 -1 21428 -1 21429 -1 21430 -1 21431 -1 21432 -1 21433 -1 21434 -1 21435 -1 21436 -1 21437 -1 21438 -1 21439 -1 21440 -1 21441 -1 21442 -1 21443 -1 21444 -1 21445 -1 21446 -1 21447 -1 21448 -1 21449 -1 21450 -1 21451 -1 21452 -1 21453 -1 21454 -1 21455 -1 21456 -1 21457 -1 21458 -1 21459 -1 21460 -1 21461 -1 21462 -1 21463 -1 21464 -1 21465 -1 21466 -1 21467 -1 21468 -1 21469 -1 21470 -1 21471 -1 21472 -1 21473 -1 21474 -1 21475 -1 21476 -1 21477 -1 21478 -1 21479 -1 21480 -1 21481 -1 21482 -1 21483 -1 21484 -1 21485 -1 21486 -1 21487 -1 21488 -1 21489 -1 21490 -1 21491 -1 21492 -1 21493 -1 21494 -1 21495 -1 21496 -1 21497 -1 21498 -1 21499 -1 21500 -1 21501 -1 21502 -1 21503 -1 21504 -1 21505 -1 21506 -1 21507 -1 21508 -1 21509 -1 21510 -1 21511 -1 21512 -1 21513 -1 21514 -1 21515 -1 21516 -1 21517 -1 21518 -1 21519 -1 21520 -1 21521 -1 21522 -1 21523 -1 21524 -1 21525 -1 21526 -1 21527 -1 21528 -1 21529 -1 21530 -1 21531 -1 21532 -1 21533 -1 21534 -1 21535 -1 21536 -1 21537 -1 21538 -1 21539 -1 21540 -1 21541 -1 21542 -1 21543 -1 21544 -1 21545 -1 21546 -1 21547 -1 21548 -1 21549 -1 21550 -1 21551 -1 21552 -1 21553 -1 21554 -1 21555 -1 21556 -1 21557 -1 21558 -1 21559 -1 21560 -1 21561 -1 21562 -1 21563 -1 21564 -1 21565 -1 21566 -1 21567 -1 21568 -1 21569 -1 21570 -1 21571 -1 21572 -1 21573 -1 21574 -1 21575 -1 21576 -1 21577 -1 21578 -1 21579 -1 21580 -1 21581 -1 21582 -1 21583 -1 21584 -1 21585 -1 21586 -1 21587 -1 21588 -1 21589 -1 21590 -1 21591 -1 21592 -1 21593 -1 21594 -1 21595 -1 21596 -1 21597 -1 21598 -1 21599 -1 21600 -1 21601 -1 21602 -1 21603 -1 21604 -1 21605 -1 21606 -1 21607 -1 21608 -1 21609 -1 21610 -1 21611 -1 21612 -1 21613 -1 21614 -1 21615 -1 21616 -1 21617 -1 21618 -1 21619 -1 21620 -1 21621 -1 21622 -1 21623 -1 21624 -1 21625 -1 21626 -1 21627 -1 21628 -1 21629 -1 21630 -1 21631 -1 21632 -1 21633 -1 21634 -1 21635 -1 21636 -1 21637 -1 21638 -1 21639 -1 21640 -1 21641 -1 21642 -1 21643 -1 21644 -1 21645 -1 21646 -1 21647 -1 21648 -1 21649 -1 21650 -1 21651 -1 21652 -1 21653 -1 21654 -1 21655 -1 21656 -1 21657 -1 21658 -1 21659 -1 21660 -1 21661 -1 21662 -1 21663 -1 21664 -1 21665 -1 21666 -1 21667 -1 21668 -1 21669 -1 21670 -1 21671 -1 21672 -1 21673 -1 21674 -1 21675 -1 21676 -1 21677 -1 21678 -1 21679 -1 21680 -1 21681 -1 21682 -1 21683 -1 21684 -1 21685 -1 21686 -1 21687 -1 21688 -1 21689 -1 21690 -1 21691 -1 21692 -1 21693 -1 21694 -1 21695 -1 21696 -1 21697 -1 21698 -1 21699 -1 21700 -1 21701 -1 21702 -1 21703 -1 21704 -1 21705 -1 21706 -1 21707 -1 21708 -1 21709 -1 21710 -1 21711 -1 21712 -1 21713 -1 21714 -1 21715 -1 21716 -1 21717 -1 21718 -1 21719 -1 21720 -1 21721 -1 21722 -1 21723 -1 21724 -1 21725 -1 21726 -1 21727 -1 21728 -1 21729 -1 21730 -1 21731 -1 21732 -1 21733 -1 21734 -1 21735 -1 21736 -1 21737 -1 21738 -1 21739 -1 21740 -1 21741 -1 21742 -1 21743 -1 21744 -1 21745 -1 21746 -1 21747 -1 21748 -1 21749 -1 21750 -1 21751 -1 21752 -1 21753 -1 21754 -1 21755 -1 21756 -1 21757 -1 21758 -1 21759 -1 21760 -1 21761 -1 21762 -1 21763 -1 21764 -1 21765 -1 21766 -1 21767 -1 21768 -1 21769 -1 21770 -1 21771 -1 21772 -1 21773 -1 21774 -1 21775 -1 21776 -1 21777 -1 21778 -1 21779 -1 21780 -1 21781 -1 21782 -1 21783 -1 21784 -1 21785 -1 21786 -1 21787 -1 21788 -1 21789 -1 21790 -1 21791 -1 21792 -1 21793 -1 21794 -1 21795 -1 21796 -1 21797 -1 21798 -1 21799 -1 21800 -1 21801 -1 21802 -1 21803 -1 21804 -1 21805 -1 21806 -1 21807 -1 21808 -1 21809 -1 21810 -1 21811 -1 21812 -1 21813 -1 21814 -1 21815 -1 21816 -1 21817 -1 21818 -1 21819 -1 21820 -1 21821 -1 21822 -1 21823 -1 21824 -1 21825 -1 21826 -1 21827 -1 21828 -1 21829 -1 21830 -1 21831 -1 21832 -1 21833 -1 21834 -1 21835 -1 21836 -1 21837 -1 21838 -1 21839 -1 21840 -1 21841 -1 21842 -1 21843 -1 21844 -1 21845 -1 21846 -1 21847 -1 21848 -1 21849 -1 21850 -1 21851 -1 21852 -1 21853 -1 21854 -1 21855 -1 21856 -1 21857 -1 21858 -1 21859 -1 21860 -1 21861 -1 21862 -1 21863 -1 21864 -1 21865 -1 21866 -1 21867 -1 21868 -1 21869 -1 21870 -1 21871 -1 21872 -1 21873 -1 21874 -1 21875 -1 21876 -1 21877 -1 21878 -1 21879 -1 21880 -1 21881 -1 21882 -1 21883 -1 21884 -1 21885 -1 21886 -1 21887 -1 21888 -1 21889 -1 21890 -1 21891 -1 21892 -1 21893 -1 21894 -1 21895 -1 21896 -1 21897 -1 21898 -1 21899 -1 21900 -1 21901 -1 21902 -1 21903 -1 21904 -1 21905 -1 21906 -1 21907 -1 21908 -1 21909 -1 21910 -1 21911 -1 21912 -1 21913 -1 21914 -1 21915 -1 21916 -1 21917 -1 21918 -1 21919 -1 21920 -1 21921 -1 21922 -1 21923 -1 21924 -1 21925 -1 21926 -1 21927 -1 21928 -1 21929 -1 21930 -1 21931 -1 21932 -1 21933 -1 21934 -1 21935 -1 21936 -1 21937 -1 21938 -1 21939 -1 21940 -1 21941 -1 21942 -1 21943 -1 21944 -1 21945 -1 21946 -1 21947 -1 21948 -1 21949 -1 21950 -1 21951 -1 21952 -1 21953 -1 21954 -1 21955 -1 21956 -1 21957 -1 21958 -1 21959 -1 21960 -1 21961 -1 21962 -1 21963 -1 21964 -1 21965 -1 21966 -1 21967 -1 21968 -1 21969 -1 21970 -1 21971 -1 21972 -1 21973 -1 21974 -1 21975 -1 21976 -1 21977 -1 21978 -1 21979 -1 21980 -1 21981 -1 21982 -1 21983 -1 21984 -1 21985 -1 21986 -1 21987 -1 21988 -1 21989 -1 21990 -1 21991 -1 21992 -1 21993 -1 21994 -1 21995 -1 21996 -1 21997 -1 21998 -1 21999 -1 22000 -1 22001 -1 22002 -1 22003 -1 22004 -1 22005 -1 22006 -1 22007 -1 22008 -1 22009 -1 22010 -1 22011 -1 22012 -1 22013 -1 22014 -1 22015 -1 22016 -1 22017 -1 22018 -1 22019 -1 22020 -1 22021 -1 22022 -1 22023 -1 22024 -1 22025 -1 22026 -1 22027 -1 22028 -1 22029 -1 22030 -1 22031 -1 22032 -1 22033 -1 22034 -1 22035 -1 22036 -1 22037 -1 22038 -1 22039 -1 22040 -1 22041 -1 22042 -1 22043 -1 22044 -1 22045 -1 22046 -1 22047 -1 22048 -1 22049 -1 22050 -1 22051 -1 22052 -1 22053 -1 22054 -1 22055 -1 22056 -1 22057 -1 22058 -1 22059 -1 22060 -1 22061 -1 22062 -1 22063 -1 22064 -1 22065 -1 22066 -1 22067 -1 22068 -1 22069 -1 22070 -1 22071 -1 22072 -1 22073 -1 22074 -1 22075 -1 22076 -1 22077 -1 22078 -1 22079 -1 22080 -1 22081 -1 22082 -1 22083 -1 22084 -1 22085 -1 22086 -1 22087 -1 22088 -1 22089 -1 22090 -1 22091 -1 22092 -1 22093 -1 22094 -1 22095 -1 22096 -1 22097 -1 22098 -1 22099 -1 22100 -1 22101 -1 22102 -1 22103 -1 22104 -1 22105 -1 22106 -1 22107 -1 22108 -1 22109 -1 22110 -1 22111 -1 22112 -1 22113 -1 22114 -1 22115 -1 22116 -1 22117 -1 22118 -1 22119 -1 22120 -1 22121 -1 22122 -1 22123 -1 22124 -1 22125 -1 22126 -1 22127 -1 22128 -1 22129 -1 22130 -1 22131 -1 22132 -1 22133 -1 22134 -1 22135 -1 22136 -1 22137 -1 22138 -1 22139 -1 22140 -1 22141 -1 22142 -1 22143 -1 22144 -1 22145 -1 22146 -1 22147 -1 22148 -1 22149 -1 22150 -1 22151 -1 22152 -1 22153 -1 22154 -1 22155 -1 22156 -1 22157 -1 22158 -1 22159 -1 22160 -1 22161 -1 22162 -1 22163 -1 22164 -1 22165 -1 22166 -1 22167 -1 22168 -1 22169 -1 22170 -1 22171 -1 22172 -1 22173 -1 22174 -1 22175 -1 22176 -1 22177 -1 22178 -1 22179 -1 22180 -1 22181 -1 22182 -1 22183 -1 22184 -1 22185 -1 22186 -1 22187 -1 22188 -1 22189 -1 22190 -1 22191 -1 22192 -1 22193 -1 22194 -1 22195 -1 22196 -1 22197 -1 22198 -1 22199 -1 22200 -1 22201 -1 22202 -1 22203 -1 22204 -1 22205 -1 22206 -1 22207 -1 22208 -1 22209 -1 22210 -1 22211 -1 22212 -1 22213 -1 22214 -1 22215 -1 22216 -1 22217 -1 22218 -1 22219 -1 22220 -1 22221 -1 22222 -1 22223 -1 22224 -1 22225 -1 22226 -1 22227 -1 22228 -1 22229 -1 22230 -1 22231 -1 22232 -1 22233 -1 22234 -1 22235 -1 22236 -1 22237 -1 22238 -1 22239 -1 22240 -1 22241 -1 22242 -1 22243 -1 22244 -1 22245 -1 22246 -1 22247 -1 22248 -1 22249 -1 22250 -1 22251 -1 22252 -1 22253 -1 22254 -1 22255 -1 22256 -1 22257 -1 22258 -1 22259 -1 22260 -1 22261 -1 22262 -1 22263 -1 22264 -1 22265 -1 22266 -1 22267 -1 22268 -1 22269 -1 22270 -1 22271 -1 22272 -1 22273 -1 22274 -1 22275 -1 22276 -1 22277 -1 22278 -1 22279 -1 22280 -1 22281 -1 22282 -1 22283 -1 22284 -1 22285 -1 22286 -1 22287 -1 22288 -1 22289 -1 22290 -1 22291 -1 22292 -1 22293 -1 22294 -1 22295 -1 22296 -1 22297 -1 22298 -1 22299 -1 22300 -1 22301 -1 22302 -1 22303 -1 22304 -1 22305 -1 22306 -1 22307 -1 22308 -1 22309 -1 22310 -1 22311 -1 22312 -1 22313 -1 22314 -1 22315 -1 22316 -1 22317 -1 22318 -1 22319 -1 22320 -1 22321 -1 22322 -1 22323 -1 22324 -1 22325 -1 22326 -1 22327 -1 22328 -1 22329 -1 22330 -1 22331 -1 22332 -1 22333 -1 22334 -1 22335 -1 22336 -1 22337 -1 22338 -1 22339 -1 22340 -1 22341 -1 22342 -1 22343 -1 22344 -1 22345 -1 22346 -1 22347 -1 22348 -1 22349 -1 22350 -1 22351 -1 22352 -1 22353 -1 22354 -1 22355 -1 22356 -1 22357 -1 22358 -1 22359 -1 22360 -1 22361 -1 22362 -1 22363 -1 22364 -1 22365 -1 22366 -1 22367 -1 22368 -1 22369 -1 22370 -1 22371 -1 22372 -1 22373 -1 22374 -1 22375 -1 22376 -1 22377 -1 22378 -1 22379 -1 22380 -1 22381 -1 22382 -1 22383 -1 22384 -1 22385 -1 22386 -1 22387 -1 22388 -1 22389 -1 22390 -1 22391 -1 22392 -1 22393 -1 22394 -1 22395 -1 22396 -1 22397 -1 22398 -1 22399 -1 22400 -1 22401 -1 22402 -1 22403 -1 22404 -1 22405 -1 22406 -1 22407 -1 22408 -1 22409 -1 22410 -1 22411 -1 22412 -1 22413 -1 22414 -1 22415 -1 22416 -1 22417 -1 22418 -1 22419 -1 22420 -1 22421 -1 22422 -1 22423 -1 22424 -1 22425 -1 22426 -1 22427 -1 22428 -1 22429 -1 22430 -1 22431 -1 22432 -1 22433 -1 22434 -1 22435 -1 22436 -1 22437 -1 22438 -1 22439 -1 22440 -1 22441 -1 22442 -1 22443 -1 22444 -1 22445 -1 22446 -1 22447 -1 22448 -1 22449 -1 22450 -1 22451 -1 22452 -1 22453 -1 22454 -1 22455 -1 22456 -1 22457 -1 22458 -1 22459 -1 22460 -1 22461 -1 22462 -1 22463 -1 22464 -1 22465 -1 22466 -1 22467 -1 22468 -1 22469 -1 22470 -1 22471 -1 22472 -1 22473 -1 22474 -1 22475 -1 22476 -1 22477 -1 22478 -1 22479 -1 22480 -1 22481 -1 22482 -1 22483 -1 22484 -1 22485 -1 22486 -1 22487 -1 22488 -1 22489 -1 22490 -1 22491 -1 22492 -1 22493 -1 22494 -1 22495 -1 22496 -1 22497 -1 22498 -1 22499 -1 22500 -1 22501 -1 22502 -1 22503 -1 22504 -1 22505 -1 22506 -1 22507 -1 22508 -1 22509 -1 22510 -1 22511 -1 22512 -1 22513 -1 22514 -1 22515 -1 22516 -1 22517 -1 22518 -1 22519 -1 22520 -1 22521 -1 22522 -1 22523 -1 22524 -1 22525 -1 22526 -1 22527 -1 22528 -1 22529 -1 22530 -1 22531 -1 22532 -1 22533 -1 22534 -1 22535 -1 22536 -1 22537 -1 22538 -1 22539 -1 22540 -1 22541 -1 22542 -1 22543 -1 22544 -1 22545 -1 22546 -1 22547 -1 22548 -1 22549 -1 22550 -1 22551 -1 22552 -1 22553 -1 22554 -1 22555 -1 22556 -1 22557 -1 22558 -1 22559 -1 22560 -1 22561 -1 22562 -1 22563 -1 22564 -1 22565 -1 22566 -1 22567 -1 22568 -1 22569 -1 22570 -1 22571 -1 22572 -1 22573 -1 22574 -1 22575 -1 22576 -1 22577 -1 22578 -1 22579 -1 22580 -1 22581 -1 22582 -1 22583 -1 22584 -1 22585 -1 22586 -1 22587 -1 22588 -1 22589 -1 22590 -1 22591 -1 22592 -1 22593 -1 22594 -1 22595 -1 22596 -1 22597 -1 22598 -1 22599 -1 22600 -1 22601 -1 22602 -1 22603 -1 22604 -1 22605 -1 22606 -1 22607 -1 22608 -1 22609 -1 22610 -1 22611 -1 22612 -1 22613 -1 22614 -1 22615 -1 22616 -1 22617 -1 22618 -1 22619 -1 22620 -1 22621 -1 22622 -1 22623 -1 22624 -1 22625 -1 22626 -1 22627 -1 22628 -1 22629 -1 22630 -1 22631 -1 22632 -1 22633 -1 22634 -1 22635 -1 22636 -1 22637 -1 22638 -1 22639 -1 22640 -1 22641 -1 22642 -1 22643 -1 22644 -1 22645 -1 22646 -1 22647 -1 22648 -1 22649 -1 22650 -1 22651 -1 22652 -1 22653 -1 22654 -1 22655 -1 22656 -1 22657 -1 22658 -1 22659 -1 22660 -1 22661 -1 22662 -1 22663 -1 22664 -1 22665 -1 22666 -1 22667 -1 22668 -1 22669 -1 22670 -1 22671 -1 22672 -1 22673 -1 22674 -1 22675 -1 22676 -1 22677 -1 22678 -1 22679 -1 22680 -1 22681 -1 22682 -1 22683 -1 22684 -1 22685 -1 22686 -1 22687 -1 22688 -1 22689 -1 22690 -1 22691 -1 22692 -1 22693 -1 22694 -1 22695 -1 22696 -1 22697 -1 22698 -1 22699 -1 22700 -1 22701 -1 22702 -1 22703 -1 22704 -1 22705 -1 22706 -1 22707 -1 22708 -1 22709 -1 22710 -1 22711 -1 22712 -1 22713 -1 22714 -1 22715 -1 22716 -1 22717 -1 22718 -1 22719 -1 22720 -1 22721 -1 22722 -1 22723 -1 22724 -1 22725 -1 22726 -1 22727 -1 22728 -1 22729 -1 22730 -1 22731 -1 22732 -1 22733 -1 22734 -1 22735 -1 22736 -1 22737 -1 22738 -1 22739 -1 22740 -1 22741 -1 22742 -1 22743 -1 22744 -1 22745 -1 22746 -1 22747 -1 22748 -1 22749 -1 22750 -1 22751 -1 22752 -1 22753 -1 22754 -1 22755 -1 22756 -1 22757 -1 22758 -1 22759 -1 22760 -1 22761 -1 22762 -1 22763 -1 22764 -1 22765 -1 22766 -1 22767 -1 22768 -1 22769 -1 22770 -1 22771 -1 22772 -1 22773 -1 22774 -1 22775 -1 22776 -1 22777 -1 22778 -1 22779 -1 22780 -1 22781 -1 22782 -1 22783 -1 22784 -1 22785 -1 22786 -1 22787 -1 22788 -1 22789 -1 22790 -1 22791 -1 22792 -1 22793 -1 22794 -1 22795 -1 22796 -1 22797 -1 22798 -1 22799 -1 22800 -1 22801 -1 22802 -1 22803 -1 22804 -1 22805 -1 22806 -1 22807 -1 22808 -1 22809 -1 22810 -1 22811 -1 22812 -1 22813 -1 22814 -1 22815 -1 22816 -1 22817 -1 22818 -1 22819 -1 22820 -1 22821 -1 22822 -1 22823 -1 22824 -1 22825 -1 22826 -1 22827 -1 22828 -1 22829 -1 22830 -1 22831 -1 22832 -1 22833 -1 22834 -1 22835 -1 22836 -1 22837 -1 22838 -1 22839 -1 22840 -1 22841 -1 22842 -1 22843 -1 22844 -1 22845 -1 22846 -1 22847 -1 22848 -1 22849 -1 22850 -1 22851 -1 22852 -1 22853 -1 22854 -1 22855 -1 22856 -1 22857 -1 22858 -1 22859 -1 22860 -1 22861 -1 22862 -1 22863 -1 22864 -1 22865 -1 22866 -1 22867 -1 22868 -1 22869 -1 22870 -1 22871 -1 22872 -1 22873 -1 22874 -1 22875 -1 22876 -1 22877 -1 22878 -1 22879 -1 22880 -1 22881 -1 22882 -1 22883 -1 22884 -1 22885 -1 22886 -1 22887 -1 22888 -1 22889 -1 22890 -1 22891 -1 22892 -1 22893 -1 22894 -1 22895 -1 22896 -1 22897 -1 22898 -1 22899 -1 22900 -1 22901 -1 22902 -1 22903 -1 22904 -1 22905 -1 22906 -1 22907 -1 22908 -1 22909 -1 22910 -1 22911 -1 22912 -1 22913 -1 22914 -1 22915 -1 22916 -1 22917 -1 22918 -1 22919 -1 22920 -1 22921 -1 22922 -1 22923 -1 22924 -1 22925 -1 22926 -1 22927 -1 22928 -1 22929 -1 22930 -1 22931 -1 22932 -1 22933 -1 22934 -1 22935 -1 22936 -1 22937 -1 22938 -1 22939 -1 22940 -1 22941 -1 22942 -1 22943 -1 22944 -1 22945 -1 22946 -1 22947 -1 22948 -1 22949 -1 22950 -1 22951 -1 22952 -1 22953 -1 22954 -1 22955 -1 22956 -1 22957 -1 22958 -1 22959 -1 22960 -1 22961 -1 22962 -1 22963 -1 22964 -1 22965 -1 22966 -1 22967 -1 22968 -1 22969 -1 22970 -1 22971 -1 22972 -1 22973 -1 22974 -1 22975 -1 22976 -1 22977 -1 22978 -1 22979 -1 22980 -1 22981 -1 22982 -1 22983 -1 22984 -1 22985 -1 22986 -1 22987 -1 22988 -1 22989 -1 22990 -1 22991 -1 22992 -1 22993 -1 22994 -1 22995 -1 22996 -1 22997 -1 22998 -1 22999 -1 23000 -1 23001 -1 23002 -1 23003 -1 23004 -1 23005 -1 23006 -1 23007 -1 23008 -1 23009 -1 23010 -1 23011 -1 23012 -1 23013 -1 23014 -1 23015 -1 23016 -1 23017 -1 23018 -1 23019 -1 23020 -1 23021 -1 23022 -1 23023 -1 23024 -1 23025 -1 23026 -1 23027 -1 23028 -1 23029 -1 23030 -1 23031 -1 23032 -1 23033 -1 23034 -1 23035 -1 23036 -1 23037 -1 23038 -1 23039 -1 23040 -1 23041 -1 23042 -1 23043 -1 23044 -1 23045 -1 23046 -1 23047 -1 23048 -1 23049 -1 23050 -1 23051 -1 23052 -1 23053 -1 23054 -1 23055 -1 23056 -1 23057 -1 23058 -1 23059 -1 23060 -1 23061 -1 23062 -1 23063 -1 23064 -1 23065 -1 23066 -1 23067 -1 23068 -1 23069 -1 23070 -1 23071 -1 23072 -1 23073 -1 23074 -1 23075 -1 23076 -1 23077 -1 23078 -1 23079 -1 23080 -1 23081 -1 23082 -1 23083 -1 23084 -1 23085 -1 23086 -1 23087 -1 23088 -1 23089 -1 23090 -1 23091 -1 23092 -1 23093 -1 23094 -1 23095 -1 23096 -1 23097 -1 23098 -1 23099 -1 23100 -1 23101 -1 23102 -1 23103 -1 23104 -1 23105 -1 23106 -1 23107 -1 23108 -1 23109 -1 23110 -1 23111 -1 23112 -1 23113 -1 23114 -1 23115 -1 23116 -1 23117 -1 23118 -1 23119 -1 23120 -1 23121 -1 23122 -1 23123 -1 23124 -1 23125 -1 23126 -1 23127 -1 23128 -1 23129 -1 23130 -1 23131 -1 23132 -1 23133 -1 23134 -1 23135 -1 23136 -1 23137 -1 23138 -1 23139 -1 23140 -1 23141 -1 23142 -1 23143 -1 23144 -1 23145 -1 23146 -1 23147 -1 23148 -1 23149 -1 23150 -1 23151 -1 23152 -1 23153 -1 23154 -1 23155 -1 23156 -1 23157 -1 23158 -1 23159 -1 23160 -1 23161 -1 23162 -1 23163 -1 23164 -1 23165 -1 23166 -1 23167 -1 23168 -1 23169 -1 23170 -1 23171 -1 23172 -1 23173 -1 23174 -1 23175 -1 23176 -1 23177 -1 23178 -1 23179 -1 23180 -1 23181 -1 23182 -1 23183 -1 23184 -1 23185 -1 23186 -1 23187 -1 23188 -1 23189 -1 23190 -1 23191 -1 23192 -1 23193 -1 23194 -1 23195 -1 23196 -1 23197 -1 23198 -1 23199 -1 23200 -1 23201 -1 23202 -1 23203 -1 23204 -1 23205 -1 23206 -1 23207 -1 23208 -1 23209 -1 23210 -1 23211 -1 23212 -1 23213 -1 23214 -1 23215 -1 23216 -1 23217 -1 23218 -1 23219 -1 23220 -1 23221 -1 23222 -1 23223 -1 23224 -1 23225 -1 23226 -1 23227 -1 23228 -1 23229 -1 23230 -1 23231 -1 23232 -1 23233 -1 23234 -1 23235 -1 23236 -1 23237 -1 23238 -1 23239 -1 23240 -1 23241 -1 23242 -1 23243 -1 23244 -1 23245 -1 23246 -1 23247 -1 23248 -1 23249 -1 23250 -1 23251 -1 23252 -1 23253 -1 23254 -1 23255 -1 23256 -1 23257 -1 23258 -1 23259 -1 23260 -1 23261 -1 23262 -1 23263 -1 23264 -1 23265 -1 23266 -1 23267 -1 23268 -1 23269 -1 23270 -1 23271 -1 23272 -1 23273 -1 23274 -1 23275 -1 23276 -1 23277 -1 23278 -1 23279 -1 23280 -1 23281 -1 23282 -1 23283 -1 23284 -1 23285 -1 23286 -1 23287 -1 23288 -1 23289 -1 23290 -1 23291 -1 23292 -1 23293 -1 23294 -1 23295 -1 23296 -1 23297 -1 23298 -1 23299 -1 23300 -1 23301 -1 23302 -1 23303 -1 23304 -1 23305 -1 23306 -1 23307 -1 23308 -1 23309 -1 23310 -1 23311 -1 23312 -1 23313 -1 23314 -1 23315 -1 23316 -1 23317 -1 23318 -1 23319 -1 23320 -1 23321 -1 23322 -1 23323 -1 23324 -1 23325 -1 23326 -1 23327 -1 23328 -1 23329 -1 23330 -1 23331 -1 23332 -1 23333 -1 23334 -1 23335 -1 23336 -1 23337 -1 23338 -1 23339 -1 23340 -1 23341 -1 23342 -1 23343 -1 23344 -1 23345 -1 23346 -1 23347 -1 23348 -1 23349 -1 23350 -1 23351 -1 23352 -1 23353 -1 23354 -1 23355 -1 23356 -1 23357 -1 23358 -1 23359 -1 23360 -1 23361 -1 23362 -1 23363 -1 23364 -1 23365 -1 23366 -1 23367 -1 23368 -1 23369 -1 23370 -1 23371 -1 23372 -1 23373 -1 23374 -1 23375 -1 23376 -1 23377 -1 23378 -1 23379 -1 23380 -1 23381 -1 23382 -1 23383 -1 23384 -1 23385 -1 23386 -1 23387 -1 23388 -1 23389 -1 23390 -1 23391 -1 23392 -1 23393 -1 23394 -1 23395 -1 23396 -1 23397 -1 23398 -1 23399 -1 23400 -1 23401 -1 23402 -1 23403 -1 23404 -1 23405 -1 23406 -1 23407 -1 23408 -1 23409 -1 23410 -1 23411 -1 23412 -1 23413 -1 23414 -1 23415 -1 23416 -1 23417 -1 23418 -1 23419 -1 23420 -1 23421 -1 23422 -1 23423 -1 23424 -1 23425 -1 23426 -1 23427 -1 23428 -1 23429 -1 23430 -1 23431 -1 23432 -1 23433 -1 23434 -1 23435 -1 23436 -1 23437 -1 23438 -1 23439 -1 23440 -1 23441 -1 23442 -1 23443 -1 23444 -1 23445 -1 23446 -1 23447 -1 23448 -1 23449 -1 23450 -1 23451 -1 23452 -1 23453 -1 23454 -1 23455 -1 23456 -1 23457 -1 23458 -1 23459 -1 23460 -1 23461 -1 23462 -1 23463 -1 23464 -1 23465 -1 23466 -1 23467 -1 23468 -1 23469 -1 23470 -1 23471 -1 23472 -1 23473 -1 23474 -1 23475 -1 23476 -1 23477 -1 23478 -1 23479 -1 23480 -1 23481 -1 23482 -1 23483 -1 23484 -1 23485 -1 23486 -1 23487 -1 23488 -1 23489 -1 23490 -1 23491 -1 23492 -1 23493 -1 23494 -1 23495 -1 23496 -1 23497 -1 23498 -1 23499 -1 23500 -1 23501 -1 23502 -1 23503 -1 23504 -1 23505 -1 23506 -1 23507 -1 23508 -1 23509 -1 23510 -1 23511 -1 23512 -1 23513 -1 23514 -1 23515 -1 23516 -1 23517 -1 23518 -1 23519 -1 23520 -1 23521 -1 23522 -1 23523 -1 23524 -1 23525 -1 23526 -1 23527 -1 23528 -1 23529 -1 23530 -1 23531 -1 23532 -1 23533 -1 23534 -1 23535 -1 23536 -1 23537 -1 23538 -1 23539 -1 23540 -1 23541 -1 23542 -1 23543 -1 23544 -1 23545 -1 23546 -1 23547 -1 23548 -1 23549 -1 23550 -1 23551 -1 23552 -1 23553 -1 23554 -1 23555 -1 23556 -1 23557 -1 23558 -1 23559 -1 23560 -1 23561 -1 23562 -1 23563 -1 23564 -1 23565 -1 23566 -1 23567 -1 23568 -1 23569 -1 23570 -1 23571 -1 23572 -1 23573 -1 23574 -1 23575 -1 23576 -1 23577 -1 23578 -1 23579 -1 23580 -1 23581 -1 23582 -1 23583 -1 23584 -1 23585 -1 23586 -1 23587 -1 23588 -1 23589 -1 23590 -1 23591 -1 23592 -1 23593 -1 23594 -1 23595 -1 23596 -1 23597 -1 23598 -1 23599 -1 23600 -1 23601 -1 23602 -1 23603 -1 23604 -1 23605 -1 23606 -1 23607 -1 23608 -1 23609 -1 23610 -1 23611 -1 23612 -1 23613 -1 23614 -1 23615 -1 23616 -1 23617 -1 23618 -1 23619 -1 23620 -1 23621 -1 23622 -1 23623 -1 23624 -1 23625 -1 23626 -1 23627 -1 23628 -1 23629 -1 23630 -1 23631 -1 23632 -1 23633 -1 23634 -1 23635 -1 23636 -1 23637 -1 23638 -1 23639 -1 23640 -1 23641 -1 23642 -1 23643 -1 23644 -1 23645 -1 23646 -1 23647 -1 23648 -1 23649 -1 23650 -1 23651 -1 23652 -1 23653 -1 23654 -1 23655 -1 23656 -1 23657 -1 23658 -1 23659 -1 23660 -1 23661 -1 23662 -1 23663 -1 23664 -1 23665 -1 23666 -1 23667 -1 23668 -1 23669 -1 23670 -1 23671 -1 23672 -1 23673 -1 23674 -1 23675 -1 23676 -1 23677 -1 23678 -1 23679 -1 23680 -1 23681 -1 23682 -1 23683 -1 23684 -1 23685 -1 23686 -1 23687 -1 23688 -1 23689 -1 23690 -1 23691 -1 23692 -1 23693 -1 23694 -1 23695 -1 23696 -1 23697 -1 23698 -1 23699 -1 23700 -1 23701 -1 23702 -1 23703 -1 23704 -1 23705 -1 23706 -1 23707 -1 23708 -1 23709 -1 23710 -1 23711 -1 23712 -1 23713 -1 23714 -1 23715 -1 23716 -1 23717 -1 23718 -1 23719 -1 23720 -1 23721 -1 23722 -1 23723 -1 23724 -1 23725 -1 23726 -1 23727 -1 23728 -1 23729 -1 23730 -1 23731 -1 23732 -1 23733 -1 23734 -1 23735 -1 23736 -1 23737 -1 23738 -1 23739 -1 23740 -1 23741 -1 23742 -1 23743 -1 23744 -1 23745 -1 23746 -1 23747 -1 23748 -1 23749 -1 23750 -1 23751 -1 23752 -1 23753 -1 23754 -1 23755 -1 23756 -1 23757 -1 23758 -1 23759 -1 23760 -1 23761 -1 23762 -1 23763 -1 23764 -1 23765 -1 23766 -1 23767 -1 23768 -1 23769 -1 23770 -1 23771 -1 23772 -1 23773 -1 23774 -1 23775 -1 23776 -1 23777 -1 23778 -1 23779 -1 23780 -1 23781 -1 23782 -1 23783 -1 23784 -1 23785 -1 23786 -1 23787 -1 23788 -1 23789 -1 23790 -1 23791 -1 23792 -1 23793 -1 23794 -1 23795 -1 23796 -1 23797 -1 23798 -1 23799 -1 23800 -1 23801 -1 23802 -1 23803 -1 23804 -1 23805 -1 23806 -1 23807 -1 23808 -1 23809 -1 23810 -1 23811 -1 23812 -1 23813 -1 23814 -1 23815 -1 23816 -1 23817 -1 23818 -1 23819 -1 23820 -1 23821 -1 23822 -1 23823 -1 23824 -1 23825 -1 23826 -1 23827 -1 23828 -1 23829 -1 23830 -1 23831 -1 23832 -1 23833 -1 23834 -1 23835 -1 23836 -1 23837 -1 23838 -1 23839 -1 23840 -1 23841 -1 23842 -1 23843 -1 23844 -1 23845 -1 23846 -1 23847 -1 23848 -1 23849 -1 23850 -1 23851 -1 23852 -1 23853 -1 23854 -1 23855 -1 23856 -1 23857 -1 23858 -1 23859 -1 23860 -1 23861 -1 23862 -1 23863 -1 23864 -1 23865 -1 23866 -1 23867 -1 23868 -1 23869 -1 23870 -1 23871 -1 23872 -1 23873 -1 23874 -1 23875 -1 23876 -1 23877 -1 23878 -1 23879 -1 23880 -1 23881 -1 23882 -1 23883 -1 23884 -1 23885 -1 23886 -1 23887 -1 23888 -1 23889 -1 23890 -1 23891 -1 23892 -1 23893 -1 23894 -1 23895 -1 23896 -1 23897 -1 23898 -1 23899 -1 23900 -1 23901 -1 23902 -1 23903 -1 23904 -1 23905 -1 23906 -1 23907 -1 23908 -1 23909 -1 23910 -1 23911 -1 23912 -1 23913 -1 23914 -1 23915 -1 23916 -1 23917 -1 23918 -1 23919 -1 23920 -1 23921 -1 23922 -1 23923 -1 23924 -1 23925 -1 23926 -1 23927 -1 23928 -1 23929 -1 23930 -1 23931 -1 23932 -1 23933 -1 23934 -1 23935 -1 23936 -1 23937 -1 23938 -1 23939 -1 23940 -1 23941 -1 23942 -1 23943 -1 23944 -1 23945 -1 23946 -1 23947 -1 23948 -1 23949 -1 23950 -1 23951 -1 23952 -1 23953 -1 23954 -1 23955 -1 23956 -1 23957 -1 23958 -1 23959 -1 23960 -1 23961 -1 23962 -1 23963 -1 23964 -1 23965 -1 23966 -1 23967 -1 23968 -1 23969 -1 23970 -1 23971 -1 23972 -1 23973 -1 23974 -1 23975 -1 23976 -1 23977 -1 23978 -1 23979 -1 23980 -1 23981 -1 23982 -1 23983 -1 23984 -1 23985 -1 23986 -1 23987 -1 23988 -1 23989 -1 23990 -1 23991 -1 23992 -1 23993 -1 23994 -1 23995 -1 23996 -1 23997 -1 23998 -1 23999 -1 24000 -1 24001 -1 24002 -1 24003 -1 24004 -1 24005 -1 24006 -1 24007 -1 24008 -1 24009 -1 24010 -1 24011 -1 24012 -1 24013 -1 24014 -1 24015 -1 24016 -1 24017 -1 24018 -1 24019 -1 24020 -1 24021 -1 24022 -1 24023 -1 24024 -1 24025 -1 24026 -1 24027 -1 24028 -1 24029 -1 24030 -1 24031 -1 24032 -1 24033 -1 24034 -1 24035 -1 24036 -1 24037 -1 24038 -1 24039 -1 24040 -1 24041 -1 24042 -1 24043 -1 24044 -1 24045 -1 24046 -1 24047 -1 24048 -1 24049 -1 24050 -1 24051 -1 24052 -1 24053 -1 24054 -1 24055 -1 24056 -1 24057 -1 24058 -1 24059 -1 24060 -1 24061 -1 24062 -1 24063 -1 24064 -1 24065 -1 24066 -1 24067 -1 24068 -1 24069 -1 24070 -1 24071 -1 24072 -1 24073 -1 24074 -1 24075 -1 24076 -1 24077 -1 24078 -1 24079 -1 24080 -1 24081 -1 24082 -1 24083 -1 24084 -1 24085 -1 24086 -1 24087 -1 24088 -1 24089 -1 24090 -1 24091 -1 24092 -1 24093 -1 24094 -1 24095 -1 24096 -1 24097 -1 24098 -1 24099 -1 24100 -1 24101 -1 24102 -1 24103 -1 24104 -1 24105 -1 24106 -1 24107 -1 24108 -1 24109 -1 24110 -1 24111 -1 24112 -1 24113 -1 24114 -1 24115 -1 24116 -1 24117 -1 24118 -1 24119 -1 24120 -1 24121 -1 24122 -1 24123 -1 24124 -1 24125 -1 24126 -1 24127 -1 24128 -1 24129 -1 24130 -1 24131 -1 24132 -1 24133 -1 24134 -1 24135 -1 24136 -1 24137 -1 24138 -1 24139 -1 24140 -1 24141 -1 24142 -1 24143 -1 24144 -1 24145 -1 24146 -1 24147 -1 24148 -1 24149 -1 24150 -1 24151 -1 24152 -1 24153 -1 24154 -1 24155 -1 24156 -1 24157 -1 24158 -1 24159 -1 24160 -1 24161 -1 24162 -1 24163 -1 24164 -1 24165 -1 24166 -1 24167 -1 24168 -1 24169 -1 24170 -1 24171 -1 24172 -1 24173 -1 24174 -1 24175 -1 24176 -1 24177 -1 24178 -1 24179 -1 24180 -1 24181 -1 24182 -1 24183 -1 24184 -1 24185 -1 24186 -1 24187 -1 24188 -1 24189 -1 24190 -1 24191 -1 24192 -1 24193 -1 24194 -1 24195 -1 24196 -1 24197 -1 24198 -1 24199 -1 24200 -1 24201 -1 24202 -1 24203 -1 24204 -1 24205 -1 24206 -1 24207 -1 24208 -1 24209 -1 24210 -1 24211 -1 24212 -1 24213 -1 24214 -1 24215 -1 24216 -1 24217 -1 24218 -1 24219 -1 24220 -1 24221 -1 24222 -1 24223 -1 24224 -1 24225 -1 24226 -1 24227 -1 24228 -1 24229 -1 24230 -1 24231 -1 24232 -1 24233 -1 24234 -1 24235 -1 24236 -1 24237 -1 24238 -1 24239 -1 24240 -1 24241 -1 24242 -1 24243 -1 24244 -1 24245 -1 24246 -1 24247 -1 24248 -1 24249 -1 24250 -1 24251 -1 24252 -1 24253 -1 24254 -1 24255 -1 24256 -1 24257 -1 24258 -1 24259 -1 24260 -1 24261 -1 24262 -1 24263 -1 24264 -1 24265 -1 24266 -1 24267 -1 24268 -1 24269 -1 24270 -1 24271 -1 24272 -1 24273 -1 24274 -1 24275 -1 24276 -1 24277 -1 24278 -1 24279 -1 24280 -1 24281 -1 24282 -1 24283 -1 24284 -1 24285 -1 24286 -1 24287 -1 24288 -1 24289 -1 24290 -1 24291 -1 24292 -1 24293 -1 24294 -1 24295 -1 24296 -1 24297 -1 24298 -1 24299 -1 24300 -1 24301 -1 24302 -1 24303 -1 24304 -1 24305 -1 24306 -1 24307 -1 24308 -1 24309 -1 24310 -1 24311 -1 24312 -1 24313 -1 24314 -1 24315 -1 24316 -1 24317 -1 24318 -1 24319 -1 24320 -1 24321 -1 24322 -1 24323 -1 24324 -1 24325 -1 24326 -1 24327 -1 24328 -1 24329 -1 24330 -1 24331 -1 24332 -1 24333 -1 24334 -1 24335 -1 24336 -1 24337 -1 24338 -1 24339 -1 24340 -1 24341 -1 24342 -1 24343 -1 24344 -1 24345 -1 24346 -1 24347 -1 24348 -1 24349 -1 24350 -1 24351 -1 24352 -1 24353 -1 24354 -1 24355 -1 24356 -1 24357 -1 24358 -1 24359 -1 24360 -1 24361 -1 24362 -1 24363 -1 24364 -1 24365 -1 24366 -1 24367 -1 24368 -1 24369 -1 24370 -1 24371 -1 24372 -1 24373 -1 24374 -1 24375 -1 24376 -1 24377 -1 24378 -1 24379 -1 24380 -1 24381 -1 24382 -1 24383 -1 24384 -1 24385 -1 24386 -1 24387 -1 24388 -1 24389 -1 24390 -1 24391 -1 24392 -1 24393 -1 24394 -1 24395 -1 24396 -1 24397 -1 24398 -1 24399 -1 24400 -1 24401 -1 24402 -1 24403 -1 24404 -1 24405 -1 24406 -1 24407 -1 24408 -1 24409 -1 24410 -1 24411 -1 24412 -1 24413 -1 24414 -1 24415 -1 24416 -1 24417 -1 24418 -1 24419 -1 24420 -1 24421 -1 24422 -1 24423 -1 24424 -1 24425 -1 24426 -1 24427 -1 24428 -1 24429 -1 24430 -1 24431 -1 24432 -1 24433 -1 24434 -1 24435 -1 24436 -1 24437 -1 24438 -1 24439 -1 24440 -1 24441 -1 24442 -1 24443 -1 24444 -1 24445 -1 24446 -1 24447 -1 24448 -1 24449 -1 24450 -1 24451 -1 24452 -1 24453 -1 24454 -1 24455 -1 24456 -1 24457 -1 24458 -1 24459 -1 24460 -1 24461 -1 24462 -1 24463 -1 24464 -1 24465 -1 24466 -1 24467 -1 24468 -1 24469 -1 24470 -1 24471 -1 24472 -1 24473 -1 24474 -1 24475 -1 24476 -1 24477 -1 24478 -1 24479 -1 24480 -1 24481 -1 24482 -1 24483 -1 24484 -1 24485 -1 24486 -1 24487 -1 24488 -1 24489 -1 24490 -1 24491 -1 24492 -1 24493 -1 24494 -1 24495 -1 24496 -1 24497 -1 24498 -1 24499 -1 24500 -1 24501 -1 24502 -1 24503 -1 24504 -1 24505 -1 24506 -1 24507 -1 24508 -1 24509 -1 24510 -1 24511 -1 24512 -1 24513 -1 24514 -1 24515 -1 24516 -1 24517 -1 24518 -1 24519 -1 24520 -1 24521 -1 24522 -1 24523 -1 24524 -1 24525 -1 24526 -1 24527 -1 24528 -1 24529 -1 24530 -1 24531 -1 24532 -1 24533 -1 24534 -1 24535 -1 24536 -1 24537 -1 24538 -1 24539 -1 24540 -1 24541 -1 24542 -1 24543 -1 24544 -1 24545 -1 24546 -1 24547 -1 24548 -1 24549 -1 24550 -1 24551 -1 24552 -1 24553 -1 24554 -1 24555 -1 24556 -1 24557 -1 24558 -1 24559 -1 24560 -1 24561 -1 24562 -1 24563 -1 24564 -1 24565 -1 24566 -1 24567 -1 24568 -1 24569 -1 24570 -1 24571 -1 24572 -1 24573 -1 24574 -1 24575 -1 24576 -1 24577 -1 24578 -1 24579 -1 24580 -1 24581 -1 24582 -1 24583 -1 24584 -1 24585 -1 24586 -1 24587 -1 24588 -1 24589 -1 24590 -1 24591 -1 24592 -1 24593 -1 24594 -1 24595 -1 24596 -1 24597 -1 24598 -1 24599 -1 24600 -1 24601 -1 24602 -1 24603 -1 24604 -1 24605 -1 24606 -1 24607 -1 24608 -1 24609 -1 24610 -1 24611 -1 24612 -1 24613 -1 24614 -1 24615 -1 24616 -1 24617 -1 24618 -1 24619 -1 24620 -1 24621 -1 24622 -1 24623 -1 24624 -1 24625 -1 24626 -1 24627 -1 24628 -1 24629 -1 24630 -1 24631 -1 24632 -1 24633 -1 24634 -1 24635 -1 24636 -1 24637 -1 24638 -1 24639 -1 24640 -1 24641 -1 24642 -1 24643 -1 24644 -1 24645 -1 24646 -1 24647 -1 24648 -1 24649 -1 24650 -1 24651 -1 24652 -1 24653 -1 24654 -1 24655 -1 24656 -1 24657 -1 24658 -1 24659 -1 24660 -1 24661 -1 24662 -1 24663 -1 24664 -1 24665 -1 24666 -1 24667 -1 24668 -1 24669 -1 24670 -1 24671 -1 24672 -1 24673 -1 24674 -1 24675 -1 24676 -1 24677 -1 24678 -1 24679 -1 24680 -1 24681 -1 24682 -1 24683 -1 24684 -1 24685 -1 24686 -1 24687 -1 24688 -1 24689 -1 24690 -1 24691 -1 24692 -1 24693 -1 24694 -1 24695 -1 24696 -1 24697 -1 24698 -1 24699 -1 24700 -1 24701 -1 24702 -1 24703 -1 24704 -1 24705 -1 24706 -1 24707 -1 24708 -1 24709 -1 24710 -1 24711 -1 24712 -1 24713 -1 24714 -1 24715 -1 24716 -1 24717 -1 24718 -1 24719 -1 24720 -1 24721 -1 24722 -1 24723 -1 24724 -1 24725 -1 24726 -1 24727 -1 24728 -1 24729 -1 24730 -1 24731 -1 24732 -1 24733 -1 24734 -1 24735 -1 24736 -1 24737 -1 24738 -1 24739 -1 24740 -1 24741 -1 24742 -1 24743 -1 24744 -1 24745 -1 24746 -1 24747 -1 24748 -1 24749 -1 24750 -1 24751 -1 24752 -1 24753 -1 24754 -1 24755 -1 24756 -1 24757 -1 24758 -1 24759 -1 24760 -1 24761 -1 24762 -1 24763 -1 24764 -1 24765 -1 24766 -1 24767 -1 24768 -1 24769 -1 24770 -1 24771 -1 24772 -1 24773 -1 24774 -1 24775 -1 24776 -1 24777 -1 24778 -1 24779 -1 24780 -1 24781 -1 24782 -1 24783 -1 24784 -1 24785 -1 24786 -1 24787 -1 24788 -1 24789 -1 24790 -1 24791 -1 24792 -1 24793 -1 24794 -1 24795 -1 24796 -1 24797 -1 24798 -1 24799 -1 24800 -1 24801 -1 24802 -1 24803 -1 24804 -1 24805 -1 24806 -1 24807 -1 24808 -1 24809 -1 24810 -1 24811 -1 24812 -1 24813 -1 24814 -1 24815 -1 24816 -1 24817 -1 24818 -1 24819 -1 24820 -1 24821 -1 24822 -1 24823 -1 24824 -1 24825 -1 24826 -1 24827 -1 24828 -1 24829 -1 24830 -1 24831 -1 24832 -1 24833 -1 24834 -1 24835 -1 24836 -1 24837 -1 24838 -1 24839 -1 24840 -1 24841 -1 24842 -1 24843 -1 24844 -1 24845 -1 24846 -1 24847 -1 24848 -1 24849 -1 24850 -1 24851 -1 24852 -1 24853 -1 24854 -1 24855 -1 24856 -1 24857 -1 24858 -1 24859 -1 24860 -1 24861 -1 24862 -1 24863 -1 24864 -1 24865 -1 24866 -1 24867 -1 24868 -1 24869 -1 24870 -1 24871 -1 24872 -1 24873 -1 24874 -1 24875 -1 24876 -1 24877 -1 24878 -1 24879 -1 24880 -1 24881 -1 24882 -1 24883 -1 24884 -1 24885 -1 24886 -1 24887 -1 24888 -1 24889 -1 24890 -1 24891 -1 24892 -1 24893 -1 24894 -1 24895 -1 24896 -1 24897 -1 24898 -1 24899 -1 24900 -1 24901 -1 24902 -1 24903 -1 24904 -1 24905 -1 24906 -1 24907 -1 24908 -1 24909 -1 24910 -1 24911 -1 24912 -1 24913 -1 24914 -1 24915 -1 24916 -1 24917 -1 24918 -1 24919 -1 24920 -1 24921 -1 24922 -1 24923 -1 24924 -1 24925 -1 24926 -1 24927 -1 24928 -1 24929 -1 24930 -1 24931 -1 24932 -1 24933 -1 24934 -1 24935 -1 24936 -1 24937 -1 24938 -1 24939 -1 24940 -1 24941 -1 24942 -1 24943 -1 24944 -1 24945 -1 24946 -1 24947 -1 24948 -1 24949 -1 24950 -1 24951 -1 24952 -1 24953 -1 24954 -1 24955 -1 24956 -1 24957 -1 24958 -1 24959 -1 24960 -1 24961 -1 24962 -1 24963 -1 24964 -1 24965 -1 24966 -1 24967 -1 24968 -1 24969 -1 24970 -1 24971 -1 24972 -1 24973 -1 24974 -1 24975 -1 24976 -1 24977 -1 24978 -1 24979 -1 24980 -1 24981 -1 24982 -1 24983 -1 24984 -1 24985 -1 24986 -1 24987 -1 24988 -1 24989 -1 24990 -1 24991 -1 24992 -1 24993 -1 24994 -1 24995 -1 24996 -1 24997 -1 24998 -1 24999 -1 25000 -1 25001 -1 25002 -1 25003 -1 25004 -1 25005 -1 25006 -1 25007 -1 25008 -1 25009 -1 25010 -1 25011 -1 25012 -1 25013 -1 25014 -1 25015 -1 25016 -1 25017 -1 25018 -1 25019 -1 25020 -1 25021 -1 25022 -1 25023 -1 25024 -1 25025 -1 25026 -1 25027 -1 25028 -1 25029 -1 25030 -1 25031 -1 25032 -1 25033 -1 25034 -1 25035 -1 25036 -1 25037 -1 25038 -1 25039 -1 25040 -1 25041 -1 25042 -1 25043 -1 25044 -1 25045 -1 25046 -1 25047 -1 25048 -1 25049 -1 25050 -1 25051 -1 25052 -1 25053 -1 25054 -1 25055 -1 25056 -1 25057 -1 25058 -1 25059 -1 25060 -1 25061 -1 25062 -1 25063 -1 25064 -1 25065 -1 25066 -1 25067 -1 25068 -1 25069 -1 25070 -1 25071 -1 25072 -1 25073 -1 25074 -1 25075 -1 25076 -1 25077 -1 25078 -1 25079 -1 25080 -1 25081 -1 25082 -1 25083 -1 25084 -1 25085 -1 25086 -1 25087 -1 25088 -1 25089 -1 25090 -1 25091 -1 25092 -1 25093 -1 25094 -1 25095 -1 25096 -1 25097 -1 25098 -1 25099 -1 25100 -1 25101 -1 25102 -1 25103 -1 25104 -1 25105 -1 25106 -1 25107 -1 25108 -1 25109 -1 25110 -1 25111 -1 25112 -1 25113 -1 25114 -1 25115 -1 25116 -1 25117 -1 25118 -1 25119 -1 25120 -1 25121 -1 25122 -1 25123 -1 25124 -1 25125 -1 25126 -1 25127 -1 25128 -1 25129 -1 25130 -1 25131 -1 25132 -1 25133 -1 25134 -1 25135 -1 25136 -1 25137 -1 25138 -1 25139 -1 25140 -1 25141 -1 25142 -1 25143 -1 25144 -1 25145 -1 25146 -1 25147 -1 25148 -1 25149 -1 25150 -1 25151 -1 25152 -1 25153 -1 25154 -1 25155 -1 25156 -1 25157 -1 25158 -1 25159 -1 25160 -1 25161 -1 25162 -1 25163 -1 25164 -1 25165 -1 25166 -1 25167 -1 25168 -1 25169 -1 25170 -1 25171 -1 25172 -1 25173 -1 25174 -1 25175 -1 25176 -1 25177 -1 25178 -1 25179 -1 25180 -1 25181 -1 25182 -1 25183 -1 25184 -1 25185 -1 25186 -1 25187 -1 25188 -1 25189 -1 25190 -1 25191 -1 25192 diff --git a/thirdparty/libpointmatcher/examples/data/cloud.00002.vtk b/thirdparty/libpointmatcher/examples/data/cloud.00002.vtk deleted file mode 100644 index ed59ff3..0000000 --- a/thirdparty/libpointmatcher/examples/data/cloud.00002.vtk +++ /dev/null @@ -1,48314 +0,0 @@ -# vtk DataFile Version 3.0 -data -ASCII -DATASET POLYDATA -POINTS 24154 float -2.61792 0.0335164 -1.01009 -2.68912 0.0344045 -1.00659 -2.76833 0.0355797 -1.00777 -2.84956 0.0367368 -1.00687 -2.9378 0.0382709 -1.01004 -3.02706 0.0398622 -1.01082 -3.11727 0.0405236 -1.00896 -3.22456 0.0426955 -1.01652 -3.31588 0.0445581 -1.00932 -3.42516 0.0459063 -1.01085 -3.53446 0.0474164 -1.00908 -3.66179 0.0494629 -1.01499 -3.79015 0.051645 -1.01691 -3.92848 0.053163 -1.02008 -4.07691 0.0560402 -1.02399 -4.21631 0.0579244 -1.01848 -4.39277 0.0608798 -1.02712 -4.56226 0.0637427 -1.02589 -4.76878 0.0667975 -1.03638 -4.97634 0.0701107 -1.04038 -5.20392 0.0731513 -1.04573 -5.41459 0.076955 -1.03606 -5.67226 0.0803599 -1.03786 -5.96004 0.0848466 -1.04185 -6.22986 0.0892138 -1.02967 -6.56782 0.0948186 -1.03091 -6.92684 0.100414 -1.0269 -7.35398 0.106515 -1.03087 -7.80327 0.11373 -1.02585 -8.35079 0.122541 -1.0308 -8.95848 0.131954 -1.03124 -9.61734 0.141776 -1.02179 -10.5719 0.156958 -1.04979 -11.6387 0.17301 -1.06499 -13.1617 0.196676 -1.1195 -14.7992 0.22225 -1.13766 -16.7777 0.252908 -1.14364 -20.1596 0.305612 -1.24076 -24.2829 0.369708 -0.872694 -24.8715 0.379147 -0.491417 -25.063 0.382293 -0.0732628 -24.9588 0.379924 0.358807 -26.3457 0.401987 0.773724 -25.0663 0.381725 1.21373 -23.3695 0.355835 1.59823 -21.0174 0.319055 1.89541 -20.7593 0.314554 2.23868 -20.3257 0.308531 2.55998 -20.0074 0.30341 2.87803 -21.1539 0.320903 3.35294 -19.6124 0.296716 3.51596 -20.9899 0.318827 4.06201 -21.7223 0.329942 4.5512 -21.8928 0.33213 4.96477 -20.8307 0.316514 5.1362 -20.6679 0.313865 5.47103 -18.9238 0.286446 5.42324 -18.3501 0.277514 5.61643 -17.9591 0.271183 5.84179 -17.8523 0.269359 6.14009 -18.5037 0.279693 6.67672 -21.6735 0.329578 8.08467 -20.8116 0.315787 8.19286 -26.8545 0.409751 10.854 -19.85 0.300891 8.62259 -21.3029 0.323646 9.61727 -21.1774 0.321682 9.99111 -22.4821 0.34196 11.0182 -22.1687 0.336517 11.3358 -20.5355 0.311676 10.9897 -20.7387 0.314478 11.5364 -20.7279 0.314233 11.9835 -21.3949 0.324576 12.8224 -4.7127 0.0655474 3.4817 -4.45574 0.0621687 3.42422 -4.3787 0.0601381 3.47148 -4.30171 0.0590064 3.5167 -4.29013 0.0590845 3.6053 -4.17084 0.0569314 3.61886 -4.2217 0.058548 3.75384 -4.24429 0.0580886 3.87324 -4.16931 0.0568849 3.91944 -4.17995 0.0579085 4.03395 -4.16437 0.0576045 4.13021 -4.1397 0.0565344 4.22016 -4.04562 0.055642 4.24938 -4.19928 0.0572994 4.51042 -4.23719 0.0580365 4.67258 -4.15824 0.0572809 4.723 -4.03085 0.0548469 4.72102 -4.19483 0.0573941 5.03279 -3.93137 0.053667 4.87946 -3.82512 0.0517338 4.89311 -3.86418 0.0527084 5.08168 -3.73071 0.0507467 5.0616 -3.61638 0.0486355 5.06181 -3.55655 0.0476913 5.13171 -3.44929 0.0463349 5.13553 -3.36017 0.0449926 5.16173 -3.45794 0.0463245 5.46947 -3.4709 0.0461519 5.66382 -3.52441 0.0474235 5.93667 -3.46879 0.0468982 6.04036 -3.41516 0.0456621 6.15238 -3.09038 0.0403888 5.77183 -2.85454 0.0373098 5.52363 -2.87371 0.0368846 5.76089 -2.75525 0.0354593 5.72945 -2.66003 0.0337493 5.7408 -2.55366 0.03226 5.72279 -2.32545 0.0283666 5.40679 -2.31344 0.0289115 5.6054 -2.28924 0.0283077 5.78624 -2.24885 0.0273039 5.9393 -2.43248 0.03058 6.77513 -2.00334 0.0236325 5.7685 -1.87739 0.021359 5.65016 -1.76363 0.0196444 5.55792 -1.74382 0.0193788 5.8116 -1.69964 0.0192487 5.99789 -1.74886 0.0196942 6.63316 -1.38459 0.0142135 5.35082 -1.27235 0.0119752 5.16898 -1.19821 0.0115827 5.17189 -1.13232 0.010565 5.23293 -1.08939 0.00942799 5.48133 -1.05101 0.00840116 5.83863 -0.975312 0.0078247 5.93707 -0.889103 0.00638536 5.94463 -0.788703 0.0043758 5.72114 -0.703236 0.00376842 5.66548 -0.625715 0.00249526 5.80833 -0.554236 0.00159963 7.17973 -2.65719 -0.0291297 -1.01193 -2.72135 -0.0294439 -1.00081 -2.80938 -0.0310871 -1.00763 -2.88949 -0.0318143 -1.00562 -2.97056 -0.0334862 -1.00127 -3.06064 -0.0348973 -1.00091 -3.16674 -0.035744 -1.01011 -3.25786 -0.0369556 -1.00446 -3.36695 -0.0386817 -1.00754 -3.47605 -0.0402557 -1.00752 -3.58618 -0.0417333 -1.00431 -3.72228 -0.043404 -1.01381 -3.85141 -0.0451868 -1.01384 -3.98058 -0.0467832 -1.01008 -4.14667 -0.049371 -1.02177 -4.28684 -0.0514371 -1.01406 -4.46402 -0.053424 -1.02037 -4.64317 -0.0562493 -1.02094 -4.85836 -0.0588074 -1.03292 -5.05757 -0.0616552 -1.02974 -5.2858 -0.0645146 -1.0319 -5.52505 -0.0678633 -1.03052 -5.79228 -0.0720423 -1.03202 -6.08061 -0.0754006 -1.03172 -6.37991 -0.0801126 -1.02514 -6.70928 -0.0846074 -1.018 -7.1067 -0.089677 -1.02048 -7.54518 -0.0951021 -1.02057 -8.05263 -0.102857 -1.02408 -8.61021 -0.110383 -1.0226 -9.24889 -0.118756 -1.02031 -9.9377 -0.127582 -1.00658 -10.9926 -0.142801 -1.03998 -12.1587 -0.15788 -1.05634 -13.8811 -0.18182 -1.11999 -15.6099 -0.205199 -1.12416 -18.1252 -0.239783 -1.1648 -20.6471 -0.273444 -1.11824 -23.6096 -0.314235 -1.02263 -24.9175 -0.331506 -0.708286 -25.8723 -0.344365 -0.330502 -26.0316 -0.347303 0.10763 -26.5433 -0.353529 0.544648 -26.137 -0.34857 0.999363 -23.5243 -0.313259 1.40129 -23.5033 -0.312145 1.80269 -22.0985 -0.293238 2.13143 -23.382 -0.31144 2.5996 -20.5118 -0.272026 2.75043 -20.0008 -0.265454 3.0493 -20.5574 -0.272571 3.46238 -21.3435 -0.282871 3.92898 -22.4643 -0.298249 4.47839 -21.0606 -0.279403 4.62519 -21.8389 -0.29048 5.14756 -21.1173 -0.2804 5.38213 -17.4523 -0.230709 4.91365 -18.9532 -0.251179 5.6008 -20.9085 -0.277119 6.46815 -17.6083 -0.232058 5.90582 -19.7202 -0.261351 6.87604 -18.0928 -0.239182 6.71626 -19.3238 -0.255531 7.48142 -19.9032 -0.263739 8.06208 -19.6464 -0.260052 8.34947 -27.5811 -0.367607 11.9413 -20.7857 -0.275337 9.61101 -21.7016 -0.288564 10.4397 -20.6363 -0.27383 10.3899 -21.8627 -0.289831 11.4193 -20.5724 -0.272555 11.2277 -20.6559 -0.273375 11.7173 -20.4654 -0.271585 12.0675 -4.61415 -0.0553656 3.472 -4.52723 -0.0549049 3.51701 -4.29877 -0.0516054 3.46709 -4.31333 -0.05129 3.57209 -4.26757 -0.0512594 3.63833 -4.26103 -0.0511799 3.73309 -4.25349 -0.0510153 3.82836 -4.21082 -0.0499192 3.89963 -4.29976 -0.0514992 4.07723 -4.22994 -0.0506732 4.1302 -4.19032 -0.0494398 4.20795 -4.17076 -0.0494477 4.30532 -4.28798 -0.0512766 4.53257 -4.22525 -0.0502513 4.5982 -4.19772 -0.0496572 4.69801 -4.13996 -0.0496618 4.76915 -4.13462 -0.0489719 4.89792 -4.06588 -0.0477208 4.96077 -3.94375 -0.0462979 4.96207 -3.89306 -0.046167 5.04456 -3.778 -0.0440237 5.04877 -3.62761 -0.0422293 5.0029 -3.59305 -0.0421054 5.1049 -3.18569 -0.035718 4.69708 -3.13797 -0.0353408 4.76793 -3.1558 -0.036016 4.93783 -3.30986 -0.0380393 5.3274 -3.34504 -0.0379592 5.5539 -3.49223 -0.040764 5.98 -3.43472 -0.0391841 6.08341 -3.10345 -0.0353505 5.69655 -2.80944 -0.0310623 5.34402 -2.71034 -0.0293321 5.3391 -2.62635 -0.0282854 5.35904 -2.54941 -0.02785 5.39547 -2.50085 -0.0270258 5.49453 -2.48471 -0.0270776 5.67609 -2.34707 -0.0249814 5.57094 -2.26309 -0.0238219 5.59317 -2.16188 -0.0220235 5.56684 -1.98443 -0.0199546 5.31152 -1.99285 -0.0195201 5.59348 -1.84471 -0.0182132 5.39894 -1.74534 -0.0169025 5.3448 -1.66225 -0.0152813 5.33696 -1.72206 -0.0160525 5.89992 -1.75774 -0.0171724 6.44667 -1.39433 -0.0116153 5.20593 -1.31109 -0.0102823 5.17187 -1.23394 -0.00994268 5.16566 -1.16609 -0.00878529 5.20749 -1.11794 -0.00852607 5.39679 -1.07532 -0.00772056 5.68474 -1.01429 -0.00674424 5.89303 -0.928186 -0.005644 5.89125 -0.836714 -0.00474292 5.81823 -0.743905 -0.00279447 5.66358 -0.66395 -0.00231971 5.69712 -0.615396 -0.000882361 7.62892 -2.6154 -0.0907085 -1.01008 -2.68735 -0.0938786 -1.00658 -2.75933 -0.0969555 -1.00119 -2.84718 -0.10154 -1.00687 -2.93612 -0.105066 -1.0101 -3.01708 -0.108678 -1.00455 -3.11499 -0.112803 -1.00892 -3.21392 -0.116856 -1.01061 -3.30587 -0.121055 -1.00351 -3.41478 -0.125708 -1.00515 -3.52371 -0.130204 -1.00358 -3.64262 -0.135409 -1.00416 -3.77949 -0.14104 -1.01167 -3.90839 -0.146732 -1.0099 -4.04727 -0.153078 -1.00918 -4.19618 -0.159053 -1.00896 -4.37198 -0.167108 -1.01796 -4.54981 -0.17501 -1.02138 -4.72868 -0.182697 -1.01921 -4.94547 -0.192213 -1.02796 -5.17231 -0.201185 -1.03371 -5.38219 -0.210396 -1.0245 -5.63099 -0.221348 -1.02322 -5.91774 -0.233883 -1.02786 -6.19754 -0.246364 -1.01964 -6.51636 -0.259373 -1.01501 -6.88406 -0.27556 -1.01491 -7.29176 -0.293112 -1.01385 -7.74943 -0.312664 -1.01249 -8.27601 -0.335479 -1.01322 -8.88351 -0.36222 -1.01479 -9.55101 -0.391208 -1.00881 -10.4363 -0.429375 -1.02382 -11.5014 -0.475515 -1.04126 -12.8951 -0.535376 -1.07664 -14.6096 -0.609546 -1.11103 -16.5361 -0.692936 -1.1136 -19.5386 -0.822006 -1.17177 -24.0346 -1.01666 -0.85461 -24.4023 -1.03253 -0.463942 -26.5901 -1.1276 -0.140895 -26.6064 -1.12803 0.315061 -30.5204 -1.29738 0.73699 -25.7255 -1.09015 1.21965 -25.6177 -1.08499 1.65769 -24.0257 -1.01663 2.02742 -20.7633 -0.875242 2.23992 -23.3581 -0.987144 2.79998 -20.4689 -0.862654 2.92396 -19.9057 -0.8384 3.21256 -21.4092 -0.903327 3.75478 -26.8818 -1.13972 4.94569 -21.4979 -0.907017 4.51651 -22.2778 -0.94123 5.03949 -21.4016 -0.902651 5.25586 -17.8713 -0.750457 4.85428 -19.3565 -0.814649 5.53058 -18.7129 -0.786735 5.7141 -19.504 -0.820766 6.27464 -19.7159 -0.829686 6.69673 -19.5946 -0.825107 7.02556 -19.6575 -0.827633 7.41527 -18.9867 -0.798391 7.55199 -19.1697 -0.805978 7.98595 -19.602 -0.825123 8.53096 -23.1233 -0.977275 10.3788 -20.5921 -0.867913 9.74387 -20.7274 -0.874228 10.2262 -20.7265 -0.873943 10.6556 -4.6127 -0.177396 3.05237 -4.40367 -0.167944 3.21085 -4.34798 -0.165731 3.26855 -4.35843 -0.166509 3.36673 -4.29171 -0.163964 3.41769 -4.2401 -0.160864 3.47802 -4.22951 -0.160891 3.56571 -4.25708 -0.16177 3.68268 -4.21847 -0.15992 3.75389 -4.2009 -0.159468 3.84271 -4.13518 -0.15694 3.89457 -4.11561 -0.156382 3.9831 -4.01686 -0.15125 4.00676 -4.21104 -0.160145 4.28641 -4.28589 -0.163466 4.47242 -4.33371 -0.165004 4.64122 -4.24798 -0.161589 4.68659 -4.28174 -0.163478 4.85142 -4.08957 -0.155098 4.78634 -4.08423 -0.154423 4.91481 -4.09498 -0.154565 5.06662 -4.35397 -0.165949 5.51659 -4.09644 -0.154793 5.36719 -3.8207 -0.14346 5.17897 -3.54695 -0.131043 4.97456 -3.46514 -0.128301 5.01112 -3.16307 -0.114638 4.73668 -3.09731 -0.112398 4.78265 -3.31247 -0.121144 5.25266 -3.68888 -0.13744 6.00954 -3.56901 -0.132018 6.01332 -3.48134 -0.128113 6.06618 -3.41684 -0.12553 6.16108 -2.82603 -0.100015 5.2885 -2.93085 -0.104263 5.67436 -2.69775 -0.0941732 5.41187 -2.58162 -0.0893147 5.3684 -2.48459 -0.0859471 5.35858 -2.39975 -0.0820501 5.37428 -2.31996 -0.078083 5.39754 -2.21687 -0.0735405 5.36359 -2.11978 -0.0700099 5.33674 -2.02372 -0.0656459 5.30775 -1.9388 -0.0616398 5.30532 -1.83963 -0.0572157 5.25352 -1.74852 -0.0534388 5.21871 -1.66654 -0.0498744 5.21097 -1.59271 -0.0464421 5.2307 -1.62392 -0.0477813 5.68669 -1.48178 -0.0417807 5.4323 -1.35066 -0.0361319 5.18425 -1.27162 -0.0331219 5.1689 -1.20282 -0.0303564 5.20155 -1.15889 -0.0283515 5.41095 -1.08825 -0.0251031 5.47132 -1.05632 -0.0235597 5.88832 -0.97035 -0.0204214 5.88734 -0.88552 -0.0164361 5.90483 -0.78437 -0.0118663 5.65129 -0.704602 -0.00836147 5.68549 -0.625211 -0.00499363 5.79829 -0.554479 -0.00248225 7.27975 -2.57273 -0.150199 -1.00762 -2.65149 -0.156174 -1.01195 -2.7154 -0.160481 -1.00073 -2.7952 -0.16632 -1.00107 -2.88394 -0.172906 -1.00555 -2.96476 -0.17858 -1.00131 -3.05355 -0.18493 -1.00099 -3.14434 -0.191274 -0.998092 -3.25104 -0.199037 -1.00446 -3.35076 -0.206937 -1.00185 -3.4595 -0.214513 -1.00194 -3.56132 -0.221247 -0.993497 -3.69688 -0.23192 -1.00315 -3.83353 -0.241455 -1.00877 -3.97214 -0.251898 -1.01005 -4.1198 -0.261917 -1.01202 -4.27738 -0.273544 -1.01409 -4.43699 -0.285051 -1.01128 -4.61454 -0.29783 -1.01225 -4.82098 -0.312702 -1.02026 -5.01946 -0.327563 -1.01749 -5.26481 -0.344909 -1.02798 -5.49325 -0.361472 -1.02306 -5.76953 -0.381437 -1.02846 -6.03885 -0.401371 -1.02149 -6.34608 -0.423797 -1.01861 -6.66533 -0.446606 -1.00879 -7.03341 -0.473564 -1.00295 -7.48923 -0.506438 -1.00954 -7.97599 -0.541813 -1.00863 -8.54153 -0.583089 -1.01056 -9.19783 -0.6309 -1.01348 -9.86527 -0.678381 -0.996181 -10.8975 -0.753274 -1.02667 -12.0215 -0.835732 -1.03718 -13.71 -0.957791 -1.09815 -15.4236 -1.08161 -1.10327 -20.7549 -1.4684 -1.13499 -23.9381 -1.69991 -1.05658 -24.697 -1.754 -0.697157 -27.8403 -1.98214 -0.43738 -24.6812 -1.75303 0.152669 -24.6723 -1.75255 0.576338 -24.7761 -1.75991 0.999305 -24.6624 -1.75213 1.42224 -24.6615 -1.75216 1.84527 -24.4341 -1.73506 2.25693 -24.2196 -1.72006 2.66228 -20.3618 -1.43997 2.7417 -20.5162 -1.45116 3.10878 -21.002 -1.48603 3.52328 -19.4926 -1.37726 3.67571 -22.3492 -1.58469 4.46909 -20.3405 -1.43841 4.50707 -18.7987 -1.32633 4.56567 -19.6211 -1.38687 5.0745 -20.189 -1.42735 5.55691 -19.1682 -1.35325 5.66605 -18.6885 -1.31839 5.88588 -17.7861 -1.25374 5.96922 -18.9466 -1.33702 6.65381 -20.5907 -1.45636 7.54433 -18.7852 -1.32572 7.31214 -18.7759 -1.32553 7.66885 -19.1135 -1.34949 8.16318 -19.0594 -1.34569 8.51775 -20.3127 -1.43627 9.43126 -21.2014 -1.50098 10.2403 -20.7026 -1.46473 10.4448 -4.65017 -0.301158 3.02952 -4.47267 -0.287446 3.02915 -21.8552 -1.54851 12.384 -4.41651 -0.283759 3.17669 -4.33494 -0.277693 3.21989 -4.34738 -0.278616 3.31756 -4.37384 -0.28081 3.42689 -4.28028 -0.273437 3.46161 -4.24566 -0.271819 3.53299 -4.24217 -0.270968 3.62679 -4.21159 -0.269322 3.70364 -4.2992 -0.275369 3.87046 -4.17856 -0.266547 3.88119 -4.12704 -0.262273 3.94506 -4.12154 -0.261921 4.04661 -4.05294 -0.257309 4.09649 -4.27289 -0.273314 4.40573 -4.16927 -0.265837 4.4303 -4.26608 -0.272986 4.64676 -4.30781 -0.276033 4.81819 -4.15106 -0.264916 4.79075 -4.07757 -0.258707 4.84669 -4.07018 -0.258883 4.97572 -4.21633 -0.269347 5.28656 -3.83984 -0.242209 4.99093 -3.69506 -0.23121 4.95549 -3.72989 -0.233957 5.14478 -3.47662 -0.215734 4.96105 -3.31367 -0.203736 4.88315 -3.32645 -0.204432 5.04648 -3.23879 -0.197953 5.07039 -3.62348 -0.226035 5.82217 -3.58621 -0.223339 5.95249 -3.11954 -0.189864 5.3714 -2.94339 -0.176546 5.24337 -2.88386 -0.17257 5.31173 -2.99549 -0.180827 5.70595 -2.88167 -0.172904 5.68663 -2.67716 -0.15796 5.47594 -2.78408 -0.164856 5.91208 -2.49169 -0.14428 5.48544 -2.35148 -0.134399 5.37232 -2.28595 -0.129494 5.43187 -2.16182 -0.12048 5.34109 -2.09326 -0.115004 5.38822 -1.98016 -0.106967 5.31142 -1.88726 -0.0999207 5.27967 -1.80036 -0.0943933 5.26507 -1.70642 -0.0869473 5.21988 -1.62556 -0.0814838 5.21134 -1.54983 -0.0754449 5.22065 -1.47403 -0.0704667 5.22871 -1.38502 -0.0636619 5.17662 -1.30918 -0.0583146 5.17185 -1.23951 -0.0534604 5.2051 -1.21725 -0.0513932 5.54329 -1.12503 -0.0451268 5.4562 -1.0577 -0.040137 5.55571 -1.00828 -0.036443 5.85318 -0.925594 -0.0310569 5.8813 -0.836579 -0.0243012 5.82821 -0.741804 -0.017686 5.62367 -0.662212 -0.0112197 5.65713 -0.61597 -0.00793633 7.62896 -2.59989 -0.21481 -1.00316 -2.68547 -0.223492 -1.01332 -2.75027 -0.229814 -1.0012 -2.82201 -0.236796 -0.993918 -2.91752 -0.247061 -1.00368 -3.00611 -0.256465 -1.00451 -3.08884 -0.264088 -0.996782 -3.19428 -0.275857 -1.00454 -3.29387 -0.28583 -1.00344 -3.40242 -0.296484 -1.00517 -3.51093 -0.307974 -1.00356 -3.63735 -0.320921 -1.00953 -3.75685 -0.333003 -1.00647 -3.89427 -0.346493 -1.00999 -4.02372 -0.360045 -1.00424 -4.17109 -0.374961 -1.00417 -4.34727 -0.393081 -1.01338 -4.5235 -0.410921 -1.01689 -4.69276 -0.428854 -1.01054 -4.9177 -0.452125 -1.02378 -5.12486 -0.472564 -1.02181 -5.35285 -0.496307 -1.02064 -5.60875 -0.521922 -1.0232 -5.88552 -0.550733 -1.02436 -6.19216 -0.582392 -1.02632 -6.47106 -0.610402 -1.00872 -6.84738 -0.649338 -1.01188 -7.25262 -0.690825 -1.01103 -7.70865 -0.737368 -1.00983 -8.19457 -0.787329 -1.0007 -8.81887 -0.850467 -1.00782 -9.50288 -0.920813 -1.00665 -10.2965 -1.00171 -1.00392 -11.4154 -1.11693 -1.03401 -12.7346 -1.25099 -1.05845 -14.5295 -1.43509 -1.1081 -16.4183 -1.62836 -1.10708 -21.3642 -2.13443 -1.01997 -24.3211 -2.43674 -0.88524 -23.8742 -2.39057 -0.437736 -23.8453 -2.38842 -0.0252043 -26.8827 -2.69896 0.304835 -25.1795 -2.52423 0.782757 -25.4385 -2.55139 1.21809 -24.2775 -2.43199 1.62517 -23.3384 -2.33653 2.00174 -23.7547 -2.3786 2.42906 -20.9299 -2.08939 2.61563 -20.9088 -2.08736 2.97474 -20.4562 -2.04163 3.28494 -20.3046 -2.02586 3.62037 -19.9605 -1.99108 3.92305 -19.2796 -1.92122 4.15847 -18.3415 -1.82528 4.32345 -24.8314 -2.48943 5.9755 -19.0016 -1.89273 5.12255 -22.0426 -2.20362 6.1981 -20.8602 -2.08239 6.29237 -21.1492 -2.11198 6.75562 -18.8139 -1.87361 6.45253 -20.4999 -2.04588 7.33821 -12.6889 -1.24678 5.09921 -19.7427 -1.96878 7.84912 -18.6892 -1.8607 7.83539 -19.521 -1.94565 8.53097 -19.3044 -1.9238 8.82907 -19.2025 -1.9126 9.17365 -20.6594 -2.06233 10.2345 -4.61262 -0.420123 2.97158 -4.50622 -0.409896 3.00776 -22.8159 -2.28312 12.6768 -21.4477 -2.14241 12.432 -4.36178 -0.394841 3.19609 -4.30534 -0.388595 3.2533 -4.27526 -0.385647 3.4177 -4.2577 -0.384508 3.50018 -4.17227 -0.375498 3.53736 -4.21771 -0.379924 3.66527 -4.18619 -0.377225 3.74198 -4.2167 -0.379883 3.86713 -4.15921 -0.374509 3.92569 -4.08476 -0.366794 3.97035 -4.10829 -0.368921 4.09773 -4.10586 -0.368372 4.20696 -4.27742 -0.386302 4.47912 -4.20203 -0.378168 4.53108 -4.32466 -0.391396 4.77777 -4.29334 -0.387452 4.87985 -4.17691 -0.375651 4.8951 -4.17657 -0.375829 5.03269 -4.06617 -0.364204 5.05171 -3.73637 -0.33122 4.80949 -3.78416 -0.335466 5.00456 -3.68266 -0.325437 5.02249 -3.72748 -0.329969 5.22841 -3.62403 -0.318925 5.2442 -3.45235 -0.301697 5.16001 -3.73391 -0.330544 5.73031 -3.39376 -0.295559 5.39445 -3.2421 -0.279744 5.32639 -3.04719 -0.260295 5.17778 -3.02496 -0.25751 5.30798 -3.04185 -0.260199 5.51704 -3.07695 -0.263726 5.77185 -2.91113 -0.246382 5.65666 -2.7372 -0.228087 5.51035 -2.82973 -0.237935 5.9099 -2.48864 -0.203195 5.38594 -2.4756 -0.201459 5.56688 -2.41829 -0.195571 5.65625 -2.69166 -0.223872 6.59164 -2.24519 -0.178297 5.69261 -2.84419 -0.239536 7.65492 -2.51976 -0.205861 7.0691 -1.96534 -0.149323 5.67307 -1.85847 -0.138884 5.61182 -1.71713 -0.12414 5.41336 -1.58068 -0.110346 5.2017 -1.50507 -0.102342 5.21031 -1.42127 -0.0938427 5.17851 -1.34255 -0.0857644 5.16462 -1.27601 -0.0795798 5.20829 -1.21881 -0.0735999 5.31989 -1.26468 -0.0776867 6.14285 -1.09031 -0.0603687 5.51109 -1.03874 -0.0544728 5.7492 -0.967716 -0.0473425 5.88738 -0.885221 -0.0395014 5.92479 -0.784435 -0.0289352 5.67125 -0.703893 -0.0208608 5.69552 -0.624806 -0.0124935 5.80837 -0.553424 -0.00532544 7.09977 -2.5604 -0.270822 -1.00761 -2.63093 -0.280979 -1.00516 -2.70253 -0.290102 -1.00077 -2.78202 -0.300936 -1.00107 -2.85366 -0.309862 -0.992681 -2.95005 -0.322132 -1.00135 -3.03847 -0.334474 -1.00094 -3.13584 -0.347532 -1.00407 -3.23523 -0.360574 -1.00441 -3.33365 -0.373413 -1.00185 -3.44203 -0.38699 -1.00204 -3.55137 -0.401467 -0.998985 -3.67756 -0.418324 -1.00316 -3.80578 -0.43512 -1.00364 -3.93397 -0.452716 -1.00008 -4.09002 -0.472528 -1.00725 -4.2371 -0.492321 -1.00473 -4.41301 -0.515308 -1.0113 -4.581 -0.53732 -1.00783 -4.76781 -0.562633 -1.00756 -4.99242 -0.591739 -1.01751 -5.21802 -0.621549 -1.02023 -5.45456 -0.65284 -1.01926 -5.71991 -0.688028 -1.02132 -5.98733 -0.72291 -1.0147 -6.30242 -0.764047 -1.01547 -6.61952 -0.805786 -1.0057 -7.00412 -0.857113 -1.00591 -7.42855 -0.912751 -1.00412 -7.93142 -0.979458 -1.00861 -8.47409 -1.05121 -1.00576 -9.09732 -1.13282 -1.00235 -9.79011 -1.22431 -0.992104 -10.7869 -1.35597 -1.01712 -11.9129 -1.50388 -1.03034 -13.494 -1.712 -1.07633 -15.3048 -1.9509 -1.09919 -20.8107 -2.67737 -1.15394 -25.2048 -3.25643 -0.743309 -27.1153 -3.50826 0.530584 -24.3237 -3.13987 0.999158 -23.7552 -3.06516 1.40867 -22.6945 -2.92546 1.78103 -22.6577 -2.91996 2.17053 -22.8415 -2.94411 2.57496 -23.5713 -3.0406 3.03512 -20.8804 -2.68632 3.15987 -20.8106 -2.67654 3.51468 -21.5593 -2.7757 3.98453 -22.3707 -2.88217 4.88889 -19.409 -2.49164 4.70671 -19.7788 -2.54101 5.13255 -25.8771 -3.34487 6.90849 -19.7482 -2.5373 6.20153 -18.6552 -2.39264 6.25019 -18.9217 -2.42754 6.68004 -19.9517 -2.56366 7.37427 -19.0326 -2.4429 7.43575 -19.3839 -2.48867 7.93195 -19.4555 -2.4979 8.33864 -18.9763 -2.43545 8.52888 -20.9612 -2.69693 9.75941 -20.4443 -2.6289 9.95558 -21.3191 -2.74361 10.7912 -23.0717 -2.97499 12.103 -22.1425 -2.85274 12.1219 -21.4832 -2.76532 12.2523 -21.927 -2.82431 12.9787 -4.45977 -0.521314 3.4957 -4.3994 -0.513765 3.55417 -4.27228 -0.496446 3.56654 -4.20291 -0.48783 3.61532 -4.20539 -0.488036 3.71534 -4.29264 -0.500059 3.88255 -4.18744 -0.485536 3.90569 -4.09817 -0.473489 3.93874 -4.09965 -0.474248 4.0466 -4.18102 -0.485232 4.22762 -4.39023 -0.512825 4.53281 -4.27802 -0.498025 4.55299 -4.2437 -0.493309 4.64674 -4.22235 -0.490687 4.75452 -4.19108 -0.485799 4.85545 -4.12377 -0.477536 4.91985 -4.00256 -0.461002 4.9236 -4.21416 -0.488766 5.30917 -3.99196 -0.459805 5.19776 -3.56968 -0.404717 4.82342 -3.68642 -0.419465 5.11318 -3.82318 -0.438192 5.44824 -3.41377 -0.383315 5.04487 -3.30341 -0.368953 5.03823 -3.21606 -0.357479 5.06208 -3.18377 -0.353282 5.16806 -3.40493 -0.382909 5.68952 -3.05817 -0.336428 5.29428 -3.30061 -0.368529 5.89288 -3.13915 -0.34726 5.8015 -2.9014 -0.315994 5.55583 -2.87225 -0.312324 5.69545 -2.88632 -0.314372 5.93424 -2.66646 -0.285345 5.68544 -2.48368 -0.260702 5.49453 -2.35503 -0.244127 5.40912 -2.37523 -0.246854 5.68214 -2.23046 -0.227785 5.54647 -2.63267 -0.280729 6.91049 -2.55569 -0.270508 7.02283 -2.38084 -0.24798 6.83938 -1.90285 -0.184874 5.62845 -1.9266 -0.18807 6.0177 -1.94455 -0.190373 6.43809 -1.53799 -0.136874 5.20134 -1.46148 -0.126329 5.19942 -1.38189 -0.116148 5.18643 -1.30944 -0.106018 5.20132 -1.23899 -0.0965893 5.22474 -1.35112 -0.112175 6.4224 -1.13626 -0.083539 5.56503 -1.05577 -0.0726296 5.56563 -1.13161 -0.0825138 7.05656 -0.925174 -0.0561211 5.90126 -0.83654 -0.0438802 5.8581 -0.742147 -0.031775 5.66361 -0.662895 -0.0213269 5.71709 -0.649057 -0.0195939 9.61863 -2.50606 -0.325206 -0.997299 -2.58345 -0.337176 -1.00283 -2.6618 -0.3501 -1.00621 -2.73229 -0.361112 -1.00082 -2.81167 -0.373891 -1.00002 -2.892 -0.38762 -0.996973 -2.97935 -0.400971 -0.998007 -3.06859 -0.416315 -0.996455 -3.16585 -0.431308 -0.998287 -3.26408 -0.447222 -0.997278 -3.3712 -0.464814 -0.99906 -3.47935 -0.48231 -0.997651 -3.5964 -0.501456 -0.998434 -3.7323 -0.523082 -1.00605 -3.8593 -0.543712 -1.00444 -3.98826 -0.565264 -0.998788 -4.13514 -0.588185 -0.998919 -4.29978 -0.615412 -1.00358 -4.46645 -0.642501 -1.00297 -4.66088 -0.673656 -1.01008 -4.84742 -0.703811 -1.00666 -5.08052 -0.741482 -1.01716 -5.29677 -0.777377 -1.0124 -5.56066 -0.819719 -1.0189 -5.82556 -0.862686 -1.01658 -6.11032 -0.90876 -1.01225 -6.41594 -0.957942 -1.00474 -6.77013 -1.01532 -1.00211 -7.16302 -1.079 -0.998768 -7.61541 -1.15244 -0.998225 -8.13524 -1.23708 -0.999766 -8.71563 -1.3312 -0.997413 -9.38531 -1.43972 -0.994655 -10.1146 -1.55731 -0.980809 -11.2246 -1.73727 -1.01265 -12.426 -1.93161 -1.02069 -14.2363 -2.22536 -1.07829 -15.8654 -2.48975 -1.0477 -18.8305 -2.97004 -1.11396 -21.4778 -3.39831 -1.04429 -24.0978 -3.82348 -0.459831 -24.1782 -3.83585 -0.0450452 -25.9092 -4.11648 0.328361 -25.9075 -4.11616 0.777714 -27.4961 -4.37369 1.24122 -26.8366 -4.26691 1.70114 -22.0877 -3.49696 1.95685 -22.3435 -3.53879 2.35548 -22.5727 -3.57561 2.76189 -21.6148 -3.42063 3.06169 -21.1451 -3.34513 3.38489 -26.9039 -4.27743 4.52401 -26.4782 -4.20924 4.93562 -33.144 -5.28875 6.537 -22.2993 -3.53166 5.09496 -20.1452 -3.18306 5.05096 -24.0909 -3.82182 6.30059 -19.8885 -3.14153 5.71737 -20.1198 -3.17857 6.14209 -20.7316 -3.27782 6.68601 -19.9307 -3.14795 6.83253 -20.2971 -3.20782 7.32559 -18.9962 -2.99651 7.27159 -18.998 -2.99652 7.63773 -24.9177 -3.9557 10.2511 -19.0146 -2.99932 8.39027 -18.6655 -2.94254 8.62462 -20.4231 -3.22821 9.77823 -25.2278 -4.00636 12.4187 -23.3519 -3.70197 12.0446 -21.1614 -3.34696 11.4383 -21.469 -3.39686 12.0607 -20.9282 -3.30922 12.2389 -22.0378 -3.4888 13.3469 -4.3767 -0.627478 3.59999 -4.23381 -0.604794 3.6002 -4.49317 -0.646387 3.88645 -4.41105 -0.633109 3.9328 -4.25822 -0.608346 3.92238 -4.14616 -0.590742 3.93862 -4.09488 -0.582465 4.00259 -4.05754 -0.576437 4.07869 -4.06308 -0.577065 4.19412 -4.21116 -0.60061 4.44582 -4.1011 -0.583092 4.46274 -4.29412 -0.614211 4.77824 -4.37353 -0.62734 4.99453 -3.82872 -0.539012 4.55464 -3.78044 -0.531468 4.62774 -3.65837 -0.511553 4.61771 -3.66004 -0.511159 4.74904 -3.62572 -0.506433 4.84299 -3.6334 -0.507553 4.99157 -3.6002 -0.501473 5.09396 -3.61689 -0.504843 5.26881 -3.35392 -0.462473 5.05454 -3.62451 -0.505579 5.6071 -3.2835 -0.450971 5.26138 -3.25235 -0.445342 5.37739 -3.2332 -0.442165 5.51926 -3.20006 -0.436966 5.64442 -3.16794 -0.432388 5.77852 -2.94369 -0.395512 5.56131 -3.21104 -0.439313 6.27794 -3.01383 -0.406628 6.11028 -2.97285 -0.400071 6.25325 -2.3863 -0.305777 5.19514 -2.27895 -0.287725 5.14524 -2.31609 -0.294209 5.44403 -2.38758 -0.305134 5.85691 -2.22395 -0.279235 5.6742 -2.53213 -0.328476 6.81631 -2.27805 -0.287293 6.38665 -2.18188 -0.272416 6.40771 -2.04436 -0.250221 6.28325 -1.9684 -0.237441 6.36752 -1.85604 -0.219204 6.31525 -1.49242 -0.16071 5.19105 -1.41602 -0.148201 5.18843 -1.34162 -0.136403 5.19415 -1.2958 -0.128622 5.35593 -1.50458 -0.162787 7.0855 -1.28156 -0.126022 6.30118 -1.09347 -0.0957205 5.57067 -1.02139 -0.0839143 5.64004 -0.967192 -0.0749168 5.91727 -0.879781 -0.0607143 5.89494 -0.787899 -0.0467654 5.78113 -0.702265 -0.0328091 5.71554 -0.623384 -0.0194264 5.80842 -0.551131 -0.00767789 7.06977 -2.46483 -0.37705 -1.00074 -2.5341 -0.391238 -1.00018 -2.61138 -0.405153 -1.00461 -2.68168 -0.419214 -1.00027 -2.753 -0.433238 -0.993938 -2.83913 -0.449706 -0.998614 -2.92629 -0.466112 -1.0008 -3.00753 -0.481729 -0.994263 -3.10354 -0.500728 -0.99749 -3.20063 -0.518653 -0.997976 -3.29968 -0.537554 -0.995525 -3.3977 -0.557249 -0.990123 -3.51455 -0.579483 -0.992755 -3.63144 -0.601546 -0.991892 -3.76606 -0.628018 -0.99766 -3.89282 -0.652563 -0.994349 -4.04733 -0.681311 -1.00156 -4.18498 -0.708334 -0.994512 -4.35828 -0.741208 -1.00137 -4.52467 -0.773169 -0.998209 -4.72759 -0.812928 -1.00667 -4.92274 -0.849678 -1.0044 -5.16427 -0.896905 -1.01529 -5.38914 -0.939352 -1.01078 -5.64263 -0.988706 -1.00955 -5.91697 -1.04125 -1.00673 -6.21901 -1.0995 -1.00444 -6.54286 -1.16188 -0.998222 -6.91423 -1.23334 -0.995736 -7.32524 -1.31213 -0.9916 -7.80355 -1.40421 -0.991647 -8.35119 -1.50953 -0.99209 -8.96817 -1.62791 -0.989335 -9.64464 -1.75747 -0.977788 -10.5448 -1.93063 -0.986488 -11.7468 -2.16225 -1.01762 -13.051 -2.41278 -1.0221 -15.0284 -2.79271 -1.07679 -16.1342 -3.00578 -0.952186 -25.3429 -4.77643 -0.764859 -27.1737 -5.12766 -0.419109 -27.3809 -5.16814 0.0485234 -27.511 -5.19252 0.524284 -27.5054 -5.19145 1.00437 -27.3334 -5.15841 1.48139 -28.666 -5.41448 2.00621 -22.104 -4.15306 2.15646 -22.8349 -4.29387 2.59405 -22.8428 -4.29557 2.99427 -21.5745 -4.05135 3.25919 -21.718 -4.07944 3.65653 -19.9094 -3.73131 3.78104 -20.0726 -3.7625 4.16006 -23.1291 -4.3505 5.06707 -19.9324 -3.73586 4.84991 -19.4639 -3.64614 5.46165 -19.5936 -3.67076 5.85121 -20.0961 -3.76764 6.35033 -20.3221 -3.81056 6.7916 -20.5957 -3.86304 7.26 -12.8737 -2.37849 5.09647 -21.2413 -3.98704 8.27646 -20.5687 -3.85795 8.44212 -23.5919 -4.43922 10.0309 -21.0847 -3.95735 9.47311 -21.5512 -4.04656 10.1034 -24.6936 -4.65116 11.9735 -23.0683 -4.33881 11.7212 -20.9314 -3.92805 11.1516 -21.0686 -3.95444 11.6765 -21.7233 -4.07973 12.4959 -22.1079 -4.15425 13.2012 -4.36151 -0.742138 3.55498 -4.29341 -0.729448 3.60655 -4.79477 -0.825335 4.06358 -4.51108 -0.770761 3.96901 -4.28695 -0.72818 3.90741 -4.23681 -0.717823 3.97428 -4.2542 -0.721821 4.09689 -4.37309 -0.744462 4.31103 -4.14592 -0.700731 4.22847 -4.00918 -0.674879 4.21917 -3.98985 -0.670957 4.31515 -4.39144 -0.748009 4.8282 -4.24878 -0.720791 4.81898 -4.16882 -0.705371 4.87071 -3.91466 -0.655848 4.73051 -3.6335 -0.601907 4.54535 -3.52058 -0.580303 4.54007 -3.68657 -0.612131 4.86903 -3.94134 -0.660865 5.32929 -4.04773 -0.681654 5.62624 -3.51322 -0.579482 5.07355 -3.41429 -0.55985 5.08598 -3.25347 -0.529019 5.00613 -3.61832 -0.59943 5.70948 -3.22106 -0.523037 5.26932 -3.08015 -0.495565 5.2067 -3.14389 -0.507758 5.48344 -3.11081 -0.501606 5.60765 -3.13173 -0.505535 5.83706 -3.08473 -0.49691 5.95375 -3.0138 -0.483038 6.02572 -2.52268 -0.388782 5.22467 -2.41655 -0.368168 5.18745 -2.35244 -0.355711 5.23921 -2.20215 -0.327079 5.0874 -2.10289 -0.30825 5.0428 -2.30459 -0.34659 5.78962 -2.25868 -0.338139 5.92433 -2.3565 -0.356933 6.49379 -2.21033 -0.328446 6.36428 -2.16969 -0.321004 6.56598 -2.06371 -0.300034 6.55638 -1.88103 -0.264831 6.25491 -1.52731 -0.197402 5.20159 -1.45104 -0.182855 5.19977 -1.37683 -0.168022 5.20624 -1.30664 -0.154532 5.23096 -1.42292 -0.176878 6.33781 -1.31964 -0.15673 6.27445 -1.18645 -0.132132 5.98123 -1.05391 -0.106646 5.60556 -0.999657 -0.0960952 5.85338 -0.922836 -0.0805687 5.93132 -0.834445 -0.0643302 5.88816 -0.740398 -0.0457221 5.68364 -0.659084 -0.0305865 5.66731 -0.646595 -0.0279696 9.62877 -2.49081 -0.443988 -1.00416 -2.56003 -0.459128 -1.00266 -2.63707 -0.476986 -1.00599 -2.70732 -0.492 -1.0007 -2.77852 -0.507974 -0.993372 -2.86449 -0.527379 -0.996801 -2.95147 -0.546723 -0.997738 -3.0316 -0.564228 -0.9902 -3.13631 -0.587995 -0.998068 -3.23318 -0.609844 -0.997057 -3.32318 -0.629856 -0.987572 -3.42996 -0.653302 -0.986461 -3.54559 -0.679391 -0.987392 -3.67901 -0.708906 -0.995304 -3.80452 -0.737486 -0.993988 -3.93994 -0.767717 -0.99367 -4.08528 -0.799575 -0.993851 -4.23948 -0.833976 -0.994077 -4.41343 -0.872775 -0.998248 -4.58737 -0.912297 -0.996776 -4.78902 -0.956842 -1.00218 -4.99266 -1.00218 -1.00086 -5.2249 -1.05449 -1.00433 -5.47599 -1.10994 -1.00749 -5.73792 -1.1688 -1.00576 -6.01965 -1.23176 -1.00178 -6.33108 -1.30054 -0.997954 -6.67111 -1.37698 -0.992573 -7.0596 -1.4635 -0.989782 -7.46888 -1.55489 -0.979006 -8.02137 -1.67816 -0.991722 -8.56705 -1.79995 -0.982831 -9.21846 -1.94543 -0.978916 -9.93916 -2.10568 -0.96611 -10.9789 -2.33809 -0.988218 -12.1571 -2.60126 -0.99669 -13.9558 -3.00283 -1.05812 -15.5563 -3.35983 -1.02847 -16.9753 -3.67591 -0.920593 -25.4372 -5.56447 -1.00674 -26.3544 -5.769 -0.615944 -27.7817 -6.08814 -0.215926 -27.2128 -5.9606 0.287716 -27.5334 -6.03263 0.762714 -30.266 -6.64191 1.27103 -22.8283 -4.98281 2.00257 -25.2726 -5.52727 2.55653 -26.3318 -5.76453 3.08729 -25.5152 -5.58178 3.47212 -21.3872 -4.6609 3.4418 -20.0161 -4.35481 3.63591 -21.8993 -4.77462 4.28038 -20.1937 -4.39483 4.38009 -20.4982 -4.46256 4.80104 -22.8787 -4.99362 5.66883 -19.6231 -4.26727 5.34702 -19.4417 -4.22663 5.66264 -20.3887 -4.43808 6.27372 -20.926 -4.5574 6.8077 -20.7398 -4.51632 7.14647 -19.9992 -4.35148 7.30291 -20.111 -4.37633 7.72687 -21.1992 -4.61868 8.51397 -20.4644 -4.45512 8.6517 -21.0121 -4.57729 9.28256 -23.9966 -5.24328 10.9764 -25.7563 -5.63615 12.2567 -21.6535 -4.7203 10.8813 -21.191 -4.61654 11.1159 -21.6005 -4.70847 11.7835 -21.916 -4.77886 12.427 -21.4773 -4.68091 12.6746 -5.58696 -1.13457 3.95047 -5.76721 -1.17537 4.43956 -5.52094 -1.12002 4.40624 -5.50172 -1.11603 4.52384 -4.98851 -1.00175 4.28177 -4.8294 -0.965941 4.28417 -4.7883 -0.957034 4.37327 -4.57754 -0.909588 4.32494 -4.2873 -0.845086 4.20011 -4.04666 -0.791136 4.10494 -4.47512 -0.886491 4.60526 -4.33474 -0.855127 4.60152 -4.35722 -0.860048 4.75217 -4.30721 -0.848926 4.83462 -4.2343 -0.833503 4.89501 -4.36917 -0.862686 5.17873 -3.63739 -0.700188 4.50999 -3.55153 -0.680696 4.53555 -3.57303 -0.685443 4.6885 -4.05597 -0.793588 5.42201 -3.5425 -0.679069 4.92141 -3.43977 -0.655507 4.92757 -3.33196 -0.632152 4.92337 -3.3387 -0.632858 5.07914 -3.44498 -0.65681 5.39307 -3.11714 -0.583652 5.05314 -3.11588 -0.583874 5.20896 -2.94634 -0.545277 5.09305 -3.25313 -0.61445 5.79109 -3.20027 -0.602249 5.89184 -3.14841 -0.590698 6.00091 -3.05365 -0.569502 6.02975 -2.55855 -0.458721 5.23343 -2.48257 -0.441755 5.26053 -2.28765 -0.398662 5.02236 -2.3396 -0.410219 5.33801 -2.15355 -0.368996 5.09314 -2.51997 -0.450758 6.25721 -2.27595 -0.395993 5.87097 -2.22214 -0.383987 5.98684 -2.34495 -0.411563 6.65235 -2.2071 -0.380184 6.55087 -2.12641 -0.362431 6.62853 -1.94613 -0.322302 6.34844 -1.58117 -0.241451 5.28913 -1.48293 -0.218834 5.20079 -1.41186 -0.202666 5.21778 -1.33771 -0.18686 5.22369 -1.44338 -0.209975 6.22123 -1.3769 -0.195304 6.37542 -1.28914 -0.175755 6.42001 -1.09357 -0.131893 5.63022 -1.01863 -0.115365 5.66995 -0.95941 -0.102512 5.89746 -0.877504 -0.084165 5.92494 -0.783856 -0.0630649 5.77115 -0.697315 -0.0435056 5.65563 -0.618307 -0.0265632 5.67855 -0.550871 -0.0111642 7.05983 -2.43983 -0.491893 -1.0007 -2.50786 -0.510017 -1.00015 -2.58384 -0.528871 -1.00463 -2.66077 -0.548679 -1.00697 -2.72397 -0.564891 -0.993952 -2.80193 -0.584559 -0.992198 -2.89566 -0.607699 -1.00081 -2.9746 -0.628189 -0.994219 -3.06243 -0.650412 -0.991517 -3.1581 -0.675275 -0.99205 -3.26267 -0.701822 -0.995475 -3.36038 -0.726516 -0.990126 -3.467 -0.75288 -0.987368 -3.59028 -0.784624 -0.991887 -3.71459 -0.816242 -0.992615 -3.84876 -0.850513 -0.994392 -3.99284 -0.886416 -0.996767 -4.12801 -0.921323 -0.98991 -4.29964 -0.965133 -0.99682 -4.46348 -1.00598 -0.993902 -4.64597 -1.05311 -0.993926 -4.85611 -1.10624 -1.00028 -5.07713 -1.16189 -1.00359 -5.31688 -1.22268 -1.007 -5.57635 -1.28863 -1.00951 -5.83683 -1.35521 -1.00329 -6.12695 -1.42864 -0.997963 -6.45449 -1.51247 -0.995125 -6.79296 -1.59857 -0.984051 -7.20836 -1.70387 -0.983353 -7.68097 -1.82372 -0.983894 -8.19308 -1.95364 -0.977542 -8.78214 -2.10326 -0.971331 -9.49647 -2.28484 -0.971545 -10.2612 -2.47871 -0.956033 -11.4293 -2.77545 -0.986405 -12.7434 -3.10921 -0.998689 -14.7144 -3.61039 -1.05869 -15.9788 -3.93154 -0.958259 -26.1222 -6.50755 -0.844269 -26.9234 -6.71066 -0.424392 -27.9408 -6.96894 0.0158156 -28.4769 -7.10566 0.500803 -28.1518 -7.02292 1.00462 -29.3106 -7.31695 1.52357 -25.3639 -6.31462 1.89992 -24.9969 -6.22205 2.3287 -25.2122 -6.27652 2.78704 -25.2746 -6.2919 3.24047 -25.108 -6.24938 3.67262 -20.6724 -5.12347 3.55896 -21.3841 -5.3045 4.03182 -25.7425 -6.41106 5.12926 -19.7416 -4.88698 4.50395 -20.2599 -5.01873 4.9663 -21.9625 -5.45077 5.71062 -19.5562 -4.84032 5.5426 -20.4362 -5.06285 6.13192 -20.5803 -5.09973 6.55492 -20.5951 -5.10316 6.94875 -21.5387 -5.34352 7.64027 -19.8834 -4.92341 7.50182 -19.908 -4.92929 7.89871 -19.9257 -4.93361 8.29837 -22.5403 -5.59813 9.73337 -23.2702 -5.78293 10.4961 -22.4015 -5.56201 10.596 -21.6067 -5.3604 10.6999 -24.2059 -6.02137 12.4102 -21.449 -5.32094 11.5462 -23.1497 -5.75215 12.9118 -5.6357 -1.3046 3.93881 -5.56901 -1.28747 4.0209 -5.3846 -1.23981 4.02922 -5.41486 -1.24771 4.16975 -5.2947 -1.21719 4.21415 -5.37647 -1.23822 4.39516 -5.42954 -1.25218 4.56274 -4.87467 -1.11128 4.28064 -4.96538 -1.1343 4.47319 -4.73821 -1.07619 4.41766 -4.41584 -0.994671 4.27312 -4.23411 -0.948529 4.23384 -4.54387 -1.0269 4.62874 -4.43846 -0.999883 4.66078 -4.51837 -1.02053 4.86762 -4.31975 -0.970398 4.80735 -4.40572 -0.991573 5.03119 -4.24277 -0.950167 5.0002 -4.36544 -0.981865 5.27903 -3.53377 -0.770723 4.47843 -3.5572 -0.776623 4.63072 -4.02534 -0.895283 5.33643 -3.95163 -0.876681 5.39928 -3.8879 -0.859977 5.47646 -3.33347 -0.719559 4.8819 -3.34707 -0.723297 5.04557 -3.60121 -0.7878 5.57139 -3.11702 -0.664283 5.00474 -3.04818 -0.646788 5.05118 -3.02606 -0.641425 5.17284 -2.85974 -0.599115 5.05483 -3.21782 -0.690203 5.85887 -3.15407 -0.674201 5.94209 -3.07845 -0.654393 6.00669 -2.50057 -0.508227 5.0545 -2.4576 -0.497191 5.1438 -2.38773 -0.479217 5.17841 -2.31585 -0.461187 5.21174 -2.29791 -0.456131 5.37273 -2.71354 -0.562025 6.65624 -2.30512 -0.45873 5.85499 -2.21943 -0.436399 5.8773 -2.1497 -0.418781 5.94537 -2.03189 -0.389336 5.86976 -1.98328 -0.376372 6.01128 -1.92264 -0.361114 6.12375 -1.60772 -0.281134 5.26965 -1.51463 -0.257819 5.20165 -1.4457 -0.240264 5.22897 -1.36771 -0.220149 5.21598 -1.4861 -0.250639 6.24211 -1.40556 -0.229452 6.30829 -1.22926 -0.184768 5.76081 -1.14734 -0.164647 5.76337 -1.05413 -0.140819 5.66511 -0.983566 -0.122121 5.75396 -0.936192 -0.110135 6.16044 -0.829223 -0.083565 5.87823 -0.733252 -0.0587869 5.61375 -0.655428 -0.0388798 5.63721 -0.643938 -0.0363185 9.59877 -2.45489 -0.557826 -0.997185 -2.52968 -0.579669 -1.00271 -2.59867 -0.598713 -0.999313 -2.67443 -0.621408 -1.0006 -2.75226 -0.643123 -0.999844 -2.82224 -0.662931 -0.990411 -2.91573 -0.690005 -0.997728 -2.98674 -0.709668 -0.984105 -3.0891 -0.73932 -0.992166 -3.19247 -0.768876 -0.997036 -3.28899 -0.796584 -0.993231 -3.38653 -0.824206 -0.986435 -3.50074 -0.857232 -0.987415 -3.62386 -0.891883 -0.990087 -3.75577 -0.930134 -0.993954 -3.88088 -0.965516 -0.988696 -4.02368 -1.00626 -0.989122 -4.18416 -1.05231 -0.994032 -4.35451 -1.10092 -0.998193 -4.51802 -1.14762 -0.992481 -4.71694 -1.20405 -0.998085 -4.91779 -1.26226 -0.996909 -5.14625 -1.3274 -1.00052 -5.38461 -1.39494 -1.00018 -5.65146 -1.47134 -1.00223 -5.93806 -1.55283 -1.00189 -6.22661 -1.63596 -0.99167 -6.57033 -1.73385 -0.98957 -6.9446 -1.84044 -0.984179 -7.34743 -1.95553 -0.973691 -7.8634 -2.10332 -0.979208 -8.40015 -2.25672 -0.971197 -9.04227 -2.43979 -0.968165 -9.77099 -2.64891 -0.960131 -10.6918 -2.91129 -0.962709 -11.9748 -3.27826 -0.995043 -13.5277 -3.72149 -1.02275 -15.4666 -4.27512 -1.04668 -16.8458 -4.6698 -0.934136 -26.4706 -7.41958 -0.647629 -26.7052 -7.48607 -0.185543 -26.9616 -7.55952 0.283723 -27.0181 -7.57524 0.763742 -27.0844 -7.59447 1.24566 -32.0074 -9.00066 1.86326 -33.7851 -9.50894 2.51692 -24.2149 -6.77455 2.51238 -24.9332 -6.98013 3.00392 -21.6318 -6.03673 3.11976 -20.3418 -5.66833 3.35453 -20.9378 -5.83862 3.80185 -19.5284 -5.43566 3.96077 -19.6343 -5.466 4.69153 -22.1794 -6.193 5.59097 -20.25 -5.64182 5.55708 -20.4036 -5.68663 5.97328 -20.7368 -5.78158 6.4466 -20.2348 -5.63762 6.69539 -19.9793 -5.56473 7.00441 -20.1409 -5.61086 7.44424 -21.1973 -5.91272 8.20618 -20.8462 -5.81288 8.49721 -21.97 -6.13325 9.35233 -21.8794 -6.10742 9.76279 -21.2767 -5.93513 9.95432 -22.5164 -6.29013 10.9603 -23.2906 -6.51059 11.8064 -23.5132 -6.57481 12.4208 -5.50391 -1.42971 3.9456 -5.45314 -1.41514 4.03589 -5.31938 -1.37713 4.07313 -5.37337 -1.39167 4.23001 -5.27811 -1.36487 4.29032 -5.17398 -1.33493 4.34253 -5.18843 -1.33905 4.47919 -5.36103 -1.38859 4.74229 -4.96135 -1.27409 4.56199 -4.96886 -1.2768 4.69854 -5.11391 -1.31787 4.95713 -4.68832 -1.1965 4.72203 -4.55346 -1.15781 4.73121 -4.46208 -1.13195 4.77722 -4.51619 -1.14694 4.96556 -4.44955 -1.12829 5.03796 -4.33345 -1.09516 5.05907 -4.36383 -1.10422 5.2369 -4.29229 -1.08342 5.30632 -3.58292 -0.880745 4.62552 -3.52114 -0.863233 4.68092 -3.56936 -0.87663 4.87403 -3.38968 -0.825277 4.78051 -3.31501 -0.803937 4.8165 -3.3474 -0.813659 5.00375 -3.37987 -0.822871 5.20139 -3.22788 -0.779147 5.12936 -3.052 -0.729234 5.01145 -2.95254 -0.700401 5.00651 -2.98608 -0.709846 5.22097 -3.43185 -0.837716 6.17892 -3.15075 -0.756599 5.87438 -3.0593 -0.730536 5.90425 -3.0255 -0.721388 6.04755 -3.04748 -0.727443 6.3163 -2.39478 -0.541019 5.13414 -2.8 -0.656558 6.25089 -2.70757 -0.630342 6.28267 -2.72875 -0.636992 6.59912 -2.69426 -0.627109 6.79686 -2.29753 -0.513165 6.00211 -2.65849 -0.616852 7.34441 -2.01544 -0.433207 5.71345 -2.04588 -0.44182 6.10271 -1.93029 -0.408626 6.0245 -1.63209 -0.323711 5.24982 -1.54628 -0.298356 5.2116 -1.47346 -0.277479 5.22026 -1.39761 -0.255968 5.2178 -1.52971 -0.293907 6.27223 -1.43405 -0.267123 6.25084 -1.34958 -0.242191 6.28662 -1.18562 -0.195367 5.77709 -1.30659 -0.230255 7.38513 -1.01488 -0.147272 5.70969 -1.05255 -0.157644 6.98247 -0.900598 -0.113921 6.30369 -1.01161 -0.14561 9.72379 -0.693479 -0.0547898 5.62568 -0.615789 -0.0334246 5.65848 -0.54977 -0.0136089 7.06987 -2.40691 -0.605254 -1.00068 -2.46789 -0.624615 -0.993206 -2.54256 -0.648413 -0.997832 -2.61038 -0.670353 -0.993584 -2.6939 -0.696807 -1.00055 -2.77062 -0.720402 -0.998596 -2.8483 -0.744952 -0.994498 -2.93281 -0.772111 -0.99423 -3.01928 -0.800265 -0.991426 -3.11365 -0.830066 -0.992007 -3.20904 -0.859792 -0.989797 -3.31321 -0.893185 -0.990179 -3.4174 -0.926421 -0.987365 -3.53044 -0.962299 -0.986594 -3.66997 -1.00639 -0.997743 -3.78501 -1.04301 -0.989341 -3.92555 -1.08773 -0.991856 -4.06806 -1.13335 -0.989837 -4.23615 -1.18598 -0.996887 -4.39733 -1.2377 -0.993815 -4.57722 -1.29471 -0.993934 -4.76597 -1.35417 -0.9922 -4.98315 -1.42364 -0.995806 -5.21905 -1.49825 -0.999506 -5.47362 -1.57897 -1.00235 -5.7302 -1.66037 -0.996472 -6.02406 -1.75427 -0.994676 -6.31901 -1.84773 -0.982798 -6.66994 -1.95897 -0.978296 -7.06899 -2.08623 -0.97509 -7.52408 -2.231 -0.973467 -8.01854 -2.38785 -0.965454 -8.6348 -2.58374 -0.969099 -9.28164 -2.78871 -0.957018 -10.0709 -3.03968 -0.95031 -11.1816 -3.39181 -0.974305 -12.4455 -3.79358 -0.983054 -14.3178 -4.3877 -1.03511 -15.9663 -4.91133 -0.989936 -26.4368 -8.23744 -0.898553 -26.5501 -8.27311 -0.428014 -26.4748 -8.24873 0.0526767 -26.4289 -8.23435 0.529421 -26.443 -8.23874 1.00431 -26.8011 -8.35283 1.48609 -30.9796 -9.68005 2.1219 -33.5002 -10.4808 3.42675 -21.9005 -6.79673 2.96804 -21.9024 -6.79727 3.36384 -21.0742 -6.53425 3.65412 -20.8292 -6.4561 4.00114 -19.4952 -6.03263 4.15996 -19.4211 -6.00909 4.50391 -20.4737 -6.34315 5.07703 -20.5798 -6.37664 5.48173 -20.623 -6.39069 5.87797 -20.3818 -6.31378 6.2046 -20.5864 -6.37925 6.65075 -20.7822 -6.44172 7.10594 -26.0957 -8.12905 9.73074 -20.666 -6.4041 8.28947 -20.2918 -6.28574 8.56184 -21.1949 -6.57257 9.33897 -21.0877 -6.5386 9.73163 -24.3168 -7.56419 11.6122 -28.5948 -8.92246 14.1298 -28.8559 -9.00539 14.8791 -5.95058 -1.73135 4.17156 -5.76493 -1.67203 4.19093 -5.63737 -1.63178 4.24042 -5.50194 -1.58849 4.28102 -5.38323 -1.55088 4.32856 -5.28722 -1.51999 4.38948 -5.26911 -1.51415 4.50538 -5.21841 -1.49847 4.59802 -5.27137 -1.515 4.77413 -5.25326 -1.50977 4.89797 -5.19477 -1.49061 4.99071 -4.82136 -1.37189 4.80599 -4.59889 -1.30153 4.74021 -4.46525 -1.25898 4.74779 -4.45104 -1.25519 4.86766 -4.51695 -1.27515 5.07137 -4.85253 -1.3821 5.56859 -4.5243 -1.27762 5.37421 -4.42522 -1.2464 5.41801 -4.255 -1.19197 5.37773 -4.14402 -1.15706 5.40052 -3.42785 -0.929743 4.66219 -3.38402 -0.915286 4.73852 -3.30354 -0.889948 4.76715 -3.29828 -0.888168 4.89776 -3.49595 -0.950955 5.32872 -3.30858 -0.892315 5.21097 -3.12122 -0.832358 5.07934 -3.03776 -0.806155 5.10154 -2.97909 -0.78746 5.16436 -3.33079 -0.899317 5.94635 -3.35857 -0.907639 6.19665 -3.20189 -0.857994 6.11695 -3.07194 -0.816999 6.07741 -3.0085 -0.796622 6.16832 -2.91828 -0.767315 6.20444 -2.87173 -0.752836 6.33856 -2.72781 -0.707249 6.25325 -2.81859 -0.735978 6.73514 -2.65875 -0.685393 6.60986 -2.58548 -0.66223 6.70452 -2.578 -0.660381 6.99565 -2.04702 -0.491037 5.71844 -2.15125 -0.523896 6.3357 -1.99297 -0.473579 6.12601 -1.64945 -0.364823 5.21055 -1.57474 -0.341197 5.21168 -1.50405 -0.318933 5.23067 -1.43636 -0.297432 5.25818 -1.40296 -0.286381 5.46055 -1.37573 -0.278311 5.73171 -1.3417 -0.267327 6.01288 -1.19938 -0.221939 5.64232 -1.32465 -0.262096 7.16959 -1.0554 -0.176587 5.75446 -0.977929 -0.151396 5.78377 -0.990117 -0.156072 6.89768 -0.927859 -0.135724 7.43444 -0.728314 -0.0725157 5.59383 -0.653902 -0.0483229 5.6472 -0.641396 -0.0451897 9.59882 -2.48465 -0.694966 -0.99579 -2.55915 -0.721705 -0.999269 -2.63473 -0.747405 -1.0007 -2.69557 -0.769453 -0.986885 -2.77894 -0.798736 -0.990408 -2.86332 -0.827962 -0.99154 -2.94766 -0.858063 -0.990125 -3.03407 -0.88716 -0.986173 -3.12721 -0.920835 -0.985453 -3.22243 -0.953492 -0.981896 -3.33325 -0.992505 -0.98636 -3.45292 -1.03415 -0.992766 -3.56573 -1.07394 -0.990099 -3.69522 -1.11907 -0.994009 -3.81785 -1.16232 -0.988746 -3.95811 -1.21193 -0.989016 -4.10822 -1.26415 -0.989437 -4.26714 -1.31989 -0.989353 -4.43487 -1.37911 -0.988166 -4.62224 -1.44467 -0.989726 -4.81849 -1.51265 -0.988935 -5.04211 -1.59155 -0.992929 -5.28539 -1.67664 -0.996574 -5.55612 -1.77152 -1.00226 -5.81125 -1.86064 -0.99188 -6.10261 -1.96317 -0.985335 -6.42244 -2.07539 -0.977537 -6.78838 -2.20357 -0.972723 -7.21122 -2.3514 -0.970996 -7.68993 -2.51965 -0.969207 -8.21774 -2.70463 -0.961877 -8.82894 -2.91876 -0.955175 -9.55392 -3.17294 -0.950204 -10.4104 -3.47215 -0.94456 -11.6041 -3.89142 -0.967113 -13.0353 -4.39291 -0.982894 -15.2834 -5.18048 -1.05975 -17.331 -5.89745 -1.02915 -21.4016 -7.32385 -1.12903 -26.9217 -9.25932 -0.707905 -26.6162 -9.15167 -0.203859 -26.5469 -9.12742 0.281596 -26.6394 -9.16031 0.762676 -27.1303 -9.33226 1.25075 -30.6314 -10.5586 1.84109 -25.0286 -8.59506 2.59378 -21.7431 -7.44375 2.77508 -21.9079 -7.50245 3.18788 -21.7744 -7.45527 3.57209 -21.1019 -7.21995 3.87761 -21.2756 -7.28002 4.29371 -21.5072 -7.36171 4.72863 -21.9991 -7.53427 5.22594 -20.5389 -7.02195 5.32362 -20.6586 -7.06375 5.73904 -20.357 -6.95864 6.05505 -20.5269 -7.01747 6.49163 -20.9963 -7.18278 7.02691 -21.3284 -7.29869 7.54142 -20.5248 -7.0169 7.69391 -20.6348 -7.05646 8.14264 -23.2893 -7.98627 9.5558 -21.8989 -7.49871 9.48194 -21.6337 -7.40549 9.82507 -26.0616 -8.95823 12.2244 -26.5658 -9.13406 13.0145 -27.8065 -9.5689 14.1916 -28.3001 -9.7424 15.0563 -5.85484 -1.87605 4.21146 -5.62229 -1.79445 4.19837 -5.52839 -1.76233 4.26652 -5.46604 -1.7402 4.35363 -5.4096 -1.72023 4.44491 -5.29802 -1.68088 4.49552 -5.61565 -1.79292 4.86837 -5.25595 -1.6667 4.73034 -5.18569 -1.64237 4.8117 -5.13716 -1.62453 4.91013 -5.15948 -1.63291 5.07167 -4.71879 -1.47837 4.81944 -4.76776 -1.4953 5.00291 -4.319 -1.3383 4.70968 -4.23681 -1.30982 4.75909 -4.37648 -1.35859 5.03793 -4.57344 -1.42705 5.39428 -4.40944 -1.37032 5.36745 -4.03143 -1.23711 5.08514 -4.03803 -1.23988 5.23972 -3.99241 -1.22337 5.33488 -3.96251 -1.21371 5.45289 -3.38377 -1.01039 4.84312 -3.41704 -1.02215 5.03077 -3.44639 -1.03256 5.22078 -3.75447 -1.14 5.83639 -3.66343 -1.10829 5.8794 -3.34306 -0.995771 5.5535 -3.11543 -0.916768 5.35237 -3.36854 -1.0051 5.96286 -3.31507 -0.986675 6.06691 -3.13888 -0.924948 5.94411 -3.12902 -0.921017 6.13273 -3.00924 -0.878821 6.10958 -2.92015 -0.847546 6.14629 -2.81909 -0.812964 6.1542 -2.74887 -0.787782 6.23261 -2.67364 -0.761791 6.30101 -2.62626 -0.744915 6.44203 -2.57796 -0.727532 6.59214 -2.20445 -0.597149 5.83355 -2.15006 -0.577563 5.93975 -1.98408 -0.520052 5.70394 -1.79607 -0.453596 5.35874 -1.67265 -0.410886 5.19992 -1.60409 -0.386647 5.22089 -1.54854 -0.367392 5.29878 -1.484 -0.345066 5.34675 -1.40746 -0.318475 5.34475 -1.60155 -0.38626 6.74257 -1.30881 -0.283258 5.63135 -1.26879 -0.268884 5.87246 -1.16811 -0.233894 5.74748 -1.29581 -0.278285 7.41481 -1.01124 -0.179204 5.76926 -1.03221 -0.186919 6.87303 -0.93828 -0.153751 6.92181 -0.998524 -0.174869 9.66395 -0.688723 -0.0655228 5.60572 -0.613332 -0.0392842 5.63846 -0.548801 -0.0170921 7.11981 -2.50029 -0.767225 -0.997771 -2.57468 -0.795915 -1.00025 -2.63446 -0.818948 -0.987376 -2.71669 -0.850233 -0.992195 -2.79307 -0.879722 -0.988144 -2.87634 -0.910827 -0.988073 -2.96051 -0.943869 -0.985512 -3.05258 -0.978555 -0.986236 -3.14654 -1.01521 -0.983974 -3.25517 -1.05719 -0.990177 -3.358 -1.09636 -0.987361 -3.46862 -1.13911 -0.986534 -3.58909 -1.18455 -0.987454 -3.70953 -1.23079 -0.98433 -3.84753 -1.2844 -0.987089 -3.98656 -1.33784 -0.985159 -4.15204 -1.40034 -0.992304 -4.30086 -1.45812 -0.985032 -4.47713 -1.52497 -0.98554 -4.67094 -1.59999 -0.988088 -4.87462 -1.67749 -0.987989 -5.08807 -1.75942 -0.984546 -5.32013 -1.84848 -0.980898 -5.58835 -1.95204 -0.982731 -5.86741 -2.05896 -0.978477 -6.18266 -2.18022 -0.976607 -6.53517 -2.3148 -0.975377 -6.89944 -2.4546 -0.964172 -7.33611 -2.62223 -0.960581 -7.83739 -2.81489 -0.958272 -8.3965 -3.02885 -0.951166 -9.05741 -3.2822 -0.946633 -9.8113 -3.572 -0.936938 -10.7522 -3.93263 -0.934348 -12.11 -4.45362 -0.967517 -13.7762 -5.09331 -0.996183 -15.9575 -5.92888 -1.0301 -21.7059 -8.13444 -0.983483 -26.7276 -10.0605 -0.959886 -27.2027 -10.2437 -0.494365 -27.3725 -10.3087 -0.000502589 -29.327 -11.0586 0.46598 -29.3119 -11.053 1.00489 -29.4761 -11.1153 1.54662 -30.8252 -11.6328 2.13933 -32.6015 -12.3138 2.80728 -32.1852 -12.155 3.37847 -23.6584 -8.88374 3.17404 -22.3479 -8.381 3.46325 -23.6391 -8.8764 4.04691 -21.1261 -7.91211 4.10836 -21.6719 -8.12153 4.59524 -21.5728 -8.08426 4.98357 -21.4405 -8.03335 5.36348 -21.8414 -8.18729 5.8625 -21.2318 -7.95264 6.13001 -21.0631 -7.88824 6.49503 -21.6651 -8.11937 7.07795 -20.4945 -7.67022 7.14451 -20.1591 -7.54196 7.44133 -20.9397 -7.84048 8.11686 -21.5263 -8.06577 8.75849 -21.9404 -8.22532 9.36251 -21.5306 -8.06791 9.65087 -29.5759 -11.1541 13.5877 -28.1631 -10.6117 13.5821 -27.6979 -10.4337 13.9752 -27.6518 -10.4156 14.5661 -27.0404 -10.1811 14.8699 -6.06013 -2.1327 4.30245 -5.93313 -2.08401 4.36093 -5.85323 -2.05387 4.44658 -5.79596 -2.03144 4.54606 -5.61982 -1.96379 4.56285 -5.39841 -1.87931 4.54052 -5.3627 -1.86576 4.64877 -5.19728 -1.80221 4.65686 -5.06229 -1.75059 4.68392 -5.06098 -1.74988 4.81787 -5.099 -1.76467 4.99071 -4.83326 -1.66204 4.89604 -4.95193 -1.70791 5.14707 -5.01559 -1.73245 5.35683 -4.93767 -1.70186 5.43374 -4.25357 -1.44006 4.8838 -4.12334 -1.39012 4.88268 -4.75399 -1.63146 5.71958 -4.52931 -1.54609 5.63016 -3.99149 -1.33958 5.15477 -3.96565 -1.32918 5.27221 -3.94961 -1.32362 5.40533 -4.05978 -1.36531 5.71008 -3.33328 -1.08649 4.8854 -3.85937 -1.28873 5.77638 -3.76953 -1.25395 5.82224 -3.67475 -1.21736 5.85814 -3.27111 -1.0631 5.40268 -3.23441 -1.04942 5.51254 -3.12078 -1.0053 5.49514 -3.29744 -1.07272 5.98917 -3.14132 -1.01344 5.90218 -3.14728 -1.01518 6.11699 -3.09791 -0.996253 6.2363 -2.9912 -0.955542 6.23954 -2.84392 -0.898903 6.15051 -2.7441 -0.860438 6.15732 -2.69771 -0.843043 6.28979 -2.60381 -0.807196 6.3117 -2.6676 -0.831494 6.74893 -2.23542 -0.665627 5.84558 -2.14036 -0.629547 5.83034 -1.97575 -0.56605 5.59553 -1.77412 -0.489034 5.20396 -1.70276 -0.460979 5.21756 -1.63929 -0.437054 5.25863 -1.60584 -0.423816 5.42415 -1.52448 -0.392752 5.40535 -1.44611 -0.362474 5.39456 -1.66367 -0.445928 6.86907 -1.36163 -0.330652 5.75131 -1.29349 -0.303788 5.82572 -1.20006 -0.268237 5.74111 -1.31175 -0.312003 7.19927 -1.10272 -0.231084 6.2706 -0.974343 -0.182322 5.84349 -0.979339 -0.183495 6.87769 -0.919374 -0.160799 7.44435 -0.723533 -0.0852684 5.5938 -0.650284 -0.0576241 5.63727 -0.639127 -0.053607 9.64882 -2.38188 -0.786471 -1.0042 -2.43375 -0.807905 -0.988941 -2.51382 -0.841343 -0.999343 -2.57347 -0.866419 -0.987368 -2.64677 -0.8969 -0.986849 -2.72783 -0.931062 -0.990415 -2.8031 -0.962439 -0.985362 -2.87938 -0.993765 -0.978016 -2.96925 -1.0314 -0.98028 -3.06891 -1.07279 -0.985541 -3.16852 -1.11502 -0.987555 -3.26234 -1.15445 -0.980851 -3.37183 -1.19925 -0.982117 -3.48122 -1.24586 -0.979688 -3.61605 -1.3016 -0.988926 -3.72843 -1.34902 -0.978872 -3.8808 -1.41289 -0.98905 -4.01861 -1.47015 -0.98482 -4.16616 -1.53201 -0.980442 -4.33029 -1.60106 -0.979545 -4.51305 -1.67639 -0.98149 -4.70552 -1.7572 -0.98094 -4.92435 -1.84887 -0.98527 -5.14425 -1.94022 -0.981915 -5.40901 -2.05082 -0.988281 -5.65723 -2.1546 -0.978531 -5.94257 -2.27385 -0.97262 -6.27282 -2.4121 -0.971535 -6.63043 -2.56187 -0.967096 -7.01743 -2.7232 -0.957716 -7.48545 -2.91893 -0.956696 -8.00918 -3.13793 -0.952569 -8.59842 -3.38375 -0.944337 -9.26095 -3.6608 -0.930343 -10.0983 -4.01109 -0.926343 -11.2561 -4.4944 -0.948973 -12.6454 -5.07563 -0.965213 -14.5964 -5.89076 -1.00893 -16.8545 -6.83398 -1.01674 -20.1353 -8.20616 -1.04578 -27.2167 -11.1648 -0.766427 -27.7759 -11.3984 -0.286073 -29.0005 -11.9099 0.195975 -28.8429 -11.8444 0.736674 -28.8611 -11.852 1.27307 -29.1294 -11.9646 1.81735 -31.8587 -13.1052 2.48926 -33.1742 -13.6544 3.17148 -23.936 -9.79368 3.00308 -23.4689 -9.59928 3.40102 -27.149 -11.1364 4.29526 -21.5294 -8.78819 4.00434 -22.0075 -8.98771 4.48746 -22.1024 -9.02807 4.92183 -23.234 -9.50057 5.5706 -21.1137 -8.61426 5.54898 -22.3345 -9.12467 6.25008 -22.4881 -9.18962 6.72544 -23.2593 -9.5115 7.38348 -20.6724 -8.43008 7.06699 -21.6334 -8.8315 7.78861 -20.0686 -8.17811 7.69095 -24.9283 -10.2085 9.8631 -26.6605 -10.9326 11.0451 -26.0797 -10.6898 11.3703 -27.3628 -11.2263 13.6647 -27.1718 -11.1467 14.7936 -5.8331 -2.2284 4.54342 -5.61904 -2.13959 4.53634 -5.52364 -2.09933 4.605 -5.38113 -2.03998 4.63715 -5.23864 -1.97984 4.66506 -5.2834 -1.99907 4.83746 -5.49896 -2.08844 5.15865 -5.32205 -2.01553 5.15926 -5.29044 -2.00154 5.28158 -5.09489 -1.91985 5.25468 -5.06712 -1.90891 5.38071 -5.09047 -1.91843 5.56102 -4.7289 -1.76758 5.3511 -4.67172 -1.74344 5.44449 -4.57915 -1.70494 5.5013 -4.03662 -1.47834 5.04098 -3.89585 -1.41878 5.01874 -3.93483 -1.43574 5.2097 -3.9503 -1.44225 5.38051 -4.22544 -1.55646 5.90039 -3.94502 -1.43931 5.6962 -3.82972 -1.39178 5.70518 -3.83056 -1.39219 5.88001 -3.64934 -1.31662 5.78752 -3.44154 -1.22912 5.64038 -3.46803 -1.23978 5.86207 -3.12118 -1.09524 5.46201 -3.38215 -1.20477 6.09932 -3.28067 -1.16158 6.11852 -3.0203 -1.0538 5.83093 -3.11405 -1.09229 6.22066 -2.9957 -1.04312 6.19835 -2.91092 -1.00761 6.24473 -2.76687 -0.947228 6.15419 -2.75616 -0.942943 6.36913 -2.63284 -0.890824 6.31929 -2.59943 -0.877964 6.49744 -2.24041 -0.727764 5.79202 -2.18225 -0.702818 5.88037 -2.09431 -0.666273 5.88317 -1.79898 -0.542355 5.21078 -1.72573 -0.51161 5.21566 -1.67531 -0.491077 5.30536 -1.73944 -0.518224 5.84735 -1.56371 -0.444403 5.46334 -1.4785 -0.409084 5.42453 -1.63936 -0.476101 6.57487 -1.48844 -0.412785 6.27218 -1.30297 -0.335664 5.70015 -1.27829 -0.32485 6.04995 -1.13854 -0.266592 5.63868 -1.2383 -0.308089 7.08762 -1.00761 -0.211648 5.83876 -1.01933 -0.216731 6.86299 -0.928718 -0.179251 6.92183 -0.984595 -0.203092 9.624 -0.683966 -0.0762608 5.58566 -0.610929 -0.0466679 5.64846 -0.548735 -0.0206151 7.14982 -2.38102 -0.851072 -0.993213 -2.45215 -0.883681 -0.997779 -2.51074 -0.909747 -0.986848 -2.58284 -0.943217 -0.987374 -2.65602 -0.975643 -0.985757 -2.73016 -1.00902 -0.981899 -2.81107 -1.046 -0.981921 -2.894 -1.08299 -0.979456 -2.98364 -1.12456 -0.980324 -3.08213 -1.1688 -0.984033 -3.17381 -1.2102 -0.979017 -3.27328 -1.2552 -0.976489 -3.3893 -1.30759 -0.981339 -3.51406 -1.36458 -0.987432 -3.63207 -1.41769 -0.984351 -3.75106 -1.47167 -0.977331 -3.88661 -1.53295 -0.97579 -4.03873 -1.60146 -0.97873 -4.20053 -1.67553 -0.980672 -4.36344 -1.74838 -0.977076 -4.54481 -1.8305 -0.975973 -4.75148 -1.92444 -0.980197 -4.96015 -2.01914 -0.977089 -5.18643 -2.12091 -0.973773 -5.45646 -2.24382 -0.979376 -5.72856 -2.36637 -0.9752 -6.0104 -2.49419 -0.964334 -6.36336 -2.65404 -0.966573 -6.73487 -2.82267 -0.961318 -7.14348 -3.00742 -0.95286 -7.61544 -3.22116 -0.946181 -8.16057 -3.46743 -0.939982 -8.77784 -3.74695 -0.930015 -9.55011 -4.09649 -0.929344 -10.4228 -4.49172 -0.918811 -11.6932 -5.06722 -0.944008 -13.2377 -5.76628 -0.962892 -15.5366 -6.8069 -1.02401 -17.7054 -7.78841 -0.981976 -20.5383 -9.07088 -0.920882 -27.547 -12.2433 -0.551354 -27.7035 -12.3146 -0.0381551 -28.445 -12.6502 0.469298 -28.3393 -12.6032 1.00479 -28.3175 -12.5925 1.53769 -28.7141 -12.7718 2.08634 -40.7378 -18.2153 3.32159 -41.276 -18.4591 4.13682 -22.2258 -9.83451 3.09015 -22.7147 -10.0561 3.56676 -23.6739 -10.4904 4.12741 -22.7461 -10.07 4.43577 -22.2202 -9.83262 4.77999 -22.1471 -9.79966 5.19376 -22.605 -10.0068 5.72047 -29.5837 -13.1663 7.7911 -28.4775 -12.6651 8.09509 -27.7147 -12.3204 8.45333 -27.5573 -12.2485 8.96317 -27.3045 -12.1348 10.5655 -6.20401 -2.58234 4.47218 -6.17147 -2.56721 4.59595 -5.98825 -2.48466 4.62167 -5.74441 -2.37375 4.59902 -5.61789 -2.31644 4.64997 -5.58234 -2.30061 4.76421 -5.5879 -2.30361 4.9127 -5.59153 -2.30543 5.06244 -5.49734 -2.26202 5.13535 -5.45204 -2.24161 5.24894 -5.60356 -2.31064 5.53829 -5.32816 -2.1861 5.44894 -5.08504 -2.07569 5.37675 -5.10247 -2.08315 5.55089 -4.80926 -1.9509 5.41324 -4.45031 -1.78885 5.18954 -4.30596 -1.72345 5.17966 -4.2577 -1.70083 5.27354 -3.88482 -1.53206 4.98644 -4.18069 -1.66643 5.48923 -4.09123 -1.62559 5.53639 -3.98309 -1.57683 5.55857 -3.95052 -1.56187 5.67904 -3.80214 -1.49456 5.64196 -3.75583 -1.47364 5.74443 -3.56711 -1.38837 5.6362 -3.34692 -1.28828 5.46481 -3.23963 -1.23987 5.46067 -3.26205 -1.25081 5.67189 -3.29442 -1.265 5.91073 -3.16354 -1.20599 5.86921 -2.99031 -1.12783 5.73758 -2.94604 -1.10675 5.84583 -2.87212 -1.07448 5.90079 -2.90173 -1.08764 6.17715 -2.87919 -1.07735 6.35724 -2.70883 -0.9995 6.20257 -3.02575 -1.14319 7.2308 -2.60561 -0.953925 6.44976 -2.27309 -0.802494 5.82167 -2.22289 -0.780066 5.9296 -2.11239 -0.730309 5.86795 -1.82165 -0.598571 5.21727 -1.74657 -0.564133 5.21347 -1.70324 -0.54406 5.32276 -1.88539 -0.626648 6.30639 -1.60476 -0.499728 5.53042 -1.51478 -0.459012 5.47326 -1.59132 -0.49411 6.19367 -1.59349 -0.495486 6.65398 -1.33654 -0.37926 5.73167 -1.25154 -0.340188 5.68786 -1.32975 -0.376077 6.75843 -1.26756 -0.347242 7.00121 -1.07937 -0.262703 6.19114 -0.968838 -0.21264 5.91311 -0.965567 -0.210736 6.85771 -0.909891 -0.185809 7.45436 -0.91815 -0.189443 9.79807 -0.646744 -0.0664397 5.63723 -0.636954 -0.0620451 9.71873 -2.38961 -0.92394 -0.99581 -2.45388 -0.954745 -0.9926 -2.51811 -0.986454 -0.987444 -2.5901 -1.02187 -0.986872 -2.66311 -1.05724 -0.984109 -2.74289 -1.09622 -0.985326 -2.81587 -1.13236 -0.978018 -2.90444 -1.17493 -0.980229 -2.99392 -1.21943 -0.97965 -3.09124 -1.26654 -0.981907 -3.18952 -1.31456 -0.980924 -3.28106 -1.35873 -0.971366 -3.40261 -1.41865 -0.979693 -3.51838 -1.47575 -0.978802 -3.64293 -1.53644 -0.978905 -3.77622 -1.6017 -0.979554 -3.91832 -1.67049 -0.980198 -4.06133 -1.74111 -0.975954 -4.21414 -1.81529 -0.971011 -4.39896 -1.90601 -0.977323 -4.58677 -1.99758 -0.977008 -4.79111 -2.09722 -0.977629 -5.00516 -2.20228 -0.974556 -5.24548 -2.32009 -0.974268 -5.50435 -2.44594 -0.971828 -5.79916 -2.59018 -0.972674 -6.10371 -2.73962 -0.965531 -6.44334 -2.90523 -0.95857 -6.82868 -3.0937 -0.95235 -7.2753 -3.3121 -0.949246 -7.77644 -3.55673 -0.943282 -8.33208 -3.82843 -0.931412 -9.00443 -4.15757 -0.924348 -9.85482 -4.57323 -0.928154 -10.7783 -5.02445 -0.912767 -12.2376 -5.73736 -0.950526 -13.9587 -6.57952 -0.969881 -16.3171 -7.73269 -1.00321 -19.172 -9.12759 -0.998043 -22.2364 -10.6259 -0.90044 -29.436 -14.1464 -0.401276 -28.5194 -13.6977 0.188054 -28.3576 -13.6187 0.734128 -28.331 -13.6053 1.27515 -28.7169 -13.7949 1.82729 -41.7393 -20.1611 3.81467 -41.6078 -20.0968 4.60823 -26.9868 -12.9484 3.84347 -27.5189 -13.2092 4.4313 -22.2051 -10.6115 4.18458 -42.4092 -20.4883 8.81372 -46.9718 -22.7194 11.5324 -48.2466 -23.3429 12.7909 -6.23829 -2.805 4.61531 -5.97934 -2.67906 4.59434 -5.93027 -2.65454 4.70546 -6.0149 -2.69653 4.91251 -5.72761 -2.55572 4.85339 -5.65215 -2.51863 4.94308 -5.72806 -2.55594 5.15287 -5.56175 -2.4748 5.17062 -5.35246 -2.37208 5.1465 -4.90076 -2.15151 4.89773 -4.89361 -2.14836 5.0335 -5.0898 -2.24407 5.36506 -5.00062 -2.20017 5.43369 -4.85083 -2.12665 5.43937 -4.74103 -2.07377 5.48189 -4.30558 -1.86061 5.16407 -4.20748 -1.8127 5.20174 -4.11623 -1.76798 5.24401 -4.04941 -1.73541 5.31373 -3.99339 -1.70783 5.39702 -4.03428 -1.72789 5.60864 -4.02433 -1.72272 5.76156 -3.86547 -1.64538 5.71185 -3.67623 -1.55274 5.60997 -3.56039 -1.49675 5.60663 -3.47301 -1.45366 5.64095 -3.26697 -1.35272 5.48372 -3.16185 -1.3015 5.47843 -3.30788 -1.37322 5.90903 -3.14588 -1.29415 5.8094 -3.04767 -1.24572 5.81701 -2.96708 -1.20676 5.85708 -2.89929 -1.17338 5.92186 -2.92096 -1.18392 6.18062 -2.93189 -1.18913 6.43271 -2.72249 -1.0872 6.19025 -2.6036 -1.02826 6.14164 -3.6331 -1.53224 9.02482 -2.2475 -0.854217 5.94085 -2.17868 -0.820942 6.00214 -1.8363 -0.653255 5.20442 -1.7643 -0.618499 5.21079 -1.97931 -0.723538 6.22671 -1.86605 -0.667856 6.13956 -1.65846 -0.566023 5.6546 -1.54285 -0.509907 5.49246 -1.53258 -0.505367 5.79399 -1.56046 -0.518547 6.33078 -1.41195 -0.445847 5.99777 -1.28014 -0.380917 5.69024 -1.23537 -0.359686 5.90201 -1.28669 -0.384241 6.865 -1.21562 -0.349318 7.05789 -1.00092 -0.244907 5.90833 -1.00031 -0.24462 6.80333 -0.940119 -0.215277 7.2408 -0.976098 -0.233214 9.69393 -0.679307 -0.0870098 5.58572 -0.608569 -0.0525433 5.64846 -0.548022 -0.0231282 7.23986 -2.32056 -0.956413 -0.986362 -2.38365 -0.990208 -0.984198 -2.45356 -1.02666 -0.986863 -2.52448 -1.06307 -0.987436 -2.5953 -1.10137 -0.985712 -2.6672 -1.13862 -0.981846 -2.74581 -1.18048 -0.981911 -2.82544 -1.22228 -0.979484 -2.90608 -1.26402 -0.974465 -3.00121 -1.31409 -0.978362 -3.10506 -1.36882 -0.984602 -3.20217 -1.41969 -0.981968 -3.30701 -1.47514 -0.981272 -3.42834 -1.53894 -0.987404 -3.52841 -1.59149 -0.974398 -3.65074 -1.65596 -0.972496 -3.79058 -1.72876 -0.975829 -3.93039 -1.80233 -0.974218 -4.08766 -1.88515 -0.976395 -4.2469 -1.96882 -0.97284 -4.43038 -2.06532 -0.975954 -4.62263 -2.16622 -0.976317 -4.81681 -2.26889 -0.9696 -5.04501 -2.38802 -0.970153 -5.29937 -2.52187 -0.972592 -5.56345 -2.661 -0.96874 -5.86248 -2.81842 -0.967369 -6.18003 -2.98473 -0.960802 -6.5325 -3.17014 -0.95317 -6.94711 -3.38762 -0.950261 -7.4054 -3.62863 -0.943836 -7.92583 -3.90239 -0.935492 -8.50943 -4.20879 -0.921737 -9.23276 -4.58922 -0.91606 -10.1241 -5.05728 -0.915312 -11.2182 -5.63295 -0.915983 -12.8511 -6.491 -0.958694 -14.9879 -7.61348 -1.0071 -16.9619 -8.65177 -0.951737 -30.8165 -15.9326 -0.190759 -30.1844 -15.6003 0.41977 -30.2241 -15.6218 1.00514 -30.4677 -15.7497 1.59612 -46.5813 -24.2179 3.73618 -5.65094 -2.70716 4.78064 -5.48212 -2.61787 4.79781 -5.36484 -2.55707 4.84961 -5.848 -2.81113 5.39164 -5.41887 -2.5856 5.1895 -5.55612 -2.65749 5.46439 -5.15614 -2.44681 5.26125 -4.92667 -2.32675 5.19819 -5.00152 -2.36628 5.42262 -4.84032 -2.28159 5.41702 -4.81671 -2.26857 5.54964 -4.52273 -2.11425 5.39088 -4.43559 -2.06902 5.44842 -4.18841 -1.93825 5.31669 -4.07875 -1.88144 5.33759 -4.04045 -1.86078 5.44461 -3.94255 -1.80918 5.47599 -3.9013 -1.78741 5.58147 -3.86399 -1.76751 5.69453 -3.68687 -1.67473 5.61037 -3.6368 -1.64898 5.70452 -3.51145 -1.58321 5.68475 -4.50442 -2.10463 7.46381 -3.33509 -1.49004 5.75085 -3.34772 -1.49662 5.95703 -3.2478 -1.4438 5.97004 -3.07046 -1.35052 5.83489 -2.94203 -1.28326 5.78084 -2.8459 -1.23313 5.78464 -2.84296 -1.23128 5.98021 -2.71741 -1.16555 5.9188 -2.67625 -1.14389 6.04262 -2.61651 -1.11187 6.13002 -2.57242 -1.0896 6.26244 -2.51174 -1.05714 6.35764 -2.42249 -1.01062 6.37799 -1.99359 -0.784581 5.39747 -1.8282 -0.697806 5.12547 -1.78392 -0.675529 5.21734 -1.74371 -0.653594 5.32752 -1.89919 -0.735362 6.17385 -1.80385 -0.685994 6.14304 -1.56885 -0.561708 5.51112 -1.52486 -0.538226 5.64788 -1.5783 -0.567212 6.28136 -1.54567 -0.550126 6.56593 -1.35055 -0.446636 5.94753 -1.23387 -0.385288 5.70754 -1.31888 -0.430195 6.84728 -1.23778 -0.387511 6.94174 -1.05015 -0.288913 6.07201 -0.97562 -0.249837 6.12194 -0.949764 -0.236829 6.81796 -0.896344 -0.208541 7.42445 -0.909895 -0.215568 9.868 -0.769682 -0.142015 9.78479 -0.634897 -0.0710054 9.81871 -2.2709 -0.998087 -0.99724 -2.32616 -1.0291 -0.988943 -2.39494 -1.06754 -0.992603 -2.45693 -1.10312 -0.987439 -2.52668 -1.14242 -0.98686 -2.5907 -1.17793 -0.97781 -2.66818 -1.2218 -0.97917 -2.75238 -1.27026 -0.984061 -2.82414 -1.31022 -0.974354 -2.91131 -1.35959 -0.973817 -3.01203 -1.41623 -0.981941 -3.10795 -1.47012 -0.980951 -3.2106 -1.52854 -0.982095 -3.31427 -1.58684 -0.979648 -3.42667 -1.64976 -0.978845 -3.54775 -1.71826 -0.978937 -3.66886 -1.78656 -0.974835 -3.79865 -1.86041 -0.970928 -3.94594 -1.94255 -0.971459 -4.10093 -2.03013 -0.970982 -4.26467 -2.12217 -0.969052 -4.43805 -2.22072 -0.965078 -4.64438 -2.33674 -0.970016 -4.85171 -2.45344 -0.967319 -5.08518 -2.5849 -0.967308 -5.3361 -2.72634 -0.965241 -5.61311 -2.88339 -0.963114 -5.91636 -3.05399 -0.959527 -6.24574 -3.24007 -0.952883 -6.62747 -3.45455 -0.949662 -7.05275 -3.69462 -0.944225 -7.53811 -3.9684 -0.938607 -8.07677 -4.27219 -0.927129 -8.71133 -4.62996 -0.916459 -9.46697 -5.05626 -0.90638 -10.4144 -5.58977 -0.902861 -11.7599 -6.34843 -0.929865 -13.3766 -7.26025 -0.943875 -15.862 -8.66228 -1.00663 -18.0139 -9.87591 -0.932941 -38.448 -21.3979 -0.134238 -38.2938 -21.3107 0.627937 -41.2899 -23.0003 1.41572 -45.3855 -25.3096 5.06318 -44.126 -24.6006 13.0321 -45.4126 -25.3258 15.3074 -18.9245 -10.3898 7.67283 -5.51679 -2.82889 4.67063 -5.42414 -2.77658 4.74298 -5.33732 -2.72747 4.81845 -5.11529 -2.60256 4.78122 -5.09944 -2.59327 4.90875 -4.85303 -2.45461 4.83599 -4.77295 -2.40929 4.90388 -4.95561 -2.51207 5.21798 -4.95627 -2.51353 5.37153 -4.8636 -2.46071 5.43365 -4.76991 -2.40795 5.49347 -4.34029 -2.16555 5.18588 -4.22019 -2.09846 5.19915 -4.07093 -2.0135 5.17313 -4.01904 -1.98406 5.2586 -4.20003 -2.08651 5.63807 -3.92203 -1.92999 5.44193 -3.85357 -1.8914 5.50976 -3.79584 -1.85877 5.59172 -3.73617 -1.82507 5.67273 -3.56919 -1.73062 5.59402 -3.51923 -1.70293 5.68707 -3.41759 -1.64509 5.69794 -4.41148 -2.20577 7.536 -3.27283 -1.56349 5.81202 -3.20821 -1.52794 5.88377 -2.86512 -1.33392 5.4342 -2.76235 -1.27565 5.41192 -2.6478 -1.21108 5.36089 -2.74748 -1.26778 5.75478 -2.69461 -1.23812 5.84345 -2.66727 -1.22198 5.99416 -2.61347 -1.19186 6.09092 -2.54695 -1.15433 6.15989 -2.194 -0.955308 5.47556 -2.09594 -0.899702 5.42564 -1.93888 -0.811306 5.19646 -1.84758 -0.759424 5.14036 -1.79552 -0.731033 5.20446 -1.76227 -0.711561 5.33413 -1.96267 -0.824661 6.33153 -1.73339 -0.695496 5.78472 -1.59562 -0.618117 5.53891 -1.54773 -0.591313 5.65701 -1.61687 -0.630421 6.34824 -1.51277 -0.571699 6.25266 -1.44541 -0.533167 6.34081 -1.34217 -0.474681 6.22131 -1.34088 -0.474991 6.77982 -1.26188 -0.429884 6.86504 -1.19203 -0.390513 7.04798 -0.990189 -0.276389 5.94811 -0.985519 -0.27382 6.80328 -0.936937 -0.246787 7.39036 -0.957165 -0.258101 9.614 -0.673649 -0.0977031 5.58569 -0.700767 -0.113722 9.88707 -0.545667 -0.0264825 7.20981 -2.21367 -1.03292 -1.00069 -2.26205 -1.06221 -0.986311 -2.32196 -1.09882 -0.984184 -2.38963 -1.13916 -0.986942 -2.45825 -1.18044 -0.987457 -2.52014 -1.21788 -0.979397 -2.58974 -1.26001 -0.975574 -2.6728 -1.31048 -0.981959 -2.75019 -1.35616 -0.979524 -2.82748 -1.40371 -0.974494 -2.92025 -1.45966 -0.978284 -3.01304 -1.51545 -0.978978 -3.10679 -1.57214 -0.976432 -3.20827 -1.63342 -0.976024 -3.31078 -1.69458 -0.972026 -3.42196 -1.76135 -0.969422 -3.54081 -1.83364 -0.967709 -3.67511 -1.91514 -0.971072 -3.81144 -1.99653 -0.96965 -3.95546 -2.08336 -0.967621 -4.10145 -2.17106 -0.960259 -4.28599 -2.28288 -0.967835 -4.4648 -2.39082 -0.964543 -4.66774 -2.51347 -0.965825 -4.87268 -2.63687 -0.959376 -5.11043 -2.7806 -0.958896 -5.37432 -2.93898 -0.959003 -5.6469 -3.10355 -0.951967 -5.97841 -3.30326 -0.954982 -6.32828 -3.51475 -0.950355 -6.72846 -3.75545 -0.947793 -7.14696 -4.00875 -0.934144 -7.6506 -4.31162 -0.926541 -8.22276 -4.65758 -0.915458 -8.89747 -5.06391 -0.904622 -9.75088 -5.57879 -0.903178 -10.759 -6.18697 -0.895667 -12.1681 -7.03626 -0.912915 -14.0314 -8.16011 -0.937677 -16.5451 -9.67551 -0.966456 -19.5916 -11.5136 -0.947137 -23.428 -13.8267 -0.868257 -40.4502 -24.0925 0.192693 -40.3013 -24.003 1.00698 -45.9124 -27.3874 1.93359 -45.8655 -27.3588 2.8579 -42.9067 -25.5744 3.60267 -45.8936 -27.3757 4.7147 -43.3507 -25.8424 11.644 -5.04287 -2.73958 4.57966 -4.92511 -2.66927 4.62009 -4.8986 -2.65303 4.73324 -4.93034 -2.67173 4.90052 -4.79027 -2.58726 4.91629 -4.76474 -2.57182 5.03468 -4.6576 -2.50813 5.07605 -4.71273 -2.54055 5.27826 -4.57164 -2.45556 5.28311 -4.52575 -2.42763 5.38593 -4.1825 -2.22076 5.15469 -4.12003 -2.18321 5.22913 -3.99633 -2.10847 5.23034 -4.35286 -2.32406 5.82765 -4.14847 -2.20099 5.73451 -3.90908 -2.05568 5.58167 -3.91661 -2.06145 5.75781 -3.78121 -1.97925 5.73342 -3.56204 -1.84729 5.57888 -3.47716 -1.79616 5.61668 -3.40301 -1.75099 5.66852 -3.17102 -1.61107 5.45672 -3.11825 -1.57891 5.53525 -3.05961 -1.54383 5.60478 -3.03121 -1.52676 5.73252 -2.76196 -1.3636 5.39762 -2.62714 -1.28284 5.30451 -2.58306 -1.25683 5.39099 -2.7539 -1.35961 5.95378 -2.64841 -1.29636 5.92767 -2.62308 -1.28088 6.08761 -2.53227 -1.22593 6.09384 -2.27897 -1.07324 5.66861 -2.0617 -0.942028 5.29903 -1.93239 -0.864628 5.14486 -1.84033 -0.808118 5.08003 -1.83158 -0.802892 5.27589 -1.75122 -0.754403 5.2456 -1.66099 -0.700277 5.17537 -1.7105 -0.729936 5.6287 -1.63409 -0.684431 5.62396 -1.57847 -0.650004 5.70431 -1.52675 -0.61943 5.81285 -1.53756 -0.625383 6.2521 -1.49212 -0.59837 6.45829 -1.40107 -0.543675 6.41877 -1.36586 -0.522529 6.74161 -1.27995 -0.470369 6.75835 -1.22214 -0.436286 7.01114 -1.02507 -0.316919 6.00259 -1.05681 -0.335884 7.19605 -0.936245 -0.263115 6.83778 -1.02774 -0.318431 9.83858 -0.902886 -0.243319 10.0078 -0.764102 -0.160302 9.89467 -0.633149 -0.0805246 9.9887 -2.20282 -1.09694 -0.990147 -2.25591 -1.13084 -0.982091 -2.32814 -1.17785 -0.992567 -2.38895 -1.21638 -0.987449 -2.44971 -1.2558 -0.980384 -2.52393 -1.3036 -0.984128 -2.59242 -1.34761 -0.979102 -2.66762 -1.39624 -0.978007 -2.75054 -1.4495 -0.980249 -2.82672 -1.49893 -0.973916 -2.91838 -1.55674 -0.976305 -3.00224 -1.61164 -0.969863 -3.10253 -1.67594 -0.9713 -3.20184 -1.74002 -0.969236 -3.31753 -1.81443 -0.973701 -3.42648 -1.88498 -0.969092 -3.55088 -1.96476 -0.970059 -3.66954 -2.04073 -0.961756 -3.81795 -2.13721 -0.966997 -3.95204 -2.22311 -0.958127 -4.11783 -2.33055 -0.960765 -4.30103 -2.44815 -0.965043 -4.47657 -2.56075 -0.958593 -4.68483 -2.69476 -0.959959 -4.90947 -2.83975 -0.960315 -5.14376 -2.99107 -0.955229 -5.41854 -3.16823 -0.956803 -5.71171 -3.3563 -0.95358 -6.03761 -3.56639 -0.950134 -6.39726 -3.79847 -0.944373 -6.79166 -4.05249 -0.934203 -7.24389 -4.34413 -0.924643 -7.77235 -4.68358 -0.91634 -8.37598 -5.07252 -0.904495 -9.09626 -5.53677 -0.893676 -9.96019 -6.09389 -0.88143 -11.1259 -6.84365 -0.887131 -12.7861 -7.91358 -0.921752 -14.9919 -9.33469 -0.961446 -17.4873 -10.9419 -0.942617 -33.8635 -21.4902 -0.0333147 -42.3985 -26.9869 0.572413 -42.7965 -27.2435 3.20402 -43.8561 -27.9277 16.2845 -5.17363 -3.01013 4.96698 -4.79671 -2.76775 4.78383 -4.68799 -2.69701 4.82377 -4.65665 -2.67756 4.935 -4.57887 -2.62743 5.00163 -4.44976 -2.54378 5.01426 -4.55408 -2.61172 5.26799 -4.4036 -2.51492 5.25691 -4.54782 -2.60733 5.5714 -4.36631 -2.49051 5.52153 -4.28171 -2.43638 5.57971 -4.43379 -2.53435 5.93326 -4.33278 -2.4689 5.9773 -4.31421 -2.45714 6.13096 -3.82398 -2.14136 5.63151 -4.15682 -2.35506 6.27857 -4.05769 -2.29173 6.3224 -3.49819 -1.93121 5.64958 -3.4193 -1.88105 5.6951 -4.15487 -2.35441 7.09837 -3.10312 -1.67762 5.50848 -3.01353 -1.61947 5.52015 -2.97838 -1.59682 5.63065 -2.56761 -1.33266 5.01636 -2.55089 -1.32126 5.14479 -2.465 -1.26643 5.13457 -2.51262 -1.29667 5.41202 -2.66066 -1.39272 5.94112 -2.62957 -1.37174 6.08361 -2.24722 -1.12575 5.35986 -2.15155 -1.06409 5.31353 -2.0041 -0.968597 5.11786 -1.94057 -0.927588 5.13928 -1.85158 -0.870749 5.08482 -1.83599 -0.860477 5.25275 -1.76166 -0.813378 5.24221 -1.71774 -0.785105 5.33408 -1.64148 -0.735503 5.31102 -1.68803 -0.765447 5.7752 -1.59313 -0.704604 5.69316 -1.54059 -0.670424 5.79252 -1.54338 -0.671773 6.17323 -1.5088 -0.650492 6.41866 -1.4289 -0.598529 6.43877 -1.39966 -0.579756 6.7817 -1.30192 -0.517185 6.71081 -1.24817 -0.482327 6.96394 -1.11419 -0.395861 6.56216 -0.982559 -0.311122 6.0475 -0.969822 -0.302981 6.82316 -1.11763 -0.398247 10.3612 -0.941494 -0.285238 9.61406 -0.831889 -0.214821 10.0915 -0.692859 -0.125259 9.84705 -0.54289 -0.0287458 7.07988 -2.14384 -1.12765 -0.99368 -2.1958 -1.16353 -0.98632 -2.25446 -1.20408 -0.98419 -2.31989 -1.24829 -0.986939 -2.37953 -1.28971 -0.980869 -2.44493 -1.33471 -0.979375 -2.51229 -1.38072 -0.975643 -2.58536 -1.43128 -0.975838 -2.65945 -1.48178 -0.973441 -2.7345 -1.53322 -0.968602 -2.82297 -1.59393 -0.972625 -2.9057 -1.65085 -0.967878 -2.99615 -1.71237 -0.965669 -3.09427 -1.77947 -0.965449 -3.19236 -1.8474 -0.961784 -3.31353 -1.93033 -0.969379 -3.42032 -2.00366 -0.962914 -3.54343 -2.08827 -0.961731 -3.67328 -2.17731 -0.960584 -3.81276 -2.27291 -0.958889 -3.95222 -2.36925 -0.951752 -4.12345 -2.48611 -0.955672 -4.29466 -2.60365 -0.95295 -4.49088 -2.73796 -0.954708 -4.70242 -2.88419 -0.9558 -4.92367 -3.03579 -0.952099 -5.17761 -3.20963 -0.952471 -5.44023 -3.38967 -0.945897 -5.75089 -3.60304 -0.946175 -6.07217 -3.82359 -0.936673 -6.46558 -4.09313 -0.937447 -6.87632 -4.37521 -0.926929 -7.3611 -4.70806 -0.919807 -7.8873 -5.06902 -0.90312 -8.54522 -5.52061 -0.895135 -9.30224 -6.04007 -0.880692 -10.2804 -6.71182 -0.876931 -11.5635 -7.5921 -0.883754 -13.3898 -8.84454 -0.917129 -15.8009 -10.5003 -0.947718 -18.3568 -12.2537 -0.891545 -33.0404 -22.3309 -0.372414 -33.5659 -22.6911 0.305759 -41.2625 -27.9729 7.07735 -5.3255 -3.31139 4.11341 -5.60538 -3.50332 5.33714 -5.58198 -3.48781 5.47984 -4.60134 -2.8148 4.75004 -4.53341 -2.76791 4.82396 -4.35626 -2.64659 4.78916 -4.3704 -2.65697 4.94095 -4.27636 -2.59203 4.98295 -4.2123 -2.54745 5.05556 -4.16556 -2.51601 5.1472 -4.08114 -2.45832 5.1964 -4.08479 -2.45998 5.34934 -3.94718 -2.36531 5.33105 -3.8898 -2.3268 5.41071 -3.53921 -2.08555 5.09525 -3.68509 -2.18631 5.44578 -3.4409 -2.01767 5.25209 -4.07414 -2.45259 6.3551 -3.13908 -1.81148 5.09816 -3.29296 -1.91636 5.49678 -3.15025 -1.81897 5.42584 -3.11904 -1.79746 5.53857 -2.69787 -1.50907 4.95492 -2.63165 -1.4635 4.98414 -2.54409 -1.40278 4.96923 -2.51568 -1.38394 5.07196 -2.50678 -1.37717 5.21787 -2.36182 -1.27814 5.07608 -2.67086 -1.49001 5.95373 -2.34017 -1.26357 5.38412 -2.2886 -1.22713 5.44932 -2.07725 -1.08294 5.10588 -1.91744 -0.972916 4.86455 -1.86178 -0.93499 4.89406 -1.88616 -0.951196 5.16329 -1.84913 -0.925778 5.26667 -1.78182 -0.880131 5.27587 -1.68028 -0.810508 5.16051 -1.61003 -0.761805 5.14686 -1.8514 -0.927613 6.3651 -1.51945 -0.699788 5.31624 -1.45898 -0.658504 5.34693 -1.44086 -0.645849 5.58003 -1.36669 -0.595209 5.56021 -1.44867 -0.650848 6.41915 -1.39064 -0.611971 6.56609 -1.33679 -0.573962 6.76129 -1.25716 -0.519702 6.80781 -1.16452 -0.456098 6.74374 -1.01329 -0.352396 6.08192 -1.00737 -0.348171 6.86783 -0.918662 -0.287113 6.81787 -1.00578 -0.347678 9.80865 -0.893977 -0.27097 10.1675 -0.752981 -0.173636 9.83474 -0.629289 -0.0894005 10.1286 -2.13581 -1.1942 -0.990148 -2.19241 -1.23567 -0.988858 -2.25666 -1.28286 -0.992453 -2.31422 -1.3252 -0.987322 -2.37281 -1.36751 -0.980299 -2.44379 -1.41913 -0.98403 -2.50998 -1.46801 -0.978947 -2.58195 -1.52045 -0.977839 -2.65487 -1.57382 -0.974191 -2.72881 -1.62713 -0.96795 -2.81605 -1.6917 -0.970472 -2.90437 -1.75518 -0.969752 -2.9926 -1.82049 -0.965837 -3.0952 -1.89606 -0.969042 -3.19983 -1.97156 -0.968461 -3.30442 -2.04787 -0.964035 -3.41669 -2.1297 -0.9604 -3.54429 -2.22273 -0.961642 -3.67287 -2.31658 -0.957945 -3.81578 -2.4215 -0.957923 -3.96067 -2.52727 -0.952268 -4.13621 -2.65545 -0.956866 -4.31175 -2.7843 -0.954524 -4.50464 -2.92424 -0.952475 -4.72044 -3.08275 -0.953098 -4.94497 -3.24653 -0.948325 -5.20207 -3.43452 -0.947025 -5.47457 -3.63325 -0.941313 -5.80359 -3.87394 -0.944199 -6.14132 -4.12062 -0.936045 -6.54334 -4.41362 -0.933933 -6.96164 -4.72003 -0.919676 -7.45287 -5.07909 -0.907313 -8.03341 -5.50179 -0.896132 -8.70212 -5.99077 -0.880488 -9.532 -6.59704 -0.869464 -10.6506 -7.41421 -0.876188 -12.1893 -8.53761 -0.902921 -13.9545 -9.82745 -0.895229 -16.8736 -11.9593 -0.948585 -18.9589 -13.483 -0.794765 -30.4385 -21.8677 -0.61176 -30.7955 -22.1285 0.024512 -30.716 -22.0711 0.680432 -38.2418 -27.5676 1.41655 -38.0997 -27.4641 3.8565 -38.713 -27.9131 4.73318 -38.2206 -27.5531 5.50666 -38.464 -27.7317 10.5743 -5.3455 -3.53962 3.86404 -5.2903 -3.49945 3.95943 -5.22643 -3.45305 4.04866 -5.21843 -3.44634 4.17425 -5.29218 -3.50079 4.35947 -5.60566 -3.73022 4.72651 -4.8782 -3.19818 4.4559 -4.81528 -3.15214 4.53894 -5.07119 -3.33865 4.89231 -5.25197 -3.47175 5.1996 -5.03591 -3.31427 5.15892 -4.45748 -2.89172 4.76306 -4.31549 -2.78796 4.76088 -4.33063 -2.7984 4.91276 -4.26858 -2.75378 4.98856 -4.20565 -2.70718 5.06276 -4.11277 -2.63945 5.10172 -4.25916 -2.74585 5.42008 -4.15566 -2.67083 5.45165 -3.80416 -2.414 5.16616 -3.75082 -2.37481 5.24426 -3.55939 -2.23516 5.13688 -3.59678 -2.2626 5.33718 -3.95975 -2.52753 6.01946 -3.28237 -2.03259 5.18288 -3.26373 -2.01939 5.30503 -3.03538 -1.85255 5.09438 -3.08251 -1.88707 5.32539 -3.00786 -1.83189 5.35611 -2.89545 -1.7497 5.31902 -2.66491 -1.58145 5.05325 -2.52915 -1.4822 4.94752 -2.47759 -1.44442 4.99933 -2.41627 -1.40093 5.03292 -2.43165 -1.41112 5.23045 -2.30931 -1.32241 5.13093 -2.2956 -1.31239 5.27583 -2.12761 -1.18928 5.04553 -2.0663 -1.14519 5.07108 -1.91174 -1.03194 4.84046 -1.95734 -1.06525 5.15472 -1.8338 -0.974606 4.99154 -1.75982 -0.920351 4.96393 -1.77935 -0.934752 5.24343 -1.70636 -0.881187 5.22335 -1.62061 -0.819264 5.154 -1.57879 -0.789186 5.24437 -1.7054 -0.880567 6.04374 -1.45419 -0.698178 5.26921 -1.56365 -0.777814 6.10249 -1.35813 -0.627016 5.43428 -1.48108 -0.716645 6.48701 -1.42121 -0.673569 6.61523 -1.36249 -0.630153 6.77195 -1.27701 -0.5684 6.76018 -1.19855 -0.511248 6.80575 -1.05083 -0.403203 6.19536 -0.985097 -0.354615 6.28601 -0.954222 -0.332157 6.86306 -1.07896 -0.424344 10.152 -0.929276 -0.314669 9.73384 -0.819927 -0.235197 10.1514 -0.685205 -0.135827 9.84713 -0.567887 -0.0505295 11.0197 -2.07495 -1.22277 -0.993271 -2.12474 -1.26153 -0.985953 -2.18122 -1.30496 -0.983864 -2.24342 -1.35298 -0.986501 -2.29987 -1.39722 -0.980468 -2.36967 -1.45183 -0.985345 -2.42716 -1.49592 -0.975221 -2.49793 -1.55136 -0.975359 -2.56309 -1.60102 -0.967025 -2.64724 -1.66663 -0.973977 -2.71901 -1.72275 -0.96638 -2.79844 -1.78449 -0.961771 -2.89124 -1.85646 -0.965074 -2.9783 -1.92464 -0.959608 -3.07309 -1.99739 -0.955981 -3.19548 -2.09268 -0.968785 -3.29121 -2.16711 -0.957373 -3.41461 -2.26302 -0.961144 -3.53993 -2.3608 -0.959932 -3.67294 -2.46404 -0.958112 -3.81457 -2.57376 -0.955341 -3.9782 -2.70018 -0.959032 -4.12846 -2.81705 -0.948268 -4.31497 -2.96282 -0.950087 -4.51113 -3.11498 -0.947863 -4.72361 -3.2791 -0.94438 -4.96566 -3.46729 -0.945054 -5.21732 -3.66272 -0.93874 -5.50059 -3.88219 -0.933497 -5.82967 -4.13875 -0.9328 -6.19138 -4.41917 -0.928485 -6.59995 -4.73648 -0.923328 -7.05734 -5.09165 -0.913993 -7.56164 -5.48339 -0.897524 -8.15969 -5.94806 -0.882217 -8.86209 -6.49309 -0.863484 -9.80646 -7.22615 -0.862755 -11.012 -8.16277 -0.866499 -12.6193 -9.411 -0.879532 -14.576 -10.9299 -0.867907 -17.5659 -13.2518 -0.884054 -29.698 -22.6731 -0.280112 -29.3872 -22.4314 0.372283 -29.9518 -22.8702 1.01085 -37.5746 -28.79 2.65279 -38.6246 -29.6059 4.3895 -38.4479 -29.469 6.91349 -37.2936 -28.5739 10.9162 -5.46076 -3.85252 4.06614 -5.37503 -3.7861 4.14805 -5.26144 -3.69801 4.2083 -5.15455 -3.6153 4.26946 -5.13598 -3.60109 4.39176 -5.03389 -3.5217 4.45254 -4.96541 -3.46827 4.53626 -4.80373 -3.34288 4.54179 -4.92445 -3.43657 4.78184 -4.54179 -3.13929 4.58642 -4.479 -3.09055 4.66342 -4.46618 -3.08064 4.78699 -4.77343 -3.3199 5.23126 -4.3156 -2.96385 4.9158 -4.29123 -2.94559 5.03174 -4.14574 -2.83224 5.01651 -4.0137 -2.72932 5.00949 -4.14904 -2.83485 5.31167 -4.17381 -2.8543 5.49586 -3.80978 -2.57142 5.19448 -3.72961 -2.50924 5.23821 -3.62252 -2.42529 5.24304 -3.49412 -2.32665 5.21488 -3.71546 -2.49811 5.68803 -3.21903 -2.11277 5.10712 -3.79807 -2.56187 6.16149 -3.2311 -2.12157 5.42975 -3.16436 -2.06984 5.4814 -3.05611 -1.98619 5.45872 -3.32037 -2.1908 6.10438 -2.93612 -1.89281 5.57733 -2.51984 -1.56915 4.94255 -2.46547 -1.52756 4.98669 -2.3735 -1.45551 4.95234 -2.42935 -1.49899 5.23568 -2.29768 -1.3969 5.11146 -2.18143 -1.30667 5.00932 -2.11836 -1.2578 5.02804 -2.06305 -1.2146 5.0632 -1.95053 -1.1275 4.94306 -1.86316 -1.05999 4.88317 -1.84954 -1.04876 5.03241 -1.76408 -0.982549 4.96895 -1.77771 -0.992971 5.22037 -1.72141 -0.949621 5.25733 -1.64469 -0.889786 5.21755 -1.57474 -0.835538 5.19471 -1.55064 -0.816794 5.36129 -1.48853 -0.768268 5.37421 -1.44201 -0.732967 5.46305 -1.37699 -0.681861 5.46376 -1.31391 -0.632468 5.47274 -1.47811 -0.761146 6.84005 -1.38798 -0.691394 6.80189 -1.30672 -0.627865 6.81083 -1.2155 -0.556714 6.73887 -1.13413 -0.493863 6.73402 -0.997496 -0.387104 6.15164 -0.982485 -0.376224 6.83817 -1.14444 -0.502519 10.3746 -0.978748 -0.374065 9.72906 -0.877684 -0.295076 10.2077 -0.740034 -0.188895 9.83489 -0.624469 -0.0992238 10.2888 -2.01428 -1.24835 -0.996343 -2.06293 -1.28908 -0.98982 -2.1116 -1.32973 -0.981699 -2.17737 -1.38438 -0.992148 -2.23276 -1.4296 -0.98706 -2.2891 -1.47578 -0.979929 -2.34546 -1.52187 -0.971 -2.41317 -1.57819 -0.972472 -2.48283 -1.63551 -0.971507 -2.55815 -1.69836 -0.97382 -2.6288 -1.75648 -0.967617 -2.7118 -1.82481 -0.970121 -2.79006 -1.88941 -0.963861 -2.8807 -1.96418 -0.965508 -2.96665 -2.03421 -0.95834 -3.05922 -2.11075 -0.952907 -3.17175 -2.2041 -0.958721 -3.2796 -2.29268 -0.955119 -3.40072 -2.39335 -0.956536 -3.53047 -2.50054 -0.9575 -3.66791 -2.61315 -0.957457 -3.81292 -2.73318 -0.955909 -3.96556 -2.85958 -0.952405 -4.1411 -3.00467 -0.953971 -4.31763 -3.15046 -0.948201 -4.50946 -3.30818 -0.941966 -4.7384 -3.49766 -0.944375 -4.96936 -3.68777 -0.936857 -5.22985 -3.90286 -0.93165 -5.53614 -4.15509 -0.932087 -5.87388 -4.43417 -0.929952 -6.25747 -4.75014 -0.928169 -6.66488 -5.08712 -0.91643 -7.13439 -5.47397 -0.904232 -7.67258 -5.91798 -0.889168 -8.29664 -6.43319 -0.870282 -9.05045 -7.05556 -0.85176 -10.0732 -7.89969 -0.851299 -11.4738 -9.05441 -0.868897 -13.4286 -10.6678 -0.904779 -15.8548 -12.6703 -0.911146 -18.0938 -14.5167 -0.788539 -28.7034 -23.2712 -0.586026 -29.3446 -23.8009 0.0313753 -29.0528 -23.5601 0.687572 -38.442 -31.3083 2.30217 -28.494 -23.0998 2.59504 -28.4149 -23.0347 3.22395 -28.4035 -23.0247 3.85753 -28.4141 -23.0348 4.49523 -28.4085 -23.0299 5.13312 -28.4248 -23.0441 5.77709 -28.3944 -23.0186 6.41566 -33.9422 -27.5966 9.8342 -38.5646 -31.4129 14.7017 -5.1693 -3.85365 3.89057 -5.06849 -3.77011 3.95564 -5.11695 -3.81009 4.11862 -5.20278 -3.88085 4.31326 -4.91522 -3.64434 4.24183 -5.02402 -3.73447 4.45817 -4.87821 -3.61317 4.48149 -4.9085 -3.63901 4.64462 -4.65343 -3.42784 4.56717 -4.55342 -3.34619 4.61532 -4.41607 -3.23308 4.62516 -4.41671 -3.23342 4.76084 -4.37136 -3.19592 4.85497 -4.31259 -3.14724 4.93575 -4.2116 -3.06418 4.97061 -4.2986 -3.1358 5.20993 -4.07965 -2.95503 5.10967 -3.97865 -2.87139 5.13599 -4.05612 -2.93522 5.37931 -4.06255 -2.94152 5.54327 -4.0278 -2.91262 5.65887 -3.82696 -2.74644 5.54936 -3.6971 -2.63934 5.52811 -3.67672 -2.62255 5.65981 -3.76881 -2.69815 5.96677 -3.24584 -2.26621 5.3222 -3.20135 -2.23022 5.40719 -3.13193 -2.17266 5.45177 -3.16348 -2.19878 5.67147 -2.96122 -2.03263 5.47867 -2.90044 -1.9821 5.53364 -2.59214 -1.72802 5.10357 -2.44554 -1.60669 4.9648 -2.41255 -1.57936 5.05083 -2.31887 -1.50163 5.0074 -2.23768 -1.43455 4.98692 -2.17287 -1.38087 4.99931 -2.14663 -1.35988 5.10752 -2.16679 -1.37659 5.34117 -1.92223 -1.17541 4.87275 -1.87382 -1.13436 4.91347 -1.86987 -1.13135 5.09067 -1.78466 -1.06107 5.02872 -1.80111 -1.0752 5.2898 -1.7809 -1.05802 5.44982 -1.66653 -0.96423 5.28021 -1.59683 -0.90593 5.25847 -1.58831 -0.899297 5.48299 -1.47478 -0.805368 5.27682 -1.42151 -0.762013 5.31756 -1.3693 -0.718303 5.36679 -1.31709 -0.675167 5.42465 -1.25114 -0.621077 5.40349 -1.40742 -0.750757 6.80165 -1.32828 -0.685307 6.81148 -1.25015 -0.620521 6.82934 -1.08751 -0.485708 6.11352 -1.01789 -0.428721 6.12609 -1.01074 -0.422851 6.84254 -0.932563 -0.358925 6.86324 -0.854418 -0.29358 6.87216 -0.917246 -0.346658 9.92364 -0.803707 -0.253255 10.1316 -0.674382 -0.146687 9.81721 -0.553344 -0.0462442 9.42986 -1.94804 -1.2672 -0.991892 -1.99463 -1.30885 -0.986208 -2.04223 -1.35049 -0.979031 -2.10123 -1.40143 -0.983802 -2.1555 -1.44865 -0.979808 -2.21541 -1.50145 -0.980491 -2.2697 -1.54847 -0.972501 -2.33628 -1.60678 -0.975168 -2.40282 -1.66598 -0.975388 -2.46474 -1.71946 -0.967041 -2.53325 -1.77953 -0.962228 -2.61406 -1.85082 -0.966372 -2.68926 -1.91632 -0.961745 -2.7777 -1.99405 -0.965132 -2.85482 -2.06136 -0.954323 -2.94426 -2.13981 -0.950874 -3.05459 -2.23614 -0.958827 -3.15831 -2.3266 -0.957504 -3.27724 -2.43026 -0.96116 -3.38949 -2.52904 -0.95549 -3.50937 -2.63428 -0.949464 -3.64353 -2.75159 -0.946961 -3.80616 -2.89421 -0.954955 -3.95653 -3.02534 -0.948298 -4.1278 -3.17501 -0.9465 -4.31425 -3.33863 -0.944339 -4.51595 -3.51515 -0.941063 -4.74051 -3.71115 -0.938612 -4.98689 -3.9275 -0.935734 -5.26374 -4.1698 -0.933524 -5.56243 -4.43228 -0.927391 -5.9145 -4.73935 -0.925997 -6.28938 -5.06743 -0.91614 -6.73177 -5.45493 -0.909605 -7.21229 -5.87535 -0.893542 -7.76032 -6.35578 -0.872762 -8.47294 -6.97922 -0.865377 -8.99464 -7.43604 -0.784674 -9.75409 -8.10084 -0.724964 -11.9786 -10.0478 -0.868738 -14.022 -11.8371 -0.883666 -28.7135 -24.6979 -0.298862 -28.7184 -24.7029 0.35585 -28.7224 -24.7068 1.01052 -37.8579 -32.7044 3.61597 -36.3412 -31.3771 6.02017 -36.3986 -31.4287 8.57059 -31.2073 -26.8841 10.4345 -32.2778 -27.8217 12.3298 -33.7729 -29.1312 13.6943 -33.3422 -28.7543 14.3588 -4.94326 -3.89016 4.01169 -4.90279 -3.85554 4.11433 -4.86809 -3.82509 4.22084 -4.91616 -3.86685 4.5297 -4.53099 -3.52948 4.35066 -4.41026 -3.42452 4.37829 -4.57139 -3.56506 4.65316 -4.47936 -3.48462 4.7069 -4.54596 -3.54275 4.91038 -4.42236 -3.43494 4.93139 -4.32266 -3.34763 4.97254 -4.27555 -3.30601 5.06689 -4.19876 -3.23915 5.12819 -4.10379 -3.15624 5.16742 -3.91986 -2.99518 5.09648 -3.83824 -2.92384 5.14107 -3.82075 -2.90854 5.26652 -4.09426 -3.14828 5.78146 -3.92658 -3.00076 5.72017 -3.77702 -2.86961 5.67465 -3.59963 -2.71418 5.57901 -3.76036 -2.85598 5.98991 -3.62702 -2.73919 5.95759 -3.16392 -2.33281 5.37638 -3.16179 -2.33097 5.5321 -3.10112 -2.27914 5.59321 -2.98298 -2.17496 5.54767 -2.9444 -2.1417 5.64556 -2.77819 -1.99572 5.49432 -2.44862 -1.70679 4.99292 -2.37248 -1.64031 4.98665 -2.3194 -1.59386 5.02945 -2.27401 -1.55409 5.08843 -2.17954 -1.4719 5.03277 -2.1727 -1.4649 5.18587 -2.11671 -1.41649 5.22408 -2.12049 -1.4199 5.42276 -1.91321 -1.2381 5.0337 -1.80506 -1.14384 4.90146 -1.89191 -1.21944 5.36386 -1.81467 -1.15223 5.33053 -1.79258 -1.13236 5.48181 -1.66113 -1.01766 5.24793 -1.60028 -0.964467 5.25541 -1.53746 -0.9097 5.25171 -1.47658 -0.856656 5.25609 -1.62573 -0.986893 6.22981 -1.37623 -0.768367 5.35678 -1.32414 -0.722678 5.40561 -1.28472 -0.688986 5.53132 -1.44732 -0.83067 6.93783 -1.34874 -0.745227 6.82147 -1.27279 -0.677518 6.84027 -1.18982 -0.605896 6.80807 -1.03322 -0.468001 6.06061 -0.987714 -0.428279 6.30052 -0.962849 -0.406676 6.88788 -0.885831 -0.339344 6.89779 -0.958175 -0.403455 9.77883 -0.850695 -0.309359 9.98792 -0.73045 -0.203908 9.90479 -0.625282 -0.112109 10.8187 -1.9332 -1.33037 -0.989273 -1.97874 -1.37292 -0.982836 -2.03092 -1.42115 -0.981679 -2.08875 -1.47499 -0.985498 -2.1409 -1.52403 -0.980397 -2.19407 -1.57303 -0.973502 -2.25858 -1.63229 -0.977408 -2.31835 -1.68782 -0.972548 -2.38378 -1.74889 -0.971466 -2.45587 -1.81556 -0.973866 -2.52228 -1.87743 -0.967645 -2.59528 -1.94588 -0.964458 -2.67495 -2.01987 -0.963855 -2.75559 -2.09477 -0.960111 -2.84289 -2.17519 -0.958351 -2.93674 -2.26309 -0.957977 -3.03827 -2.35652 -0.958693 -3.13412 -2.44516 -0.950489 -3.24983 -2.55253 -0.952035 -3.37875 -2.67293 -0.95755 -3.49642 -2.78192 -0.948918 -3.63395 -2.90953 -0.947739 -3.779 -3.04552 -0.944506 -3.93935 -3.19353 -0.942604 -4.11388 -3.35545 -0.940933 -4.296 -3.52464 -0.935059 -4.51317 -3.72647 -0.937771 -4.73889 -3.9365 -0.933839 -4.98649 -4.16586 -0.92873 -5.27106 -4.42969 -0.926524 -5.56981 -4.70804 -0.916709 -5.94163 -5.05255 -0.918236 -6.32862 -5.4124 -0.907215 -6.78868 -5.83905 -0.899998 -7.28569 -6.30146 -0.881302 -7.8634 -6.8378 -0.859511 -8.52172 -7.44979 -0.828833 -8.90643 -7.80623 -0.71133 -10.2568 -9.06023 -0.749188 -12.6292 -11.2633 -0.881347 -14.73 -13.2149 -0.864522 -17.9367 -16.1932 -0.86616 -28.0177 -25.555 -0.629353 -28.3204 -25.8361 0.016255 -28.3282 -25.8439 0.678991 -9.11588 -8.00159 1.10595 -36.0769 -33.04 3.13315 -35.5023 -32.5075 6.45576 -29.6875 -27.1093 10.575 -30.6643 -28.0168 13.2067 -31.9356 -29.198 14.5403 -31.8197 -29.0903 15.3155 -31.3217 -28.6276 15.9091 -4.38444 -3.6088 4.25148 -4.33651 -3.56349 4.33814 -4.32945 -3.55791 4.46217 -4.30244 -3.53289 4.56989 -4.29836 -3.52817 4.70055 -4.72681 -3.9269 5.27245 -4.34036 -3.56749 5.17234 -4.2581 -3.49138 5.23142 -4.10342 -3.34702 5.20332 -3.83511 -3.09867 5.03004 -3.7719 -3.03946 5.09541 -3.74012 -3.01027 5.20026 -3.72743 -2.99891 5.33287 -3.67661 -2.95159 5.41625 -3.66592 -2.94097 5.55658 -3.68576 -2.9597 5.74928 -3.78494 -3.05201 6.07173 -3.41983 -2.71285 5.67007 -3.32691 -2.62726 5.68492 -3.06576 -2.38453 5.40713 -3.02251 -2.34464 5.49141 -2.99938 -2.32306 5.61519 -2.62989 -1.97925 5.07957 -2.52722 -1.88418 5.03085 -2.49637 -1.85482 5.12027 -2.40323 -1.7688 5.08283 -2.32062 -1.69175 5.05938 -2.283 -1.65756 5.13659 -2.19366 -1.57416 5.09145 -2.14456 -1.52867 5.13996 -2.13579 -1.52051 5.29382 -2.05405 -1.445 5.26062 -2.06842 -1.45829 5.49555 -1.95688 -1.35454 5.36848 -2.08391 -1.4733 5.98036 -1.80197 -1.21032 5.29663 -1.76831 -1.17902 5.40149 -1.68062 -1.09859 5.31863 -1.59394 -1.01682 5.22359 -1.54381 -0.971465 5.26801 -1.47826 -0.910495 5.24451 -1.46114 -0.89476 5.43981 -1.38689 -0.825267 5.37531 -1.31646 -0.75964 5.31837 -1.28495 -0.729991 5.47336 -1.43603 -0.871911 6.78014 -1.37592 -0.814699 6.88975 -1.29423 -0.739504 6.87048 -1.21939 -0.669896 6.88847 -1.05248 -0.514127 6.06413 -0.988053 -0.454964 6.08646 -0.991909 -0.458896 6.92205 -0.915104 -0.386503 6.9129 -1.0115 -0.478283 9.93277 -0.89567 -0.370419 9.90365 -0.786397 -0.26872 10.0616 -0.665789 -0.156202 9.81715 -0.550185 -0.0495697 9.43986 -1.88128 -1.35917 -1.00627 -1.91068 -1.38869 -0.979222 -1.96079 -1.43785 -0.979005 -2.01656 -1.49261 -0.983863 -2.06764 -1.54265 -0.979906 -2.12438 -1.59826 -0.980525 -2.17643 -1.64916 -0.972528 -2.23878 -1.71123 -0.975277 -2.29744 -1.76865 -0.969315 -2.36076 -1.83154 -0.967025 -2.42604 -1.89543 -0.962299 -2.50261 -1.97047 -0.966425 -2.57351 -2.04073 -0.961831 -2.65202 -2.11758 -0.959676 -2.7239 -2.18861 -0.949145 -2.81562 -2.27849 -0.950959 -2.91954 -2.38146 -0.958936 -3.00562 -2.46635 -0.947835 -3.10489 -2.56436 -0.942402 -3.21738 -2.67544 -0.941837 -3.34408 -2.79961 -0.945147 -3.47736 -2.93113 -0.946947 -3.61162 -3.06341 -0.942809 -3.7667 -3.21529 -0.944481 -3.92931 -3.37548 -0.9427 -4.10611 -3.54957 -0.940849 -4.3037 -3.74407 -0.941063 -4.51644 -3.9534 -0.938666 -4.73578 -4.16981 -0.929564 -4.99109 -4.42072 -0.924859 -5.28132 -4.70692 -0.922 -5.58673 -5.00766 -0.910536 -5.96305 -5.37737 -0.90896 -6.35355 -5.76231 -0.893931 -6.82255 -6.22342 -0.883188 -7.37 -6.76243 -0.87104 -8.00253 -7.38554 -0.853329 -8.36234 -7.73889 -0.744292 -8.74294 -8.11392 -0.62234 -8.74769 -8.1181 -0.417819 -8.76368 -8.13512 -0.21556 -8.76375 -8.13402 -0.0112626 -8.76749 -8.13821 0.191964 -8.79772 -8.16818 0.393045 -29.0164 -28.0718 -0.386651 -29.7778 -28.8212 0.293864 -8.75891 -8.13056 1.00326 -8.75796 -8.1295 1.20546 -8.76077 -8.13266 1.40805 -9.57979 -8.93842 1.67125 -9.56281 -8.92239 1.89287 -9.55722 -8.91703 2.11563 -9.57058 -8.92971 2.34143 -36.1323 -35.0788 7.15299 -33.9684 -32.9493 7.61343 -34.789 -33.7577 8.63429 -29.3893 -28.4415 10.3709 -29.808 -28.8546 12.8053 -30.2625 -29.303 13.7817 -30.3978 -29.4366 15.4597 -31.5398 -30.5612 16.8675 -4.86726 -4.30122 4.83306 -4.80155 -4.23562 4.92307 -4.64555 -4.08255 4.9272 -4.57885 -4.0162 5.01087 -4.28603 -3.72799 4.86326 -4.24295 -3.68641 4.96148 -4.39573 -3.8356 5.27418 -4.14166 -3.58706 5.14242 -3.9152 -3.36354 5.0252 -3.95581 -3.40348 5.21988 -3.88234 -3.33101 5.27707 -3.86501 -3.31349 5.40701 -3.74296 -3.1942 5.3985 -3.84838 -3.29778 5.70353 -3.71594 -3.16672 5.67701 -3.65195 -3.10418 5.74774 -3.64034 -3.09299 5.89856 -3.40114 -2.85728 5.68792 -3.32853 -2.78635 5.73527 -3.24259 -2.70184 5.75723 -2.9374 -2.40108 5.38232 -2.92958 -2.39332 5.52928 -2.60128 -2.06966 5.06221 -2.47221 -1.94268 4.95737 -2.36312 -1.83558 4.88068 -2.27983 -1.75282 4.85023 -2.27286 -1.74664 4.98655 -2.24111 -1.71539 5.07228 -2.38622 -1.85894 5.59072 -2.22934 -1.70331 5.38256 -2.07032 -1.54773 5.15059 -2.0702 -1.5478 5.33102 -1.9408 -1.42042 5.15307 -1.93792 -1.41635 5.33281 -2.07983 -1.5579 5.98865 -2.0071 -1.48524 5.98986 -1.76327 -1.24521 5.39547 -1.66721 -1.15103 5.27636 -1.60483 -1.08856 5.26677 -1.53943 -1.02546 5.24587 -1.4982 -0.984268 5.31836 -1.41641 -0.904073 5.21775 -1.38001 -0.86789 5.31648 -1.31845 -0.807875 5.2988 -1.5607 -1.04671 6.98729 -1.21965 -0.709361 5.38505 -1.36866 -0.857205 6.75192 -1.31649 -0.805101 6.90977 -1.24083 -0.731862 6.91908 -1.16227 -0.653478 6.88702 -1.01024 -0.504789 6.12007 -0.960984 -0.455245 6.29054 -0.941198 -0.436496 6.92766 -0.865471 -0.361187 6.89773 -0.94287 -0.438252 9.94846 -0.833505 -0.33091 10.0178 -0.72213 -0.221048 10.0547 -0.619002 -0.119778 10.8587 -1.80977 -1.36629 -0.994146 -1.84843 -1.40714 -0.982131 -1.89648 -1.45723 -0.982853 -1.93986 -1.50258 -0.97486 -1.98981 -1.5546 -0.971997 -2.04448 -1.61116 -0.973855 -2.09911 -1.66861 -0.973567 -2.15469 -1.72701 -0.971036 -2.21128 -1.78536 -0.966313 -2.27811 -1.85586 -0.971487 -2.34032 -1.92063 -0.967995 -2.40907 -1.99297 -0.967687 -2.47226 -2.05854 -0.958857 -2.54764 -2.13729 -0.958386 -2.62398 -2.21695 -0.954775 -2.70034 -2.29645 -0.947867 -2.79454 -2.39468 -0.952996 -2.88407 -2.48815 -0.948911 -2.98015 -2.58909 -0.945711 -3.08385 -2.69651 -0.942754 -3.19977 -2.81693 -0.944261 -3.3222 -2.94572 -0.944707 -3.4522 -3.08191 -0.943648 -3.60203 -3.23765 -0.948593 -3.74719 -3.38855 -0.942626 -3.90447 -3.55427 -0.937328 -4.08354 -3.74051 -0.935098 -4.27581 -3.9405 -0.931196 -4.4953 -4.17039 -0.930645 -4.72901 -4.41396 -0.92573 -4.99757 -4.69389 -0.923809 -5.27926 -4.98927 -0.914123 -5.63733 -5.36217 -0.918254 -5.98881 -5.72968 -0.902672 -6.41006 -6.16883 -0.891431 -6.90567 -6.68675 -0.881411 -7.48517 -7.29186 -0.868772 -8.10065 -7.93323 -0.835612 -8.52508 -8.37695 -0.730656 -9.32715 -9.21412 -0.676433 -9.25006 -9.13342 -0.43759 -9.23792 -9.12054 -0.212849 -27.7302 -28.4233 -0.708283 -29.4544 -30.2238 -0.085059 -30.1343 -30.9332 0.637282 -9.15174 -9.03195 1.54946 -9.1443 -9.02369 1.76768 -9.1406 -9.01964 1.98648 -9.13404 -9.0134 2.2053 -28.8779 -29.624 5.68478 -32.527 -33.4329 7.10747 -28.7512 -29.4921 7.84518 -27.7385 -28.436 8.30871 -28.3864 -29.1135 12.9532 -29.0953 -29.8534 14.0461 -29.8979 -30.6916 16.0622 -29.8404 -30.6319 16.8717 -30.8032 -31.6368 18.2697 -4.49884 -4.17485 4.14131 -4.41806 -4.09148 4.20724 -4.4083 -4.08074 4.33104 -4.43254 -4.10658 4.48661 -4.44832 -4.12304 4.63908 -4.60514 -4.28653 4.93143 -4.2149 -3.87951 4.69444 -4.15307 -3.81484 4.77025 -4.20205 -3.86542 4.96298 -4.15915 -3.8208 5.06195 -4.2223 -3.88781 5.28442 -3.97867 -3.63208 5.14862 -3.80687 -3.45327 5.08632 -3.76776 -3.41204 5.18243 -3.67081 -3.31085 5.20345 -3.66388 -3.30443 5.34477 -3.60103 -3.23922 5.40994 -3.49933 -3.13246 5.41621 -3.39755 -3.02689 5.41874 -3.39546 -3.02416 5.57231 -3.35822 -2.98574 5.67465 -3.25169 -2.8746 5.66242 -3.2696 -2.89285 5.86232 -3.15447 -2.77316 5.82981 -3.09638 -2.7122 5.89606 -2.88422 -2.49125 5.66341 -2.56643 -2.15934 5.19354 -2.45304 -2.04012 5.11319 -2.27393 -1.85238 4.8783 -2.23361 -1.8118 4.9394 -2.1715 -1.74642 4.94849 -2.16271 -1.73712 5.08488 -2.22833 -1.8056 5.42213 -2.09181 -1.66368 5.24543 -2.02778 -1.59643 5.24944 -2.04779 -1.61664 5.49327 -2.26941 -1.84929 6.37113 -2.13006 -1.70298 6.17841 -2.02881 -1.59792 6.09034 -2.0568 -1.62729 6.4424 -1.6719 -1.22495 5.30839 -1.58571 -1.13454 5.20621 -1.56761 -1.11555 5.36491 -1.47264 -1.01713 5.21104 -1.43441 -0.976699 5.29216 -1.37788 -0.91793 5.29593 -1.31844 -0.856002 5.27894 -1.59066 -1.14076 7.10952 -1.48924 -1.03418 6.97082 -1.39736 -0.93844 6.86802 -1.33071 -0.868685 6.91919 -1.2875 -0.824773 7.16548 -1.21512 -0.749271 7.20419 -1.04219 -0.568404 6.27183 -0.967269 -0.489389 6.1558 -0.969173 -0.491681 6.98161 -0.900681 -0.420844 7.05237 -0.988853 -0.513605 10.0424 -0.876435 -0.395883 9.97354 -0.771446 -0.286389 10.0916 -0.657465 -0.167779 9.89718 -0.548316 -0.0530083 9.50983 -1.75241 -1.38634 -1.00322 -1.78537 -1.42252 -0.984684 -1.82767 -1.46894 -0.979233 -1.87924 -1.52655 -0.98602 -1.9215 -1.5738 -0.977024 -1.96477 -1.62103 -0.966535 -2.01733 -1.67942 -0.967485 -2.07648 -1.74443 -0.972568 -2.13095 -1.80471 -0.968935 -2.18544 -1.86489 -0.963105 -2.25116 -1.93726 -0.967076 -2.31684 -2.0105 -0.968202 -2.38348 -2.08465 -0.966487 -2.45115 -2.15872 -0.96188 -2.52436 -2.24027 -0.959753 -2.60317 -2.32829 -0.959756 -2.67737 -2.41057 -0.950992 -2.77035 -2.51263 -0.953921 -2.85672 -2.60882 -0.947875 -2.96182 -2.7257 -0.951873 -3.05677 -2.82924 -0.941929 -3.16941 -2.95435 -0.940777 -3.29422 -3.09339 -0.942841 -3.4276 -3.23987 -0.942905 -3.57309 -3.4012 -0.944538 -3.72611 -3.57085 -0.942818 -3.88573 -3.74772 -0.93729 -4.05947 -3.93945 -0.930844 -4.2585 -4.16001 -0.928988 -4.48476 -4.41043 -0.929685 -4.72412 -4.67642 -0.924915 -4.9852 -4.9646 -0.916522 -5.29124 -5.3039 -0.913282 -5.62552 -5.67371 -0.904261 -6.01889 -6.10944 -0.898574 -6.46019 -6.59795 -0.887469 -6.9813 -7.17456 -0.876872 -7.59625 -7.85602 -0.863866 -8.15324 -8.47254 -0.805333 -8.81729 -9.20756 -0.740522 -10.3408 -10.8933 -0.798589 -12.2398 -12.9959 -0.836136 -14.57 -15.5748 -0.830958 -27.1299 -29.478 -0.377113 -27.041 -29.3809 0.318984 -28.8369 -31.3694 1.74866 -33.9816 -37.0647 2.75691 -29.7518 -32.383 3.2982 -27.2778 -29.6443 5.91535 -27.351 -29.7267 7.3551 -33.0025 -35.9829 9.56265 -28.338 -30.821 12.1396 -27.8938 -30.3295 12.7303 -28.6867 -31.2068 14.6752 -29.3011 -31.8879 15.8077 -29.5073 -32.1167 16.7642 -4.33247 -4.24452 4.17217 -4.30111 -4.20837 4.27648 -4.23351 -4.13385 4.48311 -4.15204 -4.04478 4.54165 -4.13857 -4.02887 4.66413 -4.12218 -4.01175 4.78707 -4.07761 -3.96128 4.88076 -3.99426 -3.86948 4.93128 -3.96849 -3.84116 5.04633 -3.90025 -3.76563 5.11084 -3.67146 -3.51286 4.97377 -3.69578 -3.53881 5.14757 -3.6558 -3.49553 5.24358 -3.54218 -3.36965 5.23649 -3.44936 -3.26596 5.25245 -3.43205 -3.24764 5.37825 -3.29661 -3.09769 5.32439 -3.31438 -3.11682 5.50631 -3.29712 -3.0982 5.6384 -3.18528 -2.97437 5.61237 -3.22481 -3.01913 5.85015 -3.11774 -2.89946 5.8272 -3.11854 -2.90072 6.00497 -2.83805 -2.58927 5.63304 -2.72412 -2.46405 5.57192 -2.4661 -2.17829 5.19487 -2.35682 -2.0574 5.11279 -2.25794 -1.94755 5.0432 -2.22069 -1.90669 5.11377 -2.13792 -1.81448 5.07225 -2.15006 -1.82847 5.27018 -2.06156 -1.72994 5.20757 -2.30106 -1.99602 6.06009 -2.23547 -1.92345 6.08838 -2.20228 -1.88614 6.21377 -2.14904 -1.82826 6.28453 -2.0053 -1.66859 6.05255 -1.73163 -1.3656 5.33615 -1.69356 -1.32234 5.41393 -1.62196 -1.24397 5.36969 -1.5226 -1.134 5.20097 -1.46721 -1.07259 5.19859 -1.40991 -1.00861 5.18509 -1.3679 -0.962912 5.24645 -1.69619 -1.32727 7.2392 -1.61637 -1.23861 7.23077 -1.51918 -1.13023 7.11337 -1.39181 -0.98969 6.77847 -1.36413 -0.958796 7.08455 -1.28894 -0.876406 7.07669 -1.18545 -0.761484 6.82065 -1.05226 -0.613452 6.2252 -0.988313 -0.543182 6.20914 -0.991024 -0.545484 6.9953 -0.92165 -0.469506 7.02706 -0.843158 -0.381397 6.88778 -0.919417 -0.467983 10.0283 -0.820816 -0.358857 10.2277 -0.710567 -0.236446 10.1346 -0.611742 -0.127893 10.9087 -1.69154 -1.39879 -1.00473 -1.72244 -1.43588 -0.986836 -1.7673 -1.48886 -0.989293 -1.80848 -1.53717 -0.982839 -1.85431 -1.59104 -0.981756 -1.90015 -1.64481 -0.978775 -1.94695 -1.69956 -0.973852 -1.9984 -1.75982 -0.9736 -2.0508 -1.82104 -0.971106 -2.1078 -1.88876 -0.972635 -2.16118 -1.95081 -0.965502 -2.22473 -2.02599 -0.968017 -2.28367 -2.09544 -0.961866 -2.35384 -2.17705 -0.964519 -2.42393 -2.2605 -0.963976 -2.49503 -2.34385 -0.960242 -2.57268 -2.43471 -0.958394 -2.65036 -2.5254 -0.95305 -2.73354 -2.6245 -0.948937 -2.82433 -2.73013 -0.945766 -2.92068 -2.84314 -0.942877 -3.02912 -2.97112 -0.944254 -3.13855 -3.09991 -0.940393 -3.26014 -3.24263 -0.939548 -3.39484 -3.40027 -0.940676 -3.5416 -3.57374 -0.942724 -3.69035 -3.74797 -0.937441 -3.85677 -3.94448 -0.935208 -4.03734 -4.1558 -0.931258 -4.24306 -4.3979 -0.9308 -4.44981 -4.64054 -0.91981 -4.70143 -4.93551 -0.918219 -4.97826 -5.26097 -0.914227 -5.2944 -5.63197 -0.910911 -5.62358 -6.02023 -0.895737 -6.03045 -6.49787 -0.8894 -6.48974 -7.03658 -0.877573 -7.04528 -7.68959 -0.868901 -7.71123 -8.47157 -0.858869 -8.42307 -9.30824 -0.823784 -9.34809 -10.3958 -0.793877 -10.6808 -11.9614 -0.785754 -15.426 -17.5361 -0.806652 -29.1252 -33.6323 -0.145539 -28.7126 -33.1476 0.63089 -31.0748 -35.9234 2.24686 -27.068 -31.218 5.68081 -28.2059 -32.5552 6.63874 -26.8687 -30.9846 7.09087 -29.6211 -34.218 8.5305 -29.2744 -33.812 10.8545 -28.6392 -33.066 12.2401 -27.9193 -32.2216 13.5439 -28.688 -33.1247 15.5653 -4.43085 -4.62019 4.16001 -4.32074 -4.49002 4.20325 -4.18799 -4.33463 4.22199 -4.13415 -4.27107 4.3055 -4.12912 -4.26538 4.43432 -4.14376 -4.28385 4.5853 -4.04858 -4.17168 4.6277 -4.09245 -4.2233 4.81341 -3.90706 -4.00447 4.75276 -3.77514 -3.84955 4.74279 -3.66008 -3.71509 4.7452 -3.60241 -3.64715 4.8111 -3.58894 -3.6313 4.93228 -3.50965 -3.53741 4.96935 -3.59967 -3.644 5.2354 -3.62296 -3.67138 5.41958 -3.54933 -3.58426 5.46865 -3.44267 -3.45959 5.46597 -3.27385 -3.2611 5.35913 -3.21894 -3.1973 5.42591 -3.182 -3.15325 5.52066 -3.15636 -3.12286 5.63712 -3.1156 -3.07563 5.73083 -3.0749 -3.02744 5.82371 -2.96343 -2.89635 5.7828 -2.88118 -2.79961 5.79282 -2.81117 -2.7176 5.82408 -2.54191 -2.40032 5.42154 -2.3886 -2.22127 5.24505 -2.24381 -2.05068 5.0701 -2.17263 -1.96777 5.05748 -2.13368 -1.92124 5.11898 -2.07668 -1.85474 5.13649 -2.01686 -1.78457 5.14362 -2.03189 -1.80185 5.35962 -2.18255 -1.97907 5.99461 -2.13988 -1.92993 6.08395 -2.0878 -1.86857 6.14542 -1.79928 -1.52778 5.40476 -1.69186 -1.40221 5.23734 -1.68329 -1.39279 5.41677 -1.62631 -1.32499 5.41999 -1.5416 -1.22607 5.30917 -1.48261 -1.15628 5.28949 -1.42551 -1.08923 5.27743 -1.3636 -1.01638 5.23499 -1.31118 -0.955871 5.23844 -1.63884 -1.34033 7.35083 -1.52752 -1.21025 7.14828 -1.45172 -1.12102 7.13608 -1.35561 -1.00783 6.97539 -1.29226 -0.933236 7.02699 -1.21049 -0.83736 6.93922 -1.05538 -0.654033 6.13886 -1.00825 -0.599455 6.27182 -0.960327 -0.542897 6.42351 -0.93648 -0.516259 6.95184 -0.874253 -0.442815 7.04234 -0.806064 -0.362009 7.05152 -0.861638 -0.428755 10.2231 -0.759024 -0.308324 10.2814 -0.662149 -0.194652 10.7768 -0.544831 -0.0552636 9.43988 -1.66431 -1.45188 -0.996005 -1.69979 -1.49559 -0.984726 -1.73891 -1.54482 -0.979212 -1.78267 -1.59962 -0.979068 -1.82645 -1.65432 -0.977126 -1.87582 -1.71562 -0.979911 -1.92614 -1.77787 -0.980554 -1.97084 -1.83434 -0.972626 -2.02214 -1.89745 -0.96903 -2.0826 -1.97364 -0.975476 -2.13387 -2.03751 -0.967136 -2.18052 -2.09568 -0.950629 -2.25215 -2.18577 -0.960786 -2.31558 -2.2636 -0.956262 -2.38913 -2.35548 -0.959738 -2.45255 -2.43401 -0.949171 -2.52703 -2.52762 -0.945861 -2.61825 -2.64186 -0.953985 -2.69373 -2.73615 -0.94304 -2.78695 -2.85109 -0.942535 -2.88561 -2.97538 -0.941913 -2.99649 -3.11264 -0.945257 -3.1027 -3.24511 -0.938686 -3.22561 -3.39899 -0.938905 -3.35604 -3.56123 -0.93677 -3.49853 -3.73929 -0.935355 -3.64756 -3.92557 -0.930183 -3.81525 -4.13417 -0.927566 -3.98943 -4.35192 -0.919345 -4.20646 -4.62202 -0.923609 -4.43 -4.90111 -0.919172 -4.6676 -5.19678 -0.908424 -4.94143 -5.53892 -0.900385 -5.25907 -5.93496 -0.89465 -5.62055 -6.38475 -0.887521 -6.02571 -6.89107 -0.875156 -6.52403 -7.51268 -0.869378 -7.08576 -8.21286 -0.853631 -7.87085 -9.19259 -0.863261 -8.60874 -10.1126 -0.81848 -9.57105 -11.3132 -0.776909 -11.0511 -13.1585 -0.768623 -31.0642 -38.1191 2.71794 -32.4955 -39.9055 3.69291 -27.3988 -33.5495 5.53009 -28.0158 -34.3213 11.167 -27.7768 -34.0244 12.696 -4.14914 -4.55276 4.10465 -4.08245 -4.46891 4.17696 -4.05215 -4.4318 4.2815 -4.12291 -4.52037 4.48314 -4.04216 -4.41932 4.54129 -4.00256 -4.36993 4.6396 -3.98794 -4.35175 4.90745 -3.70212 -3.99462 4.72195 -3.64093 -3.91851 4.78668 -3.54974 -3.80541 4.81218 -3.43419 -3.6615 4.80232 -3.3776 -3.59182 4.86432 -3.36424 -3.57407 4.98351 -3.36678 -3.577 5.12971 -3.33463 -3.53701 5.22953 -3.29685 -3.49002 5.32193 -3.24028 -3.42027 5.38523 -3.20536 -3.37622 5.48267 -3.1432 -3.29863 5.53552 -3.0679 -3.2044 5.56392 -3.04233 -3.17301 5.68023 -2.98675 -3.10336 5.74282 -2.9264 -3.02887 5.79601 -2.88211 -2.97294 5.87882 -2.78703 -2.85395 5.8567 -2.58652 -2.604 5.5961 -2.43197 -2.41201 5.41607 -2.50248 -2.49895 5.7512 -2.41285 -2.38804 5.71421 -2.65211 -2.68685 6.51328 -2.05448 -1.94045 5.14087 -1.98356 -1.85222 5.11427 -1.9749 -1.84146 5.26009 -1.96345 -1.82749 5.40657 -2.09096 -1.98634 5.99929 -2.04941 -1.9353 6.08793 -1.73832 -1.54576 5.25113 -1.6455 -1.43027 5.12064 -1.60753 -1.38393 5.17964 -1.67397 -1.46667 5.65506 -1.51371 -1.26644 5.22967 -1.46252 -1.20273 5.23846 -1.41897 -1.14717 5.27422 -1.35819 -1.07234 5.23268 -1.306 -1.00727 5.22729 -1.26527 -0.956148 5.27807 -1.461 -1.20102 6.74775 -1.43229 -1.16587 6.99686 -1.28841 -0.985384 6.4764 -1.29444 -0.994058 6.99652 -1.18391 -0.855373 6.64475 -1.07197 -0.716705 6.20999 -1.02015 -0.651193 6.27457 -0.949682 -0.563343 6.13984 -0.954302 -0.568797 6.94567 -0.887138 -0.485394 6.92759 -0.830064 -0.414352 7.07703 -0.901304 -0.505171 10.2677 -0.800807 -0.379756 10.2875 -0.71231 -0.269094 10.8942 -0.589706 -0.116254 9.53894 -1.59794 -1.4566 -0.990043 -1.63504 -1.50583 -0.986917 -1.67309 -1.55604 -0.982147 -1.71116 -1.60617 -0.97588 -1.75287 -1.66181 -0.974977 -1.7919 -1.71284 -0.96527 -1.85301 -1.79385 -0.987204 -1.89101 -1.84562 -0.973646 -1.94481 -1.91626 -0.977409 -1.98842 -1.97452 -0.96638 -2.0422 -2.04593 -0.965499 -2.09236 -2.11169 -0.956157 -2.1517 -2.1905 -0.956158 -2.211 -2.27017 -0.953213 -2.27684 -2.35739 -0.952952 -2.34829 -2.45107 -0.954921 -2.41413 -2.53896 -0.948019 -2.49662 -2.64851 -0.9531 -2.57451 -2.75232 -0.949016 -2.65341 -2.85599 -0.941042 -2.74241 -2.97458 -0.938321 -2.84351 -3.10815 -0.939867 -2.95011 -3.25003 -0.940446 -3.0577 -3.39269 -0.935488 -3.1884 -3.56635 -0.940704 -3.31916 -3.73966 -0.938929 -3.45185 -3.91475 -0.930174 -3.60669 -4.12061 -0.928291 -3.768 -4.33563 -0.921304 -3.95348 -4.58139 -0.918204 -4.15654 -4.85123 -0.91386 -4.39028 -5.16018 -0.912642 -4.62948 -5.47898 -0.900972 -4.92905 -5.87522 -0.900991 -5.22956 -6.27371 -0.884288 -5.61251 -6.78214 -0.880856 -6.04465 -7.35545 -0.871721 -6.5426 -8.01678 -0.858082 -7.14909 -8.82114 -0.845781 -7.84653 -9.74572 -0.820983 -8.72381 -10.9098 -0.79535 -9.87189 -12.4323 -0.770167 -11.0277 -13.9651 -0.679859 -29.5292 -38.5121 0.590268 -29.457 -38.4159 1.43096 -29.3819 -38.3167 2.26761 -33.3321 -43.5586 4.34884 -33.3939 -43.6409 5.31368 -4.01352 -4.6634 4.58054 -3.57496 -4.0819 4.38472 -3.48986 -3.96785 4.41664 -3.45316 -3.91923 4.50285 -3.47423 -3.94785 4.65938 -3.43471 -3.89607 4.74515 -3.46153 -3.9303 4.91683 -3.34085 -3.77068 4.89402 -3.2668 -3.67313 4.93027 -3.23484 -3.62948 5.02319 -3.28962 -3.70276 5.25064 -3.23144 -3.62607 5.31031 -3.19385 -3.57608 5.40286 -3.15157 -3.52018 5.48746 -3.08785 -3.43475 5.53463 -3.06798 -3.40924 5.66069 -3.08653 -3.43349 5.86178 -2.9451 -3.24638 5.76119 -2.92158 -3.21473 5.88538 -2.82128 -3.08187 5.85321 -2.71813 -2.94545 5.80867 -2.94281 -3.24413 6.4914 -2.39552 -2.51787 5.42146 -2.35601 -2.46482 5.49235 -2.36807 -2.48055 5.69558 -2.24409 -2.31653 5.55514 -2.02057 -2.01931 5.12749 -1.94338 -1.91688 5.07621 -1.90558 -1.86756 5.13486 -1.85373 -1.79854 5.1487 -2.03241 -2.03502 5.89702 -1.84604 -1.78802 5.49317 -1.98265 -1.9692 6.17252 -1.65379 -1.53248 5.2137 -1.57825 -1.4329 5.1273 -1.51877 -1.35375 5.09335 -1.50182 -1.33071 5.23392 -1.4574 -1.27246 5.26235 -1.44243 -1.25216 5.43088 -1.35539 -1.1371 5.25841 -1.29576 -1.05884 5.20637 -1.26566 -1.018 5.30553 -1.41093 -1.21157 6.47393 -1.40893 -1.20947 6.85781 -1.30962 -1.07681 6.62069 -1.30798 -1.07434 7.07294 -1.23058 -0.972581 6.98776 -1.10774 -0.80842 6.46723 -1.03377 -0.71164 6.32629 -0.979255 -0.637914 6.35093 -0.9247 -0.566292 6.3938 -0.905895 -0.541495 6.95182 -0.838835 -0.453095 6.89304 -0.791146 -0.3888 7.20104 -0.847983 -0.465763 10.5524 -0.745736 -0.331236 10.5112 -0.650563 -0.20398 10.7769 -0.529084 -0.0424571 7.08997 -1.56884 -1.50758 -0.981403 -1.60852 -1.5633 -0.984786 -1.64552 -1.61441 -0.979263 -1.68148 -1.66639 -0.972188 -1.72208 -1.72391 -0.970283 -1.77185 -1.7946 -0.979919 -1.81805 -1.85861 -0.980643 -1.86058 -1.91796 -0.972657 -1.9067 -1.98376 -0.969087 -1.95377 -2.05051 -0.963176 -2.00544 -2.12374 -0.961188 -2.05814 -2.19691 -0.956608 -2.11531 -2.27852 -0.955052 -2.17808 -2.36664 -0.956325 -2.24182 -2.45565 -0.954458 -2.31011 -2.55206 -0.954566 -2.37931 -2.65036 -0.951084 -2.45312 -2.75502 -0.949029 -2.53342 -2.86814 -0.94791 -2.61929 -2.98865 -0.947273 -2.70607 -3.11099 -0.942048 -2.80854 -3.25476 -0.945306 -2.91093 -3.40025 -0.942972 -3.01531 -3.54658 -0.934905 -3.14081 -3.72377 -0.936803 -3.27277 -3.91022 -0.935494 -3.41027 -4.10483 -0.930322 -3.56538 -4.3227 -0.927652 -3.73245 -4.55824 -0.922707 -3.9161 -4.81783 -0.917511 -4.12282 -5.10996 -0.913402 -4.34714 -5.42605 -0.905752 -4.60652 -5.79153 -0.900558 -4.89451 -6.1977 -0.89239 -5.22863 -6.6689 -0.885296 -5.60894 -7.20494 -0.875281 -6.0584 -7.83946 -0.865679 -6.59468 -8.59554 -0.855497 -7.24627 -9.51504 -0.844705 -8.1285 -10.7603 -0.850671 -8.94471 -11.9099 -0.789324 -10.152 -13.6138 -0.750089 -11.9019 -16.0822 -0.720236 -23.4472 -32.366 -0.376565 -23.3249 -32.1936 0.320105 -23.828 -32.9044 2.4176 -12.2355 -16.5564 7.59898 -3.54973 -4.30296 4.42702 -3.43706 -4.1456 4.42908 -3.34585 -4.01576 4.44836 -3.28701 -3.9332 4.50434 -3.21425 -3.83075 4.53983 -3.32809 -3.99202 4.8245 -3.89158 -4.78647 5.75278 -3.75391 -4.59293 5.72584 -3.26499 -3.90334 5.16056 -3.28709 -3.9337 5.3438 -3.16327 -3.75799 5.2977 -3.123 -3.70211 5.38438 -3.0372 -3.58119 5.39223 -3.037 -3.58051 5.54729 -2.9754 -3.49322 5.59395 -2.64928 -3.03499 5.13287 -2.92289 -3.41948 5.82363 -2.84724 -3.31368 5.84236 -2.76883 -3.20322 5.85037 -2.74448 -3.16858 5.97331 -2.61009 -2.97907 5.84862 -2.85348 -3.32225 6.60748 -2.30566 -2.54939 5.46517 -2.23828 -2.45425 5.46102 -2.17645 -2.36778 5.47088 -2.17448 -2.36431 5.63953 -2.03787 -2.17174 5.43231 -1.88621 -1.95754 5.15755 -1.88327 -1.95326 5.32127 -1.85783 -1.91853 5.42419 -1.75847 -1.77737 5.27747 -2.2367 -2.45283 7.16647 -2.11035 -2.27479 6.98231 -1.55652 -1.49255 5.11148 -1.5424 -1.47263 5.25329 -1.5029 -1.41764 5.30266 -1.45967 -1.35639 5.33234 -1.49095 -1.40035 5.71772 -1.33919 -1.18683 5.22694 -1.3026 -1.13383 5.28019 -1.27919 -1.10148 5.41856 -1.2103 -1.00504 5.29722 -1.3429 -1.19221 6.45789 -1.29331 -1.12287 6.52146 -1.27821 -1.10081 6.8467 -1.25852 -1.07347 7.19214 -1.11703 -0.873196 6.50728 -1.07913 -0.820105 6.70242 -0.973522 -0.670349 6.19557 -0.928769 -0.6079 6.3081 -0.923624 -0.599591 6.99528 -0.859741 -0.510853 6.9674 -0.795754 -0.419661 6.88773 -0.877082 -0.5359 10.4073 -0.78101 -0.401198 10.3974 -0.69304 -0.277371 10.7443 -0.558553 -0.0859083 7.09919 -1.54501 -1.56961 -0.98698 -1.57995 -1.62164 -0.982297 -1.61484 -1.67459 -0.975966 -1.65338 -1.73303 -0.974901 -1.70108 -1.80465 -0.985576 -1.74059 -1.86396 -0.980571 -1.78105 -1.92424 -0.973624 -1.8251 -1.99097 -0.971194 -1.87469 -2.06526 -0.972642 -1.91972 -2.13282 -0.965573 -1.9657 -2.20134 -0.956263 -2.01522 -2.27726 -0.950421 -2.07945 -2.37385 -0.958999 -2.13096 -2.45062 -0.947524 -2.19618 -2.54794 -0.949565 -2.26683 -2.6547 -0.953289 -2.34762 -2.77543 -0.963315 -2.40457 -2.86217 -0.944084 -2.4863 -2.98456 -0.945826 -2.56442 -3.10124 -0.938307 -2.65716 -3.24033 -0.939916 -2.75989 -3.39623 -0.944883 -2.8546 -3.5369 -0.935516 -2.97483 -3.71795 -0.940787 -3.09512 -3.89866 -0.939067 -3.21629 -4.08208 -0.930212 -3.3596 -4.29627 -0.92833 -3.50839 -4.51956 -0.921439 -3.66815 -4.76045 -0.911968 -3.85551 -5.04139 -0.907956 -4.06488 -5.35576 -0.904177 -4.29629 -5.70347 -0.898434 -4.56626 -6.10885 -0.89617 -4.85824 -6.5483 -0.886699 -5.20075 -7.0631 -0.878831 -5.59738 -7.66036 -0.869842 -6.05658 -8.34944 -0.856436 -6.65247 -9.24502 -0.855892 -7.22837 -10.1102 -0.81233 -8.22265 -11.6046 -0.832071 -8.65767 -12.258 -0.674348 -8.30834 -11.7335 -0.354031 -8.37555 -11.8341 -0.115633 -8.39691 -11.8652 0.131433 -22.2708 -32.7136 -0.0205155 -22.3105 -32.7742 0.664995 -30.603 -45.2387 8.16574 -3.87265 -5.0707 4.58974 -3.26027 -4.14944 4.17665 -3.17773 -4.02583 4.20237 -3.18289 -4.03377 4.33158 -3.15483 -3.99151 4.42144 -3.14803 -3.98119 4.54033 -3.18835 -4.04159 4.72671 -3.16497 -4.00599 4.82957 -3.63603 -4.71496 5.67008 -3.6571 -4.74733 5.87215 -3.19088 -4.04634 5.30153 -3.01033 -3.77384 5.1559 -2.99802 -3.75577 5.28267 -3.05421 -3.8409 5.53592 -3.0799 -3.88026 5.7442 -2.86583 -3.55819 5.50559 -2.52658 -3.04836 4.99693 -2.57168 -3.11664 5.23251 -2.79673 -3.45419 5.85997 -2.53785 -3.06577 5.46857 -2.44685 -2.92715 5.42253 -2.79732 -3.45596 6.41164 -2.22182 -2.58933 5.20496 -2.21227 -2.57604 5.33995 -2.14893 -2.48015 5.33564 -2.1246 -2.44356 5.43696 -2.12908 -2.45068 5.62251 -1.89081 -2.09198 5.10184 -1.93714 -2.16264 5.41223 -1.82617 -1.996 5.23931 -1.80648 -1.96622 5.35074 -1.73648 -1.8605 5.29374 -1.72426 -1.8425 5.43953 -1.66168 -1.74814 5.40515 -1.63087 -1.70111 5.48669 -1.57197 -1.61274 5.45748 -1.52424 -1.54193 5.4721 -1.47845 -1.47286 5.4944 -1.36875 -1.30901 5.20617 -1.32667 -1.24442 5.22346 -1.29958 -1.20366 5.32479 -1.24614 -1.12328 5.28262 -1.20019 -1.05459 5.2768 -1.33303 -1.25392 6.43527 -1.28177 -1.17686 6.47043 -1.24381 -1.12046 6.61094 -1.17068 -1.01032 6.47745 -1.16242 -0.998917 6.89958 -1.09023 -0.890544 6.77207 -0.988026 -0.735912 6.28679 -0.948299 -0.67728 6.44983 -0.935168 -0.657301 6.99853 -0.876415 -0.56986 7.01142 -0.816657 -0.479921 6.99255 -0.762949 -0.398042 7.08147 -0.81442 -0.477671 10.3928 -0.726877 -0.345651 10.5211 -0.637845 -0.212219 10.7368 -0.526948 -0.0438284 7.07995 -1.47542 -1.56175 -0.974101 -1.51913 -1.63249 -0.991998 -1.54481 -1.67318 -0.972279 -1.58586 -1.7392 -0.979172 -1.61871 -1.7929 -0.970385 -1.66073 -1.85978 -0.973239 -1.70634 -1.93311 -0.98061 -1.74469 -1.99522 -0.972655 -1.78411 -2.05629 -0.962857 -1.83059 -2.13234 -0.963293 -1.87451 -2.20179 -0.955121 -1.92655 -2.28525 -0.956539 -1.97854 -2.36957 -0.95511 -2.03156 -2.4538 -0.95079 -2.09007 -2.54652 -0.949 -2.15206 -2.64757 -0.949231 -2.21961 -2.75606 -0.951142 -2.28813 -2.86542 -0.949115 -2.35668 -2.97459 -0.943191 -2.43066 -3.09315 -0.937951 -2.51468 -3.22759 -0.937517 -2.60321 -3.37031 -0.936611 -2.70278 -3.52889 -0.938718 -2.80234 -3.68819 -0.934983 -2.91284 -3.86528 -0.932962 -3.02786 -4.05053 -0.928074 -3.15389 -4.25249 -0.923253 -3.29641 -4.47965 -0.920928 -3.43889 -4.70837 -0.909716 -3.60689 -4.97809 -0.905201 -3.78588 -5.26528 -0.89601 -3.9859 -5.58583 -0.886548 -4.23337 -5.982 -0.887763 -4.50739 -6.41971 -0.885244 -4.8078 -6.90183 -0.876447 -5.15021 -7.45156 -0.86506 -5.55212 -8.09409 -0.852488 -6.03248 -8.86374 -0.840097 -6.67073 -9.88645 -0.843355 -7.27905 -10.8617 -0.796742 -8.28251 -12.4703 -0.801637 -7.96073 -11.9544 -0.478114 -7.96271 -11.9582 -0.230134 -7.99393 -12.0082 0.0132737 -8.20885 -12.3524 0.494661 -22.585 -35.3867 0.280615 -22.6037 -35.4179 1.0087 -3.6752 -5.09003 4.60666 -3.15629 -4.25841 4.13827 -3.10447 -4.17608 4.19821 -3.07014 -4.1209 4.27797 -3.15246 -4.25271 4.51148 -3.11999 -4.2003 4.59837 -3.06451 -4.11194 4.65414 -3.60553 -4.97998 5.58802 -3.56773 -4.91818 5.69602 -3.97773 -5.5753 6.51654 -3.15901 -4.26367 5.37053 -3.02354 -4.04649 5.29685 -2.9414 -3.91477 5.30444 -2.97706 -3.97228 5.52325 -2.93548 -3.90456 5.60426 -2.92143 -3.88286 5.74147 -2.76555 -3.63302 5.59386 -2.46022 -3.14468 5.11792 -2.38443 -3.02168 5.09886 -2.43393 -3.10201 5.35963 -2.36732 -2.99463 5.36059 -2.39477 -3.03922 5.58704 -2.23119 -2.77652 5.34535 -2.1506 -2.64769 5.2966 -2.09221 -2.55365 5.30125 -2.10214 -2.57077 5.49415 -2.03721 -2.46728 5.47927 -2.13339 -2.62052 5.9449 -2.02501 -2.44658 5.80085 -1.81649 -2.1121 5.31348 -1.78853 -2.06801 5.39994 -1.71795 -1.95459 5.33585 -1.69744 -1.92177 5.44674 -1.64629 -1.8403 5.44955 -2.03038 -2.45532 7.20887 -1.94236 -2.31446 7.13056 -1.42852 -1.49129 5.14277 -1.40249 -1.44836 5.22837 -1.35399 -1.37107 5.21094 -1.30359 -1.29122 5.18208 -1.63325 -1.81935 7.23153 -1.5637 -1.70832 7.20139 -1.19269 -1.11346 5.29417 -1.44331 -1.51509 7.22949 -1.26813 -1.23326 6.42896 -1.21703 -1.15273 6.45344 -1.20957 -1.14077 6.82717 -1.14725 -1.04046 6.77147 -1.10684 -0.975509 6.91959 -1.07517 -0.924326 7.18496 -0.934744 -0.700131 6.21526 -0.941786 -0.711195 6.97159 -0.888023 -0.626549 7.01511 -0.831406 -0.535254 7.00717 -0.766649 -0.431389 6.81805 -0.841623 -0.553272 10.3375 -0.761381 -0.424697 10.5671 -0.673927 -0.284667 10.6144 -0.553338 -0.0901097 7.10925 -1.44766 -1.62255 -0.979708 -1.47585 -1.67081 -0.967948 -1.51747 -1.74328 -0.982939 -1.54926 -1.79796 -0.974996 -1.58927 -1.86477 -0.978939 -1.6256 -1.9269 -0.973971 -1.66552 -1.9955 -0.973719 -1.7064 -2.06505 -0.971226 -1.74265 -2.12889 -0.960267 -1.79166 -2.21236 -0.965664 -1.83347 -2.28363 -0.956285 -1.8834 -2.36889 -0.956196 -1.92977 -2.4475 -0.947694 -1.98873 -2.54863 -0.953104 -2.04766 -2.65058 -0.954969 -2.10403 -2.74592 -0.948127 -2.17294 -2.86468 -0.953149 -2.23383 -2.96822 -0.944238 -2.30368 -3.08864 -0.941177 -2.36904 -3.20133 -0.929249 -2.46244 -3.36198 -0.940016 -2.53881 -3.49136 -0.927755 -2.63317 -3.65352 -0.927343 -2.743 -3.84097 -0.932818 -2.84734 -4.02055 -0.927624 -2.96264 -4.21786 -0.922946 -3.08788 -4.4328 -0.917882 -3.22315 -4.66433 -0.91148 -3.36938 -4.91345 -0.902499 -3.53456 -5.19695 -0.896085 -3.72423 -5.5222 -0.892918 -3.93028 -5.87529 -0.885109 -4.16634 -6.27842 -0.878783 -4.44225 -6.75129 -0.875153 -4.75808 -7.29272 -0.870373 -5.10034 -7.87831 -0.85412 -5.51691 -8.59297 -0.842026 -6.01976 -9.45426 -0.829717 -6.65329 -10.5393 -0.821366 -7.33874 -11.7122 -0.782774 -8.28003 -13.3244 -0.75486 -7.61646 -12.1893 -0.356129 -7.663 -12.2674 -0.115065 -7.66581 -12.2743 0.133658 -7.8631 -12.6122 0.620579 -22.9363 -38.4273 0.620526 -3.4787 -5.10528 4.76775 -3.43284 -5.02603 4.85373 -3.41885 -5.00272 4.98306 -3.15015 -4.54154 4.75246 -3.44032 -5.03948 5.31971 -3.48582 -5.11713 5.54874 -3.40979 -4.98685 5.59541 -3.12806 -4.50397 5.30097 -2.98242 -4.25497 5.20949 -2.86242 -4.04811 5.14901 -2.89233 -4.10003 5.35188 -2.8856 -4.09047 5.49604 -2.95045 -4.20061 5.78128 -2.87615 -4.07276 5.80122 -2.40713 -3.26923 5.43404 -2.24913 -2.99878 5.21384 -2.25899 -3.01565 5.39121 -2.14583 -2.82269 5.26108 -2.14473 -2.82006 5.41395 -2.11973 -2.77762 5.51098 -2.45698 -3.35516 6.65437 -2.44225 -3.33153 6.82974 -2.00716 -2.58399 5.6984 -2.04109 -2.64344 5.99722 -1.98949 -2.55474 6.02401 -1.91579 -2.42757 5.97038 -1.75161 -2.14616 5.57919 -1.66381 -1.99708 5.4445 -1.61108 -1.90733 5.43049 -1.55933 -1.81774 5.41419 -1.57879 -1.85064 5.705 -1.47514 -1.6731 5.45741 -1.40105 -1.54584 5.32418 -1.3278 -1.42027 5.17802 -1.27114 -1.32427 5.10306 -1.23494 -1.26261 5.12925 -1.52314 -1.75605 7.0793 -1.17569 -1.1601 5.26346 -1.13113 -1.08342 5.23832 -1.26548 -1.31518 6.49318 -1.25317 -1.29522 6.79967 -1.16864 -1.14838 6.54292 -1.1906 -1.18633 7.19992 -1.13624 -1.09416 7.23266 -1.05523 -0.954908 6.96875 -0.948059 -0.771174 6.33609 -0.935685 -0.74965 6.81573 -0.893673 -0.678333 6.96885 -0.840118 -0.58618 6.96174 -0.788512 -0.498791 7.00251 -0.72879 -0.396811 6.84218 -0.785222 -0.494951 10.3728 -0.706138 -0.360468 10.5612 -0.624135 -0.217871 10.6668 -0.523832 -0.0456456 7.07996 -1.38558 -1.62189 -0.981454 -1.41534 -1.67666 -0.977596 -1.44868 -1.73794 -0.979355 -1.48204 -1.79913 -0.979216 -1.51535 -1.86122 -0.977229 -1.54962 -1.92429 -0.9733 -1.58847 -1.99388 -0.974093 -1.62271 -2.05775 -0.96632 -1.66154 -2.12813 -0.962869 -1.70032 -2.1994 -0.957171 -1.74717 -2.28568 -0.961212 -1.78593 -2.35772 -0.95077 -1.83833 -2.45138 -0.955193 -1.88964 -2.54682 -0.956417 -1.9465 -2.64973 -0.95992 -1.99422 -2.73935 -0.949286 -2.05553 -2.85147 -0.951171 -2.11782 -2.96447 -0.949216 -2.18007 -3.07827 -0.943216 -2.2423 -3.19288 -0.933371 -2.32256 -3.33937 -0.937622 -2.40274 -3.4876 -0.93668 -2.47943 -3.62813 -0.926177 -2.5651 -3.78539 -0.918727 -2.66878 -3.97534 -0.921329 -2.78241 -4.18297 -0.924441 -2.88796 -4.37633 -0.912572 -3.01148 -4.6032 -0.907309 -3.1495 -4.85508 -0.903334 -3.30093 -5.13384 -0.899146 -3.46328 -5.43108 -0.890331 -3.64902 -5.77199 -0.883962 -3.85822 -6.15543 -0.87749 -4.10171 -6.60124 -0.873232 -4.38205 -7.11652 -0.869857 -4.68781 -7.67599 -0.856902 -5.07466 -8.38433 -0.854596 -5.48494 -9.13727 -0.833363 -5.97287 -10.0311 -0.807624 -6.64638 -11.2661 -0.801034 -7.47768 -12.791 -0.78605 -7.44918 -12.7371 -0.522146 -7.3323 -12.5227 -0.2452 -7.37931 -12.6098 -0.00159918 -23.3262 -41.8411 0.177173 -3.59747 -5.68126 4.44257 -3.51387 -5.52732 4.49194 -3.33146 -5.19206 4.41623 -3.44176 -5.39458 4.69404 -3.50311 -5.50831 4.92272 -3.42216 -5.35984 4.96623 -2.96019 -4.51207 4.46806 -2.97342 -4.53741 4.62039 -2.98592 -4.5586 4.77462 -3.01825 -4.61922 4.96708 -2.89812 -4.39881 4.91665 -2.94325 -4.48195 5.13574 -3.23828 -5.02338 5.8028 -2.85102 -4.31215 5.27191 -2.78257 -4.18742 5.29676 -2.79601 -4.21149 5.47495 -2.75387 -4.13596 5.55097 -2.77013 -4.1644 5.74568 -2.61701 -3.88437 5.58315 -2.51669 -3.69985 5.52071 -2.48459 -3.6414 5.6084 -2.47444 -3.62183 5.748 -2.09227 -2.92221 4.96882 -2.00813 -2.76737 4.89419 -2.01326 -2.77795 5.05107 -2.11433 -2.96334 5.4811 -2.0914 -2.91995 5.57977 -2.01452 -2.77873 5.52238 -1.96494 -2.68941 5.54381 -2.00505 -2.763 5.84818 -1.88328 -2.53973 5.63102 -1.88415 -2.54054 5.81798 -1.87675 -2.5276 5.98892 -1.83735 -2.45513 6.04715 -1.65116 -2.11344 5.53011 -1.58963 -2.0002 5.47337 -1.57672 -1.97709 5.62032 -1.56018 -1.94716 5.75865 -1.5069 -1.84893 5.73272 -1.84423 -2.46942 7.62824 -1.69349 -2.19342 7.18494 -1.24425 -1.36784 5.06146 -1.20733 -1.30002 5.06933 -1.51031 -1.85727 7.14635 -1.44147 -1.7306 7.06828 -1.44788 -1.74199 7.49381 -1.34087 -1.54529 7.14287 -1.31013 -1.48968 7.33693 -1.1616 -1.21631 6.56013 -1.16171 -1.21797 7.01227 -1.10853 -1.11977 7.00616 -1.0515 -1.01484 6.94899 -0.967754 -0.86134 6.56454 -0.924782 -0.782271 6.63008 -0.900135 -0.738792 6.99139 -0.849704 -0.644767 6.98537 -0.800205 -0.554945 7.01709 -0.742714 -0.448523 6.84791 -0.685826 -0.34524 6.63643 -0.739685 -0.446034 10.697 -0.656255 -0.293622 10.5943 -0.548165 -0.0928077 7.10922 -1.26703 -1.51155 -0.984137 -1.29482 -1.56539 -0.984214 -1.32256 -1.62015 -0.982744 -1.35032 -1.67485 -0.979776 -1.37902 -1.73052 -0.975166 -1.41026 -1.79363 -0.976016 -1.44614 -1.86229 -0.981938 -1.48092 -1.93278 -0.985658 -1.51413 -1.99673 -0.980676 -1.54278 -2.05397 -0.967277 -1.58307 -2.13283 -0.971231 -1.61627 -2.19749 -0.960307 -1.65652 -2.27712 -0.959617 -1.70126 -2.36521 -0.96225 -1.73792 -2.43906 -0.950502 -1.79074 -2.54198 -0.959079 -1.83642 -2.63171 -0.95313 -1.89012 -2.73735 -0.954972 -1.93932 -2.83528 -0.948147 -2.00553 -2.96516 -0.958309 -2.05665 -3.06485 -0.944304 -2.11475 -3.18131 -0.936439 -2.18641 -3.32116 -0.938545 -2.25798 -3.46276 -0.935659 -2.34301 -3.62963 -0.940648 -2.40754 -3.75684 -0.919089 -2.49253 -3.92517 -0.912993 -2.59896 -4.13556 -0.920018 -2.70291 -4.33823 -0.915789 -2.80673 -4.54352 -0.904021 -2.94545 -4.81608 -0.911552 -3.07616 -5.07329 -0.902652 -3.22825 -5.37419 -0.899183 -3.38678 -5.6851 -0.887365 -3.57561 -6.05737 -0.882583 -3.79572 -6.49188 -0.881299 -4.03473 -6.96229 -0.872993 -4.31398 -7.51244 -0.866195 -4.62995 -8.13477 -0.854238 -5.00851 -8.88133 -0.844082 -5.45614 -9.76126 -0.829922 -5.94843 -10.7322 -0.796525 -6.59917 -12.014 -0.771235 -7.58803 -13.962 -0.781071 -7.75621 -14.2934 0.0226544 -3.51342 -5.93904 4.17845 -3.40708 -5.72869 4.2049 -3.38517 -5.68649 4.32125 -3.36243 -5.64127 4.43675 -3.25952 -5.43965 4.45309 -3.27097 -5.46166 4.60977 -3.24645 -5.41252 4.72139 -2.74735 -4.42895 4.16569 -2.7253 -4.38696 4.25741 -2.75564 -4.44554 4.42776 -2.77142 -4.47887 4.58396 -2.68459 -4.30752 4.57583 -2.66357 -4.26538 4.67185 -2.66955 -4.2776 4.81698 -2.74055 -4.41707 5.08459 -3.26553 -5.45056 6.22276 -3.15883 -5.24249 6.20277 -2.82018 -4.57477 5.70307 -2.55624 -4.05539 5.31689 -2.51906 -3.98038 5.38859 -2.44925 -3.84282 5.38739 -2.41104 -3.76796 5.4546 -2.34481 -3.63761 5.45393 -2.3247 -3.59794 5.56197 -2.29102 -3.53189 5.63929 -2.00112 -2.95989 5.02856 -1.94918 -2.85833 5.03109 -1.91451 -2.78968 5.07855 -1.9677 -2.89582 5.38973 -1.89412 -2.74921 5.32363 -1.91295 -2.78728 5.54983 -1.90918 -2.78001 5.7121 -1.87908 -2.72111 5.79115 -1.78722 -2.53912 5.64757 -1.8508 -2.66517 6.07568 -2.06379 -3.08667 7.11937 -2.02398 -3.00736 7.21391 -1.56565 -2.10311 5.53318 -1.53004 -2.03275 5.57366 -1.47977 -1.93462 5.54951 -1.4744 -1.92222 5.73227 -1.47814 -1.93022 5.98014 -1.71195 -2.39169 7.47699 -1.65563 -2.28108 7.49493 -1.54328 -2.06008 7.18258 -1.5365 -2.04764 7.4859 -1.42761 -1.83326 7.14562 -1.37211 -1.72321 7.13284 -1.335 -1.65087 7.25193 -1.28877 -1.5583 7.30262 -1.14208 -1.26982 6.50914 -1.19994 -1.38431 7.46669 -1.09851 -1.18492 6.99482 -1.04371 -1.07555 6.9289 -0.96993 -0.930227 6.63439 -0.928112 -0.847137 6.6813 -0.906361 -0.80632 7.05313 -0.856189 -0.705712 7.01835 -0.805879 -0.607202 6.98157 -0.759489 -0.515602 7.01248 -0.710104 -0.418856 6.98168 -0.623241 -0.248211 7.38409 -0.570202 -0.142342 7.10807 -0.521678 -0.0465106 7.0599 -1.20769 -1.49952 -0.975649 -1.23342 -1.55428 -0.976567 -1.26273 -1.61557 -0.983399 -1.29099 -1.67771 -0.98848 -1.31763 -1.7343 -0.984609 -1.34429 -1.7908 -0.97904 -1.37196 -1.84729 -0.971978 -1.40215 -1.91121 -0.970177 -1.43488 -1.98254 -0.97304 -1.46956 -2.05489 -0.973864 -1.49974 -2.11952 -0.966022 -1.53082 -2.18611 -0.956288 -1.56901 -2.26668 -0.956837 -1.60364 -2.3406 -0.948873 -1.64533 -2.42945 -0.950444 -1.68798 -2.51923 -0.949074 -1.73418 -2.61638 -0.950574 -1.78833 -2.73043 -0.959616 -1.8274 -2.81425 -0.943692 -1.88249 -2.93003 -0.945749 -1.93654 -3.04654 -0.943857 -1.99257 -3.16398 -0.938029 -2.05209 -3.2897 -0.933024 -2.11853 -3.43312 -0.932711 -2.19495 -3.59339 -0.936255 -2.26241 -3.73737 -0.92581 -2.33527 -3.89166 -0.914301 -2.43202 -4.09644 -0.920925 -2.52529 -4.29343 -0.91649 -2.62645 -4.50896 -0.912108 -2.72413 -4.71671 -0.896566 -2.8635 -5.01147 -0.906115 -2.97805 -5.25513 -0.886339 -3.14318 -5.60445 -0.892711 -3.30032 -5.93833 -0.880554 -3.48678 -6.33345 -0.874331 -3.69897 -6.78327 -0.867827 -3.94136 -7.29705 -0.860221 -4.21745 -7.88295 -0.84994 -4.53621 -8.55855 -0.836691 -4.90991 -9.35266 -0.820356 -5.37331 -10.3359 -0.806654 -5.93532 -11.5274 -0.787503 -6.59596 -12.9276 -0.750869 -7.58749 -15.0313 -0.742065 -8.36595 -16.6866 3.59777 -8.32821 -16.6075 3.91308 -8.40612 -16.7728 4.27482 -3.18957 -5.70994 4.35858 -3.12681 -5.57673 4.41972 -3.14176 -5.60771 4.58182 -2.73415 -4.74471 4.15367 -2.63113 -4.5251 4.12807 -2.60753 -4.47524 4.21492 -2.63314 -4.52883 4.37905 -2.61756 -4.49665 4.48312 -2.56714 -4.39006 4.52814 -2.58111 -4.42026 4.68461 -2.66761 -4.60348 4.97868 -2.55816 -4.3713 4.91577 -2.52203 -4.29538 4.98672 -3.06446 -5.44673 6.23708 -2.46148 -4.16727 5.15002 -2.98815 -5.28507 6.45091 -2.60978 -4.48264 5.78771 -2.41779 -4.07378 5.50561 -2.31891 -3.86416 5.42531 -2.28819 -3.7991 5.50646 -2.21167 -3.63692 5.46756 -2.23391 -3.6845 5.68799 -2.16104 -3.52847 5.65106 -2.0502 -3.29551 5.50082 -1.99885 -3.1847 5.5085 -1.89073 -2.95494 5.33767 -1.78511 -2.73272 5.15938 -1.78312 -2.72815 5.30975 -1.81538 -2.79666 5.5856 -1.8549 -2.8814 5.90725 -1.71684 -2.58735 5.5804 -1.68694 -2.52408 5.64682 -2.07172 -3.342 7.40108 -1.94088 -3.06444 7.11464 -1.72124 -2.5979 6.4046 -1.51848 -2.16795 5.70535 -1.47229 -2.06951 5.69256 -1.45869 -2.04129 5.84047 -1.41436 -1.94568 5.83342 -1.6799 -2.51273 7.54576 -1.62046 -2.38463 7.52822 -1.56271 -2.26232 7.51726 -1.45288 -2.02941 7.16517 -1.41874 -1.95804 7.28849 -1.34075 -1.7913 7.09699 -1.32779 -1.76348 7.37927 -1.28086 -1.66525 7.42197 -1.15102 -1.38787 6.72853 -1.15563 -1.40036 7.21051 -1.13011 -1.34424 7.44124 -1.02728 -1.12614 6.85963 -0.967971 -1.00038 6.69392 -0.931055 -0.923115 6.79114 -0.903721 -0.865735 7.04516 -0.858556 -0.768434 7.05095 -0.808487 -0.662824 6.97557 -0.765159 -0.570365 7.00731 -0.712787 -0.459716 6.80825 -0.637959 -0.301879 7.37159 -0.59105 -0.201014 7.38643 -0.540936 -0.0963768 7.10935 -1.22765 -1.66551 -0.981371 -1.25229 -1.72202 -0.978389 -1.27945 -1.78597 -0.980869 -1.30506 -1.84337 -0.974547 -1.33319 -1.90821 -0.973486 -1.36385 -1.98047 -0.977387 -1.39295 -2.04618 -0.972487 -1.42207 -2.1118 -0.965689 -1.45366 -2.1858 -0.963204 -1.48275 -2.25222 -0.952461 -1.51883 -2.33462 -0.951803 -1.55493 -2.41688 -0.948647 -1.59352 -2.50749 -0.948707 -1.63406 -2.59907 -0.94593 -1.68068 -2.70546 -0.951284 -1.72115 -2.79875 -0.942416 -1.76864 -2.90786 -0.940935 -1.81963 -3.0253 -0.941075 -1.87158 -3.1436 -0.937276 -1.92703 -3.27018 -0.9343 -1.98941 -3.41447 -0.936315 -2.04922 -3.55212 -0.928924 -2.11254 -3.698 -0.921157 -2.18032 -3.85313 -0.912569 -2.27088 -4.0607 -0.922412 -2.35353 -4.25101 -0.91752 -2.45297 -4.47783 -0.92038 -2.52512 -4.64522 -0.8907 -2.6518 -4.93428 -0.901931 -2.76257 -5.19014 -0.890036 -2.88226 -5.46444 -0.875004 -3.04058 -5.82724 -0.878357 -3.1805 -6.14849 -0.85507 -3.38975 -6.62905 -0.865155 -3.5974 -7.1045 -0.855054 -3.8244 -7.62492 -0.83819 -4.10671 -8.27348 -0.829886 -4.42515 -9.00408 -0.813733 -4.81566 -9.90063 -0.799908 -5.28976 -10.9887 -0.783345 -5.87557 -12.333 -0.762283 -6.64514 -14.0997 -0.742248 -7.6268 -16.3519 -0.705849 -8.33664 -17.9959 3.59713 -8.23415 -17.7616 3.90812 -8.38884 -18.1186 4.32033 -8.45464 -18.271 4.70676 -8.34162 -18.0114 5.00999 -8.35798 -18.0523 5.37832 -8.37278 -18.0859 5.74932 -8.51979 -18.425 6.21086 -8.02384 -17.2881 6.24203 -8.54403 -18.4843 6.98574 -8.50062 -18.3861 7.33669 -7.43703 -15.9436 6.83062 -8.66084 -18.7594 9.48951 -8.7385 -18.9405 9.99701 -3.08684 -5.9522 4.38471 -2.99993 -5.75203 4.41141 -2.98539 -5.72094 4.53525 -2.94713 -5.63202 4.6232 -2.66985 -4.99425 4.34275 -2.54817 -4.71611 4.28138 -2.98708 -5.72523 5.13849 -2.59002 -4.81258 4.61189 -2.49576 -4.59678 4.58091 -2.44234 -4.47254 4.61418 -2.42862 -4.44324 4.72318 -2.42744 -4.44054 4.85703 -2.39437 -4.3638 4.92821 -2.41441 -4.41193 5.11464 -2.40087 -4.38026 5.23114 -2.92893 -5.59616 6.59832 -2.85158 -5.41917 6.61437 -2.0394 -3.54984 4.80903 -2.21592 -3.95764 5.39697 -2.22372 -3.97545 5.5732 -2.23416 -4.00061 5.76619 -1.87894 -3.18221 4.9273 -1.85906 -3.13678 5.01013 -2.00034 -3.46379 5.58647 -1.91643 -3.27005 5.48721 -1.83867 -3.09124 5.39794 -1.73235 -2.84594 5.1987 -1.69375 -2.75731 5.21968 -1.74533 -2.87655 5.56825 -1.73265 -2.84832 5.69733 -1.68695 -2.7431 5.70023 -1.62062 -2.59085 5.61518 -1.59002 -2.52197 5.67241 -1.555 -2.44171 5.71089 -1.67782 -2.72506 6.47757 -1.59176 -2.52717 6.29782 -1.56671 -2.47005 6.40775 -1.41757 -2.12676 5.86702 -1.36907 -2.01458 5.82484 -1.33486 -1.93743 5.86238 -1.47664 -2.26619 6.97046 -1.54932 -2.43564 7.74786 -1.47496 -2.26267 7.60568 -1.36862 -2.01942 7.22351 -1.36932 -2.02121 7.59285 -1.3028 -1.8689 7.46815 -1.22531 -1.68974 7.22457 -1.12018 -1.44776 6.69677 -1.08081 -1.3558 6.72331 -1.09927 -1.40104 7.37068 -1.00371 -1.18032 6.81041 -0.95409 -1.06573 6.71436 -0.913703 -0.972543 6.72392 -0.894859 -0.931833 7.07691 -0.846124 -0.818597 6.97491 -0.807775 -0.730868 7.05891 -0.761752 -0.624553 6.98247 -0.714605 -0.515227 6.844 -0.677277 -0.432385 6.99252 -0.599803 -0.254785 7.3848 -0.552971 -0.147296 7.12878 -0.510581 -0.0478141 7.06055 -1.17063 -1.66344 -0.988933 -1.19064 -1.71433 -0.979282 -1.21674 -1.77925 -0.982507 -1.23934 -1.83652 -0.977069 -1.26641 -1.90234 -0.976853 -1.29249 -1.96801 -0.974834 -1.31859 -2.03359 -0.970918 -1.34558 -2.10113 -0.96501 -1.37264 -2.16758 -0.957353 -1.40218 -2.24242 -0.95391 -1.43268 -2.31821 -0.948326 -1.4693 -2.40789 -0.952519 -1.49977 -2.48444 -0.942091 -1.53977 -2.58438 -0.946609 -1.57727 -2.67671 -0.94237 -1.62426 -2.79335 -0.951529 -1.65816 -2.87987 -0.935732 -1.70607 -2.99822 -0.937806 -1.75743 -3.12585 -0.940953 -1.80528 -3.24581 -0.935138 -1.85758 -3.3751 -0.930001 -1.90985 -3.50517 -0.92052 -1.97598 -3.66984 -0.924267 -2.0421 -3.83524 -0.922472 -2.11168 -4.00978 -0.918952 -2.19262 -4.21138 -0.921203 -2.27454 -4.4137 -0.916517 -2.36336 -4.63449 -0.911879 -2.45561 -4.8653 -0.902872 -2.56266 -5.13235 -0.898709 -2.66027 -5.37483 -0.875754 -2.80383 -5.73289 -0.882227 -2.93012 -6.04745 -0.862065 -3.11457 -6.50744 -0.871864 -3.25316 -6.85194 -0.833508 -3.48986 -7.44147 -0.843363 -3.72412 -8.02366 -0.82943 -3.99138 -8.68987 -0.81113 -4.32912 -9.53128 -0.8012 -4.68953 -10.4301 -0.769503 -5.14753 -11.5697 -0.740368 -5.74998 -13.0694 -0.716214 -6.60465 -15.1999 -0.706418 -7.52849 -17.4998 -0.632572 -7.66501 -17.8638 3.72299 -7.78837 -18.1746 4.11985 -7.86221 -18.3595 4.50652 -7.81117 -18.2366 4.8378 -7.72277 -18.0175 5.14463 -7.61424 -17.7489 5.43316 -7.61305 -17.7473 5.78563 -7.09858 -16.4662 5.77071 -7.93805 -18.5625 6.75406 -7.04534 -16.3376 6.3986 -6.93399 -16.0621 6.63986 -6.93096 -16.0564 6.97362 -8.22204 -19.2805 8.5808 -8.15982 -19.129 8.93129 -8.14845 -19.1012 9.33482 -7.81177 -18.2626 9.37157 -7.98659 -18.7008 9.99076 -7.90853 -18.5113 10.3198 -8.01705 -18.7834 10.8903 -2.93687 -6.09318 4.35256 -2.83843 -5.85022 4.35853 -2.8846 -5.9649 4.56985 -2.83175 -5.83403 4.63643 -2.82356 -5.81481 4.77132 -2.82682 -5.82329 4.9278 -2.76961 -5.68073 4.98213 -2.74302 -5.61568 5.08827 -2.38502 -4.72016 4.56732 -2.76004 -5.66055 5.43817 -2.76336 -5.66927 5.61019 -2.69727 -5.50622 5.64205 -2.28098 -4.46363 4.90067 -2.26039 -4.41449 4.99684 -2.23735 -4.35553 5.08573 -2.21593 -4.3034 5.18036 -2.20156 -4.26878 5.29472 -2.05095 -3.89144 5.0545 -1.93013 -3.58925 4.8723 -1.90422 -3.5262 4.93909 -1.85547 -3.4049 4.93893 -1.90094 -3.52019 5.21797 -1.7624 -3.17173 4.93602 -1.70469 -3.02983 4.89536 -1.80762 -3.28789 5.37941 -1.78092 -3.22167 5.44835 -2.0517 -3.90375 6.58709 -1.96953 -3.69799 6.48962 -1.98626 -3.74161 6.76317 -1.67233 -2.95283 5.72106 -1.64295 -2.88072 5.78413 -1.87403 -3.46155 6.97447 -1.54172 -2.62813 5.71785 -1.48757 -2.49162 5.6539 -1.59743 -2.77163 6.39128 -1.53267 -2.60913 6.2923 -1.59055 -2.75544 6.83079 -1.50087 -2.53007 6.59384 -1.33531 -2.11373 5.88805 -1.5253 -2.59639 7.28866 -1.48198 -2.487 7.31797 -1.47697 -2.47803 7.61414 -1.43542 -2.37449 7.66906 -1.31589 -2.07258 7.13913 -1.28225 -1.99062 7.23389 -1.26757 -1.95601 7.48913 -1.20246 -1.79376 7.32398 -1.14815 -1.65764 7.23161 -1.05655 -1.42673 6.74 -1.03114 -1.36249 6.89203 -0.98475 -1.24594 6.81919 -0.940009 -1.13667 6.76341 -0.910129 -1.06078 6.88207 -0.885842 -1.002 7.12748 -0.838385 -0.882736 7.00706 -0.802142 -0.792574 7.08201 -0.758245 -0.684327 7.00666 -0.717196 -0.580905 6.95885 -0.673018 -0.471303 6.80933 -0.607397 -0.309501 7.3627 -0.565528 -0.20491 7.33746 -0.522734 -0.0992407 7.11034 -1.10847 -1.64829 -0.981478 -1.12905 -1.70562 -0.979926 -1.15314 -1.77048 -0.984139 -1.17726 -1.83525 -0.986554 -1.19875 -1.8944 -0.980114 -1.22025 -1.95348 -0.972075 -1.2478 -2.02755 -0.975863 -1.27179 -2.09495 -0.970839 -1.29679 -2.16232 -0.964022 -1.32174 -2.2306 -0.955259 -1.35023 -2.30633 -0.950763 -1.3812 -2.39041 -0.950081 -1.41219 -2.47438 -0.946902 -1.44561 -2.56767 -0.946888 -1.48004 -2.66089 -0.944083 -1.51444 -2.75497 -0.938432 -1.55579 -2.8659 -0.940518 -1.59617 -2.9766 -0.939104 -1.63746 -3.08917 -0.934 -1.68471 -3.21847 -0.93523 -1.73294 -3.34862 -0.932222 -1.78461 -3.48803 -0.929586 -1.83526 -3.62814 -0.922303 -1.89724 -3.79543 -0.923185 -1.95821 -3.96338 -0.918421 -2.02959 -4.15734 -0.920069 -2.09843 -4.34462 -0.911113 -2.18359 -4.5756 -0.914156 -2.26621 -4.79983 -0.905596 -2.35815 -5.05182 -0.899251 -2.45795 -5.32321 -0.890312 -2.57749 -5.64838 -0.890001 -2.70142 -5.98442 -0.880881 -2.83218 -6.3406 -0.865118 -2.97575 -6.73352 -0.84665 -3.15815 -7.22867 -0.839787 -3.3705 -7.80795 -0.834335 -3.60798 -8.45259 -0.821766 -3.88566 -9.21091 -0.807434 -4.21595 -10.1097 -0.790123 -4.6116 -11.1867 -0.767777 -5.12417 -12.5819 -0.749946 -5.78902 -14.3904 -0.730035 -6.45409 -16.2007 -0.643359 -8.6826 -22.2756 0.403601 -7.51477 -19.1009 0.844098 -7.8481 -20.0107 1.20866 -8.68555 -22.2944 1.64693 -7.98773 -20.3965 1.97173 -8.06235 -20.6022 2.36561 -8.67994 -22.2894 2.89387 -6.55013 -16.4906 2.71055 -6.45671 -16.2364 2.98946 -6.25308 -15.6884 3.51593 -6.16556 -15.4507 3.77237 -7.51767 -19.1415 4.80116 -6.20487 -15.5629 4.39113 -5.96712 -14.9192 4.54081 -5.78378 -14.4205 4.70509 -5.6771 -14.1311 4.90969 -6.0628 -15.1871 5.50439 -6.71017 -16.9557 6.37012 -5.69588 -14.1892 5.78257 -5.57101 -13.8502 5.95323 -5.67214 -14.1307 6.34718 -5.60936 -13.962 6.57739 -5.49834 -13.659 6.74781 -5.46232 -13.563 7.00079 -6.52706 -16.4754 8.65072 -6.37031 -16.0498 8.81037 -7.3633 -18.7655 10.5569 -7.23859 -18.4305 10.8103 -7.41236 -18.9089 11.5076 -7.34404 -18.7252 11.8525 -2.61166 -5.78687 4.93512 -2.62693 -5.8308 5.11948 -2.70706 -6.0522 5.60691 -2.69209 -6.01318 5.74849 -6.03691 -15.1842 13.8846 -2.14916 -4.53267 5.43124 -2.07506 -4.32994 5.38382 -2.03293 -4.21819 5.42162 -1.78839 -3.54571 4.84955 -1.8515 -3.72153 5.18349 -1.70849 -3.32895 4.87558 -1.65066 -3.17152 4.82445 -1.63908 -3.13896 4.92076 -1.59944 -3.03307 4.92448 -1.69247 -3.2894 5.41092 -1.68168 -3.26254 5.53485 -1.89362 -3.84719 6.544 -1.64637 -3.16724 5.7348 -1.64274 -3.15782 5.90007 -1.55419 -2.91668 5.69929 -1.76495 -3.49985 6.85817 -1.48655 -2.73136 5.75349 -1.44516 -2.62004 5.74315 -1.41173 -2.52868 5.76495 -1.50377 -2.78611 6.47063 -1.46169 -2.67035 6.46818 -1.4556 -2.65556 6.67806 -1.49717 -2.77181 7.19598 -1.40043 -2.50658 6.86422 -1.37942 -2.4519 7.01078 -1.32761 -2.30964 6.94433 -1.29785 -2.22922 7.03283 -1.3054 -2.25161 7.41994 -1.23485 -2.05881 7.19676 -1.21405 -2.00405 7.38568 -1.19239 -1.94776 7.58413 -1.1271 -1.76735 7.36022 -1.07237 -1.61761 7.21853 -1.00051 -1.41734 6.8408 -0.964467 -1.3191 6.85649 -0.928409 -1.22095 6.87027 -0.911476 -1.17716 7.16632 -0.87366 -1.07554 7.18716 -0.843231 -0.993668 7.32455 -0.797054 -0.868981 7.19364 -0.755491 -0.753777 7.0996 -0.713735 -0.639151 6.97345 -0.672767 -0.524657 6.80515 -0.741501 -0.746081 11.101 -0.684824 -0.595778 11.3727 -0.574292 -0.261723 7.37563 -0.53369 -0.150604 7.11948 -0.497429 -0.0499935 7.06126 -1.05269 -1.64228 -0.989043 -1.06963 -1.69405 -0.980727 -1.08915 -1.75229 -0.978421 -1.1112 -1.81798 -0.981776 -1.13069 -1.87706 -0.976224 -1.1537 -1.94364 -0.976039 -1.17309 -2.00455 -0.967192 -1.19865 -2.07846 -0.970072 -1.22159 -2.14676 -0.964294 -1.24448 -2.21596 -0.95647 -1.26997 -2.29157 -0.953158 -1.29787 -2.37653 -0.95361 -1.32328 -2.4539 -0.945605 -1.35216 -2.53968 -0.941219 -1.38605 -2.64125 -0.945709 -1.41838 -2.73627 -0.941396 -1.4522 -2.83954 -0.939695 -1.49051 -2.9512 -0.940019 -1.52526 -3.0562 -0.931631 -1.56844 -3.18636 -0.93499 -1.61013 -3.30896 -0.929197 -1.65419 -3.44177 -0.924223 -1.70424 -3.59123 -0.923985 -1.75774 -3.74989 -0.923221 -1.81363 -3.91868 -0.921379 -1.87045 -4.08924 -0.91375 -1.9391 -4.29512 -0.916194 -2.00527 -4.49329 -0.907783 -2.07833 -4.70996 -0.899819 -2.15971 -4.95435 -0.894765 -2.24794 -5.21811 -0.887612 -2.34645 -5.51059 -0.880631 -2.45675 -5.83996 -0.875035 -2.5822 -6.21649 -0.871647 -2.7145 -6.61308 -0.860019 -2.86049 -7.04841 -0.843993 -3.0217 -7.53058 -0.823684 -3.23626 -8.17233 -0.821388 -3.43566 -8.76943 -0.786424 -3.69192 -9.53494 -0.761157 -4.02105 -10.5189 -0.743958 -4.40946 -11.6825 -0.717301 -4.88455 -13.1026 -0.68083 -5.44543 -14.7785 -0.620659 -6.11062 -16.769 -0.527534 -6.5884 -18.2023 0.0150863 -6.59221 -18.216 0.350142 -6.65352 -18.4049 0.682434 -7.13585 -19.8554 1.75381 -7.36713 -20.5514 2.15914 -6.48924 -17.9275 2.34246 -5.94867 -16.316 2.52409 -6.00161 -16.4768 2.84515 -5.93312 -16.2742 3.1259 -5.41772 -14.7348 3.20083 -5.31341 -14.4244 3.42591 -5.16733 -13.9908 3.61762 -5.22027 -14.1497 3.91687 -5.31977 -14.4529 4.25618 -5.26638 -14.2953 4.49676 -5.25809 -14.2722 4.76894 -5.27874 -14.3359 5.06727 -5.23885 -14.2208 5.31654 -5.33779 -14.5199 5.6978 -5.24444 -14.2416 5.89603 -6.13263 -16.9117 7.15969 -5.63654 -15.4263 6.93825 -5.4581 -14.8916 7.04506 -5.38167 -14.6664 7.26548 -5.41866 -14.7799 7.63221 -5.73529 -15.7337 8.40446 -5.76634 -15.8321 8.80284 -5.62778 -15.4194 8.94796 -5.63594 -15.4467 9.31679 -5.83356 -16.044 10.0135 -6.38038 -17.6923 11.3611 -5.91329 -16.3138 13.0638 -5.71579 -15.7212 13.0618 -2.49702 -6.02902 5.79836 -2.44554 -5.87405 5.84683 -2.42567 -5.81544 5.97306 -2.35085 -5.59405 5.95697 -2.06035 -4.71689 5.32996 -2.00259 -4.54528 5.32218 -1.99461 -4.52226 5.45298 -1.82019 -3.99778 5.07646 -1.78381 -3.88976 5.10688 -1.75173 -3.79445 5.14901 -1.69915 -3.63445 5.11563 -1.62745 -3.42066 5.01078 -1.60042 -3.34147 5.05787 -1.5915 -3.31619 5.17234 -1.52664 -3.12179 5.06939 -1.79327 -3.93001 6.30907 -1.76393 -3.84145 6.38044 -1.64918 -3.49545 6.0778 -1.52573 -3.12222 5.7068 -1.44875 -2.88997 5.52289 -1.46056 -2.92908 5.75991 -1.40848 -2.77414 5.68572 -1.4421 -2.8773 6.05337 -1.35634 -2.61763 5.78478 -1.32503 -2.52442 5.80588 -1.43504 -2.86276 6.68189 -1.40214 -2.76436 6.72478 -1.35099 -2.61057 6.64874 -1.31016 -2.48955 6.63241 -1.29643 -2.44906 6.80514 -1.27929 -2.39723 6.95972 -1.24109 -2.28429 6.96579 -1.20907 -2.18858 7.01611 -1.22001 -2.22489 7.45014 -1.16077 -2.04757 7.27249 -1.21681 -2.22452 8.2224 -1.1524 -2.02985 8.00389 -1.0569 -1.73828 7.39579 -0.984083 -1.51714 6.97259 -0.952864 -1.42521 7.02859 -0.943242 -1.39792 7.38517 -0.903194 -1.27831 7.34137 -0.842276 -1.09333 6.93177 -0.864872 -1.17088 8.00482 -0.794629 -0.955709 7.36332 -0.755378 -0.835554 7.27082 -0.710269 -0.697432 6.98735 -0.673409 -0.58619 6.87985 -0.644254 -0.500796 7.02908 -0.691177 -0.683162 11.2971 -0.580885 -0.316394 7.35323 -0.546202 -0.209736 7.33795 -0.510596 -0.102002 7.12078 -0.958739 -1.50757 -0.975996 -0.97208 -1.5529 -0.963562 -0.995412 -1.62875 -0.988155 -1.01029 -1.68142 -0.980479 -1.02623 -1.73311 -0.971658 -1.04628 -1.79872 -0.975902 -1.0647 -1.85879 -0.971295 -1.08213 -1.91871 -0.965085 -1.10309 -1.98613 -0.964142 -1.12711 -2.06836 -0.97481 -1.14552 -2.12908 -0.963262 -1.16893 -2.20571 -0.962987 -1.18977 -2.27574 -0.954105 -1.21321 -2.35216 -0.949635 -1.23655 -2.43047 -0.942869 -1.26242 -2.51614 -0.939866 -1.2882 -2.60367 -0.934168 -1.32005 -2.70606 -0.9373 -1.3508 -2.81022 -0.937232 -1.38251 -2.91529 -0.933923 -1.41425 -3.0202 -0.927419 -1.4509 -3.14279 -0.927694 -1.48851 -3.26625 -0.924129 -1.52857 -3.39894 -0.921432 -1.57354 -3.54921 -0.923617 -1.61944 -3.7013 -0.920814 -1.66778 -3.86253 -0.917481 -1.71711 -4.02457 -0.90881 -1.7772 -4.22288 -0.910657 -1.83481 -4.4135 -0.902049 -1.89973 -4.63187 -0.897942 -1.96907 -4.86035 -0.88997 -2.04325 -5.10812 -0.880888 -2.12429 -5.37525 -0.869608 -2.22437 -5.70732 -0.870207 -2.33519 -6.07713 -0.870538 -2.45626 -6.47641 -0.865899 -2.56313 -6.83138 -0.834688 -2.62514 -7.03776 -0.754053 -2.76861 -7.51559 -0.72871 -2.93217 -8.0587 -0.70052 -3.14496 -8.76383 -0.683684 -3.49519 -9.92425 -0.720261 -3.823 -11.0125 -0.703337 -4.19765 -12.255 -0.667787 -4.64991 -13.7554 -0.617786 -5.15981 -15.448 -0.532461 -5.87984 -17.8392 -0.442218 -6.02103 -18.3104 -0.144945 -6.03293 -18.3558 0.1877 -6.04659 -18.4053 0.521431 -6.1619 -18.794 0.854001 -6.70623 -20.6132 1.96754 -6.80852 -20.9577 2.36672 -5.77878 -17.5434 2.46576 -5.06924 -15.1914 2.54857 -4.93314 -14.7447 2.77491 -5.01087 -15.0079 3.08419 -4.854 -14.4881 3.28137 -4.79461 -14.2972 3.51846 -4.84819 -14.479 3.82263 -4.79071 -14.2894 4.05607 -4.92792 -14.7503 4.43557 -4.9481 -14.8218 4.73679 -4.78502 -14.2844 4.87799 -4.78596 -14.2916 5.15918 -4.80199 -14.3489 5.45884 -4.89592 -14.6652 5.8494 -4.93798 -14.8091 6.19545 -4.981 -14.9545 6.55158 -4.95595 -14.878 6.83027 -4.96794 -14.9216 7.15922 -4.93455 -14.8168 7.43018 -5.20313 -15.7167 8.15891 -5.18332 -15.6558 8.47327 -5.25339 -15.8927 8.93861 -5.2545 -15.9038 9.303 -5.26418 -15.9405 9.6885 -5.16301 -15.6083 9.87242 -5.97122 -18.3165 11.8479 -6.58531 -20.3996 15.1289 -1.74913 -4.20155 4.13725 -1.71416 -4.0867 4.16553 -5.22944 -15.8834 13.7506 -2.28994 -6.02485 6.01446 -2.06246 -5.26042 5.53736 -1.70909 -4.07671 4.64397 -1.7121 -4.088 4.78397 -1.7303 -4.15062 4.97954 -1.71126 -4.09124 5.06148 -1.68226 -3.99494 5.10724 -1.60931 -3.75142 4.99373 -1.6048 -3.73689 5.11951 -1.49281 -3.36383 4.84004 -1.48656 -3.3438 4.95315 -1.49549 -3.37643 5.1352 -1.52915 -3.48934 5.42774 -1.49916 -3.39168 5.45922 -1.45571 -3.24631 5.42499 -1.43755 -3.18897 5.50752 -1.46527 -3.28561 5.81743 -1.36405 -2.94512 5.48071 -1.32389 -2.81123 5.44171 -1.33646 -2.85502 5.68636 -1.30818 -2.76176 5.71204 -1.32666 -2.82885 6.02016 -1.4075 -3.1069 6.74146 -1.34784 -2.90594 6.59489 -1.33329 -2.86053 6.74446 -1.38368 -3.03824 7.36875 -1.24108 -2.55157 6.59214 -1.21372 -2.46195 6.64683 -1.23534 -2.5389 7.1036 -1.18137 -2.35947 6.95464 -1.15152 -2.26029 6.99666 -1.11469 -2.1395 6.9806 -1.13147 -2.20205 7.49948 -1.15104 -2.27538 8.10767 -1.1257 -2.19449 8.27201 -1.04041 -1.90395 7.71614 -0.953177 -1.60239 7.03629 -0.962597 -1.64497 7.64556 -0.932969 -1.54505 7.72299 -0.884682 -1.3829 7.51566 -0.840693 -1.23531 7.34365 -0.833332 -1.21643 7.85682 -0.790204 -1.07163 7.69035 -0.745975 -0.921804 7.44164 -0.696786 -0.754086 6.98143 -0.666829 -0.654353 6.99409 -0.635954 -0.549095 6.95522 -0.610028 -0.468015 7.20345 -0.597244 -0.446226 8.61833 -0.548936 -0.267685 7.38633 -0.515486 -0.153483 7.12017 -0.485413 -0.050746 7.0719 -0.90921 -1.49783 -0.981491 -0.924752 -1.55512 -0.985207 -0.938674 -1.60685 -0.979673 -0.954119 -1.66599 -0.980394 -0.968001 -1.71858 -0.972213 -0.986042 -1.78412 -0.977346 -1.00246 -1.8441 -0.973528 -1.02041 -1.91147 -0.975167 -1.03679 -1.97229 -0.968004 -1.05319 -2.03303 -0.959242 -1.07205 -2.10219 -0.955494 -1.09398 -2.18614 -0.963057 -1.11281 -2.2561 -0.955264 -1.13671 -2.34094 -0.958194 -1.15704 -2.41912 -0.952412 -1.17833 -2.49824 -0.944388 -1.19964 -2.57726 -0.934067 -1.22842 -2.68053 -0.938733 -1.2561 -2.78559 -0.940099 -1.28234 -2.88211 -0.932962 -1.31101 -2.98792 -0.928091 -1.34212 -3.10299 -0.925187 -1.37961 -3.2441 -0.933571 -1.41412 -3.36927 -0.927795 -1.45008 -3.50359 -0.922782 -1.49096 -3.65551 -0.922551 -1.53276 -3.80923 -0.917333 -1.57701 -3.9721 -0.911384 -1.62508 -4.15439 -0.908117 -1.68009 -4.35424 -0.906744 -1.73404 -4.5557 -0.898676 -1.79133 -4.76824 -0.887387 -1.85843 -5.0168 -0.882716 -1.9279 -5.27629 -0.872821 -2.00808 -5.5737 -0.866355 -2.11459 -5.96392 -0.878966 -2.18985 -6.24563 -0.844897 -2.23597 -6.41623 -0.770299 -2.34482 -6.82003 -0.750323 -2.46583 -7.27156 -0.727497 -2.60093 -7.77181 -0.699085 -2.76708 -8.38754 -0.67586 -3.0061 -9.26978 -0.679166 -3.31443 -10.4125 -0.692954 -3.62378 -11.5583 -0.665849 -3.98701 -12.9071 -0.623186 -4.39062 -14.4023 -0.547726 -4.89236 -16.2634 -0.451259 -5.5519 -18.718 0.34855 -5.56028 -18.7559 0.686461 -5.7053 -19.2995 1.02631 -5.83811 -19.7983 1.38487 -4.86802 -16.2252 2.4927 -4.68293 -15.5451 2.71386 -4.59623 -15.2268 2.95763 -4.58323 -15.1824 3.23119 -4.39639 -14.4938 3.39799 -4.61357 -15.3076 3.81702 -4.87201 -16.2723 4.29861 -4.52285 -14.9774 4.31826 -4.54085 -15.0518 4.62014 -4.56319 -15.138 4.93047 -4.40081 -14.5383 5.05518 -4.5346 -15.0434 5.48895 -4.57405 -15.1972 5.83351 -4.5356 -15.0589 6.08874 -4.452 -14.7514 6.28165 -4.44056 -14.7154 6.56803 -4.37002 -14.4575 6.76838 -4.62101 -15.397 7.46445 -4.62783 -15.4277 7.80433 -4.64947 -15.5139 8.17584 -4.83725 -16.2227 8.85757 -4.80127 -16.0965 9.15383 -4.67729 -15.6396 9.27505 -4.7814 -16.0345 9.85271 -4.95396 -16.6858 10.6026 -4.97492 -16.7731 11.0529 -6.0954 -20.9855 14.6098 -5.14456 -17.4334 12.7498 -5.08757 -17.2252 13.0572 -1.64176 -4.30286 4.12785 -1.61241 -4.19498 4.16394 -4.82205 -16.254 13.7084 -4.72355 -15.8934 13.8829 -1.59613 -4.14215 4.48127 -1.60569 -4.17903 4.6392 -1.60033 -4.161 4.75349 -1.65541 -4.36968 5.0827 -1.60943 -4.20125 5.06538 -1.57762 -4.08367 5.0919 -1.58553 -4.11638 5.27116 -1.5711 -4.06464 5.36645 -1.38506 -3.36511 4.74363 -1.36984 -3.30767 4.81122 -1.37851 -3.34441 4.99128 -1.40483 -3.4441 5.25809 -1.39446 -3.40902 5.36628 -1.37592 -3.3403 5.43494 -1.35229 -3.25446 5.47867 -1.33116 -3.17809 5.53666 -1.20511 -2.70243 5.00306 -1.17394 -2.58651 4.97659 -1.22447 -2.78212 5.44226 -1.23756 -2.83513 5.70398 -1.19151 -2.66039 5.59143 -1.28313 -3.0171 6.41863 -1.30658 -3.10827 6.81351 -1.21945 -2.77856 6.41813 -1.27638 -3.0025 7.10932 -1.16145 -2.56474 6.45214 -1.14876 -2.52222 6.60635 -1.14121 -2.49835 6.81549 -1.13127 -2.46373 7.01622 -1.09432 -2.32552 6.96687 -1.07677 -2.26317 7.11063 -1.05835 -2.19931 7.26333 -1.02473 -2.0748 7.24526 -0.982643 -1.91545 7.11041 -0.955861 -1.8154 7.15357 -0.918693 -1.67736 7.06027 -0.924449 -1.70956 7.61129 -0.910675 -1.66368 7.91282 -0.848539 -1.42325 7.38616 -0.817402 -1.30774 7.37162 -0.781878 -1.17388 7.25669 -0.782537 -1.1889 7.98603 -0.739896 -1.02801 7.71984 -0.697981 -0.865757 7.38069 -0.657443 -0.708733 6.97831 -0.630578 -0.606715 6.98012 -0.606637 -0.525205 7.21921 -0.578947 -0.420805 7.22761 -0.551555 -0.322625 7.37389 -0.521906 -0.214757 7.3487 -0.493432 -0.103433 7.11147 -0.871713 -1.53778 -0.983338 -0.883572 -1.59042 -0.978543 -0.89644 -1.64306 -0.972455 -0.909893 -1.70205 -0.972567 -0.924356 -1.76103 -0.971186 -0.938772 -1.82093 -0.968157 -0.953138 -1.88176 -0.963681 -0.969034 -1.94997 -0.964561 -0.985943 -2.01815 -0.963648 -1.00333 -2.09462 -0.967539 -1.01869 -2.15617 -0.956126 -1.03546 -2.22707 -0.949472 -1.05383 -2.3043 -0.947325 -1.07461 -2.39091 -0.949143 -1.0929 -2.46991 -0.942403 -1.11366 -2.55727 -0.939277 -1.13691 -2.65298 -0.939465 -1.16012 -2.74953 -0.936808 -1.1833 -2.84695 -0.931205 -1.2079 -2.9536 -0.928063 -1.24141 -3.09376 -0.942569 -1.26547 -3.19376 -0.927234 -1.29745 -3.32715 -0.928544 -1.32787 -3.45399 -0.920951 -1.36368 -3.60672 -0.923144 -1.39899 -3.75194 -0.915989 -1.43717 -3.91557 -0.912759 -1.48116 -4.09876 -0.912418 -1.52904 -4.30034 -0.914108 -1.57059 -4.47557 -0.89772 -1.62329 -4.69722 -0.893856 -1.67835 -4.92986 -0.885968 -1.73689 -5.17152 -0.873859 -1.81034 -5.47996 -0.875508 -1.86778 -5.72469 -0.845818 -1.91272 -5.91326 -0.790854 -1.99587 -6.26154 -0.775004 -2.08522 -6.64006 -0.754514 -2.1829 -7.04687 -0.728094 -2.30659 -7.56917 -0.713227 -2.4361 -8.11218 -0.684173 -2.59986 -8.8001 -0.66329 -2.8418 -9.81529 -0.674007 -3.10448 -10.9199 -0.661875 -3.3962 -12.1424 -0.626056 -3.73327 -13.5602 -0.569288 -4.10088 -15.1053 -0.474367 -4.58201 -17.1259 -0.362396 -5.15259 -19.5256 -0.20157 -6.65985 -25.8509 -0.126553 -9.90022 -39.4738 0.695932 -5.26902 -20.0702 2.2886 -5.21585 -19.8513 2.63241 -4.46523 -16.7034 2.67595 -4.29966 -16.0153 2.89757 -4.91077 -18.5952 3.54141 -4.33171 -16.1637 3.50515 -4.26546 -15.8885 3.75478 -4.227 -15.7347 4.01916 -5.18689 -19.7901 5.16516 -4.08301 -15.1389 4.47073 -4.03091 -14.9265 4.70421 -4.23042 -15.7749 5.21528 -4.11829 -15.3083 5.38489 -5.14514 -19.653 7.01024 -3.95726 -14.6408 5.76518 -3.80486 -14.0042 5.83594 -3.97015 -14.7086 6.37436 -3.91249 -14.4702 6.58117 -3.87078 -14.3009 6.81038 -3.96637 -14.7124 7.2846 -3.94812 -14.6393 7.5634 -3.89031 -14.4031 7.76682 -4.0445 -15.0677 8.4081 -4.22888 -15.8536 9.14672 -4.15659 -15.5585 9.34645 -4.59586 -17.4321 10.7525 -4.48044 -16.9504 10.881 -4.79692 -18.3068 12.1089 -4.84175 -18.5058 12.6815 -4.70545 -17.9356 12.7692 -4.61739 -17.5708 12.9783 -1.55628 -4.52943 4.20814 -1.49711 -4.2773 4.14346 -1.49101 -4.25392 4.24348 -1.50261 -4.30681 4.40458 -1.47548 -4.19521 4.43756 -1.47505 -4.19597 4.56326 -1.47375 -4.19462 4.68996 -1.48226 -4.23298 4.85738 -1.52887 -4.43229 5.1829 -1.50728 -4.34752 5.24799 -1.48523 -4.25313 5.3041 -1.49298 -4.28932 5.49395 -1.32094 -3.55615 4.85855 -1.30523 -3.48988 4.9216 -1.53894 -4.50006 6.23564 -1.29878 -3.46859 5.18133 -1.296 -3.45953 5.32008 -1.30624 -3.50652 5.53797 -1.28953 -3.44146 5.61601 -1.2512 -3.2756 5.5563 -1.19144 -3.02285 5.36163 -1.15525 -2.87127 5.2997 -1.10696 -2.66354 5.1418 -1.12452 -2.74442 5.43359 -1.12015 -2.72965 5.58448 -1.1125 -2.70146 5.71883 -1.20634 -3.11366 6.66348 -1.16136 -2.91978 6.53376 -1.13009 -2.78947 6.51419 -1.08084 -2.57839 6.32148 -1.06347 -2.50865 6.41201 -1.07407 -2.56207 6.78381 -1.07494 -2.57223 7.08567 -1.04461 -2.44298 7.06605 -1.02238 -2.35342 7.14603 -0.994503 -2.23519 7.14975 -0.969097 -2.12788 7.17932 -0.940293 -2.00728 7.16902 -0.913192 -1.89299 7.17534 -0.884396 -1.77111 7.15065 -0.899924 -1.85446 7.87541 -0.856106 -1.66403 7.6169 -0.819716 -1.50808 7.46084 -0.783232 -1.35022 7.26214 -0.748248 -1.20118 7.06967 -0.755591 -1.24843 7.92608 -0.729378 -1.14358 8.02617 -0.689182 -0.965712 7.63998 -0.645927 -0.767556 6.9917 -0.632181 -0.723926 7.53114 -0.59726 -0.565854 7.03535 -0.575523 -0.476954 7.22389 -0.562739 -0.455165 8.63877 -0.525617 -0.272275 7.38674 -0.499293 -0.157004 7.13058 -0.474412 -0.0520752 7.09238 -0.819736 -1.51949 -0.981124 -0.832223 -1.5776 -0.984776 -0.84309 -1.63014 -0.979277 -0.855479 -1.69011 -0.980034 -0.864791 -1.73604 -0.964535 -0.878718 -1.80334 -0.96975 -0.892658 -1.87055 -0.973166 -0.904975 -1.93221 -0.967732 -0.918303 -1.99386 -0.960704 -0.932163 -2.06281 -0.958928 -0.948556 -2.13918 -0.961915 -0.962325 -2.20994 -0.956245 -0.977109 -2.28067 -0.948582 -0.993369 -2.35973 -0.945328 -1.00965 -2.43868 -0.939777 -1.02987 -2.5344 -0.944046 -1.04612 -2.61411 -0.93385 -1.06627 -2.71157 -0.932727 -1.0889 -2.81733 -0.934319 -1.10903 -2.91549 -0.927253 -1.13306 -3.03132 -0.927861 -1.15459 -3.13955 -0.919811 -1.18249 -3.27381 -0.923349 -1.2089 -3.40052 -0.917935 -1.23922 -3.54478 -0.917896 -1.27094 -3.69916 -0.917873 -1.30115 -3.84596 -0.908398 -1.33524 -4.01123 -0.902752 -1.37562 -4.20431 -0.903999 -1.41593 -4.39908 -0.898856 -1.45771 -4.60283 -0.89118 -1.50427 -4.82696 -0.883843 -1.55709 -5.07968 -0.879256 -1.61519 -5.36088 -0.876115 -1.65013 -5.53204 -0.826432 -1.6952 -5.75041 -0.785725 -1.7634 -6.08078 -0.770836 -1.84022 -6.45075 -0.754973 -1.92083 -6.84162 -0.731204 -2.01925 -7.31815 -0.714181 -2.12242 -7.81643 -0.684814 -2.24721 -8.4205 -0.659031 -2.41466 -9.22852 -0.648498 -2.63236 -10.2808 -0.648391 -2.86494 -11.4039 -0.620896 -3.1254 -12.6639 -0.570772 -3.41848 -14.082 -0.492618 -3.77065 -15.7833 -0.389406 -4.02059 -16.9973 -0.191578 -4.24357 -18.0818 0.055673 -5.23699 -22.9415 2.25657 -5.19925 -22.7701 2.65465 -5.20882 -22.8274 3.06809 -5.13469 -22.4774 3.44077 -5.09058 -22.2773 3.82127 -5.24618 -23.0406 4.33562 -4.66868 -20.253 4.30138 -5.12557 -22.479 5.07594 -3.77954 -15.957 4.1883 -3.5278 -14.7417 4.2192 -3.52225 -14.7228 4.49046 -3.55091 -14.8704 4.80566 -3.56347 -14.9355 5.10642 -3.61866 -15.2115 5.47418 -3.8542 -16.3697 6.13186 -4.13202 -17.7323 6.90637 -3.38879 -14.1202 5.98358 -3.40606 -14.2078 6.29954 -3.35139 -13.9515 6.48723 -3.49688 -14.6725 7.07287 -3.45031 -14.4496 7.28247 -3.62313 -15.3072 7.97924 -3.63497 -15.3723 8.33978 -3.64286 -15.4201 8.70031 -3.63264 -15.3834 9.02389 -3.57434 -15.1053 9.22135 -3.8507 -16.4705 10.3441 -4.2701 -18.5395 11.9535 -4.00647 -17.2587 11.6112 -3.94975 -16.9919 11.8639 -3.88917 -16.7048 12.0994 -3.92851 -16.9116 12.6696 -1.37956 -4.36425 4.12793 -1.37751 -4.35755 4.24046 -1.38494 -4.39572 4.38995 -1.42508 -4.59955 4.67729 -1.40128 -4.48292 4.7145 -1.37015 -4.33618 4.72296 -1.35636 -4.27237 4.79963 -1.40629 -4.51916 5.1631 -1.37431 -4.36954 5.16791 -1.32219 -4.11375 5.06415 -1.32416 -4.12712 5.22178 -1.35905 -4.30599 5.561 -1.34375 -4.23473 5.64433 -1.36553 -4.34502 5.93473 -1.20088 -3.52742 5.15005 -1.18943 -3.47536 5.23519 -1.33155 -4.19084 6.29197 -1.20283 -3.55198 5.64815 -1.1907 -3.49541 5.74259 -1.13675 -3.22913 5.54491 -1.07321 -2.91556 5.25747 -1.02309 -2.66738 5.04313 -1.03132 -2.71558 5.27461 -1.04369 -2.78184 5.55141 -1.03551 -2.74443 5.66878 -1.03603 -2.75239 5.87292 -1.08657 -3.01527 6.55996 -1.05943 -2.88312 6.54207 -1.00824 -2.63221 6.28044 -0.977897 -2.48187 6.20051 -0.972184 -2.45914 6.38897 -0.929793 -2.24739 6.15763 -0.932788 -2.27305 6.47306 -0.921489 -2.22376 6.62401 -0.879916 -2.01194 6.35442 -0.969188 -2.48903 7.98744 -0.941174 -2.35667 7.99277 -0.936828 -2.34289 8.36649 -0.915452 -2.24304 8.49312 -0.865583 -1.99276 8.09904 -0.827099 -1.79801 7.85319 -0.783396 -1.57882 7.4667 -0.760313 -1.46523 7.48394 -0.72881 -1.30774 7.28391 -0.720531 -1.28271 7.73811 -0.699131 -1.18115 7.83862 -0.676946 -1.07509 7.9276 -0.642559 -0.901188 7.54937 -0.612241 -0.743282 7.17721 -0.591571 -0.644692 7.25903 -0.569058 -0.534458 7.22957 -0.547615 -0.435024 7.3477 -0.525434 -0.335154 7.51419 -0.502737 -0.218607 7.36907 -0.480356 -0.105136 7.12187 -0.790799 -1.61628 -0.986054 -0.799039 -1.66324 -0.972198 -0.809437 -1.72305 -0.972346 -0.819786 -1.78379 -0.970946 -0.830148 -1.84445 -0.967948 -0.841519 -1.9051 -0.963557 -0.853363 -1.97407 -0.964368 -0.865219 -2.04295 -0.963482 -0.87493 -2.0989 -0.947194 -0.889272 -2.17611 -0.949422 -0.902573 -2.25414 -0.949398 -0.915306 -2.32571 -0.940877 -0.931041 -2.41301 -0.942821 -0.945796 -2.50015 -0.942362 -0.959984 -2.5808 -0.933406 -0.977122 -2.67814 -0.933666 -0.994222 -2.77634 -0.93108 -1.01381 -2.88285 -0.93121 -1.0309 -2.98177 -0.922782 -1.04941 -3.0899 -0.916515 -1.07178 -3.21666 -0.917074 -1.09565 -3.35159 -0.918845 -1.11795 -3.47996 -0.911414 -1.14418 -3.62588 -0.90936 -1.17186 -3.78091 -0.90717 -1.19945 -3.93769 -0.899987 -1.22986 -4.11387 -0.896079 -1.26416 -4.30845 -0.894502 -1.30086 -4.51307 -0.890348 -1.34324 -4.75555 -0.894191 -1.37981 -4.96348 -0.875857 -1.4274 -5.23609 -0.874156 -1.44777 -5.35148 -0.809577 -1.49245 -5.6078 -0.786326 -1.54765 -5.92134 -0.771561 -1.60809 -6.26417 -0.754198 -1.67903 -6.66496 -0.740178 -1.75276 -7.08655 -0.717149 -1.84077 -7.58636 -0.696798 -1.93684 -8.13545 -0.669185 -2.05762 -8.82176 -0.647942 -2.20836 -9.67458 -0.630872 -2.39608 -10.7434 -0.6162 -2.59669 -11.8828 -0.573231 -2.82727 -13.1905 -0.509318 -3.08833 -14.6752 -0.416628 -3.33017 -16.0524 -0.263285 -3.42906 -16.6226 -0.0121788 -3.46749 -16.8545 0.273247 -4.61938 -23.4982 3.32456 -4.44404 -22.5155 3.63091 -4.44862 -22.5557 4.04125 -4.51384 -22.9387 4.5074 -4.54077 -23.1088 4.95318 -4.51692 -22.9892 5.3528 -3.30079 -16.0492 4.33487 -3.04942 -14.625 4.31005 -3.06805 -14.7386 4.61075 -3.08508 -14.8458 4.91655 -3.09905 -14.9377 5.22453 -3.18785 -15.4587 5.66814 -3.09502 -14.935 5.79944 -3.17948 -15.4298 6.26062 -3.0206 -14.5295 6.24188 -2.99654 -14.4006 6.48445 -3.01287 -14.5054 6.81947 -3.18129 -15.4863 7.53194 -3.07724 -14.8942 7.59349 -3.16018 -15.3877 8.13892 -3.2118 -15.6989 8.62178 -3.23141 -15.8213 9.02823 -3.21269 -15.725 9.33043 -3.55484 -17.7175 10.7884 -3.38893 -16.7752 10.6567 -3.35395 -16.5816 10.937 -3.41554 -16.9552 11.5693 -3.1188 -15.2511 10.8832 -1.40375 -5.28902 4.56284 -1.35592 -5.016 4.50846 -1.27782 -4.57037 4.31768 -1.26613 -4.50479 4.39214 -1.25294 -4.43045 4.45918 -1.24035 -4.36295 4.53086 -1.23 -4.30905 4.6139 -1.24158 -4.38144 4.8067 -1.23961 -4.37487 4.93675 -1.21736 -4.24802 4.95943 -1.20323 -4.17259 5.02723 -1.16595 -3.95535 4.95307 -1.19632 -4.14225 5.28671 -1.27597 -4.61683 5.94738 -1.26665 -4.56528 6.06527 -1.20954 -4.23559 5.868 -1.17885 -4.06182 5.83568 -1.2557 -4.52311 6.57862 -1.18807 -4.1269 6.27404 -1.20899 -4.25746 6.64004 -1.17522 -4.06652 6.58587 -1.05739 -3.36909 5.80151 -0.935671 -2.64453 4.91203 -0.932066 -2.63186 5.0417 -0.960485 -2.81024 5.48417 -0.947389 -2.73279 5.53323 -0.946188 -2.73455 5.71886 -0.936552 -2.68745 5.82746 -0.950906 -2.7782 6.19956 -0.955084 -2.81589 6.49644 -0.918985 -2.6026 6.30362 -0.898227 -2.48087 6.28559 -0.882536 -2.39764 6.34681 -0.859367 -2.26277 6.2875 -0.84779 -2.19774 6.39133 -0.834502 -2.12708 6.48529 -0.812876 -2.00075 6.4376 -0.873017 -2.39741 7.87716 -0.851472 -2.27617 7.90902 -0.853371 -2.30231 8.41562 -0.788944 -1.9058 7.53438 -0.772002 -1.81407 7.64415 -0.755913 -1.72704 7.78168 -0.712175 -1.45634 7.15948 -0.695058 -1.36696 7.26235 -0.681362 -1.29504 7.46198 -0.67018 -1.24309 7.80835 -0.65182 -1.14328 7.93766 -0.626952 -0.992145 7.73909 -0.600817 -0.839511 7.46798 -0.579863 -0.711549 7.3327 -0.558578 -0.591239 7.22473 -0.54008 -0.48484 7.24418 -0.52732 -0.461032 8.63914 -0.502474 -0.276394 7.41706 -0.483259 -0.159544 7.16097 -0.465292 -0.0530032 7.08279 -0.739056 -1.59404 -0.984737 -0.746294 -1.64096 -0.971575 -0.754113 -1.69427 -0.965014 -0.76246 -1.75493 -0.964403 -0.771816 -1.81558 -0.962399 -0.781702 -1.88356 -0.965947 -0.790024 -1.94498 -0.960692 -0.799298 -2.00739 -0.953795 -0.810101 -2.07717 -0.952155 -0.821381 -2.15525 -0.955318 -0.831157 -2.22577 -0.949728 -0.841885 -2.29727 -0.942296 -0.854616 -2.38445 -0.945424 -0.865317 -2.45674 -0.933747 -0.879488 -2.55311 -0.938237 -0.89069 -2.63353 -0.928168 -0.906249 -2.74002 -0.932872 -0.920304 -2.83898 -0.928924 -0.935381 -2.93785 -0.922084 -0.952361 -3.05426 -0.922908 -0.967778 -3.16413 -0.914929 -0.988634 -3.29899 -0.918783 -1.00841 -3.43557 -0.918338 -1.02667 -3.5646 -0.908941 -1.0488 -3.71217 -0.90467 -1.07139 -3.86878 -0.90016 -1.09679 -4.04479 -0.899024 -1.12175 -4.21227 -0.888292 -1.15137 -4.41765 -0.887749 -1.18341 -4.63307 -0.88433 -1.21723 -4.86865 -0.880935 -1.24919 -5.08635 -0.862986 -1.26412 -5.19241 -0.798921 -1.30599 -5.47737 -0.790262 -1.3483 -5.77206 -0.77502 -1.39437 -6.08781 -0.755269 -1.45035 -6.47075 -0.743109 -1.51055 -6.88374 -0.725102 -1.57735 -7.33699 -0.701964 -1.64877 -7.8303 -0.67169 -1.73807 -8.44132 -0.647189 -1.84711 -9.18911 -0.625938 -1.98521 -10.1345 -0.609829 -2.13975 -11.1903 -0.576009 -2.31685 -12.4042 -0.524795 -2.50805 -13.7186 -0.44152 -2.73134 -15.2492 -0.331355 -2.81669 -15.8428 -0.102124 -2.8461 -16.0569 0.16718 -3.16284 -18.2353 0.376005 -5.07008 -31.2827 0.479362 -6.75703 -42.918 2.55622 -3.8881 -23.3125 3.0852 -3.89286 -23.3844 3.92573 -3.94596 -23.788 4.83203 -3.94784 -23.8256 5.2701 -2.82682 -16.1045 4.18112 -2.83135 -16.1537 4.48758 -2.78859 -15.8698 4.71998 -2.78555 -15.8611 5.01383 -2.75982 -15.6945 5.26698 -2.69545 -15.2667 5.44071 -2.65608 -15.0081 5.6535 -2.71554 -15.4336 6.08474 -2.71331 -15.4286 6.38548 -2.70318 -15.3707 6.67037 -2.70935 -15.4279 7.00154 -2.69543 -15.3499 7.28397 -2.68039 -15.2569 7.56137 -2.7058 -15.449 7.96789 -2.72044 -15.5691 8.35355 -3.09406 -18.1968 9.98823 -2.76284 -15.8967 9.20263 -2.80963 -16.2428 9.74491 -2.73115 -15.7089 9.81633 -2.73397 -15.7431 10.2021 -1.2526 -5.34442 4.25266 -2.65946 -15.257 10.6506 -1.28514 -5.5853 4.67354 -1.24198 -5.28398 4.60912 -1.24003 -5.27727 4.74187 -1.13397 -4.53178 4.33403 -1.12333 -4.46532 4.40735 -1.11275 -4.39791 4.47941 -1.09578 -4.28392 4.5123 -1.11048 -4.38942 4.72882 -1.11488 -4.42946 4.89756 -1.17385 -4.85429 5.42369 -1.06739 -4.10379 4.87373 -1.06684 -4.10779 5.015 -1.14297 -4.66036 5.71658 -1.14909 -4.70909 5.93479 -1.12222 -4.52227 5.9072 -1.08291 -4.25147 5.77787 -1.06376 -4.12288 5.79914 -1.13298 -4.63079 6.58398 -1.11753 -4.52794 6.65694 -1.18262 -5.00838 7.48492 -0.999748 -3.68724 5.94996 -0.989988 -3.62469 6.04649 -0.888048 -2.8894 5.17514 -0.853717 -2.64582 4.96831 -0.862746 -2.71652 5.23243 -0.881582 -2.86874 5.64446 -0.870375 -2.79395 5.70295 -0.857811 -2.70697 5.74263 -0.847233 -2.6395 5.8159 -0.877904 -2.88125 6.47993 -0.862318 -2.77741 6.512 -0.833019 -2.5682 6.32624 -0.806551 -2.38015 6.16212 -0.797565 -2.32278 6.27632 -0.781995 -2.21636 6.27962 -0.811049 -2.45058 7.13394 -0.758251 -2.05752 6.41969 -0.79459 -2.35951 7.55482 -0.789434 -2.33703 7.86014 -0.783514 -2.31304 8.19512 -0.744537 -2.02281 7.68947 -0.722426 -1.86643 7.57973 -0.730764 -1.95995 8.39416 -0.681921 -1.57807 7.39868 -0.668634 -1.4949 7.54249 -0.64396 -1.31763 7.26444 -0.638439 -1.29985 7.75782 -0.622239 -1.19355 7.83873 -0.600565 -1.03699 7.61164 -0.582036 -0.903992 7.50003 -0.564957 -0.786325 7.46525 -0.547039 -0.654554 7.28911 -0.530637 -0.542679 7.25971 -0.529017 -0.712401 11.2786 -0.499908 -0.330995 7.3647 -0.483702 -0.223492 7.42943 -0.468296 -0.107407 7.1423 -0.687802 -1.5644 -0.975376 -0.695182 -1.62417 -0.978405 -0.700427 -1.67095 -0.964735 -0.708345 -1.73802 -0.972417 -0.714124 -1.7921 -0.963699 -0.72143 -1.85358 -0.960836 -0.729265 -1.9224 -0.963626 -0.736596 -1.98373 -0.957567 -0.744338 -2.05437 -0.956762 -0.753153 -2.12398 -0.954113 -0.760864 -2.19544 -0.949563 -0.770111 -2.27424 -0.94967 -0.777329 -2.33813 -0.934775 -0.78801 -2.42615 -0.936944 -0.797713 -2.51399 -0.936611 -0.808313 -2.60375 -0.933687 -0.8194 -2.70174 -0.934068 -0.830511 -2.79958 -0.931553 -0.842991 -2.90766 -0.931649 -0.854964 -3.00827 -0.923198 -0.867433 -3.11705 -0.916952 -0.88275 -3.24439 -0.917627 -0.898511 -3.38084 -0.919359 -0.912771 -3.50973 -0.91204 -0.929891 -3.65711 -0.910042 -0.946987 -3.80526 -0.903401 -0.965476 -3.96351 -0.896375 -0.985842 -4.14009 -0.892769 -1.00903 -4.33601 -0.891339 -1.03399 -4.55217 -0.891231 -1.06037 -4.77827 -0.887843 -1.0773 -4.93184 -0.848995 -1.09996 -5.12229 -0.818694 -1.12626 -5.35139 -0.794833 -1.15584 -5.60885 -0.772508 -1.19467 -5.9438 -0.764373 -1.23354 -6.2792 -0.745002 -1.27878 -6.67435 -0.729254 -1.33148 -7.12815 -0.714089 -1.38593 -7.60358 -0.687763 -1.45206 -8.16706 -0.663212 -1.52642 -8.81004 -0.63382 -1.61643 -9.59142 -0.605262 -1.73543 -10.6208 -0.58648 -1.85597 -11.6606 -0.533356 -2.00276 -12.9291 -0.470004 -2.16848 -14.367 -0.378562 -2.27008 -15.2506 -0.193586 -2.30065 -15.5268 0.0588344 -2.38424 -16.2662 0.300543 -2.7102 -19.0858 0.514358 -2.69009 -18.9325 0.851011 -2.69688 -19.0126 1.1844 -2.68789 -18.9565 1.51703 -2.68562 -18.9549 1.85038 -2.68305 -18.9582 2.18458 -2.67206 -18.885 2.51348 -2.66921 -18.8764 2.84689 -2.66013 -18.8214 3.17597 -2.65275 -18.7715 3.50489 -2.64553 -18.7356 3.83579 -2.64007 -18.7038 4.16778 -2.63625 -18.6949 4.50499 -2.62952 -18.6509 4.8369 -2.63095 -18.6888 5.18778 -2.31241 -15.9193 4.86212 -2.31044 -15.9264 5.16126 -2.3069 -15.9095 5.45642 -2.28463 -15.7353 5.70676 -2.26971 -15.6228 5.97339 -2.26737 -15.6197 6.27563 -2.27305 -15.685 6.60599 -2.23345 -15.3622 6.79641 -2.2127 -15.1954 7.03969 -2.20524 -15.1435 7.32856 -2.22764 -15.3691 7.74136 -2.2663 -15.7294 8.23033 -2.27926 -15.8618 8.63052 -2.35537 -16.563 9.32798 -2.46745 -17.5794 10.2279 -2.32116 -16.2997 9.92357 -2.17519 -15.0274 9.57247 -1.08353 -5.28169 4.13868 -1.07376 -5.20106 4.21529 -1.07838 -5.25355 4.37603 -1.07401 -5.21883 4.4843 -1.09574 -5.42802 4.76253 -1.0709 -5.20863 4.74684 -0.986239 -4.45607 4.32567 -0.985571 -4.46079 4.45217 -0.979662 -4.41684 4.54247 -0.960861 -4.24679 4.53026 -0.978771 -4.41977 4.80584 -0.965646 -4.3088 4.84305 -1.01404 -4.76165 5.39817 -1.02468 -4.87168 5.66011 -0.988387 -4.5491 5.50648 -0.987899 -4.55394 5.67122 -1.06696 -5.29297 6.62153 -0.955843 -4.2756 5.70286 -0.953207 -4.26567 5.85959 -0.969932 -4.43284 6.23051 -0.992609 -4.658 6.69355 -0.912475 -3.92181 5.96787 -0.891583 -3.73228 5.90106 -0.881729 -3.65285 5.97383 -0.799368 -2.89056 5.08408 -0.790208 -2.81371 5.12594 -0.788966 -2.81386 5.28325 -0.817176 -3.09146 5.88879 -0.807298 -3.01156 5.95083 -0.784051 -2.80418 5.79605 -0.79973 -2.96469 6.27979 -0.79332 -2.91572 6.4101 -0.766172 -2.66575 6.15874 -0.768895 -2.71306 6.48224 -0.745851 -2.49821 6.27623 -0.736573 -2.42706 6.36472 -0.73271 -2.40909 6.58074 -0.717164 -2.2626 6.50198 -0.69975 -2.11208 6.40121 -0.698618 -2.12335 6.71856 -0.724076 -2.40534 7.83918 -0.719697 -2.39052 8.19332 -0.701046 -2.22956 8.11958 -0.669702 -1.92268 7.53425 -0.658023 -1.8252 7.62477 -0.639473 -1.65304 7.43304 -0.624864 -1.52881 7.41223 -0.608377 -1.3732 7.23311 -0.598689 -1.30206 7.44235 -0.587643 -1.21625 7.60183 -0.572465 -1.07622 7.47402 -0.559136 -0.970258 7.5315 -0.546757 -0.869006 7.63666 -0.532353 -0.721745 7.37262 -0.519144 -0.604466 7.3145 -0.514388 -0.803615 11.2621 -0.492918 -0.459386 8.54951 -0.480346 -0.281086 7.45732 -0.468107 -0.161622 7.16129 -0.456287 -0.0544584 7.10315 -0.64462 -1.59899 -0.977141 -0.649435 -1.65217 -0.971763 -0.6542 -1.7063 -0.965138 -0.658975 -1.76036 -0.957213 -0.664277 -1.82177 -0.95534 -0.670169 -1.88952 -0.959068 -0.675435 -1.95177 -0.953949 -0.681234 -2.02134 -0.954082 -0.686986 -2.09182 -0.952468 -0.692753 -2.16221 -0.948957 -0.699995 -2.24094 -0.950153 -0.705672 -2.31313 -0.942647 -0.712886 -2.39266 -0.939599 -0.719532 -2.46571 -0.928153 -0.727652 -2.56272 -0.932764 -0.735267 -2.65225 -0.928627 -0.743309 -2.75099 -0.927745 -0.752842 -2.85798 -0.929574 -0.761808 -2.95849 -0.922706 -0.77174 -3.07548 -0.923546 -0.781579 -3.1943 -0.920792 -0.792384 -3.314 -0.914497 -0.804107 -3.45111 -0.914263 -0.815803 -3.58902 -0.909785 -0.828827 -3.73805 -0.905571 -0.841887 -3.88684 -0.896664 -0.85724 -4.06326 -0.895829 -0.872937 -4.25066 -0.893457 -0.891884 -4.46662 -0.896716 -0.909766 -4.68417 -0.892981 -0.922311 -4.82742 -0.853604 -0.940745 -5.03718 -0.833634 -0.956322 -5.22905 -0.800304 -0.979247 -5.49651 -0.785545 -1.00361 -5.7738 -0.764909 -1.03275 -6.12008 -0.754239 -1.0633 -6.47704 -0.734644 -1.09929 -6.89262 -0.71742 -1.13926 -7.35846 -0.697459 -1.18424 -7.87447 -0.671968 -1.23623 -8.48928 -0.647888 -1.29642 -9.18447 -0.61662 -1.37047 -10.0471 -0.58805 -1.45527 -11.0312 -0.546194 -1.55577 -12.2032 -0.493527 -1.66712 -13.4958 -0.412594 -1.75574 -14.541 -0.265136 -1.7803 -14.8488 -0.0303396 -1.84258 -15.5909 0.192044 -1.90697 -16.3498 0.439573 -2.12078 -18.8572 0.683594 -2.12358 -18.9203 1.01397 -2.12677 -18.9772 1.34645 -2.12834 -19.0279 1.68094 -2.55686 -24.1571 3.56511 -2.54839 -24.0996 3.98667 -2.53044 -23.916 4.39011 -2.50353 -23.6475 4.77552 -2.40027 -22.4601 4.99055 -2.45709 -23.1697 5.53639 -2.48725 -23.5557 6.04151 -1.87246 -16.3293 4.79612 -1.85672 -16.1639 5.05725 -1.82493 -15.8127 5.26453 -1.83117 -15.9181 5.59326 -1.83781 -16.0173 5.92698 -1.80699 -15.6826 6.12625 -1.80532 -15.6854 6.43268 -2.14338 -19.7552 8.23078 -1.81469 -15.8505 7.11865 -1.74457 -15.0402 7.11025 -1.77019 -15.3814 7.56434 -1.78547 -15.5924 7.97929 -1.81196 -15.9387 8.47127 -1.81733 -16.0302 8.8589 -1.79768 -15.8291 9.1066 -0.963455 -5.71876 4.05816 -0.946748 -5.53387 4.08506 -0.930935 -5.3503 4.1064 -0.922623 -5.26194 4.17902 -0.923638 -5.28994 4.32367 -0.920201 -5.25626 4.43218 -0.917379 -5.22938 4.54602 -0.9148 -5.21598 4.67154 -0.854627 -4.47405 4.26812 -0.852773 -4.46427 4.38209 -0.863721 -4.61733 4.62612 -0.893091 -4.99453 5.06533 -0.887359 -4.93138 5.1586 -0.880177 -4.85849 5.24428 -0.875431 -4.81357 5.35545 -0.852436 -4.54033 5.25481 -0.834919 -4.32927 5.20153 -0.834399 -4.33369 5.35453 -0.849896 -4.55527 5.73926 -0.813518 -4.10535 5.42308 -0.81724 -4.16087 5.64295 -0.877561 -4.95533 6.72678 -0.870622 -4.88093 6.84333 -0.781095 -3.74996 5.65279 -0.773598 -3.66342 5.70987 -0.774107 -3.68829 5.91704 -0.737334 -3.21589 5.44668 -0.705346 -2.81869 5.04345 -0.703636 -2.80864 5.18334 -0.710083 -2.90967 5.50034 -0.71757 -3.03107 5.87289 -0.75336 -3.53183 6.90265 -0.712861 -3.00519 6.2272 -0.692874 -2.75393 5.99024 -0.688956 -2.71387 6.12597 -0.687007 -2.71463 6.3509 -0.674171 -2.55573 6.2628 -0.669388 -2.51477 6.41552 -0.661926 -2.42802 6.4769 -0.657651 -2.39888 6.67504 -0.641657 -2.19966 6.46574 -0.63509 -2.13605 6.58742 -0.64144 -2.26689 7.25361 -0.645622 -2.36561 7.89752 -0.642149 -2.35391 8.27073 -0.616228 -1.99664 7.55523 -0.605527 -1.87691 7.56985 -0.593084 -1.72682 7.46646 -0.581642 -1.5749 7.34034 -0.57232 -1.46722 7.37658 -0.562703 -1.36822 7.4599 -0.552116 -1.24094 7.40437 -0.542107 -1.12443 7.39543 -0.532499 -1.02724 7.50297 -0.523449 -0.913511 7.51988 -0.513343 -0.80133 7.54479 -0.50272 -0.656874 7.26924 -0.493342 -0.546436 7.25989 -0.478586 -0.716362 11.2587 -0.470878 -0.399237 8.62313 -0.463691 -0.226305 7.46968 -0.456259 -0.107668 7.14261 -0.595543 -1.56647 -0.967739 -0.598356 -1.61958 -0.96325 -0.602116 -1.67368 -0.957418 -0.605464 -1.73408 -0.957782 -0.60934 -1.80183 -0.963997 -0.612135 -1.85567 -0.954065 -0.615916 -1.92525 -0.956886 -0.619192 -1.98734 -0.950958 -0.623001 -2.05676 -0.950382 -0.627701 -2.12813 -0.947815 -0.631479 -2.19836 -0.943494 -0.636196 -2.28523 -0.950178 -0.63936 -2.34989 -0.935413 -0.64499 -2.4386 -0.937508 -0.649175 -2.51879 -0.9312 -0.655249 -2.61661 -0.934353 -0.660287 -2.71523 -0.934755 -0.665816 -2.80644 -0.926614 -0.671306 -2.91411 -0.926976 -0.6777 -3.02368 -0.923948 -0.68459 -3.14141 -0.923126 -0.691388 -3.26096 -0.918609 -0.699103 -3.39793 -0.920353 -0.705839 -3.51911 -0.908347 -0.71302 -3.64939 -0.897299 -0.721545 -3.8063 -0.895666 -0.731825 -3.98356 -0.897655 -0.742508 -4.1708 -0.898154 -0.754021 -4.37724 -0.900621 -0.765524 -4.58436 -0.896546 -0.77357 -4.71927 -0.856342 -0.784988 -4.92879 -0.840034 -0.796398 -5.13897 -0.816985 -0.809595 -5.3693 -0.79346 -0.824077 -5.62787 -0.771463 -0.841965 -5.94525 -0.757919 -0.860679 -6.28247 -0.7391 -0.882342 -6.67008 -0.721535 -0.907035 -7.10696 -0.702575 -0.934717 -7.59398 -0.679674 -0.965227 -8.15024 -0.654095 -1.00272 -8.80619 -0.62788 -1.04637 -9.59186 -0.600449 -1.09528 -10.4573 -0.557926 -1.15435 -11.5026 -0.509052 -1.22107 -12.6878 -0.439752 -1.29069 -13.9437 -0.336265 -1.31793 -14.4528 -0.130555 -1.33274 -14.7398 0.105803 -1.40793 -16.1097 0.304755 -1.56592 -18.9234 0.513797 -2.4124 -33.9249 0.718482 -2.40984 -33.9655 1.31193 -2.41177 -34.0644 1.9085 -2.77431 -40.5974 2.79252 -4.05302 -63.6518 6.0421 -1.87733 -24.8261 3.40617 -1.86349 -24.6421 3.82387 -1.74754 -22.6195 3.99368 -1.82093 -23.986 4.60188 -1.71175 -22.0783 4.71129 -1.73211 -22.4913 5.18608 -1.6842 -21.6819 5.42875 -1.73358 -22.6347 6.03686 -1.70131 -22.1168 6.32876 -1.36302 -15.9692 5.1452 -1.37281 -16.1838 5.50388 -1.36653 -16.1121 5.78887 -1.36447 -16.1216 6.09984 -1.35732 -16.031 6.3809 -1.34223 -15.8029 6.61341 -1.54817 -19.6867 8.38189 -1.32447 -15.5607 7.14753 -1.32983 -15.7009 7.52203 -1.32585 -15.6761 7.83523 -1.32307 -15.6826 8.16628 -1.58185 -20.62 10.8603 -1.366 -16.5854 9.29041 -1.28714 -15.1453 8.90442 -1.2813 -15.0846 9.21076 -0.777594 -5.4666 4.10281 -0.770863 -5.36845 4.17243 -0.773307 -5.42379 4.33373 -1.29534 -15.5713 10.9432 -1.29596 -15.6285 11.3684 -0.785471 -5.73584 4.95341 -0.725731 -4.58502 4.28029 -0.717601 -4.43938 4.29453 -0.752377 -5.1419 4.95623 -0.752727 -5.16589 5.12011 -0.756539 -5.27077 5.35612 -0.749757 -5.1561 5.41512 -0.735958 -4.89893 5.34543 -0.717242 -4.54991 5.18025 -0.706293 -4.34686 5.13522 -0.693978 -4.13167 5.07028 -0.703748 -4.34692 5.43431 -0.70434 -4.38625 5.63298 -0.729723 -4.93843 6.40212 -0.692483 -4.195 5.75334 -0.709636 -4.5729 6.366 -0.668546 -3.74789 5.55745 -0.657439 -3.52524 5.44218 -0.653454 -3.46563 5.52689 -0.629955 -2.98844 5.04807 -0.623324 -2.86474 5.02633 -0.624137 -2.91955 5.2571 -0.616738 -2.77253 5.19897 -0.63207 -3.1604 5.97223 -0.627015 -3.08433 6.04373 -0.641177 -3.42638 6.82927 -0.61331 -2.82844 6.00914 -0.612757 -2.85923 6.27739 -0.60347 -2.67088 6.14025 -0.599913 -2.62484 6.27559 -0.594581 -2.55484 6.36581 -0.588732 -2.43566 6.355 -0.585439 -2.40606 6.5434 -0.577109 -2.25546 6.45527 -0.570749 -2.14568 6.45654 -0.571433 -2.20371 6.90533 -0.578489 -2.49416 8.05535 -0.570842 -2.35552 8.0504 -0.561243 -2.14854 7.82334 -0.550369 -1.9214 7.49548 -0.542773 -1.77561 7.41228 -0.535698 -1.63908 7.34546 -0.528907 -1.51886 7.3342 -0.522529 -1.41292 7.37931 -0.516001 -1.28485 7.32451 -0.509504 -1.18214 7.3853 -0.503114 -1.07752 7.44439 -0.496962 -0.966443 7.47203 -0.489909 -0.893303 7.78538 -0.484084 -0.722315 7.34279 -0.477837 -0.607475 7.30466 -0.47054 -0.513416 7.51366 -0.463607 -0.408378 7.66135 -0.457448 -0.286776 7.5574 -0.452646 -0.166797 7.34149 -0.447342 -0.0549166 7.12347 -0.556739 -1.82734 -0.955822 -0.558998 -1.88949 -0.952286 -0.560849 -1.95791 -0.954447 -0.562075 -2.02085 -0.947761 -0.563833 -2.09109 -0.946227 -0.566023 -2.15492 -0.936201 -0.568793 -2.24075 -0.944223 -0.569941 -2.32101 -0.943293 -0.572638 -2.39293 -0.933975 -0.574757 -2.47405 -0.928806 -0.576887 -2.57071 -0.933487 -0.57945 -2.66094 -0.929476 -0.581973 -2.75204 -0.922819 -0.585453 -2.85967 -0.924868 -0.587901 -2.96809 -0.923668 -0.591312 -3.07741 -0.919226 -0.594101 -3.19682 -0.916688 -0.597393 -3.32435 -0.915556 -0.601117 -3.44545 -0.905733 -0.604348 -3.5746 -0.896912 -0.609218 -3.74167 -0.902261 -0.612652 -3.90015 -0.898009 -0.618381 -4.08623 -0.90153 -0.623459 -4.28321 -0.903109 -0.629042 -4.4727 -0.894447 -0.632556 -4.61569 -0.861019 -0.637958 -4.82502 -0.848177 -0.6425 -5.01657 -0.821784 -0.648739 -5.24568 -0.80227 -0.656139 -5.50504 -0.784584 -0.663347 -5.78431 -0.764215 -0.671799 -6.0927 -0.742827 -0.680449 -6.43107 -0.718967 -0.692103 -6.86756 -0.708034 -0.704126 -7.31548 -0.684527 -0.71796 -7.8327 -0.660534 -0.734389 -8.43933 -0.636075 -0.753391 -9.13612 -0.606407 -0.774381 -9.93294 -0.568637 -0.797577 -10.8103 -0.514613 -0.827933 -11.9167 -0.458408 -0.861509 -13.2029 -0.382685 -0.879471 -13.9117 -0.212145 -0.88392 -14.1213 0.0177826 -0.900605 -14.8049 0.229447 -0.987874 -18.0528 0.375267 -1.42343 -34.248 1.00757 -1.41804 -34.2531 1.6056 -1.41312 -34.2172 2.20282 -1.40583 -34.1211 2.7963 -1.15438 -25.1535 3.65102 -1.07091 -22.2238 4.13056 -1.07734 -22.6008 4.58696 -1.04438 -21.4424 4.78804 -1.03492 -21.1963 5.12747 -1.07657 -22.9496 5.88578 -1.05027 -22.0627 6.10115 -1.08618 -23.5994 6.89203 -0.99973 -20.2972 6.44617 -0.988133 -19.9495 6.72795 -0.943055 -18.35 6.96964 -0.893213 -16.4381 6.66707 -0.897113 -16.7222 7.0934 -0.900004 -16.9394 7.50975 -0.862544 -15.4888 7.26499 -0.896471 -17.006 8.22613 -0.927928 -18.4853 9.2379 -0.910798 -17.8674 9.33945 -0.891617 -17.1798 9.38703 -0.885529 -17.0576 9.69927 -0.89822 -17.734 10.4371 -0.860155 -16.2286 10.0033 -0.868752 -16.7181 10.6602 -0.616735 -5.61376 4.37793 -0.617567 -5.69779 4.56548 -0.613065 -5.50909 4.58268 -0.608683 -5.38767 4.63913 -0.613959 -5.69253 4.99078 -0.609768 -5.53311 5.02483 -0.60629 -5.41358 5.08467 -0.606801 -5.5233 5.32014 -0.597756 -5.11315 5.14528 -0.591989 -4.90921 5.12449 -0.588603 -4.82218 5.19654 -0.587216 -4.77082 5.30016 -0.594201 -5.21357 5.86692 -0.572941 -4.19337 5.05404 -0.576065 -4.38362 5.38826 -0.575166 -4.43156 5.59357 -0.577019 -4.57538 5.9116 -0.576403 -4.65649 6.17652 -0.571092 -4.44163 6.11364 -0.572549 -4.596 6.48145 -0.562326 -4.12208 6.09451 -0.549473 -3.43549 5.40127 -0.544882 -3.20184 5.25286 -0.540048 -3.02709 5.17053 -0.538114 -2.96539 5.2391 -0.533103 -2.71752 5.03323 -0.549359 -3.91621 7.03417 -0.537772 -3.19003 6.1093 -0.534499 -3.08048 6.12998 -0.535157 -3.27968 6.68513 -0.529194 -2.93353 6.29551 -0.526126 -2.85888 6.38118 -0.52145 -2.61955 6.14509 -0.520112 -2.64833 6.43276 -0.516433 -2.50637 6.37836 -0.516059 -2.66014 6.97855 -0.510878 -2.32541 6.48096 -0.508153 -2.20312 6.45585 -0.50461 -2.09711 6.46539 -0.504653 -2.55193 8.01401 -0.500734 -2.41954 8.02917 -0.497251 -2.32124 8.14632 -0.493702 -1.93345 7.32511 -0.490127 -1.85568 7.4732 -0.486664 -1.70615 7.36937 -0.4833 -1.57596 7.32055 -0.480306 -1.48586 7.43469 -0.477249 -1.34631 7.33254 -0.474583 -1.22053 7.27652 -0.471072 -1.11806 7.3362 -0.466566 -1.051 7.63121 -0.464087 -0.918466 7.5297 -0.45956 -0.82785 7.73334 -0.459477 -0.658764 7.25936 -0.43242 -0.907949 11.3642 -0.451953 -0.454387 7.48798 -0.441696 -0.398953 8.59331 -0.446299 -0.224185 7.36989 -0.445354 -0.109027 7.18281 -0.502722 -1.85912 -0.954536 -0.50299 -1.92112 -0.950392 -0.502311 -1.99772 -0.958639 -0.502026 -2.05315 -0.944099 -0.502732 -2.12429 -0.941812 -0.501979 -2.2026 -0.944168 -0.50218 -2.28187 -0.944481 -0.501874 -2.35366 -0.936147 -0.500989 -2.43466 -0.932162 -0.50112 -2.5156 -0.925884 -0.501204 -2.61307 -0.929308 -0.501249 -2.7114 -0.929885 -0.500257 -2.81053 -0.927612 -0.500696 -2.91891 -0.928 -0.500102 -3.02806 -0.925137 -0.499472 -3.13805 -0.919029 -0.499281 -3.25719 -0.914778 -0.498474 -3.38639 -0.91173 -0.498695 -3.51546 -0.904892 -0.498304 -3.65455 -0.898758 -0.497725 -3.81292 -0.897083 -0.497442 -3.99878 -0.903571 -0.497085 -4.18635 -0.903967 -0.496293 -4.36538 -0.894467 -0.495732 -4.50927 -0.863866 -0.494752 -4.70818 -0.850985 -0.494128 -4.91799 -0.835068 -0.493923 -5.13769 -0.815766 -0.493083 -5.36819 -0.792523 -0.4919 -5.63701 -0.773804 -0.491526 -5.92579 -0.751908 -0.489718 -6.25465 -0.731036 -0.489353 -6.64197 -0.714312 -0.48759 -7.06916 -0.694018 -0.486759 -7.54738 -0.669923 -0.485133 -8.10478 -0.645737 -0.482929 -8.72193 -0.613505 -0.48045 -9.45936 -0.57997 -0.477981 -10.2966 -0.535927 -0.475712 -11.2636 -0.480201 -0.472234 -12.4004 -0.410323 -0.468827 -13.3589 -0.284023 -0.465893 -13.7377 -0.0789627 -0.46379 -14.0546 0.142572 -0.456849 -16.345 0.288159 -0.448328 -19.0139 0.503517 -0.420753 -29.0698 0.746324 -0.41646 -29.0494 1.25338 -0.412278 -28.9609 1.7583 -0.394695 -33.9183 2.48001 -0.388991 -34.0776 3.08331 -0.383416 -34.0857 3.6816 -0.378853 -34.0438 4.27701 -0.414024 -22.3864 3.55129 -0.406734 -23.4587 4.08881 -0.422721 -18.4268 3.75503 -0.418112 -18.849 4.15528 -0.412779 -19.3519 4.58752 -0.409975 -19.3941 4.94665 -0.406548 -19.4976 5.32342 -0.401167 -20.0219 5.80758 -0.411226 -17.3016 5.47565 -0.401172 -18.7822 6.20957 -0.39857 -18.7371 6.5508 -0.395878 -18.6089 6.86792 -0.400629 -17.081 6.71605 -0.398639 -17.0065 7.02318 -0.398097 -16.6178 7.21406 -0.394834 -16.6841 7.57278 -0.388974 -17.2226 8.13454 -0.377028 -18.6549 9.1116 -0.379799 -17.6455 9.04207 -0.376494 -17.6477 9.41767 -0.389597 -15.2514 8.60471 -0.388299 -14.9916 8.80513 -0.387473 -14.8269 9.05126 -0.384252 -14.8592 9.40721 -0.447422 -5.93751 4.5 -0.447497 -5.70488 4.49859 -0.447687 -5.62628 4.58694 -0.446141 -5.63019 4.72872 -0.446387 -5.49821 4.78111 -0.444586 -5.47188 4.90548 -0.44283 -5.62059 5.16091 -0.441915 -5.49144 5.21574 -0.445171 -5.04133 5.01219 -0.445658 -4.88602 5.02959 -0.444849 -4.85979 5.15316 -0.443945 -4.76426 5.21746 -0.43256 -5.81861 6.33345 -0.443869 -4.54189 5.31237 -0.447107 -4.10253 5.03355 -0.446403 -4.07378 5.14738 -0.442694 -4.26202 5.49337 -0.441574 -4.27825 5.6703 -0.439907 -4.34155 5.90891 -0.440784 -4.08589 5.78621 -0.429548 -4.89278 6.9369 -0.447881 -3.30696 5.15907 -0.444401 -3.49563 5.55724 -0.445631 -3.30269 5.46485 -0.451017 -2.86382 5.01713 -0.451527 -2.7371 4.98407 -0.450432 -2.6777 5.04784 -0.430684 -3.85967 7.05886 -0.430565 -3.78922 7.18496 -0.431647 -3.6003 7.1123 -0.438166 -3.09394 6.46931 -0.431991 -3.29362 7.0672 -0.440171 -2.74831 6.28121 -0.439948 -2.65669 6.32838 -0.439833 -2.56315 6.37394 -0.438886 -2.52651 6.54517 -0.438159 -2.46607 6.67096 -0.439712 -2.27801 6.50062 -0.439727 -2.18179 6.53954 -0.435579 -2.25724 7.03569 -0.423559 -2.59212 8.3184 -0.424269 -2.42611 8.24866 -0.433876 -1.99496 7.3267 -0.432244 -1.91826 7.47563 -0.432664 -1.79521 7.46958 -0.433336 -1.66623 7.44182 -0.434018 -1.53533 7.39213 -0.434559 -1.40656 7.33984 -0.436209 -1.27342 7.25559 -0.43583 -1.16653 7.28669 -0.435368 -1.06328 7.3456 -0.43425 -0.985867 7.59052 -0.432638 -0.89841 7.81492 -0.435859 -0.726954 7.37254 -0.437709 -0.607552 7.29467 -0.435446 -0.512283 7.49376 -0.435429 -0.405628 7.60156 -0.437105 -0.282961 7.44774 -0.436937 -0.170417 7.45162 -0.440296 -0.0554849 7.12365 -0.449564 -1.82691 -0.9564 -0.447349 -1.89618 -0.960189 -0.446108 -1.95066 -0.947992 -0.443379 -2.0281 -0.955381 -0.441624 -2.09077 -0.946982 -0.438866 -2.16901 -0.950327 -0.436541 -2.24082 -0.944979 -0.434231 -2.31254 -0.937734 -0.431401 -2.39247 -0.934887 -0.429526 -2.47335 -0.929798 -0.426139 -2.56236 -0.928504 -0.422647 -2.66886 -0.936362 -0.419649 -2.76793 -0.935377 -0.416613 -2.86786 -0.931546 -0.4136 -2.96765 -0.924819 -0.409962 -3.07755 -0.920494 -0.405765 -3.19653 -0.917921 -0.402008 -3.32465 -0.916906 -0.397806 -3.44428 -0.907192 -0.393928 -3.57501 -0.898438 -0.388876 -3.74048 -0.903888 -0.382685 -3.90863 -0.904091 -0.377374 -4.09504 -0.907509 -0.371148 -4.26465 -0.896826 -0.367054 -4.41669 -0.872907 -0.360637 -4.6062 -0.859243 -0.353633 -4.80559 -0.843187 -0.346986 -5.01588 -0.823995 -0.339187 -5.24515 -0.804663 -0.331186 -5.4944 -0.783947 -0.321791 -5.78287 -0.766802 -0.312153 -6.09218 -0.745626 -0.300583 -6.44966 -0.727177 -0.28817 -6.83794 -0.703903 -0.272987 -7.30454 -0.685672 -0.256375 -7.81182 -0.660025 -0.237925 -8.39912 -0.632336 -0.216051 -9.07628 -0.600306 -0.191409 -9.83299 -0.55764 -0.163734 -10.6902 -0.503003 -0.129878 -11.7162 -0.439631 -0.0936458 -12.833 -0.350251 -0.0762707 -13.3324 -0.168088 -0.0648871 -13.62 0.0459742 -0.031417 -14.6329 0.231154 --0.0716234 -17.8304 0.374192 --0.592798 -34.0238 0.990616 --0.606688 -34.2681 1.58885 --0.612224 -34.2922 2.18852 --0.614517 -34.1963 2.78337 --0.760875 -38.3549 4.34585 --0.487067 -29.8412 4.12999 --0.261523 -22.8577 3.80273 --0.1064 -18.0646 3.53676 --0.122399 -18.4419 3.91887 --0.115444 -18.1516 4.19882 --0.12133 -18.2604 4.54773 --0.125682 -18.2934 4.8867 --0.0927332 -17.2287 4.97653 --0.0851059 -16.9243 5.21873 --0.0985008 -17.2437 5.6196 --0.0953347 -17.0648 5.89244 --0.102386 -17.177 6.25094 --0.0832558 -16.5411 6.37425 --0.0910835 -16.7006 6.74999 --0.107031 -17.0669 7.21156 --0.0988037 -16.7506 7.42985 --0.116476 -17.1826 7.94221 --0.182942 -18.9456 9.04138 --0.188964 -19.0301 9.4725 --0.198791 -19.215 9.95975 --0.0554235 -15.1205 8.37561 --0.0526784 -14.9805 8.63394 --0.0444904 -14.6776 8.80523 --0.0648124 -15.1602 9.40431 --0.0654837 -15.0975 9.71772 -0.273816 -5.86161 4.52457 -0.279902 -5.66353 4.54173 -0.276903 -5.71013 4.71085 -0.280659 -5.56952 4.75958 -0.282124 -5.50362 4.85636 -0.282384 -5.45891 4.9694 -0.272274 -5.6843 5.28673 -0.281147 -5.4359 5.24993 -0.301882 -4.87136 4.948 -0.30132 -4.84047 5.06453 -0.306321 -4.69341 5.0829 -0.305556 -4.66628 5.20433 -0.309105 -4.56253 5.25787 -0.32247 -4.19338 5.05231 -0.306528 -4.54594 5.54894 -0.32269 -4.12516 5.27523 -0.320305 -4.14549 5.44896 -0.31897 -4.14746 5.60987 -0.316064 -4.17849 5.80986 -0.324619 -3.94644 5.70598 -0.342892 -3.48018 5.30027 -0.347117 -3.34294 5.28168 -0.348314 -3.29805 5.37929 -0.347132 -3.27911 5.51704 -0.355851 -3.05728 5.3689 -0.342253 -3.32727 5.93546 -0.350169 -3.1204 5.80839 -0.319619 -3.73545 6.98125 -0.323614 -3.60523 7.00275 -0.327587 -3.47515 7.02147 -0.330543 -3.38379 7.10747 -0.341489 -3.09829 6.83023 -0.369342 -2.47866 5.86793 -0.367018 -2.48611 6.0992 -0.358446 -2.62015 6.62209 -0.37109 -2.33104 6.23773 -0.370382 -2.30976 6.44335 -0.371828 -2.22527 6.51057 -0.375844 -2.10804 6.49267 -0.344629 -2.6309 8.22911 -0.373983 -2.04203 6.93159 -0.369839 -2.06131 7.34668 -0.374761 -1.92725 7.30531 -0.376389 -1.84473 7.43411 -0.381214 -1.71189 7.3881 -0.384221 -1.59777 7.4073 -0.386599 -1.49939 7.49276 -0.393094 -1.34626 7.3321 -0.397372 -1.22242 7.28594 -0.399764 -1.12334 7.36545 -0.402368 -1.01982 7.43344 -0.403754 -0.926928 7.58896 -0.405295 -0.83618 7.80267 -0.415392 -0.659623 7.26927 -0.41989 -0.454454 7.48804 -0.411665 -0.400158 8.61333 -0.415925 -0.270773 8.69925 -0.434314 -0.109354 7.18302 -0.393731 -1.85558 -0.955253 -0.389526 -1.92468 -0.958234 -0.385815 -1.98636 -0.952372 -0.381576 -2.05629 -0.951807 -0.377292 -2.12712 -0.949396 -0.373023 -2.19787 -0.945086 -0.368173 -2.27783 -0.945326 -0.362341 -2.35763 -0.943463 -0.357524 -2.43738 -0.939408 -0.352132 -2.52631 -0.939103 -0.346699 -2.61612 -0.936351 -0.340225 -2.72237 -0.942696 -0.334184 -2.82218 -0.940149 -0.328694 -2.91359 -0.929208 -0.321583 -3.03065 -0.931813 -0.314493 -3.13196 -0.920374 -0.307838 -3.24244 -0.91109 -0.300042 -3.37122 -0.908308 -0.292215 -3.50082 -0.901681 -0.282318 -3.64761 -0.900401 -0.271073 -3.83208 -0.912278 -0.260851 -4.00084 -0.909615 -0.25067 -4.16935 -0.901759 -0.241144 -4.31196 -0.876458 -0.229771 -4.50033 -0.866015 -0.218325 -4.6904 -0.84948 -0.20415 -4.90861 -0.837349 -0.191539 -5.11838 -0.814832 -0.175519 -5.36735 -0.798273 -0.159933 -5.62613 -0.776529 -0.140334 -5.93408 -0.760348 -0.120754 -6.24254 -0.73413 -0.0973692 -6.62949 -0.717544 -0.0705891 -7.05618 -0.697477 -0.0395615 -7.55287 -0.678044 -0.00736211 -8.0699 -0.645788 --0.0320232 -8.70508 -0.617885 --0.0756916 -9.41171 -0.579731 --0.125727 -10.2077 -0.53073 --0.182945 -11.123 -0.470203 --0.250984 -12.2177 -0.398479 --0.293819 -12.8867 -0.247339 --0.312715 -13.1653 -0.0424713 --0.359888 -13.9085 0.142789 --0.447235 -15.2975 0.324936 --0.709377 -19.5169 0.479172 --1.62319 -34.2039 1.28012 --1.63855 -34.3737 1.88271 --1.64174 -34.3428 2.48316 --1.64895 -34.3616 3.08649 --1.65867 -34.4391 3.69622 --1.66332 -34.4158 4.30086 --1.66636 -34.3826 4.9055 --0.667907 -18.4266 3.42209 --0.675144 -18.4907 3.76011 --0.712218 -19.0203 4.18 --1.32361 -28.6288 6.30038 --0.580003 -16.8435 4.42588 --0.583422 -16.8589 4.73715 --0.588817 -16.9078 5.05929 --0.585211 -16.8055 5.3468 --0.596581 -16.9388 5.69866 --0.550191 -16.1647 5.79014 --0.564942 -16.3552 6.15915 --0.587394 -16.6601 6.5773 --0.572417 -16.3819 6.80452 --0.597557 -16.7172 7.25442 --0.716628 -18.5001 8.2921 --0.774424 -19.3296 9.01183 --0.745806 -18.8396 9.1974 --0.754062 -18.9112 9.625 --0.740896 -18.6505 9.90285 --0.559806 -15.8656 8.9176 --0.531911 -15.3977 9.02326 --0.539221 -15.4665 9.40577 --0.539869 -15.4211 9.73395 --0.503864 -14.8455 9.75395 --0.499172 -14.7247 10.0331 --0.658172 -17.0317 11.8618 -0.10729 -5.66941 4.75904 -0.113149 -5.56196 4.82931 -0.148648 -5.02331 4.58962 -0.150039 -4.97534 4.68877 -0.152047 -4.93416 4.79347 -0.155482 -4.86793 4.8792 -0.153683 -4.87653 5.02732 -0.160388 -4.75261 5.06653 -0.161193 -4.73323 5.19534 -0.161988 -4.69644 5.31127 -0.171859 -4.53359 5.3102 -0.17844 -4.42917 5.36079 -0.201669 -4.07945 5.1597 -0.204675 -4.02024 5.24488 -0.195831 -4.12109 5.50612 -0.199942 -4.04257 5.57762 -0.204162 -3.96212 5.64763 -0.222844 -3.69046 5.48485 -0.246871 -3.3377 5.20451 -0.242669 -3.37364 5.40506 -0.247974 -3.29022 5.45529 -0.230398 -3.50188 5.91908 -0.238295 -3.37122 5.9137 -0.248954 -3.20726 5.8552 -0.255191 -3.10684 5.88537 -0.256457 -3.06276 6.00714 -0.257669 -3.02026 6.13741 -0.22122 -3.47155 7.14648 -0.268614 -2.83014 6.2224 -0.278189 -2.68412 6.16479 -0.28435 -2.58479 6.19301 -0.280667 -2.60127 6.46308 -0.277083 -2.61775 6.75337 -0.276662 -2.59282 6.97242 -0.291085 -2.38874 6.77676 -0.306549 -2.18135 6.54798 -0.288249 -2.36493 7.3344 -0.310913 -2.06748 6.84713 -0.310054 -2.03527 7.09106 -0.312943 -1.9674 7.2496 -0.316072 -1.89555 7.40775 -0.325171 -1.75685 7.34359 -0.330592 -1.65648 7.41221 -0.33561 -1.56732 7.53735 -0.347635 -1.40182 7.32958 -0.360947 -1.22338 7.02004 -0.374558 -1.0562 6.70635 -0.367045 -1.07128 7.40441 -0.372742 -0.965463 7.46184 -0.374818 -0.88885 7.75523 -0.389957 -0.719118 7.31284 -0.397771 -0.602099 7.25486 -0.40043 -0.510665 7.48374 -0.407372 -0.400885 7.54167 -0.416047 -0.281674 7.42782 -0.421905 -0.170501 7.45185 -0.432197 -0.0544637 7.09393 -0.342752 -1.8205 -0.957175 -0.336544 -1.88952 -0.960945 -0.331309 -1.94377 -0.948828 -0.325067 -2.01363 -0.949252 -0.318839 -2.0834 -0.947879 -0.313042 -2.14675 -0.937913 -0.304772 -2.23291 -0.945932 -0.297993 -2.3117 -0.945212 -0.290647 -2.38403 -0.935995 -0.283248 -2.4729 -0.937078 -0.274871 -2.5616 -0.93566 -0.266453 -2.65117 -0.931695 -0.256934 -2.75817 -0.936677 -0.247909 -2.85773 -0.932817 -0.238906 -2.95717 -0.926161 -0.22828 -3.06665 -0.921901 -0.219204 -3.16778 -0.909153 -0.206934 -3.30367 -0.913496 -0.195683 -3.42388 -0.903898 -0.183356 -3.56137 -0.900152 -0.16768 -3.73646 -0.910252 -0.152566 -3.90306 -0.910361 -0.137373 -4.07141 -0.905277 -0.125049 -4.19451 -0.874403 -0.107662 -4.38268 -0.867227 -0.0912593 -4.57162 -0.854013 -0.0722734 -4.7703 -0.838398 -0.0537041 -4.9789 -0.819696 -0.0312964 -5.2175 -0.803996 -0.00774933 -5.47501 -0.786757 --0.01642 -5.74324 -0.763881 --0.0455946 -6.06056 -0.745963 --0.0775034 -6.40667 -0.725308 --0.112879 -6.79359 -0.702621 --0.155453 -7.24943 -0.682701 --0.201019 -7.75499 -0.657811 --0.25093 -8.29994 -0.623344 --0.312744 -8.97476 -0.592916 --0.380082 -9.70876 -0.548726 --0.455832 -10.5329 -0.491932 --0.544967 -11.4961 -0.423797 --0.623333 -12.3514 -0.310785 --0.654137 -12.66 -0.119666 --0.684904 -12.9853 0.0803777 --0.791764 -14.1331 0.24723 --1.09089 -17.4076 0.377375 --2.18464 -29.3293 0.976241 --2.23406 -29.823 1.49839 --2.22583 -29.6795 2.01643 --2.19691 -29.3093 2.51846 --2.25469 -29.8941 3.07449 --2.24886 -29.7735 3.59117 --2.2431 -29.6541 4.1053 --2.23922 -29.5656 4.62086 --1.43356 -20.8001 3.91947 --1.4198 -20.6174 4.26332 --1.11335 -17.2814 4.04729 --1.09167 -17.011 4.30798 --1.09406 -17.0095 4.61801 --1.12889 -17.3511 5.00962 --1.07815 -16.7766 5.18786 --1.06265 -16.5751 5.44768 --1.02115 -16.1034 5.62493 --1.08088 -16.7152 6.11922 --1.06308 -16.4913 6.3683 --1.07227 -16.5549 6.71172 --1.06781 -16.4723 7.0078 --1.1565 -17.3782 7.68528 --2.26042 -28.9677 12.7272 --1.2657 -18.4641 8.85555 --1.29355 -18.7156 9.35252 --1.05267 -16.149 8.54913 --1.03908 -15.9793 8.81362 --1.00228 -15.5654 8.952 --0.982794 -15.3279 9.17217 --0.990328 -15.3664 9.54127 --0.998865 -15.4228 9.92918 --1.04152 -15.8284 10.5375 --2.28932 -28.6591 18.956 --0.0294071 -5.33444 4.61161 --0.0188442 -5.2141 4.66448 --0.00543173 -5.06114 4.69081 -0.00232878 -4.97187 4.76086 -0.0175542 -4.80395 4.76751 -0.0211009 -4.75325 4.86381 -0.0215933 -4.73893 4.99146 -0.0235731 -4.69855 5.1002 -0.0235711 -4.69352 5.24203 -0.014329 -4.7644 5.45995 -0.0284567 -4.61513 5.47343 -0.0350018 -4.52965 5.54668 -0.0645763 -4.22799 5.39536 -0.044302 -4.40896 5.74653 -0.0742288 -4.09951 5.5707 -0.0821224 -4.00693 5.62686 -0.0942412 -3.87385 5.63515 -0.105851 -3.74953 5.64807 -0.0911234 -3.86995 5.9729 -0.0819666 -3.94465 6.25548 -0.107005 -3.68357 6.08947 -0.132916 -3.42333 5.90768 -0.150772 -3.23728 5.8179 -0.164625 -3.08786 5.77341 -0.171655 -3.00999 5.83531 -0.17391 -2.96603 5.95588 -0.164054 -3.03943 6.28417 -0.18718 -2.80705 6.08314 -0.190673 -2.75979 6.21105 -0.198205 -2.67319 6.26751 -0.197029 -2.65981 6.47532 -0.191461 -2.69543 6.80202 -0.192387 -2.66342 7.00369 -0.191602 -2.64759 7.26114 -0.227874 -2.30335 6.7228 -0.210326 -2.42865 7.35026 -0.229106 -2.23628 7.16645 -0.250033 -2.03813 6.94018 -0.25158 -1.99851 7.17462 -0.256693 -1.92623 7.32351 -0.268522 -1.79372 7.27957 -0.279512 -1.67948 7.29079 -0.274645 -1.68324 7.77531 -0.290536 -1.52498 7.62844 -0.311939 -1.32268 7.24357 -0.340399 -1.08052 6.57885 -0.346932 -0.996351 6.66598 -0.341059 -0.996928 7.31465 -0.34962 -0.893349 7.37087 -0.351305 -0.835957 7.8223 -0.372426 -0.658548 7.27906 -0.389907 -0.45163 7.46801 -0.400654 -0.337048 7.42515 -0.407178 -0.233529 7.67994 -0.422471 -0.109651 7.22327 -0.286583 -1.83876 -0.948827 -0.277386 -1.90757 -0.951983 -0.270678 -1.96907 -0.946306 -0.261448 -2.0387 -0.945817 -0.252753 -2.11564 -0.95038 -0.24449 -2.18615 -0.946151 -0.235184 -2.2575 -0.93997 -0.224884 -2.34437 -0.944633 -0.21555 -2.41652 -0.934308 -0.204632 -2.51346 -0.940374 -0.19474 -2.59468 -0.931702 -0.181277 -2.70051 -0.938212 -0.170834 -2.79076 -0.930193 -0.158824 -2.89009 -0.92512 -0.145251 -2.99847 -0.922493 -0.133227 -3.09851 -0.911477 -0.119057 -3.21682 -0.907657 -0.103334 -3.34414 -0.905185 -0.0869974 -3.48149 -0.903516 -0.0690537 -3.6288 -0.902248 -0.0474084 -3.80339 -0.909722 -0.0251664 -3.98793 -0.916002 -0.0114073 -4.10182 -0.883166 --0.0103554 -4.27963 -0.874762 --0.0321342 -4.45817 -0.860715 --0.0539284 -4.63743 -0.840926 --0.0800874 -4.85494 -0.829436 --0.10725 -5.07305 -0.8109 --0.135557 -5.31011 -0.791524 --0.168687 -5.57704 -0.773448 --0.204631 -5.87386 -0.754981 --0.240558 -6.1712 -0.726677 --0.286223 -6.5457 -0.708625 --0.336342 -6.96088 -0.687137 --0.3934 -7.42464 -0.662509 --0.45768 -7.95808 -0.636102 --0.531772 -8.571 -0.606116 --0.612227 -9.22394 -0.561698 --0.705908 -9.99622 -0.512516 --0.807071 -10.8273 -0.444767 --0.934454 -11.8763 -0.373219 --0.981553 -12.254 -0.199205 --1.00977 -12.4711 0.000412651 --1.08973 -13.1103 0.180521 --1.37729 -15.4831 0.304233 --1.72593 -18.3402 0.497771 --2.96201 -28.5309 0.71787 --2.9786 -28.6303 1.2202 --2.9991 -28.7615 1.72692 --2.99993 -28.7333 2.23197 --2.99588 -28.6575 2.73384 --3.02627 -28.8705 3.25677 --3.02671 -28.8363 3.76482 --3.0282 -28.8029 4.27363 --3.02663 -28.7518 4.78083 --2.01496 -20.4532 4.0575 --1.97678 -20.1131 4.36919 --3.03275 -28.68 6.32216 --3.0329 -28.6414 6.83751 --1.974 -20.0057 5.44643 --1.59437 -16.9037 5.07071 --1.62465 -17.1191 5.44208 --1.93251 -19.5843 6.44997 --1.94133 -19.6288 6.8359 --1.68036 -17.4987 6.53929 --1.67605 -17.437 6.85873 --1.55366 -16.4251 6.8419 --1.67747 -17.3994 7.53463 --1.6883 -17.4594 7.90912 --1.61581 -16.8508 8.01292 --1.61723 -16.8357 8.35581 --1.69775 -17.4552 8.99403 --1.60298 -16.6686 8.99069 --1.55541 -16.2604 9.14909 --2.01212 -19.859 11.3914 --3.11133 -28.5409 16.5756 --3.0737 -28.1886 17.031 --3.13976 -28.6139 18.628 --0.315588 -6.33991 5.06374 --0.209428 -5.4986 4.66234 --0.175828 -5.22129 4.61151 --0.166162 -5.13395 4.68544 --0.154954 -5.03707 4.75138 --0.153186 -5.01796 4.87588 --0.128731 -4.811 4.85171 --0.116461 -4.71254 4.91035 --0.147574 -4.93878 5.24561 --0.118402 -4.70075 5.18623 --0.115981 -4.67074 5.30879 --0.106613 -4.58837 5.38337 --0.092174 -4.469 5.42145 --0.0880382 -4.4265 5.53507 --0.0644212 -4.2316 5.48917 --0.0347189 -3.99841 5.39347 --0.0250214 -3.90901 5.44828 --0.053577 -4.11503 5.85061 --0.00990895 -3.77169 5.60622 -0.00734083 -3.63555 5.6015 --0.0318558 -3.91178 6.13242 --0.0325514 -3.9048 6.3129 --0.0251251 -3.84068 6.42153 --0.030111 -3.85899 6.65295 --0.0368449 -3.89249 6.91998 -0.05619 -3.19688 6.05225 -0.0852105 -2.96856 5.87771 -0.0831085 -2.96965 6.07562 -0.0907222 -2.90063 6.16189 -0.100211 -2.81502 6.22098 -0.126853 -2.60955 6.04818 -0.132557 -2.55796 6.16495 -0.089274 -2.84379 7.00295 -0.0923339 -2.8098 7.20671 -0.0904565 -2.79637 7.47519 -0.101586 -2.70309 7.56965 -0.164299 -2.24639 6.74213 -0.145572 -2.35591 7.34259 -0.183261 -2.07962 6.91211 -0.184461 -2.04651 7.15638 -0.191515 -1.97533 7.30591 -0.20262 -1.8822 7.39727 -0.218222 -1.75502 7.37168 -0.225689 -1.67753 7.52751 -0.231688 -1.61471 7.76998 -0.240868 -1.52536 7.92432 -0.296459 -1.15533 6.71584 -0.31226 -1.0363 6.62726 -0.314732 -0.987811 6.94055 -0.310582 -0.973364 7.55043 -0.332506 -0.819608 7.25935 -0.342964 -0.722361 7.37224 -0.358841 -0.599753 7.25476 -0.366513 -0.514696 7.5634 -0.381353 -0.394755 7.47179 -0.395236 -0.281953 7.47776 -0.409008 -0.169224 7.4619 -0.426228 -0.054602 7.1041 -0.279209 -1.52869 -0.975412 -0.227641 -1.86858 -0.954607 -0.215974 -1.94457 -0.963899 -0.207697 -1.99957 -0.95022 -0.197476 -2.06909 -0.948827 -0.187209 -2.13953 -0.945587 -0.175483 -2.21713 -0.947089 -0.162715 -2.29556 -0.946341 -0.150902 -2.37495 -0.94345 -0.140578 -2.44699 -0.932121 -0.127208 -2.53539 -0.930878 -0.110799 -2.64012 -0.938921 -0.0973494 -2.73026 -0.932385 -0.0823942 -2.82848 -0.928745 -0.0674008 -2.92756 -0.922259 -0.0507843 -3.03668 -0.91817 -0.0351919 -3.14571 -0.910789 -0.0186265 -3.25452 -0.900208 --0.00324206 -3.39992 -0.905711 --0.0250752 -3.5451 -0.906718 --0.0501523 -3.71036 -0.912221 --0.0788646 -3.90188 -0.925717 --0.093477 -3.99734 -0.88627 --0.120193 -4.174 -0.880787 --0.144775 -4.33307 -0.861868 --0.171525 -4.51118 -0.845299 --0.204639 -4.72745 -0.83742 --0.234556 -4.92517 -0.815658 --0.269884 -5.16201 -0.800443 --0.309345 -5.41759 -0.783675 --0.350995 -5.69295 -0.764215 --0.396454 -5.99814 -0.743962 --0.449328 -6.343 -0.723703 --0.505923 -6.71652 -0.699205 --0.572773 -7.15978 -0.677808 --0.644368 -7.63242 -0.647623 --0.729911 -8.20266 -0.620543 --0.821273 -8.80393 -0.578878 --0.931371 -9.53245 -0.537122 --1.05108 -10.3217 -0.478489 --1.19267 -11.2577 -0.410977 --1.2831 -11.8513 -0.273579 --1.33397 -12.1762 -0.0918144 --1.36421 -12.3609 0.111135 --1.686 -14.4869 0.213985 --2.02727 -16.7417 0.38689 --3.43352 -26.0626 0.503134 --3.54099 -26.7485 0.961995 --3.68493 -27.6746 1.44906 --3.88267 -28.9463 1.98065 --3.87848 -28.8852 2.48935 --3.89942 -28.9916 3.00847 --3.90872 -29.0215 3.52586 --3.91102 -29.0019 4.04075 --3.91502 -28.994 4.55823 --3.92751 -29.0443 5.08595 --3.93948 -29.0865 5.61667 --3.94884 -29.1187 6.14998 --3.97022 -29.2184 6.70102 --2.49925 -19.559 5.17732 --2.40089 -18.8956 5.38566 --2.42186 -19.0078 5.7666 --2.46084 -19.2384 6.18634 --3.99707 -29.2209 9.43062 --3.99871 -29.1934 9.98307 --3.99925 -29.1647 10.5402 --4.00384 -29.1543 11.1088 --4.00728 -29.1416 11.6833 --4.00908 -29.1189 12.2605 --2.22407 -17.5408 8.14252 --2.19198 -17.3139 8.40836 --2.17405 -17.1747 8.70896 --4.01697 -29.0116 14.6376 --4.01685 -28.9763 15.2485 --4.0144 -28.9192 15.8576 --4.01675 -28.8936 16.4924 --3.99174 -28.6904 17.0391 --3.9127 -28.1422 17.3888 --4.03518 -28.8809 18.5049 --0.548261 -6.61725 5.17501 --0.457674 -6.03082 4.95446 --0.354968 -5.37062 4.6587 --0.327656 -5.18528 4.6672 --0.312004 -5.08086 4.72894 --0.309853 -5.05502 4.8481 --0.295605 -4.9574 4.91228 --0.295521 -4.9506 5.04951 --0.294815 -4.93308 5.18131 --0.294728 -4.92688 5.32668 --0.261438 -4.70453 5.27956 --0.241239 -4.57196 5.30753 --0.245466 -4.58934 5.47783 --0.207936 -4.34326 5.38875 --0.180186 -4.16395 5.35709 --0.159847 -4.0274 5.36435 --0.150242 -3.95792 5.44226 --0.104405 -3.66666 5.26279 --0.110168 -3.69417 5.44941 --0.160928 -3.99644 5.9874 --0.147997 -3.90387 6.04944 --0.166635 -4.00606 6.3729 --0.150685 -3.89542 6.4187 --0.151238 -3.88693 6.60952 --0.130879 -3.75025 6.61937 --0.0193874 -3.0658 5.77167 --0.00117997 -2.94682 5.76589 --0.00341102 -2.94996 5.9628 -0.00777931 -2.86941 6.02293 -0.0373378 -2.68581 5.89814 --0.0795649 -3.36299 7.39162 --0.0479365 -3.16219 7.27208 --0.00759135 -2.90622 7.02179 -0.0106636 -2.78881 7.04512 -0.00544448 -2.80105 7.35825 -0.0170519 -2.7179 7.47132 -0.0455189 -2.53544 7.34238 -0.0955927 -2.23427 6.88255 -0.0837616 -2.28491 7.3438 -0.122516 -2.04879 7.0147 -0.108743 -2.10395 7.54437 -0.113927 -2.05491 7.79103 -0.152252 -1.82272 7.42288 -0.17326 -1.68579 7.35762 -0.172444 -1.66451 7.74536 -0.184609 -1.57478 7.89074 -0.248862 -1.22035 6.80301 -0.267641 -1.10347 6.73544 -0.285327 -0.987116 6.6558 -0.27718 -0.996145 7.35377 -0.29731 -0.871531 7.26168 -0.305289 -0.795816 7.54415 -0.329667 -0.652452 7.26899 -0.307626 -0.691002 8.97286 -0.359006 -0.44825 7.45807 -0.372164 -0.345495 7.64486 -0.390888 -0.228959 7.5702 -0.411626 -0.110014 7.26343 -0.231144 -1.53986 -1.03676 -0.230187 -1.54452 -0.970043 -0.177898 -1.82959 -0.956932 -0.165767 -1.89721 -0.960023 -0.15359 -1.96575 -0.961266 -0.143322 -2.02059 -0.946878 -0.129636 -2.09722 -0.951416 -0.116382 -2.16743 -0.947163 -0.102667 -2.24486 -0.947657 -0.0878516 -2.32411 -0.94575 -0.0755826 -2.39509 -0.93556 -0.0592081 -2.48337 -0.9356 -0.0428541 -2.57153 -0.933044 -0.0259892 -2.66784 -0.933787 -0.00802691 -2.76596 -0.93173 --0.00991253 -2.86393 -0.926777 --0.0294751 -2.97195 -0.924221 --0.0474878 -3.07163 -0.913176 --0.067061 -3.18034 -0.904278 --0.0912959 -3.31542 -0.906964 --0.119659 -3.46858 -0.915038 --0.147045 -3.62255 -0.918173 --0.177091 -3.78738 -0.920855 --0.197751 -3.89907 -0.892478 --0.227842 -4.06542 -0.885472 --0.256377 -4.22338 -0.869279 --0.292227 -4.41852 -0.863317 --0.323369 -4.587 -0.839978 --0.364017 -4.81186 -0.832319 --0.403098 -5.02825 -0.813873 --0.449518 -5.2826 -0.801115 --0.494363 -5.52844 -0.776773 --0.549721 -5.83127 -0.761463 --0.606685 -6.14466 -0.738513 --0.674247 -6.51682 -0.720203 --0.743393 -6.89939 -0.691456 --0.828844 -7.36858 -0.66934 --0.921706 -7.87804 -0.639081 --1.02676 -8.45675 -0.604123 --1.14815 -9.12349 -0.564111 --1.28166 -9.85908 -0.511411 --1.4389 -10.7222 -0.450258 --1.58379 -11.517 -0.350907 --1.6251 -11.734 -0.166008 --1.67262 -11.9876 0.0229384 --1.79676 -12.6607 0.193547 --2.26512 -15.2381 0.299297 --3.86725 -24.0806 0.317393 --4.01232 -24.8545 0.736216 --4.8465 -29.4299 1.2087 --4.88379 -29.6081 1.73529 --4.88452 -29.5801 2.25987 --4.86319 -29.4353 2.77724 --4.91209 -29.6742 3.32052 --4.91458 -29.6589 3.84934 --4.91387 -29.6237 4.37716 --4.91221 -29.5896 4.90602 --4.91578 -29.576 5.43914 --4.91993 -29.5722 5.97615 --4.91929 -29.5387 6.51076 --2.98931 -18.9768 4.89137 --2.96424 -18.8202 5.20818 --4.92734 -29.4894 8.14192 --4.92672 -29.4573 8.68892 --4.93012 -29.4425 9.24491 --4.93248 -29.4276 9.80559 --4.93422 -29.4026 10.3683 --4.93334 -29.3677 10.9328 --4.93949 -29.3675 11.5155 --4.93834 -29.329 12.0908 --4.93861 -29.298 12.6752 --4.94488 -29.3017 13.2811 --4.94328 -29.2573 13.8747 --4.94908 -29.2543 14.4952 --4.94759 -29.213 15.1067 --4.9473 -29.1761 15.7298 --4.93122 -29.0576 16.3191 --0.519722 -5.40554 3.97647 --0.531065 -5.45637 4.13094 --0.512324 -5.35092 4.1969 --0.678331 -6.22633 4.86958 --0.649448 -6.06806 4.92065 --0.627418 -5.94161 4.98916 --0.605412 -5.81532 5.05457 --0.498671 -5.23997 4.79229 --0.548748 -5.49814 5.12806 --0.547043 -5.48129 5.26759 --0.576763 -5.63027 5.54428 --0.465185 -5.03561 5.21212 --0.453255 -4.96171 5.30091 --0.434614 -4.8575 5.36193 --0.411331 -4.72393 5.39363 --0.377255 -4.5404 5.37383 --0.351358 -4.39502 5.38391 --0.301961 -4.13288 5.26902 --0.274528 -3.97675 5.25493 --0.261749 -3.90384 5.32494 --0.260071 -3.88717 5.46087 --0.227741 -3.71383 5.41546 --0.22317 -3.68111 5.53467 --0.292531 -4.03176 6.14637 --0.302977 -4.07514 6.39158 --0.303342 -4.06299 6.57552 --0.26266 -3.84669 6.47616 --0.275661 -3.90276 6.76587 --0.259558 -3.80864 6.84272 --0.139568 -3.18949 6.08417 --0.204139 -3.50295 6.80435 --0.101431 -2.97767 6.13414 --0.0898187 -2.90886 6.22118 --0.160178 -3.24563 7.07091 --0.173923 -3.3044 7.44676 --0.12672 -3.05276 7.21846 --0.0867827 -2.8436 7.05539 --0.0746597 -2.76849 7.16875 --0.0996338 -2.87801 7.7211 --0.0308678 -2.52791 7.19894 -0.0152858 -2.28778 6.89903 -0.000107975 -2.34479 7.36942 -0.0265038 -2.20258 7.31607 -0.024549 -2.19709 7.66705 -0.0449022 -2.07855 7.69561 -0.0837806 -1.87971 7.44424 -0.090082 -1.82938 7.69834 -0.113694 -1.70377 7.69118 -0.120353 -1.65058 7.98298 -0.205716 -1.24726 6.71356 -0.221509 -1.15694 6.77418 -0.245446 -1.03434 6.66624 -0.241745 -1.02338 7.2064 -0.255746 -0.937256 7.36226 -0.278861 -0.812882 7.26896 -0.280321 -0.77119 7.86874 -0.332752 -0.504084 7.49356 -0.352574 -0.39506 7.53171 -0.372485 -0.283625 7.55792 -0.394133 -0.168327 7.4821 -0.419127 -0.0536412 7.07437 -0.191397 -1.50697 -0.968177 -0.117141 -1.8563 -0.96275 -0.104498 -1.91648 -0.957893 -0.0907506 -1.97851 -0.951233 -0.0765967 -2.0468 -0.94997 -0.0613993 -2.11594 -0.946755 -0.0442054 -2.20056 -0.954879 -0.0289191 -2.2715 -0.94757 -0.013647 -2.34234 -0.938463 --0.00314043 -2.42132 -0.933451 --0.0229718 -2.51666 -0.938324 --0.0397833 -2.59641 -0.928667 --0.0622203 -2.70164 -0.933935 --0.0846321 -2.80671 -0.936007 --0.105614 -2.90542 -0.929392 --0.126573 -3.00399 -0.91998 --0.147569 -3.10342 -0.907522 --0.172646 -3.22 -0.902199 --0.20496 -3.37203 -0.9126 --0.234778 -3.51672 -0.913569 --0.271235 -3.68754 -0.923615 --0.297482 -3.80824 -0.90166 --0.328371 -3.95519 -0.888693 --0.359283 -4.1029 -0.871081 --0.395365 -4.26952 -0.856606 --0.436125 -4.46323 -0.848072 --0.479525 -4.66768 -0.836788 --0.525502 -4.88184 -0.822102 --0.573113 -5.10674 -0.803572 --0.62649 -5.36048 -0.786985 --0.688185 -5.65199 -0.773683 --0.752486 -5.95403 -0.753235 --0.825142 -6.29468 -0.732928 --0.89939 -6.64582 -0.703482 --0.988771 -7.06445 -0.677912 --1.0897 -7.54146 -0.650384 --1.20994 -8.10562 -0.62383 --1.336 -8.70081 -0.58279 --1.48132 -9.38279 -0.535334 --1.64659 -10.1634 -0.478071 --1.85212 -11.1289 -0.416914 --1.92464 -11.4624 -0.25248 --1.97596 -11.6959 -0.0674947 --2.03709 -11.9757 0.121746 --2.39662 -13.6683 0.241552 --4.37033 -22.9779 0.542434 --4.59313 -24.0084 0.949944 --5.81321 -29.7468 1.46748 --5.82675 -29.7818 1.99966 --5.8294 -29.7693 2.53132 --5.84882 -29.8358 3.0689 --5.86243 -29.8724 3.60767 --5.85938 -29.8321 4.14123 --5.85632 -29.7918 4.67538 --5.85749 -29.772 5.21319 --5.84876 -29.704 5.74534 --5.84426 -29.6567 6.28155 --5.83557 -29.5896 6.81555 --5.82946 -29.5322 7.35295 --5.81 -29.419 7.87909 --5.82458 -29.4573 8.44378 --5.81172 -29.3713 8.98112 --5.79738 -29.2773 9.51787 --5.78707 -29.2008 10.0623 --5.77263 -29.1056 10.6036 --5.75156 -28.9831 11.1379 --5.7437 -28.9148 11.6945 --5.73216 -28.8357 12.2518 --5.70939 -28.7021 12.7909 --5.68654 -28.5672 13.3326 --5.5183 -27.762 13.5737 --5.72299 -28.6764 14.6058 --5.89017 -29.4154 15.6001 --5.86971 -29.2911 16.1909 --0.745521 -5.68462 4.08096 --0.720788 -5.56266 4.14336 --0.708486 -5.49956 4.23729 --0.71398 -5.51918 4.38117 --0.673228 -5.32737 4.39476 --0.685363 -5.37563 4.55992 --0.660858 -5.25695 4.61638 --0.637816 -5.14608 4.67543 --0.752602 -5.66007 5.19449 --0.756616 -5.67364 5.36099 --0.721266 -5.50592 5.38802 --0.683086 -5.32317 5.39787 --0.673292 -5.26998 5.51152 --0.68804 -5.33252 5.72927 --0.564103 -4.76369 5.37666 --0.539638 -4.64464 5.42028 --0.515256 -4.52674 5.46106 --0.42696 -4.12426 5.20971 --0.409428 -4.03815 5.26842 --0.442492 -4.1785 5.57354 --0.476632 -4.32175 5.89964 --0.435092 -4.12822 5.84805 --0.420353 -4.05752 5.93648 --0.405139 -3.97826 6.01597 --0.455021 -4.19399 6.47972 --0.405522 -3.96367 6.37049 --0.394449 -3.9063 6.48904 --0.363615 -3.76094 6.48446 --0.357804 -3.7274 6.64196 --0.324419 -3.57124 6.61561 --0.314429 -3.51621 6.74639 --0.308318 -3.47831 6.91119 --0.278811 -3.33805 6.90337 --0.272753 -3.30235 7.08449 --0.292139 -3.37296 7.47779 --0.267863 -3.25757 7.5283 --0.215441 -3.02104 7.32534 --0.225439 -3.04913 7.67723 --0.107199 -2.5326 6.80909 --0.0833094 -2.42086 6.82594 --0.105786 -2.50121 7.32237 --0.0428722 -2.22412 6.91858 --0.0599692 -2.28052 7.39878 --0.0544912 -2.24402 7.65606 --0.00450793 -2.02387 7.36261 -0.0233147 -1.89217 7.32158 -0.0170254 -1.89976 7.76765 -0.0388053 -1.79421 7.83929 -0.0917653 -1.56317 7.4051 -0.115599 -1.4524 7.4225 -0.181614 -1.17745 6.65575 -0.195808 -1.10325 6.79387 -0.221541 -0.986379 6.71433 -0.218056 -0.973444 7.27432 -0.242899 -0.8577 7.23159 -0.261117 -0.767938 7.38504 -0.307526 -0.547354 7.37914 -0.329242 -0.443448 7.45797 -0.351997 -0.333126 7.46519 -0.372249 -0.228884 7.65015 -0.401803 -0.108422 7.28355 -0.140193 -1.52508 -0.97089 -0.0564097 -1.86724 -0.953925 -0.0402992 -1.93454 -0.955298 -0.0256191 -1.99548 -0.947985 -0.00841677 -2.06455 -0.945858 --0.00777162 -2.13358 -0.94174 --0.0279522 -2.21797 -0.94885 --0.0436951 -2.2805 -0.934341 --0.0648993 -2.36561 -0.937002 --0.0852055 -2.45265 -0.936972 --0.109019 -2.54768 -0.940528 --0.127817 -2.62725 -0.929563 --0.147655 -2.70764 -0.916347 --0.175578 -2.82063 -0.922893 --0.201011 -2.92631 -0.920606 --0.224955 -3.02463 -0.909881 --0.251456 -3.13193 -0.901198 --0.28766 -3.28184 -0.913975 --0.319907 -3.41723 -0.912378 --0.358736 -3.57778 -0.920407 --0.394549 -3.72276 -0.914305 --0.419623 -3.82496 -0.881855 --0.461156 -3.99788 -0.879743 --0.499555 -4.15325 -0.863899 --0.543695 -4.33669 -0.854541 --0.587334 -4.51266 -0.835543 --0.640781 -4.73376 -0.828367 --0.690153 -4.93835 -0.807016 --0.744665 -5.16167 -0.785305 --0.812638 -5.44088 -0.77426 --0.883222 -5.73064 -0.756669 --0.959036 -6.04092 -0.734424 --1.04157 -6.37974 -0.709223 --1.13763 -6.77603 -0.686499 --1.24405 -7.21158 -0.658762 --1.36657 -7.71431 -0.630101 --1.5026 -8.27508 -0.594878 --1.64899 -8.87571 -0.546703 --1.83125 -9.62169 -0.499917 --2.03116 -10.4451 -0.437377 --2.21156 -11.1814 -0.335411 --2.28191 -11.4634 -0.161008 --2.34684 -11.7231 0.0246715 --2.54284 -12.5229 0.183742 --4.22773 -19.4657 0.0787504 --4.68158 -21.3234 0.373817 --4.91566 -22.2728 0.74579 --6.36419 -28.22 1.18337 --6.46023 -28.5899 1.6993 --6.45393 -28.5438 2.21143 --6.38898 -28.2563 2.70812 --6.48601 -28.6279 3.24718 --6.45704 -28.4883 3.75173 --6.47061 -28.5228 4.27297 --6.46652 -28.4805 4.7873 --6.46155 -28.4402 5.30272 --6.46175 -28.4194 5.82274 --6.46034 -28.3887 6.34327 --6.33064 -27.8363 6.75806 --6.28978 -27.6474 7.23807 --5.86686 -25.9018 7.33443 --6.27422 -27.5395 8.25992 --6.47368 -28.3287 9.01303 --6.46554 -28.2706 9.54618 --6.47073 -28.2689 10.1007 --6.47424 -28.2561 10.6577 --6.41598 -27.9736 11.6918 --6.23959 -27.2352 11.9708 --6.16305 -26.8997 12.3979 --6.13125 -26.7463 12.8995 --6.08526 -26.5388 13.3785 --5.7862 -25.3061 13.357 --6.17318 -26.84 14.7023 --0.924392 -5.69002 4.03738 --0.904734 -5.60385 4.1202 --0.87502 -5.48225 4.18128 --0.867116 -5.44326 4.28944 --0.928483 -5.68522 4.57414 --0.915244 -5.62381 4.67585 --0.856574 -5.38161 4.65548 --0.882496 -5.47901 4.86452 --0.89434 -5.52358 5.04352 --0.877146 -5.44579 5.13629 --0.889975 -5.49084 5.32473 --0.834255 -5.26379 5.29872 --0.834124 -5.25731 5.44979 --0.814611 -5.17391 5.53725 --0.77307 -5.00156 5.54378 --0.687932 -4.65855 5.38389 --0.754549 -4.91426 5.78966 --0.75543 -4.90905 5.95421 --0.56413 -4.14975 5.3376 --0.736979 -4.82467 6.22196 --0.571391 -4.16401 5.66816 --0.566007 -4.13562 5.80219 --0.597769 -4.25543 6.11871 --0.506755 -3.88918 5.84799 --0.709998 -4.67731 7.04193 --0.554289 -4.05974 6.43646 --0.534891 -3.97829 6.52482 --0.472273 -3.72605 6.36806 --0.449028 -3.62828 6.42615 --0.460955 -3.6646 6.69056 --0.437715 -3.56748 6.75569 --0.43066 -3.5306 6.92133 --0.403375 -3.41407 6.95814 --0.386387 -3.3413 7.07098 --0.338239 -3.14992 6.96358 --0.388062 -3.32654 7.56868 --0.329974 -3.09736 7.38636 --0.31012 -3.00934 7.48641 --0.188217 -2.54061 6.73082 --0.172377 -2.46996 6.83997 --0.14556 -2.35944 6.85595 --0.194148 -2.5265 7.59474 --0.100421 -2.16916 6.9657 --0.126588 -2.24986 7.53136 --0.113991 -2.19052 7.732 --0.0689461 -2.01214 7.56108 --0.0454569 -1.91161 7.63476 -0.000361631 -1.73407 7.42763 -0.0332184 -1.59992 7.36131 -0.0473162 -1.53253 7.56425 -0.114462 -1.28485 6.95682 -0.155975 -1.12276 6.67559 -0.170986 -1.05471 6.85246 -0.174 -1.02343 7.28473 -0.197437 -0.923218 7.35181 -0.228358 -0.802315 7.25872 -0.253916 -0.695853 7.27242 -0.301065 -0.493102 7.4337 -0.326756 -0.386441 7.47181 -0.351704 -0.279363 7.55787 -0.38022 -0.166477 7.48221 -0.412045 -0.0531918 7.05458 -0.0904163 -1.53684 -0.965314 --0.0070935 -1.88973 -0.958928 --0.0237763 -1.95059 -0.952403 --0.0404464 -2.01136 -0.944281 --0.0585796 -2.07933 -0.9413 --0.0792309 -2.1554 -0.943008 --0.0984519 -2.22511 -0.936029 --0.120129 -2.30192 -0.933587 --0.14332 -2.38685 -0.93494 --0.166612 -2.47366 -0.933897 --0.190883 -2.56028 -0.930253 --0.216662 -2.65499 -0.929803 --0.242539 -2.75157 -0.926558 --0.269392 -2.84794 -0.920312 --0.296282 -2.94516 -0.91122 --0.324733 -3.05143 -0.904274 --0.356739 -3.1666 -0.899166 --0.397918 -3.31611 -0.909922 --0.434082 -3.45016 -0.906357 --0.484499 -3.63566 -0.925985 --0.508426 -3.71952 -0.886434 --0.554852 -3.89027 -0.887093 --0.592115 -4.02739 -0.865647 --0.63806 -4.19142 -0.851522 --0.689682 -4.38249 -0.843432 --0.740801 -4.56608 -0.825402 --0.802781 -4.7957 -0.818442 --0.861622 -5.00775 -0.79715 --0.929735 -5.25662 -0.781286 --1.00822 -5.54414 -0.768649 --1.08769 -5.83212 -0.746069 --1.18014 -6.16862 -0.726711 --1.27511 -6.51454 -0.698159 --1.38815 -6.92677 -0.673617 --1.51418 -7.38817 -0.645057 --1.66445 -7.93543 -0.617694 --1.81207 -8.47379 -0.569364 --1.99174 -9.12757 -0.52102 --2.20241 -9.89653 -0.466574 --2.46058 -10.8379 -0.40719 --2.56061 -11.1951 -0.248583 --2.64134 -11.4834 -0.0710892 --2.73218 -11.8068 0.113417 --3.14544 -13.3121 0.241472 --4.9118 -19.772 0.229244 --5.09249 -20.417 0.573535 --5.92582 -23.4493 0.933782 --6.42344 -25.2485 1.38511 --6.42296 -25.2279 1.84156 --6.40347 -25.1414 2.29443 --6.35408 -24.9409 2.73715 --6.46546 -25.3302 3.22523 --6.45086 -25.2584 3.68025 --6.43386 -25.1798 4.13342 --6.4231 -25.1217 4.58855 --6.40475 -25.0373 5.03962 --6.3901 -24.9646 5.4922 --6.38069 -24.9124 5.94913 --6.36722 -24.8425 6.40335 --6.32725 -24.681 6.83675 --6.28078 -24.4942 7.26115 --6.36576 -24.7837 7.8137 --6.35873 -24.7388 8.28322 --6.37974 -24.7957 8.788 --6.37271 -24.7514 9.26636 --6.3606 -24.6894 9.74241 --6.34695 -24.6184 10.2187 --6.33842 -24.5667 10.7059 --6.31875 -24.479 11.1828 --6.31266 -24.4355 11.6828 --6.29649 -24.3571 12.1723 --6.24101 -24.1376 12.5992 --6.24635 -24.1368 13.135 --1.14152 -5.83678 4.06993 --1.12529 -5.7756 4.17053 --1.07107 -5.57717 4.19269 --1.07367 -5.58133 4.32808 --1.07601 -5.58144 4.46458 --1.06979 -5.55472 4.58627 --1.07869 -5.58237 4.74599 --1.08247 -5.59071 4.89672 --1.08599 -5.59499 5.04884 --1.10736 -5.66673 5.25508 --1.09084 -5.60119 5.36307 --1.13196 -5.73965 5.63572 --1.01541 -5.32324 5.45696 --0.958737 -5.11398 5.43752 --0.976119 -5.16973 5.64725 --0.883629 -4.83924 5.50684 --0.875933 -4.80527 5.63477 --0.748653 -4.35177 5.34727 --0.672664 -4.07976 5.22107 --0.65766 -4.02115 5.30879 --0.693491 -4.13932 5.59262 --0.912872 -4.90011 6.63045 --0.908803 -4.88048 6.80887 --0.943951 -4.99252 7.15637 --0.849488 -4.65732 6.95143 --0.980755 -5.10288 7.75832 --0.578222 -3.69878 6.081 --0.552043 -3.60157 6.13129 --0.538197 -3.54763 6.24487 --0.590305 -3.71722 6.70567 --0.564119 -3.62121 6.77234 --0.510944 -3.43116 6.68489 --0.561332 -3.59258 7.19123 --0.504602 -3.39175 7.0827 --0.458606 -3.22305 7.02119 --0.480757 -3.28894 7.40507 --0.468963 -3.24144 7.58847 --0.414635 -3.04612 7.46691 --0.268992 -2.54463 6.65256 --0.241743 -2.44517 6.68891 --0.225145 -2.37918 6.80609 --0.201473 -2.29187 6.8763 --0.166908 -2.16523 6.84258 --0.123046 -2.01038 6.72159 --0.185365 -2.20249 7.62622 --0.167106 -2.12932 7.78899 --0.104428 -1.91357 7.48283 --0.0663193 -1.77499 7.41115 --0.0387752 -1.67183 7.46193 --0.0319076 -1.63481 7.79197 -0.0265145 -1.43607 7.44113 -0.0992488 -1.19436 6.82133 -0.122981 -1.10605 6.8914 -0.117011 -1.1035 7.48165 -0.15664 -0.964275 7.30349 -0.190563 -0.843505 7.21138 -0.21902 -0.739691 7.2359 -0.224729 -0.694779 7.8451 -0.272934 -0.538747 7.36898 -0.298594 -0.439113 7.48784 -0.323628 -0.33958 7.6848 -0.353635 -0.22679 7.71016 -0.391017 -0.107788 7.32365 -0.0500769 -1.50703 -0.979577 -0.0364051 -1.55174 -0.967361 --0.0524265 -1.84402 -0.962218 --0.0710517 -1.9038 -0.956532 --0.0911406 -1.97077 -0.956088 --0.109801 -2.03139 -0.947156 --0.133393 -2.10633 -0.949798 --0.154558 -2.17496 -0.943757 --0.17718 -2.25076 -0.942259 --0.200904 -2.32838 -0.93846 --0.227079 -2.41307 -0.9386 --0.253295 -2.49863 -0.936193 --0.279552 -2.58507 -0.93124 --0.308375 -2.68053 -0.929428 --0.335649 -2.76765 -0.919228 --0.367012 -2.87197 -0.917161 --0.399408 -2.97708 -0.911843 --0.4343 -3.09015 -0.908418 --0.476905 -3.23039 -0.916112 --0.519477 -3.37042 -0.919512 --0.568227 -3.52936 -0.927442 --0.599199 -3.62939 -0.898856 --0.642905 -3.7727 -0.88877 --0.689149 -3.92485 -0.878229 --0.739047 -4.08777 -0.86673 --0.794047 -4.26856 -0.857518 --0.847487 -4.44093 -0.838618 --0.913731 -4.65825 -0.831627 --0.978526 -4.86911 -0.813752 --1.05097 -5.10672 -0.798507 --1.12703 -5.35488 -0.77811 --1.21791 -5.64858 -0.763469 --1.30788 -5.94484 -0.738698 --1.42401 -6.32439 -0.72635 --1.53498 -6.68631 -0.696086 --1.6635 -7.10636 -0.666132 --1.8156 -7.6013 -0.637621 --1.97897 -8.13417 -0.598947 --2.15726 -8.71576 -0.549654 --2.38185 -9.4492 -0.503751 --2.63784 -10.2885 -0.446294 --2.9132 -11.1846 -0.365567 --3.01424 -11.51 -0.193098 --3.10369 -11.7942 -0.00582043 --3.32235 -12.5059 0.162519 --5.13166 -18.4311 0.100236 --5.34011 -19.1019 0.416275 --5.53063 -19.7104 0.757346 --6.71222 -23.5641 1.13886 --6.9895 -24.4558 1.59034 --6.83718 -23.9444 2.01558 --6.70978 -23.5124 2.42759 --6.96031 -24.3133 2.92186 --6.96517 -24.3139 3.36898 --7.01478 -24.4594 3.83438 --7.01571 -24.445 4.28554 --7.01415 -24.4227 4.73699 --7.01275 -24.4033 5.19039 --7.00623 -24.3652 5.64243 --7.00345 -24.3397 6.09842 --6.86278 -23.8662 6.45452 --6.80414 -23.6589 6.8619 --6.71201 -23.343 7.23624 --6.79376 -23.5937 7.76453 --6.77718 -23.5216 8.20841 --7.03438 -24.3362 8.94341 --7.03029 -24.3076 9.42436 --7.02715 -24.2787 9.91012 --7.02656 -24.2592 10.4043 --6.98762 -24.1159 10.8534 --6.98443 -24.0873 11.3532 --6.84287 -23.6114 11.6572 --6.67561 -23.0543 11.91 --6.61817 -22.8508 12.3211 --1.32812 -5.83762 4.02809 --6.5145 -22.4813 13.1629 --6.34777 -21.93 13.3776 --6.65177 -22.884 14.4619 --1.28417 -5.67831 4.48249 --1.25222 -5.57035 4.55453 --1.23749 -5.5178 4.66117 --1.21428 -5.43954 4.75056 --1.23374 -5.49447 4.93403 --1.20685 -5.40474 5.01652 --1.26188 -5.57501 5.29835 --1.18596 -5.32771 5.26018 --1.14565 -5.1954 5.30743 --1.15761 -5.22573 5.49044 --1.11964 -5.09917 5.54009 --1.20735 -5.37316 5.95613 --1.33484 -5.76923 6.51145 --0.828516 -4.16359 5.12089 --0.804095 -4.07976 5.18246 --0.77869 -3.99607 5.24233 --1.08184 -4.94471 6.43552 --1.10443 -5.00839 6.70155 --0.949015 -4.51301 6.32196 --0.931823 -4.45395 6.44167 --0.920534 -4.41146 6.58408 --0.969429 -4.55556 6.97622 --0.720775 -3.77385 6.13297 --0.680679 -3.64166 6.13718 --0.799342 -4.00483 6.86092 --0.75309 -3.85263 6.85128 --0.686505 -3.63759 6.73786 --0.623859 -3.43883 6.63539 --0.62552 -3.43406 6.85084 --0.655893 -3.52027 7.23969 --0.667062 -3.54751 7.54649 --0.519856 -3.0862 6.93515 --0.520251 -3.07921 7.17681 --0.54998 -3.15892 7.61659 --0.357612 -2.56601 6.61926 --0.329651 -2.47211 6.66559 --0.299415 -2.37289 6.70093 --0.437874 -2.77918 8.00757 --0.342841 -2.48296 7.58376 --0.20046 -2.04786 6.72103 --0.173726 -1.95845 6.77671 --0.236039 -2.1318 7.65489 --0.201999 -2.01963 7.69306 --0.133608 -1.80783 7.37494 --0.103018 -1.70328 7.41692 --0.0736962 -1.60533 7.48607 --0.0556452 -1.53967 7.69937 -0.033275 -1.27203 6.99508 -0.0745384 -1.14326 6.87088 -0.0782794 -1.11497 7.28417 -0.108685 -1.01406 7.33345 -0.147653 -0.892008 7.23283 -0.17381 -0.801147 7.35742 -0.207408 -0.691106 7.33172 -0.238935 -0.587622 7.37355 -0.26951 -0.483169 7.41354 -0.301087 -0.379371 7.46176 -0.331904 -0.27465 7.54788 -0.36823 -0.162718 7.44228 -0.405331 -0.0523093 7.10465 -0.00196511 -1.50848 -0.966311 --0.0151223 -1.55936 -0.961374 --0.115268 -1.85617 -0.960125 --0.133408 -1.90857 -0.946695 --0.157963 -1.98261 -0.952477 --0.178552 -2.04206 -0.942686 --0.206607 -2.12404 -0.951055 --0.229759 -2.1925 -0.944005 --0.252897 -2.26087 -0.935058 --0.281019 -2.34451 -0.936536 --0.309182 -2.42902 -0.935567 --0.34091 -2.52251 -0.937835 --0.370091 -2.6077 -0.931618 --0.399372 -2.69477 -0.922806 --0.433621 -2.79699 -0.922321 --0.46644 -2.89286 -0.913249 --0.501759 -2.99671 -0.906468 --0.542214 -3.11864 -0.906368 --0.586156 -3.24844 -0.907357 --0.642318 -3.41333 -0.922945 --0.694981 -3.57091 -0.928508 --0.722841 -3.65354 -0.889087 --0.780126 -3.82163 -0.889791 --0.828766 -3.96429 -0.872589 --0.880003 -4.11677 -0.854483 --0.946055 -4.31419 -0.850374 --1.01662 -4.52021 -0.843104 --1.08368 -4.71889 -0.825308 --1.15689 -4.93626 -0.807347 --1.23985 -5.18221 -0.791209 --1.32631 -5.43671 -0.769617 --1.4287 -5.73864 -0.75308 --1.53718 -6.059 -0.731184 --1.66156 -6.4266 -0.710247 --1.80181 -6.8413 -0.687773 --1.94562 -7.26619 -0.652555 --2.1238 -7.79463 -0.623494 --2.3065 -8.33298 -0.577291 --2.51994 -8.9656 -0.527717 --2.77942 -9.72971 -0.475327 --3.09793 -10.6746 -0.418999 --3.34226 -11.3923 -0.302326 --3.51311 -11.8935 -0.138696 --3.65802 -12.3157 0.0488911 --5.24253 -17.0131 -0.00137512 --5.53093 -17.8595 0.278059 --5.68449 -18.3028 0.597308 --7.00067 -22.1904 0.91937 --7.16699 -22.6703 1.33513 --7.18778 -22.7165 1.75448 --7.04893 -22.2929 2.1519 --7.026 -22.2119 2.55845 --7.2417 -22.8328 3.02498 --7.22365 -22.767 3.44242 --7.23221 -22.7775 3.86853 --7.2251 -22.7439 4.29055 --7.22269 -22.722 4.71528 --7.20822 -22.666 5.13514 --7.2045 -22.639 5.56161 --7.19735 -22.6052 5.98833 --7.17651 -22.5266 6.40642 --7.10506 -22.3044 6.78753 --7.03834 -22.094 7.16715 --7.10016 -22.2606 7.65521 --7.09149 -22.2186 8.08772 --7.18708 -22.484 8.62766 --7.21474 -22.5496 9.11189 --7.20603 -22.5087 9.56377 --7.20695 -22.4955 10.0308 --7.2018 -22.4647 10.4963 --7.19661 -22.4336 10.9672 --7.14071 -22.2552 11.3756 --7.00878 -21.8551 11.6755 --6.93227 -21.6147 12.0466 --6.88238 -21.4529 12.4572 --6.89282 -21.4681 12.9679 --6.73459 -20.9925 13.2033 --6.98907 -21.7135 14.1502 --6.9126 -21.4752 14.5387 --1.4066 -5.4738 5.18078 --1.44138 -5.57052 5.41299 --1.27488 -5.08568 5.1782 --1.28074 -5.09634 5.34037 --1.20174 -4.86373 5.29308 --1.40724 -5.45001 5.98321 --1.51552 -5.75336 6.44962 --0.973606 -4.19323 5.11508 --0.939082 -4.0899 5.15729 --1.10589 -4.56338 5.80292 --1.06636 -4.44339 5.84348 --1.05551 -4.40739 5.97589 --1.06368 -4.4261 6.17512 --1.02897 -4.32098 6.23366 --0.975209 -4.16035 6.22114 --1.01299 -4.26436 6.54524 --0.862134 -3.82718 6.15963 --0.805182 -3.66116 6.11819 --0.771772 -3.55974 6.161 --0.922404 -3.97917 6.98588 --0.847679 -3.7624 6.87673 --0.844781 -3.74752 7.07932 --0.79359 -3.59594 7.06316 --0.704877 -3.33878 6.8552 --0.704344 -3.33166 7.08032 --0.846143 -3.71755 8.06628 --0.627929 -3.10125 7.1472 --0.616689 -3.06342 7.33719 --0.483087 -2.68383 6.80095 --0.427743 -2.52341 6.70513 --0.385201 -2.39792 6.67811 --0.528684 -2.78168 7.90728 --0.312992 -2.1836 6.69885 --0.285529 -2.09964 6.7666 --0.230595 -1.94241 6.62638 --0.243133 -1.96624 7.02054 --0.301984 -2.11193 7.85398 --0.216215 -1.87119 7.4529 --0.169245 -1.73515 7.38116 --0.125686 -1.60713 7.32567 --0.147075 -1.64886 7.97509 --0.0622071 -1.41374 7.45965 --0.0100054 -1.26532 7.27994 -0.0211515 -1.17036 7.35172 -0.0653199 -1.04544 7.25463 -0.0868723 -0.971829 7.47072 -0.1384 -0.828854 7.22079 -0.172768 -0.725884 7.23548 -0.18037 -0.683598 7.85471 -0.237457 -0.530611 7.38868 -0.270995 -0.428399 7.44778 -0.271887 -0.383761 8.71305 -0.339558 -0.220368 7.62025 -0.382923 -0.104251 7.26377 --0.0553445 -1.52757 -0.976135 --0.0695815 -1.56579 -0.955122 --0.18098 -1.86612 -0.957716 --0.202588 -1.92565 -0.950517 --0.227594 -1.99124 -0.9485 --0.251648 -2.0578 -0.944541 --0.279218 -2.1324 -0.945166 --0.3043 -2.19971 -0.937357 --0.335366 -2.28222 -0.940068 --0.364003 -2.35843 -0.934097 --0.395151 -2.4427 -0.931915 --0.426279 -2.52685 -0.927236 --0.463498 -2.62812 -0.931281 --0.495702 -2.71394 -0.921105 --0.53041 -2.80777 -0.91372 --0.568676 -2.91053 -0.908672 --0.609498 -3.02225 -0.905366 --0.65739 -3.15091 -0.908482 --0.708827 -3.28841 -0.912236 --0.774994 -3.46908 -0.934581 --0.805742 -3.54962 -0.896942 --0.857314 -3.69045 -0.887115 --0.909849 -3.831 -0.872689 --0.965978 -3.98133 -0.857554 --1.03786 -4.17555 -0.85676 --1.10117 -4.34534 -0.838111 --1.17664 -4.54991 -0.827869 --1.25318 -4.75607 -0.810632 --1.34292 -4.99783 -0.799052 --1.43371 -5.24111 -0.778979 --1.53063 -5.50294 -0.756144 --1.64534 -5.81005 -0.737653 --1.77339 -6.15544 -0.718379 --1.90852 -6.51908 -0.691544 --2.06158 -6.93068 -0.662513 --2.24109 -7.41499 -0.635209 --2.43237 -7.92908 -0.595736 --2.64045 -8.4898 -0.546031 --2.90114 -9.1909 -0.49873 --3.19644 -9.98458 -0.439198 --3.55662 -10.9566 -0.372802 --3.98359 -12.1062 -0.289642 --4.55653 -13.6479 -0.198694 --5.21662 -15.4241 -0.0670094 --5.68923 -16.6934 0.156254 --5.87011 -17.1724 0.451937 --6.68932 -19.3714 0.741614 --7.3296 -21.0878 1.11081 --7.36603 -21.1754 1.50548 --7.35202 -21.1247 1.89786 --7.32139 -21.031 2.28641 --7.36845 -21.1456 2.6889 --7.53845 -21.589 3.12903 --7.45878 -21.3633 3.5089 --7.47098 -21.3825 3.91514 --7.44257 -21.2926 4.30699 --7.35589 -21.0491 4.67081 --7.34057 -20.9934 5.06404 --7.33153 -20.9592 5.46228 --7.31144 -20.8908 5.85406 --7.29504 -20.8341 6.24933 --7.26561 -20.7434 6.63663 --7.25154 -20.6924 7.03551 --7.15313 -20.4181 7.36689 --7.30548 -20.8101 7.91259 --7.23918 -20.6217 8.27417 --7.34034 -20.8784 8.79931 --7.31897 -20.8071 9.21146 --7.29775 -20.7386 9.62704 --7.27756 -20.6709 10.0464 --7.26091 -20.6126 10.4738 --7.24528 -20.555 10.9059 --7.22973 -20.4991 11.3432 --7.21659 -20.4507 11.7902 --7.1761 -20.3284 12.202 --7.15698 -20.2642 12.6505 --7.10804 -20.1176 13.0559 --6.92798 -19.6255 13.2479 --7.15561 -20.2122 14.126 --7.11385 -20.0876 14.5652 --1.79885 -6.0226 5.73187 --1.64335 -5.60966 5.57109 --1.81252 -6.04722 6.10865 --1.79344 -5.9914 6.24613 --1.55816 -5.36916 5.8724 --1.444 -5.06362 5.76087 --1.41233 -4.97795 5.84803 --1.41556 -4.97914 6.02253 --1.26537 -4.58163 5.78675 --1.25469 -4.54852 5.92131 --1.19262 -4.38323 5.9116 --1.19819 -4.39082 6.09565 --1.16526 -4.29988 6.16942 --1.14167 -4.23304 6.27178 --1.13324 -4.20579 6.42707 --1.04899 -3.9812 6.32546 --0.940393 -3.69391 6.12236 --0.896089 -3.57622 6.14257 --1.01179 -3.86618 6.76867 --0.991652 -3.80883 6.89776 --0.994573 -3.80937 7.12609 --0.914205 -3.59824 7.01146 --0.890374 -3.52865 7.12901 --0.803096 -3.29846 6.96202 --0.745947 -3.14557 6.91882 --0.699277 -3.02074 6.92423 --0.945671 -3.63782 8.44032 --0.848058 -3.38173 8.22162 --0.53751 -2.58831 6.77967 --0.662443 -2.89411 7.76277 --0.615625 -2.76772 7.77942 --0.387814 -2.18944 6.63144 --0.414092 -2.24528 7.07123 --0.332459 -2.03324 6.79445 --0.307608 -1.96295 6.90714 --0.39195 -2.16034 7.88069 --0.401437 -2.17212 8.33941 --0.328833 -1.98226 8.13027 --0.327753 -1.96544 8.55155 --0.234334 -1.72852 8.12327 --0.134653 -1.47597 7.55259 --0.0807234 -1.33618 7.42345 --0.033452 -1.21077 7.34012 --0.00470768 -1.12885 7.48986 -0.00923264 -1.07798 7.86512 -0.0916172 -0.875121 7.24215 -0.127861 -0.776753 7.2877 -0.164169 -0.677987 7.34133 -0.199561 -0.57927 7.4131 -0.238026 -0.475271 7.43332 -0.276519 -0.369856 7.44166 -0.31326 -0.269017 7.55786 -0.354456 -0.159382 7.45233 -0.398484 -0.0503882 7.11482 --0.107688 -1.53213 -0.970092 --0.243155 -1.86791 -0.948028 --0.269107 -1.93249 -0.946954 --0.29369 -1.99171 -0.937344 --0.32809 -2.07865 -0.952427 --0.355176 -2.14588 -0.945507 --0.382186 -2.21202 -0.936639 --0.412769 -2.28718 -0.932006 --0.44933 -2.37751 -0.937194 --0.479936 -2.45343 -0.927817 --0.516516 -2.5445 -0.927661 --0.554192 -2.63736 -0.924606 --0.591845 -2.73008 -0.918754 --0.632997 -2.83074 -0.915288 --0.670724 -2.92516 -0.903344 --0.718985 -3.04363 -0.903554 --0.776832 -3.18713 -0.914573 --0.834762 -3.33238 -0.920699 --0.890197 -3.4703 -0.917393 --0.930019 -3.56771 -0.887264 --0.99002 -3.71517 -0.879749 --1.05004 -3.86339 -0.867191 --1.11008 -4.01235 -0.849589 --1.18073 -4.18708 -0.838348 --1.2631 -4.38941 -0.831966 --1.34448 -4.59246 -0.818449 --1.43042 -4.80508 -0.801121 --1.528 -5.04417 -0.785706 --1.63632 -5.31172 -0.770711 --1.74463 -5.5798 -0.746177 --1.87179 -5.89406 -0.725235 --2.01315 -6.2445 -0.702804 --2.17688 -6.64982 -0.681506 --2.34879 -7.07518 -0.649548 --2.55114 -7.57294 -0.617799 --2.74997 -8.06389 -0.565887 --3.00781 -8.70112 -0.521744 --3.2951 -9.4122 -0.465532 --3.66845 -10.3359 -0.412018 --4.0615 -11.3061 -0.32963 --4.60323 -12.6465 -0.247712 --5.16909 -14.0413 -0.120078 --5.84583 -15.7146 0.0426312 --6.02276 -16.1435 0.320806 --6.20907 -16.5962 0.61414 --7.54248 -19.8902 0.910787 --7.63148 -20.0999 1.28804 --7.6133 -20.0452 1.66488 --7.58911 -19.9739 2.03915 --7.5026 -19.7496 2.40061 --7.81035 -20.4985 2.84172 --7.79775 -20.4541 3.22632 --7.75239 -20.331 3.60058 --7.77523 -20.3761 3.99647 --7.75811 -20.3231 4.3797 --7.74569 -20.2816 4.76525 --7.72739 -20.2256 5.14853 --7.71479 -20.1811 5.53502 --7.70235 -20.1395 5.92337 --7.65462 -20.0099 6.29008 --7.63641 -19.9557 6.67646 --7.60272 -19.8599 7.05166 --7.55049 -19.7218 7.41332 --7.63038 -19.9042 7.88458 --7.55931 -19.7187 8.23305 --7.59947 -19.8062 8.68461 --7.58086 -19.7463 9.08512 --7.57286 -19.7142 9.5006 --7.55442 -19.6579 9.9097 --7.53349 -19.5937 10.3192 --7.51616 -19.5399 10.7375 --7.51024 -19.5106 11.174 --7.49388 -19.4572 11.6034 --7.47753 -19.4045 12.0386 --7.38424 -19.1651 12.3693 --7.40503 -19.2012 12.8681 --7.25118 -18.8146 13.1059 --7.5279 -19.4711 14.0325 --7.45771 -19.2866 14.4196 --2.0181 -6.06955 5.7316 --1.99463 -6.00655 5.85748 --2.06051 -6.1598 6.1659 --1.85733 -5.66445 5.9248 --1.61037 -5.06532 5.56432 --1.68902 -5.24951 5.90079 --1.56372 -4.94112 5.77943 --1.5267 -4.84916 5.85852 --1.56574 -4.93603 6.12222 --1.40153 -4.53784 5.87689 --1.38873 -4.50282 6.01204 --1.43117 -4.59831 6.30031 --1.34788 -4.39339 6.24584 --1.29355 -4.25916 6.26805 --1.42683 -4.57186 6.85907 --1.28146 -4.21916 6.60391 --1.47308 -4.6702 7.42886 --1.21402 -4.04618 6.77611 --1.19752 -4.00071 6.92433 --1.19713 -3.99514 7.13812 --1.14037 -3.85271 7.14659 --1.07922 -3.7025 7.13513 --1.05454 -3.63644 7.26345 --1.03346 -3.58196 7.4169 --0.979065 -3.4455 7.42339 --0.806471 -3.03479 6.89453 --0.764864 -2.93005 6.93351 --0.809591 -3.02773 7.39723 --0.818837 -3.04056 7.71372 --0.685527 -2.72452 7.29115 --0.700325 -2.74988 7.65185 --0.672068 -2.67473 7.78581 --0.638246 -2.58883 7.90047 --0.428055 -2.09714 6.88625 --0.346379 -1.90292 6.63437 --0.354205 -1.91132 6.98137 --0.514401 -2.26428 8.50773 --0.436875 -2.07763 8.32063 --0.375059 -1.92769 8.24399 --0.366157 -1.89366 8.61732 --0.251647 -1.62668 8.0321 --0.153087 -1.3979 7.52687 --0.124632 -1.32337 7.70912 --0.0710426 -1.1913 7.60599 --0.0188041 -1.06633 7.51964 --0.014451 -1.0392 8.07216 -0.0800573 -0.824969 7.32919 -0.126569 -0.713611 7.26488 -0.118832 -0.703788 8.22214 -0.202137 -0.5215 7.42826 -0.243529 -0.418723 7.44762 -0.245395 -0.376166 8.73281 -0.323793 -0.214389 7.60025 -0.373045 -0.101135 7.25388 --0.160906 -1.53463 -0.963843 --0.313031 -1.87993 -0.951893 --0.340972 -1.94434 -0.949911 --0.369956 -2.0096 -0.945976 --0.401399 -2.08197 -0.94678 --0.430413 -2.14803 -0.938901 --0.462941 -2.22212 -0.935406 --0.495451 -2.29611 -0.929714 --0.531471 -2.37809 -0.927707 --0.570996 -2.46805 -0.929084 --0.610559 -2.55887 -0.927516 --0.651158 -2.65048 -0.923097 --0.694258 -2.7501 -0.921169 --0.73487 -2.84242 -0.910808 --0.786079 -2.95979 -0.91275 --0.838256 -3.07691 -0.910892 --0.900077 -3.22005 -0.919494 --0.973466 -3.38801 -0.937199 --1.00914 -3.46725 -0.899585 --1.06952 -3.60455 -0.889863 --1.12986 -3.74163 -0.875646 --1.19836 -3.89743 -0.86465 --1.27391 -4.06999 -0.856081 --1.34695 -4.23518 -0.837779 --1.43416 -4.43505 -0.827877 --1.52594 -4.64449 -0.814264 --1.62585 -4.87244 -0.799677 --1.73489 -5.1188 -0.783014 --1.85104 -5.38364 -0.763284 --1.97879 -5.67479 -0.74217 --2.12638 -6.01198 -0.723144 --2.28305 -6.36732 -0.696648 --2.47125 -6.7962 -0.674601 --2.66295 -7.23422 -0.638861 --2.87996 -7.72664 -0.598148 --3.12032 -8.27441 -0.549325 --3.40127 -8.91377 -0.495284 --3.55963 -9.27139 -0.375447 --3.43484 -8.9823 -0.158542 --3.41249 -8.92562 0.0207223 --5.27683 -13.185 -0.196331 --5.95117 -14.7181 -0.0543465 --3.47722 -9.05912 0.526505 --6.39607 -15.7202 0.473767 --7.77427 -18.8572 0.72701 --7.875 -19.077 1.08733 --8.10943 -19.6029 1.46324 --7.92056 -19.1604 1.81838 --7.83302 -18.9516 2.17168 --8.05556 -19.4487 2.57462 --8.09102 -19.519 2.95512 --8.05217 -19.42 3.31931 --8.20597 -19.7599 3.74201 --8.20532 -19.747 4.12395 --8.19325 -19.7109 4.50325 --8.1914 -19.695 4.88743 --8.15841 -19.6103 5.25857 --8.18667 -19.6629 5.66157 --8.14896 -19.5666 6.03131 --7.94 -19.0827 6.29325 --7.8735 -18.9223 6.63538 --7.8405 -18.8371 6.99839 --7.77397 -18.6759 7.33618 --7.87389 -18.8913 7.80731 --7.80159 -18.7175 8.14373 --8.25587 -19.732 8.95618 --8.25599 -19.7189 9.38226 --7.9558 -18.9968 10.7982 --8.09759 -19.3029 11.4114 --7.8396 -18.7102 11.5407 --7.72116 -18.433 11.8349 --7.64063 -18.2394 12.1757 --7.63493 -18.2145 12.6231 --7.55903 -18.0322 12.9745 --7.37393 -17.605 13.1573 --7.71736 -18.3612 14.1767 --7.61126 -18.1079 14.4976 --2.1539 -5.89748 5.73904 --2.0953 -5.76246 5.80263 --1.82805 -5.16064 5.46048 --1.78792 -5.06686 5.53946 --1.88516 -5.2788 5.90047 --1.95024 -5.41893 6.21164 --1.97521 -5.46985 6.44893 --1.82068 -5.12217 6.28566 --1.57256 -4.56643 5.88084 --1.58838 -4.59632 6.08819 --1.69786 -4.83594 6.54367 --1.75793 -4.96247 6.89228 --1.98092 -5.45048 7.70227 --1.93009 -5.32981 7.79056 --1.85335 -5.15608 7.80706 --1.37072 -4.08782 6.59516 --1.40564 -4.15976 6.90194 --1.44028 -4.22811 7.22106 --1.27994 -3.87197 6.91175 --1.22508 -3.7457 6.93585 --1.17024 -3.61958 6.95696 --1.15616 -3.58293 7.12646 --1.24363 -3.76607 7.69583 --1.3512 -3.99318 8.38567 --1.24322 -3.7528 8.22694 --0.864009 -2.92424 6.86933 --0.843059 -2.87123 7.01304 --0.863728 -2.90985 7.36203 --0.939074 -3.06413 8.00228 --0.737635 -2.62466 7.27945 --0.796971 -2.74285 7.87805 --0.752304 -2.63975 7.94833 --0.501649 -2.09851 6.8095 --0.43845 -1.95686 6.70883 --0.475167 -2.02738 7.24444 --0.610867 -2.30177 8.50392 --0.507524 -2.07452 8.17596 --0.452786 -1.9484 8.17664 --0.459539 -1.95135 8.67515 --0.340344 -1.69467 8.15098 --0.26839 -1.53502 7.97887 --0.215054 -1.41385 7.95898 --0.132709 -1.23487 7.62323 --0.173649 -1.29892 8.64826 --0.0659296 -1.07214 7.99248 -0.0293144 -0.872037 7.37005 -0.083022 -0.752966 7.24753 -0.129275 -0.648195 7.21189 -0.160283 -0.570944 7.47247 -0.205683 -0.465829 7.46295 -0.249137 -0.365253 7.52135 -0.295522 -0.260902 7.51786 -0.343585 -0.153684 7.41239 -0.392557 -0.0490183 7.115 --0.376954 -1.87756 -0.941493 --0.410297 -1.94796 -0.945482 --0.443683 -2.01926 -0.947324 --0.474642 -2.08426 -0.940584 --0.509055 -2.15629 -0.938277 --0.54351 -2.22921 -0.933723 --0.581475 -2.31013 -0.932953 --0.620418 -2.39087 -0.929682 --0.661928 -2.48064 -0.929552 --0.704414 -2.57021 -0.92662 --0.747936 -2.66058 -0.920838 --0.794019 -2.75993 -0.917397 --0.845593 -2.86708 -0.915933 --0.896141 -2.97412 -0.910979 --0.959331 -3.10701 -0.91697 --1.026 -3.24773 -0.92325 --1.08924 -3.38218 -0.920053 --1.13042 -3.46926 -0.885615 --1.20625 -3.62924 -0.886872 --1.2715 -3.7649 -0.870283 --1.34386 -3.91835 -0.85677 --1.43239 -4.1064 -0.853043 --1.51841 -4.28708 -0.838986 --1.60796 -4.47642 -0.822072 --1.71014 -4.69224 -0.808164 --1.82139 -4.92549 -0.792828 --1.93626 -5.16928 -0.771939 --2.0683 -5.44826 -0.753392 --2.12742 -5.5703 -0.677146 --2.11158 -5.53397 -0.552198 --2.12804 -5.5659 -0.447573 --2.13531 -5.57908 -0.337934 --2.12525 -5.5548 -0.220259 --2.08059 -5.45674 -0.0897598 --2.0566 -5.40116 0.0285714 --2.05943 -5.40678 0.1344 --2.03317 -5.34651 0.248978 --2.02668 -5.33059 0.355478 --1.81531 -4.88052 0.505622 --1.96062 -5.18426 0.575051 --2.05421 -5.37987 0.663191 --2.1213 -5.51941 0.760986 --2.10217 -5.47711 0.868793 --3.92983 -9.33766 0.952256 --8.08159 -18.1025 1.25135 --8.06971 -18.0669 1.59994 --8.04994 -18.0168 1.94686 --7.95551 -17.8083 2.2811 --8.27658 -18.4769 2.68793 --8.28318 -18.4827 3.04851 --8.18981 -18.2751 3.3831 --8.22506 -18.341 3.75187 --8.219 -18.3195 4.11031 --8.20253 -18.2748 4.46543 --8.19633 -18.2513 4.82557 --8.18225 -18.2134 5.18374 --8.16582 -18.1695 5.5417 --8.14703 -18.1198 5.89936 --8.10428 -18.0211 6.2438 --8.09234 -17.9857 6.60762 --8.05194 -17.8927 6.95457 --7.81711 -17.3903 7.15673 --8.07948 -17.9307 7.73261 --8.03201 -17.8201 8.07834 --8.04971 -17.8472 8.48201 --8.03551 -17.8091 8.8632 --8.02684 -17.7802 9.25279 --8.00779 -17.7283 9.63577 --8.00028 -17.7029 10.0361 --7.98133 -17.6534 10.4294 --7.9714 -17.6218 10.837 --7.95348 -17.5737 11.2416 --7.94007 -17.5348 11.6572 --7.91967 -17.4795 12.0694 --7.84939 -17.3239 12.4215 --7.82903 -17.27 12.8446 --7.65172 -16.8898 13.0422 --7.95398 -17.5047 13.9668 --7.90268 -17.3854 14.3724 --7.70262 -16.958 14.5379 --2.38746 -5.94812 5.93029 --2.26146 -5.6841 5.8858 --1.8928 -4.91685 5.38254 --2.12179 -5.38718 5.97544 --2.03897 -5.21202 5.98791 --2.03966 -5.20239 6.34289 --2.05989 -5.24085 6.57432 --2.2743 -5.67576 7.25187 --2.2219 -5.56288 7.34674 --2.13337 -5.37539 7.35195 --2.04493 -5.18916 7.35172 --2.12898 -5.35495 7.78966 --1.98529 -5.05504 7.64093 --1.56252 -4.18632 6.70123 --1.48792 -4.02901 6.68751 --1.44828 -3.94392 6.77293 --1.49729 -4.03756 7.13075 --1.3632 -3.75907 6.92278 --1.30672 -3.63959 6.95361 --1.25801 -3.53457 7.00684 --1.23735 -3.48713 7.15924 --1.22668 -3.45905 7.35432 --1.39698 -3.79613 8.25811 --0.977469 -2.94463 6.86602 --0.921195 -2.82648 6.86968 --0.850457 -2.67932 6.80833 --1.04213 -3.05508 7.91754 --0.996647 -2.95629 8.00325 --0.78376 -2.52519 7.26701 --0.892419 -2.73339 8.11443 --0.739812 -2.42458 7.63018 --0.545614 -2.03433 6.85675 --0.524758 -1.98502 7.02698 --0.45111 -1.83298 6.88557 --0.614246 -2.14178 8.28763 --0.541394 -1.99028 8.19501 --0.50777 -1.91308 8.37689 --0.433981 -1.76141 8.26873 --0.35596 -1.60102 8.09884 --0.280269 -1.44571 7.92491 --0.227259 -1.33216 7.93283 --0.225507 -1.31427 8.47781 --0.178608 -1.21168 8.60117 --0.0705667 -0.999122 7.98263 -0.0281709 -0.807349 7.35837 -0.0805523 -0.698343 7.29423 -0.0809513 -0.676871 8.13221 -0.163869 -0.516267 7.52763 -0.216185 -0.407049 7.44746 -0.25877 -0.313063 7.61462 -0.311895 -0.205088 7.51038 -0.368581 -0.0957521 7.09406 --0.38088 -1.7602 -0.946225 --0.412709 -1.82247 -0.94622 --0.441111 -1.8785 -0.937637 --0.476443 -1.94874 -0.940717 --0.512757 -2.01882 -0.941695 --0.549113 -2.08978 -0.940427 --0.585513 -2.16164 -0.937011 --0.621896 -2.23339 -0.931398 --0.666252 -2.32018 -0.935496 --0.707181 -2.40073 -0.930817 --0.748151 -2.48216 -0.923692 --0.797024 -2.57758 -0.925128 --0.84699 -2.67477 -0.923265 --0.896992 -2.77281 -0.918156 --0.946969 -2.87069 -0.909951 --1.00953 -2.99346 -0.91324 --1.07558 -3.12407 -0.917118 --1.15519 -3.27941 -0.930488 --1.20278 -3.37243 -0.902316 --1.27096 -3.50626 -0.892703 --1.3391 -3.63986 -0.878495 --1.41635 -3.79113 -0.867653 --1.50163 -3.95909 -0.859233 --1.5754 -4.10382 -0.833621 --1.68336 -4.31485 -0.831316 --1.78331 -4.51059 -0.814507 --1.89584 -4.73179 -0.800253 --2.01849 -4.97133 -0.784018 --2.15019 -5.22822 -0.764656 --2.19509 -5.31465 -0.681259 --2.18284 -5.2874 -0.561745 --2.1867 -5.29382 -0.453265 --2.1985 -5.31505 -0.349503 --2.17935 -5.27322 -0.23106 --2.17632 -5.26499 -0.122053 --2.19037 -5.2902 -0.02058 --2.20785 -5.32227 0.080055 --2.22527 -5.35329 0.181639 --2.21427 -5.32946 0.291319 --2.22034 -5.33896 0.395662 --2.27541 -5.44525 0.491127 --3.89464 -8.6269 0.359882 --4.00492 -8.83911 0.517554 --2.25136 -5.38857 0.813956 --2.26657 -5.41654 0.919078 --8.30183 -17.2588 1.06687 --8.28922 -17.2268 1.40422 --8.26972 -17.1802 1.74009 --8.2616 -17.156 2.07596 --8.23193 -17.0902 2.40831 --8.33169 -17.2771 2.7646 --8.31554 -17.2363 3.10179 --8.30974 -17.2178 3.44185 --8.29247 -17.175 3.77884 --8.27744 -17.1361 4.11673 --8.26363 -17.1011 4.45572 --8.25106 -17.0699 4.79631 --8.22808 -17.0155 5.13248 --8.21983 -16.9899 5.47698 --8.19472 -16.9335 5.81433 --8.18533 -16.9059 6.16143 --8.14202 -16.813 6.48954 --8.13952 -16.8005 6.84515 --8.00448 -16.5278 7.10833 --8.19532 -16.8905 7.61235 --8.17462 -16.842 7.96695 --8.18996 -16.862 8.35423 --8.20537 -16.8837 8.7483 --8.19242 -16.8489 9.12185 --8.17258 -16.7996 9.49233 --8.16523 -16.7758 9.88049 --8.1455 -16.729 10.2615 --8.13579 -16.6999 10.6572 --8.13841 -16.6942 11.0734 --8.12865 -16.6655 11.4828 --8.10302 -16.6052 11.8789 --8.00652 -16.4102 12.1881 --8.04048 -16.4643 12.674 --7.91568 -16.2125 12.9466 --7.73572 -15.854 13.1342 --8.11944 -16.5826 14.1758 --7.98771 -16.3161 14.4526 --2.49314 -5.73999 5.91279 --2.2649 -5.29348 5.87024 --2.83013 -6.34484 8.21226 --2.3046 -5.33537 7.28285 --2.69681 -6.0791 8.41382 --2.14613 -5.02376 7.3477 --2.13898 -5.00505 7.55168 --2.09943 -4.92484 7.68009 --1.66151 -4.08776 6.74783 --1.59648 -3.95908 6.77224 --1.67744 -4.10702 7.20967 --1.68361 -4.11269 7.452 --1.42719 -3.62293 6.90007 --1.31786 -3.41223 6.77142 --1.26526 -3.30804 6.81274 --1.34804 -3.45848 7.319 --1.13232 -3.04718 6.79388 --1.19273 -3.15463 7.24368 --1.03611 -2.85648 6.89339 --0.892966 -2.58376 6.55987 --0.926587 -2.63953 6.93143 --1.08246 -2.92286 7.86491 --1.01982 -2.80024 7.88553 --0.829574 -2.44001 7.29053 --0.913164 -2.58727 8.00159 --0.784853 -2.34459 7.67126 --0.596509 -1.99057 6.96915 --0.746168 -2.25718 8.14606 --0.730391 -2.21869 8.4359 --0.614437 -1.99822 8.10777 --0.600675 -1.96283 8.43363 --0.514317 -1.79763 8.26974 --0.437794 -1.65024 8.15947 --0.375387 -1.52845 8.14289 --0.276689 -1.34369 7.80193 --0.235774 -1.25881 7.94532 --0.245539 -1.26101 8.63746 --0.152553 -1.0879 8.29721 --0.0986157 -0.979828 8.35776 -0.0391224 -0.73582 7.27687 -0.0330156 -0.726531 8.16466 -0.125197 -0.560371 7.54182 -0.181437 -0.451827 7.45284 -0.226867 -0.358954 7.60101 -0.282008 -0.254079 7.53785 -0.33767 -0.147267 7.35255 -0.392485 -0.0469779 7.07515 --0.406643 -1.70565 -0.949703 --0.440414 -1.76685 -0.950536 --0.473233 -1.82901 -0.949627 --0.501151 -1.87768 -0.9334 --0.541882 -1.95389 -0.942152 --0.576714 -2.01666 -0.935591 --0.614999 -2.08645 -0.933363 --0.653327 -2.15715 -0.928988 --0.692697 -2.22866 -0.922362 --0.73898 -2.31429 -0.925401 --0.782835 -2.39361 -0.919758 --0.838118 -2.49502 -0.928459 --0.88199 -2.57507 -0.917273 --0.934881 -2.67102 -0.914146 --0.995784 -2.78289 -0.918084 --1.05672 -2.89556 -0.918177 --1.11862 -3.00799 -0.91447 --1.1931 -3.14525 -0.920959 --1.26859 -3.2832 -0.9226 --1.31113 -3.35996 -0.883852 --1.39119 -3.50745 -0.881084 --1.46425 -3.63965 -0.864904 --1.54986 -3.79652 -0.855823 --1.64099 -3.962 -0.844876 --1.74021 -4.1451 -0.835101 --1.846 -4.33767 -0.822106 --1.9563 -4.53881 -0.80525 --2.08016 -4.7653 -0.790447 --2.20052 -4.98442 -0.764218 --2.32087 -5.20414 -0.72965 --2.5193 -5.56841 -0.731923 --2.70163 -5.90037 -0.710277 --2.91119 -6.2849 -0.689739 --3.13174 -6.68631 -0.658775 --3.38511 -7.14984 -0.626002 --3.63384 -7.60465 -0.573469 --3.95924 -8.19968 -0.529265 --4.08676 -8.42936 -0.401037 --4.07088 -8.39654 -0.225655 --4.07752 -8.40385 -0.0575363 --4.09212 -8.42682 0.108711 --4.05716 -8.3601 0.283178 --4.05024 -8.34215 0.451251 --4.03213 -8.30483 0.619185 --4.02193 -8.28217 0.785098 --4.01969 -8.27513 0.949939 --4.06365 -8.35254 1.11549 --8.65377 -16.7417 1.55828 --8.43524 -16.3352 1.87031 --8.36204 -16.1946 2.18622 --8.684 -16.7763 2.56426 --8.68272 -16.7657 2.89974 --8.66449 -16.7233 3.23193 --8.67114 -16.7281 3.57104 --8.67095 -16.7194 3.90962 --8.65736 -16.6875 4.24527 --8.65151 -16.668 4.58439 --8.66045 -16.6784 4.93189 --8.64893 -16.6481 5.27214 --8.64762 -16.638 5.61956 --8.63842 -16.6134 5.96531 --8.52931 -16.407 6.25498 --8.48299 -16.3135 6.57813 --8.44241 -16.2326 6.90534 --8.34908 -16.0553 7.19597 --8.46758 -16.2608 7.63934 --8.44042 -16.2043 7.98357 --8.66296 -16.5978 8.53431 --8.65921 -16.5833 8.91413 --8.64858 -16.5541 9.29169 --8.64248 -16.5343 9.67895 --8.63294 -16.5076 10.0679 --8.62347 -16.4825 10.4631 --8.61495 -16.4571 10.8647 --8.52146 -16.2787 11.1771 --8.37536 -16.0044 11.4261 --8.22721 -15.7285 11.6675 --8.21417 -15.6951 12.0742 --8.20889 -15.6754 12.4991 --8.16681 -15.5907 12.8824 --7.96507 -15.2177 13.044 --8.29654 -15.8032 13.9814 --8.24072 -15.6909 14.3726 --3.03333 -6.30372 8.14686 --2.92949 -6.1138 8.17896 --3.01133 -6.24711 8.8701 --2.25321 -4.89295 7.38738 --2.88995 -6.01847 9.13826 --1.8348 -4.1416 6.80621 --2.22292 -4.8238 8.00971 --1.77426 -4.02314 7.06394 --2.08005 -4.55883 8.12634 --1.57573 -3.66392 6.94431 --1.43734 -3.41497 6.75267 --1.35422 -3.26354 6.71174 --1.3681 -3.28196 6.97067 --1.23109 -3.03661 6.74528 --1.09534 -2.794 6.50341 --0.996063 -2.61619 6.36694 --0.951694 -2.53304 6.41877 --1.00276 -2.6163 6.84188 --0.949577 -2.51854 6.87571 --1.12078 -2.81063 7.8564 --1.07484 -2.72213 7.95752 --1.04219 -2.66034 8.13074 --0.872041 -2.3596 7.64685 --0.914347 -2.42353 8.18709 --0.833653 -2.27714 8.12249 --0.732442 -2.09612 7.93158 --0.702846 -2.03824 8.14377 --0.621213 -1.88979 8.04082 --0.593631 -1.83501 8.28922 --0.508911 -1.68244 8.1518 --0.45431 -1.58086 8.22368 --0.354984 -1.40717 7.94343 --0.271792 -1.25847 7.74644 --0.287084 -1.26992 8.44759 --0.240689 -1.18042 8.62996 --0.294275 -1.24841 9.98509 --0.0198598 -0.802633 7.51631 -0.0435998 -0.688706 7.40308 -0.0814839 -0.613814 7.66493 -0.139819 -0.507879 7.62703 -0.201932 -0.396684 7.4773 -0.256123 -0.298284 7.50488 -0.310227 -0.197947 7.49052 -0.37372 -0.0920265 7.07431 --0.490522 -1.75195 -0.933652 --0.533154 -1.8262 -0.945689 --0.572297 -1.8932 -0.948698 --0.612542 -1.96203 -0.949606 --0.644894 -2.01755 -0.93551 --0.689573 -2.09324 -0.938549 --0.72642 -2.15663 -0.926735 --0.772121 -2.23303 -0.925126 --0.821387 -2.3184 -0.926652 --0.87163 -2.40357 -0.925477 --0.92191 -2.4896 -0.921356 --0.976688 -2.58351 -0.919717 --1.0325 -2.6782 -0.914927 --1.09626 -2.7878 -0.917151 --1.1566 -2.89116 -0.910498 --1.23145 -3.01824 -0.91468 --1.30984 -3.15414 -0.918902 --1.37671 -3.26676 -0.904834 --1.44361 -3.38018 -0.886621 --1.52407 -3.51828 -0.877102 --1.60549 -3.65608 -0.862484 --1.70052 -3.81946 -0.854511 --1.79199 -3.97455 -0.836862 --1.90706 -4.17094 -0.831216 --2.01763 -4.36004 -0.814749 --2.13377 -4.55864 -0.794367 --2.27904 -4.80718 -0.784921 --2.42073 -5.0473 -0.7631 --2.58608 -5.33034 -0.745692 --2.77258 -5.64818 -0.727611 --2.97364 -5.99197 -0.704336 --3.20487 -6.3871 -0.681104 --3.45164 -6.80791 -0.64858 --3.70945 -7.24647 -0.603181 --3.99742 -7.73703 -0.550786 --4.38498 -8.39868 -0.509829 --4.80369 -9.11272 -0.450834 --5.31189 -9.9815 -0.384836 --5.8567 -10.9109 -0.291242 --4.30193 -8.24241 0.194021 --4.31529 -8.26145 0.360065 --4.33202 -8.28631 0.526121 --7.45954 -13.6319 0.492217 --8.55549 -15.5006 0.735208 --8.77683 -15.8718 1.04965 --8.8997 -16.0739 1.37533 --8.73652 -15.7874 1.68838 --8.626 -15.5923 1.99612 --8.58362 -15.5132 2.30629 --8.87613 -16.005 2.67367 --8.87834 -16.0017 3.00043 --8.80692 -15.8733 3.31025 --9.10463 -16.3716 3.72014 --9.06672 -16.3015 4.04641 --9.02647 -16.2257 4.37057 --9.00396 -16.1786 4.70039 --8.96818 -16.1105 5.02537 --8.95366 -16.0797 5.36006 --8.93677 -16.0431 5.69474 --8.84859 -15.8852 5.99287 --8.70372 -15.6321 6.25554 --8.67348 -15.5727 6.58019 --8.61111 -15.461 6.8855 --8.51852 -15.2951 7.16838 --8.63736 -15.4891 7.60137 --8.61824 -15.4493 7.94309 --8.9125 -15.9386 8.53774 --8.90436 -15.9168 8.90696 --8.87833 -15.8635 9.26519 --8.85789 -15.8205 9.63237 --8.82865 -15.7641 9.99602 --8.80586 -15.7158 10.3691 --8.84194 -15.7681 10.8091 --8.87344 -15.8113 11.2541 --8.51467 -15.1994 11.2672 --8.46967 -15.1141 11.6258 --8.42575 -15.0305 11.9895 --8.37298 -14.9327 12.3477 --8.36782 -14.915 12.7727 --8.18551 -14.6005 12.9644 --8.01975 -14.3124 13.1708 --8.44144 -15.0083 14.2383 --8.25784 -14.6896 14.4363 --3.21357 -6.21025 8.03215 --2.85608 -5.58231 8.812 --2.83002 -5.53316 9.02574 --2.62037 -5.17937 8.78995 --2.54273 -5.04566 8.87048 --1.80561 -3.82344 7.18944 --1.62091 -3.51366 6.90544 --1.49121 -3.29539 6.75213 --1.40982 -3.15716 6.72617 --1.3405 -3.03876 6.73043 --1.22088 -2.83736 6.5684 --1.08718 -2.61305 6.33947 --1.11082 -2.647 6.63729 --0.998028 -2.45795 6.46081 --1.03248 -2.51015 6.82248 --0.98394 -2.42487 6.88199 --1.16911 -2.71921 7.90155 --0.925006 -2.31886 7.16988 --0.790841 -2.09672 6.85725 --1.00964 -2.44066 8.17066 --0.67447 -1.89728 6.87437 --0.78781 -2.07079 7.76827 --0.782055 -2.05252 8.10315 --0.683753 -1.88825 7.93501 --0.780778 -2.03372 8.94906 --0.578582 -1.70568 8.12416 --0.528555 -1.61743 8.24538 --0.402936 -1.4108 7.81182 --0.322362 -1.27704 7.67446 --0.314638 -1.2534 8.14031 --0.299069 -1.21614 8.60734 --0.378947 -1.31892 10.1389 --0.260028 -1.12568 9.73058 -0.0053273 -0.722863 7.37563 -0.00332696 -0.708756 8.224 -0.116292 -0.533166 7.43232 -0.175251 -0.433351 7.39311 -0.229304 -0.338926 7.44151 -0.281725 -0.247072 7.59789 -0.345059 -0.142698 7.37279 -0.406548 -0.0447892 7.05551 --0.600355 -1.82728 -0.94811 --0.638075 -1.88796 -0.943431 --0.675781 -1.94855 -0.936954 --0.717939 -2.01612 -0.934905 --0.761137 -2.08451 -0.930505 --0.804318 -2.15279 -0.924007 --0.855472 -2.23612 -0.927121 --0.904196 -2.31314 -0.921452 --0.956365 -2.39713 -0.919019 --1.01849 -2.49597 -0.924688 --1.07173 -2.5816 -0.916058 --1.13938 -2.68906 -0.92016 --1.21158 -2.80532 -0.925395 --1.27483 -2.90739 -0.916679 --1.35353 -3.03212 -0.918543 --1.44574 -3.18058 -0.929749 --1.49209 -3.25408 -0.890831 --1.57638 -3.38907 -0.883837 --1.6662 -3.53271 -0.875874 --1.75154 -3.66913 -0.858689 --1.85685 -3.83696 -0.851719 --1.95317 -3.9896 -0.831048 --2.07859 -4.19138 -0.825456 --2.2005 -4.38581 -0.808838 --2.33798 -4.60548 -0.794163 --2.47539 -4.82473 -0.771098 --2.63848 -5.08683 -0.753535 --2.83364 -5.39844 -0.741599 --3.02427 -5.70257 -0.714947 --3.26156 -6.08155 -0.697167 --3.50441 -6.47058 -0.666234 --3.78937 -6.9263 -0.635699 --4.04967 -7.34102 -0.577835 --3.27807 -6.09806 -0.180489 --3.24718 -6.04598 -0.0433173 --3.24742 -6.04368 0.0837285 --3.20879 -5.97917 0.218126 --3.24344 -6.03138 0.336506 --3.21368 -5.98062 0.466042 --3.22951 -6.00371 0.587949 --7.23856 -12.4253 0.396369 --8.38336 -14.2538 0.600028 --8.78534 -14.8923 0.888268 --8.85749 -15.0001 1.1961 --8.84654 -14.9764 1.50424 --8.78461 -14.8719 1.80739 --8.73148 -14.7799 2.10774 --8.98659 -15.1818 2.45198 --8.99106 -15.1819 2.76731 --8.98671 -15.1686 3.08201 --8.93244 -15.0746 3.38475 --8.98015 -15.1446 3.71437 --8.96138 -15.1082 4.02752 --8.95588 -15.0927 4.34571 --8.93709 -15.0562 4.66026 --8.925 -15.0311 4.97863 --8.91605 -15.0087 5.29955 --8.89836 -14.9739 5.6184 --8.88733 -14.9505 5.94246 --8.85407 -14.8898 6.25571 --8.8419 -14.8643 6.58307 --8.77215 -14.7456 6.87606 --8.68379 -14.5997 7.15585 --8.80843 -14.7896 7.58278 --8.79288 -14.7588 7.92006 --8.87871 -14.8863 8.33881 --8.89065 -14.8983 8.70905 --8.86936 -14.8563 9.05695 --8.86361 -14.8405 9.42298 --8.85886 -14.8253 9.79526 --8.84524 -14.7958 10.165 --8.82825 -14.7603 10.5361 --8.80139 -14.7106 10.9037 --8.70179 -14.5457 11.1959 --8.63729 -14.4339 11.5264 --8.61798 -14.3947 11.9147 --8.51836 -14.2296 12.2105 --8.53967 -14.2541 12.662 --8.407 -14.0366 12.92 --8.20734 -13.7146 13.0832 --8.59883 -14.3204 14.0851 --8.47588 -14.1169 14.3732 --3.0585 -5.57141 8.25937 --3.03493 -5.52959 8.46389 --2.92714 -5.35709 8.49361 --2.88274 -5.28242 8.6577 --2.82627 -5.18863 8.79753 --2.70868 -5.00037 8.79276 --2.77225 -5.09303 9.23355 --1.84134 -3.64715 7.12079 --1.6905 -3.40846 6.93977 --1.32104 -2.83484 6.13313 --1.50143 -3.10838 6.84985 --1.40533 -2.95587 6.78564 --1.21375 -2.65783 6.41505 --1.16449 -2.57685 6.46956 --1.40268 -2.93671 7.49886 --1.05527 -2.40107 6.54697 --1.06778 -2.41541 6.82912 --1.01637 -2.33235 6.88772 --1.25546 -2.6896 8.11033 --0.85954 -2.08338 6.77964 --0.836099 -2.04116 6.95169 --0.775028 -1.94385 6.96566 --0.937289 -2.17993 8.05526 --0.840481 -2.02802 7.9395 --0.79622 -1.95425 8.08541 --0.890735 -2.08669 9.04144 --0.756432 -1.87805 8.71965 --0.607569 -1.64921 8.25668 --0.452763 -1.41231 7.68023 --0.388369 -1.30942 7.68959 --0.321847 -1.2027 7.67731 --0.371721 -1.26218 8.66244 --0.34234 -1.20805 9.08167 --0.296824 -1.1277 9.40227 --0.13768 -0.890896 8.48536 --0.0483228 -0.752707 8.24569 -0.0647847 -0.586176 7.59512 -0.134781 -0.477346 7.44775 -0.185941 -0.3908 7.61691 -0.245136 -0.295731 7.68457 -0.312667 -0.191572 7.5007 -0.381181 -0.0894923 7.1345 --0.672363 -1.82504 -0.950156 --0.713009 -1.88449 -0.944513 --0.752703 -1.94491 -0.937027 --0.796788 -2.0113 -0.933819 --0.841914 -2.07852 -0.92846 --0.895951 -2.15973 -0.932857 --0.945562 -2.23476 -0.92848 --1.00067 -2.31763 -0.92728 --1.05577 -2.40037 -0.923283 --1.11635 -2.49092 -0.921762 --1.17251 -2.5753 -0.911769 --1.24754 -2.6885 -0.919335 --1.3236 -2.80244 -0.922751 --1.40067 -2.9171 -0.921919 --1.48775 -3.04747 -0.926244 --1.57039 -3.17161 -0.920997 --1.62862 -3.25881 -0.889423 --1.71683 -3.39243 -0.879862 --1.81144 -3.53265 -0.869526 --1.91608 -3.68943 -0.861602 --2.01079 -3.8321 -0.840032 --2.13197 -4.01391 -0.831049 --2.25866 -4.20423 -0.8183 --2.39186 -4.40297 -0.801381 --2.54611 -4.63477 -0.788881 --2.70685 -4.87489 -0.770114 --2.88313 -5.14009 -0.750093 --3.08793 -5.44581 -0.732263 --3.29275 -5.75292 -0.702148 --3.45447 -5.99594 -0.64178 --3.4767 -6.02557 -0.518099 --3.44826 -5.98115 -0.376527 --3.42415 -5.94168 -0.238983 --3.40998 -5.91692 -0.106646 --3.37718 -5.86605 0.028568 --3.34871 -5.82013 0.159954 --3.3357 -5.79761 0.286202 --3.3868 -5.87308 0.400948 --3.39915 -5.88833 0.523445 --3.39841 -5.88623 0.647589 --3.39096 -5.87251 0.771611 --3.39447 -5.87421 0.894774 --3.38485 -5.85765 1.01794 --9.60117 -15.183 1.35432 --9.07793 -14.3921 1.63836 --8.9624 -14.2121 1.92938 --8.88229 -14.0873 2.21808 --9.22045 -14.5871 2.56929 --9.22838 -14.5943 2.87949 --9.17892 -14.5133 3.1781 --9.42329 -14.8722 3.54989 --9.59172 -15.1187 3.91696 --9.53783 -15.0314 4.22523 --9.54562 -15.0378 4.55381 --9.58404 -15.0877 4.89628 --9.3257 -14.695 5.11966 --9.57848 -15.0662 5.5592 --9.52464 -14.9798 5.86983 --9.15226 -14.4183 6.01473 --9.04133 -14.2463 6.28175 --9.0237 -14.2126 6.59895 --8.93374 -14.073 6.87403 --8.87333 -13.9759 7.16556 --8.9918 -14.1457 7.58073 --8.96542 -14.1002 7.90359 --11.4162 -17.7361 10.1207 --11.3957 -17.6972 10.5454 --11.3807 -17.6665 10.9799 --9.94655 -15.5281 10.176 --11.173 -17.3393 11.7034 --9.26534 -14.5018 10.3436 --9.15658 -14.3337 10.628 --9.38927 -14.6703 11.2641 --9.05605 -14.1691 11.3185 --8.82031 -13.8122 11.4613 --8.79031 -13.7605 11.8326 --8.67813 -13.585 12.1097 --8.70929 -13.6237 12.5668 --8.58517 -13.4323 12.8344 --8.39986 -13.1505 13.0193 --8.76172 -13.6757 13.961 --8.68986 -13.5608 14.3231 --3.12247 -5.32913 7.94981 --3.10552 -5.29776 8.15809 --3.00283 -5.14435 8.20101 --3.08591 -5.26045 8.63089 --3.07653 -5.24158 8.8811 --2.89332 -4.96846 8.74619 --2.8253 -4.8643 8.8662 --2.07835 -3.77281 7.33208 --1.97175 -3.61452 7.29624 --1.46757 -2.87835 6.21001 --1.4121 -2.79328 6.25356 --1.71585 -3.2289 7.31363 --1.64398 -3.12025 7.34687 --1.54835 -2.97749 7.30817 --1.5294 -2.94496 7.50176 --1.12655 -2.36189 6.44118 --1.09269 -2.30824 6.55292 --1.09435 -2.30596 6.79913 --1.05508 -2.24561 6.91089 --1.61068 -3.03136 9.36194 --1.13178 -2.34203 7.78581 --0.870419 -1.96594 6.99062 --1.04813 -2.21031 8.09647 --0.916506 -2.01824 7.8419 --0.844788 -1.91055 7.85567 --0.781608 -1.81515 7.91457 --0.913807 -1.99051 9.07184 --0.752627 -1.75717 8.61336 --0.565513 -1.49064 7.92536 --0.478015 -1.36018 7.81083 --0.374991 -1.21102 7.5663 --0.407204 -1.2442 8.35466 --0.374012 -1.18773 8.70466 --0.378722 -1.17918 9.47793 --0.297025 -1.05652 9.5025 --0.104823 -0.792371 8.24678 --0.0322158 -0.683561 8.22354 -0.0904051 -0.515581 7.45198 -0.156195 -0.417166 7.39286 -0.21896 -0.32373 7.39149 -0.272307 -0.237986 7.60783 -0.346942 -0.134202 7.243 -0.410645 -0.0425163 7.04565 --0.729914 -1.81629 -0.944926 --0.771491 -1.87464 -0.938528 --0.817521 -1.93997 -0.936459 --0.860125 -1.99906 -0.926012 --0.911584 -2.07117 -0.925769 --0.963144 -2.14515 -0.922931 --1.02455 -2.23203 -0.929194 --1.08252 -2.31266 -0.926679 --1.145 -2.40117 -0.926746 --1.19859 -2.47649 -0.912912 --1.26659 -2.57364 -0.91201 --1.34547 -2.68451 -0.917658 --1.4299 -2.80411 -0.924135 --1.50544 -2.9105 -0.916412 --1.61624 -3.06733 -0.937072 --1.66646 -3.13859 -0.898133 --1.75398 -3.26114 -0.886819 --1.84598 -3.3914 -0.87489 --1.93899 -3.52237 -0.858013 --2.05399 -3.6846 -0.851341 --2.16894 -3.84653 -0.838277 --2.29597 -4.02581 -0.825768 --2.42844 -4.21259 -0.809543 --2.58292 -4.43141 -0.79838 --2.73938 -4.65067 -0.778568 --2.91689 -4.90288 -0.761077 --3.11287 -5.17895 -0.741369 --3.33179 -5.48666 -0.720325 --3.59032 -5.85234 -0.702831 --3.82776 -6.18602 -0.661643 --3.57326 -5.82399 -0.434124 --3.56026 -5.8021 -0.300535 --3.5517 -5.78711 -0.169776 --3.55749 -5.79359 -0.0445581 --3.56322 -5.79907 0.0806105 --3.56783 -5.80262 0.205775 --3.54179 -5.76365 0.335619 --3.53115 -5.74703 0.461175 --3.5775 -5.81056 0.579903 --3.60515 -5.84695 0.702457 --9.00778 -13.4812 0.593432 --9.11658 -13.6299 0.880338 --9.11353 -13.6197 1.17167 --9.10071 -13.597 1.46232 --9.09213 -13.5781 1.75258 --9.06285 -13.5315 2.04052 --9.17373 -13.6832 2.34651 --9.36883 -13.953 2.67399 --9.37111 -13.949 2.97568 --9.25977 -13.7875 3.25292 --9.74884 -14.469 3.68023 --9.87143 -14.6357 4.03271 --9.55669 -14.1883 4.25396 --9.55353 -14.178 4.56731 --9.57547 -14.2027 4.8922 --9.45313 -14.0242 5.16061 --9.45225 -14.0117 5.79918 --9.27203 -13.7513 6.03018 --9.1444 -13.567 6.28194 --9.04841 -13.4263 6.54651 --8.95573 -13.2904 6.81004 --8.83254 -13.1123 7.05203 --9.11942 -13.5068 7.56748 --9.10744 -13.4842 7.89458 --8.89037 -13.1737 8.07086 --11.5556 -16.8933 10.5015 --11.5406 -16.8631 10.9273 --10.1137 -14.8625 10.1474 --8.99563 -13.2938 9.5443 --8.99222 -13.2832 9.90489 --9.09645 -13.421 10.3763 --8.94265 -13.1994 10.6021 --8.95649 -13.212 10.9994 --8.94959 -13.1954 11.3839 --8.9197 -13.145 11.7488 --8.81263 -12.988 12.0297 --8.83066 -13.0065 12.4643 --8.75834 -12.8982 12.7958 --8.55673 -12.6102 12.9616 --8.94918 -13.1464 13.9292 --8.86575 -13.021 14.2738 --3.2833 -5.25146 8.10656 --3.17349 -5.09576 8.1438 --3.15131 -5.06071 8.35156 --3.05126 -4.91863 8.40567 --3.09057 -4.96721 8.7535 --2.99154 -4.82586 8.81195 --2.24393 -3.79762 7.37856 --2.09134 -3.58362 7.2478 --1.97231 -3.41643 7.18418 --1.81566 -3.19855 7.01515 --1.44377 -2.68791 6.25644 --1.72543 -3.06671 7.23525 --1.28946 -2.47077 6.23165 --1.24075 -2.39944 6.29314 --1.20719 -2.35073 6.40602 --1.17779 -2.30594 6.53606 --1.13021 -2.23784 6.61214 --1.09652 -2.18833 6.7412 --1.06599 -2.14277 6.88811 --1.02361 -2.0807 6.99806 --0.912866 -1.92675 6.83915 --0.850277 -1.83814 6.86163 --0.982416 -2.0076 7.75359 --0.890818 -1.8792 7.68328 --0.846041 -1.81409 7.83723 --0.984292 -1.98761 8.96342 --0.858571 -1.81336 8.74691 --0.667767 -1.55704 8.12046 --0.534191 -1.37352 7.75656 --0.451469 -1.25951 7.68873 --0.388554 -1.16824 7.74483 --0.439155 -1.22161 8.71054 --0.403712 -1.16429 9.10053 --0.336884 -1.06749 9.27317 --0.153072 -0.826512 8.22771 --0.0796474 -0.723241 8.23538 -0.0461252 -0.559434 7.5453 -0.119925 -0.456378 7.42772 -0.170944 -0.379414 7.68666 -0.244589 -0.278563 7.56488 -0.31498 -0.181636 7.44092 -0.386478 -0.0847807 7.13483 --0.750103 -1.7522 -0.951419 --0.793623 -1.80947 -0.94586 --0.836131 -1.86672 -0.938408 --0.880679 -1.92475 -0.928999 --0.933086 -1.99586 -0.93 --0.987468 -2.06672 -0.928494 --1.04635 -2.14551 -0.930268 --1.10082 -2.21811 -0.923369 --1.16072 -2.29755 -0.919596 --1.23151 -2.39078 -0.923771 --1.29694 -2.47888 -0.919129 --1.3688 -2.5737 -0.916408 --1.45606 -2.69023 -0.925016 --1.53443 -2.79355 -0.919524 --1.62274 -2.91159 -0.919339 --1.72303 -3.04517 -0.923702 --1.78707 -3.12901 -0.892147 --1.87745 -3.24926 -0.87862 --1.98419 -3.39097 -0.872621 --2.09852 -3.54216 -0.864795 --2.20635 -3.68623 -0.847157 --2.33809 -3.86038 -0.838167 --2.4644 -4.02832 -0.818611 --2.60815 -4.21942 -0.802084 --2.78134 -4.44925 -0.793136 --2.96101 -4.68738 -0.777522 --3.14722 -4.9348 -0.754791 --3.35733 -5.21287 -0.732169 --3.60787 -5.54594 -0.714838 --3.72608 -5.70119 -0.631689 --3.7613 -5.74635 -0.513351 --4.49537 -6.72438 -0.619729 --4.85571 -7.20183 -0.573115 --5.3055 -7.7994 -0.529408 --5.78564 -8.43634 -0.467007 --6.37358 -9.21594 -0.399054 --7.01591 -10.0683 -0.306674 --7.13228 -10.2196 -0.101382 --7.28236 -10.4149 0.105935 --7.6222 -10.8639 0.305084 --8.62136 -12.1889 0.485963 --9.1689 -12.9117 0.737139 --9.28142 -13.0554 1.01932 --9.27631 -13.0436 1.30425 --9.24942 -13.003 1.58771 --9.22683 -12.9673 1.87012 --9.09221 -12.7846 2.13853 --9.26125 -13.003 2.44415 --9.30727 -13.0588 2.73872 --9.29561 -13.0383 3.02507 --9.27524 -13.0064 3.3099 --9.27009 -12.9944 3.59862 --9.25618 -12.9699 3.88597 --9.23904 -12.9417 4.17301 --9.22957 -12.9248 4.46406 --9.20596 -12.8889 4.75087 --9.19741 -12.8709 5.04438 --9.18469 -12.85 5.33852 --9.17512 -12.8319 5.63572 --9.16224 -12.8089 5.93346 --9.14613 -12.782 6.23178 --9.13216 -12.7578 6.53376 --9.06937 -12.6697 6.80899 --8.95878 -12.5179 7.05327 --9.15965 -12.7773 7.50303 --9.14235 -12.7487 7.81728 --9.06644 -12.6424 8.09161 --9.1738 -12.7778 8.50731 --9.16178 -12.7551 8.83901 --9.14545 -12.7275 9.17214 --9.13557 -12.708 9.51583 --9.12132 -12.6827 9.8613 --9.11358 -12.6665 10.2184 --9.09597 -12.636 10.5722 --9.08817 -12.62 10.9436 --9.077 -12.5982 11.3173 --9.04522 -12.5492 11.6763 --8.97879 -12.4548 12.0019 --8.9524 -12.4136 12.3798 --8.92695 -12.3719 12.7653 --8.71346 -12.0853 12.9184 --9.05207 -12.5197 13.7994 --9.03076 -12.4837 14.2272 --8.77299 -12.1402 14.3291 --3.46255 -5.2064 7.36084 --3.3576 -5.06581 7.41087 --3.29044 -4.97511 7.52153 --3.25558 -4.9258 7.68865 --3.38651 -5.09108 8.16057 --3.33543 -5.02121 8.31703 --3.21642 -4.86164 8.3424 --3.20078 -4.83711 8.57296 --3.15601 -4.77388 8.74952 --1.66066 -2.83959 5.78551 --1.62842 -2.79533 5.88801 --2.03087 -3.31038 7.00622 --1.96508 -3.2219 7.07024 --1.54333 -2.67655 6.24275 --1.88276 -3.10778 7.32772 --1.43681 -2.53241 6.36659 --1.41408 -2.50023 6.51722 --1.29393 -2.34237 6.38807 --1.28078 -2.32202 6.5717 --1.22902 -2.25054 6.64017 --1.16672 -2.16805 6.68038 --1.09476 -2.07199 6.68241 --1.06757 -2.0334 6.8464 --0.977546 -1.91473 6.78029 --0.91518 -1.83063 6.81282 --0.860311 -1.75735 6.88077 --0.948398 -1.86193 7.57716 --0.940791 -1.8453 7.90148 --0.88763 -1.77259 8.03686 --0.959759 -1.85322 8.83117 --0.752638 -1.59012 8.17943 --0.621657 -1.42202 7.88569 --0.526476 -1.29703 7.77107 --0.447118 -1.19198 7.74095 --0.448954 -1.18444 8.29528 --0.429476 -1.15043 8.78246 --0.404283 -1.10722 9.29998 --0.334386 -1.01013 9.48219 --0.127858 -0.758385 8.23658 --0.0525317 -0.65831 8.26301 -0.0826942 -0.494051 7.45199 -0.14738 -0.40618 7.50253 -0.158131 -0.371057 8.64864 -0.283751 -0.224567 7.52828 -0.364841 -0.125152 7.10344 -0.428956 -0.0395946 7.06619 --0.630699 -1.51775 -0.953061 --0.67409 -1.57236 -0.954142 --0.714054 -1.62073 -0.946546 --0.753068 -1.67007 -0.937307 --0.801944 -1.73243 -0.939566 --0.851742 -1.79363 -0.939872 --0.897237 -1.85065 -0.931507 --0.947061 -1.91264 -0.927469 --1.00239 -1.98251 -0.927306 --1.06416 -2.05918 -0.930463 --1.12051 -2.12973 -0.925052 --1.1877 -2.21311 -0.928437 --1.24952 -2.29136 -0.923105 --1.31784 -2.37736 -0.920145 --1.39153 -2.46916 -0.919261 --1.47176 -2.56966 -0.919801 --1.56288 -2.68384 -0.92629 --1.64417 -2.78588 -0.918736 --1.74723 -2.91542 -0.925779 --1.84141 -3.03174 -0.918523 --1.91282 -3.12128 -0.889433 --2.0125 -3.24607 -0.877712 --2.11865 -3.37845 -0.864967 --2.24871 -3.54097 -0.862068 --2.36684 -3.68947 -0.845133 --2.49792 -3.85329 -0.829146 --2.64095 -4.03243 -0.813113 --2.81435 -4.24926 -0.805402 --2.97681 -4.45197 -0.782552 --3.18162 -4.70784 -0.770974 --3.3929 -4.97194 -0.751232 --3.61714 -5.252 -0.725197 --3.90871 -5.61694 -0.712685 --4.21319 -5.99758 -0.688788 --4.54912 -6.41812 -0.658277 --4.88596 -6.8387 -0.609435 --5.27817 -7.32998 -0.557084 --5.76456 -7.93699 -0.505416 --6.33771 -8.65368 -0.445275 --6.93566 -9.40163 -0.357971 --7.224 -9.75905 -0.190062 --7.49279 -10.0927 -0.00405061 --7.56624 -10.1817 0.215364 --7.91187 -10.6111 0.4194 --9.27242 -12.3114 0.600337 --9.38988 -12.4532 0.873857 --9.38046 -12.436 1.15188 --9.39818 -12.4532 1.43041 --9.36935 -12.4131 1.70686 --9.36217 -12.3998 1.98409 --9.31489 -12.336 2.25643 --9.43324 -12.4777 2.55207 --9.4358 -12.4766 2.83429 --9.42312 -12.4554 3.1143 --9.41268 -12.4381 3.39541 --9.40006 -12.4179 3.67657 --9.38414 -12.3929 3.95766 --9.36499 -12.3641 4.23844 --9.36097 -12.3541 4.52548 --9.34826 -12.3327 4.81078 --9.32585 -12.3 5.09375 --9.31857 -12.286 5.38456 --9.30153 -12.2597 5.67319 --9.28771 -12.237 5.96513 --9.27603 -12.217 6.26063 --9.25466 -12.1857 6.55359 --9.1717 -12.0776 6.81185 --9.08653 -11.9658 7.06691 --9.29293 -12.217 7.51411 --9.27474 -12.1898 7.82301 --9.20138 -12.0924 8.09519 --9.30069 -12.2099 8.49883 --9.28772 -12.1874 8.82514 --9.27043 -12.1602 9.15287 --9.26498 -12.1475 9.49603 --9.23364 -12.1032 9.82161 --9.22488 -12.0863 10.1732 --9.201 -12.0506 10.5163 --9.17813 -12.0156 10.8662 --9.16064 -11.9877 11.2284 --9.14308 -11.9594 11.5981 --9.08563 -11.8812 11.9292 --9.07339 -11.8596 12.3195 --9.05571 -11.8311 12.7122 --8.85075 -11.5706 12.8768 --8.68785 -11.3632 13.0907 --3.68186 -5.20467 6.74411 --3.61502 -5.11902 6.85372 --3.53741 -5.01974 6.94776 --3.47278 -4.93784 7.05997 --3.53795 -5.01364 7.37359 --3.51297 -4.97997 7.55697 --3.02017 -4.3721 6.96444 --2.86551 -4.17965 6.90721 --3.61561 -5.09279 8.45392 --2.61315 -3.86403 6.86399 --3.05739 -4.40257 7.92281 --3.00657 -4.33624 8.06814 --1.73587 -2.78548 5.71306 --1.72198 -2.76621 5.85568 --2.27141 -3.43046 7.2448 --1.62031 -2.63648 5.98617 --1.59454 -2.60172 6.11182 --1.5421 -2.53538 6.17834 --1.5195 -2.50463 6.32033 --2.89638 -4.16125 10.1937 --1.36553 -2.31203 6.32617 --1.72822 -2.74498 7.59073 --2.49013 -3.65415 10.1537 --1.1645 -2.05893 6.39566 --1.18851 -2.0839 6.71247 --1.12745 -2.00603 6.75912 --0.872436 -1.69725 6.11598 --0.964095 -1.80276 6.7083 --0.945395 -1.77553 6.91618 --1.01211 -1.84891 7.49912 --0.920286 -1.73471 7.44623 --1.10332 -1.94273 8.65147 --1.01753 -1.8359 8.68539 --0.940048 -1.73681 8.75511 --0.718087 -1.47109 8.03263 --0.618003 -1.34882 7.93002 --0.516934 -1.22421 7.79485 --0.444065 -1.13248 7.83202 --0.494333 -1.1788 8.77846 --0.468354 -1.13761 9.27675 --0.419265 -1.07006 9.66713 --0.172862 -0.786174 8.18774 --0.0977342 -0.691065 8.23514 -0.0436265 -0.528125 7.46568 -0.119148 -0.433738 7.39788 -0.180786 -0.355337 7.55714 -0.254254 -0.26305 7.50517 -0.32943 -0.171436 7.40126 -0.406597 -0.0794273 7.08525 --0.726303 -1.55802 -0.951031 --0.767259 -1.60628 -0.942631 --0.808203 -1.65447 -0.932632 --0.858948 -1.71467 -0.934082 --0.915141 -1.78177 -0.939755 --0.962503 -1.83663 -0.93048 --1.01972 -1.90444 -0.931504 --1.07791 -1.97207 -0.930027 --1.13621 -2.04157 -0.925954 --1.19988 -2.11692 -0.925056 --1.26899 -2.1991 -0.926983 --1.33468 -2.27504 -0.920232 --1.40486 -2.35885 -0.915763 --1.48792 -2.45627 -0.918434 --1.57641 -2.56045 -0.922232 --1.66598 -2.66635 -0.921731 --1.74368 -2.75926 -0.907645 --1.86344 -2.89917 -0.921657 --1.96054 -3.0142 -0.912238 --2.04019 -3.10737 -0.885608 --2.15017 -3.23664 -0.875489 --2.27212 -3.38136 -0.867721 --2.38858 -3.5189 -0.850336 --2.52988 -3.68546 -0.841442 --2.67218 -3.85261 -0.825503 --2.83287 -4.04185 -0.812239 --3.01298 -4.25405 -0.800097 --3.19959 -4.47458 -0.781689 --3.4066 -4.71787 -0.7619 --3.62552 -4.97624 -0.736873 --3.73938 -5.10895 -0.659271 --3.64557 -4.99547 -0.501881 --3.4859 -4.80497 -0.329269 --3.43214 -4.73853 -0.19829 --3.42707 -4.7302 -0.0846985 --3.43292 -4.73643 0.025189 --3.43111 -4.73203 0.136296 --3.42282 -4.71996 0.248277 --3.38648 -4.67531 0.363643 --3.45816 -4.75838 0.461904 --8.09741 -10.2391 0.0688803 --8.07001 -10.2029 0.306282 --3.43451 -4.72543 0.791108 --9.51318 -11.898 0.734619 --9.60751 -12.0052 1.00696 --9.63384 -12.032 1.28232 --9.63104 -12.0246 1.55757 --9.60012 -11.9828 1.83062 --9.4366 -11.7853 2.08806 --9.65701 -12.041 2.38911 --9.7393 -12.1329 2.68032 --9.73323 -12.1214 2.96026 --9.73789 -12.1221 3.24328 --9.73932 -12.119 3.52689 --9.72999 -12.1035 3.80931 --9.72493 -12.0927 4.09399 --9.72849 -12.0922 4.38315 --9.71696 -12.0737 4.6688 --9.70757 -12.058 4.95721 --9.71332 -12.061 5.25387 --9.70384 -12.0441 5.54633 --9.69658 -12.0308 5.84239 --9.69791 -12.0277 6.14542 --9.65943 -11.9778 6.43052 --9.67249 -11.9875 6.74559 --9.44475 -11.7156 6.92317 --9.76418 -12.0844 7.43091 --9.76423 -12.0784 7.75431 --9.64079 -11.9293 7.99823 --9.90511 -12.2327 8.51633 --9.8847 -12.2036 8.84435 --9.88463 -12.1974 9.19177 --9.87912 -12.1844 9.54122 --9.86831 -12.1666 9.8928 --9.85955 -12.1504 10.2513 --9.839 -12.121 10.6065 --9.83119 -12.105 10.9792 --9.81801 -12.0831 11.3543 --9.80477 -12.061 11.7371 --9.65752 -11.883 11.9844 --9.69244 -11.9169 12.4326 --9.647 -11.8582 12.8016 --9.3765 -11.5363 12.9068 --9.77536 -11.993 13.8316 --3.62551 -4.85834 6.39365 --3.66287 -4.89923 6.63605 --3.61021 -4.834 6.76159 --3.31056 -4.48403 6.53809 --3.36602 -4.54521 6.81447 --3.2408 -4.3977 6.82666 --3.10272 -4.23423 6.81224 --3.01066 -4.12482 6.86531 --2.94001 -4.04051 6.95233 --2.85647 -3.94016 7.01462 --3.09199 -4.20807 7.65631 --1.85997 -2.78875 5.57692 --1.82161 -2.74158 5.66452 --1.77685 -2.68722 5.7432 --1.73857 -2.64174 5.83718 --2.31111 -3.29304 7.25729 --2.90756 -3.97127 8.8331 --1.59571 -2.46858 6.06454 --1.57647 -2.44426 6.21438 --1.95646 -2.87325 7.37595 --1.87845 -2.78027 7.42444 --1.84177 -2.73343 7.58435 --2.59376 -3.58252 9.99539 --1.25995 -2.06577 6.42468 --1.19609 -1.99049 6.46304 --1.24955 -2.04681 6.88024 --1.12112 -1.89816 6.71703 --0.910466 -1.65745 6.24508 --1.02381 -1.7805 6.92275 --0.978747 -1.72487 7.04762 --1.00514 -1.74835 7.4724 --1.20041 -1.95975 8.6754 --1.11588 -1.85885 8.72975 --1.06592 -1.79658 8.95408 --0.813089 -1.51072 8.14947 --0.694418 -1.37323 7.97167 --0.595738 -1.25903 7.88669 --0.498158 -1.14539 7.78893 --0.540323 -1.18153 8.62706 --0.444599 -1.07001 8.58549 --0.446324 -1.0586 9.31905 --0.365575 -0.961105 9.46191 --0.144739 -0.721245 8.21657 --0.0647068 -0.626979 8.25296 -0.0781166 -0.471215 7.46192 -0.144665 -0.390516 7.57237 -0.203641 -0.316081 7.8507 -0.296325 -0.212252 7.48853 -0.380531 -0.1191 7.16369 -0.452141 -0.0364583 7.05654 --0.777455 -1.54272 -0.947575 --0.82475 -1.59591 -0.94509 --0.867621 -1.64293 -0.934133 --0.92564 -1.70698 -0.941143 --0.973947 -1.76082 -0.932811 --1.02764 -1.82057 -0.928853 --1.08679 -1.88721 -0.928718 --1.14691 -1.95366 -0.926082 --1.21247 -2.02696 -0.926671 --1.28446 -2.10704 -0.930081 --1.35104 -2.181 -0.924823 --1.42411 -2.26271 -0.922036 --1.49815 -2.3442 -0.915948 --1.59492 -2.45224 -0.9269 --1.68632 -2.55512 -0.928436 --1.76785 -2.64489 -0.916276 --1.8667 -2.75517 -0.914286 --1.97846 -2.87993 -0.916589 --2.07936 -2.99162 -0.905002 --2.16838 -3.09035 -0.880428 --2.28759 -3.22314 -0.871765 --2.41433 -3.36442 -0.861224 --2.54745 -3.51222 -0.848311 --2.68809 -3.66844 -0.832521 --2.84706 -3.84579 -0.819955 --3.0264 -4.04506 -0.809155 --3.21323 -4.25261 -0.792483 --3.41941 -4.48204 -0.775185 --3.62657 -4.7119 -0.747645 --3.60215 -4.68295 -0.619499 --3.59498 -4.67346 -0.500274 --3.60711 -4.68423 -0.388412 --3.70767 -4.79637 -0.304516 --5.29008 -6.56247 -0.628529 --3.58025 -4.64948 -0.0392965 --3.54618 -4.60951 0.0801219 --3.50459 -4.561 0.198762 --3.49425 -4.54812 0.309285 --3.54201 -4.60041 0.41025 --3.51653 -4.56932 0.522163 --3.54172 -4.59667 0.627533 --3.6001 -4.65919 0.731888 --3.60372 -4.66157 0.841169 --10.2993 -12.1172 0.85871 --10.3287 -12.1454 1.14338 --10.3483 -12.1622 1.42911 --10.3498 -12.1599 1.71486 --10.3555 -12.1624 2.00138 --10.2452 -12.0342 2.27496 --10.4636 -12.2731 2.59079 --10.4853 -12.2923 2.88547 --10.4781 -12.2793 3.17653 --10.473 -12.2691 3.46895 --10.4777 -12.2702 3.76511 --10.4597 -12.2448 4.05668 --10.4707 -12.2523 4.35791 --10.4581 -12.2343 4.65399 --10.4487 -12.2191 4.95274 --10.4286 -12.1925 5.24945 --10.4256 -12.1836 5.55426 --10.4375 -12.1914 5.86843 --10.426 -12.1739 6.17555 --10.3855 -12.1245 6.47078 --10.392 -12.1263 6.79191 --10.1609 -11.8668 6.98561 --10.5046 -12.2406 7.50569 --10.4972 -12.2277 7.835 --10.3817 -12.0942 8.09807 --10.6417 -12.3759 8.61387 --10.6448 -12.3742 8.96885 --10.6308 -12.3527 9.31722 --10.6232 -12.3394 9.67635 --10.6113 -12.3202 10.0375 --10.595 -12.2962 10.4004 --10.5904 -12.2846 10.7803 --10.5806 -12.2683 11.1627 --10.5588 -12.2377 11.5418 --10.5318 -12.2024 11.9229 --10.3776 -12.0264 12.181 --10.4614 -12.1125 12.6896 --10.2559 -11.8789 12.8965 --10.027 -11.6212 13.072 --3.9207 -4.92868 6.31483 --3.81184 -4.80697 6.37337 --3.82131 -4.81434 6.57716 --3.80725 -4.79528 6.75633 --3.72608 -4.70331 6.8488 --3.73648 -4.71081 7.06922 --3.48283 -4.43092 6.9137 --3.33361 -4.26525 6.89658 --3.21323 -4.13209 6.91703 --3.12148 -4.02832 6.97719 --3.20095 -4.11089 7.31889 --2.98596 -3.87437 7.17221 --2.93998 -3.82119 7.30951 --1.95087 -2.74496 5.70185 --1.87124 -2.65566 5.71866 --1.83301 -2.61115 5.81329 --1.78427 -2.55708 5.89095 --1.72372 -2.48795 5.94275 --1.68551 -2.44416 6.04302 --2.20854 -3.00425 7.44094 --1.9911 -2.76699 7.17066 --1.9917 -2.76379 7.41651 --1.93406 -2.69769 7.52505 --1.84575 -2.59831 7.55331 --2.75099 -3.56236 10.3722 --1.2462 -1.95008 6.36723 --1.16037 -1.85426 6.34092 --1.24003 -1.93607 6.83948 --1.10992 -1.79264 6.67411 --1.05147 -1.7265 6.744 --1.00771 -1.67584 6.86832 --0.975465 -1.63777 7.04832 --1.06879 -1.73044 7.75597 --1.18153 -1.84219 8.62161 --1.18823 -1.84296 9.1036 --0.997486 -1.6369 8.67726 --0.788399 -1.41339 8.09914 --0.706455 -1.3204 8.13247 --0.565526 -1.16871 7.82324 --0.529273 -1.12388 8.12423 --0.537964 -1.12256 8.78755 --0.452709 -1.02715 8.85338 --0.447981 -1.0101 9.60734 --0.188477 -0.743073 8.1479 --0.108644 -0.653777 8.20516 -0.0392127 -0.501782 7.46563 -0.127352 -0.406065 7.29843 -0.185932 -0.336583 7.55728 -0.262261 -0.251524 7.56532 -0.349586 -0.159016 7.27173 -0.427828 -0.0746616 7.06562 --0.834767 -1.52938 -0.950582 --0.88393 -1.58041 -0.947188 --0.927792 -1.62732 -0.935227 --0.982332 -1.68417 -0.934608 --1.03797 -1.74286 -0.931787 --1.0936 -1.80144 -0.92667 --1.16101 -1.87183 -0.931492 --1.22305 -1.93709 -0.927498 --1.29148 -2.00815 -0.926772 --1.35994 -2.08007 -0.923101 --1.43483 -2.15875 -0.922051 --1.78795 -2.52971 -0.923978 --1.87778 -2.62412 -0.914628 --1.98688 -2.73791 -0.914988 --2.11434 -2.87308 -0.923665 --2.19435 -2.95597 -0.89243 --2.3045 -3.07199 -0.878255 --2.42851 -3.20135 -0.866819 --2.55903 -3.33924 -0.853411 --2.71627 -3.50402 -0.848284 --2.86163 -3.65578 -0.828972 --3.04669 -3.8499 -0.822386 --3.23174 -4.04458 -0.80696 --3.43809 -4.26005 -0.791548 --3.65835 -4.49051 -0.771785 --3.90544 -4.75043 -0.751765 --3.9465 -4.79178 -0.644581 --3.92648 -4.76954 -0.515471 --4.21408 -5.07058 -0.484001 --4.52303 -5.39398 -0.444056 --5.7129 -6.64663 -0.615857 --6.18866 -7.14479 -0.561009 --6.72542 -7.70792 -0.495179 --3.7849 -4.60912 0.221956 --3.77348 -4.59511 0.336221 --7.87942 -8.91248 -0.0782943 --8.62113 -9.68926 0.0617195 --9.78968 -10.9135 0.206047 --10.9568 -12.1359 0.409046 --10.9647 -12.1399 0.701669 --11.1618 -12.3422 0.994005 --11.1696 -12.3461 1.29172 --11.1389 -12.3091 1.58803 --11.1596 -12.3272 1.88685 --10.9919 -12.1458 2.16818 --11.5696 -12.7477 2.53531 --11.6339 -12.8102 2.85497 --11.5988 -12.7681 3.16141 --11.8737 -13.0521 3.53016 --11.8985 -13.0735 3.85731 --11.8857 -13.0544 4.17767 --11.8677 -13.0316 4.4982 --11.8603 -13.0179 4.82268 --11.8551 -13.008 5.15005 --11.8456 -12.9933 5.47816 --11.8467 -12.9887 5.81216 --11.6355 -12.7644 6.0622 --11.4691 -12.586 6.32336 --11.4456 -12.5554 6.64527 --11.3583 -12.4599 6.93836 --10.9552 -12.0346 7.06478 --11.4649 -12.5602 7.67684 --11.4307 -12.5189 8.00595 --11.7932 -12.8918 8.5808 --11.7845 -12.8773 8.94457 --11.7396 -12.8248 9.28887 --11.7659 -12.8457 9.68569 --12.3046 -13.3993 10.4668 --11.7558 -12.8241 10.4573 --12.0983 -13.1733 11.1297 --11.8201 -12.8788 11.3177 --11.4407 -12.479 11.4072 --11.3392 -12.3679 11.7294 --11.2281 -12.2466 12.0441 --11.2117 -12.2224 12.4512 --11.193 -12.1969 12.8663 --10.8884 -11.8752 12.9904 --11.467 -12.4663 14.0583 --11.3483 -12.3371 14.4022 --4.01849 -4.76153 6.37056 --3.91114 -4.6485 6.43415 --3.87176 -4.60558 6.57912 --3.83656 -4.56609 6.73049 --3.75778 -4.4808 6.82701 --3.93798 -4.66401 7.28217 --3.52297 -4.23322 6.90741 --3.38915 -4.09241 6.91616 --3.37946 -4.08038 7.11003 --3.24994 -3.9443 7.11945 --3.22742 -3.91776 7.29769 --3.10642 -3.79077 7.31573 --2.05825 -2.71394 5.69106 --1.96732 -2.61899 5.69369 --1.90281 -2.55033 5.74097 --1.84572 -2.48954 5.80261 --1.81609 -2.45641 5.9201 --1.77271 -2.40931 6.01256 --2.18647 -2.8284 7.11023 --2.07633 -2.71249 7.09386 --2.11493 -2.74791 7.42491 --2.0206 -2.64814 7.4481 --1.9632 -2.58665 7.56458 --2.75829 -3.38492 9.95685 --1.32129 -1.93071 6.34284 --1.2358 -1.84138 6.32677 --1.33623 -1.93879 6.86961 --1.18769 -1.78615 6.6699 --1.02874 -1.62209 6.40948 --0.937073 -1.52696 6.35613 --0.977271 -1.56291 6.77573 --1.15097 -1.73064 7.75293 --1.26978 -1.84257 8.60771 --1.20878 -1.77625 8.78539 --1.03011 -1.5937 8.4366 --0.908858 -1.46832 8.32146 --0.723458 -1.28098 7.85483 --0.632568 -1.18503 7.83739 --0.600618 -1.14748 8.1682 --0.573465 -1.11277 8.57749 --0.487467 -1.02088 8.63398 --0.483131 -1.00628 9.3382 --0.403761 -0.919801 9.54038 --0.160509 -0.684707 8.22621 --0.0185264 -0.543442 7.64745 -0.0875683 -0.437074 7.33261 -0.154804 -0.363966 7.47286 -0.226165 -0.28716 7.59158 -0.310994 -0.200069 7.46889 -0.39987 -0.111703 7.13414 -0.473756 -0.0342772 7.14708 --0.993184 -1.61469 -0.94234 --1.0443 -1.66536 -0.934042 --1.89484 -2.50816 -0.923192 --2.00031 -2.61203 -0.921165 --2.10587 -2.71767 -0.914544 --2.23805 -2.8484 -0.920498 --2.33276 -2.94174 -0.895543 --2.45415 -3.06116 -0.882614 --2.57555 -3.1813 -0.864142 --2.73013 -3.33519 -0.85877 --2.8867 -3.48962 -0.846247 --3.0561 -3.65729 -0.833473 --3.24038 -3.83904 -0.81919 --3.43857 -4.03587 -0.802354 --3.658 -4.25246 -0.784981 --3.89877 -4.49072 -0.765375 --4.11279 -4.70245 -0.724454 --4.1206 -4.709 -0.603121 --4.16794 -4.75494 -0.494961 --4.46505 -5.04808 -0.457297 --5.70917 -6.28469 -0.65489 --6.16395 -6.73406 -0.602102 --6.68162 -7.24642 -0.540919 --7.27063 -7.82911 -0.467911 --7.72603 -8.27796 -0.344657 --7.82076 -8.36891 -0.150109 --8.47228 -9.01292 -0.0142231 --9.42752 -9.95731 0.126494 --10.7791 -11.294 0.288699 --11.8254 -12.3272 0.528816 --11.8385 -12.3354 0.834395 --12.4229 -12.9115 1.14654 --12.6276 -13.1086 1.47392 --12.1397 -12.6208 1.77022 --12.0239 -12.5024 2.07428 --11.9548 -12.4283 2.37818 --12.5184 -12.982 2.76405 --12.5249 -12.9834 3.09057 --12.4005 -12.8565 3.39454 --12.6252 -13.0733 3.7662 --12.6051 -13.0492 4.09377 --12.5808 -13.0204 4.42107 --12.5744 -13.0083 4.75404 --12.5489 -12.9785 5.08318 --12.5266 -12.9513 5.41448 --12.5203 -12.9409 5.75324 --12.5033 -12.9192 6.09026 --12.3577 -12.7714 6.37681 --12.346 -12.7552 6.71765 --12.2078 -12.614 7.00259 --12.1674 -12.569 7.33217 --12.3501 -12.7434 7.78021 --12.2736 -12.6629 8.10006 --12.4424 -12.8244 8.56308 --12.4347 -12.8105 8.93299 --12.4144 -12.7855 9.30056 --12.3897 -12.7556 9.66946 --12.3778 -12.7383 10.0527 --12.3551 -12.7098 10.4334 --12.3389 -12.6884 10.825 --12.2801 -12.6247 11.1892 --12.2469 -12.5863 11.5785 --12.2135 -12.5477 11.9743 --12.0349 -12.3673 12.2483 --12.1414 -12.4639 12.7811 --11.9066 -12.2292 13.0058 --11.6189 -11.9415 13.1703 --12.3374 -12.6363 14.3634 --4.23429 -4.71843 6.5721 --4.06166 -4.54761 6.56615 --4.13769 -4.61882 6.8578 --4.14488 -4.62273 7.07372 --4.14782 -4.62277 7.29181 --4.02386 -4.49929 7.34364 --3.58816 -4.07271 6.9497 --3.30694 -3.79685 6.74661 --3.3427 -3.82911 7.00309 --3.23482 -3.72217 7.04585 --3.26303 -3.74571 7.30544 --3.16247 -3.64476 7.36007 --3.08833 -3.57013 7.45854 --3.23238 -3.70549 7.95153 --2.63127 -3.12301 7.07995 --2.55618 -3.04746 7.15765 --2.46318 -2.95466 7.20051 --2.25866 -2.75491 7.00747 --2.15733 -2.65423 7.01704 --2.29469 -2.7825 7.56019 --2.10396 -2.59576 7.37119 --2.07825 -2.56758 7.56625 --2.0452 -2.53322 7.75313 --2.70213 -3.15459 9.77508 --1.31633 -1.83134 6.33001 --1.273 -1.78644 6.4388 --1.05171 -1.57284 6.01946 --1.18104 -1.69257 6.66365 --1.12815 -1.63777 6.76117 --1.33208 -1.82669 7.75987 --1.2872 -1.77905 7.94581 --1.78369 -2.23748 10.2326 --1.24711 -1.73032 8.57278 --1.12087 -1.60648 8.47299 --1.02375 -1.51 8.49392 --0.806577 -1.30258 7.92483 --0.711802 -1.20879 7.90896 --0.667616 -1.16227 8.17256 --0.635473 -1.12477 8.54323 --0.552759 -1.04071 8.63997 --0.468003 -0.955867 8.73486 --0.458311 -0.935568 9.43916 --0.479189 -0.940899 10.5603 -0.0503776 -0.474147 6.53974 -0.0339324 -0.476422 7.50537 -0.11302 -0.397365 7.53731 -0.128925 -0.365952 8.5542 -0.276094 -0.235778 7.5356 -0.373662 -0.144803 7.10223 -0.450156 -0.0699674 7.06612 --1.79949 -2.29039 -0.926129 --1.90138 -2.38453 -0.925909 --1.9959 -2.47365 -0.916682 --2.10523 -2.57518 -0.912636 --2.21458 -2.67747 -0.903947 --2.35056 -2.80485 -0.907533 --2.46195 -2.90853 -0.888847 --2.59996 -3.03723 -0.881138 --2.72516 -3.154 -0.859899 --2.88445 -3.30343 -0.851205 --3.04475 -3.45345 -0.835364 --3.24112 -3.63586 -0.828863 --3.43011 -3.81311 -0.810458 --3.64877 -4.01681 -0.795227 --3.88872 -4.24121 -0.77841 --4.1573 -4.49194 -0.761075 --4.44921 -4.76408 -0.738701 --4.47178 -4.78276 -0.616957 --4.47744 -4.78718 -0.490539 --4.73306 -5.0256 -0.431559 --4.73756 -5.02781 -0.299552 --4.71761 -5.0072 -0.163152 --4.70403 -4.99236 -0.0294214 --4.70324 -4.98997 0.100716 --4.69287 -4.9781 0.231413 --4.69534 -4.97961 0.359665 --4.68179 -4.96498 0.489201 --4.68103 -4.96272 0.616641 --4.67174 -4.95193 0.744297 --4.6678 -4.94688 0.871175 --4.66275 -4.93991 0.997749 --4.65559 -4.93107 1.12392 --4.65378 -4.92794 1.25 --4.63603 -4.90977 1.37503 --4.62464 -4.89724 1.49998 --4.61854 -4.88939 1.6253 --4.63266 -4.90124 1.75345 --13.4518 -13.1226 3.34201 --13.8062 -13.4481 3.75046 --13.8083 -13.4446 4.10214 --13.7976 -13.4298 4.45287 --13.8613 -13.4848 4.82472 --13.806 -13.428 5.16753 --13.9025 -13.5141 5.55789 --14.2002 -13.785 6.0237 --13.5494 -13.1744 6.1627 --13.3353 -12.9719 6.44222 --13.3151 -12.9476 6.79431 --13.1371 -12.7777 7.07943 --13.2609 -12.8878 7.50032 --13.3095 -12.9275 7.89464 --13.1664 -12.7898 8.19683 --14.1295 -13.6777 9.10248 --14.0805 -13.6267 9.48356 --14.0864 -13.6267 9.90102 --14.0606 -13.5962 10.3045 --14.0083 -13.5418 10.6961 --13.7503 -13.2917 11.3814 --13.3607 -12.9258 11.5281 --13.1699 -12.7436 11.8142 --13.0827 -12.6564 12.1813 --13.0145 -12.5882 12.5687 --12.979 -12.5484 12.9887 --12.6309 -12.2213 13.1314 --13.3082 -12.8399 14.2341 --13.1226 -12.6622 14.5453 --4.26308 -4.48207 7.17718 --4.2112 -4.43165 7.32668 --4.15091 -4.37409 7.46856 --3.46815 -3.7453 6.74024 --3.42587 -3.7038 6.88014 --3.35618 -3.63673 6.98253 --3.60011 -3.85751 7.57321 --3.30736 -3.58707 7.33545 --3.25445 -3.53525 7.47396 --3.02182 -3.31996 7.30496 --2.75364 -3.07371 7.05516 --2.5506 -2.88506 6.89962 --2.60287 -2.93025 7.21914 --2.30346 -2.65542 6.85545 --2.47623 -2.80885 7.43465 --2.89827 -3.18741 8.59117 --2.21543 -2.56637 7.36282 --2.13115 -2.48638 7.42 --2.12439 -2.47752 7.66742 --1.93542 -2.30231 7.46639 --1.93382 -2.2979 7.7392 --1.32719 -1.74944 6.37033 --1.14204 -1.58042 6.08022 --1.09892 -1.53872 6.18487 --1.1881 -1.61452 6.71194 --1.41656 -1.8143 7.74491 --1.43219 -1.82355 8.14608 --1.49331 -1.8723 8.7472 --1.30915 -1.70385 8.46464 --1.14806 -1.55709 8.2424 --1.0916 -1.50078 8.43543 --0.896661 -1.32486 8.01304 --0.770114 -1.20851 7.86375 --0.701341 -1.14211 7.99191 --0.691016 -1.12608 8.46944 --0.622954 -1.06032 8.66482 --0.523001 -0.965658 8.6727 --0.470948 -0.912846 9.03244 --0.268614 -0.734344 8.24652 --0.170082 -0.643503 8.21615 --0.0136119 -0.505548 7.56805 -0.106038 -0.398912 7.15377 -0.165051 -0.340473 7.43318 -0.242123 -0.267011 7.53189 -0.330659 -0.185663 7.41927 -0.423261 -0.103551 7.10452 -0.449001 -0.0456977 9.59696 --1.70115 -2.08964 -0.924849 --1.80384 -2.18002 -0.930815 --1.89378 -2.25945 -0.922701 --1.99752 -2.35137 -0.920572 --2.10862 -2.44889 -0.918812 --2.22819 -2.55391 -0.916817 --2.35417 -2.66554 -0.914247 --2.49493 -2.78947 -0.914761 --2.5879 -2.87146 -0.881265 --2.73708 -3.00255 -0.874653 --2.87989 -3.12852 -0.858129 --3.04391 -3.27348 -0.845913 --3.23012 -3.43731 -0.836799 --3.43121 -3.6152 -0.825877 --3.64066 -3.79932 -0.809176 --3.8724 -4.00413 -0.791784 --4.13373 -4.23426 -0.775018 --4.4247 -4.49061 -0.756631 --4.74634 -4.77402 -0.73467 --4.8124 -4.83164 -0.621785 --4.79036 -4.81 -0.482247 --4.79487 -4.81228 -0.351639 --4.78347 -4.80032 -0.21805 --4.76996 -4.78653 -0.0853686 --4.76919 -4.7842 0.04357 --4.76636 -4.781 0.17215 --4.755 -4.76927 0.301244 --4.75736 -4.76887 0.427799 --4.74925 -4.76104 0.555009 --4.74102 -4.75125 0.68152 --4.7371 -4.74626 0.807199 --4.72471 -4.73377 0.932644 --4.71867 -4.72693 1.05762 --4.71793 -4.7248 1.18236 --4.70866 -4.71418 1.30662 --4.69734 -4.70271 1.43052 --4.69872 -4.70245 1.55537 --4.68422 -4.68819 1.67861 --14.5199 -13.3495 3.27085 --14.4374 -13.2733 3.61409 --14.5146 -13.3364 3.98615 --14.4912 -13.3102 4.34132 --14.4764 -13.2933 4.69982 --14.4583 -13.2716 5.05845 --14.4562 -13.2656 5.4238 --14.4423 -13.2484 5.78779 --14.4094 -13.2145 6.14741 --14.3491 -13.1566 6.49883 --14.3638 -13.1649 6.88003 --14.1365 -12.9599 7.16473 --14.3486 -13.1414 7.63619 --14.3389 -13.128 8.01962 --14.2057 -13.0055 8.34537 --14.3479 -13.1252 8.81274 --14.3286 -13.1029 9.20498 --14.3114 -13.0832 9.60257 --14.3015 -13.0686 10.01 --14.2726 -13.0374 10.4108 --14.23 -12.9952 10.8084 --14.2095 -12.9708 11.2253 --14.1943 -12.9525 11.6535 --14.1926 -12.9455 12.0986 --13.9761 -12.7508 12.385 --14.0976 -12.8504 12.9405 --13.7893 -12.5746 13.1514 --14.27 -12.9813 14.5406 --3.54295 -3.61368 6.81546 --3.56142 -3.62365 7.25925 --3.44473 -3.52025 7.30201 --3.18859 -3.2961 7.11787 --3.0804 -3.20032 7.15837 --2.74486 -2.90899 6.80741 --2.60637 -2.7867 6.77217 --2.5308 -2.71939 6.84607 --2.3935 -2.59943 6.80285 --2.35555 -2.56349 6.94677 --3.05583 -3.16066 8.61503 --2.9213 -3.04104 8.62221 --1.8175 -2.09485 6.47386 --2.2578 -2.46726 7.71182 --1.99113 -2.23665 7.34716 --1.47438 -1.79337 6.31668 --1.40431 -1.73204 6.36437 --1.33829 -1.67212 6.41938 --1.32126 -1.65525 6.61837 --1.24482 -1.58693 6.65316 --1.21517 -1.55869 6.83386 --1.42624 -1.73258 7.82358 --1.44279 -1.74129 8.23464 --1.40218 -1.70255 8.47872 --1.28483 -1.5988 8.44827 --1.18306 -1.50849 8.47177 --0.996752 -1.34919 8.12877 --0.84366 -1.21703 7.88548 --0.765775 -1.14603 7.97599 --0.73817 -1.11728 8.34672 --0.631457 -1.02384 8.31806 --0.597255 -0.988544 8.72757 --0.490418 -0.894327 8.71469 --0.495058 -0.887842 9.52751 --0.229523 -0.669535 8.26606 --0.133168 -0.584675 8.27425 -0.0556298 -0.431392 7.28692 -0.133345 -0.360821 7.34833 -0.181988 -0.310973 7.86664 -0.291023 -0.220109 7.5259 -0.39153 -0.135871 7.16253 -0.473736 -0.0643734 7.10651 --1.51912 -1.83061 -0.920683 --1.69961 -1.98148 -0.926469 --1.78402 -2.05224 -0.918924 --1.88317 -2.13448 -0.918109 --1.99608 -2.22821 -0.923128 --2.09623 -2.31099 -0.914169 --2.22396 -2.41789 -0.919526 --2.33255 -2.50797 -0.906337 --2.47603 -2.62688 -0.910179 --2.63436 -2.75905 -0.916157 --2.73756 -2.8445 -0.884014 --2.88314 -2.96643 -0.87037 --3.05188 -3.10626 -0.861572 --3.22061 -3.24674 -0.845633 --3.4263 -3.41755 -0.839028 --3.61823 -3.5774 -0.817349 --3.85557 -3.7751 -0.805068 --4.10027 -3.97902 -0.785415 --4.39135 -4.2205 -0.770861 --4.713 -4.48708 -0.753331 --4.97546 -4.70548 -0.703591 --4.94511 -4.67915 -0.560545 --4.93687 -4.66992 -0.425095 --4.93296 -4.66559 -0.292375 --4.92792 -4.65934 -0.160258 --4.92078 -4.65125 -0.0288486 --4.90416 -4.63568 0.10302 --4.90869 -4.63811 0.230632 --4.89533 -4.62648 0.360016 --4.89663 -4.62512 0.486917 --4.89587 -4.62289 0.613758 --4.88564 -4.6132 0.740759 --4.8743 -4.6016 0.867057 --4.87567 -4.6013 0.992708 --4.86857 -4.5935 1.11822 --4.86683 -4.59139 1.24376 --4.86391 -4.58636 1.36905 --4.84318 -4.56843 1.49296 --4.83714 -4.5616 1.61773 --4.8438 -4.56595 1.74435 --15.6637 -13.5507 3.56429 --16.1252 -13.9284 4.02311 --16.1145 -13.9149 4.40944 --16.0921 -13.8912 4.79448 --16.0709 -13.8692 5.18131 --16.0527 -13.849 5.57016 --16.044 -13.8371 5.96389 --15.8573 -13.677 6.30329 --15.5623 -13.4284 6.59984 --15.5315 -13.3982 6.98289 --15.2376 -13.1492 7.26461 --15.5499 -13.4022 7.78942 --15.5317 -13.3826 8.18781 --15.9501 -13.7234 8.79457 --15.9391 -13.7082 9.21566 --15.8998 -13.6711 9.62734 --15.8835 -13.6519 10.0552 --15.8609 -13.6279 10.4849 --15.8173 -13.5865 10.9076 --15.7673 -13.5405 11.3312 --15.4913 -13.3066 11.6108 --15.2532 -13.1045 11.909 --15.1811 -13.0394 12.3201 --15.2308 -13.0735 12.8259 --15.0515 -12.9209 13.1678 --14.6654 -12.5976 13.3415 --15.5318 -13.3029 14.5487 --7.89117 -6.9786 11.6185 --7.6932 -6.81306 11.7389 --7.35492 -6.53213 11.667 --3.77961 -3.60973 7.33487 --3.68938 -3.53342 7.42623 --3.28861 -3.20457 7.04147 --3.21211 -3.14026 7.13703 --3.73426 -3.56084 8.2141 --2.7279 -2.74159 6.76521 --2.64104 -2.66868 6.82422 --2.478 -2.53415 6.74204 --1.80793 -1.98906 5.68592 --1.73183 -1.92599 5.71546 --2.40202 -2.46355 7.26712 --2.26197 -2.34721 7.21495 --1.7867 -1.96223 6.41454 --2.07892 -2.19422 7.30702 --2.23031 -2.31258 7.93169 --1.50705 -1.72909 6.42011 --1.41323 -1.65182 6.41377 --1.43049 -1.66248 6.70369 --1.27745 -1.53688 6.53041 --1.2645 -1.52343 6.75663 --1.5425 -1.74032 7.91018 --1.4835 -1.68882 8.06998 --1.41827 -1.63317 8.21983 --1.35813 -1.58086 8.39711 --1.17516 -1.43225 8.11763 --1.11912 -1.38349 8.31965 --0.944649 -1.24129 8.02163 --0.834115 -1.14979 7.97882 --0.828099 -1.13797 8.44697 --0.702171 -1.03542 8.34222 --0.631377 -0.973342 8.52735 --0.568609 -0.91849 8.7997 --0.122569 -0.575821 6.44307 --0.474406 -0.828548 9.737 -0.0121926 -0.462182 6.57269 -0.0183173 -0.448997 7.25054 -0.0908888 -0.38716 7.39251 -0.161819 -0.324853 7.60265 -0.255255 -0.248731 7.53219 -0.362548 -0.16431 7.1201 -0.446636 -0.0948832 7.06506 -0.529572 -0.0269818 6.9981 --1.44393 -1.68019 -0.931066 --1.52172 -1.74059 -0.929089 --1.6006 -1.80278 -0.924111 --1.67947 -1.86484 -0.916337 --1.77942 -1.9433 -0.921307 --1.86669 -2.0118 -0.912149 --1.98137 -2.10154 -0.919654 --2.09713 -2.19299 -0.92246 --2.20014 -2.27349 -0.911487 --2.33799 -2.38189 -0.918994 --2.46315 -2.48032 -0.912273 --2.60403 -2.59 -0.90888 --2.76608 -2.71778 -0.91184 --2.8869 -2.81246 -0.885011 --3.05097 -2.94151 -0.875578 --3.21605 -3.07117 -0.859499 --3.40426 -3.21865 -0.846668 --3.62297 -3.38961 -0.83885 --3.83536 -3.55633 -0.818776 --4.08566 -3.75314 -0.804134 --4.36749 -3.97413 -0.789758 --4.66608 -4.20781 -0.768519 --5.03314 -4.49595 -0.75578 --5.27994 -4.68852 -0.692113 --5.22546 -4.64512 -0.539382 --5.20878 -4.62913 -0.398824 --5.20483 -4.62463 -0.262908 --5.19042 -4.6127 -0.126038 --5.19803 -4.61674 0.005683 --5.18039 -4.60107 0.140843 --5.11437 -4.54796 0.280891 --5.11671 -4.54742 0.410242 --5.14759 -4.57137 0.537017 --5.15417 -4.57459 0.666286 --5.15127 -4.57034 0.796015 --5.13791 -4.55871 0.925499 --5.13919 -4.55725 1.0545 --5.14583 -4.56148 1.18362 --5.12824 -4.54614 1.31198 --5.12329 -4.54107 1.44055 --5.11729 -4.53506 1.56907 --16.7962 -13.6822 3.47804 --16.7929 -13.675 3.87004 --16.7769 -13.6576 4.26115 --16.7472 -13.629 4.65069 --16.7438 -13.6216 5.04699 --16.7341 -13.6095 5.44411 --16.7117 -13.5862 5.83978 --16.6979 -13.5722 6.24028 --16.6723 -13.546 6.63909 --16.6626 -13.5344 7.04624 --16.4355 -13.3522 7.37573 --16.6786 -13.537 7.88473 --16.6363 -13.4984 8.28981 --16.7072 -13.5486 8.74799 --16.7036 -13.5414 9.18015 --16.68 -13.5167 9.60707 --16.6491 -13.4873 10.0353 --16.6329 -13.4704 10.4766 --16.6029 -13.4414 10.9157 --16.574 -13.4131 11.3604 --9.20859 -7.67939 7.20928 --16.473 -13.3233 12.2407 --16.4367 -13.2898 12.6987 --8.82031 -7.36822 7.76775 --8.84276 -7.38234 8.06238 --16.4645 -13.2938 14.2224 --16.3965 -13.2346 14.69 --6.94483 -5.89135 8.09765 --6.4429 -5.497 8.12559 --8.15741 -6.81124 10.8259 --7.9203 -6.61601 11.613 --7.60798 -6.37035 11.5873 --3.91374 -3.52159 7.29035 --3.84879 -3.46892 7.42022 --3.70353 -3.35457 7.43528 --3.31225 -3.05134 7.06868 --5.04544 -4.37307 10.3436 --1.95323 -2.00382 5.4541 --1.84609 -1.92022 5.42983 --1.88048 -1.94397 5.65724 --1.817 -1.8929 5.71261 --1.94494 -1.9891 6.14537 --1.91255 -1.96137 6.27862 --1.8636 -1.92289 6.38618 --1.58506 -1.70864 5.98909 --1.73432 -1.81885 6.53794 --1.60645 -1.71981 6.46589 --1.48582 -1.62511 6.39871 --1.44301 -1.59028 6.52623 --1.35354 -1.52 6.53528 --1.36755 -1.52735 6.83523 --1.30286 -1.47565 6.92499 --1.56451 -1.6681 8.04527 --1.15066 -1.35452 7.0449 --1.43534 -1.56277 8.36449 --1.2569 -1.42594 8.12497 --1.17116 -1.35752 8.21345 --1.0289 -1.24683 8.07033 --0.903216 -1.14952 7.98095 --0.821622 -1.08426 8.08163 --0.76754 -1.03826 8.32665 --0.654158 -0.949718 8.28827 --0.634373 -0.928768 8.79551 --0.552243 -0.861408 8.97959 --0.0793883 -0.52128 6.4021 --0.230694 -0.61876 8.21652 -0.0111421 -0.443598 6.94615 -0.0753937 -0.390822 7.13799 -0.136003 -0.33997 7.42818 -0.208899 -0.279837 7.65754 -0.312813 -0.201294 7.44641 -0.415969 -0.123745 7.09296 -0.499215 -0.0588797 7.12696 --1.42796 -1.58259 -0.925773 --1.5013 -1.63603 -0.919567 --1.58835 -1.70011 -0.922042 --1.66811 -1.76018 -0.915859 --1.75617 -1.82489 -0.912088 --1.85893 -1.90009 -0.915394 --1.96177 -1.9771 -0.914806 --2.07292 -2.05868 -0.91523 --2.19148 -2.14685 -0.916073 --2.32572 -2.24534 -0.921593 --2.43893 -2.32913 -0.908475 --2.58892 -2.43963 -0.912479 --2.71789 -2.53544 -0.898047 --2.89204 -2.66455 -0.902248 --3.02298 -2.76071 -0.876869 --3.19816 -2.89112 -0.867983 --3.38265 -3.0268 -0.85546 --3.58289 -3.17453 -0.842121 --3.79989 -3.33419 -0.826862 --4.03267 -3.5068 -0.80864 --4.29688 -3.70166 -0.791982 --4.60834 -3.93202 -0.780116 --4.94492 -4.18064 -0.76255 --5.34446 -4.47581 -0.74921 --5.80804 -4.81928 -0.735797 --6.37646 -5.23894 -0.728028 --6.32096 -5.19667 -0.556426 --6.28745 -5.16951 -0.39272 --6.2592 -5.14622 -0.232387 --8.77162 -7.00643 -0.472061 --9.26277 -7.36892 -0.329739 --9.35382 -7.43334 -0.121505 --10.1145 -7.99479 0.0292085 --11.2274 -8.8154 0.188118 --12.8847 -10.0394 0.369224 --15.771 -12.1711 0.590681 --16.8219 -12.9437 0.944186 --16.9907 -13.0649 1.32734 --17.0346 -13.0923 1.7129 --17.0239 -13.0799 2.09738 --16.9274 -13.0048 2.47491 --17.1473 -13.1619 2.88215 --17.2635 -13.2442 3.28699 --17.2318 -13.2158 3.67613 --17.2253 -13.2067 4.06982 --17.2052 -13.1874 4.4624 --17.1966 -13.1763 4.85838 --17.189 -13.166 5.25681 --17.1678 -13.1466 5.65398 --17.1497 -13.1279 6.05361 --17.1327 -13.111 6.45624 --17.056 -13.0503 6.84164 --16.9656 -12.9787 7.22249 --16.7853 -12.842 7.56929 --17.2067 -13.1468 8.15188 --17.1205 -13.0793 8.54488 --17.4391 -13.3074 9.11928 --17.4156 -13.2853 9.55325 --17.3994 -13.2684 9.99594 --17.3695 -13.2413 10.4366 --17.347 -13.2193 10.8866 --17.3327 -13.2034 11.3468 --17.3174 -13.1872 11.8136 --9.20919 -7.24375 7.21502 --7.08857 -5.68795 6.09793 --6.98177 -5.60705 6.2412 --8.65808 -6.83119 7.64968 --8.787 -6.92165 8.01478 --7.48749 -5.96956 7.29576 --7.47354 -5.95672 7.53121 --7.2675 -5.80367 7.61199 --7.27437 -5.80557 7.86855 --7.02663 -5.62214 7.90495 --6.8655 -5.50124 8.01068 --6.60745 -5.31077 8.01942 --6.57781 -5.28634 8.24486 --6.75558 -5.41206 8.68888 --8.3676 -6.58184 10.6854 --8.3093 -6.53533 10.966 --8.25831 -6.49471 11.2607 --8.03223 -6.32614 11.3552 --7.61148 -6.01705 11.2033 --2.05444 -1.97274 5.472 --1.94442 -1.89123 5.4496 --1.92376 -1.87502 5.57921 --1.86463 -1.83028 5.64303 --2.0213 -1.94082 6.11566 --1.98903 -1.91508 6.24931 --1.85621 -1.8179 6.18622 --1.69339 -1.69908 6.04994 --1.57931 -1.61495 6.00426 --1.70538 -1.70203 6.50164 --1.63164 -1.64737 6.56105 --1.56823 -1.59985 6.64593 --1.89835 -1.83053 7.76122 --1.50223 -1.54743 6.99457 --1.32829 -1.42097 6.78313 --1.17925 -1.3126 6.62165 --1.48759 -1.52636 7.88221 --1.08932 -1.24188 6.92334 --1.29921 -1.38595 7.98988 --1.263 -1.35573 8.25914 --0.930354 -1.11992 7.39199 --1.04981 -1.1971 8.29933 --0.865101 -1.06518 7.9684 --0.812258 -1.02311 8.21362 --0.736799 -0.965229 8.3805 --0.817697 -1.01332 9.43589 --0.684776 -0.914889 9.37805 --0.603545 -0.853063 9.65172 --0.511908 -0.782356 9.89463 --0.142801 -0.531483 7.89905 -0.0571917 -0.394374 6.94307 -0.119408 -0.346071 7.18381 -0.154798 -0.312074 7.85179 -0.270541 -0.229591 7.55246 -0.381596 -0.152442 7.18034 -0.471318 -0.0868396 7.09551 -0.5572 -0.0231492 7.06858 --1.41645 -1.49199 -0.925407 --1.48434 -1.53852 -0.914778 --1.56489 -1.59477 -0.913283 --1.66114 -1.6615 -0.91996 --1.75003 -1.72323 -0.91773 --1.84001 -1.78673 -0.9123 --1.94563 -1.85967 -0.913793 --2.05122 -1.93241 -0.91139 --2.16422 -2.01178 -0.909906 --2.29291 -2.10148 -0.913498 --2.42994 -2.19667 -0.916554 --2.55334 -2.28296 -0.905736 --2.69973 -2.38431 -0.902809 --2.84713 -2.48632 -0.894135 --3.02502 -2.61104 -0.895218 --3.18914 -2.72484 -0.881927 --3.35428 -2.83928 -0.86229 --3.54987 -2.97628 -0.849515 --3.77046 -3.12893 -0.838677 --3.99948 -3.2888 -0.822012 --4.25354 -3.46518 -0.804739 --4.54001 -3.66371 -0.788126 --4.86629 -3.89098 -0.77249 --5.25748 -4.16376 -0.762419 --5.69879 -4.47047 -0.749384 --6.19759 -4.81664 -0.732357 --6.25435 -4.85543 -0.592435 --6.29326 -4.88099 -0.447395 --7.94267 -6.03081 -0.602003 --6.18572 -4.80227 -0.124605 --9.44378 -7.07365 -0.441537 --9.66019 -7.22155 -0.249141 --10.0044 -7.46026 -0.0610907 --10.8956 -8.0786 0.0980519 --12.2356 -9.00929 0.268862 --14.4771 -10.5674 0.463874 --18.2098 -13.1623 0.731967 --18.2702 -13.1998 1.13468 --18.6036 -13.428 1.54751 --18.5625 -13.3952 1.95628 --18.5727 -13.3973 2.36747 --18.241 -13.1627 2.74852 --19.4011 -13.9647 3.28506 --19.2376 -13.846 3.69445 --19.7764 -14.2153 4.20804 --19.7624 -14.2013 4.64859 --19.7253 -14.1708 5.08604 --19.7061 -14.153 5.52837 --19.6888 -14.136 5.97295 --19.6329 -14.0917 6.40957 --19.1311 -13.7395 6.71873 --19.0878 -13.7047 7.15131 --18.4599 -13.2653 7.39111 --19.1014 -13.704 8.05811 --18.9683 -13.6076 8.46553 --19.5949 -14.036 9.17726 --19.5619 -14.0078 9.64309 --19.5382 -13.9858 10.1169 --19.5144 -13.9635 10.5958 --19.4824 -13.9365 11.0764 --19.3981 -13.8728 11.5347 --19.073 -13.6433 11.8648 --8.78973 -6.54397 6.46476 --9.78064 -7.22469 7.30789 --6.82228 -5.18259 5.73089 --7.18165 -5.42801 6.1695 --7.07931 -5.3547 6.31628 --6.81037 -5.16794 6.34424 --6.95907 -5.26724 6.66888 --7.1494 -5.39588 7.03884 --6.77323 -5.13496 6.9737 --7.06859 -5.33539 7.44684 --7.21185 -5.43096 7.81271 --7.2208 -5.43451 8.07408 --6.83021 -5.16415 7.97412 --6.35437 -4.83475 7.77297 --6.23852 -4.75208 7.90236 --6.84437 -5.16482 8.77275 --6.46019 -4.89867 8.64081 --6.30167 -4.7871 8.73731 --7.78816 -5.8012 10.7088 --7.57839 -5.65372 10.803 --6.17733 -4.69285 9.43407 --7.40822 -5.53043 11.2918 --2.18751 -1.9585 5.53642 --2.04874 -1.86253 5.47655 --1.93074 -1.78097 5.44458 --1.91943 -1.77143 5.5899 --1.87699 -1.74013 5.68615 --1.85427 -1.72364 5.82404 --1.75489 -1.65373 5.81762 --1.86756 -1.72836 6.23848 --1.8746 -1.73072 6.46554 --1.80103 -1.67891 6.52779 --1.56325 -1.51612 6.21665 --1.63009 -1.55912 6.60296 --1.69053 -1.59684 7.00268 --1.61478 -1.54345 7.07936 --1.39793 -1.39535 6.77001 --1.29243 -1.32253 6.74868 --1.20751 -1.2629 6.78033 --1.2243 -1.27125 7.13761 --1.12287 -1.20052 7.12993 --1.06145 -1.15656 7.26196 --0.924165 -1.06171 7.11694 --1.07438 -1.15643 8.09828 --0.777681 -0.957852 7.30633 --0.84553 -0.997019 8.05201 --0.793761 -0.958471 8.32605 --0.726556 -0.909237 8.55118 --0.693565 -0.881429 9.01052 --0.65711 -0.850874 9.52948 --0.0799245 -0.482155 6.42181 --0.0164496 -0.436707 6.54584 -0.0242603 -0.404205 6.88674 -0.0803383 -0.362064 7.17779 -0.148681 -0.312642 7.42834 -0.227254 -0.254825 7.61792 -0.346172 -0.177053 7.20726 -0.4416 -0.111712 7.06343 -0.530206 -0.0511341 7.0175 --1.56548 -1.50483 -0.920799 --1.64255 -1.55391 -0.912075 --1.73333 -1.6136 -0.911731 --1.83875 -1.68282 -0.918815 --1.93787 -1.74795 -0.916838 --2.04529 -1.81767 -0.916372 --2.15373 -1.88814 -0.912057 --2.27686 -1.96902 -0.913121 --2.40834 -2.05542 -0.91425 --2.54183 -2.14246 -0.910425 --2.68994 -2.23883 -0.910232 --2.83279 -2.33201 -0.900224 --3.00601 -2.44594 -0.900573 --3.19588 -2.56995 -0.901897 --3.36372 -2.67934 -0.884989 --3.5399 -2.7941 -0.865149 --3.74846 -2.93029 -0.851611 --3.96639 -3.07268 -0.832988 --4.224 -3.24107 -0.820685 --4.49933 -3.4212 -0.803762 --4.83204 -3.63835 -0.794179 --5.19081 -3.87269 -0.778741 --5.61535 -4.1504 -0.767064 --6.08989 -4.45996 -0.750924 --6.73044 -4.87883 -0.75434 --7.27473 -5.23396 -0.710282 --7.86901 -5.62155 -0.653723 --6.18779 -4.51802 -0.180101 --6.25481 -4.56036 -0.0434277 --6.19445 -4.51919 0.11187 --10.0726 -7.05806 -0.165011 --10.7654 -7.50852 0.000741575 --11.8326 -8.204 0.169865 --13.5414 -9.31942 0.353455 --16.4955 -11.2484 0.5767 --20.0498 -13.5684 0.920201 --20.1506 -13.63 1.35485 --20.3786 -13.7748 1.7986 --20.3907 -13.7783 2.23961 --20.1963 -13.6465 2.66554 --21.2479 -14.3284 3.20894 --21.2056 -14.2963 3.66529 --21.6647 -14.5915 4.19264 --21.6422 -14.5715 4.66256 --21.6207 -14.5525 5.13384 --21.6002 -14.5342 5.60707 --21.5819 -14.5178 6.0825 --21.4728 -14.4416 6.53787 --20.9254 -14.0809 6.87298 --20.8466 -14.0241 7.32504 --20.494 -13.7905 7.69146 --20.9441 -14.0774 8.31694 --21.4462 -14.399 8.9863 --21.4236 -14.3798 9.48309 --21.3946 -14.3548 9.98115 --9.20369 -6.43395 5.26644 --21.3585 -14.3214 11.0023 --9.16042 -6.40116 5.71745 --8.84388 -6.1936 5.79828 --20.5974 -13.8121 12.2086 --7.61825 -5.3949 5.59761 --7.61181 -5.38801 5.80507 --7.03879 -5.01478 5.6755 --6.97735 -4.97319 5.84068 --7.25987 -5.15343 6.23102 --7.16098 -5.08776 6.38111 --6.96025 -4.95569 6.45704 --6.97252 -4.96174 6.68422 --6.95981 -4.95094 6.89725 --6.92941 -4.92867 7.10027 --6.8606 -4.88202 7.27526 --7.21843 -5.11035 7.81764 --7.11843 -5.04407 7.98141 --6.59083 -4.7012 7.75085 --6.44624 -4.60533 7.85774 --6.85041 -4.86279 8.50455 --6.67048 -4.74412 8.58852 --6.39 -4.56083 8.56068 --6.22989 -4.4556 8.65268 --6.46364 -4.60341 9.19003 --6.45162 -4.59253 9.46444 --7.26724 -5.11201 10.7586 --7.50456 -5.26128 11.4037 --3.235 -2.51372 7.18264 --1.98923 -1.71687 5.39163 --1.98832 -1.71493 5.55323 --1.9171 -1.66775 5.60021 --1.94189 -1.68137 5.82125 --1.89028 -1.64702 5.90937 --1.81802 -1.5996 5.96244 --1.77147 -1.56719 6.06591 --1.74251 -1.54762 6.2125 --1.67431 -1.50225 6.28012 --1.75639 -1.55103 6.69327 --1.55328 -1.42058 6.45628 --1.94577 -1.66482 7.68737 --1.47953 -1.37013 6.77452 --1.31569 -1.26439 6.59833 --1.29155 -1.24653 6.80592 --1.28675 -1.23981 7.0887 --1.15688 -1.15589 6.99755 --1.16115 -1.15537 7.34669 --1.02926 -1.07023 7.24184 --0.930144 -1.0057 7.248 --0.862639 -0.960259 7.3768 --0.917213 -0.989026 8.04497 --0.655254 -0.825132 7.3405 --0.791487 -0.902515 8.50651 --0.88012 -0.949185 9.60144 --0.740615 -0.858654 9.55405 --0.126358 -0.48882 6.43312 --0.0750048 -0.452242 6.64668 --0.0184654 -0.413507 6.86961 -0.0413408 -0.372014 7.11171 -0.118296 -0.320478 7.25355 -0.165348 -0.283586 7.81206 -0.289481 -0.206586 7.45286 -0.402206 -0.136567 7.1008 -0.490027 -0.078949 7.13583 -0.581347 -0.0190557 7.03895 --1.66076 -1.47253 -0.931747 --1.73148 -1.51662 -0.915808 --1.82506 -1.57306 -0.913901 --1.92501 -1.63523 -0.913865 --2.02692 -1.69711 -0.910323 --2.15086 -1.77426 -0.918073 --2.26943 -1.84626 -0.916506 --2.38803 -1.91906 -0.910695 --2.52963 -2.00696 -0.914072 --2.66586 -2.0897 -0.907834 --2.81775 -2.1827 -0.904973 --2.98636 -2.28683 -0.904437 --3.15493 -2.39066 -0.897609 --3.34945 -2.50921 -0.895561 --3.5284 -2.61995 -0.879 --3.73225 -2.7444 -0.865874 --3.95378 -2.87975 -0.851274 --4.19199 -3.02601 -0.834303 --4.46355 -3.19344 -0.819535 --4.76003 -3.3753 -0.80246 --5.11587 -3.59399 -0.791419 --5.51431 -3.83809 -0.778293 --5.9388 -4.09921 -0.755916 --6.52359 -4.45806 -0.75531 --7.13436 -4.8335 -0.736764 --6.21239 -4.26288 -0.384676 --8.38662 -5.60118 -0.63062 --9.11982 -6.05074 -0.556707 --10.0216 -6.60416 -0.476564 --10.5513 -6.92731 -0.316145 --10.6812 -7.00482 -0.0956486 --11.6064 -7.57171 0.0685434 --12.9301 -8.3826 0.247959 --15.3329 -9.85775 0.44307 --18.9276 -12.0624 0.718743 --22.0834 -13.9964 1.13887 --22.5146 -14.2566 1.61722 --22.4787 -14.2302 2.09173 --22.4697 -14.2202 2.56715 --22.5211 -14.2474 3.04839 --22.7607 -14.3895 3.55326 --22.7299 -14.3664 4.03469 --22.701 -14.3433 4.51672 --22.6806 -14.3265 5.00123 --22.6539 -14.3051 5.48597 --22.6106 -14.2737 5.96889 --22.5859 -14.254 6.45733 --22.5364 -14.2189 6.94182 --22.4555 -14.164 7.41898 --21.7879 -13.752 7.72188 --22.7158 -14.3139 8.51052 --22.8479 -14.3903 9.07281 --22.8002 -14.356 9.58027 --8.85253 -5.83561 4.71375 --9.0631 -5.96228 5.01779 --9.0348 -5.94238 5.23106 --8.90789 -5.86239 5.40074 --8.75512 -5.76767 5.55519 --7.97249 -5.28858 5.38852 --7.86856 -5.2229 5.54497 --7.85391 -5.21264 5.74961 --7.62965 -5.07347 5.83552 --7.93748 -5.25877 6.23453 --7.80662 -5.17734 6.37738 --7.56995 -5.03065 6.44801 --7.59149 -5.04157 6.68701 --7.46271 -4.96127 6.82473 --7.21688 -4.81021 6.87344 --7.04358 -4.70261 6.96872 --7.05991 -4.71068 7.21074 --6.98817 -4.66521 7.38586 --6.80347 -4.55005 7.46526 --6.97917 -4.65427 7.86004 --6.71585 -4.49227 7.86743 --7.09638 -4.72076 8.48009 --6.87442 -4.58332 8.52846 --6.65256 -4.44721 8.57009 --6.48867 -4.34605 8.66545 --6.44367 -4.31574 8.88659 --7.14103 -4.73395 9.95982 --7.51962 -4.95913 10.7226 --7.67065 -5.04721 11.2502 --6.2446 -4.16877 11.5061 --2.07644 -1.6671 5.37866 --5.93495 -3.97573 11.7912 --3.94535 -2.78127 8.85111 --2.16526 -1.71509 6.04223 --1.96023 -1.59085 5.86451 --3.19775 -2.32696 8.38487 --3.65405 -2.5956 9.5721 --2.46502 -1.88562 7.49735 --2.34734 -1.81351 7.51722 --2.22658 -1.73915 7.52533 --1.54503 -1.33273 6.23543 --2.10317 -1.66017 7.81204 --1.98655 -1.58899 7.83185 --1.4137 -1.24835 6.64066 --1.38346 -1.22772 6.83055 --1.3347 -1.19599 6.9836 --1.23069 -1.13236 6.97755 --1.15629 -1.08547 7.06307 --1.09418 -1.04658 7.19473 --0.97793 -0.97584 7.14469 --0.876964 -0.91298 7.1396 --0.7456 -0.834195 7.00724 --0.589964 -0.741219 6.74563 --0.572386 -0.727128 7.09163 --0.51102 -0.687234 7.2629 --0.852136 -0.87449 9.68546 --0.711867 -0.788587 9.6468 --0.12148 -0.454813 6.59892 --0.0770795 -0.424437 6.90145 -0.020365 -0.365307 6.8371 -0.078196 -0.327289 7.12804 -0.138488 -0.286494 7.478 -0.223692 -0.232561 7.63778 -0.352025 -0.158307 7.14742 -0.445396 -0.101926 7.10357 -0.537753 -0.0455833 7.05772 --1.80606 -1.47415 -0.918709 --1.9015 -1.52838 -0.915093 --2.00425 -1.58729 -0.913392 --2.12263 -1.6556 -0.918116 --2.24203 -1.72465 -0.91869 --2.35513 -1.78962 -0.910302 --2.49844 -1.87254 -0.916314 --2.62918 -1.9475 -0.908199 --2.79012 -2.0403 -0.912485 --2.93748 -2.12519 -0.902549 --3.11708 -2.22872 -0.903158 --3.29769 -2.33286 -0.897021 --3.51151 -2.45544 -0.898627 --3.7357 -2.58418 -0.895644 --3.92763 -2.69474 -0.871079 --4.13613 -2.81429 -0.845643 --4.39555 -2.96336 -0.83007 --4.68826 -3.13254 -0.81575 --5.01618 -3.32062 -0.800825 --5.39608 -3.53977 -0.787769 --5.83514 -3.79252 -0.776201 --6.21692 -4.01204 -0.732474 --6.19215 -3.99596 -0.58037 --6.17365 -3.98368 -0.431534 --6.14374 -3.96505 -0.282399 --6.171 -3.97966 -0.144999 --6.29072 -4.04752 -0.0207744 --6.24628 -4.02072 0.128646 --6.3016 -4.05175 0.264972 --11.4533 -7.02031 -0.0336369 --12.5402 -7.64508 0.141881 --14.3621 -8.69238 0.327521 --17.2477 -10.3512 0.559587 --25.6931 -15.2072 1.41231 --26.8805 -15.8854 1.98663 --26.5006 -15.6621 2.52245 --25.8095 -15.2589 3.02014 --26.9696 -15.921 3.66865 --26.8668 -15.8567 4.21897 --26.9456 -15.8968 4.79176 --26.9299 -15.8829 5.35515 --26.8874 -15.8536 5.91588 --26.8458 -15.8242 6.4778 --26.7606 -15.7698 7.03195 --26.6765 -15.7163 7.58644 --26.2959 -15.4929 8.06408 --26.7352 -15.7387 8.76136 --26.733 -15.7328 9.34847 --26.7048 -15.7116 9.93223 --7.57246 -4.74994 3.8935 --7.79308 -4.87398 4.15765 --7.49786 -4.70355 4.23226 --8.99237 -5.5574 5.0362 --8.85853 -5.47816 5.19926 --7.25448 -4.55944 4.68373 --7.73479 -4.83162 5.10288 --7.537 -4.71719 5.20404 --7.49652 -4.69174 5.38219 --7.49231 -4.68811 5.58182 --7.88018 -4.90715 6.01205 --7.26546 -4.55469 5.85844 --7.23016 -4.53265 6.0425 --7.63648 -4.7623 6.51936 --7.11197 -4.46162 6.38501 --7.40647 -4.62736 6.81019 --7.39897 -4.62081 7.03238 --7.59614 -4.73125 7.41712 --6.49827 -4.10469 6.78537 --6.27697 -3.97698 6.8187 --6.77371 -4.25715 7.46125 --6.8271 -4.28496 7.74569 --6.65015 -4.18226 7.82756 --6.68699 -4.20118 8.10902 --6.29533 -3.97665 7.97616 --6.51379 -4.09848 8.44914 --6.90547 -4.31791 9.12973 --7.37327 -4.57989 9.93175 --7.39209 -4.5871 10.269 --7.62227 -4.71404 10.8675 --7.37086 -4.56965 10.9097 --7.41834 -4.58941 11.6872 --6.16993 -3.87309 11.4308 --5.99181 -3.76934 11.5352 --4.08555 -2.69639 8.83443 --5.76824 -3.63623 11.9633 --2.8229 -1.98344 7.23294 --1.95532 -1.49614 5.89926 --4.49439 -2.91304 10.8852 --4.2437 -2.76943 10.7896 --2.39216 -1.73405 7.40633 --2.33632 -1.70091 7.55595 --1.58428 -1.28058 6.1672 --1.499 -1.2312 6.19484 --2.07733 -1.54947 7.83053 --1.46661 -1.20905 6.6 --1.37512 -1.15618 6.62472 --1.61884 -1.28756 7.58226 --1.33816 -1.12998 7.09692 --1.18534 -1.0432 6.94968 --1.12441 -1.00724 7.0814 --1.07562 -0.977797 7.26941 --0.915838 -0.887217 7.06565 --0.779611 -0.810154 6.92473 --0.646603 -0.735555 6.77063 --0.568315 -0.6889 6.83591 --0.558807 -0.680443 7.24052 --0.679992 -0.739549 8.38889 --0.785018 -0.788435 9.64166 --0.165703 -0.459641 6.62974 --0.0794647 -0.409337 6.6367 --0.0201299 -0.373268 6.84973 -0.0553333 -0.329102 6.98273 -0.113311 -0.292654 7.32311 -0.18071 -0.250299 7.67273 -0.316865 -0.176925 7.15392 -0.414962 -0.121252 7.0611 -0.509141 -0.0679816 7.01619 -0.598641 -0.015572 7.04936 --1.89593 -1.43524 -0.931426 --1.97036 -1.47482 -0.909972 --2.07497 -1.53153 -0.906663 --2.20342 -1.6004 -0.914684 --2.32562 -1.66618 -0.913394 --2.45511 -1.73655 -0.912422 --2.59489 -1.8113 -0.911353 --2.73469 -1.88682 -0.905441 --2.89936 -1.97525 -0.90701 --3.06503 -2.06433 -0.902631 --3.23272 -2.154 -0.8923 --3.45752 -2.2753 -0.901792 --3.64286 -2.37562 -0.885192 --3.91117 -2.52042 -0.895591 --4.09012 -2.6162 -0.860641 --4.33647 -2.74792 -0.84352 --4.59948 -2.8905 -0.82293 --4.90697 -3.05565 -0.805989 --5.26627 -3.24895 -0.792763 --5.66905 -3.4656 -0.777647 --6.10805 -3.70181 -0.755978 --6.70351 -4.02184 -0.754092 --7.41197 -4.4043 -0.753354 --6.17302 -3.73261 -0.343547 --6.19299 -3.74263 -0.205928 --9.55897 -5.55827 -0.586546 --6.31478 -3.80641 0.0586854 --6.29425 -3.79346 0.203067 --11.5855 -6.64631 -0.156895 --12.2793 -7.01805 0.0374399 --13.6029 -7.72927 0.224175 --15.876 -8.95093 0.429944 --15.7509 -8.88085 0.761632 --15.8413 -8.92735 1.08933 --15.7514 -8.87545 1.41608 --29.0836 -16.046 2.33497 --29.0347 -16.0147 2.92438 --29.2663 -16.1338 3.5366 --29.4265 -16.215 4.15201 --29.3497 -16.1691 4.74638 --29.3246 -16.1499 5.34718 --29.2736 -16.1173 5.94532 --29.2381 -16.0936 6.54742 --29.1767 -16.0545 7.14597 --29.0978 -16.0067 7.74183 --29.2588 -16.0878 8.39769 --29.1508 -16.0247 8.99328 --29.6158 -16.2688 9.75395 --8.02168 -4.69313 3.72344 --7.83559 -4.59181 3.84926 --7.78285 -4.56165 4.01587 --7.82835 -4.58494 4.21892 --7.58649 -4.45348 4.31249 --7.40259 -4.35385 4.42179 --7.38293 -4.34132 4.59724 --7.32713 -4.30966 4.75764 --7.40666 -4.35079 4.98416 --7.58632 -4.44522 5.26816 --7.50363 -4.39936 5.42395 --7.44365 -4.3656 5.59113 --7.38783 -4.33443 5.76177 --7.32164 -4.29714 5.92683 --7.38449 -4.32924 6.1738 --7.2667 -4.26447 6.30876 --6.8972 -4.06606 6.26948 --6.64433 -3.92949 6.29732 --6.37809 -3.78567 6.30578 --6.23773 -3.70919 6.40094 --6.34177 -3.76287 6.68835 --6.46738 -3.82785 7.00512 --6.75476 -3.97883 7.47366 --6.61329 -3.90167 7.5839 --6.59341 -3.88893 7.80439 --6.64355 -3.91351 8.09715 --6.7204 -3.9517 8.42674 --6.83528 -4.01009 8.80848 --7.07466 -4.13473 9.34083 --7.42807 -4.31822 10.0243 --7.3008 -4.24905 10.1987 --7.50786 -4.35576 10.7679 --7.03889 -4.10448 10.5405 --6.83854 -3.99601 10.6257 --7.46996 -4.3261 11.7965 --7.12245 -4.13968 11.7112 --6.07119 -3.58337 10.6174 --6.17194 -3.63289 11.1141 --5.99015 -3.53384 11.2091 --5.63078 -3.34205 11.0241 --5.3506 -3.19247 10.9431 --2.88312 -1.89642 7.15465 --2.77414 -1.83755 7.20026 --3.48116 -2.2044 8.73111 --4.42328 -2.69368 10.824 --4.22848 -2.58842 10.8376 --2.45497 -1.66231 7.60325 --1.65413 -1.24313 6.16992 --1.58332 -1.20408 6.23442 --2.15861 -1.50042 7.81053 --1.53675 -1.1765 6.60466 --1.42908 -1.11833 6.59395 --1.40822 -1.10581 6.81124 --1.47081 -1.13496 7.27994 --1.29273 -1.0403 7.07955 --1.21458 -0.99761 7.16584 --1.10491 -0.939513 7.15622 --1.02163 -0.893751 7.22981 --0.907844 -0.832059 7.19655 --0.664469 -0.705795 6.64105 --0.587479 -0.66406 6.70668 --0.505405 -0.620176 6.76115 --0.449449 -0.587563 6.94083 --0.29586 -0.507906 6.63063 --0.755265 -0.727093 9.84287 --0.113683 -0.409654 6.60885 --0.0614873 -0.379701 6.8719 -0.0356281 -0.327595 6.82732 -0.0893302 -0.296401 7.1779 -0.149495 -0.26013 7.55782 -0.260665 -0.20153 7.43882 -0.379999 -0.139887 7.10795 -0.472316 -0.0900061 7.13401 -0.570148 -0.038473 7.03829 --2.06079 -1.42872 -0.919734 --2.16819 -1.48215 -0.914361 --2.2839 -1.54016 -0.9103 --2.4151 -1.60553 -0.911763 --2.56392 -1.68009 -0.917842 --2.69823 -1.74781 -0.909753 --2.84076 -1.81903 -0.901427 --3.01648 -1.90787 -0.90439 --3.18482 -1.99163 -0.897148 --3.36356 -2.08167 -0.887713 --3.60022 -2.20025 -0.897245 --3.78922 -2.29517 -0.877177 --4.08788 -2.44444 -0.893425 --4.28613 -2.54419 -0.860731 --4.54537 -2.67403 -0.841798 --4.83047 -2.8173 -0.821602 --5.16097 -2.98203 -0.803999 --5.54321 -3.17385 -0.788863 --5.97093 -3.38885 -0.770728 --6.54751 -3.6781 -0.772604 --7.60816 -4.21118 -0.860116 --7.45206 -4.13137 -0.65851 --6.26211 -3.52835 0.00566568 --6.23243 -3.51302 0.148757 --6.23682 -3.51394 0.286607 --12.2443 -6.53041 -0.0785 --13.2859 -7.05194 0.110213 --15.4248 -8.1235 0.290231 --15.6845 -8.25091 0.600408 --15.4213 -8.11639 0.923336 --15.8411 -8.32481 1.24546 --16.801 -8.80282 1.60221 --37.8813 -19.3681 3.06647 --37.4536 -19.1473 3.79227 --32.925 -16.8727 4.12406 --36.3527 -18.5837 5.17116 --36.55 -18.6766 5.93021 --35.1058 -17.9423 7.16565 --34.5486 -17.6577 7.77706 --34.6334 -17.6937 8.50619 --31.7207 -16.2267 9.21148 --32.5723 -16.6462 10.1122 --30.3681 -15.5404 10.1566 --8.03697 -4.38832 3.78338 --8.06993 -4.40263 3.98059 --7.5966 -4.16542 4.00055 --7.78637 -4.25879 4.25314 --7.7688 -4.24792 4.43309 --7.69767 -4.21123 4.59202 --7.67493 -4.19769 4.7715 --7.94494 -4.33108 5.09016 --7.56974 -4.14228 5.10667 --7.57794 -4.14493 5.30631 --7.38938 -4.05019 5.4034 --7.32025 -4.01341 5.56185 --7.32017 -4.01158 5.7607 --7.3706 -4.03605 5.99469 --7.44765 -4.07181 6.25167 --6.71865 -3.70893 5.9821 --6.69384 -3.69439 6.16401 --6.76375 -3.72778 6.41691 --6.45491 -3.57292 6.39636 --6.37041 -3.52896 6.53631 --6.63265 -3.65786 6.95482 --6.43903 -3.55928 7.01443 --6.48618 -3.58156 7.27632 --6.6813 -3.67616 7.67949 --7.03156 -3.84762 8.24536 --6.99308 -3.82586 8.46796 --6.60834 -3.63419 8.35179 --6.42706 -3.54213 8.42654 --7.13441 -3.88932 9.44329 --6.6706 -3.6581 9.22994 --6.90512 -3.77069 9.78879 --6.8418 -3.73676 10.0241 --6.55478 -3.59413 9.99333 --6.48526 -3.55677 10.2247 --6.39317 -3.50886 10.4331 --6.21183 -3.41698 10.5246 --6.06847 -3.34436 10.6668 --6.15059 -3.38211 11.1405 --5.72637 -3.17137 10.8704 --5.51021 -3.06173 10.8972 --3.00657 -1.83636 7.18391 --2.85073 -1.75888 7.15605 --2.73988 -1.7022 7.20015 --4.85872 -2.72843 11.7369 --4.35649 -2.48037 11.1817 --4.04362 -2.32557 10.9626 --1.61018 -1.14453 6.14861 --1.6538 -1.16297 6.47196 --1.58004 -1.12567 6.54534 --1.51543 -1.09254 6.64482 --1.37744 -1.02385 6.55966 --1.37291 -1.02011 6.82267 --1.40686 -1.03359 7.21739 --1.27492 -0.9674 7.15542 --1.16138 -0.910954 7.13744 --1.07931 -0.869621 7.22137 --0.961724 -0.810573 7.1799 --0.758125 -0.710855 6.80925 --0.634756 -0.650359 6.70288 --0.56592 -0.614782 6.81643 --0.545331 -0.601394 7.17215 --0.343609 -0.504604 6.65928 --0.244629 -0.455305 6.62104 --0.159687 -0.412398 6.65931 --0.0956617 -0.3785 6.83426 -0.00623547 -0.328621 6.77083 -0.0834326 -0.288077 6.89359 -0.12646 -0.262393 7.38299 -0.218925 -0.215325 7.47387 -0.344118 -0.155469 7.13433 -0.442081 -0.106847 7.10143 -0.538953 -0.0587482 7.05666 -0.633027 -0.0111039 7.05998 --2.12815 -1.36714 -0.912916 --2.26016 -1.42877 -0.920864 --2.37767 -1.48355 -0.914645 --2.51173 -1.54663 -0.913794 --2.64675 -1.60942 -0.908345 --2.79932 -1.68038 -0.906962 --2.95291 -1.75202 -0.900231 --3.13129 -1.83553 -0.90033 --3.31163 -1.91862 -0.894128 --3.53437 -2.02282 -0.900071 --3.75086 -2.12381 -0.894406 --3.95903 -2.22074 -0.877693 --4.24571 -2.35511 -0.882351 --4.48169 -2.46505 -0.858271 --4.74446 -2.58741 -0.834272 --5.07014 -2.73854 -0.819777 --5.4134 -2.89931 -0.798464 --5.78442 -3.07216 -0.771532 --6.27099 -3.29896 -0.759662 --7.32632 -3.79288 -0.860253 --7.51533 -3.87969 -0.737256 --7.40914 -3.82874 -0.551361 --9.1513 -4.64299 -0.686576 --6.20623 -3.26346 -0.045832 --6.18691 -3.25368 0.0939091 --6.2635 -3.28787 0.221446 --12.9648 -6.41875 -0.261835 --13.1923 -6.523 -0.0118213 --14.5913 -7.17409 0.183168 --15.8705 -7.76939 0.435747 --15.9058 -7.78345 0.756411 --15.6184 -7.64649 1.07693 --15.86 -7.75737 1.39866 --17.4549 -8.49837 1.78734 --38.2365 -18.1835 3.4235 --34.5614 -16.464 3.87989 --34.1156 -16.2515 4.52025 --34.1283 -16.2522 5.20042 --34.1215 -16.2439 5.8808 --32.4649 -15.4621 6.95634 --32.1441 -15.3085 7.55132 --32.056 -15.2622 8.18814 --31.345 -14.9268 8.6776 --30.9913 -14.757 9.23558 --31.1134 -14.8091 9.91713 --31.1355 -14.8141 10.5796 --32.0262 -15.2228 11.5273 --9.92587 -4.96244 4.67081 --9.86701 -4.93373 4.87649 --8.17638 -4.14794 4.45602 --8.10433 -4.113 4.62114 --7.77617 -3.95959 4.676 --8.52385 -4.30455 5.20306 --7.44706 -3.80462 4.90479 --8.69222 -4.37956 5.71049 --7.31134 -3.73926 5.2151 --7.45622 -3.80438 5.48507 --7.65142 -3.89263 5.79392 --7.6061 -3.87036 5.97439 --7.70977 -3.91676 6.24742 --7.67264 -3.89841 6.44026 --7.05091 -3.60864 6.24462 --7.8047 -3.95516 6.97555 --6.42531 -3.31792 6.21439 --6.38723 -3.29867 6.38606 --7.04418 -3.59974 7.09968 --6.80066 -3.4855 7.1312 --6.49974 -3.3454 7.10683 --6.46772 -3.32865 7.3017 --7.04307 -3.59195 8.04696 --7.03551 -3.58622 8.29322 --6.72745 -3.44307 8.25803 --6.53835 -3.35375 8.32745 --6.50106 -3.33497 8.54931 --6.47294 -3.31993 8.78584 --6.36796 -3.27021 8.94538 --6.70138 -3.4198 9.60856 --6.80013 -3.46315 10.03 --6.62632 -3.38107 10.137 --6.47504 -3.30937 10.2704 --6.43844 -3.29048 10.5544 --6.53173 -3.33062 11.0269 --6.19419 -3.1741 10.913 --5.89556 -3.03441 10.8372 --5.71262 -2.9489 10.9235 --3.07765 -1.74849 7.12969 --2.97523 -1.7003 7.1947 --2.81254 -1.62474 7.15667 --2.83631 -1.63072 7.69482 --4.6682 -2.45691 11.4774 --4.35275 -2.3111 11.2825 --2.55331 -1.49657 7.97365 --1.7193 -1.1192 6.46572 --1.69154 -1.10582 6.64807 --1.58327 -1.05512 6.64933 --1.50143 -1.01582 6.71223 --1.36169 -0.951292 6.62616 --1.38455 -0.959799 6.97289 --1.3057 -0.92211 7.06033 --1.21363 -0.878119 7.1089 --1.14899 -0.847925 7.25039 --0.971872 -0.766737 7.01993 --0.811087 -0.692411 6.81326 --0.676772 -0.63093 6.67942 --0.621239 -0.604686 6.85151 --0.518203 -0.555856 6.82898 --0.381158 -0.494337 6.63855 --0.299338 -0.455148 6.69916 --0.197569 -0.408555 6.65021 --0.106755 -0.365493 6.65829 --0.0358599 -0.331507 6.80295 -0.0461014 -0.292679 6.89691 -0.0839947 -0.270696 7.40656 -0.16852 -0.229691 7.58801 -0.314141 -0.166357 7.08053 -0.412007 -0.120201 7.05847 -0.509703 -0.075114 7.01464 -0.603735 -0.0314598 7.05881 --2.11518 -1.26752 -0.931128 --2.21701 -1.312 -0.920532 --2.34355 -1.36658 -0.921259 --2.47106 -1.42089 -0.917787 --2.59965 -1.47694 -0.910017 --2.74468 -1.53923 -0.906815 --2.89998 -1.60589 -0.902919 --3.07182 -1.68072 -0.901894 --3.25387 -1.75885 -0.898926 --3.44525 -1.8423 -0.893219 --3.68085 -1.94371 -0.899098 --3.89994 -2.03834 -0.88972 --4.13753 -2.14082 -0.87911 --4.42868 -2.26665 -0.878846 --4.70331 -2.38565 -0.862127 --4.97061 -2.50045 -0.832656 --5.30074 -2.64299 -0.812141 --5.64009 -2.78951 -0.782046 --6.01644 -2.9517 -0.748787 --6.55449 -3.18457 -0.740119 --7.74232 -3.69817 -0.852616 --7.36546 -3.53332 -0.609068 --6.05982 -2.96676 -0.215448 --6.01482 -2.94644 -0.074425 --5.94925 -2.9173 0.0670046 --6.14618 -3.00142 0.173812 --13.1772 -6.04386 -0.404329 --13.821 -6.32029 -0.189237 --14.2322 -6.49653 0.0644574 --16.1992 -7.34475 0.264792 --15.9072 -7.21557 0.595867 --15.7739 -7.15666 0.914721 --16.1867 -7.33248 1.23549 --16.6961 -7.54967 1.57517 --34.2655 -15.1328 2.80774 --34.554 -15.2527 3.49674 --34.6017 -15.2683 4.17682 --34.9033 -15.3933 4.8881 --34.3177 -15.1365 5.49996 --34.4424 -15.1848 6.19636 --31.9318 -14.0985 6.46215 --32.1677 -14.1949 7.14417 --31.9124 -14.0805 7.73839 --31.6119 -13.9466 8.31667 --31.2056 -13.7666 8.86131 --30.8179 -13.5958 9.39985 --30.7866 -13.5775 10.0299 --30.7718 -13.5667 10.6694 --31.291 -13.7856 11.4891 --10.357 -4.78713 4.88957 --9.87519 -4.57866 4.94732 --9.39653 -4.37084 4.98801 --9.56371 -4.44171 5.27676 --9.23809 -4.29966 5.36223 --9.64227 -4.47176 5.76846 --9.57329 -4.44084 5.97025 --9.36777 -4.35033 6.10406 --7.95079 -3.74179 5.59863 --7.88505 -3.71225 5.76887 --7.88086 -3.7093 5.97505 --9.22816 -4.28378 6.98899 --7.70931 -3.63247 6.29713 --7.40262 -3.49964 6.31512 --7.36355 -3.48171 6.50177 --6.61729 -3.16174 6.19712 --6.61 -3.15649 6.39275 --6.59147 -3.14713 6.58398 --6.59036 -3.14582 6.79367 --6.6158 -3.15469 7.02879 --6.86754 -3.26042 7.46229 --7.10791 -3.36126 7.90708 --7.13831 -3.37278 8.18393 --6.96699 -3.29804 8.28153 --6.91131 -3.27212 8.48778 --6.57429 -3.12751 8.41625 --6.50224 -3.09449 8.60349 --5.44325 -2.64381 7.73538 --6.94921 -3.28045 9.64902 --6.84834 -3.23502 9.83853 --5.6712 -2.73433 8.74736 --6.58018 -3.11661 10.146 --6.31381 -3.00198 10.1323 --6.0904 -2.9055 10.1653 --6.3316 -3.00451 10.8282 --6.06732 -2.89092 10.811 --5.91532 -2.82411 10.9478 --3.03316 -1.6079 6.90397 --3.01665 -1.59919 7.09975 --2.80231 -1.50778 6.97913 --2.68174 -1.45464 7.00431 --2.76299 -1.48699 7.38571 --2.82781 -1.5125 7.76313 --2.5382 -1.38946 7.48217 --1.79165 -1.07416 6.47669 --1.68771 -1.02967 6.4892 --1.5959 -0.989224 6.52664 --1.54073 -0.965212 6.65329 --1.49761 -0.94469 6.81624 --1.58732 -0.979493 7.3401 --1.39809 -0.899427 7.14224 --1.27382 -0.846441 7.10802 --1.21024 -0.817149 7.25026 --1.04555 -0.74734 7.07863 --0.964846 -0.712576 7.17 --0.808379 -0.645627 6.99137 --0.661212 -0.583844 6.81856 --0.616686 -0.562075 7.04883 --0.423487 -0.481833 6.63686 --0.336884 -0.444861 6.67882 --0.231192 -0.398942 6.62107 --0.141596 -0.360294 6.63979 --0.0738366 -0.33012 6.80488 -0.0158912 -0.290653 6.84028 -0.0554531 -0.270213 7.30063 -0.155368 -0.22696 7.32366 -0.271796 -0.177635 7.16562 -0.37729 -0.132332 7.07496 -0.475004 -0.0902333 7.07202 -0.572703 -0.048228 7.06719 -0.694557 -0.00366675 6.03086 --2.29736 -1.24903 -0.92189 --2.4257 -1.3004 -0.920559 --2.56326 -1.35523 -0.919585 --2.71006 -1.41352 -0.918569 --2.85787 -1.4725 -0.912605 --3.00665 -1.53118 -0.901743 --3.20693 -1.61177 -0.909923 --3.36594 -1.67449 -0.891873 --3.57743 -1.75896 -0.890664 --3.82489 -1.85763 -0.896283 --4.04764 -1.94683 -0.882938 --4.32377 -2.05645 -0.881286 --4.6102 -2.17113 -0.872696 --4.9418 -2.30336 -0.868495 --5.21262 -2.41063 -0.833258 --5.52047 -2.53376 -0.798653 --5.88271 -2.67783 -0.767297 --6.39911 -2.88403 -0.76061 --7.47252 -3.31261 -0.859962 --7.31026 -3.2465 -0.66414 --6.13015 -2.77116 -0.0177458 --6.13764 -2.77317 0.114475 --6.09584 -2.75585 0.251766 --14.5191 -6.11919 -0.382247 --14.9201 -6.2776 -0.120798 --15.66 -6.57119 0.136945 --16.4613 -6.88891 0.419985 --16.2553 -6.80483 0.748345 --16.2391 -6.7959 1.06938 --16.7013 -6.97726 1.40032 --41.0593 -16.6834 2.72676 --39.5802 -16.089 3.42713 --35.349 -14.3984 3.85673 --39.5186 -16.0545 4.94743 --38.8126 -15.7683 5.63058 --39.1665 -15.9038 6.4333 --39.6168 -16.0779 7.26761 --39.7685 -16.1332 8.07111 --33.6127 -13.6805 7.66645 --33.1906 -13.5087 8.24642 --32.3523 -13.1708 8.71764 --31.952 -13.0081 9.27129 --11.0351 -4.69924 4.23809 --10.9006 -4.64435 4.43688 --10.7455 -4.58114 4.626 --10.8723 -4.62987 4.90483 --10.6404 -4.53564 5.06468 --9.6863 -4.15673 4.94774 --9.53446 -4.09465 5.1101 --9.37961 -4.03198 5.268 --9.26679 -3.98612 5.44018 --9.44992 -4.05713 5.74718 --33.448 -13.5487 17.5622 --32.7721 -13.276 17.9989 --6.86216 -3.02883 5.07985 --7.8797 -3.43009 5.82196 --9.4813 -4.06066 6.95259 --9.09112 -3.90584 6.96974 --9.00178 -3.86869 7.16005 --7.81878 -3.40024 6.63962 --7.34089 -3.21036 6.54012 --7.41332 -3.23686 6.80752 --6.8415 -3.01022 6.61307 --6.65839 -2.93736 6.68704 --7.63966 -3.32181 7.67074 --6.94528 -3.04658 7.35128 --6.92258 -3.03639 7.56416 --7.81028 -3.38375 8.58034 --7.111 -3.1069 8.21871 --7.18215 -3.1336 8.54428 --6.97646 -3.05134 8.61292 --7.34866 -3.19449 9.25756 --5.51767 -2.47555 7.63969 --6.38091 -2.81186 8.80742 --6.86005 -2.99741 9.6196 --5.66881 -2.52986 8.54496 --6.68843 -2.92691 10.0368 --6.83354 -2.98148 10.5395 --6.55331 -2.86896 10.5205 --6.46888 -2.83354 10.7509 --3.09304 -1.517 6.43911 --2.98806 -1.47478 6.48787 --3.1825 -1.54896 6.98015 --3.09064 -1.5113 7.06258 --2.76371 -1.38308 6.76965 --2.75538 -1.37822 6.97891 --2.74192 -1.3716 7.18964 --2.69894 -1.35378 7.35863 --2.61418 -1.31884 7.45848 --4.01673 -1.85778 10.4569 --2.54722 -1.28917 7.87531 --1.75296 -0.982469 6.49181 --1.64814 -0.940082 6.50332 --1.6488 -0.938463 6.75766 --1.49532 -0.87751 6.65673 --1.57388 -0.906337 7.13265 --1.69666 -0.950533 7.77068 --1.30447 -0.799684 7.02247 --1.30775 -0.798674 7.36246 --1.20484 -0.756816 7.40145 --1.00619 -0.680244 7.12438 --0.839894 -0.614242 6.91838 --0.79759 -0.596246 7.15076 --0.625494 -0.529293 6.89009 --0.511827 -0.48454 6.83874 --0.365211 -0.428055 6.61915 --0.281699 -0.393987 6.67969 --0.174277 -0.351719 6.61109 --0.0877529 -0.316481 6.65844 --0.0329245 -0.292696 6.92166 -0.0567312 -0.256786 6.98638 -0.109223 -0.233068 7.387 -0.183817 -0.201096 7.69782 -0.342689 -0.142489 7.09095 -0.435582 -0.104625 7.17877 -0.543575 -0.0625949 7.02517 -0.639301 -0.0240515 7.06948 --2.23801 -1.12997 -0.91639 --2.35992 -1.17457 -0.912438 --2.48179 -1.21898 -0.904591 --2.63757 -1.27609 -0.911072 --2.7861 -1.33016 -0.907947 --2.92745 -1.38219 -0.895567 --3.12114 -1.45313 -0.903273 --3.29012 -1.5146 -0.892414 --3.47657 -1.58314 -0.883374 --3.70812 -1.66759 -0.886312 --3.94167 -1.75253 -0.881101 --4.20191 -1.84798 -0.877667 --4.46414 -1.94386 -0.865185 --4.75404 -2.0501 -0.852376 --5.2071 -2.21668 -0.879974 --5.44551 -2.30301 -0.827898 --5.73933 -2.41039 -0.782262 --6.11514 -2.54744 -0.747039 --7.08693 -2.90346 -0.837239 --7.51283 -3.05915 -0.773872 --7.2545 -2.96296 -0.562462 --6.06641 -2.52569 -0.0671496 --6.02774 -2.51023 0.069256 --6.03319 -2.51152 0.198422 --13.8605 -5.38 -0.450975 --16.0925 -6.19636 -0.355747 --16.5254 -6.35246 -0.0662265 --17.2164 -6.60408 0.227618 --17.1429 -6.57471 0.565715 --17.1861 -6.58861 0.900051 --17.3636 -6.65144 1.23745 --18.5133 -7.06998 1.61169 --41.3269 -15.4089 3.10181 --41.2785 -15.386 3.88467 --40.3271 -15.0344 4.58901 --38.9087 -14.5105 5.21051 --38.9292 -14.5132 5.96033 --40.5838 -15.1136 6.94802 --33.144 -12.3891 7.17461 --33.2511 -12.4245 7.84782 --33.577 -12.5391 8.57741 --10.4945 -4.12133 3.94903 --10.4728 -4.11183 4.16696 --10.3018 -4.04829 4.34171 --10.4622 -4.10519 4.61721 --10.5008 -4.11689 4.86018 --9.87479 -3.88846 4.86886 --9.84599 -3.87667 5.08102 --9.9102 -3.89846 5.33201 --9.33137 -3.68641 5.31703 --9.42423 -3.71898 5.57878 --9.21046 -3.64039 5.7047 --8.99569 -3.56118 5.82407 --7.1113 -2.87517 5.08378 --6.79159 -2.75844 5.09635 --8.87328 -3.51067 6.66797 --8.78721 -3.47763 6.8526 --8.74711 -3.46142 7.06636 --7.45431 -2.99275 6.46155 --7.7441 -3.09623 6.87391 --7.59178 -3.0393 6.99377 --7.52422 -3.01346 7.17229 --7.81894 -3.11941 7.63007 --7.11361 -2.86252 7.31823 --7.28476 -2.92295 7.69121 --7.4538 -2.98281 8.07855 --6.15633 -2.51338 7.19122 --6.45388 -2.61936 7.68527 --6.97651 -2.80523 8.418 --6.75799 -2.7247 8.46729 --5.60003 -2.30713 7.55788 --5.5122 -2.2744 7.69775 --5.68986 -2.33513 8.38057 --6.51931 -2.63131 9.60965 --6.59501 -2.65615 10.0078 --6.5505 -2.63761 10.274 --6.50499 -2.61969 10.5491 --3.25215 -1.45489 6.52702 --3.0873 -1.39402 6.4989 --2.91338 -1.3307 6.45027 --2.92145 -1.33255 6.66609 --2.88172 -1.3174 6.81772 --2.75048 -1.26867 6.82761 --2.80517 -1.28764 7.14696 --2.69014 -1.24441 7.18809 --2.61173 -1.2157 7.296 --2.79999 -1.28029 7.9084 --2.65451 -1.22764 7.91338 --1.84827 -0.940428 6.55597 --1.78623 -0.917562 6.6679 --1.71398 -0.890226 6.76101 --1.59616 -0.846587 6.75293 --1.64732 -0.863652 7.15557 --1.46077 -0.796416 6.97888 --1.36921 -0.761836 7.03934 --1.37561 -0.762633 7.37955 --1.25175 -0.717766 7.36315 --1.09061 -0.659333 7.22074 --0.901424 -0.591419 6.9598 --0.839089 -0.567376 7.11602 --0.72348 -0.525575 7.08843 --0.55078 -0.464241 6.81632 --0.416323 -0.415618 6.6661 --0.339966 -0.387149 6.76682 --0.213701 -0.341813 6.62123 --0.119432 -0.307942 6.63023 --0.056839 -0.283528 6.8347 -0.0286812 -0.251375 6.91975 -0.112325 -0.220218 7.04312 -0.167904 -0.196727 7.46315 -0.309271 -0.147209 7.07643 -0.408651 -0.111641 7.08541 -0.36495 -0.111788 9.61819 -0.609371 -0.0383749 7.06782 -0.743097 0.00218334 5.64161 --2.19232 -1.02056 -0.919821 --2.30579 -1.0585 -0.912859 --2.43671 -1.1027 -0.911859 --2.56858 -1.14664 -0.90666 --2.7353 -1.20219 -0.915133 --2.86096 -1.24382 -0.896379 --3.0379 -1.30346 -0.898664 --3.22506 -1.3664 -0.899104 --3.41317 -1.42897 -0.893247 --3.62073 -1.49844 -0.8884 --3.84669 -1.57383 -0.883618 --4.09103 -1.65508 -0.877902 --4.37325 -1.74931 -0.876658 --4.66564 -1.84661 -0.868674 --4.9867 -1.95413 -0.859162 --5.34453 -2.07346 -0.84928 --5.63165 -2.16933 -0.806265 --5.97399 -2.28315 -0.76754 --6.51085 -2.46317 -0.763579 --7.54101 -2.80741 -0.849092 --8.32533 -3.06984 -0.846343 --8.95284 -3.27871 -0.786185 --8.37256 -3.08317 -0.505097 --8.42485 -3.09984 -0.338762 --8.44643 -3.10609 -0.167374 --13.3986 -4.76278 -0.528683 --15.0095 -5.30043 -0.407783 --16.5168 -5.80294 -0.220641 --16.5161 -5.80109 0.10056 --16.2832 -5.72063 0.429086 --16.0821 -5.65175 0.748219 --16.3494 -5.73946 1.06101 --36.584 -12.4947 1.80623 --41.5991 -14.1658 2.69457 --41.557 -14.1467 3.47526 --40.1014 -13.6521 4.90651 --37.3156 -12.719 5.35117 --34.5023 -11.774 6.35371 --34.2883 -11.6985 6.983 --33.8955 -11.5636 7.57422 --32.7684 -11.1841 8.00197 --32.9079 -11.2274 8.67863 --33.3874 -11.3829 9.44898 --10.4425 -3.74881 4.02013 --10.6302 -3.81006 4.29586 --10.4279 -3.7418 4.46242 --10.098 -3.63045 4.58131 --9.96517 -3.5856 4.75758 --9.73129 -3.5067 4.89404 --9.77294 -3.51857 5.12974 --7.71172 -2.8341 4.51318 --7.66175 -2.81609 4.6742 --7.02423 -2.60393 4.57115 --7.44962 -2.74325 4.945 --7.41804 -2.73175 5.11439 --6.93065 -2.56978 5.05023 --6.88888 -2.5545 5.20685 --9.12874 -3.29447 6.65096 --8.77681 -3.17672 6.68305 --7.81138 -2.85648 6.3272 --5.86989 -2.21389 5.30664 --7.74388 -2.83216 6.71776 --7.58474 -2.77795 6.83149 --7.59779 -2.78065 7.06471 --7.34093 -2.69489 7.10434 --7.61468 -2.78397 7.5434 --7.43726 -2.7245 7.64411 --7.27506 -2.66873 7.75253 --6.27829 -2.33986 7.14361 --6.19773 -2.31222 7.2935 --7.18757 -2.63545 8.42915 --6.25327 -2.32766 7.80443 --5.79324 -2.17538 7.59238 --5.58856 -2.10631 7.61641 --7.21422 -2.63844 9.57021 --7.20954 -2.63494 9.86887 --5.4983 -2.07272 8.24192 --5.47867 -2.06526 8.47699 --5.22428 -1.98046 8.43367 --6.54426 -2.40984 10.364 --3.3417 -1.36159 6.51924 --3.20263 -1.31617 6.53263 --3.0371 -1.26045 6.50266 --2.92339 -1.22228 6.54114 --2.85837 -1.19969 6.65106 --2.96068 -1.23209 7.02601 --2.72627 -1.15433 6.87707 --2.9105 -1.21268 7.41785 --2.69643 -1.14231 7.29747 --2.62013 -1.11606 7.41412 --2.73412 -1.15139 7.89765 --2.58485 -1.10151 7.89202 --2.28087 -1.00183 7.56183 --2.0145 -0.914702 7.27681 --1.6543 -0.797177 6.74806 --1.7094 -0.813027 7.15016 --1.45251 -0.729079 6.8096 --1.37332 -0.702407 6.89778 --1.47249 -0.732738 7.48007 --1.31052 -0.679155 7.36222 --1.14662 -0.624823 7.22139 --1.15474 -0.625669 7.61919 --0.865388 -0.53178 7.03318 --0.765019 -0.498194 7.06408 --0.593576 -0.442773 6.8128 --0.486337 -0.407236 6.79029 --0.365134 -0.367012 6.69725 --0.258947 -0.331129 6.66021 --0.165773 -0.299663 6.68005 --0.0943958 -0.275172 6.83608 --0.0100312 -0.246427 6.93193 -0.077377 -0.216934 7.02631 -0.192293 -0.17945 6.91082 -0.27597 -0.149949 7.0615 -0.376236 -0.116392 7.07148 -0.480249 -0.0821154 7.01962 -0.578603 -0.0491504 7.05577 -0.724493 -0.00878004 5.66082 --2.26426 -0.951134 -0.922164 --2.37954 -0.985857 -0.913242 --2.51219 -1.02584 -0.910134 --2.654 -1.06829 -0.907432 --2.80604 -1.11413 -0.904483 --2.96731 -1.16339 -0.900893 --3.13872 -1.21499 -0.896107 --3.33675 -1.27532 -0.897491 --3.54491 -1.33791 -0.896181 --3.76328 -1.40372 -0.891329 --3.99189 -1.47373 -0.882584 --4.24802 -1.55122 -0.87596 --4.53371 -1.63698 -0.870097 --4.8562 -1.73467 -0.866163 --5.1991 -1.83887 -0.856741 --5.63588 -1.97022 -0.861867 --5.92552 -2.05857 -0.811792 --6.27224 -2.16273 -0.765698 --7.1697 -2.43488 -0.833769 --7.98827 -2.68223 -0.851817 --8.52581 -2.84513 -0.786615 --9.7261 -3.20742 -0.816235 --8.34415 -2.78806 -0.405574 --8.37693 -2.79683 -0.238079 --8.33007 -2.78186 -0.0610635 --37.1492 -11.4939 1.45655 --41.9017 -12.9277 2.29252 --41.8556 -12.9089 3.0716 --38.9878 -12.0387 3.66297 --36.2765 -11.2157 4.16408 --36.2483 -11.2027 4.84427 --36.1418 -11.1678 5.51624 --34.3819 -10.6325 5.95548 --34.7017 -10.7255 6.66233 --34.3392 -10.6123 7.26357 --33.8821 -10.4711 7.83655 --33.3607 -10.311 8.38277 --10.6478 -3.46054 4.16248 --10.5111 -3.41847 4.34807 --10.3713 -3.37477 4.52965 --10.2743 -3.34499 4.72237 --9.34917 -3.06482 4.62182 --9.39594 -3.07785 4.84831 --9.66163 -3.1564 5.16564 --7.73888 -2.57786 4.59042 --7.13002 -2.39401 4.50861 --6.93061 -2.33381 4.59019 --7.37453 -2.4655 4.97402 --7.15268 -2.39808 5.04625 --7.01533 -2.35578 5.15633 --7.15785 -2.3975 5.41582 --6.55351 -2.21604 5.25997 --7.88837 -2.61488 6.23074 --6.07754 -2.07105 5.32489 --6.08578 -2.07272 5.50376 --5.86521 -2.00634 5.53321 --5.63751 -1.93699 5.55043 --5.56038 -1.91372 5.66873 --5.3805 -1.85835 5.70985 --7.85447 -2.59604 7.80469 --7.5117 -2.4926 7.77979 --7.27061 -2.41962 7.82577 --6.35192 -2.14419 7.27805 --6.47872 -2.18088 7.61747 --6.23882 -2.10843 7.63125 --5.9644 -2.02503 7.60426 --5.71543 -1.94949 7.59018 --5.6178 -1.91968 7.72361 --7.31536 -2.42274 9.77148 --5.93685 -2.0114 8.56006 --5.4871 -1.87724 8.31393 --5.3701 -1.84112 8.43649 --5.25816 -1.80641 8.56467 --6.52998 -2.18157 10.4537 --3.28807 -1.22107 6.52583 --3.09047 -1.16214 6.4581 --6.34297 -2.12055 11.2647 --6.23766 -2.08752 11.4928 --3.21362 -1.19424 7.27896 --2.88146 -1.09604 6.99368 --3.07448 -1.15143 7.54299 --2.82935 -1.07785 7.38366 --2.62072 -1.01488 7.26918 --2.56783 -0.998158 7.42804 --2.67453 -1.02831 7.90365 --2.55482 -0.991687 7.95868 --2.11415 -0.861447 7.33936 --1.7081 -0.741491 6.73343 --1.7662 -0.757179 7.13515 --1.57622 -0.700539 6.97148 --1.40345 -0.648755 6.8305 --1.58207 -0.699755 7.60717 --1.35092 -0.630979 7.31361 --1.31292 -0.618458 7.5517 --1.076 -0.548289 7.19214 --0.949641 -0.509834 7.15061 --0.803338 -0.466491 7.02969 --0.695159 -0.433859 7.03064 --0.554033 -0.39199 6.8939 --0.393084 -0.34475 6.64691 --0.295053 -0.314421 6.64976 --0.210017 -0.289014 6.71953 --0.147654 -0.26852 6.92559 --0.0485661 -0.238507 6.94356 -0.0613487 -0.205138 6.88058 -0.158427 -0.175707 6.9046 -0.25747 -0.145969 6.91698 -0.341976 -0.12007 7.07694 -0.438367 -0.0898891 7.1557 -0.547033 -0.0574004 7.05322 -0.69507 -0.0192516 5.91949 -0.781864 0.0063459 5.73232 --2.227 -0.84774 -0.935846 --2.32675 -0.874954 -0.918404 --2.45203 -0.909224 -0.91253 --2.58548 -0.946044 -0.907368 --2.74644 -0.989687 -0.911465 --2.89201 -1.02855 -0.901601 --3.06314 -1.07529 -0.899659 --3.24549 -1.12529 -0.896067 --3.44512 -1.17934 -0.894343 --3.63862 -1.23225 -0.88211 --3.88617 -1.29968 -0.884857 --4.15304 -1.37189 -0.886116 --4.41277 -1.44291 -0.874875 --4.71931 -1.52548 -0.870307 --5.05445 -1.61725 -0.86376 --5.40987 -1.71352 -0.851225 --5.8693 -1.8384 -0.854488 --6.35926 -1.97202 -0.848871 --6.91643 -2.12357 -0.841643 --7.57855 -2.30404 -0.837475 --8.45163 -2.54188 -0.851355 --9.41324 -2.80368 -0.849643 --10.3869 -3.06815 -0.815166 --11.6784 -3.41926 -0.79115 --8.21043 -2.47234 -0.126268 --8.19019 -2.46617 0.0430786 --16.1651 -4.63916 -0.495237 --42.2567 -11.7346 0.332664 --42.2434 -11.7268 1.11354 --42.1781 -11.7051 1.89293 --42.1292 -11.6885 2.67119 --42.0854 -11.6727 3.44883 --37.1305 -10.3227 3.85922 --37.5392 -10.4303 4.58971 --36.9165 -10.2579 5.22274 --34.9671 -9.72224 6.32399 --34.6736 -9.63927 6.93876 --34.3973 -9.56046 7.54978 --34.8324 -9.67556 8.29927 --11.1708 -3.25904 3.70515 --11.0017 -3.21275 3.89388 --10.8581 -3.17285 4.08453 --10.8142 -3.15983 4.29951 --10.7204 -3.13248 4.49998 --10.4752 -3.06558 4.65095 --10.1557 -2.9777 4.76927 --10.0366 -2.94488 4.94925 --9.47013 -2.79011 4.95741 --8.14147 -2.43072 4.64003 --8.02563 -2.39865 4.78062 --7.08252 -2.14292 4.55287 --6.88957 -2.09029 4.63568 --7.0543 -2.13409 4.88663 --7.03198 -2.12623 5.05207 --6.95387 -2.10502 5.19069 --7.30839 -2.19931 5.56797 --6.36191 -1.94399 5.21466 --6.34881 -1.93956 5.38075 --6.10923 -1.87344 5.40795 --6.01796 -1.84814 5.52364 --5.86785 -1.80732 5.59905 --5.65378 -1.74872 5.62562 --5.70161 -1.76149 5.83578 --5.79903 -1.78612 6.09027 --5.59722 -1.73162 6.12035 --5.4045 -1.67856 6.15076 --6.47853 -1.96579 7.24235 --6.31309 -1.9206 7.32344 --6.42441 -1.94882 7.6504 --6.19002 -1.88487 7.66804 --5.78034 -1.7741 7.50829 --5.91998 -1.81048 7.87893 --5.75561 -1.76563 7.95182 --6.24762 -1.89606 8.72735 --5.83398 -1.78387 8.54046 --5.6422 -1.73097 8.58671 --6.31698 -1.90959 9.66442 --6.18889 -1.87467 9.81678 --3.43106 -1.13974 6.59605 --3.27725 -1.09794 6.59479 --3.07286 -1.04189 6.51774 --3.16687 -1.06655 6.85641 --3.00097 -1.02168 6.83077 --2.95636 -1.00876 6.98367 --2.89754 -0.991521 7.11983 --2.85087 -0.978313 7.28122 --2.75468 -0.95186 7.36547 --2.5646 -0.900209 7.28333 --2.78115 -0.956409 7.94942 --2.60111 -0.906973 7.8913 --2.44033 -0.863844 7.86459 --1.75879 -0.684002 6.71849 --1.65873 -0.65605 6.75678 --1.66737 -0.657072 7.04926 --1.49792 -0.612077 6.92917 --1.60691 -0.638876 7.51006 --1.42835 -0.590519 7.36771 --1.43258 -0.590412 7.72878 --1.31928 -0.559097 7.7701 --1.20201 -0.527591 7.79987 --0.840542 -0.432869 6.99489 --0.723538 -0.401149 6.96798 --0.59559 -0.36659 6.89028 --0.431877 -0.323455 6.64477 --0.330043 -0.295788 6.63901 --0.241102 -0.270555 6.68983 --0.147276 -0.245652 6.71971 --0.0859422 -0.227161 6.9448 -0.0316557 -0.19616 6.84342 -0.126657 -0.169595 6.88803 -0.253808 -0.136275 6.66302 -0.308936 -0.119325 7.07196 -0.402211 -0.0934427 7.18159 -0.520323 -0.0624132 6.98029 -0.61743 -0.0359113 7.0464 -0.76407 -0.00212027 5.68151 --2.27009 -0.766248 -0.922688 --2.37064 -0.790341 -0.903992 --2.51301 -0.824971 -0.905975 --2.66654 -0.861941 -0.908056 --2.81189 -0.896936 -0.900787 --2.9756 -0.937028 -0.897328 --3.14841 -0.978525 -0.892827 --3.3589 -1.02928 -0.898487 --3.55206 -1.07635 -0.889447 --3.80122 -1.13685 -0.896027 --4.02378 -1.19001 -0.883753 --4.30338 -1.25738 -0.883848 --4.59315 -1.32784 -0.877704 --4.91135 -1.40457 -0.870728 --5.2417 -1.48416 -0.855505 --5.68408 -1.59212 -0.860934 --6.1487 -1.70424 -0.855972 --6.66105 -1.82729 -0.846493 --7.26095 -1.9732 -0.838304 --8.06322 -2.16709 -0.850595 --8.85822 -2.35892 -0.832807 --9.71311 -2.56529 -0.796813 --10.2137 -2.68557 -0.676625 --10.0387 -2.64273 -0.449122 --9.92676 -2.61486 -0.236208 --15.3549 -3.92825 -0.565272 --35.7484 -8.82723 6.73343 --11.023 -2.8614 3.99494 --11.1394 -2.88714 4.48712 --10.2924 -2.68186 4.68253 --10.0538 -2.62311 4.82294 --10.4727 -2.72266 5.19759 --9.79064 -2.5578 5.16579 --9.82704 -2.56596 5.40197 --7.98256 -2.12261 4.83701 --7.07065 -1.90279 4.61598 --7.00791 -1.88744 4.75921 --7.16318 -1.92383 5.00933 --7.06791 -1.9 5.14067 --7.36711 -1.97128 5.48304 --7.25659 -1.94346 5.61227 --9.23221 -2.41531 6.95952 --6.1914 -1.68761 5.35362 --5.83577 -1.60128 5.30262 --5.77004 -1.58495 5.42896 --5.78332 -1.58723 5.6095 --5.98499 -1.63447 5.92829 --5.89289 -1.61212 6.04602 --5.79875 -1.589 6.16179 --5.57901 -1.53526 6.17814 --7.07941 -1.89176 7.59869 --6.16411 -1.67288 7.05919 --6.25305 -1.69296 7.35504 --6.23875 -1.68921 7.5694 --5.8116 -1.58703 7.39932 --6.06225 -1.64479 7.87121 --5.81322 -1.58504 7.86241 --5.83214 -1.58791 8.12532 --5.97846 -1.62187 8.53645 --5.97406 -1.62011 8.79975 --6.18884 -1.66923 9.3277 --5.87608 -1.59375 9.24854 --3.5068 -1.03268 6.57938 --3.30883 -0.985143 6.52502 --3.22698 -0.964502 6.61618 --3.15929 -0.947887 6.73027 --3.16933 -0.950038 6.95784 --3.00773 -0.910541 6.9398 --3.01358 -0.910479 7.17664 --2.7623 -0.850661 7.01012 --2.55345 -0.800714 6.89629 --2.921 -0.88627 7.77757 --2.40488 -0.763796 7.11378 --2.39851 -0.761116 7.3576 --2.4917 -0.781903 7.81602 --1.81322 -0.622864 6.71191 --1.71638 -0.599229 6.76035 --1.7672 -0.609231 7.14401 --1.58894 -0.567107 7.01719 --1.40576 -0.523866 6.85823 --1.57571 -0.56173 7.60695 --1.44057 -0.528836 7.58534 --1.4126 -0.520309 7.87226 --1.25246 -0.482377 7.78043 --0.942477 -0.410544 7.17932 --0.782622 -0.371921 7.02017 --0.66487 -0.344308 6.99226 --0.495334 -0.304435 6.74877 --0.375694 -0.275133 6.6763 --0.308768 -0.258234 6.83564 --0.1734 -0.226438 6.67081 --0.159718 -0.221449 7.15215 -0.0051787 -0.182874 6.79592 -0.101907 -0.159355 6.82164 -0.223061 -0.130695 6.65718 -0.31482 -0.108599 6.70883 -0.374917 -0.0914652 7.10731 -0.487227 -0.0651219 7.00671 -0.586138 -0.0411815 7.06383 -0.747472 -0.00817232 5.64038 -0.825808 0.0112997 5.64302 --2.32734 -0.686367 -0.918851 --2.44598 -0.710771 -0.908208 --2.59015 -0.742166 -0.907833 --2.73621 -0.772223 -0.903003 --2.8915 -0.805718 -0.897831 --3.05689 -0.840572 -0.891913 --3.2589 -0.883781 -0.89681 --3.44359 -0.92331 -0.887306 --3.69329 -0.975956 -0.897871 --3.89919 -1.01892 -0.882324 --4.15088 -1.07266 -0.877001 --4.44214 -1.13427 -0.876086 --4.76184 -1.20215 -0.874638 --5.09269 -1.27297 -0.865149 --5.4722 -1.35301 -0.858128 --5.91878 -1.44831 -0.856036 --6.41504 -1.55348 -0.850666 --6.9224 -1.66125 -0.830261 --7.62369 -1.80963 -0.833568 --8.50878 -1.99763 -0.848299 --9.38656 -2.18344 -0.830155 --10.3637 -2.39058 -0.796763 --9.97672 -2.3077 -0.535351 --13.323 -3.01899 -0.750293 --9.82847 -2.27517 -0.123505 --46.0059 -9.94964 0.267424 --45.9924 -9.944 1.10548 --10.6664 -2.43525 4.44678 --10.1859 -2.33218 4.52124 --9.93853 -2.27918 4.65746 --8.0157 -1.87368 4.19337 --7.95092 -1.85882 4.34952 --7.94799 -1.85809 4.52958 --8.05033 -1.87881 4.75568 --7.92175 -1.85091 4.88837 --7.83669 -1.83157 5.03804 --7.78412 -1.82056 5.20279 --7.40449 -1.73911 5.2041 --7.11406 -1.6777 5.23875 --6.91983 -1.63644 5.31619 --7.32368 -1.72099 5.72853 --6.29366 -1.50387 5.31366 --5.72518 -1.38344 5.13756 --5.67884 -1.37355 5.27218 --5.85901 -1.41062 5.55927 --6.07245 -1.45394 5.88207 --5.83593 -1.40427 5.89749 --5.67319 -1.36892 5.95895 --5.40035 -1.31152 5.93176 --5.70061 -1.3738 6.35299 --5.53287 -1.33808 6.40789 --6.16539 -1.46981 7.14774 --6.21473 -1.4788 7.412 --5.77819 -1.38645 7.23722 --5.69221 -1.36767 7.37689 --5.7799 -1.38499 7.68942 --5.78173 -1.38503 7.92903 --6.16502 -1.46393 8.58142 --6.22818 -1.47544 8.9198 --6.16416 -1.46092 9.12864 --5.96092 -1.41755 9.17888 --5.87066 -1.39785 9.36233 --5.72697 -1.36745 9.48286 --3.28997 -0.861488 6.59409 --3.23549 -0.849258 6.72502 --4.94612 -1.2015 9.35081 --3.04993 -0.809272 6.8876 --3.00344 -0.79845 7.0411 --2.79893 -0.756071 6.9514 --2.4284 -0.678712 6.57592 --2.44837 -0.681817 6.83285 --2.56278 -0.704175 7.27419 --2.38953 -0.667499 7.21346 --2.34699 -0.658008 7.39598 --1.92772 -0.570992 6.82961 --1.7507 -0.534045 6.71827 --1.89286 -0.56221 7.29188 --1.65361 -0.511917 7.04002 --1.47469 -0.47443 6.9014 --1.86683 -0.553023 8.19654 --0.719774 -0.320288 5.50848 --1.4437 -0.465113 7.7945 --1.33378 -0.441657 7.85526 --1.19587 -0.4122 7.8284 --0.848549 -0.341368 7.09078 --0.719911 -0.313766 7.03544 --0.566511 -0.282028 6.87118 --0.414229 -0.250362 6.6839 --0.214527 -0.209751 6.24929 --0.241964 -0.214053 6.83705 --0.139443 -0.192119 6.83787 --0.0260585 -0.167847 6.77771 -0.0704943 -0.147286 6.80427 -0.18369 -0.124191 6.72015 -0.291895 -0.101413 6.64378 -0.343959 -0.0878193 7.08245 -0.453251 -0.065791 7.03275 -0.552048 -0.0438101 7.09066 -0.729189 -0.0121607 5.63882 -0.806624 0.00486432 5.69214 --2.27489 -0.58066 -0.928061 --2.37613 -0.599689 -0.909208 --2.51287 -0.624387 -0.906317 --2.65871 -0.650564 -0.903882 --2.79743 -0.675716 -0.892342 --2.97988 -0.710105 -0.897826 --3.16521 -0.743032 -0.897552 --3.36889 -0.780958 -0.899091 --3.54605 -0.812567 -0.882526 --3.79835 -0.858858 -0.889478 --4.02319 -0.899855 -0.877583 --4.29674 -0.950396 -0.874748 --4.58948 -1.00366 -0.869225 --4.94002 -1.06787 -0.87172 --5.30166 -1.13397 -0.865224 --5.72207 -1.21074 -0.862246 --6.17279 -1.29236 -0.852483 --6.69143 -1.38697 -0.84345 --7.28914 -1.49683 -0.833645 --8.04283 -1.63392 -0.834891 --8.8958 -1.78968 -0.82783 --9.71213 -1.93884 -0.784636 --11.1234 -2.1965 -0.802012 --12.6359 -2.47331 -0.782708 --14.2189 -2.76166 -0.718027 --16.2437 -3.132 -0.64003 --18.3988 -3.52453 -0.500645 --10.5127 -2.06777 4.27714 --10.2667 -2.02221 4.42335 --10.216 -2.01224 4.62541 --10.4233 -2.04951 4.91603 --10.3544 -2.03665 5.1177 --10.2551 -2.01718 5.3076 --7.93775 -1.59622 4.60435 --9.85545 -1.94357 5.59981 --9.82898 -1.9375 5.81527 --9.85307 -1.94115 6.05623 --8.11379 -1.62619 5.44404 --8.27443 -1.65469 5.72555 --6.71849 -1.37215 5.10598 --6.47415 -1.32774 5.14623 --6.56515 -1.34316 5.37168 --7.60752 -1.53116 6.1768 --7.459 -1.50334 6.29161 --6.9359 -1.40804 6.16036 --6.89549 -1.39991 6.33315 --5.92038 -1.22382 5.85315 --5.84372 -1.20909 5.98058 --5.78126 -1.19799 6.11882 --5.89529 -1.21745 6.39651 --5.68648 -1.17954 6.42414 --6.32898 -1.29383 7.15981 --6.91681 -1.39847 7.89368 --7.09207 -1.43 8.2983 --6.23474 -1.27493 7.75678 --5.69019 -1.17661 7.46992 --5.84422 -1.20342 7.85402 --6.46971 -1.31402 8.74557 --6.44417 -1.30931 8.99284 --6.19388 -1.263 8.99771 --6.02929 -1.23308 9.09376 --5.89586 -1.20757 9.22442 --5.69204 -1.17059 9.26786 --6.00147 -1.22466 9.96481 --5.1717 -1.07551 9.1895 --5.03035 -1.04961 9.29735 --4.86383 -1.01895 9.37003 --3.12293 -0.708852 7.10442 --3.0232 -0.68984 7.1845 --2.51054 -0.598111 6.60445 --1.20865 -0.366956 4.65967 --3.06452 -0.695129 8.01862 --2.53305 -0.599963 7.34874 --2.38116 -0.571909 7.33084 --2.35373 -0.566742 7.54935 --1.78982 -0.466132 6.68491 --2.39773 -0.571878 8.2417 --1.70803 -0.45072 7.03464 --1.53735 -0.419307 6.92532 --1.90098 -0.481756 8.11551 --0.76544 -0.282869 5.53994 --0.673327 -0.266719 5.53281 --1.38177 -0.388096 7.82507 --1.23012 -0.360285 7.76154 --1.23201 -0.359409 8.18143 --0.785712 -0.281184 7.10665 --0.633506 -0.254342 6.96356 --0.396005 -0.212487 6.45852 --0.22242 -0.182518 6.14159 --0.295425 -0.192438 6.90439 --0.182162 -0.172033 6.86725 --0.0600949 -0.15018 6.7689 -0.0372817 -0.13263 6.79641 -0.146423 -0.112787 6.74291 -0.257431 -0.0926261 6.65764 -0.307322 -0.0818823 7.09686 -0.395375 -0.0652193 7.27717 -0.523702 -0.0427249 7.01734 -0.706246 -0.0144103 5.68687 -0.785464 0.000549938 5.72096 -0.858866 0.0151489 6.00361 --2.32974 -0.494654 -0.919137 --2.44093 -0.512243 -0.90358 --2.58655 -0.534535 -0.903441 --2.75141 -0.5599 -0.907805 --2.90001 -0.582546 -0.898213 --3.06685 -0.608287 -0.89233 --3.28026 -0.640981 -0.901358 --3.45814 -0.667682 -0.887832 --3.68265 -0.70224 -0.887269 --3.90915 -0.737316 -0.879356 --4.15485 -0.77521 -0.870753 --4.46634 -0.822895 -0.87677 --4.76161 -0.868731 -0.866186 --5.07705 -0.917152 -0.85141 --5.52611 -0.985968 -0.864517 --5.96904 -1.05426 -0.859675 --6.46046 -1.12951 -0.851807 --6.9923 -1.21096 -0.836107 --7.68097 -1.31675 -0.834997 --8.44952 -1.43535 -0.82532 --9.39503 -1.58059 -0.819948 --10.3525 -1.72757 -0.783259 --11.6843 -1.93212 -0.765523 --13.5379 -2.21634 -0.765094 --15.5329 -2.52261 -0.713909 --16.2588 -2.63379 -0.482557 --16.3817 -2.65171 -0.184443 --16.3498 -2.64631 0.125024 --56.2253 -8.77092 1.11186 --9.90024 -1.64341 4.1952 --9.95773 -1.65174 4.42234 --9.91624 -1.64438 4.6213 --9.31956 -1.55276 4.62692 --9.367 -1.55991 4.84962 --9.21651 -1.53549 4.99952 --10.0622 -1.66448 5.55539 --11.7562 -1.92182 6.51473 --9.94478 -1.64532 5.96333 --8.41623 -1.4119 5.47285 --8.44443 -1.41543 5.69101 --7.74643 -1.3087 5.53809 --7.09093 -1.20864 5.38083 --6.8338 -1.16803 5.42077 --6.5506 -1.1251 5.43795 --6.8037 -1.16247 5.77179 --6.74529 -1.1534 5.92467 --7.091 -1.20498 6.34454 --7.04663 -1.19795 6.52007 --6.20625 -1.07035 6.13222 --6.23648 -1.07393 6.34679 --6.45106 -1.1062 6.70891 --6.22742 -1.07199 6.74071 --7.2404 -1.22399 7.78163 --6.17687 -1.06221 7.12091 --7.04659 -1.19345 8.10761 --6.96776 -1.18021 8.28866 --5.89464 -1.01769 7.53301 --6.66929 -1.13443 8.52346 --6.85303 -1.16106 8.97627 --6.65245 -1.13047 9.04868 --6.36436 -1.08603 9.0213 --6.17891 -1.05733 9.09782 --5.91607 -1.01694 9.07955 --5.94676 -1.02089 9.40739 --5.99346 -1.02718 9.76982 --5.44733 -0.944141 9.37896 --5.18865 -0.904552 9.33943 --5.92605 -1.01328 10.6783 --6.39803 -1.08329 11.7258 --3.02808 -0.579085 7.06566 --3.31582 -0.621119 7.74863 --1.2705 -0.315523 4.69107 --1.18652 -0.302288 4.69616 --2.66608 -0.521843 7.44727 --2.60264 -0.512162 7.59839 --2.38187 -0.478314 7.45762 --1.83588 -0.396818 6.65113 --1.94568 -0.412481 7.13195 --1.69423 -0.374682 6.86549 --1.63681 -0.364845 7.01244 --2.07593 -0.429131 8.35681 --0.815054 -0.243694 5.56154 --0.719015 -0.228199 5.546 --1.4526 -0.334855 7.84154 --1.2962 -0.310735 7.77004 --1.27327 -0.306574 8.10437 --0.802662 -0.237015 6.98557 --0.636794 -0.212345 6.79512 --0.503803 -0.192125 6.69736 --0.264939 -0.157455 6.1502 --0.198575 -0.14654 6.26909 --0.22391 -0.148448 6.847 --0.117776 -0.132227 6.83816 --0.0195145 -0.116688 6.86666 -0.113987 -0.0970836 6.67621 -0.217 -0.0814757 6.6512 -0.263718 -0.0735265 7.09089 -0.359317 -0.0582224 7.19231 -0.483706 -0.0394968 6.99327 -0.66309 -0.015073 5.88389 -0.755262 -0.00172494 5.7192 -0.825686 0.0100526 6.04247 --2.24636 -0.391545 -0.922856 --2.36547 -0.406984 -0.914051 --2.48555 -0.422181 -0.901545 --2.65113 -0.442614 -0.908448 --2.79851 -0.461441 -0.901256 --2.96606 -0.482249 -0.897913 --3.15178 -0.505121 -0.897629 --3.34866 -0.530224 -0.895245 --3.56468 -0.557246 -0.894218 --3.78172 -0.584857 -0.886046 --4.02797 -0.614887 -0.881329 --4.29347 -0.648697 -0.875174 --4.58923 -0.685725 -0.869624 --4.92436 -0.727503 -0.866233 --5.27966 -0.771804 -0.857353 --5.75117 -0.831129 -0.868246 --6.19531 -0.886933 -0.855698 --6.73842 -0.955217 -0.851269 --7.32187 -1.02859 -0.836761 --8.05271 -1.11962 -0.832039 --8.92293 -1.22932 -0.827404 --9.93236 -1.35533 -0.815565 --11.2286 -1.51756 -0.811202 --12.6165 -1.69164 -0.773294 --14.587 -1.93872 -0.752943 --16.8874 -2.2272 -0.694918 --16.499 -2.17825 -0.347146 --10.0758 -1.36179 4.1384 --9.98197 -1.34933 4.32188 --10.1693 -1.37168 4.59358 --9.5787 -1.29814 4.61155 --9.43053 -1.2793 4.76735 --9.16947 -1.2455 4.87687 --9.32257 -1.26413 5.14402 --9.07573 -1.23354 5.25251 --9.33752 -1.2648 5.57761 --9.79771 -1.32193 6.00897 --10.8016 -1.44643 6.72556 --10.7277 -1.43594 6.94613 --8.0553 -1.10354 5.79978 --8.11875 -1.11186 6.04019 --6.46882 -0.905853 5.30659 --6.34216 -0.890451 5.40736 --6.70456 -0.934922 5.80869 --6.60397 -0.921783 5.93321 --7.00544 -0.971017 6.39315 --6.3636 -0.891284 6.1533 --6.56378 -0.915558 6.49198 --4.77863 -0.694296 5.36108 --4.71847 -0.686274 5.47476 --6.86623 -0.951277 7.36529 --6.86305 -0.950237 7.59239 --7.04879 -0.97244 7.99044 --1.58256 -0.297867 3.3523 --1.52692 -0.291612 3.3844 --1.47822 -0.284658 3.42212 --6.03098 -0.844445 8.0288 --6.65138 -0.920443 8.9162 --6.25437 -0.871227 8.77409 --3.56149 -0.539546 6.0806 --3.40803 -0.520479 6.08566 --5.43615 -0.768437 8.66788 --3.98605 -0.590487 7.16568 --4.05714 -0.59868 7.48023 --3.86642 -0.574824 7.46544 --4.79059 -0.687277 8.96698 --2.92079 -0.458463 6.61494 --2.74535 -0.43628 6.56802 --2.61507 -0.42031 6.58353 --1.30005 -0.259465 4.71348 --1.19923 -0.247454 4.69417 --1.1454 -0.23991 4.75005 --2.7433 -0.43255 7.75819 --2.3939 -0.390541 7.39252 --1.85766 -0.324518 6.62622 --0.939145 -0.213386 5.01024 --0.852347 -0.202684 5.00813 --0.544958 -0.165582 4.51258 --2.29907 -0.374545 8.76098 --0.809445 -0.196495 5.50881 --0.738509 -0.187255 5.55906 --1.52595 -0.279777 7.93243 --1.34889 -0.258133 7.81593 --1.21268 -0.241081 7.7998 --0.913597 -0.204857 7.2562 --0.641665 -0.172 6.733 --0.513869 -0.156483 6.65544 --0.282141 -0.127909 6.1587 --0.195196 -0.117529 6.19075 --0.271977 -0.125239 6.9733 --0.141302 -0.108758 6.85802 --0.0313975 -0.0947911 6.82853 -0.116645 -0.0769201 6.56016 -0.202884 -0.0659028 6.64464 -0.241611 -0.0599904 7.11443 -0.351476 -0.0468885 7.08769 -0.466148 -0.0321311 6.99905 -0.565422 -0.0196702 7.06784 -0.751299 -5.7921e-05 5.70754 -0.822236 0.00925654 5.96154 -0.908957 0.0207255 5.93436 --2.30117 -0.304027 -0.923819 --2.413 -0.315553 -0.908154 --2.55204 -0.328981 -0.903296 --2.70822 -0.343613 -0.903149 --2.85733 -0.358209 -0.893648 --3.0347 -0.375509 -0.892201 --3.23123 -0.394783 -0.893211 --3.42871 -0.413682 -0.887823 --3.65449 -0.436131 -0.887345 --3.89227 -0.458664 -0.882963 --4.15832 -0.484629 -0.881093 --4.43543 -0.511658 -0.873678 --4.73167 -0.540394 -0.863324 --5.07827 -0.573343 -0.857673 --5.47336 -0.612492 -0.85404 --5.93789 -0.656706 -0.855117 --6.45186 -0.706779 -0.852513 --7.01717 -0.761456 -0.843471 --7.6621 -0.824234 -0.831802 --8.43504 -0.899464 -0.822618 --9.38738 -0.992158 -0.817771 --10.4504 -1.09443 -0.797164 --11.7816 -1.22367 -0.777024 --13.164 -1.35785 -0.71659 --15.5181 -1.58642 -0.709244 --17.0038 -1.73024 -0.544394 --16.9094 -1.72082 -0.219297 --16.799 -1.70953 0.102477 --10.4598 -1.08606 4.13369 --10.5382 -1.09349 4.37387 --10.668 -1.10578 4.63541 --9.94138 -1.03493 4.62311 --9.73605 -1.01415 4.76625 --9.45433 -0.986616 4.87581 --9.55289 -0.996426 5.12428 --9.10121 -0.951947 5.15548 --9.06499 -0.948572 5.34857 --10.5511 -1.09108 6.22714 --12.7576 -1.30238 7.51085 --10.4702 -1.08236 6.68364 --10.299 -1.06547 6.84837 --6.55185 -0.704807 5.09292 --6.34898 -0.685006 5.15273 --6.13809 -0.66422 5.20171 --6.2779 -0.677256 5.45626 --5.71046 -0.623173 5.27602 --6.59454 -0.707323 6.02173 --6.79443 -0.726057 6.35112 --5.10435 -0.564267 5.36147 --5.17282 -0.570617 5.57478 --4.82258 -0.536378 5.47823 --4.7836 -0.53213 5.61137 --3.25825 -0.386801 4.53411 --3.12714 -0.373809 4.55126 --1.63957 -0.23209 3.37546 --1.53877 -0.221464 3.36863 --1.49125 -0.217421 3.40691 --1.42058 -0.209843 3.4233 --5.85604 -0.631888 7.97713 --4.22876 -0.477112 6.52684 --3.58929 -0.415859 6.03279 --3.52823 -0.409062 6.14312 --1.70382 -0.235839 4.21268 --1.54 -0.220738 4.13015 --1.41022 -0.207908 4.08174 --1.30155 -0.197815 4.05355 --4.91969 -0.539258 9.00328 --4.95522 -0.541998 9.34973 --2.74152 -0.332682 6.47729 --1.32914 -0.199314 4.57629 --1.25647 -0.192461 4.60071 --1.20375 -0.186807 4.65759 --1.10506 -0.176757 4.63659 --2.74966 -0.330933 7.65552 --1.12253 -0.178091 4.97271 --1.89231 -0.249466 6.60068 --0.965118 -0.162637 5.01086 --0.891441 -0.155777 5.03668 --0.5695 -0.125318 4.52602 --0.528811 -0.121118 4.59958 --0.48513 -0.117115 4.67283 --0.76384 -0.141899 5.55283 --1.61206 -0.219983 8.02198 --1.38157 -0.198413 7.7668 --1.27735 -0.187728 7.84625 --1.14927 -0.174844 7.85752 --0.679255 -0.131395 6.73741 --0.552614 -0.11928 6.67074 --0.328141 -0.0987918 6.22462 --0.230392 -0.0889329 6.21886 --0.300348 -0.0949664 6.9424 --0.171809 -0.0823478 6.84775 --0.0856367 -0.07361 6.94686 -0.0858261 -0.0574215 6.57196 -0.174789 -0.0495167 6.63745 -0.191967 -0.0459288 7.23638 -0.307614 -0.0351044 7.19098 -0.429889 -0.0232104 7.05387 -0.530967 -0.0133109 7.11366 -0.732533 0.00295743 5.72526 -0.812332 0.0108981 5.76009 -0.888901 0.0188705 5.95343 --2.3375 -0.210059 -0.913831 --2.45815 -0.218202 -0.901366 --2.6151 -0.228899 -0.903709 --2.78109 -0.240029 -0.90556 --2.93194 -0.250383 -0.89355 --3.13721 -0.264466 -0.901654 --3.32534 -0.277859 -0.895208 --3.53356 -0.292124 -0.890364 --3.76088 -0.307272 -0.886127 --3.99826 -0.323623 -0.877947 --4.27593 -0.342831 -0.875317 --4.58172 -0.363364 -0.873 --4.91876 -0.386967 -0.869486 --5.27583 -0.411087 -0.860382 --5.69231 -0.439843 -0.855287 --6.18825 -0.473123 -0.856153 --6.71435 -0.509106 -0.847137 --7.33004 -0.551787 -0.83959 --8.0362 -0.599879 -0.82886 --8.87115 -0.65721 -0.817464 --9.9053 -0.727785 -0.810055 --11.1205 -0.811037 -0.793388 --12.6536 -0.915181 -0.776095 --14.5468 -1.04507 -0.745788 --17.117 -1.22126 -0.714081 --19.7109 -1.39769 -0.594467 --19.6568 -1.39371 -0.225733 --19.665 -1.39425 0.137607 --12.1313 -0.871618 4.46003 --11.8578 -0.852555 4.63145 --11.0279 -0.796483 4.62897 --10.4211 -0.754968 4.668 --8.28474 -0.608753 4.1708 --8.36924 -0.615122 4.38445 --9.29004 -0.676472 4.91816 --9.38743 -0.683416 5.16517 --9.11128 -0.664147 5.26307 --8.88037 -0.648582 5.37273 --6.18299 -0.464901 4.81761 --6.55338 -0.489597 5.18319 --6.21944 -0.466392 5.1679 --6.74719 -0.50183 5.65109 --5.76441 -0.43552 5.23219 --5.88392 -0.443342 5.47501 --7.74201 -0.568131 6.88479 --5.20642 -0.396771 5.35825 --5.15445 -0.392621 5.48499 --5.00332 -0.382988 5.5397 --4.90027 -0.375853 5.62705 --4.83429 -0.371058 5.74344 --3.22044 -0.262522 4.57817 --3.04449 -0.250213 4.55526 --1.51147 -0.147311 3.31952 --1.50104 -0.146378 3.39148 --1.45958 -0.143652 3.43628 --1.40908 -0.139854 3.47324 --1.33861 -0.135365 3.48778 --1.3021 -0.132126 3.5369 --3.54586 -0.282336 6.08807 --1.54927 -0.148345 4.00101 --1.58074 -0.15031 4.14553 --1.45618 -0.141711 4.10658 --1.06176 -0.115519 3.71951 --1.29314 -0.130739 4.12188 --1.38652 -0.137164 4.36403 --2.95328 -0.240812 6.69652 --1.30231 -0.130605 4.49771 --1.2967 -0.130782 4.62233 --1.21712 -0.124785 4.63793 --1.14359 -0.120086 4.66044 --2.66103 -0.219677 7.39775 --1.14206 -0.119248 4.96236 --1.08342 -0.115007 5.01816 --0.989915 -0.108973 5.01102 --0.920335 -0.10439 5.0466 --0.845724 -0.0986165 5.07186 --0.522425 -0.07785 4.54945 --0.452933 -0.0725684 4.55855 --0.794958 -0.0942962 5.56465 --1.66293 -0.14995 8.01704 --1.42582 -0.134152 7.75468 --1.41702 -0.133176 8.1087 --0.684592 -0.0865672 6.32014 --0.960239 -0.103509 7.52382 --0.595083 -0.0789194 6.70473 --0.334329 -0.0622407 6.14507 --0.292068 -0.059499 6.35296 --0.168832 -0.0510022 6.24965 --0.214896 -0.0532931 6.89572 --0.0748693 -0.0438328 6.73115 --0.00552336 -0.0387758 6.91759 -0.136255 -0.0290947 6.69893 -0.190155 -0.0253948 7.02122 -0.273571 -0.0193434 7.20439 -0.395708 -0.0114139 7.0883 -0.506174 -0.00396071 7.04952 -0.709166 0.00869875 5.79235 -0.799135 0.0146608 5.6783 -0.868026 0.0200572 5.97216 -0.956266 0.0259407 5.91511 --2.83362 -0.132156 -0.897828 --3.01138 -0.139392 -0.896173 --3.19009 -0.146292 -0.888919 --3.38897 -0.155086 -0.883716 --3.62496 -0.164076 -0.887222 --3.86295 -0.173558 -0.882879 --4.11102 -0.184224 -0.874193 --4.40823 -0.195335 -0.873709 --4.71656 -0.208449 -0.86643 --5.06401 -0.222275 -0.860511 --5.46069 -0.238253 -0.856801 --5.90758 -0.256194 -0.852699 --6.41372 -0.27654 -0.847912 --6.95197 -0.298437 -0.832584 --7.61878 -0.325035 -0.825924 --8.42421 -0.357491 -0.82309 --9.34105 -0.393818 -0.81148 --10.4467 -0.438703 -0.79796 --11.7532 -0.490995 -0.773785 --13.3991 -0.55768 -0.745427 --15.505 -0.642257 -0.707561 --18.0314 -0.743728 -0.63271 --11.8846 -0.49146 4.51791 --11.8693 -0.490504 4.75804 --11.5823 -0.478917 4.9165 --8.37754 -0.350213 4.11348 --8.4358 -0.352605 4.31791 --8.37671 -0.349947 4.48392 --7.72725 -0.324017 4.42246 --4.17627 -0.181875 3.15919 --11.0507 -0.455476 6.19855 --6.70581 -0.282701 4.84111 --6.54965 -0.275617 4.93145 --6.07408 -0.257325 4.84801 --6.10229 -0.257819 5.02617 --6.86156 -0.288213 5.63249 --5.89837 -0.24954 5.23922 --5.74733 -0.242963 5.31311 --5.6464 -0.238959 5.41564 --5.65157 -0.239082 5.5889 --5.82387 -0.24612 5.88437 --4.48704 -0.192641 5.09185 --5.2037 -0.22127 5.78565 --4.07337 -0.176341 5.07487 --3.28041 -0.144538 4.57846 --3.10274 -0.137232 4.55788 --1.57917 -0.0772146 3.35606 --6.6638 -0.277403 8.03306 --1.43041 -0.0716334 3.38685 --4.49037 -0.190992 6.43575 --4.32456 -0.184672 6.46177 --1.35219 -0.0684418 3.5667 --1.25283 -0.0642088 3.55059 --2.71056 -0.12082 5.26536 --1.45064 -0.0718943 3.96374 --1.2574 -0.0636654 3.83916 --1.12714 -0.0584775 3.7788 --1.00489 -0.0536012 3.72263 --1.0054 -0.0536102 3.82296 --1.20737 -0.0614597 4.20751 --1.0602 -0.055816 4.11626 --1.0676 -0.0560167 4.24479 --1.21746 -0.061389 4.60117 --1.18586 -0.0597936 4.69206 --2.77983 -0.122056 7.50233 --2.0885 -0.0950054 6.5638 --1.13582 -0.0581434 5.06945 --0.994666 -0.0522787 4.97534 --0.939089 -0.049512 5.03814 --0.859673 -0.0464421 5.05519 --0.729613 -0.0418761 4.96182 --0.899473 -0.047448 5.53254 --0.832922 -0.0453863 5.59449 --1.68191 -0.076522 7.93739 --1.52155 -0.0708864 7.88228 --1.35718 -0.063591 7.80484 --0.732614 -0.0400195 6.371 --0.626192 -0.035749 6.36424 --0.673012 -0.0377805 6.85281 --0.405534 -0.0268941 6.3059 --0.303155 -0.0226955 6.29277 --0.180154 -0.0181521 6.19035 --0.243988 -0.0199946 6.8845 --0.143429 -0.0164386 6.91688 --0.0496825 -0.0126133 6.98684 -0.100797 -0.00585732 6.74002 -0.182776 -0.00310186 6.8752 -0.364825 0.00430658 6.31592 -0.359847 0.00495753 7.13203 -0.476916 0.00959804 7.04458 -0.682038 0.0161293 5.88891 -0.781489 0.0196145 5.69602 -0.848267 0.0231625 5.99049 -0.937233 0.0260448 5.91425 --2.90996 -0.019406 -0.901663 --3.07937 -0.0217833 -0.893003 --3.27685 -0.0237912 -0.890848 --3.47633 -0.0263661 -0.882341 --3.72294 -0.0286931 -0.885791 --3.95147 -0.0313642 -0.874147 --4.2483 -0.0357034 -0.878204 --4.53698 -0.0388971 -0.869464 --4.8738 -0.0424655 -0.866235 --5.24173 -0.0470208 -0.860109 --5.67788 -0.052788 -0.860394 --6.14605 -0.0582687 -0.853433 --6.66327 -0.0635927 -0.842388 --7.25177 -0.0714995 -0.828652 --7.95851 -0.0794825 -0.818887 --8.82572 -0.0900431 -0.813839 --9.89145 -0.102806 -0.811824 --11.0593 -0.116331 -0.787741 --12.4868 -0.132899 -0.756958 --14.3735 -0.155938 -0.728346 --16.7113 -0.183706 -0.676925 --11.8577 -0.12309 4.63667 --9.20452 -0.0916662 4.09248 --9.60696 -0.0963881 4.41728 --8.41786 -0.0824572 4.225 --8.0306 -0.0773461 4.27386 --4.237 -0.0331022 3.03101 --4.11738 -0.0313217 3.09125 --7.85681 -0.0751371 4.75258 --7.27666 -0.0684029 4.6848 --6.90266 -0.0636761 4.68953 --6.8918 -0.0631465 4.85502 --6.94895 -0.0637233 5.05695 --7.0181 -0.0649592 5.27142 --6.16128 -0.0545748 4.98722 --6.0385 -0.0531695 5.0842 --5.90673 -0.0517044 5.1731 --5.9699 -0.0527236 5.37901 --5.90107 -0.0515087 5.50756 --5.61339 -0.0476254 5.49129 --5.64056 -0.0485638 5.68198 --4.34692 -0.0334662 4.93264 --3.64297 -0.0254118 4.55684 --3.60437 -0.0247416 4.65783 --4.02513 -0.0292498 5.12644 --3.00396 -0.0180371 4.4321 --2.87554 -0.016116 4.44521 --2.88293 -0.0162922 4.57423 --2.93816 -0.0161832 4.75188 --3.67594 -0.0244761 5.58733 --5.78237 -0.0490655 7.82517 --4.04545 -0.0292496 6.29504 --1.27877 0.00298848 3.55931 --1.23446 0.0033774 3.60089 --1.31478 0.00227374 3.78421 --1.20764 0.00352339 3.75787 --1.08261 0.00440685 3.70548 --1.14088 0.00438841 3.87685 --0.98794 0.0064475 3.78103 --1.12888 0.00446276 4.075 --1.08752 0.00470346 4.13023 --1.06599 0.00574046 4.21782 --0.998764 0.00573523 4.23891 --1.14139 0.00457565 4.58792 --3.14267 -0.0169875 8.00595 --2.07353 -0.00542233 6.46697 --1.12826 0.00491208 5.01523 --1.02906 0.0062475 5.00117 --0.968616 0.00732219 5.05601 --0.898277 0.00786628 5.09197 --2.1228 -0.00487088 7.85414 --0.506602 0.0126571 4.61386 --0.558342 0.0113059 4.9079 --1.7145 1.99517e-05 7.90395 --1.56923 0.00145383 7.88732 --1.43778 0.00342873 7.90521 --0.758642 0.0103859 6.36462 --0.662274 0.0117044 6.38722 --0.690292 0.0112326 6.80879 --0.15406 0.0164536 5.36253 --0.118116 0.0175129 5.5288 --0.243431 0.016357 6.34395 --0.252251 0.016192 6.79508 --0.105738 0.0183785 6.6131 --0.00646726 0.0189414 6.624 -0.0752933 0.0203332 6.73142 -0.259373 0.0222436 6.24578 -0.354567 0.0237623 6.23054 -0.322202 0.0233987 7.1951 -0.442997 0.0248858 7.08905 -0.67133 0.0271912 5.81577 -0.763102 0.0280954 5.72328 -0.833292 0.0290244 5.92864 -0.917653 0.0296444 5.96299 -1.00298 0.0306416 5.9859 --2.98298 0.0982354 -0.903962 --3.17116 0.100751 -0.900401 --3.36023 0.104618 -0.890891 --3.59749 0.107762 -0.893982 --3.83569 0.111345 -0.889378 --4.10286 0.116555 -0.887228 --4.38108 0.120702 -0.879533 --4.68931 0.125654 -0.871941 --5.05562 0.131745 -0.871657 --5.45396 0.13797 -0.867222 --5.89132 0.144694 -0.859801 --6.3987 0.153535 -0.854536 --6.93712 0.161761 -0.838783 --7.63273 0.172729 -0.837847 --8.41031 0.186068 -0.82827 --9.3471 0.200952 -0.819618 --10.435 0.218381 -0.802091 --11.752 0.239903 -0.778855 --13.3302 0.264867 -0.741414 --15.4869 0.299434 -0.709299 --18.1239 0.342605 -0.643586 --20.8766 0.386979 -0.10814 --46.4921 0.80047 1.07961 --9.38122 0.20213 3.85507 --9.32033 0.200393 4.03579 --8.84562 0.193409 4.08887 --8.32505 0.185126 4.1109 --4.18757 0.118129 2.86409 --4.19208 0.117674 2.97078 --8.42024 0.186335 4.70703 --8.06769 0.180558 4.757 --8.73696 0.191324 5.23092 --8.0229 0.179673 5.11734 --8.15772 0.182504 5.37428 --6.90371 0.161465 4.96043 --6.89685 0.161549 5.13228 --6.62944 0.157225 5.16854 --6.83517 0.160997 5.45923 --5.84825 0.144361 5.0718 --5.75065 0.142727 5.17794 --6.45627 0.15433 5.78628 --3.42241 0.105044 3.99741 --3.32005 0.104142 4.04321 --3.17689 0.101226 4.05764 --3.60816 0.108397 4.48601 --3.03616 0.0989274 4.1827 --3.02761 0.0988347 4.29238 --3.032 0.0991746 4.41525 --2.90281 0.0971062 4.42975 --2.88828 0.0966552 4.53949 --2.96737 0.0981766 4.73678 --2.96774 0.0977631 4.86957 --2.85647 0.0965181 4.89909 --2.85179 0.0968185 5.03221 --2.89193 0.0973599 5.21672 --2.72295 0.0945671 5.18419 --1.25297 0.0704063 3.69617 --1.18682 0.0693567 3.71512 --1.1774 0.0690624 3.80157 --1.12817 0.068083 3.84178 --1.09779 0.0683704 3.90481 --1.26337 0.0704951 4.23141 --1.15938 0.0690826 4.20823 --1.08627 0.0674327 4.22356 --1.14128 0.0688613 4.42807 --1.09791 0.0684451 4.49273 --3.27408 0.10301 8.12164 --2.09032 0.084066 6.43067 --2.0158 0.0830487 6.52114 --1.08707 0.0683407 5.07016 --0.979156 0.0662447 5.03798 --0.907936 0.0647588 5.07453 --0.644437 0.0610599 4.7141 --0.529714 0.0592892 4.63609 --0.55166 0.0595247 4.85682 --0.499295 0.0586324 4.92283 --1.7344 0.0785301 8.18861 --1.52605 0.074787 8.02305 --1.44121 0.0740499 8.1722 --0.693262 0.0613604 6.40015 --0.254908 0.0548119 5.36594 --0.120622 0.0524397 5.1985 --0.0523635 0.0513415 5.23926 --0.421428 0.0577624 6.92163 --0.248538 0.0547385 6.6667 --0.136652 0.0522678 6.6318 --0.0179215 0.0503481 6.55567 -0.031473 0.0504725 6.8206 -0.286458 0.0456867 5.96267 -0.342543 0.0447813 6.17453 -0.430749 0.0436177 6.19782 -0.415034 0.0433394 7.08326 -0.6378 0.0399337 5.9712 -0.741953 0.0382099 5.78013 -0.81481 0.0375359 5.93618 -0.90078 0.0356213 5.92138 -0.984307 0.0342162 6.015 --2.85578 0.213076 -0.900893 --3.0346 0.221097 -0.896274 --3.24142 0.230495 -0.898009 --3.44024 0.23893 -0.889148 --3.67698 0.250252 -0.888539 --3.93481 0.260874 -0.88723 --4.19251 0.272911 -0.877481 --4.50024 0.286605 -0.875028 --4.82796 0.300713 -0.868333 --5.20461 0.317611 -0.864994 --5.61223 0.335614 -0.856859 --6.10783 0.357491 -0.857534 --6.61529 0.380796 -0.843867 --7.22272 0.407929 -0.834306 --7.93909 0.439574 -0.826011 --8.78533 0.477113 -0.816582 --9.80144 0.521962 -0.805973 --10.9383 0.572956 -0.778094 --12.345 0.635451 -0.745751 --14.1203 0.714551 -0.706213 --16.4461 0.817349 -0.657093 --20.6218 1.00263 -0.287668 --20.7508 1.00902 0.0885985 --13.4473 0.681943 4.55299 --9.49726 0.507141 3.79634 --9.13912 0.490474 3.89647 --8.87673 0.479426 4.01349 --8.62243 0.4676 4.12521 --4.22046 0.272083 2.83386 --4.21595 0.271957 2.93796 --9.01756 0.485219 4.84874 --5.10243 0.31144 3.5039 --6.86674 0.389529 4.36572 --8.12521 0.444873 5.08159 --4.86426 0.300903 3.78379 --4.69817 0.293303 3.83281 --4.31781 0.276215 3.76948 --6.54465 0.37515 5.05464 --4.50794 0.284901 4.11758 --6.50312 0.372789 5.38123 --6.52914 0.37398 5.57582 --5.76819 0.339965 5.29085 --3.73937 0.250729 4.16237 --3.40018 0.235188 4.05983 --3.46236 0.237799 4.21879 --3.38907 0.234781 4.28765 --3.88525 0.256973 4.77807 --3.43864 0.236894 4.57329 --3.05581 0.220107 4.39768 --2.98059 0.216571 4.45844 --4.03569 0.263083 5.48663 --3.87472 0.256229 5.50402 --2.78773 0.208134 4.66479 --2.88261 0.211752 4.88513 --1.39131 0.146828 3.55173 --2.97669 0.21598 5.26032 --3.05945 0.21979 5.49928 --2.69788 0.204263 5.26251 --1.25538 0.139782 3.77749 --1.36913 0.145139 4.00991 --1.29709 0.141821 4.03073 --1.13268 0.135041 3.93244 --1.20864 0.137843 4.13916 --1.18323 0.137337 4.22059 --1.15095 0.135013 4.29394 --1.14436 0.135272 4.40831 --1.20029 0.137291 4.62362 --1.13714 0.134506 4.66461 --1.04721 0.130939 4.66177 --2.04536 0.174599 6.51087 --0.957587 0.126708 4.80696 --0.867685 0.122925 4.79973 --0.791685 0.119198 4.81713 --0.663216 0.113918 4.72557 --0.546728 0.108093 4.64884 --0.627926 0.112208 4.99701 --0.538085 0.108048 4.98209 --0.442355 0.103526 4.94681 --1.68393 0.157048 8.31642 --0.220376 0.0936854 4.77604 --1.36456 0.143635 8.23266 --0.594451 0.109609 6.34053 --0.17174 0.0917 5.32112 --0.0200282 0.084873 5.08507 -0.0667007 0.0807825 5.04755 --0.271164 0.0956298 6.65466 --0.177048 0.0911208 6.6986 --0.0564932 0.0861432 6.6237 -0.130308 0.0780854 6.2033 -0.268028 0.0719979 5.96513 -0.301607 0.070327 6.29595 -0.417808 0.0652025 6.15211 -0.377709 0.0662638 7.15621 -0.631208 0.0552538 5.86757 -0.726665 0.051511 5.76678 -0.80493 0.0480969 5.83371 -0.879676 0.0447671 5.99919 -0.966615 0.040743 6.00371 -1.0719 0.0364659 5.25687 --2.16749 0.281551 -0.9269 --2.28016 0.289142 -0.911066 --2.43673 0.301391 -0.915441 --2.57634 0.311304 -0.905817 --2.74391 0.323478 -0.904894 --2.91243 0.335966 -0.898773 --3.10896 0.349812 -0.899406 --3.31645 0.364436 -0.897689 --3.53384 0.380809 -0.892976 --3.76224 0.397018 -0.884763 --4.01955 0.415837 -0.879355 --4.31576 0.437784 -0.8785 --4.64192 0.461566 -0.877098 --5.00801 0.487725 -0.8764 --5.386 0.515077 -0.866155 --5.81284 0.546372 -0.856119 --6.33753 0.584096 -0.85584 --6.87506 0.623377 -0.839817 --7.54032 0.671943 -0.832556 --8.32529 0.728751 -0.825157 --9.25986 0.796658 -0.816623 --10.374 0.877621 -0.803912 --11.5897 0.96595 -0.766433 --13.1825 1.08088 -0.732695 --15.1852 1.22623 -0.686109 --17.7663 1.41351 -0.619603 --39.3469 2.98132 -0.346459 --37.9888 2.88143 0.385559 --12.8938 1.05632 4.30155 --12.0896 0.997629 4.36048 --12.4141 1.02086 4.69661 --9.79924 0.831155 4.19772 --9.77032 0.829336 4.39853 --4.2302 0.428299 2.79653 --4.1132 0.419459 2.86192 --4.1645 0.422674 2.98562 --4.40889 0.440407 3.18712 --4.97973 0.482009 3.533 --5.00901 0.483655 3.67212 --4.92574 0.478173 3.76415 --4.74998 0.464894 3.81158 --4.10054 0.418213 3.62082 --4.2055 0.424949 3.79063 --4.13031 0.419364 3.87071 --4.40227 0.439284 4.14341 --4.0187 0.41151 4.05054 --4.29855 0.431874 4.3428 --4.3407 0.434305 4.50231 --3.47697 0.37197 4.07485 --3.36502 0.364289 4.11699 --3.58018 0.3796 4.38617 --3.51299 0.374356 4.46339 --4.48634 0.443987 5.3292 --4.37925 0.436185 5.40344 --4.72821 0.461209 5.8471 --4.25348 0.427378 5.62175 --4.03718 0.411145 5.59831 --2.96479 0.334437 4.79134 --2.76755 0.320014 4.74073 --1.35515 0.218408 3.50197 --1.40335 0.222064 3.63834 --1.19749 0.206667 3.51793 --1.40544 0.221685 3.83041 --1.40298 0.221347 3.92773 --1.21398 0.208315 3.81424 --1.14014 0.202406 3.82547 --1.17832 0.205102 3.97492 --1.01623 0.19332 3.8741 --0.995886 0.191968 3.9525 --0.979475 0.191259 4.03911 --1.26324 0.211191 4.56061 --1.07938 0.198159 4.42063 --1.155 0.203051 4.66989 --1.07016 0.197257 4.67662 --1.03681 0.194729 4.76739 --0.965883 0.188922 4.79736 --0.899829 0.184777 4.83469 --0.973229 0.189109 5.13602 --0.923914 0.186182 5.21798 --0.764031 0.174436 5.07472 --0.696996 0.169503 5.11759 --0.928911 0.186027 5.83579 --0.553055 0.158966 5.18155 --1.6904 0.239249 8.22662 --0.235731 0.136538 4.79217 --0.200298 0.133795 4.90137 --0.223886 0.134501 5.19027 --0.224619 0.135035 5.44286 --0.0456053 0.121861 5.13232 --0.0423357 0.121598 5.39393 --0.227968 0.134591 6.4007 --0.140947 0.127966 6.454 --0.176004 0.130155 7.042 -0.163857 0.10662 5.94983 -0.240939 0.100246 6.01632 -0.276363 0.0975122 6.32796 -0.408885 0.0885648 6.08645 -0.330946 0.0931735 7.29804 -0.417662 0.0859623 7.50096 -0.711513 0.0662849 5.76307 -0.791484 0.0603204 5.80088 -0.863197 0.0556885 5.97686 -0.949058 0.0487427 6.00205 -1.06112 0.0421079 5.23615 --2.18524 0.384457 -0.916296 --2.32261 0.39892 -0.91332 --2.46199 0.412723 -0.905892 --2.61932 0.428382 -0.903118 --2.78657 0.445672 -0.899746 --2.98275 0.465367 -0.903373 --3.17094 0.484081 -0.896802 --3.38699 0.506218 -0.895586 --3.614 0.529184 -0.891021 --3.86096 0.553379 -0.885958 --4.13777 0.581292 -0.882746 --4.43445 0.611544 -0.876788 --4.77898 0.646436 -0.875987 --5.1354 0.682481 -0.866439 --5.56058 0.72536 -0.863493 --6.04547 0.774828 -0.861101 --6.56123 0.826629 -0.849269 --7.13572 0.884215 -0.832753 --7.88847 0.960805 -0.832186 --8.72186 1.04484 -0.820235 --9.73351 1.14662 -0.809054 --10.8665 1.2616 -0.780544 --12.2863 1.40504 -0.75017 --14.0655 1.58468 -0.710633 --16.3515 1.81567 -0.657411 --39.9775 4.20177 -0.00734664 --39.7958 4.18076 2.15673 --39.7406 4.17392 2.87481 --13.7805 1.54977 4.11039 --13.5892 1.52968 4.34276 --12.3974 1.40878 4.32739 --11.5101 1.31916 4.34943 --10.4628 1.21412 4.29568 --10.5184 1.2193 4.53456 --4.19601 0.583242 2.7466 --4.17463 0.580796 2.84467 --4.46041 0.6094 3.05317 --4.8068 0.643409 3.29683 --4.42358 0.604704 3.26628 --4.4111 0.603402 3.37658 --4.07767 0.569767 3.34717 --3.99168 0.561119 3.41911 --3.90371 0.552238 3.48874 --4.04725 0.565999 3.67232 --4.14101 0.575895 3.83858 --4.26659 0.58786 4.02801 --4.21335 0.582382 4.12398 --4.14124 0.57521 4.20877 --4.35703 0.597187 4.47001 --4.07748 0.568162 4.42748 --3.62816 0.523695 4.26012 --3.84987 0.545843 4.53782 --3.77189 0.536923 4.61474 --5.24263 0.684816 5.84608 --4.59793 0.619966 5.52589 --4.44145 0.603428 5.56502 --3.188 0.478252 4.68892 --1.7326 0.332794 3.56892 --3.9809 0.557476 5.66457 --1.58397 0.318183 3.61712 --1.20689 0.280104 3.34899 --1.22239 0.280915 3.4476 --1.27747 0.286296 3.59014 --1.07587 0.266991 3.46665 --1.10616 0.269819 3.5879 --1.17308 0.27618 3.75602 --1.08645 0.267741 3.75205 --1.07016 0.265653 3.83092 --1.04594 0.262708 3.90216 --0.984051 0.257127 3.92568 --0.968699 0.255482 4.01234 --2.79002 0.435534 6.69896 --1.2346 0.281211 4.63204 --1.06195 0.263618 4.50779 --1.04843 0.262515 4.62338 --1.03197 0.260263 4.73961 --0.992755 0.255958 4.82191 --0.921892 0.249134 4.85152 --0.731627 0.230151 4.66002 --0.690448 0.225523 4.73822 --0.913524 0.247441 5.35346 --0.684849 0.225351 5.06519 --0.593356 0.215191 5.05265 --0.59435 0.215969 5.24916 --0.440792 0.200623 5.08631 --0.253891 0.182003 4.81712 --0.177233 0.174229 4.81439 --0.2234 0.178067 5.15919 --0.179035 0.173831 5.26939 --0.0699466 0.162758 5.17896 -0.0135918 0.153897 5.16272 --0.220908 0.176397 6.30167 --0.148719 0.169076 6.40378 --0.0735427 0.161525 6.50489 --0.014893 0.155273 6.69297 -0.179118 0.136306 6.24341 -0.289204 0.125167 6.15288 -0.390479 0.114399 6.09955 -0.489783 0.105162 6.03424 -0.600514 0.0942419 5.868 -0.692818 0.0847261 5.80877 -0.774574 0.0766968 5.82734 -0.852634 0.0682722 5.91435 -0.924433 0.0610739 6.13981 -1.05247 0.0491065 5.22516 -1.12598 0.0418053 5.1877 --2.10461 0.476176 -0.930547 --2.2079 0.489464 -0.90976 --2.36298 0.509648 -0.914135 --2.50211 0.527561 -0.904407 --2.66907 0.549724 -0.90358 --2.83605 0.571149 -0.897409 --3.04087 0.597331 -0.902088 --3.23867 0.622607 -0.896264 --3.45433 0.650913 -0.89155 --3.69985 0.682847 -0.890483 --3.96526 0.717048 -0.888169 --4.2416 0.752189 -0.880209 --4.55672 0.792525 -0.875402 --4.92054 0.839614 -0.874648 --5.32509 0.892235 -0.872643 --5.74954 0.946482 -0.862051 --6.25245 1.01225 -0.856313 --6.78624 1.0804 -0.840136 --7.43825 1.1654 -0.830463 --8.20962 1.26462 -0.821049 --9.13904 1.38437 -0.812599 --10.2076 1.52207 -0.793722 --11.4649 1.68475 -0.763772 --13.0294 1.88637 -0.727507 --15.0113 2.14285 -0.679934 --17.5876 2.47524 -0.614385 --39.3833 5.28833 -0.350447 --39.7642 5.33518 1.08092 --45.4383 6.06614 1.91134 --46.5257 6.20568 2.77361 --48.1086 6.40663 4.57424 --52.4954 6.9702 5.84218 --46.8017 6.23505 6.18506 --49.9043 6.63269 7.4309 --45.7712 6.09613 9.4527 --13.3047 1.9136 3.89563 --13.1753 1.89657 4.13464 --13.0906 1.88564 4.38132 --13.1648 1.89427 4.66733 --4.17389 0.736937 2.49497 --10.4373 1.54267 4.41891 --4.9352 0.834973 2.9378 --4.25972 0.747966 2.83533 --4.26515 0.748725 2.94517 --4.01655 0.71654 2.96302 --4.26016 0.747214 3.16348 --4.30429 0.752342 3.29403 --4.66584 0.798603 3.56404 --4.70291 0.803798 3.70455 --4.87091 0.825176 3.91078 --3.98273 0.710217 3.60485 --3.83144 0.690882 3.64196 --4.08271 0.723427 3.89104 --4.56104 0.783701 4.28113 --4.40868 0.764776 4.32782 --4.18898 0.736513 4.32888 --4.1983 0.736889 4.4667 --4.09655 0.724091 4.53482 --3.97701 0.708534 4.5892 --3.82578 0.688768 4.61752 --3.58645 0.657248 4.57683 --4.33855 0.753719 5.28249 --4.77952 0.809409 5.78745 --1.80907 0.429702 3.52861 --1.76503 0.424678 3.58208 --1.71213 0.417754 3.62826 --1.29896 0.364711 3.34506 --1.40346 0.378003 3.52626 --1.27342 0.361284 3.48911 --1.21665 0.353324 3.51909 --1.16576 0.347018 3.55504 --1.10795 0.339876 3.58257 --1.14316 0.343462 3.71313 --1.01814 0.327464 3.66417 --1.06807 0.334138 3.81883 --1.02513 0.327917 3.86706 --1.22514 0.353995 4.2302 --0.88974 0.311221 3.89755 --0.833974 0.303287 3.92683 --1.15726 0.344429 4.50427 --2.23152 0.479713 6.24744 --1.13823 0.341253 4.74658 --1.03592 0.328168 4.72869 --0.991839 0.322161 4.80283 --0.802827 0.297919 4.62511 --0.716351 0.287275 4.61695 --0.602359 0.272248 4.55391 --0.62129 0.274916 4.74646 --0.67861 0.281448 5.03085 --0.754493 0.290388 5.38164 --0.62271 0.273792 5.2884 --0.521451 0.261068 5.25629 --0.292577 0.231447 4.8973 --0.196374 0.219238 4.84918 --0.245415 0.225247 5.1938 --0.134491 0.211185 5.106 --0.0941713 0.205623 5.22501 --0.00384847 0.194454 5.1907 --0.265541 0.22585 6.39501 --0.244271 0.222221 6.69158 --0.0745537 0.200799 6.42587 --0.035495 0.195591 6.69205 -0.128153 0.175275 6.4008 -0.296324 0.153605 6.02708 -0.368412 0.144413 6.13179 -0.442429 0.134054 6.23554 -0.581034 0.117184 5.90237 -0.678042 0.104946 5.8142 -0.757721 0.0940554 5.85345 -0.838527 0.0845233 5.90124 -0.905334 0.0751311 6.15729 -1.04301 0.0591467 5.21383 -1.11732 0.049325 5.16697 --2.40889 0.628567 -0.918313 --2.55671 0.651922 -0.910586 --2.71345 0.676838 -0.902465 --2.90797 0.707473 -0.905941 --3.10444 0.738538 -0.903115 --3.30092 0.768915 -0.893948 --3.52614 0.804815 -0.889331 --3.78021 0.844317 -0.887668 --4.05505 0.888164 -0.884352 --4.35871 0.935746 -0.881293 --4.69213 0.988194 -0.877037 --5.04635 1.04418 -0.867284 --5.48696 1.11382 -0.869335 --5.94933 1.18727 -0.861491 --6.45139 1.26646 -0.847007 --7.03282 1.35847 -0.832527 --7.75028 1.47135 -0.82581 --8.58777 1.60367 -0.815899 --9.58204 1.76066 -0.80306 --10.7162 1.93984 -0.775992 --12.1262 2.16192 -0.745554 --13.8824 2.43954 -0.704802 --16.0931 2.78764 -0.645809 --19.4182 3.31293 -0.596051 --46.4746 7.58101 0.674753 --46.8 7.63065 1.52203 --47.8597 7.79546 2.40177 --45.8753 7.48049 3.18026 --46.1958 7.52926 4.03625 --47.2006 7.68597 4.96111 --45.5232 7.41962 5.65824 --45.5838 7.42699 6.50179 --49.8789 8.10191 7.92204 --47.1799 7.67035 10.1931 --46.8793 7.62097 11.0198 --13.5736 2.3791 4.37891 --13.2066 2.32006 4.56575 --4.26246 0.913105 2.48081 --4.26493 0.913487 2.58664 --4.81442 0.999283 2.85859 --4.85748 1.0054 2.9902 --4.73798 0.987078 3.06965 --4.07863 0.883192 2.95101 --4.24755 0.908939 3.12289 --4.55006 0.956842 3.35631 --4.42772 0.936786 3.42452 --4.79257 0.993804 3.70514 --4.53846 0.953933 3.71631 --4.03691 0.87466 3.5984 --4.07097 0.880347 3.73226 --3.98825 0.867063 3.80785 --3.93127 0.85795 3.89576 --3.84658 0.844368 3.96775 --4.73069 0.982158 4.61765 --4.01961 0.87028 4.31997 --3.71229 0.822244 4.25153 --3.99263 0.86581 4.56608 --4.0286 0.870943 4.72691 --3.94783 0.858074 4.80851 --3.78699 0.83231 4.82873 --4.81653 0.993417 5.7717 --4.54781 0.950996 5.72901 --1.77049 0.516951 3.57529 --1.70383 0.506588 3.60931 --1.33385 0.448278 3.36957 --1.25638 0.436169 3.38157 --1.17892 0.423962 3.39157 --1.36323 0.452387 3.65935 --1.17906 0.424436 3.56276 --1.25667 0.435744 3.73673 --1.08346 0.408493 3.64088 --1.12941 0.415514 3.78718 --1.1832 0.423888 3.9512 --1.59711 0.487407 4.5661 --0.914896 0.381363 3.82502 --0.926249 0.382874 3.94278 --0.846831 0.370974 3.94113 --0.83647 0.369003 4.03536 --1.27547 0.436361 4.79826 --1.16639 0.419646 4.77609 --1.12241 0.411753 4.85253 --1.11777 0.410604 4.99682 --0.873869 0.372948 4.73683 --0.673409 0.341572 4.53034 --0.598908 0.330431 4.53801 --0.564777 0.324606 4.62393 --0.743919 0.351414 5.14857 --0.821613 0.363495 5.49983 --0.874657 0.370927 5.82778 --0.347502 0.28951 4.82809 --0.330908 0.286838 4.97648 --0.251537 0.27402 4.97648 --0.234856 0.271264 5.14349 --0.163265 0.260211 5.1696 --0.0378727 0.240857 5.0332 --0.0220949 0.237512 5.22768 --0.264987 0.272944 6.33402 -0.228327 0.198401 4.8856 --0.100603 0.247341 6.46294 --0.0802112 0.242656 6.79782 -0.0958774 0.215731 6.46935 -0.286264 0.187424 6.00907 -0.336887 0.178909 6.22266 -0.454233 0.160281 6.07086 -0.551255 0.145649 6.01535 -0.663462 0.127635 5.82922 -0.740188 0.115938 5.88906 -0.826458 0.102152 5.87794 -0.889252 0.0910115 6.15454 -1.03466 0.0711155 5.20229 -1.10887 0.058818 5.16607 -1.18042 0.0480892 5.17845 --2.28621 0.718509 -0.917189 --2.43275 0.74668 -0.911911 --2.58031 0.77414 -0.901985 --2.7557 0.805903 -0.89986 --2.94088 0.841336 -0.896337 --3.12713 0.87513 -0.886717 --3.36887 0.920492 -0.893449 --3.60265 0.963945 -0.888534 --3.84725 1.01027 -0.879371 --4.13058 1.0627 -0.875008 --4.43372 1.11852 -0.867151 --4.79427 1.18646 -0.866746 --5.16572 1.25553 -0.856699 --5.60555 1.33749 -0.852053 --6.12366 1.43401 -0.85151 --6.64269 1.53047 -0.833135 --7.27959 1.64976 -0.821561 --8.03443 1.79018 -0.810596 --8.96465 1.96303 -0.804347 --10.0236 2.16032 -0.78567 --11.2607 2.39105 -0.754715 --12.8209 2.6816 -0.719948 --14.7266 3.0371 -0.666225 --17.2802 3.51251 -0.601672 --31.025 6.07316 -0.0721734 --43.4827 8.39393 0.302773 --43.4393 8.3836 1.09802 --44.2082 8.52536 1.90752 --44.3738 8.5537 2.72244 --45.6823 8.79497 3.60719 --44.5237 8.57677 4.36021 --46.026 8.85431 5.31549 --43.9714 8.46932 5.94058 --43.9676 8.46734 6.75476 --48.7926 9.35955 9.18075 --48.8487 9.36768 10.1056 --13.5676 2.80773 3.98825 --13.5148 2.79755 4.25186 --13.3611 2.76807 4.4918 --4.3072 1.08604 2.45475 --4.30075 1.08482 2.55949 --4.27356 1.07908 2.65888 --4.37591 1.09822 2.79882 --4.27943 1.08026 2.87774 --4.5628 1.13187 3.08789 --4.54445 1.12823 3.19866 --4.7723 1.17036 3.40665 --4.69462 1.15521 3.49919 --4.52398 1.12338 3.55048 --4.53426 1.12531 3.67812 --4.64734 1.14606 3.85771 --4.79205 1.17185 4.05984 --4.65203 1.14642 4.12206 --4.24232 1.07018 4.03437 --3.80304 0.988506 3.91357 --3.92302 1.01022 4.10418 --3.86911 0.999511 4.1966 --3.73022 0.973958 4.23481 --3.59235 0.94828 4.26922 --4.21978 1.06397 4.82657 --5.78706 1.35175 6.09135 --3.77614 0.981229 4.7907 --4.51091 1.11574 5.49565 --4.80426 1.16928 5.89442 --4.94159 1.19399 6.18505 --4.46115 1.10568 5.96023 --4.42678 1.09889 6.10787 --4.29475 1.07387 6.16873 --4.23472 1.06245 6.29468 --5.15391 1.23034 7.38742 --5.18932 1.23646 7.64983 --1.95783 0.642919 4.47139 --1.07415 0.480508 3.62786 --1.08851 0.48276 3.7367 --1.0802 0.480581 3.82425 --1.01865 0.469156 3.85086 --1.73017 0.599742 4.84888 --1.61531 0.578277 4.83912 --1.24849 0.510356 4.48262 --0.813837 0.431125 4.0009 --1.2915 0.51811 4.80909 --1.25349 0.510104 4.89619 --1.11117 0.483858 4.82346 --0.942332 0.453295 4.69598 --0.751969 0.418068 4.52089 --0.658001 0.40014 4.4963 --0.597387 0.389152 4.53061 --0.532858 0.377437 4.555 --0.881557 0.439779 5.40764 --0.840431 0.431722 5.51775 --0.770846 0.418239 5.57333 --0.476779 0.364751 5.11588 --0.318101 0.336167 4.93501 --0.250607 0.323464 4.96333 --0.30252 0.331659 5.30807 --0.151826 0.304188 5.1197 --0.0364279 0.282874 5.0125 --0.0255653 0.280303 5.21659 -0.0186236 0.272486 5.33528 -0.195291 0.239779 4.99207 --0.137272 0.297416 6.53806 -0.00266786 0.272019 6.37841 -0.0929681 0.255114 6.41047 -0.264627 0.223841 6.04961 -0.332569 0.211443 6.16552 -0.444921 0.190612 6.04411 -0.529233 0.174695 6.06856 -0.640423 0.154766 5.90326 -0.73041 0.138391 5.86471 -0.815506 0.121704 5.85434 -0.875327 0.110253 6.14129 -1.05244 0.0812382 4.82129 -1.10063 0.0707806 5.17476 -1.17105 0.058143 5.18774 --1.91654 0.7526 -0.932389 --2.0173 0.774681 -0.913256 --2.14485 0.801834 -0.905374 --2.29813 0.83507 -0.907301 --2.45337 0.868667 -0.904324 --2.60957 0.902566 -0.896448 --2.77468 0.938055 -0.887578 --2.97744 0.981311 -0.889307 --3.16331 1.02125 -0.876688 --3.41254 1.07508 -0.883576 --3.64587 1.1257 -0.875213 --3.90792 1.18196 -0.868903 --4.20856 1.24638 -0.866494 --4.53884 1.31767 -0.862788 --4.87897 1.39097 -0.850692 --5.2973 1.48055 -0.848292 --5.73529 1.5758 -0.836503 --6.27919 1.69299 -0.83497 --6.84382 1.81415 -0.818851 --7.5073 1.95733 -0.802933 --8.32509 2.13361 -0.792733 --9.29024 2.34108 -0.778198 --10.4214 2.58511 -0.754638 --11.8167 2.88546 -0.725857 --13.4868 3.24544 -0.679017 --15.4504 3.66783 -0.601088 --19.1401 4.46301 -0.589248 --28.2662 6.42853 -0.245729 --31.2349 7.06574 0.209535 --40.2861 9.01432 0.727511 --40.0083 8.9505 2.20608 --43.0464 9.59925 3.88133 --43.2839 9.64804 4.69732 --43.7695 9.74969 5.549 --48.2401 10.7083 6.89302 --43.7244 9.73432 7.17491 --46.0389 10.2295 8.35399 --45.859 10.1879 9.19025 --13.03 3.13265 3.77202 --13.009 3.12733 4.03404 --12.9465 3.11305 4.28746 --12.9937 3.12178 4.56785 --5.55102 1.52412 2.85624 --4.27539 1.24998 2.62377 --4.43489 1.28345 2.78087 --4.41364 1.27839 2.88668 --4.61257 1.3205 3.06881 --4.48463 1.29329 3.14113 --4.44755 1.28515 3.24466 --5.07181 1.41852 3.61639 --10.1907 2.51344 5.92902 --4.51401 1.2975 3.63536 --4.64662 1.32583 3.82265 --4.99431 1.39987 4.12342 --4.53888 1.30153 4.03005 --4.44357 1.28074 4.11122 --4.46662 1.28535 4.25705 --4.16415 1.22095 4.21678 --3.80558 1.14389 4.13123 --3.82669 1.14802 4.26967 --3.71274 1.12275 4.32368 --3.81072 1.14334 4.51838 --3.54891 1.0869 4.46773 --3.69609 1.11863 4.70572 --3.6718 1.11304 4.82485 --5.0713 1.41062 6.0669 --4.58673 1.30671 5.85612 --7.03577 1.82685 8.10305 --6.14818 1.63701 7.58094 --4.39712 1.26445 6.22616 --4.25747 1.23363 6.28034 --6.1005 1.62478 8.2621 --3.8728 1.15085 6.27307 --1.16746 0.576806 3.63568 --1.9296 0.738489 4.55188 --1.11642 0.565229 3.76781 --1.04317 0.549429 3.78113 --1.0024 0.540403 3.83081 --1.81113 0.71139 4.93855 --0.990641 0.537148 4.02221 --0.837752 0.505199 3.92826 --0.758639 0.48829 3.92637 --1.66688 0.678497 5.34093 --1.60324 0.665057 5.41037 --1.85188 0.716513 5.96309 --0.896905 0.514867 4.6175 --0.783325 0.491677 4.57139 --0.678743 0.468315 4.53106 --0.565275 0.444423 4.47067 --0.529336 0.436061 4.54809 --1.10382 0.556528 5.83259 --0.76883 0.485574 5.35594 --0.451706 0.418191 4.86885 --0.421474 0.411949 4.98206 --0.318858 0.390142 4.93026 --0.326764 0.39119 5.14403 --0.263291 0.376686 5.1918 --0.141191 0.350681 5.07908 --0.0259677 0.326411 4.97273 -0.00825258 0.318658 5.1008 -0.106834 0.298077 5.02835 -0.224758 0.272415 4.87699 -0.0937771 0.29856 5.62897 -0.0652084 0.303427 6.07661 -0.097073 0.296109 6.33193 -0.208419 0.271554 6.25556 -0.333284 0.245183 6.09838 -0.395361 0.232056 6.25313 -0.49887 0.210155 6.1803 -0.631956 0.181593 5.88779 -0.716029 0.163565 5.88962 -0.806729 0.144116 5.83038 -0.911479 0.122359 5.60014 -1.07449 0.0915728 4.4902 -1.09348 0.0851782 5.17321 -1.16373 0.0695742 5.18683 -1.23244 0.0544545 5.28926 --1.90116 0.855974 -0.912456 --2.02649 0.886905 -0.90658 --2.16168 0.920402 -0.901453 --2.3157 0.957809 -0.901076 --2.46968 0.995461 -0.895705 --2.64241 1.03808 -0.893834 --2.82499 1.08339 -0.890415 --3.01847 1.13046 -0.884795 --3.22968 1.18256 -0.880283 --3.46068 1.23886 -0.875822 --3.71139 1.30041 -0.870462 --4.00064 1.37109 -0.869551 --4.2997 1.4447 -0.8619 --4.62839 1.52519 -0.85275 --5.01335 1.61986 -0.84876 --5.42891 1.72166 -0.839172 --5.91257 1.8405 -0.831987 --6.47325 1.97799 -0.825812 --6.87374 2.07641 -0.765014 --7.23667 2.1646 -0.682782 --8.01936 2.35726 -0.663651 --8.95804 2.58759 -0.641436 --10.1011 2.86759 -0.614844 --11.6409 3.24635 -0.596885 --13.5114 3.70526 -0.558831 --15.3362 4.1519 -0.449647 --27.2087 7.06703 -0.463241 --40.0794 10.2234 0.359621 --40.0463 10.2122 1.10443 --40.3015 10.2728 1.85379 --13.9483 3.80336 1.8781 --13.93 3.7965 2.42968 --45.9475 11.6426 6.23703 --47.7313 12.0763 7.32774 --45.4256 11.5084 7.88725 --45.4177 11.5033 8.7459 --13.0368 3.57312 3.66503 --13.0751 3.58108 3.94078 --13.0235 3.56773 4.19975 --12.9306 3.54338 4.44872 --11.5233 3.19902 4.35633 --12.7585 3.49952 4.94714 --4.27244 1.42496 2.69715 --4.19705 1.40562 2.78341 --4.46163 1.4706 2.98255 --5.39142 1.69744 3.43069 --7.0375 2.09821 4.18782 --9.04876 2.58886 5.15948 --10.3819 2.91237 5.93316 --4.40768 1.45469 3.55662 --4.40907 1.45489 3.68037 --4.60055 1.50133 3.89827 --4.62952 1.50733 4.04458 --4.48216 1.47117 4.10167 --4.11233 1.38017 4.03183 --4.36571 1.44211 4.30483 --4.41823 1.4546 4.47253 --4.12624 1.38276 4.43121 --3.95237 1.34033 4.45485 --4.15454 1.38799 4.72464 --3.70414 1.27909 4.55393 --3.58059 1.24776 4.59845 --3.70682 1.27881 4.8281 --6.21544 1.88623 6.92183 --4.13334 1.38097 5.45852 --4.4119 1.44745 5.85304 --6.96746 2.0664 8.24324 --5.91438 1.81026 7.55667 --5.99684 1.82965 7.86745 --6.44781 1.93765 8.54534 --2.13183 0.892974 4.50814 --2.09297 0.882731 4.59164 --2.02558 0.866309 4.64598 --3.04836 1.11304 5.90788 --2.92583 1.08224 5.94167 --2.13566 0.891356 5.17878 --1.82183 0.815508 4.94173 --1.82806 0.816301 5.09173 --0.785362 0.564952 3.86204 --1.94437 0.843331 5.55579 --1.70825 0.785624 5.38766 --1.60061 0.759322 5.39291 --3.53679 1.22319 8.52516 --1.88324 0.825718 6.18525 --0.835018 0.574172 4.65495 --0.722684 0.547006 4.60804 --0.579092 0.511787 4.49751 --0.581403 0.511253 4.64573 --0.569932 0.508055 4.77726 --0.998485 0.610246 5.8103 --0.475523 0.484175 4.91636 --0.57241 0.506619 5.31161 --0.295036 0.440893 4.87021 --0.2971 0.440656 5.06518 --0.191764 0.415093 5.00162 --0.104061 0.393323 4.97287 --0.0105313 0.370175 4.9234 --0.000743936 0.367184 5.11771 -0.117119 0.338652 4.98933 -0.237847 0.310383 4.82927 -0.24189 0.308036 5.07005 -0.110292 0.33724 5.86273 -0.182667 0.319818 5.92319 -0.176658 0.318948 6.3433 -0.309108 0.287729 6.15826 -0.363273 0.27306 6.35319 -0.483019 0.244325 6.20277 -0.611192 0.214064 5.95094 -0.711384 0.189709 5.84481 -0.79525 0.169154 5.83585 -0.930102 0.13834 5.31806 -1.06959 0.10679 4.52814 -1.08639 0.100558 5.1713 -1.1566 0.0834751 5.19552 -1.225 0.0664227 5.2586 --1.78178 0.941122 -0.910871 --1.91378 0.97813 -0.911949 --2.03886 1.01316 -0.904073 --2.18269 1.05307 -0.901396 --2.33539 1.09554 -0.898474 --2.48805 1.13825 -0.890658 --2.66045 1.186 -0.886138 --2.85054 1.23972 -0.883875 --3.04264 1.29288 -0.87526 --3.27118 1.35686 -0.8748 --3.50067 1.42127 -0.866744 --3.76764 1.49571 -0.864091 --4.03654 1.57071 -0.85224 --4.3705 1.66411 -0.852194 --4.68766 1.75233 -0.835004 --5.06197 1.85679 -0.822668 --5.46482 1.96927 -0.804894 --5.95341 2.10566 -0.793826 --6.36896 2.22128 -0.748372 --6.81302 2.34506 -0.694383 --7.39897 2.50895 -0.651859 --8.27174 2.75296 -0.637443 --9.24199 3.02374 -0.606553 --10.5758 3.39602 -0.589699 --12.1992 3.84971 -0.558441 --13.9308 4.33237 -0.479095 --14.0981 4.37775 -0.212676 --14.079 4.37159 0.0705265 --14.0728 4.36911 0.351846 --14.1021 4.37573 0.631698 --40.2646 11.6822 0.728472 --40.4079 11.7193 1.48491 --15.1216 4.6571 1.5038 --14.0822 4.365 1.75425 --14.0671 4.35993 2.03443 --14.0481 4.3536 2.31434 --14.0438 4.35126 2.59587 --13.9864 4.33439 2.87178 --42.0819 12.1637 7.05226 --42.1747 12.1858 7.87041 --42.1198 12.167 8.67029 --13.116 4.08723 3.84266 --13.0095 4.05609 4.09295 --11.4749 3.62639 4.25506 --11.5682 3.65157 4.52789 --5.81043 2.04987 3.10981 --4.27808 1.62284 2.77678 --4.37691 1.65003 2.92151 --4.3351 1.63746 3.02252 --11.4433 3.61122 5.76742 --8.86361 2.89394 5.02399 --9.07305 2.95152 5.32328 --5.53932 1.97013 4.0165 --5.46986 1.94968 4.13361 --5.40818 1.93283 4.25319 --5.12737 1.85418 4.26346 --5.01961 1.82308 4.35415 --4.24553 1.60828 4.08035 --5.58912 1.98041 4.97207 --4.45848 1.66656 4.47035 --4.47456 1.67002 4.62159 --4.20771 1.59547 4.59622 --4.21981 1.59859 4.74545 --4.09248 1.56261 4.80218 --3.6951 1.45244 4.66238 --3.74258 1.46489 4.83536 --3.63886 1.43565 4.89796 --4.49708 1.67203 5.72684 --4.3422 1.62872 5.7703 --4.32081 1.62202 5.92435 --5.87032 2.04747 7.47859 --6.32931 2.17388 8.13361 --6.06041 2.09828 8.1301 --5.87685 2.04661 8.20178 --3.33891 1.34789 5.86019 --2.04991 0.992143 4.66592 --1.94834 0.963837 4.68403 --1.83406 0.931896 4.6848 --2.53697 1.12518 5.64284 --2.50884 1.11595 5.77423 --2.44731 1.09879 5.8672 --2.23987 1.04139 5.77137 --1.91304 0.951142 5.50259 --1.74003 0.902731 5.42481 --1.60425 0.864775 5.39116 --3.52502 1.389 8.46485 --3.51593 1.38487 8.73642 --0.986752 0.69508 4.90583 --0.775878 0.637062 4.70066 --0.64522 0.601022 4.6185 --0.636739 0.598036 4.75064 --0.459272 0.549112 4.56682 --0.940859 0.678687 5.68293 --0.759379 0.629025 5.50932 --0.41905 0.53555 4.96936 --0.328485 0.510908 4.94683 --0.284739 0.498462 5.0323 --0.184497 0.470696 4.97881 --0.110589 0.449639 4.98807 --0.036634 0.429506 4.99579 --0.00166465 0.418276 5.11531 -0.0888082 0.393678 5.07335 -0.191806 0.364859 4.98174 -0.247263 0.349409 5.04114 -0.11195 0.384312 5.82286 -0.419169 0.30165 4.9347 -0.169367 0.365542 6.32334 -0.287088 0.333641 6.20774 -0.349796 0.315056 6.35434 -0.488541 0.277858 6.09685 -0.552302 0.259556 6.25044 -0.704019 0.218991 5.8195 -0.781973 0.196787 5.85102 -0.93466 0.156545 5.20529 -1.05162 0.126677 4.70502 -1.07935 0.11693 5.16925 -1.14747 0.0974922 5.20411 -1.21568 0.0779799 5.2578 -1.24186 0.0634182 7.09958 --1.79669 1.05911 -0.916248 --1.92059 1.09699 -0.910124 --2.04541 1.13612 -0.900149 --2.18699 1.18002 -0.895282 --2.33936 1.2276 -0.89011 --2.50949 1.28009 -0.888344 --2.68841 1.3362 -0.884985 --2.87817 1.39507 -0.879573 --3.06887 1.45432 -0.867764 --3.31369 1.53114 -0.87091 --3.5595 1.60744 -0.865612 --3.82596 1.69009 -0.858461 --4.02831 1.75334 -0.820525 --4.33311 1.84761 -0.807735 --4.69294 1.95997 -0.800806 --5.08225 2.08137 -0.788883 --5.51979 2.2168 -0.775267 --5.97591 2.35892 -0.750619 --6.39751 2.49012 -0.701678 --6.91257 2.64985 -0.656604 --7.60663 2.86582 -0.625899 --8.51997 3.15068 -0.605761 --9.70874 3.52005 -0.59241 --11.1846 3.97932 -0.572101 --12.9759 4.53687 -0.532106 --14.8831 5.13021 -0.437188 --23.2305 7.73026 -0.73091 --23.1035 7.68917 -0.272027 --23.0169 7.66022 0.18007 --40.5177 13.1068 0.344406 --40.5044 13.0998 1.11099 --15.1522 5.20551 1.36016 --14.2277 4.91717 1.62746 --14.2067 4.90899 1.91284 --14.1995 4.9057 2.1991 --14.1776 4.89746 2.48439 --14.1507 4.8879 2.7692 --42.6242 13.7327 6.77982 --51.8281 16.5833 9.96865 --41.9127 13.4972 9.93678 --50.5924 16.1863 12.7128 --11.7977 4.14663 4.50218 --5.5872 2.22071 3.00374 --5.5257 2.20085 3.12318 --11.3053 3.99027 5.12455 --5.71489 2.25836 3.46587 --5.69165 2.25069 3.60243 --5.43187 2.16912 3.64944 --5.36939 2.14911 3.76708 --5.33243 2.13715 3.89443 --5.35335 2.14306 4.0488 --5.3635 2.14518 4.20066 --5.07632 2.05606 4.20948 --5.20222 2.09417 4.42017 --5.11916 2.06737 4.52696 --4.90856 2.00217 4.56104 --4.77354 1.95943 4.63226 --4.42278 1.85086 4.56925 --4.26526 1.80141 4.61339 --4.41463 1.84649 4.85495 --4.40611 1.8431 4.99923 --3.82516 1.66377 4.74044 --3.77844 1.64919 4.84712 --3.64454 1.60704 4.88848 --7.2906 2.72784 7.91903 --4.42987 1.84732 5.82403 --4.37914 1.83071 5.95541 --3.84947 1.66708 5.66751 --3.64213 1.60227 5.64463 --10.3726 3.66767 12.1743 --10.0869 3.57803 12.2922 --3.44602 1.53972 5.95724 --2.81595 1.34618 5.47148 --1.94637 1.07903 4.68327 --1.85187 1.04945 4.70751 --1.7906 1.03062 4.76662 --2.39148 1.21285 5.62607 --2.21565 1.15944 5.57214 --2.10939 1.12526 5.59891 --2.26203 1.17196 5.97048 --2.53485 1.25344 6.53283 --1.74164 1.01139 5.5914 --1.91182 1.06187 6.01759 --1.44912 0.920397 5.48813 --1.31164 0.878564 5.43904 --0.701953 0.692214 4.58813 --0.642791 0.673483 4.62633 --0.543622 0.642821 4.59402 --1.01578 0.785214 5.63623 --2.34911 1.18654 8.46423 --0.726568 0.696112 5.44579 --0.4306 0.606343 5.00743 --0.404519 0.59687 5.13134 --0.316058 0.569814 5.11826 --0.24031 0.545802 5.13085 --0.0935925 0.5012 4.95627 --0.0616106 0.490196 5.07671 -0.02578 0.463368 5.0467 -0.0927617 0.442498 5.07153 -0.163651 0.420857 5.08555 -0.273221 0.387161 4.96429 -0.291803 0.380585 5.1577 -0.441835 0.334628 4.85871 -0.0822951 0.438754 6.66206 -0.257721 0.385878 6.31514 -0.365518 0.352453 6.23764 -0.512564 0.307346 5.93192 -0.534929 0.299286 6.30229 -0.711339 0.247441 5.73465 -0.837603 0.209692 5.39018 -0.936909 0.179819 5.17169 -1.04529 0.147415 4.79186 -1.07651 0.135529 5.17677 -1.1445 0.114634 5.2023 -1.20887 0.0938431 5.30644 -1.22021 0.0816916 7.15853 --1.682 1.13328 -0.919293 --1.79584 1.1717 -0.91017 --1.91849 1.21361 -0.902251 --2.05095 1.25909 -0.894931 --2.19227 1.3071 -0.887765 --2.35122 1.362 -0.884503 --2.52003 1.41955 -0.880093 --2.70745 1.48415 -0.877884 --2.88705 1.54476 -0.865529 --3.11965 1.62483 -0.869031 --3.26571 1.67473 -0.82968 --3.49236 1.75232 -0.815285 --3.78192 1.85106 -0.815251 --4.0458 1.94218 -0.79602 --4.33819 2.04207 -0.776095 --4.65903 2.15183 -0.753827 --5.01818 2.274 -0.730164 --5.45091 2.42239 -0.712317 --5.94061 2.5894 -0.691831 --6.40365 2.74794 -0.64781 --7.04441 2.96749 -0.621505 --7.89138 3.25705 -0.607828 --8.83441 3.5803 -0.577927 --10.1918 4.04484 -0.570125 --11.6166 4.53258 -0.520477 --13.7688 5.26988 -0.490873 --21.6968 7.98585 -0.848762 --32.5699 11.7038 0.16056 --23.6678 8.65153 0.84959 --32.9009 11.8103 1.41969 --40.4923 14.3896 5.38951 --41.3923 14.6928 6.28242 --51.6458 18.1867 9.53483 --12.5581 4.83276 3.79954 --12.4274 4.78661 4.03927 --12.2829 4.73449 4.53981 --11.0965 4.32895 4.4818 --5.43201 2.39648 3.05606 --5.37943 2.37824 3.17689 --5.3073 2.35243 3.29043 --5.27826 2.34194 3.41777 --5.25512 2.33297 3.54819 --5.26621 2.33679 3.69257 --5.30868 2.35031 3.85284 --8.48663 3.43028 5.39657 --6.00082 2.58396 4.46498 --5.14314 2.29203 4.21424 --5.02987 2.25258 4.305 --4.99202 2.23858 4.43294 --4.93453 2.2189 4.5511 --4.65976 2.1247 4.54365 --4.32929 2.01093 4.49257 --4.64572 2.11814 4.83292 --4.27609 1.99217 4.74538 --4.08563 1.92642 4.76403 --4.05462 1.91563 4.88767 --4.23199 1.97519 5.16459 --4.03177 1.90617 5.1697 --4.38902 2.02653 5.60415 --4.30514 1.99737 5.70484 --4.12354 1.93413 5.72284 --3.63591 1.76865 5.4676 --3.5482 1.73823 5.5476 --3.54357 1.73574 5.70538 --1.79262 1.14466 4.17131 --1.67779 1.10548 4.16842 --2.8056 1.48515 5.45486 --2.14855 1.26266 4.90362 --2.6382 1.42644 5.58719 --1.82702 1.15344 4.81214 --2.30282 1.31244 5.51725 --3.33965 1.65948 6.96457 --2.14619 1.25815 5.64494 --2.7757 1.46845 6.65122 --1.84227 1.15473 5.56793 --1.77232 1.1298 5.63588 --1.81149 1.14256 5.86565 --1.64498 1.08576 5.79294 --1.47757 1.02827 5.70723 --0.713943 0.772763 4.62012 --0.664619 0.75553 4.67654 --0.819757 0.806115 5.10311 --0.798513 0.79915 5.23124 --0.710147 0.769013 5.23683 --0.653944 0.748817 5.30256 --0.641406 0.744128 5.46599 --0.368435 0.652391 5.06105 --0.329715 0.638793 5.15763 --0.223019 0.602304 5.0979 --0.195938 0.592161 5.22975 --0.0601678 0.546563 5.08244 --0.00298937 0.526789 5.13763 --0.104639 0.558482 5.67313 --0.258253 0.607384 6.43168 -0.25079 0.439899 5.04978 -0.352394 0.405567 4.94644 -0.445267 0.374598 4.85982 -0.206565 0.450385 6.11754 -0.250585 0.433433 6.31476 -0.370722 0.393395 6.17962 -0.471552 0.359279 6.12012 -0.843078 0.240179 4.49463 -0.709222 0.279881 5.71875 -0.861978 0.230748 5.19722 -0.938297 0.204632 5.14784 -1.04186 0.170508 4.8286 -1.07573 0.157516 5.15397 -1.1388 0.134917 5.22007 -1.20213 0.112708 5.3348 -1.19859 0.104481 7.16699 -1.32714 0.0669328 6.06076 --1.67044 1.24041 -0.909126 --1.78309 1.28186 -0.89836 --1.91333 1.3311 -0.893344 --2.06126 1.38619 -0.892982 --2.20232 1.43832 -0.883417 --2.36001 1.49728 -0.877562 --2.51866 1.55657 -0.866308 --2.7136 1.62958 -0.865354 --2.82216 1.66946 -0.820401 --3.03573 1.74884 -0.814707 --3.27571 1.83871 -0.811824 --3.50098 1.92241 -0.794035 --3.75266 2.01666 -0.777658 --4.00532 2.11041 -0.752337 --4.29521 2.21834 -0.729122 --4.59384 2.3302 -0.698121 --4.93072 2.45545 -0.666175 --5.36852 2.61927 -0.646642 --5.8347 2.79332 -0.617475 --6.44005 3.01934 -0.599577 --7.24045 3.31764 -0.595607 --8.12694 3.64899 -0.576162 --9.26526 4.07358 -0.561014 --10.7033 4.61074 -0.542125 --12.5067 5.28398 -0.51002 --21.2087 8.5308 -0.187619 --30.664 12.0606 -0.0920532 --30.8092 12.112 0.504805 --31.1798 12.2466 1.10737 --31.9421 12.5282 1.73202 --44.905 17.3566 3.73764 --41.5753 16.1095 4.34787 --41.4503 16.0581 5.14299 --41.3586 16.0199 5.93983 --41.6457 16.1224 6.78661 --46.5831 17.9569 8.35761 --41.6277 16.1061 8.42248 --5.30768 2.57951 2.44835 --12.284 5.17416 4.18111 --5.27623 2.56525 2.70482 --5.22963 2.54736 2.82548 --5.19868 2.53562 2.95007 --5.17557 2.52646 3.07679 --5.17692 2.52624 3.21218 --5.19395 2.53131 3.35444 --5.22559 2.54267 3.50452 --11.39 4.82999 6.05627 --11.2011 4.75806 6.25176 --8.7603 3.85147 5.46575 --6.2809 2.93055 4.5593 --4.96427 2.44217 4.10203 --4.64205 2.32159 4.08559 --4.48212 2.26155 4.14174 --9.13634 3.9837 6.8248 --4.6079 2.30666 4.49366 --4.50174 2.26627 4.5772 --4.52355 2.27357 4.73812 --4.06863 2.10462 4.59585 --4.19205 2.14932 4.82091 --4.18455 2.14594 4.96409 --4.58526 2.29234 5.40561 --4.28281 2.17979 5.34507 --4.19617 2.14716 5.43981 --8.28163 3.6529 8.90147 --4.12247 2.11799 5.70999 --5.95933 2.79384 7.47347 --5.64506 2.67711 7.42386 --3.03032 1.71377 5.21992 --1.86891 1.28456 4.24984 --1.76111 1.2443 4.25688 --2.81962 1.63298 5.46563 --2.9252 1.67083 5.73624 --2.00808 1.33361 4.88732 --1.74627 1.23649 4.72432 --1.65408 1.20192 4.74642 --1.71003 1.22131 4.94785 --1.66943 1.20624 5.03719 --1.73308 1.22847 5.26638 --1.83658 1.26544 5.56224 --1.6596 1.20048 5.47914 --1.52652 1.15075 5.44759 --1.52872 1.15029 5.61764 --1.53184 1.15037 5.79738 --1.01463 0.960659 5.13019 --1.01195 0.959208 5.28624 --0.893606 0.914959 5.24603 --1.12896 0.999402 5.85309 --0.71328 0.848227 5.25269 --0.679499 0.834626 5.36343 --0.518509 0.775437 5.21548 --0.544844 0.784082 5.45887 --0.440197 0.744894 5.42312 --0.322005 0.700947 5.34835 --0.115665 0.626055 5.04012 --0.0818705 0.612543 5.15266 --0.0470051 0.599421 5.27438 --0.0644189 0.603404 5.55597 --0.00818873 0.582136 5.64057 -0.0847645 0.547937 5.61028 -0.367674 0.445874 4.9081 -0.449756 0.415499 4.86078 -0.188204 0.506467 6.1743 -0.265836 0.477284 6.22648 -0.346315 0.446377 6.26762 -0.751703 0.304176 4.68275 -0.84303 0.270473 4.51888 -0.787388 0.287526 5.21975 -0.870278 0.257153 5.13298 -0.937904 0.231528 5.14361 -1.02347 0.200883 4.99396 -1.09662 0.173845 4.92212 -1.13338 0.158156 5.25732 -1.13971 0.150878 6.23072 -1.23123 0.117113 6.10631 -1.30929 0.0869123 6.25986 --1.78278 1.40236 -0.895169 --1.92066 1.45796 -0.892509 --2.05949 1.51385 -0.885249 --2.21497 1.57657 -0.881898 --2.35567 1.63405 -0.86509 --2.47872 1.68407 -0.835639 --2.65374 1.75436 -0.824796 --2.85613 1.83609 -0.818805 --3.05847 1.91817 -0.805823 --3.28035 2.00847 -0.792391 --3.51106 2.10153 -0.774318 --3.71622 2.18489 -0.739049 --3.94879 2.27886 -0.705087 --4.22635 2.39134 -0.676185 --4.52248 2.51122 -0.642193 --4.89983 2.66359 -0.618269 --5.31529 2.83155 -0.589303 --5.79423 3.02648 -0.558959 --6.53937 3.32807 -0.562995 --7.48689 3.71269 -0.575222 --8.50182 4.1237 -0.562281 --9.64769 4.58773 -0.529587 --11.3656 5.28464 -0.522647 --19.4001 8.54296 -0.692671 --28.9448 12.4097 -0.32449 --29.0371 12.4436 0.247377 --29.3426 12.5637 0.820797 --29.2032 12.5038 1.40006 --30.3047 12.9434 2.61266 --30.3861 12.9724 3.21912 --42.6433 17.9316 4.89868 --41.0446 17.2793 5.56592 --41.3352 17.391 6.41267 --5.14629 2.74618 2.24365 --5.09783 2.7261 2.3631 --5.09437 2.72323 2.49138 --5.10549 2.72747 2.62412 --5.11466 2.73064 2.7578 --5.11311 2.72907 2.88973 --5.14474 2.74109 3.03297 --5.21837 2.76949 3.19225 --11.8549 5.44468 5.60782 --11.3577 5.24294 5.70503 --11.9881 5.49507 6.21885 --11.7974 5.41677 6.42965 --11.5795 5.32697 6.62378 --8.46522 4.07154 5.50969 --8.26419 3.98945 5.63649 --4.68934 2.54928 4.08869 --4.60578 2.51503 4.18754 --4.45491 2.45376 4.24813 --4.81224 2.5967 4.59186 --4.58337 2.50351 4.60955 --6.024 3.08115 5.64373 --4.09645 2.30621 4.60189 --4.29861 2.38637 4.87989 --4.25115 2.36636 4.99934 --4.10133 2.30546 5.04601 --4.50118 2.46535 5.49767 --3.97621 2.25336 5.26035 --3.56433 2.08755 5.08823 --3.32891 1.99182 5.04241 --3.15484 1.92195 5.03907 --3.06071 1.88321 5.1006 --2.99385 1.85532 5.18585 --1.77415 1.36699 4.16655 --1.77753 1.3679 4.28197 --3.41818 2.02171 6.08263 --3.6461 2.11158 6.50474 --1.59592 1.29361 4.44118 --1.6742 1.32382 4.65168 --1.67751 1.32461 4.78483 --1.54954 1.27259 4.76155 --1.59075 1.28834 4.94793 --1.52693 1.26226 5.00548 --1.77904 1.36086 5.49323 --1.67818 1.32071 5.51453 --1.59974 1.28841 5.56556 --1.39696 1.20713 5.42748 --1.01557 1.05528 4.99419 --0.951833 1.02867 5.04095 --0.960882 1.03074 5.21324 --0.830124 0.978478 5.14789 --0.978741 1.03637 5.58806 --0.694793 0.923375 5.23313 --0.644621 0.902039 5.30898 --0.566289 0.870311 5.33095 --0.509275 0.847025 5.39602 --0.426108 0.813409 5.40603 --0.247139 0.742564 5.18652 --0.106079 0.685411 5.03513 --0.0404214 0.658841 5.06475 --0.0163299 0.64829 5.20495 --0.130274 0.690616 5.75786 --0.0316197 0.651772 5.72174 -0.0621002 0.613583 5.69284 -0.0623702 0.611604 5.97689 -0.111879 0.590551 6.11831 -0.169157 0.56705 6.24006 -0.26293 0.528565 6.22549 -0.360586 0.489786 6.18948 -0.774998 0.331682 4.59831 -0.840399 0.305376 4.57225 -0.806594 0.315295 5.1154 -0.874095 0.288272 5.1179 -0.937767 0.261887 5.14883 -1.00433 0.235287 5.15873 -1.11685 0.19168 4.74006 -1.1756 0.167892 4.75669 -1.13583 0.176109 6.14822 -1.22617 0.139439 6.02445 -1.30906 0.106598 5.96884 -1.38428 0.0749943 6.17155 --1.43105 1.37216 -0.913979 --1.53246 1.417 -0.901866 --1.65931 1.47286 -0.900806 --1.79497 1.53224 -0.900251 --1.89929 1.57781 -0.877037 --2.03587 1.63767 -0.867787 --2.1568 1.69022 -0.845486 --2.31192 1.75826 -0.835391 --2.4846 1.83427 -0.827651 --2.64169 1.90199 -0.80641 --2.8407 1.98967 -0.797635 --3.05926 2.08558 -0.788508 --3.28658 2.18525 -0.774792 --3.48947 2.27327 -0.743775 --3.70107 2.36604 -0.708417 --3.92144 2.46258 -0.668369 --4.2229 2.59437 -0.643331 --4.53309 2.73012 -0.609808 --4.87934 2.88222 -0.5738 --5.37016 3.09721 -0.557865 --5.8355 3.30082 -0.518042 --6.81551 3.73015 -0.558341 --7.75335 4.14109 -0.554014 --8.92048 4.6532 -0.548445 --10.3082 5.26065 -0.527397 --12.2814 6.12552 -0.518986 --18.2718 8.75302 -0.806694 --18.9106 9.03079 -0.473683 --27.3696 12.7354 0.0116494 --27.6297 12.8455 0.558774 --27.5697 12.8152 1.11447 --27.7849 12.9061 1.6739 --50.7561 22.9635 3.18055 --60.556 27.2248 8.34291 --5.02015 2.92556 2.05022 --4.93958 2.89022 2.16376 --4.93907 2.88845 2.2905 --4.98037 2.90675 2.4272 --5.02956 2.92673 2.56798 --5.11088 2.96125 2.72011 --10.6458 5.37687 4.37812 --10.671 5.38603 4.63318 --11.167 5.59968 5.04051 --11.3987 5.69982 5.38204 --11.5895 5.78033 5.72121 --11.9711 5.94573 6.14432 --11.3717 5.68229 6.19389 --11.2536 5.62941 6.42444 --10.0115 5.08659 6.15406 --11.0495 5.53616 6.89619 --4.4448 2.66105 3.95022 --4.37214 2.62855 4.05086 --6.06853 3.3657 5.09764 --4.77882 2.80359 4.557 --4.40632 2.64048 4.49259 --4.32582 2.60537 4.5905 --4.25999 2.57555 4.69648 --3.99661 2.46011 4.67164 --3.69725 2.32971 4.6114 --3.60134 2.28635 4.68307 --3.51122 2.2465 4.7578 --3.42112 2.20653 4.83024 --3.31546 2.15991 4.88857 --3.23898 2.12614 4.96813 --3.17514 2.09766 5.05833 --3.25227 2.13005 5.27361 --3.42266 2.20285 5.58337 --5.26362 2.99689 7.50017 --5.16647 2.95258 7.63515 --4.94582 2.8565 7.64523 --1.7168 1.46259 4.46518 --1.5842 1.40425 4.44137 --1.51667 1.37429 4.48576 --1.42973 1.33596 4.50658 --1.39814 1.32125 4.59226 --1.33446 1.29369 4.63987 --1.55321 1.38666 5.05474 --7.7296 4.03758 13.5485 --3.07955 2.04003 7.49151 --1.26807 1.2612 5.0972 --1.23442 1.24613 5.1984 --1.036 1.16035 5.04526 --0.956898 1.12464 5.06862 --0.961019 1.12601 5.23289 --0.951591 1.12078 5.38165 --0.924695 1.10824 5.50541 --0.697442 1.00995 5.25654 --0.544739 0.944393 5.1318 --0.547857 0.944497 5.31214 --0.46199 0.906369 5.31534 --0.285273 0.830325 5.10962 --0.157933 0.774985 4.9983 --0.10882 0.753327 5.06636 --0.180321 0.782548 5.44716 --0.0163805 0.711644 5.22838 --0.00191048 0.704564 5.40663 --0.0442398 0.720311 5.77374 -0.0589458 0.675193 5.71778 --1.48915 1.31786 11.209 -0.121074 0.645601 6.08669 -0.186854 0.616686 6.1703 -0.244024 0.590645 6.30139 -0.549229 0.463038 5.35398 -0.68076 0.407374 5.07943 -0.836887 0.342314 4.62513 -0.86498 0.328464 4.80481 -0.878048 0.320859 5.11236 -0.940605 0.292565 5.1439 -1.02307 0.257651 5.02572 -1.12783 0.213488 4.66732 -1.19859 0.184093 4.54505 -1.12562 0.204642 6.16502 -1.21867 0.165365 6.01222 -1.29337 0.132445 6.12709 -1.37782 0.0954879 6.03082 --1.41724 1.48388 -0.909663 --1.53408 1.53929 -0.905556 --1.64411 1.59071 -0.892697 --1.77751 1.65406 -0.890052 --1.86402 1.69507 -0.856141 --1.99157 1.75469 -0.840843 --2.13564 1.82314 -0.829453 --2.31388 1.90716 -0.828871 --2.45992 1.97525 -0.806735 --2.62346 2.05232 -0.786804 --2.84652 2.15714 -0.785389 --3.04509 2.25134 -0.766123 --3.27879 2.36143 -0.752168 --3.4783 2.45543 -0.717767 --3.7051 2.56205 -0.684671 --3.94942 2.67689 -0.648638 --4.26388 2.82552 -0.623523 --4.60559 2.98707 -0.593622 --5.05453 3.19859 -0.576545 --5.48682 3.40211 -0.53878 --6.08864 3.6862 -0.518756 --7.25479 4.23617 -0.578031 --8.13702 4.65313 -0.546403 --9.4967 5.29484 -0.548686 --11.3542 6.17082 -0.559454 --17.2112 8.93756 -0.910821 --20.9755 10.7073 0.0131264 --26.1781 13.161 0.315873 --26.4213 13.2714 0.85003 --27.0549 13.5666 1.39841 --20.8083 10.6158 1.74864 --20.7849 10.6026 2.17974 --4.92903 3.1215 1.86466 --4.83503 3.07629 1.97778 --4.7829 3.05088 2.09516 --4.80085 3.05836 2.2242 --4.87034 3.09062 2.36534 --12.4762 6.66287 4.80006 --10.5412 5.75112 4.52812 --11.9835 6.42653 5.2259 --11.4483 6.17376 5.33152 --11.3956 6.14717 5.58782 --11.2972 6.09894 5.82741 --11.5439 6.2127 6.20264 --11.9267 6.38935 6.64883 --10.406 5.67437 6.28018 --4.22271 2.77544 3.69564 --4.13858 2.73475 3.78679 --4.14381 2.73673 3.9214 --4.08984 2.7096 4.02664 --3.93566 2.63758 4.07682 --3.84766 2.59522 4.15921 --3.76551 2.55534 4.24382 --3.69891 2.52279 4.33621 --3.63808 2.49378 4.43197 --3.57633 2.46364 4.52648 --3.52812 2.44081 4.63045 --3.45469 2.40555 4.71691 --3.40362 2.38044 4.81876 --3.3438 2.35145 4.91393 --3.28881 2.325 5.01382 --3.27555 2.31789 5.14953 --1.73123 1.59771 3.93601 --1.95681 1.70203 4.24805 --3.14361 2.25251 5.48862 --3.11279 2.23803 5.61845 --1.78657 1.61971 4.43358 --1.7453 1.6 4.51132 --7.97209 4.48946 11.4227 --1.6143 1.53806 4.61515 --1.48878 1.47837 4.59587 --1.43881 1.45453 4.66153 --1.38691 1.42953 4.72622 --1.34564 1.4099 4.80536 --1.60264 1.52751 5.28631 --1.55745 1.50525 5.37796 --3.03471 2.18669 7.67189 --1.10605 1.29513 5.02808 --0.969018 1.23055 4.96469 --0.937397 1.21543 5.06231 --0.908705 1.2009 5.16832 --1.03755 1.25886 5.55327 --0.767191 1.1329 5.24384 --1.28327 1.36908 6.38422 --0.583087 1.04712 5.23499 --0.534095 1.02284 5.31079 --0.378875 0.951013 5.16391 --0.413814 0.965054 5.42471 --0.308781 0.916401 5.38062 --0.956573 1.2091 7.15645 --0.167327 0.848652 5.4408 --0.0835776 0.80927 5.43637 --0.00656302 0.77313 5.44865 --0.152697 0.837108 6.11579 --0.232231 0.870313 6.64804 --0.318179 0.906889 7.26068 --0.205215 0.854303 7.24806 -0.228718 0.658046 6.02376 -0.535588 0.519553 5.14205 -0.747167 0.423326 4.53135 -0.779857 0.407345 4.65343 -0.790709 0.40098 4.90236 -0.864506 0.366739 4.84789 -0.916384 0.341604 4.90989 -0.995759 0.304439 4.80326 -1.06841 0.270575 4.71454 -1.13917 0.238752 4.62423 -1.19843 0.209994 4.60195 -1.12048 0.235873 6.16152 -1.20962 0.194842 6.04949 -1.28943 0.156714 6.04533 -1.3711 0.119425 5.99966 -1.41786 0.0873734 7.35204 --1.20212 1.49717 -0.925827 --1.29341 1.54351 -0.911565 --1.41593 1.60494 -0.914217 --1.50817 1.65167 -0.893458 --1.60917 1.70285 -0.87435 --1.72575 1.76172 -0.860804 --1.8667 1.83265 -0.856269 --1.98515 1.89304 -0.834372 --2.1358 1.96884 -0.824393 --2.28733 2.04595 -0.809164 --2.45643 2.13105 -0.795892 --2.63425 2.22081 -0.780176 --2.83732 2.32394 -0.768222 --3.06763 2.44065 -0.758423 --3.27264 2.54366 -0.731029 --3.52135 2.67004 -0.710546 --3.74576 2.78276 -0.672763 --3.99538 2.90907 -0.634348 --4.35888 3.09235 -0.617558 --4.6181 3.22418 -0.560614 --4.95618 3.39444 -0.512346 --5.29516 3.56539 -0.45129 --6.62632 4.24073 -0.56999 --7.70827 4.78844 -0.592572 --8.74819 5.31495 -0.566384 --10.6136 6.25999 -0.610218 --19.0316 10.5235 -0.920807 --16.9501 9.4657 -0.359503 --24.4902 13.2829 -0.409783 --24.6707 13.371 0.0951391 --24.825 13.4448 0.606864 --24.9899 13.5245 1.12439 --5.30734 3.55739 1.45585 --5.01524 3.40887 1.56748 --4.75724 3.27707 1.67134 --4.70228 3.24854 1.79016 --4.69012 3.24087 1.91319 --4.66724 3.22846 2.03457 --4.66867 3.22775 2.16017 --4.39519 3.08937 2.23109 --4.28783 3.03456 2.32866 --4.29317 3.03588 2.44988 --4.28779 3.03245 2.56936 --4.28046 3.02791 2.68897 --4.23725 3.00465 2.79841 --4.20956 2.98956 2.91217 --4.18765 2.97795 3.02831 --4.16481 2.96526 3.1442 --4.12255 2.94303 3.25309 --4.09578 2.92906 3.3679 --4.05837 2.90923 3.47882 --4.01997 2.8893 3.58893 --3.97093 2.86348 3.69434 --3.91318 2.83286 3.79451 --3.86117 2.80673 3.89741 --3.79951 2.77474 3.99472 --3.75341 2.75007 4.09969 --3.69661 2.72047 4.19892 --3.66206 2.7029 4.31155 --3.64986 2.69544 4.43888 --3.69484 2.71658 4.6081 --3.70681 2.72177 4.75883 --5.60921 3.67322 6.29602 --5.80017 3.7672 6.64385 --5.52901 3.62943 6.64327 --5.60656 3.66676 6.91729 --1.75883 1.74261 3.87134 --1.72161 1.72283 3.9426 --1.71729 1.71962 4.04485 --1.71779 1.71905 4.15422 --3.04919 2.38216 5.56841 --1.74485 1.73133 4.40915 --1.75015 1.73289 4.53537 --2.83129 2.26983 5.83394 --1.63299 1.67265 4.65665 --1.44002 1.57497 4.5604 --1.36593 1.53821 4.59697 --7.14986 4.40947 11.9439 --0.797442 1.25352 4.11997 --1.54596 1.6238 5.23387 --1.74435 1.72114 5.66069 --3.15984 2.42054 7.86614 --0.98565 1.34347 4.87527 --0.967689 1.33303 4.98989 --0.936182 1.31595 5.0885 --1.13239 1.41183 5.56923 --0.99848 1.34475 5.5124 --1.24946 1.46727 6.14004 --0.705758 1.19752 5.32719 --0.606679 1.14758 5.31064 --0.514358 1.10136 5.30017 --0.480815 1.08379 5.4114 --0.376058 1.03031 5.37075 --0.335793 1.0088 5.47151 --0.228086 0.955484 5.41751 --0.145496 0.913295 5.41573 --0.083024 0.881984 5.46724 --0.0206202 0.849628 5.5178 --0.427637 1.04411 6.94132 --0.454058 1.05476 7.3465 --0.32023 0.987806 7.27174 -0.46095 0.609667 4.94677 -0.525167 0.57729 4.95867 -0.591293 0.544247 4.95947 -0.649713 0.514049 4.98803 -0.774974 0.453273 4.7241 -0.8124 0.433537 4.83691 -0.89164 0.393041 4.74386 -0.960512 0.359515 4.69781 -1.0671 0.30793 4.39422 -1.08562 0.295983 4.64107 -1.13825 0.268657 4.68004 -1.20037 0.238265 4.64851 -1.10805 0.27248 6.23732 -1.1971 0.228472 6.14606 -1.28313 0.185069 6.04309 -1.35653 0.147215 6.15801 -1.44139 0.10525 6.00171 --1.08648 1.55414 -0.930538 --1.1611 1.5939 -0.907373 --1.2814 1.65911 -0.91213 --1.36469 1.70444 -0.888269 --1.4548 1.7531 -0.86632 --1.58572 1.8243 -0.86438 --1.69234 1.88188 -0.844441 --1.81647 1.9483 -0.829404 --1.96484 2.02883 -0.822378 --2.11316 2.10962 -0.809959 --2.26344 2.19079 -0.792236 --2.43799 2.28519 -0.779979 --2.6465 2.39833 -0.775182 --2.83947 2.50222 -0.755936 --3.04986 2.61622 -0.735948 --3.27772 2.7394 -0.71407 --3.51527 2.86746 -0.686449 --3.75275 2.99596 -0.649939 --4.05043 3.15677 -0.62175 --4.383 3.33683 -0.591529 --4.66503 3.48904 -0.535707 --4.679 3.49619 -0.408591 --4.69203 3.50228 -0.28133 --4.70319 3.50627 -0.15388 --4.69485 3.50118 -0.0237358 --4.70983 3.50832 0.101987 --4.72387 3.51442 0.228054 --4.72622 3.51485 0.355209 --4.7189 3.50971 0.482961 --4.72607 3.51338 0.608993 --4.74105 3.52052 0.734716 --4.74541 3.52104 0.861281 --4.73803 3.51684 0.987785 --4.72978 3.51057 1.11408 --4.66622 3.47477 1.23809 --4.57447 3.42503 1.35826 --4.54297 3.40606 1.47939 --4.52595 3.39602 1.6009 --4.50794 3.38588 1.72191 --4.45313 3.35521 1.83762 --4.37894 3.31411 1.94879 --4.31256 3.27644 2.05875 --4.2442 3.23853 2.16631 --4.18259 3.205 2.2733 --4.16269 3.19345 2.38825 --4.13314 3.17618 2.5007 --4.12682 3.17166 2.61952 --4.1195 3.16709 2.73844 --4.1093 3.16034 2.85753 --4.09711 3.15348 2.97672 --4.07533 3.13987 3.09296 --4.06798 3.13546 3.21527 --4.05104 3.12431 3.33463 --4.03111 3.11297 3.45388 --4.02567 3.10989 3.58044 --4.04354 3.11785 3.71917 --4.01008 3.09851 3.83509 --4.01436 3.09951 3.97145 --9.04014 5.7989 6.85454 --6.77772 4.58104 5.8246 --4.7924 3.51412 4.85122 --4.78687 3.50969 5.01139 --4.12839 3.1551 4.75128 --4.73706 3.48057 5.3141 --2.21126 2.12532 3.71563 --4.69209 3.45332 5.62837 --4.67975 3.44489 5.79719 --6.35238 4.33931 7.29353 --5.9193 4.10572 7.17614 --1.7585 1.87882 3.88777 --1.68655 1.83945 3.92989 --2.0755 2.0462 4.38898 --1.72525 1.85823 4.18058 --1.69003 1.83795 4.2595 --1.57359 1.77568 4.25814 --1.4785 1.72355 4.27346 --1.27522 1.6148 4.16857 --1.25837 1.6043 4.26066 --1.31289 1.63249 4.43893 --2.54954 2.28945 6.04682 --1.55108 1.75806 4.98202 --2.06183 2.02712 5.78062 --0.800513 1.35626 4.26634 --1.82983 1.90209 5.80736 --1.07711 1.50177 4.90176 --1.10832 1.517 5.08989 --1.00944 1.46273 5.08687 --0.860407 1.38319 4.99949 --1.20265 1.56283 5.71716 --1.10077 1.50778 5.72216 --0.588873 1.23589 4.98917 --0.596871 1.23885 5.1605 --0.542253 1.20946 5.22098 --0.464635 1.16645 5.237 --0.475408 1.17095 5.43611 --0.330447 1.09365 5.30801 --0.245145 1.04704 5.30111 --0.205888 1.02552 5.40058 --0.137856 0.988065 5.43603 --0.0813542 0.956617 5.4977 -0.0251164 0.90063 5.42883 --0.416632 1.12722 6.93174 -0.0864049 0.863941 5.7143 -0.429121 0.685291 4.87553 -0.491292 0.652107 4.88888 -0.547676 0.621166 4.9202 -0.607908 0.588455 4.94075 -0.663352 0.557938 4.97946 -0.719786 0.527305 5.01706 -0.873152 0.447022 4.59628 -0.926665 0.418895 4.62016 -0.990505 0.384173 4.58432 -1.04486 0.354395 4.59617 -1.08137 0.334011 4.73525 -1.14425 0.30017 4.69577 -1.20052 0.269122 4.70456 -1.08653 0.316544 6.41194 -1.17834 0.268415 6.32187 -1.27535 0.217466 6.10033 -1.35211 0.175991 6.12609 -1.4316 0.133301 6.11044 -1.50909 0.090152 6.10334 --0.948779 1.59358 -0.918241 --1.02902 1.64035 -0.902184 --1.11702 1.69148 -0.888483 --1.22834 1.75546 -0.886743 --1.32507 1.81121 -0.871498 --1.44505 1.88088 -0.866866 --1.55828 1.94556 -0.853431 --1.68797 2.02003 -0.844653 --1.81756 2.09572 -0.831329 --1.94817 2.17071 -0.813258 --2.11172 2.26521 -0.805897 --2.25874 2.35034 -0.785191 --2.45621 2.46382 -0.780298 --2.62937 2.56366 -0.757905 --2.84421 2.68761 -0.745079 --3.07644 2.82173 -0.730213 --3.2602 2.92714 -0.689287 --3.52724 3.08171 -0.668643 --3.78655 3.23044 -0.635057 --4.07964 3.40028 -0.60124 --4.28942 3.52061 -0.533809 --4.32958 3.54284 -0.41764 --4.35904 3.55955 -0.298581 --4.38761 3.57425 -0.178629 --4.4055 3.58339 -0.0565856 --4.42144 3.59143 0.0658967 --4.43545 3.59836 0.188618 --4.43876 3.59969 0.312632 --4.4489 3.6044 0.435733 --4.44835 3.60349 0.559526 --4.44692 3.60051 0.683214 --4.4425 3.59734 0.806687 --4.43714 3.59309 0.929806 --4.42886 3.58765 1.05266 --4.42837 3.58568 1.1753 --4.40848 3.57347 1.2972 --4.41281 3.5748 1.41992 --4.39779 3.56487 1.54144 --4.35469 3.53905 1.65971 --4.32708 3.52221 1.77856 --4.30721 3.50987 1.89776 --4.30186 3.50554 2.01928 --4.30325 3.50571 2.14234 --4.30277 3.50378 2.26578 --4.37763 3.5464 2.40705 --4.6527 3.7031 2.60247 --4.69563 3.72693 2.74762 --4.71922 3.73944 2.89007 --4.72448 3.74061 3.02862 --4.73546 3.74631 3.1708 --4.74356 3.74989 3.31397 --4.70047 3.72342 3.43938 --4.67954 3.71075 3.57351 --4.65673 3.69596 3.70762 --4.63194 3.68104 3.84152 --4.62169 3.67339 3.98279 --4.5998 3.65983 4.12045 --4.59245 3.65359 4.26638 --4.56668 3.63781 4.40442 --4.56117 3.63394 4.55555 --4.55377 3.62799 4.70758 --4.53672 3.61625 4.8556 --4.51574 3.60328 5.00396 --2.31731 2.34425 3.693 --2.23188 2.29535 3.74128 --4.475 3.57615 5.47745 --2.07565 2.20361 3.84128 --2.01826 2.17018 3.90465 --4.42938 3.54484 5.97364 --4.42475 3.54049 6.15434 --4.41524 3.53389 6.33621 --4.41736 3.53268 6.53173 --1.63409 1.94587 4.11719 --1.75892 2.01615 4.35071 --1.7093 1.98644 4.41886 --1.52181 1.87917 4.34486 --2.16883 2.24562 5.16148 --4.32425 3.46865 7.72051 --2.59907 2.48766 5.95848 --1.42344 1.8187 4.72192 --1.46136 1.83988 4.9005 --1.91327 2.09437 5.61875 --0.78647 1.45445 4.28123 --1.00919 1.58026 4.70633 --1.70042 1.96949 5.82726 --1.28605 1.7341 5.38801 --0.959329 1.54895 5.0459 --0.847164 1.48455 5.01654 --1.16955 1.66423 5.6986 --0.720996 1.41016 5.1062 --0.579138 1.32863 5.01037 --0.532373 1.30117 5.08003 --0.515356 1.2905 5.20908 --0.404252 1.22701 5.15646 --0.501426 1.2795 5.53021 --0.331819 1.18316 5.35148 --0.250489 1.13628 5.35484 --0.215206 1.11451 5.46447 --0.0860114 1.04069 5.34683 --0.79937 1.43552 7.40331 --0.614318 1.33059 7.21167 -0.343369 0.79837 4.78594 -0.402449 0.763515 4.80231 -0.463513 0.728471 4.81727 -0.512133 0.700012 4.86894 -0.564542 0.668801 4.91021 -0.616081 0.63907 4.96003 -0.670412 0.606648 4.99944 -0.72865 0.573455 5.02804 -0.840017 0.510915 4.81277 -0.943616 0.4527 4.59434 -0.984612 0.42822 4.67652 -1.02384 0.405269 4.78737 -1.10831 0.357858 4.62193 -1.16254 0.326008 4.63228 -1.20461 0.300749 4.74052 -1.09412 0.351041 6.30776 -1.19118 0.29668 6.13885 -1.27136 0.250148 6.10727 -1.347 0.206775 6.13383 -1.42538 0.162181 6.11888 -1.50005 0.117196 6.17247 --0.745615 1.59086 -0.927818 --0.809254 1.62995 -0.904806 --0.902898 1.68795 -0.90121 --0.975283 1.73155 -0.878751 --0.995287 1.74376 -0.818719 --1.08987 1.80219 -0.807327 --1.28905 1.92502 -0.858748 --1.40684 1.99765 -0.852277 --1.54109 2.08009 -0.850262 --1.65403 2.14907 -0.830632 --1.78142 2.22775 -0.81507 --1.94947 2.3312 -0.814623 --2.09427 2.42009 -0.796421 --2.24773 2.51461 -0.776425 --2.43411 2.62877 -0.764544 --2.63684 2.75396 -0.752275 --2.84928 2.88399 -0.735261 --3.07806 3.02515 -0.716061 --3.29137 3.15606 -0.682263 --3.51337 3.29178 -0.643025 --3.8339 3.48959 -0.624684 --4.11476 3.66213 -0.582185 --4.18003 3.70056 -0.473422 --4.23558 3.73358 -0.360666 --4.26403 3.75027 -0.240713 --4.29055 3.76588 -0.120021 --4.29104 3.76412 0.00572465 --4.29723 3.76763 0.129654 --4.30155 3.76903 0.253673 --4.29524 3.7638 0.378434 --4.28794 3.75849 0.50269 --4.29521 3.761 0.625376 --4.28304 3.75335 0.748808 --4.27869 3.74914 0.871532 --4.2724 3.7438 0.993895 --4.28054 3.74835 1.11619 --4.28781 3.75085 1.23877 --4.26698 3.73756 1.36021 --4.22787 3.71203 1.4796 --4.18683 3.6853 1.59744 --4.16022 3.6685 1.7157 --4.21764 3.70244 1.84484 --4.29818 3.75115 1.98046 --4.40961 3.81824 2.12572 --4.43515 3.83241 2.25889 --4.45008 3.83989 2.39161 --4.45434 3.84165 2.52312 --4.46438 3.84692 2.6575 --4.46481 3.84551 2.79034 --4.47097 3.84861 2.9262 --4.46653 3.84495 3.06011 --4.46887 3.84487 3.1973 --4.46061 3.83802 3.33214 --4.45807 3.8357 3.47041 --4.47002 3.84164 3.61609 --4.47037 3.84074 3.75941 --4.46879 3.83876 3.90348 --4.48945 3.84877 4.05994 --4.49846 3.85294 4.214 --4.52766 3.87005 4.38189 --4.53855 3.8757 4.5432 --4.56297 3.8887 4.71497 --6.19995 4.88515 5.88491 --5.99967 4.76161 5.9636 --2.35255 2.53674 3.72908 --2.22399 2.45779 3.74986 --6.3302 4.9571 6.83318 --2.11236 2.38761 3.8864 --4.44919 3.80845 5.82428 --4.44073 3.80162 6.00027 --4.40147 3.77578 6.15391 --4.4064 3.77774 6.3492 --1.95405 2.28643 4.32456 --1.9122 2.25979 4.40463 --1.7164 2.14029 4.33697 --1.75827 2.16381 4.49744 --1.45097 1.97703 4.30095 --2.13123 2.3873 5.15172 --2.03828 2.33064 5.19442 --1.28896 1.87554 4.47446 --8.33338 6.1323 13.0428 --2.02964 2.32124 5.64247 --0.844556 1.60343 4.28188 --0.992922 1.69217 4.59608 --1.81436 2.18643 5.85595 --1.61775 2.06691 5.74844 --1.53641 2.01638 5.79944 --0.749763 1.54147 4.76607 --0.729061 1.5274 4.87163 --0.671845 1.49225 4.92026 --0.662624 1.48511 5.0504 --0.667743 1.48655 5.21467 --0.518522 1.39568 5.10132 --0.458467 1.35814 5.14564 --0.366807 1.30158 5.12817 --0.318246 1.27089 5.19548 --0.271496 1.24272 5.27088 --0.251605 1.22925 5.40776 --0.088292 1.12951 5.21343 -0.124725 1.00171 4.878 -0.266858 0.915609 4.69038 -0.3249 0.87995 4.70949 -0.38007 0.845863 4.73657 -0.435232 0.811716 4.76244 -0.491384 0.77746 4.78731 -0.541806 0.74643 4.82978 -0.573085 0.724828 4.93793 -0.611213 0.701319 5.03621 -0.62936 0.6883 5.22053 -0.840274 0.564245 4.61421 -0.865956 0.546692 4.75674 -0.931515 0.507006 4.72403 -1.00362 0.462906 4.65074 -1.02662 0.446853 4.84048 -1.11562 0.393744 4.64654 -0.921072 0.497192 6.39446 -1.22388 0.327043 4.66719 -1.28271 0.291862 4.63621 -1.18954 0.335179 6.14459 -1.26212 0.289083 6.19344 -1.33767 0.243244 6.23084 -1.40776 0.198602 6.36664 -1.44263 0.16592 7.55023 -1.5474 0.104296 7.2038 --0.624064 1.6289 -0.922934 --0.70111 1.67921 -0.912483 --0.784922 1.7338 -0.904792 --0.820391 1.75635 -0.857361 --0.854855 1.77888 -0.809135 --0.968623 1.85269 -0.814467 --1.07552 1.92352 -0.810896 --1.24238 2.03243 -0.840562 --1.3889 2.12807 -0.850313 --1.52189 2.21456 -0.845904 --1.64707 2.29702 -0.832247 --1.78869 2.38934 -0.821948 --1.93127 2.48198 -0.806352 --2.09794 2.59083 -0.796468 --2.24143 2.68409 -0.76948 --2.42442 2.80423 -0.754115 --2.64024 2.94514 -0.744317 --2.8724 3.09718 -0.732233 --3.07368 3.22832 -0.699442 --3.30776 3.38036 -0.669521 --3.5263 3.52313 -0.625451 --3.91561 3.7775 -0.622461 --4.11865 3.90955 -0.553156 --4.18277 3.95007 -0.441201 --4.18706 3.95163 -0.313986 --4.18172 3.94665 -0.185425 --4.17446 3.94051 -0.0575236 --4.18164 3.94411 0.0669103 --4.18689 3.94659 0.191384 --4.18252 3.94251 0.316704 --4.20028 3.95366 0.439048 --4.20847 3.95728 0.562688 --4.20698 3.95532 0.686825 --4.2113 3.9567 0.810544 --4.21468 3.95702 0.934208 --4.21507 3.95716 1.05796 --4.2059 3.94969 1.1814 --4.17844 3.93003 1.3038 --4.10661 3.8824 1.42212 --3.99243 3.80682 1.53387 --3.90911 3.75111 1.64458 --3.87491 3.72761 1.75851 --3.83879 3.70293 1.87117 --3.92591 3.75892 2.00407 --4.51471 4.14116 2.23905 --4.53827 4.15447 2.37765 --4.55115 4.16208 2.51555 --4.52078 4.14053 2.64383 --4.5048 4.12906 2.77583 --4.51093 4.13232 2.91499 --4.50752 4.12789 3.05235 --4.53387 4.14389 3.20125 --10.4507 7.98828 5.53541 --10.1214 7.77217 5.6847 --9.90292 7.62662 5.86775 --9.85463 7.59305 6.11923 --10.1161 7.75987 6.51519 --5.34577 4.66222 4.47278 --5.61048 4.83192 4.78112 --6.51931 5.41954 5.45068 --6.4992 5.40499 5.64697 --5.55815 4.7935 5.30394 --6.59265 5.46057 6.12798 --5.84498 4.97427 5.86913 --2.24994 2.64722 3.67478 --5.6347 4.83534 6.13532 --6.09795 5.1319 6.67659 --2.57711 2.85523 4.25487 --2.17896 2.5963 4.06951 --5.52269 4.75401 6.89707 --2.1357 2.56652 4.26998 --2.00754 2.48197 4.27863 --2.15967 2.57921 4.53717 --1.67342 2.26472 4.20847 --1.672 2.26228 4.32282 --1.57838 2.20168 4.34739 --1.40327 2.08763 4.28352 --1.36155 2.05954 4.35456 --2.02387 2.48415 5.2128 --1.04598 1.85471 4.22907 --0.969798 1.80403 4.25048 --0.92808 1.77652 4.31298 --0.948675 1.78885 4.45552 --1.72831 2.28661 5.61456 --1.6663 2.24563 5.69288 --0.93561 1.77687 4.81655 --0.901574 1.75299 4.90226 --0.653923 1.59378 4.66332 --0.509796 1.50009 4.56767 --0.398172 1.42859 4.51583 --0.313412 1.37361 4.50164 --0.253631 1.33312 4.52659 --0.184194 1.28813 4.53316 --0.114771 1.24305 4.53803 --0.0501644 1.20061 4.54962 -0.0134916 1.15914 4.55956 -0.0694705 1.12194 4.58558 -0.125438 1.08467 4.6102 -0.185258 1.04567 4.62466 -0.246066 1.00654 4.63782 -0.302003 0.969081 4.65854 -0.35513 0.934191 4.68717 -0.412047 0.89656 4.70559 -0.466153 0.861497 4.73191 -0.520189 0.825378 4.75709 -0.575276 0.790146 4.78122 -0.534329 0.8132 5.13555 -0.296087 0.957313 6.25463 -0.375237 0.906316 6.27333 --0.0714982 1.17591 8.47534 -0.876837 0.592228 4.77805 -0.933724 0.55503 4.78493 -1.01327 0.504584 4.67365 -1.04369 0.482662 4.81476 -1.1363 0.424391 4.60202 -1.18371 0.393459 4.64282 -1.23114 0.361971 4.69265 -1.28425 0.327617 4.71184 -1.17323 0.383434 6.30895 -1.2624 0.326996 6.18967 -1.33117 0.281061 6.27759 -1.4137 0.227829 6.19465 -1.45797 0.191379 6.88895 -1.53458 0.139114 7.22282 --0.439194 1.62213 -0.935472 --0.500632 1.66486 -0.917263 --0.583299 1.72218 -0.91392 --0.658217 1.77443 -0.902179 --0.679182 1.78755 -0.845187 --0.720322 1.81617 -0.803516 --0.802975 1.87295 -0.790735 --0.893326 1.93512 -0.77996 --1.0482 2.04336 -0.808487 --1.06039 2.05153 -0.739407 --1.34245 2.24845 -0.833863 --1.46547 2.33365 -0.823061 --1.62608 2.44441 -0.828037 --1.74324 2.52594 -0.803184 --1.92113 2.64898 -0.804121 --2.06905 2.75222 -0.783596 --2.25654 2.88135 -0.774544 --2.42178 2.99595 -0.748233 --2.64091 3.14815 -0.737261 --2.88603 3.31796 -0.726449 --3.11573 3.47658 -0.70009 --3.35399 3.64206 -0.667192 --3.65573 3.852 -0.644288 --3.95942 4.06166 -0.60904 --4.04646 4.12127 -0.504249 --4.06809 4.13472 -0.380686 --4.08777 4.14707 -0.256684 --4.11414 4.16478 -0.133994 --4.13864 4.18041 -0.0105154 --4.16988 4.20043 0.1124 --4.1905 4.21388 0.237257 --4.20923 4.22525 0.362801 --4.23565 4.24209 0.488138 --4.24281 4.24583 0.615468 --4.24804 4.24845 0.742838 --4.26001 4.25549 0.870144 --4.24606 4.24393 0.997959 --4.22918 4.23116 1.12511 --4.21905 4.22279 1.2518 --4.19931 4.20778 1.37763 --4.21895 4.22034 1.50593 --3.884 3.98708 1.59925 --3.73653 3.88294 1.70173 --3.62074 3.80172 1.80282 --3.57603 3.7703 1.91125 --3.53139 3.73779 2.01812 --3.4925 3.70965 2.12503 --3.47568 3.69709 2.23615 --3.40994 3.64986 2.33457 --3.25485 3.54174 2.40634 --3.13052 3.45469 2.48133 --3.06186 3.40677 2.56935 --2.96065 3.33515 2.64406 --2.87378 3.27452 2.72064 --2.79466 3.21836 2.79707 --2.70691 3.15637 2.86741 --2.65652 3.12138 2.95153 --2.60621 3.08532 3.034 --6.45429 5.73465 5.00706 --6.27496 5.60997 5.1183 --6.4123 5.70208 5.3926 --8.96669 7.45828 7.03168 --5.5714 5.119 5.3184 --5.56099 5.11055 5.50436 --5.56211 5.10931 5.70047 --5.19795 4.85647 5.65726 --1.83321 2.54387 3.51428 --1.76186 2.49389 3.56423 --1.69052 2.4438 3.61188 --1.62491 2.39822 3.66266 --1.55268 2.34686 3.70597 --1.4938 2.30577 3.75829 --1.42824 2.25991 3.80318 --1.37515 2.22231 3.85807 --1.30198 2.17048 3.89308 --1.24692 2.1326 3.94467 --1.17948 2.08524 3.98211 --1.12444 2.0472 4.0305 --1.06948 2.0081 4.07744 --1.00108 1.96042 4.10948 --0.945141 1.9211 4.15333 --0.876774 1.87323 4.18157 --0.814173 1.82899 4.21519 --0.756277 1.78931 4.25423 --0.693701 1.7449 4.28445 --0.635889 1.70408 4.32055 --0.578028 1.66419 4.35519 --0.514493 1.61948 4.38051 --0.445165 1.57195 4.39642 --0.387401 1.53082 4.42632 --0.3191 1.48317 4.43854 --0.255558 1.43913 4.45712 --0.192028 1.39501 4.4741 --0.128512 1.3508 4.48939 --0.0707487 1.3103 4.51155 --0.0120595 1.26866 4.53226 -0.0466789 1.22795 4.55152 -0.105406 1.18717 4.56938 -0.164123 1.14633 4.58584 -0.219026 1.10809 4.60971 -0.274918 1.06972 4.63238 -0.329741 1.03036 4.65381 -0.381814 0.994566 4.68309 -0.434815 0.957653 4.71122 -0.487807 0.920686 4.73825 -0.54359 0.881028 4.75488 -0.594703 0.845527 4.78896 -0.61547 0.829996 4.92582 -0.305691 1.03115 6.27867 -0.376093 0.982157 6.32717 -0.477652 0.911984 6.24942 -0.922962 0.61941 4.6542 -0.968298 0.586845 4.7 -1.00243 0.562301 4.81297 -1.0723 0.51434 4.73998 -1.12524 0.477707 4.75348 -1.20161 0.426261 4.61814 -1.24798 0.393856 4.66842 -1.30735 0.352703 4.61881 -1.16566 0.43269 6.40301 -1.26103 0.36847 6.21528 -1.34247 0.312906 6.14467 -1.41737 0.261128 6.1222 -1.46821 0.220951 6.56732 -1.52377 0.175801 7.2213 -1.6091 0.115042 7.39453 --0.398746 1.71032 -0.928208 --0.465785 1.76018 -0.914709 --0.539594 1.8143 -0.904271 --0.553778 1.82323 -0.842621 --0.599656 1.85684 -0.807265 --0.687865 1.92165 -0.801143 --0.769326 1.98145 -0.786817 --0.787269 1.99457 -0.726245 --0.968776 2.12762 -0.7724 --1.13666 2.25263 -0.802249 --1.30749 2.37817 -0.825191 --1.45712 2.48833 -0.828822 --1.62306 2.61041 -0.834512 --1.76787 2.71608 -0.82194 --1.90586 2.81778 -0.800116 --2.08136 2.94622 -0.790324 --2.24333 3.06549 -0.766872 --2.42066 3.19573 -0.743336 --2.65175 3.36563 -0.73394 --2.89248 3.54145 -0.717851 --3.16375 3.74215 -0.702743 --3.36692 3.89027 -0.653449 --3.7342 4.16059 -0.64571 --4.00162 4.35585 -0.59392 --4.18158 4.48729 -0.508747 --5.06419 5.13782 -0.581603 --6.37194 6.10035 -0.705883 --7.51722 6.94309 -0.742056 --9.46463 8.37673 -0.863208 --11.761 10.0658 -0.950504 --13.1022 11.0511 -0.819619 --17.8389 14.5351 -0.977849 --17.9139 14.5856 -0.556216 --18.1769 14.7744 -0.1432 --18.5147 15.0183 0.277514 --18.2904 14.8492 0.720992 --27.0438 21.2801 1.21221 --27.0643 21.2883 1.83724 --4.31316 4.56436 1.32998 --4.187 4.47058 1.45334 --4.12511 4.42384 1.5773 --4.10062 4.40453 1.70331 --4.09148 4.39625 1.8305 --3.71142 4.1159 1.89915 --3.50007 3.95979 1.98184 --3.37504 3.8665 2.07345 --3.28066 3.79623 2.16697 --3.19304 3.73029 2.25873 --3.09679 3.65854 2.3449 --2.9919 3.58094 2.42498 --2.90143 3.51329 2.50578 --2.81766 3.45101 2.58578 --2.7339 3.38857 2.66258 --2.65684 3.33154 2.73916 --2.5712 3.26768 2.80971 --2.47693 3.19796 2.87386 --0.739033 1.92722 2.18167 --2.30385 3.06832 2.99872 --2.23069 3.01397 3.06399 --2.14218 2.94916 3.11874 --2.06906 2.89454 3.17852 --2.00938 2.84906 3.24426 --1.94201 2.79879 3.30367 --1.86595 2.74363 3.35614 --1.79097 2.68742 3.40617 --1.72936 2.6414 3.46341 --1.67348 2.59989 3.52368 --1.61096 2.55263 3.57718 --1.56751 2.52025 3.64461 --1.51737 2.48312 3.70551 --1.4596 2.44018 3.75933 --1.4009 2.39609 3.81159 --1.35556 2.36234 3.87387 --1.29589 2.31803 3.92293 --1.24199 2.27731 3.97647 --1.13842 2.20091 3.97781 --1.12748 2.19191 4.07268 --1.07262 2.15091 4.12172 --1.02253 2.11346 4.17603 --0.942804 2.05541 4.19477 --0.868851 2.00094 4.21799 --0.807355 1.95485 4.25331 --0.733435 1.90017 4.27243 --0.67097 1.85383 4.30406 --0.608458 1.80841 4.33393 --0.546021 1.7619 4.36205 --0.489343 1.71905 4.39625 --0.425872 1.67331 4.42113 --0.363473 1.62656 4.44436 --0.305833 1.58343 4.47396 --0.242401 1.53745 4.49394 --0.175237 1.48775 4.50396 --0.117634 1.44438 4.52886 --0.050436 1.39551 4.53544 -0.00720274 1.35299 4.5572 -0.0610259 1.31305 4.58607 -0.115778 1.272 4.61379 -0.177186 1.22661 4.62264 -0.228175 1.18909 4.65642 -0.264888 1.16118 4.72489 -0.334864 1.11016 4.71172 -0.355437 1.09342 4.82392 -0.441516 1.03099 4.76223 -0.501056 0.987755 4.7719 -0.559586 0.944503 4.78007 -0.618104 0.901183 4.78684 -0.673753 0.859438 4.80167 -0.705835 0.835315 4.90042 -0.393219 1.05013 6.3231 --0.0744668 1.36912 8.54508 -0.935155 0.66933 4.68459 -1.00581 0.617477 4.61499 -1.02851 0.599565 4.76688 -1.10668 0.543695 4.64566 -1.12378 0.527975 4.85515 -1.01205 0.598553 5.91978 -1.09885 0.535562 5.80705 -1.12424 0.513761 6.14674 -1.19901 0.45875 6.13984 -1.2627 0.411257 6.23058 -1.34297 0.352797 6.16083 -1.41677 0.298608 6.1491 -1.47174 0.255293 6.45507 -1.54144 0.202605 6.61019 -1.59644 0.153368 7.40356 --0.423145 1.85133 -0.905705 --0.456458 1.87661 -0.861229 --0.482101 1.89572 -0.810502 --0.574869 1.9685 -0.811042 --0.640775 2.01977 -0.78801 --0.699999 2.06497 -0.757624 --0.710221 2.07285 -0.692149 --0.761763 2.11195 -0.654115 --1.03961 2.32933 -0.755617 --1.23494 2.48165 -0.7941 --1.4388 2.6417 -0.82869 --1.60148 2.76776 -0.831096 --1.74397 2.87845 -0.815486 --1.89406 2.99572 -0.797835 --2.05952 3.12391 -0.780901 --2.24023 3.26507 -0.763782 --2.39123 3.38235 -0.726701 --2.57388 3.52333 -0.695341 --2.89248 3.77171 -0.706532 --3.16694 3.98579 -0.688452 --3.42703 4.18777 -0.653871 --3.78664 4.46807 -0.637871 --4.14914 4.74931 -0.606376 --4.59576 5.09753 -0.580812 --5.71164 5.96808 -0.687868 --6.83983 6.84673 -0.747666 --8.43974 8.09414 -0.843286 --10.6941 9.85185 -0.97243 --12.9472 11.6064 -1.00111 --16.9917 14.7546 -0.717163 --17.1096 14.8422 -0.307428 --17.2458 14.9432 0.105803 --17.1877 14.8925 0.529456 --25.8161 21.6095 0.914824 --25.8328 21.6148 1.52635 --25.8169 21.596 2.13741 --25.8326 21.6012 2.75013 --25.8551 21.611 3.36518 --4.11989 4.70146 1.66004 --3.97787 4.58919 1.77377 --3.5041 4.21939 1.83165 --3.38412 4.12474 1.92997 --3.39417 4.13127 2.04928 --3.39559 4.1312 2.16754 --3.91499 4.53377 2.41178 --3.95851 4.56455 2.55459 --3.99041 4.5886 2.69724 --4.20581 4.75405 2.89917 --4.67623 5.11726 3.19792 --0.706435 2.03912 1.92911 --0.70141 2.03468 1.98736 --0.710702 2.04145 2.05188 --0.711393 2.04156 2.11386 --0.711146 2.04061 2.17608 --0.687991 2.02173 2.22809 --4.93913 5.30718 4.44211 --4.97949 5.33633 4.63704 --2.06936 3.08677 3.1912 --1.99642 3.02918 3.25133 --1.9225 2.97139 3.30875 --1.8353 2.9022 3.35472 --1.77478 2.85444 3.41606 --1.74192 2.82827 3.49468 --1.79017 2.86409 3.63228 --2.03298 3.04956 3.92124 --2.01344 3.03328 4.02131 --1.97862 3.00551 4.11051 --1.94286 2.97665 4.19905 --1.16353 2.37606 3.63609 --4.44492 4.89682 6.72056 --4.2335 4.73113 6.73154 --1.82367 2.87915 4.58297 --2.11474 3.10033 5.00714 --1.73691 2.80915 4.75354 --1.75734 2.82313 4.9094 --1.70913 2.78529 4.99388 --1.66668 2.75109 5.08424 --1.73656 2.80274 5.31244 --1.85777 2.89429 5.61517 --1.63347 2.72092 5.48716 --1.59954 2.69331 5.59858 --1.4781 2.59834 5.59127 --1.41468 2.5479 5.66274 --1.40264 2.53639 5.80929 --0.727823 2.02127 4.94118 --0.831815 2.09892 5.24776 --0.777948 2.05678 5.31299 --0.662397 1.96653 5.27226 --0.503118 1.84432 5.14594 --0.423714 1.78178 5.1547 --0.340462 1.71748 5.15279 --0.262971 1.65683 5.15686 --0.255671 1.64966 5.30424 --0.151568 1.56965 5.25378 --0.0466233 1.48799 5.19128 -0.0668282 1.40033 5.09898 --0.1617 1.57076 5.83022 -0.180044 1.31189 5.17272 --0.121164 1.53541 6.15774 --0.0502445 1.47901 6.1991 --0.423671 1.75538 7.53493 -0.0746927 1.38078 6.3325 -0.136193 1.3316 6.40682 -0.693299 0.916813 4.80931 -0.753542 0.869811 4.80464 -0.805258 0.828681 4.82707 --0.0599957 1.46059 8.52615 -0.954846 0.713867 4.67624 -0.999071 0.679413 4.72304 -1.06388 0.628841 4.67215 -1.07154 0.620192 4.91161 -1.14767 0.562905 4.79978 -0.958499 0.692088 6.30459 -1.09646 0.589432 5.87912 -1.12917 0.561778 6.15015 -1.20461 0.502779 6.12432 -1.26619 0.453437 6.21567 -1.35078 0.389301 6.07718 -1.40891 0.342972 6.2453 -1.46443 0.296181 6.50208 -1.53909 0.237304 6.5182 -1.58464 0.192642 7.37208 -1.67025 0.124877 7.48527 --0.466488 2.00488 -0.815285 --0.538009 2.06319 -0.798562 --0.589399 2.1051 -0.764371 --0.646499 2.15222 -0.733195 --0.711242 2.2057 -0.704574 --0.693757 2.18979 -0.619726 --0.673351 2.17264 -0.536342 --0.674043 2.17212 -0.466725 --0.666149 2.16423 -0.39371 --0.670631 2.1677 -0.329165 --0.638857 2.13979 -0.246444 --0.641415 2.14208 -0.183258 --0.643097 2.14229 -0.120278 --0.687791 2.17824 -0.0769357 --0.679637 2.1701 0.0521585 --0.641172 2.13744 0.128052 --0.645701 2.14062 0.186704 --0.649294 2.14274 0.245201 --0.652886 2.14485 0.303697 --0.692794 2.17673 0.351907 --0.724055 2.20225 0.403565 --6.20811 6.7403 -0.748918 --7.62634 7.91064 -0.842384 --9.27822 9.27382 -0.912042 --11.7689 11.33 -1.03396 --13.9595 13.1359 -1.00407 --16.1153 14.9127 -0.871704 --16.2101 14.9854 -0.470932 --16.407 15.1434 -0.073242 --16.5141 15.2264 0.336138 --16.9705 15.5982 0.744495 --27.1185 23.9615 1.24681 --27.1073 23.9451 1.90123 --16.6936 15.3541 2.00585 --16.5956 15.2683 2.41819 --24.635 21.8853 3.62595 --3.10553 4.14905 1.84929 --3.09459 4.13887 1.96064 --3.09698 4.13967 2.07496 --0.711587 2.17687 1.62632 --0.702698 2.17015 1.68355 --0.724412 2.18675 1.74919 --0.729911 2.19017 1.81134 --0.719205 2.18034 1.86891 --0.715103 2.17705 1.92891 --0.710123 2.1717 1.98901 --0.711744 2.17292 2.05204 --0.705825 2.16653 2.11238 --0.705567 2.16565 2.176 --4.83927 5.55095 4.22059 --4.85384 5.56071 4.39965 --4.85886 5.56276 4.57641 --4.86771 5.5673 4.75828 --4.31678 5.11472 4.61607 --4.46359 5.23366 4.87381 --4.87031 5.56262 5.30791 --4.26244 5.06376 5.09083 --1.8953 3.13054 3.61841 --1.96251 3.18252 3.77549 --1.45689 2.76953 3.50684 --1.92636 3.15114 3.97559 --1.46087 2.76992 3.7121 --1.21799 2.57063 3.60984 --1.11199 2.48428 3.61585 --1.86839 3.09769 4.40458 --1.85363 3.08431 4.51686 --1.75139 3.00027 4.54452 --1.74046 2.98937 4.66171 --1.69147 2.94823 4.74134 --1.59974 2.87212 4.77459 --1.64859 2.91051 4.96323 --1.56634 2.84251 5.00707 --1.89153 3.10336 5.54249 --1.75321 2.98994 5.52745 --1.6871 2.93438 5.60005 --1.53365 2.80855 5.55536 --1.4467 2.73597 5.59328 --1.36446 2.66793 5.63612 --0.917078 2.30489 5.13059 --1.26926 2.58717 5.82266 --2.14844 3.29254 7.40604 --0.776891 2.18628 5.35698 --0.588626 2.03322 5.19 --0.523607 1.97898 5.2272 --0.515409 1.9705 5.36962 --0.314032 1.80686 5.14679 --0.287821 1.78446 5.25292 --0.215313 1.72354 5.26555 --0.145507 1.66711 5.28469 --0.0616811 1.59699 5.26735 -0.115823 1.45404 5.02807 -0.143858 1.42919 5.12759 -0.171024 1.40584 5.23596 -0.238817 1.35005 5.24517 --0.0123937 1.54672 6.1341 -0.0337959 1.50698 6.23841 -0.116837 1.43887 6.2405 -0.148901 1.40967 6.39858 -0.224396 1.34727 6.42568 -0.76373 0.92228 4.80308 -0.817249 0.878589 4.81652 -0.87256 0.832253 4.81926 -0.905385 0.803994 4.91641 -1.00952 0.721023 4.7051 -0.782072 0.892102 6.05746 -0.859263 0.828959 6.03112 -0.919588 0.778113 6.09061 -0.978982 0.72775 6.1587 -1.09426 0.636342 5.87172 -1.10455 0.623417 6.2911 -1.20293 0.544744 6.07852 -1.26799 0.490762 6.12101 -1.34219 0.429713 6.07256 -1.39818 0.382047 6.23135 -1.44714 0.337646 6.54854 -1.52418 0.2742 6.49568 -1.56204 0.233022 7.36998 -1.63854 0.165749 7.66404 --0.48144 2.15196 -0.780139 --0.583247 2.24117 -0.784019 --0.680295 2.32553 -0.778887 --0.777312 2.41007 -0.76986 --0.895271 2.51348 -0.770104 --1.03422 2.63482 -0.778173 --1.22949 2.80437 -0.812897 --1.40554 2.95872 -0.827501 --1.58353 3.11357 -0.834305 --1.7415 3.25007 -0.822744 --1.88606 3.37541 -0.797424 --2.05916 3.52619 -0.779235 --2.23985 3.68367 -0.756611 --2.40719 3.82898 -0.720278 --2.48015 3.89151 -0.640572 --2.76368 4.13867 -0.633757 --3.28922 4.59669 -0.694865 --3.58314 4.85192 -0.659429 --3.89223 5.12054 -0.615119 --4.71948 5.84173 -0.692282 --5.61603 6.62437 -0.747388 --6.93349 7.77211 -0.85035 --8.20303 8.87831 -0.882865 --10.1865 10.6074 -0.975293 --10.9776 11.2936 -0.805116 --11.1363 11.4285 -0.523736 --11.1266 11.4159 -0.21972 --15.5839 15.298 -0.242309 --15.6299 15.3327 0.160145 --0.647755 2.27545 0.961263 --0.648478 2.27536 1.01924 --0.633023 2.26124 1.07689 --0.625193 2.25357 1.13407 --0.630665 2.25777 1.19198 --0.628519 2.25548 1.24945 --0.633051 2.25864 1.3077 --0.629967 2.25529 1.36521 --0.625008 2.24982 1.42271 --0.627601 2.25187 1.4813 --0.629316 2.25189 1.54019 --0.622422 2.24529 1.59753 --0.629806 2.25076 1.65849 --0.650462 2.2683 1.72398 --0.671109 2.28589 1.79066 --0.683267 2.29489 1.85609 --0.686819 2.29726 1.91978 --0.631441 2.24886 1.96187 --0.69864 2.30649 2.05109 --0.692709 2.30017 2.11293 --0.684842 2.29273 2.17481 --3.7791 4.96747 3.71765 --9.35618 9.78714 6.67416 --8.99416 9.47058 6.77937 --6.00396 6.8837 5.40504 --5.65463 6.58027 5.41569 --1.77782 3.23062 3.25113 --1.69484 3.15779 3.29961 --1.67166 3.13658 3.38557 --1.75379 3.20667 3.54598 --1.39565 2.89656 3.39218 --1.23303 2.7551 3.36721 --1.41667 2.91251 3.60723 --1.5444 3.01975 3.81413 --1.10574 2.64214 3.55018 --1.07879 2.61807 3.62353 --1.14481 2.67306 3.78215 --3.67854 4.84768 6.29912 --3.90057 5.03511 6.71359 --1.54831 3.01453 4.51308 --4.29316 5.36621 7.55197 --3.9558 5.07533 7.41672 --4.44664 5.49205 8.20351 --1.4998 2.96676 4.98422 --5.1965 6.12806 9.63808 --4.11306 5.1973 8.5724 --1.4811 2.94479 5.39336 --1.43877 2.90795 5.49075 --1.32373 2.80645 5.48542 --1.27481 2.76367 5.57244 --1.24013 2.73187 5.68126 --1.26221 2.74815 5.88149 --1.16412 2.66279 5.89782 --3.92022 5.00215 10.6771 --0.515294 2.10719 5.13252 --0.474999 2.0715 5.21035 --0.397871 2.00424 5.22216 --0.41146 2.01315 5.40546 --0.307889 1.92361 5.36449 --0.254327 1.87707 5.42172 --0.358412 1.9623 5.82015 --0.0728203 1.71903 5.36838 -0.133405 1.54295 5.06241 -0.157644 1.52081 5.17154 -0.28173 1.41411 5.03173 -0.260786 1.42992 5.2644 -0.0234276 1.62685 6.11466 -0.0364944 1.61171 6.31074 -0.226492 1.4506 5.98345 -0.315841 1.37411 5.94555 -0.219106 1.4506 6.52067 -0.310337 1.37141 6.4912 -0.842279 0.928717 4.80605 -0.894735 0.884055 4.81884 -0.94892 0.835746 4.82089 -0.600117 1.11744 6.61773 -0.712763 1.02165 6.46165 -0.875676 0.885647 6.0211 -0.937667 0.830758 6.06175 -0.994147 0.781081 6.14014 -1.06455 0.719598 6.139 -1.13586 0.657481 6.12617 -1.19882 0.601735 6.17097 -1.27472 0.536219 6.11542 -1.33312 0.484053 6.20663 -1.38986 0.432884 6.35638 -1.44946 0.379481 6.50501 -1.52357 0.314727 6.48288 -1.58708 0.257422 6.65871 -1.62542 0.210576 7.70249 -1.71937 0.132524 7.3959 --0.448139 2.27203 -0.785998 --0.478345 2.29846 -0.734794 --0.616959 2.42687 -0.761636 --0.731762 2.53297 -0.76444 --0.788602 2.58358 -0.723325 --1.03747 2.81443 -0.800987 --1.18835 2.95363 -0.807235 --1.35349 3.10568 -0.814404 --1.54146 3.27798 -0.82539 --1.716 3.4392 -0.82102 --1.87824 3.58735 -0.802088 --2.04036 3.73685 -0.776114 --2.21772 3.89937 -0.748957 --2.26199 3.93857 -0.659621 --2.31854 3.99036 -0.574211 --2.3324 4.00131 -0.471412 --2.33668 4.00478 -0.366219 --2.34109 4.00624 -0.261226 --2.33593 4.00018 -0.154538 --2.34404 4.00675 -0.0521698 --2.34271 4.00381 0.0518926 --2.34795 4.00818 0.153945 --2.34475 4.00309 0.257398 --2.34818 4.00433 0.359189 --2.35631 4.01082 0.45986 --2.36351 4.01625 0.560674 --2.36213 4.01418 0.66219 --2.36751 4.01651 0.763143 --2.37089 4.01871 0.864087 --2.37233 4.01979 0.965069 --2.38052 4.0253 1.06619 --2.3877 4.03077 1.1677 --2.40063 4.04063 1.26985 --2.38976 4.02994 1.37091 --2.38558 4.02467 1.47216 --2.41647 4.05185 1.5781 --2.40186 4.03691 1.67894 --2.54748 4.16944 1.80735 --0.670651 2.44592 1.53929 --0.67895 2.4526 1.60311 --0.672091 2.44516 1.6638 --0.67851 2.44975 1.7282 --0.676322 2.44771 1.79096 --0.673195 2.44463 1.85387 --0.670129 2.44054 1.91682 --0.672727 2.44195 1.98255 --0.675323 2.44338 2.04858 --0.668381 2.43708 2.11202 --0.654901 2.4232 2.17227 --3.51596 5.03715 3.60262 --3.53155 5.04863 3.75437 --3.55179 5.06565 3.91118 --3.59004 5.09846 4.08119 --3.62546 5.12821 4.25372 --3.77917 5.26622 4.50317 --6.77246 7.99277 6.58664 --6.96648 8.16583 6.96795 --1.60446 3.27936 3.47425 --1.32583 3.02493 3.37571 --4.82132 6.20449 6.13455 --1.8009 3.45427 3.9507 --1.92157 3.56158 4.16745 --1.36878 3.05747 3.8177 --1.28323 2.97868 3.85003 --1.16744 2.87243 3.85104 --1.30699 2.99705 4.09052 --1.12972 2.83584 4.02885 --0.979993 2.6982 3.98417 --4.20104 5.61454 7.53414 --4.10559 5.52593 7.6638 --3.88559 5.3223 7.64844 --4.78577 6.13349 8.95324 --4.63449 5.99365 9.04832 --4.61733 5.97452 9.31045 --4.50577 5.86964 9.4552 --1.3406 3.01152 5.43343 --1.27395 2.94931 5.49413 --1.18186 2.8636 5.51624 --1.16801 2.84958 5.65489 --1.16739 2.84655 5.81703 --1.08191 2.76676 5.84951 --0.485344 2.23019 5.01992 --0.452782 2.19843 5.10673 --0.413603 2.16083 5.18506 --0.347017 2.10006 5.21395 --0.356799 2.10633 5.38904 --0.226244 1.98726 5.29113 --0.377185 2.1194 5.76943 --0.269178 2.02113 5.71953 --0.193203 1.9511 5.73479 -0.0256894 1.75421 5.40893 -0.00663795 1.76863 5.63605 -0.225348 1.57185 5.27173 --0.0726239 1.83287 6.24848 -0.0400046 1.73076 6.1671 -0.156332 1.62533 6.06383 -0.154389 1.62336 6.30494 -0.349399 1.44896 5.93831 -0.257621 1.52618 6.49383 -0.329822 1.459 6.52139 -0.408666 1.38738 6.52839 -0.920098 0.93813 4.8277 -0.97795 0.885676 4.8113 -1.02089 0.8464 4.86045 -0.827949 1.00765 6.01618 -0.874884 0.963158 6.12683 -0.965512 0.880833 6.01322 -1.04959 0.804756 5.91647 -1.12533 0.73702 5.85642 -1.13988 0.717948 6.19746 -1.21006 0.653858 6.18394 -1.30876 0.56717 5.9315 -1.33297 0.539363 6.31045 -1.41042 0.469656 6.21273 -1.44977 0.428859 6.57067 -1.52455 0.360117 6.5296 -1.56029 0.31825 7.18518 -1.61224 0.261326 7.8603 -1.713 0.175485 7.40496 -0.25675 1.74925 -0.942694 -0.19804 1.80512 -0.939368 -0.140405 1.86203 -0.9339 -0.0760573 1.92418 -0.93214 -0.0107918 1.98752 -0.927828 --0.0544532 2.05098 -0.920919 --0.114008 2.10849 -0.905853 --0.138415 2.13151 -0.855728 --0.508067 2.49012 -0.78973 --0.587465 2.56706 -0.771056 --0.63554 2.61327 -0.72699 --0.670288 2.64715 -0.672712 --0.789496 2.7628 -0.670344 --1.13244 3.09825 -0.796056 --1.3075 3.26874 -0.807656 --1.51104 3.46571 -0.825539 --1.69549 3.64545 -0.823902 --1.85999 3.80582 -0.804051 --2.03972 3.97922 -0.782816 --2.14446 4.08088 -0.721203 --2.1933 4.12734 -0.632688 --2.28388 4.21375 -0.558122 --2.3033 4.23206 -0.45524 --2.25274 4.18008 -0.329233 --2.2485 4.17517 -0.220992 --2.24338 4.16816 -0.113255 --2.24292 4.16733 -0.00808823 --2.24258 4.16449 0.0967781 --2.23267 4.15409 0.202641 --2.22847 4.14896 0.306488 --2.23096 4.14917 0.408823 --2.22389 4.14182 0.511856 --2.22351 4.13982 0.613577 --2.22226 4.13575 0.715192 --2.21901 4.13155 0.816497 --2.21383 4.12622 0.917543 --0.5598 2.51489 1.0222 --0.567127 2.52135 1.08272 --0.565895 2.52026 1.14323 --0.550546 2.50423 1.20277 --0.57023 2.52154 1.26496 --2.21155 4.11493 1.52192 --2.2045 4.10745 1.62236 --2.21168 4.11297 1.72497 --2.21036 4.10991 1.82674 --2.20056 4.09825 1.92716 --2.20298 4.09952 2.03064 --0.646039 2.58964 1.71647 --0.644837 2.58774 1.78083 --0.656907 2.59791 1.84971 --0.646223 2.58732 1.91223 --0.656409 2.59542 1.9822 --0.64379 2.58371 2.04455 --0.645493 2.58316 2.11247 --0.638599 2.57595 2.17765 --2.2163 4.09912 2.99756 --2.20551 4.08672 3.10452 --2.21356 4.09304 3.22211 --2.21215 4.09063 3.33696 --2.21638 4.09379 3.45629 --2.21979 4.09394 3.57646 --2.22026 4.09295 3.69746 --2.22543 4.09651 3.82368 --2.23631 4.1047 3.95533 --2.23766 4.10513 4.08367 --2.23054 4.09682 4.20808 --1.86036 3.73833 4.04395 --1.69861 3.58153 4.03225 --1.33604 3.2321 3.8394 --1.13768 3.03919 3.77112 --1.08543 2.9877 3.82801 --1.1812 3.07754 4.0261 --1.04975 2.95029 4.00688 --0.943778 2.84755 4.00609 --3.80653 5.58826 7.20152 --4.19668 5.95744 7.86019 --4.07796 5.84129 7.96839 --3.88215 5.64955 7.98127 --4.7794 6.50447 9.34237 --4.03459 5.78866 8.6792 --3.69375 5.46007 8.49582 --3.56009 5.32846 8.57362 --4.18101 5.91654 9.72437 --4.98794 6.68043 11.2208 --3.54843 5.30669 9.38249 --1.09015 2.96595 5.79044 --0.979524 2.85835 5.77813 --3.81192 5.54296 10.7517 --3.99001 5.708 11.4153 --0.430741 2.3306 5.31102 --3.70723 5.42886 11.6528 --0.160025 2.0702 5.10241 --0.0646277 1.97811 5.06062 --0.125049 2.03283 5.34226 --1.90137 3.70337 9.3974 --0.0318408 1.94035 5.47192 --0.0602473 1.96425 5.71708 -0.285394 1.63777 5.05606 -0.343176 1.58115 5.07691 -0.0245063 1.87692 6.10217 --0.0252356 1.91979 6.461 -0.217146 1.69168 5.99941 -0.320861 1.59179 5.91159 -0.298363 1.60923 6.21569 -0.263782 1.63676 6.58707 -0.365735 1.53969 6.51364 -0.383588 1.51863 6.73761 -0.447213 1.45576 6.80147 -0.984874 0.959167 4.90606 -1.06024 0.887803 4.81285 -1.07412 0.871496 4.98635 -0.919189 1.00779 6.02908 -0.796313 1.11354 7.041 -0.999803 0.92538 6.32625 -1.14373 0.791646 5.86791 -1.14626 0.783734 6.27779 -1.22911 0.705027 6.16696 -1.30351 0.632686 6.09333 -1.35874 0.577771 6.1859 -1.41951 0.518486 6.2376 -1.46678 0.469829 6.4669 -1.5339 0.403046 6.47626 -1.54537 0.379478 7.47125 -1.62056 0.303998 7.59822 -1.70957 0.21977 7.38358 -1.79385 0.141744 7.14666 -0.249017 1.88548 -0.935607 -0.186777 1.94945 -0.935054 -0.123559 2.01361 -0.9319 -0.0604222 2.07889 -0.926199 -0.0199862 2.11998 -0.895258 --0.0554506 2.19772 -0.895979 --0.125916 2.2682 -0.814581 --0.195628 2.34021 -0.80265 --0.26065 2.40631 -0.782857 --0.349241 2.49809 -0.779458 --0.439799 2.59018 -0.772254 --0.480168 2.63106 -0.725183 --0.520527 2.67201 -0.676715 --0.592098 2.74499 -0.647495 --0.708116 2.86354 -0.643293 --0.894925 3.05676 -0.676041 --1.25191 3.42447 -0.795418 --1.45 3.62832 -0.809576 --1.66226 3.8462 -0.820908 --1.84332 4.03139 -0.80635 --2.03089 4.22426 -0.78631 --2.24679 4.4458 -0.768758 --2.5033 4.70863 -0.757117 --2.79468 5.00765 -0.745679 --3.11334 5.33562 -0.72964 --3.51607 5.7484 -0.724213 --4.09617 6.3448 -0.751338 --4.8301 7.09837 -0.790277 --5.82816 8.12432 -0.856333 --6.82882 9.15289 -0.872835 --8.35791 10.7234 -0.939928 --9.86403 12.2695 -0.926402 --9.72136 12.1182 -0.60681 --9.63718 12.028 -0.302268 --14.0524 16.5625 -0.406193 --14.2376 16.7465 -0.0160797 --14.2927 16.7969 0.387578 --0.593472 2.72205 0.991765 --0.58659 2.71475 1.05535 --0.57977 2.70645 1.11868 --0.578577 2.7045 1.18194 --0.576445 2.70149 1.24525 --20.1368 22.7536 3.47557 --20.1489 22.7579 4.03305 --10.1246 12.4807 2.97501 --9.85207 12.197 3.22999 --9.92915 12.2716 3.54643 --6.45097 8.70846 3.02421 --2.2405 4.3977 2.13204 --1.98768 4.13642 2.16731 --1.92602 4.07262 2.25035 --1.93126 4.07707 2.3539 --0.634994 2.75049 1.97992 --0.629959 2.74549 2.04701 --0.631647 2.74504 2.11693 --0.624736 2.73793 2.1842 --2.06486 4.2055 2.94038 --2.09453 4.23463 3.06684 --1.58496 3.71256 2.90925 --1.49706 3.62153 2.96058 --1.42138 3.54346 3.01569 --1.53862 3.66135 3.18694 --2.0933 4.22434 3.64976 --1.48512 3.60448 3.35942 --2.09147 4.2183 3.89414 --2.08717 4.21311 4.01731 --2.08864 4.21156 4.14596 --2.08158 4.20226 4.27061 --2.07823 4.19748 4.40078 --2.08522 4.20292 4.54224 --1.6101 3.71842 4.25071 --1.0485 3.14898 3.84853 --0.921262 3.01812 3.83223 --0.916151 3.01173 3.93213 --0.948635 3.04281 4.07423 --2.08474 4.18934 5.42189 --2.08131 4.1838 5.57733 --2.08539 4.18542 5.74659 --2.08195 4.17931 5.91087 --2.08596 4.18139 6.08952 --2.0862 4.17932 6.26984 --2.09395 4.18447 6.46539 --2.09423 4.18089 6.65581 --2.10002 4.18444 6.86193 --2.10673 4.1885 7.07725 --2.10405 4.1827 7.28727 --2.15007 4.22614 7.58117 --5.30403 7.38498 13.0285 --3.84808 5.92075 10.9632 --3.4055 5.47253 10.5343 --5.47696 7.53867 14.6831 --5.35712 7.4114 14.9528 --0.192477 2.24877 5.2657 --0.0317924 2.08719 5.09566 --0.0256099 2.07871 5.2356 -0.00205485 2.04783 5.33432 -0.0438827 2.00479 5.40719 --0.0470439 2.09284 5.79787 --0.651813 2.68873 7.48998 -0.0655318 1.97486 5.9021 --0.0690304 2.10546 6.47055 -0.184677 1.85074 5.99176 -0.269433 1.76391 5.96221 -0.332801 1.69945 5.99352 -0.241386 1.78515 6.51818 -0.289913 1.73429 6.62372 -0.088971 1.92584 7.61203 -0.39064 1.62723 6.83264 -0.490335 1.52617 6.75672 -0.681946 1.33693 6.28902 -1.0894 0.939206 4.8129 -1.14121 0.885509 4.80451 -1.1894 0.836924 4.81393 -1.23195 0.792066 4.85114 -1.29208 0.731246 4.79018 -1.3411 0.680932 4.78595 -1.40025 0.621524 4.71181 -1.25557 0.750287 6.10055 -1.31324 0.689874 6.14591 -1.37832 0.623478 6.14035 -1.43334 0.566048 6.22244 -1.47578 0.518694 6.47214 -1.51937 0.46918 6.7808 -1.55369 0.426007 7.36788 -1.61347 0.359372 7.7151 -1.71006 0.265823 7.32175 -1.79308 0.18442 7.07588 -0.109499 2.17806 -0.929654 -0.0465166 2.24555 -0.919757 -0.018502 2.27556 -0.874653 --0.0105029 2.30568 -0.828545 --0.0837726 2.38561 -0.822983 --0.141019 2.44743 -0.799035 --0.216236 2.52778 -0.78727 --0.314895 2.63586 -0.791201 --0.378733 2.7043 -0.763121 --0.423694 2.75232 -0.719169 --0.462981 2.79429 -0.669156 --0.563522 2.9032 -0.658495 --0.911845 3.28335 -0.799776 --1.04622 3.42926 -0.792167 --1.18814 3.58279 -0.781669 --1.39309 3.80597 -0.798725 --1.61314 4.04427 -0.8123 --1.84069 4.29044 -0.818093 --2.04362 4.51117 -0.801103 --2.25976 4.74496 -0.779644 --2.50973 5.01577 -0.760638 --2.81333 5.34465 -0.748667 --3.18367 5.74639 -0.744155 --3.64704 6.25052 -0.750346 --4.31274 6.97281 -0.790689 --5.23985 7.98002 -0.865194 --6.23175 9.05597 -0.906621 --7.43411 10.3616 -0.940952 --8.96926 12.0275 -0.974032 --10.9791 14.2078 -1.0023 --12.5889 15.9523 -0.874857 --0.574217 2.89299 0.760943 --0.557051 2.87324 0.82856 --0.55959 2.87564 0.894044 --0.554687 2.86858 0.959833 --0.576039 2.89117 1.02527 --0.555078 2.86807 1.09072 --0.548305 2.85885 1.1558 --0.547096 2.857 1.22096 --0.551569 2.86053 1.28681 --19.101 22.9478 3.7185 --19.1177 22.958 4.26781 --19.1204 22.9523 4.81728 --19.1371 22.9618 5.37194 --19.1472 22.9649 5.92825 --9.5316 12.5621 4.00282 --2.01465 4.43499 2.16807 --1.78892 4.18945 2.20439 --1.76231 4.15831 2.29672 --1.72716 4.11947 2.38556 --1.72492 4.11528 2.48587 --1.7142 4.10243 2.58364 --7.30967 10.1338 5.19362 --5.28758 7.94966 4.49189 --3.779 6.32247 3.93775 --3.70051 6.23558 4.06125 --1.306 3.65617 2.88048 --1.27848 3.62439 2.96082 --7.14425 9.93089 6.70484 --6.66031 9.40624 6.66602 --3.13479 5.61455 4.52493 --3.09952 5.57399 4.66001 --3.0745 5.54548 4.80329 --3.01202 5.47619 4.91824 --3.07988 5.54533 5.13756 --3.14949 5.61805 5.36642 --3.30903 5.78679 5.68229 --3.33554 5.81178 5.89103 --1.01563 3.32502 3.87837 --0.783897 3.07541 3.75925 --0.757287 3.04548 3.8354 --0.828963 3.12099 4.01658 --3.37214 5.83517 6.92484 --4.00309 6.50644 7.86003 --4.62455 7.1654 8.84161 --3.61482 6.08404 7.88563 --2.03464 4.39681 6.12709 --2.0209 4.37894 6.28896 --2.02394 4.37951 6.47889 --2.0092 4.36101 6.64969 --2.00566 4.35431 6.84243 --1.97495 4.31918 7.00071 --1.8994 4.23595 7.09331 --1.99866 4.33666 7.46601 --1.99871 4.33395 7.69453 --1.9913 4.32249 7.91731 --1.98757 4.3151 8.15714 --1.97545 4.29787 8.39078 --1.98006 4.29875 8.66581 --1.98271 4.29801 8.95122 --1.97978 4.29004 9.23894 --1.98701 4.29345 9.56193 --1.98765 4.28958 9.88753 --1.68165 3.96302 9.52069 -0.0812584 2.10897 5.61174 -0.118297 2.0681 5.70246 -0.149661 2.03142 5.81015 --0.782939 3.00242 8.53842 --0.43293 2.63307 7.86796 -0.333372 1.83152 5.90673 --0.261515 2.44566 7.95861 -0.279338 1.88098 6.5348 -0.371253 1.78168 6.48489 -0.105921 2.05017 7.6923 -0.382514 1.76046 7.00118 -0.525448 1.6094 6.75866 -0.604356 1.52382 6.74703 -0.670387 1.45276 6.79015 -1.17237 0.936809 4.80495 -1.22863 0.876358 4.76693 -1.27842 0.822664 4.75616 -1.33012 0.768305 4.73429 -1.37981 0.713992 4.71094 -1.43412 0.655868 4.65679 -1.48192 0.603534 4.63055 -1.52062 0.561112 4.67178 -1.56845 0.509652 4.64299 -1.43209 0.631367 6.38514 -1.48881 0.568811 6.46707 -1.54655 0.505104 6.56746 -1.56783 0.471688 7.23426 -1.64373 0.389335 7.18304 -1.72233 0.306759 7.06993 -1.79793 0.226276 6.93472 -1.88989 0.143735 5.86772 -0.0505094 2.40262 -0.822073 --0.0103569 2.47135 -0.804644 --0.0880144 2.56156 -0.799452 --0.166702 2.65101 -0.790609 --0.274487 2.77435 -0.801225 --0.353988 2.86625 -0.784386 --0.404467 2.92255 -0.742199 --0.549725 3.0897 -0.764383 --0.720307 3.28604 -0.79541 --0.826099 3.40675 -0.775675 --0.980654 3.58438 -0.780178 --1.14274 3.76968 -0.780493 --1.35448 4.01323 -0.799597 --1.55589 4.24397 -0.801533 --1.78351 4.50528 -0.805366 --2.05521 4.81698 -0.817533 --2.27899 5.07338 -0.794422 --2.52249 5.35123 -0.767402 --2.84275 5.71918 -0.756218 --3.24084 6.17563 -0.754474 --3.7814 6.796 -0.776079 --4.53096 7.65619 -0.827941 --5.44538 8.70577 -0.8819 --6.5256 9.94447 -0.924816 --7.86895 11.4861 -0.96332 --9.73132 13.6229 -1.02096 --11.644 15.8155 -0.986817 --12.1656 16.4077 -0.683289 --12.6908 17.0054 -0.353572 --13.2131 17.5983 0.00349451 --14.5194 19.0909 0.355589 --0.642548 3.16834 0.991458 --0.635671 3.1604 1.06208 --0.636417 3.15892 1.13255 --0.635227 3.15633 1.20305 --16.0162 20.7696 2.6903 --16.1613 20.9294 3.18802 --18.6458 23.7463 5.1433 --8.2905 11.9005 3.35981 --8.24454 11.8438 3.62776 --8.16303 11.7463 3.88482 --1.79024 4.46525 2.20206 --1.79638 4.47094 2.30927 --1.80065 4.47453 2.41706 --5.09143 8.21613 4.42068 --5.01588 8.12665 4.58929 --3.76145 6.69581 4.12503 --5.19295 8.32045 5.10601 --6.60906 9.92807 6.167 --6.35482 9.63505 6.27191 --3.80467 6.73365 4.85582 --3.74887 6.66726 5.00081 --2.95787 5.76581 4.61503 --2.92266 5.72426 4.75036 --6.34801 9.60651 7.606 --2.81316 5.59411 4.98988 --2.73871 5.50842 5.09212 --2.78946 5.56308 5.3032 --2.9784 5.77317 5.64861 --0.707711 3.20074 3.64866 --0.654999 3.14082 3.69805 --0.636031 3.11663 3.77939 --0.599266 3.07343 3.84309 --3.33967 6.16604 7.00205 --5.29295 8.36676 9.47792 --3.97597 6.8761 8.20732 --3.44251 6.27223 7.80454 --3.36523 6.18035 7.94722 --3.44078 6.26123 8.29287 --3.33822 6.1424 8.40824 --3.08012 5.84762 8.30023 --3.75084 6.59792 9.54665 --2.01628 4.64626 7.19483 --2.98125 5.72484 8.93817 --2.92716 5.65972 9.12707 --1.44316 3.99406 6.89755 --3.26005 6.02354 10.2934 --3.0476 5.78123 10.2373 --4.86226 7.80281 13.9824 --3.21819 5.95974 11.2424 --2.98626 5.69514 11.1448 --2.8426 5.53056 11.217 --2.79484 5.47004 11.4908 --1.94334 4.51841 9.96445 --1.87709 4.43939 10.1507 --2.72526 5.37387 12.5692 -0.128318 2.2082 5.80924 -0.203296 2.12324 5.80551 -0.283741 2.03094 5.78178 --0.302344 2.67269 7.65272 --0.204861 2.56231 7.64936 --0.0917698 2.43311 7.58874 --0.123075 2.46284 7.98812 -0.36377 1.92513 6.65812 -0.493272 1.77955 6.46921 -0.550613 1.71272 6.52641 -0.580275 1.67613 6.69448 -0.259419 2.01849 8.33273 -0.184369 2.09263 9.0689 -0.851934 1.3685 6.44492 -1.25528 0.933387 4.79646 -1.30575 0.875203 4.77689 -1.35162 0.822193 4.77513 -1.39748 0.769119 4.77207 -1.45898 0.701167 4.67009 -1.50843 0.644778 4.62481 -1.5543 0.593007 4.60757 -1.60008 0.54069 4.57924 -1.63672 0.49731 4.61883 -1.6681 0.460132 4.73665 -1.52639 0.586979 6.96009 -1.5921 0.510806 7.00086 -1.66416 0.430212 6.9602 -1.73328 0.350196 6.92764 -1.80261 0.272065 6.91311 -1.87008 0.194944 6.91666 --0.19663 2.87763 -0.706988 --0.256195 2.95006 -0.674231 --0.269028 2.96424 -0.606142 --0.299644 2.99999 -0.549685 --0.334909 3.0419 -0.495797 --0.375754 3.09107 -0.444023 --0.440013 3.16814 -0.404249 --0.270487 2.9597 -0.234348 --1.2117 4.10851 -0.646205 --1.74609 4.75883 -0.804697 --2.02231 5.09494 -0.815625 --2.24527 5.36453 -0.788562 --2.53637 5.71773 -0.776482 --2.87235 6.12377 -0.764742 --3.31369 6.6607 -0.770415 --3.91389 7.38859 -0.800136 --4.73436 8.38515 -0.858237 --5.60233 9.43841 -0.882805 --6.90623 11.0221 -0.956323 --8.70024 13.199 -1.05271 --10.3734 15.228 -1.03015 --11.3021 16.3511 -0.813368 --11.7861 16.9336 -0.497345 --12.2935 17.5428 -0.157617 --12.7905 18.1397 0.209766 --14.8545 20.6369 0.56034 --14.8929 20.6763 1.02438 --0.663178 3.41386 1.10321 --0.656395 3.40408 1.17733 --15.0781 20.8778 2.4346 --17.1146 23.3372 3.12873 --17.1249 23.34 3.65823 --9.4445 14.0359 2.9231 --9.4937 14.0903 3.25122 --7.93625 12.2017 3.22939 --7.65464 11.856 3.43859 --8.08716 12.374 3.83066 --7.743 11.955 4.01243 --7.9853 12.2422 4.3715 --7.88739 12.1184 4.62321 --5.11198 8.74811 4.88833 --3.75434 7.11001 4.33482 --8.06875 12.2975 7.10391 --3.74461 7.09299 4.69111 --3.73469 7.0771 4.86833 --3.67998 7.00898 5.01763 --3.62435 6.93971 5.16497 --2.78519 5.92883 4.7145 --2.76234 5.89752 4.85944 --8.03515 12.2198 9.4012 --6.79481 10.726 8.68143 --2.50377 5.5795 5.13284 --2.41943 5.47643 5.22024 --2.49323 5.56189 5.45792 --2.82641 5.95735 5.96757 --2.79775 5.92142 6.12751 --2.79989 5.92015 6.32173 --2.84007 5.96471 6.56456 --2.52247 5.58209 6.39592 --2.42236 5.45936 6.47024 --2.46715 5.50971 6.72314 --2.62615 5.69617 7.13415 --3.32093 6.51966 8.28995 --3.20205 6.37457 8.38114 --3.06936 6.21137 8.44759 --3.27905 6.45718 9.02289 --2.0569 5.00022 7.40595 --3.30669 6.48032 9.63783 --3.25088 6.40911 9.84744 --2.70079 5.75145 9.20959 --3.02518 6.13099 10.0763 --2.75891 5.81055 9.90591 --2.53907 5.54535 9.80156 --2.68428 5.71242 10.4047 --2.31627 5.27234 9.98833 --2.98554 6.05556 11.7386 --2.78136 5.80884 11.6846 --2.68185 5.68487 11.8546 --2.60077 5.58347 12.0727 --2.664 5.65022 12.6541 -0.228858 2.2559 5.70018 -0.296977 2.17279 5.70522 --0.285274 2.85011 7.50931 --0.275111 2.83323 7.74765 --0.176169 2.71442 7.73769 --0.0884735 2.60649 7.75141 -0.0279151 2.46711 7.67173 -0.0668002 2.41711 7.84349 -0.544193 1.8608 6.4505 -0.612425 1.77901 6.46199 -0.604204 1.78376 6.7702 -0.692575 1.67686 6.70447 -0.761647 1.59279 6.71136 -0.800461 1.54359 6.85875 -0.889684 1.43634 6.7667 -1.01 1.2944 6.49848 -0.749791 1.58107 8.32142 -1.07224 1.2137 6.90886 -1.2088 1.05557 6.4756 -1.52893 0.696796 4.68738 -1.57898 0.635359 4.62192 -1.62556 0.580531 4.58439 -1.66114 0.536229 4.62433 -1.69409 0.495013 4.70309 -1.72977 0.450091 4.7711 -1.60622 0.563904 6.97631 -1.67335 0.482122 6.96638 -1.73968 0.402291 6.97459 -1.80507 0.322917 6.99089 -1.86793 0.244059 7.09539 -1.96285 0.152992 5.71851 --0.888806 3.9253 -0.771714 --1.06001 4.14216 -0.773907 --1.19113 4.307 -0.744826 --1.48059 4.67531 -0.789971 --1.71411 4.97123 -0.790951 --2.00168 5.33504 -0.80325 --2.28541 5.69451 -0.797444 --0.27432 3.13267 0.113927 --2.98229 6.57578 -0.784775 --3.48659 7.21531 -0.800598 --4.27863 8.21943 -0.873814 --5.06867 9.21969 -0.901298 --6.04478 10.4559 -0.928991 --7.5142 12.3172 -1.00633 --9.13598 14.371 -1.02845 --10.6383 16.2716 -0.940648 --11.0559 16.7946 -0.631537 --11.5264 17.3849 -0.305187 --12.0118 17.9933 0.0458193 --15.2756 22.1213 0.307925 --15.4898 22.3831 0.794272 --15.3502 22.1995 1.28709 --16.2481 23.3271 1.81649 --16.2964 23.3799 2.33642 --16.3085 23.3864 2.85594 --16.3271 23.4013 3.3779 --16.3345 23.4016 3.90019 --8.48424 13.4781 2.97707 --8.76575 13.8289 3.33812 --8.58149 13.5913 3.60426 --7.47612 12.1919 3.61242 --7.5467 12.2761 3.90991 --8.00385 12.8476 4.3399 --5.29876 9.43414 3.66864 --3.78731 7.50633 4.56001 --3.90643 7.65196 4.82313 --3.66439 7.34509 4.85632 --3.68042 7.36202 5.05676 --3.63146 7.29762 5.21343 --3.52503 7.16033 5.32547 --2.65775 6.07207 4.82531 --2.60059 5.99725 4.94357 --2.60839 6.00331 5.11705 --7.78625 12.4774 9.98312 --7.56611 12.1961 10.1409 --2.19024 5.472 5.22796 --2.12939 5.39317 5.33068 --4.04277 7.7791 7.5242 --2.73606 6.14561 6.33418 --2.689 6.08377 6.47952 --2.62528 6.00094 6.60604 --2.55042 5.90468 6.71821 --2.42562 5.74503 6.76572 --2.20912 5.47227 6.687 --2.38712 5.68959 7.13069 --4.07659 7.78638 9.73344 --3.1972 6.6887 8.75476 --3.0778 6.53554 8.84554 --2.1794 5.41698 7.71174 --2.07219 5.2801 7.77229 --3.40858 6.93121 10.2523 --2.57531 5.89427 9.12759 --2.46236 5.75115 9.21083 --2.80795 6.17228 10.142 --2.34479 5.59555 9.57399 --2.41758 5.68045 10.0242 --2.313 5.54607 10.1319 --2.32754 5.55786 10.4934 --2.98716 6.36273 12.3079 --4.75359 8.52471 16.7988 --2.54994 5.8054 12.5444 --2.43587 5.65859 12.6961 --2.55399 5.79557 13.4739 -0.401897 2.18275 5.73044 -0.446794 2.125 5.7937 --1.50184 4.48986 11.8884 --0.156105 2.85001 8.10964 -0.0077452 2.64623 7.88126 -0.123691 2.50037 7.79159 -0.209276 2.39123 7.79848 -0.258185 2.32714 7.94112 -0.717128 1.77078 6.46387 -0.78508 1.68538 6.46293 -0.766882 1.70201 6.83692 -0.841231 1.60816 6.81491 -0.931141 1.49643 6.71426 -0.998115 1.41122 6.71591 -1.06327 1.3285 6.72507 -1.18039 1.18606 6.42256 -1.24268 1.10679 6.41685 -1.30223 1.03056 6.42884 -1.30569 1.01965 6.86038 -1.44135 0.857801 6.29015 -1.67386 0.588763 4.72829 -1.71845 0.533457 4.69891 -1.75575 0.485488 4.72771 -1.78953 0.440641 4.81515 -1.67779 0.545233 7.09151 -1.74118 0.464103 7.13064 -1.81245 0.375482 7.0283 -1.87415 0.295743 7.11363 -1.93946 0.212719 7.15734 --1.68018 5.24998 -0.792093 --1.91824 5.56895 -0.778551 --2.23336 5.98998 -0.78313 --0.333354 3.43367 0.0841889 --3.06464 7.10315 -0.808927 --3.72376 7.98479 -0.864157 --4.40864 8.90162 -0.888273 --5.24365 10.0191 -0.911951 --6.3474 11.4972 -0.949719 --8.05377 13.7812 -1.04585 --9.80705 16.1267 -1.05022 --10.2592 16.7259 -0.763798 --10.6963 17.3064 -0.450552 --11.1316 17.8821 -0.112449 --11.5028 18.3731 0.253841 --15.0259 23.0804 0.553719 --15.3439 23.4965 1.05412 --15.3633 23.5139 1.56375 --15.3773 23.524 2.0742 --15.3977 23.5427 2.58648 --8.61549 14.4744 2.29759 --8.53747 14.3653 2.6003 --8.21227 13.925 2.85556 --7.83709 13.4191 3.0825 --7.7684 13.3235 3.3607 --7.8461 13.421 3.67482 --7.73019 13.2625 3.9381 --6.58141 11.7268 3.86 --6.47038 11.5737 4.08341 --3.24171 7.24549 4.63701 --3.35386 7.39057 4.8977 --3.50106 7.58269 5.1943 --3.41996 7.47202 5.32685 --3.69007 7.82485 5.74138 --4.11887 8.38968 6.31355 --2.40911 6.12443 5.03114 --2.38815 6.09449 5.18103 --5.09909 9.67148 7.94941 --4.98081 9.51084 8.11066 --1.93303 5.48376 5.23227 --1.85957 5.38317 5.31603 --3.93289 8.11506 7.7984 --4.04547 8.25937 8.18468 --2.94928 6.8109 7.13181 --2.24922 5.88481 6.48203 --2.26424 5.90052 6.69974 --2.43039 6.11634 7.12759 --2.35309 6.01085 7.23859 --2.41223 6.08473 7.54381 --2.69169 6.44656 8.18906 --1.84559 5.3343 7.13887 --1.58594 4.98975 6.93928 --1.97489 5.49567 7.78797 --2.46131 6.12763 8.85491 --2.98432 6.80647 10.0539 --2.21532 5.79725 8.96472 --2.1251 5.67379 9.0729 --2.26394 5.85025 9.63042 --2.17084 5.72402 9.74703 --2.10627 5.63461 9.92392 --1.97739 5.46028 9.96371 --2.18486 5.72493 10.7595 --1.15713 4.3846 8.70937 --1.0192 4.20135 8.66092 --2.75421 6.43263 13.7989 --2.35314 5.90762 13.207 --1.39638 4.66636 10.9847 --0.110153 3.00456 7.60097 --0.0991067 2.98566 7.8401 --0.100878 2.98228 8.13384 --0.183116 3.08239 8.7173 -0.165012 2.63205 7.84758 -0.213692 2.56467 7.98417 -0.348261 2.38681 7.7977 -0.951528 1.6161 5.71359 -0.920403 1.65129 6.08196 -0.822843 1.77015 6.78227 -0.925085 1.63553 6.61926 -0.983622 1.55738 6.65188 -0.730047 1.86698 8.31844 -1.13241 1.36024 6.53904 -1.2308 1.2323 6.32417 -1.25568 1.19546 6.54205 -1.30869 1.12364 6.59443 -1.33457 1.08363 6.8507 -1.44723 0.941045 6.45893 -1.51727 0.84857 6.35829 -1.49945 0.859605 7.08498 -1.77663 0.528626 4.77348 -1.81389 0.479124 4.81177 -1.852 0.428026 4.83911 -1.73604 0.537221 7.42566 -1.80543 0.445727 7.38445 -1.8857 0.344142 7.03166 -1.94787 0.260353 7.05611 -2.01101 0.176415 7.07876 --1.90121 5.91659 -0.786448 --2.21683 6.36197 -0.786012 --2.65601 6.98591 -0.814398 --3.17092 7.71575 -0.842483 --3.79009 8.59322 -0.872492 --4.47478 9.56185 -0.883534 --5.40485 10.8802 -0.916729 --6.78994 12.8437 -0.996344 --8.52293 15.2973 -1.05975 --9.49655 16.6744 -0.892934 --9.88485 17.2185 -0.589092 --10.2878 17.7835 -0.264239 --10.734 18.4093 0.0808988 --13.979 22.9991 0.331194 --14.4201 23.6154 0.813929 --14.7302 24.0454 1.3207 --14.781 24.108 1.83386 --14.8318 24.1708 2.35042 --8.13617 14.6925 2.14183 --8.1028 14.6395 2.44965 --8.26768 14.867 2.78951 --8.27388 14.8711 3.10864 --7.95109 14.4084 3.35351 --7.7343 14.097 3.60769 --6.26135 12.0128 3.48369 --6.98201 13.0247 3.97753 --4.22792 9.09415 5.60087 --3.30412 7.79542 5.13244 --3.25838 7.72733 5.29181 --3.31011 7.79651 5.53152 --3.74911 8.40745 6.11092 --3.24981 7.70507 5.88487 --2.22653 6.26891 5.13304 --2.16982 6.18699 5.24915 --2.17286 6.18882 5.424 --4.81785 9.87898 8.39046 --4.62102 9.59991 8.46379 --1.58655 5.36053 5.29316 --1.67888 5.48484 5.56352 --1.87941 5.76235 5.98 --1.97063 5.88599 6.27882 --2.07097 6.02245 6.60262 --2.81404 7.05248 7.81924 --1.77853 5.60832 6.59733 --2.25976 6.273 7.50092 --2.20389 6.19151 7.64506 --2.18468 6.16133 7.84864 --1.47657 5.17459 6.93655 --1.46395 5.15289 7.12114 --1.75942 5.55792 7.8494 --1.77603 5.57624 8.11756 --1.64954 5.3977 8.13024 --1.50019 5.1872 8.09244 --2.0088 5.88347 9.35705 --1.92896 5.76875 9.48731 --2.11477 6.0183 10.1871 --1.91487 5.73883 10.0743 --2.06937 5.94451 10.7569 --0.250946 3.4425 6.77427 --0.899634 4.32819 8.59327 --0.814566 4.20587 8.65758 --0.808129 4.1909 8.9299 --1.34427 4.91904 10.7227 --1.07623 4.54651 10.3332 --0.0177017 3.09706 7.53582 --0.0650953 3.1576 7.95063 --0.00389192 3.06915 8.0416 -0.0819177 2.94704 8.05033 -0.208756 2.77 7.91145 -0.327318 2.60413 7.78549 -0.267483 2.68005 8.33342 -0.481517 2.38561 7.81454 -0.998108 1.68741 5.95422 -0.958139 1.73652 6.39017 -0.885627 1.82821 7.01822 -0.983768 1.69128 6.86447 -1.10723 1.52199 6.55402 -1.15823 1.44957 6.61224 -1.27057 1.29504 6.30286 -1.28534 1.26926 6.56954 -1.31471 1.22468 6.77835 -1.37465 1.13898 6.78189 -1.44638 1.04008 6.69527 -1.50455 0.957788 6.70456 -1.54651 0.893754 6.86006 -1.60481 0.812275 6.88593 -1.83838 0.51908 4.81802 -1.8753 0.465582 4.83598 -1.91228 0.412521 4.86282 -1.82467 0.49364 7.24137 -1.89682 0.39551 7.02925 -1.94756 0.317817 7.3043 -2.01525 0.225748 7.12807 --1.53142 5.76792 -0.765238 --1.82249 6.20555 -0.769822 --2.19079 6.75851 -0.787971 --0.484742 4.18135 0.00911035 --3.30485 8.43482 -0.886558 --3.95047 9.40446 -0.910572 --4.76684 10.6318 -0.942493 --5.70714 12.0441 -0.953791 --7.27021 14.394 -1.04227 --8.76033 16.6327 -1.01834 --9.14598 17.205 -0.729119 --9.49013 17.716 -0.411585 --9.89853 18.3229 -0.0791308 --13.4193 23.6007 0.582991 --13.975 24.425 1.07623 --13.9925 24.4423 1.58595 --14.0394 24.5027 2.09859 --7.74001 15.0415 1.99701 --14.0506 24.5 3.12368 --14.0664 24.5125 3.63963 --7.72304 14.9978 2.93578 --7.73843 15.0155 3.25453 --7.55844 14.7403 3.52545 --7.40418 14.5035 3.79348 --3.42407 8.49507 5.32069 --3.297 8.30206 5.42629 --2.93644 7.76295 5.33008 --3.00078 7.85456 5.582 --2.82246 7.58691 5.62058 --2.91698 7.72324 5.90829 --4.3704 9.87394 7.55956 --1.95679 6.29033 5.32701 --1.92503 6.24114 5.46604 --4.33368 9.80511 8.34001 --3.76206 8.95322 7.95823 --1.32056 5.33746 5.27318 --1.28994 5.28741 5.39354 --0.998643 4.85486 5.1773 --1.44692 5.51323 5.93316 --0.869645 4.65883 5.30536 --0.811606 4.5695 5.37477 --1.68892 5.85996 6.84538 --1.62427 5.76103 6.95196 --1.67653 5.83383 7.24376 --1.67856 5.8319 7.46544 --1.28526 5.25013 7.01393 --1.18778 5.1036 7.05 --1.24369 5.18066 7.36274 --2.13051 6.47665 9.27711 --1.26764 5.20786 7.86181 --1.16833 5.0583 7.89982 --2.28324 6.68409 10.503 --2.03238 6.3113 10.2897 --1.81171 5.98257 10.119 --1.70404 5.81926 10.1931 --2.02434 6.27907 11.3081 --0.803258 4.49619 8.59918 -0.0194519 3.29626 6.72345 --0.601127 4.19251 8.62782 --0.579274 4.1544 8.8568 --0.503671 4.03964 8.94064 -0.0726256 3.202 7.49661 -0.153396 3.07989 7.49927 -0.125275 3.11558 7.86109 -0.138901 3.08957 8.10145 -0.205326 2.98975 8.17201 --0.10726 3.4307 9.66439 -0.0109681 3.25467 9.59601 -0.216021 2.95457 9.15437 -0.64538 2.33798 7.70084 -0.993678 1.83802 6.45759 -1.02624 1.7863 6.58703 -0.739275 2.18313 8.33348 -1.13032 1.6288 6.67285 -1.00175 1.80168 7.73709 -1.21812 1.49225 6.85808 -1.2734 1.40954 6.89585 -1.32595 1.32987 6.95131 -1.41693 1.19668 6.72265 -1.43634 1.16152 7.0283 -1.53889 1.01501 6.66653 -1.53175 1.01407 7.26577 -1.62869 0.874653 6.8986 -1.60796 0.888251 7.81502 -1.89993 0.507035 4.85237 -1.93665 0.451028 4.85994 -1.97257 0.396996 4.88614 -1.90499 0.455477 7.13598 -1.9571 0.373788 7.33212 -2.02183 0.278405 7.20683 -2.11145 0.176809 5.48979 --1.04789 5.40051 -0.78895 --1.22321 5.6792 -0.762909 --1.51193 6.14012 -0.780569 --1.82253 6.63591 -0.789056 --2.09832 7.07516 -0.762601 --2.57257 7.83149 -0.793609 --0.552549 4.59469 0.0698425 --3.91396 9.97129 -0.884233 --4.87062 11.4976 -0.942952 --7.34937 15.381 2.48168 --7.34834 15.3725 2.79738 --7.39108 15.4344 3.12368 --7.38359 15.4166 3.44109 --7.1891 15.1001 3.70622 --5.79359 12.8789 3.57843 --3.34321 8.93218 5.57653 --3.45717 9.10911 5.89053 --3.9829 9.9326 6.58493 --3.03682 8.43663 5.94879 --3.1289 8.57868 6.25372 --2.95879 8.30703 6.30267 --4.16055 10.1929 7.79465 --1.77146 6.42994 5.43523 --1.70349 6.32035 5.53299 --1.69838 6.30842 5.70315 --1.74049 6.37161 5.93497 --1.06769 5.31233 5.2565 --1.01531 5.2273 5.34527 --0.945678 5.11487 5.40801 --0.892395 5.02854 5.49183 --0.730079 4.771 5.41129 --0.797737 4.87329 5.67212 --0.742628 4.78453 5.74974 --1.57426 6.0795 7.28596 --1.36547 5.75024 7.1507 --1.18045 5.45665 7.03831 --1.17158 5.43862 7.23166 --1.00472 5.1749 7.13316 --1.09752 5.3144 7.52724 --1.13573 5.36997 7.83279 --0.922636 5.03485 7.62499 --1.06248 5.24634 8.15958 --1.90843 6.55268 10.3122 --1.911 6.54941 10.6476 --1.99052 6.66509 11.1843 --0.726458 4.70517 8.39627 --0.633147 4.55649 8.42457 --0.512747 4.3652 8.37484 --0.477349 4.30672 8.55335 -0.275374 3.14339 6.66286 --0.184176 3.8452 8.26083 --0.100969 3.71198 8.28494 --0.00693132 3.56217 8.27103 -0.281275 3.11595 7.59331 -0.202731 3.23018 8.1425 -0.397736 2.92717 7.73103 -0.598978 2.61658 7.25499 -0.677425 2.49193 7.22375 -0.291943 3.06893 9.12563 -0.659644 2.5075 7.90036 -0.854111 2.20735 7.34357 -1.12581 1.79484 6.35474 -1.17251 1.71893 6.39785 -1.22548 1.63314 6.41106 -1.19698 1.66964 6.88999 -1.25282 1.58107 6.91142 -1.29336 1.51316 7.02757 -1.57336 1.09828 5.51535 -1.44155 1.28173 6.80909 -1.52487 1.15288 6.59789 -1.51483 1.15769 7.14772 -1.57691 1.06024 7.11907 -1.62125 0.986602 7.26592 -1.66212 0.917062 7.47086 -1.73387 0.805824 7.33779 -1.95952 0.494084 4.9065 -1.99779 0.43397 4.87361 -2.03167 0.378526 4.90931 -1.97464 0.42433 7.21976 -2.03374 0.330295 7.15523 -2.11828 0.221762 5.91916 --2.64833 8.38417 5.32363 --2.39319 7.95186 5.29059 --2.52211 8.16291 5.60704 --2.56395 8.2297 5.85119 --2.80224 8.62478 6.30685 --3.31662 9.47991 7.08681 --2.87322 8.73344 6.83383 --2.37829 7.90287 6.48525 --2.46637 8.04351 6.80684 --1.47222 6.3813 5.76958 --1.45265 6.34463 5.92361 --0.808163 5.26605 5.22599 --0.787687 5.22998 5.35295 --0.753716 5.17013 5.46166 --0.602308 4.9137 5.39026 --0.580122 4.87325 5.51172 --0.579528 4.87011 5.67166 --0.542859 4.80575 5.77356 --0.573929 4.85371 5.99502 --0.54893 4.80946 6.12426 --0.5601 4.82399 6.32278 --0.488223 4.70051 6.36762 --0.419945 4.58344 6.41619 --1.16914 5.81662 8.16205 --1.04742 5.61106 8.14986 --0.868902 5.31215 8.00303 --0.927603 5.40377 8.38357 --1.68122 6.63776 10.4437 --1.90815 7.00287 11.3404 --1.58888 6.472 10.8948 --0.361124 4.45139 7.99175 --0.275612 4.30685 8.01289 --0.18207 4.14837 8.00542 --0.243404 4.24118 8.4472 --0.116478 4.02974 8.34294 -0.414819 3.15813 6.92767 -0.336508 3.28065 7.42189 -0.0158113 3.79616 8.78971 -0.258322 3.39594 8.23555 -0.626345 2.79473 7.15922 -0.72407 2.63153 7.04151 -0.715122 2.64113 7.34548 -0.702607 2.65487 7.68823 -0.64988 2.73237 8.23612 -1.04554 2.09309 6.72901 -1.1278 1.9558 6.60925 -1.24673 1.76217 6.28811 -1.29316 1.68273 6.32048 -1.28077 1.69598 6.69389 -1.49463 1.35292 5.72014 -1.51778 1.31029 5.85962 -1.58273 1.20255 5.72823 -1.64331 1.10393 5.61335 -1.46564 1.36864 7.37734 -1.61733 1.12685 6.56991 -1.64098 1.08239 6.83483 -1.61634 1.10735 7.63168 -1.70691 0.96032 7.28526 -1.77203 0.852986 7.18238 -1.96531 0.564993 5.21075 -2.01557 0.4848 5.01004 -2.05696 0.416512 4.89703 -2.08986 0.360588 4.94207 -2.07541 0.355262 6.35429 -2.12913 0.269604 6.10826 -2.18204 0.189552 5.63048 --2.41766 8.5755 5.25565 --2.35227 8.45303 5.39411 --2.20128 8.17972 5.44679 --2.23037 8.22684 5.67389 --2.30434 8.35559 5.9552 --2.25064 8.25441 6.10413 --2.41377 8.53881 6.50285 --2.08563 7.95063 6.32821 --2.18289 8.1205 6.66175 --2.3558 8.4218 7.10628 --1.2798 6.50555 5.88 --1.22705 6.40849 5.98928 --0.551546 5.20549 5.18709 --0.611231 5.30845 5.43081 --0.37981 4.89522 5.22791 --0.433221 4.98648 5.46585 --0.472228 5.05209 5.68951 --0.534615 5.15767 5.96276 --0.504431 5.10059 6.08217 --0.34944 4.82389 5.97049 --0.397313 4.90514 6.23581 --0.33927 4.7996 6.30211 --0.292086 4.71171 6.38735 --0.98748 5.92913 8.06308 --0.988433 5.92643 8.31082 --0.783211 5.5613 8.09525 --0.669553 5.35574 8.07311 --0.685757 5.37907 8.36205 --1.15427 6.19257 9.81463 --0.453981 4.96184 8.2811 --0.260746 4.61797 8.01422 --0.166765 4.45034 8.00489 --0.119442 4.36207 8.12319 --0.0765658 4.28185 8.25675 --0.115075 4.34185 8.6513 -0.372869 3.49016 7.34232 -0.524584 3.22185 7.07196 -0.471753 3.30739 7.4988 -0.514537 3.22784 7.6053 -0.523401 3.20603 7.8439 -0.782 2.75621 7.09781 -0.824757 2.67773 7.18553 -0.805057 2.70378 7.54525 -0.844349 2.63132 7.66905 -0.645214 2.96209 8.93886 -1.16721 2.06942 6.70328 -1.32176 1.80236 6.17861 -1.30217 1.82849 6.56026 -1.51934 1.45718 5.58726 -1.52027 1.45117 5.85158 -1.56809 1.36592 5.82905 -1.57069 1.35278 6.11333 -1.6777 1.17147 5.66212 -1.5748 1.33042 6.82047 -1.58497 1.30429 7.17571 -1.69793 1.11291 6.62963 -1.75283 1.01534 6.56961 -1.72312 1.04951 7.44485 -1.75386 0.986514 7.74928 -1.99318 0.610237 5.22663 -2.0319 0.541671 5.18564 -2.0807 0.458049 4.93425 -2.11585 0.396059 4.90017 -2.13837 0.349616 5.1642 -2.14271 0.3188 6.22689 -2.19164 0.235379 5.99992 --5.73321 15.6868 3.2327 --5.5888 15.4033 3.49779 --5.55296 15.3264 3.79074 --2.59807 9.57119 5.79779 --2.7378 9.83136 6.16108 --2.039 8.49313 5.6539 --2.16439 8.72728 5.99542 --2.25218 8.88961 6.30984 --1.8369 8.09448 6.03263 --1.98277 8.36721 6.41938 --1.89731 8.19869 6.5233 --1.96351 8.32121 6.82999 --1.2709 6.99949 6.08175 --1.13104 6.72966 6.06977 --0.352221 5.24638 5.08119 --0.319562 5.18214 5.1808 --0.276289 5.09624 5.26108 --0.378396 5.28605 5.58647 --0.42248 5.36578 5.8258 --0.395216 5.30997 5.94707 --0.356347 5.23238 6.048 --0.250601 5.029 6.01971 --0.258956 5.04098 6.21082 --0.177299 4.88318 6.22284 --0.185654 4.89455 6.42169 --0.826353 6.09425 8.02917 --0.754296 5.95442 8.10866 --0.814016 6.06158 8.49775 --0.76796 5.96672 8.64352 -0.203508 4.14063 6.43803 -0.270919 4.01195 6.45363 --0.3429 5.15475 8.32181 --0.220344 4.91939 8.23538 --0.055194 4.60445 8.01226 -0.000712069 4.49505 8.09919 -0.0619132 4.37537 8.16727 -0.519879 3.51845 6.93888 -0.316536 3.89108 7.85403 -0.668624 3.23368 6.87931 -0.575322 3.40008 7.45118 -0.810063 2.96109 6.81358 -0.682343 3.19028 7.55807 -0.835435 2.90237 7.19774 -0.892851 2.79045 7.2153 -0.754885 3.03676 8.11051 -0.900867 2.76411 7.74578 -1.12084 2.35658 6.97629 -1.22584 2.15909 6.72204 -1.29023 2.03668 6.65816 -1.41447 1.80598 6.24319 -1.55708 1.54423 5.6695 -1.58077 1.49622 5.782 -1.61407 1.42972 5.83667 -1.6439 1.36981 5.91898 -1.6975 1.26918 5.83609 -1.6242 1.38915 6.77034 -1.65076 1.33274 6.95983 -1.70529 1.22787 6.91399 -1.7364 1.16408 7.1016 -1.84036 0.977522 6.50019 -1.88601 0.888815 6.48627 -2.02895 0.645057 5.14304 -2.0664 0.573605 5.08278 -2.10132 0.507721 5.0508 -2.13853 0.436679 4.93785 -2.17001 0.376348 4.95298 -2.19896 0.319083 5.02685 -2.18678 0.299819 6.86867 -2.24698 0.202985 6.04112 --2.33668 9.88182 -0.929011 --2.91017 11.0659 -0.950808 --3.39874 12.075 -0.898299 --4.28111 13.8984 -0.922936 --5.533 16.4863 -0.970792 --6.83087 19.1677 -0.928063 --7.81492 21.1961 -0.727072 --9.6265 24.9227 -0.076021 --9.70344 25.0693 0.400579 --9.71978 25.0912 0.883229 --9.78681 25.1836 2.82592 --9.79778 25.1945 3.31498 --9.80524 25.1972 3.80501 --9.81705 25.2103 4.29827 --9.82535 25.2153 4.7929 --5.016 15.3078 3.6055 --5.19653 15.6712 3.97626 --1.58526 8.18505 4.94947 --1.80034 8.61959 5.35945 --2.07743 9.18079 5.86122 --2.18776 9.39894 6.20181 --2.00873 9.0296 6.21323 --1.85468 8.70971 6.24075 --1.67747 8.34528 6.22771 --1.63164 8.24654 6.37568 --1.69305 8.36634 6.67385 --0.952306 6.85579 5.81717 --1.76617 8.50356 7.22788 --0.163419 5.24768 4.95318 --0.108925 5.1339 5.0107 --0.185538 5.28558 5.286 --0.171848 5.25307 5.41555 --0.287294 5.48387 5.78269 --0.259439 5.42172 5.89826 --0.215467 5.33017 5.98682 --0.228201 5.35187 6.1863 --0.0596497 5.00621 6.01532 --0.877218 6.6499 7.94621 -0.297878 4.2797 5.5749 -0.362869 4.14477 5.58282 -0.34476 4.17687 5.78333 --1.43885 7.75153 10.3421 -0.157592 4.54352 6.59773 -0.292485 4.26968 6.4383 -0.321294 4.2072 6.54838 --0.247415 5.33908 8.35255 -0.410749 4.01908 6.68677 --0.141704 5.11559 8.56605 -0.849417 3.13638 5.72393 -0.593424 3.64112 6.73113 -0.710344 3.40328 6.54745 -0.698629 3.42132 6.79576 -0.796164 3.22323 6.66195 -0.822294 3.16538 6.78133 -0.755263 3.29221 7.27504 -0.924891 2.95313 6.8335 -0.950256 2.89804 6.96706 -0.892121 3.00507 7.4768 -0.794641 3.18872 8.20946 -1.1255 2.53646 6.92797 -1.25519 2.27778 6.54197 -1.35586 2.07656 6.26801 -1.37844 2.02547 6.3979 -1.43961 1.90114 6.31161 -1.49739 1.78582 6.24112 -1.54533 1.68635 6.21519 -1.63167 1.51503 5.91975 -1.64913 1.47525 6.08958 -1.69172 1.38575 6.07611 -1.74314 1.28222 5.99278 -1.80921 1.15139 5.7612 -1.74364 1.26242 6.74718 -1.77094 1.20187 6.93467 -1.82151 1.09807 6.8855 -1.88764 0.968893 6.64673 -1.95003 0.845815 6.38485 -2.07439 0.620015 5.11818 -2.1021 0.560046 5.17648 -2.07207 0.592352 6.41836 -2.17529 0.414027 4.95059 -2.20479 0.353281 4.97516 -2.23195 0.29556 5.09833 -2.25372 0.238937 5.54049 --1.47416 8.79109 -0.938504 --1.8319 9.58234 -0.932496 --2.25493 10.5191 -0.923809 --2.78144 11.6826 -0.918035 --3.31846 12.8679 -0.870894 --4.27167 14.9773 -0.899505 --10.4669 28.6483 0.0581008 --10.4812 28.6661 0.60341 --10.2817 28.2106 1.14726 --10.84 29.4319 1.71284 --10.8799 29.5054 2.27694 --10.8827 29.4964 2.8398 --10.8854 29.4884 3.40341 --10.8882 29.4805 3.96832 --10.8944 29.4809 4.53585 --10.8689 29.4088 5.09568 --10.8593 29.3741 5.661 --10.7235 29.0595 6.1783 --1.3402 8.3487 4.88704 --1.37499 8.41798 5.10899 --1.893 9.54392 5.88419 --1.88182 9.51332 6.08975 --2.00165 9.77064 6.46033 --1.7686 9.25773 6.39318 --1.3307 8.29748 6.02989 --1.34938 8.33412 6.26052 --1.63818 8.95642 6.88804 --1.89438 9.50595 7.50356 --1.4495 8.53516 7.05743 --1.30032 8.20444 7.04276 --0.00831765 5.39864 5.09162 -0.165231 5.01841 4.93732 -0.250067 4.83222 4.92697 -0.227546 4.8757 5.10874 --0.147071 5.6819 5.98232 --0.215081 5.82383 6.29398 --0.120541 5.61598 6.28322 -0.168758 4.98687 5.84286 -0.341305 4.61165 5.62654 -0.406688 4.46666 5.63445 -0.409796 4.456 5.78733 -0.496208 4.26583 5.73902 -0.517677 4.21469 5.8464 -0.59712 4.04129 5.80412 -0.407501 4.44389 6.49112 -0.422113 4.40835 6.64163 -0.838592 3.51181 5.61546 -0.853137 3.47771 5.73437 -0.935022 3.29882 5.64509 -0.939791 3.28284 5.79382 -0.728685 3.72784 6.68245 -0.728423 3.72317 6.89134 -0.761427 3.64796 6.99259 -0.925478 3.29558 6.5997 -0.945302 3.248 6.73635 -1.25842 2.58209 5.68395 -0.952773 3.22076 7.16696 -1.0441 3.02101 7.01255 -1.20791 2.6734 6.5132 -0.818302 3.48016 8.61348 -1.33732 2.3918 6.35219 -1.43454 2.183 6.08314 -1.47963 2.0846 6.0752 -1.49765 2.04022 6.21351 -1.54954 1.92587 6.15544 -1.60153 1.81339 6.09447 -1.67594 1.65432 5.86991 -1.64478 1.71181 6.36434 -1.75536 1.47891 5.84776 -1.78908 1.40434 5.882 -1.74688 1.48029 6.55293 -1.76684 1.42979 6.7524 -1.82655 1.3033 6.60044 -1.80467 1.3347 7.2677 -1.88994 1.15728 6.82779 -1.92718 1.07212 6.89546 -1.96121 0.994533 7.03086 -2.01723 0.875754 6.84792 -2.16639 0.591734 5.02403 -2.08187 0.7213 7.23036 -2.18998 0.520224 5.81543 -2.25372 0.397872 5.00353 -2.28056 0.338218 5.08735 -2.30805 0.274984 5.1402 -2.33071 0.21324 5.62174 --1.05005 8.53196 -0.934525 --1.35457 9.25889 -0.926779 --1.71092 10.1055 -0.91519 --2.21266 11.2994 -0.933333 --2.53974 12.0771 -0.840592 --3.30055 13.8894 -0.861932 --4.41693 16.548 -0.915534 --5.62848 19.432 -0.891041 --12.0221 34.5689 2.1616 --12.5611 35.8317 2.87918 --12.595 35.8946 3.561 --12.6053 35.9009 4.24172 --12.3444 35.2636 4.85469 --12.3495 35.2581 5.52662 --11.2728 32.6851 5.82294 --3.17466 13.4511 4.28804 --2.02246 10.6719 5.57579 --1.24593 8.83882 4.97416 --1.81868 10.1807 5.80977 --1.31812 8.99801 5.4465 --1.23643 8.8005 5.54787 --1.31866 8.98919 5.85464 --1.27962 8.89331 6.01163 --1.2852 8.89942 6.22915 --1.15551 8.59094 6.25479 --1.3676 9.0815 6.78665 --1.40706 9.16742 7.0756 --1.34108 9.0062 7.20195 --1.25058 8.79022 7.28524 --1.22907 8.73247 7.48194 -0.125942 5.56785 5.24896 --1.74665 9.92559 8.94489 --0.0176868 5.89384 5.84253 -0.488489 4.71146 4.98679 -0.545481 4.57568 5.00833 -0.244788 5.26915 5.80246 --0.167126 6.21895 6.89686 -0.433598 4.82241 5.70107 -0.324517 5.07081 6.12727 -0.443273 4.79193 6.00826 -0.575833 4.48055 5.83739 -0.357357 4.98035 6.58831 -0.412607 4.84752 6.62684 -0.539054 4.55072 6.4592 -0.668059 4.24852 6.26687 -0.824863 3.88439 5.97184 -0.941612 3.61177 5.77455 -0.954234 3.57826 5.90285 -1.01449 3.43457 5.86998 -1.07051 3.30278 5.84958 -1.04584 3.35354 6.11491 -1.09052 3.24641 6.13274 -0.686834 4.16062 7.91517 -0.711743 4.09585 8.07545 -1.33877 2.66769 5.68763 -1.37384 2.58277 5.71695 -1.42112 2.47233 5.69157 -1.42766 2.45172 5.85012 -1.45503 2.3853 5.91965 -1.4789 2.32596 6.00618 -1.51573 2.23756 6.02815 -1.55434 2.1465 6.03913 -1.58417 2.07222 6.09451 -1.60461 2.01973 6.21377 -1.75582 1.68072 5.48831 -1.74877 1.69016 5.77126 -1.71951 1.74756 6.24566 -1.78796 1.58966 6.01718 -1.84532 1.45861 5.85145 -1.82387 1.49509 6.33833 -1.83421 1.46307 6.59534 -1.87445 1.3671 6.59003 -1.90637 1.29141 6.6804 -2.01431 1.05396 5.88702 -1.96567 1.14255 6.92644 -2.00767 1.04313 6.91457 -2.06044 0.921094 6.7226 -2.20103 0.634587 5.02015 -2.15922 0.69757 6.34042 -2.21399 0.577204 5.92168 -2.24723 0.497819 5.91881 -2.24844 0.468789 6.93277 -2.33272 0.316058 5.16922 -2.36074 0.24928 5.17148 --0.669477 8.33209 -0.941624 --0.93973 9.02968 -0.937612 --1.25778 9.84758 -0.932325 --1.65114 10.8613 -0.93246 --2.03583 11.8496 -0.890559 --2.46365 12.9508 -0.828434 --3.30867 15.1266 -0.861861 --4.46029 18.0951 -0.899466 --5.60917 21.05 -0.824683 --11.5368 36.2977 -0.148178 --11.5386 36.2802 0.528329 --11.5679 36.3366 1.20433 --11.6214 36.4568 1.88409 --11.6318 36.4621 2.56426 --11.6333 36.4477 3.24431 --11.6453 36.4593 3.92738 --11.6573 36.4699 4.6126 --11.6754 36.4962 5.30241 --2.76421 13.5976 3.63692 --2.67535 13.3609 3.84679 --2.76891 13.5937 4.15889 --2.95333 14.057 4.54028 --2.13442 11.9567 4.2433 --1.60245 10.562 5.14515 --1.53365 10.3795 5.29194 --2.04962 11.686 6.08829 --1.73375 10.8745 5.96757 --1.13883 9.35862 5.47304 --1.09855 9.25049 5.62731 --0.95555 8.88147 5.64181 --0.934303 8.82149 5.81329 --1.42216 10.053 6.73185 --1.3112 9.76278 6.7989 --1.24412 9.58655 6.92728 -0.248031 5.80813 4.70074 -0.202818 5.92018 4.92307 -0.207396 5.90177 5.06301 -0.217377 5.87375 5.19777 -0.258355 5.76677 5.27499 -0.281114 5.70365 5.38505 -0.164447 5.99431 5.7845 -0.41635 5.35398 5.41617 -0.713134 4.60519 4.91775 -0.791016 4.4059 4.87737 -0.298828 5.63447 6.17588 -0.391511 5.39888 6.12945 -0.3902 5.39582 6.30883 -0.428594 5.29531 6.39196 -0.647578 4.74322 5.98291 -0.519076 5.05926 6.51558 --0.213824 6.87293 9.10518 -0.649526 4.71745 6.69945 -0.83568 4.25104 6.29937 -1.02083 3.78716 5.86813 -0.937891 3.98523 6.32253 -1.13071 3.50452 5.82438 -1.18007 3.3776 5.813 -1.20374 3.31514 5.89699 -1.27957 3.12182 5.77222 -1.15674 3.42 6.4575 -0.979993 3.84748 7.41891 -1.0713 3.61516 7.25479 -1.46992 2.63535 5.66035 -1.51315 2.52418 5.63563 -1.54526 2.44026 5.66123 -1.64149 2.20159 5.3548 -1.66157 2.14684 5.42822 -1.68601 2.08287 5.48273 -1.68319 2.08483 5.70082 -1.64888 2.16148 6.13257 -1.79509 1.80466 5.42605 -1.84079 1.69002 5.3344 -1.87031 1.61446 5.34328 -1.82928 1.70378 5.88099 -1.83592 1.68011 6.09947 -1.89935 1.52292 5.85888 -1.93902 1.42216 5.79684 -1.94576 1.3978 6.04198 -1.96365 1.34888 6.20995 -1.97393 1.31526 6.47504 -2.06473 1.09776 5.82029 -2.01316 1.20198 6.8881 -2.05628 1.09257 6.81784 -2.11094 0.958522 6.54775 -2.08862 0.989143 7.54256 -2.19102 0.756565 6.37542 -2.24039 0.639017 6.04739 -2.27655 0.549544 5.94577 -2.29655 0.488749 6.28141 -2.33981 0.388319 5.92706 -2.38475 0.29188 5.2507 -2.41147 0.222659 5.22235 --0.298697 8.10219 -0.93906 --0.542725 8.78678 -0.942727 --0.821062 9.566 -0.940959 --1.15091 10.4868 -0.937531 --1.55684 11.6237 -0.937507 --1.8059 12.3153 -0.827035 --1.92095 12.6334 -0.641204 --1.87581 12.4986 -0.392138 --1.92232 12.6225 -0.173984 --1.93118 12.6395 0.0565377 --1.89454 12.5307 0.294579 --1.92394 12.6059 0.520602 --11.693 39.9439 0.12873 --11.6962 39.9315 0.865574 --1.92389 12.584 1.21063 --1.94127 12.6256 1.44171 --1.92013 12.5593 1.66918 --1.92123 12.5557 1.89894 --1.925 12.5574 2.12968 --11.8217 40.1451 5.32349 --11.7479 39.9166 6.04471 --12.1233 40.8669 9.25661 --3.08546 15.7329 4.47483 --12.1277 40.8326 10.8242 --1.80571 12.164 4.15163 --2.98655 15.43 5.30384 --2.40756 13.7909 5.94688 --2.42819 13.8393 6.24924 --0.795288 9.3193 4.71432 --0.714442 9.0916 4.81258 --0.778972 9.2613 5.08169 --0.758721 9.20139 5.25339 --0.710441 9.06164 5.38643 --0.745 9.14917 5.63301 --0.825463 9.36566 5.95622 --0.98533 9.79826 6.41462 --0.975291 9.76501 6.62594 --0.920144 9.60598 6.76307 --0.685113 8.95299 6.58403 --0.455177 8.31651 6.38781 --0.637873 8.81124 6.93845 --0.618562 8.75113 7.12538 --0.956273 9.66729 8.03622 -0.483263 5.72519 5.27687 --2.03742 12.6044 10.9101 -0.403967 5.93086 5.76771 -0.55263 5.52197 5.59188 -0.943649 4.45038 4.8074 -0.97138 4.37372 4.87292 -0.560739 5.48497 6.06912 -1.0077 4.26478 5.04639 -0.98341 4.32664 5.25291 -0.971082 4.35646 5.43476 -0.628906 5.27751 6.60062 -0.914894 4.49801 5.91476 -0.978208 4.32209 5.88305 -0.824876 4.7297 6.55319 -1.0504 4.11693 5.98026 -1.11875 3.92792 5.91312 -1.14727 3.84736 5.98193 -1.2537 3.55582 5.75461 -1.37196 3.23323 5.46154 -1.33677 3.3225 5.76251 -1.37621 3.21219 5.77052 -1.47653 2.93835 5.50824 -1.42363 3.074 5.91391 -1.13388 3.83795 7.45471 -1.19295 3.67508 7.41799 -1.56899 2.674 5.77161 -1.59987 2.58625 5.7995 -1.71522 2.2768 5.36334 -1.72571 2.24195 5.48231 -1.75495 2.1609 5.50178 -1.77995 2.09042 5.547 -1.79132 2.05288 5.67361 -1.85174 1.89145 5.48552 -1.89602 1.7705 5.38608 -1.91506 1.71493 5.46185 -1.93317 1.65985 5.54631 -1.73765 2.15053 7.41559 -1.95803 1.58297 5.84676 -1.99473 1.48191 5.79537 -1.95712 1.56755 6.46519 -2.03307 1.36861 6.02491 -2.07211 1.26021 5.9295 -2.10792 1.16236 5.86083 -2.13793 1.0792 5.85877 -2.12653 1.09245 6.43572 -2.17633 0.9607 6.16566 -2.20312 0.88447 6.23878 -2.22822 0.81025 6.35036 -2.26237 0.716499 6.30163 -2.31024 0.59652 5.90255 -2.328 0.534916 6.1989 -2.36915 0.432642 5.84525 -2.39663 0.354434 5.87931 -2.43615 0.263762 5.25198 -0.178326 7.49661 -0.979858 -0.0135421 7.99972 -0.966525 --0.179167 8.58768 -0.955036 --0.417428 9.31734 -0.953052 --0.685461 10.1335 -0.941567 --1.04122 11.2229 -0.949515 --1.35288 12.1752 -0.895312 --1.73065 13.3255 -0.83479 --2.42197 15.4407 -0.851732 --3.44557 18.5715 -0.897919 --4.48162 21.7358 -0.832108 --11.8796 44.3078 0.459938 --1.53658 12.6463 1.78684 --13.2915 48.3915 7.52385 --2.45004 15.3677 3.93298 --2.45191 15.363 4.22098 --2.48827 15.4651 4.53524 --2.35263 15.043 4.72562 --2.33662 14.9875 5.00025 --2.45066 15.3225 5.38739 --2.44647 15.3017 5.68154 --1.41292 12.1661 4.95673 --1.36348 12.008 5.14473 --1.3579 11.9821 5.37765 --1.38939 12.068 5.65602 --0.382577 9.02573 4.65711 --0.559979 9.55257 5.07297 --0.533384 9.46579 5.23642 --0.45459 9.22162 5.32389 --0.469242 9.25954 5.54471 --0.562212 9.53215 5.8922 --0.592773 9.61823 6.15484 --0.725303 10.0073 6.59745 --0.577408 9.55748 6.56661 --0.895751 10.5037 7.37841 --0.175056 8.33779 6.24788 --0.21146 8.442 6.525 --0.331197 8.79293 6.98319 -0.378836 6.66333 5.68127 -0.413723 6.5536 5.77639 -0.394776 6.60361 5.99326 -0.226435 7.10111 6.5768 -0.383148 6.62785 6.38704 -0.608689 5.95098 5.99799 -1.09688 4.4936 4.87446 -1.11077 4.4505 4.97278 -1.13116 4.38391 5.05048 -1.18016 4.23421 5.04463 -1.11006 4.43751 5.39765 -1.12226 4.39823 5.51052 -1.11668 4.40804 5.68119 -1.10865 4.42582 5.86822 -1.17694 4.21952 5.79611 -1.29458 3.8675 5.53593 -1.39141 3.58079 5.33358 -1.24278 4.01189 6.0585 -1.398 3.55116 5.61383 -1.47609 3.31567 5.45047 -1.50746 3.21969 5.47486 -1.54212 3.11356 5.4805 -1.57677 3.00731 5.48374 -1.48119 3.28071 6.10695 -1.54924 3.07667 5.95894 -1.59394 2.94148 5.91667 -1.63941 2.80364 5.86231 -1.66582 2.72315 5.90971 -1.81701 2.28108 5.22966 -1.85504 2.16889 5.1781 -1.86364 2.13606 5.29499 -1.89248 2.05 5.29378 -1.79901 2.30845 6.12387 -1.93077 1.92832 5.415 -1.94461 1.88357 5.52062 -1.97402 1.79171 5.50437 -2.002 1.7078 5.50497 -1.80733 2.24061 7.43585 -2.01062 1.66769 5.92008 -2.07808 1.47245 5.54436 -2.0797 1.46135 5.80792 -2.10664 1.37664 5.81127 -2.11659 1.34159 6.02678 -2.15017 1.23993 5.95952 -2.18054 1.14832 5.92913 -2.18069 1.13506 6.32928 -2.22236 1.01228 6.12912 -2.2511 0.925018 6.12377 -2.26454 0.87541 6.41406 -2.28129 0.815065 6.69413 -2.34275 0.650514 5.93869 -2.37145 0.565451 5.89668 -2.39927 0.481857 5.86302 -2.42402 0.404824 5.9377 -2.4494 0.324192 5.98101 -2.48573 0.236221 5.28288 -0.479009 7.33382 -0.983643 -0.336779 7.81245 -0.971287 -0.168668 8.37671 -0.962634 --0.0360289 9.06519 -0.961495 --0.27245 9.85805 -0.957123 --0.562946 10.8335 -0.958087 --0.905039 11.9818 -0.95282 --1.33433 13.4272 -0.950441 --1.70712 14.6744 -0.869591 --2.51535 17.3913 -0.910059 --3.41073 20.3999 -0.879061 --16.8515 65.5432 -0.381273 --1.78666 14.7807 3.66442 --1.82348 14.8929 3.96147 --1.82438 14.8887 4.23873 --1.78804 14.7574 4.48799 --1.7807 14.7243 4.75979 --1.77024 14.6768 5.02887 --0.47504 10.3596 4.03603 --0.499394 10.4355 4.26108 --0.526387 10.5168 4.49289 --0.351552 9.93051 4.49328 --1.07235 12.3123 5.58836 --0.394654 10.0588 4.94508 --0.414123 10.1156 5.17613 --0.311482 9.77133 5.23589 --0.480333 10.3199 5.69637 --0.731867 11.1442 6.31638 --0.245556 9.52876 5.74439 --0.58828 10.6516 6.5496 --0.497267 10.3458 6.62258 -0.101486 8.36424 5.72246 -0.151628 8.19231 5.81582 -0.0915364 8.38203 6.12977 -0.0986179 8.35167 6.31503 -0.12397 8.26218 6.46281 -0.637854 6.57202 5.49057 -0.624816 6.60557 5.68597 -0.718841 6.29403 5.62654 -0.642195 6.53728 5.98856 -0.851082 5.84904 5.61291 -0.448711 7.15693 6.88088 -0.474879 7.06562 7.01322 -1.2549 4.51784 4.92869 -1.00134 5.33533 5.8334 -1.01832 5.27573 5.94673 -1.22681 4.59186 5.43631 -1.22972 4.5787 5.57911 -1.26799 4.44808 5.60094 -1.35351 4.1687 5.45169 -1.36449 4.12629 5.56052 -1.42019 3.94256 5.50352 -1.49878 3.68205 5.34188 -1.54453 3.53096 5.30399 -1.52834 3.57682 5.52133 -1.5543 3.48921 5.56628 -1.49697 3.66609 5.98878 -1.51212 3.61012 6.09223 -1.49865 3.64849 6.34387 -1.59371 3.33953 6.05462 -1.56367 3.42762 6.39886 -1.70949 2.95672 5.79837 -1.76834 2.76622 5.64916 -1.80235 2.65165 5.62549 -1.88981 2.3711 5.27293 -1.93695 2.21737 5.14294 -1.91689 2.27485 5.44835 -2.00907 1.98109 4.99698 -2.00283 1.9931 5.2113 -2.02939 1.90355 5.19747 -2.02258 1.9195 5.45015 -2.04504 1.84197 5.47161 -1.79585 2.59464 7.866 -2.09345 1.68053 5.49117 -2.07602 1.72381 5.89759 -2.14576 1.50514 5.45662 -2.1779 1.39833 5.36459 -2.19726 1.33345 5.41488 -2.21082 1.28327 5.53188 -2.20737 1.28078 5.88207 -2.24125 1.17159 5.76431 -2.22201 1.21373 6.42881 -2.26067 1.08917 6.2498 -2.29385 0.98377 6.14698 -2.3085 0.926663 6.36844 -2.35091 0.794672 6.02386 -2.38235 0.696613 5.88495 -2.40708 0.611314 5.8536 -2.43059 0.53348 5.89038 -2.44705 0.466366 6.19542 -2.47812 0.37157 5.93981 -2.50143 0.290022 5.98238 -0.765958 7.19271 -0.991689 -0.641765 7.65508 -0.981881 -0.502137 8.17666 -0.970053 -0.328837 8.82113 -0.968502 -0.122097 9.59182 -0.970584 --0.120552 10.4972 -0.971186 --0.407256 11.5678 -0.968248 --0.74533 12.8316 -0.957367 --1.18001 14.452 -0.950728 --1.7617 16.6225 -0.952228 --4.69252 27.5547 -0.78153 --3.63122 23.5029 1.59351 --3.64029 23.5173 2.0155 --1.39474 15.0266 4.95407 --0.206447 10.6291 3.99205 --0.187409 10.5486 4.17147 --0.16651 10.4659 4.34898 --0.17596 10.491 4.56218 --0.129093 10.3107 4.70454 --0.0994039 10.1925 4.8657 --0.0825073 10.1262 5.04564 --0.292273 10.8865 5.57765 --0.20546 10.5603 5.65907 --0.128515 10.2691 5.74676 -0.112818 9.37612 5.5301 -0.174232 9.14293 5.61536 --0.73165 12.4491 7.58954 -0.388204 8.34586 5.57973 -0.330195 8.55346 5.89279 -0.295471 8.66932 6.16412 -0.272361 8.74661 6.42032 -0.291583 8.67035 6.58462 -0.365835 8.3893 6.61055 -0.397276 8.26948 6.74074 -0.874531 6.52787 5.67721 -0.869241 6.54136 5.86191 -1.03608 5.9304 5.5574 -1.11033 5.65621 5.49899 -0.953907 6.21379 6.13555 -1.25947 5.10488 5.34387 -1.41632 4.53251 4.97616 -1.34126 4.79933 5.37035 -1.31879 4.87311 5.59678 -1.30611 4.912 5.79933 -1.30648 4.905 5.96197 -1.32216 4.8411 6.06801 -1.59897 3.848 5.12909 -1.59992 3.83646 5.26161 -1.63675 3.70129 5.25074 -1.67903 3.54303 5.20561 -1.67047 3.56875 5.39025 -1.6256 3.72417 5.75913 -1.59434 3.82716 6.07872 -1.65126 3.61847 5.96477 -1.67191 3.54041 6.03402 -1.69963 3.43372 6.06037 -1.56126 3.91472 7.03547 -1.60599 3.74732 6.99107 -1.82511 2.97365 5.87612 -1.89326 2.72964 5.63005 -1.91379 2.6514 5.67509 -1.99467 2.36322 5.30242 -2.02242 2.26105 5.27829 -2.1136 1.93865 4.77416 -2.12682 1.88757 4.83214 -2.1023 1.96551 5.20086 -2.10424 1.95074 5.37058 -2.1111 1.92028 5.513 -2.1372 1.82414 5.48728 -2.08958 1.97447 6.17503 -2.17586 1.67907 5.56208 -2.23466 1.47447 5.16887 -2.23028 1.47864 5.44995 -2.24907 1.40587 5.48201 -2.26724 1.33805 5.53205 -2.27263 1.30971 5.75598 -2.28119 1.26919 5.96065 -2.30398 1.1825 5.95962 -2.31975 1.11855 6.08479 -2.33957 1.04283 6.15974 -2.35223 0.98587 6.38181 -2.3651 0.928322 6.65287 -2.42773 0.730403 5.73164 -2.45822 0.626408 5.47189 -2.4772 0.554857 5.52872 -2.48392 0.509267 6.03342 -2.51353 0.411622 5.71859 -2.53683 0.328709 5.57179 -2.55321 0.254868 5.94335 -1.0424 7.04338 -0.996444 -0.931373 7.5086 -0.993989 -0.80443 8.04193 -0.992551 -0.658139 8.65269 -0.990758 -0.493593 9.342 -0.98447 -0.294752 10.1766 -0.983043 -0.0534139 11.1861 -0.983869 --0.22695 12.361 -0.976185 --0.570508 13.7986 -0.965089 --1.03858 15.7615 -0.970202 --1.61709 18.1814 -0.95584 --5.61876 34.9425 -0.931435 --11.1989 58.19 1.91639 -0.156987 10.5533 3.65489 -0.068939 10.9113 3.95018 -0.0884393 10.8218 4.13074 -0.178024 10.4416 4.2192 -0.091666 10.7926 4.53715 -0.13737 10.5932 4.67805 -0.232507 10.1912 4.73819 -0.0219496 11.0533 5.27963 --0.0102576 11.1773 5.55544 -0.0536816 10.901 5.66613 -0.0883401 10.7493 5.82499 -0.3882 9.51163 5.4629 -0.456259 9.2247 5.52452 -0.474814 9.13806 5.68101 -0.523621 8.92791 5.77055 -0.537529 8.86305 5.93593 -0.572959 8.71113 6.05064 -0.561364 8.74925 6.27934 -0.626201 8.47731 6.31572 -0.654372 8.35347 6.44163 -0.586496 8.62295 6.83763 -0.780609 7.82139 6.48499 -1.35468 5.48392 4.95184 -1.28739 5.75018 5.30375 -1.23213 5.96857 5.63558 -1.03714 6.75112 6.45333 -1.21841 6.00916 6.01246 -1.2393 5.9164 6.10926 -1.57691 4.54956 5.03013 -1.51699 4.78717 5.3998 -1.53539 4.7045 5.4744 -1.51662 4.77312 5.70246 -1.44557 5.05105 6.16396 -1.61875 4.35258 5.57894 -1.72433 3.92277 5.25229 -1.74132 3.85079 5.31827 -1.72492 3.90908 5.54341 -1.79001 3.64172 5.3688 -1.73655 3.84885 5.79929 -1.74632 3.80268 5.91172 -1.79719 3.59335 5.79785 -1.8117 3.52846 5.88242 -1.86029 3.33125 5.76747 -1.92774 3.05919 5.52138 -1.94306 2.9924 5.58882 -1.95768 2.93004 5.66376 -1.98317 2.82199 5.65995 -1.98422 2.80922 5.82848 -1.98928 2.78133 5.98019 -2.16443 2.09612 4.81559 -2.16564 2.08743 4.96549 -2.20291 1.93742 4.81757 -2.22669 1.83813 4.76589 -2.21535 1.87662 5.04284 -2.19518 1.94343 5.41478 -2.13353 2.16551 6.23789 -2.14508 2.11346 6.37552 -2.29734 1.53426 4.95418 -2.30417 1.50354 5.0914 -2.34043 1.35976 4.86559 -2.32752 1.39668 5.25066 -2.37479 1.21679 4.85622 -2.39156 1.14647 4.85434 -2.33287 1.34021 6.01963 -2.36464 1.2167 5.85344 -2.36827 1.18683 6.14553 -2.39363 1.08296 6.06393 -2.42132 0.972885 5.92093 -2.44227 0.888519 5.92401 -2.47198 0.772207 5.65765 -2.4883 0.702904 5.75655 -2.51422 0.603118 5.53567 -2.53263 0.526094 5.54211 -2.54955 0.453058 5.60694 -2.56711 0.376437 5.6407 -2.58681 0.29618 5.54306 -1.47029 6.13664 -1.00084 -1.39739 6.48722 -0.998158 -1.31488 6.87753 -0.995051 -1.22477 7.30755 -0.98933 -1.10903 7.86158 -1.00181 -0.996444 8.39957 -0.990303 -0.852076 9.09212 -0.995246 -0.685607 9.8825 -0.996209 -0.489996 10.8201 -0.997164 -0.268575 11.8762 -0.985415 --0.0321029 13.3122 -0.995103 --0.392636 15.0323 -0.992641 --0.882116 17.3694 -1.00225 --0.929739 17.5851 -0.7149 --0.944858 17.6414 -0.407562 --0.899234 17.4091 -0.0804228 --8.5553 53.989 -0.532354 --9.5792 58.736 2.45993 -0.749418 9.34559 3.95034 -0.761951 9.27533 4.10628 -0.752202 9.31364 4.30051 -0.743226 9.34799 4.49694 -0.343677 11.2087 5.42786 -0.369613 11.0773 5.60041 -0.419666 10.8356 5.72193 --0.0516069 13.0249 6.96257 -0.734587 9.34288 5.45524 -0.760412 9.21262 5.5906 --0.538575 15.2553 8.99079 -0.800547 9.00813 5.88488 -0.646096 9.71585 6.49703 -0.916255 8.44832 5.96292 -0.925912 8.39583 6.12983 -0.962597 8.21734 6.216 -0.930338 8.35533 6.51195 -1.02575 7.90507 6.40786 -1.0757 7.66893 6.43999 -1.39579 6.18179 5.52269 -1.38758 6.2128 5.71337 -1.35297 6.3618 6.00579 -1.51161 5.62642 5.56918 -1.52736 5.54797 5.66492 -1.70112 4.74138 5.10513 -1.73926 4.56249 5.08408 -1.65544 4.93988 5.59356 -1.72422 4.61678 5.43237 -1.73382 4.56831 5.5386 -1.74855 4.491 5.61557 -1.73582 4.54393 5.83825 -1.85393 4.00071 5.38401 -1.91806 3.70312 5.18525 -1.88287 3.85545 5.52398 -1.87321 3.89366 5.73664 -1.86263 3.93245 5.9599 -1.87663 3.85942 6.04147 -1.81481 4.13146 6.61772 -1.96796 3.4356 5.79814 -2.02526 3.17558 5.58008 -2.04993 3.05497 5.56478 -2.06024 3.00277 5.65737 -2.07737 2.91848 5.69772 -2.10079 2.8095 5.69308 -2.26047 2.0984 4.5538 -2.26452 2.07422 4.65768 -2.27007 2.04249 4.75281 -2.24743 2.13521 5.11829 -2.28587 1.95933 4.91557 -2.30461 1.87319 4.90023 -2.32383 1.77998 4.8646 -2.34861 1.66752 4.77101 -2.35193 1.64505 4.90856 -2.3698 1.56163 4.88638 -2.37301 1.53661 5.03296 -2.39784 1.42631 4.92244 -2.389 1.45159 5.25959 -2.42584 1.29075 4.95361 -2.4435 1.206 4.90447 -2.39866 1.37554 5.92236 -2.40651 1.32563 6.09847 -2.4321 1.2119 5.9804 -2.4499 1.12492 5.98763 -2.48297 0.985696 5.66781 -2.49616 0.91576 5.75014 -2.51401 0.831538 5.73211 -2.53782 0.727988 5.53385 -2.55572 0.64662 5.49255 -2.56903 0.577385 5.58916 -2.58322 0.50553 5.69471 -2.60154 0.420467 5.57939 -2.61802 0.343372 5.60227 -2.6327 0.265791 5.67385 -2.40006 2.13771 -0.976156 -2.38883 2.19986 -0.970409 -1.80612 5.43009 -1.00432 -1.75421 5.71406 -1.00475 -1.69948 6.0174 -1.00219 -1.6396 6.35119 -0.998792 -1.57202 6.72354 -0.995922 -1.49543 7.14551 -0.994417 -1.40931 7.62517 -0.994068 -1.30511 8.20382 -1.00174 -1.20007 8.78352 -0.989439 -1.06204 9.54778 -0.996953 -0.906048 10.4118 -0.997309 -0.723002 11.4241 -0.993921 -0.50623 12.6232 -0.985327 -0.213766 14.2442 -0.995458 --0.180105 16.4244 -1.01914 --0.441659 17.8661 -0.885138 --0.41788 17.7195 -0.556126 --1.28721 22.5345 -0.596034 --1.31156 22.6467 -0.205261 -0.728776 11.1009 4.38894 -0.701321 11.2386 4.64571 -1.01871 9.49905 4.25797 -1.00696 9.55305 4.46276 -1.0373 9.38274 4.58483 -1.0569 9.2651 4.72442 -1.06677 9.2002 4.88412 -1.0664 9.19545 5.07109 -1.09331 9.0351 5.18749 -1.04269 9.29784 5.50899 -1.08632 9.05315 5.58335 -1.07402 9.11247 5.81402 -1.14815 8.70144 5.78736 -1.43446 7.15253 5.08012 -1.1441 8.70148 6.18779 -1.47368 6.92489 5.27051 -1.5479 6.52129 5.17151 -1.63319 6.05701 5.01502 -1.67677 5.81881 4.99774 -1.66569 5.86885 5.1843 -1.61594 6.12701 5.53576 -1.5771 6.3197 5.85471 -1.69168 5.70784 5.52902 -1.7403 5.44095 5.46525 -1.75162 5.37192 5.56367 -1.88312 4.6713 5.08681 -1.89732 4.58638 5.15145 -1.87434 4.69881 5.40843 -1.89852 4.56706 5.43073 -1.87325 4.68902 5.7153 -1.8988 4.54768 5.72805 -1.89902 4.53843 5.88569 -1.93727 4.33217 5.81833 -1.88894 4.57166 6.28043 -1.86978 4.66098 6.58177 -1.90209 4.4853 6.5574 -1.94462 4.25366 6.4488 -1.97527 4.0846 6.41441 -1.97185 4.09346 6.62937 -1.99223 3.98001 6.67232 -2.13735 3.22873 5.71636 -2.17976 3.00136 5.53175 -2.16898 3.05014 5.79436 -2.17799 2.993 5.88701 -2.34135 2.15921 4.56389 -2.34677 2.12607 4.65058 -2.32683 2.21615 4.98634 -2.32781 2.20354 5.13783 -2.36134 2.0285 4.94592 -2.38829 1.88889 4.81309 -2.37653 1.93535 5.10877 -2.41142 1.75443 4.86056 -2.42063 1.70288 4.9244 -2.43997 1.59856 4.84677 -2.45799 1.50415 4.78548 -2.45293 1.51533 5.04519 -2.47302 1.40876 4.94324 -2.49842 1.2814 4.75235 -2.46774 1.40933 5.49453 -2.4828 1.32723 5.49554 -2.49253 1.26576 5.58259 -2.50099 1.21277 5.71769 -2.49494 1.22228 6.20547 -2.56246 0.915309 4.97228 -2.55909 0.909597 5.37889 -2.57633 0.820963 5.29139 -2.58038 0.781827 5.57913 -2.59547 0.701145 5.56846 -2.60743 0.628544 5.63601 -2.62103 0.551786 5.68243 -2.6373 0.465872 5.56767 -2.65096 0.389467 5.62128 -2.66594 0.309966 5.5736 -2.48183 2.19843 -0.986992 -2.4726 2.26052 -0.980156 -2.04029 5.09573 -1.00927 -2.0017 5.35172 -1.01163 -1.95922 5.62606 -1.01255 -1.91694 5.90285 -1.00439 -1.86901 6.21893 -0.99981 -1.81149 6.59238 -1.00278 -1.75078 6.99531 -1.00177 -1.684 7.42998 -0.995156 -1.60011 7.98027 -1.004 -1.51402 8.54254 -0.996297 -1.40427 9.26094 -1.00428 -1.281 10.0698 -1.00559 -1.13563 11.0264 -1.00648 -0.960623 12.1714 -1.00577 -0.739984 13.6218 -1.01159 -0.465243 15.4188 -1.01308 -0.104056 17.7895 -1.01823 --0.619729 22.5203 -0.777414 --0.611716 22.4384 -0.376963 -0.989218 11.6419 4.4316 -1.03398 11.3456 4.55774 -1.34398 9.34117 4.09996 -1.36329 9.20304 4.23044 -1.35213 9.26694 4.43355 -1.37928 9.07807 4.54143 -0.88457 12.2315 6.03848 -1.30679 9.52249 5.10169 -1.28747 9.63014 5.34777 -1.31686 9.42897 5.45304 -1.33853 9.28044 5.57911 -1.36736 9.08702 5.67829 -1.37675 9.01416 5.83869 -1.67154 7.13886 4.97189 -1.67804 7.08681 5.10336 -1.65465 7.22603 5.35402 -1.64123 7.30091 5.57332 -1.75571 6.57043 5.26247 -1.75491 6.56118 5.41893 -1.85787 5.90486 5.11293 -1.89241 5.68245 5.09976 -1.83172 6.05076 5.5354 -1.96531 5.2058 5.02257 -1.93625 5.38043 5.31289 -1.95784 5.23827 5.34473 -1.85718 5.85094 6.04754 -2.05427 4.61886 5.08734 -2.04226 4.68503 5.29464 -2.05883 4.57483 5.33767 -2.07602 4.45908 5.37096 -2.07684 4.44487 5.51012 -2.05349 4.57998 5.81936 -2.07072 4.4645 5.85803 -2.10024 4.27781 5.8105 -2.10391 4.24503 5.94284 -2.08476 4.34995 6.25523 -2.09325 4.28336 6.35886 -2.08284 4.33757 6.63032 -2.08944 4.28678 6.76703 -1.80337 5.99072 9.48815 -2.27611 3.14172 5.46582 -2.28061 3.10718 5.58393 -2.28918 3.04422 5.65954 -2.27722 3.10445 5.94944 -2.43653 2.15192 4.45186 -2.42897 2.19126 4.66956 -2.45024 2.05524 4.56183 -2.41155 2.27709 5.1656 -2.40502 2.29912 5.39956 -2.43575 2.11234 5.18992 -2.43395 2.11567 5.39653 -2.45109 2.00581 5.34602 -2.39444 2.31193 6.35289 -2.40108 2.26071 6.50124 -2.53131 1.51558 4.68041 -2.53295 1.49708 4.8352 -2.53448 1.47606 4.99992 -2.53047 1.48566 5.28964 -2.55613 1.33491 5.03182 -2.54997 1.35301 5.38932 -2.55222 1.32334 5.60282 -2.5688 1.22313 5.52381 -2.58705 1.10832 5.35459 -2.60136 1.01903 5.29078 -2.61215 0.9473 5.31384 -2.62929 0.846755 5.14783 -2.62813 0.827877 5.55457 -2.63425 0.776622 5.80274 -2.65621 0.65719 5.42356 -2.6642 0.593741 5.58991 -2.6735 0.522163 5.71531 -2.68852 0.434803 5.56989 -2.69987 0.356523 5.58286 -2.70667 0.282703 6.0443 -2.57455 2.17403 -0.981818 -2.56737 2.23695 -0.975941 -2.27445 4.57912 -1.00807 -2.24746 4.79515 -1.01316 -2.21952 5.01159 -1.01116 -2.18937 5.25804 -1.01351 -2.15686 5.51488 -1.01145 -2.12259 5.79197 -1.00767 -2.08267 6.10832 -1.00798 -2.03994 6.44412 -1.00381 -1.99363 6.82023 -1.00029 -1.94025 7.24485 -0.997895 -1.87951 7.73003 -0.996816 -1.80845 8.29293 -0.998672 -1.72967 8.92668 -0.997138 -1.63172 9.70755 -1.00528 -1.52227 10.5789 -1.00386 -1.38872 11.648 -1.00736 -1.22455 12.9556 -1.01172 -1.02473 14.5505 -1.01129 -0.746054 16.7799 -1.03428 -0.428725 19.3099 -1.01116 -0.00790129 22.6439 -0.574866 --0.0224168 22.8564 -0.190975 -1.31459 11.8062 4.80394 -1.26807 12.1512 5.14951 -1.65192 9.15037 4.28853 -1.25812 12.1952 5.64093 -1.22713 12.4172 5.9737 -1.62731 9.30646 4.89812 -1.64341 9.16531 5.02447 -1.62817 9.27446 5.26513 -1.59835 9.48564 5.56328 -1.68217 8.83005 5.43091 -1.88502 7.2549 4.78068 -1.65301 9.01976 5.92385 -1.66739 8.89913 6.05751 -1.67828 8.80242 6.20395 -1.8637 7.37276 5.51317 -1.77267 8.05192 6.13244 -1.93514 6.80219 5.48226 -1.97842 6.46418 5.41382 -2.03916 5.99326 5.23522 -2.08298 5.65045 5.13146 -2.07612 5.6879 5.3121 -2.14784 5.14269 5.02403 -2.14643 5.14085 5.16741 -2.10464 5.44271 5.58044 -2.13837 5.17911 5.50431 -2.16255 4.98494 5.48152 -2.22057 4.5427 5.21052 -2.22324 4.51125 5.32799 -2.23475 4.41588 5.38084 -2.20457 4.63048 5.76773 -2.21285 4.56129 5.85907 -2.0303 5.88991 7.57004 -2.2021 4.61471 6.27595 -2.19407 4.66054 6.52287 -2.24912 4.24113 6.18269 -2.24801 4.24055 6.37196 -2.20903 4.50993 6.94256 -2.2318 4.32701 6.9022 -2.31547 3.71395 6.21126 -2.31485 3.70516 6.39733 -2.3916 3.14352 5.70342 -2.32373 3.61425 6.67867 -2.40232 3.0396 5.90648 -2.49178 2.39553 4.94128 -2.50018 2.33212 4.98748 -2.4966 2.34063 5.17503 -2.50015 2.30711 5.29219 -2.49078 2.35903 5.59959 -2.50771 2.23101 5.52665 -2.52862 2.07588 5.37691 -2.48746 2.33494 6.2425 -2.50043 2.23426 6.25064 -2.51313 2.13001 6.24735 -2.52607 2.02913 6.2515 -2.5745 1.69659 5.53115 -2.57533 1.67616 5.74731 -2.5946 1.53085 5.55084 -2.60958 1.42198 5.45705 -2.62045 1.33762 5.44809 -2.62977 1.25926 5.45697 -2.65187 1.10643 5.11237 -2.66199 1.02737 5.08784 -2.67293 0.947197 5.04193 -2.68037 0.884093 5.09323 -2.68157 0.849171 5.36136 -2.69387 0.761759 5.27224 -2.70518 0.676339 5.16141 -2.70684 0.638679 5.55693 -2.71157 0.57884 5.83257 -2.72224 0.49322 5.79784 -2.73501 0.404982 5.61174 -2.74206 0.330766 5.92391 -2.66601 2.16305 -0.99071 -2.65983 2.22588 -0.985437 -2.65303 2.29549 -0.985598 -2.64636 2.36719 -0.983961 -2.63846 2.45243 -0.993993 -2.63146 2.51766 -0.981622 -2.47207 4.15383 -1.00996 -2.4547 4.33027 -1.01279 -2.4375 4.50899 -1.01002 -2.41701 4.71665 -1.01415 -2.39609 4.93351 -1.01542 -2.37287 5.16169 -1.01363 -2.34881 5.40898 -1.01177 -2.32297 5.67649 -1.00888 -2.29205 5.99306 -1.01398 -2.26169 6.30126 -1.00525 -2.22538 6.67747 -1.00762 -2.18635 7.07426 -1.00297 -2.14237 7.5215 -0.998356 -2.08544 8.10393 -1.0139 -2.02927 8.68039 -1.00723 -1.96123 9.37561 -1.00709 -1.88137 10.1899 -1.00721 -1.78606 11.1625 -1.00857 -1.66124 12.443 -1.02793 -1.52348 13.8548 -1.0223 -1.33981 15.7332 -1.02961 -1.10769 18.1005 -1.0276 --0.794122 37.5082 -0.639798 --0.842377 37.9492 0.00224159 -1.60017 12.5255 4.90964 -1.58613 12.6352 5.1844 -1.57932 12.6836 5.4442 -1.57686 12.6891 5.69306 -1.60465 12.3931 5.82643 -1.89557 9.50275 4.87465 -1.92171 9.23402 4.94882 -1.91837 9.24586 5.143 -1.94015 9.02002 5.22711 -1.92803 9.11479 5.46485 -1.94165 8.96635 5.58277 -2.13401 7.08407 4.75407 -1.91061 9.23617 6.13146 -1.9718 8.62209 5.97931 -1.99219 8.40757 6.04716 -1.99235 8.39494 6.23771 -2.01743 8.12893 6.2641 -2.02162 8.06941 6.42418 -2.18339 6.49946 5.50529 -2.25922 5.76497 5.12715 -2.21868 6.13512 5.56376 -2.27533 5.58768 5.29333 -2.26521 5.6674 5.51327 -2.2719 5.58842 5.60761 -2.278 5.51576 5.70715 -2.24629 5.80075 6.13625 -2.20903 6.13684 6.63847 -2.37481 4.56851 5.29174 -2.37852 4.52226 5.39531 -2.39705 4.33552 5.35367 -2.41044 4.19315 5.35105 -2.19806 6.14921 7.72399 -2.34516 4.77099 6.34514 -2.4603 3.703 5.23646 -2.46145 3.67891 5.35898 -2.47293 3.55465 5.35508 -2.47723 3.50265 5.44451 -2.44192 3.81346 6.04588 -2.44059 3.80969 6.23121 -2.45723 3.64246 6.17621 -2.45145 3.6754 6.42885 -2.51883 3.06571 5.64456 -2.5135 3.09146 5.87412 -2.52103 3.01262 5.9319 -2.58884 2.40429 5.01358 -2.60198 2.2797 4.9444 -2.5788 2.46459 5.48919 -2.60437 2.23218 5.20263 -2.5473 2.69617 6.41912 -2.55914 2.57846 6.40629 -2.57793 2.4052 6.25245 -2.58348 2.33971 6.35454 -2.57131 2.41366 6.83981 -2.58874 2.2501 6.69792 -2.62846 1.9048 5.99278 -2.6355 1.83291 6.06874 -2.63667 1.80156 6.28754 -2.67896 1.44958 5.36994 -2.69278 1.32729 5.20643 -2.69568 1.28165 5.34141 -2.6986 1.23547 5.48573 -2.71445 1.10386 5.23786 -2.7225 1.0239 5.21289 -2.73026 0.940896 5.16674 -2.73217 0.903479 5.40566 -2.74099 0.82078 5.3669 -2.74965 0.737032 5.30676 -2.76008 0.64367 5.11562 -2.7529 0.638797 5.95926 -2.76147 0.550838 5.93548 -2.77338 0.454717 5.67027 -2.78078 0.37515 5.71317 -2.78967 0.293462 5.67466 -2.74931 2.19766 -0.98025 -2.74456 2.2681 -0.98147 -2.73863 2.35306 -0.994707 -2.73354 2.41704 -0.984994 -2.72833 2.49649 -0.987153 -2.72214 2.57611 -0.98711 -2.71646 2.66451 -0.991307 -2.70986 2.75409 -0.993051 -2.70272 2.85156 -0.998383 -2.69622 2.9424 -0.994884 -2.65624 3.50616 -1.00203 -2.64654 3.64393 -1.00682 -2.63638 3.79071 -1.01245 -2.62587 3.93096 -1.00854 -2.61392 4.09789 -1.01454 -2.60207 4.26608 -1.0153 -2.59082 4.42669 -1.00638 -2.57624 4.63284 -1.01349 -2.56083 4.84137 -1.0141 -2.54457 5.06896 -1.01583 -2.52842 5.2979 -1.01023 -2.5077 5.58461 -1.01864 -2.48852 5.86282 -1.01433 -2.4657 6.18018 -1.01382 -2.44118 6.51893 -1.00904 -2.41403 6.89692 -1.00476 -2.38344 7.33411 -1.00437 -2.34743 7.83076 -1.00495 -2.3058 8.41678 -1.01048 -2.25987 9.06355 -1.00964 -2.20469 9.83902 -1.01385 -2.13856 10.7645 -1.02034 -2.06329 11.8194 -1.01759 -1.96479 13.2029 -1.0304 -1.84628 14.8669 -1.0345 -1.68212 17.1675 -1.05949 -1.50653 19.6215 -1.02024 -0.874135 28.4277 -0.46687 -0.858213 28.5883 0.0211814 -1.95549 12.5918 5.04255 -1.94042 12.7651 5.34224 -1.96224 12.4534 5.47512 -1.97041 12.3087 5.66279 -2.16665 9.66407 4.83746 -2.19157 9.31163 4.8806 -2.19378 9.25233 5.04249 -2.19638 9.19917 5.20768 -2.19563 9.18841 5.39415 -2.21992 8.84387 5.41388 -2.22588 8.74915 5.55406 -2.24791 8.43372 5.57128 -2.24619 8.43935 5.76355 -2.33126 7.30454 5.27334 -2.32777 7.33104 5.4596 -2.29877 7.67965 5.86012 -2.25525 8.22229 6.41373 -2.29408 7.70249 6.25443 -2.38885 6.46421 5.55026 -2.38132 6.53686 5.77233 -2.41407 6.09928 5.60483 -2.30248 7.50697 6.91337 -2.36248 6.71561 6.46146 -2.38618 6.40238 6.38354 -2.40858 6.08543 6.28979 -2.4333 5.75917 6.17296 -2.52104 4.63579 5.26906 -2.51568 4.69568 5.47923 -2.52745 4.52765 5.46275 -2.50499 4.78314 5.89493 -2.49889 4.84465 6.13676 -2.58571 3.753 5.0625 -2.59549 3.61821 5.04652 -2.59399 3.6302 5.20564 -2.59961 3.5383 5.24044 -2.6094 3.40417 5.21742 -2.61934 3.27287 5.19105 -2.59657 3.53208 5.71796 -2.58022 3.70624 6.15579 -2.60155 3.43197 5.9304 -2.62363 3.15543 5.68008 -2.62766 3.08429 5.74722 -2.63099 3.03191 5.84799 -2.63451 2.96759 5.93072 -2.64052 2.88128 5.97746 -2.6431 2.83173 6.09392 -2.65929 2.61987 5.88673 -2.64591 2.75438 6.39837 -2.66236 2.54724 6.18563 -2.66653 2.477 6.27095 -2.6696 2.41864 6.39244 -2.68072 2.27838 6.30823 -2.67643 2.29626 6.6434 -2.68471 2.18528 6.64038 -2.69278 2.07173 6.62576 -2.71143 1.84813 6.24572 -2.7196 1.73832 6.20549 -2.75336 1.38227 5.23599 -2.76276 1.26815 5.09014 -2.76305 1.24004 5.29226 -2.75432 1.29352 5.91518 -2.77417 1.09049 5.32415 -2.77892 1.01816 5.34789 -2.79016 0.89609 5.06434 -2.79362 0.832658 5.1244 -2.79781 0.765635 5.17361 -2.80406 0.689472 5.14216 -2.8035 0.649951 5.51767 -2.80003 0.619909 6.20212 -2.81137 0.508416 5.80831 -2.81532 0.43055 5.94196 -2.82368 0.340529 5.69431 -2.84002 2.19137 -0.996576 -2.83746 2.24731 -0.984084 -2.83352 2.33211 -0.99823 -2.83048 2.39692 -0.989475 -2.82719 2.47521 -0.992493 -2.82405 2.5556 -0.993413 -2.81993 2.63616 -0.992031 -2.81688 2.71776 -0.988606 -2.81172 2.81504 -0.995245 -2.80821 2.90563 -0.993159 -2.80366 3.01287 -1.00029 -2.79925 3.1048 -0.992658 -2.79431 3.22211 -0.999483 -2.7884 3.33966 -1.00281 -2.78364 3.45932 -1.00254 -2.77742 3.60555 -1.01448 -2.77227 3.71785 -1.00153 -2.76469 3.87436 -1.00996 -2.75968 4.0056 -0.999143 -2.75137 4.18322 -1.0075 -2.74362 4.3699 -1.01471 -2.7345 4.56677 -1.0203 -2.72603 4.7571 -1.01546 -2.71663 4.96545 -1.01251 -2.70561 5.21358 -1.0183 -2.69416 5.47098 -1.01964 -2.682 5.74956 -1.01961 -2.6685 6.03854 -1.01377 -2.65481 6.35763 -1.00791 -2.63766 6.73572 -1.00962 -2.61947 7.16295 -1.01304 -2.59857 7.61085 -1.00734 -2.57297 8.19747 -1.02173 -2.54652 8.78512 -1.01615 -2.51484 9.50207 -1.01887 -2.47747 10.3398 -1.02117 -2.43411 11.3263 -1.02213 -2.37842 12.573 -1.03225 -2.31145 14.0793 -1.03793 -2.22842 15.9649 -1.04137 -2.11886 18.4208 -1.04429 -1.84618 24.5175 -0.887323 -1.83461 24.7062 -0.47328 -1.81831 24.9986 -0.0579822 -2.32555 12.5349 5.62004 -2.30755 12.8523 5.99117 -2.47603 9.30236 4.77709 -2.4704 9.37364 4.99411 -2.47765 9.20327 5.10705 -2.47597 9.19352 5.29267 -2.48125 9.05592 5.41673 -2.49872 8.66727 5.40825 -2.50029 8.59842 5.5591 -2.51927 8.18795 5.51703 -2.54917 7.54045 5.32012 -2.5595 7.31173 5.35259 -2.55872 7.30193 5.51799 -2.55547 7.3318 5.71188 -2.52363 7.93184 6.30443 -2.53766 7.61988 6.2809 -2.59426 6.47481 5.62992 -2.61446 6.04438 5.47008 -2.62273 5.86529 5.48942 -2.62441 5.80144 5.59938 -2.63366 5.60722 5.59803 -2.62324 5.77374 5.90923 -2.62969 5.62896 5.95063 -2.61835 5.81037 6.29815 -2.67574 4.69876 5.39251 -2.67687 4.64338 5.49074 -2.69731 4.24183 5.22575 -2.66771 4.76904 5.95041 -2.71636 3.84115 5.07767 -2.72008 3.75058 5.11673 -2.7283 3.57743 5.05358 -2.71091 3.86122 5.55682 -2.73269 3.44175 5.17485 -2.73493 3.37452 5.23771 -2.73817 3.30718 5.29957 -2.73834 3.28336 5.42619 -2.73828 3.25556 5.55321 -2.74108 3.18113 5.61331 -2.7371 3.2271 5.868 -2.74651 3.0301 5.72962 -2.74915 2.96782 5.81196 -2.76981 2.58879 5.31377 -2.77032 2.55458 5.4336 -2.76631 2.59784 5.71445 -2.76995 2.50744 5.73649 -2.7642 2.56615 6.08418 -2.76649 2.49803 6.16951 -2.77229 2.38101 6.14307 -2.77885 2.24748 6.06768 -2.76355 2.44318 6.86008 -2.8004 1.85398 5.52134 -2.79561 1.89307 5.89922 -2.78567 2.0065 6.55625 -2.82023 1.4842 5.14786 -2.82295 1.41183 5.16851 -2.82451 1.36286 5.27503 -2.82856 1.28184 5.26446 -2.82789 1.25278 5.48657 -2.83984 1.07512 5.0133 -2.83923 1.04643 5.2431 -2.84294 0.962669 5.19692 -2.84873 0.85931 5.00081 -2.85038 0.808401 5.14937 -2.85251 0.740468 5.19795 -2.85662 0.662905 5.15587 -2.84938 0.657035 5.99956 -2.85098 0.583382 6.21532 -2.86173 0.465002 5.58076 -2.86567 0.385185 5.53349 -2.87096 0.304291 5.36501 -2.92881 2.16888 -0.998073 -2.92804 2.23901 -1.00071 -2.92692 2.30258 -0.994412 -2.92524 2.37395 -0.993399 -2.92338 2.45979 -1.00421 -2.92299 2.5179 -0.985833 -2.92122 2.60495 -0.992297 -2.9196 2.69412 -0.996364 -2.91856 2.77567 -0.99155 -2.91703 2.86608 -0.990672 -2.9144 2.97213 -0.999264 -2.91348 3.07251 -0.998981 -2.91158 3.17309 -0.995696 -2.90921 3.28259 -0.995148 -2.90687 3.40977 -1.00218 -2.90462 3.53813 -1.00546 -2.90246 3.66769 -1.0049 -2.90034 3.81499 -1.01041 -2.89782 3.95476 -1.00645 -2.8949 4.10457 -1.00297 -2.89161 4.28203 -1.00845 -2.88851 4.47939 -1.01712 -2.88543 4.65942 -1.01102 -2.88209 4.88589 -1.01961 -2.87735 5.10497 -1.01702 -2.87383 5.34402 -1.01482 -2.86862 5.62196 -1.01922 -2.86355 5.90134 -1.01457 -2.85781 6.2197 -1.01375 -2.85238 6.55931 -1.00866 -2.84502 6.96679 -1.01269 -2.83799 7.39572 -1.00867 -2.82865 7.9027 -1.01097 -2.8188 8.50077 -1.01804 -2.80782 9.12866 -1.01145 -2.79428 9.89675 -1.01262 -2.77837 10.8243 -1.0182 -2.75852 11.9515 -1.02675 -2.73399 13.3486 -1.03891 -2.7059 14.9665 -1.03335 -2.6755 16.658 -0.980521 -2.62303 19.6939 -1.01067 -2.53311 24.71 -0.679415 -2.52404 25.0559 -0.269504 -2.7605 9.18276 4.81537 -2.76065 9.10697 4.96617 -2.75945 9.07337 5.13664 -2.68595 12.3542 7.18831 -2.7985 7.08006 4.65321 -2.79475 7.183 4.86355 -2.78241 7.68651 5.31341 -2.7919 7.20789 5.20017 -2.79199 7.13361 5.32056 -2.77759 7.69553 5.85347 -2.77855 7.60228 5.97659 -2.78689 7.18646 5.87449 -2.77907 7.42521 6.22948 -2.80308 6.36669 5.62557 -2.80806 6.08916 5.57739 -2.81315 5.81423 5.52087 -2.81693 5.59737 5.50125 -2.81388 5.67717 5.73124 -2.81377 5.61661 5.84495 -2.81453 5.55396 5.95796 -2.82187 5.20863 5.79935 -2.83101 4.78524 5.54543 -2.8322 4.68465 5.60193 -2.85101 3.90906 4.9324 -2.85238 3.81333 4.96562 -2.85252 3.78989 5.07961 -2.85163 3.75072 5.17867 -2.85363 3.63453 5.18436 -2.85681 3.50631 5.1715 -2.85315 3.5898 5.43486 -2.86057 3.27182 5.16046 -2.84946 3.62951 5.82643 -2.85993 3.20987 5.38689 -2.86309 3.06777 5.33687 -2.86394 2.9657 5.34268 -2.86971 2.74611 5.14907 -2.86929 2.71356 5.26081 -2.86805 2.69786 5.40777 -2.87239 2.53185 5.28162 -2.83709 3.54224 7.44961 -2.87482 2.36965 5.33092 -2.86654 2.57758 5.97398 -2.8661 2.52747 6.09569 -2.86556 2.48921 6.25397 -2.86862 2.33463 6.13418 -2.85845 2.56028 6.99085 -2.87722 2.02145 5.83661 -2.88069 1.86248 5.64894 -2.88394 1.74214 5.5524 -2.88473 1.66905 5.59644 -2.89143 1.47823 5.2357 -2.89249 1.40992 5.27539 -2.89335 1.32665 5.25574 -2.8946 1.24825 5.25398 -2.89103 1.26809 5.7105 -2.89831 1.08271 5.1972 -2.8996 1.01705 5.25008 -2.89937 0.956393 5.34137 -2.89922 0.905618 5.53089 -2.90143 0.816311 5.45196 -2.90423 0.714961 5.23204 -2.89509 0.738601 6.34482 -2.90607 0.57351 5.31476 -2.90832 0.496887 5.28937 -2.90768 0.426803 5.41257 -2.90796 0.353077 5.56457 -3.01606 2.02197 -1.00236 -3.01577 2.08321 -1.00156 -3.01655 2.14546 -0.999316 -3.01777 2.21543 -1.00276 -3.01764 2.27891 -0.997268 -3.01889 2.34906 -0.997019 -3.01922 2.42035 -0.995017 -3.02062 2.49268 -0.991171 -3.0209 2.58056 -0.998693 -3.02177 2.66082 -0.997235 -3.02271 2.74219 -0.99353 -3.02361 2.84012 -1.00005 -3.02409 2.93048 -0.997682 -3.02559 3.03837 -1.0047 -3.02618 3.13 -0.996885 -3.02778 3.23919 -0.997855 -3.02848 3.34959 -0.995574 -3.03021 3.47762 -1.00077 -3.03147 3.61463 -1.00741 -3.03238 3.74511 -1.00472 -3.03434 3.89328 -1.00801 -3.03584 4.05049 -1.01143 -3.03702 4.21878 -1.0146 -3.03829 4.38833 -1.01243 -3.04069 4.57669 -1.01369 -3.04227 4.76742 -1.00885 -3.045 4.99469 -1.01403 -3.04747 5.25086 -1.02322 -3.04903 5.49081 -1.0168 -3.05238 5.76061 -1.01316 -3.05559 6.07818 -1.01736 -3.05842 6.38842 -1.00789 -3.0613 6.76633 -1.00926 -3.06572 7.2031 -1.01502 -3.07054 7.66238 -1.01149 -3.07583 8.22936 -1.02005 -3.08169 8.83793 -1.01875 -3.08895 9.53573 -1.01624 -3.09691 10.3439 -1.01194 -3.10684 11.4009 -1.02548 -3.11857 12.6187 -1.02912 -3.1342 14.1659 -1.03965 -3.14989 15.8264 -1.0111 -3.17769 18.6511 -1.05753 -3.20121 21.1633 -0.975258 -3.04446 9.27327 4.39738 -3.04189 9.25185 4.75118 -3.03976 9.07579 4.85927 -3.03783 9.06265 5.03705 -3.03566 8.98187 5.18541 -3.03283 8.6841 5.22509 -3.02235 7.01378 4.53996 -3.02889 8.4982 5.49668 -3.02093 7.25233 4.97962 -3.01831 7.08821 5.04487 -3.02273 8.07382 5.81093 -3.01863 7.49231 5.62916 -3.01511 7.2196 5.62737 -3.01407 7.08023 5.70811 -3.01102 6.75365 5.65189 -3.00944 6.82509 5.87707 -3.00773 6.69159 5.95403 -3.00476 6.13511 5.69173 -3.00186 5.78323 5.57056 -3.00089 5.80223 5.75026 -2.99467 4.21366 4.51411 -2.99374 4.15925 4.58898 -2.99253 4.02382 4.58723 -2.99303 4.49642 5.17767 -2.99138 4.44503 5.27202 -2.98961 3.87414 4.82178 -2.98782 3.82189 4.89866 -2.98757 4.48906 5.79113 -2.98556 3.73677 5.08067 -2.98488 3.71575 5.20206 -2.98375 4.22767 5.99704 -2.9823 3.35588 5.04174 -2.9815 3.27351 5.07873 -2.98034 3.39377 5.39893 -2.97953 3.26642 5.37846 -2.97788 3.20069 5.44658 -2.97596 3.36555 5.87634 -2.97514 3.22316 5.83568 -2.97509 2.7583 5.24005 -2.97376 2.65459 5.23044 -2.97284 2.60024 5.30641 -2.97266 2.47056 5.23969 -2.9716 2.41408 5.31306 -2.96788 2.70146 6.10777 -2.96779 2.48737 5.87629 -2.96655 2.39859 5.90489 -2.96478 2.34398 6.01502 -2.96333 2.33444 6.24558 -2.95952 2.49523 6.955 -2.96315 1.94375 5.72971 -2.96234 1.86195 5.75796 -2.96211 1.72191 5.60364 -2.96084 1.64792 5.64724 -2.96221 1.44096 5.21755 -2.96148 1.36278 5.21779 -2.95828 1.42743 5.80967 -2.95739 1.3208 5.7215 -2.96087 1.07747 4.94525 -2.9554 1.16553 5.80414 -2.95898 0.943407 4.9903 -2.95729 0.911178 5.24851 -2.9577 0.805088 5.01102 -2.95744 0.734818 5.00957 -2.95419 0.700483 5.38524 -2.94902 0.668627 5.95014 -2.95307 0.541231 5.28744 -2.95185 0.468756 5.32125 -2.95001 0.400637 5.58373 -2.95156 0.319039 5.27514 -3.0977 1.99701 -1.00168 -3.1001 2.0524 -0.994202 -3.10224 2.12119 -1.0002 -3.10402 2.18342 -0.997164 -3.10724 2.25331 -0.999721 -3.10912 2.31671 -0.993338 -3.1118 2.39449 -0.999282 -3.11476 2.45899 -0.989457 -3.1176 2.53897 -0.991405 -3.12088 2.62673 -0.997644 -3.12382 2.70793 -0.995047 -3.1272 2.79692 -0.996541 -3.13067 2.88704 -0.995487 -3.13409 2.99374 -1.00396 -3.13772 3.08612 -0.997511 -3.14132 3.19511 -0.999989 -3.14593 3.3042 -0.999176 -3.15014 3.42324 -1.00065 -3.15443 3.54345 -0.998578 -3.15971 3.68032 -1.00314 -3.16464 3.82821 -1.00854 -3.17067 3.97725 -1.0095 -3.17574 4.12658 -1.00576 -3.18198 4.29568 -1.00651 -3.18886 4.49245 -1.01502 -3.19634 4.68166 -1.01316 -3.20404 4.90848 -1.02146 -3.21229 5.12679 -1.01853 -3.22138 5.37594 -1.01982 -3.23215 5.65293 -1.0238 -3.24153 5.92261 -1.01519 -3.25283 6.24096 -1.0141 -3.26711 6.60902 -1.01797 -3.28125 7.00737 -1.01822 -3.29677 7.44487 -1.0162 -3.31598 7.94328 -1.0151 -3.33826 8.55927 -1.02611 -3.361 9.1981 -1.02072 -3.38822 9.9271 -1.01228 -3.42371 10.8933 -1.02467 -3.46357 11.9802 -1.02471 -3.51785 13.4552 -1.04822 -3.57573 15.0531 -1.03755 -3.62525 16.407 -0.941133 -3.31982 9.15152 4.44194 -3.31367 9.00741 4.5624 -3.31193 8.98171 4.72978 -3.31398 9.07998 4.95422 -3.31136 9.05567 5.12825 -3.30435 8.86623 5.22372 -3.2905 8.48966 5.21839 -3.28354 8.31806 5.30938 -3.23898 6.98405 4.75048 -3.23924 7.03942 4.93689 -3.27316 8.14343 5.75998 -3.25459 7.58592 5.59958 -3.24516 7.34591 5.62276 -3.24585 7.40581 5.84038 -3.22902 6.89462 5.66557 -3.22951 6.967 5.8919 -3.22323 6.80896 5.95368 -3.22935 7.06103 6.33153 -3.20015 6.14482 5.78172 -3.19018 5.86966 5.72253 -3.18951 5.8774 5.89797 -3.18071 5.62133 5.84083 -3.13729 4.22055 4.70539 -3.13514 4.17794 4.7943 -3.1457 4.54308 5.29312 -3.14573 4.59327 5.49621 -3.14617 4.6641 5.73162 -3.14379 4.61567 5.84446 -3.12042 3.84224 5.1267 -3.12063 3.87982 5.31839 -3.11684 3.76647 5.3338 -3.11873 3.88816 5.646 -3.10881 3.57888 5.40465 -3.12194 4.11854 6.31099 -3.11737 3.99227 6.32784 -3.10852 3.71458 6.11808 -3.10636 3.66881 6.24419 -3.09221 3.16974 5.64935 -3.0892 3.08369 5.69045 -3.07992 2.76209 5.32274 -3.07553 2.6432 5.28657 -3.07256 2.55925 5.30934 -3.06894 2.46636 5.31273 -3.06937 2.55834 5.69158 -3.06621 2.48513 5.74866 -3.06538 2.52818 6.06955 -3.0609 2.3662 5.93287 -3.06029 2.43746 6.3579 -3.06239 2.63861 7.16011 -3.0473 1.9261 5.53687 -3.04489 1.86377 5.61204 -3.04155 1.80193 5.69591 -3.03888 1.73552 5.76938 -3.03528 1.59206 5.58241 -3.03164 1.42462 5.27608 -3.02817 1.36199 5.34376 -3.02688 1.48473 6.21933 -3.02334 1.54791 6.96318 -3.0201 1.21042 5.77679 -3.01642 1.10774 5.68384 -3.01488 0.920728 5.02582 -3.01211 0.834269 4.91735 -3.00896 0.805516 5.24388 -3.00617 0.718934 5.13292 -3.00354 0.662137 5.29913 -2.99821 0.619309 5.76395 -2.99708 0.516058 5.37954 -2.99389 0.442657 5.43274 -2.99245 0.363176 5.30479 -3.18304 2.03299 -1.00151 -3.1868 2.09499 -1.00078 -3.19058 2.15706 -0.998454 -3.19543 2.22015 -0.994582 -3.19929 2.28338 -0.989207 -3.20396 2.36099 -0.99616 -3.20865 2.43871 -1.00092 -3.21304 2.51086 -0.996884 -3.21845 2.58305 -0.99096 -3.22381 2.67174 -0.99616 -3.22918 2.76056 -0.998762 -3.23519 2.84274 -0.992734 -3.2411 2.9405 -0.99648 -3.2476 3.04809 -1.00342 -3.25467 3.14807 -1.00138 -3.26083 3.24925 -0.996481 -3.26796 3.36702 -0.999718 -3.27667 3.49463 -1.00475 -3.28448 3.6235 -1.00594 -3.29338 3.75349 -1.00318 -3.30233 3.90124 -1.0064 -3.31287 4.05892 -1.00973 -3.32303 4.22667 -1.01284 -3.33429 4.39561 -1.01061 -3.34776 4.60195 -1.02035 -3.35874 4.7823 -1.01097 -3.37352 5.00985 -1.01596 -3.38945 5.25639 -1.02108 -3.40613 5.51513 -1.02191 -3.42241 5.78317 -1.01768 -3.44207 6.0909 -1.01813 -3.46514 6.43843 -1.02106 -3.48794 6.79742 -1.01545 -3.51538 7.23385 -1.02048 -3.54517 7.69165 -1.01626 -3.5793 8.23812 -1.01904 -3.61927 8.86447 -1.02199 -3.66577 9.5818 -1.02304 -3.71613 10.3786 -1.01551 -3.78172 11.3944 -1.02067 -3.86295 12.6688 -1.03374 -3.958 14.1536 -1.03362 -4.0508 15.6132 -0.978384 -6.34305 52.14 5.14613 -3.58957 8.95126 4.11013 -3.5813 8.82144 4.23301 -3.57251 8.69967 4.35581 -3.57761 8.81556 4.57505 -3.57658 8.81734 4.75139 -3.5901 9.05035 5.03681 -3.58909 9.05165 5.22368 -3.56067 8.60226 5.18861 -3.54595 8.38699 5.25927 -3.56354 8.69822 5.6102 -3.53522 8.25257 5.54941 -3.53453 8.25899 5.73863 -3.47043 7.20602 5.28102 -3.4612 7.06396 5.35816 -3.39849 6.03831 4.84623 -3.39821 6.0541 5.00266 -3.39705 6.04009 5.14342 -3.3979 6.0729 5.32053 -3.39788 6.09153 5.49403 -3.37901 5.78679 5.41403 -3.41713 6.47244 6.13939 -3.36994 5.66894 5.63575 -3.42692 6.68739 6.70346 -3.5186 8.29476 8.38237 -3.32178 4.89324 5.4084 -3.31736 4.84468 5.51615 -3.31334 4.78671 5.61645 -3.26778 4.00633 4.95397 -3.25723 3.83615 4.90765 -3.25458 3.80109 5.00641 -3.2844 4.36047 5.80482 -3.25169 3.78139 5.27313 -3.24799 3.74481 5.38039 -3.23874 3.59515 5.34476 -3.2183 3.23502 5.01578 -3.20999 3.10119 4.97696 -3.20507 3.03267 5.02532 -3.19716 2.89069 4.96417 -3.18963 2.78411 4.94984 -3.18461 2.70001 4.96713 -3.18495 2.72278 5.16365 -3.18457 2.74856 5.37955 -3.19111 2.90157 5.84367 -3.17184 2.54053 5.35613 -3.16892 2.5144 5.4931 -3.16803 2.53021 5.72983 -3.16932 2.5895 6.07754 -3.15784 2.38536 5.85086 -3.15291 2.30117 5.88668 -3.15358 2.34853 6.2559 -3.17719 2.92158 8.07085 -3.1302 1.92896 5.65503 -3.12432 1.82013 5.59744 -3.11972 1.75485 5.67107 -3.11445 1.69353 5.76303 -3.10801 1.5656 5.62289 -3.10247 1.48823 5.65396 -3.0981 1.45003 5.84911 -3.09003 1.2682 5.42918 -3.08449 1.19211 5.44547 -3.08111 1.17505 5.78496 -3.07624 1.08185 5.74031 -3.06888 0.920038 5.21926 -3.06373 0.818765 5.01142 -3.06006 0.783034 5.31798 -3.05441 0.698087 5.21626 -3.0498 0.647819 5.51173 -3.04451 0.565704 5.44732 -3.03971 0.487967 5.43135 -3.03538 0.408681 5.32404 -3.03039 0.334765 5.42533 -3.25758 1.9397 -0.99171 -3.26226 2.00052 -0.993332 -3.26932 2.06792 -1.001 -3.27408 2.1299 -0.99948 -3.27986 2.1919 -0.996362 -3.28571 2.25497 -0.991697 -3.29238 2.33241 -0.999558 -3.29825 2.39565 -0.991496 -3.30601 2.47423 -0.995417 -3.31284 2.55397 -0.997184 -3.31931 2.62715 -0.990216 -3.32948 2.73002 -1.00696 -3.33605 2.80441 -0.99555 -3.34351 2.89429 -0.994517 -3.35248 2.99293 -0.996829 -3.36148 3.09172 -0.996345 -3.37206 3.20029 -0.998757 -3.38167 3.30908 -0.997969 -3.39286 3.4277 -0.999377 -3.40359 3.55528 -1.00252 -3.41691 3.69268 -1.00697 -3.42882 3.82259 -1.00224 -3.44183 3.97122 -1.00313 -3.4569 4.13753 -1.00891 -3.47162 4.29733 -1.00486 -3.48897 4.48465 -1.00899 -3.50746 4.69083 -1.01566 -3.52605 4.89835 -1.01559 -3.54633 5.11693 -1.01277 -3.56886 5.3731 -1.01782 -3.59414 5.64138 -1.01818 -3.62111 5.93757 -1.01992 -3.64728 6.2363 -1.01177 -3.68154 6.60317 -1.01554 -3.71816 7.00905 -1.01854 -3.75822 7.45497 -1.01903 -3.8028 7.94197 -1.01477 -3.85474 8.51755 -1.01571 -3.91511 9.18286 -1.01723 -3.98674 9.96775 -1.021 -4.06807 10.8627 -1.01874 -4.16624 11.9361 -1.01676 -4.29044 13.3074 -1.02452 -4.44013 14.9495 -1.02225 -4.58708 16.5747 -0.960449 -7.54271 49.1131 -0.646186 -9.54463 71.1815 -0.163703 -7.72985 51.6885 6.48942 -7.70544 51.61 9.22604 -7.79993 52.8012 11.3134 -7.76133 52.5103 13.1691 -3.88986 9.29481 4.5063 -3.87569 9.15032 4.62955 -3.85088 8.88438 4.69788 -3.84197 8.79244 4.83543 -3.83904 8.81575 5.58503 -3.6798 7.02255 5.09284 -3.66673 6.8836 5.16745 -3.57235 5.81664 4.63338 -3.58057 5.91874 4.84136 -3.58174 5.94169 5.00222 -3.57598 5.88731 5.11217 -3.56507 5.76862 5.17316 -3.56212 5.74225 5.30524 -3.56704 5.8221 5.52585 -3.5558 5.69824 5.58319 -3.54692 5.61081 5.67035 -3.54913 5.64765 5.86978 -3.49137 4.9797 5.41674 -3.47844 4.83161 5.42842 -3.47344 4.78942 5.54247 -3.46979 4.75251 5.66346 -3.45483 4.58939 5.65286 -3.44908 4.53572 5.75697 -3.45569 4.62292 6.02667 -3.38537 3.79338 5.21251 -3.36781 3.59414 5.11751 -3.36242 3.54769 5.20594 -3.34321 3.32508 5.06243 -3.35754 3.51197 5.47076 -3.32563 3.13201 5.09198 -3.32107 3.08319 5.17401 -3.30299 2.88008 5.02073 -3.29056 2.73129 4.93792 -3.28365 2.66357 4.97985 -3.28213 2.65923 5.13316 -3.28474 2.69915 5.37498 -3.2688 2.51555 5.21312 -3.29574 2.87175 6.09792 -3.28701 2.77528 6.12406 -3.28274 2.74136 6.28435 -3.26814 2.57667 6.16179 -3.25906 2.47548 6.17314 -3.30399 3.10255 7.99097 -3.28839 2.92045 7.88009 -3.27333 2.74661 7.77441 -3.21289 1.94174 5.81124 -3.20106 1.79351 5.63949 -3.194 1.72239 5.69351 -3.18332 1.59127 5.54454 -3.1759 1.51604 5.57603 -3.16915 1.44866 5.64507 -3.1618 1.36134 5.6351 -3.15229 1.24871 5.49633 -3.14511 1.17617 5.5417 -3.14552 1.23451 6.33431 -3.13728 1.14547 6.36949 -3.12315 0.942222 5.59111 -3.11401 0.799334 5.08536 -3.10742 0.734881 5.15306 -3.10125 0.698678 5.5684 -3.09453 0.650946 6.01354 -3.08782 0.528661 5.33966 -3.08114 0.453009 5.32301 -3.07348 0.381266 5.46486 -3.34309 1.97926 -1.00013 -3.34947 2.03437 -0.993379 -3.35753 2.10176 -1.00016 -3.3643 2.16365 -0.997843 -3.37214 2.22656 -0.993986 -3.38036 2.2962 -0.995669 -3.3886 2.36592 -0.995454 -3.39834 2.44433 -1.00028 -3.40673 2.51625 -0.996172 -3.41513 2.58826 -0.990263 -3.42542 2.67565 -0.995337 -3.43578 2.76417 -0.997964 -3.44766 2.86144 -1.00424 -3.45669 2.94357 -0.995626 -3.46867 3.0421 -0.996555 -3.48074 3.14177 -0.994637 -3.49333 3.2503 -0.995561 -3.50794 3.37638 -1.00417 -3.52165 3.48618 -0.998258 -3.53694 3.62335 -1.00482 -3.55277 3.75192 -1.00204 -3.5697 3.89919 -1.00521 -3.58622 4.03893 -0.998982 -3.60787 4.21477 -1.00699 -3.62913 4.40072 -1.01379 -3.65301 4.59662 -1.01889 -3.67548 4.7851 -1.01371 -3.70067 5.00221 -1.01436 -3.72906 5.23916 -1.0156 -3.76169 5.51363 -1.02373 -3.7951 5.80036 -1.02637 -3.83015 6.09732 -1.0229 -3.86745 6.41439 -1.01584 -3.91232 6.79081 -1.01626 -3.96308 7.21495 -1.01817 -4.01893 7.68998 -1.01911 -4.08025 8.20511 -1.01396 -4.15469 8.83829 -1.01911 -4.24277 9.58089 -1.02644 -4.33699 10.374 -1.01818 -4.46014 11.4143 -1.02789 -4.59609 12.565 -1.0198 -4.77087 14.043 -1.02028 -4.97428 15.7599 -1.00058 -5.69675 21.8611 -1.0374 -10.1678 59.7249 0.558788 -9.09301 50.8713 5.08084 -9.10838 51.051 5.99383 -4.12039 8.845 4.77819 -4.04469 8.26116 5.75653 -3.90864 7.08528 5.22062 -3.81567 6.27486 4.86557 -3.76222 5.819 4.71006 -3.75786 5.78705 4.82891 -3.75797 5.79337 4.97678 -3.75378 5.76373 5.10222 -3.7414 5.66899 5.17916 -3.73696 5.63532 5.3037 -3.74233 5.6911 5.50477 -3.7479 5.74937 5.71553 -3.73886 5.6747 5.81699 -3.97114 7.75026 7.90503 -3.95458 7.61657 8.02086 -3.63529 4.78801 5.46857 -3.62124 4.66923 5.50365 -3.66024 5.02132 6.03683 -3.62559 4.72625 5.8901 -3.62597 4.73423 6.07173 -3.62584 4.74911 6.27035 -3.51443 3.75502 5.24342 -3.4875 3.52082 5.09964 -3.46267 3.304 4.96491 -3.45521 3.24222 5.02477 -3.44504 3.15487 5.05117 -3.43095 3.03955 5.03462 -3.40727 2.82794 4.86487 -3.43013 3.04892 5.36417 -3.38775 2.66777 4.90824 -3.42093 2.9777 5.59552 -3.38068 2.61533 5.13655 -3.37052 2.52935 5.15006 -3.36134 2.45757 5.1883 -3.40168 2.84619 6.15642 -3.39302 2.77889 6.24519 -3.38481 2.71745 6.3514 -3.36621 2.55296 6.22777 -3.4082 2.9763 7.51386 -3.39979 2.90738 7.6712 -3.32274 2.17948 6.06683 -3.27758 1.74351 5.10879 -3.27953 1.78066 5.45578 -3.27418 1.74572 5.61433 -3.26336 1.65193 5.59089 -3.24991 1.5249 5.44014 -3.24194 1.46805 5.53821 -3.2302 1.36413 5.4509 -3.22342 1.30907 5.56629 -3.21035 1.19063 5.38698 -3.20119 1.10772 5.36239 -3.20489 1.19022 6.3226 -3.1858 0.99627 5.64483 -3.17522 0.898302 5.51726 -3.16574 0.822097 5.54671 -3.15401 0.708161 5.17664 -3.14679 0.653583 5.40225 -3.13763 0.573699 5.33766 -3.12906 0.498177 5.34154 -3.1188 0.429103 5.53404 -3.11219 0.347509 5.19538 -3.42824 2.01221 -1.00052 -3.43693 2.07287 -1.00046 -3.44569 2.13461 -0.99896 -3.45583 2.203 -1.0032 -3.4643 2.25925 -0.991211 -3.4731 2.32122 -0.984913 -3.4852 2.40611 -0.997888 -3.49695 2.48445 -1.00163 -3.50734 2.5563 -0.996528 -3.51918 2.63585 -0.996123 -3.53004 2.71557 -0.993416 -3.54341 2.80396 -0.994859 -3.55586 2.89354 -0.99375 -3.57082 2.99182 -0.996092 -3.58625 3.09794 -1.00153 -3.60038 3.19857 -0.998069 -3.61598 3.307 -0.99721 -3.6346 3.43293 -1.00404 -3.65181 3.55137 -1.00168 -3.67062 3.67966 -1.00092 -3.69096 3.81684 -1.00121 -3.71039 3.95528 -0.997354 -3.73746 4.13846 -1.01257 -3.7601 4.29678 -1.00831 -3.78587 4.47379 -1.0079 -3.81482 4.67053 -1.01018 -3.84591 4.88611 -1.0143 -3.87862 5.11178 -1.01533 -3.91455 5.35731 -1.01646 -3.95426 5.63256 -1.02028 -3.99721 5.9278 -1.0217 -4.04187 6.23429 -1.01668 -4.09187 6.57947 -1.01381 -4.15191 6.99182 -1.01961 -4.21746 7.44511 -1.02257 -4.28793 7.92957 -1.01778 -4.37228 8.51112 -1.02068 -4.47006 9.18212 -1.02377 -4.58185 9.95169 -1.0245 -4.71033 10.8309 -1.01953 -4.86363 11.8881 -1.01519 -5.05992 13.2421 -1.02096 -5.30187 14.9025 -1.02222 -5.55723 16.6647 -0.977719 -6.03444 19.9453 -1.03117 -10.5406 51.2509 6.49017 -8.34081 36.1747 8.11004 -4.12136 7.01369 4.94642 -4.11491 6.9788 5.08446 -4.14593 7.20156 5.38686 -3.97158 5.98011 4.75497 -3.95138 5.84131 4.80369 -3.94444 5.80024 4.91771 -3.92007 5.62815 4.93716 -3.92246 5.65425 5.10247 -3.91161 5.58331 5.19585 -3.90764 5.55689 5.32584 -3.90798 5.56593 5.48819 -3.9016 5.5327 5.61943 -3.88822 5.43806 5.69718 -3.88012 5.39353 5.82078 -4.20083 7.69474 8.23855 -3.62754 3.59444 4.3477 -3.6155 3.50931 4.37611 -3.80701 4.9023 6.1821 -3.57319 3.22173 4.41159 -3.74712 4.48644 6.05671 -3.61015 3.50192 5.00949 -3.62734 3.62849 5.31723 -3.59104 3.3749 5.13523 -3.55578 3.12348 4.9374 -3.54667 3.06708 5.00261 -3.49288 2.67771 4.5693 -3.48644 2.63224 4.63547 -3.47342 2.54907 4.64166 -3.48739 2.65446 4.96337 -3.48588 2.65011 5.11649 -3.51987 2.9107 5.76073 -3.50384 2.79648 5.74374 -3.40255 2.05466 4.47626 -3.4898 2.71023 5.98989 -3.56276 3.26861 7.4275 -3.481 2.6671 6.36343 -3.52518 3.01094 7.44455 -3.52693 3.04064 7.84337 -3.35196 1.71401 4.70565 -3.34373 1.65745 4.74845 -3.34299 1.66046 4.96998 -3.33123 1.58266 4.96448 -3.34679 1.7173 5.65571 -3.3272 1.5753 5.45838 -3.31704 1.50371 5.49913 -3.29702 1.35903 5.24747 -3.28688 1.28878 5.27483 -3.27921 1.23573 5.38903 -3.26459 1.13575 5.27681 -3.25572 1.07966 5.38897 -3.24806 1.03539 5.59927 -3.24485 1.03507 6.17562 -3.22506 0.872414 5.58182 -3.21178 0.779489 5.45152 -3.19975 0.682462 5.21979 -3.1883 0.60972 5.21554 -3.17795 0.543777 5.34972 -3.16711 0.472316 5.45294 -3.15641 0.399246 5.6048 -3.50695 1.98905 -1.00751 -3.51496 2.03743 -0.993031 -3.52702 2.10458 -0.999828 -3.53914 2.1728 -1.00488 -3.54992 2.23454 -1.00078 -3.56214 2.30394 -1.00239 -3.5748 2.38108 -1.00908 -3.58567 2.44407 -0.999844 -3.59663 2.50814 -0.989059 -3.61039 2.58652 -0.989713 -3.62424 2.666 -0.988319 -3.63959 2.7542 -0.99107 -3.65496 2.84253 -0.991325 -3.67185 2.93962 -0.995125 -3.69026 3.0455 -1.00197 -3.70582 3.13623 -0.994035 -3.72584 3.25205 -1.00058 -3.74444 3.36039 -0.99804 -3.76608 3.48622 -1.00299 -3.7888 3.61319 -1.0041 -3.81061 3.7414 -1.00126 -3.83547 3.88719 -1.00441 -3.86148 4.03515 -1.00297 -3.89054 4.20075 -1.00612 -3.92173 4.38509 -1.01292 -3.95552 4.5794 -1.01802 -3.98798 4.76728 -1.01269 -4.02503 4.98167 -1.0133 -4.06791 5.22658 -1.01836 -4.11394 5.4904 -1.02267 -4.16062 5.76447 -1.02168 -4.21159 6.05946 -1.01824 -4.26831 6.38322 -1.01447 -4.33454 6.76523 -1.01783 -4.40878 7.19685 -1.02229 -4.48889 7.65853 -1.02017 -4.57546 8.16024 -1.01215 -4.68941 8.81778 -1.02432 -4.814 9.53434 -1.02655 -4.94209 10.2738 -1.00801 -5.11348 11.2663 -1.01095 -5.32148 12.4663 -1.01376 -5.58207 13.9719 -1.02017 -5.9549 16.1251 -1.05928 -6.35586 18.4399 -1.04056 -10.3829 41.7508 0.709999 -10.3817 41.7702 1.44386 -11.5706 48.6623 2.36816 -11.5886 48.7902 3.23121 -11.6328 49.3797 13.9586 -11.884 51.0242 20.3224 -4.34034 6.98411 5.02114 -4.5027 7.94788 5.78203 -4.42747 7.50827 5.68486 -4.41673 7.45182 5.82779 -4.14012 5.82545 4.87548 -4.11436 5.67846 4.91404 -4.37146 7.20345 6.2053 -4.07742 5.47159 5.04624 -4.08663 5.5256 5.23635 -4.0612 5.38438 5.27032 -4.06749 5.42333 5.45669 -4.05324 5.34638 5.54619 -4.08938 5.56594 5.91159 -4.39283 7.37499 7.82952 -4.41878 7.53892 8.23388 -3.74457 3.52585 4.34094 -3.72959 3.44183 4.36801 -3.71269 3.34406 4.37835 -3.71234 3.34503 4.49865 -3.69535 3.24611 4.50585 -3.68168 3.16708 4.53377 -3.71675 3.3825 4.93592 -3.7031 3.30294 4.97348 -3.6731 3.12963 4.8807 -3.65104 3.00056 4.84006 -3.60208 2.71163 4.55686 -3.57796 2.56851 4.47327 -3.57789 2.57247 4.61365 -3.66896 3.12923 5.67654 -3.54862 2.4037 4.61326 -3.63185 2.91383 5.67699 -3.4999 2.11506 4.37671 -3.49282 2.07566 4.44328 -3.48369 2.02098 4.48258 -4.00379 5.24001 11.4921 -3.94422 4.8923 11.2041 -3.65055 3.07824 7.45758 -3.44392 1.79849 4.64011 -3.44968 1.8374 4.9261 -3.4289 1.71863 4.81165 -3.4198 1.6636 4.86389 -3.41155 1.61938 4.95333 -3.40382 1.58154 5.0709 -3.40565 1.60173 5.3993 -3.38789 1.49732 5.31515 -3.37174 1.40169 5.24799 -3.36167 1.34439 5.33439 -3.34515 1.24514 5.23446 -3.33133 1.16705 5.22058 -3.32098 1.10611 5.29375 -3.3218 1.13451 5.92823 -3.29539 0.961409 5.3383 -3.28145 0.882568 5.30914 -3.27363 0.843601 5.62631 -3.25775 0.745826 5.43549 -3.24297 0.652422 5.21281 -3.22992 0.58222 5.25782 -3.21891 0.540508 5.98094 -3.20468 0.443491 5.50402 -3.19088 0.368068 5.66533 -3.59863 2.03188 -1.02325 -3.60623 2.07269 -1.00029 -3.61898 2.13418 -0.998703 -3.63169 2.19476 -0.99557 -3.6449 2.26405 -0.998076 -3.65769 2.32578 -0.991697 -3.67192 2.39519 -0.990613 -3.68903 2.47989 -1.00132 -3.70478 2.5581 -1.00288 -3.71918 2.6298 -0.9957 -3.7336 2.7016 -0.986624 -3.75239 2.79737 -0.99448 -3.77221 2.89322 -0.999544 -3.79354 2.99785 -1.00775 -3.80965 3.08075 -0.995232 -3.82965 3.17901 -0.991806 -3.85268 3.29474 -0.99667 -3.87679 3.41157 -0.998093 -3.90387 3.54493 -1.00646 -3.9286 3.67188 -1.00548 -3.95693 3.80858 -1.00571 -3.9858 3.95425 -1.00638 -4.01726 4.10978 -1.00726 -4.05034 4.27527 -1.00764 -4.08754 4.4594 -1.01157 -4.12741 4.65448 -1.01375 -4.17035 4.86735 -1.01764 -4.21505 5.09231 -1.01843 -4.26232 5.32631 -1.01567 -4.31788 5.59861 -1.01937 -4.37258 5.87241 -1.01403 -4.43561 6.18464 -1.01244 -4.50293 6.51789 -1.00651 -4.58733 6.93563 -1.01558 -4.67513 7.37567 -1.01585 -4.77232 7.8545 -1.0113 -4.88425 8.41154 -1.00961 -5.01455 9.05669 -1.00878 -5.16383 9.80008 -1.00632 -5.34151 10.6812 -1.00443 -5.55645 11.7474 -1.00463 -5.83124 13.1076 -1.01403 -6.17232 14.8008 -1.02248 -6.618 17.013 -1.03522 -7.15384 19.6688 -1.01639 -12.5203 46.3035 -0.552312 -14.3879 55.5861 0.111358 -14.3784 55.5652 1.09517 -14.3659 55.5274 2.07784 -12.8705 48.1252 2.7894 -12.969 48.6373 3.66979 -10.4837 36.303 3.63986 -10.5156 36.4783 4.30003 -10.5432 36.632 4.96619 -10.3575 35.7231 5.50601 -10.5987 36.9427 6.32309 -4.94655 8.8983 6.29284 -4.70796 7.70162 5.73844 -4.62399 7.28279 5.64513 -4.65082 7.42215 5.91922 -4.32097 5.7645 4.9186 -4.60709 7.212 6.13884 -4.57625 7.06103 6.21218 -4.31632 5.75142 5.35702 -4.30419 5.69132 5.46529 -4.26718 5.51022 5.46977 -4.26575 5.50706 5.62683 -4.27153 5.53729 5.81864 -4.76655 8.05721 8.38881 -4.72878 7.87391 8.4694 -3.88266 3.57268 4.34115 -3.86717 3.49613 4.37657 -3.81512 3.24312 4.44988 -3.81316 3.23478 4.56235 -3.79928 3.16755 4.60561 -3.82336 3.29303 4.89983 -3.78064 3.07964 4.75205 -3.76339 2.9922 4.76789 -3.74972 2.92813 4.8145 -3.69851 2.6659 4.56135 -3.67361 2.54106 4.5015 -3.65503 2.4503 4.48928 -3.6358 2.3506 4.45769 -3.65465 2.45366 4.77898 -3.63591 2.36074 4.76347 -3.59682 2.16358 4.54267 -3.57422 2.04543 4.45874 -3.56015 1.97766 4.47059 -3.55089 1.93529 4.53552 -3.53623 1.85952 4.52685 -3.54785 1.92535 4.85723 -3.51574 1.76077 4.63448 -3.52415 1.80794 4.94869 -3.50344 1.70403 4.87086 -3.4846 1.61232 4.81894 -3.48046 1.59613 4.99318 -3.46767 1.53125 5.0245 -3.46403 1.51944 5.24709 -3.44794 1.43725 5.22872 -3.43249 1.36341 5.23788 -3.41297 1.26437 5.13857 -3.40248 1.21447 5.25224 -3.38813 1.14185 5.26713 -3.37264 1.06775 5.27089 -3.35616 0.983185 5.20419 -3.34458 0.929621 5.34378 -3.33098 0.864163 5.42309 -3.31424 0.777927 5.32233 -3.29759 0.694118 5.20994 -3.2876 0.655555 5.6944 -3.27217 0.584396 5.87904 -3.25473 0.490045 5.53288 -3.23957 0.414274 5.62483 -3.68581 2.04743 -1.00808 -3.69813 2.10127 -0.999612 -3.71183 2.16175 -0.997284 -3.7266 2.22324 -0.993411 -3.74038 2.28486 -0.987936 -3.75934 2.36728 -1.00185 -3.77421 2.43003 -0.992729 -3.79195 2.50806 -0.9956 -3.80828 2.57859 -0.989581 -3.82749 2.66444 -0.99465 -3.84777 2.75136 -0.997176 -3.86808 2.83839 -0.997306 -3.88852 2.92756 -0.994838 -3.91043 3.02448 -0.995766 -3.93335 3.1215 -0.993803 -3.9593 3.23596 -1.00023 -3.98239 3.33527 -0.992173 -4.01095 3.45968 -0.997307 -4.0411 3.59395 -1.00374 -4.07084 3.72068 -1.00099 -4.10613 3.87363 -1.00898 -4.1375 4.01047 -1.00253 -4.17548 4.17453 -1.00568 -4.21508 4.34856 -1.00803 -4.25723 4.53153 -1.00894 -4.30357 4.73419 -1.01225 -4.35259 4.94786 -1.01282 -4.40675 5.18025 -1.01404 -4.46663 5.44122 -1.01842 -4.52665 5.70361 -1.01416 -4.59189 5.98586 -1.00771 -4.66539 6.30558 -1.00427 -4.7524 6.6833 -1.00809 -4.85041 7.11044 -1.01312 -4.95523 7.56661 -1.01132 -5.07619 8.09092 -1.01129 -5.20563 8.65528 -1.00238 -5.36884 9.36443 -1.00606 -5.54736 10.1434 -0.998868 -5.77316 11.1246 -1.00238 -6.04391 12.3018 -1.00406 -6.40269 13.8581 -1.02145 -6.81236 15.6402 -1.01328 -7.43927 18.3649 -1.05072 -8.18249 21.5995 -1.04033 -13.1056 43.0096 -0.827378 -11.4872 36.0304 2.03486 -11.4816 36.0183 2.67418 -11.4623 35.9467 3.31023 -11.4226 35.7866 3.93787 -11.2846 35.1989 4.51871 -11.7026 37.0332 5.36629 -11.4537 35.9597 5.88695 -11.5302 36.3059 6.59093 -11.7399 37.2927 10.1792 -11.7373 37.2926 10.8821 -11.4292 35.9885 12.6077 -4.92803 7.57128 5.23898 -4.90459 7.473 5.35243 -4.99809 7.88918 5.78822 -5.01223 7.95496 6.01936 -4.90514 7.48783 5.89497 -4.89424 7.44405 6.05049 -4.86757 7.32638 6.1534 -4.81771 7.11317 6.18229 -4.85694 7.28753 6.50983 -4.49569 5.69815 5.41149 -4.45623 5.52561 5.42377 -4.42375 5.38379 5.45733 -4.97274 7.81839 7.82901 -5.19333 8.80082 8.99662 -5.128 8.51615 9.00191 -5.11389 8.46317 9.2311 -3.96253 3.35697 4.29575 -3.95797 3.34003 4.39344 -3.9462 3.28958 4.45398 -3.94424 3.28126 4.56704 -3.91284 3.14673 4.52634 -3.90649 3.11741 4.61504 -3.91617 3.16245 4.80699 -3.88336 3.02229 4.75225 -3.86559 2.94225 4.77515 -3.85717 2.91138 4.87045 -3.9303 3.23833 5.52494 -3.75559 2.46009 4.44506 -3.74662 2.42205 4.51648 -3.70423 2.23375 4.32892 -3.68059 2.1292 4.27517 -3.68629 2.15832 4.46483 -3.64067 1.95499 4.21275 -3.96036 3.40572 7.33913 -3.63755 1.94762 4.48507 -3.62534 1.89203 4.52234 -3.61683 1.85996 4.6137 -3.59916 1.78428 4.60324 -3.60692 1.82306 4.88903 -3.58303 1.71689 4.80231 -3.56798 1.64931 4.81687 -3.55969 1.61799 4.94392 -3.52812 1.48499 5.25738 -3.50922 1.40542 5.24802 -3.49143 1.32772 5.23716 -3.4753 1.25779 5.26375 -3.46611 1.22222 5.46572 -3.44845 1.1453 5.47084 -3.42328 1.02994 5.23771 -3.40569 0.955369 5.22949 -3.39114 0.891499 5.29923 -3.37796 0.839919 5.49711 -3.35692 0.741972 5.2763 -3.34102 0.673503 5.33256 -3.32459 0.600523 5.33767 -3.30604 0.521178 5.19163 -3.29045 0.44955 5.14411 -3.27427 0.379359 5.1653 -3.77392 2.06193 -0.99277 -3.79092 2.12781 -0.998643 -3.80525 2.18163 -0.988283 -3.82239 2.24967 -0.990859 -3.84054 2.31775 -0.991642 -3.86013 2.39351 -0.99752 -3.87737 2.46283 -0.994453 -3.89806 2.53974 -0.99609 -3.91639 2.6102 -0.989082 -3.93867 2.69692 -0.993016 -3.9609 2.78278 -0.994405 -3.98327 2.87075 -0.993295 -4.00809 2.96644 -0.995587 -4.033 3.06325 -0.995131 -4.06037 3.16781 -0.997379 -4.08789 3.27452 -0.996629 -4.11793 3.38999 -0.997931 -4.14943 3.51332 -1.00103 -4.18209 3.63877 -1.00024 -4.21734 3.77404 -1.00056 -4.25407 3.91723 -1.00137 -4.29447 4.07121 -1.00244 -4.3364 4.23415 -1.00297 -4.38352 4.41667 -1.007 -4.43319 4.60815 -1.00928 -4.48303 4.80194 -1.00528 -4.54303 5.03177 -1.01043 -4.60215 5.26303 -1.00794 -4.67251 5.53141 -1.01196 -4.74206 5.8023 -1.00689 -4.82438 6.11921 -1.00888 -4.90949 6.44837 -1.00309 -5.01409 6.85198 -1.00942 -5.12401 7.27676 -1.00722 -5.24843 7.75881 -1.00575 -5.38848 8.30021 -1.0019 -5.54665 8.90889 -0.994898 -5.74154 9.66131 -0.997445 -5.96658 10.5305 -0.99615 -6.24916 11.6224 -1.00385 -6.59603 12.9651 -1.01316 -6.99493 14.5033 -1.00224 -7.6149 16.8992 -1.0438 -8.33178 19.6667 -1.03879 -13.705 40.4249 -1.08692 -13.6529 40.2335 -0.356421 -20.1329 65.2921 1.11146 -12.1275 34.3757 1.68866 -12.1086 34.3119 2.3001 -12.1764 34.5857 2.92871 -12.0868 34.2495 3.52354 -12.1846 34.6369 4.17387 -12.2247 34.8007 4.81571 -12.2467 34.8964 5.45693 -12.2675 34.9894 6.10411 -12.2944 35.1126 7.40716 -12.0006 33.9836 7.82737 -11.8739 33.5048 8.35301 -11.8893 33.5749 8.99684 -12.4928 35.9251 10.2384 -12.5312 36.0958 11.6642 -11.8553 33.4863 11.5379 -11.8578 33.5071 12.2017 -12.2768 35.1446 13.4507 -11.9305 33.8114 13.6538 -11.9582 33.9274 14.3878 -11.96 33.9494 15.096 -5.39504 8.42975 5.4813 -5.36598 8.32036 5.60665 -5.34082 8.22515 5.73948 -5.26222 7.92005 5.74137 -5.27595 7.97957 5.96722 -5.27872 7.99244 6.16931 -5.20011 7.68854 6.15492 -5.26437 7.94114 6.53329 -5.21678 7.76197 6.60434 -5.20609 7.72014 6.7792 -5.10596 7.33292 6.67675 -5.35869 8.32708 7.71538 -5.54408 9.06101 8.86564 -5.39442 8.48575 9.15839 -4.06092 3.26162 4.4953 -4.05614 3.24648 4.73017 -4.00809 3.05816 4.61604 -3.98604 2.97403 4.63226 -3.97886 2.94709 4.72746 -3.98398 2.96821 4.89659 -4.07172 3.31887 5.58195 -3.97014 2.92007 5.12264 -3.96025 2.88132 5.21914 -3.82937 2.36711 4.50061 -3.7611 2.09531 4.15505 -3.75401 2.07079 4.23841 -3.76782 2.12956 4.48973 -3.75895 2.09274 4.5658 -3.71978 1.93937 4.39873 -3.80426 2.28365 5.3154 -3.70876 1.90369 4.63656 -3.70452 1.88871 4.77439 -3.69032 1.83265 4.81991 -3.68787 1.82691 5.00474 -3.66841 1.75322 5.01192 -3.65586 1.70484 5.09319 -3.63486 1.62415 5.0788 -3.62997 1.60949 5.28281 -3.60579 1.51346 5.21823 -3.58775 1.44481 5.24807 -3.5683 1.37122 5.25735 -3.54831 1.29112 5.23601 -3.52891 1.21838 5.24234 -3.51685 1.17251 5.39477 -3.50369 1.12415 5.55655 -3.48113 1.03748 5.50051 -3.45663 0.941887 5.36352 -3.44003 0.87661 5.44285 -3.4267 0.830969 5.74006 -3.39898 0.718473 5.35933 -3.3785 0.637828 5.2454 -3.36075 0.570368 5.31974 -3.34117 0.487133 5.0131 -3.32327 0.420578 5.04485 -3.86528 2.08088 -0.984809 -3.88564 2.15325 -0.997435 -3.90097 2.20704 -0.98628 -3.91869 2.26742 -0.980875 -3.94021 2.34201 -0.987912 -3.96181 2.41769 -0.9929 -3.97962 2.47933 -0.982151 -4.00374 2.56377 -0.989692 -4.02888 2.64826 -0.994741 -4.05066 2.72637 -0.99094 -4.07596 2.81311 -0.991094 -4.10128 2.89996 -0.98885 -4.13054 3.00316 -0.995852 -4.16089 3.10746 -0.999712 -4.19127 3.21192 -1.00028 -4.22179 3.31853 -0.997843 -4.25228 3.4243 -0.991964 -4.29035 3.55709 -0.998586 -4.32596 3.68145 -0.995963 -4.36766 3.82421 -0.999199 -4.41091 3.9759 -1.00258 -4.45525 4.12877 -1.00113 -4.50471 4.30019 -1.00353 -4.55421 4.47189 -1.00034 -4.6124 4.67181 -1.00401 -4.67222 4.88181 -1.00488 -4.73566 5.10177 -1.00257 -4.80782 5.35012 -1.00382 -4.88671 5.62704 -1.00713 -4.96768 5.90432 -1.00096 -5.05803 6.22098 -0.998003 -5.16575 6.59343 -1.00213 -5.28126 6.99471 -1.00172 -5.4082 7.43559 -0.99794 -5.55521 7.94337 -0.996304 -5.72034 8.51833 -0.993004 -5.91171 9.17903 -0.988715 -6.14388 9.98439 -0.990851 -6.42196 10.9524 -0.995029 -6.77581 12.1791 -1.00881 -7.16908 13.5421 -0.99915 -7.74478 15.5371 -1.02598 -8.54643 18.319 -1.07281 -9.49306 21.6042 -1.06831 -14.202 37.9441 -0.627969 -13.0993 34.1527 1.99613 -13.1267 34.257 2.61547 -13.0879 34.1301 3.22465 -13.137 34.3099 3.85583 -13.3094 34.9171 4.53892 -12.8355 33.2793 4.97733 -12.8679 33.3986 5.6009 -12.9488 33.6891 6.25813 -13.059 34.0797 6.94735 -13.1248 34.3159 7.62478 -12.6397 32.638 7.90755 -13.3688 35.1924 9.77902 -13.3366 35.0879 10.4227 -13.6433 36.1666 11.4114 -12.7404 33.0302 11.1448 -12.7093 32.9292 11.7606 -12.8025 33.2648 12.5317 -12.6422 32.7147 12.9968 -12.5523 32.4103 13.5438 -13.047 34.145 14.925 -5.54789 8.0044 5.54504 -5.60496 8.20996 5.85589 -5.52246 7.92259 5.86685 -5.61672 8.25424 6.27784 -5.73701 8.67782 6.77413 -5.51135 7.89204 6.43063 -5.51548 7.90959 6.64791 -5.47284 7.76037 6.74238 -5.4875 7.81629 6.99773 -5.48388 7.80581 7.20684 -5.47397 7.7751 7.40476 -5.4574 7.71878 7.58378 -4.53057 4.48574 6.06639 -4.48058 4.30915 6.0246 -4.26137 3.53697 5.19468 -4.23101 3.43194 5.20398 -4.20483 3.34478 5.2349 -4.069 2.86674 4.69355 -4.05417 2.81551 4.75496 -4.13973 3.11892 5.37466 -4.1107 3.01972 5.38187 -4.05882 2.83636 5.2417 -4.08025 2.91671 5.55317 -4.01486 2.684 5.3115 -3.86702 2.16275 4.49112 -3.8267 2.021 4.35463 -3.80357 1.93895 4.3305 -3.81155 1.97033 4.54827 -3.80336 1.94276 4.64971 -3.80069 1.93564 4.80628 -3.74245 1.72908 4.47376 -3.73438 1.70282 4.58174 -3.76343 1.81174 5.07398 -3.7404 1.73029 5.06194 -3.73265 1.70544 5.21901 -3.7137 1.63802 5.25221 -3.68414 1.53739 5.16918 -3.66543 1.4733 5.20912 -3.65076 1.42182 5.30608 -3.63377 1.36595 5.39266 -3.60493 1.26348 5.27347 -3.589 1.20792 5.36753 -3.57215 1.15236 5.48053 -3.55055 1.07661 5.48422 -3.5307 1.00865 5.54599 -3.50915 0.933263 5.55697 -3.48431 0.845562 5.45724 -3.46496 0.781343 5.57479 -3.43907 0.687123 5.34233 -3.41726 0.611997 5.29763 -3.39462 0.532911 5.13158 -3.375 0.462538 5.06401 -3.35575 0.396465 5.2252 -3.93596 2.03984 -0.977843 -3.96297 2.12406 -1.00632 -3.9793 2.17776 -0.995772 -3.99658 2.23047 -0.983879 -4.02009 2.30488 -0.991924 -4.04119 2.37187 -0.990775 -4.06342 2.44089 -0.987832 -4.08941 2.52315 -0.996382 -4.1141 2.59992 -0.995942 -4.13545 2.6703 -0.986851 -4.16504 2.76241 -0.994612 -4.18991 2.84151 -0.987379 -4.21966 2.93589 -0.989846 -4.25288 3.03793 -0.995319 -4.2828 3.13458 -0.991992 -4.31368 3.23033 -0.985624 -4.34965 3.34442 -0.987406 -4.38808 3.46632 -0.990692 -4.43254 3.60558 -1.00049 -4.47216 3.7298 -0.995785 -4.51681 3.87149 -0.996889 -4.56256 4.01434 -0.993352 -4.61587 4.18338 -0.99867 -4.66677 4.34504 -0.994095 -4.73231 4.55116 -1.00534 -4.79044 4.7326 -0.997384 -4.86223 4.95869 -1.00295 -4.93421 5.18716 -1.00072 -5.01478 5.44205 -1.00156 -5.10011 5.70894 -0.997015 -5.19313 6.00344 -0.992988 -5.30451 6.35358 -0.997346 -5.41857 6.71406 -0.99222 -5.54856 7.12267 -0.988283 -5.69862 7.59809 -0.988085 -5.8707 8.13938 -0.987891 -6.06391 8.74778 -0.984052 -6.29306 9.47021 -0.983393 -6.55822 10.307 -0.979622 -6.90754 11.4096 -0.993977 -7.30377 12.6566 -0.991965 -7.84374 14.3593 -1.01106 -8.54715 16.5766 -1.03349 -9.60958 19.9266 -1.09847 -14.6648 35.8657 -0.87516 -14.6136 35.7118 -0.218496 -14.8667 36.525 1.07712 -13.9856 33.759 2.29714 -13.8248 33.2581 2.88151 -13.9716 33.7263 3.52097 -11.5051 25.9617 4.36141 -14.0671 34.0581 6.04125 -12.2788 28.4162 5.7278 -12.26 28.3627 6.24571 -11.466 25.8578 6.26226 -11.4821 25.9166 6.76146 -11.4879 25.9389 7.25764 -12.7359 29.8916 8.79141 -12.7535 29.9521 9.38524 -12.7291 29.8831 9.94751 -11.5381 26.1206 9.32438 -11.6639 26.5237 9.98053 -11.4889 25.9741 10.3142 -12.752 29.9821 12.3765 -12.2962 28.5431 12.4136 -13.5919 32.6544 14.7567 -5.88574 8.26731 6.22162 -5.82041 8.06067 6.28344 -5.80923 8.0271 6.4626 -5.77432 7.92019 6.59038 -5.72529 7.76513 6.68058 -5.75952 7.8761 6.97774 -4.71294 4.56587 6.10407 -4.63157 4.30913 5.96544 -4.5716 4.11876 5.89666 -4.56395 4.09641 6.0433 -4.58703 4.17265 6.33454 -4.54631 4.0453 6.34652 -4.27604 3.17968 5.24886 -4.25672 3.11999 5.31622 -4.22719 3.02828 5.33217 -4.16156 2.81964 5.151 -4.14592 2.77031 5.22954 -4.16518 2.83348 5.51534 -4.08779 2.58758 5.23597 -3.94518 2.12874 4.5072 -3.92414 2.06148 4.52098 -3.91777 2.04576 4.64125 -3.85633 1.84811 4.36308 -3.86013 1.86237 4.55409 -3.82871 1.76327 4.47951 -3.81155 1.70883 4.51366 -3.80894 1.70208 4.67771 -3.79857 1.67096 4.78605 -3.8121 1.7168 5.14033 -3.80613 1.70176 5.33546 -3.76773 1.57688 5.17739 -3.75106 1.52611 5.26602 -3.72883 1.45525 5.2865 -3.70937 1.3941 5.34442 -3.68893 1.33244 5.41119 -3.66942 1.26968 5.47701 -3.66289 1.25185 5.79713 -3.62701 1.13819 5.60555 -3.59657 1.04204 5.49046 -3.57436 0.970709 5.52177 -3.5496 0.893495 5.51225 -3.52961 0.832832 5.66026 -3.496 0.723199 5.26942 -3.47372 0.652611 5.27517 -3.45087 0.578525 5.2097 -3.42845 0.508331 5.18279 -3.40666 0.437068 5.09464 -4.03222 2.07542 -0.992664 -4.0552 2.14098 -0.997768 -4.07584 2.20011 -0.993926 -4.09649 2.25932 -0.988386 -4.11721 2.31961 -0.981298 -4.14511 2.40058 -0.993204 -4.16828 2.46859 -0.989318 -4.19491 2.54418 -0.990036 -4.22161 2.62087 -0.988607 -4.25069 2.70424 -0.991328 -4.27749 2.78216 -0.985354 -4.30917 2.87534 -0.989279 -4.3443 2.97619 -0.996212 -4.37715 3.07159 -0.994348 -4.41345 3.17468 -0.995191 -4.44634 3.27038 -0.987235 -4.48625 3.38332 -0.987189 -4.53113 3.51268 -0.993896 -4.57611 3.64325 -0.996458 -4.61873 3.76738 -0.989875 -4.67084 3.91651 -0.993605 -4.72549 4.07453 -0.996991 -4.7813 4.23475 -0.995187 -4.83966 4.40389 -0.99234 -4.90765 4.6002 -0.99631 -4.97926 4.80645 -0.997493 -5.05198 5.01399 -0.991739 -5.13588 5.25759 -0.993451 -5.22698 5.52089 -0.993884 -5.32525 5.80294 -0.99169 -5.43577 6.12221 -0.992423 -5.55354 6.46138 -0.987882 -5.6907 6.8563 -0.988334 -5.84375 7.29843 -0.988127 -6.01018 7.77917 -0.982212 -6.20676 8.34416 -0.979971 -6.4412 9.02194 -0.983269 -6.70334 9.7757 -0.978001 -7.02742 10.7089 -0.979833 -7.41605 11.8309 -0.98053 -7.93309 13.3205 -0.997589 -8.58741 15.2069 -1.0146 -9.81641 18.7495 -1.15983 -14.9816 33.6386 -1.08106 -14.9444 33.5373 -0.460328 -17.6789 41.4245 -0.0569551 -15.5499 35.2961 0.751426 -14.9611 33.6132 2.60781 -12.4635 26.4157 2.7495 -12.3765 26.1671 3.21196 -12.2666 25.8549 3.65979 -15.0972 34.0342 5.76218 -12.2895 25.9342 5.106 -12.3245 26.0413 5.60889 -12.2898 25.9433 6.07855 -12.3188 26.033 6.58795 -12.2843 25.9382 7.06086 -12.3461 26.1199 7.60473 -12.3531 26.1449 8.11679 -12.1368 25.5242 8.44404 -12.1987 25.7067 9.00419 -12.4526 26.4462 9.76325 -12.5147 26.6296 10.3611 -12.5575 26.7576 10.9516 -12.6714 27.0947 11.6373 -12.6604 27.0666 12.1915 -12.6534 27.0531 12.7593 -12.7037 27.2027 13.41 -6.10162 8.10751 6.45805 -4.80932 4.37427 5.65486 -4.77577 4.2795 5.70534 -4.76323 4.2443 5.82991 -4.6946 4.04468 5.74604 -4.67713 3.99583 5.85211 -4.63104 3.86393 5.84663 -4.4574 3.35777 5.29875 -4.33855 3.01242 4.94569 -4.32939 2.98511 5.05144 -4.3468 3.03806 5.2908 -4.28266 2.85115 5.14509 -4.24997 2.75795 5.14742 -4.23607 2.71936 5.24234 -4.19706 2.6076 5.20649 -4.16276 2.50632 5.1855 -4.02391 2.10257 4.5407 -3.99306 2.01016 4.50033 -3.96007 1.9163 4.44853 -3.92948 1.82865 4.40351 -3.90382 1.75399 4.38385 -3.89593 1.73074 4.49189 -4.18045 2.57402 6.9363 -3.91531 1.79167 5.03622 -3.88075 1.69057 4.95795 -3.87211 1.66775 5.11434 -3.86218 1.64001 5.27097 -3.81521 1.50455 5.33416 -3.78486 1.42024 5.29609 -3.76195 1.3533 5.3341 -3.76982 1.37844 5.81029 -3.71377 1.21539 5.38691 -3.71435 1.22098 5.84409 -3.6684 1.0855 5.50368 -3.64307 1.01291 5.52597 -3.61474 0.930471 5.46746 -3.59502 0.873319 5.62592 -3.5607 0.7737 5.37547 -3.53644 0.70276 5.39196 -3.51302 0.63766 5.50698 -3.48495 0.554924 5.3012 -3.45928 0.479495 5.08384 -3.43692 0.412219 5.03495 -4.12806 2.1034 -0.999399 -4.15062 2.16137 -0.996317 -4.17326 2.22042 -0.991586 -4.19728 2.28613 -0.992399 -4.22237 2.35288 -0.99137 -4.2509 2.42719 -0.995244 -4.27366 2.48758 -0.983572 -4.30465 2.56965 -0.989949 -4.32993 2.63878 -0.981028 -4.36202 2.72202 -0.982666 -4.39419 2.80638 -0.981856 -4.43468 2.91354 -0.99645 -4.46352 2.99165 -0.984293 -4.49931 3.08593 -0.981196 -4.54099 3.1955 -0.986305 -4.57933 3.29869 -0.982564 -4.62218 3.41054 -0.980786 -4.67351 3.54736 -0.990914 -4.72249 3.67778 -0.991598 -4.77151 3.8084 -0.987887 -4.82756 3.9564 -0.98939 -4.89073 4.12283 -0.994958 -4.95043 4.28093 -0.990578 -5.01725 4.45751 -0.989264 -5.0937 4.66129 -0.994168 -5.17477 4.87496 -0.99599 -5.25497 5.09006 -0.990466 -5.35027 5.34002 -0.991779 -5.44476 5.59246 -0.984297 -5.56053 5.89926 -0.987562 -5.67745 6.20754 -0.979895 -5.82071 6.58783 -0.984683 -5.97229 6.98909 -0.981256 -6.14781 7.45492 -0.981588 -6.34125 7.96805 -0.977177 -6.57037 8.57413 -0.97651 -6.82356 9.24633 -0.968367 -7.14454 10.0954 -0.971748 -7.52784 11.1133 -0.975099 -8.01465 12.4013 -0.986228 -8.68659 14.1834 -1.02298 -9.41002 16.1003 -1.01069 -10.7738 19.714 -1.11602 -15.365 31.8842 -0.69664 -15.3723 31.9079 -0.108834 -18.5074 40.2203 0.333082 -18.5156 40.2446 1.07624 -14.1978 28.8074 1.5946 -14.1318 28.6358 2.11849 -13.9668 28.2023 2.62178 -13.5458 27.0909 3.05835 -13.4988 26.9695 3.54818 -13.5367 27.0739 4.06049 -13.5435 27.0956 4.5675 -15.9712 33.5383 6.04878 -14.5483 29.7709 6.60297 -13.6488 27.3893 6.67266 -13.6976 27.5222 7.22755 -13.6398 27.3716 7.7214 -12.7884 25.1165 7.65043 -12.7866 25.1139 8.14178 -12.8175 25.2012 8.6654 -12.8219 25.2161 9.17386 -12.7663 25.0717 9.63245 -12.7408 25.0072 10.1208 -13.3112 26.5263 11.2301 -13.2716 26.4258 11.7447 -13.5 27.0367 12.5703 -13.4365 26.8753 13.667 -13.6487 27.4458 14.5485 -13.5599 27.2131 15.0465 -4.94907 4.32459 5.55147 -4.91364 4.23193 5.60176 -4.88781 4.16316 5.68023 -4.90355 4.20637 5.90326 -4.80465 3.94409 5.7326 -4.83759 4.03392 6.02679 -4.61121 3.42829 5.35075 -4.54978 3.26445 5.26907 -4.42843 2.94235 4.93671 -4.5214 3.19244 5.48149 -4.47091 3.05764 5.43234 -4.50281 3.14484 5.7529 -4.47696 3.07654 5.82074 -4.29449 2.58678 5.10752 -4.27222 2.5288 5.16541 -4.24627 2.4611 5.20459 -4.21637 2.38021 5.2158 -4.03656 1.89747 4.34402 -4.01535 1.84295 4.3717 -4.01146 1.83389 4.50794 -3.95639 1.68568 4.30409 -4.15262 2.21723 5.87672 -4.03263 1.89341 5.22824 -3.97772 1.74747 5.03009 -3.95283 1.68199 5.05473 -3.93283 1.62807 5.11631 -3.89913 1.53916 5.06217 -3.92028 1.60039 5.5541 -3.89402 1.52832 5.58568 -3.84608 1.39931 5.37323 -3.81884 1.32863 5.39133 -3.79273 1.25931 5.41797 -3.75886 1.16999 5.33532 -3.74485 1.13512 5.56582 -3.71187 1.04511 5.47038 -3.69155 0.993586 5.64038 -3.6603 0.911792 5.59127 -3.63453 0.844025 5.6699 -3.59175 0.725011 5.15964 -3.56856 0.664429 5.26493 -3.54394 0.599391 5.3393 -3.51631 0.527522 5.29249 -3.48993 0.454592 5.10444 -4.27399 2.24621 -0.996149 -4.29528 2.29879 -0.981978 -4.32804 2.37746 -0.99391 -4.35515 2.44423 -0.989994 -4.38228 2.51109 -0.98408 -4.41628 2.59303 -0.989374 -4.44692 2.66859 -0.985717 -4.48102 2.75178 -0.986066 -4.51757 2.84266 -0.990017 -4.55277 2.92703 -0.985127 -4.59285 3.02672 -0.989337 -4.63159 3.1199 -0.984608 -4.67285 3.22183 -0.98253 -4.71519 3.32485 -0.97731 -4.76343 3.44322 -0.979098 -4.81871 3.5789 -0.987199 -4.86819 3.7006 -0.980951 -4.9246 3.83765 -0.980317 -4.98811 3.9931 -0.984247 -5.05522 4.15841 -0.987388 -5.12338 4.32393 -0.984841 -5.2021 4.51557 -0.989066 -5.28451 4.71814 -0.990754 -5.36346 4.91243 -0.981495 -5.46108 5.15117 -0.983777 -5.57036 5.41717 -0.988191 -5.67527 5.67606 -0.979706 -5.79994 5.98057 -0.978022 -5.94234 6.32994 -0.980384 -6.09751 6.70783 -0.97864 -6.2705 7.1318 -0.976497 -6.47044 7.62025 -0.976431 -6.68831 8.15607 -0.970222 -6.9529 8.8021 -0.970195 -7.24712 9.52297 -0.962262 -7.61654 10.4274 -0.964037 -8.09176 11.5906 -0.978256 -8.71854 13.123 -1.0079 -9.40931 14.8159 -1.00227 -15.7945 30.4448 -0.92249 -15.7251 30.278 -0.346747 -18.571 37.2462 0.0266931 -22.2395 46.2272 0.64533 -22.2377 46.227 1.50942 -14.6727 27.7143 1.83299 -14.1661 26.4776 2.2891 -14.2798 26.7589 2.80094 -14.3595 26.9573 3.31752 -14.3685 26.9809 3.82462 -13.4203 24.6607 4.04356 -13.4386 24.7091 4.51503 -13.432 24.6954 4.98022 -13.4256 24.6839 5.44752 -13.3978 24.6181 5.90653 -13.4633 24.7808 6.41636 -13.4295 24.6994 6.87739 -13.4102 24.6557 7.34857 -13.4723 24.8106 7.87774 -12.9588 23.5545 7.99374 -12.9653 23.5728 8.47178 -13.0713 23.8373 9.04017 -13.0777 23.8544 9.53479 -13.069 23.836 10.0225 -13.9896 26.0984 11.4386 -14.4382 27.2015 12.465 -14.4502 27.2357 13.0681 -14.3994 27.1131 13.6081 -14.2005 26.6286 13.9726 -14.2517 26.759 14.6417 -5.06962 4.23036 5.55785 -5.04911 4.18146 5.65934 -5.05015 4.18479 5.82887 -5.01052 4.08924 5.87633 -4.92026 3.86671 5.7493 -4.95975 3.96399 6.06 -4.52191 2.88639 4.67049 -4.50931 2.85335 4.75762 -4.51761 2.8767 4.93523 -4.48355 2.79313 4.94801 -4.60282 3.08808 5.60001 -4.48197 2.79153 5.25759 -4.46596 2.75112 5.35371 -4.47197 2.76715 5.56284 -4.36653 2.50863 5.23755 -4.39562 2.58151 5.56945 -4.34215 2.45013 5.48451 -4.31908 2.39401 5.55864 -4.39246 2.57713 6.20548 -4.29006 2.32365 5.82365 -4.34931 2.47353 6.4506 -4.23942 2.20237 5.9863 -4.07968 1.80402 5.1013 -4.02709 1.67676 4.93856 -4.02606 1.67482 5.16123 -4.02142 1.66366 5.37538 -3.9804 1.56515 5.5842 -3.92842 1.43545 5.37311 -3.8928 1.34841 5.31408 -3.85342 1.25307 5.20444 -3.83162 1.19986 5.29823 -3.8113 1.15148 5.43063 -3.76733 1.04079 5.18771 -3.75113 1.00297 5.41677 -3.70831 0.897538 5.13984 -3.7046 0.889682 5.70505 -3.65552 0.766603 5.18603 -3.6259 0.695523 5.13249 -3.6067 0.648558 5.47677 -3.57408 0.570086 5.31097 -3.54559 0.499736 5.2735 -3.51811 0.429374 5.03477 -4.3675 2.25043 -0.979071 -4.40219 2.32793 -0.992162 -4.42786 2.38705 -0.982452 -4.46371 2.4667 -0.991052 -4.49284 2.53349 -0.984249 -4.52535 2.60687 -0.981902 -4.56137 2.68887 -0.98361 -4.59404 2.76447 -0.976667 -4.63354 2.85423 -0.979384 -4.67411 2.94507 -0.979359 -4.7182 3.04457 -0.982191 -4.75888 3.1367 -0.976123 -4.81002 3.25361 -0.983669 -4.85425 3.3546 -0.976563 -4.90994 3.48037 -0.981777 -4.96228 3.59978 -0.977742 -5.02504 3.74312 -0.984275 -5.08546 3.88005 -0.981164 -5.15391 4.03432 -0.982672 -5.22943 4.20606 -0.987497 -5.29459 4.35426 -0.973763 -5.38171 4.55234 -0.979372 -5.47352 4.76133 -0.981849 -5.56638 4.97061 -0.97704 -5.66639 5.19853 -0.971901 -5.78608 5.47097 -0.975712 -5.91394 5.76212 -0.976302 -6.05097 6.072 -0.972476 -6.20673 6.42672 -0.972002 -6.37978 6.81861 -0.969585 -6.57625 7.26621 -0.968286 -6.7935 7.75891 -0.962558 -7.05029 8.34229 -0.960994 -7.34421 9.00884 -0.956499 -7.68938 9.79368 -0.951709 -8.14357 10.8248 -0.964382 -8.69779 12.0847 -0.977159 -9.37037 13.6105 -0.98251 -10.3833 15.912 -1.03324 -15.7441 28.087 -1.0583 -15.5231 27.5864 -0.500211 -15.5147 27.5705 0.0197746 -15.2266 26.9251 1.5615 -14.6042 25.5136 2.0126 -14.5709 25.4389 2.48801 -14.4784 25.2297 2.95108 -14.486 25.251 3.42936 -14.5389 25.3725 3.92169 -14.5197 25.3321 4.39852 -14.6053 25.529 4.91242 -14.5162 25.3282 5.36723 -14.4876 25.2643 5.84358 -14.5536 25.4176 6.36658 -13.9523 24.056 7.01902 -13.9632 24.0813 7.50299 -15.0428 26.5383 8.70595 -14.7731 25.9287 9.051 -13.86 23.8542 8.88575 -13.6832 23.4549 9.23566 -13.6196 23.3128 9.67046 -13.6284 23.3351 10.1709 -13.6747 23.4425 10.7144 -15.1366 26.7725 12.6944 -15.0009 26.4638 13.1405 -14.8245 26.0668 13.5376 -14.8655 26.1623 14.1771 -15.3993 27.3798 15.4301 -5.25144 4.28905 5.74928 -5.18389 4.13542 5.72432 -5.06304 3.85945 5.53407 -5.04628 3.82187 5.64578 -5.0379 3.8044 5.78898 -5.11246 3.97538 6.21263 -4.61525 2.83775 4.69337 -4.58889 2.77942 4.7391 -4.63242 2.87802 5.04089 -4.51917 2.61917 4.76013 -4.63808 2.89384 5.3871 -4.58539 2.77229 5.33952 -4.53648 2.66225 5.30596 -4.48136 2.53565 5.23452 -4.45504 2.4769 5.29217 -4.42865 2.41711 5.34879 -4.38914 2.32786 5.34147 -4.41441 2.38708 5.67648 -4.38328 2.31602 5.72266 -4.34732 2.23379 5.7399 -4.3151 2.16165 5.78325 -4.3699 2.28898 6.39493 -4.31222 2.15581 6.28898 -4.11976 1.71455 5.18648 -4.19044 1.8811 6.30503 -4.13494 1.75332 6.16887 -4.10894 1.69472 6.2903 -3.9681 1.37157 5.2659 -3.94038 1.30789 5.30318 -3.91145 1.24172 5.32939 -3.87504 1.15853 5.26608 -3.84756 1.09763 5.31915 -3.80075 0.990552 5.06496 -3.77409 0.928466 5.09525 -3.74501 0.861985 5.09464 -3.71741 0.800328 5.13243 -3.68861 0.736193 5.15923 -3.65665 0.663749 5.05511 -3.63912 0.626549 5.61857 -3.60385 0.544746 5.36214 -3.57422 0.477367 5.46411 -4.45112 2.22708 -1.00421 -4.47528 2.27749 -0.98986 -4.50188 2.3355 -0.981104 -4.53966 2.41398 -0.990963 -4.56735 2.4731 -0.978566 -4.60179 2.54531 -0.977377 -4.63973 2.62611 -0.980444 -4.6777 2.70705 -0.980914 -4.71332 2.78153 -0.972838 -4.75918 2.87769 -0.980325 -4.80176 2.96847 -0.978911 -4.84437 3.0594 -0.974502 -4.88799 3.15041 -0.9672 -4.94208 3.26622 -0.973114 -4.99718 3.38214 -0.975237 -5.05582 3.50684 -0.978419 -5.11556 3.63267 -0.977461 -5.17982 3.76723 -0.976967 -5.24763 3.91061 -0.976433 -5.31998 4.06276 -0.975465 -5.39243 4.21618 -0.969253 -5.48095 4.40417 -0.974178 -5.57052 4.59243 -0.972516 -5.67518 4.81547 -0.979389 -5.77751 5.0322 -0.97462 -5.89238 5.27412 -0.972589 -6.00843 5.51841 -0.961772 -6.15667 5.83216 -0.967436 -6.31409 6.16468 -0.967587 -6.48421 6.52471 -0.963882 -6.67157 6.92095 -0.957586 -6.90142 7.40738 -0.961662 -7.14498 7.92064 -0.954347 -7.43461 8.5332 -0.951572 -7.76783 9.23656 -0.94559 -8.22389 10.2 -0.965766 -8.71011 11.2291 -0.960768 -9.38443 12.6528 -0.981339 -10.3312 14.6555 -1.03069 -11.5913 17.317 -1.08543 -16.7375 28.1939 -0.827773 -16.6935 28.1021 -0.285553 -19.2365 33.4782 0.0972839 -17.7558 30.3518 0.764122 -15.4071 25.3911 1.7736 -15.4157 25.4116 2.25742 -15.3738 25.3255 2.73557 -15.3674 25.3136 3.21779 -15.3955 25.3744 3.7088 -14.6595 23.8204 3.99908 -15.368 25.3208 4.67724 -15.3431 25.2679 5.15902 -15.0777 24.7094 5.54709 -15.2431 25.062 6.10318 -14.9014 24.3408 6.43426 -15.2015 24.9752 7.07326 -14.6176 23.7431 7.24461 -14.5271 23.554 7.66892 -15.6777 25.9898 8.8964 -14.6332 23.7825 8.70596 -14.5945 23.7006 9.17095 -14.4912 23.4838 9.58742 -14.3926 23.2777 10.0046 -14.4071 23.3103 10.5182 -14.7161 23.9649 11.3111 -15.1099 24.8044 12.7807 -15.5953 25.8329 13.8642 -15.4312 25.4882 14.2795 -15.1883 24.977 14.5962 -5.29995 4.0458 5.57541 -5.22968 3.89711 5.54582 -5.18503 3.80228 5.58147 -5.14751 3.72411 5.63827 -5.07945 3.57979 5.59824 -4.88841 3.17439 5.15999 -4.72171 2.8198 4.7646 -4.67917 2.72991 4.76094 -4.61788 2.60062 4.68828 -4.71853 2.81462 5.20232 -5.10044 3.62779 6.83444 -4.62993 2.62672 5.18892 -4.65462 2.6811 5.466 -4.55434 2.46828 5.21893 -4.52477 2.40623 5.26676 -4.5023 2.35953 5.34933 -4.44891 2.24486 5.27779 -4.43725 2.2226 5.42165 -4.43141 2.21087 5.60259 -4.40413 2.15183 5.67349 -4.38431 2.11212 5.79925 -4.35478 2.04915 5.86876 -4.39348 2.1323 6.39923 -4.35102 2.04224 6.4125 -4.25178 1.8334 6.32802 -4.20076 1.72469 6.25827 -4.04275 1.38629 5.18849 -4.02161 1.34213 5.30377 -3.97969 1.25292 5.21356 -3.94527 1.18209 5.19969 -3.91558 1.11936 5.23344 -3.89467 1.07544 5.39436 -3.84229 0.963201 5.0899 -3.80487 0.884327 4.97082 -3.78139 0.833901 5.09853 -3.7518 0.772341 5.13583 -3.71503 0.693764 4.94264 -3.69416 0.651398 5.29672 -3.66329 0.585729 5.33052 -3.62591 0.505154 4.83336 -3.59697 0.4425 4.40443 -4.51256 2.16508 -0.986235 -4.54438 2.22731 -0.987139 -4.57628 2.29063 -0.986295 -4.60825 2.35503 -0.983502 -4.6446 2.42596 -0.98557 -4.6776 2.4905 -0.978787 -4.71405 2.56264 -0.97661 -4.75394 2.64238 -0.978538 -4.79148 2.71568 -0.971721 -4.83584 2.80313 -0.974663 -4.88028 2.89172 -0.974759 -4.92924 2.98891 -0.977816 -4.97479 3.07873 -0.971973 -5.02486 3.17718 -0.968692 -5.08283 3.29083 -0.972829 -5.14432 3.41324 -0.978124 -5.20347 3.52922 -0.974274 -5.27059 3.66148 -0.976193 -5.33437 3.78739 -0.968862 -5.40957 3.93722 -0.970806 -5.49031 4.09579 -0.971821 -5.57566 4.26418 -0.971452 -5.66557 4.44142 -0.969151 -5.76454 4.63609 -0.968279 -5.87609 4.85688 -0.971592 -5.98877 5.07901 -0.966869 -6.11405 5.32734 -0.964333 -6.24948 5.59425 -0.959186 -6.40656 5.90472 -0.959552 -6.58631 6.2588 -0.962941 -6.77977 6.64039 -0.96138 -7.00052 7.07545 -0.960858 -7.23853 7.54691 -0.953549 -7.51397 8.09032 -0.946465 -7.83385 8.72233 -0.939376 -8.24803 9.53944 -0.948129 -8.73052 10.4911 -0.951314 -9.36101 11.7371 -0.969417 -10.1506 13.2943 -0.987944 -11.2555 15.4753 -1.03098 -16.4151 25.6614 -0.933335 -16.8251 26.4723 -0.484988 -16.8793 26.5814 0.0214584 -23.5681 39.7846 0.280766 -18.1791 29.1486 1.04646 -16.0662 24.9789 1.52513 -16.2317 25.3063 2.01887 -16.2346 25.3143 2.50706 -16.0985 25.0478 2.97488 -16.1354 25.1211 3.4668 -16.1541 25.1594 3.95898 -15.8914 24.6414 4.37758 -15.8759 24.6118 4.85504 -15.8833 24.6285 5.34177 -15.642 24.154 5.73453 -15.5935 24.0594 6.19422 -15.1307 23.1475 6.45782 -15.1172 23.1199 6.91734 -15.1782 23.2415 7.42092 -15.651 24.1791 8.67936 -14.8866 22.6717 9.146 -14.9225 22.744 9.6581 -14.9288 22.7573 10.155 -14.8928 22.6873 10.6227 -15.8864 24.6524 12.0166 -15.8221 24.5274 12.5123 -16.5705 26.0081 13.8123 -16.4665 25.8054 14.3108 -17.3254 27.5039 15.8493 -17.2296 27.3175 16.4039 -5.66038 4.45161 6.22838 -5.29949 3.73714 5.62092 -5.46252 4.06153 6.2525 -4.88473 2.91612 4.74107 -4.79169 2.73194 4.59495 -4.74266 2.63556 4.57394 -4.73757 2.62464 4.69136 -4.69654 2.54288 4.6918 -4.70559 2.56212 4.8684 -4.67739 2.50612 4.91823 -5.0846 3.31554 6.64736 -4.63868 2.43188 5.09339 -4.63618 2.42704 5.25565 -4.61509 2.38573 5.34766 -4.56128 2.27906 5.29535 -4.52381 2.20496 5.3128 -4.60698 2.37005 5.93171 -4.52395 2.20602 5.73887 -4.47009 2.09904 5.68027 -4.45046 2.06177 5.81502 -4.42714 2.01476 5.93085 -4.44071 2.04335 6.3015 -4.38582 1.93562 6.24675 -4.36167 1.8885 6.39984 -4.32805 1.82202 6.49488 -4.25264 1.67204 6.25083 -4.1051 1.37918 5.32342 -4.05766 1.2839 5.20502 -4.05027 1.27064 5.49508 -4.02363 1.21873 5.60908 -4.01062 1.19377 5.91929 -3.94335 1.05861 5.51876 -3.88062 0.934038 5.09464 -3.88697 0.948001 5.80868 -3.81341 0.803091 5.06235 -3.78395 0.742988 5.10899 -3.75089 0.678071 5.09461 -3.73011 0.640092 5.61819 -3.68235 0.543812 4.83211 -3.6506 0.478811 4.47381 -4.58205 2.12162 -0.989253 -4.6115 2.17727 -0.984008 -4.64196 2.23295 -0.977071 -4.67916 2.30166 -0.98234 -4.71307 2.36499 -0.978709 -4.748 2.42835 -0.973186 -4.78637 2.4993 -0.972267 -4.82476 2.57037 -0.969051 -4.87096 2.65549 -0.976099 -4.91388 2.73524 -0.974247 -4.95681 2.81512 -0.969897 -5.00863 2.91005 -0.974568 -5.06054 3.00614 -0.976092 -5.11247 3.10239 -0.97442 -5.16105 3.19225 -0.964098 -5.2264 3.3123 -0.97171 -5.29184 3.43357 -0.975078 -5.35838 3.55597 -0.974305 -5.42495 3.67858 -0.969238 -5.50055 3.81846 -0.969194 -5.5762 3.95858 -0.964157 -5.65739 4.10743 -0.95839 -5.76009 4.29834 -0.968075 -5.85489 4.47343 -0.962804 -5.96771 4.68209 -0.966432 -6.08165 4.89206 -0.962424 -6.20918 5.12817 -0.961108 -6.34229 5.37323 -0.954368 -6.49805 5.66173 -0.954346 -6.67745 5.99373 -0.958449 -6.86699 6.34352 -0.955696 -7.07576 6.72939 -0.950261 -7.32279 7.1849 -0.95015 -7.58804 7.67583 -0.941809 -7.89712 8.24534 -0.933969 -8.25824 8.91302 -0.926053 -8.74664 9.81459 -0.941342 -9.33447 10.9018 -0.956017 -10.052 12.227 -0.967986 -11.0209 14.0167 -0.996938 -12.0962 16.0028 -0.980307 -17.2381 25.5016 -0.704892 -17.4314 25.8589 -0.223644 -19.8423 30.3137 0.149816 -17.0756 25.2059 1.28445 -16.8233 24.7413 1.76232 -16.8294 24.7529 2.2459 -16.7508 24.6076 2.71973 -16.7863 24.6748 3.20786 -16.8229 24.7431 3.70012 -16.9353 24.9524 4.21501 -17.128 25.31 4.76243 -16.4877 24.1269 5.06467 -16.5175 24.1826 5.55731 -16.5147 24.1798 6.04248 -16.5321 24.2114 6.5389 -16.1355 23.4793 6.84742 -16.1496 23.5067 7.33656 -16.0629 23.3471 7.77582 -16.0917 23.4005 8.28029 -16.047 23.32 8.74627 -16.008 23.2494 9.21732 -15.9463 23.1364 9.67512 -16.2675 23.7306 10.4182 -16.4324 24.0359 11.0717 -16.9399 24.9756 12.0297 -18.1769 27.2654 13.675 -17.3015 25.6477 13.5034 -17.1097 25.2927 13.9187 -17.1074 25.2895 14.5177 -17.6413 26.2812 16.3362 -4.91138 2.74099 4.57955 -4.85707 2.64057 4.55147 -4.82694 2.58636 4.59472 -4.79775 2.53104 4.63691 -4.77788 2.49482 4.71164 -4.73396 2.41511 4.70939 -4.68878 2.33193 4.69641 -5.15862 3.20221 6.59617 -5.08959 3.07431 6.56235 -4.71233 2.37622 5.27437 -4.66246 2.28272 5.24962 -4.62537 2.21408 5.27661 -4.82938 2.59455 6.42145 -4.77513 2.49332 6.41764 -4.56877 2.11091 5.63536 -4.5271 2.03387 5.64928 -4.52977 2.03984 5.9145 -4.48584 1.95885 5.92673 -4.4441 1.88011 5.94674 -4.41891 1.83405 6.07957 -4.37628 1.75672 6.10653 -4.20504 1.43872 5.14899 -4.16293 1.35962 5.10054 -4.12919 1.29734 5.11829 -4.1147 1.27261 5.32998 -4.07376 1.19572 5.28722 -4.07157 1.19352 5.68503 -4.02582 1.10684 5.60074 -3.98031 1.02406 5.51445 -3.94686 0.962376 5.58493 -3.91092 0.895295 5.62455 -3.85066 0.782885 5.14525 -3.81424 0.715224 5.09169 -3.79594 0.682614 5.64562 -3.75596 0.608556 5.55986 -3.71035 0.523078 4.87286 -3.67779 0.464411 4.88401 -4.67992 2.13285 -0.987472 -4.71131 2.18742 -0.981388 -4.74277 2.24308 -0.973757 -4.78291 2.31065 -0.978093 -4.81877 2.3729 -0.973623 -4.86243 2.44917 -0.980316 -4.89838 2.51263 -0.971701 -4.93971 2.58256 -0.967452 -4.98449 2.66012 -0.967108 -5.03372 2.74525 -0.970276 -5.08303 2.83153 -0.970597 -5.13337 2.91789 -0.968026 -5.18279 3.00545 -0.962603 -5.24653 3.11555 -0.970516 -5.29805 3.2043 -0.95876 -5.36635 3.32326 -0.96464 -5.43568 3.44236 -0.966331 -5.50517 3.56368 -0.963725 -5.57912 3.69272 -0.961635 -5.65862 3.83046 -0.959414 -5.74366 3.97692 -0.956565 -5.83768 4.13974 -0.956892 -5.94077 4.31996 -0.959447 -6.04591 4.50038 -0.95522 -6.16011 4.69827 -0.951822 -6.29336 4.92978 -0.955331 -6.43224 5.17124 -0.953566 -6.58121 5.43027 -0.94924 -6.75026 5.72307 -0.947331 -6.9439 6.05836 -0.948804 -7.1532 6.42001 -0.945688 -7.38273 6.81774 -0.938796 -7.64595 7.27554 -0.933518 -7.94037 7.78484 -0.923807 -8.28416 8.38139 -0.914964 -8.73193 9.1574 -0.922665 -9.30949 10.1586 -0.944849 -9.9476 11.2645 -0.94592 -10.8297 12.7937 -0.971311 -11.9971 14.8169 -1.00509 -17.6368 24.5933 -0.918036 -18.0859 25.3725 -0.476846 -18.0764 25.3569 0.0271145 -17.81 24.8962 1.03155 -17.8172 24.9092 1.52457 -17.2812 23.9812 1.98057 -17.415 24.214 2.4698 -17.3157 24.0426 2.93667 -17.2869 23.9925 3.41003 -17.4723 24.315 3.928 -17.5334 24.4225 4.43046 -18.1304 25.4573 5.08972 -18.1668 25.5203 5.61649 -17.2432 23.9206 5.81037 -16.7871 23.1311 6.12237 -16.829 23.2032 6.61612 -16.8115 23.1746 7.08954 -16.6311 22.861 7.48373 -16.5621 22.7438 7.92917 -16.6007 22.8107 8.43521 -16.7585 23.0851 9.02214 -16.7061 22.994 9.48939 -16.8372 23.2233 10.0856 -17.5494 24.4594 11.121 -17.4917 24.3596 11.6284 -17.6567 24.6457 12.3183 -18.2269 25.6366 13.3745 -18.2268 25.6354 13.9777 -18.1786 25.5542 14.5466 -18.2608 25.6973 15.2476 -18.1788 25.5551 15.7996 -18.259 25.6958 16.5285 -5.02187 2.73235 4.53975 -4.99419 2.68452 4.59339 -4.95068 2.6105 4.60517 -4.90019 2.52253 4.59027 -4.86905 2.46829 4.63162 -4.82893 2.40023 4.6464 -4.79541 2.34057 4.67672 -4.75856 2.27659 4.69698 -5.19714 3.04062 6.4388 -5.13656 2.93387 6.43731 -4.76714 2.29305 5.22145 -4.72587 2.22224 5.24007 -4.68684 2.15468 5.26623 -4.66036 2.10807 5.34572 -4.64201 2.07625 5.47058 -4.59952 2.00226 5.48426 -4.54092 1.90092 5.4123 -4.50296 1.83442 5.4409 -4.52193 1.86957 5.80868 -4.48983 1.81253 5.89373 -4.45906 1.75933 5.99701 -4.42491 1.70081 6.09007 -4.25748 1.40837 5.18732 -4.21955 1.3439 5.19639 -4.16856 1.25531 5.0872 -4.14227 1.20988 5.19096 -4.11239 1.15717 5.26468 -4.10427 1.14385 5.61322 -4.07366 1.09105 5.74512 -4.01156 0.982893 5.45045 -3.9786 0.926118 5.55993 -3.94208 0.863521 5.62857 -3.88621 0.765254 5.25777 -3.86006 0.720761 5.58276 -3.817 0.64694 5.47779 -3.779 0.580182 5.5012 -3.73613 0.504899 5.04336 -4.74104 2.08321 -0.983513 -4.77337 2.13669 -0.978284 -4.81106 2.19658 -0.978619 -4.84783 2.25763 -0.977001 -4.89328 2.33062 -0.987052 -4.92678 2.38638 -0.974835 -4.96902 2.45509 -0.973937 -5.01128 2.52391 -0.970742 -5.05799 2.60028 -0.971657 -5.10471 2.67679 -0.969976 -5.15251 2.75435 -0.965851 -5.20814 2.84604 -0.970693 -5.26585 2.93876 -0.972398 -5.31822 3.02522 -0.965342 -5.37604 3.11925 -0.960704 -5.4472 3.23593 -0.968597 -5.51944 3.35376 -0.972251 -5.58285 3.45677 -0.96179 -5.66066 3.58345 -0.962117 -5.73857 3.71136 -0.957799 -5.82639 3.85451 -0.957712 -5.91532 3.99886 -0.952387 -6.01875 4.16806 -0.954203 -6.12766 4.34506 -0.953642 -6.25116 4.54803 -0.957976 -6.36575 4.73523 -0.947147 -6.51134 4.97203 -0.950313 -6.657 5.20927 -0.944389 -6.82278 5.48123 -0.942032 -7.00506 5.77735 -0.938087 -7.21752 6.12554 -0.939741 -7.44658 6.49908 -0.935663 -7.70673 6.92289 -0.931895 -7.98363 7.37425 -0.918399 -8.30623 7.90202 -0.906512 -8.7431 8.61433 -0.917506 -9.28446 9.49748 -0.936412 -9.86272 10.4418 -0.931179 -10.7275 11.8521 -0.969414 -11.6981 13.4361 -0.976664 -15.2089 19.1656 -1.08759 -18.5677 24.6466 -0.712121 -19.2962 25.8369 -0.276905 -20.3506 27.5567 0.18981 -24.8174 34.8465 0.667152 -24.8536 34.9063 1.3718 -19.3421 25.9123 1.80481 -19.1236 25.5562 2.30851 -17.8892 23.5428 2.68015 -17.9397 23.6249 3.16273 -17.9957 23.7169 3.65097 -18.3646 24.3183 4.21256 -19.8926 26.8124 5.09228 -18.2821 24.1849 5.18296 -18.3238 24.2538 5.69438 -19.0652 25.4637 6.45914 -18.921 25.2291 6.93436 -18.0234 23.7641 7.08408 -18.0574 23.8199 7.60222 -18.1115 23.9083 8.13691 -17.9939 23.7172 8.58927 -17.6621 23.1757 8.91675 -17.7319 23.2911 9.46772 -19.0502 25.4425 10.8277 -18.338 24.2803 10.9175 -18.7496 24.9524 11.7641 -19.4606 26.1141 12.8753 -19.3401 25.9182 13.3911 -19.2106 25.7075 13.8984 -19.5524 26.2649 14.8153 -19.8063 26.6801 15.6899 -5.68142 3.62453 6.2426 -5.61019 3.50738 6.24081 -5.53102 3.37727 6.21088 -4.92178 2.38348 4.58351 -4.88402 2.32065 4.60552 -4.83507 2.24166 4.59146 -4.79504 2.17536 4.60144 -4.79704 2.17905 4.75914 -5.371 3.11755 7.02869 -5.37926 3.13069 7.32394 -4.78628 2.16192 5.22994 -5.1698 2.78915 7.03839 -4.69178 2.00807 5.43068 -4.63476 1.91462 5.37805 -4.60057 1.85834 5.43545 -4.59852 1.8551 5.67092 -4.54955 1.77531 5.6609 -4.54775 1.77298 5.93527 -4.50914 1.7093 5.99988 -4.33541 1.4253 5.13831 -4.29894 1.36676 5.16731 -4.2682 1.31623 5.24372 -4.21419 1.2283 5.12401 -4.30431 1.37667 6.34453 -4.18712 1.18503 5.6547 -4.13067 1.09257 5.50129 -4.0979 1.03888 5.61262 -4.04472 0.951042 5.45536 -4.00374 0.885778 5.46479 -3.96757 0.826612 5.5626 -3.93546 0.774575 5.78888 -3.88547 0.692753 5.59505 -3.83724 0.614303 5.30953 -3.79219 0.538701 4.82239 -3.75399 0.477263 4.12354 -4.84203 2.0969 -0.989086 -4.87636 2.15029 -0.983068 -4.90733 2.19729 -0.968499 -4.95807 2.27557 -0.986661 -4.9935 2.33016 -0.975403 -5.03224 2.39033 -0.968952 -5.07643 2.45796 -0.967115 -5.125 2.53216 -0.96934 -5.16928 2.60102 -0.962858 -5.22338 2.68385 -0.966251 -5.2775 2.76681 -0.966747 -5.34044 2.86387 -0.975915 -5.3913 2.94159 -0.964714 -5.45104 3.03442 -0.961934 -5.51174 3.12635 -0.955714 -5.58585 3.24193 -0.961875 -5.65655 3.35016 -0.958736 -5.73277 3.46703 -0.956566 -5.81347 3.59164 -0.954812 -5.90515 3.73241 -0.957542 -5.99249 3.8669 -0.950618 -6.09519 4.02416 -0.951342 -6.20789 4.19776 -0.954248 -6.31726 4.36506 -0.946606 -6.45203 4.57234 -0.95134 -6.58693 4.78101 -0.948034 -6.7284 4.99855 -0.940109 -6.90176 5.26376 -0.943187 -7.08077 5.53903 -0.938893 -7.28086 5.84809 -0.935425 -7.50399 6.18993 -0.930743 -7.76924 6.59908 -0.933104 -8.02563 6.99277 -0.914211 -8.31961 7.44438 -0.895254 -8.7527 8.11148 -0.912308 -9.25203 8.87912 -0.925009 -9.80671 9.73237 -0.923828 -10.5413 10.8608 -0.939483 -11.5245 12.3735 -0.972968 -12.7011 14.1815 -0.986832 -18.4129 22.9644 -0.861169 -19.0548 23.952 -0.453359 -19.5457 24.7073 0.00458931 -20.7094 26.4958 0.471078 -25.0953 33.2397 1.00791 -25.0207 33.1265 1.68809 -24.7878 32.7683 2.35401 -24.8645 32.8867 3.03514 -20.9265 26.8312 3.2123 -20.4684 26.1274 3.69172 -19.3775 24.4503 4.02198 -19.3093 24.3443 4.51242 -19.031 23.9163 4.94675 -19.0825 23.9968 5.46093 -19.0653 23.9694 5.95882 -21.2422 27.3178 7.23852 -21.954 28.4117 8.09722 -19.7957 25.0937 7.79639 -19.4275 24.5276 8.17062 -19.1779 24.1439 8.58272 -20.2988 25.8679 9.7016 -19.5406 24.7025 9.85283 -19.4914 24.6252 10.3778 -19.4512 24.5648 10.9118 -21.0301 26.9931 12.5284 -21.6157 27.893 13.5691 -20.9326 26.8426 13.7231 -20.9794 26.9156 14.403 -20.6458 26.4022 15.4369 -5.8145 3.59475 6.16822 -5.77079 3.52818 6.24903 -5.71573 3.44252 6.29543 -5.70009 3.4194 6.45728 -4.98609 2.32109 4.57686 -4.96664 2.29117 4.65778 -4.91009 2.20374 4.62607 -4.89737 2.18367 4.73169 -4.87691 2.15317 4.81995 -5.41075 2.97351 6.90318 -5.39076 2.94283 7.08938 -5.34156 2.86786 7.17635 -5.2346 2.70229 7.02452 -5.17516 2.6114 7.0611 -4.75324 1.96243 5.45497 -4.70123 1.88252 5.43888 -4.65152 1.80686 5.43017 -4.65624 1.81309 5.70326 -4.60433 1.73445 5.69262 -4.59563 1.72061 5.92875 -4.5596 1.66419 6.02142 -4.37462 1.38036 5.10897 -4.34639 1.33667 5.20506 -4.29173 1.2528 5.10568 -4.27411 1.22675 5.30734 -4.34964 1.34217 6.41205 -4.30953 1.28111 6.54773 -4.06685 0.90799 4.37146 -4.03723 0.862539 4.40997 -4.08193 0.929377 5.54924 -4.03051 0.851798 5.41899 -3.99232 0.793225 5.50607 -3.9441 0.719311 5.37271 -3.90732 0.66199 5.52721 -3.86073 0.589379 5.30075 -3.80748 0.507659 4.03302 -4.9406 2.10307 -0.987162 -4.97686 2.15538 -0.980405 -5.0175 2.21419 -0.978808 -5.05816 2.27309 -0.975413 -5.09883 2.33208 -0.97012 -5.14395 2.39861 -0.969338 -5.19008 2.46518 -0.966462 -5.24059 2.53831 -0.967449 -5.29218 2.61249 -0.966092 -5.34823 2.69427 -0.968047 -5.40429 2.77619 -0.967106 -5.46138 2.85819 -0.963373 -5.52399 2.94875 -0.962206 -5.58661 3.03947 -0.957844 -5.65908 3.14428 -0.960659 -5.72726 3.24378 -0.954569 -5.8009 3.35091 -0.949698 -5.88539 3.47215 -0.950511 -5.97004 3.59562 -0.946729 -6.06561 3.73426 -0.947283 -6.16666 3.88064 -0.946858 -6.2787 4.04328 -0.949121 -6.39185 4.20716 -0.945045 -6.52589 4.40244 -0.949886 -6.66205 4.59898 -0.947095 -6.80273 4.80348 -0.940025 -6.96093 5.0329 -0.934918 -7.14758 5.3024 -0.936608 -7.34534 5.58952 -0.933445 -7.56507 5.90843 -0.930014 -7.81335 6.26871 -0.927138 -8.07478 6.64674 -0.914524 -8.36379 7.06642 -0.898165 -8.77564 7.66373 -0.912424 -9.22814 8.3193 -0.915948 -9.73783 9.05813 -0.910495 -10.4111 10.035 -0.922327 -11.3106 11.3393 -0.952924 -12.3596 12.8602 -0.962901 -15.7107 17.7191 -1.00477 -18.5412 21.8237 -1.03353 -18.9904 22.4747 -0.627702 -19.7934 23.6389 -0.22303 -19.695 23.497 0.273521 -25.0526 31.2644 2.62984 -20.6588 24.893 2.8186 -20.5814 24.7815 3.32831 -20.8107 25.1143 3.88607 -21.9933 26.828 4.64933 -21.4476 26.0373 5.09096 -21.1524 25.6083 5.56622 -20.1586 24.1674 5.82114 -25.116 31.3563 9.31209 -25.2242 31.5126 10.047 -25.0765 31.2987 11.3787 -25.2268 31.5161 12.1637 -25.1514 31.4068 12.8412 -20.0975 24.0789 10.5972 -20.1016 24.0855 11.1595 -5.96968 3.5945 6.14999 -5.89945 3.49225 6.16668 -5.87378 3.45506 6.29577 -5.83136 3.39275 6.38327 -5.82364 3.38246 6.57076 -5.04615 2.25548 4.56098 -5.01678 2.21282 4.61547 -4.98635 2.16918 4.66922 -4.98043 2.16003 4.80128 -5.59206 3.0459 7.02626 -5.48612 2.89351 6.91893 -5.42585 2.80492 6.96041 -5.43298 2.81551 7.2636 -4.91475 2.06375 5.46984 -4.86996 1.99989 5.50297 -4.7778 1.86602 5.32074 -4.7329 1.8015 5.34028 -4.74325 1.81632 5.63163 -4.71196 1.7712 5.73532 -4.65347 1.68549 5.69543 -4.65063 1.68168 5.97929 -4.64112 1.66783 6.25469 -4.42546 1.35504 5.16608 -4.38152 1.29143 5.16475 -4.3353 1.22491 5.14255 -4.43055 1.36199 6.32373 -4.16627 0.979969 4.34611 -4.14723 0.951362 4.49445 -4.09684 0.878362 4.3162 -4.06877 0.838767 4.39376 -4.11243 0.901645 5.57329 -4.0638 0.830822 5.52199 -4.00509 0.746166 5.21993 -3.95813 0.678149 5.06544 -3.92133 0.623816 5.17904 -3.88099 0.565671 5.23167 -3.83386 0.496929 4.23308 -5.01044 2.06686 -1.00536 -5.03574 2.1018 -0.977937 -5.07725 2.1585 -0.977344 -5.11884 2.21629 -0.975003 -5.16574 2.27954 -0.977378 -5.20842 2.33846 -0.971096 -5.25111 2.39747 -0.962817 -5.29918 2.46297 -0.958904 -5.36137 2.54787 -0.971273 -5.41491 2.62101 -0.968578 -5.46847 2.69426 -0.963287 -5.52748 2.77506 -0.961112 -5.59195 2.86342 -0.961655 -5.65644 2.95194 -0.959001 -5.72195 3.04056 -0.953056 -5.79736 3.14427 -0.954239 -5.87387 3.24912 -0.951581 -5.95584 3.36161 -0.949742 -6.03784 3.47432 -0.943709 -6.13719 3.60958 -0.94703 -6.23665 3.74611 -0.945007 -6.34159 3.89037 -0.942006 -6.45846 4.04985 -0.941448 -6.58195 4.21907 -0.938518 -6.72177 4.41016 -0.940093 -6.86276 4.60356 -0.933982 -7.02117 4.81985 -0.930435 -7.19711 5.06111 -0.927951 -7.39054 5.32642 -0.924884 -7.61338 5.63089 -0.925574 -7.84828 5.95204 -0.919169 -8.10078 6.29848 -0.907235 -8.39476 6.70146 -0.898005 -8.76406 7.20759 -0.901344 -9.2108 7.81809 -0.910518 -9.69268 8.47834 -0.905292 -10.298 9.30723 -0.908921 -11.127 10.4414 -0.937114 -12.0513 11.7074 -0.939297 -13.3229 13.4481 -0.959918 -15.7575 16.783 -1.11546 -18.8895 21.0708 -0.783532 -19.9369 22.5045 -0.432168 -19.8138 22.3353 0.052396 -19.9988 22.5881 0.519221 -25.723 30.4252 0.984303 -25.743 30.4541 1.63203 -25.3802 29.9564 2.25957 -25.341 29.902 2.89433 -25.4187 30.0087 3.54149 -21.7876 25.0367 3.653 -21.4 24.5055 4.12028 -25.5406 30.1746 5.49861 -25.357 29.923 6.10794 -25.4644 30.0695 6.78695 -25.5121 30.1338 8.78749 -25.3777 29.9489 9.40708 -25.4766 30.0847 10.1221 -25.5211 30.1441 11.5139 -25.5337 30.1621 12.2175 -25.4102 29.9915 12.8542 -5.99602 3.41309 6.20515 -5.96605 3.37173 6.32567 -5.91072 3.29688 6.38735 -6.09361 3.54644 7.09144 -5.77776 3.11523 6.44588 -5.70449 3.01354 6.45005 -5.64018 2.92552 6.47781 -5.61374 2.89037 6.62682 -5.50103 2.73623 7.00173 -4.94722 1.97831 5.38437 -4.91593 1.93438 5.47178 -4.85686 1.85444 5.44644 -4.80991 1.78904 5.46614 -4.79233 1.76641 5.6355 -4.75441 1.71322 5.7101 -4.72339 1.67096 5.83156 -4.63149 1.545 5.60679 -4.65141 1.57299 6.05391 -4.46759 1.32131 5.18443 -4.41144 1.24451 5.10454 -4.3678 1.18525 5.1106 -4.44998 1.29625 6.19495 -4.19628 0.949874 4.3017 -4.16827 0.911851 4.37057 -4.13564 0.867093 4.39915 -4.10073 0.819437 4.40698 -4.06338 0.767902 4.37406 -4.02722 0.718732 4.34982 -4.02083 0.709373 5.00284 -3.98183 0.655734 5.06706 -3.93461 0.591696 4.81045 -3.89664 0.538875 4.87222 -5.09686 2.05277 -0.982018 -5.136 2.10289 -0.975376 -5.17515 2.15309 -0.967137 -5.22729 2.22065 -0.977474 -5.27189 2.27839 -0.972251 -5.31545 2.3353 -0.965076 -5.37512 2.41144 -0.975093 -5.41984 2.4705 -0.963628 -5.47524 2.54144 -0.962342 -5.53503 2.61897 -0.964519 -5.60128 2.70398 -0.969617 -5.65786 2.77726 -0.960245 -5.71884 2.85715 -0.953836 -5.79165 2.95098 -0.955213 -5.85911 3.03856 -0.947731 -5.93841 3.14011 -0.947236 -6.02317 3.24932 -0.947761 -6.10803 3.35973 -0.94404 -6.19936 3.47775 -0.940644 -6.3026 3.61089 -0.941689 -6.40051 3.7378 -0.933075 -6.52116 3.89387 -0.936083 -6.64831 4.05767 -0.93672 -6.78746 4.23776 -0.938451 -6.93317 4.42666 -0.936462 -7.08539 4.6234 -0.930203 -7.26153 4.85152 -0.929379 -7.45064 5.09508 -0.925309 -7.6518 5.35516 -0.91714 -7.87691 5.64687 -0.909512 -8.13239 5.97681 -0.902999 -8.40746 6.33196 -0.89007 -8.77813 6.81163 -0.899628 -9.18031 7.331 -0.89937 -9.6489 7.93765 -0.898916 -10.1979 8.64788 -0.896173 -10.9837 9.6641 -0.927646 -11.8989 10.8467 -0.946181 -12.9013 12.143 -0.93154 -16.1896 16.3936 -0.936937 -19.4158 20.5655 -1.00726 -19.9918 21.3092 -0.621099 -20.5506 22.0325 -0.201859 -20.5368 22.0138 0.274754 -25.6698 28.6491 0.662651 -25.7069 28.6977 1.28434 -25.7079 28.6974 1.90691 -25.5786 28.5311 2.52105 -25.6699 28.648 3.15017 -25.6993 28.6854 3.77808 -25.7636 28.7693 4.41475 -25.7799 28.7887 5.04825 -25.7093 28.6972 5.66676 -25.6201 28.5816 6.27969 -25.7182 28.7077 6.94115 -25.8141 28.8315 7.61165 -25.8491 28.8761 8.2715 -25.8461 28.8726 8.9246 -25.6403 28.6048 9.50327 -25.7484 28.7435 10.207 -25.8707 28.9024 10.9299 -25.797 28.8073 11.5722 -25.8049 28.8157 12.2582 -25.6581 28.6262 12.8688 -12.9095 12.1463 8.67299 -6.20503 3.47964 6.12274 -6.14331 3.39952 6.17162 -6.06294 3.29634 6.17742 -6.28974 3.58877 6.92992 -6.21608 3.49401 6.9721 -6.17437 3.44054 7.0971 -5.77297 2.92134 6.23166 -5.75973 2.90372 6.40625 -5.75768 2.90167 6.62553 -5.67819 2.79767 6.61585 -5.00107 1.92419 5.39031 -4.96121 1.87335 5.44909 -4.90789 1.80344 5.45094 -4.87246 1.75762 5.53578 -4.90064 1.79366 5.93268 -4.79617 1.65973 5.69377 -4.74627 1.59478 5.71888 -4.65153 1.47243 5.48254 -4.59931 1.40497 5.47445 -4.71946 1.55891 6.62147 -4.46982 1.23657 5.25836 -4.40264 1.14942 5.09797 -4.26368 0.972115 4.28616 -4.23004 0.927993 4.30611 -4.19526 0.882404 4.31533 -4.19428 0.881447 4.73981 -4.13533 0.805906 4.47966 -4.09116 0.74831 4.35668 -4.05413 0.700664 4.34189 -4.02556 0.662371 4.5058 -4.00613 0.63774 5.13834 -3.94572 0.559817 4.20138 -3.91206 0.516766 4.20246 -5.19507 2.05296 -0.979897 -5.23521 2.10306 -0.972561 -5.28491 2.16302 -0.9771 -5.33038 2.21866 -0.972882 -5.38554 2.28619 -0.979937 -5.4268 2.3376 -0.965165 -5.48305 2.40629 -0.967681 -5.54032 2.47506 -0.967605 -5.59236 2.53954 -0.959067 -5.65509 2.61595 -0.96001 -5.71791 2.6935 -0.958006 -5.78713 2.77755 -0.958775 -5.85099 2.85533 -0.950883 -5.92575 2.94812 -0.950723 -6.00147 3.04003 -0.946922 -6.08371 3.1405 -0.944595 -6.1768 3.25506 -0.948152 -6.26011 3.35588 -0.93754 -6.35977 3.47929 -0.936777 -6.46684 3.60931 -0.935396 -6.5794 3.74707 -0.932936 -6.70495 3.90097 -0.933074 -6.83154 4.05512 -0.926825 -6.97553 4.23206 -0.925435 -7.14429 4.43824 -0.931185 -7.30229 4.6308 -0.921262 -7.49065 4.86224 -0.919595 -7.69838 5.11561 -0.917356 -7.93107 5.40053 -0.916062 -8.15194 5.671 -0.896944 -8.41714 5.99564 -0.884441 -8.80656 6.47153 -0.906677 -9.16586 6.91073 -0.896637 -9.65059 7.50372 -0.909256 -10.1053 8.06117 -0.886151 -10.7869 8.89389 -0.901682 -11.6503 9.9509 -0.926158 -12.6361 11.156 -0.930236 -14.0567 12.894 -0.966115 -16.1222 15.421 -1.03271 -20.3577 20.6034 -0.83642 -21.6342 22.1643 -0.49121 -21.7872 22.3514 -0.0107994 -21.569 22.0835 0.48888 -24.0907 25.1686 0.967284 -25.8036 27.2634 1.56509 -25.8143 27.2747 2.1693 -25.8239 27.2861 2.77461 -25.8391 27.3052 3.3822 -25.8542 27.3225 3.99198 -25.8433 27.3092 4.60027 -25.8638 27.3335 5.21598 -25.8584 27.3262 5.82984 -25.8529 27.3189 6.4461 -25.8962 27.3708 7.079 -25.8942 27.3688 7.70458 -25.904 27.3796 8.33806 -25.9127 27.3896 8.97639 -25.8716 27.3388 9.60047 -25.9454 27.428 10.276 -25.937 27.4176 10.9255 -25.9459 27.4279 11.5889 -25.9526 27.4357 12.2588 -25.892 27.3598 12.9 -13.347 12.0167 8.57438 -6.5151 3.66162 6.6304 -6.43516 3.56359 6.65988 -6.25882 3.34783 6.4632 -6.44736 3.57812 7.12965 -6.29285 3.38835 6.97788 -6.13414 3.19516 7.03538 -5.97836 3.00439 6.84183 -5.84224 2.83737 6.6858 -5.76542 2.74307 6.69314 -5.11273 1.94652 5.41006 -5.0543 1.87556 5.4049 -5.01243 1.82482 5.46329 -4.95498 1.75365 5.45492 -4.94743 1.74378 5.67153 -4.80906 1.57528 5.2807 -4.77153 1.52892 5.35206 -4.72184 1.46837 5.36504 -4.67433 1.4101 5.3862 -4.63027 1.35701 5.43511 -4.68939 1.42871 6.18425 -4.63102 1.35752 6.19462 -4.65619 1.38752 6.87058 -4.55839 1.26739 6.5944 -4.25959 0.904376 4.29062 -4.23655 0.875952 4.43777 -4.27506 0.921267 5.39843 -4.15382 0.774954 4.34326 -4.11349 0.725562 4.28924 -4.08142 0.685545 4.37366 -4.06766 0.668579 5.04633 -4.02172 0.611889 4.95966 -3.97671 0.556593 4.84158 -5.29421 2.0521 -0.977632 -5.33623 2.10012 -0.969408 -5.38264 2.15464 -0.966344 -5.43966 2.22 -0.974609 -5.48709 2.27466 -0.967455 -5.53459 2.33042 -0.958453 -5.59809 2.40343 -0.966144 -5.652 2.46573 -0.958915 -5.71129 2.53455 -0.955353 -5.77591 2.6089 -0.955009 -5.84168 2.68533 -0.951771 -5.91277 2.76733 -0.951252 -5.98496 2.85042 -0.947392 -6.05722 2.93467 -0.940485 -6.14127 3.03191 -0.940316 -6.23715 3.14318 -0.946236 -6.32231 3.24177 -0.937932 -6.41933 3.35441 -0.935018 -6.52919 3.48111 -0.936399 -6.64016 3.60901 -0.932542 -6.75661 3.74466 -0.927506 -6.89881 3.90933 -0.932909 -7.02924 4.0604 -0.923535 -7.18445 4.24065 -0.922497 -7.36537 4.44912 -0.927854 -7.55394 4.66745 -0.927547 -7.74903 4.89372 -0.920874 -7.96349 5.14193 -0.913428 -8.19199 5.40659 -0.900894 -8.46563 5.72234 -0.895529 -8.81578 6.12794 -0.906495 -9.15421 6.52034 -0.894593 -9.60989 7.04701 -0.904626 -10.0658 7.57585 -0.890739 -10.6907 8.2989 -0.901138 -11.5051 9.24144 -0.927214 -12.45 10.3352 -0.940421 -13.5146 11.5675 -0.927631 -15.5225 13.8918 -1.02617 -16.8388 15.4157 -0.912846 -21.4032 20.6992 -0.664936 -22.6799 22.1774 -0.288032 -22.6534 22.1457 0.213552 -23.9219 23.6134 0.691063 -27.263 27.4809 1.25605 -27.2834 27.5036 1.87895 -26.0817 26.1128 2.42631 -26.0696 26.0976 3.01707 -26.1482 26.1879 3.61907 -26.3238 26.3907 4.24071 -27.3882 27.6222 5.02549 -27.3979 27.6321 5.66171 -26.0744 26.0999 6.00151 -26.1563 26.1942 6.62671 -26.167 26.2049 7.23976 -26.099 26.1261 7.83349 -26.1151 26.1429 8.45531 -26.1669 26.2027 9.09626 -26.1098 26.1369 9.70249 -26.2037 26.2438 10.3743 -26.1434 26.1746 10.989 -26.1273 26.154 11.6272 -26.1577 26.1894 12.2958 -26.1439 26.1725 12.9494 -6.59659 3.55082 6.63951 -6.52137 3.46329 6.68415 -6.49636 3.43456 6.84295 -6.44076 3.36926 6.9349 -6.37978 3.29877 7.01694 -6.28393 3.18894 7.01158 -6.19666 3.08733 7.02036 -6.12796 3.00711 7.07891 -6.07355 2.94419 7.17995 -5.15589 1.88364 5.38818 -5.10871 1.82932 5.42857 -5.06929 1.78434 5.50508 -5.0099 1.71426 5.49617 -4.99033 1.69174 5.66544 -4.8416 1.52087 5.23456 -4.83524 1.51277 5.468 -4.76593 1.43306 5.39426 -4.71195 1.3697 5.38578 -4.66029 1.3101 5.39532 -4.61196 1.2542 5.42288 -4.56929 1.20534 5.49811 -4.66496 1.31447 6.70279 -4.58912 1.22677 6.62189 -4.48922 1.11113 6.27181 -4.45184 1.06763 6.54258 -4.28895 0.881138 5.25341 -4.18885 0.765355 4.4553 -4.13708 0.706224 4.23143 -4.10654 0.670063 4.37522 -4.08184 0.640857 4.80798 -4.04056 0.593746 4.94038 -3.99109 0.537464 4.33178 -5.34828 2.00246 -0.982229 -5.39124 2.04938 -0.974859 -5.43851 2.1018 -0.9727 -5.49215 2.16062 -0.97541 -5.54052 2.21417 -0.96931 -5.58989 2.26775 -0.961318 -5.64464 2.32782 -0.957691 -5.70472 2.39339 -0.95798 -5.76488 2.46007 -0.955822 -5.83143 2.53323 -0.956936 -5.89905 2.60747 -0.955308 -5.96664 2.68085 -0.950634 -6.03975 2.7628 -0.948626 -6.12019 2.85022 -0.948648 -6.20609 2.94525 -0.950287 -6.28765 3.03397 -0.943072 -6.38104 3.13671 -0.941946 -6.47448 3.23967 -0.936525 -6.57538 3.35018 -0.931434 -6.68913 3.47475 -0.930538 -6.80937 3.60701 -0.92857 -6.93603 3.74598 -0.92498 -7.08845 3.91401 -0.931229 -7.24193 4.08233 -0.930093 -7.41474 4.27239 -0.932379 -7.57691 4.45081 -0.919391 -7.78403 4.67792 -0.921564 -7.98484 4.89905 -0.910478 -8.21986 5.15598 -0.904224 -8.45502 5.41449 -0.886433 -8.80169 5.79603 -0.901396 -9.14309 6.17185 -0.896612 -9.5787 6.64859 -0.906338 -10.0211 7.13593 -0.896313 -10.591 7.7613 -0.90068 -11.368 8.61562 -0.93064 -12.2212 9.55171 -0.938383 -13.1561 10.5785 -0.919484 -14.7466 12.3263 -0.974906 -16.583 14.3432 -0.987012 -22.2957 20.6193 -0.947085 -22.8271 21.2024 -0.51444 -23.9262 22.409 -0.0868512 -23.9568 22.4418 0.429238 -28.8668 27.833 1.57055 -28.884 27.8509 2.21633 -26.2439 24.9514 2.6682 -26.3295 25.0436 3.25533 -26.3401 25.0558 3.83877 -26.5117 25.2432 4.44898 -26.405 25.1247 5.61106 -26.2684 24.9743 6.17261 -26.3778 25.0927 6.79351 -26.367 25.0798 7.38956 -26.4668 25.1885 8.02373 -26.4797 25.2031 8.63817 -26.3807 25.0934 9.21724 -26.314 25.0194 9.80893 -26.4161 25.1295 10.4732 -26.5012 25.2227 11.1425 -26.5336 25.2573 11.7976 -26.5316 25.2544 12.4444 -26.3498 25.0543 13.0029 -6.62152 3.39066 6.75741 -6.5641 3.32848 6.84943 -6.51746 3.27688 6.96567 -6.31875 3.05818 6.94544 -6.29504 3.03249 7.12671 -6.21361 2.9427 7.15869 -6.13541 2.85605 7.19721 -5.49058 2.14793 7.03932 -5.40676 2.05575 7.02028 -4.97348 1.58236 5.42144 -4.87473 1.47384 5.21658 -4.85527 1.45263 5.39209 -4.82153 1.41538 5.51003 -4.74031 1.32687 5.36574 -4.69997 1.28244 5.45234 -4.63735 1.21299 5.39146 -4.76352 1.35056 6.74149 -4.67352 1.25136 6.57326 -4.62724 1.2001 6.75756 -4.50869 1.07067 6.24822 -4.47396 1.03294 6.57795 -4.29071 0.833305 4.97871 -4.28324 0.824087 5.613 -4.16013 0.690382 4.22321 -4.13624 0.663689 4.58626 -4.09593 0.620075 4.66902 -4.04896 0.567534 4.32093 -5.4473 1.9996 -0.980065 -5.4912 2.0455 -0.971951 -5.54041 2.09684 -0.968953 -5.60025 2.15901 -0.977284 -5.65055 2.21149 -0.970246 -5.70187 2.264 -0.961215 -5.76288 2.32845 -0.962758 -5.8259 2.3929 -0.961814 -5.888 2.45853 -0.958318 -5.9628 2.53598 -0.963913 -6.02601 2.60282 -0.954978 -6.09654 2.67509 -0.948971 -6.17785 2.76037 -0.950796 -6.25486 2.84031 -0.943915 -6.35002 2.93963 -0.949043 -6.43984 3.0327 -0.94501 -6.53613 3.13337 -0.941802 -6.63883 3.24065 -0.938969 -6.749 3.35551 -0.936067 -6.86658 3.47698 -0.932446 -6.99704 3.61256 -0.931923 -7.14036 3.76231 -0.933399 -7.27835 3.90588 -0.924416 -7.45049 4.08491 -0.927457 -7.63546 4.27725 -0.92955 -7.82156 4.47097 -0.922809 -8.03441 4.69296 -0.92017 -8.24939 4.91633 -0.907304 -8.49113 5.16811 -0.895742 -8.79379 5.48379 -0.896811 -9.1445 5.84857 -0.90097 -9.5508 6.2711 -0.906902 -9.99893 6.73857 -0.906159 -10.524 7.28464 -0.905577 -11.2606 8.05208 -0.936658 -12.0551 8.87836 -0.944553 -12.9064 9.76475 -0.925109 -14.2675 11.1823 -0.962301 -16.3202 13.3179 -1.04792 -17.6874 14.7417 -0.93148 -19.8288 16.9711 -0.83828 -23.6723 20.9719 -0.79603 -26.3142 23.7218 -0.478926 -26.4187 23.8305 0.078713 -26.4344 23.8454 0.642551 -26.4362 23.8472 1.20675 -26.4445 23.8547 1.77141 -26.4538 23.8631 2.33692 -26.4492 23.8573 2.90254 -26.4575 23.8659 3.47046 -26.4668 23.8746 4.04036 -26.4751 23.8824 4.61262 -26.4835 23.8913 5.18733 -26.4789 23.885 5.76218 -26.5001 23.9066 6.34607 -26.4945 23.8997 6.92708 -26.5018 23.9063 7.51532 -26.5016 23.9055 8.10569 -26.5143 23.9174 8.70495 -26.5121 23.9152 9.30441 -26.5291 23.9315 9.91674 -26.5258 23.9268 10.5266 -26.5204 23.9206 11.1422 -26.5462 23.9466 11.779 -26.5376 23.9371 12.407 -26.5206 23.9183 13.0378 -6.67397 3.26553 6.94767 -6.38419 2.96347 6.95588 -6.30531 2.88197 6.99635 -5.32866 1.86594 6.51588 -4.98336 1.50803 5.28984 -4.92559 1.44804 5.28413 -4.87872 1.39873 5.32497 -4.84523 1.36492 5.45175 -4.78077 1.2972 5.40332 -4.72956 1.24349 5.43099 -4.68402 1.19682 5.50643 -4.75524 1.26864 6.47504 -4.71255 1.22467 6.6893 -4.60029 1.10733 6.29015 -4.56103 1.06596 6.56102 -4.36598 0.86561 5.01387 -4.31332 0.81104 4.9618 -4.2815 0.776972 5.22715 -4.18566 0.679358 4.25449 -4.15858 0.650342 4.60726 -4.11885 0.609129 4.77961 -4.06891 0.556854 4.23099 -5.54509 1.99282 -0.977398 -5.58993 2.0377 -0.968442 -5.64108 2.08796 -0.964605 -5.70286 2.14906 -0.972097 -5.76041 2.20584 -0.970634 -5.81267 2.25734 -0.960559 -5.87126 2.31427 -0.954806 -5.94584 2.38851 -0.964847 -6.00552 2.44662 -0.954154 -6.08226 2.52302 -0.958511 -6.15366 2.59316 -0.953908 -6.23146 2.6698 -0.951977 -6.30396 2.74118 -0.941436 -6.40092 2.83727 -0.948722 -6.48722 2.92167 -0.941732 -6.59168 3.0255 -0.945753 -6.69086 3.12409 -0.940463 -6.79738 3.22824 -0.935504 -6.91144 3.34097 -0.930325 -7.03824 3.46579 -0.928644 -7.17891 3.6047 -0.929566 -7.33344 3.75774 -0.931992 -7.48903 3.91106 -0.927432 -7.66589 4.08498 -0.926654 -7.85664 4.27316 -0.924684 -8.0613 4.47566 -0.920523 -8.27448 4.68598 -0.910105 -8.50251 4.90964 -0.895553 -8.77115 5.17568 -0.887307 -9.12483 5.52393 -0.897786 -9.50634 5.90092 -0.901386 -9.94532 6.33362 -0.905071 -10.4419 6.82322 -0.904695 -11.0514 7.425 -0.91172 -11.8452 8.20841 -0.935426 -12.7189 9.06927 -0.938334 -13.7568 10.0932 -0.931922 -15.4391 11.7531 -0.989257 -16.9983 13.2911 -0.945216 -20.1785 16.4274 -0.635211 -24.9515 21.1363 -0.615138 -26.748 22.907 -0.199725 -26.8244 22.9821 0.354378 -26.8294 22.9864 0.912117 -26.8557 23.0115 1.47047 -26.8479 23.0025 2.02886 -26.8817 23.0353 2.59028 -26.923 23.0759 3.15496 -26.929 23.0804 3.71889 -26.9426 23.0927 4.28568 -26.9625 23.1117 4.85629 -26.99 23.1376 5.43162 -27.0025 23.1494 6.00785 -27.0215 23.168 6.5894 -27.033 23.1782 7.17343 -27.051 23.1954 7.76368 -27.0753 23.2185 8.36119 -27.1061 23.2477 8.96667 -27.1284 23.2685 9.57582 -27.1561 23.2955 10.1938 -27.1956 23.3334 10.8245 -27.1998 23.337 11.4476 -27.2223 23.3583 12.0868 -27.2491 23.3839 12.7369 -27.2203 23.3547 13.3669 -6.44033 2.86485 6.95718 -5.44831 1.88727 6.54553 -5.35959 1.79973 6.49276 -5.50099 1.9379 7.46887 -4.96022 1.40786 5.28463 -4.89937 1.34747 5.26695 -4.89438 1.34166 5.54822 -5.02486 1.46901 6.67724 -4.99984 1.44404 6.99276 -4.84907 1.29606 6.47486 -4.80872 1.25596 6.70943 -4.73849 1.18682 6.7264 -4.61774 1.0675 6.25662 -4.59915 1.04869 6.78495 -4.38195 0.837798 4.93772 -4.29813 0.754854 4.39688 -4.24972 0.708443 4.29201 -4.2116 0.670274 4.34565 -4.17267 0.632081 4.43824 -4.14225 0.599991 5.16996 -5.59174 1.93593 -0.975572 -5.64375 1.984 -0.974438 -5.69583 2.03315 -0.971556 -5.75417 2.08672 -0.973345 -5.80729 2.13601 -0.966472 -5.86579 2.19177 -0.964065 -5.92524 2.24659 -0.959416 -5.99107 2.30785 -0.958638 -6.06229 2.37563 -0.961327 -6.12922 2.43809 -0.95541 -6.20249 2.50602 -0.952516 -6.27577 2.57411 -0.946625 -6.35651 2.64964 -0.943361 -6.44258 2.73076 -0.942117 -6.54343 2.82471 -0.947525 -6.63794 2.91247 -0.94367 -6.73991 3.00777 -0.940743 -6.84829 3.10968 -0.938192 -6.9577 3.21175 -0.931051 -7.08829 3.33319 -0.932338 -7.21892 3.45492 -0.927831 -7.35704 3.58429 -0.921857 -7.52911 3.74606 -0.929156 -7.68948 3.89525 -0.921226 -7.88488 4.0779 -0.924027 -8.08135 4.26092 -0.918044 -8.28534 4.45179 -0.906498 -8.51156 4.66238 -0.894894 -8.77293 4.90775 -0.887478 -9.12754 5.23862 -0.903319 -9.48333 5.57123 -0.902834 -9.93349 5.99071 -0.916771 -10.3637 6.39271 -0.903059 -10.952 6.9434 -0.914217 -11.673 7.61618 -0.931314 -12.4674 8.3586 -0.931385 -13.3936 9.22395 -0.92141 -14.8144 10.5516 -0.959262 -16.8127 12.4178 -1.02251 -18.2767 13.785 -0.91677 -20.1922 15.5752 -0.792909 -28.2074 23.0615 -0.545814 -28.4355 23.2745 0.0210458 -28.4532 23.2892 0.602002 -28.4765 23.3116 1.18344 -28.5081 23.3396 1.76644 -28.5174 23.3469 2.35012 -28.5406 23.3685 2.9361 -28.5351 23.3628 3.52135 -28.5657 23.3903 4.11239 -28.6176 23.4378 4.71009 -28.6185 23.4371 5.30355 -28.6396 23.4566 5.90377 -28.6533 23.4686 6.50642 -28.6883 23.5008 7.11832 -28.701 23.5113 7.72956 -28.7264 23.5335 8.34963 -28.7573 23.5628 8.97743 -28.7945 23.5961 9.61389 -28.8084 23.6087 10.2492 -28.8276 23.6255 10.8936 -28.8457 23.6406 11.5444 -28.8885 23.6803 12.2147 -28.9291 23.7165 12.8937 -5.80901 2.12637 7.47802 -5.46729 1.80943 6.47561 -5.40487 1.74998 6.5357 -5.23281 1.5906 6.10584 -4.99286 1.36778 5.28474 -4.93445 1.31318 5.28568 -4.92408 1.30271 5.5474 -5.07945 1.44637 6.85354 -5.0568 1.42421 7.20845 -4.86258 1.24361 6.40464 -4.8269 1.21066 6.68769 -4.72249 1.11327 6.41715 -4.62661 1.02373 6.15337 -4.61161 1.00912 6.75065 -4.53725 0.939943 6.74161 -4.34574 0.763314 4.8075 -4.26842 0.691889 4.22369 -4.22809 0.654355 4.22675 -4.1892 0.61765 4.30896 -4.14826 0.579508 4.40016 -5.69358 1.93057 -0.979916 -5.74129 1.97326 -0.971075 -5.80056 2.0257 -0.974017 -5.85461 2.07388 -0.968199 -5.92121 2.13179 -0.97337 -5.97529 2.18018 -0.963357 -6.04299 2.23926 -0.963888 -6.10446 2.29412 -0.955753 -6.17226 2.35444 -0.95134 -6.25269 2.42559 -0.955869 -6.3279 2.49248 -0.951537 -6.40944 2.56487 -0.949828 -6.49201 2.63736 -0.944927 -6.58834 2.72272 -0.947075 -6.68471 2.80825 -0.945427 -6.7821 2.89393 -0.93969 -6.89327 2.99254 -0.939601 -7.00548 3.09132 -0.934924 -7.12411 3.19674 -0.930023 -7.25753 3.31513 -0.928679 -7.39937 3.44011 -0.925822 -7.56134 3.58365 -0.928742 -7.72543 3.72841 -0.924629 -7.92449 3.90561 -0.931697 -8.10446 4.06386 -0.91956 -8.32048 4.2556 -0.916162 -8.53751 4.44675 -0.903231 -8.77585 4.65871 -0.889687 -9.12406 4.9668 -0.907562 -9.48077 5.28203 -0.912439 -9.9052 5.65707 -0.92339 -10.3087 6.01462 -0.908185 -10.8602 6.50244 -0.917266 -11.5746 7.13501 -0.944152 -12.3358 7.80899 -0.94891 -13.1659 8.54401 -0.933278 -14.3463 9.58843 -0.946917 -16.1985 11.2273 -1.01988 -17.4885 12.3698 -0.924154 -19.951 14.5477 -0.912753 -22.0723 16.4255 -0.753067 -27.8801 21.5653 -0.775327 -30.115 23.5424 -0.338756 -30.2261 23.6407 0.263687 -30.2408 23.6519 0.871473 -30.2619 23.6698 1.47988 -30.2968 23.7 2.09018 -30.3094 23.7105 2.70122 -30.321 23.7201 3.31382 -30.3326 23.7298 3.92831 -30.3728 23.7642 4.54907 -30.4056 23.7921 5.17241 -30.429 23.8127 5.79839 -30.4374 23.8192 6.42518 -30.4597 23.8372 7.0589 -30.4873 23.8613 7.69899 -30.5362 23.9037 8.35034 -30.5458 23.9111 8.99709 -30.5545 23.9188 9.64885 -30.598 23.9554 10.3187 -30.646 23.9973 10.9986 -30.6696 24.0175 11.6778 -30.6985 24.0419 12.3671 -30.703 24.0446 13.0546 -5.58984 1.82804 6.51478 -5.49643 1.74581 6.46199 -5.30986 1.5815 5.99584 -5.13055 1.42348 5.5036 -5.02256 1.32886 5.28452 -5.14817 1.43856 6.25394 -5.07833 1.3762 6.26657 -5.07407 1.37179 6.67813 -4.94094 1.25508 6.30644 -4.92168 1.23705 6.68805 -4.83551 1.16097 6.60636 -4.72697 1.06481 6.29484 -4.64595 0.993716 6.17842 -4.61095 0.96191 6.58666 -4.55623 0.913345 6.85541 -4.37061 0.751304 4.91923 -4.28755 0.679276 4.19492 -4.24751 0.644191 4.2275 -4.20662 0.607583 4.30922 -5.73194 1.86851 -0.970963 -5.78582 1.91445 -0.970039 -5.84066 1.95942 -0.967273 -5.90187 2.01079 -0.969377 -5.9631 2.06227 -0.969184 -6.01904 2.10847 -0.96038 -6.08667 2.16648 -0.96226 -6.15625 2.2235 -0.961604 -6.22492 2.2817 -0.958395 -6.30722 2.35066 -0.964333 -6.38429 2.41536 -0.96141 -6.45502 2.47385 -0.949921 -6.54581 2.5505 -0.952199 -6.63027 2.62096 -0.945511 -6.7358 2.7096 -0.951097 -6.83499 2.79206 -0.947318 -6.93528 2.87565 -0.939698 -7.04928 2.97119 -0.937479 -7.1707 3.0733 -0.935141 -7.30685 3.18738 -0.93651 -7.4441 3.30268 -0.932241 -7.6098 3.44182 -0.938477 -7.77023 3.57579 -0.933806 -7.93809 3.71649 -0.92612 -8.13648 3.88208 -0.925603 -8.34233 4.05448 -0.919973 -8.55662 4.23367 -0.908836 -8.80048 4.43801 -0.900668 -9.1413 4.72342 -0.919574 -9.4759 5.00407 -0.920676 -9.88007 5.34229 -0.930159 -10.2623 5.66302 -0.914581 -10.7888 6.10318 -0.924228 -11.4737 6.67724 -0.953413 -12.1925 7.27949 -0.95942 -12.9651 7.92664 -0.945028 -13.9984 8.7919 -0.948008 -15.5349 10.079 -0.993895 -17.3344 11.5854 -1.01047 -18.9539 12.9414 -0.921523 -20.521 14.2543 -0.753553 -23.8926 17.078 -0.670594 -31.5466 23.4878 -0.705999 -32.0869 23.9404 -0.10411 -32.0837 23.936 0.531516 -32.1397 23.9822 1.16689 -35.599 26.8779 1.89903 -35.6439 26.9158 2.617 -31.9594 23.8294 3.06465 -31.9584 23.8279 3.69952 -35.6833 26.9454 4.77941 -35.705 26.9631 5.50657 -21.8959 15.3998 3.95365 -32.0464 23.8971 6.27541 -32.0329 23.8859 6.92147 -35.8963 27.1192 8.48188 -35.8906 27.1134 9.22773 -34.9146 26.2953 9.70474 -32.1964 24.0192 9.60716 -32.0698 23.9128 10.2409 -5.66865 1.80603 6.10624 -5.63363 1.77772 6.2614 -5.60608 1.75385 6.45442 -5.52155 1.68292 6.43815 -5.34204 1.53302 6.00808 -5.15681 1.37884 5.48496 -5.21586 1.42765 6.09615 -5.15713 1.37855 6.16721 -5.10927 1.33814 6.30544 -5.03861 1.27821 6.32556 -4.95925 1.21179 6.28509 -4.93037 1.18787 6.6171 -4.81577 1.09166 6.29713 -4.72739 1.01809 6.14204 -4.65111 0.955127 6.07405 -4.61511 0.923353 6.48169 -4.55952 0.876296 6.75958 -4.48715 0.815789 6.84693 -4.31661 0.676419 4.43563 -4.26717 0.63549 4.25801 -4.22379 0.599067 4.23931 -5.83266 1.8612 -0.975502 -5.88319 1.90071 -0.966727 -5.94521 1.94896 -0.969886 -6.0073 1.99833 -0.970797 -6.07048 2.04874 -0.969666 -6.13367 2.09925 -0.966237 -6.20312 2.15421 -0.96678 -6.27465 2.21017 -0.964786 -6.34526 2.26732 -0.960239 -6.42945 2.33423 -0.964689 -6.50835 2.39588 -0.960329 -6.58733 2.45868 -0.953022 -6.6747 2.52786 -0.948298 -6.77466 2.60698 -0.950468 -6.8684 2.68189 -0.943872 -6.9778 2.76759 -0.943336 -7.0936 2.85989 -0.943375 -7.21043 2.95236 -0.938825 -7.34305 3.05771 -0.938536 -7.48198 3.16775 -0.937126 -7.63038 3.28532 -0.934157 -7.80718 3.42575 -0.941146 -7.97138 3.55566 -0.9331 -8.16611 3.71041 -0.932924 -8.36823 3.87096 -0.928084 -8.58712 4.04364 -0.921469 -8.82185 4.22954 -0.911924 -9.14695 4.48694 -0.928229 -9.46589 4.74052 -0.927777 -9.83949 5.03671 -0.932152 -10.2152 5.33357 -0.920456 -10.6983 5.71742 -0.924893 -11.3213 6.21134 -0.946651 -12.0462 6.78543 -0.966643 -12.7893 7.37488 -0.958495 -13.7124 8.10669 -0.955053 -15.0404 9.15938 -0.986181 -16.9944 10.7088 -1.06035 -18.3525 11.785 -0.963417 -20.5555 13.5305 -0.906505 -22.1501 14.7949 -0.693512 -33.7911 24.0219 -0.490596 -38.1867 27.5061 0.0405565 -38.5326 27.7794 0.79476 -38.0961 27.4314 2.30683 -32.7035 23.1565 2.73861 -32.7309 23.1774 3.37705 -22.916 15.3975 2.98714 -22.559 15.1137 3.36144 -22.3452 14.9449 3.74247 -22.1503 14.7898 4.11888 -32.8283 23.2506 6.60939 -21.7846 14.4993 4.85621 -21.753 14.4738 5.25221 -37.2814 26.7768 9.75815 -33.6165 23.8727 9.4755 -32.9643 23.3545 9.96296 -5.70443 1.75047 6.1217 -5.66303 1.71758 6.25761 -5.63029 1.69153 6.44067 -5.47726 1.57083 6.14643 -5.36709 1.484 6.00078 -5.45715 1.55325 6.75851 -5.24235 1.38444 6.10668 -5.20755 1.35567 6.31342 -5.12314 1.28921 6.26598 -5.04845 1.23051 6.26555 -5.00865 1.19886 6.50932 -4.92962 1.13578 6.49632 -4.80758 1.03902 6.09553 -4.7393 0.985058 6.11754 -4.66097 0.923198 6.02878 -4.56664 0.848861 5.68915 -4.44492 0.753926 4.71877 -4.47496 0.775757 6.49005 -4.3503 0.678629 4.94599 -4.28483 0.626904 4.28843 -5.9289 1.8455 -0.972486 -5.98661 1.88829 -0.969835 -6.04433 1.93117 -0.965287 -6.11986 1.98815 -0.978393 -6.17868 2.03218 -0.969505 -6.24375 2.08063 -0.964988 -6.32139 2.13886 -0.970562 -6.39387 2.19382 -0.967325 -6.4673 2.24785 -0.961446 -6.54713 2.30836 -0.958739 -6.63422 2.37332 -0.958611 -6.7224 2.43937 -0.955441 -6.81791 2.5109 -0.954199 -6.92076 2.58792 -0.954488 -7.0237 2.66614 -0.95093 -7.13592 2.74877 -0.948163 -7.24724 2.83266 -0.941246 -7.38891 2.93912 -0.947991 -7.517 3.03507 -0.940497 -7.66707 3.14737 -0.940587 -7.82657 3.26622 -0.93867 -7.9935 3.39176 -0.934336 -8.1835 3.53475 -0.934546 -8.39021 3.68879 -0.934028 -8.58972 3.83885 -0.921644 -8.82798 4.01725 -0.917365 -9.15215 4.25951 -0.936824 -9.46183 4.49256 -0.936993 -9.8197 4.76065 -0.940564 -10.2027 5.04664 -0.936703 -10.6488 5.38084 -0.935906 -11.2217 5.80985 -0.951779 -11.9133 6.32869 -0.9739 -12.648 6.87903 -0.97578 -13.4792 7.50132 -0.966736 -14.5969 8.33904 -0.977239 -16.3672 9.66582 -1.05114 -17.7214 10.6806 -0.9854 -19.7702 12.2147 -0.949531 -21.0475 13.1719 -0.743182 -25.1902 16.2759 -0.721422 -40.9441 28.0783 -0.434797 -41.1401 28.2231 1.16634 -22.1198 13.9732 1.87471 -21.9705 13.8596 2.25462 -21.2796 13.3427 2.57942 -21.3749 13.4142 2.96383 -21.6247 13.6 3.37436 -21.1603 13.2523 3.68516 -21.6916 13.6487 4.15561 -21.6925 13.6499 4.54472 -21.5779 13.5636 4.91011 -21.4432 13.4621 5.26769 -22.265 14.0777 5.87988 -22.2187 14.0421 6.27858 -5.76135 1.71219 5.94501 -5.72438 1.6855 6.08979 -5.67233 1.64532 6.18709 -5.63432 1.61659 6.3503 -5.57608 1.57371 6.44628 -5.42336 1.45929 6.13742 -5.46717 1.49172 6.70318 -5.26903 1.3437 6.12659 -5.20968 1.29955 6.21593 -5.18494 1.28 6.51966 -5.1475 1.25174 6.79418 -5.03634 1.16938 6.59585 -4.9281 1.08823 6.3648 -4.79646 0.990058 5.86323 -4.73936 0.947304 5.98333 -4.66127 0.889388 5.89347 -4.52838 0.790187 4.94481 -4.46227 0.740916 4.7405 -4.46861 0.743826 6.20251 -4.36369 0.66732 4.95675 -4.29988 0.619538 4.17843 -5.9904 1.80438 -0.998785 -6.02508 1.82882 -0.96922 -6.09516 1.87826 -0.979109 -6.15383 1.92014 -0.973418 -6.21975 1.96637 -0.972203 -6.27952 2.00938 -0.962571 -6.35902 2.06542 -0.969554 -6.4323 2.11726 -0.967572 -6.51291 2.17451 -0.969016 -6.59454 2.23183 -0.967669 -6.67625 2.2903 -0.963375 -6.76523 2.35322 -0.961659 -6.84898 2.41186 -0.951382 -6.95995 2.49105 -0.958949 -7.05837 2.56066 -0.95233 -7.17871 2.64546 -0.956642 -7.28557 2.72173 -0.947013 -7.41435 2.81325 -0.947116 -7.55247 2.91024 -0.94676 -7.69071 3.0085 -0.941061 -7.85919 3.12745 -0.946528 -8.02878 3.24766 -0.945358 -8.20781 3.37446 -0.941382 -8.39521 3.50695 -0.933847 -8.59832 3.65054 -0.92598 -8.83285 3.81707 -0.92309 -9.16247 4.05066 -0.948675 -9.43885 4.24606 -0.939723 -9.78006 4.48713 -0.942037 -10.1528 4.75154 -0.941039 -10.5757 5.05106 -0.939458 -11.1189 5.43575 -0.955023 -11.7761 5.90046 -0.977719 -12.5318 6.43565 -0.996642 -13.249 6.94409 -0.9747 -14.2351 7.64175 -0.976285 -15.6669 8.65564 -1.01614 -17.5969 10.0218 -1.07331 -19.02 11.0298 -0.978939 -19.981 11.7103 -0.771025 -22.3641 13.3976 -0.655307 -28.6916 17.877 -0.720912 -43.8701 28.6236 -0.113876 -43.9539 28.6826 0.731917 -43.9771 28.6982 1.58032 -23.1276 13.9364 1.69306 -22.6909 13.6264 2.07156 -22.9013 13.7755 2.4825 -21.5114 12.7912 2.74395 -21.6557 12.893 3.1324 -21.4282 12.7312 3.47545 -22.5396 13.5181 4.03039 -21.8731 13.0453 4.30416 -21.8321 13.0163 4.68107 -21.6811 12.9095 5.03324 -22.2134 13.2853 5.55375 -22.6641 13.6041 6.07842 -5.90475 1.73821 6.05775 -5.78794 1.65523 5.9413 -5.79359 1.6585 6.23655 -5.69064 1.58586 6.16324 -5.65388 1.5605 6.33528 -5.73907 1.62015 7.03515 -5.66406 1.56637 7.11328 -5.48399 1.43919 6.69582 -5.31219 1.31828 6.25325 -5.21207 1.24688 6.12759 -5.15839 1.20974 6.2639 -5.15242 1.20481 6.74378 -5.01645 1.10856 6.3566 -4.90733 1.03192 6.09409 -4.80768 0.961563 5.84842 -4.73638 0.91073 5.82875 -4.6718 0.865364 5.88706 -4.53782 0.771232 4.85726 -4.549 0.777915 6.23945 -4.42532 0.691214 4.76525 -4.37624 0.657038 4.98719 -6.0678 1.7738 -0.974864 -6.12633 1.81353 -0.97227 -6.19311 1.85754 -0.974357 -6.25266 1.8974 -0.967773 -6.31953 1.94261 -0.965715 -6.39366 1.9922 -0.967633 -6.46881 2.04185 -0.967159 -6.54398 2.09163 -0.963989 -6.62647 2.14682 -0.964246 -6.71629 2.20744 -0.96733 -6.79258 2.25856 -0.956024 -6.89169 2.32368 -0.958401 -6.98364 2.38564 -0.952057 -7.09012 2.45642 -0.952567 -7.205 2.53366 -0.954162 -7.3136 2.6057 -0.946741 -7.44417 2.69398 -0.949402 -7.58403 2.78673 -0.951656 -7.71668 2.87537 -0.944239 -7.87332 2.98025 -0.944416 -8.03826 3.08974 -0.942683 -8.21994 3.21118 -0.94237 -8.41001 3.3383 -0.938797 -8.61677 3.47646 -0.934896 -8.8236 3.61502 -0.922906 -9.14297 3.82819 -0.948107 -9.4322 4.02136 -0.948159 -9.76215 4.24201 -0.951183 -10.1338 4.49022 -0.954488 -10.5233 4.74988 -0.947982 -10.9953 5.06533 -0.949672 -11.6633 5.51168 -0.985569 -12.3263 5.9538 -0.991782 -13.0646 6.44803 -0.987931 -13.9281 7.02422 -0.97918 -15.2133 7.88274 -1.01345 -16.963 9.05109 -1.0709 -18.279 9.93041 -0.992195 -20.069 11.125 -0.916987 -20.5581 11.4525 -0.634053 -25.483 14.7421 -0.692147 -46.0823 28.5005 -0.610556 -46.1003 28.5117 0.265831 -46.1215 28.5259 1.14255 -22.3938 12.677 1.45651 -22.402 12.6823 1.83616 -22.6201 12.8271 2.23053 -23.1392 13.1742 2.66085 -21.8123 12.287 2.91483 -21.7818 12.2669 3.2813 -21.9614 12.3871 3.67929 -21.9946 12.4081 4.06157 -22.2599 12.5859 4.49199 -22.8127 12.9547 4.99777 -22.8827 13.0013 5.41585 -22.8492 12.9779 5.81275 -22.6798 12.8646 6.17329 -24.489 14.0736 7.12873 -23.9086 13.6843 7.39151 -23.8053 13.6154 7.79851 -6.04337 1.75404 6.14128 -5.89825 1.65613 5.9522 -5.82103 1.60428 5.96536 -5.80021 1.59088 6.17554 -5.75819 1.56292 6.32914 -5.67891 1.50949 6.34861 -5.77679 1.57477 7.11658 -5.57921 1.44335 6.65301 -5.53533 1.41326 6.86269 -5.31358 1.2657 6.16551 -5.2364 1.21468 6.17544 -5.18066 1.17665 6.31141 -5.04397 1.08598 5.91444 -4.96221 1.03153 5.84958 -4.96327 1.03144 6.47614 -4.82784 0.940953 5.92257 -4.68704 0.847783 5.12636 -4.62421 0.806309 5.08324 -4.55084 0.757018 4.82922 -4.50379 0.72533 5.02288 -4.43775 0.68147 4.76594 -4.38676 0.647886 4.99747 -6.16799 1.75755 -0.97836 -6.22222 1.7919 -0.967959 -6.29512 1.83827 -0.975717 -6.36386 1.88131 -0.974668 -6.43162 1.92452 -0.971417 -6.50139 1.96773 -0.965878 -6.58367 2.01972 -0.970181 -6.65353 2.06415 -0.959898 -6.74516 2.12158 -0.964642 -6.82331 2.1705 -0.954945 -6.92229 2.23352 -0.95912 -7.01604 2.29229 -0.954435 -7.12432 2.35986 -0.956805 -7.22643 2.42422 -0.950357 -7.3504 2.50277 -0.954992 -7.46914 2.57708 -0.950265 -7.60248 2.66129 -0.950546 -7.74517 2.75098 -0.950268 -7.88891 2.84088 -0.944702 -8.05564 2.94708 -0.946226 -8.23167 3.05786 -0.945345 -8.40876 3.16891 -0.937776 -8.61918 3.30162 -0.938143 -8.82134 3.4294 -0.926887 -9.08897 3.59742 -0.934345 -9.39097 3.78733 -0.944049 -9.71799 3.99294 -0.950717 -10.0877 4.22599 -0.958668 -10.4419 4.44893 -0.946677 -10.8888 4.72982 -0.947873 -11.4845 5.10584 -0.972938 -12.149 5.52421 -0.991112 -12.85 5.96537 -0.990368 -13.6614 6.47534 -0.984663 -14.7082 7.13496 -0.991766 -16.1757 8.05955 -1.02922 -17.9421 9.17145 -1.05159 -19.7277 10.2957 -1.00393 -20.4383 10.7432 -0.762974 -20.6982 10.9064 -0.452841 -29.0893 16.1898 -0.701456 -44.2031 25.7061 -0.934992 -46.4849 27.1425 -0.177875 -46.5216 27.1653 0.690591 -46.5542 27.1854 1.56032 -22.8463 12.2587 1.642 -22.7585 12.2024 2.01882 -22.5302 12.0587 2.38212 -22.8874 12.2832 2.7926 -23.1114 12.4244 3.20342 -22.0586 11.762 3.4502 -22.566 12.0807 3.90073 -22.3615 11.9517 4.24709 -23.2956 12.5403 4.81457 -22.5301 12.0575 5.04777 -23.7857 12.8486 5.74164 -24.4731 13.2802 6.3422 -24.614 13.3686 6.81944 -24.4932 13.2927 7.22592 -24.8951 13.5459 7.80405 -24.5165 13.307 8.12905 -22.0725 11.7662 13.4016 -21.8367 11.6171 13.7279 -6.04227 1.67609 6.06492 -5.94418 1.61477 6.02355 -5.90427 1.58926 6.1684 -5.80615 1.52775 6.12333 -5.73342 1.48188 6.1616 -5.6575 1.43366 6.1889 -5.65079 1.42909 6.51347 -5.43106 1.29156 5.89969 -5.4159 1.28143 6.20288 -5.31329 1.21768 6.08687 -5.26086 1.18396 6.23292 -5.15912 1.11998 6.09309 -5.03876 1.04366 5.7829 -4.96915 1.00085 5.80577 -4.96718 0.999428 6.44214 -4.75055 0.86338 5.01256 -4.67669 0.816689 4.8306 -4.6194 0.780818 4.82631 -4.56424 0.745748 4.84078 -4.50816 0.711176 4.86415 -4.45074 0.675149 4.83633 -6.20672 1.70277 -0.983984 -6.25564 1.73172 -0.967669 -6.33659 1.77922 -0.983256 -6.39896 1.8159 -0.976638 -6.4614 1.85368 -0.968072 -6.53828 1.89909 -0.970107 -6.60794 1.94035 -0.963371 -6.69934 1.99456 -0.97256 -6.77834 2.04123 -0.966764 -6.86461 2.09231 -0.964246 -6.95814 2.14785 -0.964306 -7.04545 2.19917 -0.9557 -7.14734 2.26027 -0.954798 -7.26576 2.33006 -0.960561 -7.37696 2.39574 -0.957153 -7.49649 2.46688 -0.95468 -7.63257 2.5468 -0.957175 -7.777 2.63225 -0.959406 -7.91421 2.71361 -0.951967 -8.06904 2.80476 -0.947852 -8.25506 2.91558 -0.95436 -8.41929 3.01258 -0.942196 -8.62399 3.1336 -0.942644 -8.83708 3.26034 -0.938933 -9.06054 3.3927 -0.930574 -9.39086 3.58815 -0.955792 -9.6891 3.76473 -0.955801 -10.0476 3.97735 -0.964763 -10.3833 4.1754 -0.951403 -10.8363 4.44445 -0.961179 -11.3579 4.75243 -0.972204 -12.0322 5.15252 -1.00297 -12.7439 5.57334 -1.01503 -13.4663 6.00185 -1.00082 -14.3423 6.52027 -0.98883 -15.7398 7.34829 -1.0362 -17.5508 8.42066 -1.09353 -18.9301 9.23689 -1.01653 -20.371 10.0899 -0.891456 -20.7311 10.3042 -0.600745 -21.1566 10.5562 -0.301383 -50.9159 28.1785 -0.770096 -22.2174 11.1837 0.700322 -51.0793 28.2753 1.1175 -51.1912 28.3417 2.06674 -23.4026 11.8856 1.83477 -22.5543 11.3836 2.16758 -26.7916 13.8928 2.88964 -51.5037 28.5263 5.90746 -23.5135 11.9514 3.3982 -25.7378 13.2678 4.1127 -23.9678 12.2195 4.26034 -26.2103 13.5472 5.08338 -51.7635 28.6793 10.8256 -22.9253 11.6022 5.24734 -26.3765 13.6454 6.4981 -26.2405 13.5657 6.92921 -26.1908 13.535 7.38337 -26.0506 13.4524 7.81115 -25.6637 13.224 8.15473 -25.0112 12.8367 8.39075 -25.1594 12.9246 8.90691 -25.1597 12.9248 9.37568 -11.0731 4.58334 5.16191 -22.7552 11.5001 12.8918 -18.5534 9.01296 10.5543 -18.6076 9.04481 10.9792 -21.773 10.9186 13.6832 -21.4866 10.7491 13.9625 -22.6003 11.4081 15.3384 -22.7638 11.505 16.0156 -21.3207 10.65 15.8884 -6.0939 1.63486 5.66044 -6.03942 1.60221 5.98747 -5.96158 1.55589 6.01039 -5.91128 1.52656 6.12627 -5.81865 1.47162 6.09886 -5.76303 1.43803 6.20327 -5.66616 1.3812 6.15296 -5.58413 1.33326 6.15836 -5.42218 1.23718 5.78339 -5.48171 1.27145 6.46608 -5.31211 1.17169 6.00754 -5.22665 1.12115 5.95633 -5.14651 1.07367 5.93276 -5.04263 1.0127 5.72962 -4.97958 0.974921 5.80126 -4.97243 0.970795 6.4375 -4.74706 0.837324 4.82673 -4.69767 0.807446 4.93272 -4.63164 0.768643 4.8182 -4.57561 0.735608 4.83218 -4.51976 0.702477 4.88491 -4.45983 0.667138 4.74654 -6.24245 1.6482 -0.989095 -6.29849 1.67935 -0.980353 -6.36071 1.71389 -0.976733 -6.43118 1.75271 -0.977893 -6.50068 1.79169 -0.976851 -6.57125 1.83173 -0.973566 -6.65001 1.87508 -0.974313 -6.7288 1.91855 -0.972564 -6.81485 1.96644 -0.974092 -6.90198 2.0154 -0.972878 -6.99007 2.06346 -0.968623 -7.07825 2.11264 -0.961621 -7.18194 2.17054 -0.962378 -7.29391 2.23287 -0.964719 -7.4069 2.29533 -0.963171 -7.52824 2.36325 -0.962757 -7.64961 2.43139 -0.957948 -7.78852 2.50825 -0.958112 -7.92747 2.58535 -0.953382 -8.08402 2.67224 -0.952175 -8.2562 2.7691 -0.953682 -8.44693 2.87478 -0.956771 -8.6212 2.97216 -0.945105 -8.83788 3.09246 -0.945412 -9.05563 3.2131 -0.937634 -9.37382 3.39029 -0.961659 -9.66826 3.55394 -0.964007 -9.9897 3.73312 -0.964126 -10.3464 3.93129 -0.963353 -10.7548 4.15831 -0.964805 -11.267 4.44355 -0.980547 -11.9169 4.8049 -1.01333 -12.5783 5.17271 -1.02299 -13.3538 5.60385 -1.03245 -14.0881 6.01335 -1.00258 -15.3331 6.70561 -1.04048 -16.9452 7.60279 -1.09064 -18.3099 8.36144 -1.03953 -20.3277 9.48439 -1.01837 -20.8007 9.74702 -0.749042 -21.1651 9.94937 -0.452169 -21.8219 10.3153 -0.161629 -22.1948 10.5228 0.168366 -22.0224 10.4267 0.528082 -22.0615 10.4487 0.878926 -28.6213 14.0991 4.70827 -25.5718 12.4019 4.67438 -26.2538 12.7819 5.23887 -25.6883 12.4672 5.56726 -20.822 9.75942 4.86672 -20.6327 9.65403 5.16054 -27.1673 13.2897 7.30762 -25.3765 12.294 7.25699 -26.0445 12.6656 7.91843 -25.8526 12.5587 8.32028 -25.6379 12.4396 8.71039 -25.4014 12.3081 9.08787 -22.8385 10.8817 8.5132 -18.2135 8.30872 6.94257 -19.8768 9.2342 8.0111 -22.1559 10.5022 9.45475 -22.1767 10.5142 9.88323 -24.3239 11.708 11.9158 -24.6706 11.9008 12.6064 -24.2738 11.6805 12.879 -11.0825 4.34117 5.16462 -18.671 8.56333 10.2675 -18.777 8.6224 10.718 -18.7603 8.61312 11.0971 -18.2732 8.34271 11.1391 -18.5905 8.51849 11.7733 -21.748 10.2762 14.6762 -21.104 9.91735 14.6649 -21.343 10.0506 15.3768 -20.7333 9.71094 15.3707 -6.17114 1.60951 5.58709 -6.11763 1.5796 5.66717 -6.08519 1.56164 5.81159 -6.01485 1.5218 5.85295 -5.96146 1.4927 5.94961 -5.86375 1.43813 5.9033 -5.83673 1.42257 6.10262 -5.75698 1.37809 6.12005 -5.7112 1.3537 6.28041 -5.56356 1.27071 6.0047 -5.45719 1.21179 5.88038 -5.43376 1.19916 6.16343 -5.31132 1.13115 5.93745 -5.24957 1.09647 6.03265 -5.14285 1.03723 5.84076 -5.05743 0.989484 5.76498 -4.98169 0.948014 5.74669 -4.95715 0.933531 6.2338 -4.76134 0.824054 4.83949 -4.70338 0.792225 4.85522 -4.64309 0.759008 4.81988 -4.58511 0.727061 4.83322 -4.53219 0.69715 5.03536 -6.26491 1.58813 -0.979713 -6.32798 1.62047 -0.978995 -6.39731 1.65719 -0.983247 -6.46766 1.69397 -0.985307 -6.53902 1.73078 -0.985275 -6.59704 1.76113 -0.970101 -6.67567 1.80242 -0.972248 -6.75532 1.84377 -0.971803 -6.84218 1.88852 -0.974786 -6.92293 1.93107 -0.969101 -7.01189 1.97698 -0.96655 -7.11636 2.03157 -0.972257 -7.20642 2.07872 -0.963668 -7.31194 2.13358 -0.962588 -7.43299 2.19721 -0.968269 -7.54881 2.25659 -0.964789 -7.67198 2.32149 -0.962239 -7.80437 2.38984 -0.96003 -7.94511 2.4637 -0.957758 -8.10234 2.5454 -0.959305 -8.26167 2.62826 -0.955219 -8.42105 2.7114 -0.945439 -8.62276 2.81638 -0.949381 -8.82558 2.92265 -0.946086 -9.03766 3.03257 -0.938838 -9.35926 3.20026 -0.968231 -9.61585 3.33364 -0.959583 -9.94895 3.50765 -0.969051 -10.3017 3.69182 -0.971865 -10.6732 3.88529 -0.966872 -11.148 4.13286 -0.978768 -11.7551 4.44879 -1.00858 -12.4078 4.78865 -1.02631 -13.0802 5.13938 -1.023 -13.8417 5.53623 -1.01285 -14.8162 6.044 -1.01463 -16.2654 6.79867 -1.06251 -18.0787 7.74397 -1.11051 -19.4912 8.48003 -1.03214 -20.6767 9.09844 -0.871902 -21.5169 9.53604 -0.632083 -22.0439 9.81079 -0.335642 -21.9474 9.75987 0.0168501 -22.2874 9.93832 0.34823 -22.6756 10.141 1.40794 -22.3038 9.94672 1.75112 -27.5762 12.6947 2.42106 -21.9162 9.7457 2.42366 -28.5997 13.2286 3.91636 -19.0206 8.23586 3.0583 -26.5203 12.1448 4.54797 -19.3948 8.43204 4.01141 -19.6595 8.57043 4.37358 -20.0567 8.77725 4.78041 -18.4329 7.93036 4.67721 -21.6679 9.61725 5.88199 -25.5978 11.6657 7.436 -26.7741 12.2787 8.26569 -26.5817 12.1783 8.67694 -24.9682 11.3372 8.56185 -18.1259 7.77177 6.34406 -18.284 7.85366 6.71125 -18.4338 7.93142 7.08632 -18.3784 7.90312 7.37871 -19.3466 8.4082 8.16448 -21.8573 9.71672 9.77723 -22.3377 9.96753 10.4441 -18.2544 7.83893 8.62337 -18.6162 8.02779 9.17083 -19.2468 8.35706 9.90413 -21.9202 9.75081 11.957 -18.74 8.09306 10.3346 -18.8904 8.171 10.8151 -18.7221 8.08329 11.0865 -18.5559 7.99755 11.3598 -22.948 10.2873 15.1081 -22.0023 9.79425 14.8949 -21.2394 9.39681 14.7902 -21.0383 9.2924 15.13 -6.25777 1.58676 5.75983 -6.14773 1.52886 5.69206 -6.11648 1.51329 5.84555 -6.07787 1.49268 5.98985 -5.97417 1.43907 5.93533 -5.90406 1.40254 5.98303 -5.86033 1.37959 6.13459 -5.77656 1.33586 6.1417 -5.59657 1.24162 5.74134 -5.51052 1.19683 5.70437 -5.50935 1.19721 6.07472 -5.42758 1.154 6.07458 -5.30214 1.08865 5.81756 -5.23843 1.05556 5.90199 -5.16408 1.01711 5.92599 -5.06161 0.962967 5.7208 -4.98828 0.925799 5.73151 -4.9673 0.914022 6.29775 -4.77375 0.812889 4.85195 -4.71483 0.782599 4.85711 -4.65467 0.750845 4.83121 -4.59574 0.720438 4.83397 -4.55136 0.697536 5.87552 -6.35455 1.5628 -0.976872 -6.42469 1.59641 -0.98218 -6.48873 1.62783 -0.97862 -6.57437 1.67008 -0.993085 -6.62608 1.69507 -0.972292 -6.70552 1.73325 -0.975494 -6.78604 1.77248 -0.976253 -6.86658 1.81184 -0.974515 -6.9492 1.85219 -0.97024 -7.04521 1.89933 -0.974913 -7.13605 1.94319 -0.970875 -7.22692 1.9872 -0.96384 -7.33324 2.03891 -0.964614 -7.45608 2.09932 -0.972254 -7.55727 2.14796 -0.960521 -7.68943 2.21297 -0.965156 -7.81537 2.2738 -0.960425 -7.95784 2.34342 -0.960662 -8.1168 2.42088 -0.964918 -8.26136 2.49088 -0.954877 -8.43891 2.57737 -0.956419 -8.61858 2.66506 -0.951628 -8.81475 2.76071 -0.948159 -9.03769 2.86859 -0.948506 -9.34623 3.01912 -0.975752 -9.60536 3.14511 -0.971666 -9.91713 3.29753 -0.977003 -10.266 3.46675 -0.982857 -10.6067 3.63323 -0.972892 -11.0361 3.8418 -0.976908 -11.5801 4.10685 -0.997315 -12.2406 4.42757 -1.02728 -12.9033 4.75039 -1.03224 -13.6302 5.10501 -1.02605 -14.5097 5.5335 -1.02288 -15.7556 6.13981 -1.05347 -17.4854 6.98113 -1.11553 -18.703 7.57456 -1.03582 -20.6893 8.54136 -1.00604 -21.2914 8.83452 -0.752545 -22.1598 9.25702 -0.499592 -31.955 14.0253 -0.811359 -22.162 9.25883 0.530675 -63.8224 29.5399 0.513046 -19.5505 7.98871 1.18754 -19.68 8.05173 1.4834 -19.0154 7.7277 1.74514 -19.1181 7.77798 2.03453 -19.4138 7.92198 2.34552 -19.749 8.0855 2.67317 -19.0863 7.76302 2.88756 -19.3574 7.89528 3.21475 -19.1347 7.78704 3.47123 -19.1734 7.80651 3.76943 -19.5613 7.99521 4.14329 -19.2983 7.8677 4.38681 -18.9536 7.69956 4.60144 -21.0546 8.7226 5.45998 -20.6687 8.53563 5.68987 -21.1212 8.75661 6.16626 -18.5998 7.52774 5.68148 -18.3439 7.40412 5.89072 -18.5295 7.49432 6.25699 -18.4876 7.47402 6.54497 -20.0409 8.231 7.49989 -18.6739 7.56572 7.24557 -18.6403 7.54975 7.55009 -20.2667 8.34121 8.66244 -19.2284 7.83625 8.50159 -19.166 7.80547 8.81618 -18.5663 7.51365 8.83563 -18.7451 7.60126 9.28288 -19.8291 8.12959 10.294 -18.7115 7.58562 9.97817 -18.5301 7.49757 10.2269 -18.8583 7.65772 10.822 -19.0509 7.75133 11.3465 -23.5688 9.95363 15.0815 -23.271 9.8085 15.3925 -22.5679 9.466 15.3765 -17.9636 7.22222 12.1155 -20.9165 8.66189 15.0506 -6.09692 1.44211 6.0046 -6.0133 1.40056 6.01551 -5.89929 1.34552 5.91979 -5.83255 1.31363 5.98425 -5.80262 1.29815 6.20182 -5.59983 1.1994 5.70304 -5.552 1.17598 5.84014 -5.52443 1.16263 6.10353 -5.43235 1.11858 6.05376 -5.31242 1.0593 5.82493 -5.23505 1.02209 5.82977 -5.20264 1.0063 6.1595 -5.08448 0.949166 5.85466 -4.99832 0.906823 5.7656 -4.98005 0.898809 6.43126 -4.7907 0.804901 4.93401 -4.72536 0.773515 4.86878 -4.66324 0.743361 4.83231 -4.60336 0.713987 4.83452 -6.38542 1.51056 -0.981358 -6.44932 1.53983 -0.980696 -6.51428 1.57013 -0.978191 -6.59968 1.60834 -0.993756 -6.66667 1.63873 -0.987066 -6.72551 1.66601 -0.971949 -6.81401 1.70539 -0.980387 -6.88824 1.73935 -0.973629 -6.97066 1.77665 -0.970703 -7.05417 1.81501 -0.965235 -7.15924 1.86338 -0.974346 -7.25092 1.90426 -0.968766 -7.3591 1.95377 -0.971249 -7.46006 1.99915 -0.964762 -7.58468 2.05553 -0.970515 -7.7032 2.10973 -0.967102 -7.83712 2.17073 -0.969452 -7.97315 2.23284 -0.967166 -8.11839 2.29841 -0.964823 -8.27194 2.36853 -0.961866 -8.43471 2.44215 -0.957854 -8.61604 2.52455 -0.956321 -8.80562 2.6106 -0.952229 -9.00551 2.70118 -0.945237 -9.31647 2.84229 -0.977646 -9.56992 2.95751 -0.974889 -9.8769 3.09708 -0.98236 -10.1942 3.24144 -0.981838 -10.5301 3.39398 -0.975556 -10.9278 3.57456 -0.976144 -11.452 3.81262 -0.998275 -12.0659 4.09118 -1.0249 -12.7365 4.39587 -1.04215 -13.4711 4.73033 -1.04874 -14.2181 5.06933 -1.02953 -15.2359 5.53121 -1.0342 -16.7594 6.22393 -1.08773 -18.4508 6.99139 -1.10812 -20.0367 7.71197 -1.04987 -20.9907 8.1463 -0.858649 -22.0436 8.6241 -0.641004 -22.8754 9.00271 -0.366984 -22.6856 8.91684 -0.0037295 -22.7533 8.94795 0.341939 -21.8877 8.55492 0.706881 -21.6627 8.45258 1.03898 -21.9416 8.57966 1.37257 -21.7062 8.47254 1.69687 -21.7657 8.50051 2.02974 -20.8295 8.07538 2.28838 -19.4458 7.44769 2.46829 -19.6472 7.53924 2.77989 -19.2281 7.34859 3.01624 -19.1769 7.32535 3.29442 -19.3805 7.41831 3.61676 -20.207 7.79408 4.06968 -19.5846 7.51145 4.24666 -19.1653 7.32111 4.44885 -20.6162 7.98153 5.11195 -20.558 7.95527 5.42168 -21.2509 8.2698 5.95356 -19.5342 7.49051 6.06894 -18.4387 6.99321 5.99296 -18.7106 7.11695 6.39214 -18.452 6.99916 6.5942 -18.8118 7.16253 7.05012 -18.4861 7.01515 7.22113 -19.0299 7.26321 7.78858 -26.1693 10.5095 11.6176 -24.7195 9.85074 11.3743 -19.0474 7.27142 8.80479 -19.1246 7.30717 9.19501 -25.8935 10.3853 13.5114 -25.8673 10.3743 14.0254 -19.8815 7.65214 10.7625 -19.7471 7.59127 11.0703 -19.0606 7.27915 10.9993 -19.0523 7.2767 11.3849 -18.0336 6.81303 11.0287 -18.1928 6.88557 11.5325 -17.9207 6.76236 11.71 -19.5574 7.50781 13.4646 -19.5008 7.48237 13.8736 -6.54631 1.58958 5.52083 -6.47755 1.55893 5.56743 -6.18776 1.42719 5.71315 -6.15976 1.41432 5.88482 -6.08265 1.37934 5.91488 -6.01292 1.34827 5.97192 -5.90534 1.29874 5.894 -5.87239 1.28448 6.0922 -5.80585 1.25448 6.1747 -5.63603 1.17642 5.80972 -5.56837 1.14632 5.8687 -5.52084 1.12478 6.04394 -5.45007 1.09225 6.11088 -5.3283 1.03657 5.87117 -5.24476 0.99923 5.84583 -5.17937 0.9701 5.9474 -5.09675 0.931555 5.91901 -5.04138 0.907093 6.16735 -4.96883 0.874207 6.28558 -4.79581 0.794699 4.8761 -4.73393 0.766046 4.87018 -4.67193 0.737861 4.83311 -4.61109 0.710031 4.82484 -6.47819 1.48769 -0.985572 -6.54397 1.51489 -0.983922 -6.60982 1.54319 -0.980424 -6.6828 1.57383 -0.981602 -6.76404 1.60877 -0.987063 -6.82476 1.63398 -0.971057 -6.92133 1.67463 -0.984428 -6.99744 1.70654 -0.976482 -7.08075 1.74184 -0.972164 -7.17227 1.7805 -0.971179 -7.28023 1.82677 -0.978608 -7.37379 1.86561 -0.97144 -7.47562 1.90884 -0.966757 -7.59285 1.95881 -0.969233 -7.7121 2.00885 -0.967825 -7.83958 2.06235 -0.967452 -7.97634 2.12029 -0.96757 -8.12232 2.18168 -0.967731 -8.2694 2.24425 -0.962951 -8.42572 2.31031 -0.957415 -8.60772 2.3875 -0.959136 -8.79996 2.46821 -0.958307 -8.98406 2.54591 -0.947054 -9.26363 2.66432 -0.96969 -9.51962 2.77213 -0.971795 -9.8116 2.89561 -0.978158 -10.1231 3.02614 -0.980315 -10.4706 3.17351 -0.983283 -10.8377 3.32807 -0.979348 -11.2952 3.52165 -0.988756 -11.8975 3.77554 -1.02129 -12.5287 4.04248 -1.03867 -13.1909 4.32243 -1.03912 -13.8635 4.60689 -1.01704 -14.8556 5.0256 -1.0337 -16.1406 5.56827 -1.06598 -17.9036 6.31237 -1.12663 -19.1698 6.84756 -1.04955 -20.9858 7.61434 -0.992781 -21.6029 7.87433 -0.742782 -23.0516 8.48692 -0.541084 -22.8438 8.40022 -0.176045 -22.7037 8.34095 0.177302 -22.6139 8.30335 0.52338 -21.2642 7.734 1.19286 -21.452 7.81382 1.51426 -21.5616 7.86044 1.83941 -21.7021 7.92056 2.17117 -23.0307 8.48203 2.61131 -19.2057 6.86698 2.56138 -18.5291 6.58154 2.75724 -18.3534 6.5069 3.00009 -18.9208 6.74718 3.35848 -19.2258 6.87673 3.69254 -18.9092 6.74236 3.91459 -19.1217 6.8331 4.24338 -19.4906 6.98898 4.62019 -19.4211 6.9599 4.89961 -20.1856 7.28324 5.41327 -20.6538 7.4823 5.87139 -19.055 6.80634 5.6856 -20.172 7.27928 6.36865 -19.638 7.05329 6.501 -18.7496 6.6785 6.47765 -18.9098 6.74631 6.84682 -18.6249 6.62648 7.03647 -19.7261 7.09239 7.84174 -18.8198 6.70938 7.75225 -27.7666 10.4933 12.509 -19.2345 6.8858 8.61911 -19.3486 6.93415 9.02504 -19.3081 6.91781 9.35427 -19.2367 6.88764 9.6701 -11.3225 3.54032 5.16521 -21.3294 7.77384 11.7438 -18.3046 6.49484 10.161 -18.777 6.69506 10.8497 -21.9636 8.04355 13.5254 -18.2628 6.47764 11.2396 -20.8992 7.59446 13.6706 -19.8867 7.16623 13.3288 -20.0439 7.23396 13.9153 -19.4959 7.00217 13.9135 -21.467 7.83649 16.148 -6.69492 1.58738 5.61709 -6.62105 1.55567 5.65627 -6.47018 1.49144 5.51213 -6.38696 1.45671 5.5195 -6.30686 1.42316 5.53439 -6.2684 1.40661 5.65936 -6.18721 1.372 5.67171 -6.15515 1.35888 5.83321 -6.03326 1.30746 5.71995 -5.94996 1.27227 5.71793 -5.93372 1.26537 5.9636 -5.84942 1.22961 5.96902 -5.76725 1.19512 5.98248 -5.61243 1.12948 5.66372 -5.53539 1.09746 5.67261 -5.53756 1.09854 6.10147 -5.48291 1.07539 6.27595 -5.35833 1.02285 6.03561 -5.29532 0.996603 6.17807 -5.17883 0.947362 5.91298 -5.14073 0.931284 6.31096 -5.0467 0.891384 6.22114 -4.96233 0.855758 6.20904 -4.80328 0.787321 4.85778 -4.74168 0.761618 4.87124 -4.67983 0.734389 4.85364 -6.4989 1.43241 -0.98292 -6.56454 1.45756 -0.982269 -6.63126 1.48375 -0.979676 -6.70512 1.51228 -0.981959 -6.78004 1.54185 -0.9821 -6.85493 1.57053 -0.979993 -6.92989 1.60032 -0.975739 -7.01405 1.63337 -0.975422 -7.10535 1.66883 -0.978484 -7.19054 1.70207 -0.972878 -7.29107 1.74098 -0.976082 -7.38549 1.77768 -0.970618 -7.48712 1.81783 -0.967584 -7.59897 1.86127 -0.966694 -7.72621 1.91147 -0.972565 -7.8473 1.95849 -0.96912 -7.96841 2.0057 -0.96178 -8.11513 2.06291 -0.964544 -8.27214 2.12452 -0.967005 -8.42094 2.18209 -0.959691 -8.57903 2.24416 -0.95167 -8.77293 2.31957 -0.954498 -8.9669 2.39531 -0.950735 -9.18856 2.48219 -0.951442 -9.49013 2.60014 -0.976732 -9.76613 2.70764 -0.980883 -10.0535 2.81979 -0.978642 -10.3869 2.94995 -0.981656 -10.7481 3.09064 -0.981399 -11.1566 3.2505 -0.982055 -11.7003 3.46318 -1.0068 -12.3291 3.70775 -1.03328 -12.9879 3.96535 -1.04371 -13.7032 4.24519 -1.04236 -14.522 4.56418 -1.03575 -15.6373 4.99941 -1.0545 -17.1599 5.59425 -1.10071 -18.6868 6.18963 -1.09032 -20.494 6.89545 -1.05983 -21.2853 7.20524 -0.84769 -22.1115 7.52722 -0.609893 -23.3339 8.00585 -0.371596 -23.1018 7.91558 -0.00689144 -24.8505 8.59978 1.03327 -24.9581 8.64227 1.41431 -28.9531 10.204 2.86125 -30.5149 10.8148 3.46735 -20.8188 7.02803 2.85865 -21.11 7.14195 3.2046 -18.1293 5.97814 3.06787 -17.7815 5.84253 3.26721 -18.6784 6.19353 3.69086 -18.9254 6.29097 4.01483 -19.2566 6.42097 4.36979 -21.7321 7.38845 5.27216 -19.8987 6.67214 5.11954 -21.5291 7.31024 5.89497 -18.7085 6.20759 5.3663 -18.6268 6.17629 5.6266 -18.7444 6.22265 5.95631 -18.5382 6.1426 6.17442 -18.2601 6.03415 6.35896 -19.3536 6.46231 7.10157 -18.1211 5.98038 6.88534 -19.0433 6.34242 7.60271 -19.0963 6.36242 7.94924 -19.0404 6.34154 8.24898 -19.3559 6.4655 8.74613 -19.1858 6.4 8.99819 -22.5971 7.73418 11.2948 -20.2773 6.82736 10.3492 -11.2782 3.30664 5.15231 -19.9962 6.7187 10.9507 -18.6091 6.17611 10.4153 -18.5637 6.15945 10.7522 -19.885 6.67641 12.0862 -21.6929 7.38481 13.8684 -21.0443 7.13195 13.8451 -20.8479 7.05625 14.1629 -19.8981 6.6848 13.849 -19.6727 6.59754 14.1207 -21.6328 7.36566 16.3622 -6.67278 1.50953 5.53728 -6.60633 1.48321 5.59306 -6.49425 1.44011 5.53809 -6.42053 1.41116 5.57243 -6.3468 1.38215 5.60548 -6.25222 1.34452 5.58104 -6.2025 1.32565 5.68599 -6.10589 1.2885 5.64862 -6.06451 1.27193 5.78983 -5.96261 1.23198 5.73002 -5.93182 1.22057 5.92747 -5.88754 1.20352 6.09606 -5.73841 1.14506 5.82787 -5.63428 1.10442 5.73106 -5.54682 1.06958 5.69061 -5.54493 1.0699 6.11944 -5.48306 1.0457 6.26399 -5.39589 1.01211 6.26933 -5.32575 0.9848 6.40189 -5.17949 0.926522 5.89808 -5.12438 0.905546 6.15636 -5.04678 0.875003 6.23476 -4.95943 0.841539 6.20195 -4.81442 0.782657 4.93912 -4.74835 0.75675 4.86212 -4.68588 0.732517 4.88392 -6.58325 1.40238 -0.980007 -6.64984 1.42652 -0.978513 -6.71744 1.45069 -0.975126 -6.7993 1.47946 -0.982992 -6.86799 1.50477 -0.975564 -6.95094 1.5347 -0.978889 -7.03491 1.56469 -0.979723 -7.10465 1.59025 -0.965908 -7.20596 1.62587 -0.973762 -7.29916 1.65941 -0.97274 -7.39345 1.69403 -0.968875 -7.49689 1.73098 -0.9676 -7.60035 1.76808 -0.963029 -7.72933 1.81406 -0.971009 -7.84203 1.85472 -0.964482 -7.97313 1.90198 -0.964332 -8.1124 1.95173 -0.964669 -8.25276 2.00264 -0.960365 -8.41148 2.05926 -0.960392 -8.5713 2.11706 -0.955179 -8.74849 2.18071 -0.952792 -8.94412 2.25115 -0.952487 -9.1408 2.32188 -0.945395 -9.44478 2.43041 -0.975548 -9.69677 2.52158 -0.974102 -9.98657 2.6253 -0.977174 -10.3399 2.75266 -0.99232 -10.6318 2.85731 -0.973828 -11.0343 3.00225 -0.979212 -11.5371 3.18352 -0.999586 -12.1433 3.40121 -1.02927 -12.7618 3.62313 -1.03944 -13.4285 3.86278 -1.03814 -14.1987 4.13942 -1.03446 -15.1471 4.4802 -1.03745 -16.461 4.9529 -1.07012 -18.2151 5.58352 -1.12402 -19.508 6.04784 -1.04808 -21.232 6.66742 -0.976848 -21.7117 6.841 -0.715214 -23.5018 7.48454 -0.54576 -23.3735 7.43889 -0.186368 -23.1931 7.37518 0.169918 -24.9129 7.99431 1.21791 -25.047 8.04415 1.59738 -19.2814 5.97144 1.70666 -18.6189 5.73392 1.9354 -28.8459 9.41156 3.054 -26.561 8.5904 3.27143 -24.286 7.77357 3.40597 -18.5248 5.70153 2.96781 -22.6693 7.19306 3.88947 -18.8146 5.80695 3.54517 -22.6748 7.19576 4.57754 -22.8991 7.27705 4.97298 -19.313 5.98774 4.48063 -22.2731 7.05326 5.52306 -21.8143 6.8883 5.74373 -18.3789 5.65318 5.07142 -18.1485 5.56982 5.27408 -17.9867 5.51223 5.49345 -31.0794 10.2271 10.4272 -18.2748 5.61676 6.15197 -18.6201 5.74228 6.57541 -18.2901 5.62366 6.73443 -18.6457 5.75193 7.18549 -23.7537 7.59287 9.85399 -20.8061 6.5315 8.84991 -17.5251 5.35021 7.55007 -19.4194 6.0335 8.85015 -17.9955 5.52076 8.40666 -18.8055 5.81271 9.19233 -17.2037 5.23673 8.57162 -11.2829 3.10273 5.1725 -17.2448 5.25164 9.22568 -23.6124 7.54958 13.8656 -23.8688 7.64209 14.5466 -20.0164 6.25326 12.249 -20.289 6.35238 12.8807 -20.2583 6.34191 13.2997 -20.0097 6.25302 13.5507 -20.0738 6.2776 14.0639 -19.8427 6.19468 14.3352 -21.6809 6.85934 16.4858 -6.70073 1.45548 5.57366 -6.58678 1.41456 5.51979 -6.63247 1.4311 5.84833 -6.43759 1.36078 5.58849 -6.33082 1.32255 5.53704 -6.26658 1.29923 5.59547 -6.2263 1.28518 5.72824 -6.10076 1.2405 5.60476 -6.07303 1.23044 5.79301 -5.98384 1.19808 5.78018 -5.92811 1.17884 5.8907 -5.81795 1.13826 5.78763 -5.74132 1.1113 5.81809 -5.64786 1.0774 5.76913 -5.58485 1.05487 5.86515 -5.53249 1.03656 6.03887 -5.48132 1.0181 6.25155 -5.43263 1.0019 6.53307 -5.32648 0.96247 6.4177 -5.18903 0.912569 5.97218 -5.12121 0.888406 6.13049 -5.04619 0.86264 6.26792 -4.95897 0.830629 6.24434 -4.81556 0.777199 4.83045 -4.75323 0.754478 4.86269 -6.66748 1.37038 -0.976596 -6.73496 1.3925 -0.974209 -6.81768 1.41915 -0.983378 -6.88624 1.44241 -0.976951 -6.97 1.46922 -0.981431 -7.05483 1.4971 -0.983468 -7.13257 1.52283 -0.976834 -7.21844 1.55089 -0.973882 -7.31251 1.58229 -0.974364 -7.40761 1.61378 -0.971954 -7.51085 1.64766 -0.972128 -7.61511 1.68163 -0.969211 -7.72858 1.71895 -0.968334 -7.85027 1.75971 -0.968992 -7.97393 1.79955 -0.965715 -8.1058 1.84285 -0.963474 -8.2479 1.88953 -0.96158 -8.39822 1.93973 -0.959623 -8.55872 1.99235 -0.957064 -8.72025 2.04517 -0.949217 -8.90835 2.10708 -0.948232 -9.0975 2.16924 -0.940961 -9.40296 2.26942 -0.975922 -9.65748 2.35321 -0.978739 -9.93042 2.443 -0.979592 -10.2238 2.53973 -0.977544 -10.554 2.64817 -0.977661 -10.9404 2.77499 -0.98373 -11.3748 2.91795 -0.99007 -11.9481 3.10654 -1.01967 -12.543 3.30262 -1.03369 -13.1778 3.51095 -1.0353 -13.8617 3.73597 -1.02471 -14.7521 4.02891 -1.03139 -15.9163 4.41174 -1.05627 -17.5066 4.93494 -1.10931 -18.8756 5.38477 -1.071 -20.7658 6.00687 -1.05007 -21.5438 6.26333 -0.837007 -22.0829 6.44141 -0.574159 -23.7184 6.97851 -0.372828 -23.9941 7.07077 -0.037309 -23.4011 6.87652 0.339552 -25.9552 7.71698 0.636993 -25.948 7.71572 1.02759 -25.9448 7.71521 1.41793 -21.3878 6.21606 1.6403 -19.2594 5.51647 1.8297 -18.997 5.43133 2.07885 -19.4504 5.58062 2.38514 -19.7934 5.69472 2.69672 -20.112 5.79979 3.01896 -21.6756 6.3149 3.53883 -18.3286 5.21425 3.29906 -22.4145 6.55956 4.31577 -22.4316 6.56537 4.65607 -22.4149 6.56096 4.99174 -29.8045 8.99615 7.13107 -22.6867 6.65232 5.74915 -22.5963 6.62285 6.07641 -20.2731 5.85824 5.72877 -18.2125 5.17985 5.37653 -18.2282 5.18569 5.65506 -18.5532 5.29295 6.04963 -18.6459 5.3244 6.37186 -18.4486 5.25958 6.58435 -17.4738 4.93923 6.46139 -17.6176 4.9865 6.80095 -17.45 4.93251 7.00487 -16.9873 4.78068 7.06073 -16.9712 4.77492 7.32957 -18.2345 5.19259 8.28983 -19.37 5.56843 9.24193 -18.1763 5.17493 8.8944 -17.2787 4.87928 8.6758 -17.5079 4.95529 9.13253 -18.0245 5.12651 9.79608 -20.2257 5.85467 11.6467 -20.7705 6.03488 12.4452 -19.2336 5.52834 11.7463 -18.6846 5.34803 11.7296 -18.8611 5.40719 12.268 -18.8447 5.40196 12.6683 -19.7556 5.70447 13.8706 -18.9077 5.42461 13.5861 -19.4349 5.60063 14.5213 -18.8775 5.41638 14.4755 -18.4855 5.28829 14.5704 -6.84356 1.4412 5.66174 -6.70607 1.39553 5.56454 -6.59548 1.35981 5.51851 -6.63593 1.37321 5.83813 -6.4559 1.31377 5.61348 -6.35244 1.27976 5.57041 -6.28938 1.25882 5.63772 -6.22845 1.23918 5.71356 -6.14154 1.21028 5.71256 -6.06607 1.1855 5.74801 -6.00313 1.16529 5.8301 -5.95061 1.14781 5.95973 -5.81572 1.10386 5.7588 -5.74549 1.08093 5.81765 -5.66263 1.05279 5.81668 -5.60404 1.03393 5.95153 -5.54346 1.01463 6.09553 -5.49251 0.998128 6.32763 -5.426 0.977076 6.50981 -5.32754 0.944093 6.45293 -5.19347 0.89893 6.02618 -5.1173 0.874794 6.11417 -5.04133 0.850051 6.25085 -4.95447 0.821471 6.25644 -4.86625 0.791924 6.20042 -4.75924 0.753623 4.873 -6.69543 1.31997 -0.988257 -6.75672 1.33875 -0.97975 -6.81796 1.35662 -0.969596 -6.90869 1.38351 -0.984347 -6.98525 1.40702 -0.983402 -7.06278 1.42958 -0.980214 -7.13426 1.45091 -0.968609 -7.22 1.47689 -0.967257 -7.322 1.50745 -0.975168 -7.40977 1.53359 -0.968332 -7.51382 1.56432 -0.970261 -7.61082 1.5939 -0.963467 -7.72409 1.62813 -0.964539 -7.84652 1.66474 -0.967202 -7.96185 1.69921 -0.960992 -8.10359 1.74056 -0.965842 -8.2373 1.78084 -0.961465 -8.38836 1.82686 -0.962012 -8.54953 1.8743 -0.962007 -8.69454 1.91838 -0.948193 -8.87511 1.97178 -0.946131 -9.06592 2.02865 -0.942218 -9.33725 2.11037 -0.966291 -9.60146 2.18915 -0.977448 -9.85859 2.26597 -0.975938 -10.1626 2.35662 -0.982485 -10.4769 2.45102 -0.981588 -10.8106 2.55051 -0.975888 -11.2289 2.6763 -0.98416 -11.7329 2.82653 -1.00182 -12.3408 3.00812 -1.02914 -12.9887 3.20195 -1.04437 -13.6856 3.41047 -1.04728 -14.4142 3.62804 -1.03137 -15.3601 3.91194 -1.03144 -16.7068 4.31432 -1.06682 -18.4554 4.83719 -1.11579 -19.7139 5.21361 -1.03376 -21.4693 5.73888 -0.965352 -22.0909 5.92517 -0.719478 -22.9483 6.18259 -0.471246 -23.5151 6.35268 -0.173982 -23.6852 6.40417 0.161367 -23.8502 6.45426 0.502533 -23.3374 6.30288 1.19445 -23.4851 6.34808 1.53749 -25.9424 7.08381 1.99183 -21.8882 5.8716 2.11995 -19.298 5.09722 2.22105 -19.3423 5.11103 2.49286 -19.7715 5.24041 2.81313 -19.7678 5.23936 3.09075 -18.3008 4.80086 3.14107 -17.5167 4.56611 3.2574 -23.4204 6.33535 4.64046 -17.3588 4.51965 3.70587 -18.78 4.94652 4.27535 -24.9543 6.79721 6.09313 -22.9005 6.18294 5.92972 -19.9634 5.30262 5.434 -20.3278 5.41344 5.84711 -18.0522 4.73172 5.40861 -21.3368 5.71695 6.82499 -17.3557 4.52399 5.69093 -16.898 4.3872 5.77305 -16.9688 4.409 6.05627 -16.7319 4.33882 6.21337 -17.3366 4.52031 6.74637 -17.7094 4.63359 7.19904 -17.1206 4.45723 7.19341 -16.7066 4.33295 7.25755 -19.4124 5.1468 9.00339 -19.2422 5.09612 9.25062 -17.1111 4.45632 8.33675 -16.995 4.42256 8.5662 -16.9402 4.40613 8.83557 -17.5265 4.58394 9.535 -22.0532 5.94561 12.9962 -21.3294 5.72857 12.9361 -18.6952 4.93706 11.4247 -18.981 5.02427 12.0345 -18.8776 4.99447 12.3594 -18.7086 4.94408 12.6343 -20.1969 5.39303 14.3375 -19.2358 5.10543 13.9613 -19.0465 5.04895 14.2502 -18.6244 4.92342 14.3199 -18.7059 4.94899 14.874 -18.6356 4.92897 15.2948 -6.69008 1.33338 5.72782 -6.6148 1.31103 5.77206 -6.43611 1.25741 5.54512 -6.36073 1.23438 5.57548 -6.30612 1.21832 5.67052 -6.28577 1.21282 5.8787 -6.15552 1.17389 5.74417 -6.07083 1.14822 5.7503 -6.0299 1.13696 5.91849 -5.92959 1.10622 5.86402 -5.81469 1.07186 5.73925 -5.74985 1.05303 5.82659 -5.66611 1.0269 5.82483 -5.60456 1.00971 5.94931 -5.54205 0.991508 6.09268 -5.49445 0.97774 6.36386 -5.40149 0.949432 6.34726 -5.30857 0.922032 6.32881 -5.18739 0.884983 5.98025 -5.11245 0.862224 6.0975 -5.03677 0.839915 6.2634 -4.94684 0.813513 6.22826 -4.86143 0.787698 6.29137 -VERTICES 24154 48308 -1 0 -1 1 -1 2 -1 3 -1 4 -1 5 -1 6 -1 7 -1 8 -1 9 -1 10 -1 11 -1 12 -1 13 -1 14 -1 15 -1 16 -1 17 -1 18 -1 19 -1 20 -1 21 -1 22 -1 23 -1 24 -1 25 -1 26 -1 27 -1 28 -1 29 -1 30 -1 31 -1 32 -1 33 -1 34 -1 35 -1 36 -1 37 -1 38 -1 39 -1 40 -1 41 -1 42 -1 43 -1 44 -1 45 -1 46 -1 47 -1 48 -1 49 -1 50 -1 51 -1 52 -1 53 -1 54 -1 55 -1 56 -1 57 -1 58 -1 59 -1 60 -1 61 -1 62 -1 63 -1 64 -1 65 -1 66 -1 67 -1 68 -1 69 -1 70 -1 71 -1 72 -1 73 -1 74 -1 75 -1 76 -1 77 -1 78 -1 79 -1 80 -1 81 -1 82 -1 83 -1 84 -1 85 -1 86 -1 87 -1 88 -1 89 -1 90 -1 91 -1 92 -1 93 -1 94 -1 95 -1 96 -1 97 -1 98 -1 99 -1 100 -1 101 -1 102 -1 103 -1 104 -1 105 -1 106 -1 107 -1 108 -1 109 -1 110 -1 111 -1 112 -1 113 -1 114 -1 115 -1 116 -1 117 -1 118 -1 119 -1 120 -1 121 -1 122 -1 123 -1 124 -1 125 -1 126 -1 127 -1 128 -1 129 -1 130 -1 131 -1 132 -1 133 -1 134 -1 135 -1 136 -1 137 -1 138 -1 139 -1 140 -1 141 -1 142 -1 143 -1 144 -1 145 -1 146 -1 147 -1 148 -1 149 -1 150 -1 151 -1 152 -1 153 -1 154 -1 155 -1 156 -1 157 -1 158 -1 159 -1 160 -1 161 -1 162 -1 163 -1 164 -1 165 -1 166 -1 167 -1 168 -1 169 -1 170 -1 171 -1 172 -1 173 -1 174 -1 175 -1 176 -1 177 -1 178 -1 179 -1 180 -1 181 -1 182 -1 183 -1 184 -1 185 -1 186 -1 187 -1 188 -1 189 -1 190 -1 191 -1 192 -1 193 -1 194 -1 195 -1 196 -1 197 -1 198 -1 199 -1 200 -1 201 -1 202 -1 203 -1 204 -1 205 -1 206 -1 207 -1 208 -1 209 -1 210 -1 211 -1 212 -1 213 -1 214 -1 215 -1 216 -1 217 -1 218 -1 219 -1 220 -1 221 -1 222 -1 223 -1 224 -1 225 -1 226 -1 227 -1 228 -1 229 -1 230 -1 231 -1 232 -1 233 -1 234 -1 235 -1 236 -1 237 -1 238 -1 239 -1 240 -1 241 -1 242 -1 243 -1 244 -1 245 -1 246 -1 247 -1 248 -1 249 -1 250 -1 251 -1 252 -1 253 -1 254 -1 255 -1 256 -1 257 -1 258 -1 259 -1 260 -1 261 -1 262 -1 263 -1 264 -1 265 -1 266 -1 267 -1 268 -1 269 -1 270 -1 271 -1 272 -1 273 -1 274 -1 275 -1 276 -1 277 -1 278 -1 279 -1 280 -1 281 -1 282 -1 283 -1 284 -1 285 -1 286 -1 287 -1 288 -1 289 -1 290 -1 291 -1 292 -1 293 -1 294 -1 295 -1 296 -1 297 -1 298 -1 299 -1 300 -1 301 -1 302 -1 303 -1 304 -1 305 -1 306 -1 307 -1 308 -1 309 -1 310 -1 311 -1 312 -1 313 -1 314 -1 315 -1 316 -1 317 -1 318 -1 319 -1 320 -1 321 -1 322 -1 323 -1 324 -1 325 -1 326 -1 327 -1 328 -1 329 -1 330 -1 331 -1 332 -1 333 -1 334 -1 335 -1 336 -1 337 -1 338 -1 339 -1 340 -1 341 -1 342 -1 343 -1 344 -1 345 -1 346 -1 347 -1 348 -1 349 -1 350 -1 351 -1 352 -1 353 -1 354 -1 355 -1 356 -1 357 -1 358 -1 359 -1 360 -1 361 -1 362 -1 363 -1 364 -1 365 -1 366 -1 367 -1 368 -1 369 -1 370 -1 371 -1 372 -1 373 -1 374 -1 375 -1 376 -1 377 -1 378 -1 379 -1 380 -1 381 -1 382 -1 383 -1 384 -1 385 -1 386 -1 387 -1 388 -1 389 -1 390 -1 391 -1 392 -1 393 -1 394 -1 395 -1 396 -1 397 -1 398 -1 399 -1 400 -1 401 -1 402 -1 403 -1 404 -1 405 -1 406 -1 407 -1 408 -1 409 -1 410 -1 411 -1 412 -1 413 -1 414 -1 415 -1 416 -1 417 -1 418 -1 419 -1 420 -1 421 -1 422 -1 423 -1 424 -1 425 -1 426 -1 427 -1 428 -1 429 -1 430 -1 431 -1 432 -1 433 -1 434 -1 435 -1 436 -1 437 -1 438 -1 439 -1 440 -1 441 -1 442 -1 443 -1 444 -1 445 -1 446 -1 447 -1 448 -1 449 -1 450 -1 451 -1 452 -1 453 -1 454 -1 455 -1 456 -1 457 -1 458 -1 459 -1 460 -1 461 -1 462 -1 463 -1 464 -1 465 -1 466 -1 467 -1 468 -1 469 -1 470 -1 471 -1 472 -1 473 -1 474 -1 475 -1 476 -1 477 -1 478 -1 479 -1 480 -1 481 -1 482 -1 483 -1 484 -1 485 -1 486 -1 487 -1 488 -1 489 -1 490 -1 491 -1 492 -1 493 -1 494 -1 495 -1 496 -1 497 -1 498 -1 499 -1 500 -1 501 -1 502 -1 503 -1 504 -1 505 -1 506 -1 507 -1 508 -1 509 -1 510 -1 511 -1 512 -1 513 -1 514 -1 515 -1 516 -1 517 -1 518 -1 519 -1 520 -1 521 -1 522 -1 523 -1 524 -1 525 -1 526 -1 527 -1 528 -1 529 -1 530 -1 531 -1 532 -1 533 -1 534 -1 535 -1 536 -1 537 -1 538 -1 539 -1 540 -1 541 -1 542 -1 543 -1 544 -1 545 -1 546 -1 547 -1 548 -1 549 -1 550 -1 551 -1 552 -1 553 -1 554 -1 555 -1 556 -1 557 -1 558 -1 559 -1 560 -1 561 -1 562 -1 563 -1 564 -1 565 -1 566 -1 567 -1 568 -1 569 -1 570 -1 571 -1 572 -1 573 -1 574 -1 575 -1 576 -1 577 -1 578 -1 579 -1 580 -1 581 -1 582 -1 583 -1 584 -1 585 -1 586 -1 587 -1 588 -1 589 -1 590 -1 591 -1 592 -1 593 -1 594 -1 595 -1 596 -1 597 -1 598 -1 599 -1 600 -1 601 -1 602 -1 603 -1 604 -1 605 -1 606 -1 607 -1 608 -1 609 -1 610 -1 611 -1 612 -1 613 -1 614 -1 615 -1 616 -1 617 -1 618 -1 619 -1 620 -1 621 -1 622 -1 623 -1 624 -1 625 -1 626 -1 627 -1 628 -1 629 -1 630 -1 631 -1 632 -1 633 -1 634 -1 635 -1 636 -1 637 -1 638 -1 639 -1 640 -1 641 -1 642 -1 643 -1 644 -1 645 -1 646 -1 647 -1 648 -1 649 -1 650 -1 651 -1 652 -1 653 -1 654 -1 655 -1 656 -1 657 -1 658 -1 659 -1 660 -1 661 -1 662 -1 663 -1 664 -1 665 -1 666 -1 667 -1 668 -1 669 -1 670 -1 671 -1 672 -1 673 -1 674 -1 675 -1 676 -1 677 -1 678 -1 679 -1 680 -1 681 -1 682 -1 683 -1 684 -1 685 -1 686 -1 687 -1 688 -1 689 -1 690 -1 691 -1 692 -1 693 -1 694 -1 695 -1 696 -1 697 -1 698 -1 699 -1 700 -1 701 -1 702 -1 703 -1 704 -1 705 -1 706 -1 707 -1 708 -1 709 -1 710 -1 711 -1 712 -1 713 -1 714 -1 715 -1 716 -1 717 -1 718 -1 719 -1 720 -1 721 -1 722 -1 723 -1 724 -1 725 -1 726 -1 727 -1 728 -1 729 -1 730 -1 731 -1 732 -1 733 -1 734 -1 735 -1 736 -1 737 -1 738 -1 739 -1 740 -1 741 -1 742 -1 743 -1 744 -1 745 -1 746 -1 747 -1 748 -1 749 -1 750 -1 751 -1 752 -1 753 -1 754 -1 755 -1 756 -1 757 -1 758 -1 759 -1 760 -1 761 -1 762 -1 763 -1 764 -1 765 -1 766 -1 767 -1 768 -1 769 -1 770 -1 771 -1 772 -1 773 -1 774 -1 775 -1 776 -1 777 -1 778 -1 779 -1 780 -1 781 -1 782 -1 783 -1 784 -1 785 -1 786 -1 787 -1 788 -1 789 -1 790 -1 791 -1 792 -1 793 -1 794 -1 795 -1 796 -1 797 -1 798 -1 799 -1 800 -1 801 -1 802 -1 803 -1 804 -1 805 -1 806 -1 807 -1 808 -1 809 -1 810 -1 811 -1 812 -1 813 -1 814 -1 815 -1 816 -1 817 -1 818 -1 819 -1 820 -1 821 -1 822 -1 823 -1 824 -1 825 -1 826 -1 827 -1 828 -1 829 -1 830 -1 831 -1 832 -1 833 -1 834 -1 835 -1 836 -1 837 -1 838 -1 839 -1 840 -1 841 -1 842 -1 843 -1 844 -1 845 -1 846 -1 847 -1 848 -1 849 -1 850 -1 851 -1 852 -1 853 -1 854 -1 855 -1 856 -1 857 -1 858 -1 859 -1 860 -1 861 -1 862 -1 863 -1 864 -1 865 -1 866 -1 867 -1 868 -1 869 -1 870 -1 871 -1 872 -1 873 -1 874 -1 875 -1 876 -1 877 -1 878 -1 879 -1 880 -1 881 -1 882 -1 883 -1 884 -1 885 -1 886 -1 887 -1 888 -1 889 -1 890 -1 891 -1 892 -1 893 -1 894 -1 895 -1 896 -1 897 -1 898 -1 899 -1 900 -1 901 -1 902 -1 903 -1 904 -1 905 -1 906 -1 907 -1 908 -1 909 -1 910 -1 911 -1 912 -1 913 -1 914 -1 915 -1 916 -1 917 -1 918 -1 919 -1 920 -1 921 -1 922 -1 923 -1 924 -1 925 -1 926 -1 927 -1 928 -1 929 -1 930 -1 931 -1 932 -1 933 -1 934 -1 935 -1 936 -1 937 -1 938 -1 939 -1 940 -1 941 -1 942 -1 943 -1 944 -1 945 -1 946 -1 947 -1 948 -1 949 -1 950 -1 951 -1 952 -1 953 -1 954 -1 955 -1 956 -1 957 -1 958 -1 959 -1 960 -1 961 -1 962 -1 963 -1 964 -1 965 -1 966 -1 967 -1 968 -1 969 -1 970 -1 971 -1 972 -1 973 -1 974 -1 975 -1 976 -1 977 -1 978 -1 979 -1 980 -1 981 -1 982 -1 983 -1 984 -1 985 -1 986 -1 987 -1 988 -1 989 -1 990 -1 991 -1 992 -1 993 -1 994 -1 995 -1 996 -1 997 -1 998 -1 999 -1 1000 -1 1001 -1 1002 -1 1003 -1 1004 -1 1005 -1 1006 -1 1007 -1 1008 -1 1009 -1 1010 -1 1011 -1 1012 -1 1013 -1 1014 -1 1015 -1 1016 -1 1017 -1 1018 -1 1019 -1 1020 -1 1021 -1 1022 -1 1023 -1 1024 -1 1025 -1 1026 -1 1027 -1 1028 -1 1029 -1 1030 -1 1031 -1 1032 -1 1033 -1 1034 -1 1035 -1 1036 -1 1037 -1 1038 -1 1039 -1 1040 -1 1041 -1 1042 -1 1043 -1 1044 -1 1045 -1 1046 -1 1047 -1 1048 -1 1049 -1 1050 -1 1051 -1 1052 -1 1053 -1 1054 -1 1055 -1 1056 -1 1057 -1 1058 -1 1059 -1 1060 -1 1061 -1 1062 -1 1063 -1 1064 -1 1065 -1 1066 -1 1067 -1 1068 -1 1069 -1 1070 -1 1071 -1 1072 -1 1073 -1 1074 -1 1075 -1 1076 -1 1077 -1 1078 -1 1079 -1 1080 -1 1081 -1 1082 -1 1083 -1 1084 -1 1085 -1 1086 -1 1087 -1 1088 -1 1089 -1 1090 -1 1091 -1 1092 -1 1093 -1 1094 -1 1095 -1 1096 -1 1097 -1 1098 -1 1099 -1 1100 -1 1101 -1 1102 -1 1103 -1 1104 -1 1105 -1 1106 -1 1107 -1 1108 -1 1109 -1 1110 -1 1111 -1 1112 -1 1113 -1 1114 -1 1115 -1 1116 -1 1117 -1 1118 -1 1119 -1 1120 -1 1121 -1 1122 -1 1123 -1 1124 -1 1125 -1 1126 -1 1127 -1 1128 -1 1129 -1 1130 -1 1131 -1 1132 -1 1133 -1 1134 -1 1135 -1 1136 -1 1137 -1 1138 -1 1139 -1 1140 -1 1141 -1 1142 -1 1143 -1 1144 -1 1145 -1 1146 -1 1147 -1 1148 -1 1149 -1 1150 -1 1151 -1 1152 -1 1153 -1 1154 -1 1155 -1 1156 -1 1157 -1 1158 -1 1159 -1 1160 -1 1161 -1 1162 -1 1163 -1 1164 -1 1165 -1 1166 -1 1167 -1 1168 -1 1169 -1 1170 -1 1171 -1 1172 -1 1173 -1 1174 -1 1175 -1 1176 -1 1177 -1 1178 -1 1179 -1 1180 -1 1181 -1 1182 -1 1183 -1 1184 -1 1185 -1 1186 -1 1187 -1 1188 -1 1189 -1 1190 -1 1191 -1 1192 -1 1193 -1 1194 -1 1195 -1 1196 -1 1197 -1 1198 -1 1199 -1 1200 -1 1201 -1 1202 -1 1203 -1 1204 -1 1205 -1 1206 -1 1207 -1 1208 -1 1209 -1 1210 -1 1211 -1 1212 -1 1213 -1 1214 -1 1215 -1 1216 -1 1217 -1 1218 -1 1219 -1 1220 -1 1221 -1 1222 -1 1223 -1 1224 -1 1225 -1 1226 -1 1227 -1 1228 -1 1229 -1 1230 -1 1231 -1 1232 -1 1233 -1 1234 -1 1235 -1 1236 -1 1237 -1 1238 -1 1239 -1 1240 -1 1241 -1 1242 -1 1243 -1 1244 -1 1245 -1 1246 -1 1247 -1 1248 -1 1249 -1 1250 -1 1251 -1 1252 -1 1253 -1 1254 -1 1255 -1 1256 -1 1257 -1 1258 -1 1259 -1 1260 -1 1261 -1 1262 -1 1263 -1 1264 -1 1265 -1 1266 -1 1267 -1 1268 -1 1269 -1 1270 -1 1271 -1 1272 -1 1273 -1 1274 -1 1275 -1 1276 -1 1277 -1 1278 -1 1279 -1 1280 -1 1281 -1 1282 -1 1283 -1 1284 -1 1285 -1 1286 -1 1287 -1 1288 -1 1289 -1 1290 -1 1291 -1 1292 -1 1293 -1 1294 -1 1295 -1 1296 -1 1297 -1 1298 -1 1299 -1 1300 -1 1301 -1 1302 -1 1303 -1 1304 -1 1305 -1 1306 -1 1307 -1 1308 -1 1309 -1 1310 -1 1311 -1 1312 -1 1313 -1 1314 -1 1315 -1 1316 -1 1317 -1 1318 -1 1319 -1 1320 -1 1321 -1 1322 -1 1323 -1 1324 -1 1325 -1 1326 -1 1327 -1 1328 -1 1329 -1 1330 -1 1331 -1 1332 -1 1333 -1 1334 -1 1335 -1 1336 -1 1337 -1 1338 -1 1339 -1 1340 -1 1341 -1 1342 -1 1343 -1 1344 -1 1345 -1 1346 -1 1347 -1 1348 -1 1349 -1 1350 -1 1351 -1 1352 -1 1353 -1 1354 -1 1355 -1 1356 -1 1357 -1 1358 -1 1359 -1 1360 -1 1361 -1 1362 -1 1363 -1 1364 -1 1365 -1 1366 -1 1367 -1 1368 -1 1369 -1 1370 -1 1371 -1 1372 -1 1373 -1 1374 -1 1375 -1 1376 -1 1377 -1 1378 -1 1379 -1 1380 -1 1381 -1 1382 -1 1383 -1 1384 -1 1385 -1 1386 -1 1387 -1 1388 -1 1389 -1 1390 -1 1391 -1 1392 -1 1393 -1 1394 -1 1395 -1 1396 -1 1397 -1 1398 -1 1399 -1 1400 -1 1401 -1 1402 -1 1403 -1 1404 -1 1405 -1 1406 -1 1407 -1 1408 -1 1409 -1 1410 -1 1411 -1 1412 -1 1413 -1 1414 -1 1415 -1 1416 -1 1417 -1 1418 -1 1419 -1 1420 -1 1421 -1 1422 -1 1423 -1 1424 -1 1425 -1 1426 -1 1427 -1 1428 -1 1429 -1 1430 -1 1431 -1 1432 -1 1433 -1 1434 -1 1435 -1 1436 -1 1437 -1 1438 -1 1439 -1 1440 -1 1441 -1 1442 -1 1443 -1 1444 -1 1445 -1 1446 -1 1447 -1 1448 -1 1449 -1 1450 -1 1451 -1 1452 -1 1453 -1 1454 -1 1455 -1 1456 -1 1457 -1 1458 -1 1459 -1 1460 -1 1461 -1 1462 -1 1463 -1 1464 -1 1465 -1 1466 -1 1467 -1 1468 -1 1469 -1 1470 -1 1471 -1 1472 -1 1473 -1 1474 -1 1475 -1 1476 -1 1477 -1 1478 -1 1479 -1 1480 -1 1481 -1 1482 -1 1483 -1 1484 -1 1485 -1 1486 -1 1487 -1 1488 -1 1489 -1 1490 -1 1491 -1 1492 -1 1493 -1 1494 -1 1495 -1 1496 -1 1497 -1 1498 -1 1499 -1 1500 -1 1501 -1 1502 -1 1503 -1 1504 -1 1505 -1 1506 -1 1507 -1 1508 -1 1509 -1 1510 -1 1511 -1 1512 -1 1513 -1 1514 -1 1515 -1 1516 -1 1517 -1 1518 -1 1519 -1 1520 -1 1521 -1 1522 -1 1523 -1 1524 -1 1525 -1 1526 -1 1527 -1 1528 -1 1529 -1 1530 -1 1531 -1 1532 -1 1533 -1 1534 -1 1535 -1 1536 -1 1537 -1 1538 -1 1539 -1 1540 -1 1541 -1 1542 -1 1543 -1 1544 -1 1545 -1 1546 -1 1547 -1 1548 -1 1549 -1 1550 -1 1551 -1 1552 -1 1553 -1 1554 -1 1555 -1 1556 -1 1557 -1 1558 -1 1559 -1 1560 -1 1561 -1 1562 -1 1563 -1 1564 -1 1565 -1 1566 -1 1567 -1 1568 -1 1569 -1 1570 -1 1571 -1 1572 -1 1573 -1 1574 -1 1575 -1 1576 -1 1577 -1 1578 -1 1579 -1 1580 -1 1581 -1 1582 -1 1583 -1 1584 -1 1585 -1 1586 -1 1587 -1 1588 -1 1589 -1 1590 -1 1591 -1 1592 -1 1593 -1 1594 -1 1595 -1 1596 -1 1597 -1 1598 -1 1599 -1 1600 -1 1601 -1 1602 -1 1603 -1 1604 -1 1605 -1 1606 -1 1607 -1 1608 -1 1609 -1 1610 -1 1611 -1 1612 -1 1613 -1 1614 -1 1615 -1 1616 -1 1617 -1 1618 -1 1619 -1 1620 -1 1621 -1 1622 -1 1623 -1 1624 -1 1625 -1 1626 -1 1627 -1 1628 -1 1629 -1 1630 -1 1631 -1 1632 -1 1633 -1 1634 -1 1635 -1 1636 -1 1637 -1 1638 -1 1639 -1 1640 -1 1641 -1 1642 -1 1643 -1 1644 -1 1645 -1 1646 -1 1647 -1 1648 -1 1649 -1 1650 -1 1651 -1 1652 -1 1653 -1 1654 -1 1655 -1 1656 -1 1657 -1 1658 -1 1659 -1 1660 -1 1661 -1 1662 -1 1663 -1 1664 -1 1665 -1 1666 -1 1667 -1 1668 -1 1669 -1 1670 -1 1671 -1 1672 -1 1673 -1 1674 -1 1675 -1 1676 -1 1677 -1 1678 -1 1679 -1 1680 -1 1681 -1 1682 -1 1683 -1 1684 -1 1685 -1 1686 -1 1687 -1 1688 -1 1689 -1 1690 -1 1691 -1 1692 -1 1693 -1 1694 -1 1695 -1 1696 -1 1697 -1 1698 -1 1699 -1 1700 -1 1701 -1 1702 -1 1703 -1 1704 -1 1705 -1 1706 -1 1707 -1 1708 -1 1709 -1 1710 -1 1711 -1 1712 -1 1713 -1 1714 -1 1715 -1 1716 -1 1717 -1 1718 -1 1719 -1 1720 -1 1721 -1 1722 -1 1723 -1 1724 -1 1725 -1 1726 -1 1727 -1 1728 -1 1729 -1 1730 -1 1731 -1 1732 -1 1733 -1 1734 -1 1735 -1 1736 -1 1737 -1 1738 -1 1739 -1 1740 -1 1741 -1 1742 -1 1743 -1 1744 -1 1745 -1 1746 -1 1747 -1 1748 -1 1749 -1 1750 -1 1751 -1 1752 -1 1753 -1 1754 -1 1755 -1 1756 -1 1757 -1 1758 -1 1759 -1 1760 -1 1761 -1 1762 -1 1763 -1 1764 -1 1765 -1 1766 -1 1767 -1 1768 -1 1769 -1 1770 -1 1771 -1 1772 -1 1773 -1 1774 -1 1775 -1 1776 -1 1777 -1 1778 -1 1779 -1 1780 -1 1781 -1 1782 -1 1783 -1 1784 -1 1785 -1 1786 -1 1787 -1 1788 -1 1789 -1 1790 -1 1791 -1 1792 -1 1793 -1 1794 -1 1795 -1 1796 -1 1797 -1 1798 -1 1799 -1 1800 -1 1801 -1 1802 -1 1803 -1 1804 -1 1805 -1 1806 -1 1807 -1 1808 -1 1809 -1 1810 -1 1811 -1 1812 -1 1813 -1 1814 -1 1815 -1 1816 -1 1817 -1 1818 -1 1819 -1 1820 -1 1821 -1 1822 -1 1823 -1 1824 -1 1825 -1 1826 -1 1827 -1 1828 -1 1829 -1 1830 -1 1831 -1 1832 -1 1833 -1 1834 -1 1835 -1 1836 -1 1837 -1 1838 -1 1839 -1 1840 -1 1841 -1 1842 -1 1843 -1 1844 -1 1845 -1 1846 -1 1847 -1 1848 -1 1849 -1 1850 -1 1851 -1 1852 -1 1853 -1 1854 -1 1855 -1 1856 -1 1857 -1 1858 -1 1859 -1 1860 -1 1861 -1 1862 -1 1863 -1 1864 -1 1865 -1 1866 -1 1867 -1 1868 -1 1869 -1 1870 -1 1871 -1 1872 -1 1873 -1 1874 -1 1875 -1 1876 -1 1877 -1 1878 -1 1879 -1 1880 -1 1881 -1 1882 -1 1883 -1 1884 -1 1885 -1 1886 -1 1887 -1 1888 -1 1889 -1 1890 -1 1891 -1 1892 -1 1893 -1 1894 -1 1895 -1 1896 -1 1897 -1 1898 -1 1899 -1 1900 -1 1901 -1 1902 -1 1903 -1 1904 -1 1905 -1 1906 -1 1907 -1 1908 -1 1909 -1 1910 -1 1911 -1 1912 -1 1913 -1 1914 -1 1915 -1 1916 -1 1917 -1 1918 -1 1919 -1 1920 -1 1921 -1 1922 -1 1923 -1 1924 -1 1925 -1 1926 -1 1927 -1 1928 -1 1929 -1 1930 -1 1931 -1 1932 -1 1933 -1 1934 -1 1935 -1 1936 -1 1937 -1 1938 -1 1939 -1 1940 -1 1941 -1 1942 -1 1943 -1 1944 -1 1945 -1 1946 -1 1947 -1 1948 -1 1949 -1 1950 -1 1951 -1 1952 -1 1953 -1 1954 -1 1955 -1 1956 -1 1957 -1 1958 -1 1959 -1 1960 -1 1961 -1 1962 -1 1963 -1 1964 -1 1965 -1 1966 -1 1967 -1 1968 -1 1969 -1 1970 -1 1971 -1 1972 -1 1973 -1 1974 -1 1975 -1 1976 -1 1977 -1 1978 -1 1979 -1 1980 -1 1981 -1 1982 -1 1983 -1 1984 -1 1985 -1 1986 -1 1987 -1 1988 -1 1989 -1 1990 -1 1991 -1 1992 -1 1993 -1 1994 -1 1995 -1 1996 -1 1997 -1 1998 -1 1999 -1 2000 -1 2001 -1 2002 -1 2003 -1 2004 -1 2005 -1 2006 -1 2007 -1 2008 -1 2009 -1 2010 -1 2011 -1 2012 -1 2013 -1 2014 -1 2015 -1 2016 -1 2017 -1 2018 -1 2019 -1 2020 -1 2021 -1 2022 -1 2023 -1 2024 -1 2025 -1 2026 -1 2027 -1 2028 -1 2029 -1 2030 -1 2031 -1 2032 -1 2033 -1 2034 -1 2035 -1 2036 -1 2037 -1 2038 -1 2039 -1 2040 -1 2041 -1 2042 -1 2043 -1 2044 -1 2045 -1 2046 -1 2047 -1 2048 -1 2049 -1 2050 -1 2051 -1 2052 -1 2053 -1 2054 -1 2055 -1 2056 -1 2057 -1 2058 -1 2059 -1 2060 -1 2061 -1 2062 -1 2063 -1 2064 -1 2065 -1 2066 -1 2067 -1 2068 -1 2069 -1 2070 -1 2071 -1 2072 -1 2073 -1 2074 -1 2075 -1 2076 -1 2077 -1 2078 -1 2079 -1 2080 -1 2081 -1 2082 -1 2083 -1 2084 -1 2085 -1 2086 -1 2087 -1 2088 -1 2089 -1 2090 -1 2091 -1 2092 -1 2093 -1 2094 -1 2095 -1 2096 -1 2097 -1 2098 -1 2099 -1 2100 -1 2101 -1 2102 -1 2103 -1 2104 -1 2105 -1 2106 -1 2107 -1 2108 -1 2109 -1 2110 -1 2111 -1 2112 -1 2113 -1 2114 -1 2115 -1 2116 -1 2117 -1 2118 -1 2119 -1 2120 -1 2121 -1 2122 -1 2123 -1 2124 -1 2125 -1 2126 -1 2127 -1 2128 -1 2129 -1 2130 -1 2131 -1 2132 -1 2133 -1 2134 -1 2135 -1 2136 -1 2137 -1 2138 -1 2139 -1 2140 -1 2141 -1 2142 -1 2143 -1 2144 -1 2145 -1 2146 -1 2147 -1 2148 -1 2149 -1 2150 -1 2151 -1 2152 -1 2153 -1 2154 -1 2155 -1 2156 -1 2157 -1 2158 -1 2159 -1 2160 -1 2161 -1 2162 -1 2163 -1 2164 -1 2165 -1 2166 -1 2167 -1 2168 -1 2169 -1 2170 -1 2171 -1 2172 -1 2173 -1 2174 -1 2175 -1 2176 -1 2177 -1 2178 -1 2179 -1 2180 -1 2181 -1 2182 -1 2183 -1 2184 -1 2185 -1 2186 -1 2187 -1 2188 -1 2189 -1 2190 -1 2191 -1 2192 -1 2193 -1 2194 -1 2195 -1 2196 -1 2197 -1 2198 -1 2199 -1 2200 -1 2201 -1 2202 -1 2203 -1 2204 -1 2205 -1 2206 -1 2207 -1 2208 -1 2209 -1 2210 -1 2211 -1 2212 -1 2213 -1 2214 -1 2215 -1 2216 -1 2217 -1 2218 -1 2219 -1 2220 -1 2221 -1 2222 -1 2223 -1 2224 -1 2225 -1 2226 -1 2227 -1 2228 -1 2229 -1 2230 -1 2231 -1 2232 -1 2233 -1 2234 -1 2235 -1 2236 -1 2237 -1 2238 -1 2239 -1 2240 -1 2241 -1 2242 -1 2243 -1 2244 -1 2245 -1 2246 -1 2247 -1 2248 -1 2249 -1 2250 -1 2251 -1 2252 -1 2253 -1 2254 -1 2255 -1 2256 -1 2257 -1 2258 -1 2259 -1 2260 -1 2261 -1 2262 -1 2263 -1 2264 -1 2265 -1 2266 -1 2267 -1 2268 -1 2269 -1 2270 -1 2271 -1 2272 -1 2273 -1 2274 -1 2275 -1 2276 -1 2277 -1 2278 -1 2279 -1 2280 -1 2281 -1 2282 -1 2283 -1 2284 -1 2285 -1 2286 -1 2287 -1 2288 -1 2289 -1 2290 -1 2291 -1 2292 -1 2293 -1 2294 -1 2295 -1 2296 -1 2297 -1 2298 -1 2299 -1 2300 -1 2301 -1 2302 -1 2303 -1 2304 -1 2305 -1 2306 -1 2307 -1 2308 -1 2309 -1 2310 -1 2311 -1 2312 -1 2313 -1 2314 -1 2315 -1 2316 -1 2317 -1 2318 -1 2319 -1 2320 -1 2321 -1 2322 -1 2323 -1 2324 -1 2325 -1 2326 -1 2327 -1 2328 -1 2329 -1 2330 -1 2331 -1 2332 -1 2333 -1 2334 -1 2335 -1 2336 -1 2337 -1 2338 -1 2339 -1 2340 -1 2341 -1 2342 -1 2343 -1 2344 -1 2345 -1 2346 -1 2347 -1 2348 -1 2349 -1 2350 -1 2351 -1 2352 -1 2353 -1 2354 -1 2355 -1 2356 -1 2357 -1 2358 -1 2359 -1 2360 -1 2361 -1 2362 -1 2363 -1 2364 -1 2365 -1 2366 -1 2367 -1 2368 -1 2369 -1 2370 -1 2371 -1 2372 -1 2373 -1 2374 -1 2375 -1 2376 -1 2377 -1 2378 -1 2379 -1 2380 -1 2381 -1 2382 -1 2383 -1 2384 -1 2385 -1 2386 -1 2387 -1 2388 -1 2389 -1 2390 -1 2391 -1 2392 -1 2393 -1 2394 -1 2395 -1 2396 -1 2397 -1 2398 -1 2399 -1 2400 -1 2401 -1 2402 -1 2403 -1 2404 -1 2405 -1 2406 -1 2407 -1 2408 -1 2409 -1 2410 -1 2411 -1 2412 -1 2413 -1 2414 -1 2415 -1 2416 -1 2417 -1 2418 -1 2419 -1 2420 -1 2421 -1 2422 -1 2423 -1 2424 -1 2425 -1 2426 -1 2427 -1 2428 -1 2429 -1 2430 -1 2431 -1 2432 -1 2433 -1 2434 -1 2435 -1 2436 -1 2437 -1 2438 -1 2439 -1 2440 -1 2441 -1 2442 -1 2443 -1 2444 -1 2445 -1 2446 -1 2447 -1 2448 -1 2449 -1 2450 -1 2451 -1 2452 -1 2453 -1 2454 -1 2455 -1 2456 -1 2457 -1 2458 -1 2459 -1 2460 -1 2461 -1 2462 -1 2463 -1 2464 -1 2465 -1 2466 -1 2467 -1 2468 -1 2469 -1 2470 -1 2471 -1 2472 -1 2473 -1 2474 -1 2475 -1 2476 -1 2477 -1 2478 -1 2479 -1 2480 -1 2481 -1 2482 -1 2483 -1 2484 -1 2485 -1 2486 -1 2487 -1 2488 -1 2489 -1 2490 -1 2491 -1 2492 -1 2493 -1 2494 -1 2495 -1 2496 -1 2497 -1 2498 -1 2499 -1 2500 -1 2501 -1 2502 -1 2503 -1 2504 -1 2505 -1 2506 -1 2507 -1 2508 -1 2509 -1 2510 -1 2511 -1 2512 -1 2513 -1 2514 -1 2515 -1 2516 -1 2517 -1 2518 -1 2519 -1 2520 -1 2521 -1 2522 -1 2523 -1 2524 -1 2525 -1 2526 -1 2527 -1 2528 -1 2529 -1 2530 -1 2531 -1 2532 -1 2533 -1 2534 -1 2535 -1 2536 -1 2537 -1 2538 -1 2539 -1 2540 -1 2541 -1 2542 -1 2543 -1 2544 -1 2545 -1 2546 -1 2547 -1 2548 -1 2549 -1 2550 -1 2551 -1 2552 -1 2553 -1 2554 -1 2555 -1 2556 -1 2557 -1 2558 -1 2559 -1 2560 -1 2561 -1 2562 -1 2563 -1 2564 -1 2565 -1 2566 -1 2567 -1 2568 -1 2569 -1 2570 -1 2571 -1 2572 -1 2573 -1 2574 -1 2575 -1 2576 -1 2577 -1 2578 -1 2579 -1 2580 -1 2581 -1 2582 -1 2583 -1 2584 -1 2585 -1 2586 -1 2587 -1 2588 -1 2589 -1 2590 -1 2591 -1 2592 -1 2593 -1 2594 -1 2595 -1 2596 -1 2597 -1 2598 -1 2599 -1 2600 -1 2601 -1 2602 -1 2603 -1 2604 -1 2605 -1 2606 -1 2607 -1 2608 -1 2609 -1 2610 -1 2611 -1 2612 -1 2613 -1 2614 -1 2615 -1 2616 -1 2617 -1 2618 -1 2619 -1 2620 -1 2621 -1 2622 -1 2623 -1 2624 -1 2625 -1 2626 -1 2627 -1 2628 -1 2629 -1 2630 -1 2631 -1 2632 -1 2633 -1 2634 -1 2635 -1 2636 -1 2637 -1 2638 -1 2639 -1 2640 -1 2641 -1 2642 -1 2643 -1 2644 -1 2645 -1 2646 -1 2647 -1 2648 -1 2649 -1 2650 -1 2651 -1 2652 -1 2653 -1 2654 -1 2655 -1 2656 -1 2657 -1 2658 -1 2659 -1 2660 -1 2661 -1 2662 -1 2663 -1 2664 -1 2665 -1 2666 -1 2667 -1 2668 -1 2669 -1 2670 -1 2671 -1 2672 -1 2673 -1 2674 -1 2675 -1 2676 -1 2677 -1 2678 -1 2679 -1 2680 -1 2681 -1 2682 -1 2683 -1 2684 -1 2685 -1 2686 -1 2687 -1 2688 -1 2689 -1 2690 -1 2691 -1 2692 -1 2693 -1 2694 -1 2695 -1 2696 -1 2697 -1 2698 -1 2699 -1 2700 -1 2701 -1 2702 -1 2703 -1 2704 -1 2705 -1 2706 -1 2707 -1 2708 -1 2709 -1 2710 -1 2711 -1 2712 -1 2713 -1 2714 -1 2715 -1 2716 -1 2717 -1 2718 -1 2719 -1 2720 -1 2721 -1 2722 -1 2723 -1 2724 -1 2725 -1 2726 -1 2727 -1 2728 -1 2729 -1 2730 -1 2731 -1 2732 -1 2733 -1 2734 -1 2735 -1 2736 -1 2737 -1 2738 -1 2739 -1 2740 -1 2741 -1 2742 -1 2743 -1 2744 -1 2745 -1 2746 -1 2747 -1 2748 -1 2749 -1 2750 -1 2751 -1 2752 -1 2753 -1 2754 -1 2755 -1 2756 -1 2757 -1 2758 -1 2759 -1 2760 -1 2761 -1 2762 -1 2763 -1 2764 -1 2765 -1 2766 -1 2767 -1 2768 -1 2769 -1 2770 -1 2771 -1 2772 -1 2773 -1 2774 -1 2775 -1 2776 -1 2777 -1 2778 -1 2779 -1 2780 -1 2781 -1 2782 -1 2783 -1 2784 -1 2785 -1 2786 -1 2787 -1 2788 -1 2789 -1 2790 -1 2791 -1 2792 -1 2793 -1 2794 -1 2795 -1 2796 -1 2797 -1 2798 -1 2799 -1 2800 -1 2801 -1 2802 -1 2803 -1 2804 -1 2805 -1 2806 -1 2807 -1 2808 -1 2809 -1 2810 -1 2811 -1 2812 -1 2813 -1 2814 -1 2815 -1 2816 -1 2817 -1 2818 -1 2819 -1 2820 -1 2821 -1 2822 -1 2823 -1 2824 -1 2825 -1 2826 -1 2827 -1 2828 -1 2829 -1 2830 -1 2831 -1 2832 -1 2833 -1 2834 -1 2835 -1 2836 -1 2837 -1 2838 -1 2839 -1 2840 -1 2841 -1 2842 -1 2843 -1 2844 -1 2845 -1 2846 -1 2847 -1 2848 -1 2849 -1 2850 -1 2851 -1 2852 -1 2853 -1 2854 -1 2855 -1 2856 -1 2857 -1 2858 -1 2859 -1 2860 -1 2861 -1 2862 -1 2863 -1 2864 -1 2865 -1 2866 -1 2867 -1 2868 -1 2869 -1 2870 -1 2871 -1 2872 -1 2873 -1 2874 -1 2875 -1 2876 -1 2877 -1 2878 -1 2879 -1 2880 -1 2881 -1 2882 -1 2883 -1 2884 -1 2885 -1 2886 -1 2887 -1 2888 -1 2889 -1 2890 -1 2891 -1 2892 -1 2893 -1 2894 -1 2895 -1 2896 -1 2897 -1 2898 -1 2899 -1 2900 -1 2901 -1 2902 -1 2903 -1 2904 -1 2905 -1 2906 -1 2907 -1 2908 -1 2909 -1 2910 -1 2911 -1 2912 -1 2913 -1 2914 -1 2915 -1 2916 -1 2917 -1 2918 -1 2919 -1 2920 -1 2921 -1 2922 -1 2923 -1 2924 -1 2925 -1 2926 -1 2927 -1 2928 -1 2929 -1 2930 -1 2931 -1 2932 -1 2933 -1 2934 -1 2935 -1 2936 -1 2937 -1 2938 -1 2939 -1 2940 -1 2941 -1 2942 -1 2943 -1 2944 -1 2945 -1 2946 -1 2947 -1 2948 -1 2949 -1 2950 -1 2951 -1 2952 -1 2953 -1 2954 -1 2955 -1 2956 -1 2957 -1 2958 -1 2959 -1 2960 -1 2961 -1 2962 -1 2963 -1 2964 -1 2965 -1 2966 -1 2967 -1 2968 -1 2969 -1 2970 -1 2971 -1 2972 -1 2973 -1 2974 -1 2975 -1 2976 -1 2977 -1 2978 -1 2979 -1 2980 -1 2981 -1 2982 -1 2983 -1 2984 -1 2985 -1 2986 -1 2987 -1 2988 -1 2989 -1 2990 -1 2991 -1 2992 -1 2993 -1 2994 -1 2995 -1 2996 -1 2997 -1 2998 -1 2999 -1 3000 -1 3001 -1 3002 -1 3003 -1 3004 -1 3005 -1 3006 -1 3007 -1 3008 -1 3009 -1 3010 -1 3011 -1 3012 -1 3013 -1 3014 -1 3015 -1 3016 -1 3017 -1 3018 -1 3019 -1 3020 -1 3021 -1 3022 -1 3023 -1 3024 -1 3025 -1 3026 -1 3027 -1 3028 -1 3029 -1 3030 -1 3031 -1 3032 -1 3033 -1 3034 -1 3035 -1 3036 -1 3037 -1 3038 -1 3039 -1 3040 -1 3041 -1 3042 -1 3043 -1 3044 -1 3045 -1 3046 -1 3047 -1 3048 -1 3049 -1 3050 -1 3051 -1 3052 -1 3053 -1 3054 -1 3055 -1 3056 -1 3057 -1 3058 -1 3059 -1 3060 -1 3061 -1 3062 -1 3063 -1 3064 -1 3065 -1 3066 -1 3067 -1 3068 -1 3069 -1 3070 -1 3071 -1 3072 -1 3073 -1 3074 -1 3075 -1 3076 -1 3077 -1 3078 -1 3079 -1 3080 -1 3081 -1 3082 -1 3083 -1 3084 -1 3085 -1 3086 -1 3087 -1 3088 -1 3089 -1 3090 -1 3091 -1 3092 -1 3093 -1 3094 -1 3095 -1 3096 -1 3097 -1 3098 -1 3099 -1 3100 -1 3101 -1 3102 -1 3103 -1 3104 -1 3105 -1 3106 -1 3107 -1 3108 -1 3109 -1 3110 -1 3111 -1 3112 -1 3113 -1 3114 -1 3115 -1 3116 -1 3117 -1 3118 -1 3119 -1 3120 -1 3121 -1 3122 -1 3123 -1 3124 -1 3125 -1 3126 -1 3127 -1 3128 -1 3129 -1 3130 -1 3131 -1 3132 -1 3133 -1 3134 -1 3135 -1 3136 -1 3137 -1 3138 -1 3139 -1 3140 -1 3141 -1 3142 -1 3143 -1 3144 -1 3145 -1 3146 -1 3147 -1 3148 -1 3149 -1 3150 -1 3151 -1 3152 -1 3153 -1 3154 -1 3155 -1 3156 -1 3157 -1 3158 -1 3159 -1 3160 -1 3161 -1 3162 -1 3163 -1 3164 -1 3165 -1 3166 -1 3167 -1 3168 -1 3169 -1 3170 -1 3171 -1 3172 -1 3173 -1 3174 -1 3175 -1 3176 -1 3177 -1 3178 -1 3179 -1 3180 -1 3181 -1 3182 -1 3183 -1 3184 -1 3185 -1 3186 -1 3187 -1 3188 -1 3189 -1 3190 -1 3191 -1 3192 -1 3193 -1 3194 -1 3195 -1 3196 -1 3197 -1 3198 -1 3199 -1 3200 -1 3201 -1 3202 -1 3203 -1 3204 -1 3205 -1 3206 -1 3207 -1 3208 -1 3209 -1 3210 -1 3211 -1 3212 -1 3213 -1 3214 -1 3215 -1 3216 -1 3217 -1 3218 -1 3219 -1 3220 -1 3221 -1 3222 -1 3223 -1 3224 -1 3225 -1 3226 -1 3227 -1 3228 -1 3229 -1 3230 -1 3231 -1 3232 -1 3233 -1 3234 -1 3235 -1 3236 -1 3237 -1 3238 -1 3239 -1 3240 -1 3241 -1 3242 -1 3243 -1 3244 -1 3245 -1 3246 -1 3247 -1 3248 -1 3249 -1 3250 -1 3251 -1 3252 -1 3253 -1 3254 -1 3255 -1 3256 -1 3257 -1 3258 -1 3259 -1 3260 -1 3261 -1 3262 -1 3263 -1 3264 -1 3265 -1 3266 -1 3267 -1 3268 -1 3269 -1 3270 -1 3271 -1 3272 -1 3273 -1 3274 -1 3275 -1 3276 -1 3277 -1 3278 -1 3279 -1 3280 -1 3281 -1 3282 -1 3283 -1 3284 -1 3285 -1 3286 -1 3287 -1 3288 -1 3289 -1 3290 -1 3291 -1 3292 -1 3293 -1 3294 -1 3295 -1 3296 -1 3297 -1 3298 -1 3299 -1 3300 -1 3301 -1 3302 -1 3303 -1 3304 -1 3305 -1 3306 -1 3307 -1 3308 -1 3309 -1 3310 -1 3311 -1 3312 -1 3313 -1 3314 -1 3315 -1 3316 -1 3317 -1 3318 -1 3319 -1 3320 -1 3321 -1 3322 -1 3323 -1 3324 -1 3325 -1 3326 -1 3327 -1 3328 -1 3329 -1 3330 -1 3331 -1 3332 -1 3333 -1 3334 -1 3335 -1 3336 -1 3337 -1 3338 -1 3339 -1 3340 -1 3341 -1 3342 -1 3343 -1 3344 -1 3345 -1 3346 -1 3347 -1 3348 -1 3349 -1 3350 -1 3351 -1 3352 -1 3353 -1 3354 -1 3355 -1 3356 -1 3357 -1 3358 -1 3359 -1 3360 -1 3361 -1 3362 -1 3363 -1 3364 -1 3365 -1 3366 -1 3367 -1 3368 -1 3369 -1 3370 -1 3371 -1 3372 -1 3373 -1 3374 -1 3375 -1 3376 -1 3377 -1 3378 -1 3379 -1 3380 -1 3381 -1 3382 -1 3383 -1 3384 -1 3385 -1 3386 -1 3387 -1 3388 -1 3389 -1 3390 -1 3391 -1 3392 -1 3393 -1 3394 -1 3395 -1 3396 -1 3397 -1 3398 -1 3399 -1 3400 -1 3401 -1 3402 -1 3403 -1 3404 -1 3405 -1 3406 -1 3407 -1 3408 -1 3409 -1 3410 -1 3411 -1 3412 -1 3413 -1 3414 -1 3415 -1 3416 -1 3417 -1 3418 -1 3419 -1 3420 -1 3421 -1 3422 -1 3423 -1 3424 -1 3425 -1 3426 -1 3427 -1 3428 -1 3429 -1 3430 -1 3431 -1 3432 -1 3433 -1 3434 -1 3435 -1 3436 -1 3437 -1 3438 -1 3439 -1 3440 -1 3441 -1 3442 -1 3443 -1 3444 -1 3445 -1 3446 -1 3447 -1 3448 -1 3449 -1 3450 -1 3451 -1 3452 -1 3453 -1 3454 -1 3455 -1 3456 -1 3457 -1 3458 -1 3459 -1 3460 -1 3461 -1 3462 -1 3463 -1 3464 -1 3465 -1 3466 -1 3467 -1 3468 -1 3469 -1 3470 -1 3471 -1 3472 -1 3473 -1 3474 -1 3475 -1 3476 -1 3477 -1 3478 -1 3479 -1 3480 -1 3481 -1 3482 -1 3483 -1 3484 -1 3485 -1 3486 -1 3487 -1 3488 -1 3489 -1 3490 -1 3491 -1 3492 -1 3493 -1 3494 -1 3495 -1 3496 -1 3497 -1 3498 -1 3499 -1 3500 -1 3501 -1 3502 -1 3503 -1 3504 -1 3505 -1 3506 -1 3507 -1 3508 -1 3509 -1 3510 -1 3511 -1 3512 -1 3513 -1 3514 -1 3515 -1 3516 -1 3517 -1 3518 -1 3519 -1 3520 -1 3521 -1 3522 -1 3523 -1 3524 -1 3525 -1 3526 -1 3527 -1 3528 -1 3529 -1 3530 -1 3531 -1 3532 -1 3533 -1 3534 -1 3535 -1 3536 -1 3537 -1 3538 -1 3539 -1 3540 -1 3541 -1 3542 -1 3543 -1 3544 -1 3545 -1 3546 -1 3547 -1 3548 -1 3549 -1 3550 -1 3551 -1 3552 -1 3553 -1 3554 -1 3555 -1 3556 -1 3557 -1 3558 -1 3559 -1 3560 -1 3561 -1 3562 -1 3563 -1 3564 -1 3565 -1 3566 -1 3567 -1 3568 -1 3569 -1 3570 -1 3571 -1 3572 -1 3573 -1 3574 -1 3575 -1 3576 -1 3577 -1 3578 -1 3579 -1 3580 -1 3581 -1 3582 -1 3583 -1 3584 -1 3585 -1 3586 -1 3587 -1 3588 -1 3589 -1 3590 -1 3591 -1 3592 -1 3593 -1 3594 -1 3595 -1 3596 -1 3597 -1 3598 -1 3599 -1 3600 -1 3601 -1 3602 -1 3603 -1 3604 -1 3605 -1 3606 -1 3607 -1 3608 -1 3609 -1 3610 -1 3611 -1 3612 -1 3613 -1 3614 -1 3615 -1 3616 -1 3617 -1 3618 -1 3619 -1 3620 -1 3621 -1 3622 -1 3623 -1 3624 -1 3625 -1 3626 -1 3627 -1 3628 -1 3629 -1 3630 -1 3631 -1 3632 -1 3633 -1 3634 -1 3635 -1 3636 -1 3637 -1 3638 -1 3639 -1 3640 -1 3641 -1 3642 -1 3643 -1 3644 -1 3645 -1 3646 -1 3647 -1 3648 -1 3649 -1 3650 -1 3651 -1 3652 -1 3653 -1 3654 -1 3655 -1 3656 -1 3657 -1 3658 -1 3659 -1 3660 -1 3661 -1 3662 -1 3663 -1 3664 -1 3665 -1 3666 -1 3667 -1 3668 -1 3669 -1 3670 -1 3671 -1 3672 -1 3673 -1 3674 -1 3675 -1 3676 -1 3677 -1 3678 -1 3679 -1 3680 -1 3681 -1 3682 -1 3683 -1 3684 -1 3685 -1 3686 -1 3687 -1 3688 -1 3689 -1 3690 -1 3691 -1 3692 -1 3693 -1 3694 -1 3695 -1 3696 -1 3697 -1 3698 -1 3699 -1 3700 -1 3701 -1 3702 -1 3703 -1 3704 -1 3705 -1 3706 -1 3707 -1 3708 -1 3709 -1 3710 -1 3711 -1 3712 -1 3713 -1 3714 -1 3715 -1 3716 -1 3717 -1 3718 -1 3719 -1 3720 -1 3721 -1 3722 -1 3723 -1 3724 -1 3725 -1 3726 -1 3727 -1 3728 -1 3729 -1 3730 -1 3731 -1 3732 -1 3733 -1 3734 -1 3735 -1 3736 -1 3737 -1 3738 -1 3739 -1 3740 -1 3741 -1 3742 -1 3743 -1 3744 -1 3745 -1 3746 -1 3747 -1 3748 -1 3749 -1 3750 -1 3751 -1 3752 -1 3753 -1 3754 -1 3755 -1 3756 -1 3757 -1 3758 -1 3759 -1 3760 -1 3761 -1 3762 -1 3763 -1 3764 -1 3765 -1 3766 -1 3767 -1 3768 -1 3769 -1 3770 -1 3771 -1 3772 -1 3773 -1 3774 -1 3775 -1 3776 -1 3777 -1 3778 -1 3779 -1 3780 -1 3781 -1 3782 -1 3783 -1 3784 -1 3785 -1 3786 -1 3787 -1 3788 -1 3789 -1 3790 -1 3791 -1 3792 -1 3793 -1 3794 -1 3795 -1 3796 -1 3797 -1 3798 -1 3799 -1 3800 -1 3801 -1 3802 -1 3803 -1 3804 -1 3805 -1 3806 -1 3807 -1 3808 -1 3809 -1 3810 -1 3811 -1 3812 -1 3813 -1 3814 -1 3815 -1 3816 -1 3817 -1 3818 -1 3819 -1 3820 -1 3821 -1 3822 -1 3823 -1 3824 -1 3825 -1 3826 -1 3827 -1 3828 -1 3829 -1 3830 -1 3831 -1 3832 -1 3833 -1 3834 -1 3835 -1 3836 -1 3837 -1 3838 -1 3839 -1 3840 -1 3841 -1 3842 -1 3843 -1 3844 -1 3845 -1 3846 -1 3847 -1 3848 -1 3849 -1 3850 -1 3851 -1 3852 -1 3853 -1 3854 -1 3855 -1 3856 -1 3857 -1 3858 -1 3859 -1 3860 -1 3861 -1 3862 -1 3863 -1 3864 -1 3865 -1 3866 -1 3867 -1 3868 -1 3869 -1 3870 -1 3871 -1 3872 -1 3873 -1 3874 -1 3875 -1 3876 -1 3877 -1 3878 -1 3879 -1 3880 -1 3881 -1 3882 -1 3883 -1 3884 -1 3885 -1 3886 -1 3887 -1 3888 -1 3889 -1 3890 -1 3891 -1 3892 -1 3893 -1 3894 -1 3895 -1 3896 -1 3897 -1 3898 -1 3899 -1 3900 -1 3901 -1 3902 -1 3903 -1 3904 -1 3905 -1 3906 -1 3907 -1 3908 -1 3909 -1 3910 -1 3911 -1 3912 -1 3913 -1 3914 -1 3915 -1 3916 -1 3917 -1 3918 -1 3919 -1 3920 -1 3921 -1 3922 -1 3923 -1 3924 -1 3925 -1 3926 -1 3927 -1 3928 -1 3929 -1 3930 -1 3931 -1 3932 -1 3933 -1 3934 -1 3935 -1 3936 -1 3937 -1 3938 -1 3939 -1 3940 -1 3941 -1 3942 -1 3943 -1 3944 -1 3945 -1 3946 -1 3947 -1 3948 -1 3949 -1 3950 -1 3951 -1 3952 -1 3953 -1 3954 -1 3955 -1 3956 -1 3957 -1 3958 -1 3959 -1 3960 -1 3961 -1 3962 -1 3963 -1 3964 -1 3965 -1 3966 -1 3967 -1 3968 -1 3969 -1 3970 -1 3971 -1 3972 -1 3973 -1 3974 -1 3975 -1 3976 -1 3977 -1 3978 -1 3979 -1 3980 -1 3981 -1 3982 -1 3983 -1 3984 -1 3985 -1 3986 -1 3987 -1 3988 -1 3989 -1 3990 -1 3991 -1 3992 -1 3993 -1 3994 -1 3995 -1 3996 -1 3997 -1 3998 -1 3999 -1 4000 -1 4001 -1 4002 -1 4003 -1 4004 -1 4005 -1 4006 -1 4007 -1 4008 -1 4009 -1 4010 -1 4011 -1 4012 -1 4013 -1 4014 -1 4015 -1 4016 -1 4017 -1 4018 -1 4019 -1 4020 -1 4021 -1 4022 -1 4023 -1 4024 -1 4025 -1 4026 -1 4027 -1 4028 -1 4029 -1 4030 -1 4031 -1 4032 -1 4033 -1 4034 -1 4035 -1 4036 -1 4037 -1 4038 -1 4039 -1 4040 -1 4041 -1 4042 -1 4043 -1 4044 -1 4045 -1 4046 -1 4047 -1 4048 -1 4049 -1 4050 -1 4051 -1 4052 -1 4053 -1 4054 -1 4055 -1 4056 -1 4057 -1 4058 -1 4059 -1 4060 -1 4061 -1 4062 -1 4063 -1 4064 -1 4065 -1 4066 -1 4067 -1 4068 -1 4069 -1 4070 -1 4071 -1 4072 -1 4073 -1 4074 -1 4075 -1 4076 -1 4077 -1 4078 -1 4079 -1 4080 -1 4081 -1 4082 -1 4083 -1 4084 -1 4085 -1 4086 -1 4087 -1 4088 -1 4089 -1 4090 -1 4091 -1 4092 -1 4093 -1 4094 -1 4095 -1 4096 -1 4097 -1 4098 -1 4099 -1 4100 -1 4101 -1 4102 -1 4103 -1 4104 -1 4105 -1 4106 -1 4107 -1 4108 -1 4109 -1 4110 -1 4111 -1 4112 -1 4113 -1 4114 -1 4115 -1 4116 -1 4117 -1 4118 -1 4119 -1 4120 -1 4121 -1 4122 -1 4123 -1 4124 -1 4125 -1 4126 -1 4127 -1 4128 -1 4129 -1 4130 -1 4131 -1 4132 -1 4133 -1 4134 -1 4135 -1 4136 -1 4137 -1 4138 -1 4139 -1 4140 -1 4141 -1 4142 -1 4143 -1 4144 -1 4145 -1 4146 -1 4147 -1 4148 -1 4149 -1 4150 -1 4151 -1 4152 -1 4153 -1 4154 -1 4155 -1 4156 -1 4157 -1 4158 -1 4159 -1 4160 -1 4161 -1 4162 -1 4163 -1 4164 -1 4165 -1 4166 -1 4167 -1 4168 -1 4169 -1 4170 -1 4171 -1 4172 -1 4173 -1 4174 -1 4175 -1 4176 -1 4177 -1 4178 -1 4179 -1 4180 -1 4181 -1 4182 -1 4183 -1 4184 -1 4185 -1 4186 -1 4187 -1 4188 -1 4189 -1 4190 -1 4191 -1 4192 -1 4193 -1 4194 -1 4195 -1 4196 -1 4197 -1 4198 -1 4199 -1 4200 -1 4201 -1 4202 -1 4203 -1 4204 -1 4205 -1 4206 -1 4207 -1 4208 -1 4209 -1 4210 -1 4211 -1 4212 -1 4213 -1 4214 -1 4215 -1 4216 -1 4217 -1 4218 -1 4219 -1 4220 -1 4221 -1 4222 -1 4223 -1 4224 -1 4225 -1 4226 -1 4227 -1 4228 -1 4229 -1 4230 -1 4231 -1 4232 -1 4233 -1 4234 -1 4235 -1 4236 -1 4237 -1 4238 -1 4239 -1 4240 -1 4241 -1 4242 -1 4243 -1 4244 -1 4245 -1 4246 -1 4247 -1 4248 -1 4249 -1 4250 -1 4251 -1 4252 -1 4253 -1 4254 -1 4255 -1 4256 -1 4257 -1 4258 -1 4259 -1 4260 -1 4261 -1 4262 -1 4263 -1 4264 -1 4265 -1 4266 -1 4267 -1 4268 -1 4269 -1 4270 -1 4271 -1 4272 -1 4273 -1 4274 -1 4275 -1 4276 -1 4277 -1 4278 -1 4279 -1 4280 -1 4281 -1 4282 -1 4283 -1 4284 -1 4285 -1 4286 -1 4287 -1 4288 -1 4289 -1 4290 -1 4291 -1 4292 -1 4293 -1 4294 -1 4295 -1 4296 -1 4297 -1 4298 -1 4299 -1 4300 -1 4301 -1 4302 -1 4303 -1 4304 -1 4305 -1 4306 -1 4307 -1 4308 -1 4309 -1 4310 -1 4311 -1 4312 -1 4313 -1 4314 -1 4315 -1 4316 -1 4317 -1 4318 -1 4319 -1 4320 -1 4321 -1 4322 -1 4323 -1 4324 -1 4325 -1 4326 -1 4327 -1 4328 -1 4329 -1 4330 -1 4331 -1 4332 -1 4333 -1 4334 -1 4335 -1 4336 -1 4337 -1 4338 -1 4339 -1 4340 -1 4341 -1 4342 -1 4343 -1 4344 -1 4345 -1 4346 -1 4347 -1 4348 -1 4349 -1 4350 -1 4351 -1 4352 -1 4353 -1 4354 -1 4355 -1 4356 -1 4357 -1 4358 -1 4359 -1 4360 -1 4361 -1 4362 -1 4363 -1 4364 -1 4365 -1 4366 -1 4367 -1 4368 -1 4369 -1 4370 -1 4371 -1 4372 -1 4373 -1 4374 -1 4375 -1 4376 -1 4377 -1 4378 -1 4379 -1 4380 -1 4381 -1 4382 -1 4383 -1 4384 -1 4385 -1 4386 -1 4387 -1 4388 -1 4389 -1 4390 -1 4391 -1 4392 -1 4393 -1 4394 -1 4395 -1 4396 -1 4397 -1 4398 -1 4399 -1 4400 -1 4401 -1 4402 -1 4403 -1 4404 -1 4405 -1 4406 -1 4407 -1 4408 -1 4409 -1 4410 -1 4411 -1 4412 -1 4413 -1 4414 -1 4415 -1 4416 -1 4417 -1 4418 -1 4419 -1 4420 -1 4421 -1 4422 -1 4423 -1 4424 -1 4425 -1 4426 -1 4427 -1 4428 -1 4429 -1 4430 -1 4431 -1 4432 -1 4433 -1 4434 -1 4435 -1 4436 -1 4437 -1 4438 -1 4439 -1 4440 -1 4441 -1 4442 -1 4443 -1 4444 -1 4445 -1 4446 -1 4447 -1 4448 -1 4449 -1 4450 -1 4451 -1 4452 -1 4453 -1 4454 -1 4455 -1 4456 -1 4457 -1 4458 -1 4459 -1 4460 -1 4461 -1 4462 -1 4463 -1 4464 -1 4465 -1 4466 -1 4467 -1 4468 -1 4469 -1 4470 -1 4471 -1 4472 -1 4473 -1 4474 -1 4475 -1 4476 -1 4477 -1 4478 -1 4479 -1 4480 -1 4481 -1 4482 -1 4483 -1 4484 -1 4485 -1 4486 -1 4487 -1 4488 -1 4489 -1 4490 -1 4491 -1 4492 -1 4493 -1 4494 -1 4495 -1 4496 -1 4497 -1 4498 -1 4499 -1 4500 -1 4501 -1 4502 -1 4503 -1 4504 -1 4505 -1 4506 -1 4507 -1 4508 -1 4509 -1 4510 -1 4511 -1 4512 -1 4513 -1 4514 -1 4515 -1 4516 -1 4517 -1 4518 -1 4519 -1 4520 -1 4521 -1 4522 -1 4523 -1 4524 -1 4525 -1 4526 -1 4527 -1 4528 -1 4529 -1 4530 -1 4531 -1 4532 -1 4533 -1 4534 -1 4535 -1 4536 -1 4537 -1 4538 -1 4539 -1 4540 -1 4541 -1 4542 -1 4543 -1 4544 -1 4545 -1 4546 -1 4547 -1 4548 -1 4549 -1 4550 -1 4551 -1 4552 -1 4553 -1 4554 -1 4555 -1 4556 -1 4557 -1 4558 -1 4559 -1 4560 -1 4561 -1 4562 -1 4563 -1 4564 -1 4565 -1 4566 -1 4567 -1 4568 -1 4569 -1 4570 -1 4571 -1 4572 -1 4573 -1 4574 -1 4575 -1 4576 -1 4577 -1 4578 -1 4579 -1 4580 -1 4581 -1 4582 -1 4583 -1 4584 -1 4585 -1 4586 -1 4587 -1 4588 -1 4589 -1 4590 -1 4591 -1 4592 -1 4593 -1 4594 -1 4595 -1 4596 -1 4597 -1 4598 -1 4599 -1 4600 -1 4601 -1 4602 -1 4603 -1 4604 -1 4605 -1 4606 -1 4607 -1 4608 -1 4609 -1 4610 -1 4611 -1 4612 -1 4613 -1 4614 -1 4615 -1 4616 -1 4617 -1 4618 -1 4619 -1 4620 -1 4621 -1 4622 -1 4623 -1 4624 -1 4625 -1 4626 -1 4627 -1 4628 -1 4629 -1 4630 -1 4631 -1 4632 -1 4633 -1 4634 -1 4635 -1 4636 -1 4637 -1 4638 -1 4639 -1 4640 -1 4641 -1 4642 -1 4643 -1 4644 -1 4645 -1 4646 -1 4647 -1 4648 -1 4649 -1 4650 -1 4651 -1 4652 -1 4653 -1 4654 -1 4655 -1 4656 -1 4657 -1 4658 -1 4659 -1 4660 -1 4661 -1 4662 -1 4663 -1 4664 -1 4665 -1 4666 -1 4667 -1 4668 -1 4669 -1 4670 -1 4671 -1 4672 -1 4673 -1 4674 -1 4675 -1 4676 -1 4677 -1 4678 -1 4679 -1 4680 -1 4681 -1 4682 -1 4683 -1 4684 -1 4685 -1 4686 -1 4687 -1 4688 -1 4689 -1 4690 -1 4691 -1 4692 -1 4693 -1 4694 -1 4695 -1 4696 -1 4697 -1 4698 -1 4699 -1 4700 -1 4701 -1 4702 -1 4703 -1 4704 -1 4705 -1 4706 -1 4707 -1 4708 -1 4709 -1 4710 -1 4711 -1 4712 -1 4713 -1 4714 -1 4715 -1 4716 -1 4717 -1 4718 -1 4719 -1 4720 -1 4721 -1 4722 -1 4723 -1 4724 -1 4725 -1 4726 -1 4727 -1 4728 -1 4729 -1 4730 -1 4731 -1 4732 -1 4733 -1 4734 -1 4735 -1 4736 -1 4737 -1 4738 -1 4739 -1 4740 -1 4741 -1 4742 -1 4743 -1 4744 -1 4745 -1 4746 -1 4747 -1 4748 -1 4749 -1 4750 -1 4751 -1 4752 -1 4753 -1 4754 -1 4755 -1 4756 -1 4757 -1 4758 -1 4759 -1 4760 -1 4761 -1 4762 -1 4763 -1 4764 -1 4765 -1 4766 -1 4767 -1 4768 -1 4769 -1 4770 -1 4771 -1 4772 -1 4773 -1 4774 -1 4775 -1 4776 -1 4777 -1 4778 -1 4779 -1 4780 -1 4781 -1 4782 -1 4783 -1 4784 -1 4785 -1 4786 -1 4787 -1 4788 -1 4789 -1 4790 -1 4791 -1 4792 -1 4793 -1 4794 -1 4795 -1 4796 -1 4797 -1 4798 -1 4799 -1 4800 -1 4801 -1 4802 -1 4803 -1 4804 -1 4805 -1 4806 -1 4807 -1 4808 -1 4809 -1 4810 -1 4811 -1 4812 -1 4813 -1 4814 -1 4815 -1 4816 -1 4817 -1 4818 -1 4819 -1 4820 -1 4821 -1 4822 -1 4823 -1 4824 -1 4825 -1 4826 -1 4827 -1 4828 -1 4829 -1 4830 -1 4831 -1 4832 -1 4833 -1 4834 -1 4835 -1 4836 -1 4837 -1 4838 -1 4839 -1 4840 -1 4841 -1 4842 -1 4843 -1 4844 -1 4845 -1 4846 -1 4847 -1 4848 -1 4849 -1 4850 -1 4851 -1 4852 -1 4853 -1 4854 -1 4855 -1 4856 -1 4857 -1 4858 -1 4859 -1 4860 -1 4861 -1 4862 -1 4863 -1 4864 -1 4865 -1 4866 -1 4867 -1 4868 -1 4869 -1 4870 -1 4871 -1 4872 -1 4873 -1 4874 -1 4875 -1 4876 -1 4877 -1 4878 -1 4879 -1 4880 -1 4881 -1 4882 -1 4883 -1 4884 -1 4885 -1 4886 -1 4887 -1 4888 -1 4889 -1 4890 -1 4891 -1 4892 -1 4893 -1 4894 -1 4895 -1 4896 -1 4897 -1 4898 -1 4899 -1 4900 -1 4901 -1 4902 -1 4903 -1 4904 -1 4905 -1 4906 -1 4907 -1 4908 -1 4909 -1 4910 -1 4911 -1 4912 -1 4913 -1 4914 -1 4915 -1 4916 -1 4917 -1 4918 -1 4919 -1 4920 -1 4921 -1 4922 -1 4923 -1 4924 -1 4925 -1 4926 -1 4927 -1 4928 -1 4929 -1 4930 -1 4931 -1 4932 -1 4933 -1 4934 -1 4935 -1 4936 -1 4937 -1 4938 -1 4939 -1 4940 -1 4941 -1 4942 -1 4943 -1 4944 -1 4945 -1 4946 -1 4947 -1 4948 -1 4949 -1 4950 -1 4951 -1 4952 -1 4953 -1 4954 -1 4955 -1 4956 -1 4957 -1 4958 -1 4959 -1 4960 -1 4961 -1 4962 -1 4963 -1 4964 -1 4965 -1 4966 -1 4967 -1 4968 -1 4969 -1 4970 -1 4971 -1 4972 -1 4973 -1 4974 -1 4975 -1 4976 -1 4977 -1 4978 -1 4979 -1 4980 -1 4981 -1 4982 -1 4983 -1 4984 -1 4985 -1 4986 -1 4987 -1 4988 -1 4989 -1 4990 -1 4991 -1 4992 -1 4993 -1 4994 -1 4995 -1 4996 -1 4997 -1 4998 -1 4999 -1 5000 -1 5001 -1 5002 -1 5003 -1 5004 -1 5005 -1 5006 -1 5007 -1 5008 -1 5009 -1 5010 -1 5011 -1 5012 -1 5013 -1 5014 -1 5015 -1 5016 -1 5017 -1 5018 -1 5019 -1 5020 -1 5021 -1 5022 -1 5023 -1 5024 -1 5025 -1 5026 -1 5027 -1 5028 -1 5029 -1 5030 -1 5031 -1 5032 -1 5033 -1 5034 -1 5035 -1 5036 -1 5037 -1 5038 -1 5039 -1 5040 -1 5041 -1 5042 -1 5043 -1 5044 -1 5045 -1 5046 -1 5047 -1 5048 -1 5049 -1 5050 -1 5051 -1 5052 -1 5053 -1 5054 -1 5055 -1 5056 -1 5057 -1 5058 -1 5059 -1 5060 -1 5061 -1 5062 -1 5063 -1 5064 -1 5065 -1 5066 -1 5067 -1 5068 -1 5069 -1 5070 -1 5071 -1 5072 -1 5073 -1 5074 -1 5075 -1 5076 -1 5077 -1 5078 -1 5079 -1 5080 -1 5081 -1 5082 -1 5083 -1 5084 -1 5085 -1 5086 -1 5087 -1 5088 -1 5089 -1 5090 -1 5091 -1 5092 -1 5093 -1 5094 -1 5095 -1 5096 -1 5097 -1 5098 -1 5099 -1 5100 -1 5101 -1 5102 -1 5103 -1 5104 -1 5105 -1 5106 -1 5107 -1 5108 -1 5109 -1 5110 -1 5111 -1 5112 -1 5113 -1 5114 -1 5115 -1 5116 -1 5117 -1 5118 -1 5119 -1 5120 -1 5121 -1 5122 -1 5123 -1 5124 -1 5125 -1 5126 -1 5127 -1 5128 -1 5129 -1 5130 -1 5131 -1 5132 -1 5133 -1 5134 -1 5135 -1 5136 -1 5137 -1 5138 -1 5139 -1 5140 -1 5141 -1 5142 -1 5143 -1 5144 -1 5145 -1 5146 -1 5147 -1 5148 -1 5149 -1 5150 -1 5151 -1 5152 -1 5153 -1 5154 -1 5155 -1 5156 -1 5157 -1 5158 -1 5159 -1 5160 -1 5161 -1 5162 -1 5163 -1 5164 -1 5165 -1 5166 -1 5167 -1 5168 -1 5169 -1 5170 -1 5171 -1 5172 -1 5173 -1 5174 -1 5175 -1 5176 -1 5177 -1 5178 -1 5179 -1 5180 -1 5181 -1 5182 -1 5183 -1 5184 -1 5185 -1 5186 -1 5187 -1 5188 -1 5189 -1 5190 -1 5191 -1 5192 -1 5193 -1 5194 -1 5195 -1 5196 -1 5197 -1 5198 -1 5199 -1 5200 -1 5201 -1 5202 -1 5203 -1 5204 -1 5205 -1 5206 -1 5207 -1 5208 -1 5209 -1 5210 -1 5211 -1 5212 -1 5213 -1 5214 -1 5215 -1 5216 -1 5217 -1 5218 -1 5219 -1 5220 -1 5221 -1 5222 -1 5223 -1 5224 -1 5225 -1 5226 -1 5227 -1 5228 -1 5229 -1 5230 -1 5231 -1 5232 -1 5233 -1 5234 -1 5235 -1 5236 -1 5237 -1 5238 -1 5239 -1 5240 -1 5241 -1 5242 -1 5243 -1 5244 -1 5245 -1 5246 -1 5247 -1 5248 -1 5249 -1 5250 -1 5251 -1 5252 -1 5253 -1 5254 -1 5255 -1 5256 -1 5257 -1 5258 -1 5259 -1 5260 -1 5261 -1 5262 -1 5263 -1 5264 -1 5265 -1 5266 -1 5267 -1 5268 -1 5269 -1 5270 -1 5271 -1 5272 -1 5273 -1 5274 -1 5275 -1 5276 -1 5277 -1 5278 -1 5279 -1 5280 -1 5281 -1 5282 -1 5283 -1 5284 -1 5285 -1 5286 -1 5287 -1 5288 -1 5289 -1 5290 -1 5291 -1 5292 -1 5293 -1 5294 -1 5295 -1 5296 -1 5297 -1 5298 -1 5299 -1 5300 -1 5301 -1 5302 -1 5303 -1 5304 -1 5305 -1 5306 -1 5307 -1 5308 -1 5309 -1 5310 -1 5311 -1 5312 -1 5313 -1 5314 -1 5315 -1 5316 -1 5317 -1 5318 -1 5319 -1 5320 -1 5321 -1 5322 -1 5323 -1 5324 -1 5325 -1 5326 -1 5327 -1 5328 -1 5329 -1 5330 -1 5331 -1 5332 -1 5333 -1 5334 -1 5335 -1 5336 -1 5337 -1 5338 -1 5339 -1 5340 -1 5341 -1 5342 -1 5343 -1 5344 -1 5345 -1 5346 -1 5347 -1 5348 -1 5349 -1 5350 -1 5351 -1 5352 -1 5353 -1 5354 -1 5355 -1 5356 -1 5357 -1 5358 -1 5359 -1 5360 -1 5361 -1 5362 -1 5363 -1 5364 -1 5365 -1 5366 -1 5367 -1 5368 -1 5369 -1 5370 -1 5371 -1 5372 -1 5373 -1 5374 -1 5375 -1 5376 -1 5377 -1 5378 -1 5379 -1 5380 -1 5381 -1 5382 -1 5383 -1 5384 -1 5385 -1 5386 -1 5387 -1 5388 -1 5389 -1 5390 -1 5391 -1 5392 -1 5393 -1 5394 -1 5395 -1 5396 -1 5397 -1 5398 -1 5399 -1 5400 -1 5401 -1 5402 -1 5403 -1 5404 -1 5405 -1 5406 -1 5407 -1 5408 -1 5409 -1 5410 -1 5411 -1 5412 -1 5413 -1 5414 -1 5415 -1 5416 -1 5417 -1 5418 -1 5419 -1 5420 -1 5421 -1 5422 -1 5423 -1 5424 -1 5425 -1 5426 -1 5427 -1 5428 -1 5429 -1 5430 -1 5431 -1 5432 -1 5433 -1 5434 -1 5435 -1 5436 -1 5437 -1 5438 -1 5439 -1 5440 -1 5441 -1 5442 -1 5443 -1 5444 -1 5445 -1 5446 -1 5447 -1 5448 -1 5449 -1 5450 -1 5451 -1 5452 -1 5453 -1 5454 -1 5455 -1 5456 -1 5457 -1 5458 -1 5459 -1 5460 -1 5461 -1 5462 -1 5463 -1 5464 -1 5465 -1 5466 -1 5467 -1 5468 -1 5469 -1 5470 -1 5471 -1 5472 -1 5473 -1 5474 -1 5475 -1 5476 -1 5477 -1 5478 -1 5479 -1 5480 -1 5481 -1 5482 -1 5483 -1 5484 -1 5485 -1 5486 -1 5487 -1 5488 -1 5489 -1 5490 -1 5491 -1 5492 -1 5493 -1 5494 -1 5495 -1 5496 -1 5497 -1 5498 -1 5499 -1 5500 -1 5501 -1 5502 -1 5503 -1 5504 -1 5505 -1 5506 -1 5507 -1 5508 -1 5509 -1 5510 -1 5511 -1 5512 -1 5513 -1 5514 -1 5515 -1 5516 -1 5517 -1 5518 -1 5519 -1 5520 -1 5521 -1 5522 -1 5523 -1 5524 -1 5525 -1 5526 -1 5527 -1 5528 -1 5529 -1 5530 -1 5531 -1 5532 -1 5533 -1 5534 -1 5535 -1 5536 -1 5537 -1 5538 -1 5539 -1 5540 -1 5541 -1 5542 -1 5543 -1 5544 -1 5545 -1 5546 -1 5547 -1 5548 -1 5549 -1 5550 -1 5551 -1 5552 -1 5553 -1 5554 -1 5555 -1 5556 -1 5557 -1 5558 -1 5559 -1 5560 -1 5561 -1 5562 -1 5563 -1 5564 -1 5565 -1 5566 -1 5567 -1 5568 -1 5569 -1 5570 -1 5571 -1 5572 -1 5573 -1 5574 -1 5575 -1 5576 -1 5577 -1 5578 -1 5579 -1 5580 -1 5581 -1 5582 -1 5583 -1 5584 -1 5585 -1 5586 -1 5587 -1 5588 -1 5589 -1 5590 -1 5591 -1 5592 -1 5593 -1 5594 -1 5595 -1 5596 -1 5597 -1 5598 -1 5599 -1 5600 -1 5601 -1 5602 -1 5603 -1 5604 -1 5605 -1 5606 -1 5607 -1 5608 -1 5609 -1 5610 -1 5611 -1 5612 -1 5613 -1 5614 -1 5615 -1 5616 -1 5617 -1 5618 -1 5619 -1 5620 -1 5621 -1 5622 -1 5623 -1 5624 -1 5625 -1 5626 -1 5627 -1 5628 -1 5629 -1 5630 -1 5631 -1 5632 -1 5633 -1 5634 -1 5635 -1 5636 -1 5637 -1 5638 -1 5639 -1 5640 -1 5641 -1 5642 -1 5643 -1 5644 -1 5645 -1 5646 -1 5647 -1 5648 -1 5649 -1 5650 -1 5651 -1 5652 -1 5653 -1 5654 -1 5655 -1 5656 -1 5657 -1 5658 -1 5659 -1 5660 -1 5661 -1 5662 -1 5663 -1 5664 -1 5665 -1 5666 -1 5667 -1 5668 -1 5669 -1 5670 -1 5671 -1 5672 -1 5673 -1 5674 -1 5675 -1 5676 -1 5677 -1 5678 -1 5679 -1 5680 -1 5681 -1 5682 -1 5683 -1 5684 -1 5685 -1 5686 -1 5687 -1 5688 -1 5689 -1 5690 -1 5691 -1 5692 -1 5693 -1 5694 -1 5695 -1 5696 -1 5697 -1 5698 -1 5699 -1 5700 -1 5701 -1 5702 -1 5703 -1 5704 -1 5705 -1 5706 -1 5707 -1 5708 -1 5709 -1 5710 -1 5711 -1 5712 -1 5713 -1 5714 -1 5715 -1 5716 -1 5717 -1 5718 -1 5719 -1 5720 -1 5721 -1 5722 -1 5723 -1 5724 -1 5725 -1 5726 -1 5727 -1 5728 -1 5729 -1 5730 -1 5731 -1 5732 -1 5733 -1 5734 -1 5735 -1 5736 -1 5737 -1 5738 -1 5739 -1 5740 -1 5741 -1 5742 -1 5743 -1 5744 -1 5745 -1 5746 -1 5747 -1 5748 -1 5749 -1 5750 -1 5751 -1 5752 -1 5753 -1 5754 -1 5755 -1 5756 -1 5757 -1 5758 -1 5759 -1 5760 -1 5761 -1 5762 -1 5763 -1 5764 -1 5765 -1 5766 -1 5767 -1 5768 -1 5769 -1 5770 -1 5771 -1 5772 -1 5773 -1 5774 -1 5775 -1 5776 -1 5777 -1 5778 -1 5779 -1 5780 -1 5781 -1 5782 -1 5783 -1 5784 -1 5785 -1 5786 -1 5787 -1 5788 -1 5789 -1 5790 -1 5791 -1 5792 -1 5793 -1 5794 -1 5795 -1 5796 -1 5797 -1 5798 -1 5799 -1 5800 -1 5801 -1 5802 -1 5803 -1 5804 -1 5805 -1 5806 -1 5807 -1 5808 -1 5809 -1 5810 -1 5811 -1 5812 -1 5813 -1 5814 -1 5815 -1 5816 -1 5817 -1 5818 -1 5819 -1 5820 -1 5821 -1 5822 -1 5823 -1 5824 -1 5825 -1 5826 -1 5827 -1 5828 -1 5829 -1 5830 -1 5831 -1 5832 -1 5833 -1 5834 -1 5835 -1 5836 -1 5837 -1 5838 -1 5839 -1 5840 -1 5841 -1 5842 -1 5843 -1 5844 -1 5845 -1 5846 -1 5847 -1 5848 -1 5849 -1 5850 -1 5851 -1 5852 -1 5853 -1 5854 -1 5855 -1 5856 -1 5857 -1 5858 -1 5859 -1 5860 -1 5861 -1 5862 -1 5863 -1 5864 -1 5865 -1 5866 -1 5867 -1 5868 -1 5869 -1 5870 -1 5871 -1 5872 -1 5873 -1 5874 -1 5875 -1 5876 -1 5877 -1 5878 -1 5879 -1 5880 -1 5881 -1 5882 -1 5883 -1 5884 -1 5885 -1 5886 -1 5887 -1 5888 -1 5889 -1 5890 -1 5891 -1 5892 -1 5893 -1 5894 -1 5895 -1 5896 -1 5897 -1 5898 -1 5899 -1 5900 -1 5901 -1 5902 -1 5903 -1 5904 -1 5905 -1 5906 -1 5907 -1 5908 -1 5909 -1 5910 -1 5911 -1 5912 -1 5913 -1 5914 -1 5915 -1 5916 -1 5917 -1 5918 -1 5919 -1 5920 -1 5921 -1 5922 -1 5923 -1 5924 -1 5925 -1 5926 -1 5927 -1 5928 -1 5929 -1 5930 -1 5931 -1 5932 -1 5933 -1 5934 -1 5935 -1 5936 -1 5937 -1 5938 -1 5939 -1 5940 -1 5941 -1 5942 -1 5943 -1 5944 -1 5945 -1 5946 -1 5947 -1 5948 -1 5949 -1 5950 -1 5951 -1 5952 -1 5953 -1 5954 -1 5955 -1 5956 -1 5957 -1 5958 -1 5959 -1 5960 -1 5961 -1 5962 -1 5963 -1 5964 -1 5965 -1 5966 -1 5967 -1 5968 -1 5969 -1 5970 -1 5971 -1 5972 -1 5973 -1 5974 -1 5975 -1 5976 -1 5977 -1 5978 -1 5979 -1 5980 -1 5981 -1 5982 -1 5983 -1 5984 -1 5985 -1 5986 -1 5987 -1 5988 -1 5989 -1 5990 -1 5991 -1 5992 -1 5993 -1 5994 -1 5995 -1 5996 -1 5997 -1 5998 -1 5999 -1 6000 -1 6001 -1 6002 -1 6003 -1 6004 -1 6005 -1 6006 -1 6007 -1 6008 -1 6009 -1 6010 -1 6011 -1 6012 -1 6013 -1 6014 -1 6015 -1 6016 -1 6017 -1 6018 -1 6019 -1 6020 -1 6021 -1 6022 -1 6023 -1 6024 -1 6025 -1 6026 -1 6027 -1 6028 -1 6029 -1 6030 -1 6031 -1 6032 -1 6033 -1 6034 -1 6035 -1 6036 -1 6037 -1 6038 -1 6039 -1 6040 -1 6041 -1 6042 -1 6043 -1 6044 -1 6045 -1 6046 -1 6047 -1 6048 -1 6049 -1 6050 -1 6051 -1 6052 -1 6053 -1 6054 -1 6055 -1 6056 -1 6057 -1 6058 -1 6059 -1 6060 -1 6061 -1 6062 -1 6063 -1 6064 -1 6065 -1 6066 -1 6067 -1 6068 -1 6069 -1 6070 -1 6071 -1 6072 -1 6073 -1 6074 -1 6075 -1 6076 -1 6077 -1 6078 -1 6079 -1 6080 -1 6081 -1 6082 -1 6083 -1 6084 -1 6085 -1 6086 -1 6087 -1 6088 -1 6089 -1 6090 -1 6091 -1 6092 -1 6093 -1 6094 -1 6095 -1 6096 -1 6097 -1 6098 -1 6099 -1 6100 -1 6101 -1 6102 -1 6103 -1 6104 -1 6105 -1 6106 -1 6107 -1 6108 -1 6109 -1 6110 -1 6111 -1 6112 -1 6113 -1 6114 -1 6115 -1 6116 -1 6117 -1 6118 -1 6119 -1 6120 -1 6121 -1 6122 -1 6123 -1 6124 -1 6125 -1 6126 -1 6127 -1 6128 -1 6129 -1 6130 -1 6131 -1 6132 -1 6133 -1 6134 -1 6135 -1 6136 -1 6137 -1 6138 -1 6139 -1 6140 -1 6141 -1 6142 -1 6143 -1 6144 -1 6145 -1 6146 -1 6147 -1 6148 -1 6149 -1 6150 -1 6151 -1 6152 -1 6153 -1 6154 -1 6155 -1 6156 -1 6157 -1 6158 -1 6159 -1 6160 -1 6161 -1 6162 -1 6163 -1 6164 -1 6165 -1 6166 -1 6167 -1 6168 -1 6169 -1 6170 -1 6171 -1 6172 -1 6173 -1 6174 -1 6175 -1 6176 -1 6177 -1 6178 -1 6179 -1 6180 -1 6181 -1 6182 -1 6183 -1 6184 -1 6185 -1 6186 -1 6187 -1 6188 -1 6189 -1 6190 -1 6191 -1 6192 -1 6193 -1 6194 -1 6195 -1 6196 -1 6197 -1 6198 -1 6199 -1 6200 -1 6201 -1 6202 -1 6203 -1 6204 -1 6205 -1 6206 -1 6207 -1 6208 -1 6209 -1 6210 -1 6211 -1 6212 -1 6213 -1 6214 -1 6215 -1 6216 -1 6217 -1 6218 -1 6219 -1 6220 -1 6221 -1 6222 -1 6223 -1 6224 -1 6225 -1 6226 -1 6227 -1 6228 -1 6229 -1 6230 -1 6231 -1 6232 -1 6233 -1 6234 -1 6235 -1 6236 -1 6237 -1 6238 -1 6239 -1 6240 -1 6241 -1 6242 -1 6243 -1 6244 -1 6245 -1 6246 -1 6247 -1 6248 -1 6249 -1 6250 -1 6251 -1 6252 -1 6253 -1 6254 -1 6255 -1 6256 -1 6257 -1 6258 -1 6259 -1 6260 -1 6261 -1 6262 -1 6263 -1 6264 -1 6265 -1 6266 -1 6267 -1 6268 -1 6269 -1 6270 -1 6271 -1 6272 -1 6273 -1 6274 -1 6275 -1 6276 -1 6277 -1 6278 -1 6279 -1 6280 -1 6281 -1 6282 -1 6283 -1 6284 -1 6285 -1 6286 -1 6287 -1 6288 -1 6289 -1 6290 -1 6291 -1 6292 -1 6293 -1 6294 -1 6295 -1 6296 -1 6297 -1 6298 -1 6299 -1 6300 -1 6301 -1 6302 -1 6303 -1 6304 -1 6305 -1 6306 -1 6307 -1 6308 -1 6309 -1 6310 -1 6311 -1 6312 -1 6313 -1 6314 -1 6315 -1 6316 -1 6317 -1 6318 -1 6319 -1 6320 -1 6321 -1 6322 -1 6323 -1 6324 -1 6325 -1 6326 -1 6327 -1 6328 -1 6329 -1 6330 -1 6331 -1 6332 -1 6333 -1 6334 -1 6335 -1 6336 -1 6337 -1 6338 -1 6339 -1 6340 -1 6341 -1 6342 -1 6343 -1 6344 -1 6345 -1 6346 -1 6347 -1 6348 -1 6349 -1 6350 -1 6351 -1 6352 -1 6353 -1 6354 -1 6355 -1 6356 -1 6357 -1 6358 -1 6359 -1 6360 -1 6361 -1 6362 -1 6363 -1 6364 -1 6365 -1 6366 -1 6367 -1 6368 -1 6369 -1 6370 -1 6371 -1 6372 -1 6373 -1 6374 -1 6375 -1 6376 -1 6377 -1 6378 -1 6379 -1 6380 -1 6381 -1 6382 -1 6383 -1 6384 -1 6385 -1 6386 -1 6387 -1 6388 -1 6389 -1 6390 -1 6391 -1 6392 -1 6393 -1 6394 -1 6395 -1 6396 -1 6397 -1 6398 -1 6399 -1 6400 -1 6401 -1 6402 -1 6403 -1 6404 -1 6405 -1 6406 -1 6407 -1 6408 -1 6409 -1 6410 -1 6411 -1 6412 -1 6413 -1 6414 -1 6415 -1 6416 -1 6417 -1 6418 -1 6419 -1 6420 -1 6421 -1 6422 -1 6423 -1 6424 -1 6425 -1 6426 -1 6427 -1 6428 -1 6429 -1 6430 -1 6431 -1 6432 -1 6433 -1 6434 -1 6435 -1 6436 -1 6437 -1 6438 -1 6439 -1 6440 -1 6441 -1 6442 -1 6443 -1 6444 -1 6445 -1 6446 -1 6447 -1 6448 -1 6449 -1 6450 -1 6451 -1 6452 -1 6453 -1 6454 -1 6455 -1 6456 -1 6457 -1 6458 -1 6459 -1 6460 -1 6461 -1 6462 -1 6463 -1 6464 -1 6465 -1 6466 -1 6467 -1 6468 -1 6469 -1 6470 -1 6471 -1 6472 -1 6473 -1 6474 -1 6475 -1 6476 -1 6477 -1 6478 -1 6479 -1 6480 -1 6481 -1 6482 -1 6483 -1 6484 -1 6485 -1 6486 -1 6487 -1 6488 -1 6489 -1 6490 -1 6491 -1 6492 -1 6493 -1 6494 -1 6495 -1 6496 -1 6497 -1 6498 -1 6499 -1 6500 -1 6501 -1 6502 -1 6503 -1 6504 -1 6505 -1 6506 -1 6507 -1 6508 -1 6509 -1 6510 -1 6511 -1 6512 -1 6513 -1 6514 -1 6515 -1 6516 -1 6517 -1 6518 -1 6519 -1 6520 -1 6521 -1 6522 -1 6523 -1 6524 -1 6525 -1 6526 -1 6527 -1 6528 -1 6529 -1 6530 -1 6531 -1 6532 -1 6533 -1 6534 -1 6535 -1 6536 -1 6537 -1 6538 -1 6539 -1 6540 -1 6541 -1 6542 -1 6543 -1 6544 -1 6545 -1 6546 -1 6547 -1 6548 -1 6549 -1 6550 -1 6551 -1 6552 -1 6553 -1 6554 -1 6555 -1 6556 -1 6557 -1 6558 -1 6559 -1 6560 -1 6561 -1 6562 -1 6563 -1 6564 -1 6565 -1 6566 -1 6567 -1 6568 -1 6569 -1 6570 -1 6571 -1 6572 -1 6573 -1 6574 -1 6575 -1 6576 -1 6577 -1 6578 -1 6579 -1 6580 -1 6581 -1 6582 -1 6583 -1 6584 -1 6585 -1 6586 -1 6587 -1 6588 -1 6589 -1 6590 -1 6591 -1 6592 -1 6593 -1 6594 -1 6595 -1 6596 -1 6597 -1 6598 -1 6599 -1 6600 -1 6601 -1 6602 -1 6603 -1 6604 -1 6605 -1 6606 -1 6607 -1 6608 -1 6609 -1 6610 -1 6611 -1 6612 -1 6613 -1 6614 -1 6615 -1 6616 -1 6617 -1 6618 -1 6619 -1 6620 -1 6621 -1 6622 -1 6623 -1 6624 -1 6625 -1 6626 -1 6627 -1 6628 -1 6629 -1 6630 -1 6631 -1 6632 -1 6633 -1 6634 -1 6635 -1 6636 -1 6637 -1 6638 -1 6639 -1 6640 -1 6641 -1 6642 -1 6643 -1 6644 -1 6645 -1 6646 -1 6647 -1 6648 -1 6649 -1 6650 -1 6651 -1 6652 -1 6653 -1 6654 -1 6655 -1 6656 -1 6657 -1 6658 -1 6659 -1 6660 -1 6661 -1 6662 -1 6663 -1 6664 -1 6665 -1 6666 -1 6667 -1 6668 -1 6669 -1 6670 -1 6671 -1 6672 -1 6673 -1 6674 -1 6675 -1 6676 -1 6677 -1 6678 -1 6679 -1 6680 -1 6681 -1 6682 -1 6683 -1 6684 -1 6685 -1 6686 -1 6687 -1 6688 -1 6689 -1 6690 -1 6691 -1 6692 -1 6693 -1 6694 -1 6695 -1 6696 -1 6697 -1 6698 -1 6699 -1 6700 -1 6701 -1 6702 -1 6703 -1 6704 -1 6705 -1 6706 -1 6707 -1 6708 -1 6709 -1 6710 -1 6711 -1 6712 -1 6713 -1 6714 -1 6715 -1 6716 -1 6717 -1 6718 -1 6719 -1 6720 -1 6721 -1 6722 -1 6723 -1 6724 -1 6725 -1 6726 -1 6727 -1 6728 -1 6729 -1 6730 -1 6731 -1 6732 -1 6733 -1 6734 -1 6735 -1 6736 -1 6737 -1 6738 -1 6739 -1 6740 -1 6741 -1 6742 -1 6743 -1 6744 -1 6745 -1 6746 -1 6747 -1 6748 -1 6749 -1 6750 -1 6751 -1 6752 -1 6753 -1 6754 -1 6755 -1 6756 -1 6757 -1 6758 -1 6759 -1 6760 -1 6761 -1 6762 -1 6763 -1 6764 -1 6765 -1 6766 -1 6767 -1 6768 -1 6769 -1 6770 -1 6771 -1 6772 -1 6773 -1 6774 -1 6775 -1 6776 -1 6777 -1 6778 -1 6779 -1 6780 -1 6781 -1 6782 -1 6783 -1 6784 -1 6785 -1 6786 -1 6787 -1 6788 -1 6789 -1 6790 -1 6791 -1 6792 -1 6793 -1 6794 -1 6795 -1 6796 -1 6797 -1 6798 -1 6799 -1 6800 -1 6801 -1 6802 -1 6803 -1 6804 -1 6805 -1 6806 -1 6807 -1 6808 -1 6809 -1 6810 -1 6811 -1 6812 -1 6813 -1 6814 -1 6815 -1 6816 -1 6817 -1 6818 -1 6819 -1 6820 -1 6821 -1 6822 -1 6823 -1 6824 -1 6825 -1 6826 -1 6827 -1 6828 -1 6829 -1 6830 -1 6831 -1 6832 -1 6833 -1 6834 -1 6835 -1 6836 -1 6837 -1 6838 -1 6839 -1 6840 -1 6841 -1 6842 -1 6843 -1 6844 -1 6845 -1 6846 -1 6847 -1 6848 -1 6849 -1 6850 -1 6851 -1 6852 -1 6853 -1 6854 -1 6855 -1 6856 -1 6857 -1 6858 -1 6859 -1 6860 -1 6861 -1 6862 -1 6863 -1 6864 -1 6865 -1 6866 -1 6867 -1 6868 -1 6869 -1 6870 -1 6871 -1 6872 -1 6873 -1 6874 -1 6875 -1 6876 -1 6877 -1 6878 -1 6879 -1 6880 -1 6881 -1 6882 -1 6883 -1 6884 -1 6885 -1 6886 -1 6887 -1 6888 -1 6889 -1 6890 -1 6891 -1 6892 -1 6893 -1 6894 -1 6895 -1 6896 -1 6897 -1 6898 -1 6899 -1 6900 -1 6901 -1 6902 -1 6903 -1 6904 -1 6905 -1 6906 -1 6907 -1 6908 -1 6909 -1 6910 -1 6911 -1 6912 -1 6913 -1 6914 -1 6915 -1 6916 -1 6917 -1 6918 -1 6919 -1 6920 -1 6921 -1 6922 -1 6923 -1 6924 -1 6925 -1 6926 -1 6927 -1 6928 -1 6929 -1 6930 -1 6931 -1 6932 -1 6933 -1 6934 -1 6935 -1 6936 -1 6937 -1 6938 -1 6939 -1 6940 -1 6941 -1 6942 -1 6943 -1 6944 -1 6945 -1 6946 -1 6947 -1 6948 -1 6949 -1 6950 -1 6951 -1 6952 -1 6953 -1 6954 -1 6955 -1 6956 -1 6957 -1 6958 -1 6959 -1 6960 -1 6961 -1 6962 -1 6963 -1 6964 -1 6965 -1 6966 -1 6967 -1 6968 -1 6969 -1 6970 -1 6971 -1 6972 -1 6973 -1 6974 -1 6975 -1 6976 -1 6977 -1 6978 -1 6979 -1 6980 -1 6981 -1 6982 -1 6983 -1 6984 -1 6985 -1 6986 -1 6987 -1 6988 -1 6989 -1 6990 -1 6991 -1 6992 -1 6993 -1 6994 -1 6995 -1 6996 -1 6997 -1 6998 -1 6999 -1 7000 -1 7001 -1 7002 -1 7003 -1 7004 -1 7005 -1 7006 -1 7007 -1 7008 -1 7009 -1 7010 -1 7011 -1 7012 -1 7013 -1 7014 -1 7015 -1 7016 -1 7017 -1 7018 -1 7019 -1 7020 -1 7021 -1 7022 -1 7023 -1 7024 -1 7025 -1 7026 -1 7027 -1 7028 -1 7029 -1 7030 -1 7031 -1 7032 -1 7033 -1 7034 -1 7035 -1 7036 -1 7037 -1 7038 -1 7039 -1 7040 -1 7041 -1 7042 -1 7043 -1 7044 -1 7045 -1 7046 -1 7047 -1 7048 -1 7049 -1 7050 -1 7051 -1 7052 -1 7053 -1 7054 -1 7055 -1 7056 -1 7057 -1 7058 -1 7059 -1 7060 -1 7061 -1 7062 -1 7063 -1 7064 -1 7065 -1 7066 -1 7067 -1 7068 -1 7069 -1 7070 -1 7071 -1 7072 -1 7073 -1 7074 -1 7075 -1 7076 -1 7077 -1 7078 -1 7079 -1 7080 -1 7081 -1 7082 -1 7083 -1 7084 -1 7085 -1 7086 -1 7087 -1 7088 -1 7089 -1 7090 -1 7091 -1 7092 -1 7093 -1 7094 -1 7095 -1 7096 -1 7097 -1 7098 -1 7099 -1 7100 -1 7101 -1 7102 -1 7103 -1 7104 -1 7105 -1 7106 -1 7107 -1 7108 -1 7109 -1 7110 -1 7111 -1 7112 -1 7113 -1 7114 -1 7115 -1 7116 -1 7117 -1 7118 -1 7119 -1 7120 -1 7121 -1 7122 -1 7123 -1 7124 -1 7125 -1 7126 -1 7127 -1 7128 -1 7129 -1 7130 -1 7131 -1 7132 -1 7133 -1 7134 -1 7135 -1 7136 -1 7137 -1 7138 -1 7139 -1 7140 -1 7141 -1 7142 -1 7143 -1 7144 -1 7145 -1 7146 -1 7147 -1 7148 -1 7149 -1 7150 -1 7151 -1 7152 -1 7153 -1 7154 -1 7155 -1 7156 -1 7157 -1 7158 -1 7159 -1 7160 -1 7161 -1 7162 -1 7163 -1 7164 -1 7165 -1 7166 -1 7167 -1 7168 -1 7169 -1 7170 -1 7171 -1 7172 -1 7173 -1 7174 -1 7175 -1 7176 -1 7177 -1 7178 -1 7179 -1 7180 -1 7181 -1 7182 -1 7183 -1 7184 -1 7185 -1 7186 -1 7187 -1 7188 -1 7189 -1 7190 -1 7191 -1 7192 -1 7193 -1 7194 -1 7195 -1 7196 -1 7197 -1 7198 -1 7199 -1 7200 -1 7201 -1 7202 -1 7203 -1 7204 -1 7205 -1 7206 -1 7207 -1 7208 -1 7209 -1 7210 -1 7211 -1 7212 -1 7213 -1 7214 -1 7215 -1 7216 -1 7217 -1 7218 -1 7219 -1 7220 -1 7221 -1 7222 -1 7223 -1 7224 -1 7225 -1 7226 -1 7227 -1 7228 -1 7229 -1 7230 -1 7231 -1 7232 -1 7233 -1 7234 -1 7235 -1 7236 -1 7237 -1 7238 -1 7239 -1 7240 -1 7241 -1 7242 -1 7243 -1 7244 -1 7245 -1 7246 -1 7247 -1 7248 -1 7249 -1 7250 -1 7251 -1 7252 -1 7253 -1 7254 -1 7255 -1 7256 -1 7257 -1 7258 -1 7259 -1 7260 -1 7261 -1 7262 -1 7263 -1 7264 -1 7265 -1 7266 -1 7267 -1 7268 -1 7269 -1 7270 -1 7271 -1 7272 -1 7273 -1 7274 -1 7275 -1 7276 -1 7277 -1 7278 -1 7279 -1 7280 -1 7281 -1 7282 -1 7283 -1 7284 -1 7285 -1 7286 -1 7287 -1 7288 -1 7289 -1 7290 -1 7291 -1 7292 -1 7293 -1 7294 -1 7295 -1 7296 -1 7297 -1 7298 -1 7299 -1 7300 -1 7301 -1 7302 -1 7303 -1 7304 -1 7305 -1 7306 -1 7307 -1 7308 -1 7309 -1 7310 -1 7311 -1 7312 -1 7313 -1 7314 -1 7315 -1 7316 -1 7317 -1 7318 -1 7319 -1 7320 -1 7321 -1 7322 -1 7323 -1 7324 -1 7325 -1 7326 -1 7327 -1 7328 -1 7329 -1 7330 -1 7331 -1 7332 -1 7333 -1 7334 -1 7335 -1 7336 -1 7337 -1 7338 -1 7339 -1 7340 -1 7341 -1 7342 -1 7343 -1 7344 -1 7345 -1 7346 -1 7347 -1 7348 -1 7349 -1 7350 -1 7351 -1 7352 -1 7353 -1 7354 -1 7355 -1 7356 -1 7357 -1 7358 -1 7359 -1 7360 -1 7361 -1 7362 -1 7363 -1 7364 -1 7365 -1 7366 -1 7367 -1 7368 -1 7369 -1 7370 -1 7371 -1 7372 -1 7373 -1 7374 -1 7375 -1 7376 -1 7377 -1 7378 -1 7379 -1 7380 -1 7381 -1 7382 -1 7383 -1 7384 -1 7385 -1 7386 -1 7387 -1 7388 -1 7389 -1 7390 -1 7391 -1 7392 -1 7393 -1 7394 -1 7395 -1 7396 -1 7397 -1 7398 -1 7399 -1 7400 -1 7401 -1 7402 -1 7403 -1 7404 -1 7405 -1 7406 -1 7407 -1 7408 -1 7409 -1 7410 -1 7411 -1 7412 -1 7413 -1 7414 -1 7415 -1 7416 -1 7417 -1 7418 -1 7419 -1 7420 -1 7421 -1 7422 -1 7423 -1 7424 -1 7425 -1 7426 -1 7427 -1 7428 -1 7429 -1 7430 -1 7431 -1 7432 -1 7433 -1 7434 -1 7435 -1 7436 -1 7437 -1 7438 -1 7439 -1 7440 -1 7441 -1 7442 -1 7443 -1 7444 -1 7445 -1 7446 -1 7447 -1 7448 -1 7449 -1 7450 -1 7451 -1 7452 -1 7453 -1 7454 -1 7455 -1 7456 -1 7457 -1 7458 -1 7459 -1 7460 -1 7461 -1 7462 -1 7463 -1 7464 -1 7465 -1 7466 -1 7467 -1 7468 -1 7469 -1 7470 -1 7471 -1 7472 -1 7473 -1 7474 -1 7475 -1 7476 -1 7477 -1 7478 -1 7479 -1 7480 -1 7481 -1 7482 -1 7483 -1 7484 -1 7485 -1 7486 -1 7487 -1 7488 -1 7489 -1 7490 -1 7491 -1 7492 -1 7493 -1 7494 -1 7495 -1 7496 -1 7497 -1 7498 -1 7499 -1 7500 -1 7501 -1 7502 -1 7503 -1 7504 -1 7505 -1 7506 -1 7507 -1 7508 -1 7509 -1 7510 -1 7511 -1 7512 -1 7513 -1 7514 -1 7515 -1 7516 -1 7517 -1 7518 -1 7519 -1 7520 -1 7521 -1 7522 -1 7523 -1 7524 -1 7525 -1 7526 -1 7527 -1 7528 -1 7529 -1 7530 -1 7531 -1 7532 -1 7533 -1 7534 -1 7535 -1 7536 -1 7537 -1 7538 -1 7539 -1 7540 -1 7541 -1 7542 -1 7543 -1 7544 -1 7545 -1 7546 -1 7547 -1 7548 -1 7549 -1 7550 -1 7551 -1 7552 -1 7553 -1 7554 -1 7555 -1 7556 -1 7557 -1 7558 -1 7559 -1 7560 -1 7561 -1 7562 -1 7563 -1 7564 -1 7565 -1 7566 -1 7567 -1 7568 -1 7569 -1 7570 -1 7571 -1 7572 -1 7573 -1 7574 -1 7575 -1 7576 -1 7577 -1 7578 -1 7579 -1 7580 -1 7581 -1 7582 -1 7583 -1 7584 -1 7585 -1 7586 -1 7587 -1 7588 -1 7589 -1 7590 -1 7591 -1 7592 -1 7593 -1 7594 -1 7595 -1 7596 -1 7597 -1 7598 -1 7599 -1 7600 -1 7601 -1 7602 -1 7603 -1 7604 -1 7605 -1 7606 -1 7607 -1 7608 -1 7609 -1 7610 -1 7611 -1 7612 -1 7613 -1 7614 -1 7615 -1 7616 -1 7617 -1 7618 -1 7619 -1 7620 -1 7621 -1 7622 -1 7623 -1 7624 -1 7625 -1 7626 -1 7627 -1 7628 -1 7629 -1 7630 -1 7631 -1 7632 -1 7633 -1 7634 -1 7635 -1 7636 -1 7637 -1 7638 -1 7639 -1 7640 -1 7641 -1 7642 -1 7643 -1 7644 -1 7645 -1 7646 -1 7647 -1 7648 -1 7649 -1 7650 -1 7651 -1 7652 -1 7653 -1 7654 -1 7655 -1 7656 -1 7657 -1 7658 -1 7659 -1 7660 -1 7661 -1 7662 -1 7663 -1 7664 -1 7665 -1 7666 -1 7667 -1 7668 -1 7669 -1 7670 -1 7671 -1 7672 -1 7673 -1 7674 -1 7675 -1 7676 -1 7677 -1 7678 -1 7679 -1 7680 -1 7681 -1 7682 -1 7683 -1 7684 -1 7685 -1 7686 -1 7687 -1 7688 -1 7689 -1 7690 -1 7691 -1 7692 -1 7693 -1 7694 -1 7695 -1 7696 -1 7697 -1 7698 -1 7699 -1 7700 -1 7701 -1 7702 -1 7703 -1 7704 -1 7705 -1 7706 -1 7707 -1 7708 -1 7709 -1 7710 -1 7711 -1 7712 -1 7713 -1 7714 -1 7715 -1 7716 -1 7717 -1 7718 -1 7719 -1 7720 -1 7721 -1 7722 -1 7723 -1 7724 -1 7725 -1 7726 -1 7727 -1 7728 -1 7729 -1 7730 -1 7731 -1 7732 -1 7733 -1 7734 -1 7735 -1 7736 -1 7737 -1 7738 -1 7739 -1 7740 -1 7741 -1 7742 -1 7743 -1 7744 -1 7745 -1 7746 -1 7747 -1 7748 -1 7749 -1 7750 -1 7751 -1 7752 -1 7753 -1 7754 -1 7755 -1 7756 -1 7757 -1 7758 -1 7759 -1 7760 -1 7761 -1 7762 -1 7763 -1 7764 -1 7765 -1 7766 -1 7767 -1 7768 -1 7769 -1 7770 -1 7771 -1 7772 -1 7773 -1 7774 -1 7775 -1 7776 -1 7777 -1 7778 -1 7779 -1 7780 -1 7781 -1 7782 -1 7783 -1 7784 -1 7785 -1 7786 -1 7787 -1 7788 -1 7789 -1 7790 -1 7791 -1 7792 -1 7793 -1 7794 -1 7795 -1 7796 -1 7797 -1 7798 -1 7799 -1 7800 -1 7801 -1 7802 -1 7803 -1 7804 -1 7805 -1 7806 -1 7807 -1 7808 -1 7809 -1 7810 -1 7811 -1 7812 -1 7813 -1 7814 -1 7815 -1 7816 -1 7817 -1 7818 -1 7819 -1 7820 -1 7821 -1 7822 -1 7823 -1 7824 -1 7825 -1 7826 -1 7827 -1 7828 -1 7829 -1 7830 -1 7831 -1 7832 -1 7833 -1 7834 -1 7835 -1 7836 -1 7837 -1 7838 -1 7839 -1 7840 -1 7841 -1 7842 -1 7843 -1 7844 -1 7845 -1 7846 -1 7847 -1 7848 -1 7849 -1 7850 -1 7851 -1 7852 -1 7853 -1 7854 -1 7855 -1 7856 -1 7857 -1 7858 -1 7859 -1 7860 -1 7861 -1 7862 -1 7863 -1 7864 -1 7865 -1 7866 -1 7867 -1 7868 -1 7869 -1 7870 -1 7871 -1 7872 -1 7873 -1 7874 -1 7875 -1 7876 -1 7877 -1 7878 -1 7879 -1 7880 -1 7881 -1 7882 -1 7883 -1 7884 -1 7885 -1 7886 -1 7887 -1 7888 -1 7889 -1 7890 -1 7891 -1 7892 -1 7893 -1 7894 -1 7895 -1 7896 -1 7897 -1 7898 -1 7899 -1 7900 -1 7901 -1 7902 -1 7903 -1 7904 -1 7905 -1 7906 -1 7907 -1 7908 -1 7909 -1 7910 -1 7911 -1 7912 -1 7913 -1 7914 -1 7915 -1 7916 -1 7917 -1 7918 -1 7919 -1 7920 -1 7921 -1 7922 -1 7923 -1 7924 -1 7925 -1 7926 -1 7927 -1 7928 -1 7929 -1 7930 -1 7931 -1 7932 -1 7933 -1 7934 -1 7935 -1 7936 -1 7937 -1 7938 -1 7939 -1 7940 -1 7941 -1 7942 -1 7943 -1 7944 -1 7945 -1 7946 -1 7947 -1 7948 -1 7949 -1 7950 -1 7951 -1 7952 -1 7953 -1 7954 -1 7955 -1 7956 -1 7957 -1 7958 -1 7959 -1 7960 -1 7961 -1 7962 -1 7963 -1 7964 -1 7965 -1 7966 -1 7967 -1 7968 -1 7969 -1 7970 -1 7971 -1 7972 -1 7973 -1 7974 -1 7975 -1 7976 -1 7977 -1 7978 -1 7979 -1 7980 -1 7981 -1 7982 -1 7983 -1 7984 -1 7985 -1 7986 -1 7987 -1 7988 -1 7989 -1 7990 -1 7991 -1 7992 -1 7993 -1 7994 -1 7995 -1 7996 -1 7997 -1 7998 -1 7999 -1 8000 -1 8001 -1 8002 -1 8003 -1 8004 -1 8005 -1 8006 -1 8007 -1 8008 -1 8009 -1 8010 -1 8011 -1 8012 -1 8013 -1 8014 -1 8015 -1 8016 -1 8017 -1 8018 -1 8019 -1 8020 -1 8021 -1 8022 -1 8023 -1 8024 -1 8025 -1 8026 -1 8027 -1 8028 -1 8029 -1 8030 -1 8031 -1 8032 -1 8033 -1 8034 -1 8035 -1 8036 -1 8037 -1 8038 -1 8039 -1 8040 -1 8041 -1 8042 -1 8043 -1 8044 -1 8045 -1 8046 -1 8047 -1 8048 -1 8049 -1 8050 -1 8051 -1 8052 -1 8053 -1 8054 -1 8055 -1 8056 -1 8057 -1 8058 -1 8059 -1 8060 -1 8061 -1 8062 -1 8063 -1 8064 -1 8065 -1 8066 -1 8067 -1 8068 -1 8069 -1 8070 -1 8071 -1 8072 -1 8073 -1 8074 -1 8075 -1 8076 -1 8077 -1 8078 -1 8079 -1 8080 -1 8081 -1 8082 -1 8083 -1 8084 -1 8085 -1 8086 -1 8087 -1 8088 -1 8089 -1 8090 -1 8091 -1 8092 -1 8093 -1 8094 -1 8095 -1 8096 -1 8097 -1 8098 -1 8099 -1 8100 -1 8101 -1 8102 -1 8103 -1 8104 -1 8105 -1 8106 -1 8107 -1 8108 -1 8109 -1 8110 -1 8111 -1 8112 -1 8113 -1 8114 -1 8115 -1 8116 -1 8117 -1 8118 -1 8119 -1 8120 -1 8121 -1 8122 -1 8123 -1 8124 -1 8125 -1 8126 -1 8127 -1 8128 -1 8129 -1 8130 -1 8131 -1 8132 -1 8133 -1 8134 -1 8135 -1 8136 -1 8137 -1 8138 -1 8139 -1 8140 -1 8141 -1 8142 -1 8143 -1 8144 -1 8145 -1 8146 -1 8147 -1 8148 -1 8149 -1 8150 -1 8151 -1 8152 -1 8153 -1 8154 -1 8155 -1 8156 -1 8157 -1 8158 -1 8159 -1 8160 -1 8161 -1 8162 -1 8163 -1 8164 -1 8165 -1 8166 -1 8167 -1 8168 -1 8169 -1 8170 -1 8171 -1 8172 -1 8173 -1 8174 -1 8175 -1 8176 -1 8177 -1 8178 -1 8179 -1 8180 -1 8181 -1 8182 -1 8183 -1 8184 -1 8185 -1 8186 -1 8187 -1 8188 -1 8189 -1 8190 -1 8191 -1 8192 -1 8193 -1 8194 -1 8195 -1 8196 -1 8197 -1 8198 -1 8199 -1 8200 -1 8201 -1 8202 -1 8203 -1 8204 -1 8205 -1 8206 -1 8207 -1 8208 -1 8209 -1 8210 -1 8211 -1 8212 -1 8213 -1 8214 -1 8215 -1 8216 -1 8217 -1 8218 -1 8219 -1 8220 -1 8221 -1 8222 -1 8223 -1 8224 -1 8225 -1 8226 -1 8227 -1 8228 -1 8229 -1 8230 -1 8231 -1 8232 -1 8233 -1 8234 -1 8235 -1 8236 -1 8237 -1 8238 -1 8239 -1 8240 -1 8241 -1 8242 -1 8243 -1 8244 -1 8245 -1 8246 -1 8247 -1 8248 -1 8249 -1 8250 -1 8251 -1 8252 -1 8253 -1 8254 -1 8255 -1 8256 -1 8257 -1 8258 -1 8259 -1 8260 -1 8261 -1 8262 -1 8263 -1 8264 -1 8265 -1 8266 -1 8267 -1 8268 -1 8269 -1 8270 -1 8271 -1 8272 -1 8273 -1 8274 -1 8275 -1 8276 -1 8277 -1 8278 -1 8279 -1 8280 -1 8281 -1 8282 -1 8283 -1 8284 -1 8285 -1 8286 -1 8287 -1 8288 -1 8289 -1 8290 -1 8291 -1 8292 -1 8293 -1 8294 -1 8295 -1 8296 -1 8297 -1 8298 -1 8299 -1 8300 -1 8301 -1 8302 -1 8303 -1 8304 -1 8305 -1 8306 -1 8307 -1 8308 -1 8309 -1 8310 -1 8311 -1 8312 -1 8313 -1 8314 -1 8315 -1 8316 -1 8317 -1 8318 -1 8319 -1 8320 -1 8321 -1 8322 -1 8323 -1 8324 -1 8325 -1 8326 -1 8327 -1 8328 -1 8329 -1 8330 -1 8331 -1 8332 -1 8333 -1 8334 -1 8335 -1 8336 -1 8337 -1 8338 -1 8339 -1 8340 -1 8341 -1 8342 -1 8343 -1 8344 -1 8345 -1 8346 -1 8347 -1 8348 -1 8349 -1 8350 -1 8351 -1 8352 -1 8353 -1 8354 -1 8355 -1 8356 -1 8357 -1 8358 -1 8359 -1 8360 -1 8361 -1 8362 -1 8363 -1 8364 -1 8365 -1 8366 -1 8367 -1 8368 -1 8369 -1 8370 -1 8371 -1 8372 -1 8373 -1 8374 -1 8375 -1 8376 -1 8377 -1 8378 -1 8379 -1 8380 -1 8381 -1 8382 -1 8383 -1 8384 -1 8385 -1 8386 -1 8387 -1 8388 -1 8389 -1 8390 -1 8391 -1 8392 -1 8393 -1 8394 -1 8395 -1 8396 -1 8397 -1 8398 -1 8399 -1 8400 -1 8401 -1 8402 -1 8403 -1 8404 -1 8405 -1 8406 -1 8407 -1 8408 -1 8409 -1 8410 -1 8411 -1 8412 -1 8413 -1 8414 -1 8415 -1 8416 -1 8417 -1 8418 -1 8419 -1 8420 -1 8421 -1 8422 -1 8423 -1 8424 -1 8425 -1 8426 -1 8427 -1 8428 -1 8429 -1 8430 -1 8431 -1 8432 -1 8433 -1 8434 -1 8435 -1 8436 -1 8437 -1 8438 -1 8439 -1 8440 -1 8441 -1 8442 -1 8443 -1 8444 -1 8445 -1 8446 -1 8447 -1 8448 -1 8449 -1 8450 -1 8451 -1 8452 -1 8453 -1 8454 -1 8455 -1 8456 -1 8457 -1 8458 -1 8459 -1 8460 -1 8461 -1 8462 -1 8463 -1 8464 -1 8465 -1 8466 -1 8467 -1 8468 -1 8469 -1 8470 -1 8471 -1 8472 -1 8473 -1 8474 -1 8475 -1 8476 -1 8477 -1 8478 -1 8479 -1 8480 -1 8481 -1 8482 -1 8483 -1 8484 -1 8485 -1 8486 -1 8487 -1 8488 -1 8489 -1 8490 -1 8491 -1 8492 -1 8493 -1 8494 -1 8495 -1 8496 -1 8497 -1 8498 -1 8499 -1 8500 -1 8501 -1 8502 -1 8503 -1 8504 -1 8505 -1 8506 -1 8507 -1 8508 -1 8509 -1 8510 -1 8511 -1 8512 -1 8513 -1 8514 -1 8515 -1 8516 -1 8517 -1 8518 -1 8519 -1 8520 -1 8521 -1 8522 -1 8523 -1 8524 -1 8525 -1 8526 -1 8527 -1 8528 -1 8529 -1 8530 -1 8531 -1 8532 -1 8533 -1 8534 -1 8535 -1 8536 -1 8537 -1 8538 -1 8539 -1 8540 -1 8541 -1 8542 -1 8543 -1 8544 -1 8545 -1 8546 -1 8547 -1 8548 -1 8549 -1 8550 -1 8551 -1 8552 -1 8553 -1 8554 -1 8555 -1 8556 -1 8557 -1 8558 -1 8559 -1 8560 -1 8561 -1 8562 -1 8563 -1 8564 -1 8565 -1 8566 -1 8567 -1 8568 -1 8569 -1 8570 -1 8571 -1 8572 -1 8573 -1 8574 -1 8575 -1 8576 -1 8577 -1 8578 -1 8579 -1 8580 -1 8581 -1 8582 -1 8583 -1 8584 -1 8585 -1 8586 -1 8587 -1 8588 -1 8589 -1 8590 -1 8591 -1 8592 -1 8593 -1 8594 -1 8595 -1 8596 -1 8597 -1 8598 -1 8599 -1 8600 -1 8601 -1 8602 -1 8603 -1 8604 -1 8605 -1 8606 -1 8607 -1 8608 -1 8609 -1 8610 -1 8611 -1 8612 -1 8613 -1 8614 -1 8615 -1 8616 -1 8617 -1 8618 -1 8619 -1 8620 -1 8621 -1 8622 -1 8623 -1 8624 -1 8625 -1 8626 -1 8627 -1 8628 -1 8629 -1 8630 -1 8631 -1 8632 -1 8633 -1 8634 -1 8635 -1 8636 -1 8637 -1 8638 -1 8639 -1 8640 -1 8641 -1 8642 -1 8643 -1 8644 -1 8645 -1 8646 -1 8647 -1 8648 -1 8649 -1 8650 -1 8651 -1 8652 -1 8653 -1 8654 -1 8655 -1 8656 -1 8657 -1 8658 -1 8659 -1 8660 -1 8661 -1 8662 -1 8663 -1 8664 -1 8665 -1 8666 -1 8667 -1 8668 -1 8669 -1 8670 -1 8671 -1 8672 -1 8673 -1 8674 -1 8675 -1 8676 -1 8677 -1 8678 -1 8679 -1 8680 -1 8681 -1 8682 -1 8683 -1 8684 -1 8685 -1 8686 -1 8687 -1 8688 -1 8689 -1 8690 -1 8691 -1 8692 -1 8693 -1 8694 -1 8695 -1 8696 -1 8697 -1 8698 -1 8699 -1 8700 -1 8701 -1 8702 -1 8703 -1 8704 -1 8705 -1 8706 -1 8707 -1 8708 -1 8709 -1 8710 -1 8711 -1 8712 -1 8713 -1 8714 -1 8715 -1 8716 -1 8717 -1 8718 -1 8719 -1 8720 -1 8721 -1 8722 -1 8723 -1 8724 -1 8725 -1 8726 -1 8727 -1 8728 -1 8729 -1 8730 -1 8731 -1 8732 -1 8733 -1 8734 -1 8735 -1 8736 -1 8737 -1 8738 -1 8739 -1 8740 -1 8741 -1 8742 -1 8743 -1 8744 -1 8745 -1 8746 -1 8747 -1 8748 -1 8749 -1 8750 -1 8751 -1 8752 -1 8753 -1 8754 -1 8755 -1 8756 -1 8757 -1 8758 -1 8759 -1 8760 -1 8761 -1 8762 -1 8763 -1 8764 -1 8765 -1 8766 -1 8767 -1 8768 -1 8769 -1 8770 -1 8771 -1 8772 -1 8773 -1 8774 -1 8775 -1 8776 -1 8777 -1 8778 -1 8779 -1 8780 -1 8781 -1 8782 -1 8783 -1 8784 -1 8785 -1 8786 -1 8787 -1 8788 -1 8789 -1 8790 -1 8791 -1 8792 -1 8793 -1 8794 -1 8795 -1 8796 -1 8797 -1 8798 -1 8799 -1 8800 -1 8801 -1 8802 -1 8803 -1 8804 -1 8805 -1 8806 -1 8807 -1 8808 -1 8809 -1 8810 -1 8811 -1 8812 -1 8813 -1 8814 -1 8815 -1 8816 -1 8817 -1 8818 -1 8819 -1 8820 -1 8821 -1 8822 -1 8823 -1 8824 -1 8825 -1 8826 -1 8827 -1 8828 -1 8829 -1 8830 -1 8831 -1 8832 -1 8833 -1 8834 -1 8835 -1 8836 -1 8837 -1 8838 -1 8839 -1 8840 -1 8841 -1 8842 -1 8843 -1 8844 -1 8845 -1 8846 -1 8847 -1 8848 -1 8849 -1 8850 -1 8851 -1 8852 -1 8853 -1 8854 -1 8855 -1 8856 -1 8857 -1 8858 -1 8859 -1 8860 -1 8861 -1 8862 -1 8863 -1 8864 -1 8865 -1 8866 -1 8867 -1 8868 -1 8869 -1 8870 -1 8871 -1 8872 -1 8873 -1 8874 -1 8875 -1 8876 -1 8877 -1 8878 -1 8879 -1 8880 -1 8881 -1 8882 -1 8883 -1 8884 -1 8885 -1 8886 -1 8887 -1 8888 -1 8889 -1 8890 -1 8891 -1 8892 -1 8893 -1 8894 -1 8895 -1 8896 -1 8897 -1 8898 -1 8899 -1 8900 -1 8901 -1 8902 -1 8903 -1 8904 -1 8905 -1 8906 -1 8907 -1 8908 -1 8909 -1 8910 -1 8911 -1 8912 -1 8913 -1 8914 -1 8915 -1 8916 -1 8917 -1 8918 -1 8919 -1 8920 -1 8921 -1 8922 -1 8923 -1 8924 -1 8925 -1 8926 -1 8927 -1 8928 -1 8929 -1 8930 -1 8931 -1 8932 -1 8933 -1 8934 -1 8935 -1 8936 -1 8937 -1 8938 -1 8939 -1 8940 -1 8941 -1 8942 -1 8943 -1 8944 -1 8945 -1 8946 -1 8947 -1 8948 -1 8949 -1 8950 -1 8951 -1 8952 -1 8953 -1 8954 -1 8955 -1 8956 -1 8957 -1 8958 -1 8959 -1 8960 -1 8961 -1 8962 -1 8963 -1 8964 -1 8965 -1 8966 -1 8967 -1 8968 -1 8969 -1 8970 -1 8971 -1 8972 -1 8973 -1 8974 -1 8975 -1 8976 -1 8977 -1 8978 -1 8979 -1 8980 -1 8981 -1 8982 -1 8983 -1 8984 -1 8985 -1 8986 -1 8987 -1 8988 -1 8989 -1 8990 -1 8991 -1 8992 -1 8993 -1 8994 -1 8995 -1 8996 -1 8997 -1 8998 -1 8999 -1 9000 -1 9001 -1 9002 -1 9003 -1 9004 -1 9005 -1 9006 -1 9007 -1 9008 -1 9009 -1 9010 -1 9011 -1 9012 -1 9013 -1 9014 -1 9015 -1 9016 -1 9017 -1 9018 -1 9019 -1 9020 -1 9021 -1 9022 -1 9023 -1 9024 -1 9025 -1 9026 -1 9027 -1 9028 -1 9029 -1 9030 -1 9031 -1 9032 -1 9033 -1 9034 -1 9035 -1 9036 -1 9037 -1 9038 -1 9039 -1 9040 -1 9041 -1 9042 -1 9043 -1 9044 -1 9045 -1 9046 -1 9047 -1 9048 -1 9049 -1 9050 -1 9051 -1 9052 -1 9053 -1 9054 -1 9055 -1 9056 -1 9057 -1 9058 -1 9059 -1 9060 -1 9061 -1 9062 -1 9063 -1 9064 -1 9065 -1 9066 -1 9067 -1 9068 -1 9069 -1 9070 -1 9071 -1 9072 -1 9073 -1 9074 -1 9075 -1 9076 -1 9077 -1 9078 -1 9079 -1 9080 -1 9081 -1 9082 -1 9083 -1 9084 -1 9085 -1 9086 -1 9087 -1 9088 -1 9089 -1 9090 -1 9091 -1 9092 -1 9093 -1 9094 -1 9095 -1 9096 -1 9097 -1 9098 -1 9099 -1 9100 -1 9101 -1 9102 -1 9103 -1 9104 -1 9105 -1 9106 -1 9107 -1 9108 -1 9109 -1 9110 -1 9111 -1 9112 -1 9113 -1 9114 -1 9115 -1 9116 -1 9117 -1 9118 -1 9119 -1 9120 -1 9121 -1 9122 -1 9123 -1 9124 -1 9125 -1 9126 -1 9127 -1 9128 -1 9129 -1 9130 -1 9131 -1 9132 -1 9133 -1 9134 -1 9135 -1 9136 -1 9137 -1 9138 -1 9139 -1 9140 -1 9141 -1 9142 -1 9143 -1 9144 -1 9145 -1 9146 -1 9147 -1 9148 -1 9149 -1 9150 -1 9151 -1 9152 -1 9153 -1 9154 -1 9155 -1 9156 -1 9157 -1 9158 -1 9159 -1 9160 -1 9161 -1 9162 -1 9163 -1 9164 -1 9165 -1 9166 -1 9167 -1 9168 -1 9169 -1 9170 -1 9171 -1 9172 -1 9173 -1 9174 -1 9175 -1 9176 -1 9177 -1 9178 -1 9179 -1 9180 -1 9181 -1 9182 -1 9183 -1 9184 -1 9185 -1 9186 -1 9187 -1 9188 -1 9189 -1 9190 -1 9191 -1 9192 -1 9193 -1 9194 -1 9195 -1 9196 -1 9197 -1 9198 -1 9199 -1 9200 -1 9201 -1 9202 -1 9203 -1 9204 -1 9205 -1 9206 -1 9207 -1 9208 -1 9209 -1 9210 -1 9211 -1 9212 -1 9213 -1 9214 -1 9215 -1 9216 -1 9217 -1 9218 -1 9219 -1 9220 -1 9221 -1 9222 -1 9223 -1 9224 -1 9225 -1 9226 -1 9227 -1 9228 -1 9229 -1 9230 -1 9231 -1 9232 -1 9233 -1 9234 -1 9235 -1 9236 -1 9237 -1 9238 -1 9239 -1 9240 -1 9241 -1 9242 -1 9243 -1 9244 -1 9245 -1 9246 -1 9247 -1 9248 -1 9249 -1 9250 -1 9251 -1 9252 -1 9253 -1 9254 -1 9255 -1 9256 -1 9257 -1 9258 -1 9259 -1 9260 -1 9261 -1 9262 -1 9263 -1 9264 -1 9265 -1 9266 -1 9267 -1 9268 -1 9269 -1 9270 -1 9271 -1 9272 -1 9273 -1 9274 -1 9275 -1 9276 -1 9277 -1 9278 -1 9279 -1 9280 -1 9281 -1 9282 -1 9283 -1 9284 -1 9285 -1 9286 -1 9287 -1 9288 -1 9289 -1 9290 -1 9291 -1 9292 -1 9293 -1 9294 -1 9295 -1 9296 -1 9297 -1 9298 -1 9299 -1 9300 -1 9301 -1 9302 -1 9303 -1 9304 -1 9305 -1 9306 -1 9307 -1 9308 -1 9309 -1 9310 -1 9311 -1 9312 -1 9313 -1 9314 -1 9315 -1 9316 -1 9317 -1 9318 -1 9319 -1 9320 -1 9321 -1 9322 -1 9323 -1 9324 -1 9325 -1 9326 -1 9327 -1 9328 -1 9329 -1 9330 -1 9331 -1 9332 -1 9333 -1 9334 -1 9335 -1 9336 -1 9337 -1 9338 -1 9339 -1 9340 -1 9341 -1 9342 -1 9343 -1 9344 -1 9345 -1 9346 -1 9347 -1 9348 -1 9349 -1 9350 -1 9351 -1 9352 -1 9353 -1 9354 -1 9355 -1 9356 -1 9357 -1 9358 -1 9359 -1 9360 -1 9361 -1 9362 -1 9363 -1 9364 -1 9365 -1 9366 -1 9367 -1 9368 -1 9369 -1 9370 -1 9371 -1 9372 -1 9373 -1 9374 -1 9375 -1 9376 -1 9377 -1 9378 -1 9379 -1 9380 -1 9381 -1 9382 -1 9383 -1 9384 -1 9385 -1 9386 -1 9387 -1 9388 -1 9389 -1 9390 -1 9391 -1 9392 -1 9393 -1 9394 -1 9395 -1 9396 -1 9397 -1 9398 -1 9399 -1 9400 -1 9401 -1 9402 -1 9403 -1 9404 -1 9405 -1 9406 -1 9407 -1 9408 -1 9409 -1 9410 -1 9411 -1 9412 -1 9413 -1 9414 -1 9415 -1 9416 -1 9417 -1 9418 -1 9419 -1 9420 -1 9421 -1 9422 -1 9423 -1 9424 -1 9425 -1 9426 -1 9427 -1 9428 -1 9429 -1 9430 -1 9431 -1 9432 -1 9433 -1 9434 -1 9435 -1 9436 -1 9437 -1 9438 -1 9439 -1 9440 -1 9441 -1 9442 -1 9443 -1 9444 -1 9445 -1 9446 -1 9447 -1 9448 -1 9449 -1 9450 -1 9451 -1 9452 -1 9453 -1 9454 -1 9455 -1 9456 -1 9457 -1 9458 -1 9459 -1 9460 -1 9461 -1 9462 -1 9463 -1 9464 -1 9465 -1 9466 -1 9467 -1 9468 -1 9469 -1 9470 -1 9471 -1 9472 -1 9473 -1 9474 -1 9475 -1 9476 -1 9477 -1 9478 -1 9479 -1 9480 -1 9481 -1 9482 -1 9483 -1 9484 -1 9485 -1 9486 -1 9487 -1 9488 -1 9489 -1 9490 -1 9491 -1 9492 -1 9493 -1 9494 -1 9495 -1 9496 -1 9497 -1 9498 -1 9499 -1 9500 -1 9501 -1 9502 -1 9503 -1 9504 -1 9505 -1 9506 -1 9507 -1 9508 -1 9509 -1 9510 -1 9511 -1 9512 -1 9513 -1 9514 -1 9515 -1 9516 -1 9517 -1 9518 -1 9519 -1 9520 -1 9521 -1 9522 -1 9523 -1 9524 -1 9525 -1 9526 -1 9527 -1 9528 -1 9529 -1 9530 -1 9531 -1 9532 -1 9533 -1 9534 -1 9535 -1 9536 -1 9537 -1 9538 -1 9539 -1 9540 -1 9541 -1 9542 -1 9543 -1 9544 -1 9545 -1 9546 -1 9547 -1 9548 -1 9549 -1 9550 -1 9551 -1 9552 -1 9553 -1 9554 -1 9555 -1 9556 -1 9557 -1 9558 -1 9559 -1 9560 -1 9561 -1 9562 -1 9563 -1 9564 -1 9565 -1 9566 -1 9567 -1 9568 -1 9569 -1 9570 -1 9571 -1 9572 -1 9573 -1 9574 -1 9575 -1 9576 -1 9577 -1 9578 -1 9579 -1 9580 -1 9581 -1 9582 -1 9583 -1 9584 -1 9585 -1 9586 -1 9587 -1 9588 -1 9589 -1 9590 -1 9591 -1 9592 -1 9593 -1 9594 -1 9595 -1 9596 -1 9597 -1 9598 -1 9599 -1 9600 -1 9601 -1 9602 -1 9603 -1 9604 -1 9605 -1 9606 -1 9607 -1 9608 -1 9609 -1 9610 -1 9611 -1 9612 -1 9613 -1 9614 -1 9615 -1 9616 -1 9617 -1 9618 -1 9619 -1 9620 -1 9621 -1 9622 -1 9623 -1 9624 -1 9625 -1 9626 -1 9627 -1 9628 -1 9629 -1 9630 -1 9631 -1 9632 -1 9633 -1 9634 -1 9635 -1 9636 -1 9637 -1 9638 -1 9639 -1 9640 -1 9641 -1 9642 -1 9643 -1 9644 -1 9645 -1 9646 -1 9647 -1 9648 -1 9649 -1 9650 -1 9651 -1 9652 -1 9653 -1 9654 -1 9655 -1 9656 -1 9657 -1 9658 -1 9659 -1 9660 -1 9661 -1 9662 -1 9663 -1 9664 -1 9665 -1 9666 -1 9667 -1 9668 -1 9669 -1 9670 -1 9671 -1 9672 -1 9673 -1 9674 -1 9675 -1 9676 -1 9677 -1 9678 -1 9679 -1 9680 -1 9681 -1 9682 -1 9683 -1 9684 -1 9685 -1 9686 -1 9687 -1 9688 -1 9689 -1 9690 -1 9691 -1 9692 -1 9693 -1 9694 -1 9695 -1 9696 -1 9697 -1 9698 -1 9699 -1 9700 -1 9701 -1 9702 -1 9703 -1 9704 -1 9705 -1 9706 -1 9707 -1 9708 -1 9709 -1 9710 -1 9711 -1 9712 -1 9713 -1 9714 -1 9715 -1 9716 -1 9717 -1 9718 -1 9719 -1 9720 -1 9721 -1 9722 -1 9723 -1 9724 -1 9725 -1 9726 -1 9727 -1 9728 -1 9729 -1 9730 -1 9731 -1 9732 -1 9733 -1 9734 -1 9735 -1 9736 -1 9737 -1 9738 -1 9739 -1 9740 -1 9741 -1 9742 -1 9743 -1 9744 -1 9745 -1 9746 -1 9747 -1 9748 -1 9749 -1 9750 -1 9751 -1 9752 -1 9753 -1 9754 -1 9755 -1 9756 -1 9757 -1 9758 -1 9759 -1 9760 -1 9761 -1 9762 -1 9763 -1 9764 -1 9765 -1 9766 -1 9767 -1 9768 -1 9769 -1 9770 -1 9771 -1 9772 -1 9773 -1 9774 -1 9775 -1 9776 -1 9777 -1 9778 -1 9779 -1 9780 -1 9781 -1 9782 -1 9783 -1 9784 -1 9785 -1 9786 -1 9787 -1 9788 -1 9789 -1 9790 -1 9791 -1 9792 -1 9793 -1 9794 -1 9795 -1 9796 -1 9797 -1 9798 -1 9799 -1 9800 -1 9801 -1 9802 -1 9803 -1 9804 -1 9805 -1 9806 -1 9807 -1 9808 -1 9809 -1 9810 -1 9811 -1 9812 -1 9813 -1 9814 -1 9815 -1 9816 -1 9817 -1 9818 -1 9819 -1 9820 -1 9821 -1 9822 -1 9823 -1 9824 -1 9825 -1 9826 -1 9827 -1 9828 -1 9829 -1 9830 -1 9831 -1 9832 -1 9833 -1 9834 -1 9835 -1 9836 -1 9837 -1 9838 -1 9839 -1 9840 -1 9841 -1 9842 -1 9843 -1 9844 -1 9845 -1 9846 -1 9847 -1 9848 -1 9849 -1 9850 -1 9851 -1 9852 -1 9853 -1 9854 -1 9855 -1 9856 -1 9857 -1 9858 -1 9859 -1 9860 -1 9861 -1 9862 -1 9863 -1 9864 -1 9865 -1 9866 -1 9867 -1 9868 -1 9869 -1 9870 -1 9871 -1 9872 -1 9873 -1 9874 -1 9875 -1 9876 -1 9877 -1 9878 -1 9879 -1 9880 -1 9881 -1 9882 -1 9883 -1 9884 -1 9885 -1 9886 -1 9887 -1 9888 -1 9889 -1 9890 -1 9891 -1 9892 -1 9893 -1 9894 -1 9895 -1 9896 -1 9897 -1 9898 -1 9899 -1 9900 -1 9901 -1 9902 -1 9903 -1 9904 -1 9905 -1 9906 -1 9907 -1 9908 -1 9909 -1 9910 -1 9911 -1 9912 -1 9913 -1 9914 -1 9915 -1 9916 -1 9917 -1 9918 -1 9919 -1 9920 -1 9921 -1 9922 -1 9923 -1 9924 -1 9925 -1 9926 -1 9927 -1 9928 -1 9929 -1 9930 -1 9931 -1 9932 -1 9933 -1 9934 -1 9935 -1 9936 -1 9937 -1 9938 -1 9939 -1 9940 -1 9941 -1 9942 -1 9943 -1 9944 -1 9945 -1 9946 -1 9947 -1 9948 -1 9949 -1 9950 -1 9951 -1 9952 -1 9953 -1 9954 -1 9955 -1 9956 -1 9957 -1 9958 -1 9959 -1 9960 -1 9961 -1 9962 -1 9963 -1 9964 -1 9965 -1 9966 -1 9967 -1 9968 -1 9969 -1 9970 -1 9971 -1 9972 -1 9973 -1 9974 -1 9975 -1 9976 -1 9977 -1 9978 -1 9979 -1 9980 -1 9981 -1 9982 -1 9983 -1 9984 -1 9985 -1 9986 -1 9987 -1 9988 -1 9989 -1 9990 -1 9991 -1 9992 -1 9993 -1 9994 -1 9995 -1 9996 -1 9997 -1 9998 -1 9999 -1 10000 -1 10001 -1 10002 -1 10003 -1 10004 -1 10005 -1 10006 -1 10007 -1 10008 -1 10009 -1 10010 -1 10011 -1 10012 -1 10013 -1 10014 -1 10015 -1 10016 -1 10017 -1 10018 -1 10019 -1 10020 -1 10021 -1 10022 -1 10023 -1 10024 -1 10025 -1 10026 -1 10027 -1 10028 -1 10029 -1 10030 -1 10031 -1 10032 -1 10033 -1 10034 -1 10035 -1 10036 -1 10037 -1 10038 -1 10039 -1 10040 -1 10041 -1 10042 -1 10043 -1 10044 -1 10045 -1 10046 -1 10047 -1 10048 -1 10049 -1 10050 -1 10051 -1 10052 -1 10053 -1 10054 -1 10055 -1 10056 -1 10057 -1 10058 -1 10059 -1 10060 -1 10061 -1 10062 -1 10063 -1 10064 -1 10065 -1 10066 -1 10067 -1 10068 -1 10069 -1 10070 -1 10071 -1 10072 -1 10073 -1 10074 -1 10075 -1 10076 -1 10077 -1 10078 -1 10079 -1 10080 -1 10081 -1 10082 -1 10083 -1 10084 -1 10085 -1 10086 -1 10087 -1 10088 -1 10089 -1 10090 -1 10091 -1 10092 -1 10093 -1 10094 -1 10095 -1 10096 -1 10097 -1 10098 -1 10099 -1 10100 -1 10101 -1 10102 -1 10103 -1 10104 -1 10105 -1 10106 -1 10107 -1 10108 -1 10109 -1 10110 -1 10111 -1 10112 -1 10113 -1 10114 -1 10115 -1 10116 -1 10117 -1 10118 -1 10119 -1 10120 -1 10121 -1 10122 -1 10123 -1 10124 -1 10125 -1 10126 -1 10127 -1 10128 -1 10129 -1 10130 -1 10131 -1 10132 -1 10133 -1 10134 -1 10135 -1 10136 -1 10137 -1 10138 -1 10139 -1 10140 -1 10141 -1 10142 -1 10143 -1 10144 -1 10145 -1 10146 -1 10147 -1 10148 -1 10149 -1 10150 -1 10151 -1 10152 -1 10153 -1 10154 -1 10155 -1 10156 -1 10157 -1 10158 -1 10159 -1 10160 -1 10161 -1 10162 -1 10163 -1 10164 -1 10165 -1 10166 -1 10167 -1 10168 -1 10169 -1 10170 -1 10171 -1 10172 -1 10173 -1 10174 -1 10175 -1 10176 -1 10177 -1 10178 -1 10179 -1 10180 -1 10181 -1 10182 -1 10183 -1 10184 -1 10185 -1 10186 -1 10187 -1 10188 -1 10189 -1 10190 -1 10191 -1 10192 -1 10193 -1 10194 -1 10195 -1 10196 -1 10197 -1 10198 -1 10199 -1 10200 -1 10201 -1 10202 -1 10203 -1 10204 -1 10205 -1 10206 -1 10207 -1 10208 -1 10209 -1 10210 -1 10211 -1 10212 -1 10213 -1 10214 -1 10215 -1 10216 -1 10217 -1 10218 -1 10219 -1 10220 -1 10221 -1 10222 -1 10223 -1 10224 -1 10225 -1 10226 -1 10227 -1 10228 -1 10229 -1 10230 -1 10231 -1 10232 -1 10233 -1 10234 -1 10235 -1 10236 -1 10237 -1 10238 -1 10239 -1 10240 -1 10241 -1 10242 -1 10243 -1 10244 -1 10245 -1 10246 -1 10247 -1 10248 -1 10249 -1 10250 -1 10251 -1 10252 -1 10253 -1 10254 -1 10255 -1 10256 -1 10257 -1 10258 -1 10259 -1 10260 -1 10261 -1 10262 -1 10263 -1 10264 -1 10265 -1 10266 -1 10267 -1 10268 -1 10269 -1 10270 -1 10271 -1 10272 -1 10273 -1 10274 -1 10275 -1 10276 -1 10277 -1 10278 -1 10279 -1 10280 -1 10281 -1 10282 -1 10283 -1 10284 -1 10285 -1 10286 -1 10287 -1 10288 -1 10289 -1 10290 -1 10291 -1 10292 -1 10293 -1 10294 -1 10295 -1 10296 -1 10297 -1 10298 -1 10299 -1 10300 -1 10301 -1 10302 -1 10303 -1 10304 -1 10305 -1 10306 -1 10307 -1 10308 -1 10309 -1 10310 -1 10311 -1 10312 -1 10313 -1 10314 -1 10315 -1 10316 -1 10317 -1 10318 -1 10319 -1 10320 -1 10321 -1 10322 -1 10323 -1 10324 -1 10325 -1 10326 -1 10327 -1 10328 -1 10329 -1 10330 -1 10331 -1 10332 -1 10333 -1 10334 -1 10335 -1 10336 -1 10337 -1 10338 -1 10339 -1 10340 -1 10341 -1 10342 -1 10343 -1 10344 -1 10345 -1 10346 -1 10347 -1 10348 -1 10349 -1 10350 -1 10351 -1 10352 -1 10353 -1 10354 -1 10355 -1 10356 -1 10357 -1 10358 -1 10359 -1 10360 -1 10361 -1 10362 -1 10363 -1 10364 -1 10365 -1 10366 -1 10367 -1 10368 -1 10369 -1 10370 -1 10371 -1 10372 -1 10373 -1 10374 -1 10375 -1 10376 -1 10377 -1 10378 -1 10379 -1 10380 -1 10381 -1 10382 -1 10383 -1 10384 -1 10385 -1 10386 -1 10387 -1 10388 -1 10389 -1 10390 -1 10391 -1 10392 -1 10393 -1 10394 -1 10395 -1 10396 -1 10397 -1 10398 -1 10399 -1 10400 -1 10401 -1 10402 -1 10403 -1 10404 -1 10405 -1 10406 -1 10407 -1 10408 -1 10409 -1 10410 -1 10411 -1 10412 -1 10413 -1 10414 -1 10415 -1 10416 -1 10417 -1 10418 -1 10419 -1 10420 -1 10421 -1 10422 -1 10423 -1 10424 -1 10425 -1 10426 -1 10427 -1 10428 -1 10429 -1 10430 -1 10431 -1 10432 -1 10433 -1 10434 -1 10435 -1 10436 -1 10437 -1 10438 -1 10439 -1 10440 -1 10441 -1 10442 -1 10443 -1 10444 -1 10445 -1 10446 -1 10447 -1 10448 -1 10449 -1 10450 -1 10451 -1 10452 -1 10453 -1 10454 -1 10455 -1 10456 -1 10457 -1 10458 -1 10459 -1 10460 -1 10461 -1 10462 -1 10463 -1 10464 -1 10465 -1 10466 -1 10467 -1 10468 -1 10469 -1 10470 -1 10471 -1 10472 -1 10473 -1 10474 -1 10475 -1 10476 -1 10477 -1 10478 -1 10479 -1 10480 -1 10481 -1 10482 -1 10483 -1 10484 -1 10485 -1 10486 -1 10487 -1 10488 -1 10489 -1 10490 -1 10491 -1 10492 -1 10493 -1 10494 -1 10495 -1 10496 -1 10497 -1 10498 -1 10499 -1 10500 -1 10501 -1 10502 -1 10503 -1 10504 -1 10505 -1 10506 -1 10507 -1 10508 -1 10509 -1 10510 -1 10511 -1 10512 -1 10513 -1 10514 -1 10515 -1 10516 -1 10517 -1 10518 -1 10519 -1 10520 -1 10521 -1 10522 -1 10523 -1 10524 -1 10525 -1 10526 -1 10527 -1 10528 -1 10529 -1 10530 -1 10531 -1 10532 -1 10533 -1 10534 -1 10535 -1 10536 -1 10537 -1 10538 -1 10539 -1 10540 -1 10541 -1 10542 -1 10543 -1 10544 -1 10545 -1 10546 -1 10547 -1 10548 -1 10549 -1 10550 -1 10551 -1 10552 -1 10553 -1 10554 -1 10555 -1 10556 -1 10557 -1 10558 -1 10559 -1 10560 -1 10561 -1 10562 -1 10563 -1 10564 -1 10565 -1 10566 -1 10567 -1 10568 -1 10569 -1 10570 -1 10571 -1 10572 -1 10573 -1 10574 -1 10575 -1 10576 -1 10577 -1 10578 -1 10579 -1 10580 -1 10581 -1 10582 -1 10583 -1 10584 -1 10585 -1 10586 -1 10587 -1 10588 -1 10589 -1 10590 -1 10591 -1 10592 -1 10593 -1 10594 -1 10595 -1 10596 -1 10597 -1 10598 -1 10599 -1 10600 -1 10601 -1 10602 -1 10603 -1 10604 -1 10605 -1 10606 -1 10607 -1 10608 -1 10609 -1 10610 -1 10611 -1 10612 -1 10613 -1 10614 -1 10615 -1 10616 -1 10617 -1 10618 -1 10619 -1 10620 -1 10621 -1 10622 -1 10623 -1 10624 -1 10625 -1 10626 -1 10627 -1 10628 -1 10629 -1 10630 -1 10631 -1 10632 -1 10633 -1 10634 -1 10635 -1 10636 -1 10637 -1 10638 -1 10639 -1 10640 -1 10641 -1 10642 -1 10643 -1 10644 -1 10645 -1 10646 -1 10647 -1 10648 -1 10649 -1 10650 -1 10651 -1 10652 -1 10653 -1 10654 -1 10655 -1 10656 -1 10657 -1 10658 -1 10659 -1 10660 -1 10661 -1 10662 -1 10663 -1 10664 -1 10665 -1 10666 -1 10667 -1 10668 -1 10669 -1 10670 -1 10671 -1 10672 -1 10673 -1 10674 -1 10675 -1 10676 -1 10677 -1 10678 -1 10679 -1 10680 -1 10681 -1 10682 -1 10683 -1 10684 -1 10685 -1 10686 -1 10687 -1 10688 -1 10689 -1 10690 -1 10691 -1 10692 -1 10693 -1 10694 -1 10695 -1 10696 -1 10697 -1 10698 -1 10699 -1 10700 -1 10701 -1 10702 -1 10703 -1 10704 -1 10705 -1 10706 -1 10707 -1 10708 -1 10709 -1 10710 -1 10711 -1 10712 -1 10713 -1 10714 -1 10715 -1 10716 -1 10717 -1 10718 -1 10719 -1 10720 -1 10721 -1 10722 -1 10723 -1 10724 -1 10725 -1 10726 -1 10727 -1 10728 -1 10729 -1 10730 -1 10731 -1 10732 -1 10733 -1 10734 -1 10735 -1 10736 -1 10737 -1 10738 -1 10739 -1 10740 -1 10741 -1 10742 -1 10743 -1 10744 -1 10745 -1 10746 -1 10747 -1 10748 -1 10749 -1 10750 -1 10751 -1 10752 -1 10753 -1 10754 -1 10755 -1 10756 -1 10757 -1 10758 -1 10759 -1 10760 -1 10761 -1 10762 -1 10763 -1 10764 -1 10765 -1 10766 -1 10767 -1 10768 -1 10769 -1 10770 -1 10771 -1 10772 -1 10773 -1 10774 -1 10775 -1 10776 -1 10777 -1 10778 -1 10779 -1 10780 -1 10781 -1 10782 -1 10783 -1 10784 -1 10785 -1 10786 -1 10787 -1 10788 -1 10789 -1 10790 -1 10791 -1 10792 -1 10793 -1 10794 -1 10795 -1 10796 -1 10797 -1 10798 -1 10799 -1 10800 -1 10801 -1 10802 -1 10803 -1 10804 -1 10805 -1 10806 -1 10807 -1 10808 -1 10809 -1 10810 -1 10811 -1 10812 -1 10813 -1 10814 -1 10815 -1 10816 -1 10817 -1 10818 -1 10819 -1 10820 -1 10821 -1 10822 -1 10823 -1 10824 -1 10825 -1 10826 -1 10827 -1 10828 -1 10829 -1 10830 -1 10831 -1 10832 -1 10833 -1 10834 -1 10835 -1 10836 -1 10837 -1 10838 -1 10839 -1 10840 -1 10841 -1 10842 -1 10843 -1 10844 -1 10845 -1 10846 -1 10847 -1 10848 -1 10849 -1 10850 -1 10851 -1 10852 -1 10853 -1 10854 -1 10855 -1 10856 -1 10857 -1 10858 -1 10859 -1 10860 -1 10861 -1 10862 -1 10863 -1 10864 -1 10865 -1 10866 -1 10867 -1 10868 -1 10869 -1 10870 -1 10871 -1 10872 -1 10873 -1 10874 -1 10875 -1 10876 -1 10877 -1 10878 -1 10879 -1 10880 -1 10881 -1 10882 -1 10883 -1 10884 -1 10885 -1 10886 -1 10887 -1 10888 -1 10889 -1 10890 -1 10891 -1 10892 -1 10893 -1 10894 -1 10895 -1 10896 -1 10897 -1 10898 -1 10899 -1 10900 -1 10901 -1 10902 -1 10903 -1 10904 -1 10905 -1 10906 -1 10907 -1 10908 -1 10909 -1 10910 -1 10911 -1 10912 -1 10913 -1 10914 -1 10915 -1 10916 -1 10917 -1 10918 -1 10919 -1 10920 -1 10921 -1 10922 -1 10923 -1 10924 -1 10925 -1 10926 -1 10927 -1 10928 -1 10929 -1 10930 -1 10931 -1 10932 -1 10933 -1 10934 -1 10935 -1 10936 -1 10937 -1 10938 -1 10939 -1 10940 -1 10941 -1 10942 -1 10943 -1 10944 -1 10945 -1 10946 -1 10947 -1 10948 -1 10949 -1 10950 -1 10951 -1 10952 -1 10953 -1 10954 -1 10955 -1 10956 -1 10957 -1 10958 -1 10959 -1 10960 -1 10961 -1 10962 -1 10963 -1 10964 -1 10965 -1 10966 -1 10967 -1 10968 -1 10969 -1 10970 -1 10971 -1 10972 -1 10973 -1 10974 -1 10975 -1 10976 -1 10977 -1 10978 -1 10979 -1 10980 -1 10981 -1 10982 -1 10983 -1 10984 -1 10985 -1 10986 -1 10987 -1 10988 -1 10989 -1 10990 -1 10991 -1 10992 -1 10993 -1 10994 -1 10995 -1 10996 -1 10997 -1 10998 -1 10999 -1 11000 -1 11001 -1 11002 -1 11003 -1 11004 -1 11005 -1 11006 -1 11007 -1 11008 -1 11009 -1 11010 -1 11011 -1 11012 -1 11013 -1 11014 -1 11015 -1 11016 -1 11017 -1 11018 -1 11019 -1 11020 -1 11021 -1 11022 -1 11023 -1 11024 -1 11025 -1 11026 -1 11027 -1 11028 -1 11029 -1 11030 -1 11031 -1 11032 -1 11033 -1 11034 -1 11035 -1 11036 -1 11037 -1 11038 -1 11039 -1 11040 -1 11041 -1 11042 -1 11043 -1 11044 -1 11045 -1 11046 -1 11047 -1 11048 -1 11049 -1 11050 -1 11051 -1 11052 -1 11053 -1 11054 -1 11055 -1 11056 -1 11057 -1 11058 -1 11059 -1 11060 -1 11061 -1 11062 -1 11063 -1 11064 -1 11065 -1 11066 -1 11067 -1 11068 -1 11069 -1 11070 -1 11071 -1 11072 -1 11073 -1 11074 -1 11075 -1 11076 -1 11077 -1 11078 -1 11079 -1 11080 -1 11081 -1 11082 -1 11083 -1 11084 -1 11085 -1 11086 -1 11087 -1 11088 -1 11089 -1 11090 -1 11091 -1 11092 -1 11093 -1 11094 -1 11095 -1 11096 -1 11097 -1 11098 -1 11099 -1 11100 -1 11101 -1 11102 -1 11103 -1 11104 -1 11105 -1 11106 -1 11107 -1 11108 -1 11109 -1 11110 -1 11111 -1 11112 -1 11113 -1 11114 -1 11115 -1 11116 -1 11117 -1 11118 -1 11119 -1 11120 -1 11121 -1 11122 -1 11123 -1 11124 -1 11125 -1 11126 -1 11127 -1 11128 -1 11129 -1 11130 -1 11131 -1 11132 -1 11133 -1 11134 -1 11135 -1 11136 -1 11137 -1 11138 -1 11139 -1 11140 -1 11141 -1 11142 -1 11143 -1 11144 -1 11145 -1 11146 -1 11147 -1 11148 -1 11149 -1 11150 -1 11151 -1 11152 -1 11153 -1 11154 -1 11155 -1 11156 -1 11157 -1 11158 -1 11159 -1 11160 -1 11161 -1 11162 -1 11163 -1 11164 -1 11165 -1 11166 -1 11167 -1 11168 -1 11169 -1 11170 -1 11171 -1 11172 -1 11173 -1 11174 -1 11175 -1 11176 -1 11177 -1 11178 -1 11179 -1 11180 -1 11181 -1 11182 -1 11183 -1 11184 -1 11185 -1 11186 -1 11187 -1 11188 -1 11189 -1 11190 -1 11191 -1 11192 -1 11193 -1 11194 -1 11195 -1 11196 -1 11197 -1 11198 -1 11199 -1 11200 -1 11201 -1 11202 -1 11203 -1 11204 -1 11205 -1 11206 -1 11207 -1 11208 -1 11209 -1 11210 -1 11211 -1 11212 -1 11213 -1 11214 -1 11215 -1 11216 -1 11217 -1 11218 -1 11219 -1 11220 -1 11221 -1 11222 -1 11223 -1 11224 -1 11225 -1 11226 -1 11227 -1 11228 -1 11229 -1 11230 -1 11231 -1 11232 -1 11233 -1 11234 -1 11235 -1 11236 -1 11237 -1 11238 -1 11239 -1 11240 -1 11241 -1 11242 -1 11243 -1 11244 -1 11245 -1 11246 -1 11247 -1 11248 -1 11249 -1 11250 -1 11251 -1 11252 -1 11253 -1 11254 -1 11255 -1 11256 -1 11257 -1 11258 -1 11259 -1 11260 -1 11261 -1 11262 -1 11263 -1 11264 -1 11265 -1 11266 -1 11267 -1 11268 -1 11269 -1 11270 -1 11271 -1 11272 -1 11273 -1 11274 -1 11275 -1 11276 -1 11277 -1 11278 -1 11279 -1 11280 -1 11281 -1 11282 -1 11283 -1 11284 -1 11285 -1 11286 -1 11287 -1 11288 -1 11289 -1 11290 -1 11291 -1 11292 -1 11293 -1 11294 -1 11295 -1 11296 -1 11297 -1 11298 -1 11299 -1 11300 -1 11301 -1 11302 -1 11303 -1 11304 -1 11305 -1 11306 -1 11307 -1 11308 -1 11309 -1 11310 -1 11311 -1 11312 -1 11313 -1 11314 -1 11315 -1 11316 -1 11317 -1 11318 -1 11319 -1 11320 -1 11321 -1 11322 -1 11323 -1 11324 -1 11325 -1 11326 -1 11327 -1 11328 -1 11329 -1 11330 -1 11331 -1 11332 -1 11333 -1 11334 -1 11335 -1 11336 -1 11337 -1 11338 -1 11339 -1 11340 -1 11341 -1 11342 -1 11343 -1 11344 -1 11345 -1 11346 -1 11347 -1 11348 -1 11349 -1 11350 -1 11351 -1 11352 -1 11353 -1 11354 -1 11355 -1 11356 -1 11357 -1 11358 -1 11359 -1 11360 -1 11361 -1 11362 -1 11363 -1 11364 -1 11365 -1 11366 -1 11367 -1 11368 -1 11369 -1 11370 -1 11371 -1 11372 -1 11373 -1 11374 -1 11375 -1 11376 -1 11377 -1 11378 -1 11379 -1 11380 -1 11381 -1 11382 -1 11383 -1 11384 -1 11385 -1 11386 -1 11387 -1 11388 -1 11389 -1 11390 -1 11391 -1 11392 -1 11393 -1 11394 -1 11395 -1 11396 -1 11397 -1 11398 -1 11399 -1 11400 -1 11401 -1 11402 -1 11403 -1 11404 -1 11405 -1 11406 -1 11407 -1 11408 -1 11409 -1 11410 -1 11411 -1 11412 -1 11413 -1 11414 -1 11415 -1 11416 -1 11417 -1 11418 -1 11419 -1 11420 -1 11421 -1 11422 -1 11423 -1 11424 -1 11425 -1 11426 -1 11427 -1 11428 -1 11429 -1 11430 -1 11431 -1 11432 -1 11433 -1 11434 -1 11435 -1 11436 -1 11437 -1 11438 -1 11439 -1 11440 -1 11441 -1 11442 -1 11443 -1 11444 -1 11445 -1 11446 -1 11447 -1 11448 -1 11449 -1 11450 -1 11451 -1 11452 -1 11453 -1 11454 -1 11455 -1 11456 -1 11457 -1 11458 -1 11459 -1 11460 -1 11461 -1 11462 -1 11463 -1 11464 -1 11465 -1 11466 -1 11467 -1 11468 -1 11469 -1 11470 -1 11471 -1 11472 -1 11473 -1 11474 -1 11475 -1 11476 -1 11477 -1 11478 -1 11479 -1 11480 -1 11481 -1 11482 -1 11483 -1 11484 -1 11485 -1 11486 -1 11487 -1 11488 -1 11489 -1 11490 -1 11491 -1 11492 -1 11493 -1 11494 -1 11495 -1 11496 -1 11497 -1 11498 -1 11499 -1 11500 -1 11501 -1 11502 -1 11503 -1 11504 -1 11505 -1 11506 -1 11507 -1 11508 -1 11509 -1 11510 -1 11511 -1 11512 -1 11513 -1 11514 -1 11515 -1 11516 -1 11517 -1 11518 -1 11519 -1 11520 -1 11521 -1 11522 -1 11523 -1 11524 -1 11525 -1 11526 -1 11527 -1 11528 -1 11529 -1 11530 -1 11531 -1 11532 -1 11533 -1 11534 -1 11535 -1 11536 -1 11537 -1 11538 -1 11539 -1 11540 -1 11541 -1 11542 -1 11543 -1 11544 -1 11545 -1 11546 -1 11547 -1 11548 -1 11549 -1 11550 -1 11551 -1 11552 -1 11553 -1 11554 -1 11555 -1 11556 -1 11557 -1 11558 -1 11559 -1 11560 -1 11561 -1 11562 -1 11563 -1 11564 -1 11565 -1 11566 -1 11567 -1 11568 -1 11569 -1 11570 -1 11571 -1 11572 -1 11573 -1 11574 -1 11575 -1 11576 -1 11577 -1 11578 -1 11579 -1 11580 -1 11581 -1 11582 -1 11583 -1 11584 -1 11585 -1 11586 -1 11587 -1 11588 -1 11589 -1 11590 -1 11591 -1 11592 -1 11593 -1 11594 -1 11595 -1 11596 -1 11597 -1 11598 -1 11599 -1 11600 -1 11601 -1 11602 -1 11603 -1 11604 -1 11605 -1 11606 -1 11607 -1 11608 -1 11609 -1 11610 -1 11611 -1 11612 -1 11613 -1 11614 -1 11615 -1 11616 -1 11617 -1 11618 -1 11619 -1 11620 -1 11621 -1 11622 -1 11623 -1 11624 -1 11625 -1 11626 -1 11627 -1 11628 -1 11629 -1 11630 -1 11631 -1 11632 -1 11633 -1 11634 -1 11635 -1 11636 -1 11637 -1 11638 -1 11639 -1 11640 -1 11641 -1 11642 -1 11643 -1 11644 -1 11645 -1 11646 -1 11647 -1 11648 -1 11649 -1 11650 -1 11651 -1 11652 -1 11653 -1 11654 -1 11655 -1 11656 -1 11657 -1 11658 -1 11659 -1 11660 -1 11661 -1 11662 -1 11663 -1 11664 -1 11665 -1 11666 -1 11667 -1 11668 -1 11669 -1 11670 -1 11671 -1 11672 -1 11673 -1 11674 -1 11675 -1 11676 -1 11677 -1 11678 -1 11679 -1 11680 -1 11681 -1 11682 -1 11683 -1 11684 -1 11685 -1 11686 -1 11687 -1 11688 -1 11689 -1 11690 -1 11691 -1 11692 -1 11693 -1 11694 -1 11695 -1 11696 -1 11697 -1 11698 -1 11699 -1 11700 -1 11701 -1 11702 -1 11703 -1 11704 -1 11705 -1 11706 -1 11707 -1 11708 -1 11709 -1 11710 -1 11711 -1 11712 -1 11713 -1 11714 -1 11715 -1 11716 -1 11717 -1 11718 -1 11719 -1 11720 -1 11721 -1 11722 -1 11723 -1 11724 -1 11725 -1 11726 -1 11727 -1 11728 -1 11729 -1 11730 -1 11731 -1 11732 -1 11733 -1 11734 -1 11735 -1 11736 -1 11737 -1 11738 -1 11739 -1 11740 -1 11741 -1 11742 -1 11743 -1 11744 -1 11745 -1 11746 -1 11747 -1 11748 -1 11749 -1 11750 -1 11751 -1 11752 -1 11753 -1 11754 -1 11755 -1 11756 -1 11757 -1 11758 -1 11759 -1 11760 -1 11761 -1 11762 -1 11763 -1 11764 -1 11765 -1 11766 -1 11767 -1 11768 -1 11769 -1 11770 -1 11771 -1 11772 -1 11773 -1 11774 -1 11775 -1 11776 -1 11777 -1 11778 -1 11779 -1 11780 -1 11781 -1 11782 -1 11783 -1 11784 -1 11785 -1 11786 -1 11787 -1 11788 -1 11789 -1 11790 -1 11791 -1 11792 -1 11793 -1 11794 -1 11795 -1 11796 -1 11797 -1 11798 -1 11799 -1 11800 -1 11801 -1 11802 -1 11803 -1 11804 -1 11805 -1 11806 -1 11807 -1 11808 -1 11809 -1 11810 -1 11811 -1 11812 -1 11813 -1 11814 -1 11815 -1 11816 -1 11817 -1 11818 -1 11819 -1 11820 -1 11821 -1 11822 -1 11823 -1 11824 -1 11825 -1 11826 -1 11827 -1 11828 -1 11829 -1 11830 -1 11831 -1 11832 -1 11833 -1 11834 -1 11835 -1 11836 -1 11837 -1 11838 -1 11839 -1 11840 -1 11841 -1 11842 -1 11843 -1 11844 -1 11845 -1 11846 -1 11847 -1 11848 -1 11849 -1 11850 -1 11851 -1 11852 -1 11853 -1 11854 -1 11855 -1 11856 -1 11857 -1 11858 -1 11859 -1 11860 -1 11861 -1 11862 -1 11863 -1 11864 -1 11865 -1 11866 -1 11867 -1 11868 -1 11869 -1 11870 -1 11871 -1 11872 -1 11873 -1 11874 -1 11875 -1 11876 -1 11877 -1 11878 -1 11879 -1 11880 -1 11881 -1 11882 -1 11883 -1 11884 -1 11885 -1 11886 -1 11887 -1 11888 -1 11889 -1 11890 -1 11891 -1 11892 -1 11893 -1 11894 -1 11895 -1 11896 -1 11897 -1 11898 -1 11899 -1 11900 -1 11901 -1 11902 -1 11903 -1 11904 -1 11905 -1 11906 -1 11907 -1 11908 -1 11909 -1 11910 -1 11911 -1 11912 -1 11913 -1 11914 -1 11915 -1 11916 -1 11917 -1 11918 -1 11919 -1 11920 -1 11921 -1 11922 -1 11923 -1 11924 -1 11925 -1 11926 -1 11927 -1 11928 -1 11929 -1 11930 -1 11931 -1 11932 -1 11933 -1 11934 -1 11935 -1 11936 -1 11937 -1 11938 -1 11939 -1 11940 -1 11941 -1 11942 -1 11943 -1 11944 -1 11945 -1 11946 -1 11947 -1 11948 -1 11949 -1 11950 -1 11951 -1 11952 -1 11953 -1 11954 -1 11955 -1 11956 -1 11957 -1 11958 -1 11959 -1 11960 -1 11961 -1 11962 -1 11963 -1 11964 -1 11965 -1 11966 -1 11967 -1 11968 -1 11969 -1 11970 -1 11971 -1 11972 -1 11973 -1 11974 -1 11975 -1 11976 -1 11977 -1 11978 -1 11979 -1 11980 -1 11981 -1 11982 -1 11983 -1 11984 -1 11985 -1 11986 -1 11987 -1 11988 -1 11989 -1 11990 -1 11991 -1 11992 -1 11993 -1 11994 -1 11995 -1 11996 -1 11997 -1 11998 -1 11999 -1 12000 -1 12001 -1 12002 -1 12003 -1 12004 -1 12005 -1 12006 -1 12007 -1 12008 -1 12009 -1 12010 -1 12011 -1 12012 -1 12013 -1 12014 -1 12015 -1 12016 -1 12017 -1 12018 -1 12019 -1 12020 -1 12021 -1 12022 -1 12023 -1 12024 -1 12025 -1 12026 -1 12027 -1 12028 -1 12029 -1 12030 -1 12031 -1 12032 -1 12033 -1 12034 -1 12035 -1 12036 -1 12037 -1 12038 -1 12039 -1 12040 -1 12041 -1 12042 -1 12043 -1 12044 -1 12045 -1 12046 -1 12047 -1 12048 -1 12049 -1 12050 -1 12051 -1 12052 -1 12053 -1 12054 -1 12055 -1 12056 -1 12057 -1 12058 -1 12059 -1 12060 -1 12061 -1 12062 -1 12063 -1 12064 -1 12065 -1 12066 -1 12067 -1 12068 -1 12069 -1 12070 -1 12071 -1 12072 -1 12073 -1 12074 -1 12075 -1 12076 -1 12077 -1 12078 -1 12079 -1 12080 -1 12081 -1 12082 -1 12083 -1 12084 -1 12085 -1 12086 -1 12087 -1 12088 -1 12089 -1 12090 -1 12091 -1 12092 -1 12093 -1 12094 -1 12095 -1 12096 -1 12097 -1 12098 -1 12099 -1 12100 -1 12101 -1 12102 -1 12103 -1 12104 -1 12105 -1 12106 -1 12107 -1 12108 -1 12109 -1 12110 -1 12111 -1 12112 -1 12113 -1 12114 -1 12115 -1 12116 -1 12117 -1 12118 -1 12119 -1 12120 -1 12121 -1 12122 -1 12123 -1 12124 -1 12125 -1 12126 -1 12127 -1 12128 -1 12129 -1 12130 -1 12131 -1 12132 -1 12133 -1 12134 -1 12135 -1 12136 -1 12137 -1 12138 -1 12139 -1 12140 -1 12141 -1 12142 -1 12143 -1 12144 -1 12145 -1 12146 -1 12147 -1 12148 -1 12149 -1 12150 -1 12151 -1 12152 -1 12153 -1 12154 -1 12155 -1 12156 -1 12157 -1 12158 -1 12159 -1 12160 -1 12161 -1 12162 -1 12163 -1 12164 -1 12165 -1 12166 -1 12167 -1 12168 -1 12169 -1 12170 -1 12171 -1 12172 -1 12173 -1 12174 -1 12175 -1 12176 -1 12177 -1 12178 -1 12179 -1 12180 -1 12181 -1 12182 -1 12183 -1 12184 -1 12185 -1 12186 -1 12187 -1 12188 -1 12189 -1 12190 -1 12191 -1 12192 -1 12193 -1 12194 -1 12195 -1 12196 -1 12197 -1 12198 -1 12199 -1 12200 -1 12201 -1 12202 -1 12203 -1 12204 -1 12205 -1 12206 -1 12207 -1 12208 -1 12209 -1 12210 -1 12211 -1 12212 -1 12213 -1 12214 -1 12215 -1 12216 -1 12217 -1 12218 -1 12219 -1 12220 -1 12221 -1 12222 -1 12223 -1 12224 -1 12225 -1 12226 -1 12227 -1 12228 -1 12229 -1 12230 -1 12231 -1 12232 -1 12233 -1 12234 -1 12235 -1 12236 -1 12237 -1 12238 -1 12239 -1 12240 -1 12241 -1 12242 -1 12243 -1 12244 -1 12245 -1 12246 -1 12247 -1 12248 -1 12249 -1 12250 -1 12251 -1 12252 -1 12253 -1 12254 -1 12255 -1 12256 -1 12257 -1 12258 -1 12259 -1 12260 -1 12261 -1 12262 -1 12263 -1 12264 -1 12265 -1 12266 -1 12267 -1 12268 -1 12269 -1 12270 -1 12271 -1 12272 -1 12273 -1 12274 -1 12275 -1 12276 -1 12277 -1 12278 -1 12279 -1 12280 -1 12281 -1 12282 -1 12283 -1 12284 -1 12285 -1 12286 -1 12287 -1 12288 -1 12289 -1 12290 -1 12291 -1 12292 -1 12293 -1 12294 -1 12295 -1 12296 -1 12297 -1 12298 -1 12299 -1 12300 -1 12301 -1 12302 -1 12303 -1 12304 -1 12305 -1 12306 -1 12307 -1 12308 -1 12309 -1 12310 -1 12311 -1 12312 -1 12313 -1 12314 -1 12315 -1 12316 -1 12317 -1 12318 -1 12319 -1 12320 -1 12321 -1 12322 -1 12323 -1 12324 -1 12325 -1 12326 -1 12327 -1 12328 -1 12329 -1 12330 -1 12331 -1 12332 -1 12333 -1 12334 -1 12335 -1 12336 -1 12337 -1 12338 -1 12339 -1 12340 -1 12341 -1 12342 -1 12343 -1 12344 -1 12345 -1 12346 -1 12347 -1 12348 -1 12349 -1 12350 -1 12351 -1 12352 -1 12353 -1 12354 -1 12355 -1 12356 -1 12357 -1 12358 -1 12359 -1 12360 -1 12361 -1 12362 -1 12363 -1 12364 -1 12365 -1 12366 -1 12367 -1 12368 -1 12369 -1 12370 -1 12371 -1 12372 -1 12373 -1 12374 -1 12375 -1 12376 -1 12377 -1 12378 -1 12379 -1 12380 -1 12381 -1 12382 -1 12383 -1 12384 -1 12385 -1 12386 -1 12387 -1 12388 -1 12389 -1 12390 -1 12391 -1 12392 -1 12393 -1 12394 -1 12395 -1 12396 -1 12397 -1 12398 -1 12399 -1 12400 -1 12401 -1 12402 -1 12403 -1 12404 -1 12405 -1 12406 -1 12407 -1 12408 -1 12409 -1 12410 -1 12411 -1 12412 -1 12413 -1 12414 -1 12415 -1 12416 -1 12417 -1 12418 -1 12419 -1 12420 -1 12421 -1 12422 -1 12423 -1 12424 -1 12425 -1 12426 -1 12427 -1 12428 -1 12429 -1 12430 -1 12431 -1 12432 -1 12433 -1 12434 -1 12435 -1 12436 -1 12437 -1 12438 -1 12439 -1 12440 -1 12441 -1 12442 -1 12443 -1 12444 -1 12445 -1 12446 -1 12447 -1 12448 -1 12449 -1 12450 -1 12451 -1 12452 -1 12453 -1 12454 -1 12455 -1 12456 -1 12457 -1 12458 -1 12459 -1 12460 -1 12461 -1 12462 -1 12463 -1 12464 -1 12465 -1 12466 -1 12467 -1 12468 -1 12469 -1 12470 -1 12471 -1 12472 -1 12473 -1 12474 -1 12475 -1 12476 -1 12477 -1 12478 -1 12479 -1 12480 -1 12481 -1 12482 -1 12483 -1 12484 -1 12485 -1 12486 -1 12487 -1 12488 -1 12489 -1 12490 -1 12491 -1 12492 -1 12493 -1 12494 -1 12495 -1 12496 -1 12497 -1 12498 -1 12499 -1 12500 -1 12501 -1 12502 -1 12503 -1 12504 -1 12505 -1 12506 -1 12507 -1 12508 -1 12509 -1 12510 -1 12511 -1 12512 -1 12513 -1 12514 -1 12515 -1 12516 -1 12517 -1 12518 -1 12519 -1 12520 -1 12521 -1 12522 -1 12523 -1 12524 -1 12525 -1 12526 -1 12527 -1 12528 -1 12529 -1 12530 -1 12531 -1 12532 -1 12533 -1 12534 -1 12535 -1 12536 -1 12537 -1 12538 -1 12539 -1 12540 -1 12541 -1 12542 -1 12543 -1 12544 -1 12545 -1 12546 -1 12547 -1 12548 -1 12549 -1 12550 -1 12551 -1 12552 -1 12553 -1 12554 -1 12555 -1 12556 -1 12557 -1 12558 -1 12559 -1 12560 -1 12561 -1 12562 -1 12563 -1 12564 -1 12565 -1 12566 -1 12567 -1 12568 -1 12569 -1 12570 -1 12571 -1 12572 -1 12573 -1 12574 -1 12575 -1 12576 -1 12577 -1 12578 -1 12579 -1 12580 -1 12581 -1 12582 -1 12583 -1 12584 -1 12585 -1 12586 -1 12587 -1 12588 -1 12589 -1 12590 -1 12591 -1 12592 -1 12593 -1 12594 -1 12595 -1 12596 -1 12597 -1 12598 -1 12599 -1 12600 -1 12601 -1 12602 -1 12603 -1 12604 -1 12605 -1 12606 -1 12607 -1 12608 -1 12609 -1 12610 -1 12611 -1 12612 -1 12613 -1 12614 -1 12615 -1 12616 -1 12617 -1 12618 -1 12619 -1 12620 -1 12621 -1 12622 -1 12623 -1 12624 -1 12625 -1 12626 -1 12627 -1 12628 -1 12629 -1 12630 -1 12631 -1 12632 -1 12633 -1 12634 -1 12635 -1 12636 -1 12637 -1 12638 -1 12639 -1 12640 -1 12641 -1 12642 -1 12643 -1 12644 -1 12645 -1 12646 -1 12647 -1 12648 -1 12649 -1 12650 -1 12651 -1 12652 -1 12653 -1 12654 -1 12655 -1 12656 -1 12657 -1 12658 -1 12659 -1 12660 -1 12661 -1 12662 -1 12663 -1 12664 -1 12665 -1 12666 -1 12667 -1 12668 -1 12669 -1 12670 -1 12671 -1 12672 -1 12673 -1 12674 -1 12675 -1 12676 -1 12677 -1 12678 -1 12679 -1 12680 -1 12681 -1 12682 -1 12683 -1 12684 -1 12685 -1 12686 -1 12687 -1 12688 -1 12689 -1 12690 -1 12691 -1 12692 -1 12693 -1 12694 -1 12695 -1 12696 -1 12697 -1 12698 -1 12699 -1 12700 -1 12701 -1 12702 -1 12703 -1 12704 -1 12705 -1 12706 -1 12707 -1 12708 -1 12709 -1 12710 -1 12711 -1 12712 -1 12713 -1 12714 -1 12715 -1 12716 -1 12717 -1 12718 -1 12719 -1 12720 -1 12721 -1 12722 -1 12723 -1 12724 -1 12725 -1 12726 -1 12727 -1 12728 -1 12729 -1 12730 -1 12731 -1 12732 -1 12733 -1 12734 -1 12735 -1 12736 -1 12737 -1 12738 -1 12739 -1 12740 -1 12741 -1 12742 -1 12743 -1 12744 -1 12745 -1 12746 -1 12747 -1 12748 -1 12749 -1 12750 -1 12751 -1 12752 -1 12753 -1 12754 -1 12755 -1 12756 -1 12757 -1 12758 -1 12759 -1 12760 -1 12761 -1 12762 -1 12763 -1 12764 -1 12765 -1 12766 -1 12767 -1 12768 -1 12769 -1 12770 -1 12771 -1 12772 -1 12773 -1 12774 -1 12775 -1 12776 -1 12777 -1 12778 -1 12779 -1 12780 -1 12781 -1 12782 -1 12783 -1 12784 -1 12785 -1 12786 -1 12787 -1 12788 -1 12789 -1 12790 -1 12791 -1 12792 -1 12793 -1 12794 -1 12795 -1 12796 -1 12797 -1 12798 -1 12799 -1 12800 -1 12801 -1 12802 -1 12803 -1 12804 -1 12805 -1 12806 -1 12807 -1 12808 -1 12809 -1 12810 -1 12811 -1 12812 -1 12813 -1 12814 -1 12815 -1 12816 -1 12817 -1 12818 -1 12819 -1 12820 -1 12821 -1 12822 -1 12823 -1 12824 -1 12825 -1 12826 -1 12827 -1 12828 -1 12829 -1 12830 -1 12831 -1 12832 -1 12833 -1 12834 -1 12835 -1 12836 -1 12837 -1 12838 -1 12839 -1 12840 -1 12841 -1 12842 -1 12843 -1 12844 -1 12845 -1 12846 -1 12847 -1 12848 -1 12849 -1 12850 -1 12851 -1 12852 -1 12853 -1 12854 -1 12855 -1 12856 -1 12857 -1 12858 -1 12859 -1 12860 -1 12861 -1 12862 -1 12863 -1 12864 -1 12865 -1 12866 -1 12867 -1 12868 -1 12869 -1 12870 -1 12871 -1 12872 -1 12873 -1 12874 -1 12875 -1 12876 -1 12877 -1 12878 -1 12879 -1 12880 -1 12881 -1 12882 -1 12883 -1 12884 -1 12885 -1 12886 -1 12887 -1 12888 -1 12889 -1 12890 -1 12891 -1 12892 -1 12893 -1 12894 -1 12895 -1 12896 -1 12897 -1 12898 -1 12899 -1 12900 -1 12901 -1 12902 -1 12903 -1 12904 -1 12905 -1 12906 -1 12907 -1 12908 -1 12909 -1 12910 -1 12911 -1 12912 -1 12913 -1 12914 -1 12915 -1 12916 -1 12917 -1 12918 -1 12919 -1 12920 -1 12921 -1 12922 -1 12923 -1 12924 -1 12925 -1 12926 -1 12927 -1 12928 -1 12929 -1 12930 -1 12931 -1 12932 -1 12933 -1 12934 -1 12935 -1 12936 -1 12937 -1 12938 -1 12939 -1 12940 -1 12941 -1 12942 -1 12943 -1 12944 -1 12945 -1 12946 -1 12947 -1 12948 -1 12949 -1 12950 -1 12951 -1 12952 -1 12953 -1 12954 -1 12955 -1 12956 -1 12957 -1 12958 -1 12959 -1 12960 -1 12961 -1 12962 -1 12963 -1 12964 -1 12965 -1 12966 -1 12967 -1 12968 -1 12969 -1 12970 -1 12971 -1 12972 -1 12973 -1 12974 -1 12975 -1 12976 -1 12977 -1 12978 -1 12979 -1 12980 -1 12981 -1 12982 -1 12983 -1 12984 -1 12985 -1 12986 -1 12987 -1 12988 -1 12989 -1 12990 -1 12991 -1 12992 -1 12993 -1 12994 -1 12995 -1 12996 -1 12997 -1 12998 -1 12999 -1 13000 -1 13001 -1 13002 -1 13003 -1 13004 -1 13005 -1 13006 -1 13007 -1 13008 -1 13009 -1 13010 -1 13011 -1 13012 -1 13013 -1 13014 -1 13015 -1 13016 -1 13017 -1 13018 -1 13019 -1 13020 -1 13021 -1 13022 -1 13023 -1 13024 -1 13025 -1 13026 -1 13027 -1 13028 -1 13029 -1 13030 -1 13031 -1 13032 -1 13033 -1 13034 -1 13035 -1 13036 -1 13037 -1 13038 -1 13039 -1 13040 -1 13041 -1 13042 -1 13043 -1 13044 -1 13045 -1 13046 -1 13047 -1 13048 -1 13049 -1 13050 -1 13051 -1 13052 -1 13053 -1 13054 -1 13055 -1 13056 -1 13057 -1 13058 -1 13059 -1 13060 -1 13061 -1 13062 -1 13063 -1 13064 -1 13065 -1 13066 -1 13067 -1 13068 -1 13069 -1 13070 -1 13071 -1 13072 -1 13073 -1 13074 -1 13075 -1 13076 -1 13077 -1 13078 -1 13079 -1 13080 -1 13081 -1 13082 -1 13083 -1 13084 -1 13085 -1 13086 -1 13087 -1 13088 -1 13089 -1 13090 -1 13091 -1 13092 -1 13093 -1 13094 -1 13095 -1 13096 -1 13097 -1 13098 -1 13099 -1 13100 -1 13101 -1 13102 -1 13103 -1 13104 -1 13105 -1 13106 -1 13107 -1 13108 -1 13109 -1 13110 -1 13111 -1 13112 -1 13113 -1 13114 -1 13115 -1 13116 -1 13117 -1 13118 -1 13119 -1 13120 -1 13121 -1 13122 -1 13123 -1 13124 -1 13125 -1 13126 -1 13127 -1 13128 -1 13129 -1 13130 -1 13131 -1 13132 -1 13133 -1 13134 -1 13135 -1 13136 -1 13137 -1 13138 -1 13139 -1 13140 -1 13141 -1 13142 -1 13143 -1 13144 -1 13145 -1 13146 -1 13147 -1 13148 -1 13149 -1 13150 -1 13151 -1 13152 -1 13153 -1 13154 -1 13155 -1 13156 -1 13157 -1 13158 -1 13159 -1 13160 -1 13161 -1 13162 -1 13163 -1 13164 -1 13165 -1 13166 -1 13167 -1 13168 -1 13169 -1 13170 -1 13171 -1 13172 -1 13173 -1 13174 -1 13175 -1 13176 -1 13177 -1 13178 -1 13179 -1 13180 -1 13181 -1 13182 -1 13183 -1 13184 -1 13185 -1 13186 -1 13187 -1 13188 -1 13189 -1 13190 -1 13191 -1 13192 -1 13193 -1 13194 -1 13195 -1 13196 -1 13197 -1 13198 -1 13199 -1 13200 -1 13201 -1 13202 -1 13203 -1 13204 -1 13205 -1 13206 -1 13207 -1 13208 -1 13209 -1 13210 -1 13211 -1 13212 -1 13213 -1 13214 -1 13215 -1 13216 -1 13217 -1 13218 -1 13219 -1 13220 -1 13221 -1 13222 -1 13223 -1 13224 -1 13225 -1 13226 -1 13227 -1 13228 -1 13229 -1 13230 -1 13231 -1 13232 -1 13233 -1 13234 -1 13235 -1 13236 -1 13237 -1 13238 -1 13239 -1 13240 -1 13241 -1 13242 -1 13243 -1 13244 -1 13245 -1 13246 -1 13247 -1 13248 -1 13249 -1 13250 -1 13251 -1 13252 -1 13253 -1 13254 -1 13255 -1 13256 -1 13257 -1 13258 -1 13259 -1 13260 -1 13261 -1 13262 -1 13263 -1 13264 -1 13265 -1 13266 -1 13267 -1 13268 -1 13269 -1 13270 -1 13271 -1 13272 -1 13273 -1 13274 -1 13275 -1 13276 -1 13277 -1 13278 -1 13279 -1 13280 -1 13281 -1 13282 -1 13283 -1 13284 -1 13285 -1 13286 -1 13287 -1 13288 -1 13289 -1 13290 -1 13291 -1 13292 -1 13293 -1 13294 -1 13295 -1 13296 -1 13297 -1 13298 -1 13299 -1 13300 -1 13301 -1 13302 -1 13303 -1 13304 -1 13305 -1 13306 -1 13307 -1 13308 -1 13309 -1 13310 -1 13311 -1 13312 -1 13313 -1 13314 -1 13315 -1 13316 -1 13317 -1 13318 -1 13319 -1 13320 -1 13321 -1 13322 -1 13323 -1 13324 -1 13325 -1 13326 -1 13327 -1 13328 -1 13329 -1 13330 -1 13331 -1 13332 -1 13333 -1 13334 -1 13335 -1 13336 -1 13337 -1 13338 -1 13339 -1 13340 -1 13341 -1 13342 -1 13343 -1 13344 -1 13345 -1 13346 -1 13347 -1 13348 -1 13349 -1 13350 -1 13351 -1 13352 -1 13353 -1 13354 -1 13355 -1 13356 -1 13357 -1 13358 -1 13359 -1 13360 -1 13361 -1 13362 -1 13363 -1 13364 -1 13365 -1 13366 -1 13367 -1 13368 -1 13369 -1 13370 -1 13371 -1 13372 -1 13373 -1 13374 -1 13375 -1 13376 -1 13377 -1 13378 -1 13379 -1 13380 -1 13381 -1 13382 -1 13383 -1 13384 -1 13385 -1 13386 -1 13387 -1 13388 -1 13389 -1 13390 -1 13391 -1 13392 -1 13393 -1 13394 -1 13395 -1 13396 -1 13397 -1 13398 -1 13399 -1 13400 -1 13401 -1 13402 -1 13403 -1 13404 -1 13405 -1 13406 -1 13407 -1 13408 -1 13409 -1 13410 -1 13411 -1 13412 -1 13413 -1 13414 -1 13415 -1 13416 -1 13417 -1 13418 -1 13419 -1 13420 -1 13421 -1 13422 -1 13423 -1 13424 -1 13425 -1 13426 -1 13427 -1 13428 -1 13429 -1 13430 -1 13431 -1 13432 -1 13433 -1 13434 -1 13435 -1 13436 -1 13437 -1 13438 -1 13439 -1 13440 -1 13441 -1 13442 -1 13443 -1 13444 -1 13445 -1 13446 -1 13447 -1 13448 -1 13449 -1 13450 -1 13451 -1 13452 -1 13453 -1 13454 -1 13455 -1 13456 -1 13457 -1 13458 -1 13459 -1 13460 -1 13461 -1 13462 -1 13463 -1 13464 -1 13465 -1 13466 -1 13467 -1 13468 -1 13469 -1 13470 -1 13471 -1 13472 -1 13473 -1 13474 -1 13475 -1 13476 -1 13477 -1 13478 -1 13479 -1 13480 -1 13481 -1 13482 -1 13483 -1 13484 -1 13485 -1 13486 -1 13487 -1 13488 -1 13489 -1 13490 -1 13491 -1 13492 -1 13493 -1 13494 -1 13495 -1 13496 -1 13497 -1 13498 -1 13499 -1 13500 -1 13501 -1 13502 -1 13503 -1 13504 -1 13505 -1 13506 -1 13507 -1 13508 -1 13509 -1 13510 -1 13511 -1 13512 -1 13513 -1 13514 -1 13515 -1 13516 -1 13517 -1 13518 -1 13519 -1 13520 -1 13521 -1 13522 -1 13523 -1 13524 -1 13525 -1 13526 -1 13527 -1 13528 -1 13529 -1 13530 -1 13531 -1 13532 -1 13533 -1 13534 -1 13535 -1 13536 -1 13537 -1 13538 -1 13539 -1 13540 -1 13541 -1 13542 -1 13543 -1 13544 -1 13545 -1 13546 -1 13547 -1 13548 -1 13549 -1 13550 -1 13551 -1 13552 -1 13553 -1 13554 -1 13555 -1 13556 -1 13557 -1 13558 -1 13559 -1 13560 -1 13561 -1 13562 -1 13563 -1 13564 -1 13565 -1 13566 -1 13567 -1 13568 -1 13569 -1 13570 -1 13571 -1 13572 -1 13573 -1 13574 -1 13575 -1 13576 -1 13577 -1 13578 -1 13579 -1 13580 -1 13581 -1 13582 -1 13583 -1 13584 -1 13585 -1 13586 -1 13587 -1 13588 -1 13589 -1 13590 -1 13591 -1 13592 -1 13593 -1 13594 -1 13595 -1 13596 -1 13597 -1 13598 -1 13599 -1 13600 -1 13601 -1 13602 -1 13603 -1 13604 -1 13605 -1 13606 -1 13607 -1 13608 -1 13609 -1 13610 -1 13611 -1 13612 -1 13613 -1 13614 -1 13615 -1 13616 -1 13617 -1 13618 -1 13619 -1 13620 -1 13621 -1 13622 -1 13623 -1 13624 -1 13625 -1 13626 -1 13627 -1 13628 -1 13629 -1 13630 -1 13631 -1 13632 -1 13633 -1 13634 -1 13635 -1 13636 -1 13637 -1 13638 -1 13639 -1 13640 -1 13641 -1 13642 -1 13643 -1 13644 -1 13645 -1 13646 -1 13647 -1 13648 -1 13649 -1 13650 -1 13651 -1 13652 -1 13653 -1 13654 -1 13655 -1 13656 -1 13657 -1 13658 -1 13659 -1 13660 -1 13661 -1 13662 -1 13663 -1 13664 -1 13665 -1 13666 -1 13667 -1 13668 -1 13669 -1 13670 -1 13671 -1 13672 -1 13673 -1 13674 -1 13675 -1 13676 -1 13677 -1 13678 -1 13679 -1 13680 -1 13681 -1 13682 -1 13683 -1 13684 -1 13685 -1 13686 -1 13687 -1 13688 -1 13689 -1 13690 -1 13691 -1 13692 -1 13693 -1 13694 -1 13695 -1 13696 -1 13697 -1 13698 -1 13699 -1 13700 -1 13701 -1 13702 -1 13703 -1 13704 -1 13705 -1 13706 -1 13707 -1 13708 -1 13709 -1 13710 -1 13711 -1 13712 -1 13713 -1 13714 -1 13715 -1 13716 -1 13717 -1 13718 -1 13719 -1 13720 -1 13721 -1 13722 -1 13723 -1 13724 -1 13725 -1 13726 -1 13727 -1 13728 -1 13729 -1 13730 -1 13731 -1 13732 -1 13733 -1 13734 -1 13735 -1 13736 -1 13737 -1 13738 -1 13739 -1 13740 -1 13741 -1 13742 -1 13743 -1 13744 -1 13745 -1 13746 -1 13747 -1 13748 -1 13749 -1 13750 -1 13751 -1 13752 -1 13753 -1 13754 -1 13755 -1 13756 -1 13757 -1 13758 -1 13759 -1 13760 -1 13761 -1 13762 -1 13763 -1 13764 -1 13765 -1 13766 -1 13767 -1 13768 -1 13769 -1 13770 -1 13771 -1 13772 -1 13773 -1 13774 -1 13775 -1 13776 -1 13777 -1 13778 -1 13779 -1 13780 -1 13781 -1 13782 -1 13783 -1 13784 -1 13785 -1 13786 -1 13787 -1 13788 -1 13789 -1 13790 -1 13791 -1 13792 -1 13793 -1 13794 -1 13795 -1 13796 -1 13797 -1 13798 -1 13799 -1 13800 -1 13801 -1 13802 -1 13803 -1 13804 -1 13805 -1 13806 -1 13807 -1 13808 -1 13809 -1 13810 -1 13811 -1 13812 -1 13813 -1 13814 -1 13815 -1 13816 -1 13817 -1 13818 -1 13819 -1 13820 -1 13821 -1 13822 -1 13823 -1 13824 -1 13825 -1 13826 -1 13827 -1 13828 -1 13829 -1 13830 -1 13831 -1 13832 -1 13833 -1 13834 -1 13835 -1 13836 -1 13837 -1 13838 -1 13839 -1 13840 -1 13841 -1 13842 -1 13843 -1 13844 -1 13845 -1 13846 -1 13847 -1 13848 -1 13849 -1 13850 -1 13851 -1 13852 -1 13853 -1 13854 -1 13855 -1 13856 -1 13857 -1 13858 -1 13859 -1 13860 -1 13861 -1 13862 -1 13863 -1 13864 -1 13865 -1 13866 -1 13867 -1 13868 -1 13869 -1 13870 -1 13871 -1 13872 -1 13873 -1 13874 -1 13875 -1 13876 -1 13877 -1 13878 -1 13879 -1 13880 -1 13881 -1 13882 -1 13883 -1 13884 -1 13885 -1 13886 -1 13887 -1 13888 -1 13889 -1 13890 -1 13891 -1 13892 -1 13893 -1 13894 -1 13895 -1 13896 -1 13897 -1 13898 -1 13899 -1 13900 -1 13901 -1 13902 -1 13903 -1 13904 -1 13905 -1 13906 -1 13907 -1 13908 -1 13909 -1 13910 -1 13911 -1 13912 -1 13913 -1 13914 -1 13915 -1 13916 -1 13917 -1 13918 -1 13919 -1 13920 -1 13921 -1 13922 -1 13923 -1 13924 -1 13925 -1 13926 -1 13927 -1 13928 -1 13929 -1 13930 -1 13931 -1 13932 -1 13933 -1 13934 -1 13935 -1 13936 -1 13937 -1 13938 -1 13939 -1 13940 -1 13941 -1 13942 -1 13943 -1 13944 -1 13945 -1 13946 -1 13947 -1 13948 -1 13949 -1 13950 -1 13951 -1 13952 -1 13953 -1 13954 -1 13955 -1 13956 -1 13957 -1 13958 -1 13959 -1 13960 -1 13961 -1 13962 -1 13963 -1 13964 -1 13965 -1 13966 -1 13967 -1 13968 -1 13969 -1 13970 -1 13971 -1 13972 -1 13973 -1 13974 -1 13975 -1 13976 -1 13977 -1 13978 -1 13979 -1 13980 -1 13981 -1 13982 -1 13983 -1 13984 -1 13985 -1 13986 -1 13987 -1 13988 -1 13989 -1 13990 -1 13991 -1 13992 -1 13993 -1 13994 -1 13995 -1 13996 -1 13997 -1 13998 -1 13999 -1 14000 -1 14001 -1 14002 -1 14003 -1 14004 -1 14005 -1 14006 -1 14007 -1 14008 -1 14009 -1 14010 -1 14011 -1 14012 -1 14013 -1 14014 -1 14015 -1 14016 -1 14017 -1 14018 -1 14019 -1 14020 -1 14021 -1 14022 -1 14023 -1 14024 -1 14025 -1 14026 -1 14027 -1 14028 -1 14029 -1 14030 -1 14031 -1 14032 -1 14033 -1 14034 -1 14035 -1 14036 -1 14037 -1 14038 -1 14039 -1 14040 -1 14041 -1 14042 -1 14043 -1 14044 -1 14045 -1 14046 -1 14047 -1 14048 -1 14049 -1 14050 -1 14051 -1 14052 -1 14053 -1 14054 -1 14055 -1 14056 -1 14057 -1 14058 -1 14059 -1 14060 -1 14061 -1 14062 -1 14063 -1 14064 -1 14065 -1 14066 -1 14067 -1 14068 -1 14069 -1 14070 -1 14071 -1 14072 -1 14073 -1 14074 -1 14075 -1 14076 -1 14077 -1 14078 -1 14079 -1 14080 -1 14081 -1 14082 -1 14083 -1 14084 -1 14085 -1 14086 -1 14087 -1 14088 -1 14089 -1 14090 -1 14091 -1 14092 -1 14093 -1 14094 -1 14095 -1 14096 -1 14097 -1 14098 -1 14099 -1 14100 -1 14101 -1 14102 -1 14103 -1 14104 -1 14105 -1 14106 -1 14107 -1 14108 -1 14109 -1 14110 -1 14111 -1 14112 -1 14113 -1 14114 -1 14115 -1 14116 -1 14117 -1 14118 -1 14119 -1 14120 -1 14121 -1 14122 -1 14123 -1 14124 -1 14125 -1 14126 -1 14127 -1 14128 -1 14129 -1 14130 -1 14131 -1 14132 -1 14133 -1 14134 -1 14135 -1 14136 -1 14137 -1 14138 -1 14139 -1 14140 -1 14141 -1 14142 -1 14143 -1 14144 -1 14145 -1 14146 -1 14147 -1 14148 -1 14149 -1 14150 -1 14151 -1 14152 -1 14153 -1 14154 -1 14155 -1 14156 -1 14157 -1 14158 -1 14159 -1 14160 -1 14161 -1 14162 -1 14163 -1 14164 -1 14165 -1 14166 -1 14167 -1 14168 -1 14169 -1 14170 -1 14171 -1 14172 -1 14173 -1 14174 -1 14175 -1 14176 -1 14177 -1 14178 -1 14179 -1 14180 -1 14181 -1 14182 -1 14183 -1 14184 -1 14185 -1 14186 -1 14187 -1 14188 -1 14189 -1 14190 -1 14191 -1 14192 -1 14193 -1 14194 -1 14195 -1 14196 -1 14197 -1 14198 -1 14199 -1 14200 -1 14201 -1 14202 -1 14203 -1 14204 -1 14205 -1 14206 -1 14207 -1 14208 -1 14209 -1 14210 -1 14211 -1 14212 -1 14213 -1 14214 -1 14215 -1 14216 -1 14217 -1 14218 -1 14219 -1 14220 -1 14221 -1 14222 -1 14223 -1 14224 -1 14225 -1 14226 -1 14227 -1 14228 -1 14229 -1 14230 -1 14231 -1 14232 -1 14233 -1 14234 -1 14235 -1 14236 -1 14237 -1 14238 -1 14239 -1 14240 -1 14241 -1 14242 -1 14243 -1 14244 -1 14245 -1 14246 -1 14247 -1 14248 -1 14249 -1 14250 -1 14251 -1 14252 -1 14253 -1 14254 -1 14255 -1 14256 -1 14257 -1 14258 -1 14259 -1 14260 -1 14261 -1 14262 -1 14263 -1 14264 -1 14265 -1 14266 -1 14267 -1 14268 -1 14269 -1 14270 -1 14271 -1 14272 -1 14273 -1 14274 -1 14275 -1 14276 -1 14277 -1 14278 -1 14279 -1 14280 -1 14281 -1 14282 -1 14283 -1 14284 -1 14285 -1 14286 -1 14287 -1 14288 -1 14289 -1 14290 -1 14291 -1 14292 -1 14293 -1 14294 -1 14295 -1 14296 -1 14297 -1 14298 -1 14299 -1 14300 -1 14301 -1 14302 -1 14303 -1 14304 -1 14305 -1 14306 -1 14307 -1 14308 -1 14309 -1 14310 -1 14311 -1 14312 -1 14313 -1 14314 -1 14315 -1 14316 -1 14317 -1 14318 -1 14319 -1 14320 -1 14321 -1 14322 -1 14323 -1 14324 -1 14325 -1 14326 -1 14327 -1 14328 -1 14329 -1 14330 -1 14331 -1 14332 -1 14333 -1 14334 -1 14335 -1 14336 -1 14337 -1 14338 -1 14339 -1 14340 -1 14341 -1 14342 -1 14343 -1 14344 -1 14345 -1 14346 -1 14347 -1 14348 -1 14349 -1 14350 -1 14351 -1 14352 -1 14353 -1 14354 -1 14355 -1 14356 -1 14357 -1 14358 -1 14359 -1 14360 -1 14361 -1 14362 -1 14363 -1 14364 -1 14365 -1 14366 -1 14367 -1 14368 -1 14369 -1 14370 -1 14371 -1 14372 -1 14373 -1 14374 -1 14375 -1 14376 -1 14377 -1 14378 -1 14379 -1 14380 -1 14381 -1 14382 -1 14383 -1 14384 -1 14385 -1 14386 -1 14387 -1 14388 -1 14389 -1 14390 -1 14391 -1 14392 -1 14393 -1 14394 -1 14395 -1 14396 -1 14397 -1 14398 -1 14399 -1 14400 -1 14401 -1 14402 -1 14403 -1 14404 -1 14405 -1 14406 -1 14407 -1 14408 -1 14409 -1 14410 -1 14411 -1 14412 -1 14413 -1 14414 -1 14415 -1 14416 -1 14417 -1 14418 -1 14419 -1 14420 -1 14421 -1 14422 -1 14423 -1 14424 -1 14425 -1 14426 -1 14427 -1 14428 -1 14429 -1 14430 -1 14431 -1 14432 -1 14433 -1 14434 -1 14435 -1 14436 -1 14437 -1 14438 -1 14439 -1 14440 -1 14441 -1 14442 -1 14443 -1 14444 -1 14445 -1 14446 -1 14447 -1 14448 -1 14449 -1 14450 -1 14451 -1 14452 -1 14453 -1 14454 -1 14455 -1 14456 -1 14457 -1 14458 -1 14459 -1 14460 -1 14461 -1 14462 -1 14463 -1 14464 -1 14465 -1 14466 -1 14467 -1 14468 -1 14469 -1 14470 -1 14471 -1 14472 -1 14473 -1 14474 -1 14475 -1 14476 -1 14477 -1 14478 -1 14479 -1 14480 -1 14481 -1 14482 -1 14483 -1 14484 -1 14485 -1 14486 -1 14487 -1 14488 -1 14489 -1 14490 -1 14491 -1 14492 -1 14493 -1 14494 -1 14495 -1 14496 -1 14497 -1 14498 -1 14499 -1 14500 -1 14501 -1 14502 -1 14503 -1 14504 -1 14505 -1 14506 -1 14507 -1 14508 -1 14509 -1 14510 -1 14511 -1 14512 -1 14513 -1 14514 -1 14515 -1 14516 -1 14517 -1 14518 -1 14519 -1 14520 -1 14521 -1 14522 -1 14523 -1 14524 -1 14525 -1 14526 -1 14527 -1 14528 -1 14529 -1 14530 -1 14531 -1 14532 -1 14533 -1 14534 -1 14535 -1 14536 -1 14537 -1 14538 -1 14539 -1 14540 -1 14541 -1 14542 -1 14543 -1 14544 -1 14545 -1 14546 -1 14547 -1 14548 -1 14549 -1 14550 -1 14551 -1 14552 -1 14553 -1 14554 -1 14555 -1 14556 -1 14557 -1 14558 -1 14559 -1 14560 -1 14561 -1 14562 -1 14563 -1 14564 -1 14565 -1 14566 -1 14567 -1 14568 -1 14569 -1 14570 -1 14571 -1 14572 -1 14573 -1 14574 -1 14575 -1 14576 -1 14577 -1 14578 -1 14579 -1 14580 -1 14581 -1 14582 -1 14583 -1 14584 -1 14585 -1 14586 -1 14587 -1 14588 -1 14589 -1 14590 -1 14591 -1 14592 -1 14593 -1 14594 -1 14595 -1 14596 -1 14597 -1 14598 -1 14599 -1 14600 -1 14601 -1 14602 -1 14603 -1 14604 -1 14605 -1 14606 -1 14607 -1 14608 -1 14609 -1 14610 -1 14611 -1 14612 -1 14613 -1 14614 -1 14615 -1 14616 -1 14617 -1 14618 -1 14619 -1 14620 -1 14621 -1 14622 -1 14623 -1 14624 -1 14625 -1 14626 -1 14627 -1 14628 -1 14629 -1 14630 -1 14631 -1 14632 -1 14633 -1 14634 -1 14635 -1 14636 -1 14637 -1 14638 -1 14639 -1 14640 -1 14641 -1 14642 -1 14643 -1 14644 -1 14645 -1 14646 -1 14647 -1 14648 -1 14649 -1 14650 -1 14651 -1 14652 -1 14653 -1 14654 -1 14655 -1 14656 -1 14657 -1 14658 -1 14659 -1 14660 -1 14661 -1 14662 -1 14663 -1 14664 -1 14665 -1 14666 -1 14667 -1 14668 -1 14669 -1 14670 -1 14671 -1 14672 -1 14673 -1 14674 -1 14675 -1 14676 -1 14677 -1 14678 -1 14679 -1 14680 -1 14681 -1 14682 -1 14683 -1 14684 -1 14685 -1 14686 -1 14687 -1 14688 -1 14689 -1 14690 -1 14691 -1 14692 -1 14693 -1 14694 -1 14695 -1 14696 -1 14697 -1 14698 -1 14699 -1 14700 -1 14701 -1 14702 -1 14703 -1 14704 -1 14705 -1 14706 -1 14707 -1 14708 -1 14709 -1 14710 -1 14711 -1 14712 -1 14713 -1 14714 -1 14715 -1 14716 -1 14717 -1 14718 -1 14719 -1 14720 -1 14721 -1 14722 -1 14723 -1 14724 -1 14725 -1 14726 -1 14727 -1 14728 -1 14729 -1 14730 -1 14731 -1 14732 -1 14733 -1 14734 -1 14735 -1 14736 -1 14737 -1 14738 -1 14739 -1 14740 -1 14741 -1 14742 -1 14743 -1 14744 -1 14745 -1 14746 -1 14747 -1 14748 -1 14749 -1 14750 -1 14751 -1 14752 -1 14753 -1 14754 -1 14755 -1 14756 -1 14757 -1 14758 -1 14759 -1 14760 -1 14761 -1 14762 -1 14763 -1 14764 -1 14765 -1 14766 -1 14767 -1 14768 -1 14769 -1 14770 -1 14771 -1 14772 -1 14773 -1 14774 -1 14775 -1 14776 -1 14777 -1 14778 -1 14779 -1 14780 -1 14781 -1 14782 -1 14783 -1 14784 -1 14785 -1 14786 -1 14787 -1 14788 -1 14789 -1 14790 -1 14791 -1 14792 -1 14793 -1 14794 -1 14795 -1 14796 -1 14797 -1 14798 -1 14799 -1 14800 -1 14801 -1 14802 -1 14803 -1 14804 -1 14805 -1 14806 -1 14807 -1 14808 -1 14809 -1 14810 -1 14811 -1 14812 -1 14813 -1 14814 -1 14815 -1 14816 -1 14817 -1 14818 -1 14819 -1 14820 -1 14821 -1 14822 -1 14823 -1 14824 -1 14825 -1 14826 -1 14827 -1 14828 -1 14829 -1 14830 -1 14831 -1 14832 -1 14833 -1 14834 -1 14835 -1 14836 -1 14837 -1 14838 -1 14839 -1 14840 -1 14841 -1 14842 -1 14843 -1 14844 -1 14845 -1 14846 -1 14847 -1 14848 -1 14849 -1 14850 -1 14851 -1 14852 -1 14853 -1 14854 -1 14855 -1 14856 -1 14857 -1 14858 -1 14859 -1 14860 -1 14861 -1 14862 -1 14863 -1 14864 -1 14865 -1 14866 -1 14867 -1 14868 -1 14869 -1 14870 -1 14871 -1 14872 -1 14873 -1 14874 -1 14875 -1 14876 -1 14877 -1 14878 -1 14879 -1 14880 -1 14881 -1 14882 -1 14883 -1 14884 -1 14885 -1 14886 -1 14887 -1 14888 -1 14889 -1 14890 -1 14891 -1 14892 -1 14893 -1 14894 -1 14895 -1 14896 -1 14897 -1 14898 -1 14899 -1 14900 -1 14901 -1 14902 -1 14903 -1 14904 -1 14905 -1 14906 -1 14907 -1 14908 -1 14909 -1 14910 -1 14911 -1 14912 -1 14913 -1 14914 -1 14915 -1 14916 -1 14917 -1 14918 -1 14919 -1 14920 -1 14921 -1 14922 -1 14923 -1 14924 -1 14925 -1 14926 -1 14927 -1 14928 -1 14929 -1 14930 -1 14931 -1 14932 -1 14933 -1 14934 -1 14935 -1 14936 -1 14937 -1 14938 -1 14939 -1 14940 -1 14941 -1 14942 -1 14943 -1 14944 -1 14945 -1 14946 -1 14947 -1 14948 -1 14949 -1 14950 -1 14951 -1 14952 -1 14953 -1 14954 -1 14955 -1 14956 -1 14957 -1 14958 -1 14959 -1 14960 -1 14961 -1 14962 -1 14963 -1 14964 -1 14965 -1 14966 -1 14967 -1 14968 -1 14969 -1 14970 -1 14971 -1 14972 -1 14973 -1 14974 -1 14975 -1 14976 -1 14977 -1 14978 -1 14979 -1 14980 -1 14981 -1 14982 -1 14983 -1 14984 -1 14985 -1 14986 -1 14987 -1 14988 -1 14989 -1 14990 -1 14991 -1 14992 -1 14993 -1 14994 -1 14995 -1 14996 -1 14997 -1 14998 -1 14999 -1 15000 -1 15001 -1 15002 -1 15003 -1 15004 -1 15005 -1 15006 -1 15007 -1 15008 -1 15009 -1 15010 -1 15011 -1 15012 -1 15013 -1 15014 -1 15015 -1 15016 -1 15017 -1 15018 -1 15019 -1 15020 -1 15021 -1 15022 -1 15023 -1 15024 -1 15025 -1 15026 -1 15027 -1 15028 -1 15029 -1 15030 -1 15031 -1 15032 -1 15033 -1 15034 -1 15035 -1 15036 -1 15037 -1 15038 -1 15039 -1 15040 -1 15041 -1 15042 -1 15043 -1 15044 -1 15045 -1 15046 -1 15047 -1 15048 -1 15049 -1 15050 -1 15051 -1 15052 -1 15053 -1 15054 -1 15055 -1 15056 -1 15057 -1 15058 -1 15059 -1 15060 -1 15061 -1 15062 -1 15063 -1 15064 -1 15065 -1 15066 -1 15067 -1 15068 -1 15069 -1 15070 -1 15071 -1 15072 -1 15073 -1 15074 -1 15075 -1 15076 -1 15077 -1 15078 -1 15079 -1 15080 -1 15081 -1 15082 -1 15083 -1 15084 -1 15085 -1 15086 -1 15087 -1 15088 -1 15089 -1 15090 -1 15091 -1 15092 -1 15093 -1 15094 -1 15095 -1 15096 -1 15097 -1 15098 -1 15099 -1 15100 -1 15101 -1 15102 -1 15103 -1 15104 -1 15105 -1 15106 -1 15107 -1 15108 -1 15109 -1 15110 -1 15111 -1 15112 -1 15113 -1 15114 -1 15115 -1 15116 -1 15117 -1 15118 -1 15119 -1 15120 -1 15121 -1 15122 -1 15123 -1 15124 -1 15125 -1 15126 -1 15127 -1 15128 -1 15129 -1 15130 -1 15131 -1 15132 -1 15133 -1 15134 -1 15135 -1 15136 -1 15137 -1 15138 -1 15139 -1 15140 -1 15141 -1 15142 -1 15143 -1 15144 -1 15145 -1 15146 -1 15147 -1 15148 -1 15149 -1 15150 -1 15151 -1 15152 -1 15153 -1 15154 -1 15155 -1 15156 -1 15157 -1 15158 -1 15159 -1 15160 -1 15161 -1 15162 -1 15163 -1 15164 -1 15165 -1 15166 -1 15167 -1 15168 -1 15169 -1 15170 -1 15171 -1 15172 -1 15173 -1 15174 -1 15175 -1 15176 -1 15177 -1 15178 -1 15179 -1 15180 -1 15181 -1 15182 -1 15183 -1 15184 -1 15185 -1 15186 -1 15187 -1 15188 -1 15189 -1 15190 -1 15191 -1 15192 -1 15193 -1 15194 -1 15195 -1 15196 -1 15197 -1 15198 -1 15199 -1 15200 -1 15201 -1 15202 -1 15203 -1 15204 -1 15205 -1 15206 -1 15207 -1 15208 -1 15209 -1 15210 -1 15211 -1 15212 -1 15213 -1 15214 -1 15215 -1 15216 -1 15217 -1 15218 -1 15219 -1 15220 -1 15221 -1 15222 -1 15223 -1 15224 -1 15225 -1 15226 -1 15227 -1 15228 -1 15229 -1 15230 -1 15231 -1 15232 -1 15233 -1 15234 -1 15235 -1 15236 -1 15237 -1 15238 -1 15239 -1 15240 -1 15241 -1 15242 -1 15243 -1 15244 -1 15245 -1 15246 -1 15247 -1 15248 -1 15249 -1 15250 -1 15251 -1 15252 -1 15253 -1 15254 -1 15255 -1 15256 -1 15257 -1 15258 -1 15259 -1 15260 -1 15261 -1 15262 -1 15263 -1 15264 -1 15265 -1 15266 -1 15267 -1 15268 -1 15269 -1 15270 -1 15271 -1 15272 -1 15273 -1 15274 -1 15275 -1 15276 -1 15277 -1 15278 -1 15279 -1 15280 -1 15281 -1 15282 -1 15283 -1 15284 -1 15285 -1 15286 -1 15287 -1 15288 -1 15289 -1 15290 -1 15291 -1 15292 -1 15293 -1 15294 -1 15295 -1 15296 -1 15297 -1 15298 -1 15299 -1 15300 -1 15301 -1 15302 -1 15303 -1 15304 -1 15305 -1 15306 -1 15307 -1 15308 -1 15309 -1 15310 -1 15311 -1 15312 -1 15313 -1 15314 -1 15315 -1 15316 -1 15317 -1 15318 -1 15319 -1 15320 -1 15321 -1 15322 -1 15323 -1 15324 -1 15325 -1 15326 -1 15327 -1 15328 -1 15329 -1 15330 -1 15331 -1 15332 -1 15333 -1 15334 -1 15335 -1 15336 -1 15337 -1 15338 -1 15339 -1 15340 -1 15341 -1 15342 -1 15343 -1 15344 -1 15345 -1 15346 -1 15347 -1 15348 -1 15349 -1 15350 -1 15351 -1 15352 -1 15353 -1 15354 -1 15355 -1 15356 -1 15357 -1 15358 -1 15359 -1 15360 -1 15361 -1 15362 -1 15363 -1 15364 -1 15365 -1 15366 -1 15367 -1 15368 -1 15369 -1 15370 -1 15371 -1 15372 -1 15373 -1 15374 -1 15375 -1 15376 -1 15377 -1 15378 -1 15379 -1 15380 -1 15381 -1 15382 -1 15383 -1 15384 -1 15385 -1 15386 -1 15387 -1 15388 -1 15389 -1 15390 -1 15391 -1 15392 -1 15393 -1 15394 -1 15395 -1 15396 -1 15397 -1 15398 -1 15399 -1 15400 -1 15401 -1 15402 -1 15403 -1 15404 -1 15405 -1 15406 -1 15407 -1 15408 -1 15409 -1 15410 -1 15411 -1 15412 -1 15413 -1 15414 -1 15415 -1 15416 -1 15417 -1 15418 -1 15419 -1 15420 -1 15421 -1 15422 -1 15423 -1 15424 -1 15425 -1 15426 -1 15427 -1 15428 -1 15429 -1 15430 -1 15431 -1 15432 -1 15433 -1 15434 -1 15435 -1 15436 -1 15437 -1 15438 -1 15439 -1 15440 -1 15441 -1 15442 -1 15443 -1 15444 -1 15445 -1 15446 -1 15447 -1 15448 -1 15449 -1 15450 -1 15451 -1 15452 -1 15453 -1 15454 -1 15455 -1 15456 -1 15457 -1 15458 -1 15459 -1 15460 -1 15461 -1 15462 -1 15463 -1 15464 -1 15465 -1 15466 -1 15467 -1 15468 -1 15469 -1 15470 -1 15471 -1 15472 -1 15473 -1 15474 -1 15475 -1 15476 -1 15477 -1 15478 -1 15479 -1 15480 -1 15481 -1 15482 -1 15483 -1 15484 -1 15485 -1 15486 -1 15487 -1 15488 -1 15489 -1 15490 -1 15491 -1 15492 -1 15493 -1 15494 -1 15495 -1 15496 -1 15497 -1 15498 -1 15499 -1 15500 -1 15501 -1 15502 -1 15503 -1 15504 -1 15505 -1 15506 -1 15507 -1 15508 -1 15509 -1 15510 -1 15511 -1 15512 -1 15513 -1 15514 -1 15515 -1 15516 -1 15517 -1 15518 -1 15519 -1 15520 -1 15521 -1 15522 -1 15523 -1 15524 -1 15525 -1 15526 -1 15527 -1 15528 -1 15529 -1 15530 -1 15531 -1 15532 -1 15533 -1 15534 -1 15535 -1 15536 -1 15537 -1 15538 -1 15539 -1 15540 -1 15541 -1 15542 -1 15543 -1 15544 -1 15545 -1 15546 -1 15547 -1 15548 -1 15549 -1 15550 -1 15551 -1 15552 -1 15553 -1 15554 -1 15555 -1 15556 -1 15557 -1 15558 -1 15559 -1 15560 -1 15561 -1 15562 -1 15563 -1 15564 -1 15565 -1 15566 -1 15567 -1 15568 -1 15569 -1 15570 -1 15571 -1 15572 -1 15573 -1 15574 -1 15575 -1 15576 -1 15577 -1 15578 -1 15579 -1 15580 -1 15581 -1 15582 -1 15583 -1 15584 -1 15585 -1 15586 -1 15587 -1 15588 -1 15589 -1 15590 -1 15591 -1 15592 -1 15593 -1 15594 -1 15595 -1 15596 -1 15597 -1 15598 -1 15599 -1 15600 -1 15601 -1 15602 -1 15603 -1 15604 -1 15605 -1 15606 -1 15607 -1 15608 -1 15609 -1 15610 -1 15611 -1 15612 -1 15613 -1 15614 -1 15615 -1 15616 -1 15617 -1 15618 -1 15619 -1 15620 -1 15621 -1 15622 -1 15623 -1 15624 -1 15625 -1 15626 -1 15627 -1 15628 -1 15629 -1 15630 -1 15631 -1 15632 -1 15633 -1 15634 -1 15635 -1 15636 -1 15637 -1 15638 -1 15639 -1 15640 -1 15641 -1 15642 -1 15643 -1 15644 -1 15645 -1 15646 -1 15647 -1 15648 -1 15649 -1 15650 -1 15651 -1 15652 -1 15653 -1 15654 -1 15655 -1 15656 -1 15657 -1 15658 -1 15659 -1 15660 -1 15661 -1 15662 -1 15663 -1 15664 -1 15665 -1 15666 -1 15667 -1 15668 -1 15669 -1 15670 -1 15671 -1 15672 -1 15673 -1 15674 -1 15675 -1 15676 -1 15677 -1 15678 -1 15679 -1 15680 -1 15681 -1 15682 -1 15683 -1 15684 -1 15685 -1 15686 -1 15687 -1 15688 -1 15689 -1 15690 -1 15691 -1 15692 -1 15693 -1 15694 -1 15695 -1 15696 -1 15697 -1 15698 -1 15699 -1 15700 -1 15701 -1 15702 -1 15703 -1 15704 -1 15705 -1 15706 -1 15707 -1 15708 -1 15709 -1 15710 -1 15711 -1 15712 -1 15713 -1 15714 -1 15715 -1 15716 -1 15717 -1 15718 -1 15719 -1 15720 -1 15721 -1 15722 -1 15723 -1 15724 -1 15725 -1 15726 -1 15727 -1 15728 -1 15729 -1 15730 -1 15731 -1 15732 -1 15733 -1 15734 -1 15735 -1 15736 -1 15737 -1 15738 -1 15739 -1 15740 -1 15741 -1 15742 -1 15743 -1 15744 -1 15745 -1 15746 -1 15747 -1 15748 -1 15749 -1 15750 -1 15751 -1 15752 -1 15753 -1 15754 -1 15755 -1 15756 -1 15757 -1 15758 -1 15759 -1 15760 -1 15761 -1 15762 -1 15763 -1 15764 -1 15765 -1 15766 -1 15767 -1 15768 -1 15769 -1 15770 -1 15771 -1 15772 -1 15773 -1 15774 -1 15775 -1 15776 -1 15777 -1 15778 -1 15779 -1 15780 -1 15781 -1 15782 -1 15783 -1 15784 -1 15785 -1 15786 -1 15787 -1 15788 -1 15789 -1 15790 -1 15791 -1 15792 -1 15793 -1 15794 -1 15795 -1 15796 -1 15797 -1 15798 -1 15799 -1 15800 -1 15801 -1 15802 -1 15803 -1 15804 -1 15805 -1 15806 -1 15807 -1 15808 -1 15809 -1 15810 -1 15811 -1 15812 -1 15813 -1 15814 -1 15815 -1 15816 -1 15817 -1 15818 -1 15819 -1 15820 -1 15821 -1 15822 -1 15823 -1 15824 -1 15825 -1 15826 -1 15827 -1 15828 -1 15829 -1 15830 -1 15831 -1 15832 -1 15833 -1 15834 -1 15835 -1 15836 -1 15837 -1 15838 -1 15839 -1 15840 -1 15841 -1 15842 -1 15843 -1 15844 -1 15845 -1 15846 -1 15847 -1 15848 -1 15849 -1 15850 -1 15851 -1 15852 -1 15853 -1 15854 -1 15855 -1 15856 -1 15857 -1 15858 -1 15859 -1 15860 -1 15861 -1 15862 -1 15863 -1 15864 -1 15865 -1 15866 -1 15867 -1 15868 -1 15869 -1 15870 -1 15871 -1 15872 -1 15873 -1 15874 -1 15875 -1 15876 -1 15877 -1 15878 -1 15879 -1 15880 -1 15881 -1 15882 -1 15883 -1 15884 -1 15885 -1 15886 -1 15887 -1 15888 -1 15889 -1 15890 -1 15891 -1 15892 -1 15893 -1 15894 -1 15895 -1 15896 -1 15897 -1 15898 -1 15899 -1 15900 -1 15901 -1 15902 -1 15903 -1 15904 -1 15905 -1 15906 -1 15907 -1 15908 -1 15909 -1 15910 -1 15911 -1 15912 -1 15913 -1 15914 -1 15915 -1 15916 -1 15917 -1 15918 -1 15919 -1 15920 -1 15921 -1 15922 -1 15923 -1 15924 -1 15925 -1 15926 -1 15927 -1 15928 -1 15929 -1 15930 -1 15931 -1 15932 -1 15933 -1 15934 -1 15935 -1 15936 -1 15937 -1 15938 -1 15939 -1 15940 -1 15941 -1 15942 -1 15943 -1 15944 -1 15945 -1 15946 -1 15947 -1 15948 -1 15949 -1 15950 -1 15951 -1 15952 -1 15953 -1 15954 -1 15955 -1 15956 -1 15957 -1 15958 -1 15959 -1 15960 -1 15961 -1 15962 -1 15963 -1 15964 -1 15965 -1 15966 -1 15967 -1 15968 -1 15969 -1 15970 -1 15971 -1 15972 -1 15973 -1 15974 -1 15975 -1 15976 -1 15977 -1 15978 -1 15979 -1 15980 -1 15981 -1 15982 -1 15983 -1 15984 -1 15985 -1 15986 -1 15987 -1 15988 -1 15989 -1 15990 -1 15991 -1 15992 -1 15993 -1 15994 -1 15995 -1 15996 -1 15997 -1 15998 -1 15999 -1 16000 -1 16001 -1 16002 -1 16003 -1 16004 -1 16005 -1 16006 -1 16007 -1 16008 -1 16009 -1 16010 -1 16011 -1 16012 -1 16013 -1 16014 -1 16015 -1 16016 -1 16017 -1 16018 -1 16019 -1 16020 -1 16021 -1 16022 -1 16023 -1 16024 -1 16025 -1 16026 -1 16027 -1 16028 -1 16029 -1 16030 -1 16031 -1 16032 -1 16033 -1 16034 -1 16035 -1 16036 -1 16037 -1 16038 -1 16039 -1 16040 -1 16041 -1 16042 -1 16043 -1 16044 -1 16045 -1 16046 -1 16047 -1 16048 -1 16049 -1 16050 -1 16051 -1 16052 -1 16053 -1 16054 -1 16055 -1 16056 -1 16057 -1 16058 -1 16059 -1 16060 -1 16061 -1 16062 -1 16063 -1 16064 -1 16065 -1 16066 -1 16067 -1 16068 -1 16069 -1 16070 -1 16071 -1 16072 -1 16073 -1 16074 -1 16075 -1 16076 -1 16077 -1 16078 -1 16079 -1 16080 -1 16081 -1 16082 -1 16083 -1 16084 -1 16085 -1 16086 -1 16087 -1 16088 -1 16089 -1 16090 -1 16091 -1 16092 -1 16093 -1 16094 -1 16095 -1 16096 -1 16097 -1 16098 -1 16099 -1 16100 -1 16101 -1 16102 -1 16103 -1 16104 -1 16105 -1 16106 -1 16107 -1 16108 -1 16109 -1 16110 -1 16111 -1 16112 -1 16113 -1 16114 -1 16115 -1 16116 -1 16117 -1 16118 -1 16119 -1 16120 -1 16121 -1 16122 -1 16123 -1 16124 -1 16125 -1 16126 -1 16127 -1 16128 -1 16129 -1 16130 -1 16131 -1 16132 -1 16133 -1 16134 -1 16135 -1 16136 -1 16137 -1 16138 -1 16139 -1 16140 -1 16141 -1 16142 -1 16143 -1 16144 -1 16145 -1 16146 -1 16147 -1 16148 -1 16149 -1 16150 -1 16151 -1 16152 -1 16153 -1 16154 -1 16155 -1 16156 -1 16157 -1 16158 -1 16159 -1 16160 -1 16161 -1 16162 -1 16163 -1 16164 -1 16165 -1 16166 -1 16167 -1 16168 -1 16169 -1 16170 -1 16171 -1 16172 -1 16173 -1 16174 -1 16175 -1 16176 -1 16177 -1 16178 -1 16179 -1 16180 -1 16181 -1 16182 -1 16183 -1 16184 -1 16185 -1 16186 -1 16187 -1 16188 -1 16189 -1 16190 -1 16191 -1 16192 -1 16193 -1 16194 -1 16195 -1 16196 -1 16197 -1 16198 -1 16199 -1 16200 -1 16201 -1 16202 -1 16203 -1 16204 -1 16205 -1 16206 -1 16207 -1 16208 -1 16209 -1 16210 -1 16211 -1 16212 -1 16213 -1 16214 -1 16215 -1 16216 -1 16217 -1 16218 -1 16219 -1 16220 -1 16221 -1 16222 -1 16223 -1 16224 -1 16225 -1 16226 -1 16227 -1 16228 -1 16229 -1 16230 -1 16231 -1 16232 -1 16233 -1 16234 -1 16235 -1 16236 -1 16237 -1 16238 -1 16239 -1 16240 -1 16241 -1 16242 -1 16243 -1 16244 -1 16245 -1 16246 -1 16247 -1 16248 -1 16249 -1 16250 -1 16251 -1 16252 -1 16253 -1 16254 -1 16255 -1 16256 -1 16257 -1 16258 -1 16259 -1 16260 -1 16261 -1 16262 -1 16263 -1 16264 -1 16265 -1 16266 -1 16267 -1 16268 -1 16269 -1 16270 -1 16271 -1 16272 -1 16273 -1 16274 -1 16275 -1 16276 -1 16277 -1 16278 -1 16279 -1 16280 -1 16281 -1 16282 -1 16283 -1 16284 -1 16285 -1 16286 -1 16287 -1 16288 -1 16289 -1 16290 -1 16291 -1 16292 -1 16293 -1 16294 -1 16295 -1 16296 -1 16297 -1 16298 -1 16299 -1 16300 -1 16301 -1 16302 -1 16303 -1 16304 -1 16305 -1 16306 -1 16307 -1 16308 -1 16309 -1 16310 -1 16311 -1 16312 -1 16313 -1 16314 -1 16315 -1 16316 -1 16317 -1 16318 -1 16319 -1 16320 -1 16321 -1 16322 -1 16323 -1 16324 -1 16325 -1 16326 -1 16327 -1 16328 -1 16329 -1 16330 -1 16331 -1 16332 -1 16333 -1 16334 -1 16335 -1 16336 -1 16337 -1 16338 -1 16339 -1 16340 -1 16341 -1 16342 -1 16343 -1 16344 -1 16345 -1 16346 -1 16347 -1 16348 -1 16349 -1 16350 -1 16351 -1 16352 -1 16353 -1 16354 -1 16355 -1 16356 -1 16357 -1 16358 -1 16359 -1 16360 -1 16361 -1 16362 -1 16363 -1 16364 -1 16365 -1 16366 -1 16367 -1 16368 -1 16369 -1 16370 -1 16371 -1 16372 -1 16373 -1 16374 -1 16375 -1 16376 -1 16377 -1 16378 -1 16379 -1 16380 -1 16381 -1 16382 -1 16383 -1 16384 -1 16385 -1 16386 -1 16387 -1 16388 -1 16389 -1 16390 -1 16391 -1 16392 -1 16393 -1 16394 -1 16395 -1 16396 -1 16397 -1 16398 -1 16399 -1 16400 -1 16401 -1 16402 -1 16403 -1 16404 -1 16405 -1 16406 -1 16407 -1 16408 -1 16409 -1 16410 -1 16411 -1 16412 -1 16413 -1 16414 -1 16415 -1 16416 -1 16417 -1 16418 -1 16419 -1 16420 -1 16421 -1 16422 -1 16423 -1 16424 -1 16425 -1 16426 -1 16427 -1 16428 -1 16429 -1 16430 -1 16431 -1 16432 -1 16433 -1 16434 -1 16435 -1 16436 -1 16437 -1 16438 -1 16439 -1 16440 -1 16441 -1 16442 -1 16443 -1 16444 -1 16445 -1 16446 -1 16447 -1 16448 -1 16449 -1 16450 -1 16451 -1 16452 -1 16453 -1 16454 -1 16455 -1 16456 -1 16457 -1 16458 -1 16459 -1 16460 -1 16461 -1 16462 -1 16463 -1 16464 -1 16465 -1 16466 -1 16467 -1 16468 -1 16469 -1 16470 -1 16471 -1 16472 -1 16473 -1 16474 -1 16475 -1 16476 -1 16477 -1 16478 -1 16479 -1 16480 -1 16481 -1 16482 -1 16483 -1 16484 -1 16485 -1 16486 -1 16487 -1 16488 -1 16489 -1 16490 -1 16491 -1 16492 -1 16493 -1 16494 -1 16495 -1 16496 -1 16497 -1 16498 -1 16499 -1 16500 -1 16501 -1 16502 -1 16503 -1 16504 -1 16505 -1 16506 -1 16507 -1 16508 -1 16509 -1 16510 -1 16511 -1 16512 -1 16513 -1 16514 -1 16515 -1 16516 -1 16517 -1 16518 -1 16519 -1 16520 -1 16521 -1 16522 -1 16523 -1 16524 -1 16525 -1 16526 -1 16527 -1 16528 -1 16529 -1 16530 -1 16531 -1 16532 -1 16533 -1 16534 -1 16535 -1 16536 -1 16537 -1 16538 -1 16539 -1 16540 -1 16541 -1 16542 -1 16543 -1 16544 -1 16545 -1 16546 -1 16547 -1 16548 -1 16549 -1 16550 -1 16551 -1 16552 -1 16553 -1 16554 -1 16555 -1 16556 -1 16557 -1 16558 -1 16559 -1 16560 -1 16561 -1 16562 -1 16563 -1 16564 -1 16565 -1 16566 -1 16567 -1 16568 -1 16569 -1 16570 -1 16571 -1 16572 -1 16573 -1 16574 -1 16575 -1 16576 -1 16577 -1 16578 -1 16579 -1 16580 -1 16581 -1 16582 -1 16583 -1 16584 -1 16585 -1 16586 -1 16587 -1 16588 -1 16589 -1 16590 -1 16591 -1 16592 -1 16593 -1 16594 -1 16595 -1 16596 -1 16597 -1 16598 -1 16599 -1 16600 -1 16601 -1 16602 -1 16603 -1 16604 -1 16605 -1 16606 -1 16607 -1 16608 -1 16609 -1 16610 -1 16611 -1 16612 -1 16613 -1 16614 -1 16615 -1 16616 -1 16617 -1 16618 -1 16619 -1 16620 -1 16621 -1 16622 -1 16623 -1 16624 -1 16625 -1 16626 -1 16627 -1 16628 -1 16629 -1 16630 -1 16631 -1 16632 -1 16633 -1 16634 -1 16635 -1 16636 -1 16637 -1 16638 -1 16639 -1 16640 -1 16641 -1 16642 -1 16643 -1 16644 -1 16645 -1 16646 -1 16647 -1 16648 -1 16649 -1 16650 -1 16651 -1 16652 -1 16653 -1 16654 -1 16655 -1 16656 -1 16657 -1 16658 -1 16659 -1 16660 -1 16661 -1 16662 -1 16663 -1 16664 -1 16665 -1 16666 -1 16667 -1 16668 -1 16669 -1 16670 -1 16671 -1 16672 -1 16673 -1 16674 -1 16675 -1 16676 -1 16677 -1 16678 -1 16679 -1 16680 -1 16681 -1 16682 -1 16683 -1 16684 -1 16685 -1 16686 -1 16687 -1 16688 -1 16689 -1 16690 -1 16691 -1 16692 -1 16693 -1 16694 -1 16695 -1 16696 -1 16697 -1 16698 -1 16699 -1 16700 -1 16701 -1 16702 -1 16703 -1 16704 -1 16705 -1 16706 -1 16707 -1 16708 -1 16709 -1 16710 -1 16711 -1 16712 -1 16713 -1 16714 -1 16715 -1 16716 -1 16717 -1 16718 -1 16719 -1 16720 -1 16721 -1 16722 -1 16723 -1 16724 -1 16725 -1 16726 -1 16727 -1 16728 -1 16729 -1 16730 -1 16731 -1 16732 -1 16733 -1 16734 -1 16735 -1 16736 -1 16737 -1 16738 -1 16739 -1 16740 -1 16741 -1 16742 -1 16743 -1 16744 -1 16745 -1 16746 -1 16747 -1 16748 -1 16749 -1 16750 -1 16751 -1 16752 -1 16753 -1 16754 -1 16755 -1 16756 -1 16757 -1 16758 -1 16759 -1 16760 -1 16761 -1 16762 -1 16763 -1 16764 -1 16765 -1 16766 -1 16767 -1 16768 -1 16769 -1 16770 -1 16771 -1 16772 -1 16773 -1 16774 -1 16775 -1 16776 -1 16777 -1 16778 -1 16779 -1 16780 -1 16781 -1 16782 -1 16783 -1 16784 -1 16785 -1 16786 -1 16787 -1 16788 -1 16789 -1 16790 -1 16791 -1 16792 -1 16793 -1 16794 -1 16795 -1 16796 -1 16797 -1 16798 -1 16799 -1 16800 -1 16801 -1 16802 -1 16803 -1 16804 -1 16805 -1 16806 -1 16807 -1 16808 -1 16809 -1 16810 -1 16811 -1 16812 -1 16813 -1 16814 -1 16815 -1 16816 -1 16817 -1 16818 -1 16819 -1 16820 -1 16821 -1 16822 -1 16823 -1 16824 -1 16825 -1 16826 -1 16827 -1 16828 -1 16829 -1 16830 -1 16831 -1 16832 -1 16833 -1 16834 -1 16835 -1 16836 -1 16837 -1 16838 -1 16839 -1 16840 -1 16841 -1 16842 -1 16843 -1 16844 -1 16845 -1 16846 -1 16847 -1 16848 -1 16849 -1 16850 -1 16851 -1 16852 -1 16853 -1 16854 -1 16855 -1 16856 -1 16857 -1 16858 -1 16859 -1 16860 -1 16861 -1 16862 -1 16863 -1 16864 -1 16865 -1 16866 -1 16867 -1 16868 -1 16869 -1 16870 -1 16871 -1 16872 -1 16873 -1 16874 -1 16875 -1 16876 -1 16877 -1 16878 -1 16879 -1 16880 -1 16881 -1 16882 -1 16883 -1 16884 -1 16885 -1 16886 -1 16887 -1 16888 -1 16889 -1 16890 -1 16891 -1 16892 -1 16893 -1 16894 -1 16895 -1 16896 -1 16897 -1 16898 -1 16899 -1 16900 -1 16901 -1 16902 -1 16903 -1 16904 -1 16905 -1 16906 -1 16907 -1 16908 -1 16909 -1 16910 -1 16911 -1 16912 -1 16913 -1 16914 -1 16915 -1 16916 -1 16917 -1 16918 -1 16919 -1 16920 -1 16921 -1 16922 -1 16923 -1 16924 -1 16925 -1 16926 -1 16927 -1 16928 -1 16929 -1 16930 -1 16931 -1 16932 -1 16933 -1 16934 -1 16935 -1 16936 -1 16937 -1 16938 -1 16939 -1 16940 -1 16941 -1 16942 -1 16943 -1 16944 -1 16945 -1 16946 -1 16947 -1 16948 -1 16949 -1 16950 -1 16951 -1 16952 -1 16953 -1 16954 -1 16955 -1 16956 -1 16957 -1 16958 -1 16959 -1 16960 -1 16961 -1 16962 -1 16963 -1 16964 -1 16965 -1 16966 -1 16967 -1 16968 -1 16969 -1 16970 -1 16971 -1 16972 -1 16973 -1 16974 -1 16975 -1 16976 -1 16977 -1 16978 -1 16979 -1 16980 -1 16981 -1 16982 -1 16983 -1 16984 -1 16985 -1 16986 -1 16987 -1 16988 -1 16989 -1 16990 -1 16991 -1 16992 -1 16993 -1 16994 -1 16995 -1 16996 -1 16997 -1 16998 -1 16999 -1 17000 -1 17001 -1 17002 -1 17003 -1 17004 -1 17005 -1 17006 -1 17007 -1 17008 -1 17009 -1 17010 -1 17011 -1 17012 -1 17013 -1 17014 -1 17015 -1 17016 -1 17017 -1 17018 -1 17019 -1 17020 -1 17021 -1 17022 -1 17023 -1 17024 -1 17025 -1 17026 -1 17027 -1 17028 -1 17029 -1 17030 -1 17031 -1 17032 -1 17033 -1 17034 -1 17035 -1 17036 -1 17037 -1 17038 -1 17039 -1 17040 -1 17041 -1 17042 -1 17043 -1 17044 -1 17045 -1 17046 -1 17047 -1 17048 -1 17049 -1 17050 -1 17051 -1 17052 -1 17053 -1 17054 -1 17055 -1 17056 -1 17057 -1 17058 -1 17059 -1 17060 -1 17061 -1 17062 -1 17063 -1 17064 -1 17065 -1 17066 -1 17067 -1 17068 -1 17069 -1 17070 -1 17071 -1 17072 -1 17073 -1 17074 -1 17075 -1 17076 -1 17077 -1 17078 -1 17079 -1 17080 -1 17081 -1 17082 -1 17083 -1 17084 -1 17085 -1 17086 -1 17087 -1 17088 -1 17089 -1 17090 -1 17091 -1 17092 -1 17093 -1 17094 -1 17095 -1 17096 -1 17097 -1 17098 -1 17099 -1 17100 -1 17101 -1 17102 -1 17103 -1 17104 -1 17105 -1 17106 -1 17107 -1 17108 -1 17109 -1 17110 -1 17111 -1 17112 -1 17113 -1 17114 -1 17115 -1 17116 -1 17117 -1 17118 -1 17119 -1 17120 -1 17121 -1 17122 -1 17123 -1 17124 -1 17125 -1 17126 -1 17127 -1 17128 -1 17129 -1 17130 -1 17131 -1 17132 -1 17133 -1 17134 -1 17135 -1 17136 -1 17137 -1 17138 -1 17139 -1 17140 -1 17141 -1 17142 -1 17143 -1 17144 -1 17145 -1 17146 -1 17147 -1 17148 -1 17149 -1 17150 -1 17151 -1 17152 -1 17153 -1 17154 -1 17155 -1 17156 -1 17157 -1 17158 -1 17159 -1 17160 -1 17161 -1 17162 -1 17163 -1 17164 -1 17165 -1 17166 -1 17167 -1 17168 -1 17169 -1 17170 -1 17171 -1 17172 -1 17173 -1 17174 -1 17175 -1 17176 -1 17177 -1 17178 -1 17179 -1 17180 -1 17181 -1 17182 -1 17183 -1 17184 -1 17185 -1 17186 -1 17187 -1 17188 -1 17189 -1 17190 -1 17191 -1 17192 -1 17193 -1 17194 -1 17195 -1 17196 -1 17197 -1 17198 -1 17199 -1 17200 -1 17201 -1 17202 -1 17203 -1 17204 -1 17205 -1 17206 -1 17207 -1 17208 -1 17209 -1 17210 -1 17211 -1 17212 -1 17213 -1 17214 -1 17215 -1 17216 -1 17217 -1 17218 -1 17219 -1 17220 -1 17221 -1 17222 -1 17223 -1 17224 -1 17225 -1 17226 -1 17227 -1 17228 -1 17229 -1 17230 -1 17231 -1 17232 -1 17233 -1 17234 -1 17235 -1 17236 -1 17237 -1 17238 -1 17239 -1 17240 -1 17241 -1 17242 -1 17243 -1 17244 -1 17245 -1 17246 -1 17247 -1 17248 -1 17249 -1 17250 -1 17251 -1 17252 -1 17253 -1 17254 -1 17255 -1 17256 -1 17257 -1 17258 -1 17259 -1 17260 -1 17261 -1 17262 -1 17263 -1 17264 -1 17265 -1 17266 -1 17267 -1 17268 -1 17269 -1 17270 -1 17271 -1 17272 -1 17273 -1 17274 -1 17275 -1 17276 -1 17277 -1 17278 -1 17279 -1 17280 -1 17281 -1 17282 -1 17283 -1 17284 -1 17285 -1 17286 -1 17287 -1 17288 -1 17289 -1 17290 -1 17291 -1 17292 -1 17293 -1 17294 -1 17295 -1 17296 -1 17297 -1 17298 -1 17299 -1 17300 -1 17301 -1 17302 -1 17303 -1 17304 -1 17305 -1 17306 -1 17307 -1 17308 -1 17309 -1 17310 -1 17311 -1 17312 -1 17313 -1 17314 -1 17315 -1 17316 -1 17317 -1 17318 -1 17319 -1 17320 -1 17321 -1 17322 -1 17323 -1 17324 -1 17325 -1 17326 -1 17327 -1 17328 -1 17329 -1 17330 -1 17331 -1 17332 -1 17333 -1 17334 -1 17335 -1 17336 -1 17337 -1 17338 -1 17339 -1 17340 -1 17341 -1 17342 -1 17343 -1 17344 -1 17345 -1 17346 -1 17347 -1 17348 -1 17349 -1 17350 -1 17351 -1 17352 -1 17353 -1 17354 -1 17355 -1 17356 -1 17357 -1 17358 -1 17359 -1 17360 -1 17361 -1 17362 -1 17363 -1 17364 -1 17365 -1 17366 -1 17367 -1 17368 -1 17369 -1 17370 -1 17371 -1 17372 -1 17373 -1 17374 -1 17375 -1 17376 -1 17377 -1 17378 -1 17379 -1 17380 -1 17381 -1 17382 -1 17383 -1 17384 -1 17385 -1 17386 -1 17387 -1 17388 -1 17389 -1 17390 -1 17391 -1 17392 -1 17393 -1 17394 -1 17395 -1 17396 -1 17397 -1 17398 -1 17399 -1 17400 -1 17401 -1 17402 -1 17403 -1 17404 -1 17405 -1 17406 -1 17407 -1 17408 -1 17409 -1 17410 -1 17411 -1 17412 -1 17413 -1 17414 -1 17415 -1 17416 -1 17417 -1 17418 -1 17419 -1 17420 -1 17421 -1 17422 -1 17423 -1 17424 -1 17425 -1 17426 -1 17427 -1 17428 -1 17429 -1 17430 -1 17431 -1 17432 -1 17433 -1 17434 -1 17435 -1 17436 -1 17437 -1 17438 -1 17439 -1 17440 -1 17441 -1 17442 -1 17443 -1 17444 -1 17445 -1 17446 -1 17447 -1 17448 -1 17449 -1 17450 -1 17451 -1 17452 -1 17453 -1 17454 -1 17455 -1 17456 -1 17457 -1 17458 -1 17459 -1 17460 -1 17461 -1 17462 -1 17463 -1 17464 -1 17465 -1 17466 -1 17467 -1 17468 -1 17469 -1 17470 -1 17471 -1 17472 -1 17473 -1 17474 -1 17475 -1 17476 -1 17477 -1 17478 -1 17479 -1 17480 -1 17481 -1 17482 -1 17483 -1 17484 -1 17485 -1 17486 -1 17487 -1 17488 -1 17489 -1 17490 -1 17491 -1 17492 -1 17493 -1 17494 -1 17495 -1 17496 -1 17497 -1 17498 -1 17499 -1 17500 -1 17501 -1 17502 -1 17503 -1 17504 -1 17505 -1 17506 -1 17507 -1 17508 -1 17509 -1 17510 -1 17511 -1 17512 -1 17513 -1 17514 -1 17515 -1 17516 -1 17517 -1 17518 -1 17519 -1 17520 -1 17521 -1 17522 -1 17523 -1 17524 -1 17525 -1 17526 -1 17527 -1 17528 -1 17529 -1 17530 -1 17531 -1 17532 -1 17533 -1 17534 -1 17535 -1 17536 -1 17537 -1 17538 -1 17539 -1 17540 -1 17541 -1 17542 -1 17543 -1 17544 -1 17545 -1 17546 -1 17547 -1 17548 -1 17549 -1 17550 -1 17551 -1 17552 -1 17553 -1 17554 -1 17555 -1 17556 -1 17557 -1 17558 -1 17559 -1 17560 -1 17561 -1 17562 -1 17563 -1 17564 -1 17565 -1 17566 -1 17567 -1 17568 -1 17569 -1 17570 -1 17571 -1 17572 -1 17573 -1 17574 -1 17575 -1 17576 -1 17577 -1 17578 -1 17579 -1 17580 -1 17581 -1 17582 -1 17583 -1 17584 -1 17585 -1 17586 -1 17587 -1 17588 -1 17589 -1 17590 -1 17591 -1 17592 -1 17593 -1 17594 -1 17595 -1 17596 -1 17597 -1 17598 -1 17599 -1 17600 -1 17601 -1 17602 -1 17603 -1 17604 -1 17605 -1 17606 -1 17607 -1 17608 -1 17609 -1 17610 -1 17611 -1 17612 -1 17613 -1 17614 -1 17615 -1 17616 -1 17617 -1 17618 -1 17619 -1 17620 -1 17621 -1 17622 -1 17623 -1 17624 -1 17625 -1 17626 -1 17627 -1 17628 -1 17629 -1 17630 -1 17631 -1 17632 -1 17633 -1 17634 -1 17635 -1 17636 -1 17637 -1 17638 -1 17639 -1 17640 -1 17641 -1 17642 -1 17643 -1 17644 -1 17645 -1 17646 -1 17647 -1 17648 -1 17649 -1 17650 -1 17651 -1 17652 -1 17653 -1 17654 -1 17655 -1 17656 -1 17657 -1 17658 -1 17659 -1 17660 -1 17661 -1 17662 -1 17663 -1 17664 -1 17665 -1 17666 -1 17667 -1 17668 -1 17669 -1 17670 -1 17671 -1 17672 -1 17673 -1 17674 -1 17675 -1 17676 -1 17677 -1 17678 -1 17679 -1 17680 -1 17681 -1 17682 -1 17683 -1 17684 -1 17685 -1 17686 -1 17687 -1 17688 -1 17689 -1 17690 -1 17691 -1 17692 -1 17693 -1 17694 -1 17695 -1 17696 -1 17697 -1 17698 -1 17699 -1 17700 -1 17701 -1 17702 -1 17703 -1 17704 -1 17705 -1 17706 -1 17707 -1 17708 -1 17709 -1 17710 -1 17711 -1 17712 -1 17713 -1 17714 -1 17715 -1 17716 -1 17717 -1 17718 -1 17719 -1 17720 -1 17721 -1 17722 -1 17723 -1 17724 -1 17725 -1 17726 -1 17727 -1 17728 -1 17729 -1 17730 -1 17731 -1 17732 -1 17733 -1 17734 -1 17735 -1 17736 -1 17737 -1 17738 -1 17739 -1 17740 -1 17741 -1 17742 -1 17743 -1 17744 -1 17745 -1 17746 -1 17747 -1 17748 -1 17749 -1 17750 -1 17751 -1 17752 -1 17753 -1 17754 -1 17755 -1 17756 -1 17757 -1 17758 -1 17759 -1 17760 -1 17761 -1 17762 -1 17763 -1 17764 -1 17765 -1 17766 -1 17767 -1 17768 -1 17769 -1 17770 -1 17771 -1 17772 -1 17773 -1 17774 -1 17775 -1 17776 -1 17777 -1 17778 -1 17779 -1 17780 -1 17781 -1 17782 -1 17783 -1 17784 -1 17785 -1 17786 -1 17787 -1 17788 -1 17789 -1 17790 -1 17791 -1 17792 -1 17793 -1 17794 -1 17795 -1 17796 -1 17797 -1 17798 -1 17799 -1 17800 -1 17801 -1 17802 -1 17803 -1 17804 -1 17805 -1 17806 -1 17807 -1 17808 -1 17809 -1 17810 -1 17811 -1 17812 -1 17813 -1 17814 -1 17815 -1 17816 -1 17817 -1 17818 -1 17819 -1 17820 -1 17821 -1 17822 -1 17823 -1 17824 -1 17825 -1 17826 -1 17827 -1 17828 -1 17829 -1 17830 -1 17831 -1 17832 -1 17833 -1 17834 -1 17835 -1 17836 -1 17837 -1 17838 -1 17839 -1 17840 -1 17841 -1 17842 -1 17843 -1 17844 -1 17845 -1 17846 -1 17847 -1 17848 -1 17849 -1 17850 -1 17851 -1 17852 -1 17853 -1 17854 -1 17855 -1 17856 -1 17857 -1 17858 -1 17859 -1 17860 -1 17861 -1 17862 -1 17863 -1 17864 -1 17865 -1 17866 -1 17867 -1 17868 -1 17869 -1 17870 -1 17871 -1 17872 -1 17873 -1 17874 -1 17875 -1 17876 -1 17877 -1 17878 -1 17879 -1 17880 -1 17881 -1 17882 -1 17883 -1 17884 -1 17885 -1 17886 -1 17887 -1 17888 -1 17889 -1 17890 -1 17891 -1 17892 -1 17893 -1 17894 -1 17895 -1 17896 -1 17897 -1 17898 -1 17899 -1 17900 -1 17901 -1 17902 -1 17903 -1 17904 -1 17905 -1 17906 -1 17907 -1 17908 -1 17909 -1 17910 -1 17911 -1 17912 -1 17913 -1 17914 -1 17915 -1 17916 -1 17917 -1 17918 -1 17919 -1 17920 -1 17921 -1 17922 -1 17923 -1 17924 -1 17925 -1 17926 -1 17927 -1 17928 -1 17929 -1 17930 -1 17931 -1 17932 -1 17933 -1 17934 -1 17935 -1 17936 -1 17937 -1 17938 -1 17939 -1 17940 -1 17941 -1 17942 -1 17943 -1 17944 -1 17945 -1 17946 -1 17947 -1 17948 -1 17949 -1 17950 -1 17951 -1 17952 -1 17953 -1 17954 -1 17955 -1 17956 -1 17957 -1 17958 -1 17959 -1 17960 -1 17961 -1 17962 -1 17963 -1 17964 -1 17965 -1 17966 -1 17967 -1 17968 -1 17969 -1 17970 -1 17971 -1 17972 -1 17973 -1 17974 -1 17975 -1 17976 -1 17977 -1 17978 -1 17979 -1 17980 -1 17981 -1 17982 -1 17983 -1 17984 -1 17985 -1 17986 -1 17987 -1 17988 -1 17989 -1 17990 -1 17991 -1 17992 -1 17993 -1 17994 -1 17995 -1 17996 -1 17997 -1 17998 -1 17999 -1 18000 -1 18001 -1 18002 -1 18003 -1 18004 -1 18005 -1 18006 -1 18007 -1 18008 -1 18009 -1 18010 -1 18011 -1 18012 -1 18013 -1 18014 -1 18015 -1 18016 -1 18017 -1 18018 -1 18019 -1 18020 -1 18021 -1 18022 -1 18023 -1 18024 -1 18025 -1 18026 -1 18027 -1 18028 -1 18029 -1 18030 -1 18031 -1 18032 -1 18033 -1 18034 -1 18035 -1 18036 -1 18037 -1 18038 -1 18039 -1 18040 -1 18041 -1 18042 -1 18043 -1 18044 -1 18045 -1 18046 -1 18047 -1 18048 -1 18049 -1 18050 -1 18051 -1 18052 -1 18053 -1 18054 -1 18055 -1 18056 -1 18057 -1 18058 -1 18059 -1 18060 -1 18061 -1 18062 -1 18063 -1 18064 -1 18065 -1 18066 -1 18067 -1 18068 -1 18069 -1 18070 -1 18071 -1 18072 -1 18073 -1 18074 -1 18075 -1 18076 -1 18077 -1 18078 -1 18079 -1 18080 -1 18081 -1 18082 -1 18083 -1 18084 -1 18085 -1 18086 -1 18087 -1 18088 -1 18089 -1 18090 -1 18091 -1 18092 -1 18093 -1 18094 -1 18095 -1 18096 -1 18097 -1 18098 -1 18099 -1 18100 -1 18101 -1 18102 -1 18103 -1 18104 -1 18105 -1 18106 -1 18107 -1 18108 -1 18109 -1 18110 -1 18111 -1 18112 -1 18113 -1 18114 -1 18115 -1 18116 -1 18117 -1 18118 -1 18119 -1 18120 -1 18121 -1 18122 -1 18123 -1 18124 -1 18125 -1 18126 -1 18127 -1 18128 -1 18129 -1 18130 -1 18131 -1 18132 -1 18133 -1 18134 -1 18135 -1 18136 -1 18137 -1 18138 -1 18139 -1 18140 -1 18141 -1 18142 -1 18143 -1 18144 -1 18145 -1 18146 -1 18147 -1 18148 -1 18149 -1 18150 -1 18151 -1 18152 -1 18153 -1 18154 -1 18155 -1 18156 -1 18157 -1 18158 -1 18159 -1 18160 -1 18161 -1 18162 -1 18163 -1 18164 -1 18165 -1 18166 -1 18167 -1 18168 -1 18169 -1 18170 -1 18171 -1 18172 -1 18173 -1 18174 -1 18175 -1 18176 -1 18177 -1 18178 -1 18179 -1 18180 -1 18181 -1 18182 -1 18183 -1 18184 -1 18185 -1 18186 -1 18187 -1 18188 -1 18189 -1 18190 -1 18191 -1 18192 -1 18193 -1 18194 -1 18195 -1 18196 -1 18197 -1 18198 -1 18199 -1 18200 -1 18201 -1 18202 -1 18203 -1 18204 -1 18205 -1 18206 -1 18207 -1 18208 -1 18209 -1 18210 -1 18211 -1 18212 -1 18213 -1 18214 -1 18215 -1 18216 -1 18217 -1 18218 -1 18219 -1 18220 -1 18221 -1 18222 -1 18223 -1 18224 -1 18225 -1 18226 -1 18227 -1 18228 -1 18229 -1 18230 -1 18231 -1 18232 -1 18233 -1 18234 -1 18235 -1 18236 -1 18237 -1 18238 -1 18239 -1 18240 -1 18241 -1 18242 -1 18243 -1 18244 -1 18245 -1 18246 -1 18247 -1 18248 -1 18249 -1 18250 -1 18251 -1 18252 -1 18253 -1 18254 -1 18255 -1 18256 -1 18257 -1 18258 -1 18259 -1 18260 -1 18261 -1 18262 -1 18263 -1 18264 -1 18265 -1 18266 -1 18267 -1 18268 -1 18269 -1 18270 -1 18271 -1 18272 -1 18273 -1 18274 -1 18275 -1 18276 -1 18277 -1 18278 -1 18279 -1 18280 -1 18281 -1 18282 -1 18283 -1 18284 -1 18285 -1 18286 -1 18287 -1 18288 -1 18289 -1 18290 -1 18291 -1 18292 -1 18293 -1 18294 -1 18295 -1 18296 -1 18297 -1 18298 -1 18299 -1 18300 -1 18301 -1 18302 -1 18303 -1 18304 -1 18305 -1 18306 -1 18307 -1 18308 -1 18309 -1 18310 -1 18311 -1 18312 -1 18313 -1 18314 -1 18315 -1 18316 -1 18317 -1 18318 -1 18319 -1 18320 -1 18321 -1 18322 -1 18323 -1 18324 -1 18325 -1 18326 -1 18327 -1 18328 -1 18329 -1 18330 -1 18331 -1 18332 -1 18333 -1 18334 -1 18335 -1 18336 -1 18337 -1 18338 -1 18339 -1 18340 -1 18341 -1 18342 -1 18343 -1 18344 -1 18345 -1 18346 -1 18347 -1 18348 -1 18349 -1 18350 -1 18351 -1 18352 -1 18353 -1 18354 -1 18355 -1 18356 -1 18357 -1 18358 -1 18359 -1 18360 -1 18361 -1 18362 -1 18363 -1 18364 -1 18365 -1 18366 -1 18367 -1 18368 -1 18369 -1 18370 -1 18371 -1 18372 -1 18373 -1 18374 -1 18375 -1 18376 -1 18377 -1 18378 -1 18379 -1 18380 -1 18381 -1 18382 -1 18383 -1 18384 -1 18385 -1 18386 -1 18387 -1 18388 -1 18389 -1 18390 -1 18391 -1 18392 -1 18393 -1 18394 -1 18395 -1 18396 -1 18397 -1 18398 -1 18399 -1 18400 -1 18401 -1 18402 -1 18403 -1 18404 -1 18405 -1 18406 -1 18407 -1 18408 -1 18409 -1 18410 -1 18411 -1 18412 -1 18413 -1 18414 -1 18415 -1 18416 -1 18417 -1 18418 -1 18419 -1 18420 -1 18421 -1 18422 -1 18423 -1 18424 -1 18425 -1 18426 -1 18427 -1 18428 -1 18429 -1 18430 -1 18431 -1 18432 -1 18433 -1 18434 -1 18435 -1 18436 -1 18437 -1 18438 -1 18439 -1 18440 -1 18441 -1 18442 -1 18443 -1 18444 -1 18445 -1 18446 -1 18447 -1 18448 -1 18449 -1 18450 -1 18451 -1 18452 -1 18453 -1 18454 -1 18455 -1 18456 -1 18457 -1 18458 -1 18459 -1 18460 -1 18461 -1 18462 -1 18463 -1 18464 -1 18465 -1 18466 -1 18467 -1 18468 -1 18469 -1 18470 -1 18471 -1 18472 -1 18473 -1 18474 -1 18475 -1 18476 -1 18477 -1 18478 -1 18479 -1 18480 -1 18481 -1 18482 -1 18483 -1 18484 -1 18485 -1 18486 -1 18487 -1 18488 -1 18489 -1 18490 -1 18491 -1 18492 -1 18493 -1 18494 -1 18495 -1 18496 -1 18497 -1 18498 -1 18499 -1 18500 -1 18501 -1 18502 -1 18503 -1 18504 -1 18505 -1 18506 -1 18507 -1 18508 -1 18509 -1 18510 -1 18511 -1 18512 -1 18513 -1 18514 -1 18515 -1 18516 -1 18517 -1 18518 -1 18519 -1 18520 -1 18521 -1 18522 -1 18523 -1 18524 -1 18525 -1 18526 -1 18527 -1 18528 -1 18529 -1 18530 -1 18531 -1 18532 -1 18533 -1 18534 -1 18535 -1 18536 -1 18537 -1 18538 -1 18539 -1 18540 -1 18541 -1 18542 -1 18543 -1 18544 -1 18545 -1 18546 -1 18547 -1 18548 -1 18549 -1 18550 -1 18551 -1 18552 -1 18553 -1 18554 -1 18555 -1 18556 -1 18557 -1 18558 -1 18559 -1 18560 -1 18561 -1 18562 -1 18563 -1 18564 -1 18565 -1 18566 -1 18567 -1 18568 -1 18569 -1 18570 -1 18571 -1 18572 -1 18573 -1 18574 -1 18575 -1 18576 -1 18577 -1 18578 -1 18579 -1 18580 -1 18581 -1 18582 -1 18583 -1 18584 -1 18585 -1 18586 -1 18587 -1 18588 -1 18589 -1 18590 -1 18591 -1 18592 -1 18593 -1 18594 -1 18595 -1 18596 -1 18597 -1 18598 -1 18599 -1 18600 -1 18601 -1 18602 -1 18603 -1 18604 -1 18605 -1 18606 -1 18607 -1 18608 -1 18609 -1 18610 -1 18611 -1 18612 -1 18613 -1 18614 -1 18615 -1 18616 -1 18617 -1 18618 -1 18619 -1 18620 -1 18621 -1 18622 -1 18623 -1 18624 -1 18625 -1 18626 -1 18627 -1 18628 -1 18629 -1 18630 -1 18631 -1 18632 -1 18633 -1 18634 -1 18635 -1 18636 -1 18637 -1 18638 -1 18639 -1 18640 -1 18641 -1 18642 -1 18643 -1 18644 -1 18645 -1 18646 -1 18647 -1 18648 -1 18649 -1 18650 -1 18651 -1 18652 -1 18653 -1 18654 -1 18655 -1 18656 -1 18657 -1 18658 -1 18659 -1 18660 -1 18661 -1 18662 -1 18663 -1 18664 -1 18665 -1 18666 -1 18667 -1 18668 -1 18669 -1 18670 -1 18671 -1 18672 -1 18673 -1 18674 -1 18675 -1 18676 -1 18677 -1 18678 -1 18679 -1 18680 -1 18681 -1 18682 -1 18683 -1 18684 -1 18685 -1 18686 -1 18687 -1 18688 -1 18689 -1 18690 -1 18691 -1 18692 -1 18693 -1 18694 -1 18695 -1 18696 -1 18697 -1 18698 -1 18699 -1 18700 -1 18701 -1 18702 -1 18703 -1 18704 -1 18705 -1 18706 -1 18707 -1 18708 -1 18709 -1 18710 -1 18711 -1 18712 -1 18713 -1 18714 -1 18715 -1 18716 -1 18717 -1 18718 -1 18719 -1 18720 -1 18721 -1 18722 -1 18723 -1 18724 -1 18725 -1 18726 -1 18727 -1 18728 -1 18729 -1 18730 -1 18731 -1 18732 -1 18733 -1 18734 -1 18735 -1 18736 -1 18737 -1 18738 -1 18739 -1 18740 -1 18741 -1 18742 -1 18743 -1 18744 -1 18745 -1 18746 -1 18747 -1 18748 -1 18749 -1 18750 -1 18751 -1 18752 -1 18753 -1 18754 -1 18755 -1 18756 -1 18757 -1 18758 -1 18759 -1 18760 -1 18761 -1 18762 -1 18763 -1 18764 -1 18765 -1 18766 -1 18767 -1 18768 -1 18769 -1 18770 -1 18771 -1 18772 -1 18773 -1 18774 -1 18775 -1 18776 -1 18777 -1 18778 -1 18779 -1 18780 -1 18781 -1 18782 -1 18783 -1 18784 -1 18785 -1 18786 -1 18787 -1 18788 -1 18789 -1 18790 -1 18791 -1 18792 -1 18793 -1 18794 -1 18795 -1 18796 -1 18797 -1 18798 -1 18799 -1 18800 -1 18801 -1 18802 -1 18803 -1 18804 -1 18805 -1 18806 -1 18807 -1 18808 -1 18809 -1 18810 -1 18811 -1 18812 -1 18813 -1 18814 -1 18815 -1 18816 -1 18817 -1 18818 -1 18819 -1 18820 -1 18821 -1 18822 -1 18823 -1 18824 -1 18825 -1 18826 -1 18827 -1 18828 -1 18829 -1 18830 -1 18831 -1 18832 -1 18833 -1 18834 -1 18835 -1 18836 -1 18837 -1 18838 -1 18839 -1 18840 -1 18841 -1 18842 -1 18843 -1 18844 -1 18845 -1 18846 -1 18847 -1 18848 -1 18849 -1 18850 -1 18851 -1 18852 -1 18853 -1 18854 -1 18855 -1 18856 -1 18857 -1 18858 -1 18859 -1 18860 -1 18861 -1 18862 -1 18863 -1 18864 -1 18865 -1 18866 -1 18867 -1 18868 -1 18869 -1 18870 -1 18871 -1 18872 -1 18873 -1 18874 -1 18875 -1 18876 -1 18877 -1 18878 -1 18879 -1 18880 -1 18881 -1 18882 -1 18883 -1 18884 -1 18885 -1 18886 -1 18887 -1 18888 -1 18889 -1 18890 -1 18891 -1 18892 -1 18893 -1 18894 -1 18895 -1 18896 -1 18897 -1 18898 -1 18899 -1 18900 -1 18901 -1 18902 -1 18903 -1 18904 -1 18905 -1 18906 -1 18907 -1 18908 -1 18909 -1 18910 -1 18911 -1 18912 -1 18913 -1 18914 -1 18915 -1 18916 -1 18917 -1 18918 -1 18919 -1 18920 -1 18921 -1 18922 -1 18923 -1 18924 -1 18925 -1 18926 -1 18927 -1 18928 -1 18929 -1 18930 -1 18931 -1 18932 -1 18933 -1 18934 -1 18935 -1 18936 -1 18937 -1 18938 -1 18939 -1 18940 -1 18941 -1 18942 -1 18943 -1 18944 -1 18945 -1 18946 -1 18947 -1 18948 -1 18949 -1 18950 -1 18951 -1 18952 -1 18953 -1 18954 -1 18955 -1 18956 -1 18957 -1 18958 -1 18959 -1 18960 -1 18961 -1 18962 -1 18963 -1 18964 -1 18965 -1 18966 -1 18967 -1 18968 -1 18969 -1 18970 -1 18971 -1 18972 -1 18973 -1 18974 -1 18975 -1 18976 -1 18977 -1 18978 -1 18979 -1 18980 -1 18981 -1 18982 -1 18983 -1 18984 -1 18985 -1 18986 -1 18987 -1 18988 -1 18989 -1 18990 -1 18991 -1 18992 -1 18993 -1 18994 -1 18995 -1 18996 -1 18997 -1 18998 -1 18999 -1 19000 -1 19001 -1 19002 -1 19003 -1 19004 -1 19005 -1 19006 -1 19007 -1 19008 -1 19009 -1 19010 -1 19011 -1 19012 -1 19013 -1 19014 -1 19015 -1 19016 -1 19017 -1 19018 -1 19019 -1 19020 -1 19021 -1 19022 -1 19023 -1 19024 -1 19025 -1 19026 -1 19027 -1 19028 -1 19029 -1 19030 -1 19031 -1 19032 -1 19033 -1 19034 -1 19035 -1 19036 -1 19037 -1 19038 -1 19039 -1 19040 -1 19041 -1 19042 -1 19043 -1 19044 -1 19045 -1 19046 -1 19047 -1 19048 -1 19049 -1 19050 -1 19051 -1 19052 -1 19053 -1 19054 -1 19055 -1 19056 -1 19057 -1 19058 -1 19059 -1 19060 -1 19061 -1 19062 -1 19063 -1 19064 -1 19065 -1 19066 -1 19067 -1 19068 -1 19069 -1 19070 -1 19071 -1 19072 -1 19073 -1 19074 -1 19075 -1 19076 -1 19077 -1 19078 -1 19079 -1 19080 -1 19081 -1 19082 -1 19083 -1 19084 -1 19085 -1 19086 -1 19087 -1 19088 -1 19089 -1 19090 -1 19091 -1 19092 -1 19093 -1 19094 -1 19095 -1 19096 -1 19097 -1 19098 -1 19099 -1 19100 -1 19101 -1 19102 -1 19103 -1 19104 -1 19105 -1 19106 -1 19107 -1 19108 -1 19109 -1 19110 -1 19111 -1 19112 -1 19113 -1 19114 -1 19115 -1 19116 -1 19117 -1 19118 -1 19119 -1 19120 -1 19121 -1 19122 -1 19123 -1 19124 -1 19125 -1 19126 -1 19127 -1 19128 -1 19129 -1 19130 -1 19131 -1 19132 -1 19133 -1 19134 -1 19135 -1 19136 -1 19137 -1 19138 -1 19139 -1 19140 -1 19141 -1 19142 -1 19143 -1 19144 -1 19145 -1 19146 -1 19147 -1 19148 -1 19149 -1 19150 -1 19151 -1 19152 -1 19153 -1 19154 -1 19155 -1 19156 -1 19157 -1 19158 -1 19159 -1 19160 -1 19161 -1 19162 -1 19163 -1 19164 -1 19165 -1 19166 -1 19167 -1 19168 -1 19169 -1 19170 -1 19171 -1 19172 -1 19173 -1 19174 -1 19175 -1 19176 -1 19177 -1 19178 -1 19179 -1 19180 -1 19181 -1 19182 -1 19183 -1 19184 -1 19185 -1 19186 -1 19187 -1 19188 -1 19189 -1 19190 -1 19191 -1 19192 -1 19193 -1 19194 -1 19195 -1 19196 -1 19197 -1 19198 -1 19199 -1 19200 -1 19201 -1 19202 -1 19203 -1 19204 -1 19205 -1 19206 -1 19207 -1 19208 -1 19209 -1 19210 -1 19211 -1 19212 -1 19213 -1 19214 -1 19215 -1 19216 -1 19217 -1 19218 -1 19219 -1 19220 -1 19221 -1 19222 -1 19223 -1 19224 -1 19225 -1 19226 -1 19227 -1 19228 -1 19229 -1 19230 -1 19231 -1 19232 -1 19233 -1 19234 -1 19235 -1 19236 -1 19237 -1 19238 -1 19239 -1 19240 -1 19241 -1 19242 -1 19243 -1 19244 -1 19245 -1 19246 -1 19247 -1 19248 -1 19249 -1 19250 -1 19251 -1 19252 -1 19253 -1 19254 -1 19255 -1 19256 -1 19257 -1 19258 -1 19259 -1 19260 -1 19261 -1 19262 -1 19263 -1 19264 -1 19265 -1 19266 -1 19267 -1 19268 -1 19269 -1 19270 -1 19271 -1 19272 -1 19273 -1 19274 -1 19275 -1 19276 -1 19277 -1 19278 -1 19279 -1 19280 -1 19281 -1 19282 -1 19283 -1 19284 -1 19285 -1 19286 -1 19287 -1 19288 -1 19289 -1 19290 -1 19291 -1 19292 -1 19293 -1 19294 -1 19295 -1 19296 -1 19297 -1 19298 -1 19299 -1 19300 -1 19301 -1 19302 -1 19303 -1 19304 -1 19305 -1 19306 -1 19307 -1 19308 -1 19309 -1 19310 -1 19311 -1 19312 -1 19313 -1 19314 -1 19315 -1 19316 -1 19317 -1 19318 -1 19319 -1 19320 -1 19321 -1 19322 -1 19323 -1 19324 -1 19325 -1 19326 -1 19327 -1 19328 -1 19329 -1 19330 -1 19331 -1 19332 -1 19333 -1 19334 -1 19335 -1 19336 -1 19337 -1 19338 -1 19339 -1 19340 -1 19341 -1 19342 -1 19343 -1 19344 -1 19345 -1 19346 -1 19347 -1 19348 -1 19349 -1 19350 -1 19351 -1 19352 -1 19353 -1 19354 -1 19355 -1 19356 -1 19357 -1 19358 -1 19359 -1 19360 -1 19361 -1 19362 -1 19363 -1 19364 -1 19365 -1 19366 -1 19367 -1 19368 -1 19369 -1 19370 -1 19371 -1 19372 -1 19373 -1 19374 -1 19375 -1 19376 -1 19377 -1 19378 -1 19379 -1 19380 -1 19381 -1 19382 -1 19383 -1 19384 -1 19385 -1 19386 -1 19387 -1 19388 -1 19389 -1 19390 -1 19391 -1 19392 -1 19393 -1 19394 -1 19395 -1 19396 -1 19397 -1 19398 -1 19399 -1 19400 -1 19401 -1 19402 -1 19403 -1 19404 -1 19405 -1 19406 -1 19407 -1 19408 -1 19409 -1 19410 -1 19411 -1 19412 -1 19413 -1 19414 -1 19415 -1 19416 -1 19417 -1 19418 -1 19419 -1 19420 -1 19421 -1 19422 -1 19423 -1 19424 -1 19425 -1 19426 -1 19427 -1 19428 -1 19429 -1 19430 -1 19431 -1 19432 -1 19433 -1 19434 -1 19435 -1 19436 -1 19437 -1 19438 -1 19439 -1 19440 -1 19441 -1 19442 -1 19443 -1 19444 -1 19445 -1 19446 -1 19447 -1 19448 -1 19449 -1 19450 -1 19451 -1 19452 -1 19453 -1 19454 -1 19455 -1 19456 -1 19457 -1 19458 -1 19459 -1 19460 -1 19461 -1 19462 -1 19463 -1 19464 -1 19465 -1 19466 -1 19467 -1 19468 -1 19469 -1 19470 -1 19471 -1 19472 -1 19473 -1 19474 -1 19475 -1 19476 -1 19477 -1 19478 -1 19479 -1 19480 -1 19481 -1 19482 -1 19483 -1 19484 -1 19485 -1 19486 -1 19487 -1 19488 -1 19489 -1 19490 -1 19491 -1 19492 -1 19493 -1 19494 -1 19495 -1 19496 -1 19497 -1 19498 -1 19499 -1 19500 -1 19501 -1 19502 -1 19503 -1 19504 -1 19505 -1 19506 -1 19507 -1 19508 -1 19509 -1 19510 -1 19511 -1 19512 -1 19513 -1 19514 -1 19515 -1 19516 -1 19517 -1 19518 -1 19519 -1 19520 -1 19521 -1 19522 -1 19523 -1 19524 -1 19525 -1 19526 -1 19527 -1 19528 -1 19529 -1 19530 -1 19531 -1 19532 -1 19533 -1 19534 -1 19535 -1 19536 -1 19537 -1 19538 -1 19539 -1 19540 -1 19541 -1 19542 -1 19543 -1 19544 -1 19545 -1 19546 -1 19547 -1 19548 -1 19549 -1 19550 -1 19551 -1 19552 -1 19553 -1 19554 -1 19555 -1 19556 -1 19557 -1 19558 -1 19559 -1 19560 -1 19561 -1 19562 -1 19563 -1 19564 -1 19565 -1 19566 -1 19567 -1 19568 -1 19569 -1 19570 -1 19571 -1 19572 -1 19573 -1 19574 -1 19575 -1 19576 -1 19577 -1 19578 -1 19579 -1 19580 -1 19581 -1 19582 -1 19583 -1 19584 -1 19585 -1 19586 -1 19587 -1 19588 -1 19589 -1 19590 -1 19591 -1 19592 -1 19593 -1 19594 -1 19595 -1 19596 -1 19597 -1 19598 -1 19599 -1 19600 -1 19601 -1 19602 -1 19603 -1 19604 -1 19605 -1 19606 -1 19607 -1 19608 -1 19609 -1 19610 -1 19611 -1 19612 -1 19613 -1 19614 -1 19615 -1 19616 -1 19617 -1 19618 -1 19619 -1 19620 -1 19621 -1 19622 -1 19623 -1 19624 -1 19625 -1 19626 -1 19627 -1 19628 -1 19629 -1 19630 -1 19631 -1 19632 -1 19633 -1 19634 -1 19635 -1 19636 -1 19637 -1 19638 -1 19639 -1 19640 -1 19641 -1 19642 -1 19643 -1 19644 -1 19645 -1 19646 -1 19647 -1 19648 -1 19649 -1 19650 -1 19651 -1 19652 -1 19653 -1 19654 -1 19655 -1 19656 -1 19657 -1 19658 -1 19659 -1 19660 -1 19661 -1 19662 -1 19663 -1 19664 -1 19665 -1 19666 -1 19667 -1 19668 -1 19669 -1 19670 -1 19671 -1 19672 -1 19673 -1 19674 -1 19675 -1 19676 -1 19677 -1 19678 -1 19679 -1 19680 -1 19681 -1 19682 -1 19683 -1 19684 -1 19685 -1 19686 -1 19687 -1 19688 -1 19689 -1 19690 -1 19691 -1 19692 -1 19693 -1 19694 -1 19695 -1 19696 -1 19697 -1 19698 -1 19699 -1 19700 -1 19701 -1 19702 -1 19703 -1 19704 -1 19705 -1 19706 -1 19707 -1 19708 -1 19709 -1 19710 -1 19711 -1 19712 -1 19713 -1 19714 -1 19715 -1 19716 -1 19717 -1 19718 -1 19719 -1 19720 -1 19721 -1 19722 -1 19723 -1 19724 -1 19725 -1 19726 -1 19727 -1 19728 -1 19729 -1 19730 -1 19731 -1 19732 -1 19733 -1 19734 -1 19735 -1 19736 -1 19737 -1 19738 -1 19739 -1 19740 -1 19741 -1 19742 -1 19743 -1 19744 -1 19745 -1 19746 -1 19747 -1 19748 -1 19749 -1 19750 -1 19751 -1 19752 -1 19753 -1 19754 -1 19755 -1 19756 -1 19757 -1 19758 -1 19759 -1 19760 -1 19761 -1 19762 -1 19763 -1 19764 -1 19765 -1 19766 -1 19767 -1 19768 -1 19769 -1 19770 -1 19771 -1 19772 -1 19773 -1 19774 -1 19775 -1 19776 -1 19777 -1 19778 -1 19779 -1 19780 -1 19781 -1 19782 -1 19783 -1 19784 -1 19785 -1 19786 -1 19787 -1 19788 -1 19789 -1 19790 -1 19791 -1 19792 -1 19793 -1 19794 -1 19795 -1 19796 -1 19797 -1 19798 -1 19799 -1 19800 -1 19801 -1 19802 -1 19803 -1 19804 -1 19805 -1 19806 -1 19807 -1 19808 -1 19809 -1 19810 -1 19811 -1 19812 -1 19813 -1 19814 -1 19815 -1 19816 -1 19817 -1 19818 -1 19819 -1 19820 -1 19821 -1 19822 -1 19823 -1 19824 -1 19825 -1 19826 -1 19827 -1 19828 -1 19829 -1 19830 -1 19831 -1 19832 -1 19833 -1 19834 -1 19835 -1 19836 -1 19837 -1 19838 -1 19839 -1 19840 -1 19841 -1 19842 -1 19843 -1 19844 -1 19845 -1 19846 -1 19847 -1 19848 -1 19849 -1 19850 -1 19851 -1 19852 -1 19853 -1 19854 -1 19855 -1 19856 -1 19857 -1 19858 -1 19859 -1 19860 -1 19861 -1 19862 -1 19863 -1 19864 -1 19865 -1 19866 -1 19867 -1 19868 -1 19869 -1 19870 -1 19871 -1 19872 -1 19873 -1 19874 -1 19875 -1 19876 -1 19877 -1 19878 -1 19879 -1 19880 -1 19881 -1 19882 -1 19883 -1 19884 -1 19885 -1 19886 -1 19887 -1 19888 -1 19889 -1 19890 -1 19891 -1 19892 -1 19893 -1 19894 -1 19895 -1 19896 -1 19897 -1 19898 -1 19899 -1 19900 -1 19901 -1 19902 -1 19903 -1 19904 -1 19905 -1 19906 -1 19907 -1 19908 -1 19909 -1 19910 -1 19911 -1 19912 -1 19913 -1 19914 -1 19915 -1 19916 -1 19917 -1 19918 -1 19919 -1 19920 -1 19921 -1 19922 -1 19923 -1 19924 -1 19925 -1 19926 -1 19927 -1 19928 -1 19929 -1 19930 -1 19931 -1 19932 -1 19933 -1 19934 -1 19935 -1 19936 -1 19937 -1 19938 -1 19939 -1 19940 -1 19941 -1 19942 -1 19943 -1 19944 -1 19945 -1 19946 -1 19947 -1 19948 -1 19949 -1 19950 -1 19951 -1 19952 -1 19953 -1 19954 -1 19955 -1 19956 -1 19957 -1 19958 -1 19959 -1 19960 -1 19961 -1 19962 -1 19963 -1 19964 -1 19965 -1 19966 -1 19967 -1 19968 -1 19969 -1 19970 -1 19971 -1 19972 -1 19973 -1 19974 -1 19975 -1 19976 -1 19977 -1 19978 -1 19979 -1 19980 -1 19981 -1 19982 -1 19983 -1 19984 -1 19985 -1 19986 -1 19987 -1 19988 -1 19989 -1 19990 -1 19991 -1 19992 -1 19993 -1 19994 -1 19995 -1 19996 -1 19997 -1 19998 -1 19999 -1 20000 -1 20001 -1 20002 -1 20003 -1 20004 -1 20005 -1 20006 -1 20007 -1 20008 -1 20009 -1 20010 -1 20011 -1 20012 -1 20013 -1 20014 -1 20015 -1 20016 -1 20017 -1 20018 -1 20019 -1 20020 -1 20021 -1 20022 -1 20023 -1 20024 -1 20025 -1 20026 -1 20027 -1 20028 -1 20029 -1 20030 -1 20031 -1 20032 -1 20033 -1 20034 -1 20035 -1 20036 -1 20037 -1 20038 -1 20039 -1 20040 -1 20041 -1 20042 -1 20043 -1 20044 -1 20045 -1 20046 -1 20047 -1 20048 -1 20049 -1 20050 -1 20051 -1 20052 -1 20053 -1 20054 -1 20055 -1 20056 -1 20057 -1 20058 -1 20059 -1 20060 -1 20061 -1 20062 -1 20063 -1 20064 -1 20065 -1 20066 -1 20067 -1 20068 -1 20069 -1 20070 -1 20071 -1 20072 -1 20073 -1 20074 -1 20075 -1 20076 -1 20077 -1 20078 -1 20079 -1 20080 -1 20081 -1 20082 -1 20083 -1 20084 -1 20085 -1 20086 -1 20087 -1 20088 -1 20089 -1 20090 -1 20091 -1 20092 -1 20093 -1 20094 -1 20095 -1 20096 -1 20097 -1 20098 -1 20099 -1 20100 -1 20101 -1 20102 -1 20103 -1 20104 -1 20105 -1 20106 -1 20107 -1 20108 -1 20109 -1 20110 -1 20111 -1 20112 -1 20113 -1 20114 -1 20115 -1 20116 -1 20117 -1 20118 -1 20119 -1 20120 -1 20121 -1 20122 -1 20123 -1 20124 -1 20125 -1 20126 -1 20127 -1 20128 -1 20129 -1 20130 -1 20131 -1 20132 -1 20133 -1 20134 -1 20135 -1 20136 -1 20137 -1 20138 -1 20139 -1 20140 -1 20141 -1 20142 -1 20143 -1 20144 -1 20145 -1 20146 -1 20147 -1 20148 -1 20149 -1 20150 -1 20151 -1 20152 -1 20153 -1 20154 -1 20155 -1 20156 -1 20157 -1 20158 -1 20159 -1 20160 -1 20161 -1 20162 -1 20163 -1 20164 -1 20165 -1 20166 -1 20167 -1 20168 -1 20169 -1 20170 -1 20171 -1 20172 -1 20173 -1 20174 -1 20175 -1 20176 -1 20177 -1 20178 -1 20179 -1 20180 -1 20181 -1 20182 -1 20183 -1 20184 -1 20185 -1 20186 -1 20187 -1 20188 -1 20189 -1 20190 -1 20191 -1 20192 -1 20193 -1 20194 -1 20195 -1 20196 -1 20197 -1 20198 -1 20199 -1 20200 -1 20201 -1 20202 -1 20203 -1 20204 -1 20205 -1 20206 -1 20207 -1 20208 -1 20209 -1 20210 -1 20211 -1 20212 -1 20213 -1 20214 -1 20215 -1 20216 -1 20217 -1 20218 -1 20219 -1 20220 -1 20221 -1 20222 -1 20223 -1 20224 -1 20225 -1 20226 -1 20227 -1 20228 -1 20229 -1 20230 -1 20231 -1 20232 -1 20233 -1 20234 -1 20235 -1 20236 -1 20237 -1 20238 -1 20239 -1 20240 -1 20241 -1 20242 -1 20243 -1 20244 -1 20245 -1 20246 -1 20247 -1 20248 -1 20249 -1 20250 -1 20251 -1 20252 -1 20253 -1 20254 -1 20255 -1 20256 -1 20257 -1 20258 -1 20259 -1 20260 -1 20261 -1 20262 -1 20263 -1 20264 -1 20265 -1 20266 -1 20267 -1 20268 -1 20269 -1 20270 -1 20271 -1 20272 -1 20273 -1 20274 -1 20275 -1 20276 -1 20277 -1 20278 -1 20279 -1 20280 -1 20281 -1 20282 -1 20283 -1 20284 -1 20285 -1 20286 -1 20287 -1 20288 -1 20289 -1 20290 -1 20291 -1 20292 -1 20293 -1 20294 -1 20295 -1 20296 -1 20297 -1 20298 -1 20299 -1 20300 -1 20301 -1 20302 -1 20303 -1 20304 -1 20305 -1 20306 -1 20307 -1 20308 -1 20309 -1 20310 -1 20311 -1 20312 -1 20313 -1 20314 -1 20315 -1 20316 -1 20317 -1 20318 -1 20319 -1 20320 -1 20321 -1 20322 -1 20323 -1 20324 -1 20325 -1 20326 -1 20327 -1 20328 -1 20329 -1 20330 -1 20331 -1 20332 -1 20333 -1 20334 -1 20335 -1 20336 -1 20337 -1 20338 -1 20339 -1 20340 -1 20341 -1 20342 -1 20343 -1 20344 -1 20345 -1 20346 -1 20347 -1 20348 -1 20349 -1 20350 -1 20351 -1 20352 -1 20353 -1 20354 -1 20355 -1 20356 -1 20357 -1 20358 -1 20359 -1 20360 -1 20361 -1 20362 -1 20363 -1 20364 -1 20365 -1 20366 -1 20367 -1 20368 -1 20369 -1 20370 -1 20371 -1 20372 -1 20373 -1 20374 -1 20375 -1 20376 -1 20377 -1 20378 -1 20379 -1 20380 -1 20381 -1 20382 -1 20383 -1 20384 -1 20385 -1 20386 -1 20387 -1 20388 -1 20389 -1 20390 -1 20391 -1 20392 -1 20393 -1 20394 -1 20395 -1 20396 -1 20397 -1 20398 -1 20399 -1 20400 -1 20401 -1 20402 -1 20403 -1 20404 -1 20405 -1 20406 -1 20407 -1 20408 -1 20409 -1 20410 -1 20411 -1 20412 -1 20413 -1 20414 -1 20415 -1 20416 -1 20417 -1 20418 -1 20419 -1 20420 -1 20421 -1 20422 -1 20423 -1 20424 -1 20425 -1 20426 -1 20427 -1 20428 -1 20429 -1 20430 -1 20431 -1 20432 -1 20433 -1 20434 -1 20435 -1 20436 -1 20437 -1 20438 -1 20439 -1 20440 -1 20441 -1 20442 -1 20443 -1 20444 -1 20445 -1 20446 -1 20447 -1 20448 -1 20449 -1 20450 -1 20451 -1 20452 -1 20453 -1 20454 -1 20455 -1 20456 -1 20457 -1 20458 -1 20459 -1 20460 -1 20461 -1 20462 -1 20463 -1 20464 -1 20465 -1 20466 -1 20467 -1 20468 -1 20469 -1 20470 -1 20471 -1 20472 -1 20473 -1 20474 -1 20475 -1 20476 -1 20477 -1 20478 -1 20479 -1 20480 -1 20481 -1 20482 -1 20483 -1 20484 -1 20485 -1 20486 -1 20487 -1 20488 -1 20489 -1 20490 -1 20491 -1 20492 -1 20493 -1 20494 -1 20495 -1 20496 -1 20497 -1 20498 -1 20499 -1 20500 -1 20501 -1 20502 -1 20503 -1 20504 -1 20505 -1 20506 -1 20507 -1 20508 -1 20509 -1 20510 -1 20511 -1 20512 -1 20513 -1 20514 -1 20515 -1 20516 -1 20517 -1 20518 -1 20519 -1 20520 -1 20521 -1 20522 -1 20523 -1 20524 -1 20525 -1 20526 -1 20527 -1 20528 -1 20529 -1 20530 -1 20531 -1 20532 -1 20533 -1 20534 -1 20535 -1 20536 -1 20537 -1 20538 -1 20539 -1 20540 -1 20541 -1 20542 -1 20543 -1 20544 -1 20545 -1 20546 -1 20547 -1 20548 -1 20549 -1 20550 -1 20551 -1 20552 -1 20553 -1 20554 -1 20555 -1 20556 -1 20557 -1 20558 -1 20559 -1 20560 -1 20561 -1 20562 -1 20563 -1 20564 -1 20565 -1 20566 -1 20567 -1 20568 -1 20569 -1 20570 -1 20571 -1 20572 -1 20573 -1 20574 -1 20575 -1 20576 -1 20577 -1 20578 -1 20579 -1 20580 -1 20581 -1 20582 -1 20583 -1 20584 -1 20585 -1 20586 -1 20587 -1 20588 -1 20589 -1 20590 -1 20591 -1 20592 -1 20593 -1 20594 -1 20595 -1 20596 -1 20597 -1 20598 -1 20599 -1 20600 -1 20601 -1 20602 -1 20603 -1 20604 -1 20605 -1 20606 -1 20607 -1 20608 -1 20609 -1 20610 -1 20611 -1 20612 -1 20613 -1 20614 -1 20615 -1 20616 -1 20617 -1 20618 -1 20619 -1 20620 -1 20621 -1 20622 -1 20623 -1 20624 -1 20625 -1 20626 -1 20627 -1 20628 -1 20629 -1 20630 -1 20631 -1 20632 -1 20633 -1 20634 -1 20635 -1 20636 -1 20637 -1 20638 -1 20639 -1 20640 -1 20641 -1 20642 -1 20643 -1 20644 -1 20645 -1 20646 -1 20647 -1 20648 -1 20649 -1 20650 -1 20651 -1 20652 -1 20653 -1 20654 -1 20655 -1 20656 -1 20657 -1 20658 -1 20659 -1 20660 -1 20661 -1 20662 -1 20663 -1 20664 -1 20665 -1 20666 -1 20667 -1 20668 -1 20669 -1 20670 -1 20671 -1 20672 -1 20673 -1 20674 -1 20675 -1 20676 -1 20677 -1 20678 -1 20679 -1 20680 -1 20681 -1 20682 -1 20683 -1 20684 -1 20685 -1 20686 -1 20687 -1 20688 -1 20689 -1 20690 -1 20691 -1 20692 -1 20693 -1 20694 -1 20695 -1 20696 -1 20697 -1 20698 -1 20699 -1 20700 -1 20701 -1 20702 -1 20703 -1 20704 -1 20705 -1 20706 -1 20707 -1 20708 -1 20709 -1 20710 -1 20711 -1 20712 -1 20713 -1 20714 -1 20715 -1 20716 -1 20717 -1 20718 -1 20719 -1 20720 -1 20721 -1 20722 -1 20723 -1 20724 -1 20725 -1 20726 -1 20727 -1 20728 -1 20729 -1 20730 -1 20731 -1 20732 -1 20733 -1 20734 -1 20735 -1 20736 -1 20737 -1 20738 -1 20739 -1 20740 -1 20741 -1 20742 -1 20743 -1 20744 -1 20745 -1 20746 -1 20747 -1 20748 -1 20749 -1 20750 -1 20751 -1 20752 -1 20753 -1 20754 -1 20755 -1 20756 -1 20757 -1 20758 -1 20759 -1 20760 -1 20761 -1 20762 -1 20763 -1 20764 -1 20765 -1 20766 -1 20767 -1 20768 -1 20769 -1 20770 -1 20771 -1 20772 -1 20773 -1 20774 -1 20775 -1 20776 -1 20777 -1 20778 -1 20779 -1 20780 -1 20781 -1 20782 -1 20783 -1 20784 -1 20785 -1 20786 -1 20787 -1 20788 -1 20789 -1 20790 -1 20791 -1 20792 -1 20793 -1 20794 -1 20795 -1 20796 -1 20797 -1 20798 -1 20799 -1 20800 -1 20801 -1 20802 -1 20803 -1 20804 -1 20805 -1 20806 -1 20807 -1 20808 -1 20809 -1 20810 -1 20811 -1 20812 -1 20813 -1 20814 -1 20815 -1 20816 -1 20817 -1 20818 -1 20819 -1 20820 -1 20821 -1 20822 -1 20823 -1 20824 -1 20825 -1 20826 -1 20827 -1 20828 -1 20829 -1 20830 -1 20831 -1 20832 -1 20833 -1 20834 -1 20835 -1 20836 -1 20837 -1 20838 -1 20839 -1 20840 -1 20841 -1 20842 -1 20843 -1 20844 -1 20845 -1 20846 -1 20847 -1 20848 -1 20849 -1 20850 -1 20851 -1 20852 -1 20853 -1 20854 -1 20855 -1 20856 -1 20857 -1 20858 -1 20859 -1 20860 -1 20861 -1 20862 -1 20863 -1 20864 -1 20865 -1 20866 -1 20867 -1 20868 -1 20869 -1 20870 -1 20871 -1 20872 -1 20873 -1 20874 -1 20875 -1 20876 -1 20877 -1 20878 -1 20879 -1 20880 -1 20881 -1 20882 -1 20883 -1 20884 -1 20885 -1 20886 -1 20887 -1 20888 -1 20889 -1 20890 -1 20891 -1 20892 -1 20893 -1 20894 -1 20895 -1 20896 -1 20897 -1 20898 -1 20899 -1 20900 -1 20901 -1 20902 -1 20903 -1 20904 -1 20905 -1 20906 -1 20907 -1 20908 -1 20909 -1 20910 -1 20911 -1 20912 -1 20913 -1 20914 -1 20915 -1 20916 -1 20917 -1 20918 -1 20919 -1 20920 -1 20921 -1 20922 -1 20923 -1 20924 -1 20925 -1 20926 -1 20927 -1 20928 -1 20929 -1 20930 -1 20931 -1 20932 -1 20933 -1 20934 -1 20935 -1 20936 -1 20937 -1 20938 -1 20939 -1 20940 -1 20941 -1 20942 -1 20943 -1 20944 -1 20945 -1 20946 -1 20947 -1 20948 -1 20949 -1 20950 -1 20951 -1 20952 -1 20953 -1 20954 -1 20955 -1 20956 -1 20957 -1 20958 -1 20959 -1 20960 -1 20961 -1 20962 -1 20963 -1 20964 -1 20965 -1 20966 -1 20967 -1 20968 -1 20969 -1 20970 -1 20971 -1 20972 -1 20973 -1 20974 -1 20975 -1 20976 -1 20977 -1 20978 -1 20979 -1 20980 -1 20981 -1 20982 -1 20983 -1 20984 -1 20985 -1 20986 -1 20987 -1 20988 -1 20989 -1 20990 -1 20991 -1 20992 -1 20993 -1 20994 -1 20995 -1 20996 -1 20997 -1 20998 -1 20999 -1 21000 -1 21001 -1 21002 -1 21003 -1 21004 -1 21005 -1 21006 -1 21007 -1 21008 -1 21009 -1 21010 -1 21011 -1 21012 -1 21013 -1 21014 -1 21015 -1 21016 -1 21017 -1 21018 -1 21019 -1 21020 -1 21021 -1 21022 -1 21023 -1 21024 -1 21025 -1 21026 -1 21027 -1 21028 -1 21029 -1 21030 -1 21031 -1 21032 -1 21033 -1 21034 -1 21035 -1 21036 -1 21037 -1 21038 -1 21039 -1 21040 -1 21041 -1 21042 -1 21043 -1 21044 -1 21045 -1 21046 -1 21047 -1 21048 -1 21049 -1 21050 -1 21051 -1 21052 -1 21053 -1 21054 -1 21055 -1 21056 -1 21057 -1 21058 -1 21059 -1 21060 -1 21061 -1 21062 -1 21063 -1 21064 -1 21065 -1 21066 -1 21067 -1 21068 -1 21069 -1 21070 -1 21071 -1 21072 -1 21073 -1 21074 -1 21075 -1 21076 -1 21077 -1 21078 -1 21079 -1 21080 -1 21081 -1 21082 -1 21083 -1 21084 -1 21085 -1 21086 -1 21087 -1 21088 -1 21089 -1 21090 -1 21091 -1 21092 -1 21093 -1 21094 -1 21095 -1 21096 -1 21097 -1 21098 -1 21099 -1 21100 -1 21101 -1 21102 -1 21103 -1 21104 -1 21105 -1 21106 -1 21107 -1 21108 -1 21109 -1 21110 -1 21111 -1 21112 -1 21113 -1 21114 -1 21115 -1 21116 -1 21117 -1 21118 -1 21119 -1 21120 -1 21121 -1 21122 -1 21123 -1 21124 -1 21125 -1 21126 -1 21127 -1 21128 -1 21129 -1 21130 -1 21131 -1 21132 -1 21133 -1 21134 -1 21135 -1 21136 -1 21137 -1 21138 -1 21139 -1 21140 -1 21141 -1 21142 -1 21143 -1 21144 -1 21145 -1 21146 -1 21147 -1 21148 -1 21149 -1 21150 -1 21151 -1 21152 -1 21153 -1 21154 -1 21155 -1 21156 -1 21157 -1 21158 -1 21159 -1 21160 -1 21161 -1 21162 -1 21163 -1 21164 -1 21165 -1 21166 -1 21167 -1 21168 -1 21169 -1 21170 -1 21171 -1 21172 -1 21173 -1 21174 -1 21175 -1 21176 -1 21177 -1 21178 -1 21179 -1 21180 -1 21181 -1 21182 -1 21183 -1 21184 -1 21185 -1 21186 -1 21187 -1 21188 -1 21189 -1 21190 -1 21191 -1 21192 -1 21193 -1 21194 -1 21195 -1 21196 -1 21197 -1 21198 -1 21199 -1 21200 -1 21201 -1 21202 -1 21203 -1 21204 -1 21205 -1 21206 -1 21207 -1 21208 -1 21209 -1 21210 -1 21211 -1 21212 -1 21213 -1 21214 -1 21215 -1 21216 -1 21217 -1 21218 -1 21219 -1 21220 -1 21221 -1 21222 -1 21223 -1 21224 -1 21225 -1 21226 -1 21227 -1 21228 -1 21229 -1 21230 -1 21231 -1 21232 -1 21233 -1 21234 -1 21235 -1 21236 -1 21237 -1 21238 -1 21239 -1 21240 -1 21241 -1 21242 -1 21243 -1 21244 -1 21245 -1 21246 -1 21247 -1 21248 -1 21249 -1 21250 -1 21251 -1 21252 -1 21253 -1 21254 -1 21255 -1 21256 -1 21257 -1 21258 -1 21259 -1 21260 -1 21261 -1 21262 -1 21263 -1 21264 -1 21265 -1 21266 -1 21267 -1 21268 -1 21269 -1 21270 -1 21271 -1 21272 -1 21273 -1 21274 -1 21275 -1 21276 -1 21277 -1 21278 -1 21279 -1 21280 -1 21281 -1 21282 -1 21283 -1 21284 -1 21285 -1 21286 -1 21287 -1 21288 -1 21289 -1 21290 -1 21291 -1 21292 -1 21293 -1 21294 -1 21295 -1 21296 -1 21297 -1 21298 -1 21299 -1 21300 -1 21301 -1 21302 -1 21303 -1 21304 -1 21305 -1 21306 -1 21307 -1 21308 -1 21309 -1 21310 -1 21311 -1 21312 -1 21313 -1 21314 -1 21315 -1 21316 -1 21317 -1 21318 -1 21319 -1 21320 -1 21321 -1 21322 -1 21323 -1 21324 -1 21325 -1 21326 -1 21327 -1 21328 -1 21329 -1 21330 -1 21331 -1 21332 -1 21333 -1 21334 -1 21335 -1 21336 -1 21337 -1 21338 -1 21339 -1 21340 -1 21341 -1 21342 -1 21343 -1 21344 -1 21345 -1 21346 -1 21347 -1 21348 -1 21349 -1 21350 -1 21351 -1 21352 -1 21353 -1 21354 -1 21355 -1 21356 -1 21357 -1 21358 -1 21359 -1 21360 -1 21361 -1 21362 -1 21363 -1 21364 -1 21365 -1 21366 -1 21367 -1 21368 -1 21369 -1 21370 -1 21371 -1 21372 -1 21373 -1 21374 -1 21375 -1 21376 -1 21377 -1 21378 -1 21379 -1 21380 -1 21381 -1 21382 -1 21383 -1 21384 -1 21385 -1 21386 -1 21387 -1 21388 -1 21389 -1 21390 -1 21391 -1 21392 -1 21393 -1 21394 -1 21395 -1 21396 -1 21397 -1 21398 -1 21399 -1 21400 -1 21401 -1 21402 -1 21403 -1 21404 -1 21405 -1 21406 -1 21407 -1 21408 -1 21409 -1 21410 -1 21411 -1 21412 -1 21413 -1 21414 -1 21415 -1 21416 -1 21417 -1 21418 -1 21419 -1 21420 -1 21421 -1 21422 -1 21423 -1 21424 -1 21425 -1 21426 -1 21427 -1 21428 -1 21429 -1 21430 -1 21431 -1 21432 -1 21433 -1 21434 -1 21435 -1 21436 -1 21437 -1 21438 -1 21439 -1 21440 -1 21441 -1 21442 -1 21443 -1 21444 -1 21445 -1 21446 -1 21447 -1 21448 -1 21449 -1 21450 -1 21451 -1 21452 -1 21453 -1 21454 -1 21455 -1 21456 -1 21457 -1 21458 -1 21459 -1 21460 -1 21461 -1 21462 -1 21463 -1 21464 -1 21465 -1 21466 -1 21467 -1 21468 -1 21469 -1 21470 -1 21471 -1 21472 -1 21473 -1 21474 -1 21475 -1 21476 -1 21477 -1 21478 -1 21479 -1 21480 -1 21481 -1 21482 -1 21483 -1 21484 -1 21485 -1 21486 -1 21487 -1 21488 -1 21489 -1 21490 -1 21491 -1 21492 -1 21493 -1 21494 -1 21495 -1 21496 -1 21497 -1 21498 -1 21499 -1 21500 -1 21501 -1 21502 -1 21503 -1 21504 -1 21505 -1 21506 -1 21507 -1 21508 -1 21509 -1 21510 -1 21511 -1 21512 -1 21513 -1 21514 -1 21515 -1 21516 -1 21517 -1 21518 -1 21519 -1 21520 -1 21521 -1 21522 -1 21523 -1 21524 -1 21525 -1 21526 -1 21527 -1 21528 -1 21529 -1 21530 -1 21531 -1 21532 -1 21533 -1 21534 -1 21535 -1 21536 -1 21537 -1 21538 -1 21539 -1 21540 -1 21541 -1 21542 -1 21543 -1 21544 -1 21545 -1 21546 -1 21547 -1 21548 -1 21549 -1 21550 -1 21551 -1 21552 -1 21553 -1 21554 -1 21555 -1 21556 -1 21557 -1 21558 -1 21559 -1 21560 -1 21561 -1 21562 -1 21563 -1 21564 -1 21565 -1 21566 -1 21567 -1 21568 -1 21569 -1 21570 -1 21571 -1 21572 -1 21573 -1 21574 -1 21575 -1 21576 -1 21577 -1 21578 -1 21579 -1 21580 -1 21581 -1 21582 -1 21583 -1 21584 -1 21585 -1 21586 -1 21587 -1 21588 -1 21589 -1 21590 -1 21591 -1 21592 -1 21593 -1 21594 -1 21595 -1 21596 -1 21597 -1 21598 -1 21599 -1 21600 -1 21601 -1 21602 -1 21603 -1 21604 -1 21605 -1 21606 -1 21607 -1 21608 -1 21609 -1 21610 -1 21611 -1 21612 -1 21613 -1 21614 -1 21615 -1 21616 -1 21617 -1 21618 -1 21619 -1 21620 -1 21621 -1 21622 -1 21623 -1 21624 -1 21625 -1 21626 -1 21627 -1 21628 -1 21629 -1 21630 -1 21631 -1 21632 -1 21633 -1 21634 -1 21635 -1 21636 -1 21637 -1 21638 -1 21639 -1 21640 -1 21641 -1 21642 -1 21643 -1 21644 -1 21645 -1 21646 -1 21647 -1 21648 -1 21649 -1 21650 -1 21651 -1 21652 -1 21653 -1 21654 -1 21655 -1 21656 -1 21657 -1 21658 -1 21659 -1 21660 -1 21661 -1 21662 -1 21663 -1 21664 -1 21665 -1 21666 -1 21667 -1 21668 -1 21669 -1 21670 -1 21671 -1 21672 -1 21673 -1 21674 -1 21675 -1 21676 -1 21677 -1 21678 -1 21679 -1 21680 -1 21681 -1 21682 -1 21683 -1 21684 -1 21685 -1 21686 -1 21687 -1 21688 -1 21689 -1 21690 -1 21691 -1 21692 -1 21693 -1 21694 -1 21695 -1 21696 -1 21697 -1 21698 -1 21699 -1 21700 -1 21701 -1 21702 -1 21703 -1 21704 -1 21705 -1 21706 -1 21707 -1 21708 -1 21709 -1 21710 -1 21711 -1 21712 -1 21713 -1 21714 -1 21715 -1 21716 -1 21717 -1 21718 -1 21719 -1 21720 -1 21721 -1 21722 -1 21723 -1 21724 -1 21725 -1 21726 -1 21727 -1 21728 -1 21729 -1 21730 -1 21731 -1 21732 -1 21733 -1 21734 -1 21735 -1 21736 -1 21737 -1 21738 -1 21739 -1 21740 -1 21741 -1 21742 -1 21743 -1 21744 -1 21745 -1 21746 -1 21747 -1 21748 -1 21749 -1 21750 -1 21751 -1 21752 -1 21753 -1 21754 -1 21755 -1 21756 -1 21757 -1 21758 -1 21759 -1 21760 -1 21761 -1 21762 -1 21763 -1 21764 -1 21765 -1 21766 -1 21767 -1 21768 -1 21769 -1 21770 -1 21771 -1 21772 -1 21773 -1 21774 -1 21775 -1 21776 -1 21777 -1 21778 -1 21779 -1 21780 -1 21781 -1 21782 -1 21783 -1 21784 -1 21785 -1 21786 -1 21787 -1 21788 -1 21789 -1 21790 -1 21791 -1 21792 -1 21793 -1 21794 -1 21795 -1 21796 -1 21797 -1 21798 -1 21799 -1 21800 -1 21801 -1 21802 -1 21803 -1 21804 -1 21805 -1 21806 -1 21807 -1 21808 -1 21809 -1 21810 -1 21811 -1 21812 -1 21813 -1 21814 -1 21815 -1 21816 -1 21817 -1 21818 -1 21819 -1 21820 -1 21821 -1 21822 -1 21823 -1 21824 -1 21825 -1 21826 -1 21827 -1 21828 -1 21829 -1 21830 -1 21831 -1 21832 -1 21833 -1 21834 -1 21835 -1 21836 -1 21837 -1 21838 -1 21839 -1 21840 -1 21841 -1 21842 -1 21843 -1 21844 -1 21845 -1 21846 -1 21847 -1 21848 -1 21849 -1 21850 -1 21851 -1 21852 -1 21853 -1 21854 -1 21855 -1 21856 -1 21857 -1 21858 -1 21859 -1 21860 -1 21861 -1 21862 -1 21863 -1 21864 -1 21865 -1 21866 -1 21867 -1 21868 -1 21869 -1 21870 -1 21871 -1 21872 -1 21873 -1 21874 -1 21875 -1 21876 -1 21877 -1 21878 -1 21879 -1 21880 -1 21881 -1 21882 -1 21883 -1 21884 -1 21885 -1 21886 -1 21887 -1 21888 -1 21889 -1 21890 -1 21891 -1 21892 -1 21893 -1 21894 -1 21895 -1 21896 -1 21897 -1 21898 -1 21899 -1 21900 -1 21901 -1 21902 -1 21903 -1 21904 -1 21905 -1 21906 -1 21907 -1 21908 -1 21909 -1 21910 -1 21911 -1 21912 -1 21913 -1 21914 -1 21915 -1 21916 -1 21917 -1 21918 -1 21919 -1 21920 -1 21921 -1 21922 -1 21923 -1 21924 -1 21925 -1 21926 -1 21927 -1 21928 -1 21929 -1 21930 -1 21931 -1 21932 -1 21933 -1 21934 -1 21935 -1 21936 -1 21937 -1 21938 -1 21939 -1 21940 -1 21941 -1 21942 -1 21943 -1 21944 -1 21945 -1 21946 -1 21947 -1 21948 -1 21949 -1 21950 -1 21951 -1 21952 -1 21953 -1 21954 -1 21955 -1 21956 -1 21957 -1 21958 -1 21959 -1 21960 -1 21961 -1 21962 -1 21963 -1 21964 -1 21965 -1 21966 -1 21967 -1 21968 -1 21969 -1 21970 -1 21971 -1 21972 -1 21973 -1 21974 -1 21975 -1 21976 -1 21977 -1 21978 -1 21979 -1 21980 -1 21981 -1 21982 -1 21983 -1 21984 -1 21985 -1 21986 -1 21987 -1 21988 -1 21989 -1 21990 -1 21991 -1 21992 -1 21993 -1 21994 -1 21995 -1 21996 -1 21997 -1 21998 -1 21999 -1 22000 -1 22001 -1 22002 -1 22003 -1 22004 -1 22005 -1 22006 -1 22007 -1 22008 -1 22009 -1 22010 -1 22011 -1 22012 -1 22013 -1 22014 -1 22015 -1 22016 -1 22017 -1 22018 -1 22019 -1 22020 -1 22021 -1 22022 -1 22023 -1 22024 -1 22025 -1 22026 -1 22027 -1 22028 -1 22029 -1 22030 -1 22031 -1 22032 -1 22033 -1 22034 -1 22035 -1 22036 -1 22037 -1 22038 -1 22039 -1 22040 -1 22041 -1 22042 -1 22043 -1 22044 -1 22045 -1 22046 -1 22047 -1 22048 -1 22049 -1 22050 -1 22051 -1 22052 -1 22053 -1 22054 -1 22055 -1 22056 -1 22057 -1 22058 -1 22059 -1 22060 -1 22061 -1 22062 -1 22063 -1 22064 -1 22065 -1 22066 -1 22067 -1 22068 -1 22069 -1 22070 -1 22071 -1 22072 -1 22073 -1 22074 -1 22075 -1 22076 -1 22077 -1 22078 -1 22079 -1 22080 -1 22081 -1 22082 -1 22083 -1 22084 -1 22085 -1 22086 -1 22087 -1 22088 -1 22089 -1 22090 -1 22091 -1 22092 -1 22093 -1 22094 -1 22095 -1 22096 -1 22097 -1 22098 -1 22099 -1 22100 -1 22101 -1 22102 -1 22103 -1 22104 -1 22105 -1 22106 -1 22107 -1 22108 -1 22109 -1 22110 -1 22111 -1 22112 -1 22113 -1 22114 -1 22115 -1 22116 -1 22117 -1 22118 -1 22119 -1 22120 -1 22121 -1 22122 -1 22123 -1 22124 -1 22125 -1 22126 -1 22127 -1 22128 -1 22129 -1 22130 -1 22131 -1 22132 -1 22133 -1 22134 -1 22135 -1 22136 -1 22137 -1 22138 -1 22139 -1 22140 -1 22141 -1 22142 -1 22143 -1 22144 -1 22145 -1 22146 -1 22147 -1 22148 -1 22149 -1 22150 -1 22151 -1 22152 -1 22153 -1 22154 -1 22155 -1 22156 -1 22157 -1 22158 -1 22159 -1 22160 -1 22161 -1 22162 -1 22163 -1 22164 -1 22165 -1 22166 -1 22167 -1 22168 -1 22169 -1 22170 -1 22171 -1 22172 -1 22173 -1 22174 -1 22175 -1 22176 -1 22177 -1 22178 -1 22179 -1 22180 -1 22181 -1 22182 -1 22183 -1 22184 -1 22185 -1 22186 -1 22187 -1 22188 -1 22189 -1 22190 -1 22191 -1 22192 -1 22193 -1 22194 -1 22195 -1 22196 -1 22197 -1 22198 -1 22199 -1 22200 -1 22201 -1 22202 -1 22203 -1 22204 -1 22205 -1 22206 -1 22207 -1 22208 -1 22209 -1 22210 -1 22211 -1 22212 -1 22213 -1 22214 -1 22215 -1 22216 -1 22217 -1 22218 -1 22219 -1 22220 -1 22221 -1 22222 -1 22223 -1 22224 -1 22225 -1 22226 -1 22227 -1 22228 -1 22229 -1 22230 -1 22231 -1 22232 -1 22233 -1 22234 -1 22235 -1 22236 -1 22237 -1 22238 -1 22239 -1 22240 -1 22241 -1 22242 -1 22243 -1 22244 -1 22245 -1 22246 -1 22247 -1 22248 -1 22249 -1 22250 -1 22251 -1 22252 -1 22253 -1 22254 -1 22255 -1 22256 -1 22257 -1 22258 -1 22259 -1 22260 -1 22261 -1 22262 -1 22263 -1 22264 -1 22265 -1 22266 -1 22267 -1 22268 -1 22269 -1 22270 -1 22271 -1 22272 -1 22273 -1 22274 -1 22275 -1 22276 -1 22277 -1 22278 -1 22279 -1 22280 -1 22281 -1 22282 -1 22283 -1 22284 -1 22285 -1 22286 -1 22287 -1 22288 -1 22289 -1 22290 -1 22291 -1 22292 -1 22293 -1 22294 -1 22295 -1 22296 -1 22297 -1 22298 -1 22299 -1 22300 -1 22301 -1 22302 -1 22303 -1 22304 -1 22305 -1 22306 -1 22307 -1 22308 -1 22309 -1 22310 -1 22311 -1 22312 -1 22313 -1 22314 -1 22315 -1 22316 -1 22317 -1 22318 -1 22319 -1 22320 -1 22321 -1 22322 -1 22323 -1 22324 -1 22325 -1 22326 -1 22327 -1 22328 -1 22329 -1 22330 -1 22331 -1 22332 -1 22333 -1 22334 -1 22335 -1 22336 -1 22337 -1 22338 -1 22339 -1 22340 -1 22341 -1 22342 -1 22343 -1 22344 -1 22345 -1 22346 -1 22347 -1 22348 -1 22349 -1 22350 -1 22351 -1 22352 -1 22353 -1 22354 -1 22355 -1 22356 -1 22357 -1 22358 -1 22359 -1 22360 -1 22361 -1 22362 -1 22363 -1 22364 -1 22365 -1 22366 -1 22367 -1 22368 -1 22369 -1 22370 -1 22371 -1 22372 -1 22373 -1 22374 -1 22375 -1 22376 -1 22377 -1 22378 -1 22379 -1 22380 -1 22381 -1 22382 -1 22383 -1 22384 -1 22385 -1 22386 -1 22387 -1 22388 -1 22389 -1 22390 -1 22391 -1 22392 -1 22393 -1 22394 -1 22395 -1 22396 -1 22397 -1 22398 -1 22399 -1 22400 -1 22401 -1 22402 -1 22403 -1 22404 -1 22405 -1 22406 -1 22407 -1 22408 -1 22409 -1 22410 -1 22411 -1 22412 -1 22413 -1 22414 -1 22415 -1 22416 -1 22417 -1 22418 -1 22419 -1 22420 -1 22421 -1 22422 -1 22423 -1 22424 -1 22425 -1 22426 -1 22427 -1 22428 -1 22429 -1 22430 -1 22431 -1 22432 -1 22433 -1 22434 -1 22435 -1 22436 -1 22437 -1 22438 -1 22439 -1 22440 -1 22441 -1 22442 -1 22443 -1 22444 -1 22445 -1 22446 -1 22447 -1 22448 -1 22449 -1 22450 -1 22451 -1 22452 -1 22453 -1 22454 -1 22455 -1 22456 -1 22457 -1 22458 -1 22459 -1 22460 -1 22461 -1 22462 -1 22463 -1 22464 -1 22465 -1 22466 -1 22467 -1 22468 -1 22469 -1 22470 -1 22471 -1 22472 -1 22473 -1 22474 -1 22475 -1 22476 -1 22477 -1 22478 -1 22479 -1 22480 -1 22481 -1 22482 -1 22483 -1 22484 -1 22485 -1 22486 -1 22487 -1 22488 -1 22489 -1 22490 -1 22491 -1 22492 -1 22493 -1 22494 -1 22495 -1 22496 -1 22497 -1 22498 -1 22499 -1 22500 -1 22501 -1 22502 -1 22503 -1 22504 -1 22505 -1 22506 -1 22507 -1 22508 -1 22509 -1 22510 -1 22511 -1 22512 -1 22513 -1 22514 -1 22515 -1 22516 -1 22517 -1 22518 -1 22519 -1 22520 -1 22521 -1 22522 -1 22523 -1 22524 -1 22525 -1 22526 -1 22527 -1 22528 -1 22529 -1 22530 -1 22531 -1 22532 -1 22533 -1 22534 -1 22535 -1 22536 -1 22537 -1 22538 -1 22539 -1 22540 -1 22541 -1 22542 -1 22543 -1 22544 -1 22545 -1 22546 -1 22547 -1 22548 -1 22549 -1 22550 -1 22551 -1 22552 -1 22553 -1 22554 -1 22555 -1 22556 -1 22557 -1 22558 -1 22559 -1 22560 -1 22561 -1 22562 -1 22563 -1 22564 -1 22565 -1 22566 -1 22567 -1 22568 -1 22569 -1 22570 -1 22571 -1 22572 -1 22573 -1 22574 -1 22575 -1 22576 -1 22577 -1 22578 -1 22579 -1 22580 -1 22581 -1 22582 -1 22583 -1 22584 -1 22585 -1 22586 -1 22587 -1 22588 -1 22589 -1 22590 -1 22591 -1 22592 -1 22593 -1 22594 -1 22595 -1 22596 -1 22597 -1 22598 -1 22599 -1 22600 -1 22601 -1 22602 -1 22603 -1 22604 -1 22605 -1 22606 -1 22607 -1 22608 -1 22609 -1 22610 -1 22611 -1 22612 -1 22613 -1 22614 -1 22615 -1 22616 -1 22617 -1 22618 -1 22619 -1 22620 -1 22621 -1 22622 -1 22623 -1 22624 -1 22625 -1 22626 -1 22627 -1 22628 -1 22629 -1 22630 -1 22631 -1 22632 -1 22633 -1 22634 -1 22635 -1 22636 -1 22637 -1 22638 -1 22639 -1 22640 -1 22641 -1 22642 -1 22643 -1 22644 -1 22645 -1 22646 -1 22647 -1 22648 -1 22649 -1 22650 -1 22651 -1 22652 -1 22653 -1 22654 -1 22655 -1 22656 -1 22657 -1 22658 -1 22659 -1 22660 -1 22661 -1 22662 -1 22663 -1 22664 -1 22665 -1 22666 -1 22667 -1 22668 -1 22669 -1 22670 -1 22671 -1 22672 -1 22673 -1 22674 -1 22675 -1 22676 -1 22677 -1 22678 -1 22679 -1 22680 -1 22681 -1 22682 -1 22683 -1 22684 -1 22685 -1 22686 -1 22687 -1 22688 -1 22689 -1 22690 -1 22691 -1 22692 -1 22693 -1 22694 -1 22695 -1 22696 -1 22697 -1 22698 -1 22699 -1 22700 -1 22701 -1 22702 -1 22703 -1 22704 -1 22705 -1 22706 -1 22707 -1 22708 -1 22709 -1 22710 -1 22711 -1 22712 -1 22713 -1 22714 -1 22715 -1 22716 -1 22717 -1 22718 -1 22719 -1 22720 -1 22721 -1 22722 -1 22723 -1 22724 -1 22725 -1 22726 -1 22727 -1 22728 -1 22729 -1 22730 -1 22731 -1 22732 -1 22733 -1 22734 -1 22735 -1 22736 -1 22737 -1 22738 -1 22739 -1 22740 -1 22741 -1 22742 -1 22743 -1 22744 -1 22745 -1 22746 -1 22747 -1 22748 -1 22749 -1 22750 -1 22751 -1 22752 -1 22753 -1 22754 -1 22755 -1 22756 -1 22757 -1 22758 -1 22759 -1 22760 -1 22761 -1 22762 -1 22763 -1 22764 -1 22765 -1 22766 -1 22767 -1 22768 -1 22769 -1 22770 -1 22771 -1 22772 -1 22773 -1 22774 -1 22775 -1 22776 -1 22777 -1 22778 -1 22779 -1 22780 -1 22781 -1 22782 -1 22783 -1 22784 -1 22785 -1 22786 -1 22787 -1 22788 -1 22789 -1 22790 -1 22791 -1 22792 -1 22793 -1 22794 -1 22795 -1 22796 -1 22797 -1 22798 -1 22799 -1 22800 -1 22801 -1 22802 -1 22803 -1 22804 -1 22805 -1 22806 -1 22807 -1 22808 -1 22809 -1 22810 -1 22811 -1 22812 -1 22813 -1 22814 -1 22815 -1 22816 -1 22817 -1 22818 -1 22819 -1 22820 -1 22821 -1 22822 -1 22823 -1 22824 -1 22825 -1 22826 -1 22827 -1 22828 -1 22829 -1 22830 -1 22831 -1 22832 -1 22833 -1 22834 -1 22835 -1 22836 -1 22837 -1 22838 -1 22839 -1 22840 -1 22841 -1 22842 -1 22843 -1 22844 -1 22845 -1 22846 -1 22847 -1 22848 -1 22849 -1 22850 -1 22851 -1 22852 -1 22853 -1 22854 -1 22855 -1 22856 -1 22857 -1 22858 -1 22859 -1 22860 -1 22861 -1 22862 -1 22863 -1 22864 -1 22865 -1 22866 -1 22867 -1 22868 -1 22869 -1 22870 -1 22871 -1 22872 -1 22873 -1 22874 -1 22875 -1 22876 -1 22877 -1 22878 -1 22879 -1 22880 -1 22881 -1 22882 -1 22883 -1 22884 -1 22885 -1 22886 -1 22887 -1 22888 -1 22889 -1 22890 -1 22891 -1 22892 -1 22893 -1 22894 -1 22895 -1 22896 -1 22897 -1 22898 -1 22899 -1 22900 -1 22901 -1 22902 -1 22903 -1 22904 -1 22905 -1 22906 -1 22907 -1 22908 -1 22909 -1 22910 -1 22911 -1 22912 -1 22913 -1 22914 -1 22915 -1 22916 -1 22917 -1 22918 -1 22919 -1 22920 -1 22921 -1 22922 -1 22923 -1 22924 -1 22925 -1 22926 -1 22927 -1 22928 -1 22929 -1 22930 -1 22931 -1 22932 -1 22933 -1 22934 -1 22935 -1 22936 -1 22937 -1 22938 -1 22939 -1 22940 -1 22941 -1 22942 -1 22943 -1 22944 -1 22945 -1 22946 -1 22947 -1 22948 -1 22949 -1 22950 -1 22951 -1 22952 -1 22953 -1 22954 -1 22955 -1 22956 -1 22957 -1 22958 -1 22959 -1 22960 -1 22961 -1 22962 -1 22963 -1 22964 -1 22965 -1 22966 -1 22967 -1 22968 -1 22969 -1 22970 -1 22971 -1 22972 -1 22973 -1 22974 -1 22975 -1 22976 -1 22977 -1 22978 -1 22979 -1 22980 -1 22981 -1 22982 -1 22983 -1 22984 -1 22985 -1 22986 -1 22987 -1 22988 -1 22989 -1 22990 -1 22991 -1 22992 -1 22993 -1 22994 -1 22995 -1 22996 -1 22997 -1 22998 -1 22999 -1 23000 -1 23001 -1 23002 -1 23003 -1 23004 -1 23005 -1 23006 -1 23007 -1 23008 -1 23009 -1 23010 -1 23011 -1 23012 -1 23013 -1 23014 -1 23015 -1 23016 -1 23017 -1 23018 -1 23019 -1 23020 -1 23021 -1 23022 -1 23023 -1 23024 -1 23025 -1 23026 -1 23027 -1 23028 -1 23029 -1 23030 -1 23031 -1 23032 -1 23033 -1 23034 -1 23035 -1 23036 -1 23037 -1 23038 -1 23039 -1 23040 -1 23041 -1 23042 -1 23043 -1 23044 -1 23045 -1 23046 -1 23047 -1 23048 -1 23049 -1 23050 -1 23051 -1 23052 -1 23053 -1 23054 -1 23055 -1 23056 -1 23057 -1 23058 -1 23059 -1 23060 -1 23061 -1 23062 -1 23063 -1 23064 -1 23065 -1 23066 -1 23067 -1 23068 -1 23069 -1 23070 -1 23071 -1 23072 -1 23073 -1 23074 -1 23075 -1 23076 -1 23077 -1 23078 -1 23079 -1 23080 -1 23081 -1 23082 -1 23083 -1 23084 -1 23085 -1 23086 -1 23087 -1 23088 -1 23089 -1 23090 -1 23091 -1 23092 -1 23093 -1 23094 -1 23095 -1 23096 -1 23097 -1 23098 -1 23099 -1 23100 -1 23101 -1 23102 -1 23103 -1 23104 -1 23105 -1 23106 -1 23107 -1 23108 -1 23109 -1 23110 -1 23111 -1 23112 -1 23113 -1 23114 -1 23115 -1 23116 -1 23117 -1 23118 -1 23119 -1 23120 -1 23121 -1 23122 -1 23123 -1 23124 -1 23125 -1 23126 -1 23127 -1 23128 -1 23129 -1 23130 -1 23131 -1 23132 -1 23133 -1 23134 -1 23135 -1 23136 -1 23137 -1 23138 -1 23139 -1 23140 -1 23141 -1 23142 -1 23143 -1 23144 -1 23145 -1 23146 -1 23147 -1 23148 -1 23149 -1 23150 -1 23151 -1 23152 -1 23153 -1 23154 -1 23155 -1 23156 -1 23157 -1 23158 -1 23159 -1 23160 -1 23161 -1 23162 -1 23163 -1 23164 -1 23165 -1 23166 -1 23167 -1 23168 -1 23169 -1 23170 -1 23171 -1 23172 -1 23173 -1 23174 -1 23175 -1 23176 -1 23177 -1 23178 -1 23179 -1 23180 -1 23181 -1 23182 -1 23183 -1 23184 -1 23185 -1 23186 -1 23187 -1 23188 -1 23189 -1 23190 -1 23191 -1 23192 -1 23193 -1 23194 -1 23195 -1 23196 -1 23197 -1 23198 -1 23199 -1 23200 -1 23201 -1 23202 -1 23203 -1 23204 -1 23205 -1 23206 -1 23207 -1 23208 -1 23209 -1 23210 -1 23211 -1 23212 -1 23213 -1 23214 -1 23215 -1 23216 -1 23217 -1 23218 -1 23219 -1 23220 -1 23221 -1 23222 -1 23223 -1 23224 -1 23225 -1 23226 -1 23227 -1 23228 -1 23229 -1 23230 -1 23231 -1 23232 -1 23233 -1 23234 -1 23235 -1 23236 -1 23237 -1 23238 -1 23239 -1 23240 -1 23241 -1 23242 -1 23243 -1 23244 -1 23245 -1 23246 -1 23247 -1 23248 -1 23249 -1 23250 -1 23251 -1 23252 -1 23253 -1 23254 -1 23255 -1 23256 -1 23257 -1 23258 -1 23259 -1 23260 -1 23261 -1 23262 -1 23263 -1 23264 -1 23265 -1 23266 -1 23267 -1 23268 -1 23269 -1 23270 -1 23271 -1 23272 -1 23273 -1 23274 -1 23275 -1 23276 -1 23277 -1 23278 -1 23279 -1 23280 -1 23281 -1 23282 -1 23283 -1 23284 -1 23285 -1 23286 -1 23287 -1 23288 -1 23289 -1 23290 -1 23291 -1 23292 -1 23293 -1 23294 -1 23295 -1 23296 -1 23297 -1 23298 -1 23299 -1 23300 -1 23301 -1 23302 -1 23303 -1 23304 -1 23305 -1 23306 -1 23307 -1 23308 -1 23309 -1 23310 -1 23311 -1 23312 -1 23313 -1 23314 -1 23315 -1 23316 -1 23317 -1 23318 -1 23319 -1 23320 -1 23321 -1 23322 -1 23323 -1 23324 -1 23325 -1 23326 -1 23327 -1 23328 -1 23329 -1 23330 -1 23331 -1 23332 -1 23333 -1 23334 -1 23335 -1 23336 -1 23337 -1 23338 -1 23339 -1 23340 -1 23341 -1 23342 -1 23343 -1 23344 -1 23345 -1 23346 -1 23347 -1 23348 -1 23349 -1 23350 -1 23351 -1 23352 -1 23353 -1 23354 -1 23355 -1 23356 -1 23357 -1 23358 -1 23359 -1 23360 -1 23361 -1 23362 -1 23363 -1 23364 -1 23365 -1 23366 -1 23367 -1 23368 -1 23369 -1 23370 -1 23371 -1 23372 -1 23373 -1 23374 -1 23375 -1 23376 -1 23377 -1 23378 -1 23379 -1 23380 -1 23381 -1 23382 -1 23383 -1 23384 -1 23385 -1 23386 -1 23387 -1 23388 -1 23389 -1 23390 -1 23391 -1 23392 -1 23393 -1 23394 -1 23395 -1 23396 -1 23397 -1 23398 -1 23399 -1 23400 -1 23401 -1 23402 -1 23403 -1 23404 -1 23405 -1 23406 -1 23407 -1 23408 -1 23409 -1 23410 -1 23411 -1 23412 -1 23413 -1 23414 -1 23415 -1 23416 -1 23417 -1 23418 -1 23419 -1 23420 -1 23421 -1 23422 -1 23423 -1 23424 -1 23425 -1 23426 -1 23427 -1 23428 -1 23429 -1 23430 -1 23431 -1 23432 -1 23433 -1 23434 -1 23435 -1 23436 -1 23437 -1 23438 -1 23439 -1 23440 -1 23441 -1 23442 -1 23443 -1 23444 -1 23445 -1 23446 -1 23447 -1 23448 -1 23449 -1 23450 -1 23451 -1 23452 -1 23453 -1 23454 -1 23455 -1 23456 -1 23457 -1 23458 -1 23459 -1 23460 -1 23461 -1 23462 -1 23463 -1 23464 -1 23465 -1 23466 -1 23467 -1 23468 -1 23469 -1 23470 -1 23471 -1 23472 -1 23473 -1 23474 -1 23475 -1 23476 -1 23477 -1 23478 -1 23479 -1 23480 -1 23481 -1 23482 -1 23483 -1 23484 -1 23485 -1 23486 -1 23487 -1 23488 -1 23489 -1 23490 -1 23491 -1 23492 -1 23493 -1 23494 -1 23495 -1 23496 -1 23497 -1 23498 -1 23499 -1 23500 -1 23501 -1 23502 -1 23503 -1 23504 -1 23505 -1 23506 -1 23507 -1 23508 -1 23509 -1 23510 -1 23511 -1 23512 -1 23513 -1 23514 -1 23515 -1 23516 -1 23517 -1 23518 -1 23519 -1 23520 -1 23521 -1 23522 -1 23523 -1 23524 -1 23525 -1 23526 -1 23527 -1 23528 -1 23529 -1 23530 -1 23531 -1 23532 -1 23533 -1 23534 -1 23535 -1 23536 -1 23537 -1 23538 -1 23539 -1 23540 -1 23541 -1 23542 -1 23543 -1 23544 -1 23545 -1 23546 -1 23547 -1 23548 -1 23549 -1 23550 -1 23551 -1 23552 -1 23553 -1 23554 -1 23555 -1 23556 -1 23557 -1 23558 -1 23559 -1 23560 -1 23561 -1 23562 -1 23563 -1 23564 -1 23565 -1 23566 -1 23567 -1 23568 -1 23569 -1 23570 -1 23571 -1 23572 -1 23573 -1 23574 -1 23575 -1 23576 -1 23577 -1 23578 -1 23579 -1 23580 -1 23581 -1 23582 -1 23583 -1 23584 -1 23585 -1 23586 -1 23587 -1 23588 -1 23589 -1 23590 -1 23591 -1 23592 -1 23593 -1 23594 -1 23595 -1 23596 -1 23597 -1 23598 -1 23599 -1 23600 -1 23601 -1 23602 -1 23603 -1 23604 -1 23605 -1 23606 -1 23607 -1 23608 -1 23609 -1 23610 -1 23611 -1 23612 -1 23613 -1 23614 -1 23615 -1 23616 -1 23617 -1 23618 -1 23619 -1 23620 -1 23621 -1 23622 -1 23623 -1 23624 -1 23625 -1 23626 -1 23627 -1 23628 -1 23629 -1 23630 -1 23631 -1 23632 -1 23633 -1 23634 -1 23635 -1 23636 -1 23637 -1 23638 -1 23639 -1 23640 -1 23641 -1 23642 -1 23643 -1 23644 -1 23645 -1 23646 -1 23647 -1 23648 -1 23649 -1 23650 -1 23651 -1 23652 -1 23653 -1 23654 -1 23655 -1 23656 -1 23657 -1 23658 -1 23659 -1 23660 -1 23661 -1 23662 -1 23663 -1 23664 -1 23665 -1 23666 -1 23667 -1 23668 -1 23669 -1 23670 -1 23671 -1 23672 -1 23673 -1 23674 -1 23675 -1 23676 -1 23677 -1 23678 -1 23679 -1 23680 -1 23681 -1 23682 -1 23683 -1 23684 -1 23685 -1 23686 -1 23687 -1 23688 -1 23689 -1 23690 -1 23691 -1 23692 -1 23693 -1 23694 -1 23695 -1 23696 -1 23697 -1 23698 -1 23699 -1 23700 -1 23701 -1 23702 -1 23703 -1 23704 -1 23705 -1 23706 -1 23707 -1 23708 -1 23709 -1 23710 -1 23711 -1 23712 -1 23713 -1 23714 -1 23715 -1 23716 -1 23717 -1 23718 -1 23719 -1 23720 -1 23721 -1 23722 -1 23723 -1 23724 -1 23725 -1 23726 -1 23727 -1 23728 -1 23729 -1 23730 -1 23731 -1 23732 -1 23733 -1 23734 -1 23735 -1 23736 -1 23737 -1 23738 -1 23739 -1 23740 -1 23741 -1 23742 -1 23743 -1 23744 -1 23745 -1 23746 -1 23747 -1 23748 -1 23749 -1 23750 -1 23751 -1 23752 -1 23753 -1 23754 -1 23755 -1 23756 -1 23757 -1 23758 -1 23759 -1 23760 -1 23761 -1 23762 -1 23763 -1 23764 -1 23765 -1 23766 -1 23767 -1 23768 -1 23769 -1 23770 -1 23771 -1 23772 -1 23773 -1 23774 -1 23775 -1 23776 -1 23777 -1 23778 -1 23779 -1 23780 -1 23781 -1 23782 -1 23783 -1 23784 -1 23785 -1 23786 -1 23787 -1 23788 -1 23789 -1 23790 -1 23791 -1 23792 -1 23793 -1 23794 -1 23795 -1 23796 -1 23797 -1 23798 -1 23799 -1 23800 -1 23801 -1 23802 -1 23803 -1 23804 -1 23805 -1 23806 -1 23807 -1 23808 -1 23809 -1 23810 -1 23811 -1 23812 -1 23813 -1 23814 -1 23815 -1 23816 -1 23817 -1 23818 -1 23819 -1 23820 -1 23821 -1 23822 -1 23823 -1 23824 -1 23825 -1 23826 -1 23827 -1 23828 -1 23829 -1 23830 -1 23831 -1 23832 -1 23833 -1 23834 -1 23835 -1 23836 -1 23837 -1 23838 -1 23839 -1 23840 -1 23841 -1 23842 -1 23843 -1 23844 -1 23845 -1 23846 -1 23847 -1 23848 -1 23849 -1 23850 -1 23851 -1 23852 -1 23853 -1 23854 -1 23855 -1 23856 -1 23857 -1 23858 -1 23859 -1 23860 -1 23861 -1 23862 -1 23863 -1 23864 -1 23865 -1 23866 -1 23867 -1 23868 -1 23869 -1 23870 -1 23871 -1 23872 -1 23873 -1 23874 -1 23875 -1 23876 -1 23877 -1 23878 -1 23879 -1 23880 -1 23881 -1 23882 -1 23883 -1 23884 -1 23885 -1 23886 -1 23887 -1 23888 -1 23889 -1 23890 -1 23891 -1 23892 -1 23893 -1 23894 -1 23895 -1 23896 -1 23897 -1 23898 -1 23899 -1 23900 -1 23901 -1 23902 -1 23903 -1 23904 -1 23905 -1 23906 -1 23907 -1 23908 -1 23909 -1 23910 -1 23911 -1 23912 -1 23913 -1 23914 -1 23915 -1 23916 -1 23917 -1 23918 -1 23919 -1 23920 -1 23921 -1 23922 -1 23923 -1 23924 -1 23925 -1 23926 -1 23927 -1 23928 -1 23929 -1 23930 -1 23931 -1 23932 -1 23933 -1 23934 -1 23935 -1 23936 -1 23937 -1 23938 -1 23939 -1 23940 -1 23941 -1 23942 -1 23943 -1 23944 -1 23945 -1 23946 -1 23947 -1 23948 -1 23949 -1 23950 -1 23951 -1 23952 -1 23953 -1 23954 -1 23955 -1 23956 -1 23957 -1 23958 -1 23959 -1 23960 -1 23961 -1 23962 -1 23963 -1 23964 -1 23965 -1 23966 -1 23967 -1 23968 -1 23969 -1 23970 -1 23971 -1 23972 -1 23973 -1 23974 -1 23975 -1 23976 -1 23977 -1 23978 -1 23979 -1 23980 -1 23981 -1 23982 -1 23983 -1 23984 -1 23985 -1 23986 -1 23987 -1 23988 -1 23989 -1 23990 -1 23991 -1 23992 -1 23993 -1 23994 -1 23995 -1 23996 -1 23997 -1 23998 -1 23999 -1 24000 -1 24001 -1 24002 -1 24003 -1 24004 -1 24005 -1 24006 -1 24007 -1 24008 -1 24009 -1 24010 -1 24011 -1 24012 -1 24013 -1 24014 -1 24015 -1 24016 -1 24017 -1 24018 -1 24019 -1 24020 -1 24021 -1 24022 -1 24023 -1 24024 -1 24025 -1 24026 -1 24027 -1 24028 -1 24029 -1 24030 -1 24031 -1 24032 -1 24033 -1 24034 -1 24035 -1 24036 -1 24037 -1 24038 -1 24039 -1 24040 -1 24041 -1 24042 -1 24043 -1 24044 -1 24045 -1 24046 -1 24047 -1 24048 -1 24049 -1 24050 -1 24051 -1 24052 -1 24053 -1 24054 -1 24055 -1 24056 -1 24057 -1 24058 -1 24059 -1 24060 -1 24061 -1 24062 -1 24063 -1 24064 -1 24065 -1 24066 -1 24067 -1 24068 -1 24069 -1 24070 -1 24071 -1 24072 -1 24073 -1 24074 -1 24075 -1 24076 -1 24077 -1 24078 -1 24079 -1 24080 -1 24081 -1 24082 -1 24083 -1 24084 -1 24085 -1 24086 -1 24087 -1 24088 -1 24089 -1 24090 -1 24091 -1 24092 -1 24093 -1 24094 -1 24095 -1 24096 -1 24097 -1 24098 -1 24099 -1 24100 -1 24101 -1 24102 -1 24103 -1 24104 -1 24105 -1 24106 -1 24107 -1 24108 -1 24109 -1 24110 -1 24111 -1 24112 -1 24113 -1 24114 -1 24115 -1 24116 -1 24117 -1 24118 -1 24119 -1 24120 -1 24121 -1 24122 -1 24123 -1 24124 -1 24125 -1 24126 -1 24127 -1 24128 -1 24129 -1 24130 -1 24131 -1 24132 -1 24133 -1 24134 -1 24135 -1 24136 -1 24137 -1 24138 -1 24139 -1 24140 -1 24141 -1 24142 -1 24143 -1 24144 -1 24145 -1 24146 -1 24147 -1 24148 -1 24149 -1 24150 -1 24151 -1 24152 -1 24153 diff --git a/thirdparty/libpointmatcher/examples/data/cloudList.csv b/thirdparty/libpointmatcher/examples/data/cloudList.csv deleted file mode 100644 index 27ad7c8..0000000 --- a/thirdparty/libpointmatcher/examples/data/cloudList.csv +++ /dev/null @@ -1,4 +0,0 @@ -reading -cloud.00000.vtk -cloud.00001.vtk -cloud.00002.vtk diff --git a/thirdparty/libpointmatcher/examples/data/default-convert.yaml b/thirdparty/libpointmatcher/examples/data/default-convert.yaml deleted file mode 100644 index f07c133..0000000 --- a/thirdparty/libpointmatcher/examples/data/default-convert.yaml +++ /dev/null @@ -1,12 +0,0 @@ -- BoundingBoxDataPointsFilter: - xMin: -4.0 - xMax: 4.0 - yMin: -4.0 - yMax: 4.0 - zMin: -4.0 - zMax: 4.0 - removeInside: 1 -- SamplingSurfaceNormalDataPointsFilter: - knn: 10 -- ObservationDirectionDataPointsFilter -- OrientNormalsDataPointsFilter diff --git a/thirdparty/libpointmatcher/examples/data/default-identity.yaml b/thirdparty/libpointmatcher/examples/data/default-identity.yaml deleted file mode 100644 index 747fb4e..0000000 --- a/thirdparty/libpointmatcher/examples/data/default-identity.yaml +++ /dev/null @@ -1,38 +0,0 @@ -readingDataPointsFilters: - - IdentityDataPointsFilter: - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - ratio: 1.0 - samplingMethod: 0 - averageExistingDescriptors: 0 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 1.0 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/default.yaml b/thirdparty/libpointmatcher/examples/data/default.yaml deleted file mode 100644 index 884032a..0000000 --- a/thirdparty/libpointmatcher/examples/data/default.yaml +++ /dev/null @@ -1,46 +0,0 @@ -readingDataPointsFilters: - - RandomSamplingDataPointsFilter: - prob: 0.5 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -#inspector: -# NullInspector - -inspector: - VTKFileInspector: - baseFileName: pointmatcher-run1 - dumpPerfOnExit: 0 - dumpStats: 0 - dumpIterationInfo: 1 - dumpDataLinks: 0 - dumpReading: 0 - dumpReference: 0 - - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter1.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter1.ref_trans deleted file mode 100644 index 4904fa3..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter1.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9807664752006531 -0.1583272665739059 0.1141471043229103 -0.08772790431976318 -0.1750310957431793 0.9722270369529724 -0.1553668081760406 -0.2176001071929932 --0.08637809008359909 0.1723578721284866 0.9812397956848145 -0.05287289619445801 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter1.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter1.yaml deleted file mode 100644 index 6cbd1d3..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter1.yaml +++ /dev/null @@ -1,38 +0,0 @@ -readingDataPointsFilters: - - RandomSamplingDataPointsFilter: - prob: 0.5 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - ratio: 0.7 - samplingMethod: 0 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter2.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter2.ref_trans deleted file mode 100644 index 0addcc2..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter2.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9800660610198975 -0.160915344953537 0.1165167614817619 -0.1030929088592529 -0.1780297160148621 0.9716479778289795 -0.1555817723274231 -0.2162790298461914 --0.08817778527736664 0.1732239276170731 0.9809271693229675 -0.05410361289978027 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter2.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter2.yaml deleted file mode 100644 index c59d4fe..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter2.yaml +++ /dev/null @@ -1,39 +0,0 @@ -readingDataPointsFilters: - - RandomSamplingDataPointsFilter: - prob: 0.5 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - ratio: 0.666666 - samplingMethod: 1 - averageExistingDescriptors: 0 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter3.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter3.ref_trans deleted file mode 100644 index 5dadfc7..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter3.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9799573421478271 -0.1613964289426804 0.1167683973908424 -0.1059442758560181 -0.1786032468080521 0.9714489579200745 -0.1561653017997742 -0.2180365920066833 --0.08822999894618988 0.1738905906677246 0.9808042645454407 -0.0513763427734375 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter3.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter3.yaml deleted file mode 100644 index dc1a134..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/SamplingSurfaceNormalDataPointsFilter3.yaml +++ /dev/null @@ -1,39 +0,0 @@ -readingDataPointsFilters: - - RandomSamplingDataPointsFilter: - prob: 0.5 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - ratio: 0.666666 - samplingMethod: 1 - averageExistingDescriptors: 1 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultBoundingBoxDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultBoundingBoxDataPointsFilter.ref_trans deleted file mode 100644 index 05c23a2..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultBoundingBoxDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9801148772239685 -0.1606823354959488 0.1164287924766541 -0.1039974689483643 -0.1777812242507935 0.9716974496841431 -0.1555580049753189 -0.216127872467041 --0.08813809603452682 0.173163577914238 0.9809413552284241 -0.05247235298156738 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultBoundingBoxDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultBoundingBoxDataPointsFilter.yaml deleted file mode 100644 index 7ba837e..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultBoundingBoxDataPointsFilter.yaml +++ /dev/null @@ -1,39 +0,0 @@ -readingDataPointsFilters: - - BoundingBoxDataPointsFilter: - xMin: 0.2 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - ratio: 0.666666 - samplingMethod: 1 - averageExistingDescriptors: 0 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultDistanceLimitDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultDistanceLimitDataPointsFilter.ref_trans deleted file mode 100644 index 05c23a2..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultDistanceLimitDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9801148772239685 -0.1606823354959488 0.1164287924766541 -0.1039974689483643 -0.1777812242507935 0.9716974496841431 -0.1555580049753189 -0.216127872467041 --0.08813809603452682 0.173163577914238 0.9809413552284241 -0.05247235298156738 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultDistanceLimitDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultDistanceLimitDataPointsFilter.yaml deleted file mode 100644 index 9572e17..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultDistanceLimitDataPointsFilter.yaml +++ /dev/null @@ -1,40 +0,0 @@ -readingDataPointsFilters: - - DistanceLimitDataPointsFilter: - dist: 200 - removeInside: 0 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - ratio: 0.666666 - samplingMethod: 1 - averageExistingDescriptors: 0 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultFixStepSamplingDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultFixStepSamplingDataPointsFilter.ref_trans deleted file mode 100644 index 0f72690..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultFixStepSamplingDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9797301888465881 -0.1610165983438492 0.1191739067435265 -0.1010794639587402 -0.1785348951816559 0.9716610908508301 -0.1549203097820282 -0.2270656824111938 --0.09085189551115036 0.1730567514896393 0.9807124137878418 -0.0547327995300293 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultFixStepSamplingDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultFixStepSamplingDataPointsFilter.yaml deleted file mode 100644 index 2342a59..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultFixStepSamplingDataPointsFilter.yaml +++ /dev/null @@ -1,41 +0,0 @@ -readingDataPointsFilters: - - FixStepSamplingDataPointsFilter: - startStep: 10 - endStep: 10 - stepMult: 1 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - ratio: 0.666666 - samplingMethod: 1 - averageExistingDescriptors: 0 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultIdentityDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultIdentityDataPointsFilter.ref_trans deleted file mode 100644 index 05c23a2..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultIdentityDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9801148772239685 -0.1606823354959488 0.1164287924766541 -0.1039974689483643 -0.1777812242507935 0.9716974496841431 -0.1555580049753189 -0.216127872467041 --0.08813809603452682 0.173163577914238 0.9809413552284241 -0.05247235298156738 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultIdentityDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultIdentityDataPointsFilter.yaml deleted file mode 100644 index 2598774..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultIdentityDataPointsFilter.yaml +++ /dev/null @@ -1,38 +0,0 @@ -readingDataPointsFilters: - - IdentityDataPointsFilter: - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - ratio: 0.666666 - samplingMethod: 1 - averageExistingDescriptors: 0 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxDensityDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxDensityDataPointsFilter.ref_trans deleted file mode 100644 index 602c1db..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxDensityDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9797302484512329 -0.1622524261474609 0.1174839362502098 -0.1621661186218262 -0.1795323640108109 0.971358060836792 -0.1556648015975952 -0.1850830912590027 --0.08886195719242096 0.1736017018556595 0.9807986617088318 -0.1617109775543213 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxDensityDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxDensityDataPointsFilter.yaml deleted file mode 100644 index 417bb8c..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxDensityDataPointsFilter.yaml +++ /dev/null @@ -1,40 +0,0 @@ -readingDataPointsFilters: - - SurfaceNormalDataPointsFilter: - knn: 10 - keepDensities: 1 - - - MaxDensityDataPointsFilter: - maxDensity: 0.3 - -referenceDataPointsFilters: - - SurfaceNormalDataPointsFilter: - knn: 10 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxDistDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxDistDataPointsFilter.ref_trans deleted file mode 100644 index 05c23a2..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxDistDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9801148772239685 -0.1606823354959488 0.1164287924766541 -0.1039974689483643 -0.1777812242507935 0.9716974496841431 -0.1555580049753189 -0.216127872467041 --0.08813809603452682 0.173163577914238 0.9809413552284241 -0.05247235298156738 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxDistDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxDistDataPointsFilter.yaml deleted file mode 100644 index ef86741..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxDistDataPointsFilter.yaml +++ /dev/null @@ -1,39 +0,0 @@ -readingDataPointsFilters: - - MaxDistDataPointsFilter: - maxDist: 200 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - ratio: 0.666666 - samplingMethod: 1 - averageExistingDescriptors: 0 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxPointCountDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxPointCountDataPointsFilter.ref_trans deleted file mode 100644 index 28e8ddb..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxPointCountDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9801519513130188 -0.1603859663009644 0.1165294796228409 -0.1041241884231567 -0.1775060296058655 0.9717456102371216 -0.1555691659450531 -0.2163921594619751 --0.0882859081029892 0.1731660962104797 0.980927586555481 -0.05197405815124512 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxPointCountDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxPointCountDataPointsFilter.yaml deleted file mode 100644 index 69847b3..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxPointCountDataPointsFilter.yaml +++ /dev/null @@ -1,39 +0,0 @@ -readingDataPointsFilters: - - MaxPointCountDataPointsFilter: - maxCount: 500 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - ratio: 0.666666 - samplingMethod: 1 - averageExistingDescriptors: 0 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxQuantileOnAxisDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxQuantileOnAxisDataPointsFilter.ref_trans deleted file mode 100644 index 55d1142..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxQuantileOnAxisDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9807453155517578 -0.1591110229492188 0.1132368147373199 -0.07697427272796631 -0.1757358014583588 0.971940815448761 -0.1563583761453629 -0.2175577878952026 --0.08518113195896149 0.1732474863529205 0.9811879396438599 -0.04933023452758789 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxQuantileOnAxisDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxQuantileOnAxisDataPointsFilter.yaml deleted file mode 100644 index 85fd98f..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultMaxQuantileOnAxisDataPointsFilter.yaml +++ /dev/null @@ -1,39 +0,0 @@ -readingDataPointsFilters: - - MaxQuantileOnAxisDataPointsFilter: - ratio: 0.72 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - ratio: 0.666666 - samplingMethod: 1 - averageExistingDescriptors: 0 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultObservationDirectionDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultObservationDirectionDataPointsFilter.ref_trans deleted file mode 100644 index 5774d44..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultObservationDirectionDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9808356165885925 -0.1581308841705322 0.1138257682323456 -0.08235859870910645 -0.1748028993606567 0.9722275137901306 -0.1556223481893539 -0.2180026173591614 --0.08605584502220154 0.1725370734930038 0.9812365770339966 -0.0498192310333252 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultObservationDirectionDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultObservationDirectionDataPointsFilter.yaml deleted file mode 100644 index ee6d2a6..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultObservationDirectionDataPointsFilter.yaml +++ /dev/null @@ -1,41 +0,0 @@ -readingDataPointsFilters: - - SurfaceNormalDataPointsFilter: - knn: 10 - - - ObservationDirectionDataPointsFilter: - x: 1 - y: 2 - z: 3 - -referenceDataPointsFilters: - - SurfaceNormalDataPointsFilter: - knn: 10 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultOrientNormalsDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultOrientNormalsDataPointsFilter.ref_trans deleted file mode 100644 index 5774d44..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultOrientNormalsDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9808356165885925 -0.1581308841705322 0.1138257682323456 -0.08235859870910645 -0.1748028993606567 0.9722275137901306 -0.1556223481893539 -0.2180026173591614 --0.08605584502220154 0.1725370734930038 0.9812365770339966 -0.0498192310333252 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultOrientNormalsDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultOrientNormalsDataPointsFilter.yaml deleted file mode 100644 index a931434..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultOrientNormalsDataPointsFilter.yaml +++ /dev/null @@ -1,44 +0,0 @@ -readingDataPointsFilters: - - SurfaceNormalDataPointsFilter: - knn: 10 - - - ObservationDirectionDataPointsFilter: - x: 1 - y: 2 - z: 3 - - - OrientNormalsDataPointsFilter: - towardCenter: 1 - -referenceDataPointsFilters: - - SurfaceNormalDataPointsFilter: - knn: 10 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPlaneMinDistDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPlaneMinDistDataPointsFilter.ref_trans deleted file mode 100644 index 05c23a2..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPlaneMinDistDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9801148772239685 -0.1606823354959488 0.1164287924766541 -0.1039974689483643 -0.1777812242507935 0.9716974496841431 -0.1555580049753189 -0.216127872467041 --0.08813809603452682 0.173163577914238 0.9809413552284241 -0.05247235298156738 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPlaneMinDistDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPlaneMinDistDataPointsFilter.yaml deleted file mode 100644 index b0a4da8..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPlaneMinDistDataPointsFilter.yaml +++ /dev/null @@ -1,39 +0,0 @@ -readingDataPointsFilters: - - MinDistDataPointsFilter: - minDist: 1 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - ratio: 0.666666 - samplingMethod: 1 - averageExistingDescriptors: 0 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPlaneWithCovErrorMinimizer.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPlaneWithCovErrorMinimizer.ref_trans deleted file mode 100644 index c041b40..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPlaneWithCovErrorMinimizer.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9808169603347778 -0.158151313662529 0.1139567270874977 -0.08499085903167725 -0.1748128086328506 0.9722858071327209 -0.155243769288063 -0.21916264295578 --0.08624652028083801 0.172186866402626 0.9812814593315125 -0.05274653434753418 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPointMinDistDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPointMinDistDataPointsFilter.ref_trans deleted file mode 100644 index 1141f78..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPointMinDistDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9810525178909302 -0.158873662352562 0.1109369620680809 -0.09044396877288818 -0.1747461557388306 0.9727798104286194 -0.152223140001297 -0.2512578964233398 --0.08373246341943741 0.1687234789133072 0.9821048378944397 -0.06846070289611816 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPointMinDistDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPointMinDistDataPointsFilter.yaml deleted file mode 100644 index f96868b..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPointMinDistDataPointsFilter.yaml +++ /dev/null @@ -1,41 +0,0 @@ -readingDataPointsFilters: - - MinDistDataPointsFilter: - minDist: 1 - - RandomSamplingDataPointsFilter: - prob: 0.05 - -referenceDataPointsFilters: - - MinDistDataPointsFilter: - minDist: 1.0 - - RandomSamplingDataPointsFilter: - prob: 0.05 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 3.16 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPointErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 150 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPointWithCovErrorMinimizer.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPointWithCovErrorMinimizer.ref_trans deleted file mode 100644 index 005bf05..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultPointToPointWithCovErrorMinimizer.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9837196469306946 -0.1375317871570587 0.1157093048095703 -0.1278921365737915 -0.1548487842082977 0.9753625988960266 -0.1571529656648636 -0.2221848368644714 --0.09124428033828735 0.1725115478038788 0.9807750582695007 -0.05452704429626465 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultRemoveNaNDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultRemoveNaNDataPointsFilter.ref_trans deleted file mode 100644 index 05c23a2..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultRemoveNaNDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9801148772239685 -0.1606823354959488 0.1164287924766541 -0.1039974689483643 -0.1777812242507935 0.9716974496841431 -0.1555580049753189 -0.216127872467041 --0.08813809603452682 0.173163577914238 0.9809413552284241 -0.05247235298156738 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultRemoveNaNDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultRemoveNaNDataPointsFilter.yaml deleted file mode 100644 index 1edf6a0..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultRemoveNaNDataPointsFilter.yaml +++ /dev/null @@ -1,38 +0,0 @@ -readingDataPointsFilters: - - RemoveNaNDataPointsFilter: - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - ratio: 0.666666 - samplingMethod: 1 - averageExistingDescriptors: 0 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultRobustOutlierFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultRobustOutlierFilter.ref_trans deleted file mode 100644 index 22ae54b..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultRobustOutlierFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9790875911712646 -0.1649211347103119 0.1191405802965164 -0.1759523153305054 -0.1822330206632614 0.9712686538696289 -0.153078094124794 -0.2485396265983582 --0.09047131240367889 0.171587347984314 0.9810070991516113 -0.06492233276367188 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultRobustOutlierFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultRobustOutlierFilter.yaml deleted file mode 100644 index 6622ddb..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultRobustOutlierFilter.yaml +++ /dev/null @@ -1,37 +0,0 @@ -readingDataPointsFilters: - -referenceDataPointsFilters: - -matcher: - KDTreeMatcher: - knn: 10 - epsilon: 0 - -outlierFilters: - - RobustOutlierFilter: - robustFct: cauchy - scaleEstimator: mad - tuning: 1 - -errorMinimizer: - PointToPointErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector: -# dumpDataLinks: 1 -# dumpReading: 1 -# dumpReference: 1 - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultShadowDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultShadowDataPointsFilter.ref_trans deleted file mode 100644 index 5774d44..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultShadowDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9808356165885925 -0.1581308841705322 0.1138257682323456 -0.08235859870910645 -0.1748028993606567 0.9722275137901306 -0.1556223481893539 -0.2180026173591614 --0.08605584502220154 0.1725370734930038 0.9812365770339966 -0.0498192310333252 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultShadowDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultShadowDataPointsFilter.yaml deleted file mode 100644 index d0cbecd..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultShadowDataPointsFilter.yaml +++ /dev/null @@ -1,39 +0,0 @@ -readingDataPointsFilters: - - SurfaceNormalDataPointsFilter: - knn: 10 - - - ShadowDataPointsFilter: - eps: 0.00001 - -referenceDataPointsFilters: - - SurfaceNormalDataPointsFilter: - knn: 10 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultSimilarityPointToPointMinDistDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultSimilarityPointToPointMinDistDataPointsFilter.ref_trans deleted file mode 100644 index a2df542..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultSimilarityPointToPointMinDistDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9824342131614685 -0.15690678358078 0.1140052080154419 -0.08646523952484131 -0.1735319942235947 0.9740102887153625 -0.1548466235399246 -0.2217669486999512 --0.08662448823451996 0.1716707795858383 0.9827582240104675 -0.05477428436279297 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultSimilarityPointToPointMinDistDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultSimilarityPointToPointMinDistDataPointsFilter.yaml deleted file mode 100644 index efaace1..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultSimilarityPointToPointMinDistDataPointsFilter.yaml +++ /dev/null @@ -1,40 +0,0 @@ -# Test for PointToPointSimilarityErrorMinimizer -readingDataPointsFilters: - - MinDistDataPointsFilter: - minDist: 1.0 - - RandomSamplingDataPointsFilter: - prob: 1 - -referenceDataPointsFilters: - - MinDistDataPointsFilter: - minDist: 1.0 - - RandomSamplingDataPointsFilter: - prob: 1 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 3.16 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPointSimilarityErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 150 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - PerformanceInspector - -logger: -# FileLogger - NullLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultSimpleSensorNoiseDataPointsFilter.ref_trans b/thirdparty/libpointmatcher/examples/data/icp_data/defaultSimpleSensorNoiseDataPointsFilter.ref_trans deleted file mode 100644 index 5774d44..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultSimpleSensorNoiseDataPointsFilter.ref_trans +++ /dev/null @@ -1,4 +0,0 @@ -0.9808356165885925 -0.1581308841705322 0.1138257682323456 -0.08235859870910645 -0.1748028993606567 0.9722275137901306 -0.1556223481893539 -0.2180026173591614 --0.08605584502220154 0.1725370734930038 0.9812365770339966 -0.0498192310333252 - 0 0 0 1 \ No newline at end of file diff --git a/thirdparty/libpointmatcher/examples/data/icp_data/defaultSimpleSensorNoiseDataPointsFilter.yaml b/thirdparty/libpointmatcher/examples/data/icp_data/defaultSimpleSensorNoiseDataPointsFilter.yaml deleted file mode 100644 index dbce1c1..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_data/defaultSimpleSensorNoiseDataPointsFilter.yaml +++ /dev/null @@ -1,39 +0,0 @@ -readingDataPointsFilters: - - SurfaceNormalDataPointsFilter: - knn: 10 - - - SimpleSensorNoiseDataPointsFilter: - gain: 2 - -referenceDataPointsFilters: - - SurfaceNormalDataPointsFilter: - knn: 10 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/icp_scale.yaml b/thirdparty/libpointmatcher/examples/data/icp_scale.yaml deleted file mode 100644 index 90e9a36..0000000 --- a/thirdparty/libpointmatcher/examples/data/icp_scale.yaml +++ /dev/null @@ -1,46 +0,0 @@ -readingDataPointsFilters: - - RandomSamplingDataPointsFilter: - prob: 0.5 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - -matcher: - KDTreeMatcher: - knn: 3 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.95 - -errorMinimizer: - PointToPointSimilarityErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 80 - - DifferentialTransformationChecker: - minDiffRotErr: 0.08 - minDiffTransErr: 0.01 - smoothLength: 4 - -#inspector: -# NullInspector - -inspector: - VTKFileInspector: - baseFileName: pointmatcher-run1 - dumpPerfOnExit: 0 - dumpStats: 0 - dumpIterationInfo: 1 - dumpDataLinks: 1 - dumpReading: 1 - dumpReference: 1 - - -logger: -# NullLogger - FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/unit_tests/badIcpConfig_InvalidModuleType.yaml b/thirdparty/libpointmatcher/examples/data/unit_tests/badIcpConfig_InvalidModuleType.yaml deleted file mode 100644 index 2c538e0..0000000 --- a/thirdparty/libpointmatcher/examples/data/unit_tests/badIcpConfig_InvalidModuleType.yaml +++ /dev/null @@ -1,36 +0,0 @@ -FAKE_MODULE_NAME: - - RandomSamplingDataPointsFilter: - prob: 0.5 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/data/unit_tests/badIcpConfig_InvalidParameter.yaml b/thirdparty/libpointmatcher/examples/data/unit_tests/badIcpConfig_InvalidParameter.yaml deleted file mode 100644 index b1a6ad4..0000000 --- a/thirdparty/libpointmatcher/examples/data/unit_tests/badIcpConfig_InvalidParameter.yaml +++ /dev/null @@ -1,37 +0,0 @@ -readingDataPointsFilters: - - RandomSamplingDataPointsFilter: - FAKE_PARAM: 0.5 - prob: 0.5 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - -matcher: - KDTreeMatcher: - knn: 1 - epsilon: 0 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.75 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - NullInspector -# VTKFileInspector - -logger: - NullLogger -# FileLogger - diff --git a/thirdparty/libpointmatcher/examples/demo_Qt/demo.pro b/thirdparty/libpointmatcher/examples/demo_Qt/demo.pro deleted file mode 100644 index 1a3a998..0000000 --- a/thirdparty/libpointmatcher/examples/demo_Qt/demo.pro +++ /dev/null @@ -1,28 +0,0 @@ -# Example of a configuration file for QT Creator -# -# NOTE: you will need to adapt the paths to your own system - -QT += core gui -greaterThan(QT_MAJOR_VERSION, 4): QT += widgets -TARGET = LAUPointMatcher -TEMPLATE = app -SOURCES += main.cpp - -INCLUDEPATH += /Users/francoispomerleau/Research/Code/libpointmatcher/pointmatcher \ - /Users/francoispomerleau/Research/Code/libnabo/ \ - /usr/local/Cellar/eigen/3.2.4/include/eigen3 \ - /usr/local/include/ - -CONFIG += c++11 -#QMAKE_CXXFLAGS += -mmacosx-version-min=10.7 -#QMAKE_LFLAGS += -mmacosx-version-min=10.7 - -LIBS += /usr/local/lib/libboost_thread-mt.dylib \ - /usr/local/lib/libboost_filesystem-mt.dylib \ - /usr/local/lib/libboost_system-mt.dylib \ - /usr/local/lib/libboost_program_options-mt.dylib \ - /usr/local/lib/libboost_date_time-mt.dylib \ - /usr/local/lib/libboost_chrono-mt.dylib \ - /Users/francoispomerleau/Research/Code/libpointmatcher/build/libpointmatcher.a \ - /Users/francoispomerleau/Research/Code/libnabo/build/libnabo.a \ - /Users/francoispomerleau/Research/Code/libpointmatcher/build/contrib/yaml-cpp-pm/libyaml-cpp-pm.a diff --git a/thirdparty/libpointmatcher/examples/demo_Qt/main.cpp b/thirdparty/libpointmatcher/examples/demo_Qt/main.cpp deleted file mode 100644 index ecf91a0..0000000 --- a/thirdparty/libpointmatcher/examples/demo_Qt/main.cpp +++ /dev/null @@ -1,25 +0,0 @@ -#include -#include -#include "PointMatcher.h" - -class LAUPointMatcherWidget : public QWidget -{ - //Q_OBJECT - - public: - //LAUPointMatcherWidget(QWidget *parent = 0) : QWidget(parent) { ; } - //~LAUPointMatcherWidget(); - - private: - PointMatcher::DataPoints::Label label; -}; - -int main(int argc, char *argv[]) -{ - QApplication a(argc, argv); - LAUPointMatcherWidget w; - w.show(); - - return a.exec(); -} - diff --git a/thirdparty/libpointmatcher/examples/demo_cmake/CMakeLists.txt b/thirdparty/libpointmatcher/examples/demo_cmake/CMakeLists.txt deleted file mode 100644 index 923cbbf..0000000 --- a/thirdparty/libpointmatcher/examples/demo_cmake/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ -# This is demo on how to link libpointmatcher to an -# external project. - -cmake_minimum_required (VERSION 2.8) -project(convert) - -set (CMAKE_CXX_STANDARD 11) -add_compile_options(-std=c++11) - -find_package(libpointmatcher REQUIRED) - -include_directories(${CMAKE_CURRENT_BINARY_DIR} ${libpointmatcher_INCLUDE_DIRS}) - -add_executable(${PROJECT_NAME} convert.cpp) - -target_link_libraries(${PROJECT_NAME} ${libpointmatcher_LIBRARIES}) diff --git a/thirdparty/libpointmatcher/examples/demo_cmake/convert.cpp b/thirdparty/libpointmatcher/examples/demo_cmake/convert.cpp deleted file mode 100644 index cd095a1..0000000 --- a/thirdparty/libpointmatcher/examples/demo_cmake/convert.cpp +++ /dev/null @@ -1,86 +0,0 @@ -// kate: replace-tabs off; indent-width 4; indent-mode normal -// vim: ts=4:sw=4:noexpandtab -/* - -Copyright (c) 2010--2012, -François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland -You can contact the authors at and - - -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 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 ETH-ASL 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. - -*/ - -#include "pointmatcher/PointMatcher.h" -#include -#include -#include - -using namespace std; -using namespace PointMatcherSupport; - -typedef PointMatcher PM; -typedef PM::DataPoints DP; - -void usage(char *argv[]) -{ - cerr << "Usage " << argv[0] << " [CONFIG.yaml] INPUT.csv/.vtk/.ply OUTPUT.csv/.vtk/.ply" << endl; - cerr << endl << "Example:" << endl; - cerr << argv[0] << " ../examples/data/default-convert.yaml ../examples/data/cloud.00000.vtk /tmp/output.vtk" << endl << endl; - cerr << " or " << endl; - cerr << argv[0] << "../examples/data/cloud.00000.vtk /tmp/output.csv" << endl << endl; - -} - -int main(int argc, char *argv[]) -{ - if (argc < 3) - { - usage(argv); - return 1; - } - - setLogger(PM::get().LoggerRegistrar.create("FileLogger")); - - DP d(DP::load(argv[argc-2])); - - if (argc == 4) - { - ifstream ifs(argv[1]); - if (!ifs.good()) - { - cerr << "Cannot open config file " << argv[1] << endl; - usage(argv); - return 2; - } - PM::DataPointsFilters f(ifs); - f.apply(d); - - } - - d.save(argv[argc-1]); - - return 0; -} diff --git a/thirdparty/libpointmatcher/examples/demo_cmake/default-convert.yaml b/thirdparty/libpointmatcher/examples/demo_cmake/default-convert.yaml deleted file mode 100644 index f9a013f..0000000 --- a/thirdparty/libpointmatcher/examples/demo_cmake/default-convert.yaml +++ /dev/null @@ -1,8 +0,0 @@ -- BoundingBoxDataPointsFilter: - xMin: -800.0 - xMax: 800.0 - yMin: -800.0 - yMax: 800.0 - zMin: -800.0 - zMax: 800.0 - removeInside: 0 diff --git a/thirdparty/libpointmatcher/examples/filterProfiler.cpp b/thirdparty/libpointmatcher/examples/filterProfiler.cpp deleted file mode 100644 index af07243..0000000 --- a/thirdparty/libpointmatcher/examples/filterProfiler.cpp +++ /dev/null @@ -1,99 +0,0 @@ -/* - * filterProfiler.cpp - * - * Created on: Feb 27, 2014 - * Author: sam - */ - -#include -#include -#include -#include -#include - -using namespace PointMatcherSupport; -using namespace std; -using namespace boost; - -typedef PointMatcher PM; -typedef PM::DataPoints DP; -typedef PM::Parameters Parameters; - -int main(int argc, char *argv[]) -{ - - if (argc < 2 || argc > 3) - { - std::cerr << "USAGE: filterProfiler " << std::endl; - return -1; - } - - char* useCentroid; - if (argc == 3) { - if (strcmp(argv[2],"1") != 0 && strcmp(argv[2],"0")) { - cerr << "param useCentroid must be 1 or 0" << endl; - return -1; - } else - { - useCentroid = argv[2]; - } - } else { - useCentroid = "1"; - } - - //setLogger(PM::get().LoggerRegistrar.create("FileLogger")); - - DP in(DP::load(argv[1])); - - std::shared_ptr randomSample = - PM::get().DataPointsFilterRegistrar.create( - "RandomSamplingDataPointsFilter", - {{"prob", toParam(0.5)}} - ); - - cout << "starting random sample filter" << endl; - clock_t time_a = clock(); - randomSample->inPlaceFilter(in); - clock_t time_b = clock(); - - if (time_a == ((clock_t)-1) || time_b == ((clock_t)-1)) - { - perror("Unable to calculate elapsed time"); - return -1; - } - else - { - cout << "Performed random sampling in " << (float)(time_b - time_a)/CLOCKS_PER_SEC << " seconds" << endl; - } - - std::shared_ptr voxelf = - PM::get().DataPointsFilterRegistrar.create( - "VoxelGridDataPointsFilter", - { - {"vSizeX", "0.2"}, - {"vSizeY", "0.2"}, - {"vSizeZ", "0.2"}, - {"useCentroid",useCentroid}, - {"averageExistingDescriptors","0"} - } - ); - - cout << "starting voxel grid sample filter, useCentroid: " << useCentroid << endl; - time_a = clock(); - voxelf->inPlaceFilter(in); - time_b = clock(); - - if (time_a == ((clock_t)-1) || time_b == ((clock_t)-1)) - { - perror("Unable to calculate elapsed time"); - return -1; - } - else - { - cout << "Performed voxel grid sampling in " << (float)(time_b - time_a)/CLOCKS_PER_SEC << " seconds" << endl; - } - - return 0; -} - - diff --git a/thirdparty/libpointmatcher/examples/icp.cpp b/thirdparty/libpointmatcher/examples/icp.cpp deleted file mode 100644 index ab3f143..0000000 --- a/thirdparty/libpointmatcher/examples/icp.cpp +++ /dev/null @@ -1,419 +0,0 @@ -// kate: replace-tabs off; indent-width 4; indent-mode normal -// vim: ts=4:sw=4:noexpandtab -/* - -Copyright (c) 2010--2012, -François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland -You can contact the authors at and - - -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 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 ETH-ASL 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. - -*/ - -#include "pointmatcher/PointMatcher.h" -#include "pointmatcher/Bibliography.h" - -#include "boost/filesystem.hpp" - -#include -#include -#include -#include - -using namespace std; - -typedef PointMatcher PM; -typedef PM::DataPoints DP; -typedef PM::Parameters Parameters; -typedef PointMatcherSupport::CurrentBibliography CurrentBibliography; - -void listModules(); -int validateArgs(const int argc, const char *argv[], - bool& isVerbose, - bool& isTransfoSaved, - string& configFile, - string& outputBaseFile, - string& initTranslation, string& initRotation); -PM::TransformationParameters parseTranslation(string& translation, - const int cloudDimension); -PM::TransformationParameters parseRotation(string& rotation, - const int cloudDimension); -// Helper functions -void usage(const char *argv[]); - -/** - * Code example for ICP taking 2 points clouds (2D or 3D) relatively close - * and computing the transformation between them. - * - * This code is more complete than icp_simple. It can load parameter files and - * has more options. - */ -int main(int argc, const char *argv[]) -{ - bool isTransfoSaved = false; - bool isVerbose = false; - string configFile; - string outputBaseFile("test"); - string initTranslation("0,0,0"); - string initRotation("1,0,0;0,1,0;0,0,1"); - const int ret = validateArgs(argc, argv, isVerbose, isTransfoSaved, configFile, - outputBaseFile, initTranslation, initRotation); - if (ret != 0) - { - return ret; - } - const char *refFile(argv[argc-2]); - const char *dataFile(argv[argc-1]); - - // Load point clouds - const DP ref(DP::load(refFile)); - const DP data(DP::load(dataFile)); - - // Create the default ICP algorithm - PM::ICP icp; - - - if (configFile.empty()) - { - // See the implementation of setDefault() to create a custom ICP algorithm - icp.setDefault(); - } - else - { - // load YAML config - ifstream ifs(configFile.c_str()); - if (!ifs.good()) - { - cerr << "Cannot open config file " << configFile << ", usage:"; usage(argv); exit(1); - } - icp.loadFromYaml(ifs); - } - - - int cloudDimension = ref.getEuclideanDim(); - - if (!(cloudDimension == 2 || cloudDimension == 3)) - { - cerr << "Invalid input point clouds dimension" << endl; - exit(1); - } - - - - PM::TransformationParameters translation = - parseTranslation(initTranslation, cloudDimension); - PM::TransformationParameters rotation = - parseRotation(initRotation, cloudDimension); - PM::TransformationParameters initTransfo = translation*rotation; - - std::shared_ptr rigidTrans; - rigidTrans = PM::get().REG(Transformation).create("RigidTransformation"); - - if (!rigidTrans->checkParameters(initTransfo)) { - cerr << endl - << "Initial transformation is not rigid, identiy will be used" - << endl; - initTransfo = PM::TransformationParameters::Identity( - cloudDimension+1,cloudDimension+1); - } - - const DP initializedData = rigidTrans->compute(data, initTransfo); - - // Compute the transformation to express data in ref - PM::TransformationParameters T = icp(initializedData, ref); - if(isVerbose) - cout << "match ratio: " << icp.errorMinimizer->getWeightedPointUsedRatio() << endl; - - // Transform data to express it in ref - DP data_out(initializedData); - icp.transformations.apply(data_out, T); - - // Safe files to see the results - ref.save(outputBaseFile + "_ref.vtk"); - data.save(outputBaseFile + "_data_in.vtk"); - data_out.save(outputBaseFile + "_data_out.vtk"); - if(isTransfoSaved) { - ofstream transfoFile; - string initFileName = outputBaseFile + "_init_transfo.txt"; - string icpFileName = outputBaseFile + "_icp_transfo.txt"; - string completeFileName = outputBaseFile + "_complete_transfo.txt"; - - transfoFile.open(initFileName.c_str()); - if(transfoFile.is_open()) { - transfoFile << initTransfo << endl; - transfoFile.close(); - } else { - cerr << "Unable to write the initial transformation file\n" << endl; - } - - transfoFile.open(icpFileName.c_str()); - if(transfoFile.is_open()) { - transfoFile << T << endl; - transfoFile.close(); - } else { - cerr << "Unable to write the ICP transformation file\n" << endl; - } - - transfoFile.open(completeFileName.c_str()); - if(transfoFile.is_open()) { - transfoFile << T*initTransfo << endl; - transfoFile.close(); - } else { - cerr << "Unable to write the complete transformation file\n" << endl; - } - } - else - { - if(isVerbose) - cout << "ICP transformation:" << endl << T << endl; - } - - return 0; -} - -// The following code allows to dump all existing modules -template -void dumpRegistrar(const PM& pm, const R& registrar, const std::string& name, - CurrentBibliography& bib) -{ - cout << "* " << name << " *\n" << endl; - for (BOOST_AUTO(it, registrar.begin()); it != registrar.end(); ++it) - { - cout << it->first << endl; - cout << getAndReplaceBibEntries(it->second->description(), bib) << endl; - cout << it->second->availableParameters() << endl; - } - cout << endl; -} - -#define DUMP_REGISTRAR_CONTENT(pm, name, bib) \ - dumpRegistrar(pm, pm.REG(name), # name, bib); - -void listModules() -{ - CurrentBibliography bib; - - DUMP_REGISTRAR_CONTENT(PM::get(), Transformation, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), DataPointsFilter, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), Matcher, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), OutlierFilter, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), ErrorMinimizer, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), TransformationChecker, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), Inspector, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), Logger, bib) - - cout << "* Bibliography *" << endl << endl; - bib.dump(cout); -} - -// Make sure that the command arguments make sense -int validateArgs(const int argc, const char *argv[], - bool& isVerbose, - bool& isTransfoSaved, - string& configFile, - string& outputBaseFile, - string& initTranslation, string& initRotation) -{ - if (argc == 1) - { - cerr << "Not enough arguments, usage:"; - usage(argv); - return 1; - } - else if (argc == 2) - { - if (string(argv[1]) == "-l") - { - listModules(); - return -1; // we use -1 to say that we wish to quit but in a normal way - } - else - { - cerr << "Wrong option, usage:"; - usage(argv); - return 2; - } - } - - const int endOpt(argc - 2); - for (int i = 1; i < endOpt; i += 2) - { - const string opt(argv[i]); - if (opt == "--verbose" || opt == "-v") { - isVerbose = true; - i --; - continue; - } - if (i + 1 > endOpt) - { - cerr << "Missing value for option " << opt << ", usage:"; usage(argv); exit(1); - } - if (opt == "--isTransfoSaved") { - if (strcmp(argv[i+1], "1") == 0 || strcmp(argv[i+1], "true") == 0) { - isTransfoSaved = true; - } - else if (strcmp(argv[i+1], "0") == 0 - || strcmp(argv[i+1],"false") == 0) { - isTransfoSaved = false; - } - else { - cerr << "Invalid value for parameter isTransfoSaved." << endl - << "Value must be true or false or 1 or 0." << endl - << "Default value will be used." << endl; - } - } - else if (opt == "--config") { - configFile = argv[i+1]; - } - else if (opt == "--output") { - outputBaseFile = argv[i+1]; - } - else if (opt == "--initTranslation") { - initTranslation = argv[i+1]; - } - else if (opt == "--initRotation") { - initRotation = argv[i+1]; - } - else - { - cerr << "Unknown option " << opt << ", usage:"; usage(argv); exit(1); - } - } - return 0; -} - -PM::TransformationParameters parseTranslation(string& translation, - const int cloudDimension) { - PM::TransformationParameters parsedTranslation; - parsedTranslation = PM::TransformationParameters::Identity( - cloudDimension+1,cloudDimension+1); - - translation.erase(std::remove(translation.begin(), translation.end(), '['), - translation.end()); - translation.erase(std::remove(translation.begin(), translation.end(), ']'), - translation.end()); - std::replace( translation.begin(), translation.end(), ',', ' '); - std::replace( translation.begin(), translation.end(), ';', ' '); - - float translationValues[3] = {0}; - stringstream translationStringStream(translation); - for( int i = 0; i < cloudDimension; i++) { - if(!(translationStringStream >> translationValues[i])) { - cerr << "An error occured while trying to parse the initial " - << "translation." << endl - << "No initial translation will be used" << endl; - return parsedTranslation; - } - } - float extraOutput = 0; - if((translationStringStream >> extraOutput)) { - cerr << "Wrong initial translation size" << endl - << "No initial translation will be used" << endl; - return parsedTranslation; - } - - for( int i = 0; i < cloudDimension; i++) { - parsedTranslation(i,cloudDimension) = translationValues[i]; - } - - return parsedTranslation; -} - -PM::TransformationParameters parseRotation(string &rotation, - const int cloudDimension){ - PM::TransformationParameters parsedRotation; - parsedRotation = PM::TransformationParameters::Identity( - cloudDimension+1,cloudDimension+1); - - rotation.erase(std::remove(rotation.begin(), rotation.end(), '['), - rotation.end()); - rotation.erase(std::remove(rotation.begin(), rotation.end(), ']'), - rotation.end()); - std::replace( rotation.begin(), rotation.end(), ',', ' '); - std::replace( rotation.begin(), rotation.end(), ';', ' '); - - float rotationMatrix[9] = {0}; - stringstream rotationStringStream(rotation); - for( int i = 0; i < cloudDimension*cloudDimension; i++) { - if(!(rotationStringStream >> rotationMatrix[i])) { - cerr << "An error occured while trying to parse the initial " - << "rotation." << endl - << "No initial rotation will be used" << endl; - return parsedRotation; - } - } - float extraOutput = 0; - if((rotationStringStream >> extraOutput)) { - cerr << "Wrong initial rotation size" << endl - << "No initial rotation will be used" << endl; - return parsedRotation; - } - - for( int i = 0; i < cloudDimension*cloudDimension; i++) { - parsedRotation(i/cloudDimension,i%cloudDimension) = rotationMatrix[i]; - } - - return parsedRotation; -} - -// Dump command-line help -void usage(const char *argv[]) -{ - //TODO: add new options --isTransfoSaved, --initTranslation, --initRotation - cerr << endl << endl; - cerr << "* To list modules:" << endl; - cerr << " " << argv[0] << " -l" << endl; - cerr << endl; - cerr << "* To run ICP:" << endl; - cerr << " " << argv[0] << " [OPTIONS] reference.csv reading.csv" << endl; - cerr << endl; - cerr << "OPTIONS can be a combination of:" << endl; - cerr << "-v,--verbose Be more verbose (info logging to stdout)" << endl; - cerr << "--config YAML_CONFIG_FILE Load the config from a YAML file (default: default parameters)" << endl; - cerr << "--output BASEFILENAME Name of output files (default: test)" << endl; - cerr << "--initTranslation [x,y,z] Add an initial 3D translation before applying ICP (default: 0,0,0)" << endl; - cerr << "--initTranslation [x,y] Add an initial 2D translation before applying ICP (default: 0,0)" << endl; - cerr << "--initRotation [r00,r01,r02,r10,r11,r12,r20,r21,r22]" << endl; - cerr << " Add an initial 3D rotation before applying ICP (default: 1,0,0,0,1,0,0,0,1)" << endl; - cerr << "--initRotation [r00,r01,r10,r11]" << endl; - cerr << " Add an initial 2D rotation before applying ICP (default: 1,0,0,1)" << endl; - cerr << "--isTransfoSaved BOOL Save transformation matrix in three different files:" << endl; - cerr << " - BASEFILENAME_inti_transfo.txt" << endl; - cerr << " - BASEFILENAME_icp_transfo.txt" << endl; - cerr << " - BASEFILENAME_complete_transfo.txt" << endl; - cerr << " (default: false)" << endl; - cerr << endl; - cerr << "Running this program with a VTKFileInspector as Inspector will create three" << endl; - cerr << "vtk ouptput files: ./test_ref.vtk, ./test_data_in.vtk and ./test_data_out.vtk" << endl; - cerr << endl << "2D Example:" << endl; - cerr << " " << argv[0] << " ../examples/data/2D_twoBoxes.csv ../examples/data/2D_oneBox.csv" << endl; - cerr << endl << "3D Example:" << endl; - cerr << " " << argv[0] << " ../examples/data/car_cloud400.csv ../examples/data/car_cloud401.csv" << endl; - cerr << endl; -} - - - diff --git a/thirdparty/libpointmatcher/examples/icp_advance_api.cpp b/thirdparty/libpointmatcher/examples/icp_advance_api.cpp deleted file mode 100644 index bcb8cf2..0000000 --- a/thirdparty/libpointmatcher/examples/icp_advance_api.cpp +++ /dev/null @@ -1,478 +0,0 @@ -// kate: replace-tabs off; indent-width 4; indent-mode normal -// vim: ts=4:sw=4:noexpandtab -/* - -Copyright (c) 2010--2012, -François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland -You can contact the authors at and - - -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 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 ETH-ASL 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. - -*/ - -#include "pointmatcher/PointMatcher.h" -#include "pointmatcher/Bibliography.h" - -#include "boost/filesystem.hpp" - -#include -#include -#include -#include - -using namespace std; -using namespace PointMatcherSupport; - -typedef PointMatcher PM; -typedef PM::DataPoints DP; -typedef PM::Parameters Parameters; - -void listModules(); -int validateArgs(const int argc, const char *argv[], - bool& isTransfoSaved, - string& configFile, - string& outputBaseFile, - string& initTranslation, string& initRotation); -PM::TransformationParameters parseTranslation(string& translation, - const int cloudDimension); -PM::TransformationParameters parseRotation(string& rotation, - const int cloudDimension); -void usage(const char *argv[]); - -/** - * Code example for ICP taking 2 points clouds (2D or 3D) relatively close - * and computing the transformation between them. - * - * This code is more complete than icp_simple. It can load parameter files and - * has more options. - */ -int main(int argc, const char *argv[]) -{ - bool isTransfoSaved = false; - string configFile; - string outputBaseFile("test"); - string initTranslation("0,0,0"); - string initRotation("1,0,0;0,1,0;0,0,1"); - const int ret = validateArgs(argc, argv, isTransfoSaved, configFile, - outputBaseFile, initTranslation, initRotation); - if (ret != 0) - { - return ret; - } - const char *refFile(argv[argc-2]); - const char *dataFile(argv[argc-1]); - - // Load point clouds - const DP ref(DP::load(refFile)); - const DP data(DP::load(dataFile)); - - // Create the default ICP algorithm - PM::ICP icp; - - if (configFile.empty()) - { - // See the implementation of setDefault() to create a custom ICP algorithm - icp.setDefault(); - } - else - { - // load YAML config - ifstream ifs(configFile.c_str()); - if (!ifs.good()) - { - cerr << "Cannot open config file " << configFile << ", usage:"; usage(argv); exit(1); - } - icp.loadFromYaml(ifs); - } - - int cloudDimension = ref.getEuclideanDim(); - - if (!(cloudDimension == 2 || cloudDimension == 3)) - { - cerr << "Invalid input point clouds dimension" << endl; - exit(1); - } - - PM::TransformationParameters translation = - parseTranslation(initTranslation, cloudDimension); - PM::TransformationParameters rotation = - parseRotation(initRotation, cloudDimension); - PM::TransformationParameters initTransfo = translation*rotation; - - std::shared_ptr rigidTrans; - rigidTrans = PM::get().REG(Transformation).create("RigidTransformation"); - - if (!rigidTrans->checkParameters(initTransfo)) { - cerr << endl - << "Initial transformation is not rigid, identiy will be used" - << endl; - initTransfo = PM::TransformationParameters::Identity( - cloudDimension+1,cloudDimension+1); - } - - const DP initializedData = rigidTrans->compute(data, initTransfo); - - // Compute the transformation to express data in ref - PM::TransformationParameters T = icp(initializedData, ref); - float matchRatio = icp.errorMinimizer->getWeightedPointUsedRatio(); - cout << "match ratio: " << matchRatio << endl; - - - - // Transform data to express it in ref - DP data_out(initializedData); - icp.transformations.apply(data_out, T); - - cout << endl << "------------------" << endl; - - // START demo 1 - // Test for retrieving Haussdorff distance (with outliers). We generate new matching module - // specifically for this purpose. - // - // INPUTS: - // ref: point cloud used as reference - // data_out: aligned point cloud (using the transformation outputted by icp) - // icp: icp object used to aligned the point clouds - - - // Structure to hold future match results - PM::Matches matches; - - Parametrizable::Parameters params; - params["knn"] = toParam(1); // for Hausdorff distance, we only need the first closest point - params["epsilon"] = toParam(0); - - std::shared_ptr matcherHausdorff = PM::get().MatcherRegistrar.create("KDTreeMatcher", params); - - // max. distance from reading to reference - matcherHausdorff->init(ref); - matches = matcherHausdorff->findClosests(data_out); - float maxDist1 = matches.getDistsQuantile(1.0); - float maxDistRobust1 = matches.getDistsQuantile(0.85); - - // max. distance from reference to reading - matcherHausdorff->init(data_out); - matches = matcherHausdorff->findClosests(ref); - float maxDist2 = matches.getDistsQuantile(1.0); - float maxDistRobust2 = matches.getDistsQuantile(0.85); - - float haussdorffDist = std::max(maxDist1, maxDist2); - float haussdorffQuantileDist = std::max(maxDistRobust1, maxDistRobust2); - - cout << "Haussdorff distance: " << std::sqrt(haussdorffDist) << " m" << endl; - cout << "Haussdorff quantile distance: " << std::sqrt(haussdorffQuantileDist) << " m" << endl; - - // START demo 2 - // Test for retrieving paired point mean distance without outliers. We reuse the same module used for - // the icp object. - // - // INPUTS: - // ref: point cloud used as reference - // data_out: aligned point cloud (using the transformation outputted by icp) - // icp: icp object used to aligned the point clouds - - // initiate the matching with unfiltered point cloud - icp.matcher->init(ref); - - // extract closest points - matches = icp.matcher->findClosests(data_out); - - // weight paired points - const PM::OutlierWeights outlierWeights = icp.outlierFilters.compute(data_out, ref, matches); - - // generate tuples of matched points and remove pairs with zero weight - const PM::ErrorMinimizer::ErrorElements matchedPoints( data_out, ref, outlierWeights, matches); - - // extract relevant information for convenience - const int dim = matchedPoints.reading.getEuclideanDim(); - const int nbMatchedPoints = matchedPoints.reading.getNbPoints(); - const PM::Matrix matchedRead = matchedPoints.reading.features.topRows(dim); - const PM::Matrix matchedRef = matchedPoints.reference.features.topRows(dim); - - // compute mean distance - const PM::Matrix dist = (matchedRead - matchedRef).colwise().norm(); // replace that by squaredNorm() to save computation time - const float meanDist = dist.sum()/nbMatchedPoints; - cout << "Robust mean distance: " << meanDist << " m" << endl; - - // END demo - - cout << "------------------" << endl << endl; - - - // Safe files to see the results - ref.save(outputBaseFile + "_ref.vtk"); - data.save(outputBaseFile + "_data_in.vtk"); - data_out.save(outputBaseFile + "_data_out.vtk"); - if(isTransfoSaved) { - ofstream transfoFile; - string initFileName = outputBaseFile + "_init_transfo.txt"; - string icpFileName = outputBaseFile + "_icp_transfo.txt"; - string completeFileName = outputBaseFile + "_complete_transfo.txt"; - - transfoFile.open(initFileName.c_str()); - if(transfoFile.is_open()) { - transfoFile << initTransfo << endl; - transfoFile.close(); - } else { - cout << "Unable to write the initial transformation file\n" << endl; - } - - transfoFile.open(icpFileName.c_str()); - if(transfoFile.is_open()) { - transfoFile << T << endl; - transfoFile.close(); - } else { - cout << "Unable to write the ICP transformation file\n" << endl; - } - - transfoFile.open(completeFileName.c_str()); - if(transfoFile.is_open()) { - transfoFile << T*initTransfo << endl; - transfoFile.close(); - } else { - cout << "Unable to write the complete transformation file\n" << endl; - } - } - else { - cout << "ICP transformation:" << endl << T << endl; - } - - return 0; -} - -// The following code allows to dump all existing modules -template -void dumpRegistrar(const PM& pm, const R& registrar, const std::string& name, - CurrentBibliography& bib) -{ - cout << "* " << name << " *\n" << endl; - for (BOOST_AUTO(it, registrar.begin()); it != registrar.end(); ++it) - { - cout << it->first << endl; - cout << getAndReplaceBibEntries(it->second->description(), bib) << endl; - cout << it->second->availableParameters() << endl; - } - cout << endl; -} - -#define DUMP_REGISTRAR_CONTENT(pm, name, bib) \ - dumpRegistrar(pm, pm.REG(name), # name, bib); - -void listModules() -{ - CurrentBibliography bib; - - DUMP_REGISTRAR_CONTENT(PM::get(), Transformation, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), DataPointsFilter, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), Matcher, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), OutlierFilter, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), ErrorMinimizer, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), TransformationChecker, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), Inspector, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), Logger, bib) - - cout << "* Bibliography *" << endl << endl; - bib.dump(cout); -} - -// Make sure that the command arguments make sense -int validateArgs(const int argc, const char *argv[], - bool& isTransfoSaved, - string& configFile, - string& outputBaseFile, - string& initTranslation, string& initRotation) -{ - if (argc == 1) - { - cerr << "Not enough arguments, usage:"; - usage(argv); - return 1; - } - else if (argc == 2) - { - if (string(argv[1]) == "-l") - { - listModules(); - return -1; // we use -1 to say that we wish to quit but in a normal way - } - else - { - cerr << "Wrong option, usage:"; - usage(argv); - return 2; - } - } - - const int endOpt(argc - 2); - for (int i = 1; i < endOpt; i += 2) - { - const string opt(argv[i]); - if (i + 1 > endOpt) - { - cerr << "Missing value for option " << opt << ", usage:"; usage(argv); exit(1); - } - if (opt == "--isTransfoSaved") { - if (strcmp(argv[i+1], "1") == 0 || strcmp(argv[i+1], "true") == 0) { - isTransfoSaved = true; - } - else if (strcmp(argv[i+1], "0") == 0 - || strcmp(argv[i+1],"false") == 0) { - isTransfoSaved = false; - } - else { - cerr << "Invalid value for parameter isTransfoSaved." << endl - << "Value must be true or false or 1 or 0." << endl - << "Default value will be used." << endl; - } - } - else if (opt == "--config") { - configFile = argv[i+1]; - } - else if (opt == "--output") { - outputBaseFile = argv[i+1]; - } - else if (opt == "--initTranslation") { - initTranslation = argv[i+1]; - } - else if (opt == "--initRotation") { - initRotation = argv[i+1]; - } - else - { - cerr << "Unknown option " << opt << ", usage:"; usage(argv); exit(1); - } - } - return 0; -} - -PM::TransformationParameters parseTranslation(string& translation, - const int cloudDimension) { - PM::TransformationParameters parsedTranslation; - parsedTranslation = PM::TransformationParameters::Identity( - cloudDimension+1,cloudDimension+1); - - translation.erase(std::remove(translation.begin(), translation.end(), '['), - translation.end()); - translation.erase(std::remove(translation.begin(), translation.end(), ']'), - translation.end()); - std::replace( translation.begin(), translation.end(), ',', ' '); - std::replace( translation.begin(), translation.end(), ';', ' '); - - float translationValues[3] = {0}; - stringstream translationStringStream(translation); - for( int i = 0; i < cloudDimension; i++) { - if(!(translationStringStream >> translationValues[i])) { - cerr << "An error occured while trying to parse the initial " - << "translation." << endl - << "No initial translation will be used" << endl; - return parsedTranslation; - } - } - float extraOutput = 0; - if((translationStringStream >> extraOutput)) { - cerr << "Wrong initial translation size" << endl - << "No initial translation will be used" << endl; - return parsedTranslation; - } - - for( int i = 0; i < cloudDimension; i++) { - parsedTranslation(i,cloudDimension) = translationValues[i]; - } - - return parsedTranslation; -} - -PM::TransformationParameters parseRotation(string &rotation, - const int cloudDimension){ - PM::TransformationParameters parsedRotation; - parsedRotation = PM::TransformationParameters::Identity( - cloudDimension+1,cloudDimension+1); - - rotation.erase(std::remove(rotation.begin(), rotation.end(), '['), - rotation.end()); - rotation.erase(std::remove(rotation.begin(), rotation.end(), ']'), - rotation.end()); - std::replace( rotation.begin(), rotation.end(), ',', ' '); - std::replace( rotation.begin(), rotation.end(), ';', ' '); - - float rotationMatrix[9] = {0}; - stringstream rotationStringStream(rotation); - for( int i = 0; i < cloudDimension*cloudDimension; i++) { - if(!(rotationStringStream >> rotationMatrix[i])) { - cerr << "An error occured while trying to parse the initial " - << "rotation." << endl - << "No initial rotation will be used" << endl; - return parsedRotation; - } - } - float extraOutput = 0; - if((rotationStringStream >> extraOutput)) { - cerr << "Wrong initial rotation size" << endl - << "No initial rotation will be used" << endl; - return parsedRotation; - } - - for( int i = 0; i < cloudDimension*cloudDimension; i++) { - parsedRotation(i/cloudDimension,i%cloudDimension) = rotationMatrix[i]; - } - - return parsedRotation; -} - -// Dump command-line help -void usage(const char *argv[]) -{ - //TODO: add new options --isTransfoSaved, --initTranslation, --initRotation - cerr << endl << endl; - cerr << "* To list modules:" << endl; - cerr << " " << argv[0] << " -l" << endl; - cerr << endl; - cerr << "* To run ICP:" << endl; - cerr << " " << argv[0] << " [OPTIONS] reference.csv reading.csv" << endl; - cerr << endl; - cerr << "OPTIONS can be a combination of:" << endl; - cerr << "--config YAML_CONFIG_FILE Load the config from a YAML file (default: default parameters)" << endl; - cerr << "--output BASEFILENAME Name of output files (default: test)" << endl; - cerr << "--initTranslation [x,y,z] Add an initial 3D translation before applying ICP (default: 0,0,0)" << endl; - cerr << "--initTranslation [x,y] Add an initial 2D translation before applying ICP (default: 0,0)" << endl; - cerr << "--initRotation [r00,r01,r02,r10,r11,r12,r20,r21,r22]" << endl; - cerr << " Add an initial 3D rotation before applying ICP (default: 1,0,0,0,1,0,0,0,1)" << endl; - cerr << "--initRotation [r00,r01,r10,r11]" << endl; - cerr << " Add an initial 2D rotation before applying ICP (default: 1,0,0,1)" << endl; - cerr << "--isTransfoSaved BOOL Save transformation matrix in three different files:" << endl; - cerr << " - BASEFILENAME_inti_transfo.txt" << endl; - cerr << " - BASEFILENAME_icp_transfo.txt" << endl; - cerr << " - BASEFILENAME_complete_transfo.txt" << endl; - cerr << " (default: false)" << endl; - cerr << endl; - cerr << "Running this program with a VTKFileInspector as Inspector will create three" << endl; - cerr << "vtk ouptput files: ./test_ref.vtk, ./test_data_in.vtk and ./test_data_out.vtk" << endl; - cerr << endl << "2D Example:" << endl; - cerr << " " << argv[0] << " ../examples/data/2D_twoBoxes.csv ../examples/data/2D_oneBox.csv" << endl; - cerr << endl << "3D Example:" << endl; - cerr << " " << argv[0] << " ../examples/data/car_cloud400.csv ../examples/data/car_cloud401.csv" << endl; - cerr << endl; -} diff --git a/thirdparty/libpointmatcher/examples/icp_customized.cpp b/thirdparty/libpointmatcher/examples/icp_customized.cpp deleted file mode 100644 index e3e6931..0000000 --- a/thirdparty/libpointmatcher/examples/icp_customized.cpp +++ /dev/null @@ -1,202 +0,0 @@ -// kate: replace-tabs off; indent-width 4; indent-mode normal -// vim: ts=4:sw=4:noexpandtab -/* - -Copyright (c) 2010--2012, -François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland -You can contact the authors at and - - -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 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 ETH-ASL 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. - -*/ - -#include "pointmatcher/PointMatcher.h" -#include -#include -#include "boost/filesystem.hpp" - -using namespace std; - -void validateArgs(int argc, char *argv[], bool& isCSV); - -/** - * Code example for ICP taking 2 points clouds (2D or 3D) relatively close - * and computing the transformation between them. - * - * Instead of using yaml file for configuration, we configure the solution - * directly in the code. - * - * This code replicate the solution in /evaluations/official_solutions/Besl92_pt2point.yaml - */ -int main(int argc, char *argv[]) -{ - bool isCSV = true; - validateArgs(argc, argv, isCSV); - - typedef PointMatcher PM; - typedef PM::DataPoints DP; - - // Load point clouds - const DP ref(DP::load(argv[1])); - const DP data(DP::load(argv[2])); - - // Create the default ICP algorithm - PM::ICP icp; - PointMatcherSupport::Parametrizable::Parameters params; - std::string name; - - // Uncomment for console outputs - setLogger(PM::get().LoggerRegistrar.create("FileLogger")); - - // Prepare reading filters - name = "MinDistDataPointsFilter"; - params["minDist"] = "1.0"; - std::shared_ptr minDist_read = - PM::get().DataPointsFilterRegistrar.create(name, params); - params.clear(); - - name = "RandomSamplingDataPointsFilter"; - params["prob"] = "0.05"; - std::shared_ptr rand_read = - PM::get().DataPointsFilterRegistrar.create(name, params); - params.clear(); - - // Prepare reference filters - name = "MinDistDataPointsFilter"; - params["minDist"] = "1.0"; - std::shared_ptr minDist_ref = - PM::get().DataPointsFilterRegistrar.create(name, params); - params.clear(); - - name = "RandomSamplingDataPointsFilter"; - params["prob"] = "0.05"; - std::shared_ptr rand_ref = - PM::get().DataPointsFilterRegistrar.create(name, params); - params.clear(); - - // Prepare matching function - name = "KDTreeMatcher"; - params["knn"] = "1"; - params["epsilon"] = "3.16"; - std::shared_ptr kdtree = - PM::get().MatcherRegistrar.create(name, params); - params.clear(); - - // Prepare outlier filters - name = "TrimmedDistOutlierFilter"; - params["ratio"] = "0.75"; - std::shared_ptr trim = - PM::get().OutlierFilterRegistrar.create(name, params); - params.clear(); - - // Prepare error minimization - name = "PointToPointErrorMinimizer"; - std::shared_ptr pointToPoint = - PM::get().ErrorMinimizerRegistrar.create(name); - - // Prepare transformation checker filters - name = "CounterTransformationChecker"; - params["maxIterationCount"] = "150"; - std::shared_ptr maxIter = - PM::get().TransformationCheckerRegistrar.create(name, params); - params.clear(); - - name = "DifferentialTransformationChecker"; - params["minDiffRotErr"] = "0.001"; - params["minDiffTransErr"] = "0.01"; - params["smoothLength"] = "4"; - std::shared_ptr diff = - PM::get().TransformationCheckerRegistrar.create(name, params); - params.clear(); - - // Prepare inspector - std::shared_ptr nullInspect = - PM::get().InspectorRegistrar.create("NullInspector"); - - //name = "VTKFileInspector"; - // params["dumpDataLinks"] = "1"; - // params["dumpReading"] = "1"; - // params["dumpReference"] = "1"; - - //PM::Inspector* vtkInspect = - // PM::get().InspectorRegistrar.create(name, params); - params.clear(); - - // Prepare transformation - std::shared_ptr rigidTrans = - PM::get().TransformationRegistrar.create("RigidTransformation"); - - // Build ICP solution - icp.readingDataPointsFilters.push_back(minDist_read); - icp.readingDataPointsFilters.push_back(rand_read); - - icp.referenceDataPointsFilters.push_back(minDist_ref); - icp.referenceDataPointsFilters.push_back(rand_ref); - - icp.matcher = kdtree; - - icp.outlierFilters.push_back(trim); - - icp.errorMinimizer = pointToPoint; - - icp.transformationCheckers.push_back(maxIter); - icp.transformationCheckers.push_back(diff); - - // toggle to write vtk files per iteration - icp.inspector = nullInspect; - //icp.inspector = vtkInspect; - - icp.transformations.push_back(rigidTrans); - - // Compute the transformation to express data in ref - PM::TransformationParameters T = icp(data, ref); - - // Transform data to express it in ref - DP data_out(data); - icp.transformations.apply(data_out, T); - - // Safe files to see the results - ref.save("test_ref.vtk"); - data.save("test_data_in.vtk"); - data_out.save("test_data_out.vtk"); - cout << "Final transformation:" << endl << T << endl; - - return 0; -} - -void validateArgs(int argc, char *argv[], bool& isCSV ) -{ - if (argc != 3) - { - cerr << "Wrong number of arguments, usage " << argv[0] << " reference.csv reading.csv" << endl; - cerr << "Will create 3 vtk files for inspection: ./test_ref.vtk, ./test_data_in.vtk and ./test_data_out.vtk" << endl; - cerr << endl << "2D Example:" << endl; - cerr << " " << argv[0] << " ../../examples/data/2D_twoBoxes.csv ../../examples/data/2D_oneBox.csv" << endl; - cerr << endl << "3D Example:" << endl; - cerr << " " << argv[0] << " ../../examples/data/car_cloud400.csv ../../examples/data/car_cloud401.csv" << endl; - exit(1); - } -} diff --git a/thirdparty/libpointmatcher/examples/icp_simple.cpp b/thirdparty/libpointmatcher/examples/icp_simple.cpp deleted file mode 100644 index 895773d..0000000 --- a/thirdparty/libpointmatcher/examples/icp_simple.cpp +++ /dev/null @@ -1,95 +0,0 @@ -// kate: replace-tabs off; indent-width 4; indent-mode normal -// vim: ts=4:sw=4:noexpandtab -/* - -Copyright (c) 2010--2012, -François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland -You can contact the authors at and - - -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 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 ETH-ASL 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. - -*/ - -#include "pointmatcher/PointMatcher.h" -#include -#include -#include "boost/filesystem.hpp" - -using namespace std; - -void validateArgs(int argc, char *argv[], bool& isCSV); - -/** - * Code example for ICP taking 2 points clouds (2D or 3D) relatively close - * and computing the transformation between them. - */ -int main(int argc, char *argv[]) -{ - bool isCSV = true; - validateArgs(argc, argv, isCSV); - - typedef PointMatcher PM; - typedef PM::DataPoints DP; - - // Load point clouds - const DP ref(DP::load(argv[1])); - const DP data(DP::load(argv[2])); - - // Create the default ICP algorithm - PM::ICP icp; - - // See the implementation of setDefault() to create a custom ICP algorithm - icp.setDefault(); - - // Compute the transformation to express data in ref - PM::TransformationParameters T = icp(data, ref); - - // Transform data to express it in ref - DP data_out(data); - icp.transformations.apply(data_out, T); - - // Safe files to see the results - ref.save("test_ref.vtk"); - data.save("test_data_in.vtk"); - data_out.save("test_data_out.vtk"); - cout << "Final transformation:" << endl << T << endl; - - return 0; -} - -void validateArgs(int argc, char *argv[], bool& isCSV ) -{ - if (argc != 3) - { - cerr << "Wrong number of arguments, usage " << argv[0] << " reference.csv reading.csv" << endl; - cerr << "Will create 3 vtk files for inspection: ./test_ref.vtk, ./test_data_in.vtk and ./test_data_out.vtk" << endl; - cerr << endl << "2D Example:" << endl; - cerr << " " << argv[0] << " ../../examples/data/2D_twoBoxes.csv ../../examples/data/2D_oneBox.csv" << endl; - cerr << endl << "3D Example:" << endl; - cerr << " " << argv[0] << " ../../examples/data/car_cloud400.csv ../../examples/data/car_cloud401.csv" << endl; - exit(1); - } -} diff --git a/thirdparty/libpointmatcher/examples/icp_tutorial/cloud_0.vtk b/thirdparty/libpointmatcher/examples/icp_tutorial/cloud_0.vtk deleted file mode 100644 index 8faede1..0000000 --- a/thirdparty/libpointmatcher/examples/icp_tutorial/cloud_0.vtk +++ /dev/null @@ -1,73355 +0,0 @@ -# vtk DataFile Version 3.0 -File created by libpointmatcher -ASCII -DATASET POLYDATA -POINTS 36674 float - -0.233432 -0.399415 0.467391 - -0.178044 -0.405791 0.421382 - -0.172289 -0.405858 0.416602 - -0.165037 -0.410538 0.410569 - -0.163659 -0.411619 0.409421 - -0.15698 -0.405138 0.403892 - -0.468551 -1.23518 0.660457 - -0.288149 -2.25276 0.508009 - -0.273017 -2.25621 0.495435 - -0.186574 -2.16475 0.423892 - -0.169414 -2.22081 0.409497 - -0.161959 -2.22189 0.403303 - -0.120699 -2.28227 0.368885 - -0.0675904 -2.30092 0.324737 - 0.011613 -0.44359 0.263796 - 0.0131331 -0.44267 0.262536 - 0.0317497 -0.386935 0.247222 - 0.0427898 -0.371386 0.238095 - 0.0611654 -0.366216 0.22285 - 0.0726942 -0.368105 0.213272 - 0.0960658 -0.376241 0.193843 - 0.11374 -0.382486 0.179151 - 0.136571 -0.372394 0.160219 - 0.147308 -0.388375 0.151261 - 0.17285 -0.407699 0.130002 - 0.332105 -0.473126 -0.00241107 - 0.312516 -0.419893 0.0139943 - 0.386147 -0.420543 -0.0471495 - 0.393532 -0.40348 -0.0532369 - 0.413688 -0.39991 -0.0699653 - 0.415634 -0.398328 -0.0715765 - 0.440787 -0.401682 -0.0924724 - 0.450169 -0.407053 -0.100277 - 0.605951 -0.456491 -0.229764 - 0.610778 -0.455771 -0.23377 - 0.620232 -0.409757 -0.241501 - 0.620811 -0.319361 -0.241746 - 0.618037 -0.264128 -0.239299 - 0.610169 -0.216926 -0.232643 - 0.610896 -0.213614 -0.233238 - 0.613532 -0.193168 -0.235374 - 0.614926 -0.190079 -0.236523 - 0.616065 0.013925 -0.236939 - 0.614598 0.040592 -0.235651 - 0.613723 0.0706443 -0.234847 - 0.615319 0.0978549 -0.236102 - 0.616515 0.101453 -0.237085 - 0.621067 0.285415 -0.240387 - 0.625769 0.3032 -0.244245 - 0.618 0.307008 -0.237784 - 0.367742 0.261196 -0.0300937 - 0.622834 0.493802 -0.241312 - 0.615721 0.531222 -0.235309 - 0.617885 0.563483 -0.237021 - 0.619126 0.612489 -0.237925 - 0.620809 0.683058 -0.239139 - 0.621517 0.72075 -0.239628 - 0.615889 0.732867 -0.234924 - 0.617906 0.852943 -0.236287 - 0.61771 0.991289 -0.235764 - 0.619937 1.08996 -0.237357 - 0.626186 1.20998 -0.242234 - 0.623364 1.21589 -0.239876 - 0.627093 1.23533 -0.242921 - 0.602904 1.26972 -0.222746 - 0.552013 1.20506 -0.180655 - 0.531022 1.16874 -0.163319 - 0.37191 0.833646 -0.0320667 - 0.308846 0.73411 0.0200412 - 0.256352 0.631525 0.0633647 - 0.213443 0.55683 0.0988014 - 0.225282 0.637161 0.089179 - 0.369404 1.27201 -0.028846 - 0.305076 1.2784 0.024587 - 0.268212 1.27754 0.0551961 - 0.251029 1.28278 0.0694782 - 0.224223 1.28403 0.0917404 - 0.219912 1.28513 0.0953229 - 0.129828 1.16555 0.169816 - 0.0761737 1.20239 0.214465 - -0.0722392 1.23609 0.337792 - -0.0898247 1.15988 0.352196 - -0.171813 1.16941 0.420302 - -0.264557 1.18641 0.497359 - -0.304861 1.2204 0.530915 - -0.452164 1.27853 0.653384 - -0.498188 1.23271 0.691482 - -0.499698 1.22361 0.692712 - -0.500138 0.926347 0.692305 - -0.49681 0.912131 0.689505 - -0.496172 0.90276 0.68895 - -0.492998 0.873219 0.686238 - -0.497787 0.835072 0.690115 - -0.495156 0.760483 0.687736 - -0.286001 -0.409697 0.505522 - -0.272393 -0.405763 0.494472 - -0.257824 -0.406765 0.482628 - -0.233526 -0.409896 0.462872 - -0.224095 -0.409384 0.455207 - -0.204584 -0.402144 0.439368 - -0.19776 -0.401126 0.433824 - -0.393156 -1.04854 0.590969 - -0.526218 -1.67491 0.697505 - -0.521534 -1.81233 0.693343 - -0.51276 -2.16529 0.685302 - -0.302108 -2.16872 0.51408 - -0.282176 -2.24466 0.497684 - -0.197664 -2.1794 0.429163 - -0.106274 -2.27485 0.354637 - 0.0204383 -0.42494 0.256416 - 0.0393873 -0.35258 0.241201 - 0.0439015 -0.372287 0.237482 - 0.0463153 -0.370077 0.235525 - 0.0571571 -0.363795 0.22673 - 0.0711517 -0.365402 0.215351 - 0.0726369 -0.367118 0.214139 - 0.092165 -0.375444 0.198246 - 0.112866 -0.382978 0.181401 - 0.118272 -0.381921 0.17701 - 0.153909 -0.397148 0.148006 - 0.157935 -0.394956 0.144739 - 0.159889 -0.396044 0.143148 - 0.164773 -0.400916 0.139166 - 0.172804 -0.404981 0.132628 - 0.185311 -0.393683 0.122492 - 0.191198 -0.387358 0.117724 - 0.210085 -0.37533 0.102404 - 0.245738 -0.431317 0.0732816 - 0.560357 -1.01124 -0.183928 - 0.544904 -0.972805 -0.17127 - 0.529704 -0.918248 -0.158774 - 0.448584 -0.742338 -0.0923891 - 0.305034 -0.443488 0.0250556 - 0.331114 -0.455768 0.00382641 - 0.382345 -0.423916 -0.0377311 - 0.380922 -0.418533 -0.0365599 - 0.412008 -0.405835 -0.0617937 - 0.408095 -0.394599 -0.058584 - 0.417319 -0.400532 -0.0660969 - 0.463785 -0.409276 -0.103885 - 0.47298 -0.406468 -0.111352 - 0.531737 -0.426646 -0.15916 - 0.626238 -0.347727 -0.235765 - 0.630898 -0.267702 -0.239346 - 0.628282 -0.258991 -0.237198 - 0.628722 -0.192973 -0.237386 - 0.632857 -0.165553 -0.240675 - 0.630695 -0.154336 -0.238889 - 0.631552 -0.119458 -0.239496 - 0.631955 -0.116054 -0.239815 - 0.628117 -0.108409 -0.236675 - 0.631821 -0.0952223 -0.239652 - 0.626578 -0.0841363 -0.235362 - 0.63104 -0.0539136 -0.23891 - 0.631778 0.00056671 -0.23937 - 0.63176 0.00737337 -0.239338 - 0.628749 0.068458 -0.236733 - 0.630574 0.109955 -0.23811 - 0.628435 0.241355 -0.236033 - 0.632464 0.257987 -0.239264 - 0.63024 0.287495 -0.237381 - 0.63215 0.311834 -0.238871 - 0.631755 0.368268 -0.238404 - 0.630507 0.371665 -0.237381 - 0.629567 0.387863 -0.236575 - 0.3539 0.231661 -0.0129213 - 0.35571 0.237777 -0.014377 - 0.63337 0.522803 -0.239318 - 0.638181 0.632754 -0.242945 - 0.632474 0.672908 -0.238203 - 0.639822 1.07717 -0.243134 - 0.63937 1.08627 -0.242743 - 0.63655 1.15366 -0.240277 - 0.635684 1.16288 -0.239549 - 0.557564 1.196 -0.17597 - 0.345473 0.764029 -0.0047003 - 0.336316 0.74991 0.0027055 - 0.315511 0.737869 0.0195847 - 0.279532 0.682589 0.0486854 - 0.211424 0.581411 0.103781 - 0.309879 1.01485 0.0248764 - 0.331863 1.28364 0.00770059 - 0.327067 1.28342 0.0115979 - 0.292094 1.27334 0.0399977 - 0.230213 1.28487 0.0903223 - 0.211792 1.28233 0.105288 - 0.194016 1.28331 0.119739 - 0.130702 1.16953 0.170906 - 0.110808 1.22938 0.187229 - 0.0990324 1.17443 0.196659 - 0.0864294 1.16256 0.206872 - -0.0558441 1.16601 0.322517 - -0.0745185 1.24902 0.337909 - -0.084287 1.1711 0.345648 - -0.0873769 1.16153 0.348135 - -0.104532 1.17162 0.362104 - -0.167988 1.20991 0.413778 - -0.170638 1.2 0.415907 - -0.204899 1.20004 0.443753 - -0.216318 1.17144 0.452961 - -0.260876 1.17757 0.489192 - -0.393475 1.27726 0.597222 - -0.399633 1.28039 0.602236 - -0.497916 1.01224 0.681427 - -0.500429 0.961508 0.683339 - -0.500983 0.953647 0.683769 - -0.495608 0.846291 0.679123 - -0.498193 0.806151 0.681121 - -0.235501 -0.405345 0.459907 - -0.226102 -0.408598 0.452424 - -0.222294 -0.406055 0.449402 - -0.155278 -0.409234 0.3961 - -0.154902 -0.425514 0.395759 - -0.401689 -1.07138 0.590365 - -0.212988 -0.63251 0.441423 - -0.52525 -1.78505 0.686803 - -0.517304 -1.95648 0.680046 - -0.45142 -2.1573 0.627139 - -0.282932 -2.2289 0.492967 - -0.148484 -2.19705 0.386129 - 0.00920749 -0.442504 0.265209 - 0.0171684 -0.423862 0.258925 - 0.0323241 -0.376903 0.246993 - 0.0392331 -0.354578 0.241556 - 0.0661977 -0.366361 0.220082 - 0.0673371 -0.365142 0.219179 - 0.136531 -0.373015 0.164133 - 0.151238 -0.391386 0.15239 - 0.178191 -0.394482 0.130948 - 0.208192 -0.383685 0.107118 - 0.207051 -0.377551 0.10804 - 0.550014 -0.930386 -0.166112 - 0.462919 -0.734302 -0.0963487 - 0.453051 -0.71124 -0.0884426 - 0.44447 -0.690672 -0.0815662 - 0.316216 -0.466164 0.0210011 - 0.408573 -0.57741 -0.0527298 - 0.320949 -0.425881 0.0173403 - 0.356813 -0.422542 -0.0111718 - 0.377028 -0.41442 -0.0272272 - 0.404795 -0.405889 -0.0492867 - 0.461512 -0.403991 -0.094386 - 0.466065 -0.404475 -0.0980076 - 0.513502 -0.408025 -0.135741 - 0.646365 -0.425411 -0.241444 - 0.650683 -0.414993 -0.244852 - 0.642205 -0.387756 -0.23804 - 0.645567 -0.30332 -0.240497 - 0.644816 -0.267827 -0.23981 - 0.643392 -0.24437 -0.238617 - 0.645023 -0.200286 -0.239802 - 0.645186 -0.163967 -0.239838 - 0.636344 -0.0986257 -0.23264 - 0.646623 -0.0583401 -0.240711 - 0.642501 -0.0269286 -0.237353 - 0.645183 -0.00977919 -0.239442 - 0.642876 0.007449 -0.237564 - 0.646241 0.0351657 -0.240169 - 0.644423 0.0419716 -0.238705 - 0.638481 0.0655727 -0.23392 - 0.636351 0.092833 -0.232156 - 0.648553 0.105259 -0.241828 - 0.64441 0.139839 -0.238445 - 0.635222 0.158863 -0.23109 - 0.640248 0.167315 -0.235065 - 0.645463 0.231153 -0.239049 - 0.642136 0.248653 -0.236359 - 0.641633 0.263616 -0.23592 - 0.641932 0.286842 -0.236099 - 0.355673 0.23118 -0.00859496 - 0.351353 0.232885 -0.0051553 - 0.353834 0.23948 -0.00711116 - 0.636419 0.478129 -0.231226 - 0.645389 0.499503 -0.238305 - 0.644172 0.513078 -0.237302 - 0.645875 0.565017 -0.238524 - 0.645169 0.574839 -0.237937 - 0.646143 0.591718 -0.238668 - 0.645011 0.606899 -0.23773 - 0.647823 0.715207 -0.239689 - 0.593029 0.818384 -0.19585 - 0.649771 0.974762 -0.240575 - 0.649399 0.982888 -0.240258 - 0.650239 1.02926 -0.240808 - 0.656599 1.25121 -0.245299 - 0.32588 0.734721 0.0163849 - 0.323011 0.735491 0.0186683 - 0.251817 0.617403 0.0749827 - 0.228298 0.600157 0.0936425 - 0.219778 0.60363 0.100427 - 0.229392 0.657992 0.0929198 - 0.282091 1.2835 0.0526098 - 0.276187 1.27714 0.0572886 - 0.267458 1.27986 0.0642373 - 0.217818 1.28424 0.103725 - 0.177056 1.28289 0.136137 - 0.148511 1.17993 0.158574 - 0.104791 1.19694 0.193386 - 0.0944429 1.16086 0.201523 - 0.0349619 1.17496 0.248861 - 0.0184742 1.24594 0.262154 --0.00880874 1.16207 0.283636 - -0.0240154 1.24324 0.295937 - -0.0842942 1.1572 0.343653 - -0.0924998 1.15889 0.350183 - -0.108719 1.19537 0.363174 - -0.127033 1.20794 0.377771 - -0.132771 1.157 0.382204 - -0.193053 1.17053 0.430177 - -0.276308 1.15762 0.496353 - -0.355023 1.27118 0.55924 - -0.390684 1.27225 0.587602 - -0.499803 1.25213 0.674327 - -0.496214 1.16898 0.671261 - -0.502207 1.1472 0.675971 - -0.494544 0.933304 0.669331 - -0.49676 0.879094 0.670954 - -0.488892 0.750608 0.664369 - -0.491195 0.727892 0.666142 - -0.489364 0.682173 0.664569 - -0.29281 -0.400173 0.50008 - -0.291431 -0.401928 0.499002 - -0.283673 -0.398991 0.492972 - -0.279272 -0.400233 0.489543 - -0.254935 -0.405499 0.47059 - -0.24611 -0.403264 0.463729 - -0.244211 -0.403997 0.462248 - -0.238391 -0.402346 0.457723 - -0.236 -0.402256 0.455863 - -0.211059 -0.405361 0.436445 - -0.173114 -0.403005 0.406922 - -0.166888 -0.401985 0.402079 - -0.154996 -0.400405 0.392828 - -0.155609 -0.422877 0.393248 - -0.214616 -0.630708 0.438643 - -0.489873 -1.44835 0.650784 - -0.486492 -1.45575 0.648134 - -0.525422 -1.58491 0.678104 - -0.523432 -1.59802 0.676521 - -0.526166 -1.94403 0.677772 - -0.494195 -2.18374 0.652283 - -0.468548 -2.17867 0.632338 - -0.445386 -2.18374 0.614299 - -0.437865 -2.18631 0.608439 - -0.257895 -2.19632 0.468356 - 0.0255273 -0.408999 0.252317 - 0.0386323 -0.34459 0.242282 - 0.0433317 -0.368295 0.238564 - 0.0608535 -0.364231 0.224939 - 0.0621076 -0.364031 0.223963 - 0.105411 -0.377603 0.190229 - 0.117838 -0.382436 0.180545 - 0.122607 -0.37843 0.176844 - 0.178014 -0.387365 0.133702 - 0.179347 -0.386517 0.132667 - 0.203255 -0.38597 0.114062 - 0.205909 -0.383988 0.112002 - 0.209452 -0.380107 0.109255 - 0.61377 -1.10539 -0.207236 - 0.577633 -0.990075 -0.178821 - 0.570512 -0.968293 -0.173225 - 0.571144 -0.951708 -0.173674 - 0.483778 -0.777594 -0.105242 - 0.319013 -0.459022 0.0237911 - 0.386264 -0.418533 -0.0284436 - 0.383863 -0.408508 -0.0265498 - 0.388799 -0.410514 -0.0303961 - 0.401789 -0.406857 -0.040496 - 0.406998 -0.405247 -0.0445459 - 0.500304 -0.413039 -0.117179 - 0.651739 -0.452964 -0.235131 - 0.656116 -0.389131 -0.238376 - 0.653011 -0.324681 -0.235796 - 0.658162 -0.319208 -0.239792 - 0.659512 -0.268173 -0.240712 - 0.655806 -0.24355 -0.237766 - 0.65848 -0.1662 -0.239651 - 0.659051 -0.162699 -0.240086 - 0.652163 -0.150134 -0.234694 - 0.657733 -0.133436 -0.238986 - 0.653234 -0.104104 -0.235411 - 0.658036 -0.0871644 -0.239105 - 0.660191 -0.0803677 -0.240765 - 0.650869 -0.0374711 -0.233402 - 0.654684 0.0144885 -0.236239 - 0.65055 0.0247616 -0.232995 - 0.650364 0.0316687 -0.232833 - 0.654418 0.0492953 -0.235943 - 0.652654 0.0665751 -0.234527 - 0.654125 0.126664 -0.23552 - 0.656803 0.130782 -0.237594 - 0.656188 0.141409 -0.237088 - 0.655586 0.214364 -0.236434 - 0.660782 0.543 -0.239645 - 0.658965 0.57782 -0.238143 - 0.657517 0.587159 -0.236993 - 0.658654 0.638036 -0.237748 - 0.661011 0.67551 -0.239488 - 0.667291 0.731948 -0.244232 - 0.662817 0.73968 -0.24073 - 0.65964 0.796118 -0.238115 - 0.662771 0.970093 -0.240111 - 0.667004 1.23829 -0.242726 - 0.610604 1.25679 -0.198786 - 0.340048 0.740235 0.0104595 - 0.251532 0.61956 0.07904 - 0.240615 0.610444 0.0875129 - 0.225518 0.609943 0.0992602 - 0.235727 0.729393 0.0916182 - 0.233215 0.730541 0.0935762 - 0.35586 1.28423 -0.00046718 - 0.259548 1.27859 0.0744722 - 0.246829 1.28526 0.0843873 - 0.2239 1.28611 0.102233 - 0.191547 1.28324 0.127404 - 0.182343 1.28205 0.134564 - 0.121159 1.24433 0.182083 - 0.034619 1.16996 0.249243 - 0.0266079 1.241 0.255658 - 0.0141463 1.20388 0.265262 - 0.00640213 1.1707 0.271204 - -0.0339824 1.17043 0.302632 - -0.0712039 1.23068 0.331752 - -0.16028 1.21802 0.401042 - -0.275946 1.16215 0.490915 - -0.307667 1.22981 0.515773 - -0.454115 1.27671 0.629862 - -0.495197 1.26972 0.661816 - -0.500274 1.21641 0.665631 - -0.496679 1.14787 0.66266 - -0.49963 0.916939 0.664372 - -0.494314 0.867161 0.660108 - -0.497299 0.864271 0.662423 - -0.497407 0.841376 0.66245 - -0.495029 0.766174 0.660409 - -0.202557 -0.405261 0.426024 - -0.194712 -0.402374 0.420057 - -0.187339 -0.403794 0.414439 - -0.173666 -0.404098 0.404026 - -0.167804 -0.403901 0.399562 - -0.533848 -1.71553 0.675015 - -0.523387 -1.7939 0.666852 - -0.520004 -1.98703 0.66379 - -0.369243 -2.18512 0.548485 - -0.27748 -2.20594 0.478553 - -0.203975 -2.17742 0.422649 - -0.188852 -2.17982 0.411127 - -0.163419 -2.24182 0.391603 - 0.0146516 -0.432807 0.260546 - 0.0293776 -0.401961 0.24941 - 0.0306139 -0.389935 0.248498 - 0.0593476 -0.362438 0.226686 - 0.0826338 -0.380155 0.208909 - 0.0916744 -0.376789 0.202033 - 0.10828 -0.382944 0.189371 - 0.131172 -0.381314 0.171943 - 0.141382 -0.390485 0.164145 - 0.205812 -0.381411 0.115103 - 0.214012 -0.383336 0.108854 - 0.520449 -0.833651 -0.125636 - 0.349723 -0.473181 0.00528145 - 0.334359 -0.427563 0.0170954 - 0.332286 -0.413665 0.0187091 - 0.383295 -0.423115 -0.0201585 - 0.403484 -0.402189 -0.0354807 - 0.450122 -0.405763 -0.071005 - 0.466603 -0.406417 -0.0835575 - 0.474576 -0.406226 -0.0896287 - 0.512805 -0.405227 -0.118738 - 0.674334 -0.428703 -0.241805 - 0.667323 -0.39307 -0.236376 - 0.673596 -0.349545 -0.241044 - 0.671457 -0.319365 -0.239339 - 0.666701 -0.292867 -0.235651 - 0.668719 -0.285818 -0.23717 - 0.670727 -0.20544 -0.238497 - 0.662396 -0.18061 -0.232091 - 0.657679 -0.15032 -0.228422 - 0.6681 -0.145504 -0.236346 - 0.66722 -0.134422 -0.235647 - 0.667432 -0.120026 -0.235773 - 0.67375 -0.1067 -0.240551 - 0.670962 -0.102641 -0.238417 - 0.666817 -0.0664059 -0.23517 - 0.665573 -0.0239988 -0.234116 - 0.667901 0.0287854 -0.235756 - 0.672892 0.0610636 -0.239476 - 0.664832 0.0744255 -0.233304 - 0.664572 0.077931 -0.233097 - 0.665781 0.0922791 -0.233982 - 0.662878 0.113173 -0.231719 - 0.669271 0.139624 -0.23652 - 0.668196 0.187071 -0.235583 - 0.662565 0.207646 -0.231243 - 0.668036 0.224532 -0.235367 - 0.663517 0.276664 -0.231794 - 0.673299 0.384502 -0.238972 - 0.357834 0.238983 0.00089449 - 0.680844 0.530211 -0.244352 - 0.671644 0.563745 -0.237262 - 0.668054 0.592486 -0.234455 - 0.673285 0.613839 -0.238385 - 0.67409 0.637185 -0.23894 - 0.680432 0.69095 -0.243634 - 0.593474 0.765513 -0.177226 - 0.570473 0.754038 -0.15974 - 0.580886 0.817181 -0.167511 - 0.652545 1.2727 -0.220935 - 0.385982 0.800184 -0.01913 - 0.331555 0.738271 0.0221615 - 0.26415 0.811751 0.0736769 - 0.360109 1.2729 0.00176126 - 0.315423 1.28899 0.035831 - 0.187302 1.27821 0.133371 - 0.168866 1.27559 0.147404 - 0.0703931 1.27083 0.222381 - 0.0464391 1.16674 0.24036 - 0.0383935 1.17191 0.2465 - -0.0215885 1.25151 0.292378 - -0.125355 1.16945 0.371192 - -0.153506 1.18958 0.39268 - -0.21322 1.20683 0.438197 - -0.274979 1.16477 0.485122 - -0.358212 1.27517 0.548783 - -0.368207 1.27462 0.556393 - -0.383834 1.27543 0.568295 - -0.43023 1.27331 0.603622 - -0.447488 1.27655 0.616772 - -0.461786 1.27134 0.627647 - -0.49705 1.1739 0.654257 - -0.495515 1.05906 0.652799 - -0.498788 0.93294 0.654974 - -0.499928 0.901123 0.655762 - -0.495676 0.780887 0.652222 - -0.499019 0.772091 0.654746 - -0.490629 0.70805 0.648196 - -0.492546 0.704475 0.649646 - -0.276731 -0.407087 0.477511 - -0.259406 -0.411614 0.464593 - -0.217945 -0.405653 0.433721 - -0.191599 -0.407965 0.414089 - -0.170106 -0.404759 0.398085 - -0.168689 -0.405814 0.397027 - -0.151281 -0.408892 0.384051 - -0.155519 -0.427611 0.387162 - -0.400294 -1.06267 0.567925 - -0.214068 -0.631525 0.43027 - -0.487393 -1.45031 0.631843 - -0.527804 -1.58334 0.661616 - -0.517194 -1.98809 0.652702 - -0.449783 -2.16637 0.602039 - -0.402632 -2.17327 0.566897 - -0.254499 -2.19094 0.4565 - -0.146741 -2.20794 0.376182 - -0.119184 -2.26412 0.355514 - 0.0233935 -0.412996 0.253916 - 0.0428345 -0.366298 0.23955 - 0.0570822 -0.366777 0.228935 - 0.067215 -0.364153 0.221393 - 0.080542 -0.374569 0.211439 - 0.0838468 -0.369702 0.208989 - 0.0984305 -0.382074 0.198094 - 0.10537 -0.388153 0.192909 - 0.127912 -0.383977 0.176127 - 0.130602 -0.372247 0.174152 - 0.13512 -0.377656 0.170772 - 0.136441 -0.377051 0.16979 - 0.163629 -0.397877 0.149484 - 0.167712 -0.400003 0.146437 - 0.174265 -0.381851 0.141601 - 0.190265 -0.391899 0.129657 - 0.199616 -0.388974 0.122698 - 0.200976 -0.388018 0.121687 - 0.341751 -0.505615 0.016522 - 0.34104 -0.499959 0.0170663 - 0.342592 -0.424628 0.0160978 - 0.344077 -0.422893 0.014996 - 0.38436 -0.417738 -0.0150005 - 0.384644 -0.41442 -0.0152036 - 0.411055 -0.407353 -0.034861 - 0.431989 -0.407106 -0.050456 - 0.480423 -0.408561 -0.0865406 - 0.491904 -0.407389 -0.0950904 - 0.527318 -0.40257 -0.12146 - 0.619688 -0.454034 -0.1904 - 0.691332 -0.455372 -0.243776 - 0.694653 -0.443512 -0.24622 - 0.690761 -0.395466 -0.2432 - 0.685555 -0.349105 -0.239207 - 0.68253 -0.261892 -0.236736 - 0.678995 -0.187691 -0.233917 - 0.683739 -0.118502 -0.237279 - 0.675209 -0.0917846 -0.230858 - 0.682297 0.0292129 -0.235836 - 0.682193 0.0327883 -0.23575 - 0.680474 0.0362743 -0.23446 - 0.679797 0.166666 -0.233631 - 0.679997 0.17043 -0.23377 - 0.679398 0.173991 -0.233316 - 0.675134 0.221535 -0.23002 - 0.68972 0.281861 -0.240736 - 0.688732 0.285473 -0.239991 - 0.686717 0.29268 -0.238472 - 0.684128 0.324217 -0.236465 - 0.688136 0.36428 -0.239351 - 0.687919 0.377141 -0.239156 - 0.688477 0.40839 -0.239494 - 0.408638 0.259921 -0.0313964 - 0.369745 0.235996 -0.00248253 - 0.3595 0.248279 0.00517978 - 0.368043 0.259697 -0.00115564 - 0.683044 0.513027 -0.235186 - 0.684787 0.544806 -0.236405 - 0.687652 0.718327 -0.238107 - 0.687163 0.756583 -0.237647 - 0.689089 0.813654 -0.238939 - 0.559009 0.745793 -0.142205 - 0.686831 1.05574 -0.236654 - 0.692203 1.1656 -0.240382 - 0.625984 1.246 -0.190851 - 0.343625 0.738473 0.0182287 - 0.31123 0.73883 0.0423628 - 0.22921 0.606069 0.103133 - 0.225543 0.617684 0.105894 - 0.239154 1.27882 0.0974027 - 0.234679 1.27997 0.10074 - 0.184592 1.286 0.138067 - 0.179973 1.28586 0.141508 - 0.141427 1.17428 0.169945 - 0.0766576 1.20938 0.218283 - 0.0592673 1.1943 0.2312 - 0.0339955 1.16996 0.249966 - -0.0333106 1.20569 0.300195 - -0.0619402 1.1909 0.321486 - -0.069996 1.24117 0.327613 - -0.0974994 1.16781 0.347919 - -0.130905 1.16762 0.372804 - -0.147227 1.16401 0.384954 - -0.156216 1.19547 0.391729 - -0.17178 1.211 0.403362 - -0.181266 1.16453 0.410313 - -0.212617 1.21493 0.433794 - -0.256152 1.18676 0.466155 - -0.264558 1.16581 0.472365 - -0.272222 1.1607 0.478061 - -0.280337 1.1574 0.484099 - -0.340235 1.27119 0.529004 - -0.388093 1.27728 0.564671 - -0.424036 1.27462 0.591441 - -0.488484 1.27203 0.639446 - -0.496719 1.17501 0.645338 - -0.503879 1.07725 0.650428 - -0.501025 0.964151 0.64802 - -0.503193 0.950164 0.649601 - -0.495363 0.901996 0.643647 - -0.498155 0.777825 0.645418 - -0.494681 0.732755 0.642717 - -0.262023 -0.400948 0.46188 - -0.257234 -0.404792 0.458382 - -0.223088 -0.406727 0.433498 - -0.212564 -0.403912 0.425837 - -0.199307 -0.406882 0.416171 - -0.154545 -0.412417 0.383544 - -0.219039 -0.617689 0.430027 - -0.207239 -0.62899 0.421401 - -0.530349 -1.71879 0.654119 - -0.516027 -1.96725 0.643069 - -0.48338 -2.18732 0.618738 - -0.428424 -2.16228 0.57876 - -0.258137 -2.19983 0.454598 - -0.190578 -2.15699 0.405481 - -0.0968661 -2.27023 0.336923 - 0.0122348 -0.433746 0.261978 - 0.0184428 -0.427939 0.257469 - 0.0443345 -0.374178 0.238738 - 0.074538 -0.369811 0.216743 - 0.0778439 -0.374178 0.214323 - 0.115649 -0.386817 0.186747 - 0.120996 -0.378538 0.182872 - 0.132692 -0.383202 0.17434 - 0.154688 -0.398571 0.158275 - 0.156093 -0.397863 0.157253 - 0.171038 -0.388673 0.146387 - 0.180657 -0.387365 0.139382 - 0.182023 -0.386517 0.138389 - 0.198272 -0.39174 0.126537 - 0.216317 -0.383336 0.11341 - 0.720415 -1.28898 -0.25611 - 0.358356 -0.42375 0.00982276 - 0.386444 -0.406456 -0.0105991 - 0.396382 -0.403184 -0.017832 - 0.413119 -0.406708 -0.0300349 - 0.437061 -0.402039 -0.0474674 - 0.639879 -0.452451 -0.195363 - 0.701543 -0.449517 -0.240284 - 0.699524 -0.375611 -0.238629 - 0.704777 -0.348012 -0.242389 - 0.695981 -0.225866 -0.235678 - 0.69526 -0.164443 -0.235 - 0.701471 -0.150821 -0.239491 - 0.694096 -0.0536827 -0.233878 - 0.693412 -0.0319059 -0.233326 - 0.698797 0.00060594 -0.237169 - 0.693088 0.0114259 -0.232983 - 0.694936 0.0804418 -0.234158 - 0.689019 0.101505 -0.229795 - 0.691027 0.127469 -0.231194 - 0.694076 0.169067 -0.233313 - 0.696712 0.270684 -0.234982 - 0.697504 0.30761 -0.235467 - 0.700333 0.39026 -0.237324 - 0.696159 0.401161 -0.234256 - 0.698313 0.425085 -0.235766 - 0.359712 0.234694 0.0104637 - 0.357753 0.242902 0.0119118 - 0.700949 0.642241 -0.237149 - 0.705884 0.676608 -0.24066 - 0.704886 0.718899 -0.239828 - 0.706356 0.739737 -0.240847 - 0.58165 0.758482 -0.149941 - 0.564975 0.748779 -0.137816 - 0.545873 0.741591 -0.123916 - 0.704413 1.1155 -0.238502 - 0.374902 0.757382 0.00069037 - 0.35016 0.733234 0.0186569 - 0.352727 1.22825 0.0180117 - 0.347853 1.28479 0.0217031 - 0.331477 1.27838 0.0336181 - 0.312973 1.28285 0.0471112 - 0.308661 1.28535 0.0502589 - 0.299382 1.28738 0.0570247 - 0.136852 1.16497 0.175139 - 0.118283 1.24982 0.188878 - 0.00499912 1.1577 0.271188 - 0.00091646 1.15758 0.274162 - -0.0485205 1.16234 0.310193 - -0.0798015 1.23908 0.333174 - -0.0794511 1.18482 0.332784 - -0.14658 1.17676 0.381674 - -0.171097 1.1688 0.399517 - -0.174883 1.16577 0.402268 - -0.18667 1.15949 0.41084 - -0.262004 1.18138 0.465782 - -0.271331 1.16422 0.472535 - -0.400417 1.2718 0.566852 - -0.497391 1.26921 0.6375 - -0.498131 1.244 0.637976 - -0.498379 1.13339 0.637883 - -0.497872 1.05595 0.637323 - -0.498066 0.959553 0.637225 - -0.495355 0.802031 0.63486 - -0.49286 0.756659 0.63293 - -0.491858 0.741947 0.632163 - -0.494955 0.695669 0.634306 - -0.485795 0.654139 0.627529 - -0.272448 -0.408357 0.464787 - -0.243757 -0.402922 0.444349 - -0.185725 -0.408673 0.402967 - -0.165763 -0.408222 0.388739 - -0.152577 -0.417052 0.379317 - -0.417792 -1.09996 0.566696 - -0.529309 -1.72362 0.644659 - -0.517474 -2.10628 0.635282 - -0.442082 -2.17046 0.581382 - -0.433755 -2.17002 0.575447 - -0.407877 -2.16356 0.557016 - -0.392492 -2.16808 0.546038 - -0.333515 -2.20218 0.503913 - -0.167036 -2.22193 0.385191 - -0.15799 -2.20899 0.378775 - -0.114625 -2.27584 0.347698 - 0.0134928 -0.427809 0.26091 - 0.0166248 -0.422905 0.258689 - 0.0181569 -0.42094 0.257602 - 0.0241467 -0.408999 0.253361 - 0.0340154 -0.34578 0.246482 - 0.0967652 -0.378579 0.201671 - 0.145754 -0.383878 0.166736 - 0.146224 -0.380431 0.16641 - 0.165072 -0.397877 0.152932 - 0.173853 -0.394109 0.146681 - 0.17665 -0.392488 0.144691 - 0.202757 -0.383584 0.126103 - 0.205888 -0.382516 0.123874 - 0.241397 -0.422669 0.0984627 - 0.247269 -0.42993 0.0942594 - 0.252282 -0.427138 0.0906924 - 0.583861 -0.879706 -0.146782 - 0.384963 -0.405707 -0.00383541 - 0.411961 -0.402834 -0.0230737 - 0.479362 -0.405753 -0.0711264 - 0.520327 -0.410563 -0.10034 - 0.53429 -0.406389 -0.110283 - 0.657678 -0.457741 -0.198365 - 0.71429 -0.354771 -0.238468 - 0.715905 -0.333998 -0.239568 - 0.712567 -0.319664 -0.237154 - 0.710374 -0.273176 -0.235476 - 0.713058 -0.241946 -0.237312 - 0.710052 -0.232954 -0.235148 - 0.713276 -0.218217 -0.237409 - 0.705275 -0.204039 -0.231671 - 0.714544 -0.195091 -0.238256 - 0.707242 -0.124733 -0.232878 - 0.7101 -0.1215 -0.234908 - 0.70621 -0.0322913 -0.231916 - 0.710822 0.00429074 -0.235114 - 0.708331 0.0116055 -0.23332 - 0.706533 0.0225449 -0.232012 - 0.706311 0.140733 -0.231563 - 0.71315 0.251115 -0.236167 - 0.715123 0.280271 -0.237502 - 0.711949 0.376437 -0.235003 - 0.359615 0.235505 0.0158087 - 0.697585 0.590013 -0.224239 - 0.691079 0.606123 -0.219562 - 0.71519 0.724749 -0.236458 - 0.718528 0.859941 -0.238506 - 0.71562 0.902338 -0.236328 - 0.716533 1.11741 -0.236451 - 0.717841 1.14 -0.237327 - 0.681376 1.26567 -0.211026 - 0.350789 0.737617 0.0233335 - 0.329784 0.735351 0.0383013 - 0.224831 0.60841 0.112804 - 0.259134 0.749872 0.088699 - 0.381706 1.23706 0.00252157 - 0.328163 1.27713 0.0407875 - 0.299184 1.27868 0.0614485 - 0.189813 1.27723 0.139409 - 0.141447 1.16436 0.173609 - 0.125742 1.17661 0.184834 - 0.0963794 1.17881 0.205771 - 0.0796177 1.18015 0.217723 - 0.0206559 1.24798 0.25992 - -0.0374247 1.17043 0.301131 - -0.049516 1.16333 0.309733 - -0.0796174 1.22317 0.331337 - -0.079823 1.17587 0.331368 - -0.0957029 1.1655 0.342662 - -0.100372 1.16979 0.346001 - -0.257946 1.19213 0.458381 - -0.337589 1.27514 0.515358 - -0.348289 1.27684 0.522989 - -0.358477 1.27653 0.530251 - -0.368978 1.27704 0.537738 - -0.449334 1.27807 0.595021 - -0.475825 1.27494 0.613898 - -0.496383 1.09747 0.628116 - -0.491121 1.03379 0.624209 - -0.496029 1.01356 0.627658 - -0.496987 0.977151 0.628251 - -0.495331 0.955724 0.627018 - -0.498203 0.916982 0.62897 - -0.491989 0.79034 0.62423 - -0.490096 0.720553 0.622709 - -0.301049 -0.41031 0.480018 - -0.274623 -0.400721 0.461623 - -0.247261 -0.408241 0.442534 - -0.22311 -0.403248 0.425713 - -0.216781 -0.396514 0.421319 - -0.214411 -0.407268 0.419641 - -0.199087 -0.406785 0.408962 - -0.187459 -0.400521 0.400872 - -0.153119 -0.41439 0.376904 - -0.524714 -1.61265 0.632975 - -0.528134 -1.87154 0.634728 - 0.0129048 -0.433806 0.261143 - 0.0161031 -0.428904 0.258926 - 0.0404248 -0.35641 0.242151 - 0.0464898 -0.371953 0.237886 - 0.0478212 -0.371828 0.236958 - 0.07752 -0.371224 0.21626 - 0.104581 -0.38762 0.19736 - 0.108738 -0.386294 0.194466 - 0.11012 -0.385838 0.193503 - 0.12958 -0.374331 0.179968 - 0.147084 -0.381361 0.167751 - 0.15118 -0.389058 0.164878 - 0.160852 -0.398269 0.158114 - 0.17458 -0.39854 0.148546 - 0.17673 -0.395111 0.147055 - 0.18954 -0.39635 0.138124 - 0.19761 -0.39004 0.132515 - 0.200185 -0.383741 0.130735 - 0.763972 -1.28869 -0.264415 - 0.592103 -0.910917 -0.143706 - 0.597571 -0.879141 -0.14744 - 0.494263 -0.653682 -0.0748869 - 0.371641 -0.446522 0.0110822 - 0.381733 -0.417356 0.00411969 - 0.387663 -0.409672 5.45e-06 - 0.427217 -0.40141 -0.027543 - 0.429927 -0.400517 -0.0294296 - 0.697532 -0.454639 -0.216075 - 0.717346 -0.458411 -0.229894 - 0.732929 -0.366268 -0.24053 - 0.728502 -0.320515 -0.237333 - 0.728037 -0.307556 -0.236978 - 0.724497 -0.301808 -0.234496 - 0.726137 -0.289959 -0.23561 - 0.725617 -0.285587 -0.235237 - 0.728057 -0.19359 -0.236714 - 0.726077 -0.1813 -0.235304 - 0.7275 -0.119901 -0.236145 - 0.726764 -0.0630367 -0.235494 - 0.724569 -0.0105581 -0.233836 - 0.725142 0.0267313 -0.234145 - 0.725279 0.0754005 -0.234122 - 0.721463 0.101229 -0.231399 - 0.723176 0.116591 -0.232556 - 0.730492 0.156326 -0.237558 - 0.721452 0.212541 -0.23112 - 0.720689 0.216247 -0.230579 - 0.720707 0.2202 -0.230582 - 0.728831 0.259136 -0.236149 - 0.723096 0.323377 -0.231995 - 0.711516 0.334851 -0.223897 - 0.718975 0.347078 -0.229066 - 0.735808 0.423657 -0.240611 - 0.735761 0.428322 -0.240567 - 0.705748 0.446943 -0.219603 - 0.395837 0.25146 -0.00407988 - 0.688987 0.51179 -0.207764 - 0.721237 0.595415 -0.230037 - 0.691481 0.586008 -0.209321 - 0.731969 0.730745 -0.237187 - 0.546821 0.720208 -0.108169 - 0.517535 0.736108 -0.0877188 - 0.537949 0.780337 -0.101839 - 0.721253 1.0973 -0.228824 - 0.716818 1.23967 -0.225386 - 0.691357 1.25188 -0.207611 - 0.686873 1.25541 -0.204477 - 0.385846 0.748213 0.00409454 - 0.341492 0.742707 0.0349943 - 0.241237 0.608202 0.104541 - 0.234374 0.610682 0.109331 - 0.324277 1.04631 0.0477328 - 0.292164 0.947644 0.0698745 - 0.288771 0.949056 0.0722429 - 0.355291 1.27827 0.0266825 - 0.307337 1.28589 0.060124 - 0.302733 1.28738 0.0633365 - 0.281527 1.27948 0.0780971 - 0.200608 1.28134 0.1345 - 0.0914959 1.16521 0.210265 - 0.0695399 1.25184 0.225779 - 0.0412892 1.16184 0.24525 - 0.0246853 1.223 0.256971 --0.00028193 1.16058 0.274221 - -0.0509111 1.17031 0.309531 - -0.0811766 1.17786 0.330644 - -0.0974097 1.16946 0.341938 - -0.120466 1.22011 0.358131 - -0.174489 1.16684 0.395654 - -0.212615 1.20455 0.422319 - -0.262978 1.20269 0.457415 - -0.310328 1.23811 0.490504 - -0.414052 1.27501 0.562886 - -0.461729 1.27112 0.596106 - -0.498164 1.26399 0.621483 - -0.49707 1.23438 0.620649 - -0.495595 1.16748 0.619457 - -0.494255 1.15243 0.618487 - -0.500594 1.02397 0.622592 - -0.495595 0.985235 0.619013 - -0.500388 0.975479 0.62233 - -0.496816 0.850468 0.619536 - -0.49573 0.667608 0.618333 - -0.29312 -0.407437 0.469504 - -0.249108 -0.407463 0.439523 - -0.240072 -0.404669 0.433375 - -0.154789 -0.41439 0.375257 - -0.520558 -1.62768 0.621481 - -0.525969 -1.95589 0.624372 - -0.378196 -2.18725 0.52315 - -0.316545 -2.2136 0.48109 - -0.179883 -2.23581 0.387943 - -0.14441 -2.19788 0.363871 - -0.092332 -2.27085 0.328219 - -0.0694049 -2.31341 0.312499 - 0.0075892 -0.438595 0.264588 - 0.0410713 -0.348333 0.241998 - 0.0473797 -0.367841 0.237654 - 0.0527611 -0.36827 0.233987 - 0.0606193 -0.366216 0.228639 - 0.0686525 -0.365895 0.223168 - 0.0965089 -0.382862 0.204151 - 0.105092 -0.375141 0.198323 - 0.115029 -0.380098 0.191542 - 0.132974 -0.374132 0.179333 - 0.143267 -0.372697 0.172324 - 0.203953 -0.389846 0.130944 - 0.247456 -0.429432 0.101214 - 0.270583 -0.43492 0.085447 - 0.635099 -0.938699 -0.164079 - 0.517759 -0.706317 -0.0835848 - 0.371058 -0.479367 0.0168964 - 0.502481 -0.654913 -0.0730533 - 0.504841 -0.652375 -0.0746548 - 0.509534 -0.647262 -0.0778389 - 0.367515 -0.423367 0.0194454 - 0.397705 -0.40386 -0.00107276 - 0.402471 -0.401867 -0.00431457 - 0.405166 -0.401172 -0.00614843 - 0.421027 -0.40332 -0.0169586 - 0.423751 -0.402494 -0.0188116 - 0.429662 -0.404824 -0.0228443 - 0.447256 -0.403895 -0.0348267 - 0.473073 -0.405866 -0.052418 - 0.621699 -0.421636 -0.153699 - 0.738537 -0.459452 -0.23338 - 0.741654 -0.456601 -0.235496 - 0.744003 -0.405924 -0.236974 - 0.750147 -0.37713 -0.241089 - 0.747056 -0.344241 -0.238904 - 0.74766 -0.313963 -0.239243 - 0.74632 -0.300514 -0.238297 - 0.738011 -0.210912 -0.232421 - 0.745175 -0.16119 -0.23718 - 0.742594 -0.117767 -0.235317 - 0.742605 -0.110044 -0.235306 - 0.74985 -0.0955996 -0.240206 - 0.740013 -0.0447977 -0.233382 - 0.740317 -0.0372315 -0.233571 - 0.745147 0.00444343 -0.23676 - 0.745169 0.0425671 -0.236683 - 0.744843 0.0501834 -0.236442 - 0.741081 0.11876 -0.233714 - 0.741855 0.146038 -0.234175 - 0.742244 0.233568 -0.234228 - 0.753251 0.435852 -0.241237 - 0.746136 0.450724 -0.236354 - 0.744119 0.582869 -0.23466 - 0.695445 0.580131 -0.20151 - 0.692457 0.59367 -0.199443 - 0.750073 0.744325 -0.238325 - 0.751132 0.813841 -0.238878 - 0.690033 1.25289 -0.196196 - 0.335318 1.00719 0.0448397 - 0.412777 1.2744 -0.00727883 - 0.337682 1.2803 0.0438898 - 0.244966 1.28372 0.107056 - 0.143821 1.17825 0.1757 - 0.117991 1.23388 0.19343 - 0.0495947 1.17062 0.239868 --0.00526957 1.16943 0.277238 - -0.0209738 1.25476 0.288142 - -0.103248 1.17177 0.343986 - -0.126226 1.18293 0.359665 - -0.162923 1.22202 0.384758 - -0.340542 1.2818 0.505896 - -0.357855 1.27013 0.517661 - -0.418654 1.27778 0.559096 - -0.498155 1.21386 0.613096 - -0.493476 1.11808 0.609678 - -0.491627 0.812732 0.607679 - -0.493461 0.772804 0.608831 - -0.492402 0.70581 0.607948 - -0.491005 0.673654 0.606918 - -0.304127 -0.400418 0.47217 - -0.276881 -0.407693 0.453997 - -0.262268 -0.401743 0.444273 - -0.259343 -0.404717 0.442317 - -0.233246 -0.40166 0.424934 - -0.195922 -0.401608 0.400062 - -0.191084 -0.404171 0.396833 - -0.174998 -0.404276 0.386113 - -0.168514 -0.403011 0.381795 - -0.15758 -0.400019 0.374516 - -0.221952 -0.638637 0.416839 - -0.523127 -1.77741 0.614796 - -0.522651 -1.84993 0.614305 - -0.517452 -2.0891 0.610265 - -0.514522 -2.14351 0.608182 - -0.425531 -2.15832 0.548845 - -0.371375 -2.17859 0.512709 - -0.363463 -2.18062 0.507432 - -0.231554 -2.16989 0.419557 - -0.163666 -2.21794 0.374203 - -0.0939434 -2.28083 0.32759 - 0.0315469 -0.387859 0.248517 - 0.0426488 -0.358214 0.24119 - 0.0513537 -0.369418 0.235362 - 0.053012 -0.373247 0.234248 - 0.08224 -0.374261 0.214769 - 0.083757 -0.374928 0.213756 - 0.107958 -0.3805 0.197616 - 0.10934 -0.38005 0.196697 - 0.120175 -0.38148 0.189473 - 0.134212 -0.382258 0.180117 - 0.146559 -0.386394 0.171879 - 0.150144 -0.382558 0.1695 - 0.151532 -0.381887 0.168576 - 0.173206 -0.395701 0.1541 - 0.178218 -0.390683 0.150772 - 0.249765 -0.427401 0.103007 - 0.584765 -0.797086 -0.121116 - 0.381049 -0.415092 0.0155529 - 0.409114 -0.406478 -0.00312802 - 0.447706 -0.405508 -0.0288426 - 0.4608 -0.403226 -0.0375621 - 0.486945 -0.404578 -0.054988 - 0.52247 -0.408159 -0.0786691 - 0.536593 -0.407984 -0.0880798 - 0.555782 -0.407344 -0.100865 - 0.733572 -0.453358 -0.21945 - 0.765032 -0.434215 -0.240368 - 0.763702 -0.414364 -0.239435 - 0.764811 -0.36399 -0.240052 - 0.764775 -0.31058 -0.2399 - 0.756257 -0.281359 -0.234154 - 0.757062 -0.264787 -0.23465 - 0.763238 -0.124331 -0.238429 - 0.761209 -0.104316 -0.237028 - 0.756694 -0.0532654 -0.233897 - 0.75623 -0.0455203 -0.233569 - 0.754879 -0.0377462 -0.23265 - 0.75866 -0.0224983 -0.235133 - 0.760258 0.0509298 -0.236021 - 0.756934 0.0661523 -0.23377 - 0.760033 0.101507 -0.23575 - 0.758009 0.105132 -0.234392 - 0.757964 0.128637 -0.234306 - 0.765858 0.145959 -0.239524 - 0.757748 0.172178 -0.234057 - 0.758125 0.212609 -0.234211 - 0.762588 0.302155 -0.23697 - 0.760701 0.3057 -0.235704 - 0.717193 0.32899 -0.206656 - 0.722503 0.340003 -0.210168 - 0.762424 0.395992 -0.236635 - 0.755741 0.401647 -0.232168 - 0.733209 0.597711 -0.216683 - 0.766735 0.710936 -0.238751 - 0.528639 0.73007 -0.0800445 - 0.535704 0.795088 -0.0845962 - 0.77071 1.24723 -0.240111 - 0.771982 1.2609 -0.240926 - 0.705377 1.22618 -0.196625 - 0.644231 1.18202 -0.155986 - 0.38 0.73457 0.0190149 - 0.368065 0.739303 0.0269798 - 0.339533 0.737269 0.0459875 - 0.324731 0.733903 0.0558431 - 0.328962 0.778096 0.0531301 - 0.228095 0.60841 0.119937 - 0.226194 0.610403 0.121209 - 0.402956 1.23499 0.00492057 - 0.249721 1.27668 0.107132 - 0.245255 1.27882 0.110114 - 0.226653 1.28325 0.12252 - 0.139396 1.17291 0.1804 - 0.131058 1.17606 0.185964 - 0.0762016 1.1994 0.222575 - 0.0646925 1.24707 0.230359 - -0.0333251 1.211 0.295588 - -0.0399069 1.16943 0.299874 - -0.0437501 1.1621 0.302418 - -0.0708838 1.23969 0.320685 - -0.133164 1.15859 0.361992 - -0.172227 1.18461 0.388085 - -0.275951 1.16008 0.457145 - -0.370082 1.2831 0.520167 - -0.379389 1.27891 0.526359 - -0.394815 1.27709 0.536634 - -0.399451 1.27488 0.539718 - -0.432997 1.27764 0.562078 - -0.474403 1.2838 0.589685 - -0.501597 1.23893 0.607698 - -0.497089 1.15255 0.604487 - -0.496475 1.13929 0.604046 - -0.49986 1.12332 0.606263 - -0.496978 1.10576 0.604301 - -0.492081 1.02117 0.600834 - -0.495352 1.0176 0.603005 - -0.498171 1.01316 0.604873 - -0.495009 0.950402 0.602615 - -0.492739 0.793862 0.600726 - -0.489923 0.703272 0.598632 - -0.496156 0.687207 0.602747 - -0.494359 0.67292 0.601515 - -0.492602 0.641918 0.600269 - -0.28465 -0.411343 0.454664 - -0.266325 -0.407816 0.442729 - -0.161951 -0.406173 0.37471 - -0.154105 -0.409989 0.369588 - -0.41654 -1.09882 0.538979 - -0.5224 -1.88772 0.606087 - -0.522903 -2.09483 0.605921 - -0.396873 -2.16541 0.523615 - -0.34916 -2.2267 0.492373 - -0.221883 -2.21014 0.409463 - -0.127306 -2.26213 0.347701 - 0.0299607 -0.394899 0.249663 - 0.0488365 -0.374685 0.23741 - 0.0632156 -0.366799 0.228057 - 0.0645563 -0.366583 0.227184 - 0.0791042 -0.371918 0.21769 - 0.0954116 -0.383246 0.207035 - 0.0968122 -0.382862 0.206123 - 0.106363 -0.379009 0.199908 - 0.112301 -0.385374 0.196023 - 0.128551 -0.37734 0.185451 - 0.149722 -0.379772 0.171648 - 0.159961 -0.395301 0.164938 - 0.177128 -0.39059 0.153761 - 0.197206 -0.39989 0.140653 - 0.208316 -0.383487 0.133452 - 0.623551 -0.885423 -0.138365 - 0.546635 -0.706558 -0.0878102 - 0.387612 -0.450709 0.0164403 - 0.395813 -0.407732 0.0111978 - 0.424933 -0.406062 -0.00777665 - 0.426416 -0.403962 -0.00873804 - 0.494603 -0.405059 -0.0531798 - 0.510786 -0.403704 -0.0637232 - 0.558323 -0.406808 -0.0947116 - 0.722895 -0.45317 -0.202078 - 0.757464 -0.460786 -0.224626 - 0.769342 -0.44855 -0.232338 - 0.786365 -0.438995 -0.243409 - 0.783255 -0.389346 -0.241264 - 0.781438 -0.346958 -0.239979 - 0.780502 -0.315186 -0.239293 - 0.771765 -0.289826 -0.233538 - 0.777858 -0.283512 -0.237494 - 0.780331 -0.237395 -0.238995 - 0.77792 -0.207424 -0.237352 - 0.780961 -0.195819 -0.239307 - 0.774787 -0.149541 -0.235173 - 0.779494 -0.126269 -0.238184 - 0.766668 -0.104433 -0.229774 - 0.776463 -0.030756 -0.235981 - 0.774721 0.0555345 -0.23464 - 0.771795 0.114354 -0.232593 - 0.775001 0.1308 -0.234643 - 0.776123 0.191724 -0.235229 - 0.771711 0.227602 -0.232268 - 0.774079 0.236667 -0.233789 - 0.773211 0.240575 -0.233214 - 0.783585 0.273869 -0.239896 - 0.783383 0.27812 -0.239754 - 0.721257 0.345785 -0.199103 - 0.760894 0.478752 -0.224618 - 0.359129 0.241329 0.036655 - 0.364299 0.252352 0.033312 - 0.523374 0.380841 -0.0700546 - 0.717034 0.580486 -0.19579 - 0.710118 0.580048 -0.191284 - 0.697016 0.579574 -0.182747 - 0.761252 0.664441 -0.224409 - 0.591575 0.721579 -0.11369 - 0.668673 0.894484 -0.163523 - 0.36406 0.7341 0.0346179 - 0.362682 0.830778 0.0357467 - 0.235431 0.604224 0.118138 - 0.228755 0.722684 0.122772 - 0.359617 1.27255 0.0387989 - 0.350304 1.27599 0.0448763 - 0.203586 1.2843 0.140516 - 0.0694747 1.25584 0.227852 - 0.0489772 1.16162 0.240986 - -0.0706132 1.22276 0.319072 - -0.0836711 1.16792 0.327451 - -0.0871852 1.1594 0.329721 - -0.12651 1.16317 0.355359 - -0.138842 1.15776 0.363383 - -0.177996 1.15608 0.388897 - -0.233532 1.16506 0.425112 - -0.260764 1.18306 0.442903 - -0.298304 1.19974 0.467409 - -0.327496 1.27039 0.486602 - -0.398641 1.27896 0.53299 - -0.438119 1.28223 0.558726 - -0.457494 1.27422 0.571334 - -0.496059 0.972821 0.595749 - -0.494979 0.820546 0.594681 - -0.494539 0.790712 0.594323 - -0.496524 0.707029 0.595417 - -0.490236 0.680274 0.591255 - -0.317853 -0.407228 0.471315 - -0.292498 -0.404148 0.455171 - -0.266442 -0.404761 0.43857 - -0.241919 -0.401324 0.422957 - -0.229965 -0.404556 0.415334 - -0.22052 -0.407712 0.409309 - -0.210265 -0.401549 0.402791 - -0.190945 -0.401058 0.390485 - -0.15333 -0.404653 0.366515 - -0.411832 -1.07896 0.52959 - -0.481021 -1.42246 0.572851 - -0.529968 -1.68275 0.603414 - -0.523328 -1.82542 0.598846 - -0.526078 -1.86032 0.600515 - -0.521757 -1.98342 0.597471 - -0.514971 -1.98811 0.593137 - -0.49934 -2.22739 0.582612 - -0.481805 -2.18953 0.571531 - -0.407578 -2.16127 0.524313 - -0.388263 -2.19213 0.511936 - -0.363173 -2.19339 0.49595 - -0.348834 -2.20806 0.486781 - -0.196433 -2.18394 0.389754 - -0.0780108 -2.25199 0.314153 - 0.0111873 -0.433806 0.261643 - 0.0193355 -0.412986 0.256501 - 0.0223761 -0.410999 0.254569 - 0.0315709 -0.355825 0.248843 - 0.0326485 -0.347778 0.248175 - 0.0447153 -0.355998 0.240469 - 0.0662948 -0.370322 0.226688 - 0.0854114 -0.375586 0.214498 - 0.0895535 -0.374572 0.211861 - 0.102781 -0.382226 0.203417 - 0.11677 -0.39019 0.194486 - 0.118206 -0.389697 0.193573 - 0.118444 -0.384403 0.193434 - 0.12524 -0.380869 0.189113 - 0.126381 -0.379381 0.18839 - 0.136677 -0.377312 0.181836 - 0.144305 -0.381429 0.176967 - 0.188344 -0.394522 0.148882 - 0.205957 -0.384538 0.137685 - 0.533898 -0.819491 -0.0722554 - 0.637286 -0.95865 -0.138447 - 0.63471 -0.834934 -0.136513 - 0.382146 -0.411622 0.0253826 - 0.383332 -0.405817 0.0246412 - 0.403064 -0.40253 0.012079 - 0.447109 -0.407433 -0.0159909 - 0.456874 -0.40575 -0.0222076 - 0.591333 -0.404844 -0.10786 - 0.61623 -0.401919 -0.123713 - 0.627247 -0.405235 -0.130739 - 0.772707 -0.462486 -0.223538 - 0.795569 -0.446471 -0.238064 - 0.799596 -0.438881 -0.24061 - 0.798762 -0.320779 -0.2398 - 0.796304 -0.194354 -0.237934 - 0.79833 -0.149143 -0.239117 - 0.794339 -0.111698 -0.236486 - 0.796422 -0.107938 -0.237804 - 0.79551 -0.0795172 -0.237156 - 0.79213 -0.0671462 -0.234973 - 0.795055 -0.0113246 -0.236704 - 0.786962 0.036267 -0.231436 - 0.793619 0.072611 -0.23559 - 0.798835 0.0933424 -0.238864 - 0.793035 0.133107 -0.235075 - 0.791201 0.14092 -0.233888 - 0.789847 0.144737 -0.233016 - 0.790763 0.173569 -0.233531 - 0.792926 0.186474 -0.234879 - 0.787517 0.197559 -0.231407 - 0.792674 0.236771 -0.234599 - 0.712484 0.322748 -0.183311 - 0.743492 0.394579 -0.202894 - 0.799773 0.449999 -0.238616 - 0.360124 0.243076 0.0409641 - 0.359043 0.247084 0.041662 - 0.795884 0.601594 -0.235779 - 0.6971 0.57083 -0.172923 - 0.694246 0.578958 -0.171086 - 0.710794 0.609686 -0.181555 - 0.657376 0.620721 -0.147499 - 0.579807 0.638175 -0.0980443 - 0.791487 0.977748 -0.232086 - 0.798182 1.03947 -0.236204 - 0.510686 0.721032 -0.0538152 - 0.786701 1.26986 -0.228345 - 0.703235 1.21889 -0.175294 - 0.350027 0.737475 0.0485683 - 0.344591 0.740827 0.0520395 - 0.455146 1.07445 -0.0175966 - 0.367627 0.866763 0.0376636 - 0.234898 0.60717 0.1216 - 0.277841 0.808566 0.0947218 - 0.28931 0.891966 0.0876137 - 0.222535 0.70762 0.129714 - 0.355291 1.26855 0.0464744 - 0.262476 1.28013 0.105628 - 0.199809 1.28621 0.145563 - 0.0875326 1.16555 0.216801 - 0.0792421 1.17216 0.222098 - 0.0644655 1.24707 0.231689 - 0.0402823 1.16683 0.246904 - 0.0185431 1.24998 0.26095 - -0.0453796 1.1611 0.30146 - -0.211 1.20217 0.407062 - -0.479067 1.27655 0.578006 - -0.490625 1.27671 0.585369 - -0.496315 1.26236 0.58896 - -0.498825 1.24082 0.590508 - -0.496578 1.12264 0.588796 - -0.494829 1.08488 0.587592 - -0.49261 0.649261 0.585146 - -0.317441 -0.410731 0.466079 - -0.283217 -0.413841 0.444771 - -0.271867 -0.405547 0.437726 - -0.167561 -0.398892 0.372821 - -0.161224 -0.401842 0.36887 - -0.153724 -0.419886 0.36416 - -0.155149 -0.427977 0.365027 - -0.217134 -0.618067 0.403159 - -0.212351 -0.634805 0.400143 - -0.513727 -2.1979 0.584038 - -0.489041 -2.20497 0.568656 - -0.350115 -2.19923 0.482202 - -0.288028 -2.23679 0.443471 - -0.266265 -2.20033 0.430011 - -0.217705 -2.21237 0.399759 - -0.197399 -2.176 0.387206 - -0.15194 -2.21979 0.358809 - -0.0968744 -2.27385 0.324409 - 0.00941427 -0.424751 0.262611 - 0.0109614 -0.42581 0.261645 - 0.0266335 -0.415959 0.251914 - 0.0588541 -0.36641 0.231977 - 0.0648486 -0.370546 0.228236 - 0.0684633 -0.365895 0.225997 - 0.111571 -0.386802 0.199117 - 0.121561 -0.383392 0.192908 - 0.134827 -0.38037 0.184658 - 0.20044 -0.390962 0.143795 - 0.202924 -0.388234 0.142256 - 0.273617 -0.439174 0.0981363 - 0.274288 -0.436222 0.0977257 - 0.752495 -1.11108 -0.201501 - 0.384817 -0.446109 0.028909 - 0.378379 -0.408599 0.0330041 - 0.530794 -0.407597 -0.0618568 - 0.759062 -0.456136 -0.204045 - 0.78543 -0.452595 -0.220449 - 0.816938 -0.406442 -0.239951 - 0.816886 -0.372841 -0.239839 - 0.813953 -0.325056 -0.237901 - 0.809355 -0.287267 -0.23495 - 0.810416 -0.283218 -0.235601 - 0.813622 -0.240438 -0.237496 - 0.807867 -0.204512 -0.233829 - 0.80936 -0.196426 -0.23474 - 0.810391 -0.101007 -0.235156 - 0.810404 -0.0805544 -0.235116 - 0.812091 -0.0684671 -0.236138 - 0.814036 -0.0645445 -0.237339 - 0.814272 -0.0604739 -0.237476 - 0.813069 -0.027785 -0.236651 - 0.804889 -0.0113988 -0.231521 - 0.813859 0.0822551 -0.236883 - 0.808256 0.151449 -0.233233 - 0.808416 0.168117 -0.233293 - 0.811422 0.211 -0.235063 - 0.813102 0.285446 -0.235933 - 0.814207 0.317295 -0.236546 - 0.812636 0.325751 -0.235548 - 0.811426 0.329808 -0.234786 - 0.724186 0.322082 -0.180506 - 0.739421 0.367861 -0.18988 - 0.722558 0.385181 -0.179343 - 0.721128 0.388775 -0.178445 - 0.810664 0.499552 -0.233912 - 0.387899 0.246436 0.028622 - 0.366256 0.236564 0.0420695 - 0.806882 0.612216 -0.231292 - 0.657485 0.5797 -0.138384 - 0.606924 0.583303 -0.106906 - 0.604761 0.586299 -0.105553 - 0.598844 0.595881 -0.101847 - 0.59727 0.599499 -0.100859 - 0.754192 0.832825 -0.197978 - 0.760889 1.26566 -0.201127 - 0.740565 1.25412 -0.188504 - 0.659504 1.13379 -0.138335 - 0.454413 0.783686 -0.0115106 - 0.427138 0.748433 0.0053823 - 0.400313 0.740914 0.0220602 - 0.380608 0.738274 0.0343185 - 0.349055 0.747052 0.0539779 - 0.518815 1.21186 -0.0505862 - 0.236563 0.616592 0.123686 - 0.361377 1.28479 0.0475758 - 0.293871 1.28102 0.0895828 - 0.2399 1.28599 0.123186 - 0.195813 1.2871 0.150629 - 0.0273243 1.23799 0.25538 - 0.00547317 1.16281 0.268803 - -0.0418731 1.16045 0.298266 - -0.191657 1.16272 0.391497 - -0.216113 1.1715 0.406739 - -0.285447 1.16868 0.449886 - -0.365691 1.27402 0.500079 - -0.412018 1.28324 0.528934 - -0.49845 1.24441 0.582639 - -0.501922 1.23903 0.584787 - -0.492433 0.882196 0.57804 - -0.495146 0.787082 0.579505 - -0.494404 0.778899 0.579023 - -0.495363 0.739543 0.579528 - -0.496396 0.672413 0.580013 - -0.498885 0.669737 0.581556 - -0.491209 0.626104 0.576675 - -0.32337 -0.40405 0.464769 - -0.286377 -0.407693 0.442274 - -0.267819 -0.403951 0.431002 - -0.252389 -0.407026 0.421616 - -0.232967 -0.39924 0.409828 - -0.22598 -0.40275 0.405573 - -0.205682 -0.402125 0.393236 - -0.198392 -0.400521 0.388808 - -0.148045 -0.407297 0.358189 - -0.213846 -0.626272 0.397674 - -0.522096 -1.6352 0.582686 - -0.523804 -1.82633 0.583277 - -0.385958 -2.19325 0.498627 - -0.309501 -2.2503 0.452018 - -0.21113 -2.21159 0.392313 - -0.182265 -2.17119 0.374861 - -0.150723 -2.18593 0.355654 - -0.130916 -2.25714 0.343447 - 0.00475302 -0.411539 0.265298 - 0.00911548 -0.419754 0.262627 - 0.0153158 -0.42394 0.258849 - 0.0291238 -0.400897 0.250509 - 0.0405099 -0.336262 0.243739 - 0.0569725 -0.362623 0.233671 - 0.064836 -0.35943 0.228898 - 0.0724857 -0.365145 0.224235 - 0.0795927 -0.374869 0.219892 - 0.0822275 -0.373279 0.218294 - 0.0863985 -0.372315 0.215761 - 0.0932343 -0.377765 0.211593 - 0.12251 -0.380011 0.193792 - 0.167828 -0.393294 0.166214 - 0.169294 -0.392542 0.165325 - 0.182029 -0.388964 0.157592 - 0.210752 -0.375509 0.140164 - 0.215746 -0.377845 0.137123 - 0.219811 -0.381976 0.134642 - 0.280368 -0.444484 0.0976852 - 0.278322 -0.432789 0.0989566 - 0.297714 -0.448565 0.0871317 - 0.565912 -0.876509 -0.0768972 - 0.842108 -1.20686 -0.245559 - 0.709742 -0.934248 -0.164461 - 0.677022 -0.84403 -0.144361 - 0.385991 -0.426075 0.0335243 - 0.431876 -0.406062 0.00567907 - 0.472472 -0.404442 -0.0189939 - 0.556989 -0.406389 -0.0703729 - 0.642661 -0.410645 -0.12246 - 0.821148 -0.455664 -0.231061 - 0.828819 -0.414947 -0.235628 - 0.830024 -0.367186 -0.236249 - 0.838442 -0.309867 -0.241232 - 0.829361 -0.217515 -0.235495 - 0.830961 -0.209258 -0.236449 - 0.827148 -0.186797 -0.234079 - 0.826164 -0.182301 -0.23347 - 0.834583 -0.0950885 -0.238383 - 0.833048 -0.0698614 -0.237391 - 0.833547 -0.0615734 -0.237675 - 0.829509 -0.0571261 -0.23521 - 0.831766 -0.0158562 -0.236486 - 0.82755 -0.0116584 -0.233913 - 0.832567 0.0213916 -0.236885 - 0.828645 0.137578 -0.234229 - 0.8248 0.153709 -0.231854 - 0.830812 0.171869 -0.235466 - 0.830168 0.175997 -0.235065 - 0.833649 0.28658 -0.236922 - 0.83879 0.320537 -0.239968 - 0.829498 0.321483 -0.234318 - 0.829568 0.354045 -0.234284 - 0.718379 0.329871 -0.166753 - 0.717479 0.337735 -0.166187 - 0.716217 0.341282 -0.165412 - 0.365442 0.241844 0.0475783 - 0.363629 0.245342 0.0486884 - 0.36614 0.252004 0.047178 - 0.388041 0.273259 0.0339146 - 0.828165 0.619159 -0.232811 - 0.836051 1.03094 -0.23664 - 0.832357 1.09124 -0.234254 - 0.836116 1.12569 -0.236458 - 0.831915 1.12984 -0.233895 - 0.487205 0.735923 -0.0252801 - 0.436802 0.747606 0.00538498 - 0.398855 0.734054 0.0284197 - 0.386789 0.746959 0.0357843 - 0.357905 0.739311 0.0533242 - 0.548434 1.24889 -0.0612985 - 0.303836 0.723657 0.0861539 - 0.228145 0.612389 0.131903 - 0.26603 0.763593 0.109228 - 0.214641 0.66396 0.140233 - 0.373261 1.28317 0.0452627 - 0.296058 1.2849 0.0921953 - 0.265007 1.2811 0.111061 - 0.255447 1.28352 0.116878 - 0.220633 1.28335 0.13804 - 0.187058 1.28981 0.158464 - 0.0838655 1.17785 0.220929 - 0.0795713 1.18015 0.223544 - 0.0176847 1.24798 0.261322 - -0.0285848 1.24052 0.28943 - -0.0790562 1.17795 0.319963 - -0.100786 1.17308 0.33316 - -0.170423 1.16012 0.37546 - -0.174748 1.15912 0.378086 - -0.264608 1.19031 0.432782 - -0.381069 1.27935 0.503782 - -0.418118 1.27543 0.526294 - -0.493838 1.19794 0.57214 - -0.499629 1.1855 0.575631 - -0.497222 1.14297 0.574068 - -0.4976 0.963686 0.573878 - -0.491556 0.943316 0.570157 - -0.49172 0.812261 0.56995 - -0.492513 0.743289 0.57027 - -0.488807 0.724891 0.567975 - -0.496328 0.716233 0.572526 - -0.490794 0.666163 0.569045 - -0.493164 0.623947 0.570387 - -0.288959 -0.404624 0.43964 - -0.21488 -0.396233 0.395635 - -0.176815 -0.407493 0.372988 - -0.173753 -0.409486 0.371163 - -0.164352 -0.406312 0.365584 - -0.160804 -0.444225 0.363387 - -0.511148 -1.53215 0.56906 - -0.530593 -1.60823 0.580439 - -0.527559 -1.64079 0.57856 - -0.386159 -2.17956 0.493275 - -0.278228 -2.19489 0.429097 - -0.212102 -2.20464 0.389777 - 0.025973 -0.415959 0.252454 - 0.0309721 -0.367819 0.249595 - 0.0664609 -0.362173 0.228518 - 0.103038 -0.381256 0.206736 - 0.10654 -0.383314 0.20465 - 0.116322 -0.385385 0.198832 - 0.129529 -0.381687 0.190992 - 0.139535 -0.382958 0.185042 - 0.209482 -0.390718 0.143456 - 0.210947 -0.389758 0.142588 - 0.268012 -0.433411 0.108573 - 0.293846 -0.444276 0.0931952 - 0.845104 -1.20452 -0.236179 - 0.740462 -0.970588 -0.173447 - 0.699294 -0.875593 -0.14876 - 0.68901 -0.847303 -0.142583 - 0.381195 -0.403986 0.0413782 - 0.394478 -0.408053 0.0334749 - 0.442511 -0.403553 0.00494027 - 0.487614 -0.404671 -0.0218665 - 0.493409 -0.402282 -0.0253048 - 0.509796 -0.404917 -0.0350496 - 0.595275 -0.404676 -0.0858476 - 0.673297 -0.406976 -0.13222 - 0.791634 -0.460885 -0.202672 - 0.80735 -0.460235 -0.21201 - 0.843741 -0.455646 -0.233626 - 0.852953 -0.43003 -0.239041 - 0.856616 -0.391881 -0.241129 - 0.852336 -0.380092 -0.238558 - 0.858481 -0.358561 -0.24216 - 0.857912 -0.348698 -0.241799 - 0.852735 -0.341782 -0.238706 - 0.858568 -0.325164 -0.242134 - 0.853983 -0.309343 -0.239372 - 0.847699 -0.274938 -0.235558 - 0.84576 -0.260756 -0.234372 - 0.850475 -0.239769 -0.237126 - 0.843075 -0.219982 -0.232682 - 0.847654 -0.19049 -0.235334 - 0.848655 -0.143119 -0.235819 - 0.845194 -0.121212 -0.233712 - 0.84375 -0.0285303 -0.232638 - 0.850357 0.0596733 -0.236359 - 0.855118 0.184803 -0.238897 - 0.853296 0.228528 -0.237712 - 0.859074 0.239106 -0.241122 - 0.844447 0.257185 -0.232387 - 0.854307 0.283051 -0.238187 - 0.733054 0.322446 -0.166036 - 0.856546 0.495554 -0.239023 - 0.426832 0.269787 0.0158245 - 0.361395 0.235482 0.0546332 - 0.635896 0.524418 -0.107827 - 0.629265 0.533119 -0.103866 - 0.8408 0.851021 -0.228838 - 0.8408 0.858516 -0.228821 - 0.860011 0.958849 -0.240004 - 0.853653 1.07529 -0.235955 - 0.560921 0.781898 -0.062671 - 0.499016 0.72394 -0.0260166 - 0.492654 0.720778 -0.0222429 - 0.608284 0.965764 -0.0903902 - 0.442191 0.746321 0.0078059 - 0.365168 0.74376 0.0535732 - 0.40604 0.858949 0.0295519 - 0.228731 0.62754 0.134386 - 0.331145 1.27551 0.0750296 - 0.301498 1.28059 0.0926605 - 0.296485 1.28102 0.0956406 - 0.251648 1.2847 0.122295 - 0.240827 1.28011 0.128715 - 0.211806 1.28532 0.145974 - 0.00433909 1.1718 0.269004 - -0.0578649 1.17928 0.305989 - -0.181859 1.16496 0.379644 - -0.192555 1.17359 0.38602 - -0.217075 1.1805 0.400608 - -0.259354 1.19996 0.425779 - -0.3508 1.27709 0.480303 - -0.386572 1.27072 0.501547 - -0.493417 1.01715 0.564454 - -0.492946 0.967264 0.564058 - -0.493665 0.922939 0.564382 - -0.487649 0.778854 0.560472 - -0.494659 0.754779 0.564582 - -0.491573 0.743574 0.562721 - -0.495532 0.729518 0.565042 - -0.494915 0.715813 0.564643 - -0.493545 0.64797 0.563671 - -0.297624 -0.402083 0.440161 - -0.294201 -0.408357 0.438162 - -0.251792 -0.40369 0.413586 - -0.2379 -0.400843 0.405539 - -0.218213 -0.402374 0.394123 - -0.1757 -0.397799 0.369487 - -0.17244 -0.403361 0.367585 - -0.159247 -0.400192 0.359943 - -0.164476 -0.459653 0.362837 - -0.219151 -0.623238 0.394156 - -0.523656 -1.99467 0.567517 - -0.367494 -2.20319 0.476503 - -0.24198 -2.15702 0.403845 - -0.230107 -2.19824 0.396866 - -0.204277 -2.19288 0.381904 - -0.146244 -2.19973 0.348245 - -0.0893405 -2.23049 0.315185 - 0.0111432 -0.43086 0.261091 - 0.0310406 -0.382812 0.249667 - 0.0315613 -0.351776 0.249437 - 0.0328555 -0.350719 0.248689 - 0.0385806 -0.333361 0.24541 - 0.0460799 -0.349773 0.241025 - 0.090354 -0.377506 0.215294 - 0.0952677 -0.372146 0.212457 - 0.119657 -0.379114 0.198302 - 0.135573 -0.374132 0.189086 - 0.15108 -0.376987 0.18009 - 0.20338 -0.388283 0.149744 - 0.212805 -0.37637 0.144307 - 0.251713 -0.430934 0.121625 - 0.279932 -0.439527 0.105246 - 0.28159 -0.438215 0.104288 - 0.304959 -0.455865 0.0906988 - 0.3109 -0.444595 0.0872804 - 0.944274 -1.40337 -0.282124 - 0.962254 -1.40505 -0.292552 - 0.746283 -0.955729 -0.166307 - 0.731597 -0.920036 -0.157711 - 0.380285 -0.429862 0.0470899 - 0.384732 -0.427644 0.0445167 - 0.416808 -0.404527 0.0259746 - 0.591054 -0.407336 -0.0750481 - 0.656524 -0.402534 -0.112992 - 0.696198 -0.410104 -0.13601 - 0.881718 -0.431919 -0.243613 - 0.877465 -0.330546 -0.240912 - 0.87171 -0.318808 -0.237549 - 0.869433 -0.275885 -0.23613 - 0.869776 -0.234833 -0.236234 - 0.868997 -0.225588 -0.235761 - 0.879682 -0.19671 -0.241888 - 0.866823 -0.119331 -0.234255 - 0.878563 -0.0859996 -0.240984 - 0.871118 -0.0679961 -0.236626 - 0.869352 -0.0292458 -0.235513 - 0.872283 0.0652022 -0.236993 - 0.869887 0.125523 -0.235465 - 0.869048 0.147191 -0.234929 - 0.873895 0.156837 -0.237716 - 0.86827 0.23579 -0.234273 - 0.874793 0.316556 -0.237868 - 0.869384 0.362404 -0.234626 - 0.86177 0.368814 -0.230197 - 0.786864 0.340375 -0.186837 - 0.710166 0.330451 -0.142396 - 0.713814 0.348689 -0.144469 - 0.797456 0.414287 -0.192807 - 0.70836 0.379426 -0.141235 - 0.410011 0.259826 0.0314512 - 0.367465 0.240813 0.0560724 - 0.639926 0.501251 -0.10128 - 0.878239 0.900344 -0.238516 - 0.874816 0.970072 -0.23637 - 0.882935 1.04093 -0.240913 - 0.880389 1.05613 -0.239402 - 0.874801 1.07714 -0.236114 - 0.877119 1.12848 -0.237339 - 0.48513 0.718311 -0.0110382 - 0.473401 0.719594 -0.00423563 - 0.503144 0.78114 -0.0213364 - 0.50512 0.80644 -0.0224232 - 0.386425 0.73123 0.0462147 - 0.383663 0.733062 0.0478201 - 0.582048 1.25843 -0.065976 - 0.242584 0.595561 0.12929 - 0.230126 0.620891 0.136571 - 0.280279 0.822447 0.107962 - 0.23474 0.69679 0.134072 - 0.359218 1.27695 0.0632486 - 0.304352 1.28737 0.0950809 - 0.281897 1.27826 0.108078 - 0.267403 1.28208 0.116489 - 0.236968 1.2812 0.134131 - 0.206883 1.28035 0.15157 - 0.136479 1.16655 0.192123 - 0.108057 1.20392 0.208686 - 0.0877038 1.16755 0.220402 - 0.0125771 1.18294 0.263991 - -0.07302 1.24915 0.313767 - -0.129262 1.16592 0.346181 - -0.161318 1.22982 0.364912 - -0.173125 1.15717 0.371589 - -0.220851 1.16664 0.399279 - -0.24211 1.17801 0.41163 - -0.280685 1.16032 0.433953 - -0.29441 1.19416 0.441987 - -0.320436 1.27275 0.457257 - -0.342043 1.27419 0.469787 - -0.362943 1.27231 0.481899 - -0.379688 1.27388 0.49161 - -0.469331 1.27398 0.54358 - -0.495483 1.2667 0.558724 - -0.498423 1.23181 0.560348 - -0.497005 1.10336 0.559229 - -0.495262 1.0771 0.558157 - -0.495361 1.0137 0.558068 - -0.492126 0.794411 0.555686 - -0.32808 -0.404386 0.453008 - -0.30444 -0.397233 0.439646 - -0.245479 -0.402202 0.406265 - -0.220501 -0.403198 0.392127 - -0.214024 -0.399791 0.388469 - -0.187881 -0.398756 0.373676 - -0.171725 -0.407052 0.364513 - -0.155803 -0.429762 0.355449 - -0.163839 -0.459673 0.359928 - -0.531883 -1.63147 0.565532 - -0.518693 -2.02494 0.557163 - -0.507576 -2.1496 0.550584 - -0.450217 -2.16706 0.518082 - -0.399757 -2.17553 0.489504 - -0.360917 -2.20021 0.467466 - -0.262566 -2.17211 0.411868 - -0.16527 -2.20993 0.356717 - 0.00058302 -0.437415 0.266925 - 0.0268737 -0.41693 0.252093 - 0.041329 -0.341149 0.244086 - 0.0737048 -0.364881 0.225708 - 0.0750901 -0.364609 0.224924 - 0.0870081 -0.375255 0.218155 - 0.12284 -0.384348 0.197855 - 0.180553 -0.389686 0.16518 - 0.188758 -0.391792 0.160531 - 0.191729 -0.390088 0.158854 - 0.202023 -0.383891 0.153042 - 0.213674 -0.37282 0.146474 - 0.216432 -0.374418 0.144909 - 0.31094 -0.45072 0.0912468 - 0.987846 -1.42234 -0.294083 - 0.95853 -1.30712 -0.277227 - 0.864481 -1.16563 -0.223675 - 0.893543 -1.18457 -0.240166 - 0.383346 -0.412953 0.0503548 - 0.38427 -0.403292 0.0498541 - 0.425799 -0.404449 0.0263479 - 0.430378 -0.398315 0.0237707 - 0.461715 -0.406481 0.00601682 - 0.522171 -0.410718 -0.0282085 - 0.625685 -0.409077 -0.0867885 - 0.674468 -0.407424 -0.114394 - 0.689074 -0.403594 -0.122651 - 0.698321 -0.404849 -0.127888 - 0.902096 -0.388092 -0.243176 - 0.894791 -0.364889 -0.238988 - 0.897065 -0.316813 -0.240165 - 0.895758 -0.222202 -0.239208 - 0.889548 -0.197876 -0.235637 - 0.887958 -0.082084 -0.234471 - 0.902801 -0.0523844 -0.242804 - 0.886813 -0.0383796 -0.233723 - 0.898669 -0.0168765 -0.240383 - 0.886109 0.0354474 -0.233155 - 0.889802 0.0530614 -0.235204 - 0.893817 0.0752819 -0.237426 - 0.888364 0.101113 -0.23428 - 0.894044 0.204881 -0.237257 - 0.896759 0.228491 -0.238739 - 0.893173 0.24602 -0.236669 - 0.894019 0.326741 -0.236962 - 0.896081 0.33237 -0.238116 - 0.90025 0.358574 -0.240416 - 0.71475 0.32274 -0.135514 - 0.833356 0.426153 -0.202402 - 0.830097 0.434281 -0.200538 - 0.694945 0.374185 -0.124187 - 0.752655 0.438348 -0.156701 - 0.732499 0.430821 -0.14531 - 0.361013 0.244576 0.0645055 - 0.372845 0.260502 0.0578455 - 0.690289 0.539146 -0.121173 - 0.766262 0.628592 -0.163964 - 0.875165 0.733659 -0.225357 - 0.900501 0.871514 -0.239379 - 0.902634 0.928995 -0.240454 - 0.903022 1.00536 -0.240498 - 0.898309 1.10075 -0.237612 - 0.895296 1.10661 -0.235893 - 0.897148 1.20035 -0.236725 - 0.560521 0.793975 -0.0471442 - 0.479074 0.711794 -0.00123784 - 0.431974 0.741683 0.0254871 - 0.384787 0.739234 0.052187 - 0.392678 0.778842 0.0478124 - 0.411744 0.827291 0.0371331 - 0.54857 1.25691 -0.0393166 - 0.278278 0.656682 0.112276 - 0.256297 0.607703 0.124604 - 0.247673 0.592395 0.12945 - 0.382855 1.27947 0.0545224 - 0.356477 1.28055 0.0694533 - 0.155767 1.21631 0.182898 - 0.131664 1.16015 0.19641 - 0.117948 1.21098 0.20429 - 0.0970127 1.17382 0.216053 - 0.0877522 1.16855 0.221282 - 0.0791738 1.17515 0.226152 - 0.0679664 1.23286 0.232627 - 0.0163883 1.24798 0.261853 - -0.0539765 1.16073 0.301476 - -0.0692441 1.24961 0.310321 - -0.144115 1.1655 0.3525 - -0.225889 1.15957 0.398767 - -0.230712 1.16026 0.401498 - -0.244085 1.17801 0.409108 - -0.286146 1.17277 0.4329 - -0.332007 1.26734 0.459073 - -0.347066 1.28273 0.467631 - -0.410366 1.27462 0.503437 - -0.475492 1.28129 0.540311 - -0.490068 1.24501 0.548477 - -0.492858 1.02234 0.549544 - -0.492794 1.01198 0.549484 - -0.495857 0.940861 0.551054 - -0.49593 0.923027 0.551054 - -0.494342 0.902757 0.550109 - -0.490744 0.779838 0.54779 - -0.491357 0.766743 0.548107 - -0.491115 0.713324 0.547847 - -0.492153 0.708442 0.548423 - -0.495463 0.688194 0.550251 - -0.492072 0.671715 0.548293 - -0.492848 0.649481 0.548682 - -0.316098 -0.405037 0.441555 - -0.302173 -0.402083 0.433874 - -0.295793 -0.404624 0.430346 - -0.28194 -0.397227 0.422716 - -0.280421 -0.398728 0.421874 - -0.275831 -0.403184 0.419329 - -0.274289 -0.404654 0.418475 - -0.24226 -0.401645 0.4008 - -0.21983 -0.399075 0.388423 - -0.217812 -0.399439 0.387308 - -0.210317 -0.397954 0.383173 - -0.203602 -0.405288 0.37945 - -0.199268 -0.401308 0.377066 - -0.180968 -0.402142 0.366962 - -0.1699 -0.400019 0.360857 - -0.15614 -0.436962 0.353176 - -0.206255 -0.587817 0.380498 - -0.200721 -0.58729 0.377443 - -0.191823 -0.577472 0.372554 - -0.520809 -1.95843 0.551019 - -0.509619 -2.14382 0.544418 - -0.239315 -2.17318 0.395127 - -0.226251 -2.20741 0.387837 - -0.175235 -2.20998 0.359667 - -0.110539 -2.26724 0.32382 - 0.00714277 -0.42575 0.263059 - 0.0320768 -0.345723 0.249477 - 0.049719 -0.350354 0.239727 - 0.0538267 -0.350873 0.237458 - 0.0681852 -0.366884 0.229495 - 0.0719431 -0.373302 0.227405 - 0.0792169 -0.372902 0.223391 - 0.093504 -0.377765 0.215492 - 0.0961913 -0.376043 0.214013 - 0.13386 -0.382465 0.193202 - 0.134467 -0.379057 0.192875 - 0.135914 -0.378483 0.192078 - 0.145568 -0.382994 0.186738 - 0.150911 -0.374201 0.183808 - 0.17704 -0.388554 0.169351 - 0.180002 -0.391391 0.167709 - 0.182616 -0.393302 0.166262 - 0.19454 -0.386577 0.159694 - 0.196016 -0.385703 0.158882 - 0.209244 -0.385485 0.151579 - 0.263074 -0.439576 0.121738 - 0.272383 -0.443446 0.11659 - 0.28206 -0.443317 0.111248 - 0.283753 -0.442006 0.110317 - 0.295102 -0.452498 0.104028 - 0.984251 -1.44792 -0.278698 - 1.00083 -1.42061 -0.287787 - 0.447574 -0.405688 0.0199605 - 0.473408 -0.404113 0.00570223 - 0.474949 -0.401848 0.00485638 - 0.500819 -0.405864 -0.00943425 - 0.540463 -0.404224 -0.0313166 - 0.600085 -0.409438 -0.0642436 - 0.609183 -0.407785 -0.0692622 - 0.619804 -0.407002 -0.0751236 - 0.706605 -0.411964 -0.123055 - 0.721406 -0.403155 -0.131205 - 0.848702 -0.460916 -0.201613 - 0.860708 -0.46242 -0.208244 - 0.86642 -0.460374 -0.211393 - 0.915279 -0.282796 -0.23796 - 0.914068 -0.202347 -0.237108 - 0.916049 -0.161322 -0.238108 - 0.9153 -0.106712 -0.237569 - 0.914832 -0.10215 -0.237301 - 0.909316 -0.0702741 -0.234183 - 0.913042 -0.0215102 -0.236128 - 0.908853 0.00959484 -0.233745 - 0.912256 0.0185242 -0.235603 - 0.91982 0.0861216 -0.239624 - 0.917309 0.190633 -0.237999 - 0.91118 0.263888 -0.234449 - 0.918719 0.31446 -0.238495 - 0.910292 0.365688 -0.233726 - 0.715988 0.329684 -0.12654 - 0.718762 0.335084 -0.12806 - 0.832173 0.428124 -0.190457 - 0.68481 0.378926 -0.109215 - 0.661288 0.410484 -0.0961579 - 0.441172 0.277849 0.0250561 - 0.374541 0.260502 0.0618011 - 0.716816 0.557519 -0.126477 - 0.922896 0.820599 -0.239644 - 0.919041 0.900751 -0.237333 - 0.918695 0.949028 -0.237032 - 0.925416 1.01637 -0.240588 - 0.922773 1.02227 -0.239116 - 0.476078 0.710048 0.00677341 - 0.459663 0.723412 0.015866 - 0.3963 0.736298 0.0508754 - 0.393486 0.738162 0.0524334 - 0.458527 0.912157 0.0169243 - 0.255154 0.60222 0.12849 - 0.237905 0.682396 0.138196 - 0.232632 0.674998 0.14109 - 0.342386 1.28163 0.0818854 - 0.320038 1.27623 0.0942103 - 0.295184 1.28143 0.107943 - 0.243606 1.28011 0.136414 - 0.178383 1.28153 0.172425 --0.00145246 1.1587 0.271424 - -0.0104624 1.16443 0.276411 - -0.0787427 1.17946 0.31414 - -0.146071 1.16945 0.351287 - -0.185099 1.15516 0.3728 - -0.267327 1.16625 0.41822 - -0.348572 1.27894 0.46333 - -0.405134 1.28358 0.494566 - -0.447152 1.27409 0.517741 - -0.465556 1.27706 0.527908 - -0.497986 1.16233 0.545549 - -0.49514 1.10767 0.543853 - -0.497932 0.938325 0.545008 - -0.494933 0.923927 0.543319 - -0.491833 0.909577 0.541575 - -0.496374 0.875033 0.544002 - -0.499221 0.871619 0.545567 - -0.500641 0.849845 0.546301 - -0.497346 0.784627 0.544333 - -0.491481 0.666456 0.540825 - -0.492963 0.628537 0.541556 - -0.490565 0.620147 0.540213 - -0.305625 -0.403558 0.43128 - -0.30348 -0.404425 0.430124 - -0.283468 -0.407052 0.419346 - -0.24839 -0.408059 0.400464 - -0.245767 -0.411505 0.399044 - -0.197996 -0.399844 0.373358 - -0.177275 -0.399765 0.362206 - -0.166468 -0.464233 0.356243 - -0.193039 -0.598208 0.37024 - -0.492501 -1.45772 0.52947 - -0.52665 -1.82707 0.547011 - -0.375946 -2.20613 0.465035 - -0.250742 -2.18178 0.397701 - -0.103252 -2.27385 0.318107 - 0.0165174 -0.423986 0.257844 - 0.0633729 -0.363611 0.232762 - 0.0731529 -0.372053 0.227478 - 0.102877 -0.385553 0.211449 - 0.111738 -0.382944 0.206685 - 0.149682 -0.379219 0.186271 - 0.157491 -0.382134 0.182062 - 0.207598 -0.392675 0.155068 - 0.210141 -0.381928 0.153724 - 0.210734 -0.379244 0.15341 - 0.291569 -0.457403 0.109724 - 0.300835 -0.459889 0.104731 - 0.373025 -0.433692 0.0659355 - 0.389229 -0.434175 0.0572127 - 0.389395 -0.408599 0.0571815 - 0.567658 -0.407477 -0.038764 - 0.574389 -0.408565 -0.0423895 - 0.622156 -0.406491 -0.0680949 - 0.692287 -0.409812 -0.105849 - 0.707103 -0.410104 -0.113825 - 0.811998 -0.438155 -0.170347 - 0.941513 -0.416857 -0.240009 - 0.945326 -0.397459 -0.242017 - 0.931137 -0.286261 -0.234127 - 0.936615 -0.150197 -0.236767 - 0.934307 -0.0718618 -0.235347 - 0.943203 -0.0541908 -0.240095 - 0.935704 0.0461633 -0.23583 - 0.940638 0.0968362 -0.238371 - 0.939867 0.105956 -0.237936 - 0.936142 0.250542 -0.235602 - 0.771291 0.336701 -0.146677 - 0.708507 0.336494 -0.112885 - 0.408679 0.257749 0.0483155 - 0.369744 0.234263 0.0692188 - 0.367179 0.237203 0.0706061 - 0.942296 0.782769 -0.237706 - 0.940907 0.942224 -0.236596 - 0.944424 0.988109 -0.238384 - 0.941901 0.994054 -0.237013 - 0.948238 1.11131 -0.240157 - 0.944929 1.13676 -0.238319 - 0.950518 1.24865 -0.241073 - 0.491001 0.723054 0.00506359 - 0.469251 0.708873 0.0167382 - 0.437898 0.737934 0.0336793 - 0.402692 0.737869 0.0526284 - 0.420805 0.804537 0.0430308 - 0.622135 1.24632 -0.0643295 - 0.588646 1.281 -0.0462256 - 0.544569 1.24871 -0.0225752 - 0.455193 1.04772 0.0250743 - 0.230994 0.632324 0.144803 - 0.322958 1.283 0.0967827 - 0.307063 1.28253 0.105337 - 0.302134 1.28393 0.107993 - 0.21816 1.2745 0.15317 - 0.212963 1.27349 0.155965 - 0.118255 1.21098 0.206798 - 0.0968124 1.16983 0.218246 - 0.0764119 1.21637 0.229332 - 0.0624227 1.21809 0.236866 - 0.0381371 1.16284 0.249812 - -0.0173315 1.22322 0.279804 - -0.0221339 1.22602 0.282395 - -0.214565 1.22818 0.385974 - -0.219283 1.227 0.388511 - -0.225997 1.16469 0.391983 - -0.245465 1.18806 0.402514 - -0.321337 1.26873 0.443535 - -0.426727 1.2721 0.500268 - -0.450639 1.27501 0.513145 - -0.456223 1.2745 0.51615 - -0.491012 1.15152 0.534595 - -0.494635 1.14719 0.536535 - -0.494968 0.89189 0.536134 - -0.494307 0.811148 0.535595 - -0.490003 0.741095 0.533119 - -0.491914 0.645369 0.533931 - -0.312693 -0.402516 0.430713 - -0.267654 -0.404215 0.407061 - -0.25849 -0.398383 0.402263 - -0.192173 -0.397898 0.367443 - -0.174353 -0.399069 0.358083 - -0.15915 -0.447821 0.349991 - -0.19997 -0.583779 0.371117 - -0.521128 -1.90618 0.536759 - -0.52517 -2.01059 0.538646 - -0.517928 -2.04752 0.53476 - -0.283999 -2.16032 0.411677 - -0.213173 -2.21473 0.374365 - -0.185725 -2.19905 0.359989 - -0.113618 -2.28321 0.321937 - -0.104797 -2.28383 0.317304 - 0.0351826 -0.33952 0.248197 - 0.0476993 -0.347512 0.241607 - 0.0621791 -0.366799 0.233961 - 0.0650118 -0.366361 0.232474 - 0.0674494 -0.362929 0.231202 - 0.102119 -0.381669 0.212956 - 0.131509 -0.378288 0.197532 - 0.143872 -0.386111 0.191023 - 0.158207 -0.383059 0.183503 - 0.197379 -0.390132 0.162919 - 0.202303 -0.388346 0.160337 - 0.281051 -0.450542 0.118849 - 0.297215 -0.456337 0.110349 - 1.04894 -1.39768 -0.286483 - 0.379813 -0.421236 0.0670583 - 0.451661 -0.405688 0.0293684 - 0.488445 -0.4098 0.0100451 - 0.496842 -0.40228 0.00565299 - 0.530452 -0.411298 -0.0120148 - 0.561223 -0.408454 -0.0281652 - 0.594552 -0.405445 -0.0456584 - 0.76186 -0.40839 -0.133513 - 0.909792 -0.452291 -0.211287 - 0.938223 -0.461298 -0.226235 - 0.970031 -0.422161 -0.242848 - 0.953447 -0.0176459 -0.233227 - 0.959754 -0.00849599 -0.236517 - 0.950739 0.0835383 -0.231576 - 0.962139 0.107974 -0.237507 - 0.962487 0.131539 -0.237636 - 0.964404 0.146009 -0.23861 - 0.959352 0.18316 -0.235874 - 0.962485 0.202965 -0.237474 - 0.94882 0.219066 -0.230262 - 0.958842 0.350574 -0.235228 - 0.952091 0.410319 -0.231548 - 0.713638 0.329273 -0.106527 - 0.712362 0.332689 -0.10585 - 0.366261 0.237882 0.075663 - 0.366483 0.245107 0.0755627 - 0.368086 0.253461 0.0747398 - 0.746863 0.591856 -0.123379 - 0.966992 1.10856 -0.237795 - 0.96958 1.23473 -0.238869 - 0.968066 1.25468 -0.238029 - 0.514518 0.748775 -0.00102764 - 0.479252 0.714737 0.0174125 - 0.42792 0.738135 0.0444178 - 0.613932 1.27575 -0.0520368 - 0.587188 1.28559 -0.0379718 - 0.241972 0.584532 0.141706 - 0.23902 0.583779 0.143254 - 0.235736 0.582085 0.144975 - 0.337842 1.27359 0.0929247 - 0.3226 1.27623 0.100934 - 0.199531 1.28118 0.165565 - 0.0152047 1.20798 0.262183 - -0.0313165 1.20357 0.2866 - -0.118783 1.23096 0.332587 - -0.140011 1.17305 0.343603 - -0.172625 1.17286 0.360727 - -0.274457 1.15904 0.414164 - -0.288176 1.1743 0.421402 - -0.347548 1.27696 0.452808 - -0.436814 1.27635 0.499678 - -0.463813 1.27121 0.513842 - -0.4967 1.27989 0.53113 - -0.497567 1.26734 0.531557 - -0.496219 1.22167 0.530746 - -0.497859 1.14719 0.531439 - -0.496493 1.11987 0.53066 - -0.495577 1.09443 0.530121 - -0.497404 1.05349 0.530988 - -0.494166 0.956222 0.529069 - -0.499115 0.937513 0.531625 - -0.494631 0.860946 0.529097 - -0.494468 0.852617 0.528993 - -0.494702 0.633635 0.528621 - -0.296143 -0.403994 0.417871 - -0.275961 -0.402256 0.407544 - -0.26485 -0.40842 0.401842 - -0.249356 -0.400335 0.393929 - -0.2478 -0.401645 0.39313 - -0.239443 -0.403562 0.388847 - -0.22338 -0.403938 0.380624 - -0.216352 -0.608202 0.376567 - -0.205109 -0.623249 0.370778 - -0.523844 -1.77045 0.531361 - -0.522707 -1.84475 0.530612 - -0.522434 -2.01995 0.530079 - -0.465323 -2.18064 0.500483 - -0.423267 -2.1939 0.478924 - -0.369397 -2.19139 0.451354 - -0.348547 -2.2254 0.440605 - -0.307597 -2.18982 0.419722 - -0.242874 -2.15831 0.386661 - -0.171877 -2.22187 0.350175 - 0.0157968 -0.415986 0.258162 - 0.0239324 -0.420959 0.253986 - 0.0362569 -0.340437 0.247858 - 0.0411492 -0.33406 0.245368 - 0.0473913 -0.346516 0.242145 - 0.0584762 -0.348161 0.236467 - 0.0628564 -0.361629 0.234194 - 0.0701473 -0.362439 0.23046 - 0.077965 -0.366014 0.22645 - 0.0980052 -0.369435 0.216184 - 0.104274 -0.37696 0.212958 - 0.10889 -0.376637 0.210596 - 0.12569 -0.374204 0.202002 - 0.139081 -0.380728 0.195132 - 0.146449 -0.37769 0.191367 - 0.153947 -0.379772 0.187524 - 0.15622 -0.376582 0.186368 - 0.171824 -0.385391 0.17836 - 0.189116 -0.387309 0.169504 - 0.192119 -0.385625 0.167971 - 0.212947 -0.38098 0.157319 - 0.21884 -0.377115 0.154312 - 0.227177 -0.388983 0.150017 - 0.323003 -0.46979 0.100782 - 1.07191 -1.46017 -0.284808 - 0.378416 -0.432667 0.0724997 - 0.385893 -0.430229 0.0686778 - 0.388211 -0.403718 0.0675504 - 0.630266 -0.408023 -0.0563672 - 0.636517 -0.399995 -0.0595493 - 0.751917 -0.405422 -0.118635 - 0.903389 -0.457291 -0.19629 - 0.992601 -0.370467 -0.241762 - 1.00057 -0.325816 -0.245741 - 0.990684 -0.206435 -0.240413 - 0.993606 -0.182407 -0.241854 - 0.982464 -0.165788 -0.236114 - 0.989805 -0.109014 -0.239744 - 0.984937 -0.0798415 -0.237186 - 0.985242 -0.0751063 -0.237332 - 0.984353 -0.037078 -0.236791 - 0.990945 -0.0230286 -0.240134 - 0.984051 -0.00394224 -0.236562 - 0.980058 0.128547 -0.234221 - 0.983897 0.306429 -0.235786 - 0.714777 0.352553 -0.0979196 - 0.716093 0.382389 -0.0985263 - 0.984691 0.601951 -0.235528 - 0.363172 0.234766 0.0818024 - 0.359479 0.241471 0.0837081 - 0.387698 0.271705 0.0693306 - 0.449748 0.320474 0.0376771 - 0.716197 0.538653 -0.0982284 - 0.991789 0.809156 -0.238696 - 0.990599 0.900205 -0.237882 - 0.992471 1.03814 -0.238531 - 0.941437 1.26843 -0.211889 - 0.897966 1.2639 -0.189647 - 0.462174 0.704305 0.0321786 - 0.64609 1.27046 -0.0606963 - 0.249454 0.587817 0.140808 - 0.394691 1.2786 0.0680131 - 0.345312 1.27682 0.0932862 - 0.304382 1.28393 0.114255 - 0.266897 1.28037 0.133435 - 0.261923 1.28157 0.135984 - 0.22571 1.28139 0.154521 - 0.220577 1.2814 0.157149 - 0.0421085 1.16674 0.248249 - -0.0237295 1.23501 0.282105 - -0.0315815 1.19358 0.286031 - -0.263625 1.16619 0.404753 - -0.355738 1.27799 0.452157 - -0.421874 1.27462 0.486005 - -0.475319 1.27798 0.513371 - -0.497876 1.17807 0.524693 - -0.498592 1.12952 0.524951 - -0.49126 0.963835 0.520825 - -0.495501 0.952804 0.522971 - -0.490293 0.907048 0.520203 - -0.49203 0.892764 0.521059 - -0.489291 0.764781 0.51937 - -0.491843 0.741248 0.520623 - -0.489789 0.731645 0.51955 - -0.491501 0.701956 0.52036 - -0.496079 0.671538 0.522635 - -0.342983 -0.400877 0.437066 - -0.293881 -0.40555 0.412571 - -0.261243 -0.400536 0.396306 - -0.19483 -0.405138 0.363179 - -0.164587 -0.401992 0.348106 - -0.159865 -0.404634 0.345745 - -0.226574 -0.637839 0.378489 - -0.439392 -2.17198 0.481182 - -0.381084 -2.19339 0.452059 - -0.366337 -2.21093 0.444666 - -0.292296 -2.19094 0.40779 - -0.27584 -2.19882 0.399566 - -0.172811 -2.2169 0.348151 - 0.0071352 -0.420812 0.262434 - 0.0120813 -0.41994 0.259969 - 0.0251853 -0.41893 0.253437 - 0.0293338 -0.390808 0.251431 - 0.0547222 -0.353682 0.238854 - 0.0783696 -0.368966 0.227028 - 0.0953519 -0.38655 0.218521 - 0.0968608 -0.386171 0.217769 - 0.100757 -0.374871 0.215852 - 0.114359 -0.379129 0.209059 - 0.122263 -0.378612 0.205119 - 0.125217 -0.377585 0.203649 - 0.141127 -0.386383 0.195695 - 0.142635 -0.385781 0.194945 - 0.144406 -0.380803 0.194073 - 0.158598 -0.382134 0.186993 - 0.159747 -0.380523 0.186424 - 0.276672 -0.448063 0.127968 - 0.390193 -0.425897 0.0714096 - 0.396448 -0.400315 0.0683478 - 0.419668 -0.403159 0.0567623 - 0.422805 -0.399231 0.055207 - 0.450535 -0.404605 0.0413674 - 0.458708 -0.40141 0.0372993 - 0.463749 -0.402403 0.034783 - 0.57087 -0.407984 -0.0186457 - 0.692656 -0.40414 -0.0793659 - 0.730696 -0.404835 -0.0983362 - 0.774713 -0.406895 -0.12029 - 0.924169 -0.460403 -0.194936 - 1.01589 -0.399283 -0.240537 - 1.01473 -0.366219 -0.239884 - 1.01182 -0.281039 -0.238241 - 1.01402 -0.220424 -0.239203 - 1.01181 -0.189881 -0.238034 - 1.01079 -0.0864409 -0.237296 - 1.00851 0.00080356 -0.235964 - 1.00617 0.102185 -0.234568 - 1.00711 0.121753 -0.234992 - 1.00554 0.429564 -0.233524 - 0.716345 0.364017 -0.0894619 - 0.791815 0.421901 -0.126966 - 0.657339 0.360146 -0.0600469 - 0.775862 0.603964 -0.118604 - 0.997966 0.788362 -0.228944 - 1.0166 1.0223 -0.237715 - 1.01644 1.08657 -0.237491 - 1.02325 1.14273 -0.240759 - 1.00958 1.1672 -0.233888 - 0.998688 1.27123 -0.228225 - 0.972793 1.27087 -0.215313 - 0.538402 0.763786 0.00016347 - 0.619492 1.27575 -0.0391279 - 0.231015 0.609704 0.153099 - 0.226247 0.611745 0.155481 - 0.407104 1.27772 0.0667839 - 0.374128 1.2781 0.0832286 - 0.340184 1.27262 0.100143 - 0.330236 1.2757 0.10511 - 0.216679 1.28532 0.161757 - 0.19535 1.28007 0.172381 - 0.185991 1.28668 0.177063 - 0.180966 1.28748 0.17957 - 0.169034 1.27313 0.185488 --0.00819679 1.16158 0.273615 - -0.05451 1.17507 0.29674 - -0.081843 1.1705 0.310359 - -0.0946723 1.15997 0.316733 - -0.115325 1.22271 0.327172 - -0.163965 1.22186 0.351424 - -0.168735 1.22095 0.353801 - -0.183663 1.16502 0.36112 - -0.237923 1.17317 0.388195 - -0.277229 1.15423 0.407753 - -0.407491 1.27446 0.472977 - -0.471979 1.27672 0.505139 - -0.493323 1.27058 0.515768 - -0.495998 1.03775 0.516582 - -0.490365 0.86765 0.513393 - -0.495948 0.784251 0.515991 - -0.497944 0.780124 0.516977 - -0.488097 0.680781 0.511844 - -0.4938 0.624794 0.514563 - -0.493173 0.613189 0.514224 - -0.303633 -0.404695 0.413196 - -0.27239 -0.406407 0.398025 - -0.264666 -0.399169 0.394291 - -0.263097 -0.400536 0.393526 - -0.243484 -0.400674 0.384004 - -0.220967 -0.405791 0.373061 - -0.20688 -0.396827 0.366242 - -0.203285 -0.398143 0.364494 - -0.181929 -0.401611 0.354118 - -0.16157 -0.401075 0.344236 - -0.214873 -0.618062 0.369631 - -0.198075 -0.610527 0.361492 - -0.531451 -1.634 0.521065 - -0.520526 -1.84263 0.515297 - -0.350838 -2.21163 0.432097 - -0.285395 -2.19045 0.400372 - -0.268191 -2.19329 0.392013 - -0.182046 -2.207 0.350162 - -0.148266 -2.22247 0.333727 - -0.132887 -2.2549 0.326189 - -0.115181 -2.25626 0.31759 - -0.0881302 -2.248 0.304476 - 0.0198883 -0.416994 0.256105 - 0.0643487 -0.353268 0.234662 - 0.0729023 -0.362908 0.230488 - 0.0776512 -0.36503 0.228178 - 0.0908295 -0.379462 0.221748 - 0.0967772 -0.377991 0.218864 - 0.1085 -0.380942 0.213166 - 0.120667 -0.378157 0.207265 - 0.124166 -0.379057 0.205565 - 0.129177 -0.379381 0.203131 - 0.181731 -0.385165 0.177605 - 0.183242 -0.384367 0.176873 - 0.20324 -0.386581 0.167159 - 0.214821 -0.378294 0.161555 - 0.216304 -0.377335 0.160837 - 0.387764 -0.428785 0.0774824 - 0.410645 -0.40289 0.0664316 - 0.424969 -0.403195 0.0594767 - 0.445788 -0.405559 0.0493643 - 0.481694 -0.40575 0.031932 - 0.489844 -0.405518 0.027976 - 0.531502 -0.410312 0.00774097 - 0.536177 -0.406468 0.00547993 - 0.574967 -0.405286 -0.0133493 - 0.67997 -0.403014 -0.0643211 - 0.70611 -0.406006 -0.0770185 - 0.72284 -0.407154 -0.0851433 - 0.790398 -0.404189 -0.117935 - 0.863889 -0.422767 -0.153655 - 0.948539 -0.459673 -0.194832 - 1.02389 -0.462234 -0.231419 - 1.04296 -0.363789 -0.240457 - 1.04032 -0.314248 -0.239066 - 1.03785 -0.297569 -0.237833 - 1.03477 -0.17814 -0.236068 - 1.04067 -0.138714 -0.238845 - 1.03746 -0.0684668 -0.237132 - 1.04045 0.0653417 -0.238284 - 1.039 0.0751875 -0.237563 - 1.03543 0.200169 -0.235548 - 0.959039 0.227789 -0.198402 - 0.949325 0.234911 -0.19367 - 1.03561 0.309093 -0.235393 - 1.03851 0.374741 -0.236656 - 1.03843 0.396781 -0.23657 - 1.03453 0.411928 -0.234642 - 1.03465 0.434445 -0.234648 - 0.712344 0.327992 -0.0784131 - 0.723036 0.369977 -0.0835105 - 0.772807 0.409609 -0.107585 - 0.446267 0.280506 0.0506568 - 0.405486 0.285111 0.0704655 - 0.710163 0.529014 -0.0769075 - 0.724347 0.544916 -0.0837581 - 1.04437 1.08292 -0.237929 - 1.0425 1.10961 -0.236962 - 1.04748 1.25994 -0.239043 - 0.521996 0.743136 0.0149202 - 0.441557 0.697561 0.0538707 - 0.440841 0.723274 0.0542756 - 0.437059 0.744923 0.05616 - 0.680029 1.23636 -0.0607054 - 0.682999 1.26692 -0.062079 - 0.67482 1.27678 -0.0580863 - 0.277956 0.60494 0.13309 - 0.196296 0.55073 0.172614 - 0.391407 1.27567 0.0795032 - 0.372887 1.26855 0.0884781 - 0.357924 1.27358 0.0957538 - 0.327592 1.28203 0.110498 - 0.133871 1.17009 0.204298 - 0.0414022 1.16174 0.249171 - 0.0234623 1.23499 0.258043 - 0.0048811 1.16489 0.266908 --0.00897479 1.17057 0.273647 - -0.0138692 1.18142 0.276048 - -0.0323273 1.1786 0.285002 - -0.343051 1.27482 0.436067 - -0.469255 1.27726 0.497343 - -0.49611 1.1858 0.510177 - -0.501955 1.05428 0.512722 - -0.493954 0.876834 0.508443 - -0.309033 -0.405371 0.411618 - -0.291155 -0.403997 0.403171 - -0.28956 -0.405484 0.402414 - -0.217596 -0.397424 0.368419 - -0.213847 -0.402483 0.366636 - -0.209227 -0.402156 0.364453 - -0.203684 -0.400065 0.361838 - -0.191884 -0.402003 0.356257 - -0.171246 -0.401967 0.346502 - -0.165253 -0.401987 0.34367 - -0.151707 -0.406984 0.337256 - -0.166006 -0.467847 0.34388 - -0.211438 -0.597591 0.365066 - -0.193243 -0.592844 0.356477 - -0.190903 -0.593855 0.355369 - -0.518128 -2.13679 0.506613 - -0.490456 -2.17293 0.493455 - -0.464273 -2.17813 0.481069 - -0.327754 -2.2227 0.416446 - -0.279424 -2.19783 0.393659 - -0.199912 -2.19604 0.356082 - -0.149972 -2.22945 0.332405 - 0.019495 -0.412994 0.256327 - 0.0736829 -0.368825 0.230814 - 0.0885726 -0.375896 0.223761 - 0.099342 -0.375268 0.218672 - 0.131691 -0.381687 0.203368 - 0.134409 -0.379624 0.202089 - 0.137996 -0.38037 0.200391 - 0.153204 -0.38481 0.193194 - 0.154562 -0.378844 0.192565 - 0.16087 -0.377064 0.189588 - 0.162357 -0.37637 0.188887 - 0.169712 -0.381562 0.185399 - 0.187553 -0.388964 0.17695 - 0.202508 -0.383933 0.169893 - 0.213027 -0.377509 0.164935 - 0.280093 -0.442184 0.133095 - 0.303603 -0.459632 0.121944 - 1.15976 -1.53153 -0.285075 - 0.395726 -0.403292 0.0785286 - 0.40058 -0.404918 0.0762309 - 0.42234 -0.402491 0.0659516 - 0.427297 -0.40386 0.0636055 - 0.516431 -0.407647 0.0214692 - 0.531627 -0.404917 0.0142932 - 1.01671 -0.462476 -0.2151 - 1.07642 -0.436908 -0.243267 - 1.0755 -0.413403 -0.242781 - 1.07009 -0.35497 -0.240095 - 1.07031 -0.294784 -0.240063 - 1.06821 -0.283428 -0.239047 - 1.0669 -0.272363 -0.238401 - 1.06861 -0.209306 -0.239073 - 1.0695 -0.116275 -0.239288 - 1.06625 -0.0751558 -0.23766 - 1.06293 -0.0193352 -0.235966 - 1.05935 0.0712867 -0.234075 - 1.06274 0.10194 -0.235607 - 1.06164 0.214783 -0.234836 - 1.05902 0.224655 -0.23358 - 1.05813 0.229676 -0.233147 - 0.977495 0.231196 -0.195033 - 0.951832 0.234469 -0.182896 - 0.930592 0.238414 -0.172849 - 0.714473 0.335508 -0.0704883 - 0.815115 0.435409 -0.117835 - 0.655821 0.35609 -0.042722 - 0.654413 0.359163 -0.0420497 - 0.465153 0.291686 0.0472524 - 1.01943 0.850634 -0.213483 - 1.07107 0.91896 -0.237739 - 1.07111 1.07742 -0.237408 - 1.07836 1.19412 -0.240573 - 1.0712 1.22818 -0.237114 - 1.02802 1.27443 -0.216606 - 0.974987 1.2732 -0.191542 - 0.595323 0.795944 -0.0131553 - 0.50855 0.73351 0.0277188 - 0.451814 0.760656 0.054594 - 0.619773 1.27866 -0.0236434 - 0.262961 0.587764 0.14347 - 0.237978 0.58024 0.155262 - 0.232785 0.603082 0.157766 - 0.333295 1.27859 0.111756 - 0.239623 1.29013 0.156054 - 0.227666 1.28139 0.161686 - 0.045821 1.16762 0.247381 - 0.0413342 1.17374 0.249515 - -0.0208703 1.23721 0.279056 - -0.032832 1.1746 0.284571 - -0.120214 1.20319 0.325934 - -0.126173 1.17307 0.328684 - -0.162598 1.22768 0.34602 - -0.21585 1.19203 0.37111 - -0.269094 1.16523 0.396216 - -0.347735 1.28341 0.433646 - -0.384499 1.27514 0.451004 - -0.400179 1.27107 0.458405 - -0.41589 1.28383 0.465859 - -0.437082 1.27802 0.475863 - -0.445798 1.26987 0.479964 - -0.450805 1.26761 0.482325 - -0.47752 1.2758 0.49497 - -0.494579 1.06619 0.502569 - -0.490767 1.0047 0.500631 - -0.494034 0.980793 0.502122 - -0.496049 0.842716 0.50277 - -0.491719 0.761645 0.500544 - -0.487325 0.702374 0.498335 - -0.48893 0.673865 0.499031 - -0.491896 0.665891 0.500415 - -0.494138 0.639944 0.501417 - -0.495225 0.592647 0.501827 - -0.335002 -0.405527 0.419345 - -0.331515 -0.405037 0.417743 - -0.325814 -0.405444 0.415121 - -0.254884 -0.401645 0.38252 - -0.234694 -0.404023 0.373233 - -0.230467 -0.404768 0.371288 - -0.228861 -0.405953 0.370547 - -0.216854 -0.405014 0.365029 - -0.205176 -0.400065 0.359672 - -0.20157 -0.409448 0.357993 - -0.199945 -0.410495 0.357244 - -0.172577 -0.401967 0.34468 - -0.152247 -0.400723 0.335337 - -0.150657 -0.401533 0.334604 - -0.521018 -1.74562 0.501913 - -0.364157 -2.21081 0.428774 - -0.328124 -2.21186 0.412206 - -0.318602 -2.20856 0.407836 - -0.307066 -2.19139 0.402571 - -0.273187 -2.20418 0.386967 - 0.0124029 -0.425967 0.259586 - 0.0224537 -0.418959 0.254981 - 0.0664991 -0.360951 0.234859 - 0.0907725 -0.379462 0.223659 - 0.100834 -0.382074 0.219028 - 0.124265 -0.384348 0.208251 - 0.155517 -0.380701 0.193892 - 0.204733 -0.387463 0.17125 - 0.253317 -0.431823 0.148817 - 0.275515 -0.441338 0.138591 - 0.341904 -0.456786 0.108036 - 1.1706 -1.58068 -0.275416 - 0.433932 -0.40519 0.065841 - 0.654783 -0.408554 -0.0356993 - 0.882359 -0.413209 -0.140334 - 0.997672 -0.457152 -0.193443 - 1.02042 -0.46209 -0.203914 - 1.09828 -0.414545 -0.239602 - 1.10095 -0.324239 -0.240632 - 1.10135 -0.318774 -0.240805 - 1.09741 -0.246357 -0.238831 - 1.09564 -0.203034 -0.237924 - 1.09032 -0.0249055 -0.235086 - 1.09775 -0.0146997 -0.238481 - 1.09208 0.0576652 -0.235712 - 1.09399 0.0889015 -0.236521 - 1.08961 0.177193 -0.234313 - 1.0889 0.182339 -0.233976 - 1.09143 0.225247 -0.235043 - 1.10502 0.332779 -0.241056 - 1.10185 0.348694 -0.239566 - 1.0968 0.427313 -0.237069 - 1.09462 0.467783 -0.235976 - 0.718961 0.356421 -0.06352 - 0.748406 0.388543 -0.0769863 - 0.36757 0.248046 0.0977878 - 0.717591 0.525093 -0.062519 - 1.0329 0.827614 -0.206813 - 1.10115 0.957901 -0.237899 - 1.09691 1.08924 -0.235661 - 1.10517 1.17699 -0.239268 - 1.09774 1.18951 -0.235822 - 0.608645 0.796546 -0.0118352 - 0.444646 0.690542 0.0633272 - 0.43202 0.709326 0.0691734 - 0.660624 1.29018 -0.0346449 - 0.466594 0.959606 0.0538294 - 0.379347 1.28192 0.0946491 - 0.374263 1.28364 0.0969902 - 0.286742 1.28248 0.137224 - 0.123825 1.21247 0.211969 - 0.0786357 1.18015 0.232672 - 0.076534 1.23435 0.233758 - 0.0226937 1.24399 0.258531 - -0.0215266 1.23821 0.278848 - -0.154938 1.1999 0.340097 - -0.174807 1.17184 0.34917 - -0.267968 1.17337 0.392003 - -0.273381 1.15516 0.394451 - -0.277958 1.15374 0.396552 - -0.47062 1.28147 0.485407 - -0.486911 1.27706 0.492886 - -0.492472 1.15094 0.495165 - -0.496618 1.08706 0.49693 - -0.492806 1.01327 0.495016 - -0.49896 0.994541 0.497804 - -0.493693 0.955136 0.495296 - -0.495591 0.930587 0.496114 - -0.491684 0.914473 0.494283 - -0.493873 0.909466 0.495278 - -0.492992 0.873429 0.494794 - -0.493055 0.613005 0.494249 - -0.352626 -0.404758 0.421757 - -0.330871 -0.401408 0.412098 - -0.29713 -0.406289 0.397095 - -0.266099 -0.400313 0.38332 - -0.259676 -0.405653 0.380454 - -0.254811 -0.405857 0.378292 - -0.234938 -0.408915 0.369455 - -0.231275 -0.406785 0.367832 - -0.211905 -0.404949 0.359229 - -0.151728 -0.400624 0.3325 - -0.15436 -0.42128 0.333625 - -0.155005 -0.432988 0.333886 - -0.204182 -0.599135 0.355373 - -0.185423 -0.577112 0.347086 - -0.521603 -1.55555 0.49432 - -0.525003 -1.58621 0.495764 - -0.522943 -1.93216 0.494091 - -0.522087 -1.95961 0.493651 - -0.520771 -2.01845 0.492938 - -0.266891 -2.20852 0.379715 - -0.246046 -2.18436 0.370505 - -0.185245 -2.19506 0.343466 - 0.00105918 -0.443669 0.264518 - 0.0344126 -0.335445 0.249935 - 0.0400981 -0.340043 0.247398 - 0.0627877 -0.356459 0.237281 - 0.0781425 -0.36995 0.230429 - 0.091456 -0.375197 0.224501 - 0.0948489 -0.376419 0.222991 - 0.163178 -0.386065 0.192609 - 0.164717 -0.385362 0.191927 - 0.18345 -0.386069 0.183602 - 0.190393 -0.38462 0.18052 - 0.206198 -0.389229 0.173487 - 0.270744 -0.444174 0.144687 - 0.318649 -0.458298 0.12337 - 0.321672 -0.442201 0.122062 - 0.388132 -0.427675 0.0925636 - 0.385969 -0.403464 0.0935779 - 0.416535 -0.400306 0.0800031 - 0.627096 -0.40863 -0.013574 - 0.853507 -0.406884 -0.114172 - 1.06256 -0.461432 -0.207182 - 1.14289 -0.42935 -0.242802 - 1.13972 -0.368862 -0.241264 - 1.1387 -0.288129 -0.240633 - 1.13658 -0.215128 -0.239531 - 1.13904 -0.14986 -0.24048 - 1.13721 -0.100963 -0.239563 - 1.13652 0.00089002 -0.239032 - 1.12804 0.0274101 -0.235203 - 1.13353 0.0756109 -0.23754 - 1.12662 0.139216 -0.23433 - 1.12921 0.199079 -0.235349 - 0.929606 0.245066 -0.146559 - 1.13284 0.339477 -0.236656 - 1.13449 0.351498 -0.237364 - 1.13931 0.460013 -0.239266 - 0.915276 0.539901 -0.139546 - 1.03862 0.820365 -0.193736 - 1.13855 1.1962 -0.237317 - 1.137 1.25871 -0.236492 - 0.982413 1.2265 -0.167874 - 0.423224 0.697806 0.0794343 - 0.281542 0.593413 0.14216 - 0.22805 0.601392 0.165946 - 0.406961 1.27485 0.0879233 - 0.330399 1.27913 0.121952 - 0.313949 1.27865 0.12926 - 0.286954 1.27859 0.141255 - 0.150318 1.1862 0.201764 - 0.0961252 1.16186 0.225791 - -0.0340271 1.16761 0.283634 - -0.0577381 1.17307 0.294182 - -0.0762964 1.23168 0.302556 - -0.215518 1.19804 0.364343 - -0.252324 1.20522 0.380713 - -0.302415 1.21958 0.403001 - -0.353296 1.26639 0.425712 - -0.379902 1.27993 0.437564 - -0.498356 1.20951 0.490042 - -0.494743 1.09909 0.488195 - -0.491972 0.917768 0.486567 - -0.493377 0.885069 0.48712 - -0.493467 0.876719 0.487142 - -0.493122 0.768159 0.486751 - -0.492181 0.624044 0.486017 - -0.354377 -0.400877 0.417919 - -0.343078 -0.405991 0.413028 - -0.328013 -0.406352 0.406521 - -0.32166 -0.405906 0.403779 - -0.260198 -0.400335 0.377248 - -0.194063 -0.405752 0.348674 - -0.167336 -0.406428 0.33713 - -0.203136 -0.607735 0.352153 - -0.523611 -2.05176 0.487409 - -0.419366 -2.18641 0.442096 - -0.343432 -2.22299 0.409223 - -0.0735305 -2.24293 0.292618 - 0.0149169 -0.419996 0.258392 - 0.0233286 -0.41993 0.25476 - 0.0722149 -0.361922 0.233774 - 0.104059 -0.375022 0.219993 - 0.121113 -0.378157 0.212621 - 0.164647 -0.38444 0.193807 - 0.181497 -0.385049 0.186528 - 0.196763 -0.389195 0.179926 - 0.21568 -0.379244 0.171779 - 0.224881 -0.384983 0.167793 - 0.257267 -0.436107 0.153695 - 0.259013 -0.434957 0.152943 - 0.271616 -0.435831 0.147498 - 0.308002 -0.465965 0.131719 - 0.34163 -0.491556 0.117141 - 0.312116 -0.43084 0.130019 - 0.325653 -0.438479 0.124156 - 0.329655 -0.440165 0.122424 - 0.380464 -0.406571 0.100554 - 0.441324 -0.401827 0.0742816 - 0.448718 -0.401665 0.0710886 - 0.468752 -0.402042 0.0624358 - 0.47036 -0.399888 0.0617461 - 0.513124 -0.403475 0.0432702 - 0.658208 -0.402991 -0.0193857 - 0.687861 -0.404769 -0.0321954 - 0.751152 -0.407101 -0.0595338 - 0.807908 -0.405893 -0.084042 - 1.17887 -0.441194 -0.244322 - 1.17899 -0.386179 -0.244255 - 1.16403 -0.0536597 -0.237071 - 1.16485 -0.0263817 -0.237367 - 1.16329 0.07183 -0.236479 - 1.16176 0.08266 -0.235796 - 1.15963 0.181418 -0.234657 - 0.933293 0.249662 -0.136763 - 1.17158 0.373541 -0.2394 - 1.16834 0.408504 -0.237926 - 1.16422 0.425207 -0.236109 - 1.16827 0.463669 -0.237777 - 1.08817 0.478323 -0.203152 - 0.793873 0.427307 -0.0761657 - 1.16376 0.700612 -0.235312 - 0.401488 0.252158 0.0929102 - 0.729424 0.534118 -0.0480997 - 0.928565 0.709178 -0.13372 - 1.0359 0.822255 -0.17983 - 1.16591 1.06055 -0.235454 - 1.16808 1.1007 -0.236308 - 1.16296 1.12504 -0.234041 - 1.08732 1.27338 -0.201051 - 1.08036 1.27623 -0.19804 - 0.579673 0.74429 0.0170302 - 0.543943 0.742082 0.032456 - 0.535759 0.743875 0.0359945 - 0.490658 0.73761 0.0554582 - 0.438052 0.700303 0.0780957 - 0.6002 1.04773 0.0088263 - 0.674428 1.2796 -0.0227246 - 0.667517 1.27921 -0.0197412 - 0.261902 0.586208 0.15392 - 0.238506 0.590669 0.164034 - 0.23947 0.616111 0.163673 - 0.391572 1.27555 0.099422 - 0.36464 1.27934 0.111061 - 0.292459 1.27534 0.142225 - 0.284058 1.28669 0.145878 - 0.187144 1.27975 0.187716 - 0.0825409 1.17086 0.232654 - 0.0779547 1.17316 0.234639 - -0.0279203 1.24001 0.280508 - -0.158692 1.20681 0.336912 - -0.221047 1.16844 0.363757 - -0.256153 1.19227 0.37897 - -0.269282 1.16275 0.384576 - -0.273937 1.16137 0.386583 - -0.4397 1.27835 0.458425 - -0.444818 1.27616 0.460631 - -0.450267 1.27488 0.462981 - -0.495591 1.10689 0.482189 - -0.49166 0.81296 0.479851 - -0.495417 0.739928 0.481314 - -0.492467 0.672452 0.479894 - -0.489288 0.595868 0.478354 - -0.489168 0.590532 0.47829 - -0.332557 -0.402335 0.404209 - -0.299568 -0.404761 0.390362 - -0.27642 -0.395631 0.380669 - -0.197661 -0.410105 0.347592 - -0.184999 -0.406248 0.342288 - -0.160449 -0.401789 0.331997 - -0.166111 -0.465918 0.334233 - -0.206528 -0.613319 0.350872 - -0.191265 -0.593973 0.34451 - -0.526284 -1.66136 0.482762 - -0.496732 -2.18989 0.469216 - -0.280106 -2.21507 0.37827 - -0.226001 -2.21771 0.355562 - -0.131804 -2.29251 0.315877 - -0.122579 -2.29318 0.312005 - 0.00256125 -0.423752 0.263553 - 0.0128514 -0.416986 0.259251 - 0.0868182 -0.368065 0.228322 - 0.0882986 -0.367726 0.227701 - 0.0940482 -0.380693 0.225261 - 0.10147 -0.377784 0.222153 - 0.118909 -0.382018 0.214827 - 0.120707 -0.382486 0.214071 - 0.132298 -0.381687 0.20921 - 0.136173 -0.388717 0.207569 - 0.136847 -0.385305 0.207293 - 0.141181 -0.382613 0.205481 - 0.14579 -0.380803 0.203551 - 0.168617 -0.389253 0.193955 - 0.170274 -0.384126 0.19327 - 0.190075 -0.390765 0.184948 - 0.194367 -0.387365 0.183155 - 0.256518 -0.433536 0.156977 - 0.26 -0.431243 0.155521 - 0.293267 -0.458065 0.141505 - 0.34322 -0.492367 0.120471 - 1.27069 -1.64951 -0.271186 - 0.380959 -0.423897 0.104785 - 0.430921 -0.411782 0.0838484 - 0.432576 -0.409815 0.0831585 - 0.454449 -0.405559 0.07399 - 0.473222 -0.40457 0.0661157 - 0.477182 -0.400853 0.064462 - 0.488525 -0.399807 0.0597049 - 0.548735 -0.403951 0.0344332 - 0.568814 -0.407597 0.0260005 - 0.603378 -0.405198 0.0115033 - 0.669485 -0.404397 -0.016232 - 0.959186 -0.40724 -0.137791 - 1.10509 -0.45835 -0.199121 - 1.15272 -0.466059 -0.219122 - 1.20357 -0.455044 -0.240433 - 1.20539 -0.449419 -0.241186 - 1.20897 -0.438146 -0.242664 - 1.21225 -0.408017 -0.243972 - 1.20568 -0.350735 -0.24109 - 1.20625 -0.332818 -0.241292 - 1.20682 -0.273505 -0.241404 - 1.2002 -0.248645 -0.23857 - 1.19945 -0.213794 -0.238183 - 1.20286 -0.197129 -0.239575 - 1.19412 -0.138966 -0.235782 - 1.20181 -0.0271198 -0.238767 - 1.1937 0.0176431 -0.235266 - 1.20262 0.0346244 -0.238971 - 1.19773 0.0849083 -0.23681 - 1.19431 0.129569 -0.235279 - 1.19585 0.175022 -0.235828 - 1.19514 0.180601 -0.235518 - 1.19365 0.191749 -0.234869 - 1.19216 0.208605 -0.234206 - 1.20025 0.25051 -0.23751 - 1.19765 0.279095 -0.236358 - 0.93078 0.243397 -0.124461 - 1.20411 0.39476 -0.238818 - 1.20023 0.418105 -0.237137 - 1.21168 0.440991 -0.241894 - 1.1941 0.453235 -0.234491 - 1.20173 0.494406 -0.237599 - 0.738628 0.333081 -0.0436434 - 0.722072 0.365629 -0.0366264 - 1.18407 0.717395 -0.229708 - 0.655798 0.472696 -0.00858694 - 1.19003 0.968788 -0.231665 - 1.20505 1.24576 -0.237363 - 0.606814 0.743635 0.0125534 - 0.563491 0.73976 0.0307225 - 0.501463 0.758761 0.0567893 - 0.423857 0.707592 0.0892401 - 0.565482 1.09719 0.0306625 - 0.299789 0.610127 0.141085 - 0.337757 1.27859 0.126604 - 0.252049 1.28501 0.16258 - 0.2029 1.27723 0.183185 - 0.18232 1.28054 0.191827 - 0.151228 1.19116 0.204679 - 0.0968732 1.17482 0.227449 - 0.0829688 1.18084 0.233296 - 0.0492908 1.16848 0.2474 - -0.124085 1.19724 0.320207 - -0.138706 1.15975 0.326261 - -0.16991 1.20706 0.339456 - -0.182256 1.16205 0.344538 - -0.217037 1.21677 0.35925 - -0.365737 1.27506 0.421768 - -0.394341 1.27514 0.43377 - -0.436676 1.27958 0.451542 - -0.479283 1.28147 0.469424 - -0.492553 1.02672 0.474439 - -0.490962 1.01287 0.473742 - -0.495512 0.91435 0.475437 - -0.497196 0.840984 0.475984 - -0.492982 0.781123 0.474086 - -0.494515 0.776262 0.474719 - -0.492788 0.766535 0.473973 - -0.494243 0.76169 0.474573 - -0.494579 0.755234 0.4747 - -0.495066 0.72234 0.474833 - -0.49369 0.652924 0.474106 - -0.496096 0.590304 0.474979 - -0.501261 0.580818 0.477126 - -0.340207 -0.401913 0.403186 - -0.323876 -0.400607 0.396531 - -0.249744 -0.409783 0.366289 - -0.241703 -0.404847 0.363021 - -0.219876 -0.403596 0.354125 - -0.169298 -0.405531 0.333501 - -0.166016 -0.407257 0.332159 - -0.158905 -0.439318 0.329191 - -0.206203 -0.601113 0.348124 - -0.534729 -1.70262 0.479681 - -0.520319 -1.83632 0.473518 - -0.459529 -2.17976 0.447992 - -0.450718 -2.18198 0.444396 - -0.395831 -2.18457 0.422013 - -0.317745 -2.21113 0.390121 - -0.283693 -2.22991 0.376198 - -0.0952641 -2.28594 0.299257 - -0.0746028 -2.23294 0.290948 - 0.0175067 -0.416994 0.257318 - 0.0226253 -0.42093 0.255223 - 0.0353875 -0.345339 0.250183 - 0.0379194 -0.341149 0.24916 - 0.0420529 -0.340804 0.247476 - 0.0809417 -0.370332 0.231558 - 0.0922544 -0.380082 0.226924 - 0.106316 -0.384713 0.221182 - 0.114607 -0.378167 0.217816 - 0.132691 -0.382636 0.210434 - 0.139469 -0.382258 0.207671 - 0.14441 -0.381413 0.205659 - 0.151219 -0.380794 0.202884 - 0.167584 -0.376792 0.196221 - 0.182121 -0.380644 0.190286 - 0.196712 -0.38741 0.184323 - 0.198989 -0.383911 0.183402 - 0.243082 -0.412336 0.165364 - 0.303859 -0.48337 0.140433 - 0.315483 -0.475053 0.135712 - 0.327056 -0.433843 0.131082 - 1.27872 -1.7137 -0.259662 - 1.31245 -1.56794 -0.273101 - 0.385089 -0.423621 0.107445 - 0.659704 -0.409077 -0.00448015 - 0.690447 -0.407468 -0.0170102 - 0.696138 -0.406705 -0.0193289 - 0.700213 -0.404936 -0.0209863 - 0.789023 -0.411163 -0.0572066 - 0.905717 -0.407224 -0.104773 - 0.96621 -0.408719 -0.129438 - 1.10509 -0.450688 -0.186147 - 1.24611 -0.443578 -0.243624 - 1.24684 -0.411819 -0.243853 - 1.24316 -0.203034 -0.241901 - 1.24652 -0.162217 -0.243183 - 1.23399 -0.0622313 -0.237861 - 1.23961 -0.0336457 -0.240089 - 1.22585 -0.0275626 -0.234467 - 1.23757 0.133808 -0.238895 - 1.23742 0.263354 -0.238555 - 1.24292 0.393471 -0.240518 - 1.23741 0.435942 -0.238179 - 1.2192 0.532566 -0.230547 - 0.711617 0.350896 -0.0240032 - 0.740089 0.386243 -0.0355345 - 0.613558 0.343652 0.0159586 - 0.43656 0.2733 0.0879665 - 0.372004 0.245287 0.114225 - 0.369779 0.250847 0.115144 - 1.15038 0.924072 -0.201645 - 1.2292 0.997264 -0.233621 - 1.23619 1.03979 -0.236378 - 1.23271 1.04615 -0.234944 - 1.23096 1.13153 -0.234046 - 1.23657 1.16717 -0.236258 - 1.1244 1.27333 -0.190297 - 0.62342 0.748556 0.0128124 - 0.573611 0.744165 0.0331096 - 0.561924 0.858342 0.0381207 - 0.41665 0.686198 0.0969752 - 0.682155 1.27211 -0.0100023 - 0.316425 0.617071 0.137686 - 0.310081 0.610493 0.140259 - 0.303796 0.603867 0.142807 - 0.251087 0.598511 0.164284 - 0.250851 0.612715 0.164411 - 0.244093 0.617836 0.167177 - 0.240916 0.617042 0.16847 - 0.276889 0.785144 0.154168 - 0.0305 1.19991 0.255513 --0.00776287 1.1737 0.271056 - -0.0321525 1.18983 0.281034 - -0.0361614 1.17161 0.282629 - -0.0407981 1.16935 0.284515 - -0.221951 1.15867 0.358346 - -0.344931 1.27447 0.408733 - -0.374076 1.27704 0.42062 - -0.498997 1.21985 0.471426 - -0.492314 1.07683 0.468392 - -0.493072 1.012 0.468561 - -0.496347 0.938772 0.469738 - -0.493391 0.822753 0.468282 - -0.493313 0.770566 0.468138 - -0.49057 0.745562 0.466966 - -0.491428 0.713618 0.467247 - -0.490462 0.639863 0.466693 - -0.488935 0.626766 0.466043 - -0.335921 -0.405444 0.397155 - -0.293465 -0.406797 0.38036 - -0.288301 -0.403575 0.378325 - -0.274923 -0.403478 0.373034 - -0.272152 -0.403247 0.371938 - -0.270514 -0.404592 0.371287 - -0.255683 -0.401483 0.365429 - -0.252386 -0.407712 0.364111 - -0.236776 -0.402279 0.357949 - -0.224903 -0.405858 0.353245 - -0.202624 -0.398242 0.34445 - -0.194497 -0.403256 0.341225 - -0.174975 -0.401992 0.333506 - -0.155714 -0.43369 0.32582 - -0.508957 -1.50845 0.463221 - -0.528733 -1.88468 0.470233 - -0.518893 -1.9714 0.466155 - -0.496503 -2.1676 0.456877 - -0.430004 -2.20595 0.430494 - -0.375122 -2.2118 0.408774 - -0.357161 -2.21536 0.401663 - -0.347201 -2.21117 0.397733 - -0.328785 -2.21152 0.390448 - -0.309228 -2.20378 0.38273 - -0.200668 -2.20999 0.339779 - -0.191699 -2.21098 0.33623 - 0.00863871 -0.417941 0.26085 - 0.0103345 -0.417967 0.260179 - 0.033299 -0.33844 0.251268 - 0.0387203 -0.337052 0.249126 - 0.0403065 -0.339929 0.248493 - 0.0638629 -0.359205 0.239135 - 0.0655949 -0.360951 0.238446 - 0.0670591 -0.360711 0.237867 - 0.0957517 -0.374094 0.22649 - 0.104286 -0.383197 0.223095 - 0.107997 -0.378042 0.221639 - 0.109771 -0.378568 0.220936 - 0.111306 -0.378121 0.220329 - 0.136483 -0.383411 0.21036 - 0.165849 -0.380971 0.198751 - 0.172644 -0.38871 0.196047 - 0.182055 -0.384143 0.192334 - 0.182423 -0.380644 0.192196 - 0.222017 -0.380789 0.176536 - 0.267105 -0.44147 0.158573 - 0.269384 -0.441133 0.157672 - 0.352662 -0.498899 0.12461 - 1.31495 -1.62093 -0.258402 - 0.404066 -0.403292 0.104485 - 0.412048 -0.404442 0.101325 - 0.44305 -0.406514 0.0890592 - 0.448441 -0.404449 0.0869316 - 0.475576 -0.403938 0.0762001 - 0.477213 -0.401774 0.0755576 - 0.515975 -0.405231 0.0602192 - 0.529868 -0.405236 0.0547242 - 0.587696 -0.406881 0.0318489 - 0.612399 -0.400682 0.0220918 - 0.625091 -0.405234 0.0170621 - 0.75119 -0.406932 -0.0328154 - 0.802707 -0.403203 -0.053183 - 0.881049 -0.408916 -0.0841804 - 0.998163 -0.404904 -0.130492 - 1.2321 -0.462372 -0.223141 - 1.27362 -0.464904 -0.239568 - 1.28632 -0.384452 -0.244417 - 1.29095 -0.197884 -0.245848 - 1.29083 -0.191758 -0.245786 - 1.28612 -0.160738 -0.243859 - 1.28554 -0.14859 -0.243602 - 1.28798 -0.142837 -0.244556 - 1.28684 -0.100609 -0.244013 - 1.2818 -0.0763394 -0.241967 - 1.27773 -0.0642159 -0.240333 - 1.27361 0.00098302 -0.238564 - 0.943187 0.240239 -0.107361 - 1.27394 0.427684 -0.237775 - 0.720564 0.338142 -0.0190999 - 0.764458 0.402162 -0.0363228 - 0.376817 0.257484 0.116683 - 0.974678 0.736498 -0.118748 - 1.27124 1.19568 -0.235054 - 1.15501 1.2698 -0.188926 - 0.619426 0.741032 0.021768 - 0.569023 0.742101 0.0417055 - 0.423694 0.689368 0.0990716 - 0.417917 0.686198 0.10135 - 0.620572 1.10508 0.0220979 - 0.679491 1.26253 -0.00086677 - 0.263356 0.591926 0.162278 - 0.237012 0.604943 0.172725 - 0.275992 0.780437 0.157686 - 0.406333 1.2748 0.107197 - 0.247432 1.28317 0.170063 - 0.0968368 1.17682 0.229397 - -0.0370832 1.1776 0.282365 - -0.0797933 1.17145 0.299245 - -0.142869 1.17459 0.324199 - -0.180731 1.16692 0.339157 - -0.209179 1.18749 0.350453 - -0.270248 1.167 0.374562 - -0.31615 1.2644 0.392927 - -0.380748 1.27329 0.418495 - -0.406633 1.28166 0.428751 - -0.428677 1.27727 0.43746 - -0.434516 1.27704 0.439769 - -0.440361 1.27678 0.44208 - -0.488798 1.27726 0.461239 - -0.4947 1.08814 0.463167 - -0.494605 0.969176 0.462873 - -0.490089 0.8697 0.460873 - -0.495253 0.625882 0.462391 - -0.495902 0.599743 0.462591 - -0.332949 -0.403413 0.391755 - -0.329867 -0.410483 0.390558 - -0.171632 -0.401075 0.329918 - -0.160979 -0.404349 0.325827 - -0.151039 -0.409137 0.322006 - -0.518202 -1.86807 0.459636 - -0.462482 -2.21511 0.437532 - -0.292684 -2.20475 0.372461 - -0.247235 -2.20741 0.355032 - -0.227215 -2.27646 0.347209 - 0.00986084 -0.421967 0.260296 - 0.0132993 -0.421996 0.258978 - 0.0271374 -0.424791 0.253667 - 0.0370372 -0.337159 0.25006 - 0.0384107 -0.337052 0.249533 - 0.07781 -0.362771 0.234374 - 0.12266 -0.382944 0.217138 - 0.197725 -0.383881 0.188359 - 0.211734 -0.383852 0.182989 - 0.223404 -0.382516 0.178517 - 0.281087 -0.451411 0.156257 - 0.288944 -0.460278 0.153226 - 0.308371 -0.478963 0.145738 - 0.329697 -0.490109 0.137539 - 0.318524 -0.427216 0.141957 - 1.34004 -1.64591 -0.25226 - 0.385116 -0.399546 0.116487 - 0.388361 -0.396069 0.115251 - 0.446061 -0.404502 0.0931133 - 0.447706 -0.402483 0.0924868 - 0.489083 -0.407106 0.0766149 - 0.570827 -0.401067 0.0452908 - 0.813095 -0.402486 -0.0475878 - 0.871475 -0.412516 -0.0699895 - 0.916646 -0.409174 -0.0872992 - 0.931166 -0.405696 -0.0928582 - 0.995857 -0.413016 -0.117673 - 1.01917 -0.406652 -0.126596 - 1.3231 -0.454163 -0.243212 - 1.31949 -0.360283 -0.241627 - 1.32008 -0.315243 -0.241756 - 1.32941 -0.178053 -0.24504 - 1.31169 -0.0292919 -0.237928 - 1.30908 -0.0171352 -0.236904 - 1.30913 0.0554602 -0.236767 - 1.31775 0.104691 -0.239964 - 1.31414 0.16568 -0.238451 - 1.31437 0.246375 -0.238366 - 0.955669 0.242581 -0.100863 - 1.03719 0.304377 -0.131984 - 1.30755 0.397923 -0.235425 - 1.28494 0.489277 -0.226562 - 1.30446 0.565946 -0.233883 - 0.720634 0.329118 -0.0105749 - 0.600371 0.344362 0.0355615 - 0.91551 0.546305 -0.084817 - 0.837065 0.622801 -0.0545808 - 0.787391 0.590594 -0.0356067 - 1.29172 1.07883 -0.227898 - 1.29741 1.23755 -0.229742 - 1.26404 1.27029 -0.216879 - 0.654088 0.747357 0.0158317 - 0.620253 0.739528 0.0287859 - 0.859743 1.24573 -0.0619401 - 0.852819 1.25846 -0.0592586 - 0.429771 0.690814 0.101704 - 0.473483 0.868099 0.0853268 - 0.292994 0.60381 0.153952 - 0.248034 0.602549 0.171185 - 0.229095 0.605198 0.178452 - 0.272217 0.767257 0.162267 - 0.285611 0.818421 0.157242 - 0.403747 1.28137 0.112945 - 0.352177 1.28032 0.132713 - 0.210352 1.28423 0.187091 - 0.188325 1.27975 0.195526 - 0.134216 1.16512 0.216023 - 0.129468 1.16567 0.217845 - 0.0865295 1.16755 0.23431 - -0.0250015 1.22922 0.277198 - -0.0701714 1.22854 0.294513 - -0.0947488 1.168 0.303805 - -0.214453 1.20807 0.34978 - -0.259456 1.20133 0.367018 - -0.484662 1.27593 0.453512 - -0.497593 1.20439 0.458316 - -0.495241 1.13268 0.457261 - -0.492344 1.06614 0.456008 - -0.498923 1.02407 0.45844 - -0.493186 0.971563 0.456128 - -0.493714 0.792412 0.455947 - -0.490688 0.738308 0.454671 - -0.48827 0.647741 0.45355 - -0.490906 0.64538 0.454555 - -0.489102 0.620732 0.453811 - -0.494767 0.565003 0.455863 - -0.360545 -0.400512 0.397904 - -0.350684 -0.403832 0.394233 - -0.273557 -0.400866 0.365584 - -0.253721 -0.405261 0.358205 - -0.223107 -0.398264 0.346846 - -0.215883 -0.405406 0.344147 - -0.186495 -0.403662 0.333232 - -0.15642 -0.400515 0.322065 - -0.219 -0.632864 0.34482 - -0.210256 -0.641793 0.341552 - -0.534662 -1.63242 0.459965 - -0.527014 -1.75261 0.456867 - -0.516005 -2.11289 0.452009 - -0.485215 -2.22128 0.440338 - -0.404406 -2.19731 0.410366 - -0.258502 -2.21311 0.356124 - -0.201266 -2.19109 0.334907 - -0.176423 -2.2178 0.32562 - 0.00117561 -0.410759 0.263492 - 0.0249762 -0.421846 0.254626 - 0.0341939 -0.341346 0.251373 - 0.0633145 -0.358215 0.240518 - 0.0706289 -0.356991 0.237803 - 0.0771446 -0.359822 0.235376 - 0.0833836 -0.368721 0.233039 - 0.101279 -0.38499 0.226356 - 0.120051 -0.37961 0.219393 - 0.123867 -0.375237 0.217984 - 0.131359 -0.383184 0.215184 - 0.147248 -0.378312 0.209291 - 0.190826 -0.381033 0.193094 - 0.208848 -0.393668 0.186372 - 0.212105 -0.383852 0.185183 - 0.275229 -0.440421 0.16161 - 0.584402 -0.90072 0.0457603 - 1.3059 -1.62621 -0.223845 - 0.373158 -0.439717 0.125228 - 0.374336 -0.437291 0.124795 - 0.385947 -0.439653 0.120476 - 0.39475 -0.401697 0.117287 - 0.425838 -0.401657 0.105737 - 0.444286 -0.40519 0.0988748 - 0.579599 -0.406094 0.0486003 - 0.642041 -0.409674 0.0253936 - 0.667232 -0.409584 0.0160344 - 0.692638 -0.404541 0.00660604 - 0.755478 -0.406475 -0.0167451 - 0.923175 -0.405728 -0.0790479 - 1.02884 -0.409128 -0.118312 - 1.2732 -0.46133 -0.209211 - 1.35546 -0.463721 -0.239778 - 1.36551 -0.425827 -0.24343 - 1.36013 -0.383561 -0.241341 - 1.36621 -0.358448 -0.243549 - 1.36615 -0.305414 -0.243412 - 1.36438 -0.246373 -0.242627 - 1.35781 -0.0552574 -0.239782 - 1.35832 0.158027 -0.239514 - 1.35766 0.16428 -0.239257 - 1.35814 0.17702 -0.239407 - 1.35645 0.272805 -0.238574 - 1.35424 0.304797 -0.237685 - 1.35482 0.311454 -0.237885 - 0.930951 0.262634 -0.0805108 - 1.32765 0.409287 -0.227585 - 1.35833 0.425643 -0.238947 - 1.28105 0.472768 -0.210134 - 1.2866 0.494862 -0.21215 - 1.34466 0.581498 -0.233537 - 1.26552 0.560539 -0.204177 - 0.708969 0.338098 0.00212312 - 0.707582 0.341325 0.0026454 - 0.71155 0.351179 0.00119194 - 0.714566 0.360697 9.191e-05 - 0.379516 0.243515 0.124323 - 0.375481 0.250268 0.125836 - 0.388105 0.271561 0.121192 - 0.386642 0.275596 0.121744 - 0.376658 0.288672 0.125481 - 1.27129 1.08655 -0.205201 - 1.26152 1.17778 -0.201374 - 1.25712 1.2262 -0.199636 - 1.177 1.23011 -0.169862 - 0.768909 0.819394 -0.0191195 - 0.734155 0.788488 -0.00627342 - 0.648694 0.745149 0.0253856 - 0.598508 0.736207 0.0440121 - 0.58943 0.74429 0.047402 - 0.580374 0.74572 0.0507697 - 0.528659 0.821057 0.0701443 - 0.334759 0.622723 0.14176 - 0.309503 0.610982 0.151119 - 0.304875 0.60789 0.152832 - 0.27998 0.574203 0.162009 - 0.270949 0.579953 0.165377 - 0.245656 0.595156 0.174806 - 0.369804 1.27934 0.130141 - 0.342578 1.28342 0.140265 - 0.302847 1.28083 0.155021 - 0.291517 1.27956 0.159228 - 0.1938 1.27893 0.195531 - 0.140287 1.17648 0.215194 - 0.0530528 1.17331 0.247598 - -0.0044298 1.1658 0.268938 - -0.178082 1.16586 0.333455 - -0.282464 1.16234 0.372229 - -0.49691 1.23985 0.452067 - -0.493209 1.21645 0.450642 - -0.489781 1.0789 0.449075 - -0.500003 1.05425 0.452821 - -0.495844 0.933408 0.451017 - -0.491002 0.90628 0.449161 - -0.489808 0.812646 0.448517 - -0.492521 0.717579 0.449323 - -0.487609 0.66719 0.44739 - -0.491865 0.660937 0.448958 - -0.491999 0.589428 0.448855 - -0.494406 0.587062 0.449744 - -0.353823 -0.398277 0.391013 - -0.337104 -0.404148 0.384989 - -0.309248 -0.406289 0.374968 - -0.229627 -0.403045 0.346345 - -0.210475 -0.401515 0.339462 - -0.176749 -0.398426 0.327341 - -0.170179 -0.401902 0.324971 - -0.166873 -0.403595 0.323779 - -0.16216 -0.458278 0.321968 - -0.207824 -0.62297 0.338037 - -0.530799 -1.68249 0.45192 - -0.528303 -1.74881 0.450882 - -0.517578 -2.00424 0.446483 - -0.261012 -2.1494 0.353919 - -0.254887 -2.17246 0.351667 - -0.237066 -2.25644 0.345081 - -0.0982567 -2.28095 0.295116 - 0.0430014 -0.349641 0.248427 - 0.048051 -0.342089 0.246628 - 0.0609683 -0.353489 0.241959 - 0.0713692 -0.362908 0.238199 - 0.0786308 -0.360509 0.235593 - 0.084755 -0.368396 0.233374 - 0.104088 -0.375991 0.226406 - 0.108131 -0.379009 0.224946 - 0.119017 -0.382018 0.221025 - 0.123164 -0.378612 0.219541 - 0.145206 -0.382353 0.211607 - 0.15753 -0.381629 0.207177 - 0.16222 -0.379599 0.205495 - 0.164505 -0.380752 0.204671 - 0.184411 -0.383357 0.197508 - 0.19077 -0.384547 0.195219 - 0.203042 -0.393678 0.190787 - 0.204371 -0.383937 0.190329 - 0.218885 -0.376562 0.185126 - 0.247084 -0.415772 0.174903 - 0.280348 -0.448029 0.162873 - 0.313114 -0.429028 0.151132 - 1.28929 -1.61383 -0.202399 - 0.384728 -0.414627 0.125412 - 0.423982 -0.402212 0.111323 - 0.441061 -0.404526 0.105177 - 0.444129 -0.403865 0.104075 - 0.498995 -0.40575 0.0843428 - 0.530864 -0.405864 0.0728833 - 0.596563 -0.405286 0.0492605 - 0.7064 -0.403014 0.00977036 - 0.877312 -0.407696 -0.051696 - 0.896166 -0.40684 -0.0584736 - 1.39829 -0.43461 -0.239084 - 1.40987 -0.417211 -0.243214 - 1.41053 -0.403463 -0.243421 - 1.40881 -0.341073 -0.24267 - 1.40466 -0.279458 -0.241046 - 1.40754 -0.174172 -0.241858 - 1.40267 -0.0375651 -0.239817 - 1.40686 -0.01184 -0.241268 - 1.39738 0.058819 -0.237708 - 1.40531 0.0720815 -0.240532 - 1.40388 0.13677 -0.239881 - 1.40331 0.143211 -0.239662 - 1.40144 0.16252 -0.238949 - 1.40307 0.182292 -0.239492 - 1.41023 0.222791 -0.24198 - 1.40168 0.307755 -0.238727 - 0.92372 0.268742 -0.0669455 - 1.01972 0.312225 -0.101371 - 1.28336 0.485213 -0.195804 - 0.715508 0.340174 0.00807482 - 0.708974 0.352694 0.0104509 - 0.717051 0.364828 0.00757253 - 0.66295 0.363214 0.0270227 - 0.375893 0.247504 0.129996 - 0.348557 0.263169 0.139859 - 0.74903 0.644277 -0.0033327 - 0.607018 0.744608 0.047945 - 0.58331 0.747275 0.0564755 - 0.591215 0.771313 0.0536843 - 0.347102 0.631943 0.141166 - 0.261571 0.563913 0.171776 - 0.247919 0.599777 0.176761 - 0.253411 1.27814 0.176228 - 0.205278 1.28216 0.193544 - 0.125735 1.17713 0.221923 - 0.122795 1.19854 0.223026 - 0.0428271 1.16162 0.251702 - 0.0142035 1.189 0.262052 - -0.0212297 1.23239 0.274886 - -0.0782335 1.24807 0.295416 - -0.1973 1.18369 0.338093 - -0.257315 1.20164 0.359712 - -0.262247 1.20036 0.361482 - -0.495039 1.2745 0.445346 - -0.498783 1.26845 0.44668 - -0.496858 1.24864 0.445946 - -0.498345 1.1811 0.446337 - -0.49643 1.1633 0.44561 - -0.493408 1.13054 0.444454 - -0.498138 1.1159 0.446124 - -0.493833 0.944206 0.444211 - -0.487348 0.913549 0.441814 - -0.495173 0.88294 0.444563 - -0.492358 0.869517 0.443522 - -0.490895 0.842156 0.442938 - -0.491804 0.8356 0.443251 - -0.49607 0.826691 0.444766 - -0.497268 0.805428 0.445151 - -0.489914 0.764697 0.44242 - -0.487974 0.676554 0.441535 - -0.494565 0.616114 0.443777 - -0.321238 -0.404747 0.375325 - -0.305781 -0.396416 0.369967 - -0.249994 -0.402809 0.350553 - -0.248332 -0.404023 0.349972 - -0.214829 -0.403044 0.338323 - -0.210062 -0.402552 0.336666 - -0.198205 -0.405111 0.332538 - -0.193056 -0.403535 0.33075 - -0.185067 -0.404629 0.32797 - -0.178774 -0.404667 0.325781 - -0.156106 -0.399482 0.317909 - -0.153949 -0.403781 0.31715 - -0.530619 -1.82869 0.445125 - -0.512707 -2.081 0.438361 - -0.475456 -2.24435 0.425061 - -0.402764 -2.21787 0.399837 - -0.264823 -2.16822 0.351972 - -0.256379 -2.17345 0.349024 - -0.254093 -2.23023 0.348109 - -0.178089 -2.21183 0.321716 - -0.117778 -2.27884 0.300601 - 0.0447664 -0.340401 0.248178 - 0.0562404 -0.35312 0.244161 - 0.0754884 -0.361095 0.237451 - 0.0752546 -0.350974 0.237553 - 0.0942695 -0.376419 0.230887 - 0.104713 -0.378899 0.22725 - 0.108314 -0.379975 0.225995 - 0.109879 -0.379534 0.225452 - 0.12269 -0.382944 0.22099 - 0.136809 -0.378112 0.21609 - 0.181448 -0.389334 0.200542 - 0.204396 -0.387476 0.192566 - 0.216204 -0.386425 0.188462 - 0.221128 -0.380025 0.186762 - 0.269773 -0.437734 0.169724 - 0.277195 -0.437517 0.167143 - 0.295712 -0.459374 0.160657 - 0.326061 -0.419118 0.150188 - 0.726994 -0.830715 0.0098871 - 0.730413 -0.827409 0.00870511 - 0.408109 -0.451304 0.121587 - 0.447444 -0.405852 0.108004 - 0.459101 -0.402314 0.103957 - 0.471303 -0.402494 0.0997135 - 0.502617 -0.407606 0.0888128 - 0.521468 -0.40463 0.0822636 - 0.552838 -0.406657 0.0713498 - 0.611255 -0.402514 0.0510434 - 0.643578 -0.408109 0.039791 - 0.907703 -0.41082 -0.0520677 - 1.03564 -0.403703 -0.0965436 - 1.09478 -0.410074 -0.117124 - 1.15058 -0.407674 -0.136524 - 1.38383 -0.463253 -0.217757 - 1.45489 -0.309307 -0.242145 - 1.46486 -0.269774 -0.245528 - 1.46281 -0.0927168 -0.24444 - 1.44903 0.0873903 -0.239267 - 1.44675 0.221076 -0.238189 - 1.44502 0.302515 -0.237417 - 1.28855 0.325002 -0.182954 - 1.43885 0.505927 -0.234839 - 1.28252 0.47665 -0.180534 - 0.712651 0.365425 0.0174077 - 0.711668 0.385173 0.0177913 - 0.586819 0.333284 0.0610994 - 0.663162 0.409533 0.0347115 - 0.371043 0.245906 0.135953 - 0.369546 0.251946 0.136487 - 0.350971 0.26927 0.142983 - 0.718902 0.621436 0.0157762 - 0.7168 0.653292 0.0165745 - 0.631554 0.746299 0.0464166 - 0.614286 0.738329 0.0524051 - 0.706919 0.93984 0.0206176 - 0.707725 1.05963 0.0205908 - 0.698969 1.066 0.0236494 - 0.42303 0.687044 0.118808 - 0.283382 0.537038 0.167055 - 0.278074 0.537731 0.168902 - 0.249972 0.589303 0.178784 - 0.280504 0.797678 0.168607 - 0.315834 1.28296 0.157349 - 0.258368 1.27311 0.177312 - 0.21626 1.28134 0.191974 - 0.19483 1.28289 0.199429 - 0.18425 1.28451 0.203112 - 0.171932 1.27214 0.207369 - 0.123752 1.20949 0.223992 - 0.100466 1.16646 0.231999 - 0.0773218 1.18514 0.240087 - 0.00412637 1.16895 0.265507 - -0.0876145 1.168 0.297409 - -0.113642 1.23153 0.306595 - -0.123789 1.2303 0.310121 - -0.141219 1.1674 0.31605 - -0.185738 1.1679 0.331533 - -0.220318 1.16577 0.343554 - -0.282278 1.16951 0.365109 - -0.414084 1.27883 0.411178 - -0.469588 1.28231 0.430488 - -0.495204 1.19584 0.439213 - -0.495907 1.14374 0.439347 - -0.497865 1.08605 0.439906 - -0.494543 0.877826 0.43831 - -0.491179 0.838784 0.437057 - -0.491683 0.792998 0.437135 - -0.493306 0.766335 0.437643 - -0.496461 0.763982 0.438736 - -0.490049 0.740578 0.436456 - -0.494791 0.587218 0.43778 - -0.492742 0.554939 0.436999 - -0.370973 -0.402286 0.388172 - -0.361302 -0.40256 0.38492 - -0.343435 -0.40398 0.378911 - -0.265718 -0.401822 0.352789 - -0.219185 -0.404551 0.33714 - -0.153376 -0.419728 0.314985 - -0.212593 -0.629518 0.334449 - -0.528103 -1.63652 0.43839 - -0.520907 -1.99942 0.435206 - -0.516907 -2.08873 0.433672 - -0.494889 -2.15153 0.426138 - -0.45303 -2.22045 0.411921 - -0.382715 -2.20197 0.388322 - -0.242604 -2.20067 0.341223 - -0.109612 -2.2874 0.296332 --0.00065374 -0.424751 0.263633 - 0.0151338 -0.417994 0.25834 - 0.0271995 -0.416734 0.254287 - 0.0330176 -0.338352 0.252496 - 0.0512793 -0.350701 0.246331 - 0.0840792 -0.366437 0.235271 - 0.114518 -0.378167 0.225014 - 0.121307 -0.378157 0.222732 - 0.126969 -0.374204 0.220837 - 0.128809 -0.374627 0.220217 - 0.140282 -0.377901 0.216353 - 0.145289 -0.377051 0.214672 - 0.162125 -0.378676 0.209009 - 0.201456 -0.389225 0.195765 - 0.230372 -0.388428 0.186046 - 0.328785 -0.493035 0.152741 - 0.325152 -0.47385 0.154003 - 0.315768 -0.415484 0.157281 - 1.2757 -1.64347 -0.168011 - 0.37476 -0.44608 0.137385 - 0.410457 -0.460851 0.125353 - 0.384662 -0.412453 0.134127 - 0.385428 -0.406141 0.133883 - 0.402821 -0.403424 0.128041 - 0.407882 -0.405113 0.126336 - 0.421433 -0.404629 0.121782 - 0.507128 -0.406573 0.0929696 - 0.607317 -0.40257 0.0592973 - 0.67086 -0.408064 0.0379242 - 0.684886 -0.408484 0.0332082 - 0.771806 -0.402706 0.00400028 - 0.818464 -0.404493 -0.0116886 - 0.844979 -0.408456 -0.0206106 - 0.881928 -0.40729 -0.0330291 - 0.887944 -0.405297 -0.0350476 - 0.98175 -0.401675 -0.0665748 - 1.01344 -0.409512 -0.0772453 - 1.11242 -0.409739 -0.110518 - 1.47383 -0.462587 -0.232126 - 1.49215 -0.424187 -0.238203 - 1.5063 -0.398854 -0.242909 - 1.50679 -0.384381 -0.243043 - 1.49516 -0.366959 -0.239096 - 1.50846 -0.19951 -0.243214 - 1.50703 -0.0607677 -0.24244 - 1.50227 -0.0262764 -0.240766 - 1.50331 -0.0194348 -0.241103 - 1.49886 0.110726 -0.239331 - 1.49752 0.151903 -0.238793 - 1.4981 0.200406 -0.238887 - 0.925424 0.254027 -0.0462561 - 1.04401 0.333216 -0.0859531 - 1.50115 0.619427 -0.239027 - 0.722903 0.337743 0.0220025 - 0.717216 0.350752 0.0239418 - 0.382531 0.241288 0.136223 - 0.353265 0.270475 0.146123 - 0.721711 0.622076 0.0230033 - 0.713754 0.739462 0.0259257 - 0.651301 0.741446 0.0469248 - 0.708278 0.905906 0.0281178 - 0.715952 0.949301 0.0256297 - 0.336266 0.556168 0.15244 - 0.284627 0.521859 0.169727 - 0.273604 0.544915 0.173482 - 0.293345 0.846116 0.167481 - 0.321536 1.28059 0.15892 - 0.305845 1.28569 0.164206 - 0.249163 1.28022 0.183249 - 0.243866 1.28129 0.185032 - 0.140369 1.17648 0.219604 - 0.125762 1.17813 0.224518 - 0.1132 1.20447 0.228796 - 0.0520605 1.17031 0.249278 - 0.0423788 1.17062 0.252533 - -0.0349267 1.16585 0.278511 - -0.128188 1.17343 0.309879 - -0.137762 1.17109 0.313092 - -0.230813 1.1616 0.344354 - -0.249158 1.19925 0.3506 - -0.264143 1.17384 0.355584 - -0.356652 1.27638 0.386899 - -0.390007 1.27139 0.398102 - -0.468585 1.27395 0.424523 - -0.490061 0.977735 0.431118 - -0.495791 0.876122 0.43283 - -0.491468 0.8519 0.431325 - -0.493604 0.74941 0.431827 - -0.491303 0.657077 0.430858 - -0.49578 0.645435 0.432339 - -0.332983 -0.403791 0.370401 - -0.330669 -0.404624 0.369655 - -0.316443 -0.40176 0.365084 - -0.300423 -0.406686 0.359919 - -0.295753 -0.404215 0.358422 - -0.285418 -0.401324 0.355103 - -0.222541 -0.399844 0.334877 - -0.197727 -0.403454 0.326886 - -0.177412 -0.405531 0.320346 - -0.174058 -0.402802 0.319273 - -0.160802 -0.400515 0.315013 - -0.205495 -0.582607 0.329009 - -0.219748 -0.636878 0.333481 - -0.530277 -1.7833 0.430977 - -0.520687 -1.95561 0.42753 - -0.465341 -2.22121 0.409165 - -0.393473 -2.19719 0.386094 - -0.35001 -2.21974 0.372064 - -0.33217 -2.22692 0.366309 - -0.134843 -2.22168 0.302835 - -0.125614 -2.22233 0.299864 - -0.0114946 -0.451291 0.26687 - 0.0199913 -0.426929 0.256791 - 0.0317801 -0.349422 0.253162 - 0.0541921 -0.353314 0.245943 - 0.0748897 -0.360111 0.23927 - 0.0899509 -0.365075 0.234414 - 0.119163 -0.389229 0.224965 - 0.133034 -0.382636 0.220516 - 0.145346 -0.377051 0.216566 - 0.146911 -0.376439 0.216064 - 0.157675 -0.376325 0.212601 - 0.174599 -0.390543 0.207127 - 0.198938 -0.391838 0.199294 - 0.206422 -0.394575 0.19688 - 0.210429 -0.390111 0.1956 - 0.248957 -0.416631 0.183149 - 0.313503 -0.454962 0.162302 - 1.16005 -1.65761 -0.112581 - 1.28881 -1.62484 -0.153936 - 0.702369 -0.818081 0.0364312 - 0.709143 -0.811724 0.0342653 - 0.383509 -0.406407 0.139882 - 0.443723 -0.407171 0.120508 - 0.513437 -0.406742 0.0980797 - 0.590701 -0.405124 0.0732254 - 0.620736 -0.402414 0.0635679 - 0.652566 -0.407267 0.0533172 - 0.786447 -0.404556 0.01025 - 1.12462 -0.406978 -0.0985522 - 1.5652 -0.390302 -0.240264 - 1.5848 -0.37244 -0.246533 - 1.56933 -0.338893 -0.241485 - 1.60036 -0.218333 -0.251214 - 1.59531 -0.158854 -0.249465 - 1.58961 -0.0928497 -0.247493 - 1.57258 -0.0703452 -0.241965 - 1.56098 0.179287 -0.237709 - 1.56639 0.230542 -0.239342 - 1.56704 0.259772 -0.23949 - 1.56217 0.317543 -0.237802 - 1.56878 0.348607 -0.239863 - 0.917492 0.259776 -0.0305148 - 1.1026 0.367278 -0.0898439 - 1.28575 0.487665 -0.148514 - 1.55918 0.65749 -0.236126 - 0.71414 0.332395 0.0350615 - 0.712754 0.335606 0.035514 - 0.681887 0.374209 0.0455259 - 0.596476 0.329875 0.0729117 - 0.393304 0.24761 0.138104 - 0.582616 0.463882 0.0776522 - 0.705201 0.568783 0.0384338 - 0.707038 0.925631 0.0385927 - 0.642979 0.878978 0.059104 - 0.605723 0.834556 0.070997 - 0.394659 0.567856 0.138341 - 0.332254 0.51205 0.158301 - 0.291309 0.487082 0.171422 - 0.28746 0.499905 0.172687 - 0.277475 0.506949 0.175914 - 0.278662 0.519927 0.17556 - 0.277436 0.534181 0.175984 - 0.250714 0.611037 0.184743 - 0.240816 0.649401 0.188008 - 0.36785 1.28001 0.148463 - 0.362531 1.28163 0.150177 - 0.344782 1.27956 0.155883 - 0.334141 1.28255 0.159313 - 0.328812 1.284 0.161031 - 0.304325 1.27597 0.168892 - 0.293502 1.27761 0.172377 - 0.239151 1.28332 0.189875 - 0.188973 1.27678 0.206005 - 0.173547 1.28305 0.210981 - 0.046871 1.17248 0.251504 - 0.0283775 1.2529 0.257623 --0.00159479 1.15289 0.267055 - -0.129469 1.17442 0.308241 - -0.205454 1.20726 0.332756 - -0.328062 1.26922 0.372333 - -0.418764 1.27977 0.401536 - -0.449292 1.28078 0.41136 - -0.491957 1.05154 0.424604 - -0.494726 1.01292 0.425414 - -0.491863 0.975978 0.424415 - -0.492426 0.891676 0.42442 - -0.493144 0.841957 0.424546 - -0.492778 0.62699 0.423977 - -0.369113 -0.402964 0.376718 - -0.355363 -0.405763 0.37248 - -0.333174 -0.405371 0.365651 - -0.320749 -0.404792 0.361828 - -0.306156 -0.404573 0.357336 - -0.292325 -0.404669 0.353079 - -0.290047 -0.405267 0.352376 - -0.233065 -0.403327 0.334841 - -0.2283 -0.411155 0.333357 - -0.201954 -0.400638 0.32527 - -0.193431 -0.400961 0.322646 - -0.183214 -0.397538 0.319508 - -0.172758 -0.406303 0.316271 - -0.16286 -0.397899 0.313242 - -0.161199 -0.398694 0.312729 - -0.154274 -0.396456 0.310602 - -0.152661 -0.406988 0.310084 - -0.519059 -1.94023 0.419657 - -0.520377 -2.04575 0.419841 - -0.458018 -2.22143 0.400279 - -0.393539 -2.18639 0.380505 - -0.251318 -2.1707 0.336761 - 0.00174352 -0.425861 0.262517 - 0.0106534 -0.418996 0.259789 - 0.0158784 -0.416981 0.258185 - 0.07914 -0.359224 0.238833 - 0.0863154 -0.363814 0.236615 - 0.0947608 -0.365927 0.234011 - 0.111696 -0.381015 0.228766 - 0.13142 -0.383184 0.22269 - 0.146702 -0.380803 0.217991 - 0.152826 -0.38266 0.216103 - 0.156713 -0.383221 0.214905 - 0.193018 -0.391666 0.203712 - 1.13781 -1.66509 -0.0897689 - 1.31555 -1.62379 -0.144393 - 0.777477 -0.91215 0.0227202 - 0.769242 -0.894425 0.0252922 - 0.393238 -0.401675 0.142061 - 0.422125 -0.406505 0.13316 - 0.450476 -0.40519 0.124435 - 0.452163 -0.403184 0.12392 - 0.463714 -0.402963 0.120365 - 0.482173 -0.404824 0.11468 - 0.569826 -0.407962 0.0876924 - 0.616873 -0.406352 0.0732144 - 0.677014 -0.405032 0.0547049 - 0.863829 -0.405336 -0.00279924 - 0.951023 -0.406078 -0.0296403 - 1.03485 -0.404531 -0.0554405 - 1.06868 -0.406922 -0.0658583 - 1.22769 -0.412231 -0.114815 - 1.65401 -0.363844 -0.245939 - 1.66752 -0.257555 -0.249873 - 1.67628 -0.166369 -0.25238 - 1.67037 -0.120046 -0.250463 - 1.63489 0.0902044 -0.239103 - 1.63936 0.112814 -0.240431 - 1.63629 0.142422 -0.239426 - 1.6405 0.278679 -0.240434 - 1.64032 0.309257 -0.240316 - 0.979428 0.257719 -0.0369944 - 1.05517 0.324001 -0.0601709 - 1.59336 0.65284 -0.225143 - 1.60291 0.707649 -0.227966 - 1.4909 0.673812 -0.193561 - 0.723395 0.335686 0.0419785 - 0.585992 0.326335 0.084253 - 0.571549 0.324762 0.0886953 - 0.382891 0.24967 0.146609 - 0.368549 0.261247 0.151048 - 0.354545 0.262801 0.155362 - 0.702925 0.565085 0.0487593 - 0.718653 0.599019 0.0439891 - 0.715846 0.607352 0.0448706 - 0.713413 0.672744 0.0457564 - 0.715383 0.692568 0.0451914 - 0.719725 0.71534 0.0439025 - 0.707866 0.74763 0.0476206 - 0.327243 0.457966 0.164174 - 0.297193 0.463628 0.173436 - 0.289867 0.488353 0.175742 - 0.284292 0.513607 0.177511 - 0.295585 1.28443 0.175648 - 0.267186 1.28274 0.184386 - 0.244328 1.27932 0.191415 - 0.12307 1.20451 0.228583 - 0.0277128 1.2379 0.258005 - -0.160119 1.20647 0.315756 - -0.206152 1.20333 0.329919 - -0.245528 1.19167 0.342014 - -0.252001 1.1973 0.344019 - -0.266846 1.17093 0.348533 - -0.355495 1.27808 0.376044 - -0.444993 1.27914 0.403595 - -0.491262 1.11662 0.417497 - -0.490022 0.947704 0.416762 - -0.493503 0.944526 0.417827 - -0.494942 0.824672 0.418019 - -0.489586 0.770825 0.416257 - -0.492548 0.71344 0.417049 - -0.492679 0.68198 0.417024 - -0.487378 0.590545 0.415201 - -0.493929 0.577639 0.41719 - -0.492639 0.551501 0.416738 - -0.320784 -0.399493 0.357989 - -0.311868 -0.409977 0.355326 - -0.294219 -0.401709 0.350116 - -0.292537 -0.403097 0.349614 - -0.283369 -0.40166 0.346902 - -0.251898 -0.404401 0.337574 - -0.230538 -0.401058 0.331254 - -0.198017 -0.403535 0.321616 - -0.196327 -0.404486 0.321113 - -0.15436 -0.408829 0.308673 - -0.16424 -0.460822 0.311492 - -0.533048 -1.69981 0.418151 - -0.529487 -1.81972 0.416846 - -0.478521 -2.17392 0.40101 - -0.407918 -2.20316 0.380036 - -0.390006 -2.20983 0.374717 - 0.00669907 -0.420967 0.260941 - 0.0377006 -0.340925 0.251925 - 0.0585219 -0.356676 0.245725 - 0.07258 -0.358423 0.241557 - 0.107672 -0.379009 0.23112 - 0.138107 -0.376595 0.22211 - 0.141254 -0.37543 0.22118 - 0.147379 -0.382679 0.219351 - 0.156759 -0.383221 0.216571 - 0.162582 -0.369928 0.214874 - 0.180134 -0.389194 0.209635 - 0.18865 -0.386172 0.207119 - 0.22275 -0.384452 0.197022 - 0.242883 -0.404605 0.191016 - 0.346565 -0.512231 0.16008 - 0.362374 -0.498116 0.155427 - 0.364456 -0.496515 0.154814 - 1.29967 -1.70237 -0.124718 - 1.33024 -1.59443 -0.133547 - 0.384919 -0.420483 0.148911 - 0.397393 -0.398179 0.145263 - 0.44762 -0.405191 0.13037 - 0.463783 -0.405673 0.125582 - 0.626564 -0.407881 0.0773604 - 0.667075 -0.405981 0.0653648 - 0.764661 -0.408076 0.0364549 - 0.831532 -0.407072 0.0166491 - 0.912381 -0.407636 -0.00730011 - 1.06096 -0.408246 -0.0513125 - 1.1021 -0.407376 -0.0634968 - 1.27564 -0.408269 -0.114901 - 1.61227 -0.461643 -0.214724 - 1.65767 -0.466684 -0.228182 - 1.69768 -0.461588 -0.240024 - 1.70149 -0.446225 -0.24112 - 1.7005 -0.341031 -0.240606 - 1.6972 -0.332414 -0.239612 - 1.69669 -0.324378 -0.239445 - 1.70807 -0.278888 -0.242721 - 1.7108 -0.169318 -0.243299 - 1.71054 -0.161494 -0.243206 - 1.70016 -0.0294544 -0.239857 - 1.7004 0.00896322 -0.239847 - 1.70872 0.125033 -0.24207 - 1.70762 0.140471 -0.241711 - 1.70544 0.186925 -0.24097 - 1.71161 0.234668 -0.242696 - 1.71076 0.345697 -0.242214 - 1.71286 0.370287 -0.242785 - 1.40646 0.494787 -0.151766 - 1.19136 0.436511 -0.0881759 - 0.710751 0.332698 0.0539685 - 0.709857 0.371438 0.0543139 - 0.567129 0.331396 0.0965076 - 0.387161 0.256885 0.14966 - 0.353015 0.254025 0.159768 - 0.385107 0.296271 0.15035 - 0.717973 0.602236 0.0523915 - 0.713649 0.620163 0.0537097 - 0.713046 0.636251 0.0539218 - 0.718741 0.670211 0.0523059 - 0.71569 0.697147 0.0532658 - 0.71673 0.710473 0.0529855 - 0.707652 0.74548 0.0557475 - 0.716094 0.7882 0.0533361 - 0.712791 0.791395 0.0543209 - 0.672013 0.765195 0.066345 - 0.303376 0.472884 0.174928 - 0.292407 0.482382 0.178197 - 0.234418 1.28434 0.197047 - 0.107925 1.20691 0.234353 - 0.0900997 1.1682 0.239552 - 0.0509293 1.16931 0.251157 - 0.0220292 1.22596 0.259836 - -0.201748 1.20137 0.326069 - -0.211793 1.19938 0.32904 - -0.254169 1.20119 0.341596 - -0.302152 1.22166 0.355852 - -0.322653 1.27905 0.362044 - -0.350148 1.27399 0.370178 - -0.398045 1.27708 0.384371 - -0.465372 1.27928 0.404319 - -0.488164 1.27409 0.411059 - -0.498869 1.25426 0.414188 - -0.495257 1.20142 0.413008 - -0.490917 1.17718 0.411672 - -0.493189 0.959631 0.411892 - -0.493946 0.951201 0.412098 - -0.492529 0.910675 0.411594 - -0.493621 0.885663 0.411865 - -0.491396 0.87307 0.41118 - -0.493387 0.803286 0.411624 - -0.488946 0.766694 0.410232 - -0.493235 0.610971 0.411178 - -0.372294 -0.395945 0.36888 - -0.37402 -0.40827 0.369346 - -0.337876 -0.403791 0.359061 - -0.317603 -0.400982 0.353293 - -0.284745 -0.405388 0.343926 - -0.262047 -0.406505 0.337459 - -0.25705 -0.402809 0.336043 - -0.177726 -0.39925 0.313458 - -0.175627 -0.399205 0.312861 - -0.20557 -0.580804 0.321011 - -0.224147 -0.638746 0.326182 - -0.212077 -0.639159 0.322743 - -0.51926 -1.55953 0.408318 - -0.521499 -1.84277 0.408367 - -0.486148 -2.15709 0.397645 - -0.286964 -2.28318 0.340653 - -0.176088 -2.23361 0.309177 - 0.0241695 -0.428789 0.255895 - 0.0405594 -0.344661 0.251402 - 0.0421819 -0.346516 0.250936 - 0.0617929 -0.360194 0.245322 - 0.0661728 -0.358489 0.244078 - 0.0694975 -0.35995 0.243128 - 0.0896694 -0.358866 0.237385 - 0.0990435 -0.364764 0.234703 - 0.11707 -0.382502 0.229532 - 0.121046 -0.378157 0.228409 - 0.129137 -0.381821 0.226096 - 0.131631 -0.384135 0.225381 - 0.14888 -0.376755 0.220484 - 0.171394 -0.38669 0.214051 - 0.207174 -0.399022 0.203835 - 0.218803 -0.384613 0.200553 - 0.227314 -0.380676 0.198137 - 0.265527 -0.434957 0.187141 - 1.20167 -1.67112 -0.0820534 - 1.23457 -1.70174 -0.0914887 - 1.32383 -1.58232 -0.116663 - 0.384526 -0.422914 0.153274 - 0.419376 -0.405609 0.143384 - 0.464986 -0.402314 0.1304 - 0.503064 -0.40613 0.119548 - 0.610059 -0.403669 0.0890793 - 0.615793 -0.403651 0.0874461 - 0.736753 -0.408853 0.0529847 - 0.782791 -0.403605 0.0398833 - 0.799113 -0.407675 0.0352263 - 0.879687 -0.405955 0.0122813 - 0.92354 -0.411617 -0.00022021 - 1.21814 -0.412777 -0.0841272 - 1.31379 -0.406525 -0.111356 - 1.76592 -0.428195 -0.240173 - 1.77235 -0.379479 -0.241905 - 1.79029 -0.324767 -0.246899 - 1.79164 -0.316693 -0.247267 - 1.80759 -0.269413 -0.251713 - 1.8126 -0.195466 -0.252983 - 1.81418 -0.179115 -0.2534 - 1.77562 -0.0787523 -0.242208 - 1.77165 0.0572456 -0.240795 - 1.76965 0.121146 -0.240093 - 1.76979 0.217714 -0.239932 - 1.76886 0.225689 -0.239652 - 1.7679 0.233659 -0.239362 - 1.77636 0.251077 -0.241736 - 1.76746 0.32327 -0.239049 - 1.76609 0.331232 -0.238643 - 1.77777 0.416907 -0.241791 - 0.931002 0.261358 -0.00094593 - 0.912635 0.273793 0.00431105 - 1.76327 0.60197 -0.237277 - 1.40395 0.513778 -0.135121 - 1.24447 0.486663 -0.0897557 - 1.2744 0.511628 -0.0982294 - 0.716832 0.334775 0.0602047 - 0.713999 0.34116 0.0610249 - 0.71311 0.36826 0.0613345 - 0.704376 0.383611 0.0638539 - 0.380629 0.259185 0.155802 - 0.379539 0.260856 0.156116 - 0.357383 0.263985 0.162433 - 0.358238 0.269507 0.162201 - 0.71836 0.580005 0.0602793 - 0.722199 0.648672 0.0593289 - 0.727555 0.671008 0.0578499 - 0.426591 0.459186 0.143127 - 0.386997 0.426429 0.154336 - 0.332292 0.397819 0.169857 - 0.312972 0.420084 0.175406 - 0.310752 0.448844 0.176098 - 0.292818 0.473007 0.181256 - 0.292103 0.495648 0.181507 - 0.283704 0.561888 0.184037 - 0.259475 0.622881 0.191064 - 0.288192 0.824397 0.183304 - 0.404792 1.27841 0.151039 - 0.324517 1.28253 0.173911 - 0.125894 1.1831 0.230275 - 0.0902909 1.17419 0.240396 - 0.0777865 1.21709 0.244047 - 0.0164121 1.21299 0.261518 --0.00336255 1.16689 0.267054 --0.00847937 1.1798 0.268539 - -0.0334174 1.18405 0.27565 - -0.037628 1.16585 0.276812 - -0.0918096 1.167 0.292245 - -0.125102 1.24484 0.301889 - -0.126508 1.16713 0.302128 - -0.210225 1.21316 0.326067 - -0.27181 1.15898 0.343495 - -0.283732 1.16506 0.346903 - -0.339938 1.2734 0.363137 - -0.370285 1.27753 0.371788 - -0.386933 1.27411 0.376523 - -0.459495 1.27491 0.397191 - -0.464842 1.27276 0.398709 - -0.487315 1.28284 0.405131 - -0.498065 1.27826 0.408183 - -0.494701 1.12797 0.406912 - -0.492865 1.11119 0.406354 - -0.493397 1.08766 0.406457 - -0.490051 0.858806 0.405028 - -0.491732 0.812903 0.405412 - -0.490246 0.787641 0.404936 - -0.49323 0.587511 0.405369 - -0.490189 0.568798 0.404464 - -0.495992 0.560461 0.4061 - -0.306066 -0.399168 0.346389 - -0.293416 -0.40074 0.342927 - -0.292321 -0.402901 0.342623 - -0.282012 -0.403531 0.339804 - -0.278581 -0.402447 0.338868 - -0.2291 -0.398763 0.325348 - -0.227247 -0.403477 0.324832 - -0.208784 -0.395072 0.319802 - -0.197048 -0.401842 0.316579 - -0.187669 -0.404666 0.314009 - -0.185965 -0.40556 0.313541 - -0.218511 -0.645647 0.321941 - -0.521295 -1.69994 0.402533 - -0.517582 -2.01198 0.400871 - -0.365417 -2.2161 0.358848 - -0.310476 -2.23343 0.343791 - -0.285498 -2.26237 0.336903 - -0.175932 -2.22065 0.307035 - -0.136709 -2.19674 0.296361 - 0.00212329 -0.428904 0.262072 - 0.00938133 -0.419996 0.260106 - 0.0128992 -0.415994 0.259152 - 0.0219576 -0.427844 0.256651 - 0.0236101 -0.422792 0.25621 - 0.0269403 -0.416666 0.255312 - 0.0282174 -0.368561 0.255063 - 0.0304963 -0.353415 0.254471 - 0.0464265 -0.348055 0.250127 - 0.0478912 -0.347891 0.249727 - 0.0528695 -0.352322 0.248357 - 0.125274 -0.380966 0.228503 - 0.159431 -0.375657 0.219176 - 0.170686 -0.384852 0.21608 - 0.196354 -0.393531 0.209044 - 0.271867 -0.445212 0.188293 - 1.23088 -1.69213 -0.0764756 - 0.405676 -0.39814 0.151809 - 0.587723 -0.402743 0.102029 - 0.62374 -0.404124 0.0921797 - 0.652664 -0.407065 0.084266 - 0.756392 -0.405919 0.0559102 - 0.924002 -0.405898 0.0100875 - 1.05036 -0.412773 -0.0244725 - 1.88038 -0.305516 -0.251167 - 1.8915 -0.220688 -0.254031 - 1.84416 -0.0483816 -0.240734 - 1.83802 -0.00688801 -0.238967 - 1.83707 0.00137536 -0.23869 - 1.83418 0.175043 -0.237541 - 1.8444 0.209534 -0.240262 - 1.85173 0.269572 -0.242142 - 1.84354 0.379269 -0.239677 - 0.912493 0.264247 0.0146234 - 1.27049 0.489137 -0.0827834 - 0.726041 0.334452 0.0657429 - 0.715852 0.333529 0.0685267 - 0.712337 0.370984 0.0695654 - 0.555887 0.319993 0.112231 - 0.502514 0.309558 0.126801 - 0.382594 0.248046 0.159459 - 0.383177 0.258064 0.15932 - 0.379889 0.26309 0.160229 - 0.368862 0.272271 0.163263 - 0.8452 0.726334 0.0339788 - 0.733287 0.657251 0.0644312 - 0.50795 0.468341 0.125644 - 0.33731 0.362996 0.172077 - 0.335706 0.380713 0.172552 - 0.318928 0.397972 0.177175 - 0.323379 0.414728 0.175993 - 0.316353 0.420311 0.177925 - 0.319114 0.431902 0.177194 - 0.308216 0.448548 0.180208 - 0.304137 0.455034 0.181337 - 0.304671 0.469037 0.18122 - 0.302695 0.470359 0.181763 - 0.299755 0.47467 0.182576 - 0.300227 0.494356 0.182487 - 0.294581 0.509435 0.184062 - 0.298655 0.522003 0.182975 - 0.298021 0.531565 0.183168 - 0.336886 0.76819 0.173033 - 0.255318 0.619369 0.195024 - 0.231927 0.589194 0.201357 - 0.356997 1.27262 0.168581 - 0.308094 1.28375 0.181974 - 0.302688 1.28508 0.183454 - 0.222889 1.27941 0.205259 - 0.217503 1.28035 0.206733 - 0.128441 1.1597 0.230831 - 0.0946542 1.16884 0.240087 - 0.0261317 1.20891 0.258904 - -0.0782806 1.1743 0.287377 - -0.0871515 1.16149 0.289776 - -0.113862 1.23013 0.29722 - -0.142878 1.17109 0.305031 - -0.16945 1.18015 0.312314 - -0.259962 1.19218 0.337084 - -0.266088 1.17317 0.338719 - -0.33712 1.27884 0.358358 - -0.352143 1.27016 0.362447 - -0.491939 1.14344 0.400403 - -0.490444 0.79242 0.399266 - -0.491589 0.750605 0.399493 - -0.493093 0.718835 0.399838 - -0.490708 0.636172 0.399015 - -0.483878 0.564412 0.396998 - -0.380146 -0.400877 0.362281 - -0.36853 -0.409864 0.359216 - -0.360806 -0.405037 0.3572 - -0.324261 -0.409343 0.347608 - -0.312286 -0.405345 0.344476 - -0.2533 -0.401093 0.329016 - -0.251605 -0.402279 0.328569 - -0.225799 -0.399212 0.321808 - -0.16777 -0.405066 0.306578 - -0.157436 -0.399964 0.303879 - -0.214894 -0.607929 0.318517 - -0.51252 -1.91952 0.393854 - -0.467089 -2.23021 0.381298 - -0.448248 -2.23443 0.376348 - -0.329377 -2.22255 0.3452 - -0.284224 -2.24354 0.333316 - -0.122009 -2.24989 0.290764 --0.00807672 -0.445589 0.264617 - 0.0160283 -0.417959 0.258353 - 0.0196201 -0.420892 0.257405 - 0.0287458 -0.355498 0.255147 - 0.044544 -0.347218 0.251021 - 0.0474738 -0.346897 0.250253 - 0.0701873 -0.357711 0.244275 - 0.140205 -0.383202 0.22586 - 0.146656 -0.380803 0.224174 - 0.159064 -0.374732 0.220932 - 0.178248 -0.393457 0.215863 - 0.198046 -0.38826 0.210682 - 0.200119 -0.388303 0.210138 - 0.218476 -0.3873 0.205326 - 0.23067 -0.385844 0.202132 - 0.287204 -0.466185 0.18714 - 0.347386 -0.492181 0.171304 - 1.31737 -1.74328 -0.0856513 - 1.27249 -1.63861 -0.0736639 - 1.29864 -1.62835 -0.0805022 - 1.31977 -1.62588 -0.0860371 - 0.72291 -0.831553 0.0721256 - 0.437627 -0.407638 0.147814 - 0.478298 -0.405247 0.137154 - 0.524301 -0.403344 0.125094 - 0.536991 -0.405866 0.121761 - 0.596137 -0.40777 0.106247 - 0.597854 -0.405124 0.105802 - 0.655754 -0.404158 0.09062 - 0.741818 -0.405558 0.068048 - 0.928803 -0.40708 0.0190101 - 0.957032 -0.39952 0.0116229 - 1.09239 -0.406191 -0.0238882 - 1.22334 -0.412464 -0.0582393 - 1.42489 -0.411255 -0.111092 - 1.70759 -0.460572 -0.185329 - 1.91027 -0.398106 -0.238351 - 1.90814 -0.388755 -0.237774 - 1.9269 -0.338952 -0.242588 - 1.93542 -0.322611 -0.24479 - 1.9111 -0.0328664 -0.237814 - 1.90927 0.112884 -0.237032 - 1.91319 0.19082 -0.237898 - 1.92654 0.422459 -0.24092 - 1.91669 0.660789 -0.237844 - 1.90161 0.693734 -0.233823 - 1.26669 0.499432 -0.0677238 - 0.716535 0.356487 0.0762537 - 0.393087 0.244976 0.160844 - 0.385444 0.28183 0.162924 - 0.596903 0.457217 0.107834 - 0.343727 0.369583 0.174046 - 0.338636 0.370359 0.175382 - 0.33554 0.379964 0.176214 - 0.324804 0.404995 0.179081 - 0.310359 0.438761 0.182939 - 0.311306 0.46117 0.182737 - 0.308307 0.478774 0.18356 - 0.307802 0.527162 0.183792 - 0.307181 0.536768 0.183975 - 0.296639 0.556471 0.18678 - 0.23648 0.624929 0.202698 - 0.267752 0.740897 0.194737 - 0.36661 1.28451 0.169936 - 0.113101 1.21344 0.23627 - -0.0538453 1.17006 0.27996 - -0.150045 1.18028 0.305208 - -0.203754 1.19449 0.319322 - -0.242903 1.18113 0.329561 - -0.331329 1.27366 0.352941 - -0.377907 1.27292 0.365154 - -0.383277 1.27115 0.366559 - -0.394297 1.26849 0.369443 - -0.409657 1.27898 0.373493 - -0.496277 1.21885 0.396083 - -0.495629 1.2028 0.39588 - -0.494096 1.0458 0.395154 - -0.493358 1.00017 0.394866 - -0.493579 0.779538 0.394468 - -0.489831 0.766482 0.393458 - -0.494375 0.745048 0.394605 - -0.493342 0.729882 0.394303 - -0.38576 -0.405104 0.359284 - -0.364905 -0.407941 0.354044 - -0.348119 -0.403558 0.34984 - -0.345105 -0.403684 0.349083 - -0.300036 -0.402492 0.337774 - -0.28738 -0.407526 0.334588 - -0.237873 -0.397996 0.322182 - -0.23008 -0.400695 0.320221 - -0.222153 -0.395143 0.318243 - -0.20119 -0.401777 0.312968 - -0.191673 -0.400192 0.310583 - -0.163774 -0.39857 0.303584 - -0.154217 -0.414764 0.301152 - -0.214897 -0.629694 0.315938 - -0.528609 -1.66186 0.392544 - -0.519264 -2.03946 0.38942 - -0.475421 -2.21536 0.378054 - -0.452292 -2.24617 0.372186 - -0.321126 -2.22307 0.339313 - -0.30341 -2.23387 0.334845 - -0.19697 -2.22387 0.308152 - -0.0106649 -0.450495 0.26505 - 0.0103151 -0.416999 0.259854 - 0.0321846 -0.344244 0.254515 - 0.0406507 -0.340542 0.252398 - 0.0615205 -0.364153 0.247111 - 0.0680917 -0.356005 0.245479 - 0.0742866 -0.35589 0.243925 - 0.0899331 -0.362767 0.239983 - 0.0945325 -0.361658 0.238831 - 0.10854 -0.365142 0.235309 - 0.125804 -0.377585 0.23095 - 0.152633 -0.392358 0.224186 - 0.153734 -0.380151 0.223935 - 0.16125 -0.380283 0.222048 - 0.220244 -0.394369 0.207213 - 0.294043 -0.467909 0.18854 - 0.383618 -0.41608 0.166166 - 0.489513 -0.403306 0.139615 - 0.525871 -0.407483 0.130481 - 0.565263 -0.411479 0.120587 - 0.570311 -0.407621 0.119327 - 0.697452 -0.404397 0.0874248 - 0.706757 -0.405727 0.0850867 - 0.763101 -0.407779 0.0709415 - 0.894606 -0.40526 0.037942 - 0.944198 -0.408004 0.0254899 - 1.07416 -0.409295 -0.00713083 - 1.24732 -0.413464 -0.0505971 - 1.99509 -0.45217 -0.238349 - 1.99698 -0.443235 -0.238807 - 1.99885 -0.434292 -0.239256 - 2.00699 -0.370761 -0.24117 - 2.0095 -0.361947 -0.241782 - 2.01293 -0.353286 -0.242624 - 2.02755 -0.28154 -0.246145 - 2.02505 -0.262751 -0.24548 - 2.02431 -0.207583 -0.245178 - 2.02824 -0.162232 -0.246072 - 2.00906 -0.0254803 -0.240977 - 2.00916 -0.016488 -0.240982 - 2.01667 0.037612 -0.242757 - 2.07219 0.347783 -0.25605 - 2.02287 0.348767 -0.243671 - 2.02329 0.461658 -0.243544 - 1.56447 0.681426 -0.127937 - 0.748342 0.405237 0.076322 - 0.548246 0.317485 0.12636 - 0.560297 0.337865 0.123378 - 0.377552 0.263043 0.169088 - 0.3679 0.304313 0.171596 - 0.34996 0.329827 0.176151 - 0.320518 0.432707 0.183752 - 0.316122 0.459266 0.18491 - 0.315494 0.489712 0.185131 - 0.317987 0.50821 0.184543 - 0.317043 0.521725 0.184808 - 0.314517 0.538396 0.185476 - 0.308202 0.549022 0.187083 - 0.533655 1.18516 0.131812 - 0.248444 0.600853 0.202188 - 0.400771 1.27827 0.165354 - 0.383394 1.27959 0.169718 - 0.353386 1.27706 0.177244 - 0.308371 1.2818 0.188552 - 0.286211 1.28501 0.19412 - 0.280359 1.28428 0.195587 - 0.212157 1.28028 0.212696 - 0.179193 1.2823 0.220973 - 0.173765 1.28305 0.222337 - 0.0993854 1.17144 0.240775 - 0.0715848 1.21238 0.247836 - 0.0202516 1.21596 0.260727 - 0.00505793 1.16098 0.264427 - -0.0348125 1.17506 0.274463 - -0.0792946 1.16931 0.285615 - -0.0935102 1.16103 0.289165 - -0.0987026 1.16353 0.290474 - -0.143975 1.16613 0.301841 - -0.271838 1.16511 0.33393 - -0.374316 1.27562 0.359877 - -0.41635 1.27613 0.370428 - -0.442205 1.28046 0.376926 - -0.492461 1.26576 0.389509 - -0.49215 1.0611 0.389009 - -0.491169 1.02476 0.388687 - -0.492628 0.829013 0.38865 - -0.49216 0.774552 0.38842 - -0.490963 0.751226 0.388072 - -0.493182 0.733782 0.388593 - -0.495647 0.615548 0.388968 - -0.488292 0.555508 0.386998 - -0.492977 0.550999 0.388164 - -0.389946 -0.407922 0.355932 - -0.346821 -0.400607 0.345598 - -0.298414 -0.406055 0.33397 - -0.268463 -0.405261 0.326784 - -0.262798 -0.404453 0.325426 - -0.231618 -0.401546 0.31795 - -0.22669 -0.40113 0.316768 - -0.223278 -0.403235 0.315945 - -0.152107 -0.407358 0.298857 - -0.148645 -0.408794 0.298023 - -0.215534 -0.637279 0.313605 - -0.213686 -0.649646 0.313136 - -0.522707 -1.66237 0.385212 - -0.527541 -1.72804 0.386237 - -0.522542 -1.73807 0.385017 - -0.453645 -2.24519 0.36744 - -0.334508 -2.23934 0.338861 - -0.177982 -2.21368 0.301351 - -0.159191 -2.21527 0.296838 - -0.14979 -2.216 0.294581 --0.00700463 -0.44267 0.263963 --0.00109152 -0.431859 0.262566 - 0.00812789 -0.417996 0.260382 - 0.029235 -0.35042 0.255456 - 0.0362047 -0.343916 0.253797 - 0.0394621 -0.347649 0.253007 - 0.0576182 -0.360639 0.248624 - 0.059148 -0.36042 0.248257 - 0.0661716 -0.365402 0.246561 - 0.0820059 -0.364477 0.242763 - 0.0989953 -0.354275 0.238707 - 0.108603 -0.359884 0.23639 - 0.122926 -0.374283 0.232923 - 0.132004 -0.380737 0.230731 - 0.145252 -0.382353 0.227549 - 0.15439 -0.382014 0.225356 - 0.167189 -0.380971 0.222287 - 0.184948 -0.39037 0.218006 - 0.221565 -0.392545 0.209214 - 0.25881 -0.425825 0.200208 - 0.265157 -0.432394 0.198671 - 0.33121 -0.462991 0.182757 - 1.25918 -1.68818 -0.0424558 - 0.487103 -0.404188 0.145467 - 0.530044 -0.406368 0.135157 - 0.545339 -0.407053 0.131486 - 0.667532 -0.405873 0.102164 - 0.669249 -0.402917 0.101758 - 0.827925 -0.40516 0.0636748 - 0.841049 -0.407072 0.0605213 - 0.972057 -0.409134 0.0290781 - 0.997137 -0.409456 0.0230589 - 1.17746 -0.406712 -0.0202086 - 1.29423 -0.409156 -0.048236 - 1.34887 -0.413425 -0.0613584 - 1.7403 -0.442391 -0.155352 - 2.09459 -0.415168 -0.240317 - 2.14583 -0.152007 -0.252073 - 2.13983 -0.122792 -0.250573 - 2.1068 -0.102018 -0.242605 - 2.09842 0.0203051 -0.240341 - 2.10176 0.142572 -0.240891 - 2.09396 0.170244 -0.238963 - 2.16937 0.403231 -0.25658 - 2.11545 0.471758 -0.243499 - 1.7052 0.444096 -0.145106 - 2.07923 0.734399 -0.234267 - 1.28727 0.498732 -0.0446999 - 0.818976 0.371141 0.0674192 - 0.695989 0.387708 0.0969675 - 0.545311 0.318399 0.132984 - 0.548164 0.333116 0.13233 - 0.525136 0.322024 0.137833 - 0.379473 0.259166 0.17266 - 0.376942 0.290044 0.173331 - 0.358147 0.328596 0.177921 - 0.34899 0.334254 0.18013 - 0.34757 0.335772 0.180474 - 0.347535 0.33868 0.180488 - 0.331158 0.476794 0.184702 - 0.32419 0.488891 0.186399 - 0.318904 0.524291 0.187741 - 0.313686 0.53099 0.189007 - 0.298247 0.552533 0.192756 - 0.341324 0.775515 0.182877 - 0.277955 0.642434 0.19781 - 0.390172 1.28077 0.172194 - 0.3489 1.28052 0.182098 - 0.292556 1.28669 0.195632 - 0.196197 1.28487 0.218752 - 0.134436 1.17308 0.233343 - 0.129762 1.17661 0.234472 - 0.0947682 1.17981 0.242877 - 0.0344863 1.17674 0.257337 - -0.0990545 1.15955 0.289348 - -0.159738 1.20032 0.303995 - -0.213761 1.20923 0.316978 - -0.260413 1.20217 0.328159 - -0.339705 1.27306 0.347333 - -0.414032 1.28277 0.36519 - -0.497249 1.18403 0.384957 - -0.493877 1.0611 0.383895 - -0.497075 0.98992 0.384516 - -0.492159 0.920979 0.383194 - -0.493285 0.803656 0.383223 - -0.493012 0.679409 0.382902 - -0.490961 0.646842 0.382343 - -0.492974 0.610209 0.382751 - -0.4975 0.604914 0.383826 - -0.489789 0.585309 0.381935 - -0.495521 0.566588 0.383272 - -0.49569 0.547279 0.383273 - -0.355112 -0.404883 0.343541 - -0.327318 -0.404786 0.337179 - -0.321358 -0.404717 0.335815 - -0.296671 -0.405851 0.330162 - -0.29257 -0.404041 0.329227 - -0.274713 -0.405186 0.325137 - -0.273553 -0.407268 0.324867 - -0.239679 -0.405288 0.317117 - -0.225484 -0.401329 0.313876 - -0.199993 -0.40008 0.308044 - -0.181535 -0.401902 0.303815 - -0.178554 -0.400049 0.303137 - -0.176807 -0.405334 0.302726 - -0.1696 -0.403245 0.30108 - -0.152421 -0.401083 0.297152 - -0.150098 -0.405297 0.296612 - -0.157271 -0.440031 0.298183 - -0.220552 -0.631487 0.312275 - -0.215172 -0.633519 0.311039 - -0.431589 -2.22671 0.357308 - -0.408732 -2.20995 0.352111 - -0.369723 -2.2092 0.343183 - -0.327395 -2.24877 0.333413 - -0.142222 -2.23266 0.29106 --0.00939078 -0.44359 0.264326 - 0.0271962 -0.37855 0.256084 - 0.0312651 -0.341251 0.25523 - 0.0339497 -0.338049 0.254622 - 0.0419759 -0.346373 0.252767 - 0.0493341 -0.345557 0.251085 - 0.07964 -0.361857 0.244114 - 0.0827157 -0.361212 0.243412 - 0.0846574 -0.362836 0.242964 - 0.0888503 -0.359841 0.24201 - 0.132265 -0.376392 0.232039 - 0.172336 -0.384126 0.22285 - 0.198676 -0.389155 0.216811 - 0.212207 -0.390994 0.21371 - 0.219302 -0.388174 0.212092 - 0.523208 -0.803286 0.141676 - 0.323063 -0.481186 0.18815 - 0.335158 -0.455397 0.185434 - 1.26169 -1.64285 -0.0290863 - 1.32491 -1.63563 -0.0435415 - 0.390281 -0.429782 0.172869 - 0.385614 -0.402798 0.173993 - 0.455282 -0.407852 0.158035 - 0.463394 -0.404449 0.156186 - 0.494859 -0.406467 0.148979 - 0.656108 -0.406021 0.11207 - 0.721373 -0.404285 0.0971344 - 0.733345 -0.406857 0.0943889 - 0.757416 -0.407412 0.0888778 - 0.84793 -0.405041 0.068164 - 0.854948 -0.403815 0.0665601 - 0.875209 -0.404094 0.0619217 - 1.06771 -0.405101 0.0178558 - 1.12683 -0.405075 0.00432324 - 1.4904 -0.398875 -0.0788858 - 1.91856 -0.459727 -0.177015 - 2.22827 -0.348686 -0.247681 - 2.23985 -0.330092 -0.250292 - 2.20554 -0.0671968 -0.2419 - 2.18605 0.0113656 -0.237278 - 2.19469 0.0995105 -0.239074 - 2.20699 0.248548 -0.241583 - 2.27826 0.339185 -0.257712 - 2.27341 0.390374 -0.256498 - 2.27174 0.400503 -0.256093 - 2.26634 0.420383 -0.254815 - 2.21096 0.471441 -0.242036 - 2.17299 0.722857 -0.232827 - 2.0427 0.760799 -0.202926 - 1.25812 0.505602 -0.0238612 - 1.27186 0.524265 -0.0269659 - 0.720183 0.348382 0.098951 - 0.715444 0.353853 0.100047 - 0.72364 0.390193 0.0982455 - 0.607787 0.340782 0.124663 - 0.537754 0.313393 0.140637 - 0.379951 0.276535 0.176683 - 0.36861 0.293472 0.179313 - 0.367616 0.297935 0.17955 - 0.358876 0.314768 0.181585 - 0.35764 0.319216 0.181877 - 0.340748 0.343266 0.185793 - 0.339286 0.344745 0.186131 - 0.343617 0.431465 0.185318 - 0.330185 0.483793 0.188499 - 0.322443 0.490296 0.190285 - 0.321947 0.494209 0.190406 - 0.306485 0.550356 0.194061 - 0.298797 0.564837 0.195851 - 0.297609 0.613589 0.196222 - 0.425031 0.958617 0.167764 - 0.259889 0.621032 0.204872 - 0.243959 0.62754 0.208531 - 0.371827 1.27713 0.180595 - 0.304175 1.28605 0.196099 - 0.291077 1.27888 0.199083 - 0.269676 1.28568 0.203995 - 0.264205 1.28683 0.20525 - 0.25835 1.28599 0.206588 - 0.212733 1.28324 0.217025 - 0.0766392 1.22108 0.248049 - 0.0536894 1.16513 0.253187 - 0.0194878 1.22696 0.261143 - -0.0231096 1.25954 0.27096 - -0.056481 1.18404 0.278444 - -0.186223 1.16576 0.308105 - -0.32941 1.27326 0.341101 - -0.435648 1.27025 0.365412 - -0.473924 1.27369 0.374181 - -0.495523 1.26484 0.379107 - -0.492807 0.77764 0.377485 - -0.491234 0.767903 0.377105 - -0.492316 0.762339 0.377341 - -0.493828 0.636883 0.37743 - -0.345062 -0.409941 0.337406 - -0.323623 -0.40247 0.332745 - -0.315964 -0.4038 0.331072 - -0.294705 -0.39817 0.326447 - -0.283228 -0.400843 0.323938 - -0.254823 -0.40062 0.317744 - -0.208154 -0.397146 0.307572 - -0.166781 -0.395053 0.298553 - -0.153206 -0.401083 0.29558 - -0.207012 -0.633643 0.306839 - -0.52493 -1.70899 0.373976 - -0.505982 -2.15676 0.368926 - -0.0592842 -0.514309 0.274864 - -0.243761 -2.19089 0.311666 - -0.133045 -2.22732 0.287445 - -0.0118303 -0.445501 0.264656 - 0.0453056 -0.353028 0.252384 - 0.0581391 -0.357449 0.249576 - 0.0919087 -0.360088 0.242205 - 0.103375 -0.360219 0.239704 - 0.107974 -0.358921 0.238704 - 0.119731 -0.364734 0.236128 - 0.132155 -0.365823 0.233416 - 0.14558 -0.37363 0.230472 - 0.187855 -0.387877 0.221222 - 0.199476 -0.386517 0.218691 - 0.218185 -0.389987 0.214603 - 0.322635 -0.441489 0.191717 - 1.26332 -1.62703 -0.015871 - 1.27207 -1.62375 -0.0177731 - 1.29856 -1.64303 -0.0235898 - 0.395448 -0.43891 0.175842 - 0.379548 -0.406356 0.179377 - 0.382011 -0.398467 0.178855 - 0.394944 -0.405139 0.176021 - 0.404572 -0.400993 0.17393 - 0.41459 -0.400515 0.171746 - 0.442995 -0.403097 0.165546 - 0.505872 -0.407732 0.151823 - 0.507606 -0.405508 0.151449 - 0.543133 -0.404081 0.143704 - 0.591452 -0.401626 0.13317 - 0.623713 -0.404191 0.126129 - 0.819598 -0.404013 0.0834071 - 0.838009 -0.404063 0.0793916 - 1.11254 -0.404679 0.0195162 - 1.30886 -0.412115 -0.0233159 - 1.46557 -0.412334 -0.0574945 - 2.3032 -0.454708 -0.240269 - 2.33984 -0.386781 -0.24812 - 2.33579 -0.311793 -0.247084 - 2.33644 -0.133538 -0.24686 - 2.33057 -0.0916332 -0.245494 - 2.32541 -0.0707146 -0.244326 - 2.33603 0.0329098 -0.246431 - 2.34739 0.0539637 -0.248866 - 2.34516 0.0956858 -0.248293 - 2.34095 0.210559 -0.24714 - 2.35266 0.243296 -0.249625 - 2.35413 0.339099 -0.249752 - 2.35625 0.403801 -0.25008 - 2.3409 0.498212 -0.24654 - 1.67363 0.441906 -0.101124 - 1.48013 0.404592 -0.0589983 - 0.929478 0.266424 0.060815 - 2.26022 0.750421 -0.228428 - 1.30437 0.503347 -0.0204645 - 0.719333 0.343489 0.106805 - 0.719594 0.383263 0.10683 - 0.731805 0.402304 0.104205 - 0.540368 0.324043 0.145797 - 0.460755 0.280992 0.163072 - 0.394763 0.249484 0.177401 - 0.375047 0.290463 0.181785 - 0.371303 0.295341 0.182611 - 0.362327 0.306525 0.184592 - 0.358378 0.311231 0.185463 - 0.357222 0.376002 0.185847 - 0.355616 0.377553 0.186201 - 0.322143 0.508514 0.193769 - 0.317732 0.537023 0.19479 - 0.304757 0.563989 0.197675 - 0.324646 0.678075 0.19357 - 0.271038 0.63258 0.205169 - 0.139019 1.17152 0.235066 - 0.134024 1.17208 0.236156 - 0.124709 1.18012 0.238204 - -0.0907544 1.16248 0.28516 - -0.170189 1.18886 0.302539 - -0.18828 1.17266 0.306451 - -0.403862 1.27988 0.353689 - -0.434638 1.28072 0.360403 - -0.440094 1.27872 0.361589 - -0.476194 1.27556 0.369456 - -0.491051 0.84257 0.37181 - -0.487387 0.766804 0.370855 - -0.492475 0.739108 0.371908 - -0.493402 0.687902 0.372006 - -0.493312 0.63991 0.371888 - -0.490549 0.587546 0.371178 - -0.493101 0.565152 0.371689 - -0.388117 -0.405466 0.342423 - -0.369211 -0.403359 0.338512 - -0.358002 -0.401784 0.336195 - -0.330778 -0.402518 0.330556 - -0.324164 -0.401706 0.329189 - -0.315252 -0.401484 0.327344 - -0.259754 -0.402747 0.31585 - -0.240752 -0.399952 0.311922 - -0.52187 -1.71994 0.367431 - -0.355256 -2.22434 0.331904 - -0.345749 -2.22594 0.329932 - -0.244372 -2.18791 0.309019 - -0.193116 -2.24867 0.298283 - -0.107584 -2.27596 0.280518 - 0.0178546 -0.43089 0.258314 - 0.0266269 -0.420585 0.256519 - 0.0281065 -0.379464 0.256296 - 0.0286113 -0.359405 0.256233 - 0.033366 -0.340043 0.255288 - 0.0528654 -0.355104 0.25122 - 0.0555013 -0.351722 0.250681 - 0.0639249 -0.356514 0.248927 - 0.0829367 -0.356968 0.24499 - 0.11248 -0.363781 0.238859 - 0.122965 -0.364682 0.236686 - 0.134146 -0.36188 0.234377 - 0.146834 -0.377376 0.231718 - 0.155322 -0.390127 0.229935 - 0.18825 -0.388782 0.22312 - 0.219419 -0.388174 0.216667 - 0.283301 -0.453033 0.203308 - 1.16138 -1.66427 0.019027 - 1.24279 -1.62632 0.00224939 - 1.30376 -1.63182 -0.0103852 - 0.392586 -0.409295 0.18077 - 0.55606 -0.405753 0.14693 - 0.561764 -0.406226 0.145748 - 0.579893 -0.404273 0.141998 - 0.603006 -0.405124 0.137211 - 0.637278 -0.400682 0.130124 - 0.658217 -0.406021 0.125778 - 0.681045 -0.408023 0.121047 - 0.712623 -0.406219 0.114512 - 0.783432 -0.406932 0.0998498 - 0.800002 -0.406751 0.0964195 - 0.806964 -0.401447 0.0949888 - 0.856227 -0.407596 0.0847762 - 0.940739 -0.408262 0.0672767 - 0.995622 -0.411615 0.0559063 - 1.19925 -0.411844 0.013745 - 2.32893 -0.523576 -0.220385 - 2.41015 -0.255985 -0.236654 - 2.41122 -0.245281 -0.236855 - 2.39737 -0.190217 -0.233873 - 2.41318 -0.12691 -0.237019 - 2.41892 -0.0841689 -0.238119 - 2.42117 0.0770674 -0.238256 - 2.41594 0.24935 -0.236822 - 2.30018 0.542032 -0.212255 - 1.8906 0.480643 -0.127577 - 1.31688 0.365268 -0.00902405 - 2.1841 0.766698 -0.187762 - 1.47108 0.658366 -0.0403517 - 0.725173 0.337971 0.113434 - 0.71515 0.352536 0.115539 - 0.721822 0.40023 0.114255 - 0.532378 0.315569 0.153306 - 0.530502 0.32074 0.153705 - 0.461797 0.284052 0.167856 - 0.378798 0.277598 0.185028 - 0.386424 0.363427 0.183624 - 0.376076 0.375746 0.185792 - 0.363108 0.406117 0.188539 - 0.352867 0.434679 0.190717 - 0.340481 0.467048 0.193348 - 0.327169 0.487477 0.196146 - 0.325084 0.488891 0.196581 - 0.307908 0.552106 0.200266 - 0.308682 0.571039 0.200144 - 0.305159 0.576346 0.200885 - 0.299231 0.589581 0.202139 - 0.323549 0.66765 0.197263 - 0.361981 0.75753 0.18949 - 0.549888 1.22854 0.151546 - 0.361376 1.27936 0.190681 - 0.298011 1.28248 0.203807 - 0.258765 1.28697 0.211942 - 0.212434 1.28127 0.221523 - 0.13342 1.16811 0.237652 - 0.0878067 1.16322 0.247086 - 0.0481424 1.16931 0.255311 - 0.0294959 1.24982 0.259336 --0.00677323 1.16489 0.266672 - -0.0120634 1.1828 0.267804 - -0.0241934 1.26054 0.270475 - -0.0465265 1.16262 0.274899 - -0.0516483 1.16535 0.275965 - -0.0859817 1.15694 0.283056 - -0.131226 1.15919 0.292429 - -0.143689 1.17772 0.295047 - -0.178681 1.17142 0.302279 - -0.362326 1.27687 0.340518 - -0.404332 1.27704 0.349216 - -0.434789 1.27695 0.355522 - -0.441235 1.27778 0.356858 - -0.49626 1.2745 0.368245 - -0.495508 1.24132 0.368021 - -0.49576 1.21193 0.368013 - -0.497203 0.85026 0.367573 - -0.497249 0.842032 0.367566 - -0.488404 0.795791 0.36564 - -0.487912 0.716642 0.365377 - -0.494319 0.674635 0.366618 - -0.490042 0.662872 0.365708 - -0.493417 0.534898 0.366145 - -0.393219 -0.405809 0.339035 - -0.382474 -0.405415 0.33693 - -0.356829 -0.402678 0.33191 - -0.34596 -0.404624 0.329776 - -0.287671 -0.400335 0.318361 - -0.254096 -0.396473 0.311789 - -0.252397 -0.397635 0.311453 - -0.248871 -0.40359 0.31075 - -0.232781 -0.400918 0.307602 - -0.224637 -0.407038 0.305994 - -0.208914 -0.403454 0.30292 - -0.154541 -0.405506 0.29226 - -0.221956 -0.644798 0.304984 - -0.523598 -1.74712 0.361853 - -0.520479 -1.8504 0.361031 - -0.516064 -1.86523 0.360136 - -0.4975 -2.14931 0.355919 - -0.405416 -2.22359 0.337721 - 0.00108976 -0.415941 0.261738 - 0.0256762 -0.407598 0.256936 - 0.0584644 -0.353268 0.250621 - 0.13248 -0.367714 0.236086 - 0.139768 -0.368261 0.234657 - 0.167212 -0.386284 0.229241 - 0.169248 -0.386492 0.228842 - 0.194404 -0.38462 0.223916 - 0.312787 -0.459889 0.200561 - 1.18947 -1.62532 0.0263727 - 1.3182 -1.6036 0.00118905 - 0.404218 -0.451817 0.182659 - 0.385142 -0.404479 0.186494 - 0.410338 -0.405918 0.181553 - 0.445938 -0.408407 0.174571 - 0.462699 -0.40582 0.171292 - 0.480306 -0.40332 0.167846 - 0.526721 -0.40505 0.158746 - 0.772463 -0.409174 0.110577 - 0.930651 -0.408034 0.079578 - 1.23748 -0.412152 0.0194366 - 1.33331 -0.411847 0.0006572 - 2.36162 -0.618448 -0.201292 - 2.35731 -0.595081 -0.2004 - 2.41338 -0.408362 -0.211008 - 2.41561 -0.310307 -0.211246 - 2.40618 -0.244286 -0.209264 - 2.42085 -0.127065 -0.211899 - 2.41546 -0.0624557 -0.210712 - 2.41607 -0.030339 -0.210766 - 2.42766 0.109444 -0.212753 - 2.42664 0.130956 -0.212509 - 2.4225 0.152272 -0.211653 - 2.42528 0.271561 -0.211954 - 2.42949 0.370576 -0.212578 - 2.38733 0.550414 -0.20395 - 1.94895 0.682524 -0.117767 - 1.58445 0.609838 -0.0464793 - 1.53505 0.677806 -0.0366604 - 0.721185 0.399267 0.122274 - 0.543502 0.309145 0.156913 - 0.385181 0.261983 0.187845 - 0.411347 0.307238 0.182809 - 0.39804 0.330878 0.185465 - 0.395131 0.358657 0.186092 - 0.378222 0.371054 0.189431 - 0.37663 0.372696 0.189746 - 0.348837 0.429236 0.195309 - 0.350068 0.458749 0.195127 - 0.333466 0.478438 0.198421 - 0.329282 0.52433 0.199335 - 0.327035 0.525753 0.199778 - 0.323756 0.525459 0.20042 - 0.321504 0.526857 0.200864 - 0.31787 0.541853 0.201607 - 0.310923 0.563082 0.203012 - 0.262135 0.618062 0.212685 - 0.409746 1.28031 0.185106 - 0.398187 1.28192 0.187375 - 0.35383 1.27225 0.196048 - 0.348379 1.27377 0.197119 - 0.327238 1.28253 0.201281 - 0.313682 1.27462 0.203921 - 0.304103 1.28313 0.205816 - 0.259218 1.28894 0.214624 - 0.235015 1.28139 0.219352 - 0.206459 1.2792 0.224944 - 0.0783836 1.17785 0.249838 - -0.0975433 1.167 0.284294 - -0.103483 1.17647 0.285477 - -0.16397 1.20626 0.297392 - -0.197481 1.18555 0.303918 - -0.486514 1.27802 0.360751 - -0.496569 1.25558 0.362676 - -0.487922 1.0127 0.360486 - -0.494593 0.85165 0.361465 - -0.491228 0.805607 0.360712 - -0.494146 0.802535 0.361278 - -0.487483 0.720485 0.359805 - -0.492496 0.714421 0.360775 - -0.359291 -0.404148 0.328492 - -0.347066 -0.404624 0.326225 - -0.328731 -0.400982 0.322834 - -0.303147 -0.397794 0.318098 - -0.298002 -0.401895 0.317136 - -0.2359 -0.400695 0.305627 - -0.199234 -0.404629 0.298823 - -0.175914 -0.396286 0.294517 - -0.156467 -0.398511 0.290908 - -0.524969 -1.62108 0.356727 - -0.528519 -1.75858 0.357105 - -0.516984 -2.06641 0.354341 - -0.5199 -2.15541 0.354701 - -0.472246 -2.16073 0.345857 - -0.221992 -2.22988 0.299329 - -0.174191 -2.23543 0.290457 --0.00131225 -0.424905 0.262094 - 0.0151319 -0.426929 0.259042 - 0.0246381 -0.43565 0.257262 - 0.0276533 -0.385455 0.256806 - 0.0375126 -0.345657 0.255059 - 0.0551143 -0.353703 0.25178 - 0.0648359 -0.356263 0.249973 - 0.0694166 -0.355469 0.249125 - 0.139486 -0.362982 0.236122 - 0.202076 -0.391873 0.224461 - 0.223932 -0.384452 0.220425 - 0.225088 -0.382622 0.220215 - 0.269304 -0.4338 0.211914 - 0.52145 -0.819395 0.164392 - 0.329645 -0.494255 0.200607 - 0.346901 -0.496845 0.197403 - 0.33826 -0.453934 0.199092 - 1.18777 -1.60564 0.0392834 - 1.24798 -1.61293 0.0281078 - 0.760169 -0.903109 0.119972 - 0.759566 -0.894441 0.120102 - 0.782042 -0.897123 0.11593 - 0.531222 -0.408091 0.163417 - 0.685498 -0.409555 0.134817 - 0.688097 -0.40705 0.134341 - 0.706943 -0.405884 0.13085 - 0.715526 -0.40671 0.129257 - 0.733613 -0.408642 0.1259 - 0.793626 -0.402257 0.114789 - 0.818218 -0.405864 0.110224 - 0.922179 -0.408514 0.0909479 - 1.05793 -0.409196 0.0657842 - 1.29626 -0.412217 0.0216004 - 1.31398 -0.411523 0.0183165 - 2.35362 -0.626368 -0.174829 - 2.39829 -0.17891 -0.1822 - 2.59913 -0.0440895 -0.219152 - 2.61205 0.0365987 -0.221384 - 2.61974 0.0483011 -0.222785 - 2.61712 0.106202 -0.222182 - 2.61646 0.175834 -0.221918 - 2.61388 0.198906 -0.221393 - 2.61208 0.222028 -0.221013 - 2.61009 0.245134 -0.220596 - 2.62734 0.364549 -0.223551 - 2.6273 0.400133 -0.223471 - 2.61603 0.481662 -0.221216 - 2.51671 0.544295 -0.202679 - 2.12644 0.509014 -0.13041 - 1.65532 0.442442 -0.0432177 - 1.29801 0.364931 0.0228565 - 0.908839 0.272184 0.0948052 - 0.904592 0.279585 0.0956075 - 1.99911 0.679233 -0.106461 - 1.49419 0.666435 -0.0128946 - 0.719184 0.357452 0.130133 - 0.716585 0.375925 0.130653 - 0.577176 0.324865 0.15639 - 0.518408 0.306422 0.167246 - 0.390467 0.258037 0.190863 - 0.40083 0.348001 0.189125 - 0.388758 0.358688 0.191384 - 0.385667 0.362055 0.191964 - 0.380417 0.363319 0.19294 - 0.371634 0.373826 0.194589 - 0.365261 0.39386 0.195811 - 0.359999 0.420004 0.19684 - 0.349413 0.449363 0.198862 - 0.347742 0.459466 0.199192 - 0.339696 0.456835 0.200678 - 0.327528 0.516129 0.203054 - 0.322358 0.54392 0.204069 - 0.328366 0.662128 0.203196 - 0.569821 1.18663 0.159506 - 0.270986 0.63166 0.21377 - 0.259929 0.696323 0.215951 - 0.37918 1.27742 0.195028 - 0.218175 1.28232 0.224883 - 0.0972763 1.16347 0.247051 - -0.0132867 1.1958 0.267611 - -0.0480905 1.17161 0.274013 - -0.0770686 1.22594 0.279495 - -0.237252 1.16968 0.309072 - -0.266357 1.15886 0.314445 - -0.334953 1.27616 0.327399 - -0.387805 1.27387 0.337191 - -0.393267 1.2721 0.3382 - -0.469693 1.27984 0.352382 - -0.498004 1.25558 0.35758 - -0.49468 1.21693 0.356885 - -0.495667 1.20457 0.357043 - -0.493233 1.00959 0.356196 - -0.492559 0.926329 0.355901 - -0.493539 0.830952 0.355889 - -0.490213 0.771523 0.355152 - -0.48678 0.685111 0.354339 - -0.491115 0.642805 0.355057 - -0.392822 -0.402991 0.330315 - -0.317374 -0.403697 0.317157 - -0.315636 -0.40513 0.316851 - -0.284476 -0.404243 0.31142 - -0.280422 -0.402293 0.310717 - -0.25816 -0.399791 0.30684 - -0.244257 -0.408944 0.304397 - -0.213844 -0.397044 0.299118 - -0.175824 -0.39891 0.292484 - -0.169452 -0.39857 0.291373 - -0.213403 -0.642142 0.298543 - -0.524168 -1.79488 0.350393 - -0.518456 -2.10458 0.348769 - -0.516544 -2.136 0.348372 - -0.398762 -2.22835 0.327645 - -0.003688 -0.42886 0.262406 - 0.0073713 -0.418999 0.260498 - 0.0295073 -0.343246 0.256791 - 0.0358972 -0.348776 0.255666 - 0.038804 -0.347512 0.255162 - 0.0594763 -0.354028 0.251544 - 0.0800198 -0.362518 0.247944 - 0.0823131 -0.357946 0.247553 - 0.0926704 -0.360686 0.245742 - 0.137514 -0.367903 0.237907 - 0.150691 -0.369269 0.235607 - 0.181385 -0.378707 0.230235 - 0.196514 -0.393531 0.227567 - 0.202905 -0.393659 0.226452 - 0.204595 -0.392788 0.226159 - 0.207055 -0.38925 0.225738 - 0.211319 -0.389229 0.224994 - 0.339031 -0.498835 0.202501 - 0.349931 -0.500951 0.200596 - 1.32673 -1.63764 0.0279564 - 0.4828 -0.404605 0.177622 - 0.561665 -0.397243 0.163885 - 0.596922 -0.407035 0.157717 - 0.598666 -0.404419 0.157418 - 0.614546 -0.403643 0.154651 - 0.779822 -0.403274 0.125831 - 0.807887 -0.404556 0.120934 - 0.839676 -0.411454 0.115377 - 0.876065 -0.405877 0.109043 - 1.01744 -0.403139 0.0843951 - 1.04939 -0.405261 0.0788202 - 1.14029 -0.406408 0.062966 - 1.21719 -0.410016 0.0495494 - 2.30305 -0.430204 -0.139842 - 2.4065 -0.308048 -0.157633 - 2.4058 -0.211239 -0.157315 - 2.53166 -0.132432 -0.179101 - 2.77615 -0.083832 -0.221638 - 2.77898 -0.0470668 -0.222056 - 2.76776 0.247205 -0.219502 - 2.76946 0.272034 -0.219748 - 2.82606 0.353428 -0.229452 - 2.9144 0.443207 -0.244675 - 2.89664 0.492982 -0.241477 - 2.42109 0.545043 -0.158445 - 2.14156 0.511773 -0.109769 - 1.95433 0.485126 -0.0771748 - 0.915545 0.278202 0.103547 - 1.95931 0.683829 -0.0776389 - 1.41272 0.636358 0.017577 - 0.721628 0.354292 0.137517 - 0.717001 0.363752 0.138343 - 0.712499 0.381261 0.139163 - 0.515147 0.301127 0.173415 - 0.513848 0.303373 0.173646 - 0.427101 0.261558 0.188688 - 0.4086 0.301871 0.191996 - 0.377412 0.35082 0.197533 - 0.357028 0.416199 0.201221 - 0.349482 0.453256 0.202612 - 0.345966 0.46097 0.203241 - 0.341127 0.475689 0.204114 - 0.322009 0.543058 0.207585 - 0.315941 0.590035 0.208738 - 0.584589 1.20301 0.163136 - 0.242449 0.599254 0.221573 - 0.270589 0.745604 0.216963 - 0.333313 1.28207 0.207114 - 0.274645 1.27961 0.217339 - 0.202604 1.29193 0.229927 - 0.129212 1.18257 0.242503 - 0.0783411 1.18783 0.251384 - 0.0527592 1.18811 0.255846 - 0.00178343 1.16298 0.264684 - -0.0666704 1.21867 0.276734 - -0.107956 1.20932 0.283914 - -0.118348 1.20825 0.285724 - -0.139298 1.1655 0.28929 - -0.265754 1.17467 0.31136 - -0.34156 1.27462 0.324782 - -0.491914 1.26838 0.350988 - -0.491703 1.19168 0.350796 - -0.492783 1.06287 0.350722 - -0.49435 1.05435 0.350978 - -0.494288 0.987326 0.350831 - -0.492289 0.895226 0.350296 - -0.488631 0.870854 0.349609 - -0.491097 0.857813 0.350012 - -0.494277 0.854738 0.35056 - -0.486509 0.735299 0.348963 - -0.49482 0.727035 0.350396 - -0.492821 0.717458 0.350028 - -0.496186 0.647514 0.350472 - -0.353852 -0.406022 0.318726 - -0.334432 -0.40858 0.315592 - -0.281569 -0.402293 0.307088 - -0.228664 -0.405138 0.298559 - -0.224929 -0.402717 0.297963 - -0.203586 -0.401012 0.294528 - -0.186598 -0.406356 0.29178 - -0.175438 -0.400624 0.289994 - -0.160579 -0.399621 0.287602 - -0.15713 -0.401083 0.287043 - -0.211631 -0.643112 0.295333 - -0.528775 -1.64717 0.344392 - -0.519375 -1.66708 0.342838 - -0.518636 -2.13794 0.341765 - -0.194783 -2.23075 0.289403 - 0.01786 -0.425845 0.258802 - 0.0303005 -0.340151 0.256971 - 0.068196 -0.352515 0.250841 - 0.0784691 -0.356639 0.249177 - 0.14513 -0.374566 0.238402 - 0.162218 -0.375221 0.235647 - 0.165875 -0.366007 0.235077 - 0.16745 -0.365299 0.234825 - 0.205594 -0.38659 0.228636 - 0.211701 -0.390111 0.227645 - 0.215718 -0.393604 0.226991 - 0.225849 -0.395951 0.225354 - 0.224526 -0.381756 0.225596 - 1.25139 -1.68652 0.0575222 - 0.705513 -0.835224 0.147189 - 1.34305 -1.54179 0.0430477 - 1.35629 -1.52991 0.0409394 - 0.418338 -0.398699 0.194338 - 0.442849 -0.404357 0.190378 - 0.506743 -0.402398 0.180088 - 0.558897 -0.402141 0.171686 - 0.657586 -0.399494 0.155793 - 0.748635 -0.411661 0.1411 - 0.76087 -0.405537 0.139141 - 0.764358 -0.403129 0.138584 - 0.821462 -0.406305 0.129378 - 0.877424 -0.405877 0.120363 - 0.905199 -0.409235 0.115882 - 0.936675 -0.40883 0.110811 - 0.970112 -0.40843 0.105425 - 0.992789 -0.407835 0.101773 - 1.15433 -0.410738 0.0757432 - 2.35921 -0.614453 -0.11878 - 2.39112 -0.56689 -0.123825 - 2.39835 -0.557467 -0.124971 - 2.38539 -0.510335 -0.122788 - 2.27741 -0.424577 -0.105217 - 2.42384 -0.37503 -0.128707 - 2.41248 -0.297418 -0.126721 - 2.40954 -0.15775 -0.125964 - 2.9914 -0.103374 -0.219593 - 2.9833 -0.076759 -0.218234 - 2.98133 0.0021891 -0.217757 - 2.985 0.041683 -0.218269 - 2.98085 0.0547727 -0.217574 - 3.00479 0.16136 -0.221215 - 2.98957 0.266538 -0.218549 - 2.99571 0.307071 -0.219456 - 3.21127 0.458567 -0.253878 - 2.61527 0.551548 -0.15767 - 1.25323 0.511131 0.0616777 - 1.2506 0.522895 0.0621242 - 1.50468 0.668855 0.0214867 - 0.779143 0.357204 0.137742 - 0.720215 0.357009 0.147235 - 0.717114 0.363301 0.147748 - 0.553914 0.314076 0.17394 - 0.394345 0.25292 0.199523 - 0.385006 0.256396 0.201035 - 0.401997 0.275564 0.198337 - 0.386332 0.35901 0.201029 - 0.38251 0.361662 0.20165 - 0.375335 0.370582 0.202824 - 0.372806 0.398125 0.203288 - 0.370718 0.413583 0.203655 - 0.372203 0.418934 0.203427 - 0.362458 0.426145 0.205011 - 0.356459 0.458066 0.206043 - 0.342537 0.524415 0.20842 - 0.294975 0.672416 0.216382 - 0.279243 0.780706 0.219136 - 0.373882 1.27809 0.204897 - 0.343974 1.2772 0.209713 - 0.310623 1.28472 0.215102 - 0.264801 1.28781 0.22249 - 0.189061 1.27777 0.234672 - 0.132933 1.17208 0.2435 - 0.0755349 1.23706 0.252879 - 0.0460837 1.15632 0.25746 - 0.0219346 1.2179 0.261475 --0.00890632 1.16989 0.266346 - -0.28207 1.17093 0.310356 - -0.343677 1.27751 0.320497 - -0.356306 1.28013 0.322537 - -0.434222 1.27703 0.335083 - -0.458898 1.27653 0.339058 - -0.496241 1.24355 0.345007 - -0.491405 1.09304 0.343923 - -0.489003 1.06327 0.343476 - -0.48992 0.915812 0.343325 - -0.491589 0.747424 0.343252 - -0.492229 0.651951 0.343162 - -0.496804 0.607102 0.343808 - -0.38693 -0.401543 0.319849 - -0.378575 -0.406973 0.318582 - -0.329836 -0.405484 0.311255 - -0.230714 -0.403235 0.296353 - -0.22323 -0.406485 0.295221 - -0.1983 -0.406448 0.291472 - -0.184308 -0.404497 0.289372 - -0.173202 -0.398694 0.287713 - -0.163779 -0.400717 0.286292 - -0.150055 -0.396716 0.284236 - -0.211121 -0.639329 0.292929 - -0.524245 -1.67851 0.337917 - -0.528876 -1.71899 0.338532 - -0.527641 -1.79679 0.338189 - -0.419817 -2.22173 0.321114 - -0.401529 -2.23032 0.318346 - -0.370622 -2.22369 0.313712 - -0.282332 -2.22402 0.300433 - -0.272733 -2.22527 0.298987 - -0.0106123 -0.438673 0.263181 - 0.0197803 -0.441783 0.258604 - 0.0284955 -0.3653 0.257448 - 0.034313 -0.339808 0.256625 - 0.0396612 -0.349359 0.255801 - 0.0423635 -0.346066 0.255401 - 0.0467234 -0.344564 0.254749 - 0.0559416 -0.356459 0.253338 - 0.0647354 -0.362184 0.252004 - 0.0726124 -0.35265 0.250839 - 0.0764026 -0.364131 0.250246 - 0.0907132 -0.362034 0.248098 - 0.093599 -0.360303 0.247667 - 0.0982556 -0.359114 0.24697 - 0.128775 -0.369755 0.242358 - 0.133251 -0.37244 0.24168 - 0.162046 -0.375221 0.237344 - 0.165278 -0.37383 0.236861 - 0.173659 -0.366766 0.235614 - 0.18104 -0.374315 0.234489 - 0.30934 -0.485224 0.21497 - 0.320985 -0.489551 0.21321 - 0.326702 -0.445532 0.212439 - 0.381649 -0.41021 0.204248 - 0.402187 -0.399931 0.20118 - 0.447344 -0.401154 0.194386 - 0.45719 -0.406522 0.192895 - 0.476622 -0.402189 0.189981 - 0.57494 -0.405892 0.175188 - 0.580738 -0.406243 0.174315 - 0.684598 -0.407513 0.158693 - 0.774797 -0.408244 0.145127 - 0.780062 -0.406693 0.144339 - 0.784425 -0.400301 0.143695 - 0.825914 -0.408072 0.13744 - 0.903534 -0.408005 0.125767 - 1.08189 -0.411249 0.0989385 - 1.17704 -0.40675 0.0846375 - 1.40295 -0.410601 0.0506565 - 1.5672 -0.421763 0.0259333 - 2.28457 -0.425303 -0.0819583 - 2.32824 -0.422866 -0.0885198 - 2.39795 -0.188584 -0.0985304 - 2.39875 -0.178029 -0.0986285 - 3.18543 -0.0818491 -0.216741 - 3.18598 0.058463 -0.216539 - 3.18188 0.297425 -0.21544 - 3.41397 0.440918 -0.250052 - 3.41581 0.487105 -0.250237 - 3.39472 0.668602 -0.246697 - 2.41769 0.542437 -0.100019 - 1.69201 0.442157 0.00891009 - 0.922051 0.275031 0.124364 - 1.54422 0.606038 0.031468 - 1.25127 0.522511 0.075354 - 0.715852 0.358371 0.155542 - 0.517347 0.304898 0.185287 - 0.512155 0.307849 0.186073 - 0.389495 0.264237 0.204432 - 0.436824 0.310992 0.197409 - 0.408847 0.298907 0.201592 - 0.413619 0.343038 0.200963 - 0.383727 0.42072 0.205616 - 0.367548 0.424501 0.208056 - 0.3551 0.443994 0.209968 - 0.353794 0.446315 0.210169 - 0.324273 0.599238 0.214918 - 0.343743 0.663453 0.21212 - 0.571631 1.25616 0.179047 - 0.38718 0.866319 0.205997 - 0.242645 0.585114 0.227165 - 0.269147 0.721661 0.223456 - 0.409082 1.2746 0.203529 - 0.357445 1.28285 0.211312 - 0.326531 1.27768 0.21595 - 0.305564 1.288 0.219124 - 0.297784 1.27956 0.220277 - 0.286518 1.2811 0.221975 - 0.258047 1.28305 0.22626 - 0.246966 1.28522 0.227931 - 0.230139 1.28731 0.230466 - 0.117296 1.22791 0.247316 - 0.0742965 1.22108 0.253769 - 0.0268048 1.22083 0.26091 --0.00430655 1.16595 0.265478 - -0.0345195 1.16626 0.270022 - -0.0546412 1.16535 0.273047 - -0.0898882 1.16392 0.278344 - -0.115234 1.21476 0.282259 - -0.126454 1.17331 0.283862 - -0.168333 1.17779 0.290169 - -0.209994 1.20627 0.296492 - -0.498517 1.02254 0.339511 - -0.490231 0.914059 0.338045 - -0.495162 0.690753 0.338335 - -0.499099 0.647514 0.33884 - -0.49573 0.637456 0.338313 - -0.494264 0.586744 0.33799 - -0.496876 0.564419 0.338337 - -0.494067 0.546702 0.337879 - -0.389339 -0.402964 0.316019 - -0.36752 -0.404712 0.312965 - -0.365768 -0.406352 0.312717 - -0.361334 -0.405034 0.3121 - -0.297336 -0.402999 0.303158 - -0.237217 -0.400918 0.294758 - -0.232724 -0.401329 0.29413 - -0.202993 -0.405516 0.289965 - -0.198133 -0.404666 0.289287 - -0.186722 -0.408109 0.287685 - -0.158872 -0.402008 0.283805 - -0.181119 -0.512389 0.286691 - -0.529938 -1.66759 0.333119 - -0.520575 -1.76902 0.331605 - -0.469095 -2.16772 0.323604 - -0.410687 -2.22064 0.315332 - -0.341944 -2.22354 0.305717 - -0.157455 -2.23196 0.279911 - 0.00599677 -0.410999 0.26074 - 0.0210074 -0.433724 0.258596 - 0.0273134 -0.352325 0.257879 - 0.039192 -0.348364 0.256226 - 0.0644892 -0.353047 0.252681 - 0.0740011 -0.353335 0.25135 - 0.0825743 -0.363814 0.250131 - 0.0857158 -0.363123 0.249693 - 0.0881816 -0.359481 0.249356 - 0.0897344 -0.359115 0.24914 - 0.095583 -0.362824 0.248314 - 0.111172 -0.358521 0.246144 - 0.139437 -0.37014 0.242169 - 0.145278 -0.371146 0.241351 - 0.148988 -0.366479 0.240842 - 0.168682 -0.364585 0.238093 - 0.176392 -0.373121 0.236998 - 0.1854 -0.375459 0.235734 - 0.188926 -0.370368 0.235251 - 0.32352 -0.466221 0.216243 - 0.34948 -0.477067 0.212592 - 0.361129 -0.467024 0.210984 - 0.387846 -0.416814 0.207351 - 0.463923 -0.405161 0.19674 - 0.481678 -0.402678 0.194263 - 0.496066 -0.403938 0.192249 - 0.508039 -0.406481 0.190571 - 0.586862 -0.410254 0.179545 - 0.692928 -0.408064 0.164722 - 0.760629 -0.408867 0.155257 - 0.794001 -0.404835 0.1506 - 0.807224 -0.402774 0.148756 - 0.871214 -0.402115 0.139813 - 1.57965 -0.424602 0.0407375 - 2.41719 -0.383841 -0.0762571 - 2.41315 -0.329023 -0.0755813 - 2.41228 -0.221498 -0.0752426 - 2.49621 -0.129955 -0.0867897 - 3.41337 0.047541 -0.214638 - 3.41501 0.107675 -0.214746 - 3.41551 0.12273 -0.214785 - 3.52574 0.454752 -0.229524 - 2.97354 0.625523 -0.151988 - 2.3963 0.547979 -0.0714548 - 3.60022 0.924479 -0.238986 - 0.89382 0.279103 0.138028 - 0.891376 0.286917 0.138386 - 0.941609 0.321483 0.131434 - 0.930831 0.331481 0.13296 - 0.927527 0.334875 0.133429 - 0.921255 0.346326 0.134329 - 0.89269 0.36252 0.138355 - 0.871487 0.389881 0.141374 - 0.718678 0.340071 0.162634 - 0.709012 0.398253 0.164103 - 0.390523 0.250212 0.208324 - 0.42498 0.337087 0.203683 - 0.416036 0.341874 0.204943 - 0.410066 0.349049 0.205792 - 0.399325 0.361349 0.207318 - 0.388817 0.393994 0.208853 - 0.388764 0.407941 0.208888 - 0.386132 0.415905 0.209272 - 0.382524 0.419239 0.209783 - 0.372288 0.445427 0.211267 - 0.373958 0.459562 0.211062 - 0.369476 0.483439 0.211737 - 0.378253 0.527819 0.2106 - 0.359787 0.540617 0.213207 - 0.336785 0.585408 0.216513 - 0.547493 1.21577 0.188332 - 0.249248 0.594232 0.228767 - 0.24629 0.609474 0.229211 - 0.392097 1.2779 0.210179 - 0.369134 1.28163 0.213397 - 0.274373 1.27863 0.226637 - 0.171491 1.27512 0.241011 - 0.0406534 1.16848 0.259085 - 0.0156792 1.20296 0.262646 - 0.0103567 1.17099 0.263325 - -0.0160248 1.23179 0.267136 - -0.0680599 1.21068 0.274367 - -0.0732911 1.21034 0.275098 - -0.0771301 1.19003 0.275593 - -0.126097 1.16437 0.282386 - -0.14763 1.17276 0.285413 - -0.158458 1.21468 0.287012 - -0.261151 1.18874 0.301314 - -0.328346 1.27915 0.31089 - -0.350676 1.27403 0.314001 - -0.356178 1.27244 0.314767 - -0.388585 1.28039 0.319313 - -0.475808 1.28171 0.331508 - -0.493731 1.24669 0.333943 - -0.4939 1.18708 0.333846 - -0.49263 0.955419 0.333201 - -0.490786 0.922392 0.332876 - -0.488665 0.753469 0.332239 - -0.493823 0.719667 0.332891 - -0.494543 0.669687 0.332891 - -0.49534 0.629778 0.332922 - -0.314629 -0.39891 0.302132 - -0.307937 -0.39407 0.301278 - -0.244082 -0.403005 0.293023 - -0.242336 -0.404098 0.292795 - -0.236773 -0.40284 0.29208 - -0.232264 -0.403235 0.291498 - -0.193136 -0.40197 0.286452 - -0.166698 -0.404393 0.283037 - -0.157047 -0.400877 0.281799 - -0.518713 -1.87717 0.325478 - -0.526312 -2.07706 0.326055 - -0.519513 -2.0881 0.325156 - -0.461201 -2.17175 0.317465 - -0.372003 -2.22073 0.305859 - -0.196869 -2.23075 0.283246 - -0.131976 -2.28183 0.274772 - -0.1221 -2.28241 0.273497 - -0.011708 -0.443669 0.262964 - 0.0263709 -0.436481 0.258066 - 0.0274833 -0.389356 0.258017 - 0.0557729 -0.349309 0.254449 - 0.0853965 -0.363123 0.250599 - 0.0871866 -0.363742 0.250367 - 0.120248 -0.372373 0.246085 - 0.122754 -0.374724 0.245757 - 0.159641 -0.374981 0.240998 - 0.221107 -0.380112 0.233058 - 0.313779 -0.469251 0.220923 - 0.315807 -0.467889 0.220665 - 0.358968 -0.48125 0.21507 - 0.74854 -0.924258 0.163921 - 0.464396 -0.401827 0.20163 - 0.491044 -0.410385 0.198175 - 0.571702 -0.403009 0.187784 - 0.615086 -0.40633 0.182181 - 0.627049 -0.398757 0.180653 - 0.622895 -0.384735 0.181217 - 0.626203 -0.379286 0.180801 - 0.714251 -0.40376 0.169394 - 0.818566 -0.403655 0.155937 - 1.2011 -0.408316 0.10658 - 1.43752 -0.412957 0.0760721 - 1.48214 -0.411801 0.0703179 - 2.37898 -0.572769 -0.0457011 - 2.41286 -0.404418 -0.0497331 - 2.41615 -0.350651 -0.0500481 - 2.40722 -0.199464 -0.0485917 - 3.69153 -0.0459536 -0.213962 - 3.6918 -0.0135178 -0.213931 - 3.69064 0.262542 -0.213225 - 3.54768 0.504591 -0.194295 - 3.54762 0.632416 -0.194029 - 3.55465 0.698288 -0.194803 - 3.5516 0.713896 -0.194378 - 3.57317 0.86636 -0.196853 - 1.67015 0.451046 0.0478043 - 0.900393 0.324717 0.14685 - 0.88242 0.344596 0.149208 - 0.874491 0.359216 0.150261 - 0.863058 0.381223 0.15178 - 0.720368 0.356123 0.170137 - 0.716414 0.389882 0.170715 - 0.729499 0.401193 0.16905 - 0.520988 0.303649 0.195752 - 0.497456 0.298567 0.198777 - 0.48175 0.291899 0.20079 - 0.390624 0.250212 0.212461 - 0.428506 0.299143 0.207673 - 0.420217 0.32722 0.208799 - 0.410943 0.346619 0.210034 - 0.402372 0.364041 0.211175 - 0.408078 0.57521 0.210865 - 0.252859 0.595922 0.23093 - 0.273004 0.742552 0.228627 - 0.42879 1.25972 0.209573 - 0.41791 1.28232 0.211023 - 0.392758 1.27982 0.214262 - 0.327275 1.28059 0.222711 - 0.268752 1.2798 0.230259 - 0.195496 1.28685 0.239724 - 0.143661 1.18284 0.246201 - 0.127262 1.17462 0.2483 - 0.121821 1.22542 0.249104 - 0.0908991 1.16784 0.252977 - 0.0813038 1.17653 0.254232 - 0.0352057 1.16962 0.260165 - 0.0204573 1.20491 0.262139 - -0.050602 1.16362 0.271222 - -0.0866805 1.17231 0.275894 - -0.147665 1.16781 0.283752 - -0.230268 1.16496 0.294402 - -0.325496 1.26465 0.306888 - -0.353809 1.28172 0.310575 - -0.393361 1.27292 0.31566 - -0.470716 1.28195 0.325657 - -0.49863 1.25596 0.329205 - -0.497653 1.15109 0.328868 - -0.495183 1.0687 0.328383 - -0.494245 0.966474 0.328056 - -0.489367 0.927214 0.327347 - -0.493083 0.751282 0.327472 - -0.491871 0.721862 0.327256 - -0.48816 0.709842 0.326753 - -0.489174 0.643258 0.32675 - -0.49473 0.589708 0.327359 - -0.496385 0.537169 0.327466 - -0.395128 -0.403343 0.308231 - -0.388835 -0.403987 0.307485 - -0.364539 -0.406509 0.304605 - -0.356354 -0.404534 0.303641 - -0.335196 -0.39797 0.301151 - -0.330915 -0.410749 0.300619 - -0.300769 -0.40166 0.29707 - -0.29196 -0.400843 0.29603 - -0.289062 -0.404243 0.29568 - -0.265762 -0.408449 0.292914 - -0.251782 -0.398556 0.29128 - -0.173927 -0.400394 0.282065 - -0.505434 -2.14542 0.317774 - -0.496361 -2.14861 0.316694 - -0.419959 -2.207 0.307536 - -0.412609 -2.22064 0.306639 - -0.334492 -2.22801 0.297382 - -0.306879 -2.24219 0.294086 - -0.014296 -0.448586 0.263081 - 0.00875186 -0.416981 0.260418 - 0.027852 -0.374283 0.258244 - 0.028492 -0.359211 0.258198 - 0.0396276 -0.345228 0.256909 - 0.0426182 -0.344909 0.256556 - 0.0508621 -0.349946 0.25557 - 0.0538931 -0.349528 0.255213 - 0.0624145 -0.354289 0.254195 - 0.0846389 -0.361171 0.251551 - 0.087766 -0.360456 0.251183 - 0.154773 -0.368255 0.243239 - 0.196729 -0.378537 0.238254 - 0.281719 -0.454254 0.228046 - 0.292576 -0.467482 0.226735 - 0.441302 -0.412845 0.209248 - 0.457075 -0.405856 0.207396 - 0.474073 -0.402963 0.205391 - 0.528269 -0.403834 0.198976 - 0.572938 -0.39994 0.193699 - 0.79175 -0.403021 0.167804 - 0.836979 -0.403425 0.162452 - 0.870962 -0.405924 0.158426 - 0.966799 -0.410345 0.147078 - 0.975826 -0.404168 0.146022 - 1.00968 -0.40796 0.142008 - 1.06297 -0.408123 0.135703 - 1.08229 -0.404751 0.133425 - 1.21058 -0.405267 0.118245 - 2.31795 -0.622319 -0.0132138 - 2.38654 -0.42109 -0.0209231 - 2.40881 -0.306166 -0.023327 - 2.41138 -0.28503 -0.0235881 - 2.41301 -0.157168 -0.0235242 - 3.9928 -0.0496501 -0.210223 - 3.99199 -0.03212 -0.210092 - 3.99646 0.248762 -0.210056 - 3.9805 0.388399 -0.207886 - 3.75908 0.433484 -0.181597 - 3.54824 0.456529 -0.156605 - 3.54623 0.472093 -0.156336 - 3.55479 0.584806 -0.157121 - 3.5579 0.681919 -0.157294 - 0.983937 0.2881 0.146457 - 0.907946 0.278706 0.155429 - 0.892268 0.295336 0.157317 - 0.879771 0.361113 0.158928 - 0.871778 0.362269 0.159876 - 0.724523 0.346226 0.177267 - 0.718105 0.370483 0.178075 - 0.41937 0.323553 0.213326 - 0.420311 0.32722 0.213222 - 0.410899 0.337418 0.214356 - 0.409434 0.339198 0.214533 - 0.45177 0.474721 0.209797 - 0.435218 0.521589 0.21185 - 0.441186 0.568033 0.211237 - 0.438721 0.569944 0.211533 - 0.416979 0.582393 0.21413 - 0.381351 0.595709 0.218372 - 0.377708 0.595664 0.218803 - 0.359054 0.600124 0.221019 - 0.35645 0.601673 0.221331 - 0.358584 0.656734 0.221189 - 0.355736 0.658281 0.221529 - 0.351404 0.663993 0.222053 - 0.428129 0.855865 0.213362 - 0.600341 1.273 0.193826 - 0.593981 1.27379 0.19458 - 0.570991 1.25252 0.197257 - 0.248628 0.593308 0.234071 - 0.247193 0.6047 0.234264 - 0.288726 0.819675 0.229783 - 0.368098 1.27778 0.221314 - 0.360944 1.27359 0.222152 - 0.333518 1.28207 0.225414 - 0.252538 1.28611 0.235004 - 0.120561 1.21546 0.250476 - 0.0497512 1.16313 0.258749 --0.00069888 1.16898 0.26473 - -0.0230847 1.26468 0.267571 - -0.0777287 1.18205 0.27387 - -0.117738 1.22073 0.278682 - -0.18986 1.1686 0.28711 - -0.370809 1.27495 0.308734 - -0.408129 1.27792 0.313155 - -0.482538 1.27678 0.321957 - -0.487705 1.27369 0.322562 - -0.496921 1.21823 0.323541 - -0.498026 1.10978 0.323453 - -0.48802 0.793411 0.321632 - -0.490923 0.790391 0.321969 - -0.49218 0.681887 0.321899 - -0.493206 0.602406 0.321861 - -0.395987 -0.403343 0.304291 - -0.290977 -0.405857 0.292921 - -0.28571 -0.402293 0.292358 - -0.278686 -0.407325 0.291588 - -0.267688 -0.406427 0.290399 - -0.250211 -0.398838 0.288523 - -0.219223 -0.402383 0.285162 - -0.212072 -0.401777 0.284389 - -0.203763 -0.407321 0.283479 - -0.188785 -0.399205 0.281874 - -0.18099 -0.400723 0.281028 - -0.156168 -0.40066 0.278341 - -0.521243 -1.84793 0.314941 - -0.513334 -1.91451 0.313952 - -0.519189 -2.00507 0.314403 - -0.523056 -2.13309 0.314564 - -0.489313 -2.15664 0.310865 - -0.296671 -2.23462 0.289858 - -0.279022 -2.25106 0.287915 - -0.264911 -2.21655 0.286457 - -0.169386 -2.23721 0.276077 - -0.0128167 -0.449665 0.262728 --0.00252123 -0.417941 0.261677 - 0.0120021 -0.41893 0.260104 - 0.0324342 -0.335822 0.258059 - 0.036353 -0.346516 0.257614 - 0.0376643 -0.344382 0.257476 - 0.0480757 -0.355299 0.256327 - 0.0566303 -0.360194 0.255392 - 0.111721 -0.363314 0.249423 - 0.113583 -0.363797 0.24922 - 0.120404 -0.369003 0.248472 - 0.127106 -0.367859 0.247749 - 0.142008 -0.374237 0.246123 - 0.164869 -0.366007 0.243665 - 0.178237 -0.374177 0.242202 - 0.192456 -0.351337 0.240709 - 0.362545 -0.486071 0.22203 - 0.767067 -0.989384 0.177236 - 0.750496 -0.933755 0.179141 - 0.384221 -0.398467 0.21986 - 0.408248 -0.405583 0.217245 - 0.412123 -0.405918 0.216825 - 0.518465 -0.406987 0.205314 - 0.619984 -0.405286 0.19433 - 0.666772 -0.407587 0.189261 - 0.720331 -0.40671 0.183466 - 0.738643 -0.404455 0.181489 - 0.750879 -0.406947 0.18016 - 0.793126 -0.407846 0.175586 - 0.83041 -0.408955 0.171548 - 0.853614 -0.406642 0.169041 - 0.924733 -0.406504 0.161344 - 1.07668 -0.407713 0.144897 - 1.14807 -0.406408 0.137173 - 1.39839 -0.414211 0.110066 - 2.39603 -0.542491 0.00183433 - 2.29415 -0.425122 0.0130964 - 2.40117 -0.187962 0.00199112 - 4.32827 0.00315977 -0.206193 - 4.3148 0.116679 -0.204507 - 4.32187 0.173778 -0.205157 - 3.63547 0.418788 -0.130376 - 3.56069 0.457671 -0.122204 - 3.5578 0.536779 -0.121732 - 3.56041 0.649422 -0.121788 - 2.4173 0.562115 0.00175396 - 3.57984 0.849507 -0.123489 - 0.907327 0.28267 0.164615 - 0.888595 0.328764 0.166735 - 0.870074 0.370263 0.168823 - 0.727887 0.33989 0.18415 - 0.723021 0.357009 0.184712 - 0.720767 0.391793 0.185025 - 0.440096 0.268882 0.215155 - 0.393092 0.26649 0.220237 - 0.426953 0.323535 0.216687 - 0.409545 0.35148 0.218628 - 0.460068 0.470942 0.2134 - 0.454491 0.485947 0.214034 - 0.449357 0.510823 0.214639 - 0.432889 0.599253 0.2166 - 0.391483 0.617663 0.221118 - 0.383497 0.616781 0.22198 - 0.355233 0.6574 0.225121 - 0.24927 0.610265 0.236495 - 0.244694 0.630341 0.23703 - 0.248641 0.649161 0.236641 - 0.284213 0.795792 0.233086 - 0.429871 1.26257 0.218261 - 0.42502 1.26632 0.218793 - 0.42201 1.27575 0.219138 - 0.380266 1.27838 0.223661 - 0.374717 1.28001 0.224265 - 0.363598 1.28321 0.225475 - 0.234207 1.28139 0.239475 - 0.0493243 1.16213 0.259245 - 0.0307631 1.23872 0.261408 - -0.0112996 1.16989 0.265822 - -0.0318122 1.17642 0.268055 - -0.03688 1.17525 0.268601 - -0.0419383 1.17406 0.269146 - -0.0824982 1.16971 0.273527 - -0.104885 1.1909 0.275993 - -0.18006 1.1683 0.284083 - -0.2144 1.18466 0.287833 - -0.239433 1.17663 0.290526 - -0.274813 1.16761 0.294337 - -0.294332 1.20295 0.29652 - -0.331266 1.28012 0.300673 - -0.383304 1.27351 0.306292 - -0.431796 1.27235 0.311538 - -0.491533 1.02156 0.317498 - -0.492244 0.989949 0.317512 - -0.491427 0.898745 0.31724 - -0.490722 0.691098 0.316746 - -0.494926 0.562161 0.316941 - -0.383849 -0.407696 0.298963 - -0.345668 -0.404779 0.29523 - -0.343258 -0.40555 0.294993 - -0.331552 -0.402418 0.293853 - -0.299914 -0.402202 0.290756 - -0.246735 -0.403853 0.285546 - -0.238358 -0.401985 0.28473 - -0.227585 -0.403736 0.283672 - -0.20479 -0.403742 0.28144 - -0.182918 -0.399 0.279308 - -0.218691 -0.642142 0.282322 - -0.521113 -2.04511 0.309111 - -0.517559 -2.14704 0.308559 - -0.489992 -2.15566 0.305842 - -0.297903 -2.23858 0.286869 - -0.284169 -2.20915 0.285583 - -0.015591 -0.458577 0.262806 --0.00284574 -0.411942 0.261652 - 0.00252133 -0.411996 0.261126 - 0.0136334 -0.42889 0.260004 - 0.0288556 -0.353119 0.258666 - 0.0302403 -0.351012 0.258535 - 0.0440487 -0.350701 0.257183 - 0.0566486 -0.352051 0.255947 - 0.0642387 -0.35995 0.255188 - 0.0741672 -0.361187 0.254214 - 0.0792731 -0.362191 0.253712 - 0.0844171 -0.363123 0.253206 - 0.107155 -0.360397 0.250985 - 0.160643 -0.361207 0.245747 - 0.18637 -0.358942 0.243233 - 0.194321 -0.347921 0.242476 - 0.774978 -0.955325 0.184406 - 0.750425 -0.900536 0.18692 - 0.41248 -0.409823 0.220993 - 0.455751 -0.404526 0.216767 - 0.557304 -0.407008 0.206819 - 0.661109 -0.403934 0.196662 - 0.693762 -0.407557 0.193458 - 0.998214 -0.407835 0.16365 - 1.0636 -0.41313 0.157237 - 1.406 -0.409485 0.123722 - 1.48891 -0.4126 0.115598 - 2.41256 -0.295359 0.0254021 - 2.41733 -0.253078 0.0250199 - 2.42039 -0.242694 0.0247413 - 2.41235 -0.1993 0.0256164 - 7.37418 -0.156202 -0.460092 - 3.56462 0.58529 -0.085622 - 3.56571 0.698288 -0.0855012 - 1.66889 0.441676 0.0996936 - 0.919072 0.330812 0.172883 - 0.912604 0.351146 0.173557 - 0.852331 0.384641 0.179525 - 0.755888 0.348873 0.188896 - 0.720069 0.383141 0.192471 - 0.718399 0.386276 0.192641 - 0.722009 0.400491 0.192316 - 0.49831 0.295888 0.214008 - 0.390149 0.254689 0.224515 - 0.389039 0.256379 0.224627 - 0.45744 0.322377 0.218062 - 0.430291 0.329042 0.220734 - 0.488305 0.438633 0.215274 - 0.493884 0.46354 0.214778 - 0.461191 0.497469 0.218047 - 0.411389 0.625002 0.223179 - 0.537022 0.910268 0.211452 - 0.357515 0.661806 0.228528 - 0.347588 0.65691 0.22949 - 0.364766 0.720003 0.227935 - 0.370508 0.739482 0.227412 - 0.462711 0.935771 0.218779 - 0.607553 1.27308 0.205276 - 0.355824 1.27706 0.22993 - 0.251048 1.28022 0.240194 - 0.245486 1.28129 0.240741 - 0.0303174 1.23772 0.26172 - -0.0323941 1.17942 0.267743 - -0.071288 1.22765 0.271647 - -0.133503 1.16278 0.277608 - -0.193317 1.18142 0.283502 - -0.347655 1.27173 0.298794 - -0.422906 1.27992 0.306178 - -0.46713 1.28122 0.310511 - -0.480359 1.28265 0.311809 - -0.488927 1.02553 0.312131 - -0.49292 0.725691 0.311919 - -0.492642 0.655542 0.311751 - -0.488878 0.6332 0.311338 - -0.492442 0.573216 0.311566 - -0.491 0.532794 0.311343 - -0.3994 -0.401582 0.296209 - -0.364948 -0.404296 0.293196 - -0.323564 -0.413455 0.289567 - -0.303054 -0.405388 0.287793 - -0.281254 -0.408964 0.285883 - -0.258312 -0.401608 0.283896 - -0.221987 -0.405002 0.280719 - -0.209395 -0.402779 0.279625 - -0.204125 -0.405543 0.279159 - -0.16623 -0.402384 0.275858 - -0.208735 -0.638376 0.279094 - -0.523269 -2.04995 0.303709 - -0.501147 -2.15737 0.301563 - -0.405238 -2.22147 0.293064 - -0.366554 -2.22829 0.289675 - -0.316902 -2.22793 0.285342 - -0.152023 -2.25261 0.270904 --0.00535081 -0.424905 0.261774 - 0.0213801 -0.446642 0.259397 - 0.0544563 -0.36141 0.256682 - 0.0561704 -0.362173 0.256531 - 0.0683793 -0.367285 0.255455 - 0.069264 -0.363063 0.255386 - 0.0718588 -0.359526 0.255167 - 0.0971384 -0.362018 0.252956 - 0.142126 -0.376113 0.249001 - 0.150267 -0.37299 0.248297 - 0.151518 -0.371415 0.248191 - 0.14832 -0.354376 0.248504 - 0.155657 -0.358885 0.247855 - 0.168465 -0.354245 0.246747 - 0.171538 -0.352788 0.246481 - 0.184304 -0.355379 0.245362 - 0.188923 -0.352974 0.244964 - 0.388363 -0.424604 0.227415 - 0.406073 -0.410538 0.225898 - 0.409627 -0.406997 0.225595 - 0.494072 -0.408883 0.218222 - 0.527085 -0.402618 0.215353 - 0.651865 -0.405975 0.204457 - 0.687134 -0.403501 0.201384 - 0.692325 -0.402516 0.200933 - 0.713103 -0.406379 0.199112 - 0.747146 -0.408778 0.196136 - 0.759451 -0.406976 0.195066 - 0.788562 -0.405103 0.19253 - 0.902193 -0.405545 0.182612 - 0.920334 -0.408914 0.181022 - 1.36325 -0.409687 0.142368 - 2.36215 -0.610458 0.0547926 - 2.36961 -0.601349 0.0541597 - 2.41826 -0.252974 0.0506129 - 2.41228 -0.199136 0.0512436 - 2.4012 -0.187651 0.0522331 - 7.21843 0.479957 -0.36682 - 5.41988 0.503548 -0.209816 - 3.56292 0.488867 -0.0477902 - 3.56212 0.600397 -0.0474969 - 3.56189 0.696948 -0.0472823 - 0.892481 0.299231 0.184875 - 0.868612 0.360353 0.18708 - 0.757983 0.349712 0.196713 - 0.716962 0.389404 0.200373 - 0.502201 0.295243 0.218926 - 0.465278 0.337137 0.222232 - 0.457652 0.340777 0.222905 - 0.473383 0.382339 0.221616 - 0.477726 0.392805 0.221258 - 0.483447 0.404663 0.220782 - 0.505615 0.478772 0.218996 - 0.492245 0.482581 0.220171 - 0.476195 0.6079 0.221823 - 0.429888 0.672493 0.225994 - 0.667988 1.15663 0.206187 - 0.447665 0.788865 0.224676 - 0.42874 1.2777 0.227309 - 0.351191 1.28245 0.234086 - 0.309695 1.28278 0.237708 - 0.238234 1.27447 0.243928 - 0.107272 1.1965 0.2552 - 0.100595 1.17901 0.255748 - -0.117678 1.20283 0.274844 - -0.165187 1.20107 0.278987 - -0.214305 1.1768 0.283224 - -0.228074 1.16598 0.284404 - -0.250735 1.19804 0.286446 - -0.270303 1.16493 0.288087 - -0.418849 1.28368 0.301289 - -0.447979 1.27789 0.30382 - -0.475021 1.28289 0.30619 - -0.492072 1.27742 0.307667 - -0.492995 1.2016 0.307595 - -0.49348 0.977961 0.307188 - -0.489051 0.958888 0.306764 - -0.490073 0.92105 0.306777 - -0.491406 0.895248 0.306841 - -0.492937 0.862198 0.306909 - -0.498609 0.837942 0.307355 - -0.490099 0.784474 0.306505 - -0.493278 0.75982 0.306733 - -0.491169 0.65236 0.306333 - -0.494235 0.589615 0.306475 - -0.389653 -0.404996 0.291202 - -0.382276 -0.407941 0.29063 - -0.369878 -0.401784 0.289691 - -0.32523 -0.403697 0.286262 - -0.266414 -0.40145 0.281755 - -0.226127 -0.403011 0.278661 - -0.216473 -0.410654 0.277906 - -0.156247 -0.406708 0.273293 - -0.150192 -0.412247 0.272818 - -0.527784 -1.66708 0.299266 - -0.52595 -1.71273 0.299034 - -0.517261 -1.85503 0.298082 - -0.51314 -1.9039 0.297668 - -0.525724 -2.09392 0.298252 - -0.508569 -2.14347 0.296837 - -0.482965 -2.16073 0.294838 - -0.418794 -2.23636 0.289764 - -0.124591 -2.28042 0.267107 - -0.014184 -0.450664 0.262307 --0.00210365 -0.425967 0.26143 - 0.0255802 -0.423402 0.259312 - 0.0351601 -0.346516 0.258731 - 0.0634844 -0.35995 0.256531 - 0.0722322 -0.363456 0.255853 - 0.0835142 -0.354965 0.255005 - 0.0983616 -0.361605 0.253853 - 0.107031 -0.362319 0.253186 - 0.122662 -0.367971 0.251976 - 0.133275 -0.378112 0.251141 - 0.162797 -0.358906 0.248915 - 0.166632 -0.354964 0.248629 - 0.227228 -0.377115 0.243936 - 0.38356 -0.44214 0.231813 - 0.398996 -0.403411 0.230707 - 0.401786 -0.399224 0.230501 - 0.403519 -0.397476 0.230372 - 0.43047 -0.402576 0.228294 - 0.544304 -0.404671 0.219558 - 0.772011 -0.404989 0.202089 - 0.947944 -0.406292 0.188591 - 1.05623 -0.404546 0.180287 - 1.23171 -0.411283 0.166812 - 2.36085 -0.609709 0.0797968 - 2.41283 -0.305664 0.0764192 - 2.52382 -0.141709 0.0682343 - 7.35556 -0.123354 -0.302377 - 7.46659 0.103427 -0.310439 - 7.46399 0.430348 -0.309585 - 7.47428 0.562294 -0.310109 - 5.45523 0.554605 -0.15524 - 3.55439 0.727289 -0.00907892 - 2.4326 0.542003 0.0766031 - 1.74341 0.452702 0.129292 - 1.55647 0.462656 0.143653 - 0.888413 0.293453 0.194561 - 0.872565 0.379843 0.19595 - 0.854811 0.385463 0.197323 - 0.725364 0.342207 0.207166 - 0.715428 0.392524 0.208029 - 0.710247 0.397764 0.208437 - 0.390968 0.245745 0.232625 - 0.389895 0.247439 0.23271 - 0.507643 0.406591 0.223997 - 0.539567 0.493571 0.221723 - 0.532292 0.491158 0.222276 - 0.501206 0.50891 0.224696 - 0.502792 0.524077 0.224605 - 0.508478 0.548906 0.224219 - 0.539154 0.624623 0.222017 - 0.472696 0.625673 0.227117 - 0.450684 0.647783 0.22885 - 0.251527 0.658515 0.244149 - 0.272716 0.724243 0.242656 - 0.424324 1.28335 0.232147 - 0.344412 1.2801 0.238271 - 0.275081 1.28646 0.243602 - 0.210673 1.28226 0.248534 - 0.170756 1.28206 0.251596 - 0.125732 1.17561 0.254836 - 0.0936862 1.16147 0.257266 --0.00771011 1.17795 0.265078 - -0.260102 1.18796 0.284459 - -0.492343 1.08886 0.302076 - -0.492784 0.818643 0.301567 - -0.49581 0.663301 0.301488 - -0.49576 0.590377 0.301338 - -0.400046 -0.40405 0.286659 - -0.364557 -0.402083 0.284411 - -0.314434 -0.396411 0.281242 - -0.310352 -0.398383 0.280979 - -0.296877 -0.409891 0.280101 - -0.244265 -0.40433 0.276774 - -0.240951 -0.40284 0.276566 - -0.228365 -0.405616 0.275762 - -0.213444 -0.403605 0.274819 - -0.190368 -0.410762 0.273341 - -0.156821 -0.439891 0.271154 - -0.523549 -1.93864 0.29142 - -0.512327 -2.15514 0.290274 - -0.434286 -2.20806 0.285216 - -0.415596 -2.21474 0.284017 - -0.336692 -2.21813 0.279004 - -0.20092 -2.23473 0.270355 - -0.190755 -2.23062 0.269718 - -0.148838 -2.18976 0.26714 - -0.124138 -2.26145 0.265429 - 0.0257461 -0.436384 0.259576 - 0.0275585 -0.377172 0.25958 - 0.0296432 -0.340925 0.25952 - 0.0323486 -0.337688 0.259355 - 0.064903 -0.361653 0.257241 - 0.0834479 -0.364099 0.25606 - 0.0943844 -0.367675 0.255359 - 0.126699 -0.370704 0.253302 - 0.134138 -0.371304 0.252829 - 0.139712 -0.361797 0.252494 - 0.151844 -0.35586 0.251736 - 0.163553 -0.357293 0.250991 - 0.165107 -0.356586 0.250893 - 0.166658 -0.355872 0.250796 - 0.188876 -0.350394 0.249397 - 0.192957 -0.347045 0.249145 - 0.195972 -0.345367 0.248957 - 0.197967 -0.345388 0.248831 - 0.347392 -0.4881 0.239063 - 0.73766 -0.892233 0.21349 - 1.1405 -1.29835 0.187114 - 0.382695 -0.407818 0.236984 - 0.392516 -0.403984 0.236368 - 0.420717 -0.403986 0.234579 - 0.504708 -0.406804 0.229244 - 0.527454 -0.410263 0.227794 - 0.546822 -0.402893 0.226579 - 0.594261 -0.406815 0.223561 - 0.735236 -0.406221 0.214617 - 0.752785 -0.407424 0.213501 - 0.78102 -0.40531 0.211714 - 0.815668 -0.409897 0.209506 - 0.834413 -0.405764 0.208325 - 0.926471 -0.411351 0.202473 - 0.977556 -0.408816 0.199236 - 1.11149 -0.408995 0.190737 - 1.18432 -0.40675 0.186121 - 1.46194 -0.411255 0.168495 - 2.29911 -0.424759 0.115347 - 2.41176 -0.326742 0.108396 - 2.41831 -0.274004 0.108086 - 2.41672 -0.241799 0.108251 - 2.43791 -0.136784 0.107117 - 7.28555 -0.281412 -0.200772 - 3.62082 0.431762 0.033197 - 3.56134 0.695799 0.0375004 - 3.55786 0.907446 0.0381452 - 0.88994 0.289576 0.206195 - 0.891752 0.303121 0.206107 - 0.882714 0.361492 0.206798 - 0.871702 0.374849 0.207523 - 0.870062 0.378645 0.207635 - 0.726778 0.362393 0.216694 - 0.720358 0.375 0.217127 - 0.718827 0.382201 0.217238 - 0.396657 0.264182 0.237445 - 0.398812 0.268141 0.237316 - 0.538668 0.383654 0.228673 - 0.531788 0.396475 0.229135 - 0.528316 0.401087 0.229365 - 0.522608 0.400334 0.229726 - 0.559603 0.456585 0.227491 - 0.572688 0.510479 0.226769 - 0.566641 0.523086 0.227178 - 0.552133 0.561014 0.228174 - 0.514817 0.646023 0.230712 - 0.501236 0.657859 0.231598 - 0.704528 1.16062 0.219706 - 0.429376 0.764616 0.236371 - 0.37571 0.682364 0.239612 - 0.355598 0.659162 0.240842 - 0.340259 0.664935 0.241826 - 0.406405 0.830778 0.237962 - 0.273684 0.757843 0.246237 - 0.428763 1.27865 0.23744 - 0.344141 1.2801 0.242813 - 0.332232 1.28013 0.243569 - 0.321312 1.28393 0.244269 - 0.285508 1.28208 0.246537 - 0.258305 1.29188 0.248283 - 0.105803 1.18953 0.257755 - 0.0478793 1.17113 0.261393 --0.00841582 1.18994 0.265003 - -0.0438416 1.16806 0.267207 - -0.084422 1.16472 0.269775 - -0.147162 1.17442 0.273776 - -0.380922 1.27425 0.288809 - -0.492323 0.941265 0.29521 - -0.491849 0.883477 0.295064 - -0.497277 0.849201 0.29534 - -0.49044 0.643049 0.294493 - -0.493852 0.630247 0.294684 - -0.490536 0.562768 0.294338 - -0.489523 0.519009 0.294186 - -0.375217 -0.402335 0.281147 - -0.34078 -0.406289 0.279313 - -0.327334 -0.404472 0.278604 - -0.302168 -0.401406 0.277276 - -0.282236 -0.403627 0.276215 - -0.264937 -0.400962 0.275303 - -0.249574 -0.400212 0.27449 - -0.228146 -0.408364 0.273337 - -0.214331 -0.400019 0.272622 - -0.197589 -0.40197 0.27173 - -0.192751 -0.405455 0.271467 - -0.179323 -0.399604 0.270766 - -0.518161 -1.70834 0.28611 - -0.52536 -1.75944 0.28639 - -0.527388 -2.01957 0.285976 - -0.484596 -2.16073 0.283425 - -0.396747 -2.21733 0.278654 - -0.338498 -2.22603 0.275548 - -0.309234 -2.22932 0.27399 - -0.202613 -2.24768 0.2683 - -0.192644 -2.24656 0.267774 --0.00296828 -0.416967 0.261381 - 0.0043193 -0.420994 0.260987 - 0.00987618 -0.423929 0.260686 - 0.0274724 -0.409216 0.259783 - 0.0288643 -0.355998 0.259816 - 0.0311325 -0.345787 0.259716 - 0.0731405 -0.364131 0.257452 - 0.0985551 -0.365473 0.256102 - 0.12285 -0.365546 0.254813 - 0.164777 -0.356586 0.252608 - 0.172506 -0.352949 0.252206 - 0.193347 -0.367083 0.251073 - 0.560805 -0.868385 0.230586 - 0.550974 -0.844979 0.231154 - 0.345889 -0.473024 0.242773 - 0.349651 -0.465275 0.242589 - 0.896927 -1.17663 0.212147 - 0.91449 -1.17825 0.211213 - 0.377338 -0.416631 0.241218 - 0.379772 -0.404895 0.241113 - 0.383587 -0.405424 0.240909 - 0.406014 -0.407352 0.239716 - 0.412017 -0.402724 0.239407 - 0.417347 -0.404416 0.239121 - 0.529315 -0.404442 0.233185 - 0.548966 -0.408257 0.232135 - 0.61428 -0.412798 0.228663 - 0.627018 -0.413497 0.227986 - 0.671787 -0.40623 0.225627 - 0.681312 -0.403938 0.225127 - 0.695976 -0.40857 0.22434 - 0.70733 -0.40291 0.223749 - 0.754567 -0.408377 0.221234 - 0.78904 -0.405103 0.219413 - 0.951221 -0.412413 0.210799 - 0.979561 -0.409588 0.209302 - 1.02095 -0.411325 0.207104 - 1.04215 -0.409357 0.205984 - 1.28451 -0.410023 0.193133 - 1.32438 -0.416417 0.191006 - 1.37275 -0.411987 0.18845 - 2.24718 -0.425133 0.142062 - 2.41438 -0.273441 0.133501 - 2.41456 -0.262791 0.133513 - 2.41568 -0.252248 0.133475 - 2.41775 -0.241799 0.133386 - 2.40134 -0.176782 0.134386 - 7.42071 0.0378125 -0.131311 - 3.6305 0.432708 0.0704368 - 3.55711 0.487105 0.0744367 - 3.55293 0.726088 0.0751368 - 2.41882 0.560536 0.134936 - 0.898272 0.349679 0.215133 - 0.485604 0.285588 0.236884 - 0.460495 0.278914 0.238202 - 0.571191 0.403261 0.232582 - 0.58914 0.472372 0.231769 - 0.586017 0.513395 0.232017 - 0.586734 0.523141 0.231998 - 0.560711 0.574879 0.233481 - 0.56439 0.604506 0.233346 - 0.564461 0.609896 0.233353 - 0.557385 0.640396 0.233789 - 0.529773 0.671043 0.235314 - 0.517277 0.7044 0.236044 - 0.807331 1.26736 0.221793 - 0.709192 1.17997 0.226821 - 0.709144 1.19165 0.226847 - 0.343032 0.656635 0.245187 - 0.33442 0.661045 0.245652 - 0.602452 1.26225 0.232645 - 0.59143 1.26744 0.23324 - 0.580058 1.25729 0.233822 - 0.417945 0.925739 0.241754 - 0.289378 0.654655 0.248027 - 0.397648 1.2781 0.243535 - 0.37921 1.27742 0.244512 - 0.2908 1.28083 0.249206 - 0.284785 1.28013 0.249524 - 0.129348 1.1691 0.257542 - 0.124524 1.2239 0.257908 - 0.11919 1.22442 0.258192 - 0.105059 1.18554 0.258863 - 0.0992362 1.17801 0.259157 - 0.0476007 1.17512 0.261889 - 0.00657084 1.16299 0.26404 - -0.132236 1.1753 0.271424 - -0.191614 1.18721 0.274596 - -0.220339 1.16993 0.276085 - -0.263409 1.17217 0.278373 - -0.371058 1.27947 0.284295 - -0.376629 1.27783 0.284587 - -0.388336 1.27638 0.285205 - -0.468972 1.27653 0.28948 - -0.495596 1.17236 0.290683 - -0.488752 1.07704 0.29013 - -0.491514 0.821663 0.289765 - -0.494106 0.794259 0.289847 - -0.491709 0.661475 0.289454 - -0.493625 0.545919 0.289324 - -0.396073 -0.402254 0.278056 - -0.395715 -0.405415 0.278034 - -0.370962 -0.404148 0.276985 - -0.296256 -0.400042 0.27382 - -0.276944 -0.406496 0.272987 - -0.256976 -0.399395 0.272153 - -0.238781 -0.401329 0.271377 - -0.183325 -0.398003 0.269028 - -0.524101 -1.64802 0.281 - -0.522665 -1.80527 0.280624 - -0.523033 -1.83639 0.280577 - -0.47495 -2.15893 0.277889 - -0.466591 -2.16588 0.27752 - -0.379175 -2.22763 0.273684 - -0.115305 -2.26397 0.262403 - 0.0267002 -0.434281 0.260034 - 0.0367379 -0.345228 0.259786 - 0.0402936 -0.349879 0.259626 - 0.0646411 -0.355469 0.258581 - 0.0991898 -0.36934 0.257086 - 0.101058 -0.369877 0.257005 - 0.16318 -0.353857 0.254399 - 0.222983 -0.379062 0.251808 - 0.319898 -0.499056 0.247451 - 0.320538 -0.472319 0.247478 - 1.13697 -1.45226 0.210839 - 0.381388 -0.414073 0.24501 - 0.404377 -0.405933 0.24405 - 0.547023 -0.410642 0.237981 - 0.549609 -0.408855 0.237875 - 0.555404 -0.40943 0.237628 - 0.561379 -0.40634 0.23738 - 0.746406 -0.420972 0.229492 - 0.765868 -0.418866 0.22867 - 0.782796 -0.406232 0.227976 - 0.858728 -0.408362 0.224747 - 0.887594 -0.407967 0.223521 - 1.35123 -0.418328 0.203808 - 1.354 -0.412722 0.203702 - 2.41968 -0.381505 0.1585 - 2.42061 -0.29548 0.158633 - 2.42188 -0.284913 0.1586 - 2.40346 -0.197987 0.159556 - 7.25288 -0.184771 -0.0463921 - 7.39891 0.425812 -0.0513727 - 2.43174 0.552185 0.159857 - 2.42931 0.562792 0.159981 - 1.65365 0.452036 0.192705 - 1.64965 0.466446 0.192904 - 0.935719 0.290993 0.222876 - 0.921237 0.354019 0.223618 - 0.718472 0.342777 0.232208 - 0.47433 0.284644 0.242461 - 0.391377 0.244046 0.245903 - 0.588102 0.51992 0.238099 - 0.567236 0.64624 0.239239 - 0.542658 0.700152 0.24039 - 0.849115 1.2711 0.228517 - 0.83417 1.27259 0.229155 - 0.818724 1.27308 0.229812 - 0.709081 1.17997 0.234282 - 0.411572 0.7411 0.24604 - 0.357446 0.663568 0.248184 - 0.249493 0.64715 0.252736 - 0.434566 1.26069 0.246104 - 0.402047 1.2735 0.247511 - 0.31395 1.28045 0.251266 - 0.277819 1.27646 0.252793 - 0.185618 1.2748 0.256706 - 0.134153 1.16953 0.258681 - 0.0706648 1.22807 0.261495 - 0.052065 1.16992 0.262168 - -0.0499553 1.16885 0.266499 - -0.123148 1.18239 0.269635 - -0.127863 1.17786 0.269827 - -0.150916 1.19525 0.270841 - -0.231696 1.17089 0.274223 - -0.321941 1.27236 0.278259 - -0.388708 1.27542 0.281101 - -0.4146 1.27982 0.28221 - -0.445366 1.27891 0.283515 - -0.49373 1.19514 0.285401 - -0.495742 1.14321 0.285383 - -0.488435 0.754446 0.284294 - -0.497042 0.739137 0.284629 - -0.490184 0.676788 0.284213 - -0.489082 0.645199 0.284103 - -0.492646 0.615748 0.284195 - -0.370019 -0.40961 0.273004 - -0.315296 -0.406055 0.271265 - -0.266599 -0.401794 0.269721 - -0.263742 -0.401291 0.26963 - -0.260232 -0.40359 0.269514 - -0.258469 -0.404728 0.269455 - -0.24839 -0.40046 0.269142 - -0.201681 -0.399318 0.267655 - -0.16529 -0.408284 0.266476 - -0.151352 -0.409436 0.266029 - -0.523268 -1.61908 0.275471 - -0.511958 -2.14542 0.274057 - -0.380732 -2.23354 0.269696 - -0.237439 -2.28757 0.265017 - -0.125283 -2.25745 0.2615 - -0.115436 -2.25798 0.261185 - -0.0077516 -0.429904 0.261408 - 0.021123 -0.446559 0.260454 - 0.0325661 -0.337555 0.260307 - 0.0515125 -0.355469 0.259667 - 0.108755 -0.373852 0.257805 - 0.113503 -0.366183 0.257668 - 0.146644 -0.368339 0.256607 - 0.200451 -0.348002 0.254932 - 0.232729 -0.384699 0.253829 - 0.239735 -0.38863 0.253597 - 0.542055 -0.839803 0.243052 - 1.16449 -1.51446 0.22185 - 0.811541 -1.00858 0.234119 - 0.516514 -0.40575 0.244735 - 0.561973 -0.406927 0.243283 - 0.569423 -0.408561 0.243042 - 0.626939 -0.405845 0.241213 - 0.661906 -0.412326 0.240085 - 0.820953 -0.408121 0.23502 - 0.932009 -0.408916 0.231477 - 1.39886 -0.413078 0.216578 - 2.38784 -0.516614 0.184827 - 2.19065 -0.443995 0.191262 - 2.19257 -0.434433 0.19122 - 2.41213 -0.347938 0.18439 - 2.4218 -0.306292 0.184165 - 2.40913 -0.230196 0.184722 - 2.40481 -0.187496 0.184945 - 2.40706 -0.156003 0.184936 - 7.33938 -0.347304 0.0272367 - 7.35181 -0.315739 0.0269033 - 7.40144 0.458237 0.026869 - 7.39937 0.490537 0.0269996 - 7.40827 0.588648 0.0269122 - 6.1629 0.67967 0.0668156 - 3.55204 0.517719 0.149765 - 3.55752 0.678174 0.149911 - 3.55845 0.694458 0.149914 - 3.55226 0.725488 0.150174 - 2.41762 0.548864 0.186009 - 1.64456 0.48828 0.210545 - 0.879079 0.30309 0.23459 - 0.727924 0.343489 0.239492 - 0.712621 0.391079 0.240075 - 0.399619 0.256711 0.249789 - 0.612822 0.449248 0.243374 - 0.61404 0.483957 0.243405 - 0.870508 0.933838 0.236125 - 0.615998 0.760494 0.243896 - 0.892892 1.26399 0.236072 - 0.845079 1.27729 0.237623 - 0.706469 1.21161 0.241913 - 0.428697 0.772599 0.249894 - 0.388351 0.706922 0.251049 - 0.356656 0.662687 0.251972 - 0.564629 1.23886 0.246491 - 0.254872 0.621221 0.255135 - 0.402334 1.27541 0.251741 - 0.386476 1.28342 0.252263 - 0.373872 1.28194 0.252662 - 0.361594 1.28129 0.253052 - 0.284531 1.28208 0.255512 - 0.268342 1.28862 0.256041 - 0.226984 1.28534 0.257354 - 0.215929 1.28824 0.257712 - 0.124881 1.18357 0.260407 - 0.118168 1.22243 0.260698 - 0.0978959 1.17203 0.261244 - -0.0156087 1.23288 0.264986 - -0.0507978 1.17684 0.265996 - -0.0751423 1.23763 0.266895 - -0.122929 1.17543 0.268294 - -0.132266 1.16635 0.268574 - -0.170687 1.18152 0.26983 - -0.226573 1.16895 0.271587 - -0.23776 1.17181 0.27195 - -0.249198 1.2011 0.272373 - -0.279192 1.16567 0.273259 - -0.321799 1.26946 0.274825 - -0.3349 1.27432 0.275253 - -0.341232 1.27574 0.275458 - -0.389624 1.27638 0.277003 - -0.407511 1.27496 0.27757 - -0.464418 1.27764 0.279391 - -0.497137 1.21672 0.280312 - -0.491969 0.926735 0.279567 - -0.49645 0.835839 0.279528 - -0.492356 0.759475 0.279245 - -0.491275 0.750626 0.279193 - -0.495059 0.721572 0.279255 - -0.487366 0.703795 0.278974 - -0.497179 0.643258 0.279166 - -0.497604 0.594087 0.279081 - -0.498152 0.579173 0.279069 - -0.498189 0.559179 0.27903 - -0.495938 0.551794 0.278943 - -0.37664 -0.398504 0.269342 - -0.365968 -0.397534 0.269113 - -0.351253 -0.3987 0.268793 - -0.317473 -0.400926 0.26806 - -0.306235 -0.404592 0.26781 - -0.281555 -0.400359 0.267286 - -0.261391 -0.400771 0.26685 - -0.21762 -0.399069 0.265908 - -0.154384 -0.427672 0.264486 - -0.179625 -0.511042 0.264864 - -0.370655 -2.23026 0.265548 - -0.349782 -2.22453 0.265109 - 0.0311153 -0.342668 0.260653 - 0.0459374 -0.352128 0.260314 - 0.0483304 -0.346768 0.260273 - 0.0703399 -0.364438 0.259763 - 0.0773011 -0.366107 0.259609 - 0.111048 -0.370983 0.258871 - 0.115396 -0.362329 0.258794 - 0.141604 -0.365861 0.258222 - 0.154645 -0.366001 0.25794 - 0.19557 -0.347111 0.257094 - 0.348419 -0.486588 0.253516 - 1.21498 -1.60916 0.232567 - 0.408734 -0.403807 0.25238 - 0.450085 -0.411107 0.251473 - 0.453355 -0.410487 0.251404 - 0.47277 -0.409693 0.250986 - 0.49358 -0.402042 0.250552 - 0.506431 -0.40523 0.250269 - 0.560226 -0.402141 0.249114 - 0.656653 -0.405234 0.247026 - 1.01158 -0.407586 0.239361 - 1.05225 -0.408065 0.238483 - 1.45993 -0.410443 0.229679 - 2.40665 -0.520632 0.209025 - 2.35054 -0.423221 0.210431 - 2.39686 -0.176341 0.209925 - 3.59433 0.865657 0.186164 - 0.899246 0.292673 0.243187 - 2.04723 0.787387 0.219399 - 0.734012 0.346479 0.246861 - 0.713514 0.352137 0.247314 - 0.535774 0.309388 0.251065 - 0.404559 0.250245 0.253779 - 0.641731 0.483722 0.249127 - 0.636694 0.488688 0.249245 - 0.633906 0.522679 0.249374 - 0.642264 0.543855 0.249236 - 1.06461 1.22566 0.241484 - 1.02957 1.22795 0.242245 - 1.02421 1.23243 0.242369 - 0.890157 1.28406 0.245366 - 0.266479 0.619457 0.257498 - 0.255252 0.623073 0.257747 - 0.250546 0.627127 0.257857 - 0.435226 1.26447 0.255146 - 0.416489 1.28232 0.255586 - 0.402285 1.27636 0.25588 - 0.361234 1.28129 0.256776 - 0.143879 1.17131 0.261248 - 0.112863 1.22791 0.26203 - 0.078101 1.1905 0.262706 - 0.0513025 1.17292 0.263249 - 0.0266179 1.21673 0.263869 - -0.142686 1.16316 0.267416 - -0.253919 1.19511 0.269881 - -0.26666 1.17899 0.270124 - -0.383464 1.27425 0.272835 - -0.431877 1.27236 0.273876 - -0.459428 1.27966 0.274486 - -0.477538 1.27727 0.274872 - -0.494212 1.2709 0.275219 - -0.49489 1.24053 0.275173 - -0.493107 1.10777 0.274869 - -0.493171 0.937726 0.27453 - -0.48854 0.759942 0.274074 - -0.493805 0.732508 0.274133 - -0.490541 0.714159 0.274026 - -0.492984 0.598421 0.273847 - -0.489255 0.55826 0.273686 - -0.387172 -0.405527 0.26541 - -0.278003 -0.39831 0.264235 - -0.269248 -0.40429 0.264127 - -0.241083 -0.406674 0.263816 - -0.19301 -0.401851 0.263302 - -0.151936 -0.408499 0.262841 - -0.153827 -0.424852 0.262829 - -0.21169 -0.617577 0.263074 - -0.436525 -2.20512 0.262348 - -0.372764 -2.24012 0.261583 - -0.340989 -2.229 0.261259 - -0.290858 -2.22501 0.260721 - -0.0382625 -0.496492 0.261426 - -0.150829 -2.18577 0.259274 - -0.12691 -2.27143 0.258842 - 0.00443766 -0.42198 0.26111 - 0.018121 -0.441646 0.260922 - 0.120962 -0.359326 0.259966 - 0.157368 -0.355942 0.259576 - 0.158919 -0.355253 0.259561 - 0.201605 -0.354958 0.259096 - 0.203152 -0.354077 0.259081 - 0.227216 -0.380552 0.258766 - 0.238454 -0.387778 0.258629 - 0.325669 -0.481434 0.257491 - 1.28345 -1.50011 0.245019 - 0.381914 -0.438208 0.256965 - 0.380954 -0.425722 0.257001 - 0.383981 -0.421645 0.256976 - 0.382067 -0.401579 0.257037 - 0.436605 -0.406153 0.256433 - 0.438373 -0.404246 0.256418 - 0.536422 -0.406973 0.255344 - 0.620287 -0.409638 0.254425 - 0.645151 -0.406145 0.254161 - 0.666618 -0.407587 0.253925 - 0.968075 -0.404956 0.250645 - 1.38712 -0.409678 0.246071 - 2.19358 -0.424673 0.237254 - 2.40931 -0.412139 0.234929 - 2.39957 -0.166021 0.235527 - 7.06159 0.220885 0.185509 - 7.40521 0.555709 0.182435 - 3.63358 0.432708 0.22328 - 3.55711 0.486698 0.224221 - 3.55697 0.581899 0.224413 - 3.39509 0.708695 0.226431 - 2.55537 0.5567 0.235275 - 1.65079 0.451245 0.24492 - 1.65147 0.474744 0.244959 - 1.01544 0.421306 0.251782 - 0.398225 0.246557 0.258157 - 0.948511 0.652621 0.252974 - 0.94278 0.66087 0.253053 - 0.903961 0.663514 0.253481 - 1.14783 0.914061 0.251325 - 1.14292 0.926559 0.251404 - 1.13349 1.27136 0.252196 - 1.10786 1.26465 0.252462 - 1.02955 1.26146 0.253309 - 0.864574 1.28315 0.255149 - 0.810835 1.27411 0.255717 - 0.73723 1.18102 0.256333 - 0.355906 0.662687 0.25945 - 0.595448 1.26395 0.258043 - 0.261728 0.609347 0.26037 - 0.360009 1.2784 0.260637 - 0.283291 1.28013 0.261476 - 0.236994 1.28135 0.261983 - 0.186366 1.28866 0.262549 - -0.0647771 1.22826 0.265165 - -0.0868417 1.16373 0.265276 - -0.133371 1.16735 0.26579 - -0.242599 1.19043 0.267027 - -0.330674 1.27674 0.268159 - -0.354244 1.27559 0.268413 - -0.360078 1.27499 0.268476 - -0.366743 1.27725 0.268553 - -0.482955 1.2733 0.269811 - -0.493363 1.04519 0.269468 - -0.489442 1.0027 0.26934 - -0.491071 0.867386 0.269088 - -0.494354 0.864365 0.269117 - -0.487608 0.844019 0.269003 - -0.494485 0.790868 0.268972 - -0.495794 0.785319 0.268975 - -0.492401 0.757799 0.268883 - -0.493936 0.738816 0.268862 - -0.493017 0.690824 0.268756 - -0.490763 0.681364 0.268712 - -0.492796 0.636146 0.268644 - -0.494856 0.584275 0.268562 - -0.496777 0.546659 0.268508 - -0.402381 -0.406518 0.261379 - -0.391472 -0.405991 0.261375 - -0.389697 -0.407696 0.26137 - -0.356839 -0.403946 0.261362 - -0.343895 -0.403264 0.261357 - -0.342132 -0.404761 0.261354 - -0.326636 -0.396852 0.261362 - -0.304231 -0.408059 0.261329 - -0.29534 -0.407149 0.261326 - -0.289456 -0.406453 0.261325 - -0.265722 -0.402125 0.261322 - -0.258274 -0.402204 0.261319 - -0.199158 -0.404634 0.261286 - -0.186064 -0.399816 0.261289 - -0.171607 -0.405146 0.261272 - -0.163481 -0.395539 0.261287 - -0.161754 -0.396248 0.261285 - -0.216676 -0.630817 0.260842 - -0.520116 -1.62897 0.25899 - -0.521703 -1.65889 0.258931 - -0.419913 -2.22064 0.257759 - -0.0630956 -0.499024 0.261032 - -0.0587385 -0.499555 0.261029 - -0.0553502 -0.508996 0.261008 - -0.228155 -2.28262 0.257544 - -0.0155631 -0.455733 0.261096 - 0.00213734 -0.415994 0.261167 - 0.00765507 -0.41993 0.261156 - 0.0199753 -0.449556 0.261091 - 0.0268851 -0.357993 0.261271 - 0.0464813 -0.350937 0.261276 - 0.0480121 -0.350731 0.261276 - 0.0873849 -0.36982 0.261219 - 0.0969382 -0.373634 0.261207 - 0.0983122 -0.372241 0.261209 - 0.105498 -0.360902 0.261228 - 0.14345 -0.368038 0.261196 - 0.164161 -0.363673 0.261194 - 0.179147 -0.350926 0.261213 - 0.303723 -0.466918 0.260921 - 0.343905 -0.476955 0.260882 - 1.22409 -1.62194 0.258173 - 0.385105 -0.405204 0.261006 - 0.423288 -0.408151 0.260982 - 0.445318 -0.411029 0.260966 - 0.492376 -0.408883 0.260948 - 0.546132 -0.403487 0.260933 - 0.55287 -0.401055 0.260934 - 0.634459 -0.407433 0.260883 - 0.670566 -0.40623 0.260868 - 0.749067 -0.405994 0.260831 - 0.782659 -0.406693 0.260814 - 0.84069 -0.413813 0.260772 - 2.39286 -0.583681 0.259692 - 2.40366 -0.542051 0.25977 - 2.2982 -0.424214 0.260056 - 2.4151 -0.294753 0.260259 - 2.41299 -0.241202 0.260367 - 2.41893 -0.209856 0.260427 - 7.31146 -0.0903988 0.258334 - 7.47762 0.495563 0.259427 - 7.475 0.560947 0.259559 - 3.72163 0.426762 0.261079 - 3.55515 0.597579 0.2615 - 1.67269 0.441676 0.262086 - 1.35576 0.415567 0.262185 - 0.886827 0.293139 0.262164 - 0.838615 0.36101 0.262322 - 1.21502 0.852069 0.263125 - 1.22486 0.883105 0.263182 - 1.21892 0.962337 0.263344 - 1.25014 1.26291 0.26393 - 1.23905 1.28492 0.263979 - 1.1464 1.28629 0.264026 - 1.13085 1.28004 0.264021 - 1.08135 1.2792 0.264043 - 0.982848 1.28277 0.264097 - 0.935728 1.27809 0.26411 - 0.870876 1.28102 0.264147 - 0.828034 1.27706 0.264159 - 0.712404 1.19939 0.264059 - 0.362566 0.675905 0.263179 - 0.351643 0.662465 0.263157 - 0.329726 0.66249 0.263168 - 0.408221 1.27841 0.264362 - 0.295125 1.28248 0.264424 - 0.289967 1.28571 0.264433 - 0.242318 1.28129 0.264447 - 0.236907 1.28332 0.264454 - 0.224834 1.28041 0.264454 - 0.117403 1.2284 0.264401 - -0.0170413 1.23488 0.264478 - -0.16429 1.20081 0.26448 - -0.176727 1.1768 0.264438 - -0.283302 1.17636 0.264488 - -0.42927 1.27992 0.264764 - -0.453549 1.27789 0.264772 - -0.459459 1.27684 0.264773 - -0.489358 1.27211 0.264777 - -0.488745 0.871267 0.263976 - -0.492275 0.842744 0.26392 - -0.491931 0.825531 0.263886 - -0.490459 0.79132 0.263816 - -0.489663 0.782391 0.263798 - -0.493244 0.77303 0.263781 - -0.488427 0.736799 0.263706 - -0.488266 0.683501 0.2636 - -0.490851 0.584134 0.263402 - -0.492545 0.541481 0.263318 - -0.496861 0.532064 0.263301 - -0.404906 -0.401582 0.257147 - -0.40315 -0.403343 0.257161 - -0.320172 -0.40624 0.257986 - -0.304489 -0.396897 0.258161 - -0.284072 -0.398308 0.258363 - -0.258152 -0.401362 0.258616 - -0.246726 -0.402624 0.258728 - -0.243931 -0.401985 0.258757 - -0.238574 -0.397041 0.258821 - -0.224089 -0.404236 0.258951 - -0.200007 -0.401075 0.259198 - -0.186617 -0.534489 0.259066 - -0.211579 -0.632684 0.258619 - -0.521294 -1.70834 0.253369 - -0.0598661 -0.505514 0.260392 - -0.0554237 -0.527136 0.260393 - -0.0377603 -0.507627 0.260609 - -0.0206552 -0.471565 0.260852 - 0.0341976 -0.341248 0.261662 - 0.0535002 -0.358973 0.26182 - 0.120419 -0.360275 0.262487 - 0.12535 -0.354341 0.262548 - 0.133759 -0.353383 0.262634 - 0.15928 -0.357993 0.26288 - 0.160737 -0.352947 0.262905 - 0.166197 -0.352616 0.26296 - 0.326168 -0.474459 0.264317 - 0.341119 -0.47371 0.264468 - 0.344359 -0.473833 0.2645 - 1.2521 -1.61526 0.271301 - 1.24681 -1.59402 0.271291 - 0.770247 -0.941874 0.267826 - 1.27742 -1.48087 0.271823 - 0.382932 -0.417757 0.264998 - 0.403968 -0.407352 0.26523 - 0.414262 -0.406926 0.265334 - 0.424275 -0.409539 0.265429 - 0.433243 -0.407368 0.265523 - 0.460927 -0.411179 0.265792 - 0.498784 -0.40366 0.266186 - 0.526252 -0.410878 0.266446 - 0.569408 -0.413386 0.266873 - 0.573808 -0.408978 0.266926 - 0.609199 -0.410563 0.267277 - 0.721325 -0.411831 0.268397 - 0.86631 -0.408022 0.269855 - 1.08186 -0.414561 0.271999 - 1.46275 -0.411526 0.275816 - 2.20854 -0.45781 0.283187 - 2.35656 -0.424462 0.284735 - 2.41106 -0.272992 0.285583 - 7.4175 0.102501 0.336433 - 3.55681 0.51844 0.298631 - 2.43155 0.552185 0.287439 - 1.64123 0.448871 0.279323 - 1.64867 0.474191 0.279448 - 1.65522 0.483907 0.279534 - 0.880533 0.304069 0.271422 - 0.879197 0.30791 0.271416 - 1.7131 0.6336 0.280412 - 0.732073 0.415152 0.270158 - 0.464632 0.274408 0.2672 - 0.458793 0.276394 0.267146 - 0.406632 0.267314 0.266606 - 1.23463 0.858171 0.276073 - 1.24309 0.93853 0.276319 - 1.24455 0.948188 0.276353 - 1.24313 0.9907 0.276423 - 1.23957 0.996744 0.2764 - 1.25272 1.06249 0.276663 - 1.24473 1.08406 0.276626 - 1.24716 1.12504 0.276732 - 1.24689 1.2712 0.277022 - 1.23505 1.28132 0.276924 - 1.17207 1.2815 0.276294 - 1.11256 1.2823 0.2757 - 0.935805 1.27889 0.273924 - 0.921107 1.28214 0.273784 - 0.713973 1.16778 0.271482 - 0.708682 1.25557 0.271605 - 0.388863 0.718275 0.26733 - 0.338 0.651311 0.266687 - 0.326137 0.656223 0.266578 - 0.333966 0.68692 0.266718 - 0.273371 0.623525 0.265985 - 0.255885 0.620108 0.265803 - 0.247746 0.623411 0.265728 - 0.426331 1.27865 0.268826 - 0.300008 1.28021 0.267565 - 0.231358 1.28729 0.266892 - 0.213174 1.28232 0.2667 - 0.173111 1.2823 0.266299 - 0.137976 1.17688 0.265737 - 0.0495681 1.16492 0.264828 - 0.0344055 1.16848 0.264683 - 0.00892419 1.17096 0.264433 - -0.0471443 1.16706 0.263865 - -0.070893 1.22497 0.263743 - -0.145093 1.1711 0.262892 - -0.161738 1.21837 0.26282 - -0.202998 1.20509 0.262381 - -0.249946 1.19523 0.261892 - -0.38523 1.2752 0.260698 - -0.397235 1.27466 0.260576 - -0.480787 1.28195 0.259755 - -0.491496 1.18313 0.25945 - -0.493779 1.10594 0.259273 - -0.493325 0.945194 0.258956 - -0.491436 0.912244 0.258909 - -0.490833 0.77602 0.258643 - -0.492063 0.770501 0.258619 - -0.497068 0.708205 0.258445 - -0.497628 0.624159 0.258271 - -0.496587 0.617307 0.258268 - -0.497358 0.541537 0.258108 - -0.306852 -0.402999 0.254151 - -0.248252 -0.40433 0.255496 - -0.230517 -0.390484 0.255931 - -0.200054 -0.40018 0.256612 - -0.19476 -0.407206 0.25672 - -0.164021 -0.409723 0.257421 - -0.150753 -0.412633 0.25772 - -0.154683 -0.429287 0.257597 - -0.521046 -1.78991 0.246453 - -0.520653 -1.81812 0.246406 - -0.228774 -2.28063 0.25219 - -0.208868 -2.28253 0.252644 - -0.134625 -2.21396 0.254487 - 0.00119678 -0.420994 0.261196 - 0.00668756 -0.41993 0.261325 - 0.050954 -0.356236 0.26247 - 0.0661766 -0.360805 0.26281 - 0.0683116 -0.363456 0.262854 - 0.0847799 -0.370198 0.263219 - 0.0873135 -0.373713 0.26327 - 0.17685 -0.356054 0.265364 - 0.201712 -0.354077 0.265939 - 0.204793 -0.352295 0.266014 - 0.332911 -0.463165 0.268737 - 0.341988 -0.471407 0.268929 - 0.344041 -0.469906 0.268979 - 1.24557 -1.4706 0.2877 - 0.379996 -0.422572 0.269901 - 0.396658 -0.404123 0.27032 - 0.422852 -0.40169 0.270927 - 0.496377 -0.405835 0.272609 - 0.538103 -0.409392 0.273561 - 0.551454 -0.408241 0.27387 - 0.574609 -0.413814 0.274391 - 0.643533 -0.410028 0.275983 - 0.753183 -0.40038 0.278523 - 0.834109 -0.406639 0.280371 - 0.92453 -0.411351 0.28244 - 0.948285 -0.416958 0.282975 - 1.13599 -0.407376 0.287309 - 2.39807 -0.58534 0.315963 - 2.41781 -0.359783 0.316868 - 2.40864 -0.16678 0.317044 - 7.34465 -0.283339 0.430272 - 7.01651 0.0969887 0.42349 - 7.44973 0.428626 0.434112 - 7.38138 0.716444 0.433116 - 7.39807 0.750675 0.433568 - 3.56242 0.519449 0.344938 - 2.4256 0.551078 0.318869 - 3.59616 0.866594 0.346408 - 3.59623 0.883239 0.346443 - 1.74573 0.527227 0.303194 - 0.934761 0.300361 0.284099 - 0.715824 0.365983 0.279197 - 0.469489 0.274898 0.273353 - 0.466563 0.275933 0.273288 - 1.17413 0.809114 0.290619 - 1.24591 0.958486 0.292568 - 1.24962 0.970047 0.292676 - 1.25052 0.988363 0.292733 - 1.25068 1.01537 0.292791 - 1.24626 1.23856 0.293136 - 1.25214 1.25532 0.293305 - 1.22032 1.27802 0.292619 - 1.06737 1.27547 0.289098 - 0.986518 1.27768 0.287244 - 0.873535 1.28681 0.284665 - 0.857303 1.27485 0.284268 - 0.717294 1.27211 0.281044 - 0.689712 1.24858 0.280363 - 0.327017 0.652112 0.270833 - 0.361702 0.762044 0.27185 - 0.291708 0.65121 0.270019 - 0.282586 1.28403 0.271075 - 0.271373 1.28646 0.270823 - 0.247556 1.28415 0.27027 - 0.158858 1.22157 0.268106 - 0.119102 1.20201 0.267153 - 0.0854779 1.17582 0.266328 - 0.0135286 1.17691 0.264676 - -0.0786987 1.17243 0.262548 - -0.0880259 1.15974 0.262308 - -0.117838 1.20434 0.261712 - -0.193912 1.17932 0.259913 - -0.209296 1.20715 0.259615 - -0.324568 1.27042 0.257092 - -0.335639 1.26755 0.256832 - -0.349849 1.27616 0.256522 - -0.361785 1.27595 0.256247 - -0.3679 1.27629 0.256108 - -0.435781 1.27804 0.254551 - -0.453471 1.27506 0.254138 - -0.49099 0.847481 0.25242 - -0.492776 0.833698 0.252352 - -0.489904 0.717123 0.252185 - -0.494062 0.608146 0.251871 - -0.494277 0.581987 0.251814 - -0.496811 0.579828 0.251751 - -0.497569 0.560606 0.251695 - -0.497135 0.5408 0.251666 - -0.39442 -0.404279 0.247981 - -0.350768 -0.406308 0.249442 - -0.342351 -0.410809 0.249715 - -0.317269 -0.401526 0.250575 - -0.275643 -0.3999 0.251975 - -0.231961 -0.400271 0.25344 - -0.222699 -0.404331 0.253742 - -0.180358 -0.403003 0.255166 - -0.174677 -0.404393 0.255354 - -0.164953 -0.400877 0.255687 - -0.154762 -0.405959 0.256019 - -0.152941 -0.411975 0.256068 - -0.520038 -1.75693 0.241059 - -0.51865 -1.84059 0.240939 - -0.457678 -2.15617 0.242353 - -0.421898 -2.17362 0.243518 - -0.334378 -2.24135 0.246319 - -0.0654574 -0.50696 0.258813 - -0.0632459 -0.507235 0.258887 - -0.0610333 -0.5075 0.25896 - -0.199245 -2.28342 0.250769 - -0.0393649 -0.516602 0.259669 - 0.0286848 -0.400872 0.262184 - 0.0784045 -0.366403 0.263921 - 0.0829251 -0.371543 0.264062 - 0.0877246 -0.363217 0.26424 - 0.090889 -0.362425 0.264348 - 0.0924686 -0.362018 0.264402 - 0.0953509 -0.354006 0.264514 - 0.136885 -0.354994 0.265906 - 0.141089 -0.356559 0.266044 - 0.142642 -0.355933 0.266097 - 0.169514 -0.35385 0.267003 - 0.173921 -0.355034 0.267149 - 0.182082 -0.352009 0.267428 - 0.191537 -0.354901 0.26774 - 0.233452 -0.379086 0.269098 - 0.315465 -0.473707 0.27166 - 0.357082 -0.502048 0.273 - 1.25125 -1.47823 0.301048 - 1.25768 -1.47275 0.301275 - 1.26409 -1.46724 0.301501 - 1.28914 -1.45728 0.302361 - 0.378833 -0.410944 0.273912 - 0.468081 -0.407727 0.276913 - 0.620856 -0.403669 0.282047 - 0.714813 -0.404743 0.285197 - 0.82716 -0.408072 0.28896 - 1.00256 -0.410103 0.294841 - 1.30297 -0.416715 0.304907 - 2.40291 -0.509506 0.341627 - 2.36618 -0.426588 0.340561 - 2.41324 -0.230862 0.342531 - 7.24896 -0.0896941 0.505063 - 3.56645 0.456783 0.3826 - 2.42387 0.539831 0.34443 - 0.891173 0.299549 0.292524 - 0.405959 0.247751 0.27614 - 1.2455 0.933095 0.30568 - 1.25005 0.97981 0.305926 - 1.24639 1.06795 0.30598 - 1.24771 1.12705 0.306142 - 1.25259 1.22414 0.306501 - 1.2437 1.25864 0.306271 - 1.17938 1.28005 0.304156 - 1.14557 1.28778 0.303037 - 1.02039 1.27585 0.298813 - 1.00242 1.27608 0.298211 - 0.99439 1.2773 0.297944 - 0.986976 1.27926 0.297699 - 0.903183 1.28278 0.294894 - 0.70595 1.17997 0.288071 - 0.315153 0.896681 0.274392 - 0.2816 1.28208 0.274038 - 0.276007 1.2833 0.273852 - 0.264803 1.28568 0.273481 - 0.235076 1.28233 0.272477 - 0.206262 1.28226 0.27151 - 0.200668 1.28315 0.271324 - 0.142598 1.18123 0.269172 - 0.0897228 1.17045 0.267376 - -0.0380769 1.17043 0.263088 - -0.0711558 1.21199 0.262062 - -0.125824 1.17543 0.260154 - -0.168961 1.22459 0.258805 - -0.176057 1.16295 0.258444 - -0.323214 1.26364 0.253708 - -0.392224 1.27542 0.251416 - -0.397782 1.27371 0.251226 - -0.403634 1.27292 0.251028 - -0.471488 1.27184 0.248749 - -0.47703 1.26978 0.248559 - -0.490204 1.20776 0.247993 - -0.493949 1.20192 0.247856 - -0.491794 0.94076 0.247405 - -0.494402 0.888254 0.247213 - -0.488598 0.851347 0.247334 - -0.486119 0.790044 0.247294 - -0.493612 0.682986 0.246829 - -0.490675 0.666573 0.246894 - -0.494354 0.647586 0.246733 - -0.495277 0.620248 0.246647 - -0.493972 0.586431 0.246623 - -0.492388 0.540001 0.246584 - -0.407352 -0.402991 0.243304 - -0.397849 -0.403987 0.24372 - -0.3877 -0.404081 0.244167 - -0.338175 -0.405424 0.246344 - -0.328313 -0.400598 0.246788 - -0.307543 -0.406727 0.247689 - -0.291609 -0.403562 0.248397 - -0.239323 -0.404276 0.250697 - -0.2313 -0.398538 0.251062 - -0.225093 -0.399765 0.251333 - -0.202072 -0.398414 0.252349 - -0.194629 -0.4054 0.252662 - -0.165918 -0.397387 0.253942 - -0.477313 -2.15503 0.236717 - -0.439071 -2.16007 0.23839 - -0.382057 -2.22566 0.240768 - -0.346065 -2.25075 0.242302 - -0.33625 -2.25223 0.242731 - -0.326429 -2.25367 0.243161 - -0.0603471 -0.517693 0.258348 - -0.0371805 -0.511775 0.25938 - -0.0977238 -2.23993 0.253255 - -0.012818 -0.432859 0.26061 - 0.0411717 -0.348352 0.263156 - 0.0685192 -0.36935 0.264317 - 0.0717365 -0.368721 0.26446 - 0.0751525 -0.369044 0.26461 - 0.0811326 -0.365692 0.26488 - 0.088355 -0.360884 0.265207 - 0.114825 -0.353203 0.266388 - 0.133773 -0.352794 0.267223 - 0.158546 -0.35982 0.268299 - 0.188866 -0.358337 0.269636 - 0.192573 -0.354056 0.269808 - 0.285864 -0.455637 0.273711 - 0.295372 -0.466179 0.274109 - 0.33065 -0.470143 0.275653 - 0.344386 -0.467592 0.276263 - 0.725841 -0.882208 0.292223 - 1.29556 -1.53162 0.316 - 0.574476 -0.407045 0.286512 - 0.60807 -0.411122 0.287983 - 0.763242 -0.410758 0.294813 - 0.850602 -0.406212 0.298668 - 0.946728 -0.412015 0.302887 - 1.32564 -0.411523 0.319567 - 1.35035 -0.412722 0.320652 - 2.41121 -0.544691 0.367083 - 2.3888 -0.506813 0.366172 - 2.41043 -0.145922 0.367847 - 7.28088 -0.217421 0.582083 - 7.40496 -0.124023 0.587732 - 7.17188 0.0678823 0.577857 - 7.3223 0.614545 0.585572 - 3.55257 0.662094 0.419738 - 3.55063 0.677799 0.419684 - 2.48529 0.542437 0.37252 - 2.42298 0.551078 0.369795 - 2.15295 0.650872 0.358109 - 0.884323 0.301833 0.30157 - 0.875164 0.315914 0.301195 - 0.999118 0.375449 0.30677 - 0.997471 0.379818 0.306706 - 0.849782 0.353836 0.300153 - 0.845313 0.369458 0.299988 - 0.721947 0.346226 0.294511 - 0.722229 0.350254 0.294532 - 0.716071 0.399035 0.294358 - 0.712564 0.405291 0.294217 - 0.556802 0.323406 0.287196 - 0.471715 0.276916 0.283358 - 0.432104 0.261439 0.281584 - 1.24406 0.882782 0.318567 - 1.25018 0.971886 0.319015 - 1.24472 1.00301 0.318837 - 1.24285 1.08471 0.318918 - 1.24864 1.14874 0.319301 - 1.13932 1.28181 0.314756 - 1.0751 1.27538 0.311916 - 0.918165 1.28133 0.30502 - 0.720046 1.16976 0.296076 - 0.718356 1.2384 0.296139 - 0.331355 0.692878 0.278013 - 0.280374 1.27915 0.276942 - 0.204434 1.27436 0.27359 - 0.193467 1.2771 0.273113 - 0.0592 1.18442 0.267018 - -0.0293597 1.21669 0.263184 - -0.060925 1.21056 0.261782 - -0.10059 1.17787 0.259971 - -0.208042 1.19533 0.255276 - -0.216312 1.18167 0.254885 - -0.221278 1.17974 0.254663 - -0.260359 1.18715 0.252957 - -0.284532 1.17442 0.251868 - -0.423684 1.27704 0.245948 - -0.435445 1.2752 0.245427 - -0.440999 1.27329 0.245179 - -0.493835 1.20099 0.242708 - -0.489976 1.02227 0.24252 - -0.490697 0.948224 0.24234 - -0.493895 0.914886 0.242133 - -0.491126 0.782391 0.241989 - -0.485622 0.751536 0.24217 - -0.490883 0.685129 0.241805 - -0.492696 0.681364 0.241718 - -0.491341 0.609513 0.241634 - -0.492735 0.605816 0.241565 - -0.494859 0.592418 0.241445 - -0.495509 0.587962 0.241407 - -0.495482 0.58275 0.241398 - -0.497368 0.579828 0.241309 - -0.499677 0.519739 0.241087 - -0.396679 -0.40256 0.239593 - -0.349804 -0.401003 0.242156 - -0.288397 -0.39869 0.245514 - -0.285499 -0.398308 0.245673 - -0.283761 -0.399542 0.245765 - -0.257998 -0.398838 0.247174 - -0.245601 -0.398359 0.247852 - -0.24014 -0.405138 0.248136 - -0.22144 -0.400823 0.249166 - -0.214778 -0.401012 0.24953 - -0.2069 -0.623151 0.249515 - -0.522868 -2.02284 0.229456 - -0.515542 -2.10818 0.229685 - -0.477463 -2.15503 0.231671 - -0.422652 -2.22752 0.234519 - -0.0575221 -0.508996 0.257902 - -0.0976854 -2.23094 0.252259 - -0.0171879 -0.437743 0.260247 - 0.00356385 -0.420959 0.261414 - 0.00539783 -0.42093 0.261514 - 0.0495878 -0.356236 0.264057 - 0.0565944 -0.36021 0.264432 - 0.0584944 -0.361922 0.264532 - 0.0841559 -0.352534 0.265952 - 0.0874709 -0.352734 0.266133 - 0.126413 -0.35323 0.268259 - 0.146652 -0.35928 0.269352 - 0.1789 -0.363211 0.271105 - 0.17966 -0.349349 0.271175 - 0.199201 -0.348861 0.272243 - 0.211412 -0.359076 0.272889 - 0.294478 -0.456859 0.27723 - 0.326702 -0.478577 0.278946 - 0.347929 -0.495446 0.280072 - 0.771147 -0.946518 0.302281 - 0.38281 -0.412934 0.282142 - 0.435786 -0.404925 0.285051 - 0.506558 -0.408357 0.288909 - 0.565308 -0.408561 0.292117 - 0.62528 -0.407477 0.295395 - 0.727196 -0.412612 0.30095 - 1.17264 -0.409939 0.325282 - 1.42065 -0.41423 0.338818 - 2.38019 -0.615202 0.390819 - 2.38285 -0.604785 0.390985 - 2.38615 -0.506605 0.391362 - 2.22606 -0.452339 0.382728 - 2.41788 -0.371245 0.393366 - 2.40064 -0.177075 0.392814 - 2.50264 -0.129645 0.398479 - 7.40711 -0.0917464 0.666401 - 6.59366 0.235485 0.622632 - 6.61095 0.322954 0.623752 - 6.60948 0.35185 0.623729 - 6.86128 0.425435 0.637628 - 7.39721 0.784329 0.667615 - 3.55725 0.471961 0.457279 - 3.55847 0.567475 0.457537 - 3.55551 0.907693 0.458057 - 1.64461 0.45871 0.352798 - 1.64055 0.473086 0.352605 - 0.87939 0.313418 0.310716 - 1.14621 0.519162 0.3257 - 0.411664 0.272254 0.28509 - 1.24649 1.20961 0.33256 - 1.24474 1.23997 0.332525 - 1.19108 1.28366 0.329682 - 1.13427 1.27733 0.326567 - 1.12804 1.28153 0.326235 - 1.03716 1.27618 0.321261 - 0.928346 1.27324 0.315312 - 0.724543 1.2505 0.304137 - 0.379933 0.713798 0.284241 - 0.330462 0.648335 0.281409 - 0.31189 0.64646 0.280391 - 0.280141 0.738666 0.278841 - 0.277626 0.741765 0.27871 - 0.395995 1.26873 0.28623 - 0.379378 1.27385 0.285333 - 0.375521 1.28126 0.285137 - 0.334753 1.28641 0.282921 - 0.310628 1.28531 0.281601 - 0.263013 1.28274 0.278996 - 0.245466 1.28218 0.278036 - 0.147805 1.18952 0.272517 - 0.124136 1.2144 0.271274 - 0.0183837 1.24582 0.265562 --0.00833269 1.16398 0.263939 - -0.0243308 1.2068 0.263151 - -0.0391308 1.17542 0.26228 - -0.120912 1.16999 0.257803 - -0.155004 1.19426 0.255989 - -0.169761 1.18622 0.255167 - -0.183113 1.17009 0.254406 - -0.19556 1.18228 0.253751 - -0.223402 1.16109 0.252188 - -0.267488 1.16924 0.249796 - -0.28532 1.17636 0.248837 - -0.375535 1.27851 0.244114 - -0.394262 1.2802 0.243095 - -0.48857 1.26558 0.237915 - -0.490637 1.19266 0.237656 - -0.489995 1.03344 0.237373 - -0.494493 1.0313 0.237123 - -0.49632 0.890877 0.236742 - -0.49286 0.762464 0.236673 - -0.487973 0.740595 0.236896 - -0.498554 0.72869 0.236295 - -0.494066 0.682986 0.236448 - -0.491251 0.631404 0.236499 - -0.496976 0.594723 0.236113 - -0.488115 0.544267 0.236495 - -0.490481 0.54214 0.236362 - -0.497524 0.535694 0.235964 - -0.358544 -0.400145 0.237954 - -0.301512 -0.401645 0.241662 - -0.293896 -0.402293 0.242157 - -0.292141 -0.403562 0.242268 - -0.289803 -0.40401 0.24242 - -0.270606 -0.406297 0.243664 - -0.224608 -0.406085 0.246658 - -0.177859 -0.40455 0.249703 - -0.167553 -0.394821 0.250394 - -0.150209 -0.401653 0.251509 - -0.521511 -1.6793 0.224785 - -0.520305 -1.78511 0.224651 - -0.0576986 -0.507008 0.257318 - -0.186245 -2.23642 0.245486 - 0.0258359 -0.431054 0.262906 - 0.0313354 -0.351349 0.263424 - 0.0456154 -0.353703 0.264348 - 0.0645331 -0.370934 0.265545 - 0.117272 -0.363647 0.268992 - 0.119148 -0.358797 0.269124 - 0.120289 -0.352055 0.269211 - 0.128132 -0.35454 0.269717 - 0.152333 -0.369689 0.271261 - 0.163397 -0.348276 0.272024 - 0.19254 -0.352329 0.273913 - 0.211871 -0.360794 0.275154 - 0.224336 -0.374285 0.275938 - 0.783892 -0.954697 0.311189 - 1.32911 -1.56014 0.345457 - 1.28088 -1.4644 0.34251 - 0.380556 -0.418494 0.286016 - 0.398395 -0.4084 0.287197 - 0.518183 -0.407188 0.294995 - 0.584679 -0.407689 0.299321 - 0.641549 -0.406678 0.303024 - 0.695025 -0.402991 0.306511 - 0.767691 -0.409757 0.311227 - 0.840693 -0.406895 0.315983 - 0.846961 -0.405353 0.316394 - 0.953843 -0.406054 0.323348 - 1.3403 -0.410388 0.34849 - 2.41091 -0.534363 0.417913 - 2.39761 -0.520421 0.417075 - 2.22809 -0.432847 0.406219 - 2.41057 -0.316596 0.418328 - 7.40497 -0.156582 0.74367 - 7.40558 -0.12419 0.743775 - 7.40205 -0.0917464 0.74361 - 6.87956 0.125397 0.710043 - 6.73469 0.211193 0.700787 - 7.40206 0.785381 0.745368 - 3.73774 0.429838 0.506192 - 3.55527 0.583352 0.494625 - 3.55339 0.6471 0.494631 - 2.41688 0.561664 0.420498 - 3.59647 0.885385 0.497911 - 3.56644 0.894563 0.495976 - 1.64704 0.452036 0.37018 - 1.5957 0.506349 0.366948 - 0.873547 0.30309 0.319544 - 0.862453 0.333553 0.318883 - 0.858021 0.344874 0.318618 - 0.843602 0.35639 0.317702 - 0.714653 0.370942 0.30934 - 0.713353 0.386276 0.309286 - 0.439565 0.264149 0.291224 - 1.24546 0.970047 0.345084 - 1.24985 1.00005 0.34543 - 1.24695 1.04319 0.345328 - 1.24953 1.09259 0.345594 - 1.24444 1.10748 0.345293 - 1.06416 1.27624 0.3339 - 0.973004 1.27642 0.327967 - 0.883495 1.28241 0.322154 - 0.84939 1.26822 0.319907 - 0.326978 0.649783 0.28467 - 0.315818 0.64867 0.283941 - 0.321898 0.683492 0.284407 - 0.2526 0.619184 0.279768 - 0.274663 0.755445 0.281477 - 0.420161 1.27011 0.291977 - 0.404444 1.27841 0.290971 - 0.272912 1.27744 0.282409 - 0.257192 1.28585 0.281403 - 0.245985 1.28807 0.280678 - 0.239633 1.28522 0.280259 - 0.125647 1.18401 0.272639 - 0.0990668 1.17757 0.270896 - 0.0788867 1.18417 0.269596 - -0.0680145 1.22826 0.260124 - -0.161749 1.2025 0.253973 - -0.17413 1.17756 0.253117 - -0.179255 1.1768 0.252782 - -0.204192 1.20016 0.251206 - -0.209416 1.19927 0.250864 - -0.219947 1.16893 0.250118 - -0.25653 1.16663 0.247733 - -0.277267 1.16396 0.246378 - -0.381897 1.27879 0.239799 - -0.400051 1.27848 0.238617 - -0.418571 1.27887 0.237413 - -0.493445 1.19914 0.23238 - -0.490759 1.05854 0.232273 - -0.491003 1.03524 0.232211 - -0.489061 0.986204 0.232239 - -0.487196 0.920918 0.232229 - -0.492624 0.807534 0.231649 - -0.492748 0.776866 0.231579 - -0.487071 0.746063 0.231887 - -0.491924 0.705437 0.23149 - -0.492879 0.65667 0.23133 - -0.491396 0.631404 0.231376 - -0.492981 0.540001 0.231089 - -0.406125 -0.404758 0.230641 - -0.40119 -0.406842 0.231009 - -0.398026 -0.407147 0.231247 - -0.295269 -0.400209 0.239021 - -0.286535 -0.40281 0.239675 - -0.272602 -0.405121 0.240722 - -0.262817 -0.405569 0.24146 - -0.224224 -0.400736 0.244384 - -0.208408 -0.608078 0.245163 - -0.516835 -2.03576 0.219009 - -0.505691 -2.14861 0.219625 - -0.353437 -2.23045 0.230957 - -0.33504 -2.24036 0.232327 - -0.0982076 -2.22794 0.250235 - 0.0168043 -0.449556 0.262487 - 0.0207685 -0.450364 0.262785 - 0.0364233 -0.345734 0.264177 - 0.042958 -0.348954 0.264663 - 0.0479477 -0.3624 0.265013 - 0.0720844 -0.361212 0.266838 - 0.0747998 -0.358586 0.267049 - 0.0796518 -0.351329 0.26743 - 0.0844723 -0.351183 0.267794 - 0.106072 -0.362839 0.269401 - 0.152179 -0.370611 0.272868 - 0.15379 -0.369928 0.27299 - 0.173341 -0.354265 0.274498 - 0.200568 -0.353189 0.276556 - 0.205671 -0.351344 0.276945 - 0.207197 -0.350428 0.277063 - 0.219081 -0.366595 0.277927 - 0.328561 -0.496976 0.285933 - 0.716847 -0.882282 0.31448 - 0.798777 -0.973976 0.320483 - 0.395475 -0.439398 0.291101 - 0.450252 -0.405191 0.295306 - 0.482487 -0.40441 0.297742 - 0.617511 -0.411292 0.307924 - 0.629433 -0.411286 0.308824 - 0.756124 -0.408394 0.318397 - 0.772009 -0.408244 0.319596 - 0.876531 -0.410566 0.327484 - 1.05846 -0.407765 0.341227 - 1.07234 -0.407713 0.342276 - 1.10205 -0.407958 0.344519 - 1.12163 -0.409604 0.345994 - 1.22179 -0.410016 0.353557 - 1.25103 -0.413714 0.355757 - 1.35118 -0.407675 0.363331 - 1.47601 -0.410201 0.372753 - 2.22986 -0.423461 0.42965 - 2.36006 -0.426766 0.439475 - 2.41338 -0.392862 0.44357 - 2.42749 -0.147309 0.445128 - 7.40973 0.00540118 0.821651 - 6.70569 0.328068 0.769135 - 3.55534 0.664107 0.531921 - 3.5504 0.695415 0.531611 - 1.65601 0.447153 0.388065 - 1.65833 0.486993 0.388319 - 0.85082 0.346758 0.327062 - 0.853574 0.361038 0.327298 - 0.86322 0.374058 0.328053 - 1.15739 0.525333 0.35057 - 0.709824 0.388926 0.3165 - 0.456581 0.26935 0.297137 - 0.399725 0.255361 0.292816 - 0.4805 0.321579 0.299048 - 1.20167 0.831794 0.354528 - 1.24663 0.879055 0.358018 - 1.24725 0.972498 0.358252 - 1.25401 1.05023 0.358918 - 1.22538 1.18131 0.357019 - 1.15159 1.27698 0.351639 - 1.14069 1.27607 0.350814 - 1.0094 1.27873 0.340906 - 0.930873 1.2797 0.334978 - 0.915627 1.28214 0.333832 - 0.780111 1.22344 0.323481 - 0.726926 1.16256 0.319343 - 0.709606 1.16863 0.318047 - 0.717428 1.19313 0.318687 - 0.713768 1.19884 0.318422 - 0.721112 1.27331 0.319126 - 0.677292 1.24632 0.315763 - 0.322673 0.642652 0.287774 - 0.312507 0.657739 0.287037 - 0.259289 0.621531 0.282945 - 0.25387 0.623805 0.282541 - 0.380228 1.28151 0.293402 - 0.350666 1.28381 0.291174 - 0.261931 1.28372 0.284473 - 0.231591 1.27643 0.282167 - 0.16758 1.26645 0.277314 - 0.152371 1.19282 0.276018 - 0.0573365 1.17743 0.268811 - 0.00604208 1.17596 0.264934 - -0.0449018 1.16926 0.261074 - -0.0556516 1.18183 0.260288 - -0.0690642 1.24025 0.259392 - -0.111834 1.23321 0.256148 - -0.130755 1.15897 0.254571 - -0.182874 1.16416 0.250645 - -0.272234 1.16417 0.243898 - -0.373716 1.27083 0.236449 - -0.460855 1.27496 0.229877 - -0.49228 1.01473 0.226982 - -0.488387 0.953022 0.227152 - -0.491299 0.918791 0.226864 - -0.488574 0.800697 0.226833 - -0.490177 0.772639 0.226655 - -0.49347 0.559762 0.22598 - -0.494723 0.546596 0.225859 - -0.40199 -0.400512 0.226802 - -0.385925 -0.405037 0.228174 - -0.350325 -0.401003 0.231241 - -0.333037 -0.409018 0.232711 - -0.319134 -0.406055 0.233912 - -0.311401 -0.406981 0.234575 - -0.252441 -0.40046 0.239655 - -0.249261 -0.407117 0.239915 - -0.238082 -0.396357 0.240897 - -0.163169 -0.407639 0.247313 - -0.152227 -0.400067 0.248269 - -0.161188 -0.454221 0.24739 - -0.207464 -0.631649 0.243056 - -0.519734 -1.78319 0.213907 - -0.523 -1.95251 0.213286 - -0.384605 -2.23749 0.224609 - -0.323702 -2.22991 0.229858 - -0.306436 -2.24849 0.231305 --0.00322279 -0.416999 0.261041 - 0.0160082 -0.441564 0.262644 - 0.0281636 -0.343529 0.263886 - 0.0698185 -0.368721 0.267415 - 0.138125 -0.35563 0.273312 - 0.179199 -0.355473 0.276842 - 0.198474 -0.350592 0.278509 - 0.199493 -0.348841 0.2786 - 0.348191 -0.498711 0.291079 - 1.25432 -1.70326 0.366538 - 1.25097 -1.68332 0.36629 - 0.354854 -0.439593 0.29177 - 1.3408 -1.56339 0.374251 - 1.26645 -1.46396 0.36806 - 1.29327 -1.43063 0.370432 - 0.375246 -0.407087 0.293588 - 0.462217 -0.40576 0.301065 - 0.507494 -0.407374 0.304953 - 0.53882 -0.405866 0.307649 - 0.68434 -0.410066 0.320147 - 0.70344 -0.408984 0.321791 - 0.766513 -0.410225 0.327209 - 0.823331 -0.413022 0.332086 - 0.916974 -0.410539 0.340139 - 1.52131 -0.416055 0.392068 - 2.39718 -0.565519 0.467043 - 2.40177 -0.522324 0.467525 - 2.41534 -0.25339 0.469231 - 6.71196 0.299197 0.839611 - 6.78803 0.39205 0.846335 - 7.39315 0.720306 0.899 - 3.60747 0.447699 0.573095 - 3.55192 0.664107 0.568755 - 3.56856 0.86355 0.570586 - 2.18722 0.674051 0.451487 - 0.89107 0.309942 0.339359 - 0.86356 0.321828 0.337019 - 0.860727 0.329412 0.336791 - 0.850588 0.347133 0.335955 - 1.11401 0.494582 0.358891 - 1.11185 0.499472 0.358715 - 0.723601 0.348813 0.325045 - 0.71875 0.354292 0.324639 - 0.711909 0.374538 0.324091 - 0.403329 0.24827 0.297317 - 0.533627 0.357494 0.308735 - 1.24103 0.968822 0.370759 - 0.936962 1.27801 0.345247 - 0.725575 1.27012 0.327064 - 0.710094 1.26863 0.32573 - 0.273826 0.746729 0.287188 - 0.433164 1.27677 0.301946 - 0.26724 1.2845 0.287701 - 0.209194 1.28331 0.28271 - 0.103469 1.1811 0.273418 - 0.0977318 1.17459 0.272912 - 0.0922164 1.17004 0.272429 - -0.0966535 1.1733 0.256203 - -0.18824 1.16336 0.248312 - -0.225604 1.16797 0.24511 - -0.321697 1.2757 0.237068 - -0.395082 1.28116 0.230771 - -0.488213 0.762071 0.221725 - -0.493038 0.627687 0.221041 - -0.403096 -0.405096 0.222462 - -0.381501 -0.403792 0.224549 - -0.370416 -0.405906 0.225615 - -0.355441 -0.403242 0.227067 - -0.318749 -0.412773 0.23059 - -0.249846 -0.399844 0.237269 - -0.195578 -0.408953 0.24249 - -0.183549 -0.401306 0.243667 - -0.162273 -0.399503 0.245725 - -0.155994 -0.409436 0.246311 - -0.154214 -0.410099 0.246482 - -0.150981 -0.412342 0.246789 - -0.332738 -2.22354 0.225601 - -0.211239 -2.28851 0.237202 - -0.0398795 -0.490672 0.257359 - -0.0150728 -0.438857 0.259858 --0.00909959 -0.417967 0.260477 - 0.0180116 -0.452462 0.263025 - 0.0199765 -0.452361 0.263215 - 0.023288 -0.442153 0.263555 - 0.0274093 -0.39675 0.264045 - 0.0311862 -0.348213 0.264507 - 0.0372298 -0.347543 0.265092 - 0.0505872 -0.364906 0.266346 - 0.0575785 -0.367839 0.267016 - 0.0972527 -0.35367 0.270875 - 0.12959 -0.353383 0.273997 - 0.145231 -0.361127 0.275492 - 0.156211 -0.360733 0.276553 - 0.167409 -0.36437 0.277627 - 0.171066 -0.35593 0.277997 - 0.188169 -0.354901 0.27965 - 0.191244 -0.353203 0.279951 - 0.314674 -0.460711 0.291652 - 0.318663 -0.4579 0.292043 - 0.345535 -0.49147 0.29457 - 0.351908 -0.486832 0.295194 - 0.340674 -0.446487 0.294191 - 1.32454 -1.56014 0.386947 - 0.384184 -0.440102 0.298405 - 1.28405 -1.43481 0.38329 - 0.436354 -0.408316 0.303506 - 0.457325 -0.40582 0.305536 - 0.461338 -0.40576 0.305923 - 0.554224 -0.410552 0.314882 - 0.616487 -0.408025 0.320898 - 0.651524 -0.40289 0.324292 - 0.674632 -0.408959 0.326511 - 0.76976 -0.408244 0.335697 - 0.782125 -0.410382 0.336886 - 1.22062 -0.41065 0.379224 - 1.42103 -0.409383 0.398576 - 2.36593 -0.602822 0.489419 - 2.391 -0.575795 0.491894 - 2.22108 -0.422717 0.475796 - 2.35104 -0.426057 0.488336 - 2.41277 -0.296328 0.494557 - 7.39555 0.00540118 0.976261 - 6.79067 0.362728 0.918576 - 7.3904 0.819067 0.977399 - 3.71016 0.427902 0.621278 - 3.55356 0.520891 0.606345 - 3.55784 0.682106 0.607082 - 2.61644 0.56161 0.515946 - 2.20084 0.679034 0.476055 - 2.1569 0.686283 0.471827 - 0.862656 0.334989 0.34616 - 0.715557 0.349384 0.331986 - 0.716715 0.353853 0.332107 - 0.730994 0.422816 0.333624 - 0.418064 0.255252 0.303073 - 0.410998 0.253464 0.302387 - 1.24371 0.887404 0.384061 - 1.22953 1.17798 0.383276 - 1.23111 1.27592 0.383625 - 1.17044 1.27858 0.377773 - 1.06775 1.28544 0.367872 - 1.02523 1.27915 0.363754 - 0.757885 1.19231 0.337766 - 0.713636 1.17887 0.333467 - 0.736427 1.27815 0.335867 - 0.730868 1.28139 0.335337 - 0.290089 0.649926 0.29151 - 0.277472 0.62932 0.29025 - 0.269594 0.626272 0.289484 - 0.31385 1.28587 0.295082 - 0.278947 1.28794 0.291716 - 0.248593 1.28207 0.288774 - 0.225401 1.28139 0.286533 - 0.219662 1.2814 0.285979 - 0.112282 1.22542 0.275499 - 0.0739511 1.21245 0.271772 - 0.0507219 1.16769 0.269439 - 0.0265602 1.2166 0.267204 - -0.0213689 1.24288 0.262629 - -0.0309647 1.1897 0.261596 - -0.0571015 1.19582 0.259085 - -0.0819984 1.17841 0.256646 - -0.123188 1.17795 0.252668 - -0.136821 1.16139 0.251319 - -0.143632 1.17569 0.25069 - -0.184235 1.1691 0.246756 - -0.352109 1.27809 0.230767 - -0.382046 1.27783 0.227876 - -0.405086 1.27387 0.225643 - -0.457752 1.28354 0.220578 - -0.491852 1.25692 0.217232 - -0.495357 1.23403 0.216847 - -0.488105 1.17112 0.217421 - -0.488414 0.995509 0.217038 - -0.491545 0.909603 0.216563 - -0.496858 0.838866 0.215908 - -0.49489 0.827249 0.216075 - -0.489478 0.794305 0.216531 - -0.489683 0.728843 0.21638 - -0.494669 0.586431 0.215612 - -0.497802 0.579828 0.215297 - -0.500315 0.577659 0.21505 - -0.493013 0.564165 0.215728 - -0.492612 0.55387 0.215746 - -0.493284 0.526217 0.215625 - -0.3912 -0.406973 0.21959 - -0.386695 -0.405763 0.220074 - -0.331712 -0.39994 0.225965 - -0.237752 -0.407202 0.235998 - -0.187167 -0.404156 0.241413 - -0.16937 -0.406432 0.243311 - -0.527301 -1.72555 0.202385 - -0.523252 -1.88813 0.202491 - -0.46639 -2.14927 0.208046 - -0.352679 -2.22453 0.220053 - -0.342873 -2.22505 0.221101 - 0.00893118 -0.42779 0.262334 - 0.0328741 -0.339939 0.265071 - 0.0543708 -0.361197 0.267327 - 0.0635554 -0.342244 0.268347 - 0.067365 -0.331228 0.268777 - 0.0692336 -0.332863 0.268973 - 0.0782608 -0.34513 0.269914 - 0.160812 -0.363863 0.278703 - 0.187546 -0.354901 0.28158 - 0.270547 -0.433302 0.290297 - 0.290299 -0.43457 0.292407 - 0.302391 -0.435862 0.293697 - 0.385264 -0.438396 0.302554 - 0.382217 -0.412703 0.30228 - 0.388246 -0.408297 0.302933 - 0.443707 -0.405165 0.30887 - 0.476548 -0.405247 0.312381 - 0.689882 -0.410598 0.335182 - 1.07453 -0.410189 0.376313 - 1.20018 -0.41024 0.389749 - 1.33572 -0.410972 0.40424 - 2.37484 -0.616949 0.514939 - 2.38107 -0.596287 0.515646 - 2.41032 -0.581148 0.518805 - 2.40744 -0.404089 0.518853 - 2.4048 -0.220863 0.518939 - 2.41552 -0.125774 0.520276 - 6.73201 0.330357 0.982754 - 3.55882 0.602386 0.643993 - 3.54781 0.664838 0.642942 - 2.96509 0.62348 0.580549 - 1.65958 0.449749 0.440601 - 2.19341 0.66705 0.498121 - 0.916134 0.324099 0.360853 - 0.864671 0.323216 0.355348 - 0.858926 0.338423 0.354765 - 1.22427 0.525649 0.394208 - 1.22563 0.532618 0.394367 - 0.715984 0.361946 0.339527 - 0.716643 0.378237 0.33963 - 0.716847 0.415363 0.339727 - 0.501596 0.294369 0.316467 - 0.410606 0.248791 0.306646 - 0.4014 0.250573 0.305665 - 1.11592 0.76132 0.383096 - 1.20331 0.867871 0.392654 - 1.23743 0.942747 0.396454 - 1.24469 0.974337 0.397294 - 1.23227 1.06405 0.396145 - 1.22849 1.09886 0.395812 - 1.22267 1.18338 0.395359 - 1.21817 1.22095 0.394953 - 1.06854 1.27691 0.379066 - 1.05106 1.27858 0.377201 - 1.04235 1.27934 0.37627 - 1.00453 1.27795 0.372223 - 0.936519 1.28123 0.364958 - 0.900875 1.27882 0.361142 - 0.721591 1.24214 0.341897 - 0.730697 1.27037 0.342928 - 0.301644 0.639718 0.295781 - 0.442429 1.27289 0.312108 - 0.408836 1.28328 0.308537 - 0.344306 1.26935 0.301609 - 0.202592 1.28621 0.28649 - 0.196855 1.28612 0.285876 - 0.121202 1.21341 0.27764 - 0.115936 1.21395 0.277078 - 0.110668 1.21447 0.276516 - 0.0958391 1.16562 0.274832 - 0.0859521 1.16945 0.273782 - -0.156159 1.19029 0.247936 - -0.232477 1.17386 0.239742 - -0.315021 1.27126 0.231111 - -0.333289 1.27384 0.229163 - -0.418009 1.27601 0.220109 - -0.486753 0.97065 0.212144 - -0.489126 0.9052 0.211758 - -0.491132 0.80497 0.211342 - -0.494706 0.787477 0.210925 - -0.49309 0.681364 0.210884 - -0.492803 0.616337 0.210784 - -0.493892 0.526948 0.210488 - -0.496046 0.511091 0.210226 - -0.383941 -0.402859 0.216212 - -0.35857 -0.403196 0.219203 - -0.331904 -0.403697 0.222346 - -0.318193 -0.404478 0.223961 - -0.306358 -0.403531 0.225358 - -0.282475 -0.403631 0.228174 - -0.27785 -0.404401 0.228718 - -0.268079 -0.404954 0.229869 - -0.20213 -0.412663 0.237628 - -0.154426 -0.398476 0.243281 - -0.151996 -0.402591 0.24356 - -0.497916 -2.15956 0.199237 - -0.489644 -2.16659 0.200198 - -0.449802 -2.16401 0.204901 - -0.371925 -2.22138 0.213967 - -0.0657992 -0.503265 0.25352 - -0.0357652 -0.48099 0.257105 - -0.120481 -2.26198 0.243531 - -0.0986701 -2.21096 0.246205 --0.00088576 -0.41898 0.261343 - 0.0394064 -0.348161 0.266236 - 0.0819091 -0.349242 0.271245 - 0.0877103 -0.352903 0.271921 - 0.118291 -0.359206 0.275514 - 0.129479 -0.356188 0.276839 - 0.131735 -0.357461 0.277103 - 0.138214 -0.360273 0.277861 - 0.147456 -0.36944 0.278932 - 0.154092 -0.354559 0.279745 - 0.18627 -0.357501 0.283532 - 0.195004 -0.351474 0.284574 - 0.306586 -0.455513 0.29752 - 0.335884 -0.446408 0.300993 - 0.730716 -0.921284 0.346588 - 0.383155 -0.444805 0.30657 - 0.399596 -0.410191 0.308578 - 0.425872 -0.407368 0.311681 - 0.429086 -0.406835 0.312061 - 0.475519 -0.405247 0.317539 - 0.658498 -0.40863 0.339106 - 0.686074 -0.405032 0.342364 - 0.780366 -0.410843 0.35347 - 0.793633 -0.408915 0.355038 - 0.803369 -0.405002 0.356194 - 0.877482 -0.404094 0.364933 - 1.07277 -0.410189 0.387946 - 1.15538 -0.412737 0.39768 - 1.19545 -0.409278 0.402411 - 1.34504 -0.414472 0.420038 - 2.3886 -0.610185 0.542681 - 2.40425 -0.415006 0.544919 - 2.40602 -0.404418 0.54515 - 2.41855 -0.362872 0.54671 - 2.41715 -0.330096 0.546611 - 2.41581 -0.275916 0.546563 - 2.41227 -0.243291 0.546211 - 2.39472 -0.167194 0.544295 - 2.40236 -0.157103 0.545216 - 2.41552 -0.136616 0.546809 - 6.78154 0.273462 1.0624 - 3.55271 0.650494 0.68247 - 1.92469 0.57711 0.490377 - 2.03356 0.67855 0.503417 - 0.873834 0.314087 0.36595 - 0.717505 0.35156 0.347594 - 0.709266 0.379066 0.346678 - 0.416704 0.250524 0.311925 - 0.403834 0.252665 0.310412 - 0.413285 0.271334 0.311564 - 0.969194 0.650342 0.37787 - 1.02523 0.700862 0.384578 - 1.228 1.15962 0.409409 - 1.22856 1.22259 0.409602 - 1.19908 1.27971 0.406241 - 1.1682 1.28005 0.402601 - 1.04993 1.27935 0.388656 - 0.916173 1.27892 0.372885 - 0.859088 1.28019 0.366157 - 0.826434 1.27929 0.362305 - 0.745039 1.17632 0.352501 - 0.715493 1.1632 0.348991 - 0.710445 1.16635 0.348402 - 0.723314 1.27272 0.350134 - 0.692489 1.26958 0.346493 - 0.444597 0.844221 0.31641 - 0.309539 0.636527 0.300068 - 0.300534 0.632075 0.298997 - 0.26727 0.624441 0.29506 - 0.285192 0.743615 0.297413 - 0.435232 1.27295 0.316169 - 0.333667 1.2772 0.304203 - 0.328129 1.27868 0.303553 - 0.236149 1.28522 0.292721 - 0.195667 1.28315 0.287944 - 0.190104 1.28402 0.28729 - 0.100919 1.17214 0.27655 - -0.0111849 1.18498 0.263359 - -0.0365055 1.17157 0.260346 - -0.0413317 1.16343 0.259761 - -0.157084 1.19525 0.246178 - -0.171216 1.18325 0.244487 - -0.212298 1.17768 0.239632 - -0.217221 1.17577 0.239048 - -0.436137 1.2752 0.213438 - -0.493013 1.27678 0.206735 - -0.487738 1.01686 0.206834 - -0.490424 1 0.206483 - -0.493281 0.942534 0.206031 - -0.488593 0.81694 0.20633 - -0.495667 0.745134 0.205352 - -0.496528 0.548824 0.204855 - -0.498504 0.518295 0.20456 - -0.389731 -0.405527 0.211398 - -0.346359 -0.403264 0.216982 - -0.337926 -0.403885 0.218065 - -0.317607 -0.40369 0.220679 - -0.301714 -0.404556 0.222722 - -0.284886 -0.399542 0.224896 - -0.277991 -0.400724 0.225781 - -0.266539 -0.402444 0.22725 - -0.244395 -0.394094 0.230116 - -0.22983 -0.405002 0.231967 - -0.221246 -0.401777 0.233078 - -0.217759 -0.403662 0.233522 - -0.210739 -0.40734 0.234418 - -0.188916 -0.402441 0.237235 - -0.159223 -0.405286 0.241048 - -0.150492 -0.403234 0.242176 - -0.157309 -0.440056 0.241225 - -0.163453 -0.464365 0.240385 - -0.505426 -2.15056 0.192998 - -0.40826 -2.20377 0.205389 - -0.131064 -2.27143 0.240907 - -0.0888786 -2.19836 0.246481 - -0.0104008 -0.419967 0.260161 - 0.00050465 -0.419959 0.261564 - 0.00232203 -0.41993 0.261798 - 0.0277727 -0.377533 0.265157 - 0.108031 -0.361375 0.275513 - 0.146521 -0.359806 0.280467 - 0.169643 -0.369029 0.283422 - 0.172012 -0.357843 0.28375 - 0.191261 -0.353216 0.286235 - 0.197845 -0.350568 0.287087 - 0.206983 -0.355568 0.288253 - 0.281063 -0.448063 0.297595 - 0.29595 -0.44531 0.299515 - 0.304887 -0.450035 0.300655 - 0.345307 -0.494725 0.305764 - 0.346136 -0.478037 0.305904 - 0.380512 -0.427563 0.310428 - 0.401803 -0.402724 0.313217 - 0.488905 -0.406467 0.324413 - 0.569309 -0.408774 0.33475 - 0.781564 -0.407846 0.362054 - 1.13576 -0.412098 0.407605 - 1.32957 -0.410388 0.432537 - 2.41103 -0.394942 0.571673 - 2.41271 -0.297539 0.572085 - 2.41362 -0.243789 0.572311 - 2.39161 -0.188429 0.569591 - 7.40127 0.0705953 1.21449 - 6.75319 0.153641 1.1313 - 6.75245 0.183372 1.13126 - 6.79043 0.334108 1.13645 - 6.59839 0.412092 1.11191 - 3.56378 0.460464 0.721672 - 3.555 0.571247 0.720766 - 3.5612 0.866126 0.722159 - 1.68231 0.441404 0.479626 - 1.68051 0.496811 0.479507 - 2.12502 0.689333 0.53707 - 0.860168 0.327027 0.373646 - 0.92367 0.398444 0.381958 - 0.839799 0.384641 0.371142 - 0.719688 0.3533 0.35563 - 0.709873 0.408742 0.354479 - 0.9314 0.638165 0.383436 - 0.927514 0.659722 0.382979 - 0.929028 0.673137 0.383201 - 0.908378 0.720992 0.380642 - 0.912959 0.737729 0.381265 - 1.12722 1.01199 0.409378 - 1.22306 1.16708 0.422018 - 1.18119 1.28512 0.41687 - 1.17427 1.28886 0.415988 - 1.06425 1.27614 0.40181 - 0.912178 1.27568 0.382249 - 0.88696 1.27543 0.379005 - 0.865273 1.27968 0.376224 - 0.709142 1.20141 0.355983 - 0.729873 1.2611 0.35877 - 0.325979 0.650113 0.305587 - 0.304852 0.657308 0.302884 - 0.270369 0.62598 0.298385 - 0.277677 0.765467 0.299606 - 0.337504 1.2728 0.308325 - 0.311315 1.28587 0.304982 - 0.305747 1.28725 0.304269 - 0.224234 1.28729 0.293784 - 0.157035 1.21195 0.284989 - 0.131638 1.17688 0.281651 - 0.0394017 1.17812 0.26979 - 0.0308445 1.23445 0.268803 - -0.0370644 1.17657 0.259951 - -0.0779557 1.17774 0.254694 - -0.12386 1.17497 0.248784 - -0.164087 1.20647 0.243673 - -0.231324 1.16601 0.234943 - -0.326177 1.26849 0.222949 - -0.381821 1.27687 0.215808 - -0.416071 1.27031 0.21139 - -0.439614 1.26762 0.208356 - -0.497507 1.16592 0.200704 - -0.49393 0.860026 0.200548 - -0.490195 0.844884 0.200998 - -0.487914 0.816081 0.201233 - -0.495726 0.679214 0.199952 - -0.498995 0.566525 0.199304 - -0.497102 0.512528 0.199439 - -0.406694 -0.405466 0.205102 - -0.397949 -0.407147 0.206313 - -0.364597 -0.403047 0.210953 - -0.298784 -0.400535 0.220099 - -0.242266 -0.394287 0.227961 - -0.237405 -0.401853 0.22862 - -0.226819 -0.395303 0.230104 - -0.221199 -0.397315 0.23088 - -0.204699 -0.408222 0.23315 - -0.178369 -0.401798 0.23682 - -0.520005 -1.65221 0.186848 - -0.514649 -2.14931 0.186588 - -0.111815 -2.27645 0.242277 - -0.0898987 -2.21835 0.245439 --0.00357086 -0.414994 0.261069 - 0.00585329 -0.431843 0.262344 - 0.0178386 -0.446369 0.263979 - 0.0279872 -0.427652 0.265427 - 0.0280314 -0.367427 0.265554 - 0.0465455 -0.351062 0.268159 - 0.0530148 -0.362184 0.269035 - 0.0683042 -0.335791 0.271211 - 0.0921664 -0.349299 0.274498 - 0.117443 -0.360152 0.277987 - 0.130038 -0.360862 0.279734 - 0.136991 -0.360273 0.280701 - 0.149417 -0.363727 0.28242 - 0.158668 -0.355152 0.283722 - 0.167392 -0.357592 0.284929 - 0.169813 -0.35862 0.285263 - 0.172012 -0.355275 0.285575 - 0.182102 -0.363536 0.28696 - 0.191132 -0.350608 0.28824 - 0.283821 -0.449314 0.300913 - 0.312767 -0.480355 0.304871 - 0.759149 -0.918691 0.36598 - 0.376042 -0.409064 0.313802 - 0.401551 -0.403424 0.317357 - 0.40329 -0.401627 0.317602 - 0.408587 -0.403292 0.318334 - 0.439365 -0.411107 0.322593 - 0.464356 -0.408282 0.326069 - 0.491666 -0.409628 0.329859 - 0.55155 -0.408101 0.338179 - 0.61091 -0.407477 0.346425 - 0.794206 -0.406302 0.371883 - 0.802161 -0.405893 0.372989 - 0.898582 -0.405666 0.386381 - 0.922094 -0.411329 0.389634 - 1.13661 -0.413109 0.419424 - 1.17841 -0.410649 0.425233 - 1.73324 -0.43636 0.502237 - 1.90923 -0.418282 0.526715 - 2.06385 -0.414024 0.548198 - 2.21612 -0.414049 0.569345 - 2.37278 -0.421609 0.591087 - 2.4148 -0.330766 0.597106 - 2.41366 -0.265711 0.59708 - 2.41586 -0.244385 0.597429 - 2.41882 -0.212363 0.597903 - 2.41081 -0.126084 0.596965 - 7.39815 -0.125043 1.28962 - 6.8023 0.275062 1.20767 - 6.79153 0.394692 1.20642 - 3.54781 0.570932 0.756282 - 3.55669 0.620738 0.757615 - 3.55213 0.70097 0.757144 - 2.45806 0.542011 0.604877 - 0.886961 0.293602 0.386179 - 0.866486 0.325643 0.3834 - 0.72298 0.35956 0.363538 - 0.721614 0.366861 0.363363 - 0.710242 0.405592 0.361862 - 0.569196 0.33239 0.342125 - 0.408294 0.251642 0.319616 - 0.407202 0.253464 0.319468 - 0.824584 0.555857 0.378045 - 0.852484 0.591011 0.381991 - 0.851592 0.618496 0.381922 - 0.851015 0.629558 0.381865 - 0.835013 0.707196 0.379799 - 1.09326 1.07336 0.416404 - 1.22039 1.26192 0.434442 - 1.21493 1.26732 0.433693 - 1.11881 1.27434 0.420358 - 1.01336 1.27293 0.405711 - 0.992479 1.2808 0.402826 - 0.828297 1.27479 0.380012 - 0.27037 0.627807 0.30122 - 0.139689 1.16373 0.284153 - 0.0785998 1.23604 0.275815 - -0.0228222 1.22088 0.261699 - -0.0876372 1.16509 0.252584 - -0.0931181 1.17071 0.251835 - -0.267943 1.16436 0.227542 - -0.406761 1.27959 0.208495 - -0.418726 1.27887 0.206832 - -0.468793 1.28046 0.199882 - -0.490302 1.04643 0.196422 - -0.492702 1.03976 0.196075 - -0.494339 1.02013 0.195808 - -0.487775 0.963169 0.196605 - -0.493045 0.8765 0.195698 - -0.48714 0.739759 0.196242 - -0.487452 0.72635 0.196172 - -0.49177 0.712512 0.195544 - -0.372625 -0.405034 0.206038 - -0.311475 -0.395805 0.215183 - -0.291237 -0.404824 0.218185 - -0.254901 -0.399366 0.223618 - -0.240436 -0.398936 0.225778 - -0.231771 -0.40401 0.22706 - -0.222407 -0.403535 0.228459 - -0.203499 -0.401075 0.231285 - -0.178924 -0.402716 0.234949 - -0.150386 -0.412982 0.239187 - -0.177673 -0.512414 0.234914 - -0.208803 -0.6326 0.230026 - -0.486195 -2.15488 0.185551 - -0.428317 -2.15705 0.194184 - -0.391747 -2.22398 0.199506 - -0.374159 -2.23716 0.202105 - -0.0618987 -0.498813 0.252219 - -0.0370176 -0.482986 0.255964 - -0.0130878 -0.42394 0.259655 - 0.0156106 -0.449465 0.263886 - 0.0224457 -0.435045 0.264935 - 0.0309647 -0.354022 0.26637 - 0.0343721 -0.343571 0.2669 - 0.0542618 -0.344638 0.269866 - 0.0568715 -0.342126 0.27026 - 0.126966 -0.354318 0.280696 - 0.147211 -0.360053 0.283706 - 0.163683 -0.351303 0.286182 - 0.170246 -0.356949 0.28715 - 0.182682 -0.358337 0.289003 - 0.183758 -0.356621 0.289167 - 0.204998 -0.347722 0.292354 - 0.268719 -0.43125 0.301695 - 0.312679 -0.472574 0.308171 - 0.332219 -0.483202 0.311066 - 0.336698 -0.476258 0.311748 - 1.25987 -1.62075 0.447202 - 0.753128 -0.954799 0.372926 - 0.473275 -0.402494 0.332279 - 0.492289 -0.407433 0.335107 - 0.530719 -0.404671 0.340847 - 0.596746 -0.414344 0.350681 - 0.607833 -0.410189 0.352344 - 0.767111 -0.406232 0.376122 - 0.816512 -0.409397 0.383487 - 0.857429 -0.406346 0.3896 - 0.940203 -0.410233 0.401944 - 0.976441 -0.405567 0.407362 - 1.16972 -0.408375 0.436199 - 1.20978 -0.410333 0.442174 - 1.30432 -0.41034 0.456283 - 1.44684 -0.41315 0.477545 - 1.8348 -0.419738 0.535428 - 2.06152 -0.423732 0.569254 - 2.21746 -0.425133 0.592523 - 2.41001 -0.298145 0.621514 - 2.42133 -0.277828 0.623244 - 2.41294 -0.222951 0.622103 - 7.38434 -0.157615 1.36413 - 7.40562 0.0381433 1.3677 - 3.55369 0.492528 0.793787 - 3.55929 0.557564 0.794754 - 3.55787 0.621928 0.794673 - 3.55824 0.686974 0.794859 - 2.58306 0.558481 0.649071 - 2.04183 0.634781 0.568456 - 1.19973 0.481368 0.442477 - 0.706412 0.340498 0.368573 - 0.713236 0.367358 0.369646 - 0.712171 0.411701 0.369577 - 0.409011 0.260254 0.324029 - 0.406207 0.261023 0.323612 - 0.406438 0.266266 0.323657 - 0.764421 0.516626 0.377586 - 0.770888 0.577097 0.378674 - 0.765876 0.583933 0.377939 - 0.752549 0.595019 0.375973 - 0.760246 0.617474 0.377167 - 0.76093 0.711959 0.37746 - 0.844124 0.939915 0.390336 - 0.850342 0.989297 0.391364 - 0.844993 1.00061 0.390589 - 0.844559 1.0454 0.390615 - 0.842538 1.05225 0.390327 - 0.83741 1.11369 0.389686 - 0.698083 1.27436 0.369219 - 0.384013 0.743727 0.321276 - 0.279105 0.743951 0.305621 - 0.283965 1.27664 0.307424 - 0.155821 1.21294 0.288171 - 0.134486 1.16833 0.284897 - 0.104845 1.17863 0.280495 - 0.0587716 1.17815 0.273618 - 0.0536359 1.17743 0.27285 - 0.0480896 1.16769 0.272003 --0.00738997 1.175 0.263738 - -0.0126099 1.20298 0.263016 - -0.0232718 1.22288 0.261465 - -0.0700039 1.20729 0.25446 - -0.0752133 1.207 0.253682 - -0.123081 1.2143 0.246553 - -0.175135 1.16964 0.238694 - -0.352194 1.27809 0.212491 - -0.478556 1.27353 0.193624 - -0.492844 1.26158 0.191468 - -0.490853 1.22474 0.191691 - -0.495179 1.09467 0.190782 - -0.497503 0.99391 0.190231 - -0.4918 0.784087 0.190658 - -0.488449 0.606395 0.190799 - -0.393762 -0.406711 0.198609 - -0.387526 -0.407215 0.199608 - -0.363245 -0.405371 0.203503 - -0.360188 -0.405445 0.203992 - -0.353235 -0.400985 0.205116 - -0.329972 -0.40513 0.208835 - -0.301067 -0.403752 0.21347 - -0.28027 -0.404023 0.216803 - -0.275024 -0.407617 0.217636 - -0.210582 -0.401985 0.227975 - -0.187709 -0.398808 0.231647 - -0.182395 -0.405612 0.232484 - -0.185609 -0.54352 0.23169 - -0.52098 -1.91837 0.17516 - -0.486013 -2.15586 0.180283 - -0.476294 -2.156 0.18184 - -0.427056 -2.15215 0.189738 - -0.372487 -2.22829 0.198329 - -0.297194 -2.17912 0.210495 - -0.284734 -2.15659 0.212537 - -0.0662995 -0.496316 0.250906 - -0.0374661 -0.483984 0.255551 - -0.017514 -0.437857 0.258842 - -0.0155249 -0.432903 0.259171 --0.00981521 -0.417986 0.260116 --0.00438053 -0.423994 0.260975 - 0.011184 -0.447641 0.263422 - 0.0279281 -0.395463 0.266211 - 0.0936035 -0.352709 0.276822 - 0.095122 -0.352263 0.277066 - 0.0960757 -0.349893 0.277224 - 0.144502 -0.368516 0.284947 - 0.162058 -0.357299 0.287783 - 0.173928 -0.365895 0.289668 - 0.186218 -0.347983 0.291674 - 0.217606 -0.355746 0.296688 - 0.29739 -0.46425 0.309254 - 0.319516 -0.462177 0.312804 - 0.379256 -0.448768 0.322405 - 0.394876 -0.409481 0.324988 - 0.442118 -0.408508 0.33256 - 0.44756 -0.409848 0.33343 - 0.633442 -0.408277 0.363222 - 0.727873 -0.407337 0.378357 - 0.904835 -0.410133 0.40671 - 1.15063 -0.408294 0.446104 - 1.22784 -0.411215 0.458471 - 1.33368 -0.413889 0.475428 - 1.41098 -0.417301 0.487808 - 1.45444 -0.416128 0.494776 - 1.74121 -0.423584 0.540717 - 2.40582 -0.287366 0.647501 - 7.38694 0.792539 1.44794 - 3.5582 0.542274 0.833857 - 3.55923 0.574704 0.834088 - 3.55148 0.621928 0.832942 - 3.55849 0.63939 0.8341 - 3.544 0.899416 0.832304 - 1.08317 0.402675 0.436935 - 1.19706 0.456855 0.455298 - 1.21012 0.486509 0.457451 - 0.750128 0.345971 0.383449 - 0.727076 0.339344 0.379741 - 0.468048 0.309786 0.338171 - 0.705234 0.574481 0.376718 - 0.690814 0.626026 0.374511 - 0.698189 0.672682 0.375787 - 0.710261 0.714753 0.377807 - 0.705468 0.722479 0.377055 - 0.720298 0.863594 0.379717 - 0.724853 0.876728 0.380474 - 0.720983 0.895619 0.379892 - 0.717281 0.957315 0.379424 - 0.739352 1.07116 0.383191 - 0.709249 1.1974 0.378623 - 0.71322 1.21599 0.379297 - 0.670968 1.26687 0.372629 - 0.582475 1.113 0.358135 - 0.330065 0.656635 0.316761 - 0.277147 0.704544 0.308378 - 0.349299 1.28321 0.321112 - 0.28783 1.27242 0.31124 - 0.255638 1.28372 0.306104 - 0.231094 1.27539 0.302153 - 0.00717161 1.16191 0.266039 - -0.133943 1.16593 0.243432 - -0.155797 1.21973 0.240039 - -0.221079 1.165 0.229466 - -0.334553 1.27868 0.211512 - -0.467592 1.27858 0.190191 - -0.493454 1.23217 0.185953 - -0.49097 1.21054 0.186307 - -0.490116 1.09681 0.186213 - -0.486832 0.952131 0.186447 - -0.488521 0.834973 0.185939 - -0.488599 0.826808 0.18591 - -0.492347 0.770501 0.185195 - -0.491185 0.692971 0.185224 - -0.497158 0.601505 0.184082 - -0.495319 0.593954 0.184361 - -0.496584 0.585038 0.18414 - -0.345298 -0.402503 0.202749 - -0.305038 -0.401933 0.209634 - -0.277285 -0.407256 0.214369 - -0.227582 -0.408717 0.222865 - -0.204531 -0.398414 0.226828 - -0.185059 -0.406658 0.230141 - -0.177855 -0.404393 0.231377 - -0.16654 -0.401588 0.233317 - -0.182291 -0.533086 0.230357 - -0.519223 -1.62897 0.17052 - -0.518496 -1.87849 0.170138 - -0.208811 -2.25365 0.222331 - -0.0423576 -0.488678 0.254375 - -0.0402555 -0.48883 0.254734 - -0.112644 -2.28045 0.238721 - -0.0222185 -0.453734 0.25789 - -0.0179685 -0.439857 0.258645 - 0.0090169 -0.453711 0.263231 - 0.0466268 -0.36194 0.269848 - 0.0501755 -0.354289 0.27047 - 0.060309 -0.326951 0.272259 - 0.109014 -0.350794 0.280539 - 0.137739 -0.358077 0.285436 - 0.156717 -0.359503 0.288678 - 0.167247 -0.357723 0.290482 - 0.176331 -0.364286 0.292022 - 0.212155 -0.35517 0.298166 - 0.223127 -0.362318 0.300028 - 0.260173 -0.416622 0.306252 - 0.294069 -0.447789 0.311985 - 1.18448 -1.67583 0.461748 - 1.24147 -1.69293 0.471458 - 1.25865 -1.61124 0.474563 - 0.70909 -0.89552 0.382043 - 0.767912 -0.943565 0.392004 - 0.404979 -0.406508 0.331034 - 0.54917 -0.409276 0.355684 - 0.740057 -0.41076 0.388322 - 0.811065 -0.404013 0.400477 - 0.887576 -0.408005 0.413552 - 0.901032 -0.409321 0.41585 - 0.963205 -0.406842 0.426487 - 1.08643 -0.408304 0.447554 - 1.27102 -0.413978 0.479107 - 1.82 -0.417978 0.572971 - 2.15011 -0.423723 0.629406 - 2.39462 -0.405897 0.671252 - 2.4198 -0.322307 0.675727 - 7.40829 0.00546584 1.52939 - 3.56048 0.447086 0.872338 - 0.890686 0.2967 0.415514 - 0.944945 0.342853 0.424885 - 1.21517 0.483305 0.471377 - 0.717358 0.347334 0.385978 - 0.659542 0.367903 0.376134 - 0.652042 0.371365 0.374858 - 0.607666 0.35352 0.367234 - 0.420284 0.274059 0.335032 - 0.667269 0.453637 0.377629 - 0.666949 0.45773 0.377583 - 0.656858 0.481311 0.375905 - 0.65456 0.493048 0.375536 - 0.652666 0.598447 0.375426 - 0.663625 0.669862 0.377445 - 0.66553 0.759246 0.377952 - 0.691097 0.830877 0.382469 - 0.699109 0.855425 0.383889 - 0.713238 0.962896 0.386523 - 0.723976 1.14448 0.388727 - 0.712294 1.15918 0.38676 - 0.60009 1.14913 0.367553 - 0.328581 0.655747 0.320126 - 0.30452 0.635632 0.31597 - 0.299608 0.63252 0.315124 - 0.273047 0.611057 0.310539 - 0.274727 0.747071 0.311102 - 0.27569 0.759537 0.311292 - 0.297555 1.24511 0.316016 - 0.208245 1.27941 0.300814 - 0.190033 1.2713 0.297684 - 0.0800388 1.20674 0.278744 - 0.0664714 1.24173 0.276495 - 0.0572919 1.17216 0.274785 - -0.0291499 1.2088 0.260078 - -0.0658646 1.21455 0.253811 - -0.111863 1.20034 0.245917 - -0.144789 1.16973 0.240225 - -0.166899 1.18198 0.236469 - -0.175777 1.17162 0.23493 - -0.21217 1.17275 0.228709 - -0.217212 1.17184 0.227845 - -0.255243 1.20404 0.221408 - -0.322717 1.27862 0.210021 - -0.349873 1.27037 0.205361 - -0.364815 1.28172 0.202829 - -0.370323 1.28013 0.201884 - -0.497328 0.963332 0.179524 - -0.493177 0.935072 0.180176 - -0.49351 0.897408 0.180043 - -0.488112 0.771794 0.180711 - -0.489915 0.71795 0.180294 - -0.488377 0.695924 0.180512 - -0.486879 0.662543 0.1807 - -0.485613 0.65479 0.180901 - -0.391122 -0.397563 0.189781 - -0.38519 -0.408894 0.190851 - -0.255241 -0.403853 0.214823 - -0.227044 -0.395303 0.220039 - -0.211211 -0.40734 0.222934 - -0.209461 -0.40824 0.223255 - -0.169163 -0.402729 0.230697 - -0.164324 -0.405777 0.231583 - -0.153382 -0.425891 0.23356 - -0.157617 -0.444504 0.232741 - -0.521855 -1.66461 0.163098 - -0.524457 -1.84023 0.162261 - -0.516953 -1.90776 0.163507 - -0.503882 -2.15348 0.165418 - -0.360898 -2.221 0.191645 - -0.311806 -2.21842 0.200703 - -0.0638445 -0.487637 0.249944 - -0.112739 -2.27745 0.237288 - -0.0143557 -0.418941 0.259209 - -0.0106926 -0.409986 0.259903 --0.00361683 -0.413981 0.261199 - 0.0121719 -0.449556 0.264038 - 0.144294 -2.31791 0.2846 - 0.0292571 -0.353028 0.267385 - 0.0342647 -0.35648 0.268301 - 0.0522425 -0.334529 0.271661 - 0.120049 -0.360376 0.284111 - 0.138665 -0.367056 0.28753 - 0.140238 -0.366404 0.287821 - 0.140677 -0.362975 0.287909 - 0.15847 -0.357137 0.291202 - 0.161528 -0.35565 0.291769 - 0.185381 -0.353203 0.296172 - 0.188404 -0.351478 0.296733 - 0.193905 -0.347087 0.297756 - 0.324639 -0.431584 0.32169 - 0.32465 -0.423928 0.321708 - 0.699499 -0.862886 0.389934 - 0.38804 -0.434426 0.333375 - 0.435416 -0.408471 0.342164 - 0.44432 -0.405852 0.343811 - 0.469444 -0.409936 0.348435 - 0.479994 -0.408001 0.350384 - 0.518247 -0.402225 0.35745 - 0.599669 -0.407984 0.372451 - 0.669001 -0.404515 0.385242 - 0.77267 -0.412226 0.404342 - 0.804266 -0.406305 0.41018 - 0.878753 -0.409891 0.423908 - 0.900211 -0.410133 0.427864 - 0.986764 -0.412749 0.443818 - 1.07148 -0.409295 0.459447 - 1.13491 -0.410405 0.471139 - 1.16908 -0.410974 0.477439 - 1.26006 -0.411544 0.494213 - 1.47389 -0.409497 0.533646 - 1.80455 -0.407082 0.594621 - 2.4113 -0.332912 0.706651 - 2.4085 -0.213141 0.706378 - 2.39945 -0.190838 0.704754 - 2.40561 -0.159043 0.705955 - 7.4111 -0.0603519 1.62912 - 3.55952 0.448067 0.919958 - 2.42513 0.53903 0.710974 - 1.71903 0.447305 0.58059 - 0.899615 0.282809 0.429163 - 0.889942 0.297319 0.427409 - 0.931172 0.329517 0.435077 - 1.27824 0.477041 0.499372 - 1.25471 0.532862 0.495148 - 1.25241 0.538458 0.494735 - 0.692559 0.35569 0.391132 - 0.493254 0.291649 0.354252 - 0.426595 0.276408 0.34193 - 0.599805 0.401847 0.374123 - 0.605338 0.462035 0.375266 - 0.602789 0.526395 0.374927 - 0.593658 0.537151 0.373265 - 0.591346 0.539815 0.372844 - 0.611072 0.664174 0.376734 - 0.703883 0.953339 0.394436 - 0.720349 0.99329 0.397553 - 0.717309 1.01666 0.39704 - 0.723862 1.07443 0.398366 - 0.720682 1.12128 0.397875 - 0.71738 1.22971 0.397487 - 0.732171 1.26731 0.40029 - 0.259461 0.618947 0.311809 - 0.275394 0.696813 0.314905 - 0.395145 1.28413 0.33818 - 0.340277 1.28092 0.328057 - 0.270682 1.23181 0.315124 - 0.268148 1.27134 0.314737 - 0.179822 1.28487 0.298478 - 0.160368 1.22508 0.29477 - 0.0646709 1.22376 0.277121 - 0.0571771 1.18314 0.275657 - 0.0368605 1.18412 0.271913 --0.00887378 1.168 0.263447 - -0.0142023 1.22698 0.262585 - -0.100321 1.18128 0.246612 - -0.119525 1.22376 0.243158 - -0.179664 1.16196 0.231943 - -0.207095 1.20411 0.226971 - -0.268232 1.16534 0.215619 - -0.333273 1.27481 0.203848 - -0.358003 1.27944 0.199298 - -0.404071 1.27387 0.190792 - -0.453142 1.27506 0.181746 - -0.469802 1.28704 0.178699 - -0.495011 1.07216 0.173613 - -0.491794 1.02949 0.17412 - -0.48803 0.926226 0.174604 - -0.491054 0.893903 0.173981 - -0.491062 0.884757 0.17396 - -0.495199 0.815225 0.173056 - -0.490381 0.605039 0.173517 - -0.494564 0.51181 0.172556 - -0.39281 -0.406711 0.185268 - -0.341615 -0.398699 0.19528 - -0.301761 -0.397937 0.203063 - -0.284521 -0.406919 0.206411 - -0.203791 -0.409994 0.222167 - -0.176722 -0.406067 0.227461 - -0.15061 -0.400414 0.232571 - -0.147827 -0.403553 0.233107 - -0.205113 -0.620234 0.221481 - -0.516139 -1.87463 0.158197 - -0.494055 -2.15566 0.161936 - -0.465074 -2.15611 0.167594 - -0.389086 -2.2161 0.182308 - -0.379591 -2.21777 0.184158 - -0.192304 -2.29024 0.220579 - -0.151531 -2.26923 0.228583 - -0.0148782 -0.42594 0.25902 - 0.0285514 -0.351039 0.267652 - 0.0336401 -0.355487 0.268637 - 0.0349206 -0.353314 0.268891 - 0.0495155 -0.348116 0.271752 - 0.106076 -0.356561 0.282778 - 0.14772 -0.363957 0.290894 - 0.152179 -0.353149 0.291787 - 0.190068 -0.352342 0.299186 - 0.212767 -0.352374 0.303618 - 0.310018 -0.437062 0.322434 - 0.329527 -0.443326 0.32623 - 0.329606 -0.439459 0.326253 - 0.331484 -0.437955 0.326623 - 0.381997 -0.448335 0.336465 - 0.384511 -0.406262 0.337041 - 0.386938 -0.405223 0.337517 - 0.447685 -0.406478 0.349376 - 0.450904 -0.40576 0.350005 - 0.45859 -0.408934 0.3515 - 0.562273 -0.409927 0.371742 - 0.566436 -0.409108 0.372556 - 0.664586 -0.411017 0.391716 - 0.680025 -0.40399 0.394745 - 0.764594 -0.404646 0.411256 - 0.875697 -0.414237 0.432929 - 1.08171 -0.408649 0.473165 - 1.2432 -0.413156 0.504687 - 1.85749 -0.393887 0.624666 - 2.40711 -0.38789 0.731992 - 2.40875 -0.37715 0.732333 - 2.41099 -0.25723 0.733015 - 2.39941 -0.158978 0.730954 - 7.39903 0.832108 1.70915 - 3.55899 0.529688 0.958767 - 3.55431 0.561385 0.957917 - 2.6415 0.563604 0.779695 - 1.64674 0.44525 0.585226 - 0.940495 0.28249 0.447001 - 0.896785 0.291452 0.438485 - 1.25954 0.496919 0.509731 - 0.716673 0.360877 0.403459 - 0.433096 0.265261 0.347896 - 0.431947 0.280653 0.347703 - 0.562794 0.385674 0.373465 - 0.570863 0.474252 0.375221 - 0.567025 0.561934 0.37465 - 0.566727 0.566571 0.374601 - 0.569211 0.57401 0.375101 - 0.568724 0.665499 0.375193 - 0.568048 0.72628 0.375185 - 0.571407 0.750406 0.37589 - 0.584756 0.781639 0.37856 - 0.686613 0.976187 0.398844 - 0.673653 1.26913 0.39691 - 0.285157 0.635144 0.319764 - 0.257301 0.6162 0.314287 - 0.257002 0.622879 0.314242 - 0.435457 1.28043 0.350425 - 0.229995 1.28522 0.310319 - 0.207612 1.28729 0.305953 - 0.136332 1.1667 0.291789 - 0.0457646 1.16869 0.27411 - 0.032536 1.22328 0.271639 - 0.0220571 1.2236 0.269593 - -0.0093353 1.174 0.263363 - -0.025282 1.23588 0.260375 - -0.0297908 1.1928 0.259407 - -0.113827 1.21627 0.243047 - -0.16644 1.21539 0.232772 - -0.202793 1.20991 0.225663 - -0.207972 1.20904 0.22465 - -0.274047 1.16807 0.211666 - -0.294858 1.21136 0.20769 - -0.416767 1.27696 0.184021 - -0.489902 1.07431 0.169329 - -0.494897 1.00324 0.168209 - -0.491726 0.985858 0.168792 - -0.493752 0.872606 0.168166 - -0.494055 0.806237 0.167972 - -0.489896 0.740133 0.168649 - -0.485793 0.706746 0.169382 - -0.494418 0.662276 0.167607 - -0.494252 0.638516 0.167591 - -0.486041 0.605616 0.169127 - -0.491351 0.536379 0.16795 - -0.493485 0.524795 0.167509 - -0.396242 -0.400121 0.180496 - -0.389728 -0.39685 0.181843 - -0.386999 -0.400952 0.182397 - -0.364548 -0.404534 0.187011 - -0.343582 -0.40855 0.191319 - -0.329031 -0.401373 0.194329 - -0.321302 -0.398752 0.195925 - -0.313895 -0.407216 0.197433 - -0.279303 -0.403198 0.204562 - -0.275845 -0.405597 0.205269 - -0.247177 -0.39474 0.211192 - -0.230366 -0.401398 0.214639 - -0.224047 -0.410654 0.215921 - -0.51512 -2.08457 0.152585 - -0.445076 -2.1552 0.166859 - -0.40353 -2.19 0.175341 - -0.37133 -2.22927 0.181889 - -0.284888 -2.16254 0.19982 - -0.0544806 -0.49375 0.250657 - -0.167642 -2.22099 0.223836 - -0.101674 -2.23793 0.237381 - 0.00124404 -0.431889 0.262255 - 0.00518334 -0.439784 0.26305 - 0.0400118 -0.360639 0.270381 - 0.0415525 -0.36042 0.270698 - 0.0593182 -0.330867 0.274416 - 0.0731587 -0.338937 0.277249 - 0.0757965 -0.343422 0.277782 - 0.119229 -0.356988 0.286695 - 0.133485 -0.36213 0.28962 - 0.144641 -0.358456 0.291923 - 0.176481 -0.36963 0.298455 - 0.264464 -0.420075 0.316464 - 0.310124 -0.438669 0.325825 - 0.381449 -0.415069 0.340556 - 0.383218 -0.413329 0.340924 - 0.439928 -0.407852 0.352609 - 0.590566 -0.407899 0.383618 - 0.66455 -0.408023 0.398848 - 0.731352 -0.413582 0.412588 - 0.866361 -0.410893 0.440385 - 0.876091 -0.405955 0.442398 - 0.887597 -0.401679 0.444775 - 0.958514 -0.418146 0.45934 - 0.975577 -0.410103 0.462869 - 0.992694 -0.40687 0.466399 - 1.05362 -0.415277 0.478925 - 1.18834 -0.4078 0.506673 - 1.79216 -0.38933 0.631008 - 2.30144 -0.467283 0.735686 - 2.40467 -0.388357 0.757098 - 2.41343 -0.258061 0.759166 - 7.39909 0.767123 1.78758 - 3.56033 0.612497 0.997038 - 2.42882 0.542224 0.763969 - 2.42408 0.56392 0.763038 - 3.57062 0.880175 0.999703 - 1.58237 0.444124 0.589524 - 0.893255 0.295472 0.447364 - 1.01231 0.454134 0.472195 - 0.705493 0.392438 0.40891 - 0.45808 0.272769 0.357735 - 0.426393 0.256822 0.35118 - 0.575154 0.383983 0.382062 - 0.573507 0.38658 0.381728 - 0.571848 0.38917 0.381392 - 0.566914 0.389542 0.380377 - 0.552904 0.394635 0.377504 - 0.537136 0.455952 0.374383 - 0.536691 0.459652 0.374299 - 0.533936 0.517356 0.37385 - 0.526953 0.533508 0.372445 - 0.53678 0.619443 0.374644 - 0.534778 0.622614 0.374238 - 0.537857 0.654353 0.374937 - 0.551294 0.781052 0.377961 - 0.714032 1.10639 0.412126 - 0.719395 1.27729 0.413579 - 0.63827 1.23196 0.396786 - 0.310932 0.663025 0.328241 - 0.285555 0.736022 0.323166 - 0.282406 0.737326 0.32252 - 0.305803 0.861034 0.327589 - 0.443364 1.27174 0.356745 - 0.372979 1.27886 0.342271 - 0.318424 1.25111 0.330984 - 0.228819 0.976292 0.311977 - 0.23116 1.02408 0.312557 - 0.250915 1.17645 0.316935 - 0.256064 1.27766 0.318201 - 0.188528 1.2792 0.304302 - 0.182911 1.27908 0.303145 - 0.0620091 1.19881 0.278093 - 0.0550892 1.16617 0.276602 - -0.0047658 1.17199 0.264293 - -0.0626071 1.23378 0.252512 - -0.0801561 1.17475 0.248779 - -0.135385 1.1709 0.237402 - -0.166826 1.17802 0.230944 - -0.258241 1.19315 0.212157 - -0.345787 1.2796 0.194312 - -0.351769 1.28002 0.193081 - -0.418808 1.28457 0.179291 - -0.424293 1.28273 0.178158 - -0.491961 1.26531 0.164192 - -0.49043 1.16991 0.164313 - -0.492302 1.06852 0.16372 - -0.489269 1.03796 0.164282 - -0.493495 1.01258 0.163361 - -0.48855 0.980491 0.164313 - -0.4957 0.886093 0.162648 - -0.492551 0.654521 0.162824 - -0.490377 0.628474 0.163218 - -0.493479 0.615748 0.162554 - -0.494328 0.554706 0.162254 - -0.496037 0.551794 0.161896 - -0.326409 -0.40202 0.191319 - -0.291076 -0.401938 0.198987 - -0.289359 -0.403195 0.199357 - -0.252201 -0.403247 0.20742 - -0.241794 -0.401515 0.209682 - -0.225444 -0.400736 0.213232 - -0.202083 -0.406398 0.218291 - -0.195671 -0.401789 0.219691 - -0.182805 -0.405612 0.222476 - -0.178185 -0.404393 0.223481 - -0.175316 -0.402384 0.224108 - -0.165613 -0.403219 0.226211 - -0.520077 -1.74507 0.146541 - -0.514341 -1.81139 0.14765 - -0.519444 -1.99346 0.14617 - -0.512488 -2.0768 0.147509 - -0.380569 -2.22862 0.175827 - -0.0586102 -0.489341 0.249257 - -0.0906716 -2.19436 0.238809 - -0.0156418 -0.42294 0.258718 - -0.0120199 -0.420986 0.259508 --0.00842956 -0.420999 0.260287 - 0.0027408 -0.435841 0.26268 - 0.00684482 -0.446715 0.263549 - 0.152495 -2.3232 0.291317 - 0.0262512 -0.353187 0.267952 - 0.0315734 -0.34655 0.26912 - 0.0375469 -0.357877 0.270394 - 0.0445658 -0.352805 0.271927 - 0.0494081 -0.344901 0.272994 - 0.134643 -0.362422 0.291456 - 0.165481 -0.356949 0.298159 - 0.202397 -0.355486 0.306174 - 0.205291 -0.346589 0.30682 - 0.308026 -0.4579 0.328887 - 0.327131 -0.447201 0.333056 - 0.933495 -1.15717 0.463194 - 0.385432 -0.402757 0.345799 - 0.409469 -0.409064 0.351002 - 0.457483 -0.406857 0.361427 - 0.463931 -0.405247 0.362829 - 0.592963 -0.406881 0.390828 - 0.718075 -0.411547 0.41797 - 0.75003 -0.403465 0.424921 - 0.772606 -0.406648 0.429814 - 1.27402 -0.412817 0.538618 - 1.38105 -0.413393 0.561844 - 1.64515 -0.412819 0.619158 - 1.65164 -0.406594 0.62058 - 2.41497 -0.457795 0.786132 - 2.4235 -0.425799 0.788047 - 2.42528 -0.414935 0.788457 - 2.41457 -0.368756 0.786227 - 2.41127 -0.269388 0.785713 - 2.41838 -0.23733 0.787323 - 7.4155 0.104974 1.87248 - 7.40428 0.769444 1.87141 - 3.55713 0.466937 1.03589 - 3.55083 0.514664 1.03462 - 0.896351 0.283981 0.458082 - 1.90949 0.67763 0.678758 - 1.08539 0.419661 0.499386 - 0.723457 0.342251 0.420681 - 0.721102 0.345099 0.420175 - 0.427059 0.276586 0.356223 - 0.55608 0.369007 0.384412 - 0.556964 0.373152 0.384612 - 0.505109 0.45405 0.373524 - 0.504874 0.478434 0.373523 - 0.495963 0.491171 0.371615 - 0.507696 0.520458 0.374222 - 0.505056 0.585236 0.373781 - 0.508783 0.626998 0.374675 - 0.507457 0.722151 0.374583 - 0.547535 0.846031 0.383534 - 0.612213 0.990363 0.397865 - 0.733566 1.26744 0.424768 - 0.695117 1.27646 0.416442 - 0.322359 0.659896 0.334286 - 0.301548 0.660442 0.32977 - 0.253707 0.612538 0.31929 - 0.251092 0.613706 0.318725 - 0.406095 1.27391 0.353714 - 0.38798 1.27365 0.349783 - 0.383423 1.27827 0.348803 - 0.377968 1.28001 0.347623 - 0.327928 1.26991 0.336743 - 0.223195 0.975399 0.313411 - 0.249747 1.2798 0.319796 - 0.244287 1.28095 0.318614 - 0.228784 1.28915 0.315266 - 0.19916 1.28134 0.308821 - 0.0800833 1.17443 0.282761 - 0.0690701 1.2394 0.280504 - 0.0319784 1.23927 0.272454 --0.00023402 1.17296 0.265327 - -0.0261891 1.24088 0.259834 - -0.0307161 1.1988 0.258765 - -0.0758451 1.18204 0.248937 - -0.157142 1.2237 0.23138 - -0.231567 1.16502 0.215108 - -0.391505 1.27542 0.180624 - -0.489099 1.27585 0.159446 - -0.49046 0.676788 0.157924 - -0.489807 0.663627 0.158039 - -0.493095 0.573873 0.157142 - -0.35445 -0.411614 0.181497 - -0.329868 -0.410458 0.187099 - -0.302304 -0.403248 0.193392 - -0.288002 -0.401566 0.196653 - -0.276104 -0.402747 0.19936 - -0.247608 -0.403695 0.205849 - -0.234806 -0.405616 0.208761 - -0.232599 -0.405752 0.209264 - -0.229919 -0.405002 0.209876 - -0.223005 -0.396361 0.211468 - -0.216786 -0.405478 0.212866 - -0.197751 -0.406303 0.2172 - -0.172507 -0.400356 0.222962 - -0.149649 -0.413615 0.228141 - -0.203859 -0.616429 0.215378 - -0.512712 -1.83866 0.142522 - -0.524862 -1.91512 0.139598 - -0.434692 -2.15713 0.15964 - -0.416135 -2.15988 0.163861 - -0.391979 -2.18485 0.169312 - -0.360651 -2.2289 0.176357 - -0.300509 -2.21381 0.190087 - -0.273859 -2.15285 0.196282 - -0.0550182 -0.492754 0.249533 - 0.0262433 -0.411401 0.268209 - 0.0290839 -0.355843 0.26897 - 0.0399347 -0.356459 0.271441 - 0.0635692 -0.328636 0.276881 - 0.0825208 -0.338165 0.281178 - 0.095698 -0.350885 0.284153 - 0.101652 -0.348955 0.285514 - 0.137295 -0.366404 0.293596 - 0.195461 -0.3557 0.306867 - 0.325361 -0.446408 0.336269 - 0.339811 -0.461502 0.339529 - 0.355814 -0.474059 0.343148 - 0.719122 -0.84278 0.425144 - 0.720099 -0.836532 0.425379 - 0.375511 -0.422435 0.347741 - 0.426345 -0.405112 0.359355 - 0.451796 -0.410349 0.365141 - 0.546642 -0.409728 0.386746 - 0.549174 -0.407817 0.387326 - 0.616114 -0.407881 0.402573 - 0.697197 -0.409169 0.421039 - 0.767808 -0.405288 0.43713 - 0.802639 -0.405326 0.445064 - 0.882764 -0.406478 0.463312 - 1.12164 -0.409739 0.517715 - 2.40507 -0.479421 0.809902 - 7.40067 -0.0607999 1.94863 - 7.39428 0.104919 1.94751 - 7.39774 0.304011 1.94871 - 7.39318 0.403426 1.94787 - 3.55467 0.565359 1.07389 - 2.46877 0.542208 0.826507 - 1.03454 0.385327 0.499507 - 0.912342 0.382785 0.471668 - 0.710616 0.360877 0.425675 - 0.713442 0.366311 0.42633 - 0.711165 0.373218 0.425826 - 0.714979 0.387485 0.426724 - 0.704849 0.402638 0.424447 - 0.424981 0.260271 0.360409 - 0.421498 0.273952 0.359644 - 0.526133 0.410849 0.383758 - 0.480202 0.507436 0.373494 - 0.481353 0.531339 0.373805 - 0.481116 0.713293 0.374124 - 0.696425 1.18399 0.424131 - 0.706823 1.27532 0.426687 - 0.64456 1.25135 0.412456 - 0.341494 0.693016 0.34228 - 0.3241 0.672957 0.338278 - 0.285346 0.731931 0.329571 - 0.279106 0.734544 0.328155 - 0.392946 1.27471 0.355193 - 0.217453 0.937473 0.314529 - 0.259986 1.25279 0.324863 - 0.134763 1.17266 0.296177 - 0.0890065 1.16861 0.285746 - 0.0795866 1.17643 0.283617 - 0.0343721 1.17612 0.273317 - 0.00936075 1.17783 0.267624 - -0.0106827 1.176 0.263055 - -0.17066 1.1674 0.226598 - -0.212492 1.2042 0.217146 - -0.2125 1.17374 0.217082 - -0.217316 1.17184 0.215981 - -0.372581 1.27275 0.180822 - -0.409114 1.27591 0.172508 - -0.419954 1.27229 0.170031 - -0.444118 1.27231 0.164527 - -0.49256 1.17821 0.1533 - -0.490339 1.09193 0.153629 - -0.491702 0.947854 0.153023 - -0.493983 0.763667 0.152126 - -0.489767 0.708722 0.152974 - -0.495981 0.631817 0.151401 - -0.496397 0.548878 0.151136 - -0.492705 0.530602 0.151939 - -0.491151 0.519734 0.152271 - -0.297988 -0.408768 0.191158 - -0.288274 -0.406078 0.193484 - -0.25817 -0.397996 0.200692 - -0.225419 -0.405208 0.2085 - -0.20201 -0.401942 0.214099 - -0.19859 -0.403653 0.214912 - -0.19604 -0.402692 0.215524 - -0.191588 -0.411438 0.216569 - -0.148646 -0.399162 0.226852 - -0.51451 -1.70451 0.136771 - -0.462282 -2.15513 0.14832 - -0.350859 -2.23144 0.17478 - -0.330907 -2.2275 0.179555 - -0.059708 -0.494314 0.247902 - -0.0248995 -0.461729 0.256284 - 0.0162012 -0.460239 0.266105 - 0.164494 -2.24193 0.297866 - 0.0284715 -0.422192 0.269115 - 0.0404807 -0.353268 0.272125 - 0.0469693 -0.337017 0.273709 - 0.0537325 -0.333705 0.275331 - 0.0760666 -0.333566 0.280667 - 0.0900937 -0.3451 0.283994 - 0.0915571 -0.34465 0.284344 - 0.098578 -0.35184 0.286007 - 0.156939 -0.350405 0.299951 - 0.179068 -0.368013 0.305201 - 0.228491 -0.369233 0.317004 - 0.304419 -0.431641 0.335014 - 0.712965 -0.823607 0.431801 - 0.386866 -0.406997 0.354759 - 0.388589 -0.405214 0.355175 - 0.425284 -0.409082 0.363932 - 0.427016 -0.407127 0.36435 - 0.44018 -0.4085 0.367492 - 0.483204 -0.402398 0.377782 - 0.526292 -0.407053 0.388065 - 0.534294 -0.409371 0.389972 - 0.581776 -0.409446 0.401314 - 0.673 -0.404489 0.423116 - 0.693376 -0.399927 0.427993 - 1.07205 -0.40934 0.518432 - 1.15959 -0.412923 0.539336 - 1.63236 -0.396206 0.652304 - 2.35057 -0.536089 0.823584 - 7.40218 -0.293858 2.03081 - 7.4044 0.371707 2.03271 - 7.40535 0.538687 2.03328 - 3.55413 0.566735 1.11336 - 3.5352 0.727798 1.10917 - 0.914071 0.264187 0.482078 - 0.908236 0.284847 0.480727 - 2.04498 0.678028 0.75308 - 2.0022 0.683886 0.742874 - 0.682753 0.47664 0.427258 - 0.669413 0.480819 0.42408 - 0.604006 0.442685 0.408377 - 0.511142 0.400668 0.386107 - 0.508877 0.424942 0.385616 - 0.480811 0.439269 0.378941 - 0.466778 0.441982 0.375594 - 0.455399 0.442925 0.372878 - 0.45447 0.640548 0.373063 - 0.456277 0.718737 0.373655 - 0.693888 1.26896 0.431547 - 0.302003 0.659048 0.336679 - 0.293723 0.648729 0.33468 - 0.258921 0.622324 0.326312 - 0.356151 1.2755 0.350882 - 0.338564 1.27551 0.346681 - 0.313205 1.22359 0.340516 - 0.253451 1.28059 0.326359 - 0.10395 1.17514 0.29043 - 0.0938826 1.17513 0.288025 - 0.0839041 1.17602 0.285643 - 0.0586954 1.17386 0.279617 - 0.048182 1.16345 0.277084 - 0.0311764 1.24827 0.273196 - -0.115891 1.23022 0.238027 - -0.12681 1.18094 0.235318 - -0.141834 1.17927 0.231725 - -0.157225 1.22271 0.228138 - -0.201435 1.20103 0.217533 - -0.20653 1.20016 0.216314 - -0.211621 1.19927 0.215096 - -0.23712 1.16794 0.20894 - -0.332467 1.27674 0.186387 - -0.349463 1.27519 0.182324 - -0.489423 0.802828 0.147919 - -0.48868 0.778557 0.148047 - -0.485146 0.702974 0.148736 - -0.491224 0.692452 0.147262 - -0.495481 0.626505 0.14611 - -0.495103 0.524808 0.145991 - -0.390156 -0.402846 0.164918 - -0.357673 -0.409261 0.173026 - -0.25339 -0.402156 0.199113 - -0.207465 -0.400209 0.210599 - -0.205333 -0.4002 0.211132 - -0.196004 -0.398247 0.213468 - -0.179145 -0.401798 0.217676 - -0.155461 -0.401941 0.223597 - -0.152052 -0.403234 0.224446 - -0.15964 -0.455585 0.222441 - -0.190576 -0.574572 0.214462 - -0.506786 -2.14347 0.132171 - -0.481437 -2.15878 0.138477 - -0.414862 -2.15988 0.155119 - -0.396032 -2.1605 0.159826 - -0.265354 -2.16394 0.19249 - -0.177131 -2.22125 0.214429 --0.00969164 -0.415999 0.260012 - 0.00143091 -0.436841 0.26275 - 0.155125 -2.25565 0.297426 - 0.0270011 -0.37607 0.269268 - 0.0265408 -0.356011 0.269194 - 0.0406329 -0.358215 0.272713 - 0.0650652 -0.334152 0.278871 - 0.0704603 -0.337966 0.280212 - 0.0730782 -0.33626 0.28087 - 0.112324 -0.355284 0.290643 - 0.122571 -0.359927 0.293195 - 0.124093 -0.359327 0.293577 - 0.128912 -0.362758 0.294775 - 0.143047 -0.362124 0.29831 - 0.151212 -0.351712 0.300373 - 0.192031 -0.360115 0.310561 - 0.191587 -0.345287 0.31048 - 1.31925 -1.60118 0.58982 - 0.779664 -0.918376 0.456325 - 0.769957 -0.89916 0.453938 - 0.377186 -0.423621 0.356721 - 0.457213 -0.399938 0.376777 - 0.55201 -0.408774 0.400459 - 0.629642 -0.407336 0.419872 - 0.692002 -0.400411 0.435477 - 0.704753 -0.403495 0.438658 - 0.712425 -0.403612 0.440576 - 0.801217 -0.407077 0.462768 - 0.936011 -0.413075 0.496456 - 0.964451 -0.404968 0.503583 - 1.01021 -0.408065 0.515017 - 1.10689 -0.406741 0.539192 - 1.18447 -0.410966 0.558578 - 1.24411 -0.412761 0.573486 - 1.32246 -0.412275 0.593074 - 1.42402 -0.394918 0.618502 - 2.37037 -0.519659 0.854845 - 2.37445 -0.509354 0.855884 - 2.48369 -0.132845 0.883973 - 2.52395 -0.123565 0.894059 - 7.27774 -0.322516 2.08215 - 7.28475 -0.0929703 2.08438 - 7.28721 0.1696 2.08554 - 7.27812 0.79517 2.08456 - 3.5535 0.634003 1.15302 - 2.39869 0.552426 0.864135 - 3.55721 0.851861 1.1544 - 3.54607 0.899926 1.15171 - 0.902856 0.261775 0.489558 - 1.01131 0.31778 0.516789 - 2.09402 0.675317 0.788218 - 2.04375 0.689718 0.775679 - 1.97345 0.685911 0.758095 - 0.833369 0.34331 0.472353 - 0.707654 0.357651 0.440953 - 0.420258 0.259262 0.368897 - 0.658914 0.506661 0.429074 - 0.640399 0.497164 0.424426 - 0.495965 0.412076 0.38814 - 0.493906 0.43683 0.387676 - 0.458794 0.463664 0.378953 - 0.432686 0.477814 0.372455 - 0.433978 0.608892 0.373048 - 0.431855 0.640225 0.372582 - 0.437099 0.685119 0.373986 - 0.434487 0.694125 0.373351 - 0.434012 0.713533 0.373272 - 0.468976 0.832263 0.382258 - 0.500438 0.904817 0.390274 - 0.419223 0.834706 0.369825 - 0.27858 0.739181 0.334465 - 0.425159 1.27195 0.37221 - 0.373217 1.2781 0.359237 - 0.239255 0.96418 0.325097 - 0.185126 1.28118 0.312218 - 0.0249333 1.23445 0.272071 - 0.00808923 1.16084 0.267708 - -0.0272001 1.22488 0.259017 - -0.0363622 1.1707 0.256615 - -0.0640902 1.23778 0.249821 - -0.0693291 1.23753 0.248511 - -0.0961313 1.1727 0.241676 - -0.136209 1.17289 0.231657 - -0.167902 1.22332 0.223837 - -0.211558 1.19927 0.212873 - -0.221608 1.16795 0.210296 - -0.354963 1.27559 0.177177 - -0.433006 1.27898 0.157672 - -0.455251 1.27308 0.152099 - -0.464297 1.2814 0.149854 - -0.49204 1.25663 0.142867 - -0.491945 1.24053 0.142858 - -0.48756 1.1417 0.14375 - -0.486627 1.11266 0.143924 - -0.490832 0.830685 0.142291 - -0.486607 0.799419 0.143283 - -0.487625 0.7418 0.142909 - -0.487278 0.633775 0.142774 - -0.488024 0.617902 0.142554 - -0.492753 0.607536 0.141351 - -0.494531 0.543747 0.140775 - -0.401815 -0.401582 0.157762 - -0.400114 -0.403343 0.158202 - -0.398407 -0.405096 0.158644 - -0.384513 -0.400952 0.162277 - -0.348472 -0.402513 0.171675 - -0.325547 -0.402798 0.177654 - -0.320416 -0.407026 0.178984 - -0.256033 -0.399108 0.195794 - -0.230508 -0.398668 0.202453 - -0.225133 -0.405208 0.203842 - -0.171193 -0.402008 0.217919 - -0.521887 -1.65755 0.123845 - -0.514769 -1.79567 0.125417 - -0.521787 -1.85081 0.123472 - -0.514989 -2.02574 0.124884 - -0.320178 -2.22596 0.175286 - -0.0585675 -0.498515 0.247098 - -0.214094 -2.21292 0.202985 - -0.0118636 -0.418996 0.259445 - 0.0109286 -0.451463 0.265323 - 0.0264483 -0.359989 0.26956 - 0.0380383 -0.354479 0.272595 - 0.0435623 -0.360711 0.274023 - 0.0458487 -0.337017 0.274668 - 0.0532253 -0.329495 0.276608 - 0.0658729 -0.333811 0.279898 - 0.103968 -0.347437 0.289807 - 0.105433 -0.346918 0.290191 - 0.127789 -0.361828 0.295991 - 0.131929 -0.363349 0.297068 - 0.158017 -0.352344 0.303896 - 0.188853 -0.37862 0.311885 - 0.189691 -0.372437 0.312116 - 0.185101 -0.360193 0.310944 - 0.188134 -0.358416 0.311739 - 0.191152 -0.356612 0.31253 - 0.190189 -0.347908 0.312297 - 0.208707 -0.354903 0.317113 - 0.336509 -0.462292 0.350228 - 0.394589 -0.400081 0.365507 - 0.478322 -0.401154 0.387346 - 0.516929 -0.410041 0.397399 - 0.592032 -0.403669 0.417002 - 0.666152 -0.398946 0.436346 - 0.700795 -0.402534 0.445375 - 0.954487 -0.41219 0.511531 - 0.96428 -0.411237 0.514087 - 1.14634 -0.410649 0.561578 - 1.16272 -0.410561 0.565852 - 1.18097 -0.410966 0.57061 - 1.27994 -0.413002 0.596424 - 1.35812 -0.404434 0.616835 - 2.41711 -0.384266 0.893112 - 2.40992 -0.15117 0.89172 - 7.29204 0.00548329 2.16554 - 3.71133 0.424109 1.23238 - 3.55769 0.471886 1.1924 - 3.55594 0.570097 1.19215 - 3.55861 0.603535 1.19291 - 3.55926 0.669968 1.19322 - 3.55639 0.686061 1.19251 - 2.56551 0.555839 0.933766 - 2.13915 0.670517 0.822788 - 0.798415 0.321705 0.472337 - 0.78283 0.340418 0.46831 - 0.711239 0.356574 0.449669 - 0.707468 0.403738 0.448783 - 0.652854 0.531902 0.434801 - 0.589485 0.498685 0.418203 - 0.472182 0.419459 0.387441 - 0.469668 0.420987 0.386788 - 0.466597 0.448826 0.386045 - 0.454683 0.473462 0.382988 - 0.435122 0.482151 0.377903 - 0.406849 0.488632 0.370542 - 0.416614 0.614682 0.373349 - 0.414423 0.63463 0.372819 - 0.410905 0.665999 0.371966 - 0.410559 0.698259 0.371943 - 0.267115 0.631721 0.334388 - 0.257139 0.64611 0.331815 - 0.274992 0.742332 0.336671 - 0.401136 1.12715 0.370371 - 0.445006 1.26391 0.382097 - 0.402039 1.2796 0.370922 - 0.395726 1.2786 0.369273 - 0.377175 1.27636 0.364429 - 0.34717 1.27425 0.356598 - 0.227969 0.941114 0.324816 - 0.22185 0.968528 0.323277 - 0.221527 1.00463 0.323267 - 0.246179 1.28372 0.330274 - 0.156921 1.20453 0.306828 - 0.125113 1.19774 0.298517 - 0.122547 1.2212 0.297896 - 0.0469914 1.16345 0.278068 - -0.069949 1.24452 0.247732 - -0.156287 1.21377 0.225147 - -0.16653 1.21242 0.222472 - -0.217432 1.1738 0.209115 - -0.23836 1.17579 0.203659 - -0.319263 1.27279 0.182757 - -0.335355 1.26852 0.17855 - -0.356587 1.28329 0.173042 - -0.362001 1.28172 0.171627 - -0.382189 1.27042 0.166337 - -0.485125 1.27305 0.139492 - -0.489336 1.23588 0.138317 - -0.491575 1.19606 0.13765 - -0.491427 1.08704 0.137464 - -0.487706 0.996963 0.138248 - -0.486027 0.815665 0.138311 - -0.488285 0.71663 0.137518 - -0.490424 0.706567 0.136939 - -0.485756 0.674363 0.13809 - -0.491459 0.596259 0.136441 - -0.493872 0.558433 0.135733 - -0.496318 0.546694 0.135071 - -0.501243 0.52403 0.133739 - -0.391617 -0.405713 0.156086 - -0.389904 -0.407431 0.156549 - -0.326998 -0.408897 0.173669 - -0.299775 -0.401645 0.181095 - -0.2473 -0.404551 0.195373 - -0.226943 -0.400638 0.200922 - -0.221072 -0.406248 0.202509 - -0.200032 -0.402802 0.208243 - -0.177745 -0.403474 0.214309 - -0.507317 -2.15417 0.120968 - -0.359742 -2.23679 0.160967 - -0.134405 -2.30338 0.222168 - -0.0176667 -0.42494 0.257838 --0.00158639 -0.423891 0.262218 - 0.00633243 -0.443644 0.264332 - 0.0267989 -0.353855 0.27009 - 0.0523462 -0.335668 0.277082 - 0.058984 -0.332205 0.278896 - 0.0636098 -0.333178 0.280153 - 0.0830018 -0.338293 0.285421 - 0.102373 -0.349846 0.29067 - 0.109862 -0.352456 0.292703 - 0.166124 -0.355473 0.308012 - 0.18907 -0.361888 0.314244 - 0.194148 -0.352998 0.315645 - 1.30772 -1.71448 0.615945 - 1.31881 -1.6103 0.61918 - 1.319 -1.58238 0.619289 - 0.384032 -0.419455 0.367195 - 0.389642 -0.403718 0.368755 - 0.421287 -0.409757 0.377356 - 0.430287 -0.403865 0.379819 - 0.457846 -0.410581 0.387306 - 0.471416 -0.407731 0.391006 - 0.523107 -0.408835 0.405074 - 0.52887 -0.405753 0.40665 - 0.701733 -0.408642 0.453698 - 0.711083 -0.405518 0.45625 - 0.720436 -0.406504 0.458794 - 0.752914 -0.406932 0.467634 - 0.771827 -0.408099 0.47278 - 0.825536 -0.41266 0.48739 - 0.828137 -0.4093 0.488105 - 0.922998 -0.414961 0.513915 - 0.939747 -0.407224 0.51849 - 0.999445 -0.411552 0.534732 - 1.03163 -0.408421 0.543499 - 1.29039 -0.4048 0.613943 - 1.37744 -0.391134 0.637668 - 2.42021 -0.442361 0.92141 - 2.41174 -0.384569 0.919225 - 2.41597 -0.273605 0.920606 - 2.41346 -0.229033 0.920015 - 7.27753 -0.225291 2.24406 - 7.27821 -0.093403 2.24452 - 7.27523 0.335205 2.2446 - 7.29344 0.468553 2.24983 - 3.62954 0.432687 1.25241 - 3.54948 0.521379 1.2308 - 3.55157 0.687158 1.23172 - 1.72229 0.432712 0.733245 - 1.34398 0.364321 0.630126 - 0.748846 0.335038 0.468064 - 0.41151 0.268882 0.376102 - 0.700954 0.567292 0.455509 - 0.60095 0.542749 0.428236 - 0.477202 0.452501 0.394364 - 0.425767 0.495041 0.380451 - 0.425622 0.499235 0.38042 - 0.405523 0.497667 0.374946 - 0.393357 0.572879 0.37179 - 0.404164 0.645532 0.374883 - 0.401441 0.647405 0.374145 - 0.39548 0.689238 0.37261 - 0.447899 1.25997 0.388061 - 0.401331 1.28244 0.375432 - 0.226305 1.05045 0.327308 - 0.238441 1.27899 0.331085 - 0.221371 1.27736 0.326435 - 0.0331395 1.2041 0.275045 - 0.00223162 1.16291 0.266546 - -0.012505 1.202 0.262616 - -0.0176037 1.20898 0.261242 - -0.0419111 1.16558 0.254536 - -0.0647825 1.23978 0.248464 - -0.209683 1.22087 0.208981 - -0.221535 1.16893 0.205648 - -0.267148 1.16631 0.193226 - -0.317677 1.26794 0.179682 - -0.325876 1.27818 0.177472 - -0.396302 1.28039 0.158306 - -0.401688 1.27864 0.156836 - -0.417498 1.27229 0.152519 - -0.47317 1.27633 0.137373 - -0.490177 1.04971 0.132274 - -0.485403 0.762464 0.132978 - -0.486502 0.756961 0.132668 - -0.488623 0.753133 0.132083 - -0.490546 0.596259 0.131234 - -0.495546 0.591903 0.129864 - -0.496003 0.576987 0.129708 - -0.493876 0.526258 0.130182 - -0.396674 -0.40122 0.150305 - -0.371823 -0.402516 0.157352 - -0.370129 -0.404148 0.157829 - -0.362435 -0.406022 0.160007 - -0.322881 -0.404215 0.171231 - -0.316995 -0.400143 0.172909 - -0.301068 -0.40405 0.177418 - -0.293689 -0.401016 0.179518 - -0.272949 -0.403938 0.185394 - -0.259732 -0.402204 0.189147 - -0.236746 -0.394637 0.195683 - -0.229353 -0.401398 0.197766 - -0.225974 -0.403361 0.19872 - -0.219166 -0.407195 0.200643 - -0.163631 -0.402985 0.216405 - -0.510218 -2.01509 0.114743 - -0.51482 -2.14996 0.113157 - -0.487914 -2.15761 0.120773 - -0.412985 -2.16184 0.142019 - -0.389973 -2.19174 0.148484 - -0.329344 -2.23047 0.165601 - -0.0260422 -0.450736 0.255333 - -0.0220899 -0.443855 0.256468 - -0.0161704 -0.414967 0.258207 --0.00732534 -0.42898 0.260687 - 0.0222768 -0.415542 0.269112 - 0.035425 -0.354694 0.272968 - 0.0369133 -0.354479 0.273391 - 0.046143 -0.355019 0.276007 - 0.0545522 -0.335084 0.278434 - 0.0785432 -0.341466 0.285226 - 0.129902 -0.362422 0.299751 - 0.139316 -0.355027 0.302436 - 0.194002 -0.365247 0.317927 - 0.280068 -0.439863 0.342184 - 0.292174 -0.433403 0.345632 - 1.31122 -1.70929 0.632034 - 1.31825 -1.61486 0.634224 - 1.32679 -1.55526 0.63677 - 0.378414 -0.41516 0.370132 - 0.390464 -0.409728 0.373561 - 0.56069 -0.407946 0.42185 - 0.613005 -0.412711 0.436679 - 0.619709 -0.40915 0.438588 - 0.628043 -0.406543 0.440958 - 0.672276 -0.405388 0.453507 - 1.10005 -0.413784 0.574828 - 1.15603 -0.410882 0.590713 - 2.28927 -0.638839 0.911685 - 2.35099 -0.553711 0.92937 - 2.40693 -0.463967 0.945424 - 2.40885 -0.452995 0.945991 - 2.40798 -0.385174 0.945885 - 7.23329 -0.29039 2.31479 - 7.24108 -0.191923 2.31721 - 7.23744 0.038352 2.31665 - 7.23577 0.400295 2.31693 - 7.22747 0.796433 2.3154 - 3.54591 0.571932 1.27065 - 3.54346 0.588062 1.26999 - 2.36977 0.550689 0.936993 - 1.99133 0.68828 0.829933 - 1.87595 0.686851 0.797203 - 0.720501 0.323687 0.468702 - 0.724806 0.333511 0.469943 - 0.708302 0.349626 0.465295 - 0.699061 0.397651 0.462774 - 0.401259 0.250687 0.377996 - 0.414746 0.272021 0.381866 - 0.715331 0.486884 0.467574 - 0.720197 0.563849 0.469115 - 0.59171 0.570622 0.432683 - 0.417764 0.500928 0.383198 - 0.383961 0.522534 0.373655 - 0.377918 0.563526 0.372026 - 0.3744 0.631147 0.371168 - 0.37519 0.644808 0.371421 - 0.295623 0.635139 0.348831 - 0.304011 0.721837 0.351391 - 0.26493 0.670925 0.3402 - 0.274849 0.739181 0.343155 - 0.42465 1.28515 0.386782 - 0.418934 1.28617 0.385162 - 0.3868 1.27947 0.376033 - 0.258894 1.27525 0.339744 - 0.248176 1.27766 0.336709 - 0.242809 1.27882 0.335189 - 0.198419 1.27941 0.322599 - 0.126821 1.18322 0.30209 - 0.0742857 1.2207 0.287266 - 0.0326259 1.2061 0.275419 - -0.0231157 1.20894 0.259613 - -0.146464 1.17271 0.22455 - -0.192319 1.17719 0.211552 - -0.245981 1.19043 0.196359 - -0.307538 1.25086 0.179023 - -0.337107 1.27915 0.170695 - -0.394478 1.27657 0.154416 - -0.489564 1.08704 0.127051 - -0.489465 1.03851 0.126978 - -0.491821 1.02067 0.126273 - -0.491976 0.880436 0.125937 - -0.493903 0.80832 0.12524 - -0.495758 0.803583 0.124705 - -0.491883 0.724867 0.12564 - -0.495184 0.716392 0.124686 - -0.488896 0.663077 0.126359 - -0.488989 0.645428 0.126296 - -0.48684 0.552469 0.126712 - -0.485105 0.513242 0.127123 - -0.384122 -0.40625 0.149637 - -0.298889 -0.401645 0.174788 - -0.293257 -0.404721 0.176443 - -0.280945 -0.401588 0.180081 - -0.275945 -0.401549 0.181556 - -0.249418 -0.405183 0.189373 - -0.242565 -0.401329 0.191402 - -0.159863 -0.403418 0.215793 - -0.157495 -0.402218 0.216494 - -0.152176 -0.426535 0.218012 - -0.515837 -1.8412 0.107793 - -0.514086 -1.86562 0.108258 - -0.517496 -1.9103 0.107159 - -0.487495 -2.16054 0.115487 - -0.348458 -2.2344 0.156345 - -0.337078 -2.22208 0.159727 - -0.327353 -2.22058 0.162599 - -0.318056 -2.222 0.165338 - -0.212179 -2.19898 0.196617 - -0.0131009 -0.416996 0.259055 - -0.011352 -0.419999 0.259565 - 0.144559 -2.28929 0.301656 - 0.0307675 -0.358276 0.272118 - 0.0522376 -0.341557 0.278485 - 0.0551439 -0.333803 0.279359 - 0.0593285 -0.332863 0.280595 - 0.0657894 -0.335408 0.282496 - 0.071874 -0.335883 0.284289 - 0.0872318 -0.341777 0.288807 - 0.0993963 -0.350354 0.292378 - 0.134715 -0.363236 0.302769 - 0.137749 -0.36189 0.303667 - 0.163793 -0.354584 0.311364 - 0.180494 -0.364572 0.31627 - 0.189616 -0.3557 0.318979 - 0.213024 -0.353397 0.325888 - 0.307512 -0.429102 0.353601 - 0.333097 -0.455222 0.361094 - 0.38268 -0.41053 0.375813 - 0.400189 -0.410446 0.380978 - 0.401902 -0.408569 0.381487 - 0.429853 -0.413857 0.38972 - 0.513689 -0.404676 0.414469 - 0.52885 -0.405059 0.41894 - 0.649771 -0.405529 0.454607 - 0.75265 -0.409675 0.484945 - 0.804161 -0.41408 0.50013 - 0.876203 -0.406504 0.521396 - 0.897202 -0.406292 0.527591 - 0.946549 -0.412954 0.542133 - 0.984556 -0.40826 0.553354 - 1.11066 -0.413403 0.590541 - 2.41432 -0.466871 0.97497 - 2.41133 -0.420851 0.974184 - 6.92933 0.0368352 2.30782 - 6.92435 0.321015 2.30694 - 3.69647 0.426301 1.35503 - 3.54889 0.475059 1.3116 - 3.54686 0.491255 1.31104 - 3.54829 0.524456 1.31153 - 3.55105 0.641146 1.31258 - 3.56647 0.881464 1.31763 - 1.64045 0.446927 0.748606 - 2.17234 0.676474 0.905978 - 0.703746 0.317425 0.472036 - 0.699694 0.327166 0.470861 - 0.704698 0.361132 0.472408 - 0.583036 0.388351 0.436578 - 0.69597 0.557214 0.470242 - 0.692568 0.574945 0.469276 - 0.689025 0.614392 0.468313 - 0.526219 0.557283 0.420171 - 0.405938 0.502198 0.384576 - 0.388397 0.535362 0.379471 - 0.359532 0.534232 0.370955 - 0.355044 0.537594 0.369638 - 0.35825 0.568147 0.370647 - 0.361756 0.578951 0.371704 - 0.363375 0.598228 0.372222 - 0.361388 0.60077 0.371641 - 0.362173 0.638057 0.37195 - 0.361146 0.662013 0.371697 - 0.273505 0.720841 0.345968 - 0.422247 1.28326 0.391016 - 0.334176 1.26432 0.364998 - 0.220172 0.957775 0.33073 - 0.134616 1.172 0.305941 - 0.0896754 1.16915 0.292679 - 0.027577 1.22428 0.274476 - 0.0166127 1.19461 0.27118 - -0.0134291 1.225 0.262382 - -0.0185558 1.22498 0.26087 - -0.0749191 1.22327 0.244241 - -0.180502 1.16592 0.212977 - -0.202429 1.20991 0.206601 - -0.212548 1.20814 0.203613 - -0.259086 1.20489 0.189879 - -0.47973 1.28265 0.124957 - -0.491499 1.08123 0.121065 - -0.492528 1.0131 0.12062 - -0.489669 0.528435 0.120453 - -0.491213 0.525533 0.119991 - -0.389431 -0.3987 0.143848 - -0.382992 -0.409392 0.145797 - -0.342585 -0.40176 0.158186 - -0.276616 -0.403198 0.178382 - -0.254142 -0.401904 0.185266 - -0.247765 -0.398994 0.187225 - -0.217255 -0.40008 0.196565 - -0.195726 -0.408048 0.20314 - -0.163522 -0.402985 0.213012 - -0.150614 -0.410154 0.216949 - -0.522909 -1.67565 0.100306 - -0.520399 -1.89353 0.100619 - -0.515088 -1.93864 0.102151 - -0.0626205 -0.507244 0.24369 - -0.216355 -2.24776 0.192976 - -0.152458 -2.28321 0.212467 - -0.0117626 -0.416999 0.259451 - 0.00493906 -0.443644 0.264509 - 0.0347094 -0.357666 0.273805 - 0.0385227 -0.363163 0.274961 - 0.0446103 -0.326658 0.276901 - 0.0459724 -0.326396 0.277319 - 0.111448 -0.35417 0.297309 - 0.144944 -0.351528 0.307571 - 0.150965 -0.345171 0.309428 - 0.183643 -0.37246 0.319377 - 0.185195 -0.371563 0.319854 - 0.190481 -0.362656 0.321491 - 0.20239 -0.351531 0.325161 - 0.209278 -0.349229 0.327275 - 0.347752 -0.494043 0.369372 - 1.3258 -1.6789 0.666371 - 0.382711 -0.415868 0.38024 - 0.387529 -0.406508 0.381735 - 0.558749 -0.409644 0.434156 - 0.685629 -0.41212 0.473001 - 0.738832 -0.408076 0.4893 - 0.918569 -0.412295 0.544326 - 1.02635 -0.410542 0.577331 - 1.06645 -0.409604 0.589612 - 1.14602 -0.398403 0.614 - 1.14929 -0.387819 0.615025 - 1.15637 -0.384316 0.617199 - 2.40547 -0.46669 0.9995 - 2.40564 -0.297413 0.999906 - 2.47818 -0.1346 1.02246 - 6.65141 -0.11658 2.30033 - 6.64842 -0.0253336 2.2996 - 6.6535 0.0963255 2.30141 - 6.65431 0.157202 2.30179 - 6.64198 0.583388 2.29891 - 2.15604 0.652151 0.925463 - 0.75727 0.313731 0.496456 - 0.664956 0.331002 0.468225 - 0.649165 0.624132 0.464003 - 0.637944 0.635434 0.460591 - 0.614869 0.634699 0.453524 - 0.533982 0.608604 0.428702 - 0.403338 0.492379 0.388456 - 0.392376 0.51915 0.385155 - 0.390806 0.521771 0.38468 - 0.373165 0.551094 0.37934 - 0.366232 0.556328 0.377228 - 0.348205 0.604931 0.37181 - 0.334276 0.683664 0.367709 - 0.302121 0.732383 0.357965 - 0.299062 0.733813 0.357032 - 0.444247 1.24854 0.402564 - 0.435832 1.27534 0.400043 - 0.394748 1.2777 0.387468 - 0.304396 1.18021 0.359599 - 0.24669 1.28255 0.342143 - 0.241336 1.28372 0.340506 - 0.207593 1.28139 0.33017 - 0.114279 1.22378 0.301477 - 0.0986746 1.16818 0.296582 - 0.035531 1.18191 0.277276 - 0.0273997 1.23628 0.2749 - -0.0040811 1.16296 0.265108 - -0.0289208 1.20488 0.257589 - -0.0428946 1.16258 0.253222 - -0.22045 1.16598 0.198862 - -0.345408 1.27133 0.160821 - -0.382646 1.28095 0.149439 - -0.405425 1.27877 0.142459 - -0.411942 1.28077 0.140468 - -0.471691 1.28008 0.122172 - -0.494366 1.2591 0.115185 - -0.489005 0.906172 0.116088 - -0.487088 0.875216 0.11661 - -0.485502 0.863497 0.117071 - -0.493523 0.827188 0.114539 - -0.491452 0.713936 0.114937 - -0.491238 0.590377 0.114744 - -0.338542 -0.404761 0.155553 - -0.264153 -0.399622 0.179223 - -0.263926 -0.406946 0.17928 - -0.248678 -0.393443 0.184158 - -0.242398 -0.402186 0.186136 - -0.227133 -0.398786 0.190998 - -0.166427 -0.40066 0.210302 - -0.151995 -0.420225 0.21485 - -0.514898 -1.67892 0.0967909 - -0.51647 -2.01861 0.0955782 - -0.502914 -2.15514 0.0996031 - -0.317916 -2.22991 0.158283 - -0.226243 -2.25575 0.187384 - -0.152612 -2.2872 0.210736 - -0.0229685 -0.432859 0.25586 - -0.0138987 -0.408996 0.258794 - 0.00828816 -0.446469 0.265772 - 0.0101444 -0.446369 0.266362 - 0.012498 -0.455247 0.267092 - 0.166454 -2.22619 0.31234 - 0.0325136 -0.356885 0.273665 - 0.0584526 -0.334815 0.281961 - 0.0695769 -0.338198 0.285491 - 0.0709822 -0.337819 0.285939 - 0.0751882 -0.336643 0.287279 - 0.0957991 -0.348955 0.293809 - 0.104288 -0.350167 0.296506 - 0.126607 -0.360568 0.303582 - 0.153582 -0.356694 0.31217 - 0.162547 -0.348551 0.315038 - 0.197323 -0.36585 0.326062 - 0.199325 -0.35517 0.326721 - 0.205348 -0.358275 0.32863 - 0.338608 -0.483701 0.370749 - 0.397716 -0.407881 0.389707 - 0.432734 -0.409114 0.400841 - 0.445512 -0.402678 0.404919 - 0.469928 -0.409319 0.41267 - 0.473856 -0.408982 0.41392 - 0.478735 -0.40575 0.415478 - 0.529024 -0.412212 0.431459 - 0.822979 -0.408034 0.524957 - 1.1026 -0.413403 0.613878 - 2.40629 -0.678073 1.02795 - 2.40936 -0.608145 1.02907 - 2.41114 -0.57351 1.02971 - 2.41429 -0.504603 1.03086 - 2.41478 -0.458667 1.03111 - 2.41435 -0.367356 1.03116 - 2.40655 -0.298581 1.02883 - 2.40798 -0.276309 1.02933 - 6.39212 -0.0244426 2.29697 - 6.38992 0.063515 2.29646 - 6.39292 0.122216 2.29754 - 6.39337 0.357209 2.29818 - 3.68308 0.427616 1.43634 - 3.55079 0.662232 1.39476 - 2.45248 0.540104 1.04519 - 1.65756 0.446564 0.792182 - 2.16003 0.688139 0.952494 - 0.648428 0.324229 0.47098 - 0.603401 0.355439 0.456725 - 0.453642 0.303454 0.408986 - 0.638079 0.515649 0.46809 - 0.63642 0.567677 0.467672 - 0.643109 0.61011 0.469888 - 0.630959 0.625665 0.466057 - 0.638095 0.638164 0.468352 - 0.582698 0.659818 0.450779 - 0.56777 0.666203 0.446045 - 0.541664 0.653222 0.437715 - 0.377899 0.511901 0.385335 - 0.333801 0.67168 0.371645 - 0.294053 0.633739 0.358924 - 0.304052 0.731849 0.36231 - 0.301005 0.733295 0.361344 - 0.297952 0.734727 0.360376 - 0.263499 0.693705 0.349332 - 0.264973 0.706055 0.349827 - 0.398533 1.27677 0.393502 - 0.350616 1.27289 0.378254 - 0.226391 1.05131 0.338281 - 0.184437 1.28127 0.325421 - 0.149821 1.1877 0.314215 - 0.124859 1.18917 0.306279 - -0.0978796 1.18068 0.235421 - -0.116226 1.22225 0.229673 - -0.175189 1.16469 0.2108 - -0.185013 1.16416 0.207674 - -0.346513 1.27809 0.15655 - -0.387744 1.28116 0.143444 - -0.398381 1.27769 0.140053 - -0.426999 1.2752 0.130946 - -0.473287 1.28757 0.116251 - -0.495212 1.24855 0.109196 - -0.494597 1.21638 0.109324 - -0.496386 1.13608 0.108586 - -0.49443 1.11836 0.109171 - -0.490104 1.08305 0.110473 - -0.490716 1.02516 0.110157 - -0.492014 1.01669 0.109726 - -0.488626 0.936443 0.110635 - -0.490691 0.902242 0.109907 - -0.491588 0.885656 0.109587 - -0.488629 0.871308 0.110498 - -0.49267 0.780958 0.109023 - -0.493434 0.705471 0.108622 - -0.49235 0.660315 0.108871 - -0.395441 -0.403343 0.133186 - -0.39001 -0.41175 0.134956 - -0.345163 -0.39948 0.149746 - -0.338486 -0.405525 0.151931 - -0.322111 -0.399048 0.157336 - -0.317603 -0.400313 0.158817 - -0.314271 -0.403097 0.159908 - -0.285636 -0.403195 0.169335 - -0.272332 -0.405597 0.17371 - -0.26092 -0.402751 0.177473 - -0.209619 -0.402875 0.194361 - -0.168803 -0.407152 0.207789 - -0.150192 -0.42086 0.213887 - -0.167708 -0.488504 0.207978 - -0.514776 -1.76327 0.0910366 - -0.51687 -2.02538 0.0897954 - -0.481237 -2.14787 0.101268 - -0.384477 -2.17895 0.133057 - -0.236523 -2.26768 0.181577 - -0.225151 -2.24779 0.185363 - -0.20651 -2.24967 0.191496 - -0.169945 -2.26388 0.203503 - -0.16056 -2.26458 0.206591 - -0.0418356 -0.471011 0.249453 - -0.0324295 -0.435512 0.252624 --0.00381174 -0.422892 0.262072 - 0.156891 -2.23496 0.311161 - 0.165432 -2.22519 0.313994 - 0.0915784 -0.348026 0.293633 - 0.0959324 -0.351807 0.295058 - 0.101747 -0.349754 0.296977 - 0.105277 -0.350572 0.298137 - 0.130135 -0.36733 0.306286 - 0.130562 -0.363898 0.306433 - 0.134689 -0.365327 0.307789 - 0.145214 -0.360411 0.311264 - 0.154119 -0.35593 0.314205 - 0.195618 -0.372064 0.327833 - 0.213195 -0.355695 0.333654 - 0.212383 -0.347821 0.333403 - 0.281168 -0.421545 0.355892 - 0.285176 -0.423404 0.357208 - 1.31593 -1.63461 0.693988 - 1.31444 -1.60425 0.693562 - 1.32617 -1.56255 0.697513 - 0.376885 -0.416953 0.387413 - 0.41179 -0.409082 0.39892 - 0.423931 -0.409848 0.402916 - 0.433292 -0.407727 0.406002 - 0.439771 -0.402834 0.408145 - 0.577498 -0.410741 0.453469 - 0.584149 -0.403651 0.455674 - 0.61742 -0.409964 0.466613 - 0.727957 -0.413976 0.502995 - 0.816438 -0.411004 0.53213 - 0.829303 -0.407967 0.536371 - 2.40127 -0.714755 1.05323 - 2.39962 -0.702327 1.05271 - 2.40259 -0.679363 1.05374 - 2.41345 -0.634881 1.05741 - 2.40919 -0.379199 1.05654 - 2.41462 -0.345923 1.0584 - 2.40574 -0.22092 1.05574 - 6.16883 0.574204 2.29625 - 3.57442 0.433142 1.44186 - 1.96349 0.811198 0.912322 - 0.566028 0.335211 0.451264 - 0.400073 0.254218 0.39646 - 0.610498 0.415095 0.466072 - 0.611819 0.424061 0.466526 - 0.618101 0.444938 0.468638 - 0.61296 0.458186 0.466973 - 0.61493 0.472591 0.467652 - 0.607552 0.516179 0.465315 - 0.607411 0.574105 0.46539 - 0.607898 0.660947 0.465734 - 0.599463 0.675156 0.462987 - 0.361893 0.544755 0.384502 - 0.356045 0.572282 0.382635 - 0.354649 0.586502 0.382206 - 0.343848 0.59149 0.37866 - 0.277604 0.622651 0.356918 - 0.441861 1.26932 0.412354 - 0.433612 1.28003 0.409661 - 0.313857 1.20663 0.370082 - 0.231958 0.951467 0.342583 - 0.224982 0.992673 0.340373 - 0.126893 1.17166 0.308458 - 0.11603 1.20828 0.304959 - 0.103559 1.18456 0.300804 - 0.0672052 1.23405 0.28894 - 0.0436859 1.17243 0.281068 - 0.0340454 1.17492 0.277899 - -0.0295625 1.19488 0.257001 - -0.0654544 1.22279 0.245244 - -0.0784462 1.18204 0.240881 - -0.110532 1.21374 0.230385 - -0.147091 1.17768 0.218274 - -0.157238 1.22171 0.215026 - -0.234251 1.16206 0.189547 - -0.330176 1.28352 0.158223 - -0.491604 1.16833 0.104838 - -0.491833 1.06508 0.104545 - -0.487185 0.907048 0.105742 - -0.490329 0.786518 0.104453 - -0.491443 0.685111 0.103873 - -0.492576 0.65037 0.103427 - -0.493508 0.645801 0.103111 - -0.493094 0.559963 0.103066 - -0.344009 -0.402513 0.146337 - -0.271314 -0.404768 0.171095 - -0.255456 -0.406135 0.176494 - -0.213105 -0.401937 0.190929 - -0.191482 -0.399905 0.198299 - -0.187293 -0.404156 0.199717 - -0.173337 -0.404046 0.204471 - -0.294369 -2.20291 0.159443 - -0.263647 -2.25942 0.169788 - -0.178897 -2.26014 0.198656 - -0.0335125 -0.452493 0.251998 - 0.0248599 -0.351695 0.272095 - 0.0263121 -0.351515 0.27259 - 0.0543821 -0.342613 0.28217 - 0.0572092 -0.341976 0.283135 - 0.0642531 -0.340269 0.285538 - 0.0822761 -0.345544 0.291666 - 0.092253 -0.347543 0.29506 - 0.140896 -0.360939 0.311602 - 0.152069 -0.349792 0.315431 - 0.153512 -0.349026 0.315924 - 0.160576 -0.348551 0.318331 - 0.16986 -0.35578 0.321479 - 0.177576 -0.355828 0.324107 - 0.189522 -0.370503 0.328145 - 0.198598 -0.368304 0.331241 - 0.203644 -0.36619 0.332965 - 0.216134 -0.358797 0.337235 - 0.244329 -0.38808 0.346777 - 0.273495 -0.420175 0.356644 - 0.355634 -0.484804 0.384488 - 1.3267 -1.6835 0.712734 - 1.32391 -1.63607 0.711885 - 0.430164 -0.403064 0.410048 - 0.436868 -0.405559 0.412326 - 0.457605 -0.405835 0.419389 - 0.484143 -0.402618 0.428436 - 0.508232 -0.407053 0.436632 - 0.554376 -0.40386 0.452357 - 0.574381 -0.406382 0.459166 - 0.586382 -0.410742 0.463245 - 0.641877 -0.411087 0.482148 - 0.693212 -0.413 0.499631 - 0.899295 -0.408394 0.56984 - 1.1017 -0.387467 0.638832 - 2.41204 -0.589534 1.08475 - 2.41172 -0.554256 1.08472 - 2.40054 -0.447722 1.08114 - 2.41117 -0.222216 1.08523 - 5.94719 -0.160313 2.28986 - 5.94108 0.279241 2.28871 - 5.93847 0.499488 2.28829 - 5.94454 0.638462 2.29065 - 3.54761 0.464739 1.4738 - 3.55244 0.599534 1.47573 - 3.55275 0.855511 1.47637 - 3.54921 0.889281 1.47524 - 3.54181 0.904761 1.47275 - 2.19212 0.670113 1.0125 - 2.15099 0.690161 0.998535 - 2.07923 0.688396 0.974087 - 2.03936 0.685681 0.960501 - 1.86312 0.69412 0.900484 - 0.399905 0.245116 0.40111 - 0.393162 0.261255 0.398847 - 0.586066 0.491458 0.465044 - 0.59176 0.509681 0.467022 - 0.590384 0.513094 0.466561 - 0.593231 0.548599 0.467605 - 0.591527 0.556802 0.467042 - 0.585378 0.645237 0.465134 - 0.585933 0.680618 0.465398 - 0.584076 0.70273 0.464812 - 0.576559 0.712444 0.462272 - 0.444755 0.644051 0.41723 - 0.366847 0.554468 0.390503 - 0.349581 0.544161 0.3846 - 0.34638 0.559877 0.383543 - 0.33533 0.603084 0.37987 - 0.293877 0.731985 0.366022 - 0.407623 1.27956 0.405925 - 0.360335 1.2781 0.389814 - 0.233105 0.944546 0.34577 - 0.116209 1.21822 0.306529 - 0.101552 1.17263 0.30144 - 0.0911451 1.16569 0.29788 - 0.075955 1.22328 0.292828 - 0.0575787 1.17154 0.286459 --0.00537433 1.17896 0.26503 - -0.103578 1.18726 0.231596 - -0.116232 1.22026 0.227355 - -0.155195 1.20484 0.21405 - -0.327618 1.27578 0.155467 - -0.344647 1.27616 0.149667 - -0.416632 1.28558 0.125166 - -0.427234 1.28182 0.121547 - -0.478626 1.27491 0.104026 - -0.483886 1.27276 0.10223 - -0.487744 1.26686 0.100903 - -0.491335 1.05475 0.0992315 - -0.486078 0.987271 0.10088 - -0.49015 0.985086 0.099488 - -0.492712 0.856952 0.0983445 - -0.489199 0.736125 0.099286 - -0.490169 0.593428 0.0986542 - -0.394541 -0.400877 0.124648 - -0.392887 -0.402635 0.125227 - -0.385252 -0.404996 0.127913 - -0.375031 -0.404311 0.131516 - -0.338042 -0.39271 0.144575 - -0.337608 -0.406289 0.1447 - -0.297788 -0.400335 0.158744 - -0.278492 -0.401588 0.165541 - -0.248166 -0.402397 0.176227 - -0.237198 -0.407038 0.180081 - -0.160102 -0.405286 0.207253 - -0.151726 -0.408576 0.210198 - -0.52233 -1.66664 0.0769322 - -0.415115 -2.15411 0.11368 - -0.344535 -2.23342 0.138384 - -0.326415 -2.23838 0.144759 - -0.317199 -2.23981 0.148003 - -0.187196 -2.24938 0.193795 - -0.159409 -2.25161 0.203582 - -0.0426797 -0.475002 0.248484 - -0.0407246 -0.475132 0.249173 - -0.018489 -0.411968 0.257143 --0.00457516 -0.42789 0.262012 - 0.170678 -2.20145 0.320009 - 0.0258567 -0.431971 0.272727 - 0.0275452 -0.396596 0.273397 - 0.0276699 -0.355299 0.273529 - 0.0305923 -0.354903 0.274559 - 0.0797103 -0.333597 0.291913 - 0.0879943 -0.336117 0.294827 - 0.0928891 -0.347053 0.296529 - 0.0957408 -0.346053 0.297536 - 0.108131 -0.35417 0.301885 - 0.1306 -0.364158 0.309782 - 0.148363 -0.347861 0.316076 - 0.279881 -0.427743 0.362252 - 0.336917 -0.492487 0.382214 - 1.31655 -1.81756 0.724619 - 0.332157 -0.448106 0.380631 - 0.410074 -0.411107 0.408167 - 0.514451 -0.409961 0.444951 - 0.543118 -0.405117 0.455063 - 0.578254 -0.406933 0.467441 - 0.612967 -0.41049 0.479666 - 0.6326 -0.407002 0.486592 - 0.66132 -0.408362 0.49671 - 0.666278 -0.407202 0.49846 - 0.669593 -0.405029 0.499632 - 0.69855 -0.413582 0.509818 - 0.70439 -0.412666 0.511878 - 0.731998 -0.406475 0.52162 - 2.40829 -0.746396 1.11161 - 2.39842 -0.683235 1.10827 - 2.40545 -0.625626 1.11087 - 2.40375 -0.589758 1.11035 - 2.40845 -0.543901 1.1121 - 2.40976 -0.485893 1.11268 - 2.41181 -0.451526 1.11348 - 2.40573 -0.301735 1.11165 - 2.40547 -0.267715 1.11163 - 2.39581 -0.17679 1.10842 - 2.4473 -0.134858 1.12666 - 2.5053 -0.126353 1.14711 - 5.74647 -0.235518 2.28904 - 5.73713 -0.128619 2.28598 - 5.73734 0.244033 2.28684 - 3.54708 0.702709 1.51599 - 3.51615 0.730464 1.50515 - 2.40009 0.557764 1.11149 - 3.53845 0.85529 1.51327 - 1.64265 0.463887 0.844373 - 1.65058 0.482629 0.847208 - 2.14722 0.691606 1.02266 - 1.87671 0.682264 0.927315 - 1.87743 0.822366 0.927869 - 0.669245 0.327047 0.501062 - 0.611886 0.33156 0.480859 - 0.56104 0.427757 0.463145 - 0.560892 0.460229 0.463161 - 0.57415 0.519677 0.46796 - 0.569846 0.525102 0.466455 - 0.567531 0.561201 0.465715 - 0.563279 0.592293 0.464283 - 0.560834 0.594959 0.463427 - 0.560594 0.605191 0.463364 - 0.56759 0.628821 0.465879 - 0.568534 0.681449 0.466324 - 0.567339 0.710629 0.465964 - 0.565745 0.721311 0.465425 - 0.336622 0.57392 0.384372 - 0.327696 0.587006 0.381254 - 0.332612 0.607254 0.383029 - 0.322382 0.619466 0.37945 - 0.274873 0.637015 0.362746 - 0.302938 0.84546 0.373077 - 0.417754 1.28033 0.41446 - 0.365767 1.28304 0.396146 - 0.20946 1.28823 0.341075 - 0.203323 1.28434 0.338904 - 0.143892 1.16593 0.317711 - 0.0907679 1.17067 0.299 - 0.0469198 1.16617 0.283539 - 0.0335915 1.1939 0.278901 - 0.0301405 1.23508 0.277772 - -0.0395665 1.1677 0.253065 - -0.0658796 1.2208 0.243905 - -0.130476 1.15952 0.221012 - -0.135246 1.15897 0.219329 - -0.206907 1.21199 0.194189 - -0.214916 1.16888 0.191275 - -0.259887 1.16844 0.175427 - -0.354121 1.2721 0.142439 - -0.359352 1.27052 0.140593 - -0.405637 1.27221 0.124286 - -0.479418 1.28051 0.0983037 - -0.489758 1.15604 0.0943959 - -0.493452 0.953213 0.0926641 - -0.492252 0.931177 0.0930403 - -0.49062 0.918441 0.0935884 - -0.495412 0.855597 0.0917662 - -0.488619 0.795463 0.0940326 - -0.491527 0.721304 0.0928505 - -0.488889 0.672687 0.0936773 - -0.3424 -0.402513 0.139188 - -0.280655 -0.398308 0.161675 - -0.242931 -0.401985 0.175401 - -0.22668 -0.413102 0.181293 - -0.224984 -0.414085 0.181909 - -0.223284 -0.415061 0.182526 - -0.192224 -0.398177 0.193869 - -0.183247 -0.400394 0.197132 - -0.18008 -0.39752 0.198292 - -0.176813 -0.399046 0.199478 - -0.177192 -0.40975 0.199317 - -0.165976 -0.406007 0.203408 - -0.15105 -0.401354 0.208852 - -0.513368 -1.74564 0.0740876 - -0.447832 -2.18551 0.0970099 - -0.425055 -2.16399 0.105348 - -0.352529 -2.22988 0.131611 - -0.314569 -2.22596 0.145439 - -0.294297 -2.21282 0.152847 - -0.285221 -2.2141 0.156148 - -0.184927 -2.22347 0.192641 - -0.0086548 -0.417959 0.260656 - 0.0101646 -0.448258 0.267443 - 0.0244876 -0.423013 0.272711 - 0.0663541 -0.33626 0.288137 - 0.0766471 -0.341601 0.291873 - 0.0889429 -0.34183 0.296349 - 0.101851 -0.347744 0.301036 - 0.132273 -0.36189 0.312081 - 0.152753 -0.351704 0.319558 - 0.174272 -0.361072 0.327373 - 0.186432 -0.361729 0.331798 - 0.325437 -0.496473 0.382117 - 1.32136 -1.64591 0.742242 - 0.393468 -0.414592 0.407058 - 0.44971 -0.402674 0.427558 - 0.501937 -0.409453 0.446558 - 0.508306 -0.407008 0.448881 - 0.514534 -0.408101 0.451146 - 0.523984 -0.407817 0.454587 - 0.534867 -0.412234 0.45854 - 0.53655 -0.409681 0.459158 - 0.650993 -0.412076 0.500816 - 0.798704 -0.4118 0.554592 - 0.944564 -0.411325 0.607694 - 0.950273 -0.3931 0.609811 - 0.957857 -0.385877 0.612587 - 2.40367 -0.65142 1.13838 - 2.40972 -0.558062 1.14078 - 2.4067 -0.49881 1.1398 - 2.4087 -0.417986 1.1407 - 2.40989 -0.383612 1.14121 - 2.40944 -0.246462 1.14134 - 2.40314 -0.16674 1.13921 - 5.55644 -0.176816 2.28717 - 5.56263 0.21158 2.29025 - 5.56357 0.237555 2.29064 - 5.55315 0.470665 2.28735 - 3.61396 0.425753 1.58128 - 3.54744 0.586299 1.55741 - 2.61607 0.559016 1.21828 - 1.99651 0.686889 0.992996 - 2.05904 0.827041 1.01606 - 1.87387 0.793468 0.948577 - 0.38984 0.327776 0.407317 - 0.543973 0.545632 0.463894 - 0.546862 0.583088 0.465025 - 0.541627 0.592985 0.46314 - 0.552457 0.695525 0.467302 - 0.483222 0.717424 0.442143 - 0.472356 0.714737 0.438181 - 0.459939 0.70946 0.43365 - 0.44026 0.705803 0.426477 - 0.356385 0.615085 0.39575 - 0.338318 0.59651 0.389133 - 0.317905 0.614268 0.381739 - 0.315955 0.636103 0.381075 - 0.30943 0.6433 0.378715 - 0.305909 0.643033 0.377433 - 0.286462 0.71323 0.370502 - 0.259032 0.696472 0.360481 - 0.403662 1.27956 0.414375 - 0.334325 1.2592 0.389089 - 0.222156 0.978979 0.347657 - 0.253398 1.2179 0.35954 - 0.133683 1.17033 0.315856 - 0.0938179 1.16022 0.301321 - 0.0633597 1.20811 0.290334 - -0.0263356 1.25094 0.257772 - -0.0834922 1.17475 0.236801 - -0.157703 1.22767 0.209897 - -0.190751 1.17422 0.197752 - -0.21888 1.165 0.187492 - -0.234113 1.16696 0.18195 - -0.430033 1.27896 0.110863 - -0.492921 0.879511 0.0871187 - -0.493953 0.783785 0.0865393 - -0.486157 0.641075 0.0890737 - -0.492964 0.60557 0.0865198 - -0.493018 0.595027 0.0864777 - -0.488079 0.583716 0.0882517 - -0.490466 0.581512 0.087378 - -0.496146 0.568133 0.085282 - -0.493103 0.535681 0.0863206 - -0.300282 -0.398484 0.151142 - -0.263646 -0.406628 0.164896 - -0.25486 -0.396038 0.168221 - -0.229985 -0.399404 0.177565 - -0.211658 -0.401052 0.18445 - -0.17897 -0.400118 0.19674 - -0.517289 -1.73757 0.0667086 - -0.517569 -1.79392 0.0664829 - -0.513987 -2.00178 0.0673849 - -0.50306 -2.1451 0.0711865 - -0.453484 -2.22073 0.0896605 - -0.221579 -2.2269 0.17682 - -0.033756 -0.435512 0.25125 - -0.0319769 -0.435598 0.251918 - -0.0246499 -0.426861 0.254691 --0.00902336 -0.421959 0.260576 - 0.00047687 -0.447715 0.264092 - 0.00383786 -0.440565 0.265371 - 0.0271917 -0.388454 0.274261 - 0.0324822 -0.355469 0.27632 - 0.0391215 -0.350341 0.278826 - 0.0490604 -0.340283 0.282584 - 0.0825716 -0.338456 0.295185 - 0.129799 -0.366923 0.312876 - 1.3256 -1.79583 0.759324 - 0.332906 -0.453524 0.389039 - 1.29897 -1.68351 0.749554 - 1.32036 -1.60847 0.757754 - 0.384913 -0.43735 0.408623 - 0.435158 -0.406062 0.427577 - 0.454055 -0.408363 0.434675 - 0.459562 -0.405856 0.436751 - 0.632568 -0.410577 0.501774 - 0.637465 -0.409584 0.503617 - 0.695711 -0.411236 0.525508 - 0.733909 -0.406648 0.539876 - 0.806143 -0.408034 0.567026 - 0.914585 -0.41028 0.607784 - 0.994667 -0.391513 0.637927 - 1.00066 -0.388491 0.640186 - 2.34411 -0.768275 1.14438 - 2.34543 -0.7567 1.1449 - 2.40477 -0.642359 1.16745 - 2.40809 -0.619317 1.16875 - 2.40924 -0.477944 1.16948 - 2.40789 -0.338792 1.16927 - 2.40721 -0.235841 1.16923 - 2.39666 -0.18955 1.16537 - 2.40249 -0.156056 1.16763 - 2.51731 -0.127959 1.21085 - 5.37523 0.331187 2.28612 - 3.60889 0.426849 1.62236 - 3.55967 0.437927 1.60388 - 3.5445 0.503461 1.59832 - 3.04964 0.638917 1.41259 - 2.39889 0.550136 1.16779 - 1.6785 0.444123 0.896764 - 2.08703 0.808238 1.05111 - 2.0837 0.81803 1.04988 - 2.03048 0.818971 1.02987 - 0.579546 0.334772 0.483435 - 0.373244 0.282829 0.405776 - 0.366173 0.293589 0.403141 - 0.358317 0.298255 0.400198 - 0.355816 0.309965 0.399282 - 0.351608 0.309212 0.397699 - 0.346644 0.318955 0.395854 - 0.345639 0.32955 0.395499 - 0.449769 0.476121 0.434954 - 0.506558 0.548515 0.456456 - 0.526935 0.633004 0.464296 - 0.530233 0.671359 0.465618 - 0.528094 0.674653 0.464821 - 0.528973 0.681745 0.465166 - 0.534634 0.694967 0.467322 - 0.420485 0.71118 0.424448 - 0.31255 0.619947 0.383681 - 0.280118 0.627099 0.371505 - 0.284618 0.721019 0.373397 - 0.261883 0.707542 0.364823 - 0.29616 0.825434 0.377959 - 0.257295 1.0025 0.363728 - 0.229559 0.946474 0.353182 - 0.227894 0.956291 0.352578 - 0.228921 1.07061 0.353208 - 0.216 1.27826 0.348795 - 0.183676 1.27838 0.336644 - 0.0802636 1.18056 0.297563 - 0.0366285 1.17968 0.281158 --0.00683291 1.17096 0.264803 - -0.044806 1.15958 0.250504 - -0.0549236 1.17825 0.246741 - -0.0725968 1.24752 0.240246 - -0.0972008 1.16173 0.230814 - -0.115492 1.2093 0.22404 - -0.1351 1.15798 0.21656 - -0.252634 1.21285 0.172496 - -0.342776 1.27809 0.138751 - -0.354223 1.27884 0.13445 - -0.399511 1.27782 0.117424 - -0.486085 0.914936 0.0841054 - -0.492106 0.889532 0.081788 - -0.49372 0.756539 0.080897 - -0.329974 -0.406962 0.136124 - -0.325947 -0.405345 0.13769 - -0.263762 -0.40013 0.161834 - -0.217165 -0.404486 0.179908 - -0.20672 -0.400207 0.18397 - -0.176712 -0.399964 0.195616 - -0.163937 -0.406708 0.20056 - -0.151417 -0.403234 0.205426 - -0.15138 -0.420225 0.205403 - -0.168642 -0.50156 0.19853 - -0.519878 -1.67425 0.0597087 - -0.507058 -1.98053 0.0640266 - -0.512639 -2.15347 0.06149 - -0.495097 -2.15806 0.0682877 - -0.484402 -2.15153 0.0724523 - -0.466877 -2.15586 0.0792439 - -0.422549 -2.16399 0.0964291 - -0.281168 -2.19229 0.151235 - -0.168177 -2.2539 0.194951 - -0.0112086 -0.417981 0.259805 --0.00211161 -0.437785 0.263293 - 0.0274216 -0.355104 0.274932 - 0.0422976 -0.355741 0.280703 - 0.0658029 -0.333947 0.289872 - 0.102311 -0.354341 0.303996 - 0.139352 -0.354245 0.318371 - 0.178328 -0.354885 0.333495 - 0.261531 -0.411252 0.365663 - 0.314579 -0.48119 0.386099 - 1.31431 -1.63668 0.77159 - 0.374542 -0.447284 0.409442 - 0.385494 -0.440213 0.413707 - 0.386748 -0.411828 0.414255 - 0.39076 -0.408737 0.415819 - 0.39818 -0.408994 0.418698 - 0.453917 -0.41026 0.440325 - 0.459932 -0.411834 0.442656 - 0.491076 -0.404671 0.454758 - 0.513332 -0.411037 0.463381 - 0.568641 -0.405845 0.484856 - 0.598003 -0.41414 0.496233 - 0.60618 -0.407587 0.49942 - 0.645833 -0.404397 0.514815 - 0.656402 -0.40671 0.518912 - 0.679266 -0.412031 0.527773 - 0.696555 -0.40934 0.534489 - 0.747943 -0.411695 0.554426 - 0.833679 -0.409235 0.587703 - 0.882144 -0.407614 0.606515 - 0.963193 -0.386196 0.638014 - 2.25442 -0.753818 1.13832 - 2.39108 -0.665387 1.19154 - 2.40847 -0.550532 1.19853 - 2.4035 -0.374209 1.19699 - 5.21015 -0.240632 2.28646 - 5.20362 0.346488 2.28519 - 5.20825 0.469701 2.28725 - 3.55496 0.43918 1.64558 - 3.54247 0.590272 1.64106 - 3.54603 0.693729 1.64266 - 2.17588 0.664836 1.11088 - 2.06912 0.685481 1.0695 - 2.04762 0.68899 1.06116 - 1.99994 0.810198 1.04292 - 0.58135 0.344568 0.491398 - 0.400299 0.247576 0.420929 - 0.386645 0.264697 0.415667 - 0.380525 0.265798 0.413294 - 0.378478 0.274805 0.412519 - 0.333488 0.334544 0.395187 - 0.333381 0.368249 0.395218 - 0.512136 0.739022 0.465384 - 0.501397 0.743965 0.461227 - 0.407165 0.727105 0.424622 - 0.28699 0.631437 0.37778 - 0.270614 0.652334 0.37147 - 0.284377 0.715966 0.376947 - 0.433865 1.27681 0.436163 - 0.35181 1.27428 0.404314 - 0.274582 1.05493 0.373873 - 0.221742 0.988662 0.353225 - 0.246492 1.17677 0.363233 - 0.248946 1.28696 0.364422 - 0.22054 1.28109 0.353386 - 0.188878 1.28532 0.341108 - 0.0833136 1.16915 0.299892 - 0.0359333 1.17868 0.281525 - 0.0276443 1.21609 0.278389 - 0.022697 1.21629 0.276469 - -0.0311518 1.17289 0.255479 - -0.0921855 1.15612 0.231757 - -0.27238 1.16396 0.161845 - -0.288526 1.19065 0.155636 - -0.357975 1.27533 0.128867 - -0.386602 1.27657 0.11776 - -0.489597 1.23893 0.0777099 - -0.486979 1.00066 0.0782147 - -0.493176 0.850794 0.0754883 - -0.490124 0.753224 0.0764631 - -0.486474 0.639665 0.077636 - -0.496757 0.592826 0.0735449 - -0.495862 0.576327 0.073857 - -0.356876 -0.402083 0.12156 - -0.346812 -0.407756 0.125575 - -0.322353 -0.409018 0.13536 - -0.310468 -0.403883 0.140127 - -0.306546 -0.402113 0.1417 - -0.299983 -0.407526 0.144315 - -0.251603 -0.396314 0.1637 - -0.235771 -0.399796 0.170028 - -0.222355 -0.398892 0.175398 - -0.204708 -0.4011 0.182455 - -0.155129 -0.40916 0.202278 - -0.509479 -1.83504 0.0574051 - -0.516627 -2.02594 0.0541336 - -0.391974 -2.15284 0.103743 - -0.266011 -2.22449 0.153996 - -0.261089 -2.26339 0.155881 - -0.225199 -2.27665 0.170215 --0.00628554 -0.42989 0.261797 --0.00048721 -0.446715 0.264081 - 0.146177 -2.29754 0.318785 - 0.152958 -2.26287 0.321573 - 0.024622 -0.423825 0.274178 - 0.0274377 -0.360064 0.275442 - 0.0579767 -0.340972 0.287704 - 0.0764987 -0.344059 0.29511 - 0.106366 -0.35454 0.307039 - 0.106821 -0.351156 0.307229 - 0.116248 -0.359038 0.310984 - 0.150962 -0.350926 0.324893 - 0.160555 -0.35569 0.328722 - 0.332075 -0.49568 0.397058 - 1.32549 -1.77939 0.791831 - 1.31814 -1.63421 0.789203 - 1.30903 -1.59478 0.78564 - 0.373707 -0.44473 0.413828 - 0.384899 -0.401383 0.4184 - 0.50384 -0.409371 0.46598 - 0.513167 -0.409145 0.469713 - 0.544429 -0.409846 0.482221 - 0.567298 -0.410763 0.491371 - 0.672711 -0.4143 0.533547 - 0.676006 -0.412031 0.53487 - 0.680129 -0.405994 0.536533 - 0.796117 -0.406768 0.582947 - 2.1822 -0.710412 1.13696 - 2.18972 -0.679098 1.14004 - 2.40237 -0.237384 1.22609 - 5.04983 -0.186552 2.28564 - 5.04282 0.0752837 2.2834 - 5.05034 0.12303 2.28651 - 3.59603 0.428931 1.7052 - 3.55085 0.474547 1.68722 - 3.54796 0.491178 1.6861 - 3.55044 0.559828 1.68723 - 3.53245 0.728541 1.6804 - 2.42731 0.537413 1.23774 - 2.40098 0.579135 1.22729 - 1.64751 0.464754 0.925528 - 1.6456 0.472568 0.924782 - 2.15102 0.693272 1.12751 - 1.61292 0.710404 0.912215 - 1.51745 0.78054 0.874163 - 1.26957 0.669182 0.774726 - 0.394928 0.245635 0.423807 - 0.38646 0.245541 0.420418 - 0.385242 0.27299 0.41999 - 0.378655 0.271107 0.41735 - 0.375663 0.274259 0.416159 - 0.374547 0.276096 0.415717 - 0.368855 0.285203 0.413459 - 0.369287 0.301835 0.413667 - 0.350474 0.319981 0.406178 - 0.325262 0.352246 0.396158 - 0.317536 0.385684 0.393138 - 0.466755 0.626214 0.45337 - 0.42429 0.731664 0.436604 - 0.418342 0.735776 0.434232 - 0.408384 0.740137 0.430257 - 0.377647 0.72852 0.417932 - 0.366229 0.736685 0.41338 - 0.287451 0.629127 0.381623 - 0.278558 0.623934 0.378054 - 0.265846 0.630708 0.372981 - 0.255642 0.991631 0.369675 - 0.237463 1.12113 0.36268 - 0.201861 1.27447 0.348763 - 0.0737548 1.24721 0.29744 - 0.0595916 1.18417 0.291636 - 0.0234677 1.26026 0.277344 - -0.369439 1.27975 0.120155 - -0.415118 1.27992 0.101876 - -0.488286 0.93469 0.0718526 - -0.487233 0.886061 0.0721692 - -0.488759 0.845653 0.0714715 - -0.495317 0.778473 0.0687023 - -0.490155 0.75571 0.0707189 - -0.489855 0.688533 0.0706944 - -0.486383 0.635891 0.0719701 - -0.493059 0.622327 0.0692696 - -0.490307 0.607867 0.0703396 - -0.485804 0.571085 0.0720625 - -0.492536 0.549604 0.0693223 - -0.3754 -0.399978 0.109761 - -0.315752 -0.404995 0.134347 - -0.285502 -0.402293 0.146827 - -0.272455 -0.408536 0.152194 - -0.268635 -0.410113 0.153766 - -0.234291 -0.398076 0.167954 - -0.233619 -0.400828 0.168226 - -0.215077 -0.406312 0.17586 - -0.204304 -0.4011 0.180314 - -0.200247 -0.405531 0.181977 - -0.166426 -0.495861 0.195728 - -0.515409 -1.83365 0.0489235 - -0.419137 -2.16007 0.0879174 - -0.36897 -2.24242 0.108427 - -0.289001 -2.19498 0.141506 - -0.199636 -2.19888 0.17835 - -0.0274812 -0.427809 0.253173 - -0.0257554 -0.427861 0.253884 --0.00098244 -0.445716 0.264062 - 0.00286325 -0.451554 0.265635 - 0.153069 -2.27882 0.323623 - 0.0475038 -0.335084 0.284295 - 0.0521452 -0.337091 0.286205 - 0.066855 -0.338401 0.292268 - 0.0782559 -0.336991 0.296973 - 0.0884726 -0.346102 0.301166 - 0.0898673 -0.345607 0.301742 - 0.107203 -0.354902 0.308871 - 0.11708 -0.359344 0.312934 - 0.122004 -0.367983 0.314946 - 0.124966 -0.366669 0.31617 - 0.135937 -0.359315 0.32071 - 0.17016 -0.358449 0.334825 - 0.172973 -0.360178 0.335981 - 0.179483 -0.36883 0.338647 - 0.206022 -0.365282 0.349598 - 0.209027 -0.366733 0.350834 - 0.214906 -0.362434 0.353268 - 1.32036 -1.79658 0.806026 - 0.367175 -0.497139 0.415768 - 1.31131 -1.59077 0.802737 - 0.385987 -0.433847 0.423663 - 0.386266 -0.412008 0.423825 - 0.414276 -0.414506 0.43537 - 0.434985 -0.408458 0.443923 - 0.456823 -0.409608 0.452926 - 0.477446 -0.408699 0.461433 - 0.522115 -0.410504 0.479849 - 0.546243 -0.413219 0.489793 - 0.552629 -0.410119 0.492433 - 0.631438 -0.407548 0.524937 - 0.744062 -0.404539 0.571387 - 0.813227 -0.412565 0.599891 - 2.11456 -0.859485 1.13556 - 2.13996 -0.666725 1.14645 - 2.16755 -0.664127 1.15783 - 2.40717 -0.483753 1.25703 - 2.40909 -0.472313 1.25785 - 2.40796 -0.273632 1.25782 - 4.88402 -0.22755 2.27897 - 4.89117 -0.181494 2.28202 - 4.89064 0.189207 2.28261 - 4.90262 0.375946 2.28795 - 4.89206 0.445059 2.28375 - 3.54906 0.476386 1.73 - 3.54801 0.493336 1.7296 - 1.6487 0.484005 0.946357 - 2.1798 0.6831 1.1658 - 1.24278 0.687839 0.779407 - 1.23471 0.698324 0.776102 - 0.388733 0.243207 0.42626 - 0.379735 0.250183 0.422564 - 0.373139 0.271334 0.41989 - 0.36673 0.312642 0.417337 - 0.345308 0.325758 0.408531 - 0.322942 0.33671 0.399332 - 0.32892 0.35177 0.40183 - 0.310342 0.3664 0.3942 - 0.313465 0.37974 0.395517 - 0.327854 0.456387 0.401616 - 0.331815 0.465783 0.40327 - 0.467397 0.74189 0.459778 - 0.41954 0.734569 0.440027 - 0.408654 0.737287 0.435544 - 0.393951 0.732981 0.429471 - 0.280247 0.624322 0.382348 - 0.266863 0.622651 0.376825 - 0.265964 0.627579 0.376465 - 0.26543 0.633411 0.376257 - 0.249702 0.68817 0.36989 - 0.396058 1.2824 0.431529 - 0.378456 1.28149 0.424268 - 0.338963 1.2626 0.407942 - 0.255231 1.23026 0.373343 - 0.239699 1.2833 0.367052 - 0.234519 1.2845 0.364919 - 0.0577662 1.16721 0.291777 - -0.105063 1.20022 0.224702 - -0.11507 1.20332 0.220582 - -0.125672 1.16005 0.216117 - -0.156797 1.22469 0.203421 - -0.166671 1.22332 0.199347 - -0.442079 1.27778 0.0858937 - -0.493631 1.24224 0.0645582 - -0.490367 1.13477 0.0656718 - -0.491449 1.0279 0.0649944 - -0.493383 0.856791 0.0638269 - -0.493274 0.800293 0.0637497 - -0.483619 0.733928 0.0675872 - -0.489694 0.648299 0.064897 - -0.496577 0.59132 0.0619354 - -0.490236 0.558483 0.0644791 - -0.373247 -0.402392 0.106226 - -0.369998 -0.405763 0.107598 - -0.339301 -0.400985 0.120647 - -0.333246 -0.404025 0.123212 - -0.328805 -0.405484 0.125095 - -0.271336 -0.400343 0.149515 - -0.196172 -0.406356 0.181427 - -0.160944 -0.405537 0.196391 - -0.169315 -0.498938 0.192633 - -0.510093 -1.97917 0.0446761 - -0.453554 -2.15796 0.0683017 - -0.377255 -2.24367 0.100522 - -0.27499 -2.23618 0.143974 - -0.266006 -2.23739 0.147787 - -0.165971 -2.23396 0.190284 - -0.156997 -2.23465 0.194093 - -0.0333303 -0.436597 0.250526 - -0.0209546 -0.427966 0.255801 - 0.151971 -2.27882 0.325227 - 0.172985 -2.20157 0.33432 - 0.058336 -0.34257 0.289664 - 0.0913499 -0.33841 0.303696 - 0.131288 -0.367624 0.320595 - 0.162722 -0.361023 0.333961 - 0.183645 -0.36423 0.342841 - 0.186056 -0.364993 0.343863 - 0.322982 -0.492503 0.401743 - 1.31678 -1.83266 0.820934 - 1.32081 -1.62386 0.823099 - 0.383344 -0.425837 0.427526 - 0.430259 -0.409936 0.447487 - 0.433311 -0.4091 0.448785 - 0.46432 -0.407188 0.46196 - 0.468864 -0.407353 0.46389 - 0.470493 -0.40505 0.464587 - 0.506317 -0.407977 0.479796 - 0.510323 -0.403585 0.481507 - 0.527168 -0.408828 0.48865 - 0.570949 -0.409595 0.507244 - 0.605807 -0.409339 0.52205 - 0.654729 -0.407468 0.542833 - 0.693649 -0.404989 0.559369 - 2.03507 -0.853446 1.12815 - 2.04986 -0.770941 1.1346 - 2.06464 -0.667781 1.14111 - 2.39588 -0.663447 1.28181 - 2.41923 -0.548317 1.29198 - 2.40535 -0.450082 1.28629 - 2.39589 -0.181346 1.28286 - 4.7556 0.252821 2.28606 - 4.75361 0.43445 2.2856 - 3.55864 0.445446 1.77808 - 3.54722 0.616192 1.7736 - 2.38299 0.556186 1.27898 - 2.191 0.522638 1.19736 - 1.64391 0.468018 0.964878 - 2.19282 0.678987 1.19848 - 1.91891 0.685073 1.08215 - 2.05604 0.799433 1.14064 - 1.53418 0.708131 0.918792 - 1.24224 0.698322 0.794773 - 1.23942 0.704285 0.793588 - 1.23657 0.710234 0.792392 - 0.368225 0.266804 0.42261 - 0.366056 0.297041 0.421754 - 0.367097 0.300607 0.422204 - 0.361697 0.310233 0.419931 - 0.34947 0.325499 0.414771 - 0.322303 0.34697 0.403279 - 0.320346 0.363537 0.402484 - 0.318882 0.365131 0.401865 - 0.325188 0.493826 0.404824 - 0.410792 0.737811 0.441713 - 0.276423 0.619875 0.384385 - 0.258749 0.715844 0.377087 - 0.431975 1.27469 0.451877 - 0.418828 1.27047 0.446283 - 0.40829 1.27362 0.441814 - 0.386269 1.27677 0.432468 - 0.231775 0.961688 0.366164 - 0.223717 0.979637 0.362781 - 0.138125 1.17088 0.326842 - 0.0526719 1.17354 0.290553 - 0.0477937 1.17086 0.288475 - 0.0389003 1.18242 0.284723 - 0.0101647 1.17362 0.272499 - 0.00509704 1.15474 0.270305 --0.00869224 1.17396 0.26449 - -0.0636256 1.25499 0.241334 - -0.0791652 1.16807 0.234545 - -0.12231 1.17548 0.216236 - -0.127029 1.17497 0.214231 - -0.165958 1.21936 0.197792 - -0.178234 1.16394 0.192458 - -0.208327 1.20223 0.17976 - -0.213184 1.17184 0.177631 - -0.221029 1.16109 0.174275 - -0.230346 1.15912 0.170314 - -0.239251 1.18063 0.166578 - -0.257782 1.19887 0.158747 - -0.286139 1.18968 0.146683 - -0.349807 1.27691 0.11983 - -0.459235 1.28102 0.0733614 - -0.488719 1.0719 0.0603839 - -0.487401 1.05705 0.0609113 - -0.49231 0.875039 0.0584309 - -0.495818 0.872778 0.056936 - -0.490838 0.846842 0.0589947 - -0.487386 0.77821 0.0603122 - -0.488392 0.73031 0.0597805 - -0.490859 0.571103 0.0583868 - -0.494565 0.560644 0.0567902 - -0.349261 -0.400721 0.111295 - -0.325033 -0.398652 0.121962 - -0.25262 -0.397717 0.153835 - -0.251028 -0.398838 0.154533 - -0.243657 -0.401546 0.157771 - -0.204144 -0.402883 0.175159 - -0.197277 -0.405499 0.178176 - -0.191281 -0.400886 0.180825 - -0.175295 -0.404393 0.187853 - -0.171706 -0.404969 0.189431 - -0.155114 -0.405688 0.196732 - -0.161431 -0.474276 0.193802 - -0.475704 -2.14374 0.0518352 - -0.442733 -2.15904 0.0663131 - -0.28842 -2.20588 0.134128 - -0.247166 -2.23969 0.15221 - -0.0282526 -0.427809 0.252519 - -0.026454 -0.423862 0.253319 --0.00776514 -0.426891 0.261537 - 0.103189 -2.24728 0.306393 - 0.142462 -2.29355 0.323577 - 0.0263616 -0.38011 0.27666 - 0.0509676 -0.339045 0.287579 - 0.0733974 -0.342137 0.297444 - 0.0877228 -0.33513 0.303764 - 0.0890598 -0.334629 0.304354 - 0.118611 -0.369558 0.317284 - 0.145351 -0.343031 0.329111 - 0.174447 -0.36098 0.341877 - 0.198012 -0.363999 0.352242 - 0.200962 -0.365487 0.353537 - 0.208816 -0.364597 0.356996 - 1.30668 -1.5882 0.837518 - 1.31868 -1.57479 0.84283 - 0.374615 -0.426781 0.429832 - 0.37969 -0.42115 0.432078 - 0.383345 -0.421339 0.433687 - 0.385023 -0.419429 0.434429 - 0.386351 -0.41353 0.435027 - 0.464938 -0.406742 0.469629 - 0.531923 -0.415092 0.499093 - 0.539121 -0.408887 0.502274 - 0.585145 -0.41414 0.522519 - 0.768489 -0.408362 0.603226 - 0.929938 -0.422198 0.674253 - 1.08531 -0.485364 0.742499 - 1.97324 -0.8109 1.13258 - 2.10175 -0.65086 1.18949 - 2.4092 -0.561306 1.32501 - 2.41119 -0.382632 1.32627 - 2.42737 -0.138006 1.33393 - 4.58147 0.135215 2.2826 - 3.54971 0.672608 1.82967 - 2.46618 0.541785 1.3525 - 1.65006 0.472538 0.993152 - 2.17379 0.677082 1.2241 - 2.17106 0.687522 1.22292 - 1.9312 0.683222 1.11735 - 1.56631 0.66567 0.956713 - 1.45683 0.668569 0.908533 - 1.44868 0.689596 0.904991 - 1.24482 0.696403 0.815283 - 0.399375 0.247498 0.442203 - 0.382617 0.247514 0.434828 - 0.381624 0.249417 0.434394 - 0.377021 0.254082 0.432379 - 0.376794 0.264174 0.432301 - 0.370498 0.267648 0.429538 - 0.367254 0.273169 0.428122 - 0.365438 0.290432 0.427361 - 0.331476 0.334565 0.412509 - 0.327434 0.339522 0.410741 - 0.310532 0.361744 0.403351 - 0.303627 0.363521 0.400316 - 0.291361 0.402418 0.395002 - 0.287821 0.41592 0.393473 - 0.283886 0.429442 0.391771 - 0.313059 0.516327 0.404801 - 0.421167 0.739216 0.452869 - 0.408858 0.739503 0.447452 - 0.398609 0.735884 0.442933 - 0.390222 0.742629 0.439257 - 0.380566 0.739592 0.435 - 0.368043 0.738274 0.429486 - 0.294548 0.732543 0.397126 - 0.318724 0.889038 0.408109 - 0.367861 1.28145 0.430592 - 0.229184 0.943192 0.368818 - 0.225615 0.995095 0.367361 - 0.228132 1.04192 0.368571 - 0.0936832 1.16766 0.309672 - -0.17401 1.17063 0.19186 - -0.202986 1.20312 0.179178 - -0.207788 1.20223 0.177063 - -0.226285 1.16699 0.168845 - -0.350228 1.28365 0.114549 - -0.488859 1.27079 0.0535065 - -0.489498 1.11573 0.0528865 - -0.48565 0.990881 0.0543072 - -0.490175 0.875039 0.0520626 - -0.487689 0.853364 0.0531094 - -0.485681 0.817145 0.053914 - -0.490808 0.787405 0.0515923 - -0.491921 0.781807 0.0510903 - -0.484503 0.682296 0.0541375 - -0.490223 0.58306 0.0514034 - -0.494661 0.548729 0.0493753 - -0.379073 -0.401543 0.0935556 - -0.37556 -0.401132 0.0951475 - -0.357855 -0.394875 0.103179 - -0.338662 -0.403242 0.111853 - -0.263275 -0.40145 0.145997 - -0.255234 -0.407252 0.149625 - -0.241194 -0.406261 0.155986 - -0.185581 -0.406886 0.18117 - -0.168915 -0.398511 0.188736 - -0.51853 -1.72804 0.0274883 - -0.513289 -1.73616 0.0298436 - -0.509191 -2.06407 0.0309798 - -0.473683 -2.14277 0.0468871 - -0.172842 -2.21527 0.182968 - -0.0300847 -0.420753 0.251558 - -0.0284385 -0.421812 0.252301 - -0.0183635 -0.416996 0.256874 - 0.14163 -2.29754 0.325201 - 0.03253 -0.351817 0.280065 - 0.0342156 -0.353551 0.280825 - 0.0766309 -0.330362 0.300084 - 0.120502 -0.368255 0.319869 - 0.136819 -0.361493 0.327273 - 0.13653 -0.345014 0.327178 - 0.166048 -0.361946 0.340509 - 0.181566 -0.36948 0.34752 - 0.189793 -0.36988 0.351245 - 0.202985 -0.36779 0.357223 - 0.21578 -0.354472 0.363047 - 0.217186 -0.353353 0.363686 - 0.313966 -0.481312 0.407233 - 0.318637 -0.483701 0.409344 - 1.30921 -1.77772 0.855099 - 1.31835 -1.69739 0.859414 - 1.31886 -1.56915 0.859924 - 0.372633 -0.446109 0.433879 - 0.375525 -0.441644 0.435198 - 0.510574 -0.412458 0.496421 - 0.520398 -0.41627 0.500862 - 0.537604 -0.410005 0.508668 - 0.557796 -0.409109 0.517814 - 0.589887 -0.407587 0.532351 - 0.604824 -0.409474 0.53911 - 0.645345 -0.398211 0.557486 - 1.89529 -0.85687 1.12253 - 1.91719 -0.834445 1.1325 - 2.05197 -0.660144 1.19392 - 2.29344 -0.665723 1.30326 - 2.34282 -0.667883 1.32562 - 2.40101 -0.647428 1.35202 - 2.40355 -0.635841 1.35319 - 2.40793 -0.539548 1.35539 - 2.40626 -0.419345 1.3549 - 2.40801 -0.372162 1.35579 - 2.40123 -0.265372 1.35296 - 4.44873 -0.0606162 2.28065 - 4.44895 0.0249555 2.28093 - 4.45621 0.19653 2.2846 - 4.45395 0.411479 2.28405 - 4.43869 0.453101 2.27723 - 3.55183 0.571077 1.87586 - 3.55483 0.659243 1.87741 - 2.41435 0.545217 1.36068 - 1.649 0.457593 1.01388 - 2.1727 0.668773 1.25151 - 1.4841 0.675949 0.939686 - 1.242 0.690826 0.83008 - 0.431091 0.262323 0.461908 - 0.373513 0.238353 0.43578 - 0.364387 0.283256 0.431746 - 0.362498 0.3036 0.430935 - 0.361286 0.305417 0.43039 - 0.360067 0.307229 0.429842 - 0.35957 0.309634 0.429622 - 0.361241 0.313847 0.430388 - 0.354753 0.319825 0.427464 - 0.346071 0.32376 0.42354 - 0.34478 0.325499 0.422959 - 0.332601 0.325925 0.417445 - 0.300444 0.371722 0.402983 - 0.297733 0.514254 0.402068 - 0.399622 0.734741 0.448694 - 0.388339 0.743487 0.443603 - 0.265484 0.618166 0.387692 - 0.28907 0.740952 0.398643 - 0.379652 1.11123 0.440477 - 0.378752 1.2003 0.440265 - 0.369832 1.27675 0.436393 - 0.227674 1.04676 0.37151 - 0.229816 1.28646 0.373006 - 0.201998 1.27932 0.360393 - 0.112659 1.22257 0.31981 - 0.0374092 1.18342 0.285646 - -0.0241695 1.25298 0.257912 - -0.037562 1.16381 0.251651 - -0.042038 1.1567 0.249608 - -0.130656 1.16549 0.209495 - -0.208566 1.21011 0.174311 - -0.2105 1.19146 0.173394 - -0.231081 1.16991 0.164026 - -0.265172 1.17002 0.148588 - -0.279099 1.16637 0.142273 - -0.485955 0.995324 0.0482197 - -0.490134 0.905153 0.0461291 - -0.491145 0.880206 0.0456165 - -0.489091 0.78014 0.0463269 - -0.485382 0.74546 0.0479305 - -0.488141 0.722558 0.0466306 - -0.493252 0.649264 0.0441552 - -0.489604 0.616288 0.0457346 - -0.490925 0.607186 0.0451164 - -0.489554 0.535531 0.0455801 - -0.37863 -0.406128 0.0890215 - -0.370372 -0.403832 0.0928742 - -0.337475 -0.403242 0.108204 - -0.306927 -0.395022 0.122455 - -0.301186 -0.401324 0.125116 - -0.269816 -0.39831 0.139739 - -0.267722 -0.398699 0.140714 - -0.257278 -0.400457 0.145576 - -0.231977 -0.402552 0.157361 - -0.211491 -0.399198 0.166913 - -0.152037 -0.403529 0.194605 - -0.515981 -1.96092 0.0215942 - -0.411531 -2.15321 0.0698371 - -0.377238 -2.15951 0.0858015 - -0.361462 -2.22862 0.0929998 - -0.230169 -2.26569 0.154092 - -0.173059 -2.22424 0.180793 - -0.132679 -2.30038 0.19944 - -0.0171097 -0.417999 0.257441 - 0.131463 -2.29926 0.322516 - 0.154212 -2.23815 0.33325 - 0.0285009 -0.409884 0.278711 - 0.0265531 -0.343587 0.277949 - 0.0372579 -0.358963 0.282903 - 0.0456631 -0.340963 0.286859 - 0.0544041 -0.349114 0.290914 - 0.0757728 -0.34082 0.300889 - 0.0784644 -0.33991 0.302145 - 0.0811486 -0.338973 0.303397 - 0.10656 -0.355594 0.315201 - 0.125938 -0.367401 0.324204 - 0.142359 -0.356827 0.331878 - 0.144174 -0.356949 0.332724 - 0.154836 -0.353098 0.3377 - 0.174138 -0.361793 0.346674 - 0.192727 -0.370428 0.355316 - 0.194674 -0.370258 0.356224 - 0.209102 -0.359699 0.36297 - 1.31435 -1.79397 0.87478 - 1.30748 -1.73786 0.871704 - 1.30997 -1.58066 0.873212 - 0.370801 -0.442801 0.438128 - 0.383621 -0.422884 0.444145 - 0.386525 -0.407732 0.445532 - 0.409753 -0.409038 0.456352 - 0.430293 -0.41016 0.465919 - 0.503717 -0.41323 0.500124 - 0.606918 -0.392999 0.548253 - 0.659959 -0.409259 0.572931 - 0.675162 -0.405537 0.580023 - 0.729811 -0.392457 0.605515 - 0.754746 -0.382992 0.617154 - 0.791657 -0.387334 0.634343 - 0.837349 -0.404321 0.655595 - 1.85894 -0.690854 1.13096 - 1.88768 -0.671003 1.14439 - 2.40963 -0.362421 1.38827 - 2.43102 -0.139606 1.39873 - 4.33409 -0.101267 2.28552 - 4.33019 0.338944 2.28468 - 4.32789 0.359796 2.28365 - 4.32394 0.401539 2.2819 - 4.32229 0.422436 2.28118 - 3.54876 0.48607 1.92091 - 3.54916 0.6439 1.92144 - 3.54263 0.731066 1.91859 - 2.22907 0.528856 1.30611 - 2.02751 0.502047 1.21214 - 1.94066 0.490635 1.17164 - 1.83098 0.472529 1.1205 - 1.64728 0.468041 1.0349 - 1.88555 0.684143 1.14639 - 1.75628 0.714191 1.08623 - 1.58245 0.670538 1.00513 - 1.54752 0.673214 0.988867 - 1.49067 0.674002 0.962379 - 0.365446 0.264737 0.437194 - 0.36087 0.27445 0.435083 - 0.357194 0.287579 0.4334 - 0.353415 0.303657 0.431674 - 0.35392 0.321057 0.431948 - 0.330351 0.322958 0.42097 - 0.315093 0.349262 0.413919 - 0.309883 0.362301 0.41152 - 0.307002 0.365444 0.410185 - 0.293648 0.39271 0.404023 - 0.288377 0.410749 0.401607 - 0.284054 0.431167 0.399638 - 0.271934 0.461997 0.394059 - 0.330541 0.616809 0.421707 - 0.382178 0.736627 0.446031 - 0.258934 0.635213 0.388384 - 0.275373 0.729243 0.396251 - 0.244384 0.684144 0.381712 - 0.365758 1.27106 0.43956 - 0.126551 1.1842 0.327913 - 0.0977195 1.18103 0.314472 - 0.0408798 1.17316 0.287971 - 0.00804294 1.15962 0.272641 - 0.0034562 1.15974 0.270505 - -0.12016 1.20783 0.213013 - -0.135444 1.16792 0.205804 - -0.231355 1.17481 0.161131 - -0.250499 1.2246 0.152321 - -0.372654 1.27351 0.0955119 - -0.471389 1.28115 0.0495248 - -0.487626 1.09492 0.0415482 - -0.48918 1.05076 0.0407267 - -0.491775 0.949991 0.0392955 - -0.488755 0.829013 0.0404356 - -0.486591 0.786569 0.0413503 - -0.488693 0.782641 0.0403624 - -0.494353 0.777254 0.037713 - -0.48851 0.746499 0.0403679 - -0.492189 0.705405 0.0385628 - -0.487819 0.633076 0.0404395 - -0.489875 0.577044 0.0393578 - -0.363408 -0.404311 0.0918916 - -0.348702 -0.404425 0.0989235 - -0.303815 -0.395631 0.120406 - -0.283681 -0.398926 0.130026 - -0.282625 -0.408434 0.130509 - -0.256915 -0.404954 0.142811 - -0.255318 -0.406107 0.143572 - -0.227261 -0.40287 0.156995 - -0.200185 -0.397535 0.169953 - -0.191504 -0.404497 0.174088 - -0.178232 -0.400261 0.180444 - -0.160676 -0.402985 0.188833 - -0.156367 -0.447341 0.190795 - -0.507445 -1.96813 0.0195527 - -0.514434 -2.06651 0.0159924 - -0.436548 -2.15318 0.0530423 - -0.3429 -2.23383 0.0976419 - -0.237353 -2.2537 0.148066 - -0.198671 -2.2188 0.16664 - -0.173351 -2.23421 0.178712 - -0.147297 -2.24229 0.191152 - -0.0240788 -0.418941 0.254112 - -0.0224193 -0.417967 0.254908 - -0.0207612 -0.415986 0.255705 - 0.0253627 -0.433373 0.277721 - 0.0332291 -0.355526 0.281655 - 0.0402825 -0.337916 0.285067 - 0.046334 -0.340656 0.287954 - 0.0476741 -0.340342 0.288596 - 0.0562295 -0.347436 0.292671 - 0.0800672 -0.343259 0.304078 - 0.124151 -0.369928 0.325098 - 0.130279 -0.363673 0.328042 - 0.136847 -0.35475 0.331202 - 0.170985 -0.361846 0.34751 - 0.299308 -0.461425 0.408648 - 0.301671 -0.46068 0.409779 - 1.30609 -1.61187 0.887497 - 0.366091 -0.439926 0.440628 - 0.417441 -0.411399 0.465245 - 0.46348 -0.408699 0.487265 - 0.515474 -0.409398 0.512125 - 0.608258 -0.408064 0.556493 - 0.629479 -0.409353 0.566637 - 0.705953 -0.412419 0.603197 - 0.769557 -0.387799 0.633664 - 0.833051 -0.414143 0.663966 - 1.81066 -0.806712 1.13055 - 1.80685 -0.724375 1.12891 - 1.80736 -0.704727 1.12919 - 1.82419 -0.661666 1.13734 - 1.84654 -0.659748 1.14803 - 2.11456 -0.664668 1.27618 - 2.40501 -0.655012 1.41508 - 2.40454 -0.435268 1.41534 - 2.40622 -0.423549 1.41617 - 4.20574 -0.200999 2.27711 - 4.20638 -0.119211 2.2776 - 4.21744 0.167369 2.28353 - 3.54824 0.593814 1.96449 - 2.51157 0.534563 1.46866 - 2.42055 0.539827 1.42516 - 2.39188 0.545617 1.41146 - 1.67628 0.496056 1.06918 - 1.99833 0.600789 1.2234 - 2.0664 0.686439 1.25614 - 1.43183 0.675591 0.952695 - 1.41462 0.692185 0.9445 - 1.41188 0.699111 0.943204 - 1.4091 0.706023 0.941894 - 1.25967 0.662003 0.870344 - 1.26172 0.678224 0.871361 - 1.21195 0.703826 0.847619 - 0.364284 0.255252 0.441305 - 0.36102 0.281424 0.439803 - 0.346814 0.316744 0.433089 - 0.34093 0.320136 0.430283 - 0.32516 0.328614 0.422761 - 0.317912 0.333211 0.419305 - 0.316596 0.334835 0.418679 - 0.311179 0.347196 0.416117 - 0.311022 0.353151 0.416055 - 0.297022 0.382163 0.409425 - 0.291958 0.407052 0.407059 - 0.284433 0.415239 0.403479 - 0.285073 0.427456 0.403812 - 0.273114 0.475523 0.3982 - 0.359051 0.733931 0.439864 - 0.257767 0.629377 0.391203 - 0.361359 1.21063 0.442025 - 0.226037 0.965538 0.376776 - 0.226541 1.03687 0.377175 - 0.194975 1.28627 0.362634 - 0.15554 1.1944 0.343575 - -0.0337504 1.17289 0.253017 - -0.0576217 1.19624 0.241654 - -0.105235 1.20121 0.218898 - -0.121495 1.16951 0.211053 - -0.139891 1.16735 0.202252 - -0.166906 1.15948 0.189317 - -0.175488 1.15405 0.185202 - -0.212965 1.21313 0.167413 - -0.224046 1.16404 0.162006 - -0.234651 1.16985 0.156947 - -0.257126 1.2106 0.146292 - -0.273678 1.1715 0.13829 - -0.400339 1.27799 0.0779621 - -0.4397 1.27764 0.0591409 - -0.492361 0.945081 0.0332231 - -0.493185 0.882227 0.0326899 - -0.491997 0.769173 0.0330073 - -0.490351 0.705405 0.0336529 - -0.489568 0.604914 0.0338048 - -0.370526 -0.403563 0.0839375 - -0.345228 -0.405278 0.0963564 - -0.340057 -0.402385 0.0989022 - -0.334322 -0.3987 0.101727 - -0.330008 -0.400248 0.103842 - -0.326859 -0.403264 0.105382 - -0.296511 -0.401104 0.120289 - -0.288573 -0.40405 0.124181 - -0.272778 -0.401993 0.131942 - -0.2712 -0.403227 0.132714 - -0.241134 -0.406037 0.147472 - -0.204825 -0.400192 0.165316 - -0.196928 -0.40018 0.169194 - -0.191043 -0.400049 0.172084 - -0.180718 -0.407572 0.177137 - -0.161588 -0.401361 0.186546 - -0.155762 -0.446395 0.189306 - -0.511438 -2.09985 0.0109599 - -0.488417 -2.15481 0.0221426 - -0.444366 -2.15698 0.0437699 - -0.410148 -2.16301 0.0605596 - -0.237453 -2.26265 0.145143 - -0.197618 -2.21282 0.164816 - -0.162923 -2.216 0.181847 - -0.155585 -2.23864 0.185399 - -0.114414 -2.30642 0.205467 - -0.0312942 -0.428749 0.250468 --0.00583511 -0.437785 0.26295 - -4.168e-05 -0.453552 0.26576 - 0.0285547 -0.406684 0.279907 - 0.0280105 -0.388608 0.27968 - 0.0285885 -0.347106 0.280057 - 0.0806641 -0.333264 0.30566 - 0.127741 -0.368752 0.328699 - 0.128402 -0.36185 0.329039 - 0.129818 -0.361134 0.329736 - 0.132259 -0.358775 0.33094 - 0.137853 -0.355796 0.333694 - 0.142718 -0.347475 0.336101 - 0.160222 -0.365443 0.344657 - 0.193665 -0.359431 0.361093 - 0.195069 -0.358398 0.361785 - 0.203706 -0.359139 0.366025 - 0.320272 -0.473203 0.423013 - 0.325911 -0.464239 0.425802 - 0.352933 -0.42375 0.439162 - 0.425387 -0.40673 0.47478 - 0.442938 -0.407996 0.483396 - 0.723865 -0.380379 0.621412 - 1.75343 -0.835902 1.12599 - 1.75503 -0.826512 1.12679 - 1.77257 -0.675501 1.13574 - 2.41264 -0.548885 1.45034 - 2.41039 -0.4872 1.44937 - 2.40963 -0.438469 1.44911 - 2.40826 -0.282144 1.44879 - 2.40933 -0.270346 1.44934 - 4.09118 -0.156548 2.2755 - 4.09448 0.0833135 2.27766 - 4.0931 0.143286 2.27711 - 4.09908 0.243764 2.28027 - 4.09631 0.364164 2.27918 - 4.09327 0.404157 2.27778 - 3.5633 0.439999 2.0176 - 3.54267 0.720528 2.0081 - 1.96665 0.688693 1.23409 - 1.8371 0.683572 1.17046 - 1.71936 0.677931 1.11263 - 1.61321 0.681423 1.06051 - 1.57026 0.672313 1.0394 - 1.41874 0.689596 0.965027 - 0.366813 0.263651 0.44751 - 0.361862 0.270569 0.445093 - 0.35401 0.267543 0.441231 - 0.361297 0.280691 0.444839 - 0.356919 0.301776 0.442736 - 0.354282 0.310832 0.441461 - 0.338713 0.320136 0.433836 - 0.316457 0.34578 0.422964 - 0.313661 0.352018 0.421605 - 0.310244 0.354541 0.419932 - 0.306535 0.363009 0.41813 - 0.304304 0.366872 0.417043 - 0.295005 0.36577 0.412474 - 0.301334 0.37974 0.415613 - 0.291411 0.40176 0.410789 - 0.283626 0.416794 0.407 - 0.269612 0.459777 0.400214 - 0.265229 0.502591 0.398157 - 0.324759 0.671395 0.427766 - 0.297845 0.658281 0.414521 - 0.279344 0.633007 0.405379 - 0.255261 0.620857 0.393525 - 0.354016 1.00641 0.44288 - 0.353582 1.05725 0.44278 - 0.352998 1.06931 0.442521 - 0.350411 1.10463 0.441329 - 0.357545 1.2059 0.445058 - 0.362041 1.27391 0.447417 - 0.229713 0.986717 0.381795 - 0.23782 1.13227 0.3861 - 0.253826 1.27305 0.394274 - 0.228828 1.27939 0.382012 - 0.212884 1.27801 0.37418 - 0.137172 1.17409 0.336768 - 0.125113 1.23149 0.330974 - 0.0287014 1.25384 0.283679 - -0.0155462 1.24499 0.261931 - -0.064405 1.247 0.237942 - -0.0936897 1.16908 0.223388 - -0.129883 1.16151 0.205597 - -0.228336 1.165 0.157257 - -0.234881 1.17475 0.154065 - -0.266976 1.16688 0.138287 - -0.369503 1.2716 0.0881722 - -0.49036 1.26348 0.0288049 - -0.490669 1.20463 0.0285218 - -0.487109 1.04311 0.0299099 - -0.487899 1.02249 0.0294765 - -0.489409 0.962801 0.0286017 - -0.490717 0.917303 0.027858 - -0.491866 0.874784 0.0271988 - -0.488833 0.812062 0.0285488 - -0.488006 0.773111 0.028868 - -0.492296 0.751597 0.0267134 - -0.490707 0.630836 0.0272245 - -0.491095 0.558277 0.0268724 - -0.491418 0.553803 0.0267038 - -0.370648 -0.401846 0.0792693 - -0.338768 -0.402385 0.0953408 - -0.277043 -0.399055 0.126468 - -0.262022 -0.401093 0.134036 - -0.258785 -0.407131 0.135655 - -0.257195 -0.408301 0.136453 - -0.213425 -0.402656 0.158533 - -0.186266 -0.399 0.172234 - -0.167044 -0.407358 0.181906 - -0.161791 -0.397878 0.184576 - -0.512732 -1.66186 0.00481391 - -0.484839 -2.14801 0.0177877 - -0.441533 -2.1521 0.0396115 - -0.407924 -2.16007 0.0565385 - -0.205901 -2.21491 0.158268 - -0.0214983 -0.414986 0.255268 - -0.0182661 -0.413999 0.2569 - 0.103743 -2.34712 0.314082 - 0.11837 -2.28498 0.321596 - 0.153126 -2.27103 0.339149 - 0.185121 -2.23055 0.355371 - 0.0328796 -0.352315 0.282823 - 0.0473608 -0.339045 0.290154 - 0.0486809 -0.338719 0.29082 - 0.0606049 -0.361274 0.296781 - 0.0616446 -0.340334 0.297352 - 0.0690995 -0.330721 0.301132 - 0.153664 -0.358382 0.343705 - 0.176651 -0.363279 0.355283 - 0.184177 -0.362799 0.359078 - 0.204864 -0.370397 0.369491 - 1.29844 -1.62 0.918029 - 0.33345 -0.40056 0.434252 - 0.352334 -0.400515 0.443772 - 0.363872 -0.405817 0.449577 - 0.415398 -0.407174 0.475551 - 0.435567 -0.411205 0.485711 - 0.467369 -0.40944 0.501748 - 0.483643 -0.411734 0.509948 - 0.55474 -0.412296 0.545791 - 0.668415 -0.412648 0.603101 - 1.70912 -0.750652 1.12703 - 1.70986 -0.702812 1.12751 - 1.7239 -0.670228 1.13466 - 1.8335 -0.662182 1.18993 - 1.95814 -0.664412 1.25277 - 2.4038 -0.599297 1.4776 - 2.40977 -0.477466 1.48088 - 2.40855 -0.404205 1.48043 - 2.40861 -0.367921 1.48054 - 3.98666 -0.172978 2.27657 - 3.9906 0.120849 2.27921 - 3.98918 0.14041 2.27854 - 3.98986 0.238564 2.2791 - 3.63295 0.432897 2.0996 - 3.55578 0.441424 2.06071 - 3.54128 0.724101 2.05404 - 2.47872 0.533252 1.5179 - 2.41054 0.543352 1.48355 - 2.09574 0.505282 1.32476 - 1.79536 0.536649 1.17339 - 2.18805 0.675944 1.37168 - 1.63388 0.675466 1.09229 - 1.25386 0.666236 0.900676 - 0.367166 0.268157 0.452747 - 0.366116 0.270042 0.452222 - 0.35148 0.275166 0.444855 - 0.350348 0.292913 0.444324 - 0.317002 0.339522 0.427617 - 0.302172 0.35422 0.420173 - 0.30097 0.365444 0.419592 - 0.294476 0.380634 0.416352 - 0.290059 0.428458 0.414232 - 0.283366 0.430599 0.410863 - 0.281684 0.432074 0.410018 - 0.273827 0.436293 0.406066 - 0.273723 0.440126 0.406022 - 0.25808 0.498029 0.398265 - 0.290733 0.647706 0.415063 - 0.249907 0.69535 0.394587 - 0.367237 1.26258 0.45501 - 0.268628 1.01168 0.404733 - 0.228615 1.04147 0.384627 - 0.185513 1.27843 0.363428 - 0.0888617 1.16766 0.314452 - 0.071446 1.24379 0.305842 - 0.0115714 1.18447 0.275523 - 0.00684694 1.17962 0.27313 - -0.0159736 1.24999 0.261782 - -0.0432368 1.1567 0.247828 - -0.0687996 1.23079 0.235106 - -0.0939754 1.17307 0.222284 - -0.262568 1.17294 0.137286 - -0.276254 1.16929 0.130378 - -0.347741 1.27629 0.0945771 - -0.363402 1.27425 0.0866766 - -0.386212 1.27782 0.0751847 - -0.466214 1.28208 0.0348603 - -0.488276 1.20372 0.0235622 - -0.487904 1.18861 0.0237156 - -0.491715 1.15708 0.0217239 - -0.489124 1.07547 0.0228472 - -0.492503 0.973343 0.0209147 - -0.488659 0.908078 0.0227067 - -0.489534 0.832658 0.0220968 - -0.491903 0.761281 0.0207426 - -0.489534 0.710226 0.0218223 - -0.487475 0.700715 0.022839 - -0.48449 0.630809 0.0241876 - -0.494381 0.605595 0.0191444 - -0.307396 -0.394535 0.107447 - -0.292281 -0.40166 0.115246 - -0.26726 -0.403631 0.12818 - -0.23819 -0.403477 0.143211 - -0.235704 -0.40284 0.144498 - -0.230491 -0.397041 0.147207 - -0.207868 -0.396555 0.158906 - -0.181006 -0.405866 0.172775 - -0.508258 -1.998 -2.486e-05 - -0.505847 -2.02259 0.00116682 - -0.509893 -2.15066 -0.0012137 - -0.432063 -2.15806 0.0390136 - -0.371873 -2.16246 0.0701265 - -0.281418 -2.19696 0.116821 - -0.236326 -2.26762 0.139978 - -0.113965 -2.30342 0.203168 --0.00440915 -0.456709 0.263974 --0.00238417 -0.463628 0.265006 - 0.102307 -2.33813 0.314919 - 0.0257716 -0.356459 0.279806 - 0.0311495 -0.354539 0.282591 - 0.0338954 -0.354033 0.284012 - 0.0352668 -0.35377 0.284722 - 0.0485396 -0.348816 0.291596 - 0.0695453 -0.330289 0.302499 - 0.0938985 -0.334686 0.315082 - 0.114137 -0.365479 0.325477 - 0.123674 -0.368541 0.330402 - 0.142036 -0.347576 0.339944 - 0.159563 -0.361946 0.348974 - 0.179439 -0.356865 0.359263 - 0.183631 -0.357432 0.361429 - 0.214137 -0.36063 0.377196 - 0.217242 -0.355563 0.378813 - 0.292718 -0.440353 0.417649 - 0.329922 -0.392158 0.436995 - 0.532334 -0.414004 0.541608 - 0.541467 -0.412954 0.546333 - 0.605185 -0.409057 0.579289 - 0.609072 -0.407486 0.581302 - 0.65898 -0.405068 0.607114 - 1.6603 -0.723962 1.12416 - 1.66583 -0.707441 1.12705 - 1.66855 -0.69916 1.12848 - 1.67124 -0.690865 1.12989 - 1.79807 -0.662899 1.19553 - 1.83109 -0.664919 1.2126 - 2.40449 -0.491277 1.50948 - 2.4079 -0.369798 1.51152 - 2.4049 -0.333036 1.51005 - 2.39758 -0.200191 1.50657 - 2.4883 -0.133535 1.55363 - 3.88177 -0.0542986 2.27434 - 3.8829 -0.0159763 2.27501 - 3.8836 0.0990686 2.27563 - 3.88494 0.118293 2.27636 - 3.8865 0.156752 2.27726 - 3.8851 0.195119 2.27662 - 3.88094 0.406712 2.27495 - 1.82275 0.47093 1.21085 - 1.66863 0.449009 1.1311 - 1.87737 0.563967 1.2393 - 1.84834 0.685073 1.22456 - 1.78485 0.681459 1.19172 - 1.65922 0.680247 1.12676 - 1.57049 0.670896 1.08086 - 0.383463 0.241638 0.466107 - 0.370933 0.246584 0.459639 - 0.37187 0.25482 0.460142 - 0.36405 0.259892 0.45611 - 0.35102 0.289861 0.44944 - 0.358225 0.309484 0.45321 - 0.357021 0.311336 0.452591 - 0.34 0.316744 0.443802 - 0.334056 0.317149 0.44073 - 0.317496 0.339209 0.432216 - 0.312831 0.34646 0.429821 - 0.308583 0.357322 0.427648 - 0.307193 0.358931 0.426933 - 0.302198 0.366008 0.424366 - 0.285255 0.402503 0.415688 - 0.302062 0.432312 0.424446 - 0.317617 0.469671 0.432573 - 0.27975 0.428242 0.412899 - 0.26862 0.460004 0.407216 - 0.263243 0.464214 0.404445 - 0.26486 0.489459 0.405338 - 0.263924 0.492531 0.404861 - 0.259115 0.498361 0.402387 - 0.269669 0.620612 0.408119 - 0.251999 0.621754 0.398986 - 0.25763 0.720118 0.402119 - 0.354615 1.10193 0.453127 - 0.240037 1.13682 0.39396 - 0.215311 1.28078 0.381499 - 0.161461 1.22906 0.353538 - 0.0926048 1.1691 0.317799 - 0.0694828 1.22884 0.305977 - 0.0105163 1.16548 0.275344 - -0.155779 1.23362 0.18951 - -0.180155 1.16317 0.176747 - -0.221957 1.16306 0.155132 - -0.299344 1.23263 0.115274 - -0.378948 1.27673 0.0742118 - -0.423957 1.27977 0.0509455 - -0.435079 1.27952 0.0451938 - -0.494488 1.21057 0.0143196 - -0.486676 1.02873 0.0179497 - -0.488024 0.948578 0.0170719 - -0.489867 0.861633 0.0159233 - -0.488027 0.841728 0.0168298 - -0.488613 0.818787 0.0164755 - -0.487372 0.786187 0.0170438 - -0.490897 0.625464 0.0148589 - -0.350089 -0.405617 0.0810318 - -0.347924 -0.406509 0.082177 - -0.292328 -0.410722 0.11164 - -0.282857 -0.403752 0.116676 - -0.276106 -0.400674 0.120262 - -0.258758 -0.394953 0.129472 - -0.257232 -0.396131 0.130278 - -0.236011 -0.400918 0.141516 - -0.226218 -0.406335 0.146696 - -0.207036 -0.404593 0.156868 - -0.199876 -0.397538 0.16068 - -0.193324 -0.4046 0.164137 - -0.171449 -0.401636 0.17574 - -0.165563 -0.405506 0.178851 - -0.482265 -2.15579 0.0070017 - -0.464014 -2.1525 0.0166843 - -0.403967 -2.15713 0.0485051 - -0.357579 -2.19147 0.0730183 - -0.309737 -2.22354 0.0983075 - -0.288088 -2.1897 0.109861 - 0.0243159 -0.43018 0.279453 - 0.0263196 -0.417824 0.280543 - 0.0271508 -0.372302 0.281087 - 0.0395357 -0.341557 0.287722 - 0.0497267 -0.351409 0.293102 - 0.0512311 -0.344868 0.293914 - 0.0796422 -0.338961 0.308989 - 0.114459 -0.364822 0.327387 - 0.122885 -0.365092 0.331853 - 0.133546 -0.366178 0.337502 - 0.153197 -0.362784 0.347927 - 0.208702 -0.361279 0.377354 - 0.221552 -0.358002 0.384174 - 0.308592 -0.430027 0.430152 - 0.314543 -0.394136 0.433387 - 0.373861 -0.421637 0.464771 - 0.393057 -0.405105 0.474984 - 0.516417 -0.408329 0.540372 - 0.521661 -0.408454 0.543151 - 0.529223 -0.406382 0.547165 - 0.550929 -0.414458 0.558653 - 0.621541 -0.409661 0.596097 - 0.636803 -0.381785 0.60425 - 1.62236 -0.748986 1.12588 - 1.62778 -0.676871 1.12891 - 1.7964 -0.665983 1.21833 - 2.40705 -0.44519 1.54254 - 2.40612 -0.432736 1.54207 - 2.40424 -0.322645 1.54132 - 2.41752 -0.142548 1.54878 - 3.78867 0.172498 2.27635 - 3.78806 0.229013 2.27616 - 3.55353 0.57146 2.1526 - 3.54677 0.696757 2.14931 - 1.65201 0.482112 1.14438 - 2.09571 0.688627 1.38006 - 2.05572 0.686727 1.35886 - 1.86667 0.685361 1.25863 - 1.69673 0.680244 1.16854 - 1.67827 0.682362 1.15876 - 1.50349 0.672125 1.06608 - 1.45136 0.674377 1.03845 - 1.41573 0.682951 1.01958 - 1.25486 0.674278 0.934282 - 1.21475 0.705869 0.913089 - 0.362477 0.273525 0.46031 - 0.347205 0.278087 0.452224 - 0.332747 0.32376 0.444663 - 0.322746 0.320229 0.439353 - 0.321506 0.321918 0.4387 - 0.298111 0.35125 0.426364 - 0.300091 0.366008 0.427447 - 0.307886 0.439128 0.431745 - 0.276604 0.434332 0.415151 - 0.271552 0.43869 0.412483 - 0.26643 0.463875 0.409825 - 0.26102 0.58728 0.407236 - 0.275944 0.737311 0.415487 - 0.354573 1.08052 0.457946 - 0.350721 1.0833 0.45591 - 0.332297 1.21495 0.446442 - 0.23009 0.992226 0.391756 - 0.245206 1.28313 0.400428 - 0.0796571 1.24782 0.312588 - 0.0375748 1.17815 0.290122 - 0.0145887 1.17031 0.277919 - -0.105454 1.2062 0.214364 - -0.157952 1.21311 0.18655 - -0.17073 1.16469 0.179667 - -0.180383 1.16811 0.174557 - -0.210833 1.18463 0.158453 - -0.221962 1.16699 0.152513 - -0.248258 1.20685 0.138663 - -0.257552 1.20455 0.133731 - -0.438195 1.27747 0.0381353 - -0.489329 1.13522 0.0107062 - -0.492934 0.862718 0.00817864 - -0.492736 0.829716 0.00820899 - -0.486967 0.804122 0.0112092 - -0.489298 0.770995 0.00989823 - -0.490064 0.737333 0.00941621 - -0.494026 0.710395 0.00725487 - -0.491814 0.682028 0.00836311 - -0.490386 0.55511 0.00883274 - -0.296749 -0.40074 0.105354 - -0.289499 -0.404592 0.109293 - -0.281143 -0.39924 0.113854 - -0.245604 -0.400521 0.133199 - -0.20161 -0.402875 0.157144 - -0.190759 -0.404554 0.163048 - -0.185722 -0.406163 0.165787 - -0.16074 -0.408569 0.179381 - -0.159169 -0.462473 0.180114 - -0.515981 -1.67269 -0.0168952 - -0.513738 -1.79339 -0.0159487 - -0.469772 -2.14931 0.00717628 - -0.461529 -2.15153 0.0116589 - -0.452494 -2.14982 0.0165818 - -0.402734 -2.16105 0.0436462 - -0.359836 -2.16123 0.0669997 - -0.316887 -2.22208 0.0902431 - -0.225963 -2.26967 0.139635 - -0.14558 -2.24229 0.183459 - 0.106292 -2.28462 0.320485 - 0.0392893 -0.344502 0.288426 - 0.0456864 -0.341976 0.291914 - 0.0537569 -0.354249 0.29628 - 0.0616593 -0.333348 0.30063 - 0.065978 -0.334026 0.302979 - 0.0822493 -0.33652 0.311832 - 0.102191 -0.347273 0.322664 - 0.142379 -0.361614 0.34451 - 0.143763 -0.360805 0.345266 - 0.220783 -0.359593 0.387199 - 0.268708 -0.412195 0.413171 - 0.301162 -0.427082 0.430805 - 0.318734 -0.434863 0.440353 - 0.324218 -0.387627 0.443446 - 0.369504 -0.423575 0.468019 - 0.383355 -0.419883 0.475568 - 0.378446 -0.411158 0.472916 - 0.445156 -0.409188 0.509237 - 0.459647 -0.410642 0.517123 - 0.520849 -0.414473 0.550434 - 0.556979 -0.413607 0.570106 - 0.577502 -0.41193 0.581282 - 0.624109 -0.384996 0.606717 - 1.34332 -0.746986 0.997443 - 1.55967 -0.846285 1.115 - 1.5819 -0.810114 1.12718 - 1.62519 -0.661579 1.15109 - 1.65176 -0.662943 1.16555 - 1.73506 -0.666791 1.21089 - 1.8422 -0.666627 1.26922 - 2.05789 -0.66521 1.38665 - 2.20369 -0.664453 1.46603 - 2.2581 -0.668632 1.49564 - 2.40618 -0.635504 1.57633 - 2.40224 -0.571451 1.57433 - 2.4077 -0.485248 1.5775 - 2.40526 -0.142702 1.57695 - 3.68077 -0.107274 2.27144 - 3.6818 0.0214537 2.27229 - 3.68243 0.187137 2.27301 - 3.6547 0.424431 2.25845 - 3.54554 0.48356 2.19916 - 3.55386 0.52075 2.20377 - 3.53899 0.699478 2.19609 - 2.44945 0.536061 1.60255 - 1.65468 0.4682 1.16972 - 2.11237 0.686879 1.41939 - 1.63358 0.687118 1.15873 - 1.46922 0.67824 1.06923 - 0.360379 0.243159 0.46457 - 0.356587 0.250687 0.462522 - 0.351411 0.254736 0.459714 - 0.350419 0.264206 0.459195 - 0.354088 0.285317 0.461241 - 0.351751 0.308307 0.460021 - 0.308984 0.341162 0.436813 - 0.307672 0.342795 0.436102 - 0.293088 0.376728 0.42824 - 0.288735 0.388129 0.425896 - 0.283758 0.436164 0.423296 - 0.274261 0.442024 0.418139 - 0.263805 0.463055 0.412494 - 0.250891 0.536293 0.40563 - 0.248141 0.552981 0.404171 - 0.255891 0.654135 0.408621 - 0.352976 1.05637 0.462391 - 0.354735 1.10287 0.463454 - 0.364472 1.26068 0.469115 - 0.255812 1.26937 0.409979 - 0.216544 1.27863 0.388622 - 0.135451 1.16442 0.344213 - 0.131243 1.16716 0.341929 - 0.0594898 1.17842 0.302891 - 0.0247497 1.21987 0.284073 - -0.0127068 1.21496 0.26367 - -0.121629 1.17846 0.204288 - -0.165662 1.2018 0.180369 - -0.251774 1.20473 0.133495 - -0.256388 1.20358 0.130981 - -0.261884 1.16007 0.12789 - -0.270553 1.15666 0.123162 - -0.364407 1.27447 0.0723349 - -0.424557 1.2759 0.0395916 - -0.491155 1.27317 0.00332853 - -0.485992 1.07138 0.00568014 - -0.490272 0.798653 0.00272915 - -0.49191 0.786522 0.00180966 - -0.490784 0.7422 0.00232184 - -0.487795 0.63852 0.00371283 - -0.488121 0.585125 0.00341365 - -0.367195 -0.401543 0.0623538 - -0.363216 -0.400418 0.0645758 - -0.356454 -0.406489 0.0683337 - -0.315088 -0.403184 0.091415 - -0.308121 -0.400712 0.0953066 - -0.225041 -0.399104 0.141652 - -0.210526 -0.398192 0.14975 - -0.206856 -0.407249 0.151777 - -0.189787 -0.403653 0.161306 - -0.152238 -0.405688 0.182246 - -0.492528 -2.14433 -0.0115472 - -0.416822 -2.15421 0.0306588 - -0.295745 -2.2022 0.0980847 - -0.193756 -2.20386 0.154969 - -0.185356 -2.20471 0.159653 - 0.104486 -2.27065 0.321173 - 0.121785 -2.26934 0.330826 - 0.0429099 -0.338386 0.291252 - 0.0679178 -0.334119 0.305211 - 0.0995068 -0.342631 0.322811 - 0.174448 -0.370134 0.36455 - 0.175429 -0.364767 0.36511 - 0.18052 -0.367037 0.367944 - 0.218403 -0.365173 0.389079 - 0.296789 -0.427909 0.432658 - 0.308371 -0.388889 0.439209 - 0.38466 -0.40582 0.481723 - 0.429045 -0.412109 0.506466 - 0.437323 -0.404907 0.5111 - 0.598753 -0.416681 0.601117 - 0.603478 -0.399173 0.603793 - 1.51233 -0.853986 1.1097 - 1.54597 -0.787274 1.12862 - 1.54037 -0.738428 1.12561 - 1.54876 -0.670041 1.13045 - 2.41131 -0.551643 1.61184 - 2.40498 -0.462591 1.60851 - 2.40687 -0.3885 1.60974 - 2.39812 -0.179481 1.60534 - 3.59171 -0.159491 2.27116 - 3.59229 0.0391072 2.27194 - 3.5897 0.255866 2.27099 - 3.54773 0.540997 2.24823 - 1.90091 0.685126 1.32997 - 1.41121 0.689149 1.05683 - 0.369804 0.243198 0.474923 - 0.361475 0.248007 0.470288 - 0.349147 0.267648 0.463456 - 0.343811 0.315052 0.460588 - 0.333866 0.326401 0.455067 - 0.327985 0.326766 0.451788 - 0.30079 0.349951 0.436672 - 0.264193 0.475757 0.416546 - 0.254731 0.558997 0.411459 - 0.345458 0.979735 0.463029 - 0.235672 1.10233 0.402072 - 0.25045 1.27754 0.410717 - 0.224915 1.27817 0.396475 - 0.126029 1.17187 0.341074 - 0.084744 1.16666 0.318033 - 0.0485243 1.16022 0.297815 - 0.0441021 1.16056 0.29535 - -0.156978 1.21112 0.183305 - -0.204473 1.21307 0.156817 - -0.224398 1.16304 0.145588 - -0.424167 1.2806 0.0344278 - -0.468788 1.28045 0.00953785 - -0.47399 1.27914 0.00663346 - -0.494752 1.15968 -0.00522137 - -0.493978 1.0599 -0.00501803 - -0.488379 1.0362 -0.0019491 - -0.488075 0.89683 -0.00209889 - -0.489171 0.839627 -0.00284126 - -0.489659 0.779232 -0.00325167 - -0.48754 0.761422 -0.00211018 - -0.487182 0.682028 -0.00209251 - -0.49121 0.561607 -0.00461522 - -0.344311 -0.404148 0.0706334 - -0.329683 -0.403196 0.0789971 - -0.31595 -0.40625 0.0868398 - -0.300206 -0.409384 0.0958325 - -0.281485 -0.406969 0.106539 - -0.263655 -0.404453 0.116737 - -0.216595 -0.404129 0.143638 - -0.172164 -0.402716 0.169039 - -0.16166 -0.403442 0.175041 - -0.16045 -0.405077 0.175729 - -0.148754 -0.406994 0.18241 - -0.15887 -0.464365 0.176495 - -0.440597 -2.15488 0.0115616 - -0.356891 -2.1632 0.0593901 - -0.286224 -2.20456 0.0996894 - -0.271743 -2.22699 0.107915 - -0.224247 -2.26967 0.134966 - -0.144018 -2.22832 0.180921 - -0.130224 -2.29439 0.188654 - -0.104139 -2.29588 0.203561 - -0.0249046 -0.416967 0.253181 - -0.0152711 -0.428958 0.25866 - 0.153277 -2.24428 0.350822 - 0.170017 -2.23948 0.360402 - 0.178498 -2.23851 0.365252 - 0.0256758 -0.343911 0.282262 - 0.0444545 -0.329611 0.293029 - 0.0616088 -0.340092 0.30281 - 0.0612353 -0.332941 0.302613 - 0.0798737 -0.330347 0.313273 - 0.101333 -0.350987 0.325492 - 0.120755 -0.352241 0.336591 - 0.134019 -0.368256 0.344136 - 0.134228 -0.349144 0.3443 - 0.155444 -0.357568 0.356408 - 0.16306 -0.354781 0.360768 - 0.216619 -0.365173 0.391359 - 0.280082 -0.390703 0.427576 - 0.283296 -0.391425 0.429412 - 0.352616 -0.421634 0.468966 - 0.355166 -0.417175 0.470434 - 0.399258 -0.408645 0.495658 - 0.407885 -0.406095 0.500595 - 0.483065 -0.413038 0.543553 - 0.50956 -0.411122 0.558702 - 0.591082 -0.393805 0.605341 - 0.631974 -0.386357 0.628732 - 1.49833 -0.823285 1.12295 - 1.50233 -0.751896 1.1254 - 1.5441 -0.663234 1.14948 - 1.60798 -0.662578 1.186 - 1.81507 -0.664827 1.30436 - 1.9281 -0.662964 1.36898 - 2.10272 -0.664743 1.46879 - 2.13542 -0.66336 1.48748 - 2.39292 -0.665166 1.63467 - 2.40208 -0.642007 1.63996 - 2.41002 -0.453831 1.64493 - 2.40706 -0.366052 1.64344 - 2.4027 -0.19315 1.64135 - 2.40405 -0.168784 1.64218 - 2.55226 -0.0366442 1.7272 - 2.54968 0.0279904 1.72587 - 2.54411 0.234699 1.72317 - 2.54396 0.338812 1.72332 - 2.54264 0.351701 1.7226 - 2.54056 0.469569 1.72168 - 1.66859 0.441926 1.22318 - 1.25058 0.67678 0.984785 - 0.379209 0.240444 0.485692 - 0.372007 0.241167 0.481577 - 1.25242 0.86591 0.986272 - 1.27062 0.904783 0.996767 - 0.337073 0.273508 0.461683 - 0.32868 0.323895 0.457001 - 0.299878 0.345359 0.440587 - 0.294669 0.348786 0.437618 - 0.291944 0.367585 0.436103 - 0.289144 0.370719 0.43451 - 0.284403 0.388129 0.43184 - 0.279245 0.398737 0.428916 - 0.271896 0.432863 0.424794 - 0.260009 0.459187 0.41806 - 0.253944 0.523436 0.414741 - 0.24973 0.620846 0.412557 - 0.247254 0.688604 0.411298 - 0.321094 0.910009 0.454016 - 0.346053 1.1674 0.468876 - 0.238339 0.938326 0.406777 - 0.232753 0.946636 0.403603 - 0.231288 0.971188 0.402822 - 0.230791 0.984918 0.40257 - 0.229953 0.997701 0.40212 - 0.149467 1.18566 0.356546 - 0.134019 1.17331 0.347688 - 0.126967 1.18968 0.343694 - 0.0810694 1.24333 0.317582 - 0.0482956 1.1702 0.29868 - -0.0181474 1.24499 0.260872 - -0.0228636 1.245 0.258176 - -0.181619 1.15546 0.167223 - -0.211494 1.17286 0.150187 - -0.270981 1.16831 0.116172 - -0.40506 1.27802 0.0397837 - -0.48723 1.27501 -0.007193 - -0.491372 1.27082 -0.00957012 - -0.483922 0.948887 -0.00605294 - -0.491053 0.823348 -0.0104185 - -0.488456 0.739049 -0.00912857 - -0.486866 0.678909 -0.008358 - -0.491202 0.600067 -0.0110179 - -0.493962 0.593112 -0.0126118 - -0.494098 0.57793 -0.0127246 - -0.357794 -0.401412 0.0582958 - -0.341227 -0.405772 0.0679833 - -0.311639 -0.398652 0.0853196 - -0.281833 -0.405653 0.102751 - -0.275202 -0.402629 0.106639 - -0.273176 -0.403102 0.107824 - -0.231428 -0.40284 0.132263 - -0.227293 -0.406862 0.134674 - -0.220115 -0.404748 0.13888 - -0.209268 -0.394611 0.145253 - -0.208862 -0.406248 0.145464 - -0.179457 -0.404156 0.162682 - -0.172453 -0.400118 0.166791 - -0.163357 -0.404581 0.172105 - -0.154126 -0.398079 0.177524 - -0.148359 -0.406994 0.180879 - -0.508523 -1.74845 -0.0330581 - -0.330393 -2.22594 0.0701069 - -0.322007 -2.22749 0.0750125 - -0.224068 -2.27762 0.132227 - -0.0354376 -0.440672 0.246901 --0.00346274 -0.451554 0.265593 - 0.152459 -2.25125 0.352694 - 0.159724 -2.23543 0.356984 - 0.168139 -2.2345 0.361912 - 0.0333131 -0.354485 0.287346 - 0.0587854 -0.337608 0.302295 - 0.0737407 -0.336594 0.311052 - 0.0820552 -0.340729 0.315909 - 0.131839 -0.362085 0.345002 - 0.144271 -0.35922 0.352286 - 0.162901 -0.360867 0.363187 - 0.164257 -0.359935 0.363983 - 0.179231 -0.363333 0.372741 - 0.200649 -0.365974 0.385272 - 0.215525 -0.369575 0.393971 - 0.279699 -0.386182 0.431498 - 0.296359 -0.397001 0.441225 - 0.377095 -0.414525 0.488445 - 0.405639 -0.40673 0.505172 - 0.446061 -0.407035 0.528832 - 0.515692 -0.406929 0.569593 - 0.569083 -0.405981 0.600848 - 0.581049 -0.389901 0.60789 - 0.582509 -0.386854 0.608752 - 0.682255 -0.41882 0.667066 - 1.46403 -0.828105 1.12374 - 1.45959 -0.735345 1.12136 - 1.46506 -0.720351 1.1246 - 1.49064 -0.661959 1.1397 - 1.58736 -0.658248 1.19633 - 1.64777 -0.664056 1.23168 - 1.83266 -0.665064 1.33991 - 2.08308 -0.662645 1.4865 - 2.30528 -0.669858 1.61655 - 2.41102 -0.545574 1.67873 - 2.40884 -0.456392 1.67766 - 2.40938 -0.368648 1.67818 - 2.40242 -0.28069 1.67431 - 2.40441 -0.256175 1.67554 - 2.48495 -0.111979 1.72302 - 2.48534 -0.0993076 1.72327 - 2.48338 -0.0738831 1.72218 - 2.48467 -0.0485721 1.723 - 2.48411 -0.0105575 1.72276 - 2.48531 0.14163 1.72381 - 2.48102 0.192168 1.72142 - 2.48375 0.217838 1.72308 - 2.48634 0.230819 1.72462 - 2.48362 0.307227 1.72321 - 2.47818 0.34496 1.72011 - 2.48002 0.383764 1.72128 - 2.47939 0.396544 1.72094 - 2.48214 0.409884 1.72258 - 2.48738 0.475659 1.7258 - 1.87388 0.47857 1.36668 - 2.00509 0.686447 1.44397 - 1.08141 0.638544 0.90317 - 0.365401 0.251477 0.483143 - 1.26678 0.990155 1.01249 - 0.345687 0.290153 0.471693 - 0.329903 0.293589 0.462461 - 0.316644 0.326398 0.454776 - 0.285297 0.375276 0.43654 - 0.28388 0.376824 0.435714 - 0.282456 0.378365 0.434884 - 0.277258 0.402518 0.431897 - 0.268241 0.450548 0.42673 - 0.265852 0.455076 0.425342 - 0.261182 0.460213 0.42262 - 0.249067 0.507887 0.415639 - 0.244265 0.540243 0.412903 - 0.248976 0.56698 0.415723 - 0.245411 0.615486 0.413749 - 0.341298 1.05822 0.470904 - 0.342131 1.21252 0.471749 - 0.236994 1.28118 0.410364 - 0.227333 1.28376 0.404715 - 0.146222 1.17283 0.356978 - 0.128528 1.17606 0.346628 - 0.126062 1.23103 0.345312 - 0.116784 1.23248 0.339884 - -0.036298 1.16589 0.250121 - -0.0541076 1.17442 0.239716 - -0.104915 1.20321 0.210041 - -0.141697 1.16079 0.188412 - -0.16074 1.21044 0.17738 - -0.173651 1.16691 0.169722 - -0.254254 1.20748 0.122633 - -0.371318 1.27864 0.0542724 - -0.392169 1.27708 0.0420636 - -0.446398 1.27678 0.0103188 - -0.467179 1.27265 -0.0018554 - -0.472293 1.27131 -0.00485212 - -0.487384 1.0789 -0.0141317 - -0.491039 1.03061 -0.0163829 - -0.493093 0.915729 -0.0178513 - -0.487391 0.887005 -0.0145805 - -0.488661 0.855482 -0.0153969 - -0.490399 0.842325 -0.0164446 - -0.485868 0.7736 -0.0139517 - -0.488028 0.75592 -0.0152569 - -0.485145 0.711193 -0.0136729 - -0.485405 0.611606 -0.0140559 - -0.348056 -0.402134 0.0595066 - -0.336991 -0.405906 0.0661267 - -0.283139 -0.402202 0.0983975 - -0.275554 -0.40505 0.102935 - -0.257547 -0.401549 0.11373 - -0.241092 -0.406981 0.123576 - -0.234885 -0.403247 0.127303 - -0.176298 -0.402218 0.162404 - -0.170249 -0.405312 0.166021 - -0.160599 -0.3981 0.171819 - -0.151839 -0.413852 0.17703 - -0.1496 -0.41799 0.178362 - -0.507519 -1.98926 -0.0397267 - -0.385707 -2.15509 0.0328632 - -0.354285 -2.16812 0.0516572 - -0.230588 -2.26464 0.125538 - -0.0355809 -0.436675 0.246626 - -0.0287508 -0.419906 0.250757 - -0.0193458 -0.414994 0.256403 - -0.0177925 -0.414981 0.257333 - 0.0294291 -0.404724 0.285647 - 0.0313001 -0.354755 0.286885 - 0.0335408 -0.343109 0.288254 - 0.0552318 -0.343627 0.301248 - 0.0572647 -0.334714 0.302487 - 0.0610151 -0.333488 0.304736 - 0.0657412 -0.330807 0.307574 - 0.0855631 -0.33672 0.319435 - 0.097882 -0.342957 0.326801 - 0.105391 -0.355586 0.33127 - 0.120508 -0.357688 0.340321 - 0.12958 -0.363754 0.345742 - 0.143136 -0.352266 0.35389 - 0.161914 -0.354712 0.365134 - 0.216155 -0.369978 0.397594 - 0.246626 -0.381548 0.415821 - 0.266879 -0.389144 0.427937 - 0.268331 -0.387675 0.428811 - 0.285014 -0.395836 0.438786 - 0.393741 -0.405247 0.503901 - 0.420647 -0.412735 0.520003 - 0.423715 -0.408224 0.521851 - 0.430146 -0.406742 0.525707 - 0.530393 -0.408954 0.585759 - 1.50377 -0.663051 1.16831 - 1.90995 -0.664947 1.41164 - 2.11069 -0.663876 1.5319 - 2.19117 -0.664887 1.58012 - 2.24021 -0.667375 1.60949 - 2.33847 -0.670889 1.66834 - 2.40749 -0.560973 1.70995 - 2.40049 -0.344545 1.70626 - 2.41245 -0.271099 1.7136 - 2.41244 -0.146625 1.71388 - 2.42993 0.151862 1.72506 - 2.42216 0.238818 1.7206 - 2.42472 0.301859 1.72229 - 2.42355 0.314301 1.72162 - 2.42638 0.377858 1.72346 - 2.41401 0.541303 1.71643 - 2.2287 0.535813 1.6054 - 2.1815 0.666374 1.57743 - 2.13409 0.687285 1.54907 - 2.00161 0.689533 1.46971 - 1.93067 0.686984 1.4272 - 1.53302 0.67036 1.18894 - 1.40166 0.680501 1.11027 - 1.4376 0.715104 1.13188 - 1.63926 0.823895 1.25294 - 1.24843 0.692056 1.01849 - 1.22783 0.712096 1.0062 - 0.396069 0.276111 0.506885 - 1.18088 0.947731 0.978621 - 1.29514 1.09748 1.04742 - 0.304168 0.330929 0.451956 - 0.299059 0.349454 0.448938 - 0.293865 0.352939 0.445834 - 0.285661 0.365444 0.440948 - 0.278857 0.386648 0.436922 - 0.281482 0.403994 0.438535 - 0.277222 0.42004 0.43602 - 0.271398 0.423015 0.432538 - 0.259577 0.469612 0.425565 - 0.257645 0.479658 0.424431 - 0.252231 0.483885 0.421197 - 0.253599 0.510207 0.422078 - 0.245899 0.536668 0.417527 - 0.248138 0.575361 0.418958 - 0.324148 0.965836 0.465405 - 0.324977 1.05804 0.466117 - 0.327514 1.18881 0.467942 - 0.23786 1.11744 0.414065 - 0.199153 1.27703 0.391248 - 0.179532 1.2784 0.379496 - 0.0695239 1.24133 0.313505 - 0.0235558 1.26084 0.286012 - -0.0189674 1.25099 0.260514 - -0.104877 1.2042 0.208937 - -0.165359 1.17632 0.172638 - -0.194442 1.1903 0.155248 - -0.201832 1.20912 0.150864 - -0.22703 1.16594 0.135668 - -0.247079 1.19985 0.123736 - -0.420554 1.28813 0.0200144 - -0.440381 1.28171 0.00812136 - -0.495004 1.2338 -0.0247147 - -0.488923 1.12458 -0.021326 - -0.486273 1.09379 -0.0198103 - -0.488314 0.796437 -0.0217263 - -0.489668 0.671834 -0.022828 - -0.486947 0.60081 -0.0213633 - -0.488518 0.592375 -0.0223243 - -0.491753 0.570991 -0.0243123 - -0.346443 -0.402859 0.0544635 - -0.343436 -0.406175 0.0563127 - -0.291614 -0.403097 0.0883238 - -0.286064 -0.405629 0.0917453 - -0.28304 -0.408325 0.0936069 - -0.247746 -0.402125 0.115418 - -0.240491 -0.400521 0.119902 - -0.18849 -0.402802 0.152011 - -0.159294 -0.396248 0.170057 - -0.154841 -0.449499 0.172682 - -0.512067 -1.78365 -0.0510663 - -0.504653 -1.89736 -0.0467553 - -0.510172 -2.08378 -0.050602 - -0.449643 -2.1525 -0.0133822 - -0.43364 -2.15683 -0.00350952 - -0.417606 -2.16099 0.00638293 - -0.390475 -2.14929 0.0231658 - -0.251745 -2.23442 0.108641 - -0.243446 -2.23558 0.113763 - -0.159702 -2.23595 0.16548 - -0.0260545 -0.420967 0.252284 - 0.0434108 -0.324079 0.295411 - 0.0576979 -0.330054 0.30422 - 0.0655268 -0.329407 0.309057 - 0.0826709 -0.33632 0.319628 - 0.0860615 -0.338046 0.321718 - 0.117267 -0.36185 0.340934 - 0.122005 -0.361493 0.343861 - 0.153446 -0.370689 0.363256 - 0.15892 -0.36704 0.366645 - 0.161256 -0.353777 0.368119 - 0.27519 -0.386924 0.438404 - 0.326539 -0.430574 0.470012 - 0.323796 -0.419799 0.468344 - 0.456862 -0.411734 0.55054 - 0.477637 -0.410254 0.563374 - 0.519501 -0.412374 0.589223 - 0.562054 -0.383557 0.61557 - 0.630671 -0.41123 0.657881 - 1.32865 -0.833227 1.08794 - 1.38467 -0.708548 1.12283 - 1.38639 -0.667095 1.12399 - 1.57186 -0.661579 1.23854 - 1.5968 -0.662614 1.25394 - 1.64195 -0.66203 1.28183 - 2.05501 -0.663432 1.53692 - 2.40631 -0.643466 1.75392 - 2.40405 -0.385894 1.75313 - 2.4083 -0.260351 1.75605 - 2.39382 -0.196464 1.74725 - 2.38832 -0.0103029 1.7443 - 2.38125 0.0390304 1.74004 - 2.38499 0.100856 1.7425 - 2.37907 0.348647 1.73942 - 2.09704 0.520077 1.56566 - 1.72312 0.513155 1.33472 - 2.1613 0.677832 1.60572 - 1.64608 0.676978 1.28753 - 1.64708 0.844992 1.28854 - 1.26241 0.673839 1.05058 - 1.12299 0.763249 0.964681 - 1.24004 0.965633 1.03745 - 1.23864 1.01131 1.03669 - 1.20937 1.08342 1.01878 - 0.30346 0.3276 0.457542 - 0.278108 0.396412 0.442047 - 0.264705 0.41377 0.433811 - 0.262395 0.445083 0.432458 - 0.255544 0.442358 0.42822 - 0.256 0.472684 0.428573 - 0.24866 0.491692 0.424084 - 0.24556 0.587782 0.422396 - 0.253361 0.713644 0.42751 - 0.316774 1.0431 0.467446 - 0.242534 1.28143 0.422158 - 0.237773 1.28278 0.41922 - 0.191752 1.27618 0.390784 - 0.187011 1.27727 0.387859 - 0.146868 1.16901 0.362813 - 0.036905 1.17086 0.294907 - 0.00650133 1.17448 0.27614 - -0.0457165 1.1687 0.243878 - -0.0654864 1.23701 0.231829 - -0.110991 1.22869 0.203707 - -0.115551 1.22823 0.20089 - -0.165186 1.18028 0.170124 - -0.176481 1.16416 0.163111 - -0.231246 1.17076 0.129305 - -0.256711 1.23286 0.113725 - -0.25736 1.18756 0.113217 - -0.259603 1.17564 0.111804 - -0.260559 1.15789 0.111172 - -0.347534 1.28262 0.0577518 - -0.377566 1.27792 0.039194 - -0.455475 1.2864 -0.00890061 - -0.479568 1.27593 -0.0238038 - -0.493049 1.26697 -0.032151 - -0.486404 1.20586 -0.0281908 - -0.489811 1.20075 -0.0303068 - -0.489417 1.1213 -0.0302499 - -0.489765 1.05159 -0.0306291 - -0.488449 0.780253 -0.0304537 - -0.488724 0.725561 -0.0307526 - -0.483852 0.674205 -0.0278642 - -0.489097 0.635198 -0.0311952 - -0.490457 0.604358 -0.0321073 - -0.488661 0.596796 -0.0310162 - -0.349737 -0.405527 0.0478139 - -0.340949 -0.401606 0.0533745 - -0.338312 -0.401784 0.0550397 - -0.328728 -0.399981 0.0610973 - -0.325762 -0.403131 0.0629634 - -0.315906 -0.404034 0.0691863 - -0.307067 -0.402418 0.0747729 - -0.30396 -0.401577 0.0767372 - -0.300984 -0.404472 0.0786105 - -0.264779 -0.403195 0.101481 - -0.238099 -0.397996 0.118345 - -0.223001 -0.404276 0.127867 - -0.196345 -0.401096 0.144711 - -0.179263 -0.404258 0.155493 - -0.168264 -0.403474 0.162442 - -0.166773 -0.404225 0.163382 - -0.487502 -2.14388 -0.0433135 - -0.463529 -2.14996 -0.028186 - -0.430988 -2.15488 -0.00764421 - -0.356382 -2.1546 0.0394796 - -0.166227 -2.21727 0.159438 - -0.0201834 -0.417994 0.255939 --0.00670043 -0.450638 0.264378 --0.00488399 -0.454552 0.265516 - 0.0912317 -2.28722 0.32189 - 0.0996677 -2.28662 0.32722 - 0.142455 -2.29196 0.354233 - 0.169421 -2.20966 0.37146 - 0.0268167 -0.373558 0.285731 - 0.0807872 -0.333502 0.319915 - 0.0853856 -0.330395 0.322827 - 0.102731 -0.351251 0.333733 - 0.119484 -0.366592 0.344279 - 0.12983 -0.359632 0.35083 - 0.13224 -0.353696 0.352366 - 0.154811 -0.365359 0.366595 - 0.159697 -0.364312 0.369684 - 0.204305 -0.367908 0.397851 - 0.221859 -0.355723 0.408967 - 0.227706 -0.357819 0.412655 - 0.255186 -0.38672 0.429943 - 0.292052 -0.40833 0.453178 - 0.297561 -0.411863 0.456649 - 0.355773 -0.419692 0.493399 - 0.451976 -0.414183 0.554176 - 0.533279 -0.38239 0.605605 - 1.35581 -0.75826 1.12425 - 1.3537 -0.697513 1.12306 - 1.35781 -0.691189 1.12567 - 1.38277 -0.661349 1.1415 - 1.43016 -0.666362 1.17143 - 1.44445 -0.664228 1.18046 - 1.5447 -0.663673 1.24378 - 2.1642 -0.666635 1.63506 - 2.40039 -0.400545 1.78488 - 2.40588 -0.350481 1.78846 - 2.40356 -0.198535 1.78736 - 2.40308 -0.0354697 1.78744 - 2.40513 0.431324 1.78984 - 1.93672 0.494434 1.49413 - 2.0006 0.609737 1.53475 - 2.06943 0.688332 1.57841 - 1.97237 0.689813 1.51711 - 1.53651 0.691248 1.24181 - 1.45266 0.724539 1.18893 - 1.6587 0.856459 1.31938 - 0.353756 0.229718 0.493661 - 1.23843 0.863083 1.05394 - 1.24364 0.884204 1.05729 - 1.23693 1.07493 1.0535 - 1.25413 1.1098 1.06444 - 1.28578 1.33667 1.08497 - 1.27586 1.35014 1.07874 - 0.28409 0.366719 0.449983 - 0.283876 0.379504 0.449878 - 0.280149 0.37818 0.44752 - 0.271427 0.415448 0.4421 - 0.261875 0.443617 0.436133 - 0.260234 0.445083 0.4351 - 0.254839 0.474328 0.431761 - 0.243374 0.575361 0.424759 - 0.246473 0.588159 0.426746 - 0.266114 0.735263 0.4395 - 0.253453 0.727823 0.431486 - 0.296639 0.851698 0.459056 - 0.311099 0.922752 0.468357 - 0.25507 0.958994 0.433054 - 0.241581 0.939067 0.424487 - 0.233742 0.967288 0.419602 - 0.241075 1.28434 0.424984 - 0.163113 1.22726 0.375606 - 0.146407 1.17591 0.364933 - 0.0399287 1.16056 0.297642 - -0.0199342 1.24299 0.260026 - -0.0548522 1.17842 0.237818 - -0.147972 1.18995 0.179028 - -0.224466 1.163 0.130649 - -0.249161 1.1987 0.115135 - -0.264322 1.15957 0.105467 - -0.460698 1.27635 -0.018293 - -0.4898 1.22136 -0.0368045 - -0.492503 1.18686 -0.0385939 - -0.49138 1.08395 -0.038128 - -0.485639 1.04805 -0.0345864 - -0.481099 0.974806 -0.031892 - -0.486788 0.957224 -0.0355271 - -0.488877 0.905805 -0.036968 - -0.492211 0.903394 -0.03908 - -0.484206 0.690682 -0.0345264 - -0.486747 0.688296 -0.0361371 - -0.488954 0.67332 -0.0375668 - -0.283322 -0.401895 0.0859506 - -0.267467 -0.402293 0.0961962 - -0.260119 -0.401176 0.100947 - -0.25478 -0.399521 0.104402 - -0.24555 -0.402125 0.110361 - -0.228368 -0.400918 0.121467 - -0.225851 -0.403901 0.123087 - -0.207794 -0.398986 0.134768 - -0.173895 -0.401306 0.15667 - -0.161927 -0.402008 0.164403 - -0.150291 -0.413852 0.171894 - -0.507981 -1.90251 -0.0628114 - -0.428415 -2.15391 -0.0119899 - -0.291605 -2.17112 0.0763841 - -0.102845 -2.28889 0.198092 - -0.0346439 -0.428749 0.246597 - -0.0251738 -0.421986 0.252734 - -0.0142691 -0.425891 0.259772 - 0.0242864 -0.41934 0.284704 - 0.0261672 -0.422066 0.285913 - 0.0262616 -0.374546 0.286087 - 0.0338757 -0.34352 0.291082 - 0.0392916 -0.32376 0.294629 - 0.0416614 -0.323106 0.296162 - 0.0666126 -0.330404 0.31227 - 0.0834047 -0.327595 0.323129 - 0.0864192 -0.328343 0.325075 - 0.106738 -0.352956 0.338148 - 0.113094 -0.361646 0.342234 - 0.125823 -0.361186 0.350462 - 0.136975 -0.360051 0.357672 - 0.137105 -0.356572 0.357764 - 0.169599 -0.358275 0.378759 - 0.194125 -0.367611 0.394587 - 0.224608 -0.369177 0.414284 - 0.257683 -0.389845 0.43561 - 0.327364 -0.419416 0.480571 - 0.343438 -0.412696 0.490975 - 0.39031 -0.411669 0.521269 - 0.513517 -0.390365 0.600944 - 0.553826 -0.383557 0.62701 - 1.31271 -0.843423 1.11635 - 1.31883 -0.829525 1.12034 - 1.3203 -0.804064 1.12135 - 1.32085 -0.735678 1.12187 - 1.6701 -0.662755 1.34775 - 1.7229 -0.663398 1.38187 - 2.37367 -0.669483 1.80242 - 2.40426 -0.429651 1.82277 - 2.406 0.0778309 1.8251 - 2.40951 0.103243 1.82742 - 2.40194 0.166053 1.82268 - 2.40984 0.255553 1.828 - 2.40288 0.344014 1.82372 - 2.12506 0.687469 1.64499 - 1.9475 0.685886 1.53023 - 1.25028 0.684537 1.07964 - 1.2452 0.697746 1.07639 - 1.23962 0.734925 1.07287 - 1.18927 0.745093 1.04036 - 0.376663 0.250846 0.514027 - 1.24458 0.926963 1.07654 - 1.16143 1.25072 1.02357 - 0.279567 0.370589 0.451563 - 0.274141 0.390352 0.448104 - 0.269659 0.401758 0.445234 - 0.267919 0.410107 0.444129 - 0.251411 0.450859 0.433558 - 0.245155 0.512452 0.429662 - 0.24042 0.544957 0.426679 - 0.278371 0.799875 0.451812 - 0.305114 0.92447 0.469392 - 0.306844 1.02816 0.470757 - 0.25199 1.27529 0.435896 - 0.203091 1.27766 0.404299 - 0.0577517 1.18299 0.310147 - -0.0502895 1.16058 0.240271 - -0.0734777 1.20557 0.225392 - -0.175407 1.16515 0.159423 - -0.200086 1.21405 0.143591 - -0.248975 1.20358 0.111971 - -0.26352 1.16152 0.102471 - -0.293216 1.21341 0.0834029 - -0.374302 1.27982 0.0311582 - -0.488804 1.24019 -0.0429341 - -0.490874 1.21712 -0.0443267 - -0.489024 1.15852 -0.0432713 - -0.494049 0.921187 -0.0470834 - -0.486267 0.879872 -0.0421531 - -0.489975 0.791715 -0.0447589 - -0.494017 0.703157 -0.0475825 - -0.313302 -0.404792 0.0624027 - -0.302034 -0.403116 0.06985 - -0.268658 -0.402629 0.0918994 - -0.265714 -0.405186 0.0938379 - -0.203873 -0.396438 0.13471 - -0.204912 -0.407129 0.133998 - -0.18594 -0.406356 0.146533 - -0.173933 -0.40313 0.154472 - -0.47543 -2.15209 -0.0488854 - -0.180812 -2.21169 0.145593 - -0.110762 -2.28344 0.191695 - -0.0314445 -0.411866 0.248577 - -0.0270374 -0.421967 0.251464 - 0.176556 -2.23352 0.381614 - 0.0302339 -0.422263 0.289297 - 0.0280396 -0.352784 0.288014 - 0.0381687 -0.321809 0.294779 - 0.0564678 -0.335827 0.306834 - 0.0780815 -0.335911 0.321111 - 0.0784419 -0.332562 0.321357 - 0.0808584 -0.331491 0.322956 - 0.129191 -0.360631 0.354814 - 0.133114 -0.358216 0.357411 - 0.151368 -0.364491 0.369455 - 0.20858 -0.360774 0.407257 - 0.220466 -0.372517 0.415081 - 0.255587 -0.383149 0.438256 - 0.278867 -0.407918 0.453575 - 0.306296 -0.418526 0.471669 - 0.318845 -0.41232 0.479974 - 0.34919 -0.415012 0.500012 - 0.363865 -0.416531 0.509703 - 0.379956 -0.41887 0.520327 - 0.454276 -0.410896 0.569441 - 0.484481 -0.413219 0.589389 - 0.5382 -0.383582 0.624946 - 1.28291 -0.839005 1.1158 - 1.28972 -0.817075 1.12035 - 1.29265 -0.708576 1.12255 - 1.28857 -0.689971 1.1199 - 1.29839 -0.662445 1.12645 - 1.3473 -0.66186 1.15876 - 1.43863 -0.661959 1.21909 - 1.76772 -0.664472 1.43648 - 1.84604 -0.661548 1.48822 - 1.87807 -0.662098 1.50938 - 2.09123 -0.664961 1.65018 - 2.40696 -0.629961 1.85884 - 2.40998 -0.577689 1.86095 - 2.40515 -0.265253 1.85851 - 2.40446 -0.22683 1.85815 - 2.40087 -0.0739594 1.85614 - 2.40991 0.00211862 1.8623 - 2.41234 0.34768 1.86473 - 1.64656 0.482118 1.35919 - 1.56435 0.684987 1.30537 - 1.58299 0.819198 1.318 - 1.27573 0.678605 1.1147 - 1.26027 0.678537 1.10448 - 1.24493 0.734882 1.09448 - 1.1954 0.770256 1.06185 - 1.25032 0.874449 1.09838 - 1.24587 0.934287 1.09558 - 1.24307 1.04555 1.094 - 1.25274 1.12401 1.10057 - 1.24861 1.20463 1.09804 - 1.06382 1.22879 0.976031 - 1.08809 1.31237 0.992259 - 0.271007 0.385852 0.450286 - 0.262122 0.412347 0.44448 - 0.260732 0.42146 0.443583 - 0.250039 0.456342 0.436603 - 0.249333 0.481312 0.436196 - 0.264171 0.717205 0.446564 - 0.29241 0.97795 0.465843 - 0.236168 0.977383 0.428689 - 0.24981 1.27529 0.438415 - 0.221853 1.28346 0.419966 - 0.186608 1.27716 0.396669 - 0.142996 1.17296 0.36761 - 0.125859 1.21167 0.356382 - 0.0515792 1.16845 0.30721 --0.00373624 1.17674 0.270689 - -0.0119184 1.2189 0.265385 - -0.0207749 1.22899 0.259559 - -0.0336585 1.16895 0.250904 - -0.0766913 1.17834 0.2225 - -0.161403 1.23918 0.166686 - -0.178765 1.16237 0.155033 - -0.223433 1.1679 0.125539 - -0.265941 1.15735 0.0974334 - -0.424784 1.28008 -0.00720242 - -0.483483 1.27764 -0.0459842 - -0.492713 1.24323 -0.0521635 - -0.487819 1.112 -0.0492452 - -0.486108 1.07264 -0.0482092 - -0.489357 1.03552 -0.0504446 - -0.488945 0.972845 -0.0503228 - -0.487624 0.941356 -0.0495254 - -0.488594 0.880842 -0.0503114 - -0.489976 0.753611 -0.0515296 - -0.49021 0.747163 -0.0516993 - -0.488136 0.723926 -0.0503852 - -0.490298 0.707949 -0.0518515 - -0.489744 0.70081 -0.0515025 - -0.488088 0.627969 -0.0505835 - -0.489745 0.603206 -0.0517371 - -0.487461 0.579654 -0.0502847 - -0.354614 -0.397354 0.0298655 - -0.353173 -0.399097 0.0308362 - -0.344159 -0.405527 0.0369183 - -0.292331 -0.40202 0.0719866 - -0.239703 -0.407252 0.107574 - -0.234828 -0.409792 0.110866 - -0.22394 -0.400274 0.118255 - -0.216647 -0.39738 0.123195 - -0.213138 -0.402142 0.125557 - -0.19977 -0.401895 0.1346 - -0.196095 -0.401967 0.137086 - -0.192432 -0.401992 0.139564 - -0.180812 -0.399983 0.14743 - -0.517304 -1.71773 -0.0833757 - -0.318749 -2.21705 0.0497332 --0.00541439 -0.436481 0.26599 - 0.184863 -2.25434 0.390316 - 0.02455 -0.420085 0.2863 - 0.0258335 -0.41785 0.287173 - 0.0271018 -0.415609 0.288037 - 0.0290939 -0.34732 0.289549 - 0.0349011 -0.335761 0.293505 - 0.0373251 -0.335137 0.295147 - 0.0435594 -0.334436 0.299366 - 0.0461755 -0.334691 0.301135 - 0.0520816 -0.338007 0.305122 - 0.053302 -0.337608 0.305948 - 0.0539266 -0.329092 0.306391 - 0.0572497 -0.326886 0.308645 - 0.0744764 -0.323168 0.320307 - 0.088432 -0.332761 0.329724 - 0.108809 -0.35708 0.343449 - 0.143891 -0.370714 0.367148 - 0.157872 -0.370341 0.376607 - 0.161891 -0.363914 0.379341 - 0.165991 -0.347729 0.382153 - 0.180496 -0.36733 0.391918 - 0.220994 -0.369959 0.419307 - 0.255586 -0.389901 0.442659 - 0.302739 -0.413902 0.474498 - 0.34369 -0.419574 0.502186 - 0.359432 -0.415194 0.512845 - 0.366764 -0.415783 0.517804 - 0.3841 -0.408244 0.529549 - 0.488499 -0.385332 0.600226 - 0.509579 -0.381979 0.614494 - 1.26109 -0.779793 1.1219 - 1.25597 -0.702197 1.11862 - 1.6484 -0.663693 1.38418 - 2.07141 -0.663691 1.67033 - 2.40512 -0.318918 1.8969 - 2.40286 -0.241245 1.89556 - 2.40578 0.130197 1.89843 - 2.41266 0.48131 1.90393 - 2.41097 0.53383 1.90292 - 2.08264 0.519406 1.68078 - 1.86218 0.559027 1.53174 - 1.98978 0.687696 1.61837 - 1.31771 0.697504 1.16377 - 1.24314 0.731257 1.11341 - 1.24567 0.765896 1.1152 - 1.24349 0.850012 1.11393 - 1.251 0.945272 1.11924 - 1.24069 1.0714 1.11257 - 1.24837 1.09806 1.11783 - 1.24522 1.1572 1.11584 - 1.25399 1.25221 1.122 - 1.25328 1.26273 1.12155 - 0.965121 1.20747 0.926487 - 0.252122 0.427343 0.442289 - 0.252728 0.448143 0.442749 - 0.252893 0.45669 0.442882 - 0.239218 0.605562 0.43399 - 0.237407 0.634737 0.432836 - 0.286975 0.846215 0.466877 - 0.285637 0.883955 0.466063 - 0.28435 0.891116 0.46521 - 0.289439 0.928591 0.468743 - 0.289474 0.940438 0.468795 - 0.241018 0.933458 0.436 - 0.23587 0.970304 0.432607 - 0.235508 1.03017 0.432506 - 0.245549 1.22213 0.439762 - 0.243797 1.28156 0.43872 - 0.228917 1.28083 0.428652 - 0.195889 1.28666 0.406325 - 0.0501766 1.16147 0.307454 - 0.00824736 1.16831 0.279107 - -0.0466681 1.1687 0.24196 - -0.0661948 1.245 0.228935 - -0.0734918 1.20357 0.223899 - -0.183184 1.16846 0.149612 - -0.20253 1.21116 0.136628 - -0.217836 1.16696 0.126168 - -0.221717 1.16398 0.123535 - -0.279016 1.16216 0.08477 - -0.324988 1.28076 0.0539583 - -0.3857 1.27993 0.0128876 - -0.391134 1.28085 0.00921392 - -0.431798 1.27678 -0.0183035 - -0.437915 1.27928 -0.0224354 - -0.489277 1.13503 -0.0575282 - -0.488087 1.08419 -0.0568457 - -0.491028 0.908616 -0.0592595 - -0.484756 0.799879 -0.0552795 - -0.492075 0.741462 -0.0603712 - -0.487278 0.653542 -0.0573385 - -0.491852 0.620632 -0.060512 - -0.49237 0.610545 -0.0608868 - -0.491355 0.588316 -0.0602539 - -0.33281 -0.40398 0.0398947 - -0.274592 -0.402202 0.0801655 - -0.178641 -0.396371 0.146545 - -0.163945 -0.403305 0.156693 - -0.157518 -0.40437 0.161136 - -0.147501 -0.415453 0.168037 - -0.509294 -1.72505 -0.0853848 - -0.507562 -1.96824 -0.0847781 - -0.412313 -2.15112 -0.0193429 - -0.349573 -2.16148 0.0240263 - -0.326407 -2.1675 0.0400343 - -0.239415 -2.25445 0.0999918 - -0.224365 -2.26961 0.110364 --0.00560192 -0.443472 0.266114 - -0.003966 -0.444372 0.267244 - 0.0243178 -0.438176 0.286821 - 0.0311541 -0.340576 0.291787 - 0.032933 -0.336064 0.293029 - 0.045709 -0.342822 0.301849 - 0.0469382 -0.342452 0.3027 - 0.0499103 -0.332213 0.30478 - 0.053479 -0.331016 0.307252 - 0.0836861 -0.338794 0.328126 - 0.0922046 -0.338961 0.334017 - 0.0953371 -0.343875 0.336172 - 0.101333 -0.348372 0.340308 - 0.124255 -0.359632 0.356135 - 0.146563 -0.357518 0.37157 - 0.180652 -0.357235 0.395148 - 0.194764 -0.364673 0.40489 - 0.201945 -0.363179 0.409861 - 0.204742 -0.364367 0.411793 - 0.207851 -0.362722 0.413947 - 0.223919 -0.367617 0.425049 - 0.296343 -0.412703 0.475032 - 0.300088 -0.413902 0.477619 - 0.337163 -0.415447 0.503259 - 0.388244 -0.419376 0.53858 - 0.409407 -0.403226 0.553257 - 1.47967 -0.663558 1.29288 - 2.37656 -0.671382 1.9132 - 2.40685 -0.639265 1.93423 - 2.39748 -0.424608 1.92827 - 2.40101 -0.30768 1.931 - 2.41102 -0.165943 1.93826 - 2.40254 -0.152457 1.93243 - 2.4119 0.0409231 1.93938 - 2.14747 0.527296 1.75767 - 1.64854 0.471175 1.41244 - 1.64682 0.480046 1.41127 - 2.07139 0.684874 1.70543 - 1.53079 0.680586 1.33151 - 1.50902 0.680264 1.31645 - 1.25335 0.677008 1.1396 - 1.24341 0.704024 1.13279 - 1.25607 0.744192 1.14165 - 1.24626 0.805949 1.13501 - 1.24457 0.839488 1.13393 - 1.2503 1.05751 1.13842 - 1.24467 1.07271 1.13456 - 1.24764 1.09539 1.13667 - 1.25066 1.18145 1.13897 - 1.04257 1.26673 0.995249 - 0.260424 0.416963 0.452206 - 0.252863 0.428242 0.447003 - 0.246335 0.466541 0.442581 - 0.244003 0.498663 0.441047 - 0.242485 0.515283 0.440037 - 0.238161 0.583254 0.437212 - 0.238393 0.602401 0.437418 - 0.280717 0.945573 0.467527 - 0.234909 0.946655 0.435846 - 0.241992 1.1749 0.4413 - 0.240777 1.18982 0.440496 - 0.182958 1.27814 0.40072 - 0.178057 1.27727 0.397328 - 0.0961428 1.1667 0.340402 - 0.0918556 1.16634 0.337436 - 0.0116135 1.16113 0.281924 - -0.0127299 1.2359 0.265268 - -0.061968 1.2502 0.231247 - -0.0807614 1.17406 0.218063 - -0.210799 1.18369 0.128145 - -0.256117 1.18829 0.0968118 - -0.326701 1.27436 0.0482008 - -0.366662 1.27411 0.0205615 - -0.460754 1.27549 -0.0445148 - -0.466283 1.27593 -0.0483382 - -0.48228 1.27522 -0.0594043 - -0.488458 1.15274 -0.0639752 - -0.490282 0.912866 -0.06582 - -0.488884 0.892677 -0.0649024 - -0.49236 0.795791 -0.067542 - -0.491835 0.787624 -0.0671988 - -0.488416 0.701485 -0.0650435 - -0.482259 0.622553 -0.0609768 - -0.337719 -0.405763 0.0316422 - -0.311918 -0.399449 0.0499021 - -0.296083 -0.401577 0.0610939 - -0.290632 -0.400598 0.0649509 - -0.265426 -0.404243 0.082765 - -0.249735 -0.399521 0.0938718 - -0.246877 -0.40192 0.0958869 - -0.244986 -0.402279 0.0972228 - -0.178569 -0.398177 0.144197 - -0.160398 -0.40478 0.157029 - -0.151404 -0.408088 0.163381 - -0.508189 -1.80961 -0.0923364 - -0.412783 -2.16772 -0.0257516 - -0.362298 -2.15399 0.0099805 - -0.321586 -2.20461 0.0386443 - -0.277374 -2.24021 0.0698194 - -0.261399 -2.24286 0.0811088 - -0.117083 -2.26198 0.183109 - -0.0354827 -0.419754 0.245321 - -0.0235143 -0.419999 0.253783 - 0.0936876 -2.28163 0.332097 - 0.116318 -2.25166 0.348173 - 0.0243815 -0.445115 0.287589 - 0.0252433 -0.424781 0.288248 - 0.0313512 -0.331165 0.292797 - 0.0713586 -0.333178 0.321081 - 0.088255 -0.334945 0.333024 - 0.145841 -0.355749 0.373693 - 0.157257 -0.364886 0.381743 - 0.167203 -0.363158 0.38878 - 0.172344 -0.35902 0.392425 - 0.190231 -0.366975 0.405054 - 0.215286 -0.367612 0.422769 - 0.219667 -0.371008 0.425858 - 0.223852 -0.370713 0.428818 - 0.276206 -0.414654 0.46573 - 0.292399 -0.418282 0.477172 - 0.407724 -0.408576 0.558742 - 0.483964 -0.38421 0.612712 - 0.492967 -0.383432 0.619079 - 0.539979 -0.406036 0.652267 - 1.19527 -0.842928 1.11455 - 1.19968 -0.837384 1.11769 - 1.20558 -0.824282 1.12189 - 1.20512 -0.765241 1.12171 - 1.20246 -0.747182 1.11988 - 1.39854 -0.66709 1.25872 - 1.507 -0.662245 1.33543 - 1.56653 -0.659464 1.37753 - 1.84097 -0.663773 1.57158 - 1.89987 -0.662502 1.61322 - 2.04643 -0.665469 1.71685 - 2.08278 -0.665137 1.74255 - 2.16826 -0.667204 1.803 - 2.34136 -0.679766 1.92536 - 2.40673 -0.603317 1.97177 - 2.4054 -0.495621 1.9711 - 2.4031 -0.481836 1.9695 - 2.40153 -0.441713 1.96849 - 2.40537 -0.415914 1.97127 - 2.40743 -0.258345 1.97311 - 2.41068 -0.206335 1.97554 - 2.40486 -0.192805 1.97145 - 2.40147 0.131882 1.96986 - 2.40633 0.171221 1.97339 - 2.40148 0.419817 1.97057 - 1.65526 0.467166 1.44303 - 2.13977 0.675401 1.78614 - 2.0875 0.683194 1.7492 - 1.61985 0.685486 1.41852 - 1.43292 0.677992 1.28632 - 1.43048 0.685777 1.28462 - 1.45133 0.713791 1.29943 - 1.24492 0.92708 1.154 - 1.2469 1.1869 1.15603 - 1.24584 1.25172 1.15544 - 1.24569 1.27413 1.1554 - 1.23592 1.28703 1.14852 - 1.21363 1.28689 1.13275 - 1.02771 1.28083 1.00127 - 1.02025 1.28291 0.996003 - 0.953173 1.25417 0.948505 - 0.917986 1.25212 0.923619 - 0.833105 1.16973 0.863398 - 0.848757 1.26698 0.874703 - 0.256087 0.429186 0.453571 - 0.247693 0.443484 0.44767 - 0.247565 0.468358 0.447641 - 0.236504 0.518096 0.439942 - 0.238901 0.538535 0.441687 - 0.239266 0.55568 0.441986 - 0.239315 0.561419 0.442036 - 0.239307 0.572928 0.442058 - 0.265913 0.783734 0.461387 - 0.276953 0.918179 0.469523 - 0.234986 0.941479 0.439905 - 0.236854 1.00596 0.441384 - 0.232285 1.05164 0.438266 - 0.239975 1.11869 0.443867 - 0.211006 1.28571 0.423792 - 0.181546 1.28109 0.402949 - 0.0823383 1.21582 0.332639 - 0.0484779 1.16347 0.308568 - -0.0175805 1.23996 0.262045 - -0.0344968 1.15495 0.249875 - -0.0620813 1.2502 0.230604 - -0.0665348 1.25 0.227454 - -0.119605 1.18643 0.189772 - -0.138661 1.16278 0.17624 - -0.223645 1.16195 0.116145 - -0.267664 1.16383 0.0850235 - -0.277202 1.167 0.0782871 - -0.331969 1.28331 0.0398458 - -0.462205 1.27225 -0.0522721 - -0.490519 1.16532 -0.0725549 - -0.489307 1.0445 -0.0719939 - -0.482372 0.852604 -0.0675603 - -0.49525 0.77691 -0.0768519 - -0.497521 0.77359 -0.0784656 - -0.490002 0.727707 -0.0732614 - -0.48827 0.591925 -0.0723693 - -0.355421 -0.405809 0.0139257 - -0.253564 -0.401176 0.0875587 - -0.250715 -0.403631 0.0896119 - -0.233032 -0.401362 0.102399 - -0.199291 -0.407195 0.126772 - -0.186625 -0.402865 0.135937 - -0.166731 -0.405468 0.15031 - -0.14933 -0.398079 0.162906 - -0.149075 -0.402485 0.163079 - -0.510719 -1.83145 -0.10184 - -0.508181 -1.90596 -0.10019 - -0.507184 -2.02546 -0.0997643 - -0.488373 -2.15346 -0.0864835 - -0.18766 -2.2427 0.130649 - -0.0358232 -0.422752 0.244886 - -0.0161466 -0.434889 0.259079 - 0.0282645 -0.430174 0.29119 - 0.0275166 -0.369537 0.290799 - 0.0283952 -0.366301 0.291442 - 0.028814 -0.360111 0.29176 - 0.0420244 -0.339297 0.30136 - 0.0470164 -0.338787 0.304969 - 0.0688353 -0.342261 0.320731 - 0.085587 -0.334614 0.332858 - 0.08692 -0.326359 0.333842 - 0.105174 -0.353647 0.346968 - 0.136007 -0.367187 0.369221 - 0.138596 -0.365449 0.371097 - 0.14542 -0.361846 0.376038 - 0.158557 -0.367323 0.385519 - 0.164066 -0.357104 0.389526 - 0.18057 -0.360243 0.401448 - 0.202992 -0.364738 0.417644 - 0.206561 -0.363854 0.420225 - 0.237399 -0.374002 0.44249 - 0.268959 -0.411745 0.465207 - 0.334726 -0.412287 0.512742 - 0.345675 -0.413846 0.520652 - 0.347736 -0.41252 0.522145 - 0.357932 -0.416445 0.529505 - 0.377408 -0.411438 0.543594 - 0.406753 -0.411023 0.564806 - 0.4082 -0.408699 0.565857 - 1.17766 -0.803411 1.12104 - 1.18048 -0.796936 1.1231 - 1.1749 -0.736043 1.11922 - 1.1976 -0.661825 1.13581 - 1.5852 -0.662675 1.41596 - 1.61293 -0.664318 1.436 - 1.8105 -0.668631 1.57878 - 2.40493 -0.675804 2.00842 - 2.40959 -0.649627 2.01185 - 2.40927 -0.581312 2.01179 - 2.40001 -0.484876 2.00533 - 2.40496 -0.286413 2.0094 - 2.40226 -0.128552 2.00784 - 2.40386 -0.102452 2.00906 - 2.39578 -0.0629912 2.00331 - 2.40342 0.132991 2.00932 - 2.39976 0.356313 2.00723 - 2.40114 0.383043 2.00829 - 1.24663 0.766974 1.17477 - 1.24476 0.782876 1.17346 - 1.24197 0.789707 1.17146 - 1.25041 0.847438 1.1777 - 1.24341 0.86943 1.17269 - 1.24455 0.87919 1.17354 - 1.24319 0.896311 1.1726 - 1.2468 0.926382 1.17528 - 1.24029 1.16846 1.17118 - 1.24894 1.20892 1.17753 - 1.14344 1.27858 1.10145 - 1.07114 1.27542 1.04918 - 0.908922 1.26084 0.931895 - 0.86399 1.25411 0.899402 - 0.241995 0.508473 0.447989 - 0.253355 0.714502 0.456708 - 0.258734 0.762186 0.460714 - 0.267826 0.886929 0.467594 - 0.269006 0.913282 0.468511 - 0.268135 0.922306 0.467904 - 0.239442 1.1451 0.447715 - 0.184806 1.28389 0.408567 - 0.0209504 1.22563 0.28999 - -0.0765519 1.17434 0.219389 - -0.0802745 1.16507 0.216676 - -0.119037 1.2387 0.18884 - -0.138199 1.16278 0.174803 - -0.142711 1.16613 0.17155 - -0.151514 1.21013 0.165296 - -0.160399 1.21171 0.158877 - -0.231458 1.1637 0.107398 - -0.247804 1.20532 0.0956862 - -0.26233 1.16608 0.0850903 - -0.275091 1.1641 0.0758613 - -0.489166 1.07325 -0.0790941 - -0.491956 0.974945 -0.0813533 - -0.486287 0.795791 -0.0776977 - -0.489503 0.786756 -0.0800444 - -0.494076 0.780124 -0.0833667 - -0.496341 0.776793 -0.085012 - -0.493937 0.738733 -0.0833678 - -0.492055 0.72271 -0.0820473 - -0.333279 -0.398073 0.0251444 - -0.331877 -0.399744 0.0261756 - -0.319564 -0.404425 0.0352547 - -0.307485 -0.401737 0.0441804 - -0.298013 -0.398699 0.051181 - -0.273507 -0.404041 0.0692621 - -0.266346 -0.403248 0.0745509 - -0.261603 -0.40634 0.0780452 - -0.237278 -0.404118 0.0960113 - -0.207404 -0.406748 0.118062 - -0.184347 -0.403736 0.135093 - -0.1787 -0.402692 0.139265 - -0.172354 -0.404156 0.143947 - -0.158327 -0.397589 0.15432 - -0.156438 -0.401803 0.155704 - -0.151313 -0.401124 0.15949 - -0.151159 -0.427929 0.159537 - -0.505931 -1.85309 -0.105949 - -0.508783 -1.9819 -0.108375 - -0.390265 -2.1591 -0.0213082 - -0.264979 -2.22867 0.0710221 - -0.0329124 -0.412865 0.246881 - -0.0271143 -0.412986 0.251161 - -0.0196937 -0.426958 0.256606 - -0.0181793 -0.427928 0.257721 - 0.103617 -2.21547 0.343205 - 0.0249922 -0.448817 0.289545 - 0.0257709 -0.441613 0.290137 - 0.0281815 -0.42297 0.291964 - 0.0283153 -0.380376 0.292168 - 0.0405645 -0.34257 0.301306 - 0.0619014 -0.329938 0.317092 - 0.0788302 -0.338425 0.32957 - 0.0832264 -0.330907 0.332834 - 0.103779 -0.349309 0.347964 - 0.112488 -0.356397 0.354376 - 0.113737 -0.35565 0.3553 - 0.149231 -0.366035 0.381481 - 0.160289 -0.363495 0.389652 - 0.201325 -0.37196 0.41993 - 0.222357 -0.371699 0.435459 - 0.235913 -0.378446 0.445451 - 0.284324 -0.414613 0.481105 - 0.288877 -0.413431 0.484469 - 0.304275 -0.41161 0.495843 - 0.314591 -0.417174 0.503446 - 0.322135 -0.411828 0.509029 - 0.342259 -0.409845 0.523892 - 0.449146 -0.403986 0.602826 - 0.871556 -0.661314 0.914069 - 1.1501 -0.799304 1.11939 - 1.14738 -0.75667 1.11749 - 1.15451 -0.737096 1.1228 - 1.31523 -0.662828 1.24164 - 1.35433 -0.664915 1.27051 - 1.38829 -0.663728 1.29559 - 1.9531 -0.668154 1.7126 - 2.40144 -0.208682 2.04477 - 2.40258 -0.169133 2.04571 - 2.41052 0.0947006 2.05223 - 2.4006 0.252768 2.0453 - 2.40125 0.547766 2.04651 - 1.65978 0.45643 1.49882 - 2.15317 0.689965 1.86369 - 1.98873 0.684647 1.74227 - 1.58122 0.679687 1.44137 - 1.50178 0.683294 1.38274 - 1.42516 0.675809 1.32614 - 1.28032 0.682176 1.21921 - 1.24402 0.695884 1.19245 - 1.24661 0.798722 1.19462 - 1.24779 0.971951 1.19592 - 1.25064 1.21989 1.19864 - 1.2458 1.27115 1.19519 - 1.00014 1.27796 1.01383 - 0.94127 1.28062 0.970369 - 0.82374 1.25018 0.883516 - 0.723293 1.14213 0.809084 - 0.699447 1.16692 0.791539 - 0.2469 0.484364 0.455708 - 0.237119 0.596411 0.448765 - 0.232919 0.599238 0.445671 - 0.23248 0.949056 0.446216 - 0.235672 1.0193 0.448748 - 0.235814 1.08516 0.449016 - 0.24016 1.19803 0.452506 - 0.205726 1.27986 0.427285 - 0.130585 1.17086 0.371535 - 0.10675 1.18349 0.353968 - 0.0970925 1.172 0.346809 - 0.0806158 1.1745 0.334649 - 0.0295882 1.24205 0.297142 --0.00255474 1.16062 0.273207 - -0.0270827 1.205 0.255207 - -0.0732268 1.19458 0.221111 - -0.0881412 1.15945 0.210012 - -0.134951 1.17728 0.175495 - -0.208772 1.18958 0.12102 - -0.214416 1.17089 0.116806 - -0.226219 1.16479 0.108077 - -0.236848 1.17624 0.100257 - -0.25647 1.21067 0.085855 - -0.260949 1.16608 0.0824377 - -0.360827 1.27601 0.00896659 - -0.391353 1.27789 -0.0135676 - -0.426959 1.27742 -0.039858 - -0.495267 1.27625 -0.0902955 - -0.488867 0.928165 -0.0864352 - -0.485472 0.853503 -0.0841145 - -0.49253 0.789893 -0.0894834 - -0.49053 0.687487 -0.0882615 - -0.491372 0.682671 -0.0888954 - -0.488542 0.632467 -0.0869307 - -0.48648 0.592319 -0.0855078 - -0.303185 -0.40859 0.0433739 - -0.301756 -0.410107 0.0444455 - -0.247645 -0.406496 0.0851769 - -0.225657 -0.403005 0.101733 - -0.212304 -0.399104 0.111792 - -0.200026 -0.396361 0.121039 - -0.192451 -0.408211 0.12671 - -0.173794 -0.400723 0.14077 - -0.151699 -0.431683 0.15732 - -0.515209 -1.71903 -0.11947 - -0.480936 -2.1467 -0.094747 - -0.450345 -2.15347 -0.0717419 - -0.411472 -2.15781 -0.0424978 - -0.333065 -2.1573 0.01651 - -0.178827 -2.25453 0.132342 - -0.013394 -0.452778 0.261352 - -0.0102376 -0.452637 0.263727 - 0.202382 -2.27868 0.419168 - 0.0269686 -0.375449 0.291921 - 0.0344852 -0.333839 0.297682 - 0.0387099 -0.336731 0.300854 - 0.0599179 -0.335631 0.316817 - 0.0720787 -0.332562 0.325977 - 0.0790141 -0.333564 0.331194 - 0.0963553 -0.344046 0.344218 - 0.0975528 -0.343381 0.345121 - 0.10094 -0.34476 0.347666 - 0.108984 -0.354424 0.353696 - 0.132345 -0.365426 0.371249 - 0.14479 -0.36704 0.380611 - 0.15324 -0.363062 0.38698 - 0.156591 -0.359269 0.389511 - 0.163689 -0.355897 0.394861 - 0.203845 -0.369043 0.425049 - 0.205128 -0.367791 0.426018 - 0.220381 -0.36518 0.437503 - 0.288433 -0.412453 0.488599 - 0.332802 -0.413064 0.521988 - 0.362032 -0.420181 0.543968 - 0.385504 -0.411484 0.561654 - 0.410035 -0.40944 0.58012 - 0.436024 -0.410718 0.599675 - 0.437448 -0.408198 0.600754 - 0.439131 -0.391013 0.602063 - 0.445179 -0.385022 0.60663 - 0.448527 -0.384084 0.609152 - 1.12843 -0.781968 1.11983 - 1.12464 -0.763254 1.11702 - 1.18118 -0.662629 1.15983 - 1.47175 -0.661579 1.3785 - 2.35673 -0.685734 2.04445 - 2.40367 -0.411379 2.08047 - 2.408 -0.385092 2.08379 - 2.40448 -0.117258 2.08181 - 2.40267 -0.0508301 2.08061 - 2.40281 -0.0375714 2.08075 - 2.40079 0.294631 2.08006 - 2.40316 0.524651 2.08243 - 2.40129 0.537911 2.08105 - 1.66444 0.451249 1.5263 - 2.03485 0.621203 1.80549 - 2.14501 0.692187 1.88857 - 1.2515 0.772735 1.21634 - 1.24335 0.802328 1.21028 - 1.24751 0.894356 1.21365 - 1.24881 1.0885 1.2151 - 1.24565 1.09602 1.21275 - 1.24708 1.12832 1.21391 - 1.25631 1.26783 1.2212 - 1.2474 1.2818 1.21453 - 1.04817 1.27856 1.06459 - 0.94267 1.28044 0.985196 - 0.869884 1.27029 0.930394 - 0.840624 1.27295 0.90838 - 0.804799 1.2532 0.88137 - 0.766363 1.24976 0.852435 - 0.241225 0.482549 0.455312 - 0.234114 0.58219 0.450209 - 0.248663 0.802353 0.46171 - 0.246483 0.805688 0.460077 - 0.248594 0.853258 0.461785 - 0.23345 0.946699 0.450622 - 0.235988 1.02882 0.452738 - 0.239832 1.18599 0.456024 - 0.130104 1.17777 0.373425 - 0.125827 1.21104 0.37029 - 0.0913453 1.1677 0.344231 - 0.0247905 1.24833 0.294346 - 0.00525957 1.16831 0.279447 - -0.0144796 1.2419 0.264776 - -0.0395532 1.16789 0.245722 - -0.0920874 1.15911 0.206164 - -0.175459 1.17027 0.143449 - -0.257567 1.19969 0.0817303 - -0.358633 1.27506 0.00585972 - -0.380543 1.28274 -0.0106099 - -0.487256 1.1797 -0.0911765 - -0.489792 1.14795 -0.0931648 - -0.489779 1.13561 -0.0931859 - -0.48662 1.01616 -0.0911075 - -0.486632 0.957036 -0.0912644 - -0.489797 0.8668 -0.093872 - -0.489279 0.841834 -0.0935447 - -0.489279 0.796459 -0.0936583 - -0.489678 0.789893 -0.0939756 - -0.48771 0.751678 -0.0925902 - -0.486872 0.656688 -0.0921969 - -0.485751 0.621552 -0.0914415 - -0.295263 -0.407017 0.0444624 - -0.222201 -0.398763 0.100786 - -0.21566 -0.404954 0.105811 - -0.212656 -0.402552 0.108132 - -0.20218 -0.399765 0.116212 - -0.156347 -0.410862 0.151503 - -0.14979 -0.405537 0.15657 - -0.151095 -0.438012 0.155482 - -0.50504 -1.96396 -0.121126 - -0.504196 -2.08951 -0.120792 - -0.368871 -2.15419 -0.0166724 - -0.353664 -2.15595 -0.00495839 - -0.345916 -2.15579 0.00101325 - -0.303102 -2.18152 0.033941 - -0.135815 -2.19838 0.162812 - -0.11539 -2.25998 0.178397 - -0.02342 -0.421994 0.253911 - -0.0156556 -0.442839 0.259841 - 0.0282782 -0.381071 0.293853 - 0.035455 -0.337412 0.299494 - 0.0471374 -0.339939 0.30849 - 0.115141 -0.35862 0.360848 - 0.192232 -0.370378 0.420225 - 0.200214 -0.370289 0.426377 - 0.20423 -0.370154 0.429471 - 0.252374 -0.409604 0.466473 - 0.287866 -0.412182 0.493816 - 0.304686 -0.419416 0.50676 - 0.30613 -0.417596 0.507878 - 0.340394 -0.418549 0.53428 - 0.380154 -0.41372 0.564931 - 0.405743 -0.41302 0.584652 - 0.432305 -0.411298 0.605126 - 0.430576 -0.402232 0.603816 - 0.433386 -0.393542 0.606004 - 1.09856 -0.833869 1.11748 - 1.10607 -0.672087 1.12368 - 1.51842 -0.659784 1.44147 - 1.60878 -0.668449 1.51108 - 1.88149 -0.665545 1.72124 - 2.19606 -0.683923 1.96362 - 2.40419 -0.621593 2.12415 - 2.39895 -0.346442 2.12082 - 2.40173 -0.292787 2.12309 - 2.40027 -0.0512315 2.12258 - 2.40479 0.0959825 2.12643 - 2.40065 0.149374 2.12338 - 2.39617 0.283223 2.12026 - 2.40747 0.475183 2.12945 - 2.39682 0.514199 2.12134 - 1.6688 0.446715 1.56015 - 2.03518 0.687278 1.8431 - 1.96999 0.689131 1.79286 - 1.80574 0.687009 1.66629 - 1.7115 0.683046 1.59365 - 1.65241 0.680167 1.54811 - 1.50989 0.678922 1.43828 - 1.2677 0.678153 1.25164 - 1.24672 0.691968 1.23551 - 1.24187 0.705969 1.23181 - 1.2441 0.740936 1.23361 - 1.24574 0.776216 1.23497 - 1.24606 0.802537 1.23528 - 1.24397 0.809991 1.23369 - 1.25261 1.17557 1.24127 - 1.2372 1.28305 1.22966 - 1.0679 1.27986 1.09919 - 1.05594 1.27701 1.08997 - 1.02546 1.27404 1.06647 - 0.916348 1.27927 0.982404 - 0.898915 1.27781 0.968967 - 0.892359 1.27994 0.96392 - 0.269573 0.539271 0.482122 - 0.247614 0.508603 0.465123 - 0.240137 0.504114 0.45935 - 0.236172 0.51099 0.456311 - 0.231839 0.527454 0.453014 - 0.23672 0.600229 0.456959 - 0.237649 0.67738 0.45787 - 0.245522 0.85233 0.464378 - 0.244323 0.859396 0.463472 - 0.242241 0.935239 0.46206 - 0.240534 1.20139 0.461416 - 0.238073 1.27577 0.459708 - 0.205842 1.27859 0.434877 - 0.157049 1.2007 0.39708 - 0.139431 1.16722 0.383419 - 0.0757878 1.24523 0.334571 - 0.0582714 1.1821 0.320913 - -0.0715768 1.26275 0.221054 - -0.0883459 1.16744 0.207891 - -0.113743 1.23918 0.188501 - -0.140468 1.15919 0.167704 - -0.215015 1.16202 0.110265 - -0.442129 1.27779 -0.0644603 - -0.486004 1.28334 -0.0982569 - -0.489252 1.19407 -0.100985 - -0.486684 1.17448 -0.0990561 - -0.486091 1.07691 -0.098845 - -0.488645 0.752311 -0.101633 - -0.490438 0.709468 -0.103123 - -0.49324 0.682894 -0.105349 - -0.49242 0.624514 -0.104865 - -0.490199 0.616142 -0.103174 - -0.301623 -0.39795 0.0347505 - -0.24829 -0.401993 0.0767725 - -0.208646 -0.396518 0.10803 - -0.20017 -0.406085 0.114685 - -0.164 -0.406385 0.143191 - -0.160292 -0.405146 0.146116 - -0.148462 -0.419742 0.155402 - -0.473394 -2.14477 -0.105072 - -0.435045 -2.14899 -0.0748601 - -0.397609 -2.15698 -0.0453769 - -0.177561 -2.26549 0.12777 - -0.0909607 -2.23633 0.196094 - -0.0223589 -0.41998 0.254785 - 0.194574 -2.24493 0.421105 - 0.0416945 -0.342452 0.305464 - 0.0453513 -0.336076 0.308362 - 0.0465018 -0.335679 0.309269 - 0.0770872 -0.335427 0.333375 - 0.0983947 -0.34567 0.350141 - 0.142262 -0.37317 0.384643 - 0.138077 -0.353116 0.381396 - 0.162358 -0.360898 0.400513 - 0.163254 -0.349254 0.401249 - 0.254378 -0.420281 0.472883 - 0.335788 -0.417205 0.537051 - 0.355392 -0.409936 0.55252 - 0.395964 -0.411132 0.584492 - 0.427909 -0.38152 0.609744 - 0.430525 -0.380093 0.611809 - 0.434459 -0.379732 0.61491 - 0.450968 -0.385877 0.627906 - 1.07851 -0.769522 1.1215 - 1.10357 -0.661274 1.14153 - 1.21882 -0.662831 1.23236 - 1.39661 -0.666343 1.37246 - 1.50801 -0.661067 1.46027 - 1.56471 -0.66588 1.50495 - 1.80301 -0.665626 1.69275 - 1.92339 -0.662844 1.78763 - 2.39682 -0.458628 2.16127 - 2.39828 -0.43142 2.16249 - 2.40298 -0.377376 2.16633 - 2.40175 -0.308938 2.16553 - 2.40433 -0.29564 2.1676 - 2.39569 -0.132369 2.16121 - 2.39444 -0.0919111 2.16032 - 2.39471 -0.0784642 2.16057 - 2.39526 -0.0381154 2.16111 - 2.39457 -0.024656 2.1606 - 2.39765 0.110012 2.16337 - 2.40477 0.232281 2.16929 - 2.39636 0.353737 2.16298 - 2.3987 0.3951 2.16492 - 2.39939 0.546978 2.16586 - 1.65787 0.467287 1.58125 - 2.23013 0.705399 2.03286 - 1.24757 0.81058 1.25876 - 1.24452 1.11473 1.25714 - 1.23666 1.2823 1.25137 - 1.0821 1.28524 1.12956 - 1.02908 1.27856 1.08776 - 0.968077 1.28067 1.03969 - 0.842503 1.27626 0.940711 - 0.773014 1.27195 0.885935 - 0.577253 1.11142 0.731245 - 0.264912 0.556522 0.483673 - 0.23081 0.52036 0.456704 - 0.241466 0.778262 0.46576 - 0.241287 0.787084 0.465641 - 0.240744 0.795001 0.465233 - 0.236743 1.1571 0.463002 - 0.0567492 1.17612 0.321195 - 0.0520508 1.16662 0.317468 - 0.0314964 1.24373 0.301465 - -0.0480451 1.1637 0.238574 - -0.071584 1.26275 0.220275 - -0.113112 1.2352 0.187476 - -0.127791 1.15897 0.175713 - -0.145577 1.17541 0.161738 - -0.181195 1.16466 0.13364 - -0.203909 1.23677 0.115922 - -0.208145 1.23578 0.112582 - -0.260291 1.16383 0.0713014 - -0.344307 1.27578 0.00537243 - -0.355723 1.28267 -0.00360721 - -0.388723 1.27778 -0.0296268 - -0.489359 0.949414 -0.109776 - -0.492718 0.928985 -0.112475 - -0.492876 0.861604 -0.112771 - -0.490497 0.811014 -0.111025 - -0.485893 0.7604 -0.107525 - -0.488656 0.751334 -0.109726 - -0.490735 0.747977 -0.111373 - -0.34113 -0.406173 -0.0032157 - -0.321235 -0.404521 0.0128974 - -0.306516 -0.40156 0.024823 - -0.28246 -0.408241 0.0442839 - -0.251817 -0.404374 0.069105 - -0.235174 -0.399791 0.0825926 - -0.204636 -0.403011 0.107311 - -0.200381 -0.401511 0.110761 - -0.189263 -0.400166 0.119766 - -0.15448 -0.400159 0.14793 - -0.401391 -2.15488 -0.0565096 - -0.327002 -2.16714 0.00369217 - -0.312288 -2.17046 0.0155971 - -0.254876 -2.19795 0.062013 - -0.128357 -2.22993 0.164372 - -0.0299615 -0.422967 0.248693 - -0.0214272 -0.416959 0.255619 --0.00894793 -0.446469 0.265648 - 0.147238 -2.26536 0.387431 - 0.214935 -2.24309 0.442302 - 0.0318778 -0.334815 0.298991 - 0.0354575 -0.334784 0.30189 - 0.0449091 -0.33375 0.309546 - 0.0456208 -0.331421 0.310128 - 0.0543266 -0.327049 0.317188 - 0.0804138 -0.33402 0.338293 - 0.0912588 -0.342216 0.347053 - 0.111029 -0.356827 0.363023 - 0.117988 -0.359028 0.368653 - 0.129841 -0.361072 0.378244 - 0.14395 -0.363279 0.389663 - 0.161257 -0.363399 0.403676 - 0.243085 -0.41188 0.469807 - 0.257557 -0.41166 0.481526 - 0.286692 -0.412297 0.505114 - 0.319592 -0.410351 0.531759 - 0.379611 -0.421894 0.580326 - 0.38526 -0.412724 0.584924 - 0.454718 -0.397166 0.641204 - 0.505947 -0.435252 0.682586 - 1.0214 -0.824045 1.09895 - 1.04056 -0.697694 1.11478 - 1.04983 -0.673647 1.12235 - 1.78046 -0.664526 1.71396 - 2.11644 -0.685055 1.98596 - 2.40527 -0.605644 2.22003 - 2.40233 -0.548541 2.21779 - 2.40415 -0.534904 2.2193 - 2.39834 -0.311823 2.21517 - 2.3991 -0.024968 2.21652 - 2.39914 -0.0113503 2.21659 - 2.399 0.0295029 2.21658 - 2.39333 0.315851 2.21273 - 2.38957 0.578669 2.21036 - 1.66649 0.454889 1.62457 - 2.12512 0.705517 1.99656 - 1.82207 0.684206 1.75113 - 1.40145 0.679724 1.41054 - 1.38167 0.679318 1.39452 - 1.24078 0.869237 1.28094 - 1.24574 0.89109 1.28501 - 1.24506 0.909237 1.2845 - 1.24546 0.966526 1.28498 - 1.24812 1.03747 1.28731 - 1.24865 1.13061 1.28798 - 1.14371 1.2896 1.20342 - 1.03584 1.27838 1.11605 - 0.88273 1.28076 0.992082 - 0.854635 1.27434 0.969317 - 0.843391 1.28044 0.960229 - 0.830108 1.28336 0.949481 - 0.813348 1.28073 0.935903 - 0.746378 1.2773 0.881669 - 0.732015 1.27642 0.870037 - 0.693676 1.2684 0.838974 - 0.650205 1.2482 0.803723 - 0.525121 1.08685 0.702028 - 0.278527 0.618491 0.501156 - 0.25052 0.572691 0.478361 - 0.232868 0.546784 0.464001 - 0.230927 0.612776 0.4626 - 0.245394 0.728919 0.474612 - 0.242877 0.791996 0.472737 - 0.240419 0.90022 0.471025 - 0.234215 0.940478 0.466105 - 0.232568 0.947596 0.46479 - 0.234761 1.07413 0.466891 - 0.238695 1.14263 0.470253 - 0.236604 1.19029 0.468683 - 0.236762 1.27527 0.469029 - 0.21452 1.27948 0.451031 - 0.143801 1.16829 0.393483 - 0.0769006 1.24068 0.339501 - 0.0554801 1.17712 0.321993 - 0.0112949 1.17492 0.286211 - -0.118071 1.19538 0.181516 - -0.12418 1.17046 0.176506 - -0.136076 1.16874 0.166868 - -0.140231 1.1701 0.163508 - -0.171646 1.16237 0.138052 - -0.301679 1.24516 0.032977 - -0.369575 1.27329 -0.021926 - -0.399896 1.26021 -0.04651 - -0.427601 1.26987 -0.0689186 - -0.455807 1.27856 -0.0917346 - -0.490533 1.25947 -0.119901 - -0.488979 1.00595 -0.119295 - -0.489719 0.824937 -0.12036 - -0.492907 0.76551 -0.123094 - -0.486794 0.673218 -0.118382 - -0.299496 -0.397906 0.025683 - -0.273437 -0.400313 0.0472373 - -0.190977 -0.402779 0.115457 - -0.18962 -0.403708 0.116577 - -0.183737 -0.397538 0.121461 - -0.50449 -2.1452 -0.14846 - -0.405342 -2.15079 -0.0664416 - -0.390696 -2.15405 -0.0543324 - -0.323205 -2.15631 0.00150225 - -0.316479 -2.16193 0.00705276 - -0.309206 -2.16356 0.0130659 - -0.189251 -2.24577 0.1121 - -0.148641 -2.19905 0.145821 - -0.0330624 -0.419906 0.246067 --0.00624762 -0.450255 0.268174 - 0.100439 -2.2833 0.351686 - 0.155327 -2.19871 0.397318 - 0.19877 -2.25858 0.433107 - 0.0279127 -0.441445 0.29646 - 0.0305844 -0.416519 0.298736 - 0.0274914 -0.327628 0.296407 - 0.0310398 -0.334815 0.299324 - 0.0321644 -0.334487 0.300256 - 0.038523 -0.336631 0.305511 - 0.0491078 -0.329762 0.314287 - 0.0748608 -0.345904 0.335552 - 0.107454 -0.351447 0.362504 - 0.120472 -0.365309 0.373239 - 0.143341 -0.36585 0.392159 - 0.163384 -0.36104 0.408754 - 0.17285 -0.358527 0.416593 - 0.232834 -0.410957 0.466086 - 0.261663 -0.414403 0.489929 - 0.278416 -0.416077 0.503787 - 0.27981 -0.414348 0.504944 - 0.415289 -0.389607 0.617101 - 0.417886 -0.384591 0.619262 - 0.994698 -0.82624 1.09536 - 1.02028 -0.798385 1.11659 - 1.02926 -0.659361 1.12439 - 1.13665 -0.662629 1.21323 - 1.15442 -0.664797 1.22793 - 1.2734 -0.662874 1.32637 - 1.29717 -0.666362 1.34603 - 1.45252 -0.668536 1.47456 - 1.70754 -0.664664 1.68557 - 2.18758 -0.687509 2.08268 - 2.38427 -0.437374 2.24606 - 2.38188 -0.423048 2.24413 - 2.38576 -0.29916 2.24766 - 2.38611 -0.271655 2.24802 - 2.38704 -0.244242 2.24886 - 2.38567 -0.0797112 2.24815 - 2.38626 0.359205 2.24978 - 2.38424 0.372751 2.24815 - 1.86374 0.682706 1.8183 - 1.8377 0.684702 1.79676 - 1.38371 0.677296 1.42112 - 1.24774 0.782249 1.30889 - 1.24673 1.14974 1.30901 - 1.25511 1.2572 1.31622 - 1.24842 1.27351 1.31073 - 1.12212 1.27725 1.20625 - 1.10129 1.27644 1.18901 - 0.993986 1.2833 1.10024 - 0.970016 1.28647 1.08042 - 0.955348 1.27867 1.06826 - 0.901058 1.28426 1.02336 - 0.759858 1.27663 0.906514 - 0.725093 1.27642 0.87775 - 0.593228 1.23243 0.768534 - 0.520105 1.11885 0.707739 - 0.40721 0.905276 0.613778 - 0.249928 0.594424 0.48284 - 0.226767 0.561159 0.46359 - 0.224877 0.562594 0.46203 - 0.229076 0.583671 0.465559 - 0.240785 0.77525 0.475744 - 0.241153 0.824104 0.476175 - 0.243834 0.863784 0.478497 - 0.237114 0.947459 0.473154 - 0.232675 0.999255 0.469616 - 0.236074 1.12486 0.472754 - 0.236965 1.24526 0.473803 - 0.212969 1.28434 0.454051 - 0.198961 1.28248 0.442457 - 0.174862 1.27295 0.422493 - 0.148062 1.18204 0.400083 - 0.126216 1.17197 0.381982 - 0.0720883 1.24921 0.337399 - 0.0537793 1.16815 0.32204 - 0.0459208 1.16904 0.31554 - 0.0299587 1.25271 0.302551 - -0.118111 1.20136 0.179908 - -0.157123 1.22161 0.147684 - -0.166741 1.16218 0.139571 - -0.251835 1.20455 0.0692768 - -0.329163 1.27351 0.00547627 - -0.343394 1.27401 -0.0062969 - -0.365439 1.23266 -0.0246438 - -0.426551 1.27635 -0.0750934 - -0.456773 1.27614 -0.100099 - -0.488992 1.02407 -0.12741 - -0.486145 1.00767 -0.125097 - -0.490317 0.977541 -0.128627 - -0.488003 0.935729 -0.126821 - -0.489918 0.787605 -0.12879 - -0.491147 0.782601 -0.12982 - -0.492351 0.777599 -0.130829 - -0.491151 0.76866 -0.129859 - -0.483859 0.736559 -0.123909 - -0.486763 0.715358 -0.126367 - -0.489558 0.659098 -0.128825 - -0.487148 0.644301 -0.12687 - -0.487183 0.622243 -0.126956 - -0.30931 -0.397393 0.0127509 - -0.30819 -0.413583 0.0136542 - -0.237581 -0.398699 0.0733149 - -0.234848 -0.404768 0.0756067 - -0.226186 -0.399098 0.0829354 - -0.207063 -0.40169 0.0990765 - -0.206487 -0.404445 0.0995553 - -0.196133 -0.405208 0.108296 - -0.177071 -0.4046 0.124393 - -0.153253 -0.401083 0.144515 - -0.507898 -1.815 -0.158647 - -0.50639 -2.03656 -0.157953 - -0.491108 -2.13636 -0.145311 - -0.327776 -2.15165 -0.00743392 - -0.298906 -2.15726 0.0169292 - -0.188589 -2.25174 0.109833 - -0.0156658 -0.453777 0.260554 --0.00961698 -0.45346 0.265663 - 0.0279929 -0.4362 0.297466 - 0.0367312 -0.33178 0.305117 - 0.0559164 -0.33184 0.321317 - 0.0570212 -0.331365 0.322251 - 0.0632 -0.33601 0.327456 - 0.0834499 -0.342953 0.344537 - 0.083498 -0.330953 0.344609 - 0.11645 -0.359103 0.37236 - 0.118476 -0.356572 0.374077 - 0.135176 -0.366174 0.388153 - 0.154545 -0.361103 0.404522 - 0.173866 -0.36063 0.420838 - 0.199037 -0.370741 0.442066 - 0.237493 -0.414923 0.474422 - 0.24261 -0.411883 0.47875 - 0.265097 -0.423314 0.497708 - 0.266503 -0.421645 0.4989 - 0.296564 -0.411388 0.52431 - 0.316475 -0.41442 0.541115 - 0.346084 -0.415941 0.566113 - 0.38309 -0.403428 0.597393 - 1.00196 -0.807116 1.11891 - 1.00127 -0.775022 1.11841 - 1.37561 -0.666289 1.43479 - 1.63273 -0.662105 1.65191 - 2.00172 -0.684362 1.96342 - 2.13013 -0.688426 2.07184 - 2.3313 -0.541797 2.24209 - 2.32892 -0.499758 2.24019 - 2.33775 0.327646 2.24981 - 2.34089 0.410407 2.25268 - 2.33816 0.520498 2.25066 - 2.3357 0.561701 2.24869 - 2.32478 0.572998 2.2395 - 1.66479 0.472529 1.68194 - 2.21175 0.679006 2.14434 - 2.20945 0.69179 2.14243 - 1.84764 0.682706 1.83689 - 1.49318 0.677432 1.53757 - 1.24893 0.676629 1.33133 - 1.24665 0.683914 1.32942 - 1.24435 0.691187 1.3275 - 1.24571 0.71767 1.32872 - 1.24456 0.832029 1.32804 - 1.24477 0.953945 1.32854 - 1.25287 1.03944 1.3356 - 1.24968 1.07775 1.33301 - 1.25033 1.14146 1.33373 - 1.10675 1.28244 1.21286 - 0.900452 1.27224 1.03864 - 0.788265 1.27624 0.943917 - 0.759594 1.27604 0.919707 - 0.707167 1.28011 0.875449 - 0.605676 1.25643 0.789688 - 0.249858 0.747161 0.487904 - 0.244861 0.750307 0.483694 - 0.240487 0.755208 0.480013 - 0.24891 0.835704 0.487336 - 0.252717 0.857498 0.490608 - 0.126501 1.18675 0.384893 - 0.0920207 1.16636 0.355725 - 0.0355774 1.21509 0.308192 - 0.0183334 1.18941 0.293564 --0.00199803 1.16748 0.276339 - -0.0331664 1.17198 0.250033 - -0.118754 1.21529 0.177876 - -0.119669 1.17497 0.176998 - -0.178431 1.16663 0.127358 - -0.191736 1.17577 0.116148 - -0.225697 1.15965 0.087429 - -0.251573 1.21136 0.0657144 - -0.254786 1.18354 0.0629289 - -0.258224 1.15865 0.0599606 - -0.492801 1.25693 -0.137857 - -0.491261 1.23899 -0.136604 - -0.488501 1.10687 -0.134619 - -0.488803 0.981802 -0.135202 - -0.487629 0.969814 -0.134242 - -0.492159 0.82697 -0.138441 - -0.491039 0.79556 -0.137577 - -0.49065 0.766813 -0.137325 - -0.490571 0.720407 -0.137379 - -0.483905 0.697618 -0.13181 - -0.484184 0.668032 -0.132123 - -0.325931 -0.40256 -0.00695121 - -0.303566 -0.402944 0.0123553 - -0.28907 -0.402518 0.0248711 - -0.268089 -0.40842 0.0429679 - -0.254476 -0.399536 0.054743 - -0.170064 -0.401715 0.12761 - -0.50736 -2.12435 -0.168126 - -0.345842 -2.14136 -0.0287342 - -0.332516 -2.15088 -0.0172553 - -0.25682 -2.19465 0.0479766 - -0.243353 -2.13453 0.0597614 - 0.108081 -2.20605 0.362962 - 0.148744 -2.25642 0.397933 - 0.175342 -2.21733 0.420999 - 0.0233878 -0.442041 0.294508 - 0.0512864 -0.332271 0.318883 - 0.0691467 -0.338982 0.334284 - 0.076682 -0.338322 0.340791 - 0.11832 -0.356621 0.376688 - 0.137669 -0.368619 0.39336 - 0.179905 -0.368771 0.429822 - 0.18112 -0.367575 0.430873 - 0.244096 -0.414885 0.485115 - 0.247823 -0.413247 0.488337 - 0.249686 -0.412408 0.489948 - 0.272206 -0.412182 0.509389 - 0.274089 -0.411173 0.511018 - 0.326849 -0.416502 0.556551 - 0.334945 -0.414937 0.563544 - 0.363347 -0.416864 0.588058 - 0.371604 -0.41441 0.595193 - 0.374161 -0.413339 0.597403 - 0.977671 -0.81152 1.11736 - 0.975814 -0.740275 1.11594 - 1.32163 -0.664449 1.41468 - 1.44029 -0.66568 1.51711 - 1.64598 -0.663262 1.6947 - 1.68373 -0.667497 1.72727 - 1.81998 -0.663169 1.84491 - 2.28096 -0.521582 2.24324 - 2.27969 -0.412452 2.24243 - 2.28361 -0.345542 2.24599 - 2.28471 -0.33222 2.24698 - 2.2805 -0.318164 2.24338 - 2.28666 -0.238334 2.24891 - 2.28137 -0.0776497 2.24477 - 2.28159 -0.0643409 2.24499 - 2.28121 0.015524 2.24487 - 2.2841 0.135563 2.24769 - 2.28643 0.256276 2.25002 - 2.28638 0.364118 2.25026 - 2.28137 0.554019 2.24644 - 2.19501 0.68036 2.17222 - 2.09607 0.701918 2.08686 - 1.41763 0.678013 1.5011 - 1.36191 0.669983 1.45298 - 1.28985 0.678661 1.39079 - 1.24196 0.766327 1.34969 - 1.24654 0.79592 1.35372 - 1.24393 0.933509 1.35183 - 1.24737 1.16066 1.35539 - 1.24394 1.26924 1.35272 - 1.23069 1.279 1.34131 - 1.20068 1.2827 1.31541 - 1.14885 1.28473 1.27067 - 1.04853 1.28376 1.18407 - 0.878343 1.27625 1.03712 - 0.815653 1.27443 0.982998 - 0.77463 1.27858 0.947595 - 0.686082 1.27882 0.871152 - 0.245466 0.711285 0.489273 - 0.285392 0.912081 0.524272 - 0.320157 1.07532 0.554715 - 0.247582 1.17971 0.492338 - 0.220167 1.27722 0.468929 - 0.210811 1.2752 0.460846 - 0.122237 1.2329 0.384269 - 0.118162 1.23376 0.380754 - 0.109439 1.19407 0.373118 - 0.035121 1.22507 0.309042 --0.00267741 1.16448 0.276251 - -0.0100484 1.18673 0.269947 - -0.0131735 1.25682 0.267434 - -0.0915007 1.16908 0.199583 - -0.12619 1.16494 0.169625 - -0.247273 1.22041 0.0652417 - -0.255458 1.19616 0.0581118 - -0.370566 1.22026 -0.0411963 - -0.482166 1.28108 -0.137379 - -0.491726 0.986813 -0.14641 - -0.490056 0.893926 -0.145213 - -0.487176 0.840349 -0.142869 - -0.489559 0.829388 -0.144955 - -0.49157 0.796081 -0.146779 - -0.486473 0.65384 -0.142755 - -0.4882 0.639338 -0.144284 - -0.30592 -0.40961 0.00520584 - -0.27932 -0.404654 0.0286696 - -0.207092 -0.407724 0.0923355 - -0.199734 -0.403011 0.098835 - -0.191194 -0.399069 0.106374 - -0.183159 -0.39574 0.113467 - -0.175321 -0.405499 0.12035 - -0.170731 -0.401789 0.124407 - -0.152634 -0.399434 0.140367 - -0.150753 -0.398311 0.142028 - -0.149536 -0.40437 0.143085 - -0.514185 -1.74643 -0.18196 - -0.508391 -1.9019 -0.177267 - -0.400828 -2.13498 -0.0830627 - -0.375329 -2.11402 -0.0605277 - -0.350839 -2.14341 -0.0390166 - -0.329758 -2.14891 -0.0204467 - -0.308112 -2.15011 -0.00136688 - -0.278411 -2.14353 0.0248345 - -0.27285 -2.15783 0.0296986 - -0.132079 -2.20537 0.153672 - -0.112246 -2.25599 0.171022 - -0.0883477 -2.19436 0.192255 - -0.0383744 -0.435744 0.240999 - -0.0283616 -0.417996 0.249873 - -0.0136507 -0.450638 0.262755 - 0.164166 -2.19759 0.414856 - 0.0223874 -0.440063 0.294554 - 0.0246302 -0.331845 0.296819 - 0.0409181 -0.332785 0.311176 - 0.0628352 -0.33403 0.330494 - 0.0751408 -0.337395 0.341334 - 0.106716 -0.350035 0.369136 - 0.120369 -0.361929 0.38114 - 0.136326 -0.362423 0.395206 - 0.13869 -0.360505 0.397295 - 0.141848 -0.363786 0.400071 - 0.150625 -0.364649 0.407806 - 0.167926 -0.360961 0.423068 - 0.169104 -0.359822 0.42411 - 0.954551 -0.824016 1.11531 - 1.18072 -0.665464 1.31511 - 1.29083 -0.664081 1.41218 - 1.31267 -0.666197 1.43143 - 1.44169 -0.662992 1.54519 - 2.23495 -0.666174 2.2445 - 2.23124 -0.596544 2.24142 - 2.22729 -0.514162 2.23815 - 2.23137 -0.447744 2.24192 - 2.23294 -0.287935 2.24374 - 2.23254 -0.221692 2.24356 - 2.23821 -0.182538 2.24867 - 2.23194 -0.0635395 2.24345 - 2.23681 0.0153662 2.24795 - 2.23787 0.0944818 2.2491 - 2.23655 0.279626 2.24843 - 2.24155 0.440998 2.25327 - 2.23928 0.467541 2.25134 - 1.68239 0.486506 1.76044 - 1.8416 0.554597 1.90098 - 2.2039 0.67573 2.2207 - 1.67116 0.683806 1.75108 - 1.42769 0.679583 1.53643 - 1.24651 0.714329 1.37679 - 1.24484 0.904496 1.37583 - 1.24687 0.973818 1.3778 - 1.24363 1.00108 1.37501 - 1.24569 1.21432 1.3774 - 1.08364 1.28049 1.23472 - 0.906249 1.28237 1.07834 - 0.76331 1.28398 0.952332 - 0.717995 1.2773 0.912365 - 0.575456 1.28017 0.786713 - 0.302594 0.743706 0.544734 - 0.258452 0.650807 0.505572 - 0.215014 0.605407 0.467157 - 0.235912 0.724683 0.485898 - 0.358541 1.17746 0.595212 - 0.351309 1.19794 0.588891 - 0.247977 1.27233 0.497994 - 0.12697 1.18684 0.391089 - 0.113599 1.20907 0.37936 - 0.0469856 1.17259 0.320539 - 0.0357326 1.17881 0.310635 - 0.00820184 1.16492 0.286327 - -0.0451712 1.16281 0.239269 - -0.0793124 1.15908 0.209161 - -0.0906877 1.15811 0.19913 - -0.13301 1.16079 0.161827 - -0.16818 1.16336 0.130829 - -0.182988 1.157 0.117757 - -0.223313 1.16258 0.0822227 - -0.262915 1.15888 0.0473004 - -0.341829 1.22408 -0.0220945 - -0.350323 1.22228 -0.0295875 - -0.365131 1.22691 -0.0426295 - -0.371557 1.21734 -0.0483206 - -0.437569 1.2791 -0.10635 - -0.463963 1.28334 -0.129608 - -0.481649 1.27575 -0.145219 - -0.487824 0.95849 -0.151509 - -0.488509 0.950768 -0.152133 - -0.487863 0.864377 -0.151794 - -0.49135 0.760377 -0.155146 - -0.490955 0.720416 -0.154904 - -0.486843 0.689343 -0.151362 - -0.328912 -0.406173 -0.0208565 - -0.31175 -0.396633 -0.00537094 - -0.308576 -0.406175 -0.00253752 - -0.307254 -0.407822 -0.00135136 - -0.295821 -0.40156 0.00896475 - -0.290421 -0.403994 0.0138227 - -0.250524 -0.409891 0.0497472 - -0.248321 -0.409578 0.0517327 - -0.208514 -0.401985 0.0876122 - -0.1964 -0.394206 0.0985453 - -0.191825 -0.395401 0.102663 - -0.190432 -0.404414 0.103894 - -0.169967 -0.407143 0.122322 - -0.14905 -0.416015 0.141141 - -0.154666 -0.452729 0.135983 - -0.499577 -1.99859 -0.178882 - -0.380124 -2.11781 -0.0715973 - -0.240113 -2.13651 0.0544778 - -0.196831 -2.21397 0.0932589 - -0.0606846 -0.516061 0.220473 - -0.125557 -2.23691 0.157402 - -0.104939 -2.27245 0.175879 - -0.0313278 -0.409968 0.247204 - 0.0882187 -2.29995 0.349807 - 0.128924 -2.23841 0.386641 - 0.149165 -2.21662 0.404933 - 0.155438 -2.20464 0.410616 - 0.180094 -2.236 0.432742 - 0.030166 -0.389315 0.302655 - 0.0432195 -0.342983 0.314538 - 0.0478549 -0.326542 0.318758 - 0.0520752 -0.324719 0.322565 - 0.0622159 -0.331623 0.331681 - 0.0632895 -0.331092 0.33265 - 0.0791286 -0.342032 0.346889 - 0.0886923 -0.342941 0.355501 - 0.0956902 -0.347374 0.361793 - 0.107822 -0.357161 0.372696 - 0.123961 -0.363682 0.387216 - 0.143852 -0.368733 0.405122 - 0.153015 -0.366733 0.413381 - 0.163585 -0.370375 0.422892 - 0.172614 -0.360368 0.431053 - 0.174676 -0.360785 0.432909 - 0.214946 -0.406082 0.469064 - 0.219924 -0.407088 0.473545 - 0.23152 -0.414942 0.48397 - 0.232861 -0.413417 0.485182 - 0.248519 -0.401404 0.499319 - 0.25388 -0.405625 0.504138 - 0.27597 -0.418739 0.524002 - 0.289852 -0.408373 0.536534 - 0.302247 -0.416953 0.547677 - 0.358003 -0.415861 0.597906 - 0.359072 -0.405958 0.598896 - 0.357052 -0.393064 0.597111 - 0.366376 -0.377652 0.605552 - 0.370024 -0.377641 0.608839 - 0.912307 -0.827551 1.09613 - 1.29542 -0.6641 1.44169 - 1.32406 -0.669452 1.46747 - 1.49804 -0.665366 1.6242 - 1.52071 -0.665223 1.64463 - 1.67652 -0.666565 1.78498 - 1.80823 -0.671564 1.90362 - 1.86854 -0.681686 1.95792 - 1.91314 -0.685527 1.99809 - 2.18251 -0.562446 2.24107 - 2.18606 -0.456335 2.24455 - 2.18817 -0.284986 2.24692 - 2.18236 -0.192805 2.24193 - 2.18325 -0.153799 2.24284 - 2.17994 -0.0367431 2.24017 - 2.18002 -0.023776 2.24027 - 2.18757 0.0672404 2.24733 - 2.18318 0.145137 2.24358 - 2.18951 0.27649 2.24963 - 1.91044 0.701483 1.99939 - 1.6454 0.68005 1.76058 - 1.46929 0.676371 1.60192 - 1.35232 0.678207 1.49655 - 1.26485 0.678661 1.41776 - 1.24866 0.687521 1.4032 - 1.24331 0.728394 1.39849 - 1.24613 0.914368 1.40154 - 1.24424 1.06262 1.40023 - 1.25202 1.17639 1.40754 - 1.24986 1.25323 1.40581 - 1.24405 1.2706 1.40062 - 1.21146 1.28387 1.37129 - 1.17137 1.28791 1.33519 - 1.04735 1.28455 1.22347 - 1.01773 1.28255 1.19678 - 0.993575 1.27511 1.175 - 0.844025 1.27417 1.04028 - 0.669982 1.2748 0.883495 - 0.545231 1.26503 0.77109 - 0.222702 0.605757 0.478774 - 0.216626 0.603427 0.473295 - 0.227004 0.656025 0.482785 - 0.358784 1.16287 0.60286 - 0.294962 1.23706 0.545567 - 0.215048 1.27819 0.473689 - 0.206747 1.28102 0.46622 - 0.203289 1.28628 0.463119 - 0.184622 1.27986 0.446285 - 0.1384 1.1683 0.404348 - 0.13461 1.16927 0.400936 - 0.103181 1.16738 0.372618 - 0.09853 1.16024 0.36841 - 0.0419229 1.17004 0.317443 - 0.007551 1.16692 0.286472 - -0.0223215 1.25696 0.259804 - -0.067136 1.25599 0.219432 - -0.105329 1.21374 0.184913 - -0.128271 1.15741 0.164094 - -0.139612 1.15657 0.153875 - -0.15578 1.23945 0.139534 - -0.268949 1.15805 0.0373696 - -0.311375 1.27591 -0.00053158 - -0.419313 1.27871 -0.097757 - -0.428739 1.27778 -0.106251 - -0.490164 1.12789 -0.161987 - -0.486015 1.08402 -0.158368 - -0.4882 0.996163 -0.160573 - -0.485273 0.835836 -0.158367 - -0.487992 0.825643 -0.160844 - -0.484088 0.722335 -0.157605 - -0.487305 0.666315 -0.160654 - -0.488949 0.662887 -0.162144 - -0.323124 -0.402635 -0.0227611 - -0.293811 -0.39924 0.00436121 - -0.289289 -0.399399 0.00854318 - -0.286234 -0.401737 0.011363 - -0.202673 -0.400656 0.0886562 - -0.155837 -0.406232 0.131963 - -0.151081 -0.405704 0.136363 - -0.50435 -1.81882 -0.194245 - -0.409215 -2.14219 -0.107131 - -0.384016 -2.12155 -0.0837664 - -0.29364 -2.13399 -0.00020629 - -0.279954 -2.1371 0.0124437 - -0.27207 -2.19243 0.019586 - -0.23163 -2.1437 0.0571239 - -0.067069 -0.512217 0.21378 - 0.165883 -2.18952 0.424682 - 0.0323136 -0.335053 0.306188 - 0.0351552 -0.332011 0.308824 - 0.0410579 -0.332941 0.314281 - 0.0593545 -0.335493 0.331198 - 0.0625687 -0.333906 0.334175 - 0.102666 -0.352597 0.371212 - 0.107846 -0.351205 0.376008 - 0.147609 -0.360898 0.412761 - 0.150809 -0.364006 0.415712 - 0.209889 -0.40672 0.470242 - 0.25313 -0.410011 0.510229 - 0.278567 -0.409728 0.533758 - 0.284881 -0.410927 0.539595 - 0.292039 -0.416665 0.5462 - 0.320755 -0.412315 0.572773 - 0.336245 -0.423079 0.587071 - 0.345767 -0.415317 0.5959 - 0.349715 -0.390645 0.599619 - 0.909039 -0.819189 1.1158 - 0.907443 -0.676051 1.11472 - 0.911723 -0.664911 1.11871 - 0.932306 -0.665053 1.13774 - 1.15015 -0.663172 1.33924 - 1.76393 -0.674873 1.90694 - 1.88247 -0.682988 2.01655 - 2.09287 -0.691233 2.21114 - 2.11364 -0.684564 2.23037 - 2.12946 -0.463257 2.24561 - 2.12576 -0.125978 2.24311 - 2.12572 -0.100333 2.24314 - 2.12757 0.00213388 2.24513 - 2.12715 0.0533912 2.24488 - 2.12607 0.104632 2.24402 - 2.12978 0.311227 2.24802 - 2.12988 0.467998 2.24853 - 2.12893 0.494142 2.24773 - 2.1268 0.586428 2.24601 - 1.78247 0.698037 1.92782 - 1.62709 0.680917 1.78405 - 1.47822 0.678864 1.64635 - 1.24775 0.704399 1.43324 - 1.24277 0.81899 1.42895 - 1.24819 0.937016 1.43428 - 1.24404 0.953617 1.4305 - 1.24269 1.03305 1.42946 - 1.25109 1.24687 1.43782 - 1.20322 1.2796 1.39363 - 0.99472 1.28126 1.20078 - 0.970027 1.28365 1.17794 - 0.965898 1.28958 1.17414 - 0.940199 1.27843 1.15034 - 0.920989 1.27519 1.13256 - 0.799414 1.27929 1.02012 - 0.794819 1.28345 1.01588 - 0.718976 1.27351 0.945704 - 0.709871 1.2808 0.937302 - 0.214927 0.620388 0.477701 - 0.235542 0.784897 0.497217 - 0.26941 1.27841 0.529888 - 0.254539 1.27217 0.516115 - 0.225297 1.28052 0.48909 - 0.113748 1.20921 0.385719 - 0.093677 1.1689 0.367043 - 0.0823373 1.17001 0.356558 - 0.0732559 1.24505 0.348362 - 0.0446327 1.17359 0.321692 - 0.0065247 1.16193 0.286412 - -0.0418594 1.15989 0.241654 - -0.0532569 1.17157 0.231143 - -0.1655 1.22723 0.127475 - -0.165768 1.16139 0.127047 - -0.209834 1.17272 0.0863194 - -0.242439 1.20066 0.0562372 - -0.275153 1.16096 0.0258699 - -0.310821 1.26659 -0.00683343 - -0.318919 1.2632 -0.0143337 - -0.443085 1.27553 -0.129148 - -0.459582 1.2808 -0.144393 - -0.478692 1.26413 -0.162114 - -0.479177 1.07967 -0.163065 - -0.47843 0.760722 -0.163243 - -0.302849 -0.398504 -0.0092915 - -0.255029 -0.399747 0.0358586 - -0.249492 -0.408059 0.0410637 - -0.194946 -0.397672 0.0925967 - -0.187896 -0.400823 0.099245 - -0.176561 -0.396649 0.109959 - -0.1753 -0.397535 0.111147 - -0.165039 -0.4088 0.120805 - -0.14966 -0.403856 0.13534 - -0.500391 -1.87165 -0.199869 - -0.501733 -2.08053 -0.201711 - -0.493776 -2.11007 -0.194278 - -0.450846 -2.14997 -0.153853 - -0.429256 -2.15162 -0.133471 - -0.393485 -2.11235 -0.0995866 - -0.357467 -2.15323 -0.0656901 - -0.34639 -2.1268 -0.0551581 - -0.314657 -2.15165 -0.0252634 - -0.290146 -2.12413 -0.00204352 - -0.224485 -2.15979 0.0598574 - -0.214531 -2.20678 0.0691269 - -0.0180356 -0.44778 0.259503 - 0.101369 -2.20206 0.367423 - 0.115334 -2.20045 0.380614 - 0.189909 -2.24045 0.45092 - 0.0269389 -0.322133 0.302315 - 0.0451218 -0.340307 0.319434 - 0.0470014 -0.328003 0.321242 - 0.0572903 -0.327443 0.330959 - 0.0859641 -0.340439 0.357998 - 0.0975713 -0.350551 0.36893 - 0.10647 -0.355556 0.377319 - 0.107256 -0.353859 0.378066 - 0.108376 -0.353042 0.379126 - 0.124181 -0.362712 0.394022 - 0.144473 -0.361939 0.413185 - 0.162286 -0.366975 0.429991 - 0.1698 -0.364372 0.437093 - 0.237746 -0.409319 0.501126 - 0.249774 -0.424057 0.512442 - 0.304252 -0.411182 0.563918 - 0.327463 -0.417239 0.585818 - 0.340189 -0.41342 0.597844 - 0.352441 -0.383379 0.609496 - 0.364374 -0.3811 0.620769 - 0.379299 -0.391918 0.634833 - 0.644285 -0.628543 0.88439 - 0.858382 -0.813024 1.08604 - 0.884633 -0.8292 1.11078 - 0.894874 -0.814866 1.12049 - 0.90312 -0.76802 1.12841 - 1.02771 -0.66038 1.24635 - 1.46539 -0.665674 1.6596 - 2.0305 -0.690559 2.19313 - 2.08605 -0.497468 2.24611 - 2.08377 -0.124734 2.24498 - 2.08551 -0.023264 2.2469 - 2.08554 0.00211281 2.247 - 2.08758 0.0783421 2.24914 - 2.08729 0.0910427 2.2489 - 2.08256 0.128911 2.24454 - 2.08137 0.358576 2.24405 - 2.08493 0.3979 2.24751 - 2.08507 0.410864 2.24768 - 2.08645 0.489169 2.24921 - 2.08729 0.528649 2.2501 - 2.01576 0.703616 2.18304 - 1.97616 0.702802 2.14565 - 1.4676 0.680747 1.66539 - 1.4413 0.678597 1.64056 - 1.24235 0.717295 1.45281 - 1.24797 0.811801 1.45837 - 1.24156 0.902365 1.45256 - 1.24757 1.23274 1.45915 - 1.24288 1.28619 1.45487 - 1.23177 1.28667 1.44438 - 1.04206 1.28432 1.26525 - 0.986716 1.28396 1.21299 - 0.90793 1.27028 1.13856 - 0.835522 1.27927 1.07021 - 0.815602 1.27191 1.05138 - 0.657415 1.26907 0.902007 - 0.602596 1.28102 0.850279 - 0.586737 1.2848 0.835315 - 0.21158 0.618625 0.479247 - 0.426981 1.23717 0.684337 - 0.356177 1.22558 0.61745 - 0.351486 1.2403 0.61306 - 0.306288 1.17824 0.570213 - 0.286338 1.28719 0.551674 - 0.238131 1.27137 0.506112 - 0.230049 1.27455 0.49849 - 0.226193 1.27706 0.494856 - 0.174268 1.27525 0.445821 - 0.128003 1.21053 0.401958 - 0.123587 1.239 0.397868 - 0.0917494 1.16494 0.367602 - 0.0576526 1.16069 0.335395 - 0.0322912 1.24901 0.311691 - 0.0243629 1.24972 0.304206 - -0.0727172 1.19158 0.21238 - -0.120358 1.16847 0.167333 - -0.168604 1.16155 0.121758 - -0.236108 1.17442 0.0580538 - -0.25781 1.16371 0.0375332 - -0.347723 1.28182 -0.0470404 - -0.371189 1.21798 -0.0693735 - -0.395353 1.23928 -0.0921319 - -0.425875 1.27818 -0.120845 - -0.434255 1.27431 -0.128768 - -0.475053 1.26503 -0.167316 - -0.481454 1.11731 -0.173767 - -0.483926 1.03672 -0.176322 - -0.480941 1.00993 -0.173577 - -0.482216 1.00296 -0.1748 - -0.478162 0.920819 -0.171198 - -0.478859 0.661425 -0.17257 - -0.310471 -0.405991 -0.0220126 - -0.309191 -0.407696 -0.0207832 - -0.287439 -0.406943 0.00018173 - -0.278746 -0.400248 0.00857864 - -0.265273 -0.402922 0.0215558 - -0.219931 -0.402125 0.0652558 - -0.216508 -0.406411 0.0685431 - -0.214842 -0.406702 0.0701473 - -0.194871 -0.404748 0.0894 - -0.166629 -0.402692 0.116624 - -0.162518 -0.404258 0.120581 - -0.146293 -0.410652 0.136201 - -0.506354 -1.83476 -0.214762 - -0.500822 -1.83859 -0.209441 - -0.497828 -2.08244 -0.207234 - -0.487405 -2.13393 -0.197331 - -0.48353 -2.15013 -0.193641 - -0.378828 -2.12838 -0.092675 - -0.353791 -2.14834 -0.068601 - -0.29392 -2.1176 -0.0108157 - -0.212069 -2.19586 0.0678506 - -0.0567121 -0.503471 0.222276 - -0.103068 -2.26247 0.172714 - 0.0529149 -2.24832 0.323082 - 0.0907103 -2.29328 0.359382 - 0.136928 -2.23155 0.404096 - 0.0352945 -0.336467 0.311411 - 0.0434967 -0.332204 0.319327 - 0.0529619 -0.333236 0.328446 - 0.0605002 -0.330555 0.335719 - 0.0683533 -0.337059 0.343269 - 0.069682 -0.337395 0.344549 - 0.0717966 -0.33619 0.34659 - 0.0944439 -0.346068 0.368389 - 0.135222 -0.360114 0.40765 - 0.144474 -0.366118 0.416549 - 0.219352 -0.413386 0.488581 - 0.243998 -0.423485 0.512306 - 0.250681 -0.408103 0.51879 - 0.263349 -0.411963 0.530987 - 0.309775 -0.415121 0.575721 - 0.335193 -0.412156 0.600226 - 0.334799 -0.408062 0.599858 - 0.859686 -0.822458 1.10456 - 0.872784 -0.811146 1.11722 - 0.871164 -0.712651 1.11593 - 0.872809 -0.671204 1.11763 - 1.33232 -0.667575 1.5605 - 2.02989 -0.684018 2.23272 - 2.04217 -0.622137 2.24473 - 2.04041 -0.569331 2.24319 - 2.03839 -0.465353 2.24153 - 2.03941 -0.401515 2.24269 - 2.04543 -0.287951 2.2488 - 2.0463 -0.275379 2.24967 - 2.04289 -0.249615 2.24646 - 2.03729 -0.0855909 2.24152 - 2.04275 -0.0606926 2.24685 - 2.04302 -0.0355809 2.24718 - 2.04199 0.0523004 2.24643 - 2.04375 0.432513 2.24919 - 2.04148 0.483533 2.24714 - 1.82709 0.705218 2.04114 - 1.57187 0.681964 1.79511 - 1.38292 0.677304 1.613 - 1.25197 0.693912 1.48683 - 1.24794 1.01655 1.48385 - 1.24965 1.10213 1.48574 - 1.19039 1.28009 1.42912 - 1.04539 1.27855 1.28937 - 1.02537 1.2771 1.27007 - 1.01485 1.27557 1.25993 - 0.856235 1.27772 1.10707 - 0.842721 1.28044 1.09405 - 0.705743 1.27663 0.962033 - 0.648121 1.2764 0.906499 - 0.630148 1.27727 0.88918 - 0.587246 1.28691 0.84786 - 0.548973 1.27848 0.810951 - 0.373913 0.917847 0.641236 - 0.223976 0.605804 0.495869 - 0.21731 0.60191 0.489434 - 0.211764 0.60052 0.484085 - 0.215025 0.634488 0.487322 - 0.285117 1.27771 0.556659 - 0.211309 1.28158 0.485538 - 0.061953 1.18401 0.341326 - 0.0450097 1.15421 0.324914 - 0.0127839 1.17044 0.293902 - -0.0057532 1.16448 0.27602 - -0.0460253 1.1658 0.237212 - -0.0668977 1.25 0.21733 - -0.0730366 1.20257 0.211282 - -0.123242 1.16494 0.162792 - -0.164218 1.23317 0.123491 - -0.21361 1.19022 0.0757707 - -0.214562 1.17151 0.0748008 - -0.232232 1.16178 0.0577444 - -0.356538 1.27412 -0.0617428 - -0.387257 1.22259 -0.0914909 - -0.48428 1.24703 -0.184928 - -0.482818 0.94767 -0.184351 - -0.478213 0.895142 -0.180059 - -0.482823 0.879601 -0.184545 - -0.48312 0.825792 -0.184981 - -0.478843 0.796225 -0.180941 - -0.479995 0.791144 -0.182065 - -0.476893 0.658724 -0.179444 - -0.306141 -0.399978 -0.0236292 - -0.258385 -0.401874 0.0233896 - -0.241829 -0.397138 0.0397057 - -0.241037 -0.402948 0.0404693 - -0.201178 -0.403044 0.079717 - -0.177786 -0.406432 0.102741 - -0.173337 -0.40288 0.107132 - -0.152579 -0.399964 0.12758 - -0.504476 -2.00903 -0.223441 - -0.49829 -2.0424 -0.217443 - -0.478057 -2.14534 -0.197809 - -0.456657 -2.14671 -0.176741 - -0.388675 -2.12402 -0.109737 - -0.366156 -2.15796 -0.0876581 - -0.320945 -2.13435 -0.0430743 - -0.300756 -2.13761 -0.0232034 - -0.259786 -2.20277 0.0169555 - -0.238295 -2.12632 0.0383317 - -0.225062 -2.12883 0.051355 - -0.0690917 -0.543049 0.209386 - -0.122987 -2.2449 0.15154 - 0.110919 -2.18451 0.382031 - 0.134577 -2.22657 0.405208 - 0.141496 -2.22556 0.412025 - 0.175584 -2.21494 0.44562 - 0.0251947 -0.439502 0.302519 - 0.0270237 -0.431936 0.304341 - 0.0289036 -0.324989 0.306492 - 0.0432489 -0.330807 0.320601 - 0.0442761 -0.330362 0.321614 - 0.0464611 -0.325184 0.32378 - 0.0733585 -0.33772 0.35023 - 0.0798717 -0.342468 0.35663 - 0.084854 -0.345886 0.361527 - 0.0880674 -0.343765 0.364697 - 0.100471 -0.359738 0.376866 - 0.114316 -0.358449 0.390502 - 0.148808 -0.362434 0.424454 - 0.257426 -0.415486 0.531259 - 0.278869 -0.416481 0.552371 - 0.286603 -0.412287 0.559998 - 0.287879 -0.410351 0.56126 - 0.319511 -0.420674 0.592377 - 0.325157 -0.423728 0.597928 - 0.408366 -0.432989 0.679837 - 0.856205 -0.737404 1.11996 - 0.84972 -0.703235 1.11367 - 0.853849 -0.657298 1.11786 - 0.86977 -0.662118 1.13353 - 1.01312 -0.664934 1.27467 - 1.10467 -0.665533 1.36482 - 1.10803 -0.659352 1.36815 - 1.13919 -0.660738 1.39882 - 1.16043 -0.664308 1.41973 - 1.18173 -0.66763 1.44069 - 1.35767 -0.668279 1.61393 - 1.458 -0.666136 1.71273 - 1.76817 -0.685467 2.01809 - 1.99275 -0.639726 2.23936 - 1.99724 -0.5763 2.24396 - 1.99381 -0.371633 2.24116 - 2.00115 -0.234678 2.24877 - 1.99729 -0.184332 2.24511 - 1.99664 -0.0599756 2.24482 - 1.99679 -0.0475685 2.24501 - 1.99413 -0.02272 2.24245 - 1.9934 0.0144501 2.24184 - 1.99902 0.0766203 2.24754 - 1.99626 0.126206 2.24497 - 2.00327 0.289412 2.25233 - 2.00035 0.326736 2.24956 - 2.00061 0.364639 2.24992 - 1.99934 0.440488 2.24888 - 1.99683 0.503736 2.24659 - 2.00143 0.660502 2.25156 - 1.9902 0.696102 2.2406 - 1.89662 0.701525 2.14847 - 1.82063 0.69811 2.07363 - 1.57539 0.68005 1.8321 - 1.24104 0.805483 1.50323 - 1.24582 0.904648 1.50822 - 1.24334 0.952447 1.5059 - 1.24804 1.00688 1.51069 - 1.24536 1.14306 1.50843 - 1.22017 1.28974 1.48404 - 0.979466 1.27907 1.24699 - 0.752734 1.27881 1.02373 - 0.745054 1.27751 1.01617 - 0.707065 1.28149 0.978771 - 0.610125 1.28754 0.883333 - 0.218142 0.59889 0.495424 - 0.209262 0.601393 0.486687 - 0.420508 1.27395 0.696584 - 0.405417 1.25875 0.681681 - 0.356072 1.18098 0.632874 - 0.328346 1.23596 0.605728 - 0.303811 1.19593 0.581456 - 0.229098 1.27778 0.508118 - 0.22095 1.27996 0.500101 - 0.178849 1.28151 0.458649 - 0.150001 1.17481 0.429944 - 0.131287 1.17713 0.411523 - 0.11912 1.23308 0.3997 - 0.00085983 1.16313 0.283055 - -0.0425829 1.16589 0.240286 - -0.0499365 1.1717 0.233061 - -0.0537642 1.18057 0.229317 - -0.0754222 1.17035 0.207962 - -0.0901225 1.17208 0.193492 - -0.136631 1.15756 0.147655 - -0.192164 1.18565 0.0930521 - -0.212991 1.17151 0.072505 - -0.222924 1.16223 0.0626979 - -0.257145 1.22254 0.0291709 - -0.256165 1.1753 0.0300027 - -0.310612 1.2405 -0.0234265 - -0.373914 1.2185 -0.08582 - -0.390129 1.22875 -0.101758 - -0.432828 1.27828 -0.143664 - -0.43767 1.27855 -0.148431 - -0.482884 1.16573 -0.193268 - -0.480062 1.12332 -0.190609 - -0.477758 0.992427 -0.188708 - -0.480993 0.962105 -0.191978 - -0.487679 0.881361 -0.198788 - -0.480326 0.792322 -0.191798 - -0.472981 0.682769 -0.184873 - -0.292299 -0.397233 -0.0155617 - -0.272011 -0.400244 0.00483641 - -0.267265 -0.399415 0.00961287 - -0.263552 -0.4038 0.0133348 - -0.251293 -0.407433 0.0256547 - -0.204719 -0.40689 0.0725024 - -0.180272 -0.403662 0.0971014 - -0.150632 -0.401636 0.12692 - -0.500145 -2.1349 -0.229549 - -0.333753 -2.14831 -0.0622241 - -0.0555507 -0.510619 0.222247 - -0.134219 -2.20472 0.138314 - -0.122787 -2.25788 0.149662 - -0.0341003 -0.415941 0.244091 - -0.0236492 -0.430928 0.254561 - -0.0177111 -0.45471 0.260466 - 0.0580813 -2.25981 0.33158 - 0.0807523 -2.29596 0.354281 - 0.0300338 -0.330446 0.308842 - 0.0437807 -0.328003 0.322676 - 0.0556781 -0.334971 0.334623 - 0.0809693 -0.338623 0.360052 - 0.0917787 -0.3401 0.37092 - 0.115342 -0.361918 0.394559 - 0.156078 -0.37138 0.435506 - 0.206276 -0.419235 0.485861 - 0.218922 -0.41877 0.498582 - 0.232045 -0.414538 0.511794 - 0.240346 -0.402304 0.520178 - 0.257139 -0.412676 0.537039 - 0.262385 -0.416578 0.542305 - 0.293765 -0.411851 0.573882 - 0.315747 -0.417239 0.595977 - 0.330266 -0.376747 0.610696 - 0.337686 -0.381016 0.618146 - 0.531523 -0.560984 0.812605 - 0.810825 -0.817024 1.09281 - 0.833238 -0.726169 1.11561 - 1.03243 -0.661021 1.31615 - 1.08129 -0.667005 1.36528 - 1.12397 -0.659242 1.40824 - 1.14172 -0.660979 1.42607 - 1.50269 -0.662397 1.78915 - 1.89245 -0.689956 2.18111 - 1.95277 -0.659658 2.24187 - 1.95615 -0.596323 2.24545 - 1.95063 -0.218978 2.24097 - 1.9581 0.423601 2.2503 - 1.95246 0.599997 2.24513 - 1.51151 0.680965 1.80183 - 1.24341 0.825307 1.53258 - 1.24723 1.20233 1.53749 - 1.21234 1.28383 1.50263 - 1.11442 1.28332 1.40413 - 1.00588 1.28104 1.29496 - 0.633304 1.2764 0.920191 - 0.599011 1.27934 0.885707 - 0.228211 0.618179 0.510867 - 0.206602 0.608104 0.489103 - 0.205739 0.612198 0.488247 - 0.426112 1.27639 0.711791 - 0.381853 1.23155 0.667146 - 0.367494 1.24433 0.652739 - 0.339409 1.25734 0.624527 - 0.295759 1.1961 0.580448 - 0.29176 1.28033 0.576665 - 0.189442 1.28531 0.473764 - 0.146874 1.16895 0.430618 - 0.0468992 1.1627 0.330042 --0.00983762 1.20661 0.273098 - -0.0355575 1.15298 0.247076 - -0.0934402 1.1717 0.188909 - -0.158531 1.23594 0.123621 - -0.198814 1.21606 0.0830458 - -0.230044 1.16955 0.0515015 - -0.375845 1.2371 -0.0949592 - -0.377588 1.2124 -0.0967817 - -0.428652 1.27736 -0.14796 - -0.484269 1.05706 -0.204527 - -0.476712 1.00956 -0.19706 - -0.482532 0.993641 -0.202959 - -0.482244 0.810766 -0.203188 - -0.48132 0.753608 -0.202421 - -0.304835 -0.3987 -0.0340313 - -0.298005 -0.402636 -0.0270278 - -0.287859 -0.401208 -0.0166033 - -0.27507 -0.405534 -0.00347981 - -0.257155 -0.403575 0.0149261 - -0.247492 -0.400536 0.0248603 - -0.238024 -0.404556 0.0345726 - -0.217277 -0.403458 0.0558852 - -0.186108 -0.401511 0.0879041 - -0.177348 -0.399246 0.0969086 - -0.17057 -0.397535 0.103875 - -0.450064 -2.15634 -0.188235 - -0.383245 -2.13375 -0.119541 - -0.376744 -2.13595 -0.11287 - -0.371476 -2.14592 -0.107488 - -0.0858512 -2.18937 0.185753 - -0.0305574 -0.420996 0.247615 - -0.0180807 -0.456709 0.260327 - 0.0988795 -2.26885 0.375262 - 0.102201 -2.20825 0.378847 - 0.107854 -2.19049 0.384704 - 0.121181 -2.18872 0.398397 - 0.154866 -2.18853 0.432995 - 0.177618 -2.21467 0.456289 - 0.0263736 -0.440791 0.306032 - 0.0332652 -0.341301 0.313395 - 0.0587875 -0.333751 0.339631 - 0.0778293 -0.345208 0.359156 - 0.0886205 -0.346811 0.370235 - 0.112663 -0.367191 0.394871 - 0.213747 -0.414942 0.498557 - 0.222885 -0.415581 0.507941 - 0.256751 -0.416953 0.542721 - 0.260262 -0.414769 0.546334 - 0.269524 -0.409755 0.55586 - 0.285987 -0.413807 0.572758 - 0.298822 -0.415783 0.585935 - 0.311553 -0.398881 0.59906 - 0.354449 -0.399293 0.643117 - 0.578786 -0.620718 0.872898 - 0.812219 -0.730593 1.11234 - 0.815419 -0.71902 1.11566 - 0.993834 -0.667004 1.29906 - 1.11602 -0.66186 1.42457 - 1.14201 -0.668376 1.45125 - 1.91075 -0.614398 2.24097 - 1.91053 -0.314835 2.2416 - 1.91357 -0.0709308 2.24543 - 1.9113 0.00202199 2.24331 - 1.91072 0.0627322 2.24289 - 1.91304 0.307178 2.24597 - 1.91635 0.544688 2.25005 - 1.80618 0.695448 2.13733 - 1.51828 0.680792 1.84159 - 1.24605 0.769337 1.56223 - 1.24637 0.875267 1.56286 - 1.24171 1.03443 1.55853 - 1.22025 1.28233 1.5372 - 1.21576 1.28957 1.53261 - 0.980724 1.27491 1.29116 - 0.97031 1.2842 1.28049 - 0.771218 1.28053 1.076 - 0.714917 1.27777 1.01816 - 0.68697 1.27449 0.989448 - 0.644294 1.27669 0.945622 - 0.63399 1.28029 0.935048 - 0.368699 1.26253 0.662517 - 0.34691 1.26649 0.64015 - 0.303914 1.19363 0.595779 - 0.227828 1.28097 0.517882 - 0.20701 1.28203 0.496503 - 0.144956 1.1709 0.432448 - 0.0964166 1.1656 0.382578 - 0.0141011 1.17316 0.298054 - -0.0287832 1.18599 0.254044 - -0.0668669 1.25299 0.215121 - -0.0706801 1.25276 0.211203 - -0.0754976 1.17933 0.206045 - -0.115807 1.24017 0.164817 - -0.169498 1.17452 0.109483 - -0.180459 1.1738 0.0982231 - -0.254007 1.16523 0.0226575 - -0.276819 1.16415 -0.00077638 - -0.322077 1.27696 -0.046937 - -0.344209 1.27891 -0.0696632 - -0.369928 1.27611 -0.0960875 - -0.37847 1.2121 -0.105044 - -0.408429 1.26898 -0.135652 - -0.41367 1.27121 -0.141029 - -0.427519 1.27124 -0.155253 - -0.448548 1.26399 -0.176873 - -0.479679 1.24416 -0.208904 - -0.478414 1.15316 -0.207866 - -0.481231 1.14861 -0.210772 - -0.481493 1.00121 -0.211464 - -0.479887 0.94267 -0.209982 - -0.482007 0.929633 -0.212197 - -0.478803 0.914525 -0.208949 - -0.479739 0.836519 -0.210134 - -0.484455 0.808267 -0.215059 - -0.479081 0.764045 -0.209666 - -0.273945 -0.403994 -0.00761278 - -0.271822 -0.404024 -0.00538577 - -0.236855 -0.398736 0.0313018 - -0.233215 -0.398926 0.0351183 - -0.217844 -0.408449 0.0512111 - -0.208216 -0.394914 0.0613482 - -0.193524 -0.403414 0.0767321 - -0.171842 -0.404666 0.099468 - -0.166653 -0.402839 0.104915 - -0.161817 -0.401789 0.109989 - -0.157312 -0.401533 0.114715 - -0.154042 -0.400394 0.118148 - -0.151623 -0.401949 0.12068 - -0.147912 -0.435559 0.124475 - -0.140466 -0.441771 0.132266 - -0.453216 -2.15848 -0.200711 - -0.356131 -2.15698 -0.0988869 - -0.289195 -2.1071 -0.0285423 - -0.0588256 -0.513261 0.217681 - -0.120608 -2.24091 0.147879 - -0.0857659 -2.20036 0.184537 - -0.021451 -0.446837 0.25707 - 0.0547103 -2.23285 0.33177 - 0.0909008 -2.27859 0.369592 - 0.165538 -2.1832 0.448145 - 0.0230286 -0.33123 0.304054 - 0.0353651 -0.340092 0.316967 - 0.0432495 -0.330404 0.325264 - 0.0477495 -0.326122 0.329995 - 0.0501062 -0.33129 0.332452 - 0.072354 -0.340121 0.355759 - 0.0797634 -0.336341 0.363541 - 0.087892 -0.34174 0.37205 - 0.0985779 -0.349511 0.383235 - 0.105836 -0.3506 0.390844 - 0.107231 -0.350608 0.392307 - 0.192984 -0.408915 0.482073 - 0.219747 -0.411745 0.510132 - 0.283313 -0.415158 0.576788 - 0.286605 -0.415861 0.580239 - 0.28888 -0.415194 0.582627 - 0.303091 -0.411399 0.597542 - 0.323116 -0.381359 0.61863 - 0.59589 -0.651363 0.903924 - 0.800732 -0.686385 1.11865 - 0.798979 -0.664285 1.11688 - 0.874277 -0.658892 1.19586 - 0.92312 -0.664566 1.24707 - 0.959808 -0.659602 1.28557 - 1.29018 -0.666233 1.63203 - 1.86912 -0.409206 2.23994 - 1.86739 -0.311235 2.23841 - 1.87015 -0.214703 2.24159 - 1.87118 -0.178576 2.24278 - 1.8697 0.134276 2.24213 - 1.87283 0.291966 2.24587 - 1.8765 0.439868 2.25015 - 1.87164 0.525575 2.2453 - 1.34969 0.680976 1.69834 - 1.25742 0.681292 1.60158 - 1.25276 0.688047 1.59671 - 1.24162 0.691248 1.58504 - 1.24804 0.788669 1.59205 - 1.24878 0.866869 1.59306 - 1.24474 0.88389 1.58886 - 1.2431 0.922739 1.58726 - 1.24994 0.958304 1.59453 - 1.24783 0.987705 1.59241 - 1.24172 1.28269 1.58686 - 1.09602 1.2793 1.43404 - 1.08025 1.27279 1.41748 - 0.89901 1.27131 1.2274 - 0.675056 1.27897 0.992546 - 0.618132 1.2756 0.932835 - 0.554035 1.28563 0.865642 - 0.495038 1.24882 0.803661 - 0.215275 0.62623 0.50845 - 0.345776 1.26227 0.647159 - 0.311618 1.2051 0.61117 - 0.274713 1.27673 0.572672 - 0.191836 1.28253 0.485771 - 0.18797 1.28393 0.48172 - 0.0818774 1.18151 0.370157 - 0.0818716 1.22086 0.370265 - -0.0663767 1.23801 0.214837 - -0.124061 1.16238 0.15412 - -0.137491 1.15393 0.140011 - -0.174305 1.16389 0.10143 - -0.261475 1.15615 0.00998743 - -0.296366 1.22979 -0.0263924 - -0.329157 1.28277 -0.0606287 - -0.352211 1.27107 -0.0848404 - -0.423582 1.27124 -0.159692 - -0.433807 1.27443 -0.170406 - -0.480845 1.14752 -0.220106 - -0.479447 1.09897 -0.218781 - -0.480621 1.09097 -0.220035 - -0.481854 0.930081 -0.221794 - -0.479351 0.859658 -0.219373 - -0.47911 0.700805 -0.219581 - -0.288368 -0.406175 -0.0281657 - -0.27619 -0.400816 -0.0151231 - -0.263485 -0.397212 -0.0015213 - -0.262297 -0.398699 -0.00025485 - -0.252508 -0.402798 0.0102048 - -0.250026 -0.401874 0.0128628 - -0.214276 -0.40429 0.0510987 - -0.194342 -0.404954 0.0724206 - -0.173302 -0.399281 0.0949449 - -0.166108 -0.404634 0.102626 - -0.164899 -0.405499 0.103915 - -0.155909 -0.405066 0.113535 - -0.153488 -0.406658 0.11612 - -0.50312 -1.81632 -0.262026 - -0.131611 -0.426836 0.139463 - -0.464195 -2.16452 -0.221405 - -0.223207 -2.18931 0.0363166 - -0.187569 -2.15429 0.0745427 - -0.0568053 -0.504468 0.219259 - -0.0298635 -0.417999 0.248333 - -0.0247431 -0.427928 0.253781 - 0.100065 -2.22718 0.382024 - 0.139902 -2.22253 0.424654 - 0.0211479 -0.457911 0.302785 - 0.0297008 -0.45874 0.311932 - 0.0500314 -0.326502 0.334068 - 0.0600744 -0.339154 0.344774 - 0.128548 -0.371276 0.417929 - 0.139829 -0.36161 0.430025 - 0.142467 -0.363805 0.43284 - 0.196602 -0.409314 0.490618 - 0.205493 -0.414154 0.500115 - 0.210948 -0.412643 0.505955 - 0.229558 -0.417946 0.525848 - 0.240991 -0.410454 0.538099 - 0.298488 -0.39256 0.599659 - 0.339543 -0.399922 0.643556 - 0.781651 -0.74833 1.11548 - 0.779498 -0.724888 1.11324 - 0.775979 -0.666376 1.10965 - 0.795636 -0.661923 1.13069 - 0.983122 -0.659055 1.33126 - 1.15835 -0.666374 1.51869 - 1.23871 -0.665359 1.60466 - 1.28003 -0.668207 1.64885 - 1.46873 -0.669105 1.85071 - 1.63351 -0.684974 2.02693 - 1.83139 -0.117056 2.24027 - 1.83167 0.156866 2.24138 - 1.83425 0.216962 2.24432 - 1.83353 0.240877 2.24362 - 1.83459 0.313293 2.24496 - 1.83412 0.373768 2.24464 - 1.83659 0.658902 2.24811 - 1.38773 0.67702 1.768 - 1.31102 0.678609 1.68595 - 1.24129 0.707809 1.61144 - 1.2462 0.757689 1.61684 - 1.24303 0.882219 1.61381 - 1.24708 1.05092 1.61864 - 1.21649 1.2827 1.58659 - 0.954157 1.29153 1.30599 - 0.865292 1.27148 1.21087 - 0.84512 1.2759 1.1893 - 0.736749 1.28646 1.0734 - 0.711018 1.27675 1.04585 - 0.694299 1.28166 1.02798 - 0.687869 1.28166 1.0211 - 0.64493 1.28322 0.975171 - 0.577854 1.27852 0.903403 - 0.573645 1.28159 0.89891 - 0.464621 1.21342 0.782082 - 0.38311 1.2785 0.695077 - 0.301508 1.18292 0.607503 - 0.289913 1.28285 0.595392 - 0.147734 1.16963 0.442966 - 0.0931989 1.16659 0.384619 - 0.0164453 1.18384 0.302562 - -0.114528 1.23818 0.162614 - -0.160096 1.24404 0.113885 - -0.216688 1.16515 0.0531146 - -0.231542 1.16608 0.0372276 - -0.310892 1.2702 -0.0473518 - -0.319956 1.27324 -0.0570387 - -0.480222 1.14554 -0.228856 - -0.482177 1.03267 -0.231278 - -0.479935 0.823608 -0.229492 - -0.480684 0.789122 -0.230394 - -0.478078 0.724833 -0.227794 - -0.264723 -0.401003 -0.00972965 - -0.26279 -0.404786 -0.00761655 - -0.257911 -0.406962 -0.00226089 - -0.193526 -0.403901 0.0685118 - -0.182389 -0.399657 0.0807643 - -0.178062 -0.408892 0.0854922 - -0.174031 -0.401895 0.0899437 - -0.171044 -0.401967 0.0932258 - -0.15978 -0.403595 0.105602 - -0.153351 -0.401425 0.112674 - -0.151071 -0.39857 0.115187 - -0.147419 -0.420491 0.119137 - -0.146941 -0.424023 0.119651 - -0.506872 -1.85647 -0.280191 - -0.503541 -1.86797 -0.276564 - -0.499938 -1.9041 -0.272711 - -0.340696 -2.14829 -0.0984209 - -0.194294 -2.18504 0.0623742 - -0.0602626 -0.513072 0.214651 - -0.0290102 -0.418994 0.249279 - -0.0277798 -0.41898 0.250631 - -0.0236731 -0.443886 0.255071 - -0.022311 -0.446837 0.256559 - 0.0660544 -2.25169 0.348314 - 0.101986 -2.1865 0.387999 - 0.144124 -2.2274 0.43419 - 0.15199 -2.16355 0.443024 - 0.0220215 -0.451327 0.30527 - 0.0345353 -0.472253 0.318961 - 0.0279226 -0.323521 0.312135 - 0.0313763 -0.336643 0.315892 - 0.0397439 -0.325643 0.325121 - 0.0473048 -0.326069 0.33343 - 0.078411 -0.34267 0.367568 - 0.106175 -0.358438 0.398036 - 0.107225 -0.357549 0.399192 - 0.109625 -0.360115 0.401823 - 0.17792 -0.410273 0.476733 - 0.1873 -0.417248 0.487022 - 0.1967 -0.412505 0.497367 - 0.212144 -0.414073 0.514337 - 0.224815 -0.413336 0.528265 - 0.280331 -0.415194 0.589275 - 0.288519 -0.415043 0.598274 - 0.287802 -0.396256 0.597542 - 0.294717 -0.380391 0.605189 - 0.310397 -0.384598 0.62241 - 0.758827 -0.675647 1.1144 - 0.760796 -0.670526 1.11657 - 0.795885 -0.665221 1.15516 - 0.884207 -0.661391 1.25224 - 0.926614 -0.661631 1.29885 - 0.934659 -0.659602 1.30769 - 1.08156 -0.665973 1.46913 - 1.15969 -0.668324 1.55499 - 1.23394 -0.663577 1.63661 - 1.28363 -0.670553 1.69119 - 1.33544 -0.667443 1.74816 - 1.78646 -0.534926 2.24425 - 1.79184 -0.463235 2.25037 - 1.78181 -0.115641 2.24038 - 1.78835 0.0845709 2.24816 - 1.78726 0.143584 2.24714 - 1.78985 0.26257 2.25034 - 1.79088 0.286598 2.25154 - 1.78602 0.369565 2.24644 - 1.7849 0.381346 2.24525 - 1.78869 0.466829 2.24967 - 1.78436 0.502196 2.24502 - 1.72076 0.699926 2.1757 - 1.62767 0.697493 2.07339 - 1.26819 0.676279 1.67823 - 1.25149 0.686342 1.6599 - 1.2451 1.01121 1.65385 - 1.24499 1.03252 1.65379 - 1.24708 1.05584 1.65616 - 1.02071 1.2811 1.40804 - 0.924654 1.28309 1.30247 - 0.863355 1.27681 1.23508 - 0.732725 1.27658 1.09151 - 0.629692 1.28515 0.978296 - 0.585305 1.27808 0.929491 - 0.551983 1.27854 0.892869 - 0.548592 1.28315 0.889156 - 0.431289 1.25948 0.760163 - 0.412048 1.27245 0.739054 - 0.279229 1.27738 0.593094 - 0.249469 1.27575 0.56038 - 0.20472 1.27706 0.511203 - 0.20009 1.27377 0.506104 - 0.183939 1.27283 0.48835 - 0.127667 1.23211 0.426383 - 0.084797 1.17508 0.379097 - 0.081912 1.18177 0.375946 - 0.0817141 1.25852 0.375957 - 0.0780163 1.25925 0.371895 - 0.0455965 1.16519 0.335984 - 0.0343696 1.21289 0.323787 - -0.0847233 1.16444 0.192753 - -0.0919217 1.17071 0.18486 - -0.114542 1.25013 0.160235 - -0.211149 1.16729 0.0538118 - -0.242712 1.20221 0.0192263 - -0.388132 1.2262 -0.140528 - -0.450425 1.26954 -0.208863 - -0.482969 1.24245 -0.24471 - -0.480722 1.10612 -0.242646 - -0.482317 0.944367 -0.244879 - -0.298398 -0.399468 -0.0530739 - -0.217121 -0.400768 0.0381741 - -0.207145 -0.401291 0.0493727 - -0.201483 -0.399679 0.0557353 - -0.194799 -0.407117 0.0632169 - -0.193614 -0.408189 0.0645437 - -0.151109 -0.397784 0.112296 - -0.500362 -1.8518 -0.284191 - -0.501525 -1.88107 -0.285585 - -0.491411 -2.14894 -0.275035 - -0.466956 -2.16364 -0.247623 - -0.440306 -2.16713 -0.217713 - -0.434009 -2.16981 -0.210651 - -0.426121 -2.16378 -0.201777 - -0.41845 -2.15865 -0.193149 - -0.1128 -2.27542 0.149662 - -0.0341893 -0.419967 0.243499 - 0.0859753 -2.28258 0.37281 - 0.101339 -2.20543 0.390291 - 0.0318734 -0.339129 0.317912 - 0.0653948 -0.336172 0.355557 - 0.0764145 -0.345186 0.367902 - 0.0798524 -0.348276 0.371752 - 0.0875514 -0.341369 0.380417 - 0.0965969 -0.352266 0.39054 - 0.133006 -0.364597 0.43138 - 0.267159 -0.417057 0.58184 - 0.285341 -0.37752 0.602372 - 0.742181 -0.760186 1.11413 - 0.747205 -0.667057 1.12005 - 0.806603 -0.646976 1.1868 - 0.867121 -0.664221 1.25469 - 0.967046 -0.666364 1.36687 - 1.07884 -0.663938 1.49239 - 1.28691 -0.67069 1.72598 - 1.29956 -0.667424 1.7402 - 1.73307 -0.683613 2.22685 - 1.74484 -0.553187 2.24046 - 1.74553 -0.517059 2.24135 - 1.74682 -0.397439 2.24316 - 1.74908 0.142258 2.24732 - 1.74465 0.153593 2.24238 - 1.74715 0.247716 2.24546 - 1.74876 0.438039 2.24785 - 1.74808 0.461897 2.24716 - 1.74778 0.497989 2.24692 - 1.74977 0.645321 2.2496 - 1.31456 0.679233 1.76108 - 1.24527 0.86719 1.68385 - 1.23998 0.893959 1.67799 - 1.24157 0.90529 1.67981 - 1.24709 1.05765 1.68646 - 1.24741 1.17019 1.68717 - 1.24569 1.18015 1.68526 - 1.24619 1.19222 1.68586 - 0.785749 1.277 1.16917 - 0.659207 1.27618 1.02709 - 0.541102 1.28232 0.894513 - 0.524064 1.28012 0.875377 - 0.486698 1.27782 0.833418 - 0.480576 1.27523 0.826537 - 0.358452 1.28 0.68944 - 0.304211 1.21214 0.628338 - 0.300687 1.21434 0.624388 - 0.207295 1.2861 0.51975 - 0.203206 1.28574 0.515158 - 0.177706 1.27617 0.486499 - 0.128049 1.19568 0.430506 - 0.104215 1.17601 0.403688 - 0.0581107 1.16596 0.351896 - 0.00360285 1.16669 0.2907 - -0.0156715 1.25172 0.269316 - -0.0267852 1.19596 0.256671 - -0.117734 1.25257 0.15473 - -0.121831 1.16337 0.149863 - -0.132636 1.16946 0.13775 - -0.180297 1.16109 0.0842144 - -0.209491 1.19186 0.0515304 - -0.227077 1.16608 0.0317084 - -0.263182 1.16471 -0.00883216 - -0.31726 1.23737 -0.0693282 - -0.375134 1.23855 -0.134301 - -0.480957 1.11897 -0.253472 - -0.484751 0.951206 -0.258235 - -0.477434 0.902244 -0.250167 - -0.483757 0.882508 -0.257326 - -0.481716 0.832609 -0.255185 - -0.479281 0.799261 -0.252552 - -0.482161 0.79033 -0.255811 - -0.481906 0.776104 -0.255568 - -0.482718 0.744166 -0.256576 - -0.484201 0.714724 -0.258329 - -0.294247 -0.397354 -0.0544474 - -0.25749 -0.400244 -0.0123453 - -0.217539 -0.405686 0.0334083 - -0.183077 -0.401137 0.0729041 - -0.173615 -0.400019 0.0837481 - -0.162009 -0.404634 0.0970304 - -0.150388 -0.408486 0.110333 - -0.147889 -0.414503 0.113177 - -0.148739 -0.422641 0.11218 - -0.448136 -2.16068 -0.236116 - -0.388661 -2.12451 -0.167868 - -0.360908 -2.15445 -0.136164 - -0.301421 -2.14417 -0.06798 - -0.271569 -2.16159 -0.0338326 - -0.0556263 -0.511616 0.218585 - -0.104001 -2.22802 0.157943 - -0.0902501 -2.19298 0.173803 - -0.0837661 -2.18537 0.181255 - -0.0184646 -0.47362 0.261275 - 0.133653 -2.23346 0.430198 - 0.210619 -2.28228 0.518228 - 0.050277 -0.334844 0.340452 - 0.0626128 -0.339266 0.354571 - 0.0723949 -0.34476 0.365762 - 0.0942499 -0.350509 0.390783 - 0.115778 -0.367449 0.415395 - 0.119591 -0.373289 0.419746 - 0.130509 -0.363768 0.432283 - 0.134832 -0.366552 0.437227 - 0.17923 -0.40499 0.487976 - 0.22691 -0.416343 0.542567 - 0.232296 -0.414048 0.548745 - 0.241439 -0.410139 0.559231 - 0.252287 -0.411828 0.571654 - 0.280459 -0.376277 0.604038 - 0.733081 -0.819278 1.12125 - 0.724962 -0.766406 1.1121 - 1.10971 -0.664228 1.55321 - 1.45193 -0.687481 1.94521 - 1.4709 -0.6854 1.96694 - 1.70201 -0.667129 2.23178 - 1.71037 -0.323223 2.2424 - 1.70983 -0.102114 2.24245 - 1.70637 -0.0788235 2.23856 - 1.70841 0.0943364 2.24142 - 1.71037 0.198831 2.24399 - 1.71166 0.351084 2.24593 - 1.71314 0.493964 2.24806 - 1.71378 0.615145 2.24916 - 1.71462 0.639935 2.2502 - 1.31346 0.676667 1.79072 - 1.28275 0.680654 1.75555 - 1.25396 0.684869 1.72258 - 1.24681 0.868168 1.71493 - 1.24989 1.13995 1.71929 - 1.24863 1.26824 1.71824 - 1.18689 1.28954 1.64757 - 1.09863 1.28765 1.54645 - 1.00579 1.28181 1.44006 - 0.99396 1.27857 1.42651 - 0.94889 1.2779 1.37487 - 0.840339 1.27404 1.25049 - 0.82912 1.2687 1.23762 - 0.820386 1.278 1.22765 - 0.812512 1.27731 1.21862 - 0.781223 1.27377 1.18277 - 0.769811 1.26692 1.16967 - 0.67649 1.2661 1.06275 - 0.573607 1.28458 0.944939 - 0.55572 1.2818 0.924438 - 0.501456 1.27917 0.862262 - 0.382008 1.28388 0.725429 - 0.361899 1.27753 0.702371 - 0.340802 1.2812 0.678212 - 0.130093 1.17396 0.436484 - 0.0836922 1.16244 0.383289 - 0.080341 1.19958 0.379562 - 0.0823597 1.26074 0.382061 - 0.0616152 1.18421 0.358062 - 0.0431306 1.1642 0.336824 --0.00688059 1.18031 0.279577 - -0.0473368 1.1658 0.233183 - -0.0702197 1.25676 0.207244 - -0.116598 1.24561 0.154075 - -0.124537 1.16377 0.144732 - -0.194091 1.19631 0.0651442 - -0.202276 1.22949 0.0558686 - -0.240102 1.1902 0.012413 - -0.252341 1.21732 -0.00152653 - -0.258275 1.17005 -0.00846842 - -0.338239 1.27013 -0.099776 - -0.352658 1.27798 -0.116272 - -0.383068 1.22022 -0.151288 - -0.458377 1.26565 -0.237429 - -0.475296 1.22254 -0.256943 - -0.47716 1.02814 -0.25967 - -0.477185 1.01852 -0.259727 - -0.474083 0.956281 -0.256362 - -0.474577 0.700926 -0.257705 - -0.268471 -0.403684 -0.0323551 - -0.243498 -0.40513 -0.00296789 - -0.240795 -0.407191 0.00020714 - -0.23653 -0.409807 0.00521885 - -0.212834 -0.397091 0.0331473 - -0.197942 -0.400521 0.0506637 - -0.166095 -0.404653 0.0881323 - -0.148907 -0.418311 0.108319 - -0.500171 -1.78127 -0.309305 - -0.460505 -2.1531 -0.263769 - -0.408017 -2.15479 -0.202 - -0.388977 -2.1192 -0.179481 - -0.378241 -2.13173 -0.166884 - -0.295372 -2.1265 -0.0693367 - -0.216809 -2.22005 0.0228374 - -0.0311827 -0.412999 0.246889 - -0.0206702 -0.460706 0.259114 - 0.0962209 -2.29794 0.391013 - 0.100491 -2.25922 0.396157 - 0.156116 -2.15618 0.461943 - 0.218533 -2.27015 0.535051 - 0.0230686 -0.462437 0.310587 - 0.0263287 -0.377606 0.314686 - 0.025797 -0.329316 0.314209 - 0.035627 -0.328003 0.325782 - 0.0607531 -0.33496 0.355333 - 0.123208 -0.374292 0.428717 - 0.16908 -0.406531 0.482605 - 0.170224 -0.405177 0.483956 - 0.177192 -0.404374 0.492159 - 0.21598 -0.416283 0.537773 - 0.221531 -0.411003 0.544322 - 0.233866 -0.41624 0.558824 - 0.237363 -0.410842 0.562956 - 0.24432 -0.414177 0.571134 - 0.261242 -0.417133 0.591041 - 0.265985 -0.416533 0.596625 - 0.703826 -0.830556 1.11066 - 0.708476 -0.820624 1.11616 - 0.707372 -0.797015 1.11493 - 0.706656 -0.703772 1.11438 - 0.70948 -0.692768 1.11774 - 0.71231 -0.661665 1.12116 - 0.789901 -0.665838 1.21247 - 0.808161 -0.659159 1.23398 - 0.816376 -0.658442 1.24365 - 1.01081 -0.665082 1.47246 - 1.66561 -0.651284 2.24317 - 1.66538 -0.343076 2.24385 - 1.66246 -0.330885 2.24045 - 1.66342 -0.273216 2.24176 - 1.66296 -0.238564 2.24132 - 1.47078 0.70085 2.01804 - 1.34367 0.682306 1.86838 - 1.25766 0.697754 1.76721 - 1.24773 0.751116 1.75569 - 1.243 0.848551 1.75041 - 1.25019 1.00111 1.75935 - 1.25047 1.15861 1.76017 - 1.24715 1.19066 1.75636 - 1.25099 1.24198 1.76103 - 1.23307 1.28497 1.74008 - 0.905495 1.27425 1.35451 - 0.887868 1.28376 1.33379 - 0.651178 1.28552 1.05523 - 0.616451 1.27608 1.01433 - 0.530282 1.28185 0.912931 - 0.489925 1.2844 0.865441 - 0.438398 1.27852 0.804779 - 0.423761 1.27746 0.787549 - 0.385521 1.27372 0.742531 - 0.281086 1.2871 0.61966 - 0.190603 1.2757 0.513132 - 0.140161 1.16749 0.453431 - 0.0956037 1.16803 0.400992 - 0.0155758 1.17653 0.306831 --0.00158175 1.15793 0.28658 - -0.0588238 1.2314 0.219437 - -0.0774015 1.17106 0.197386 - -0.0974547 1.17288 0.17379 - -0.167114 1.16291 0.0917742 - -0.209009 1.19167 0.0425556 - -0.225587 1.16286 0.0229555 - -0.370266 1.28284 -0.146951 - -0.464948 1.1176 -0.258896 - -0.467028 0.991041 -0.261735 - -0.27905 -0.400952 -0.0507651 - -0.222151 -0.402948 0.0175669 - -0.202749 -0.404628 0.040864 - -0.193878 -0.406399 0.0515127 - -0.175785 -0.398786 0.0732676 - -0.174358 -0.398892 0.0749813 - -0.171816 -0.399946 0.0780308 - -0.161643 -0.403773 0.0902366 - -0.153507 -0.399983 0.100021 - -0.150064 -0.426567 0.104073 - -0.489139 -1.73741 -0.30727 - -0.49006 -1.80798 -0.308596 - -0.482391 -2.03313 -0.300089 - -0.476204 -2.15655 -0.293045 - -0.442689 -2.15404 -0.252783 - -0.390556 -2.11482 -0.190046 - -0.339766 -2.15391 -0.129168 - -0.0606686 -0.526023 0.21113 - -0.0545331 -0.520754 0.218515 - -0.102401 -2.22403 0.1557 - -0.033781 -0.419986 0.243755 - -0.02668 -0.424929 0.252268 - -0.0253341 -0.434889 0.253853 - -0.0209383 -0.465703 0.259036 - 0.0440091 -2.33023 0.331213 - 0.0503004 -2.32372 0.33879 - 0.054643 -2.26725 0.344182 - 0.0867349 -2.27284 0.382708 - 0.135695 -2.2423 0.441607 - 0.149657 -2.18121 0.458567 - 0.208512 -2.26686 0.528987 - 0.0310626 -0.479111 0.32145 - 0.0350679 -0.47779 0.326265 - 0.0208633 -0.335053 0.30965 - 0.0334693 -0.343183 0.324765 - 0.034611 -0.333226 0.326168 - 0.038926 -0.334213 0.331347 - 0.0750272 -0.349179 0.37466 - 0.0820872 -0.344809 0.383153 - 0.0941093 -0.3506 0.397574 - 0.165325 -0.41537 0.482905 - 0.173032 -0.412507 0.492171 - 0.178903 -0.416764 0.499208 - 0.180062 -0.415324 0.500605 - 0.181218 -0.413876 0.501997 - 0.19961 -0.407918 0.524105 - 0.259252 -0.405191 0.595747 - 0.262612 -0.399205 0.599801 - 0.269883 -0.377715 0.608602 - 0.361063 -0.470126 0.717825 - 0.692762 -0.776286 1.11525 - 0.701051 -0.659667 1.12557 - 0.714008 -0.664579 1.14112 - 0.7852 -0.663066 1.22663 - 0.802558 -0.662786 1.24748 - 0.848507 -0.661963 1.30267 - 1.03464 -0.663198 1.52621 - 1.17114 -0.663911 1.69016 - 1.26765 -0.667755 1.80606 - 1.62865 -0.514128 2.24012 - 1.63142 -0.491467 2.24352 - 1.63213 -0.479941 2.24441 - 1.6284 -0.385818 2.24022 - 1.63212 -0.179965 2.24533 - 1.63198 0.00188976 2.24573 - 1.62825 0.115209 2.24161 - 1.62644 0.205956 2.23972 - 1.63028 0.674409 2.24579 - 1.49407 0.697668 2.08227 - 1.38086 0.698641 1.9463 - 1.24623 0.881856 1.78517 - 1.24101 1.028 1.77936 - 1.23811 1.03668 1.77591 - 1.24932 1.15996 1.78976 - 0.933571 1.28236 1.41091 - 0.761692 1.27878 1.20447 - 0.645983 1.28012 1.0655 - 0.53952 1.28262 0.937638 - 0.505854 1.27729 0.897187 - 0.390323 1.27689 0.758427 - 0.356317 1.28211 0.7176 - 0.223753 1.28209 0.558386 - 0.210978 1.27672 0.543025 - 0.157719 1.20629 0.478838 - 0.144485 1.16607 0.462818 - 0.0813903 1.17826 0.387076 - 0.0679273 1.2186 0.371033 - 0.0381536 1.18162 0.335157 - 0.00133042 1.16969 0.290894 - -0.0135316 1.27059 0.273359 - -0.0411213 1.16595 0.239896 - -0.0665031 1.26099 0.209708 - -0.0716456 1.20257 0.203349 - -0.163461 1.17168 0.0929776 - -0.202365 1.23227 0.0464411 - -0.230913 1.16506 0.0119436 - -0.28007 1.1631 -0.0471016 - -0.364649 1.27543 -0.148334 - -0.388462 1.22683 -0.177087 - -0.398559 1.24714 -0.18915 - -0.42918 1.26325 -0.225877 - -0.434408 1.26593 -0.232147 - -0.454639 1.09241 -0.256989 - -0.45301 1.07757 -0.255078 - -0.456874 1.05619 -0.259786 - -0.458018 1.02895 -0.261245 - -0.451401 0.993868 -0.253407 - -0.456441 0.977783 -0.259511 - -0.455871 0.932124 -0.258969 - -0.45267 0.860001 -0.25535 - -0.266255 -0.401943 -0.0416388 - -0.245287 -0.403184 -0.0159005 - -0.235402 -0.405624 -0.0037732 - -0.232722 -0.403883 -0.00047813 - -0.206624 -0.406882 0.0315519 - -0.195833 -0.400234 0.0448203 - -0.194727 -0.401362 0.0461748 - -0.193618 -0.402483 0.0475331 - -0.190493 -0.39852 0.0513811 - -0.185211 -0.396653 0.0578724 - -0.17028 -0.399946 0.0761919 - -0.161352 -0.402883 0.0871431 - -0.147631 -0.42737 0.10391 - -0.146941 -0.430007 0.104749 - -0.477062 -1.8018 -0.304868 - -0.472043 -1.82846 -0.298791 - -0.355819 -2.16098 -0.157162 - -0.327761 -2.1394 -0.122648 - -0.30651 -2.07203 -0.0963464 - -0.235606 -2.13312 -0.00949423 - -0.0228104 -0.457775 0.25705 - 0.0359464 -2.31572 0.323299 - 0.101903 -2.23941 0.404512 - 0.106008 -2.20564 0.409658 - 0.0199425 -0.474978 0.309481 - 0.0219037 -0.341481 0.312311 - 0.0291538 -0.342563 0.321208 - 0.0381261 -0.336112 0.332244 - 0.0356118 -0.319507 0.329209 - 0.0569388 -0.331279 0.355354 - 0.0667014 -0.346355 0.367292 - 0.0732118 -0.352616 0.375264 - 0.0755571 -0.348608 0.378156 - 0.0774719 -0.347108 0.380512 - 0.0782244 -0.342019 0.381451 - 0.0880773 -0.34963 0.393523 - 0.0953802 -0.352342 0.40248 - 0.151929 -0.415098 0.471704 - 0.25163 -0.41442 0.594104 - 0.252988 -0.398569 0.595821 - 0.253734 -0.39265 0.596755 - 0.25481 -0.390673 0.598083 - 0.255979 -0.385404 0.599535 - 0.679376 -0.743744 1.11818 - 0.934835 -0.664001 1.43205 - 1.01877 -0.662088 1.5351 - 1.18154 -0.669194 1.73491 - 1.59342 -0.603906 2.24075 - 1.59726 -0.45291 2.24595 - 1.59396 -0.417345 2.242 - 1.59035 -0.26813 2.23804 - 1.59552 -0.133206 2.24482 - 1.59066 0.1141 2.23963 - 1.59366 0.2726 2.24382 - 1.596 0.341503 2.24691 - 1.59593 0.48006 2.24726 - 1.59519 0.491498 2.24639 - 1.59253 0.655899 2.24365 - 1.25374 0.683685 1.82782 - 1.24734 0.709978 1.82005 - 1.24595 0.719156 1.81837 - 1.24771 0.926654 1.82119 - 1.25104 0.983323 1.82546 - 1.24831 0.992193 1.82213 - 1.03062 1.28445 1.55581 - 1.01357 1.27534 1.53484 - 0.923118 1.28559 1.42384 - 0.826305 1.27292 1.30495 - 0.790093 1.28501 1.26053 - 0.57678 1.2865 0.998661 - 0.567579 1.27869 0.98734 - 0.535309 1.2787 0.947724 - 0.526436 1.28241 0.936843 - 0.506954 1.28524 0.912934 - 0.458533 1.27611 0.853462 - 0.440546 1.2792 0.831389 - 0.412203 1.27833 0.796592 - 0.391831 1.28549 0.771604 - 0.377735 1.28352 0.754293 - 0.35339 1.27583 0.724382 - 0.349056 1.27579 0.719061 - 0.330595 1.286 0.69643 - 0.295828 1.28133 0.653734 - 0.288051 1.28305 0.644191 - 0.23639 1.28529 0.580777 - 0.196222 1.27778 0.53144 - 0.189166 1.28092 0.522788 - 0.181608 1.28106 0.513511 - 0.139221 1.17117 0.461126 - 0.127599 1.18557 0.446903 - 0.127894 1.24064 0.44744 - 0.0452093 1.15817 0.345671 - 0.0365037 1.17465 0.335036 --0.00594869 1.16713 0.282896 - -0.0348927 1.159 0.247337 - -0.0478625 1.1738 0.231461 - -0.119283 1.17232 0.143778 - -0.12831 1.16252 0.132664 - -0.210375 1.17953 0.0319714 - -0.293316 1.17131 -0.069878 - -0.301694 1.17616 -0.0801476 - -0.372536 1.21423 -0.166996 - -0.386753 1.22167 -0.184426 - -0.417667 1.26949 -0.222226 - -0.441094 1.2612 -0.251013 - -0.444562 1.25837 -0.255279 - -0.445968 1.22329 -0.257116 - -0.444783 0.910521 -0.256652 - -0.442547 0.737083 -0.254456 - -0.282737 -0.398764 -0.0682706 - -0.281647 -0.400512 -0.0669098 - -0.243063 -0.410749 -0.0185882 - -0.217499 -0.398438 0.0134883 - -0.215319 -0.401016 0.0162118 - -0.176878 -0.398396 0.0643953 - -0.150677 -0.403524 0.0972135 - -0.462584 -1.81071 -0.298184 - -0.42723 -2.15876 -0.254994 - -0.413927 -2.15559 -0.238312 - -0.351429 -2.15709 -0.159994 - -0.261767 -2.17736 -0.0476931 - -0.0331224 -0.415996 0.244495 - -0.0234561 -0.444782 0.256516 - 0.0286022 -2.31614 0.315756 - 0.0568915 -2.23372 0.351473 - 0.116089 -2.20369 0.425757 - 0.192281 -2.2329 0.521148 - 0.0306263 -0.471393 0.324208 - 0.0313707 -0.467042 0.325155 - 0.0308598 -0.453903 0.324557 - 0.0318146 -0.451508 0.325761 - 0.0262023 -0.381669 0.318951 - 0.0277 -0.329227 0.320997 - 0.033145 -0.34228 0.327778 - 0.0332427 -0.327547 0.327948 - 0.0411266 -0.331724 0.337815 - 0.0431728 -0.32734 0.340393 - 0.0701543 -0.351528 0.374129 - 0.0900855 -0.349728 0.399113 - 0.181373 -0.411081 0.51332 - 0.185621 -0.411891 0.51864 - 0.218439 -0.415486 0.559757 - 0.244679 -0.416953 0.592636 - 0.25074 -0.397255 0.600295 - 0.256284 -0.377388 0.607307 - 0.264173 -0.380841 0.617182 - 0.660248 -0.834512 1.11209 - 0.663671 -0.76497 1.11661 - 0.659762 -0.725682 1.11183 - 0.669829 -0.661519 1.12465 - 0.816123 -0.661828 1.30799 - 0.857694 -0.663741 1.36008 - 0.942734 -0.669928 1.46664 - 0.949136 -0.666225 1.47467 - 1.54335 -0.686517 2.21928 - 1.55949 -0.634158 2.23968 - 1.5638 -0.210792 2.24644 - 1.56142 -0.16564 2.2436 - 1.56075 0.169354 2.24383 - 1.55799 0.292559 2.24077 - 1.55936 0.360782 2.2427 - 1.56452 0.442169 2.24943 - 1.56481 0.558403 2.25016 - 1.5562 0.697043 2.23983 - 1.42616 0.695265 2.07685 - 1.24805 0.749832 1.85382 - 1.25101 0.823763 1.85776 - 1.24811 0.863858 1.85425 - 1.2499 0.951015 1.85678 - 1.24771 0.99333 1.85417 - 1.25184 1.25382 1.86019 - 1.19594 1.28351 1.79023 - 1.0984 1.28604 1.66799 - 1.06861 1.27553 1.63062 - 1.05156 1.27908 1.60927 - 0.852673 1.28309 1.36003 - 0.788345 1.27635 1.2794 - 0.770263 1.27028 1.25671 - 0.739297 1.27592 1.21793 - 0.675211 1.27733 1.13762 - 0.644307 1.27675 1.09889 - 0.439435 1.28021 0.842149 - 0.320007 1.28029 0.692481 - 0.308046 1.28211 0.677497 - 0.193586 1.28066 0.534049 - 0.127603 1.1776 0.451028 - 0.0680028 1.2169 0.376462 - -0.110496 1.25112 0.152875 - -0.195549 1.2088 0.0461502 - -0.216093 1.16317 0.0202579 - -0.278208 1.16426 -0.0575827 - -0.296104 1.16487 -0.0800084 - -0.344192 1.27276 -0.139926 - -0.362862 1.26718 -0.163342 - -0.38188 1.21894 -0.18733 - -0.398845 1.24937 -0.208493 - -0.437228 1.22435 -0.256675 - -0.437828 1.07442 -0.257908 - -0.433904 0.674856 -0.254272 - -0.264627 -0.401606 -0.0519971 - -0.263544 -0.403248 -0.050615 - -0.256146 -0.400721 -0.0411306 - -0.24816 -0.400233 -0.0309005 - -0.239664 -0.405424 -0.0200363 - -0.237792 -0.405345 -0.0176374 - -0.222878 -0.396594 0.00149307 - -0.434472 -2.15694 -0.275242 - -0.366237 -2.15984 -0.187855 - -0.359109 -2.15347 -0.178704 - -0.333732 -2.14689 -0.14618 - -0.18323 -2.20491 0.0463977 - -0.125437 -2.25161 0.120268 - -0.0417622 -0.444739 0.233313 - -0.0345072 -0.418986 0.242689 - -0.0333828 -0.419996 0.244126 - 0.0746687 -2.25665 0.376552 - 0.155782 -2.1338 0.480843 - 0.0176264 -0.447679 0.30937 - 0.030426 -0.458784 0.325728 - 0.031409 -0.430684 0.327078 - 0.0217752 -0.323139 0.315088 - 0.0366773 -0.326122 0.334166 - 0.0498649 -0.330907 0.351041 - 0.0507517 -0.330319 0.352179 - 0.0583758 -0.339204 0.361915 - 0.070132 -0.349179 0.37694 - 0.0710675 -0.348447 0.378141 - 0.125619 -0.380341 0.447908 - 0.135707 -0.39703 0.460775 - 0.143503 -0.407729 0.470726 - 0.161805 -0.414487 0.494145 - 0.185451 -0.410342 0.524444 - 0.193344 -0.417756 0.534529 - 0.206547 -0.415857 0.551446 - 0.213866 -0.421151 0.560804 - 0.216113 -0.417642 0.563693 - 0.235567 -0.419951 0.588603 - 0.245256 -0.381531 0.601137 - 0.630602 -0.824697 1.09326 - 0.643556 -0.698228 1.11026 - 0.648184 -0.66308 1.1163 - 0.651541 -0.659782 1.12061 - 0.69132 -0.663917 1.17155 - 0.802885 -0.660515 1.31445 - 1.25002 -0.675232 1.88711 - 1.52412 -0.616858 2.23837 - 1.52403 -0.489686 2.23866 - 1.52536 -0.455831 2.24048 - 1.52675 -0.3655 2.24256 - 1.52656 -0.17534 2.24292 - 1.52813 -0.13109 2.24509 - 1.52554 -0.0865952 2.24191 - 1.53055 -0.0314146 2.24851 - 1.5257 -0.0092119 2.24237 - 1.52781 0.145899 2.24558 - 1.528 0.157028 2.24586 - 1.52712 0.302033 2.2452 - 1.52479 0.324025 2.24229 - 1.52899 0.438258 2.24803 - 1.52896 0.461117 2.24807 - 1.52846 0.564803 2.24777 - 1.52535 0.669152 2.24412 - 1.3283 0.699846 1.99184 - 1.26437 0.718021 1.91001 - 1.26798 0.740703 1.91471 - 1.26341 0.790198 1.90902 - 1.26356 0.800812 1.90925 - 1.16806 1.28388 1.7885 - 1.03678 1.27908 1.62033 - 0.951144 1.27669 1.51064 - 0.814787 1.2785 1.336 - 0.801613 1.28091 1.31913 - 0.778399 1.27843 1.28939 - 0.686473 1.2815 1.17166 - 0.670521 1.27532 1.15121 - 0.665857 1.27808 1.14525 - 0.645826 1.27475 1.11958 - 0.638787 1.27275 1.11056 - 0.585696 1.28158 1.04259 - 0.531667 1.28133 0.973383 - 0.392725 1.2827 0.795427 - 0.36922 1.27799 0.765306 - 0.245554 1.17466 0.606576 - 0.246098 1.22456 0.607436 - 0.239827 1.2824 0.599591 - 0.190415 1.28163 0.5363 - 0.181731 1.27417 0.525154 - 0.172987 1.26561 0.513927 - 0.128513 1.25515 0.45693 - 0.1009 1.16731 0.421276 - 0.0943002 1.16624 0.41282 - 0.0556387 1.16373 0.363294 - 0.052512 1.16436 0.359291 --0.00453512 1.14994 0.286177 - -0.0186816 1.26472 0.268431 - -0.0222871 1.24082 0.263735 - -0.0258303 1.20591 0.259083 - -0.0323294 1.17199 0.250649 - -0.0416816 1.15995 0.238631 - -0.0626671 1.2572 0.212069 - -0.133055 1.16514 0.121615 - -0.184085 1.16097 0.0562418 - -0.221604 1.1693 0.00821351 - -0.249921 1.23457 -0.0278431 - -0.264344 1.16165 -0.0465532 - -0.270957 1.16025 -0.0550288 - -0.319437 1.23326 -0.116885 - -0.367955 1.22704 -0.179048 - -0.372742 1.21589 -0.185215 - -0.431548 1.26209 -0.260385 - -0.430581 1.23248 -0.259243 - -0.430204 1.19314 -0.258889 - -0.433105 1.18945 -0.262615 - -0.428883 0.849281 -0.258313 - -0.227943 -0.401093 -0.010344 - -0.214576 -0.397937 0.00715262 - -0.206748 -0.406078 0.0173663 - -0.192718 -0.402444 0.0357302 - -0.153954 -0.401075 0.0864431 - -0.148655 -0.396445 0.0933901 - -0.146547 -0.398096 0.0961424 - -0.36793 -2.1584 -0.199252 - -0.337451 -2.15737 -0.159378 - -0.164961 -2.2259 0.0660349 - -0.15321 -2.22876 0.081398 - -0.126188 -2.29551 0.116527 - -0.0314154 -0.416994 0.246688 - 0.0445699 -2.30175 0.339879 - 0.123738 -2.20554 0.443758 - 0.137014 -2.22409 0.461063 - 0.147542 -2.13609 0.475125 - 0.207055 -2.25959 0.552569 - 0.0310154 -0.427314 0.328321 - 0.0294598 -0.334632 0.326591 - 0.0329942 -0.33279 0.331221 - 0.069518 -0.360587 0.378907 - 0.0711751 -0.350405 0.381108 - 0.0768112 -0.353598 0.388471 - 0.0819718 -0.354807 0.395217 - 0.155694 -0.418583 0.491445 - 0.157164 -0.418027 0.49337 - 0.183623 -0.416443 0.527987 - 0.197651 -0.413336 0.546348 - 0.227625 -0.416967 0.585546 - 0.242358 -0.379558 0.604942 - 0.253899 -0.381654 0.620031 - 0.635686 -0.666342 1.11852 - 0.688626 -0.663661 1.18778 - 0.697287 -0.66477 1.19911 - 0.728899 -0.665268 1.24046 - 0.819932 -0.660587 1.35956 - 0.97312 -0.667469 1.55993 - 1.01458 -0.668894 1.61415 - 1.37722 -0.68563 2.08848 - 1.49577 -0.613777 2.24379 - 1.49442 -0.532505 2.2423 - 1.49581 -0.363072 2.24467 - 1.49231 -0.217894 2.24057 - 1.49465 -0.130006 2.24392 - 1.49244 -0.0639573 2.24125 - 1.49445 0.0347612 2.24421 - 1.49433 0.0457379 2.24408 - 1.496 0.0567813 2.2463 - 1.49552 0.188953 2.24611 - 1.4939 0.288458 2.24432 - 1.49363 0.400265 2.24433 - 1.49553 0.412044 2.24686 - 1.4956 0.423361 2.24699 - 1.49778 0.492211 2.25006 - 1.4976 0.538036 2.24998 - 1.26697 0.708366 1.94885 - 1.26577 0.738966 1.94739 - 1.26488 0.769976 1.94632 - 1.26398 0.833347 1.94535 - 1.27074 1.00443 1.95476 - 1.06161 1.27853 1.68209 - 1.01804 1.27376 1.62507 - 1.01269 1.27893 1.6181 - 0.959947 1.28238 1.54911 - 0.896041 1.27743 1.4655 - 0.873802 1.2805 1.43642 - 0.79713 1.26899 1.33608 - 0.590091 1.27371 1.06527 - 0.538063 1.27801 0.997221 - 0.464842 1.27034 0.901413 - 0.460811 1.27224 0.896147 - 0.441601 1.28379 0.871055 - 0.422996 1.28351 0.846716 - 0.403355 1.27908 0.821009 - 0.393623 1.27658 0.80827 - 0.38878 1.27527 0.80193 - 0.313255 1.27688 0.703139 - 0.241172 1.23686 0.608713 - 0.223614 1.2777 0.58588 - 0.20302 1.28747 0.558973 - 0.126947 1.18426 0.459119 - 0.0982837 1.1624 0.421552 - 0.0952006 1.16334 0.417522 - 0.0923273 1.16624 0.413773 - 0.0583389 1.17695 0.369347 - 0.0511596 1.16535 0.359917 - 0.0367541 1.18609 0.341141 - 0.0221599 1.21332 0.32214 - 0.00467516 1.17216 0.299132 - 0.00141941 1.16744 0.294857 --0.00476998 1.16792 0.286762 - -0.0546824 1.18857 0.221538 - -0.0716075 1.22554 0.19952 - -0.0882535 1.16373 0.177541 - -0.0913362 1.16333 0.173508 - -0.102939 1.20285 0.15846 - -0.251396 1.17947 -0.0358181 - -0.261796 1.1626 -0.0494788 - -0.339772 1.26965 -0.151129 - -0.400394 1.25777 -0.230469 - -0.418797 0.990524 -0.255422 - -0.423329 0.955724 -0.261465 - -0.421052 0.835338 -0.258883 - -0.418879 0.801348 -0.256153 - -0.417528 0.777464 -0.254464 - -0.420196 0.735891 -0.258092 - -0.411458 0.70057 -0.246777 - -0.416205 0.673119 -0.253077 - -0.244718 -0.400199 -0.0384698 - -0.237782 -0.400982 -0.0291963 - -0.21625 -0.406727 -0.00042078 - -0.21233 -0.401645 0.00483856 - -0.197623 -0.404401 0.0244972 - -0.160239 -0.404593 0.0744913 - -0.152773 -0.39752 0.0845001 - -0.151731 -0.398389 0.0858896 - -0.434209 -1.71339 -0.296266 - -0.125895 -0.439383 0.120305 - -0.436935 -2.1597 -0.301401 - -0.371506 -2.17143 -0.213942 - -0.341247 -2.1707 -0.173473 - -0.310968 -2.12183 -0.132818 - -0.301541 -2.09355 -0.120116 - -0.231183 -2.12871 -0.0261416 - -0.180167 -2.21386 0.0417985 - -0.162738 -2.21595 0.0651006 - 0.0313772 -2.30672 0.324392 - 0.0696754 -2.21975 0.375899 - 0.0770419 -2.25091 0.385647 - 0.140332 -2.22386 0.470376 - 0.207079 -2.23621 0.559598 - 0.0393692 -0.32734 0.34169 - 0.0442864 -0.340295 0.348223 - 0.0455895 -0.328703 0.350004 - 0.0580553 -0.349289 0.366606 - 0.0678874 -0.352788 0.379743 - 0.0782509 -0.356443 0.39359 - 0.0953891 -0.352922 0.416522 - 0.108889 -0.357564 0.43456 - 0.143133 -0.415456 0.480162 - 0.152093 -0.413222 0.492151 - 0.160793 -0.417248 0.503774 - 0.200682 -0.414159 0.557127 - 0.204735 -0.410454 0.56256 - 0.231658 -0.404357 0.598586 - 0.616744 -0.808146 1.11222 - 0.651085 -0.664655 1.15863 - 0.711667 -0.659642 1.23966 - 0.782078 -0.662266 1.33381 - 0.836877 -0.66038 1.4071 - 0.894287 -0.663623 1.48387 - 0.935944 -0.66852 1.53956 - 1.0837 -0.66772 1.73717 - 1.45606 -0.675761 2.23511 - 1.46154 -0.620167 2.24262 - 1.45964 -0.607853 2.24011 - 1.46217 -0.49469 2.24387 - 1.45811 -0.31495 2.23904 - 1.46468 -0.272091 2.24797 - 1.46163 -0.0308706 2.24471 - 1.4579 0.241712 2.24062 - 1.46426 0.331265 2.24943 - 1.45688 0.418554 2.23985 - 1.45861 0.475209 2.24236 - 1.46145 0.487423 2.24619 - 1.46308 0.533446 2.24853 - 1.26546 0.749406 1.98497 - 1.26337 0.780134 1.98227 - 1.26651 0.803531 1.98655 - 1.26606 0.814058 1.98599 - 1.27042 0.984022 1.99238 - 1.26824 1.07546 1.98977 - 1.27261 1.23806 1.99616 - 0.927801 1.28168 1.53519 - 0.91037 1.28118 1.51187 - 0.84688 1.28301 1.42697 - 0.643666 1.27285 1.15517 - 0.627113 1.28639 1.13308 - 0.559573 1.27415 1.04272 - 0.494211 1.27748 0.95532 - 0.393309 1.28134 0.820395 - 0.240945 1.15949 0.616228 - 0.229275 1.13923 0.600554 - 0.207142 1.26984 0.571391 - 0.141759 1.16911 0.483616 - 0.134937 1.16679 0.474485 - 0.132022 1.16899 0.470594 - 0.0900555 1.16427 0.414456 - 0.0823257 1.24957 0.404403 - -0.0692819 1.26475 0.201706 - -0.0788271 1.16876 0.18862 - -0.0817977 1.16644 0.18464 - -0.0971303 1.16647 0.164135 - -0.114867 1.25002 0.140695 - -0.1544 1.24632 0.0878137 - -0.163948 1.24164 0.075029 - -0.21001 1.20941 0.0133224 - -0.259105 1.16355 -0.0524869 - -0.34175 1.26245 -0.16268 - -0.371355 1.25663 -0.202291 - -0.414769 1.10649 -0.260851 - -0.410245 1.0506 -0.254988 - -0.410249 0.927236 -0.255404 - -0.411986 0.922842 -0.257742 - -0.409913 0.860338 -0.255179 - -0.407613 0.832049 -0.252197 - -0.408331 0.826133 -0.253177 - -0.409754 0.821814 -0.255094 - -0.408176 0.673654 -0.25348 - -0.269968 -0.398059 -0.0793132 - -0.266038 -0.401846 -0.0739537 - -0.254919 -0.403248 -0.0587553 - -0.245998 -0.400816 -0.04655 - -0.245352 -0.403131 -0.0456755 - -0.219527 -0.404478 -0.0103702 - -0.218481 -0.405851 -0.0089449 - -0.212153 -0.406455 -0.00029515 - -0.195617 -0.397055 0.0223446 - -0.174194 -0.406 0.0516047 - -0.17078 -0.400124 0.0562923 - -0.164449 -0.401611 0.0649438 - -0.149787 -0.405499 0.0849767 - -0.440173 -1.69702 -0.316424 - -0.438779 -1.73459 -0.314645 - -0.1237 -0.440056 0.120527 - -0.43073 -2.12338 -0.304958 - -0.378674 -2.13294 -0.233818 - -0.283934 -2.07099 -0.104076 - -0.0319646 -0.418994 0.246022 - 0.0631265 -2.23941 0.369866 - 0.11163 -2.18178 0.436377 - 0.190163 -2.22183 0.543614 - 0.029409 -0.331356 0.330231 - 0.0341522 -0.336077 0.3367 - 0.0744045 -0.353696 0.391674 - 0.088112 -0.359284 0.410397 - 0.0890348 -0.358383 0.411662 - 0.0939019 -0.351131 0.41834 - 0.133122 -0.409385 0.471767 - 0.182202 -0.415502 0.538849 - 0.195635 -0.415127 0.557217 - 0.203159 -0.414048 0.567507 - 0.224308 -0.413383 0.596425 - 0.227643 -0.39388 0.60105 - 0.225817 -0.377628 0.59861 - 0.237912 -0.378132 0.615145 - 0.599909 -0.721697 1.10891 - 0.694979 -0.661277 1.2391 - 0.799878 -0.663995 1.38251 - 0.884675 -0.666381 1.49844 - 0.897256 -0.667395 1.51564 - 1.04252 -0.670489 1.71424 - 1.1987 -0.686191 1.92772 - 1.25571 -0.686428 2.00567 - 1.42557 -0.602639 2.23819 - 1.42709 -0.591854 2.24031 - 1.43037 -0.468798 2.24521 - 1.43293 -0.402623 2.24893 - 1.43085 -0.204307 2.24676 - 1.42688 -0.0954095 2.24169 - 1.42992 0.0775676 2.24644 - 1.43047 0.142684 2.24742 - 1.42508 0.305372 2.24059 - 1.42966 0.643525 2.248 - 1.42963 0.678318 2.24808 - 1.37932 0.700193 2.17937 - 1.33101 0.69825 2.11331 - 1.26541 0.749589 2.02379 - 1.26797 0.794355 2.02745 - 1.26613 0.915066 2.02534 - 1.26893 1.04414 2.02961 - 1.26971 1.08044 2.03079 - 1.26896 1.18964 2.03013 - 1.27254 1.26895 2.0353 - 1.2672 1.2766 2.02803 - 1.25778 1.28017 2.01516 - 0.73529 1.28571 1.30081 - 0.684842 1.2773 1.23181 - 0.569489 1.27975 1.0741 - 0.483106 1.28133 0.956004 - 0.478141 1.28102 0.949215 - 0.444985 1.28086 0.903882 - 0.3805 1.27483 0.815695 - 0.362877 1.27282 0.791593 - 0.325898 1.27313 0.741036 - 0.319317 1.27843 0.732056 - 0.292805 1.28337 0.695825 - 0.284114 1.27989 0.68393 - 0.215994 1.14305 0.59033 - 0.214461 1.15147 0.588263 - 0.198762 1.28383 0.567248 - 0.104239 1.1702 0.437628 - 0.0918382 1.17121 0.420676 - 0.0347768 1.25329 0.342938 - -0.0271071 1.19491 0.258131 - -0.0936314 1.1689 0.167088 - -0.0966411 1.16846 0.162972 - -0.101163 1.19488 0.156879 - -0.16976 1.16306 0.0629832 - -0.199252 1.21897 0.0228502 - -0.311452 1.22936 -0.130518 - -0.320358 1.23642 -0.142672 - -0.346903 1.26903 -0.178855 - -0.36507 1.26455 -0.203708 - -0.407523 1.22016 -0.261902 - -0.404073 1.19612 -0.257265 - -0.40555 1.15167 -0.259436 - -0.400744 0.933501 -0.253604 - -0.402876 0.921436 -0.25656 - -0.404168 0.858721 -0.258539 - -0.400049 0.748797 -0.25328 - -0.400468 0.68055 -0.254084 - -0.253801 -0.403064 -0.0639543 - -0.223072 -0.406556 -0.0210144 - -0.215359 -0.404269 -0.0102263 - -0.208099 -0.402447 -7.206e-05 - -0.185199 -0.398261 0.0319508 - -0.185046 -0.405569 0.0321401 - -0.16187 -0.407052 0.0645287 - -0.152432 -0.397538 0.0777541 - -0.429393 -1.61414 -0.313553 - -0.427831 -1.68982 -0.311629 - -0.122656 -0.446395 0.119205 - -0.118744 -0.432853 0.124719 - -0.367354 -2.16602 -0.228734 - -0.32185 -2.13206 -0.165014 - -0.267313 -2.05111 -0.0885064 - -0.245048 -2.1537 -0.0577371 - -0.225059 -2.11883 -0.0296774 - -0.172345 -2.24078 0.0435841 - -0.153274 -2.20694 0.0703575 - -0.0857468 -2.20896 0.164737 - -0.0387245 -0.428904 0.236581 - 0.055305 -2.22611 0.361834 - 0.129091 -2.22112 0.464986 - 0.145554 -2.14371 0.488263 - 0.154491 -2.11923 0.500839 - 0.20851 -2.26201 0.575854 - 0.0229593 -0.474212 0.322645 - 0.0298652 -0.460329 0.332345 - 0.0287185 -0.419599 0.330882 - 0.020326 -0.333348 0.319448 - 0.0221991 -0.328267 0.322084 - 0.0300003 -0.335643 0.332962 - 0.0320737 -0.336572 0.335857 - 0.060344 -0.349517 0.375328 - 0.0761062 -0.353924 0.397344 - 0.0770023 -0.353098 0.3986 - 0.079573 -0.357537 0.402178 - 0.0908998 -0.348574 0.418041 - 0.1254 -0.408052 0.466058 - 0.146328 -0.413222 0.495294 - 0.148429 -0.414264 0.498226 - 0.157277 -0.418983 0.510577 - 0.190373 -0.419231 0.556837 - 0.203638 -0.414102 0.575397 - 0.21426 -0.414177 0.590243 - 0.223094 -0.414215 0.60259 - 0.215322 -0.394751 0.591794 - 0.589873 -0.797984 1.11394 - 0.589207 -0.726929 1.11325 - 0.705625 -0.666768 1.27618 - 0.710404 -0.663989 1.28287 - 0.840015 -0.66677 1.46403 - 0.906873 -0.667756 1.55748 - 1.0109 -0.669342 1.70288 - 1.08289 -0.668207 1.8035 - 1.26144 -0.689028 2.053 - 1.3975 -0.645411 2.24333 - 1.3973 -0.622457 2.24313 - 1.39353 -0.430601 2.23852 - 1.39345 -0.419559 2.23844 - 1.40087 -0.377604 2.24897 - 1.39369 -0.321139 2.23913 - 1.39524 -0.29972 2.24135 - 1.39573 -0.234762 2.24227 - 1.39577 -0.137735 2.24265 - 1.3958 -0.116241 2.24277 - 1.39651 -0.0840663 2.24387 - 1.39661 -0.019672 2.24424 - 1.39663 -0.00894278 2.2443 - 1.39781 0.315014 2.24707 - 1.26993 1.02468 2.07077 - 1.27289 1.11133 2.07519 - 1.26857 1.15684 2.06931 - 1.2719 1.21002 2.07416 - 1.26075 1.28912 2.05883 - 1.24541 1.28673 2.03738 - 1.0002 1.2843 1.69464 - 0.957658 1.27747 1.63515 - 0.884767 1.2837 1.53329 - 0.850215 1.28025 1.48498 - 0.560865 1.28053 1.08054 - 0.480267 1.28159 0.967884 - 0.460075 1.27859 0.93965 - 0.452917 1.28431 0.929665 - 0.364474 1.28396 0.806042 - 0.34386 1.28441 0.77723 - 0.302714 1.28074 0.719706 - 0.27946 1.28081 0.687202 - 0.209989 1.14865 0.589645 - 0.196813 1.2735 0.571658 - 0.186257 1.27385 0.556904 - 0.130638 1.17456 0.478821 - 0.0930225 1.17321 0.426238 - 0.089313 1.16728 0.421033 - 0.0828204 1.19464 0.412052 - 0.081597 1.2487 0.410528 - 0.0784243 1.24957 0.406096 - 0.0439411 1.16894 0.35762 - 0.0307633 1.26276 0.339523 - 0.0077577 1.16156 0.307019 - 0.00480778 1.16188 0.302897 --0.00095221 1.16744 0.294865 --0.00391687 1.16769 0.290722 - -0.011463 1.24227 0.28043 - -0.0335844 1.17199 0.249269 - -0.117585 1.26831 0.132187 - -0.164358 1.18466 0.0665227 - -0.24862 1.17345 -0.0512938 - -0.371231 1.21879 -0.222519 - -0.391982 0.819236 -0.252898 - -0.389098 0.742974 -0.249128 - -0.389021 0.716996 -0.24911 - -0.389316 0.711297 -0.249541 - -0.251773 -0.401408 -0.0680759 - -0.236902 -0.404747 -0.0468281 - -0.235511 -0.405534 -0.0448418 - -0.207095 -0.401933 -0.00420327 - -0.147273 -0.430603 0.0812225 - -0.414328 -1.63499 -0.304782 - -0.121207 -0.444504 0.11844 - -0.414053 -2.12536 -0.3061 - -0.40873 -2.12826 -0.298499 - -0.379042 -2.12386 -0.25604 - -0.328931 -2.1315 -0.184425 - -0.256346 -2.18485 -0.0808377 - -0.233354 -2.11978 -0.0477396 - -0.184347 -2.19471 0.0220635 - -0.178855 -2.19586 0.0299114 - -0.149821 -2.1721 0.0715026 - -0.121431 -2.28852 0.111685 - -0.0968166 -2.23002 0.14708 - 0.0550574 -2.25804 0.364112 - 0.136807 -2.20872 0.48116 - 0.0202725 -0.48191 0.320579 - 0.0277786 -0.462747 0.331377 - 0.0228972 -0.338825 0.324831 - 0.0240869 -0.335076 0.326544 - 0.0310225 -0.33752 0.336452 - 0.0378957 -0.338596 0.346274 - 0.0489205 -0.339561 0.362033 - 0.0903082 -0.359852 0.421133 - 0.120481 -0.405906 0.46411 - 0.125724 -0.411829 0.471584 - 0.144045 -0.422351 0.497741 - 0.161115 -0.4118 0.522182 - 0.184181 -0.417946 0.555138 - 0.212779 -0.411137 0.596047 - 0.21482 -0.407368 0.598978 - 0.22133 -0.379603 0.608382 - 0.223653 -0.376347 0.611714 - 0.560725 -0.822833 1.09206 - 0.575935 -0.777981 1.11396 - 0.576788 -0.683558 1.11551 - 0.612911 -0.66304 1.16723 - 0.703125 -0.667677 1.29619 - 0.79405 -0.6642 1.42619 - 0.798827 -0.66038 1.43303 - 1.36213 -0.673274 2.23833 - 1.36544 -0.572831 2.24341 - 1.36262 -0.549311 2.23946 - 1.36671 -0.50631 2.24545 - 1.35951 -0.492666 2.23522 - 1.36223 -0.329693 2.23968 - 1.36383 -0.222315 2.24234 - 1.36467 -0.019528 2.24424 - 1.36105 0.0336421 2.23926 - 1.36194 0.0549329 2.2406 - 1.36682 0.444144 2.24893 - 1.36259 0.689873 2.24374 - 1.26388 0.771493 2.1029 - 1.2625 0.837517 2.10117 - 1.26781 0.874994 2.10889 - 1.26995 1.02845 2.11248 - 1.27047 1.04088 2.11327 - 1.27064 1.08956 2.11368 - 1.27228 1.19066 2.11637 - 1.15169 1.28494 1.94431 - 1.05063 1.28137 1.7998 - 1.04315 1.28456 1.78912 - 0.858657 1.27793 1.52534 - 0.849573 1.28767 1.51238 - 0.700542 1.27661 1.29928 - 0.662917 1.27658 1.24549 - 0.647023 1.28073 1.22278 - 0.471629 1.27995 0.972019 - 0.425703 1.28017 0.90636 - 0.384813 1.27532 0.847884 - 0.381049 1.27678 0.842507 - 0.358485 1.28484 0.810277 - 0.293234 1.27962 0.716971 - 0.190877 1.28097 0.570639 - 0.175167 1.27041 0.548141 - 0.142241 1.1661 0.500704 - 0.135831 1.1649 0.491536 - 0.103463 1.17699 0.445302 - 0.0450584 1.16337 0.361756 --0.00959166 1.2131 0.283797 - -0.0213449 1.25072 0.267125 - -0.0246878 1.22383 0.262252 - -0.0425882 1.15795 0.236431 - -0.0618995 1.24521 0.209126 - -0.0802008 1.15546 0.182648 - -0.109645 1.25854 0.140913 - -0.121357 1.15954 0.123823 - -0.144447 1.18509 0.0908998 - -0.161833 1.20529 0.0661151 - -0.189516 1.17704 0.0264379 - -0.232497 1.17101 -0.0350313 - -0.374833 1.22182 -0.238348 - -0.377881 1.21923 -0.242715 - -0.386933 0.978201 -0.256497 - -0.387367 0.933685 -0.257273 - -0.384657 0.778111 -0.253942 - -0.383139 0.690499 -0.252077 - -0.383198 0.655308 -0.252285 - -0.381329 0.629462 -0.249702 - -0.250302 -0.404311 -0.0729609 - -0.222649 -0.402346 -0.0325273 - -0.20373 -0.399536 -0.00486003 - -0.191523 -0.402809 0.0129738 - -0.189529 -0.405228 0.0158812 - -0.181433 -0.402751 0.0277247 - -0.163979 -0.399404 0.0532526 - -0.156417 -0.400019 0.0643063 - -0.149957 -0.40824 0.0737213 - -0.406052 -1.64345 -0.305043 - -0.123747 -0.438012 0.111932 - -0.117608 -0.437589 0.120909 - -0.341357 -2.1705 -0.212331 - -0.314429 -2.1379 -0.17285 - -0.24483 -2.15602 -0.0711666 - -0.214832 -2.18893 -0.0274279 - -0.136848 -2.15889 0.0866842 - -0.120369 -2.29052 0.110307 - -0.0955008 -2.21005 0.146948 - -0.0845405 -2.20796 0.162979 - -0.0790398 -2.20536 0.171029 - -0.0379229 -0.417941 0.23747 - -0.0306772 -0.421959 0.248049 - -0.0296259 -0.422929 0.249582 - -0.0249808 -0.444717 0.256296 - 0.0324875 -2.30126 0.333733 - 0.0740745 -2.22021 0.394816 - 0.200247 -2.25512 0.579145 - 0.0297013 -0.434616 0.336272 - 0.0291674 -0.423484 0.335531 - 0.0283147 -0.396935 0.334378 - 0.0245837 -0.349893 0.329091 - 0.0252797 -0.348479 0.330113 - 0.0423952 -0.338916 0.355168 - 0.0444544 -0.335267 0.358192 - 0.0491699 -0.342601 0.365059 - 0.0556273 -0.356167 0.374451 - 0.0625678 -0.358201 0.38459 - 0.128648 -0.418446 0.48098 - 0.168795 -0.412564 0.539692 - 0.193424 -0.420123 0.575671 - 0.202136 -0.417596 0.588416 - 0.209617 -0.405314 0.599396 - 0.209589 -0.384565 0.599428 - 0.549131 -0.82672 1.09424 - 0.558501 -0.810425 1.108 - 0.564512 -0.693368 1.1172 - 0.630573 -0.664408 1.21388 - 0.65276 -0.665766 1.24631 - 0.8324 -0.665593 1.50893 - 0.841294 -0.664411 1.52193 - 0.938601 -0.668171 1.66417 - 0.975721 -0.666896 1.71844 - 1.05621 -0.672484 1.8361 - 1.30611 -0.689732 2.20137 - 1.33011 -0.667943 2.23652 - 1.33129 -0.47914 2.23891 - 1.33147 -0.167401 2.24028 - 1.3351 -0.0723543 2.24592 - 1.33277 -0.00880822 2.24275 - 1.33627 0.0547526 2.2481 - 1.33266 0.407282 2.24406 - 1.33162 0.41785 2.24259 - 1.33603 0.474016 2.24923 - 1.3344 0.517591 2.24699 - 1.33585 0.529238 2.24916 - 1.33782 0.541134 2.25208 - 1.33765 0.630971 2.25215 - 1.29558 0.70039 2.19089 - 1.26654 0.718119 2.1485 - 1.26616 0.762349 2.14811 - 1.26924 0.86634 2.15297 - 1.27015 0.890074 2.15439 - 1.26935 0.912801 2.1533 - 1.26975 0.948301 2.15401 - 1.27102 0.99683 2.15603 - 1.27112 1.00892 2.15622 - 1.26912 1.01942 2.15334 - 1.07684 1.28297 1.87318 - 1.00876 1.28669 1.77366 - 0.902875 1.279 1.61884 - 0.834313 1.28511 1.51863 - 0.650627 1.27369 1.25006 - 0.642767 1.28135 1.2386 - 0.636527 1.28073 1.22947 - 0.600552 1.27779 1.17687 - 0.595536 1.27894 1.16954 - 0.58053 1.28208 1.14762 - 0.532432 1.2808 1.0773 - 0.494833 1.28615 1.02235 - 0.472976 1.27951 0.990372 - 0.421675 1.27664 0.915364 - 0.371103 1.27908 0.841441 - 0.34282 1.28018 0.800098 - 0.328867 1.28725 0.779726 - 0.0910174 1.16732 0.431585 - 0.088139 1.16829 0.427381 - 0.0788056 1.26251 0.41407 - 0.0381497 1.16953 0.354305 - 0.0361582 1.18501 0.351449 - 0.0182574 1.18 0.325261 - -0.0219277 1.24172 0.266733 - -0.0427433 1.15595 0.235999 - -0.0456381 1.16089 0.231784 - -0.0515583 1.1747 0.223178 - -0.0548727 1.19956 0.218421 - -0.0705154 1.22854 0.195655 - -0.114375 1.24744 0.131604 - -0.118199 1.1701 0.125739 - -0.211445 1.1728 -0.0105683 - -0.221413 1.15759 -0.0251943 - -0.247919 1.16641 -0.0639128 - -0.262407 1.15891 -0.0851189 - -0.31075 1.22966 -0.155542 - -0.356941 1.27124 -0.222922 - -0.371045 1.25314 -0.243605 - -0.382139 1.19885 -0.260015 - -0.380229 1.07445 -0.257664 - -0.378586 0.959459 -0.255669 - -0.380377 0.937189 -0.258367 - -0.374858 0.82476 -0.250696 - -0.376537 0.813867 -0.25319 - -0.37688 0.751369 -0.253912 - -0.373012 0.66245 -0.248573 - -0.374788 0.648704 -0.251218 - -0.372881 0.622965 -0.248521 - -0.241032 -0.395775 -0.0660285 - -0.225887 -0.404025 -0.0434308 - -0.221151 -0.404654 -0.0363574 - -0.213652 -0.39891 -0.0251325 - -0.193635 -0.402381 0.00476132 - -0.149694 -0.403764 0.0704059 - -0.146239 -0.40912 0.0755482 - -0.149042 -0.428882 0.0712896 - -0.402794 -1.53472 -0.311806 - -0.394729 -1.72486 -0.300439 - -0.391498 -1.73237 -0.29564 - -0.126421 -0.463178 0.104963 - -0.373271 -2.11447 -0.269782 - -0.342244 -2.16809 -0.223618 - -0.306361 -2.14884 -0.169937 - -0.245852 -2.14155 -0.0795073 - -0.183528 -2.16376 0.0135281 - -0.0424838 -0.436744 0.230465 - -0.0412147 -0.422811 0.232412 - -0.0391419 -0.420906 0.235515 - -0.0350522 -0.412996 0.241654 - -0.0288257 -0.42789 0.250903 - 0.103336 -2.1947 0.442007 - 0.13585 -2.19554 0.490582 - 0.143467 -2.15622 0.502104 - 0.158076 -2.14007 0.523988 - 0.186503 -2.21061 0.566207 - 0.0194 -0.46106 0.322836 - 0.0234904 -0.456384 0.328964 - 0.0281206 -0.396449 0.336097 - 0.0267634 -0.363797 0.334187 - 0.0302318 -0.346053 0.339433 - 0.0332717 -0.337793 0.344004 - 0.0355259 -0.335237 0.347381 - 0.0445605 -0.341732 0.360856 - 0.0453881 -0.34111 0.362095 - 0.0649683 -0.353489 0.391304 - 0.0683676 -0.361614 0.396354 - 0.0701163 -0.359989 0.398972 - 0.0776173 -0.347995 0.410222 - 0.0914159 -0.364636 0.430778 - 0.143046 -0.414692 0.507737 - 0.150166 -0.416106 0.518369 - 0.159738 -0.414942 0.532675 - 0.170509 -0.415402 0.548766 - 0.191695 -0.405583 0.580454 - 0.206258 -0.382017 0.602296 - 0.2107 -0.378933 0.608944 - 0.219337 -0.385404 0.621825 - 0.539843 -0.826095 1.09909 - 0.550718 -0.769121 1.11555 - 0.549299 -0.725983 1.11358 - 0.575138 -0.663233 1.15241 - 0.756316 -0.66868 1.42308 - 0.794649 -0.669621 1.48035 - 0.821901 -0.667583 1.52107 - 1.02299 -0.671239 1.8215 - 1.03301 -0.668207 1.83648 - 1.28712 -0.690291 2.21605 - 1.29972 -0.618198 2.23514 - 1.30188 -0.541611 2.23864 - 1.30316 -0.531127 2.24059 - 1.30565 -0.510128 2.24439 - 1.30267 -0.443637 2.24017 - 1.30252 -0.378858 2.24018 - 1.29865 -0.271304 2.23479 - 1.30085 -0.19774 2.23834 - 1.3011 -0.0296961 2.23931 - 1.30116 -0.00873549 2.23948 - 1.30538 0.0753791 2.24608 - 1.30283 0.212229 2.24277 - 1.30108 0.393153 2.24081 - 1.30533 0.648022 2.24807 - 1.30477 0.670381 2.24732 - 1.26346 0.727334 2.1858 - 1.26882 0.890974 2.1944 - 1.26767 0.901922 2.19272 - 1.27918 1.26037 2.21121 - 1.15847 1.28081 2.03093 - 1.14031 1.28654 2.00382 - 0.999348 1.28256 1.7932 - 0.77062 1.28654 1.45148 - 0.743508 1.2765 1.41094 - 0.680947 1.27028 1.31745 - 0.63709 1.27899 1.25195 - 0.56336 1.27691 1.14179 - 0.544186 1.28083 1.11316 - 0.41123 1.27932 0.91451 - 0.403537 1.28205 0.903026 - 0.39926 1.28209 0.896636 - 0.395279 1.28293 0.89069 - 0.351463 1.27527 0.825199 - 0.34187 1.28342 0.810896 - 0.319224 1.27296 0.777025 - 0.278295 1.291 0.715939 - 0.208101 1.14956 0.610557 - 0.203894 1.17587 0.604366 - 0.201223 1.17868 0.600385 - 0.199764 1.23894 0.598422 - 0.194433 1.2464 0.590485 - 0.133197 1.16454 0.498699 - 0.124512 1.21275 0.485897 - 0.109155 1.18834 0.462866 - 0.0829695 1.26068 0.424003 - 0.0768426 1.26251 0.414856 - 0.0606615 1.17903 0.39038 - 0.0354853 1.24822 0.353014 - 0.0111495 1.17283 0.316384 - -0.022207 1.26072 0.266864 - -0.0544882 1.17757 0.218335 - -0.0972287 1.17198 0.154458 - -0.113602 1.24943 0.130274 - -0.125134 1.16019 0.112723 - -0.174338 1.15892 0.0392056 - -0.207109 1.17995 -0.0096799 - -0.208101 1.16603 -0.0112134 - -0.210927 1.16468 -0.0154405 - -0.215967 1.15805 -0.0229936 - -0.221576 1.15519 -0.0313848 - -0.224849 1.15661 -0.0362688 - -0.240878 1.17823 -0.0601402 - -0.254399 1.16615 -0.080384 - -0.305792 1.24015 -0.156901 - -0.342517 1.2758 -0.211643 - -0.351996 1.26941 -0.225828 - -0.361199 1.26189 -0.239604 - -0.367076 1.21474 -0.248554 - -0.371094 0.989549 -0.255368 - -0.369463 0.758965 -0.253761 - -0.37095 0.755561 -0.255994 - -0.368618 0.737076 -0.252576 - -0.366368 0.706626 -0.249324 - -0.369384 0.664678 -0.253982 - -0.233739 -0.401462 -0.0622313 - -0.232047 -0.40156 -0.0596431 - -0.227456 -0.406289 -0.0526391 - -0.223381 -0.404786 -0.0463999 - -0.219065 -0.406193 -0.0398029 - -0.189391 -0.401176 0.00560257 - -0.184957 -0.400724 0.0123865 - -0.183997 -0.40192 0.0138509 - -0.167568 -0.397506 0.0389953 - -0.165661 -0.399613 0.0419042 - -0.159502 -0.400405 0.0513216 - -0.154944 -0.406173 0.0582729 - -0.142433 -0.449561 0.0772505 - -0.385146 -1.72863 -0.298666 - -0.37665 -2.10041 -0.28703 - -0.372492 -2.14328 -0.280827 - -0.302977 -2.15566 -0.174546 - -0.165883 -2.25967 0.0347668 - -0.152393 -2.21098 0.0555785 - -0.0382722 -0.416941 0.236689 - 0.0460825 -2.28562 0.358884 - 0.0760023 -2.22535 0.404869 - 0.142345 -2.17997 0.506509 - 0.025314 -0.453044 0.333816 - 0.0285947 -0.388238 0.339071 - 0.0229939 -0.343236 0.330668 - 0.0602072 -0.358351 0.387533 - 0.075522 -0.354958 0.41097 - 0.0805703 -0.353063 0.418698 - 0.11969 -0.41309 0.478314 - 0.12322 -0.414722 0.483709 - 0.129093 -0.410763 0.492705 - 0.176788 -0.409792 0.565661 - 0.188708 -0.418023 0.583863 - 0.21106 -0.386107 0.618169 - 0.367652 -0.604376 0.856887 - 0.532928 -0.815212 1.10891 - 0.536665 -0.791571 1.11472 - 0.538167 -0.717442 1.11729 - 0.558465 -0.655979 1.14856 - 0.621429 -0.662833 1.24484 - 0.667608 -0.666294 1.31546 - 0.683553 -0.659791 1.33987 - 0.787072 -0.66677 1.49818 - 1.00046 -0.667908 1.82457 - 1.27045 -0.614702 2.23772 - 1.26976 -0.603312 2.23672 - 1.27526 -0.561635 2.24527 - 1.27269 -0.440914 2.24178 - 1.27213 -0.019112 2.24247 - 1.27215 -0.00868821 2.24254 - 1.27942 0.10665 2.25409 - 1.28157 0.159501 2.25757 - 1.27246 0.305876 2.24416 - 1.27576 0.34928 2.24937 - 1.27561 0.59953 2.25005 - 1.27573 0.610724 2.25029 - 1.27205 0.69879 2.24498 - 1.26826 0.765111 2.23942 - 1.27289 1.06779 2.2476 - 1.27096 1.22025 2.24521 - 1.14118 1.28337 2.04694 - 0.988065 1.2778 1.81272 - 0.745635 1.27886 1.44191 - 0.712185 1.27906 1.39075 - 0.60852 1.27858 1.23219 - 0.605084 1.28298 1.22695 - 0.59053 1.27607 1.20466 - 0.583478 1.27285 1.19386 - 0.539297 1.28012 1.12631 - 0.443539 1.2805 0.979849 - 0.275121 1.28486 0.722261 - 0.216904 1.18104 0.632835 - 0.197657 1.1815 0.603397 - 0.188793 1.2558 0.590111 - 0.180745 1.26682 0.577842 - 0.126994 1.18462 0.495326 - 0.125857 1.19853 0.493637 - 0.0847862 1.17812 0.430743 - 0.0285848 1.25926 0.345077 - -0.0875773 1.16134 0.167043 - -0.0937665 1.17344 0.15762 - -0.172953 1.16381 0.0364647 - -0.182623 1.17119 0.0217015 - -0.195924 1.20455 0.00147824 - -0.219917 1.16192 -0.0353758 - -0.236852 1.1725 -0.06124 - -0.23998 1.1728 -0.0660234 - -0.242776 1.17117 -0.0703053 - -0.252368 1.17279 -0.084971 - -0.364893 1.22552 -0.256891 - -0.363667 1.02235 -0.255759 - -0.362492 0.873271 -0.254506 - -0.360358 0.763375 -0.251645 - -0.359631 0.690779 -0.250798 - -0.357362 0.617592 -0.247594 - -0.148492 -0.43427 0.0639893 - -0.149803 -0.459653 0.061842 - -0.388977 -1.50617 -0.316375 - -0.387304 -1.59324 -0.31408 - -0.11599 -0.439775 0.114837 - -0.112547 -0.439815 0.120226 - -0.111512 -0.440442 0.121843 - -0.319059 -2.14668 -0.209326 - -0.257382 -2.06598 -0.112496 - -0.252523 -2.06779 -0.104898 - -0.220103 -2.15782 -0.0544914 - -0.183632 -2.15461 0.00260139 - -0.0325197 -0.42398 0.245535 - -0.0294905 -0.426891 0.250265 - 0.0525458 -2.21348 0.372023 - 0.0567366 -2.18884 0.378674 - 0.0733272 -2.21041 0.40456 - 0.170081 -2.17189 0.556131 - 0.0232075 -0.492446 0.332499 - 0.0685602 -0.356621 0.403985 - 0.0787621 -0.353922 0.419962 - 0.121069 -0.416364 0.485944 - 0.123015 -0.413824 0.489 - 0.151144 -0.421793 0.532994 - 0.175883 -0.418781 0.571725 - 0.195972 -0.381904 0.603302 - 0.198077 -0.382017 0.606597 - 0.523125 -0.697119 1.11416 - 0.524519 -0.660123 1.11648 - 0.528796 -0.658787 1.12318 - 0.553325 -0.661161 1.16156 - 0.676701 -0.657181 1.35467 - 0.804502 -0.667958 1.55465 - 1.03765 -0.683873 1.91949 - 1.24235 -0.491496 2.24058 - 1.24453 -0.38518 2.24438 - 1.2404 -0.153546 2.23878 - 1.24449 -0.14363 2.24522 - 1.24433 0.0224699 2.24559 - 1.24199 0.0431383 2.242 - 1.24025 0.0844681 2.23942 - 1.24034 0.334902 2.24051 - 1.24379 0.539787 2.24665 - 1.24565 0.617664 2.24986 - 1.24373 0.650098 2.24697 - 1.24364 0.683653 2.24695 - 1.24544 0.98867 2.25091 - 1.24705 1.00215 2.25348 - 1.24423 1.02451 2.24916 - 1.2343 1.28479 2.23458 - 1.22042 1.28401 2.21285 - 1.09567 1.27927 2.01759 - 1.04633 1.28453 1.94038 - 1.00313 1.28134 1.87276 - 0.993846 1.28198 1.85823 - 0.825766 1.27732 1.59515 - 0.822745 1.2843 1.59045 - 0.72539 1.27773 1.43806 - 0.717605 1.27582 1.42587 - 0.669268 1.2807 1.35023 - 0.660887 1.2766 1.3371 - 0.599706 1.28225 1.24137 - 0.547319 1.27371 1.15934 - 0.488683 1.27563 1.06758 - 0.335502 1.2783 0.827848 - 0.293644 1.27763 0.762333 - 0.273085 1.28327 0.730178 - 0.250123 1.27671 0.694215 - 0.177695 1.25174 0.580765 - 0.145095 1.16574 0.529423 - 0.133405 1.16666 0.511131 - 0.120682 1.22734 0.491444 - 0.0947437 1.1583 0.450592 - 0.0532731 1.16692 0.385718 - 0.0450377 1.16902 0.372837 - 0.0369722 1.17391 0.360232 --0.00714385 1.18767 0.291237 - -0.0460674 1.16989 0.230252 - -0.0516464 1.1757 0.221542 - -0.0698567 1.23353 0.193256 - -0.0844157 1.16472 0.170214 - -0.0925692 1.16248 0.157445 - -0.143305 1.17058 0.0780675 - -0.174102 1.16565 0.0298502 - -0.176363 1.16063 0.0262928 - -0.209895 1.17198 -0.026147 - -0.212645 1.17057 -0.0304552 - -0.339013 1.27004 -0.227863 - -0.356453 1.23972 -0.255273 - -0.358543 1.10861 -0.259031 - -0.356934 1.00681 -0.256889 - -0.357178 0.98788 -0.257342 - -0.356961 0.977586 -0.257041 - -0.356409 0.815865 -0.256778 - -0.354105 0.795389 -0.253248 - -0.354532 0.684409 -0.254328 - -0.353863 0.648002 -0.253416 - -0.348803 0.621228 -0.245596 - -0.193924 -0.40405 -0.0141988 - -0.165872 -0.401546 0.0309823 - -0.152139 -0.397146 0.0531146 - -0.144664 -0.44696 0.0649623 - -0.372789 -1.46588 -0.306256 - -0.376494 -1.49986 -0.312352 - -0.378713 -1.60536 -0.316324 - -0.369114 -1.62125 -0.300928 - -0.334869 -2.14863 -0.247782 - -0.241493 -2.0988 -0.0972257 - -0.190813 -2.15306 -0.0158199 - -0.176699 -2.16872 0.00684828 - -0.15589 -2.25276 0.0400398 - -0.130338 -2.14793 0.0815844 - -0.0395542 -0.410908 0.234361 - -0.0318692 -0.423959 0.246687 - -0.0251727 -0.46063 0.257331 - 0.0372506 -2.27623 0.35097 - 0.162275 -2.13444 0.552838 - 0.177172 -2.18329 0.576642 - 0.18721 -2.17975 0.592819 - 0.192633 -2.18184 0.601544 - 0.0233123 -0.44965 0.335449 - 0.0292152 -0.444678 0.344974 - 0.0308225 -0.440713 0.347577 - 0.0250474 -0.33513 0.338678 - 0.0302032 -0.334844 0.346981 - 0.04355 -0.346275 0.368431 - 0.0764581 -0.354781 0.421391 - 0.109667 -0.409715 0.47466 - 0.128053 -0.413222 0.504255 - 0.12932 -0.412668 0.506297 - 0.137957 -0.415194 0.520196 - 0.159635 -0.42001 0.555087 - 0.187213 -0.385455 0.599626 - 0.498089 -0.83062 1.09855 - 0.505122 -0.715079 1.11032 - 0.539663 -0.665916 1.16612 - 0.600137 -0.665738 1.26351 - 0.775093 -0.665991 1.54524 - 0.780491 -0.662441 1.55395 - 1.20265 -0.348899 2.23495 - 1.20495 -0.276503 2.23893 - 1.20909 -0.152899 2.24607 - 1.20871 0.0222997 2.24612 - 1.20754 0.0737221 2.24444 - 1.20951 0.104788 2.24772 - 1.2087 0.177055 2.24669 - 1.20902 0.281101 2.24761 - 1.20826 0.3438 2.24662 - 1.21334 0.614651 2.25582 - 1.20842 0.667557 2.2481 - 1.21072 0.827922 2.2524 - 1.20767 0.955461 2.24797 - 1.20902 0.980619 2.25026 - 1.21133 1.04362 2.25422 - 1.20626 1.16493 2.24651 - 1.20885 1.20615 2.25083 - 1.15774 1.28441 2.16883 - 1.12462 1.28723 2.11551 - 0.886956 1.27559 1.73274 - 0.7637 1.28818 1.53431 - 0.62685 1.27286 1.31387 - 0.515678 1.27471 1.13486 - 0.51107 1.2754 1.12744 - 0.500232 1.28422 1.11002 - 0.476393 1.28386 1.07163 - 0.427483 1.28545 0.992874 - 0.424513 1.28929 0.988106 - 0.359265 1.28006 0.883 - 0.313403 1.28133 0.809152 - 0.276904 1.28195 0.75038 - 0.189198 1.18432 0.608775 - 0.167026 1.23439 0.573259 - 0.11927 1.22022 0.496303 - 0.0985624 1.16881 0.462763 - 0.0928497 1.16809 0.453561 - 0.0456926 1.16735 0.377619 - 0.0403131 1.16869 0.368962 - 0.035647 1.18185 0.361498 - 0.0323593 1.27507 0.356557 --0.00833727 1.17568 0.290645 - -0.010186 1.21688 0.287824 - -0.0545904 1.18957 0.216215 - -0.16316 1.16496 0.0412887 - -0.168515 1.16284 0.0326578 - -0.203821 1.23554 -0.0239214 - -0.210124 1.17539 -0.0342996 - -0.228962 1.16486 -0.0646746 - -0.305724 1.22377 -0.188063 - -0.339495 1.26693 -0.242281 - -0.348725 1.19331 -0.257424 - -0.346536 1.077 -0.254341 - -0.345873 1.01109 -0.253523 - -0.348281 0.979312 -0.25752 - -0.347775 0.958791 -0.256783 - -0.348857 0.952814 -0.258549 - -0.345273 0.89779 -0.252985 - -0.345525 0.826015 -0.253664 - -0.3428 0.803847 -0.249359 - -0.343606 0.716882 -0.250987 - -0.342016 0.67634 -0.24858 - -0.343867 0.634372 -0.25172 - -0.344241 0.629624 -0.25234 - -0.233909 -0.404311 -0.0862091 - -0.223024 -0.39924 -0.0682451 - -0.211409 -0.405484 -0.0491202 - -0.204967 -0.397624 -0.0384683 - -0.204063 -0.399048 -0.0369837 - -0.196678 -0.402687 -0.024823 - -0.195763 -0.404041 -0.0233196 - -0.182308 -0.405686 -0.00114192 - -0.172518 -0.396803 0.0150329 - -0.166429 -0.40555 0.0250377 - -0.161788 -0.40284 0.032699 - -0.149929 -0.412417 0.0522137 - -0.148774 -0.416988 0.0541007 - -0.369811 -1.61006 -0.314916 - -0.356715 -2.11753 -0.295282 - -0.305424 -2.15967 -0.210884 - -0.290958 -2.16833 -0.187067 - -0.246658 -2.08545 -0.113712 - -0.176926 -2.20741 0.00078273 - -0.117194 -2.22997 0.0991732 - -0.0312214 -0.42093 0.247889 - 0.0307538 -2.27778 0.342904 - 0.0537075 -2.20579 0.381025 - 0.102689 -2.18356 0.461864 - 0.0258047 -0.453007 0.341782 - 0.0409579 -0.341683 0.367194 - 0.0583306 -0.361422 0.395759 - 0.0595754 -0.354584 0.397838 - 0.104487 -0.414107 0.471652 - 0.124753 -0.412421 0.505071 - 0.14314 -0.420245 0.535354 - 0.145081 -0.421054 0.538551 - 0.172246 -0.417235 0.583352 - 0.175717 -0.420518 0.589062 - 0.179479 -0.413356 0.595292 - 0.496083 -0.689299 1.1162 - 0.492663 -0.672071 1.11063 - 0.524835 -0.660176 1.16371 - 1.1056 -0.691528 2.12108 - 1.17439 -0.666725 2.23459 - 1.17587 -0.656546 2.23707 - 1.17237 -0.600221 2.23151 - 1.17899 -0.538631 2.24266 - 1.17241 -0.419322 2.23228 - 1.17935 -0.369204 2.2439 - 1.17707 -0.33723 2.24028 - 1.17353 -0.253599 2.23476 - 1.17408 -0.243424 2.2357 - 1.17867 -0.213419 2.24339 - 1.17855 -0.131243 2.2435 - 1.17721 -0.100414 2.24142 - 1.17702 -0.0391219 2.24133 - 1.17586 0.309479 2.24078 - 1.17705 0.393358 2.24306 - 1.1787 0.47859 2.24611 - 1.1731 0.518985 2.23704 - 1.17241 0.529381 2.23593 - 1.1824 0.698397 2.25305 - 1.17948 0.730306 2.24836 - 1.17779 0.740535 2.24562 - 1.18014 0.844806 2.2499 - 1.17951 0.890974 2.24903 - 1.17731 1.23511 2.24673 - 1.07966 1.2844 2.08593 - 0.992092 1.27976 1.94154 - 0.847353 1.27687 1.70291 - 0.81885 1.28134 1.65593 - 0.797096 1.28293 1.62007 - 0.777977 1.27614 1.58853 - 0.764968 1.27837 1.56709 - 0.715516 1.27623 1.48555 - 0.674723 1.27239 1.41828 - 0.638274 1.27232 1.35819 - 0.554695 1.28255 1.22044 - 0.549042 1.28153 1.21111 - 0.511583 1.27628 1.14933 - 0.483161 1.27687 1.10248 - 0.385513 1.28423 0.941519 - 0.324618 1.27702 0.841094 - 0.321719 1.28006 0.836328 - 0.306019 1.27689 0.810431 - 0.303121 1.27977 0.805665 - 0.268418 1.28454 0.74847 - 0.265504 1.28711 0.743676 - 0.246388 1.27935 0.712129 - 0.239983 1.28132 0.701577 - 0.219307 1.27907 0.667481 - 0.179052 1.18426 0.600748 - 0.10279 1.17918 0.474999 - 0.0815406 1.1899 0.440007 - 0.0804931 1.23808 0.438466 - 0.0439014 1.16537 0.377858 - 0.0357893 1.25796 0.364841 - 0.017905 1.1811 0.33506 - 0.00391218 1.16521 0.311929 --0.00894088 1.18168 0.290802 - -0.0184319 1.27043 0.275497 - -0.027727 1.17483 0.259804 - -0.0489188 1.1678 0.224839 - -0.057956 1.2294 0.210177 - -0.123517 1.16839 0.101854 - -0.128799 1.16691 0.0931405 - -0.163781 1.24256 0.0357587 - -0.285389 1.27259 -0.164616 - -0.306216 1.23076 -0.199113 - -0.326654 1.2475 -0.232745 - -0.339466 1.25826 -0.253826 - -0.339704 0.97758 -0.255301 - -0.339978 0.816947 -0.256372 - -0.336568 0.699443 -0.251203 - -0.336066 0.633947 -0.250628 - -0.337854 0.626689 -0.253604 - -0.332913 0.590162 -0.245598 - -0.241295 -0.406173 -0.10859 - -0.190733 -0.399278 -0.0227004 - -0.171233 -0.400962 0.0104072 - -0.168066 -0.399098 0.0157926 - -0.149412 -0.427611 0.0473575 - -0.150931 -0.457476 0.0446615 - -0.327109 -1.31572 -0.257903 - -0.339258 -2.1496 -0.28182 - -0.313368 -2.14678 -0.237843 - -0.296626 -2.17557 -0.209526 - -0.183775 -2.13226 -0.0177151 - -0.171494 -2.24732 0.00268605 - -0.120661 -2.23222 0.0890703 - -0.0441971 -0.448666 0.225948 - -0.0315055 -0.427928 0.247582 - -0.0295802 -0.429844 0.250844 - 0.100393 -2.19747 0.464594 - 0.132672 -2.16669 0.51953 - 0.186008 -2.15643 0.610144 - 0.224576 -2.27537 0.675171 - 0.0175475 -0.4336 0.33086 - 0.0289319 -0.448411 0.350135 - 0.0209262 -0.337062 0.336979 - 0.0295657 -0.342728 0.351628 - 0.0294143 -0.33749 0.351391 - 0.0342818 -0.340176 0.359646 - 0.03788 -0.340481 0.365756 - 0.0462529 -0.357293 0.379908 - 0.0472543 -0.357496 0.381608 - 0.0507096 -0.359849 0.387466 - 0.0540758 -0.365554 0.39316 - 0.0631903 -0.35058 0.408697 - 0.0719625 -0.35564 0.423574 - 0.107335 -0.420518 0.483387 - 0.125315 -0.419851 0.513923 - 0.135241 -0.418553 0.530783 - 0.17196 -0.394268 0.593235 - 0.17626 -0.385255 0.600572 - 0.473756 -0.8249 1.10404 - 0.474372 -0.728123 1.10547 - 0.492866 -0.661733 1.13713 - 0.500075 -0.657922 1.14939 - 0.631278 -0.660689 1.37219 - 0.645921 -0.667874 1.39702 - 0.870632 -0.665847 1.77863 - 0.897396 -0.667313 1.82407 - 0.965513 -0.68696 1.93967 - 1.11385 -0.690398 2.19156 - 1.13483 -0.551823 2.22773 - 1.13834 -0.521592 2.23381 - 1.14249 -0.407601 2.24132 - 1.14522 -0.387656 2.24602 - 1.14605 -0.377499 2.24747 - 1.14192 -0.283244 2.24083 - 1.14397 -0.110003 2.24499 - 1.14099 -0.0793163 2.24006 - 1.14376 0.103236 2.24547 - 1.14189 0.30751 2.24311 - 1.14243 0.59221 2.24514 - 1.14305 0.603352 2.24625 - 1.1461 0.615793 2.25147 - 1.14381 0.658304 2.24775 - 1.14598 0.703739 2.25162 - 1.14478 0.770196 2.24985 - 1.14151 0.894023 2.24477 - 1.14203 0.953232 2.24589 - 1.14556 1.0405 2.25222 - 1.14365 1.20178 2.24963 - 1.04328 1.28296 2.07949 - 0.94702 1.28742 1.91605 - 0.797272 1.27706 1.66171 - 0.78163 1.27589 1.63514 - 0.752033 1.28601 1.58492 - 0.735827 1.28218 1.55738 - 0.657568 1.26967 1.42444 - 0.650426 1.27885 1.41235 - 0.632027 1.27774 1.3811 - 0.577276 1.28044 1.28813 - 0.502259 1.27164 1.16071 - 0.497817 1.27243 1.15316 - 0.483894 1.27293 1.12952 - 0.474122 1.28315 1.11297 - 0.439093 1.28535 1.05349 - 0.406905 1.27886 0.998806 - 0.401508 1.27523 0.989627 - 0.395271 1.28108 0.979058 - 0.316497 1.27702 0.845271 - 0.28683 1.27385 0.794879 - 0.277004 1.27674 0.778203 - 0.267625 1.28114 0.762293 - 0.253324 1.27871 0.737998 - 0.156861 1.18624 0.573823 - 0.135905 1.16138 0.538138 - 0.114476 1.21115 0.501945 - 0.107522 1.17747 0.490003 - 0.087125 1.16613 0.45532 - 0.0845401 1.1672 0.450935 - 0.0287316 1.26711 0.356556 - 0.012903 1.16064 0.329257 --0.00230383 1.17086 0.303473 - -0.064102 1.26698 0.198908 - -0.079559 1.15412 0.172215 - -0.114451 1.2591 0.113377 - -0.187807 1.17869 -0.0115123 - -0.206824 1.17491 -0.0438219 - -0.212853 1.15896 -0.0541217 - -0.304849 1.23493 -0.210048 - -0.331971 1.17179 -0.256354 - -0.330658 1.12938 -0.254293 - -0.330779 1.0499 -0.25481 - -0.329245 0.973222 -0.252508 - -0.325626 0.694216 -0.247462 - -0.32868 0.689233 -0.252669 - -0.194657 -0.397972 -0.0359759 - -0.172155 -0.402747 0.00315379 - -0.138403 -0.458765 0.0616499 - -0.303975 -1.2324 -0.229512 - -0.349109 -1.49352 -0.309084 - -0.109501 -0.437589 0.112018 - -0.307552 -2.13904 -0.239375 - -0.227409 -2.11624 -0.0998525 - -0.213453 -2.17798 -0.07582 - -0.109792 -2.24064 0.104275 - -0.0903611 -2.246 0.138059 - -0.0438904 -0.427681 0.226205 - -0.0382682 -0.418967 0.236022 - -0.0373572 -0.418986 0.237607 - 0.050252 -2.21477 0.38282 - 0.105217 -2.16237 0.478657 - 0.109714 -2.15816 0.486498 - 0.135545 -2.18205 0.531341 - 0.213536 -2.26584 0.666691 - 0.0188317 -0.471515 0.335152 - 0.0269607 -0.43001 0.349461 - 0.0182282 -0.338021 0.334637 - 0.0376197 -0.338288 0.368373 - 0.0471006 -0.356058 0.384797 - 0.0611142 -0.357537 0.409171 - 0.0747354 -0.357837 0.432868 - 0.07684 -0.361104 0.436516 - 0.104685 -0.41309 0.484751 - 0.108186 -0.415543 0.490833 - 0.117408 -0.414566 0.506881 - 0.124946 -0.419449 0.519976 - 0.125854 -0.418039 0.521562 - 0.126759 -0.41662 0.523142 - 0.156597 -0.416814 0.575052 - 0.157499 -0.415127 0.576627 - 0.173245 -0.377084 0.604175 - 0.211 -0.425892 0.669663 - 0.468098 -0.77361 1.11556 - 0.463068 -0.699036 1.10711 - 0.46572 -0.664353 1.11186 - 0.467152 -0.65996 1.11437 - 0.533774 -0.658169 1.23029 - 0.640313 -0.667312 1.4156 - 0.672166 -0.668254 1.47102 - 0.69188 -0.663692 1.50533 - 0.703775 -0.66675 1.52601 - 0.741524 -0.668352 1.59168 - 0.875748 -0.672907 1.82518 - 1.11405 -0.594728 2.24009 - 1.11507 -0.447104 2.24245 - 1.11587 -0.416132 2.24397 - 1.11883 -0.221445 2.2499 - 1.11342 -0.169737 2.24069 - 1.11209 -0.149341 2.23846 - 1.11258 0.0318598 2.24004 - 1.11577 0.183705 2.2462 - 1.11733 0.194129 2.24896 - 1.11511 0.306066 2.24556 - 1.11371 0.326229 2.24319 - 1.11615 0.536165 2.24829 - 1.11215 0.609155 2.24161 - 1.11128 0.619475 2.24014 - 1.11523 0.654222 2.24715 - 1.11475 0.719903 2.24658 - 1.11366 1.12961 2.24633 - 1.11921 1.14766 2.25605 - 0.811385 1.28732 1.72107 - 0.662137 1.27919 1.46138 - 0.588913 1.28334 1.33401 - 0.432213 1.27882 1.06137 - 0.403167 1.27995 1.01084 - 0.392821 1.28564 0.992861 - 0.371747 1.28234 0.956183 - 0.273282 1.28573 0.78489 - 0.262116 1.28205 0.765448 - 0.101084 1.16996 0.484839 - 0.0794734 1.25279 0.447575 - 0.0562134 1.1717 0.406782 - 0.0180332 1.18659 0.340417 - -0.0197336 1.27043 0.275048 - -0.0725838 1.19003 0.182778 - -0.107227 1.24943 0.122745 - -0.110995 1.2667 0.116259 - -0.127922 1.16119 0.0863867 - -0.153249 1.23677 0.0426253 - -0.163138 1.19817 0.0252669 - -0.217644 1.15531 -0.0697339 - -0.223733 1.15879 -0.0803139 - -0.261548 1.27797 -0.145625 - -0.289639 1.26003 -0.194569 - -0.297008 1.26484 -0.207369 - -0.309969 1.22101 -0.230095 - -0.322001 1.11512 -0.251452 - -0.322914 1.07236 -0.253212 - -0.323992 0.89948 -0.255782 - -0.322523 0.81464 -0.253567 - -0.32164 0.6783 -0.252578 - -0.316765 0.655062 -0.244189 - -0.31738 0.601495 -0.245475 - -0.170613 -0.410574 -0.00145054 - -0.165654 -0.40296 0.00747399 - -0.162089 -0.399395 0.0138838 - -0.153466 -0.402186 0.0293384 - -0.148251 -0.425514 0.0385958 - -0.149173 -0.433567 0.0369087 - -0.140898 -0.474246 0.0515842 - -0.336522 -2.10985 -0.306008 - -0.275539 -2.16541 -0.196855 - -0.211136 -2.19771 -0.0814734 - -0.199635 -2.17217 -0.0607414 - -0.191704 -2.12818 -0.0463344 - -0.125774 -2.19973 0.0716249 - -0.0838287 -2.21452 0.146797 - -0.0403229 -0.426904 0.232172 - -0.0375732 -0.413986 0.237157 - -0.0340039 -0.42198 0.243526 - -0.0302697 -0.431843 0.250183 - -0.0293353 -0.432787 0.251855 - -0.0284541 -0.430726 0.253444 - -0.0264842 -0.436569 0.256953 - 0.110534 -2.15293 0.495662 - 0.21163 -2.25585 0.676566 - 0.0281436 -0.442878 0.354909 - 0.025214 -0.397608 0.34984 - 0.0238167 -0.33726 0.347582 - 0.0306154 -0.346946 0.359736 - 0.0312901 -0.333419 0.361002 - 0.0378719 -0.352705 0.372728 - 0.0491233 -0.361953 0.392871 - 0.0847109 -0.392237 0.456577 - 0.0961434 -0.40924 0.477012 - 0.115699 -0.416425 0.512058 - 0.118348 -0.416078 0.51681 - 0.119228 -0.414692 0.518394 - 0.126955 -0.416215 0.532247 - 0.150069 -0.416283 0.573704 - 0.162162 -0.40629 0.595437 - 0.449975 -0.812934 1.10999 - 0.466411 -0.661944 1.14009 - 0.534333 -0.660966 1.26192 - 0.605574 -0.669586 1.38966 - 0.703725 -0.66665 1.56572 - 0.737124 -0.663989 1.62564 - 1.02266 -0.693815 2.13765 - 1.05068 -0.690803 2.18793 - 1.0795 -0.622508 2.23989 - 1.08001 -0.590733 2.24095 - 1.08297 -0.260169 2.24761 - 1.07789 -0.108255 2.23912 - 1.07827 -0.0882808 2.23989 - 1.07711 -0.0682104 2.23789 - 1.08025 0.031694 2.24392 - 1.07644 0.0914873 2.23734 - 1.07851 0.14177 2.24127 - 1.07783 0.161754 2.24013 - 1.08013 0.212486 2.24445 - 1.08153 0.243129 2.24709 - 1.0838 0.44931 2.25201 - 1.08126 0.479616 2.24758 - 1.08105 0.500498 2.24729 - 1.08202 0.771451 2.25014 - 1.08464 0.795734 2.25494 - 1.08118 0.815823 2.24882 - 1.07809 0.836193 2.24336 - 1.0818 1.09947 2.25109 - 0.955059 1.27753 2.0245 - 0.882302 1.27801 1.89401 - 0.864404 1.27689 1.8619 - 0.698878 1.27318 1.565 - 0.68899 1.27855 1.54728 - 0.44721 1.27966 1.11363 - 0.376453 1.27859 0.986713 - 0.373726 1.2823 0.981836 - 0.357283 1.27917 0.95233 - 0.336074 1.28374 0.914308 - 0.323702 1.27902 0.892098 - 0.301896 1.2779 0.852982 - 0.267971 1.28029 0.792145 - 0.234807 1.28001 0.732659 - 0.20691 1.28434 0.682641 - 0.154018 1.1688 0.587298 - 0.130408 1.17576 0.54498 - 0.120008 1.19947 0.526424 - 0.106952 1.18171 0.502934 - 0.0621408 1.17995 0.422552 - 0.0532348 1.16479 0.406516 - 0.0354076 1.24972 0.374889 - 0.0335224 1.26428 0.371568 - 0.0106052 1.16761 0.330066 - -0.0150695 1.26905 0.284432 - -0.0177665 1.26926 0.279596 - -0.132299 1.17438 0.0737797 - -0.158256 1.2563 0.0275581 - -0.169921 1.1632 0.00625336 - -0.196123 1.20234 -0.0405821 - -0.211207 1.17372 -0.0677543 - -0.307262 1.23562 -0.239786 - -0.308467 1.22683 -0.241983 - -0.316972 1.19551 -0.257366 - -0.315018 1.13615 -0.254105 - -0.315999 1.09238 -0.256045 - -0.314099 1.01939 -0.252937 - -0.317652 0.826158 -0.260102 - -0.311586 0.640158 -0.249987 - -0.308714 0.606374 -0.244974 - -0.309937 0.598571 -0.2472 - -0.226889 -0.399805 -0.111058 - -0.205261 -0.4078 -0.0713116 - -0.20355 -0.410873 -0.0681762 - -0.194044 -0.401484 -0.0506539 - -0.190026 -0.401874 -0.0432654 - -0.174753 -0.399864 -0.0151647 - -0.162602 -0.400457 0.00718193 - -0.14723 -0.39926 0.0354593 - -0.13969 -0.476977 0.0490033 - -0.114924 -0.442228 0.0946999 - -0.252837 -2.22081 -0.166407 - -0.219259 -2.11034 -0.104187 - -0.21231 -2.13632 -0.0915135 - -0.207231 -2.18883 -0.0823913 - -0.14343 -2.21496 0.0348475 - -0.0925768 -2.2255 0.128336 - -0.0368905 -0.414996 0.23834 - -0.0324826 -0.422929 0.246414 - -0.0316013 -0.422892 0.248035 - 0.0239133 -2.24083 0.34253 - 0.0937156 -2.22726 0.470973 - 0.0969674 -2.20325 0.477054 - 0.211894 -2.25754 0.688208 - 0.0187247 -0.458866 0.340448 - 0.0220808 -0.461192 0.346611 - 0.0242971 -0.470313 0.350649 - 0.0261994 -0.45362 0.354218 - 0.027559 -0.435021 0.356796 - 0.0172163 -0.338961 0.338175 - 0.0176143 -0.336572 0.338917 - 0.0204083 -0.334551 0.344065 - 0.0343814 -0.347843 0.36971 - 0.0404995 -0.352038 0.380945 - 0.0950004 -0.414241 0.480927 - 0.107157 -0.41238 0.503293 - 0.114611 -0.418255 0.51698 - 0.132727 -0.413403 0.550321 - 0.161732 -0.382542 0.603798 - 0.398773 -0.775428 1.03814 - 0.548822 -0.663315 1.31459 - 0.584585 -0.660519 1.38038 - 0.662548 -0.664934 1.52376 - 0.749668 -0.671284 1.68397 - 1.04807 -0.648854 2.23291 - 1.04903 -0.575086 2.23498 - 1.05938 -0.199052 2.25559 - 1.05442 -0.17809 2.24655 - 1.05311 -0.018256 2.24482 - 1.04763 0.22037 2.23574 - 1.05056 0.281345 2.24139 - 1.05246 0.528718 2.24591 - 1.05193 0.810137 2.24611 - 1.05161 0.832423 2.24562 - 1.04987 0.981013 2.24304 - 1.05103 1.16478 2.24594 - 1.0571 1.20947 2.25729 - 0.927511 1.27894 2.01924 - 0.879021 1.28643 1.93008 - 0.850839 1.28256 1.87823 - 0.841492 1.28098 1.86103 - 0.830998 1.27753 1.84172 - 0.713967 1.27866 1.62647 - 0.578131 1.28295 1.37665 - 0.48641 1.27881 1.20793 - 0.465363 1.28321 1.16923 - 0.450434 1.27897 1.14176 - 0.445686 1.27795 1.13302 - 0.397822 1.28452 1.04501 - 0.302796 1.28047 0.870216 - 0.255699 1.28214 0.783599 - 0.225542 1.27695 0.728112 - 0.203788 1.27748 0.688101 - 0.136453 1.16761 0.563793 - 0.0987503 1.15971 0.494414 - 0.0963298 1.16096 0.489968 - 0.0295337 1.26989 0.367567 - 0.00685096 1.16406 0.325404 - -0.0856301 1.16591 0.155313 - -0.113118 1.25446 0.105126 - -0.132536 1.16565 0.0690391 - -0.137388 1.16389 0.0601074 - -0.168408 1.17002 0.00307931 - -0.173048 1.16567 -0.00547454 - -0.175474 1.16443 -0.00994182 - -0.178015 1.16414 -0.0146166 - -0.187253 1.1757 -0.0315598 - -0.201061 1.18018 -0.0569367 - -0.203245 1.17677 -0.0609682 - -0.207859 1.17181 -0.0694758 - -0.284348 1.26801 -0.209758 - -0.290171 1.26625 -0.220474 - -0.302788 1.26697 -0.243678 - -0.307917 1.20498 -0.253371 - -0.308994 1.108 -0.255758 - -0.30712 0.916178 -0.253115 - -0.305112 0.883378 -0.249559 - -0.305411 0.761682 -0.250617 - -0.306288 0.723863 -0.252389 - -0.308692 0.717367 -0.256838 - -0.30473 0.608584 -0.250007 - -0.301594 0.585937 -0.244334 - -0.302359 0.577488 -0.245776 - -0.299889 0.56716 -0.241277 - -0.216091 -0.408166 -0.0993758 - -0.214297 -0.407639 -0.0959929 - -0.192476 -0.404573 -0.0548563 - -0.182852 -0.400536 -0.0367033 - -0.147821 -0.404276 0.0292996 - -0.148898 -0.433985 0.0271442 - -0.149125 -0.439414 0.0266923 - -0.15656 -0.478509 0.0125144 - -0.178282 -0.583873 -0.0288732 - -0.175884 -0.586498 -0.0243647 - -0.244655 -0.993232 -0.155703 - -0.128096 -0.456781 0.0662502 - -0.116029 -0.449923 0.0890192 - -0.313671 -2.12649 -0.290606 - -0.291537 -2.17632 -0.249106 - -0.207936 -2.17835 -0.0915603 - -0.203476 -2.17995 -0.0831626 - -0.177482 -2.13193 -0.0339707 - -0.136743 -2.20998 0.0424734 - -0.0278514 -0.450638 0.255194 - 0.0821608 -2.23147 0.454922 - 0.143729 -2.18766 0.571139 - 0.146681 -2.1154 0.57701 - 0.0200916 -0.463655 0.345491 - 0.0211598 -0.464092 0.347502 - 0.0272004 -0.449002 0.35895 - 0.0204166 -0.34209 0.346622 - 0.0250724 -0.345904 0.35538 - 0.0261181 -0.347194 0.357345 - 0.0291221 -0.345737 0.363013 - 0.0487883 -0.364106 0.399997 - 0.0501447 -0.358139 0.402578 - 0.0687223 -0.358561 0.437588 - 0.122136 -0.413279 0.538016 - 0.151404 -0.389773 0.593274 - 0.184728 -0.413066 0.655977 - 0.430434 -0.78987 1.11742 - 0.426381 -0.748636 1.10996 - 0.424107 -0.72497 1.10577 - 0.454892 -0.666027 1.16404 - 0.479626 -0.666342 1.21065 - 0.500111 -0.659168 1.24929 - 0.541409 -0.667603 1.32708 - 0.594452 -0.662012 1.42707 - 0.689959 -0.664017 1.60705 - 0.70908 -0.665147 1.64308 - 0.924406 -0.693784 2.04876 - 1.02631 -0.521588 2.24153 - 1.02428 -0.266223 2.2388 - 1.02635 -0.0379511 2.24368 - 1.0264 0.0115488 2.24398 - 1.02326 0.0510108 2.23824 - 1.02989 0.101063 2.25094 - 1.02659 0.120609 2.24481 - 1.02371 0.179825 2.23963 - 1.02616 0.240182 2.24451 - 1.02708 0.290645 2.24646 - 1.02721 0.310863 2.24679 - 1.02655 0.75105 2.24743 - 1.02588 0.761593 2.2462 - 1.02565 0.88491 2.24629 - 1.01093 1.28286 2.22025 - 1.00382 1.28711 2.20688 - 0.966057 1.27826 2.13567 - 0.911983 1.28268 2.03378 - 0.863101 1.27637 1.94163 - 0.765034 1.28345 1.75685 - 0.754927 1.27888 1.73778 - 0.704108 1.2749 1.64199 - 0.479903 1.27626 1.21946 - 0.39978 1.2797 1.06848 - 0.364894 1.28066 1.00274 - 0.361747 1.28275 0.996818 - 0.339872 1.2844 0.9556 - 0.277082 1.28549 0.837272 - 0.217576 1.27843 0.7251 - 0.200232 1.28398 0.692437 - 0.130156 1.16634 0.559871 - 0.0843654 1.16865 0.473585 - 0.0775695 1.25853 0.461161 - 0.0495706 1.16775 0.408008 - 0.0357676 1.2669 0.382418 - 0.00343446 1.16546 0.321051 - -0.0139367 1.26184 0.288724 - -0.0274476 1.18873 0.26295 - -0.0419171 1.15998 0.235559 - -0.0605313 1.26819 0.20094 - -0.0631244 1.26798 0.196053 - -0.0717134 1.20501 0.179597 - -0.118648 1.1637 0.0909686 - -0.121026 1.16295 0.086484 - -0.157167 1.25914 0.0187845 - -0.163385 1.16729 0.00667419 - -0.192268 1.17443 -0.0477278 - -0.252801 1.26555 -0.161418 - -0.269609 1.26065 -0.193114 - -0.301841 1.05295 -0.254746 - -0.298211 0.893316 -0.248584 - -0.300031 0.890892 -0.252025 - -0.297084 0.692989 -0.247316 - -0.299526 0.640342 -0.252142 - -0.215324 -0.399978 -0.10667 - -0.17907 -0.404835 -0.0365897 - -0.177437 -0.407526 -0.0334437 - -0.148044 -0.421064 0.0233344 - -0.162057 -0.504639 -0.0041256 - -0.17572 -0.590527 -0.0309201 - -0.171135 -0.589974 -0.0220517 - -0.232706 -0.911096 -0.142506 - -0.263829 -1.10633 -0.203535 - -0.31544 -1.59686 -0.305469 - -0.107252 -0.441945 0.102121 - -0.107249 -0.448287 0.102097 - -0.315898 -2.11447 -0.308608 - -0.290591 -2.17099 -0.259919 - -0.174407 -2.12599 -0.035065 - -0.0389454 -0.419967 0.234296 - -0.0364199 -0.419999 0.239179 - -0.0329213 -0.432928 0.245888 - 0.0214759 -2.24483 0.343183 - 0.0260583 -2.24728 0.352033 - 0.110126 -2.14533 0.515034 - 0.176591 -2.23781 0.643151 - 0.181262 -2.23775 0.652183 - 0.0212995 -0.460111 0.350613 - 0.0227852 -0.345537 0.353984 - 0.0267345 -0.349736 0.361603 - 0.0510076 -0.358337 0.408501 - 0.090599 -0.417575 0.484798 - 0.102899 -0.417231 0.508583 - 0.12826 -0.419483 0.557612 - 0.129929 -0.416336 0.560854 - 0.130759 -0.41475 0.562466 - 0.14718 -0.417235 0.594207 - 0.417199 -0.819043 1.11458 - 0.414203 -0.80647 1.10884 - 0.416604 -0.741321 1.11376 - 0.472431 -0.664109 1.22205 - 0.481803 -0.66304 1.24018 - 0.514519 -0.663317 1.30344 - 0.59291 -0.666643 1.455 - 0.595473 -0.661963 1.45998 - 0.633319 -0.662864 1.53315 - 0.99116 -0.692578 2.22496 - 0.997061 -0.61149 2.23672 - 0.99659 -0.579748 2.23595 - 0.997501 -0.559381 2.2378 - 1.00349 -0.448623 2.24985 - 1.00436 -0.43874 2.25158 - 0.982082 -0.409329 2.20864 - 0.961465 -0.381489 2.16889 - 0.954215 -0.292003 2.15527 - 0.955314 -0.273165 2.15747 - 0.998398 -0.225288 2.24099 - 1.00175 -0.0279653 2.24833 - 1.0004 0.00164128 2.24585 - 1.00155 0.209535 2.24898 - 0.998737 0.33894 2.2441 - 0.999414 0.379599 2.24559 - 1.00095 0.54487 2.24928 - 1.00093 0.759049 2.25018 - 0.997817 0.778769 2.24424 - 0.99837 1.05523 2.24651 - 0.988947 1.28186 2.22928 - 0.952066 1.28645 2.15798 - 0.920762 1.28321 2.09744 - 0.552112 1.27872 1.38458 - 0.529926 1.27448 1.34167 - 0.475194 1.27969 1.23585 - 0.377807 1.28769 1.04758 - 0.35686 1.28149 1.00705 - 0.353521 1.28275 1.0006 - 0.33871 1.28234 0.971956 - 0.256894 1.28278 0.813755 - 0.246946 1.28123 0.794513 - 0.230207 1.27637 0.762125 - 0.163829 1.20214 0.63345 - 0.155674 1.16928 0.617539 - 0.152712 1.16736 0.611803 - 0.100936 1.16358 0.51167 - 0.057335 1.16919 0.427386 - 0.0427589 1.16738 0.399193 - 0.0254242 1.24902 0.36603 - 0.0171066 1.1786 0.34964 - 0.00246863 1.16845 0.321291 - -0.0170325 1.27205 0.284034 - -0.049175 1.1718 0.221446 - -0.0570263 1.2214 0.20648 - -0.0747605 1.16245 0.171932 - -0.0770895 1.1621 0.167427 - -0.0816308 1.15835 0.158629 - -0.0881927 1.14808 0.145896 - -0.100043 1.19675 0.123193 - -0.117191 1.1981 0.0900408 - -0.122226 1.16613 0.0801671 - -0.183028 1.16371 -0.0374121 - -0.192159 1.17588 -0.0550168 - -0.208985 1.16803 -0.087586 - -0.215527 1.17713 -0.100195 - -0.2356 1.27234 -0.138595 - -0.242353 1.27896 -0.151624 - -0.250173 1.27402 -0.166766 - -0.273022 1.27117 -0.210961 - -0.28768 1.2699 -0.23931 - -0.296473 1.17115 -0.256742 - -0.294146 1.09885 -0.252558 - -0.29509 1.00366 -0.254796 - -0.294534 0.981355 -0.253818 - -0.292623 0.773821 -0.251028 - -0.290428 0.658498 -0.247285 - -0.21779 -0.404758 -0.122955 - -0.209899 -0.407941 -0.10721 - -0.206773 -0.407639 -0.100966 - -0.200654 -0.399869 -0.0887115 - -0.192681 -0.401003 -0.0727933 - -0.1735 -0.394775 -0.0344579 - -0.172756 -0.399813 -0.0329937 - -0.168284 -0.404721 -0.0240845 - -0.164097 -0.40281 -0.0157146 - -0.159704 -0.3999 -0.00692815 - -0.155271 -0.404118 0.00190645 - -0.147905 -0.430594 0.0164979 - -0.171205 -0.549048 -0.0305637 - -0.226917 -0.916586 -0.14347 - -0.274542 -1.23108 -0.239987 - -0.273001 -1.25319 -0.237009 - -0.311372 -1.51278 -0.3148 - -0.309736 -1.52288 -0.311577 - -0.308256 -1.68343 -0.30934 - -0.306627 -2.09623 -0.307929 - -0.288655 -2.16949 -0.272364 - -0.254649 -2.2351 -0.204743 - -0.198159 -2.1468 -0.0915313 - -0.0803431 -2.20653 0.143495 - -0.0391325 -0.420967 0.233774 - 0.110178 -2.13999 0.524288 - 0.194858 -2.24681 0.692926 - 0.0239108 -0.449002 0.359554 - 0.0264694 -0.453531 0.364644 - 0.0230283 -0.387565 0.358066 - 0.0270958 -0.348824 0.366362 - 0.0362224 -0.349716 0.384585 - 0.0389461 -0.354592 0.390003 - 0.0458426 -0.365986 0.403725 - 0.0520906 -0.365443 0.416206 - 0.0568073 -0.358339 0.425658 - 0.0806293 -0.415061 0.47298 - 0.0911717 -0.411437 0.49405 - 0.0999163 -0.419657 0.511478 - 0.109434 -0.4212 0.53048 - 0.110253 -0.41977 0.532121 - 0.111069 -0.418333 0.533758 - 0.124877 -0.414827 0.561348 - 0.133717 -0.418686 0.578987 - 0.142957 -0.411581 0.597471 - 0.141527 -0.397811 0.594677 - 0.142223 -0.389076 0.596106 - 0.14243 -0.382807 0.596548 - 0.401619 -0.78357 1.11239 - 0.402884 -0.771915 1.11497 - 0.425504 -0.662484 1.16063 - 0.565373 -0.661571 1.43997 - 0.632123 -0.671261 1.57324 - 0.708184 -0.67046 1.72514 - 0.779189 -0.670489 1.86695 - 0.966275 -0.577501 2.241 - 0.967174 -0.485106 2.24321 - 0.968118 -0.465115 2.24518 - 0.928074 -0.359062 2.16568 - 0.926644 -0.291332 2.16313 - 0.973176 -0.205703 2.25644 - 0.967991 -0.175058 2.24623 - 0.965801 0.0016282 2.24264 - 0.969149 0.149052 2.24998 - 0.967889 0.367643 2.24844 - 0.968908 0.378107 2.25053 - 0.96926 0.459583 2.25159 - 0.97109 0.532695 2.25557 - 0.966527 0.561437 2.24659 - 0.965403 0.571227 2.24439 - 0.968607 0.646901 2.25113 - 0.96714 0.830928 2.24902 - 0.965423 0.874379 2.24578 - 0.963889 0.90705 2.24287 - 0.968095 0.956971 2.25149 - 0.96838 0.980563 2.25216 - 0.968482 0.992391 2.25242 - 0.966687 1.23537 2.24992 - 0.887942 1.28441 2.09288 - 0.814855 1.27753 1.94688 - 0.801686 1.28174 1.9206 - 0.783783 1.27813 1.88483 - 0.773263 1.28547 1.86385 - 0.732828 1.27893 1.78307 - 0.681548 1.28355 1.68068 - 0.647052 1.28926 1.61181 - 0.533377 1.27097 1.3847 - 0.509945 1.2734 1.33792 - 0.498438 1.27989 1.31497 - 0.449404 1.28132 1.21705 - 0.419061 1.27897 1.15644 - 0.4027 1.27847 1.12376 - 0.388353 1.2827 1.09513 - 0.29283 1.28918 0.904384 - 0.286777 1.27852 0.892248 - 0.258881 1.28399 0.83656 - 0.251627 1.27996 0.822056 - 0.190699 1.2771 0.700361 - 0.130422 1.17198 0.579511 - 0.123913 1.25793 0.566895 - 0.0949519 1.16587 0.508646 - 0.0814721 1.22545 0.481991 - 0.0736138 1.24959 0.466405 - 0.0518816 1.16419 0.422621 - 0.0322479 1.27286 0.383896 - -0.0012933 1.16385 0.316423 - -0.146022 1.18952 0.0274968 - -0.162428 1.18366 -0.0052947 - -0.28638 1.1929 -0.252802 - -0.288428 1.11289 -0.257248 - -0.286235 1.01375 -0.253313 - -0.287172 0.95742 -0.255436 - -0.285142 0.844979 -0.251883 - -0.283798 0.816936 -0.249323 - -0.28459 0.659266 -0.251609 - -0.283352 0.570269 -0.249536 - -0.206033 -0.403359 -0.1085 - -0.18728 -0.405525 -0.0700561 - -0.178966 -0.400465 -0.0529848 - -0.178469 -0.402654 -0.0519755 - -0.166234 -0.402629 -0.0268869 - -0.161592 -0.406505 -0.0173877 - -0.148844 -0.408944 0.00874281 - -0.149316 -0.418832 0.0077288 - -0.170998 -0.602542 -0.0375683 - -0.132903 -0.476025 0.0411241 - -0.300076 -1.60045 -0.306801 - -0.294563 -1.7513 -0.296184 - -0.0968455 -0.427724 0.115281 - -0.0957169 -0.432721 0.117573 - -0.0953922 -0.437127 0.118218 - -0.29896 -2.11425 -0.306857 - -0.273574 -2.15984 -0.255009 - -0.139611 -2.2199 0.0194124 - -0.135362 -2.22093 0.0281196 - -0.105757 -2.23296 0.0887717 - 0.0870019 -2.23005 0.484043 - 0.132283 -2.19554 0.577051 - 0.155823 -2.16722 0.625449 - 0.0190978 -0.459558 0.352882 - 0.0208515 -0.458425 0.356483 - 0.0233941 -0.349736 0.362193 - 0.0337085 -0.353857 0.383324 - 0.0343834 -0.353149 0.384711 - 0.0500313 -0.365443 0.416741 - 0.0510357 -0.358449 0.418833 - 0.0564529 -0.361729 0.429926 - 0.0571421 -0.360794 0.431344 - 0.0675833 -0.381447 0.452659 - 0.0782893 -0.412227 0.474472 - 0.0932182 -0.412063 0.505085 - 0.100565 -0.419628 0.520114 - 0.10216 -0.416874 0.523397 - 0.110384 -0.410957 0.54029 - 0.144026 -0.37803 0.609424 - 0.390081 -0.814989 1.11197 - 0.390886 -0.74017 1.11396 - 0.389002 -0.710639 1.11024 - 0.389374 -0.660589 1.11123 - 0.507706 -0.666004 1.35385 - 0.556496 -0.665987 1.45389 - 0.746176 -0.675043 1.8428 - 0.939937 -0.553833 2.24066 - 0.90093 -0.346934 2.16162 - 0.941167 -0.0666005 2.24541 - 0.945356 0.0897679 2.25471 - 0.942579 0.197377 2.24951 - 0.94037 0.246137 2.2452 - 0.940996 0.275951 2.24662 - 0.941498 0.44643 2.24843 - 0.939474 0.496401 2.24451 - 0.945561 0.635173 2.25762 - 0.94053 0.78233 2.24798 - 0.938603 0.972175 2.24489 - 0.937371 1.2637 2.2437 - 0.934928 1.27342 2.23873 - 0.913552 1.28362 2.19494 - 0.882141 1.27875 2.13051 - 0.765213 1.27642 1.89074 - 0.750996 1.27738 1.86159 - 0.624613 1.28559 1.60247 - 0.509788 1.26717 1.36694 - 0.409477 1.29126 1.16136 - 0.385383 1.27829 1.11189 - 0.327968 1.28263 0.99418 - 0.30422 1.28379 0.945489 - 0.286795 1.28074 0.909745 - 0.283685 1.28139 0.903369 - 0.238449 1.27664 0.810591 - 0.201254 1.28395 0.734355 - 0.180434 1.27969 0.691644 - 0.146866 1.17304 0.622323 - 0.12519 1.17934 0.577906 - 0.0766973 1.25711 0.478824 - 0.054208 1.16236 0.432277 - 0.0392398 1.17826 0.401657 - -0.0335272 1.16591 0.252389 - -0.0424595 1.16898 0.234087 - -0.0623291 1.27098 0.193809 - -0.074224 1.1824 0.169014 - -0.0825316 1.16192 0.151886 - -0.153927 1.24515 0.0058669 - -0.15761 1.2577 -0.00162832 - -0.162318 1.18245 -0.0116256 - -0.163115 1.16761 -0.0133272 - -0.206238 1.20045 -0.101602 - -0.229522 1.27046 -0.149028 - -0.270404 1.26625 -0.232877 - -0.274706 1.27409 -0.241662 - -0.280039 1.25689 -0.252677 - -0.280819 1.07772 -0.255093 - -0.280787 1.02231 -0.255281 - -0.278108 0.878867 -0.250442 - -0.278378 0.871396 -0.25103 - -0.278507 0.685949 -0.25214 - -0.278227 0.638343 -0.251783 - -0.276339 0.611502 -0.248035 - -0.277663 0.563565 -0.250969 - -0.208932 -0.404386 -0.123914 - -0.198758 -0.400877 -0.102474 - -0.185699 -0.398737 -0.0749666 - -0.184816 -0.407052 -0.073148 - -0.16569 -0.405361 -0.0328662 - -0.158392 -0.404047 -0.017494 - -0.15687 -0.406496 -0.0143013 - -0.154625 -0.406427 -0.00957364 - -0.148358 -0.395751 0.00367263 - -0.164729 -0.598927 -0.0317451 - -0.149357 -0.544211 0.00087655 - -0.296527 -1.51082 -0.313515 - -0.293692 -1.51347 -0.307557 - -0.0992095 -0.439815 0.106955 - -0.28419 -2.03733 -0.289991 - -0.276617 -2.15402 -0.274589 - -0.194413 -2.12844 -0.10138 - -0.191553 -2.14582 -0.0954398 - -0.117141 -2.23659 0.0608221 - -0.0313188 -0.434786 0.24993 - 0.0126785 -2.22735 0.334215 - 0.0169201 -2.22985 0.343134 - 0.0535155 -2.20157 0.420322 - 0.0926598 -2.22855 0.502619 - 0.0977794 -2.1744 0.513652 - 0.13255 -2.13902 0.58703 - 0.0166782 -0.46645 0.350846 - 0.027088 -0.433883 0.372917 - 0.0163811 -0.338596 0.350816 - 0.0184316 -0.333564 0.355157 - 0.0382266 -0.352476 0.39675 - 0.0485504 -0.356705 0.418468 - 0.053817 -0.36352 0.429526 - 0.0551711 -0.361653 0.432386 - 0.0791871 -0.40924 0.482733 - 0.0826846 -0.409785 0.490094 - 0.0959002 -0.414823 0.517898 - 0.111348 -0.415691 0.550421 - 0.135487 -0.38488 0.601392 - 0.143558 -0.38227 0.618399 - 0.33588 -0.760253 1.02159 - 0.385824 -0.796003 1.12659 - 0.393104 -0.662147 1.14254 - 0.398799 -0.658274 1.15455 - 0.413571 -0.667637 1.18561 - 0.424705 -0.658088 1.2091 - 0.469778 -0.666867 1.30397 - 0.490422 -0.672971 1.34741 - 0.506761 -0.665373 1.38185 - 0.528203 -0.655399 1.42704 - 0.628416 -0.664805 1.63801 - 0.655038 -0.674798 1.69402 - 0.913348 -0.56085 2.23845 - 0.915242 -0.520963 2.24262 - 0.878347 -0.403579 2.16548 - 0.920851 -0.174203 2.25605 - 0.916991 -0.105278 2.24824 - 0.916732 -0.0955237 2.24775 - 0.917825 0.275338 2.25178 - 0.912604 0.332999 2.24105 - 0.911114 0.412002 2.23828 - 0.915533 0.566783 2.24831 - 0.914445 0.576486 2.24606 - 0.91562 0.608429 2.24869 - 0.915374 0.650259 2.24836 - 0.914348 0.789064 2.24685 - 0.917481 0.93746 2.25414 - 0.910883 1.03533 2.2407 - 0.914662 1.06326 2.24879 - 0.914841 1.21074 2.24985 - 0.913605 1.23448 2.24736 - 0.912263 1.25828 2.24465 - 0.772024 1.27913 1.94945 - 0.760832 1.2854 1.92592 - 0.680563 1.2796 1.75687 - 0.658403 1.2858 1.71024 - 0.60751 1.29155 1.60311 - 0.558811 1.29277 1.50057 - 0.50389 1.28138 1.38488 - 0.496074 1.28524 1.36844 - 0.48355 1.2773 1.34203 - 0.418489 1.27624 1.20503 - 0.374576 1.27351 1.11255 - 0.363818 1.2748 1.08991 - 0.360916 1.27728 1.08381 - 0.342723 1.27689 1.0455 - 0.336949 1.28133 1.03336 - 0.314412 1.28739 0.985936 - 0.306613 1.28355 0.969497 - 0.285735 1.27935 0.925515 - 0.276591 1.28139 0.906271 - 0.259421 1.28885 0.870154 - 0.235476 1.27742 0.81968 - 0.204844 1.28577 0.75522 - 0.189452 1.27948 0.722781 - 0.177937 1.27748 0.698525 - 0.135799 1.17663 0.609329 - 0.129207 1.16501 0.595394 - 0.126887 1.16577 0.590513 - 0.124851 1.22294 0.586494 - 0.0812375 1.18163 0.494467 - 0.0368638 1.24511 0.401328 - 0.0357408 1.26668 0.399064 - 0.024484 1.23483 0.375213 --0.00531505 1.1702 0.312167 - -0.0144123 1.27257 0.293489 - -0.0513659 1.1697 0.215199 - -0.105212 1.22767 0.10209 - -0.116366 1.25652 0.0787382 - -0.118225 1.17799 0.0744584 - -0.130398 1.16003 0.0487427 - -0.153846 1.24205 -0.00024724 - -0.186387 1.16717 -0.0691161 - -0.222294 1.28368 -0.14418 - -0.242829 1.26042 -0.187527 - -0.261771 1.27543 -0.227341 - -0.272606 1.25835 -0.250235 - -0.277522 1.24019 -0.260671 - -0.276987 1.22318 -0.259623 - -0.27353 1.05575 -0.253126 - -0.274005 1.01439 -0.254318 - -0.27569 1.01112 -0.257882 - -0.27439 0.946167 -0.255448 - -0.271851 0.8489 -0.250554 - -0.269605 0.744634 -0.246312 - -0.271191 0.610754 -0.250274 - -0.271666 0.575746 -0.251439 - -0.206945 -0.404758 -0.129606 - -0.2062 -0.406518 -0.128001 - -0.18498 -0.401737 -0.0820624 - -0.175339 -0.406686 -0.0612249 - -0.168255 -0.403478 -0.04588 - -0.156612 -0.406505 -0.0207023 - -0.165047 -0.613251 -0.0399398 - -0.286825 -1.60776 -0.308186 - -0.101645 -0.440056 0.098078 - -0.0948948 -0.429629 0.112733 - -0.0903098 -0.420465 0.122698 - -0.163697 -2.20951 -0.0446286 - -0.119453 -2.23274 0.0509973 - -0.0395547 -0.423967 0.232506 - -0.0372221 -0.425999 0.237543 - -0.0317351 -0.42779 0.249408 - -0.0288764 -0.452553 0.255475 - 0.033732 -2.2843 0.382216 - 0.0553148 -2.19768 0.42933 - 0.0861118 -2.23874 0.495773 - 0.0980519 -2.16315 0.52197 - 0.172003 -2.25411 0.681553 - 0.0190719 -0.452464 0.359227 - 0.0191313 -0.364858 0.359773 - 0.0179023 -0.347774 0.357195 - 0.0198061 -0.341702 0.361344 - 0.0256195 -0.341301 0.373925 - 0.0354544 -0.355796 0.395137 - 0.0557967 -0.36574 0.439106 - 0.0586864 -0.369736 0.44534 - 0.0750951 -0.416119 0.480624 - 0.0757309 -0.40674 0.482045 - 0.0851457 -0.424212 0.502334 - 0.105825 -0.417149 0.547113 - 0.11337 -0.416399 0.563443 - 0.129552 -0.393958 0.598565 - 0.126058 -0.382413 0.591061 - 0.140072 -0.380427 0.621393 - 0.389907 -0.814838 1.15992 - 0.384364 -0.783006 1.14808 - 0.386984 -0.699791 1.15414 - 0.391659 -0.668723 1.16441 - 0.392871 -0.664259 1.16705 - 0.481382 -0.662695 1.35858 - 0.550189 -0.666274 1.50745 - 0.600705 -0.667454 1.61675 - 0.662604 -0.680734 1.75062 - 0.726809 -0.679129 1.88956 - 0.797044 -0.692553 2.04147 - 0.835 -0.693703 2.1236 - 0.859054 -0.69219 2.17565 - 0.876703 -0.695336 2.21383 - 0.885132 -0.638931 2.23233 - 0.848258 -0.361212 2.15387 - 0.85485 -0.297398 2.16844 - 0.868095 -0.215839 2.19749 - 0.893414 -0.0565257 2.25303 - 0.890673 0.00160859 2.24738 - 0.890532 0.0305887 2.24721 - 0.888934 0.0884484 2.24403 - 0.891253 0.254166 2.24984 - 0.889901 0.512922 2.24814 - 0.892243 0.544962 2.25337 - 0.888372 0.677861 2.24562 - 0.891204 0.798418 2.25233 - 0.890144 0.94288 2.25072 - 0.890198 0.977464 2.251 - 0.885243 1.2761 2.24171 - 0.821173 1.28548 2.10311 - 0.751503 1.28738 1.95237 - 0.488723 1.27428 1.3837 - 0.482562 1.28165 1.3704 - 0.3495 1.28135 1.08248 - 0.323712 1.27688 1.02666 - 0.300875 1.27917 0.977254 - 0.284092 1.27694 0.940927 - 0.276612 1.28524 0.924781 - 0.19553 1.28093 0.749315 - 0.187491 1.28266 0.731928 - 0.0953852 1.16912 0.532086 - 0.091095 1.17189 0.522816 - 0.0768673 1.26548 0.492476 - 0.0500717 1.16629 0.434022 - 0.0478617 1.16624 0.42924 - -0.0685294 1.26122 0.177844 - -0.0699566 1.22697 0.174592 - -0.0812053 1.16491 0.149956 - -0.113167 1.26719 0.0812838 - -0.122081 1.16071 0.0614878 - -0.126399 1.15995 0.052141 - -0.158145 1.23653 -0.0161868 - -0.171982 1.16854 -0.0464513 - -0.192106 1.18077 -0.0899376 - -0.208722 1.2691 -0.12547 - -0.23162 1.26649 -0.17503 - -0.26636 1.26622 -0.250201 - -0.268336 1.26202 -0.254497 - -0.268281 1.13776 -0.25497 - -0.268725 1.04539 -0.256373 - -0.267366 1.01764 -0.253563 - -0.264811 0.985642 -0.248187 - -0.266614 0.916379 -0.252419 - -0.263971 0.806812 -0.247223 - -0.264492 0.723884 -0.248745 - -0.264482 0.679693 -0.248935 - -0.200224 -0.400832 -0.125016 - -0.19805 -0.405991 -0.120204 - -0.191494 -0.403248 -0.105604 - -0.162758 -0.402202 -0.0416572 - -0.150322 -0.397055 -0.0139598 - -0.148908 -0.414995 -0.0109025 - -0.141626 -0.43186 0.00521821 - -0.153517 -0.582624 -0.0219756 - -0.152472 -0.583856 -0.0196553 - -0.112046 -0.439898 0.0709985 - -0.0974715 -0.438231 0.103436 - -0.0966859 -0.438865 0.105181 - -0.089976 -0.426211 0.120173 - -0.0884473 -0.427312 0.123569 - -0.267289 -2.16466 -0.282848 - -0.248229 -2.18043 -0.240515 - -0.241855 -2.20049 -0.226431 - -0.19178 -2.13171 -0.114673 - -0.168628 -2.20376 -0.0635081 - -0.137133 -2.21684 0.0065069 - -0.129969 -2.23784 0.0223447 - -0.125964 -2.23884 0.0312522 - -0.113736 -2.2356 0.0584756 - -0.0931759 -2.21734 0.104314 - -0.0404024 -0.415941 0.23053 - 0.0441594 -2.279 0.409598 - 0.0965088 -2.18986 0.526516 - 0.116013 -2.12656 0.570223 - 0.119812 -2.12494 0.578685 - 0.162401 -2.24841 0.672847 - 0.0165601 -0.458425 0.35707 - 0.0224332 -0.448792 0.370185 - 0.0264262 -0.445496 0.379086 - 0.0199886 -0.370211 0.365129 - 0.0201407 -0.339885 0.365615 - 0.0259901 -0.340212 0.378629 - 0.031442 -0.352788 0.390699 - 0.0866622 -0.416423 0.513259 - 0.0903521 -0.420994 0.521447 - 0.0911031 -0.41586 0.523143 - 0.0978592 -0.422133 0.538146 - 0.109054 -0.421807 0.563057 - 0.11319 -0.42237 0.572257 - 0.116177 -0.415888 0.578935 - 0.125736 -0.377616 0.600392 - 0.126407 -0.375874 0.601893 - 0.133631 -0.378911 0.617952 - 0.299101 -0.724309 0.984456 - 0.385197 -0.85482 1.17539 - 0.387223 -0.821589 1.18006 - 0.38605 -0.701629 1.17804 - 0.392843 -0.6671 1.19332 - 0.395197 -0.657922 1.1986 - 0.428744 -0.661636 1.27323 - 0.433475 -0.661665 1.28376 - 0.474063 -0.66884 1.37403 - 0.563591 -0.674232 1.57322 - 0.742805 -0.690865 1.9719 - 0.765346 -0.69156 2.02206 - 0.858844 -0.676898 2.23017 - 0.861439 -0.626859 2.23619 - 0.860844 -0.60584 2.23497 - 0.861849 -0.50477 2.2377 - 0.846631 -0.41764 2.20426 - 0.824196 -0.340853 2.15472 - 0.863496 0.0592139 2.24412 - 0.863364 0.0688135 2.24387 - 0.863961 0.165231 2.24567 - 0.86502 0.204186 2.24821 - 0.862363 0.300831 2.24277 - 0.8624 0.399301 2.24333 - 0.863718 0.419786 2.24637 - 0.86769 0.68899 2.25652 - 0.863863 0.717902 2.24814 - 0.862255 0.824585 2.24509 - 0.863055 0.847347 2.24698 - 0.864142 1.01894 2.25023 - 0.865628 1.03237 2.25361 - 0.864747 1.06686 2.25181 - 0.864291 1.2383 2.25164 - 0.567329 1.27983 1.59107 - 0.52519 1.27782 1.49729 - 0.446547 1.27634 1.3223 - 0.380277 1.28131 1.17487 - 0.369358 1.27058 1.15052 - 0.361243 1.2796 1.1325 - 0.358449 1.28227 1.1263 - 0.353449 1.27771 1.11515 - 0.313819 1.27192 1.02694 - 0.242237 1.2866 0.867737 - 0.232294 1.28133 0.845588 - 0.181611 1.27989 0.732806 - 0.130023 1.16077 0.617436 - 0.127721 1.17757 0.612397 - 0.117489 1.17126 0.589599 - 0.0812866 1.21828 0.509273 - 0.0787889 1.26592 0.503948 - 0.0193989 1.19711 0.371464 - 0.0053368 1.16867 0.340035 --0.00103589 1.16705 0.325847 - -0.0113164 1.27599 0.303504 - -0.0233941 1.22328 0.276372 - -0.0282018 1.17362 0.265433 - -0.053564 1.18657 0.209062 - -0.0637896 1.27274 0.18673 - -0.0660654 1.27249 0.181664 - -0.0763604 1.16771 0.158246 - -0.113904 1.26543 0.0751832 - -0.211913 1.28267 -0.142811 - -0.23383 1.27466 -0.19162 - -0.243507 1.26996 -0.213174 - -0.258966 1.26764 -0.247583 - -0.262231 0.996183 -0.256173 - -0.258913 0.784044 -0.249825 - -0.259377 0.710395 -0.251217 - -0.256259 0.657837 -0.244534 - -0.257887 0.551345 -0.248677 - -0.199232 -0.40405 -0.133252 - -0.188579 -0.404712 -0.108864 - -0.172892 -0.399415 -0.0729192 - -0.171077 -0.408346 -0.0688084 - -0.162134 -0.405629 -0.0483184 - -0.156199 -0.400535 -0.0347041 - -0.153155 -0.401126 -0.0277372 - -0.147463 -0.410944 -0.0147552 - -0.144057 -0.425912 -0.00702982 - -0.140648 -0.42877 0.00075969 - -0.150564 -0.574203 -0.0226702 - -0.104538 -0.44785 0.0833439 - -0.100317 -0.436819 0.0930646 - -0.25777 -2.16324 -0.276074 - -0.253985 -2.16566 -0.267421 - -0.244435 -2.1921 -0.245687 - -0.157802 -2.20456 -0.0473896 - -0.141721 -2.1957 -0.0105264 - -0.0916329 -2.20437 0.104115 - -0.0412909 -0.423905 0.228277 - -0.0316023 -0.427727 0.250441 - 0.0491734 -2.25335 0.426266 - 0.0868989 -2.21535 0.512834 - 0.0976295 -2.19735 0.537493 - 0.189347 -2.23515 0.747305 - 0.0202333 -0.367409 0.369428 - 0.0214897 -0.344438 0.372419 - 0.0223618 -0.341301 0.374432 - 0.0469662 -0.362656 0.43066 - 0.0488537 -0.359852 0.434996 - 0.0768774 -0.415975 0.49888 - 0.0790152 -0.415917 0.503775 - 0.0823672 -0.41238 0.511468 - 0.0874029 -0.414264 0.522988 - 0.108329 -0.415502 0.570894 - 0.114355 -0.414073 0.584699 - 0.118063 -0.402547 0.593248 - 0.116621 -0.372056 0.590097 - 0.131791 -0.384285 0.624771 - 0.389892 -0.893341 1.21319 - 0.389161 -0.860765 1.21167 - 0.446812 -0.662404 1.34467 - 0.467931 -0.669957 1.39298 - 0.725343 -0.691889 1.98226 - 0.816401 -0.691265 2.19075 - 0.834384 -0.695336 2.2319 - 0.838392 -0.513651 2.24199 - 0.837702 -0.5032 2.24046 - 0.836295 -0.472418 2.23739 - 0.84023 -0.454563 2.24649 - 0.835069 -0.432101 2.23479 - 0.810321 -0.29629 2.1788 - 0.811687 -0.277914 2.18202 - 0.841796 -0.181077 2.25144 - 0.843158 -0.162031 2.25466 - 0.842616 -0.152284 2.25347 - 0.841531 -0.0463735 2.25151 - 0.836447 -0.00794995 2.24006 - 0.842702 0.030423 2.25458 - 0.840357 0.12632 2.24969 - 0.838796 0.329434 2.24713 - 0.839958 0.379075 2.25004 - 0.837464 0.588851 2.24537 - 0.836155 0.681262 2.24284 - 0.834939 0.690804 2.2401 - 0.837119 0.756258 2.24542 - 0.834409 0.77535 2.23931 - 0.837415 1.24348 2.24853 - 0.58929 1.27677 1.68058 - 0.55459 1.28375 1.60117 - 0.530626 1.2762 1.54626 - 0.492728 1.26685 1.45944 - 0.46487 1.27641 1.3957 - 0.424348 1.28142 1.30295 - 0.412031 1.28079 1.27474 - 0.391702 1.27843 1.22818 - 0.345464 1.27112 1.12228 - 0.332502 1.27405 1.09261 - 0.297885 1.28063 1.01339 - 0.26005 1.27834 0.926746 - 0.232363 1.2725 0.863324 - 0.20968 1.28573 0.811454 - 0.18959 1.28053 0.76543 - 0.187347 1.28303 0.760307 - 0.111641 1.17388 0.58642 - 0.0935039 1.17202 0.544884 - 0.0818487 1.25617 0.518618 - 0.0351563 1.20215 0.411439 - 0.0325544 1.27084 0.405825 - 0.0105189 1.17507 0.354893 - -0.028723 1.16862 0.265011 - -0.0429821 1.16098 0.232324 - -0.0613004 1.27797 0.190967 - -0.0943479 1.17033 0.114762 - -0.0963902 1.16973 0.110083 - -0.137788 1.16293 0.0152633 - -0.152487 1.2297 -0.0180604 - -0.163755 1.16506 -0.044183 - -0.174785 1.16577 -0.0694325 - -0.201866 1.27292 -0.130904 - -0.215669 1.28372 -0.162454 - -0.220742 1.26658 -0.174154 - -0.22654 1.272 -0.187403 - -0.228756 1.26997 -0.192487 - -0.238465 1.26717 -0.214732 - -0.255603 1.23214 -0.254145 - -0.252754 1.05065 -0.248531 - -0.252886 0.947143 -0.249348 - -0.255484 0.902844 -0.255518 - -0.253727 0.886779 -0.251576 - -0.252782 0.841112 -0.249641 - -0.252838 0.662514 -0.250663 - -0.251043 0.628538 -0.246721 - -0.2505 0.584471 -0.245698 - -0.252253 0.579113 -0.249738 - -0.177474 -0.400892 -0.0928166 - -0.160923 -0.40369 -0.0538217 - -0.156509 -0.403531 -0.0434173 - -0.155125 -0.406165 -0.040167 - -0.145565 -0.417142 -0.0176907 - -0.142425 -0.437598 -0.0103959 - -0.13442 -0.428861 0.00851527 - -0.133159 -0.436425 0.0114505 - -0.119458 -0.454223 0.0436507 - -0.106849 -0.449519 0.0733947 - -0.0989996 -0.443154 0.0919273 - -0.0879859 -0.449002 0.117856 - -0.264909 -2.09473 -0.30757 - -0.175062 -2.15726 -0.0961259 - -0.13188 -2.19995 0.00543325 - -0.106671 -2.2424 0.0646335 - -0.0406438 -0.42194 0.229577 - -0.0399247 -0.421967 0.231272 - -0.0341504 -0.423891 0.244872 - -0.0334282 -0.423846 0.246574 - 0.0749776 -2.19312 0.493021 - 0.0882626 -2.22589 0.524165 - 0.16106 -2.25097 0.695617 - 0.164891 -2.24876 0.704656 - 0.193087 -2.24664 0.771125 - 0.0205311 -0.445603 0.373642 - 0.0260515 -0.347191 0.387157 - 0.083741 -0.416425 0.522774 - 0.112813 -0.416814 0.591292 - 0.115934 -0.386615 0.598803 - 0.113775 -0.377919 0.59376 - 0.385597 -0.859527 1.23196 - 0.38633 -0.845745 1.23376 - 0.384723 -0.720899 1.23061 - 0.385507 -0.708704 1.23252 - 0.392495 -0.66686 1.24921 - 0.404047 -0.658114 1.27648 - 0.43246 -0.665738 1.34341 - 0.456344 -0.663978 1.39971 - 0.667705 -0.682469 1.89778 - 0.707497 -0.692572 1.99152 - 0.813864 -0.442008 2.2435 - 0.807067 -0.399346 2.2277 - 0.796867 -0.356105 2.20388 - 0.796955 -0.251504 2.20463 - 0.811902 -0.188853 2.24018 - 0.812478 -0.16985 2.24163 - 0.812719 0.0206076 2.24317 - 0.811173 0.0870889 2.23987 - 0.813332 0.115939 2.24511 - 0.816926 0.193335 2.25397 - 0.811959 0.455093 2.24361 - 0.811921 0.465018 2.24357 - 0.813597 0.526138 2.24783 - 0.812718 0.586516 2.24607 - 0.815161 0.608755 2.25194 - 0.813739 0.743791 2.24928 - 0.81569 0.777692 2.25405 - 0.810125 0.804918 2.24108 - 0.812756 0.9745 2.24814 - 0.730025 1.28406 2.05474 - 0.617427 1.27226 1.78929 - 0.542518 1.2779 1.61276 - 0.468098 1.27162 1.43733 - 0.457677 1.27867 1.4128 - 0.425033 1.28147 1.33587 - 0.419409 1.27711 1.3226 - 0.388218 1.27729 1.24908 - 0.291492 1.27609 1.0211 - 0.283931 1.27092 1.00325 - 0.274159 1.28102 0.98027 - 0.256364 1.28193 0.938334 - 0.238962 1.28222 0.89732 - 0.221224 1.27841 0.855491 - 0.204785 1.2785 0.816748 - 0.19705 1.28031 0.798524 - 0.171198 1.28266 0.737604 - 0.15242 1.27628 0.693314 - 0.10683 1.16627 0.585298 - 0.102843 1.16952 0.575918 - 0.0999357 1.16347 0.569034 - 0.0276458 1.25678 0.399128 - 0.00857376 1.16214 0.353692 --0.00863885 1.19215 0.313276 - -0.0311933 1.16774 0.259992 - -0.0431094 1.16098 0.231872 - -0.0450879 1.16095 0.227208 - -0.0583254 1.24721 0.19645 - -0.0701334 1.20968 0.168427 - -0.0808238 1.16149 0.142983 - -0.116649 1.18623 0.0586721 - -0.175354 1.15992 -0.079827 - -0.210485 1.2752 -0.16204 - -0.225227 1.2756 -0.196782 - -0.227395 1.27353 -0.201903 - -0.252334 1.24222 -0.260845 - -0.246477 1.16667 -0.247427 - -0.24779 1.14751 -0.250619 - -0.249573 1.14428 -0.254837 - -0.246435 0.930896 -0.248533 - -0.249527 0.856138 -0.256205 - -0.247481 0.823831 -0.251548 - -0.244787 0.658574 -0.246045 - -0.245657 0.655499 -0.248112 - -0.24401 0.565047 -0.244692 - -0.186992 -0.398277 -0.125645 - -0.165816 -0.400118 -0.0742636 - -0.151731 -0.400042 -0.0400808 - -0.133697 -0.45871 0.00337553 - -0.125222 -0.450124 0.023987 - -0.116081 -0.450579 0.0461695 - -0.112017 -0.447666 0.0560476 - -0.0936373 -0.430959 0.100738 - -0.258316 -2.12041 -0.307773 - -0.23389 -2.22747 -0.249059 - -0.147373 -2.18309 -0.0388665 - -0.041455 -0.423905 0.227412 - -0.0358236 -0.422959 0.241083 - -0.0329981 -0.423792 0.247935 - 0.0378284 -2.26904 0.410131 - 0.0513669 -2.22757 0.443204 - 0.0571094 -2.18774 0.457349 - 0.0604267 -2.17971 0.465441 - 0.148706 -2.25623 0.679275 - 0.178654 -2.23903 0.752045 - 0.196208 -2.25499 0.794562 - 0.0265576 -0.4038 0.39257 - 0.0219239 -0.357772 0.381567 - 0.0378459 -0.359323 0.420198 - 0.04039 -0.360152 0.426368 - 0.0433455 -0.36259 0.433528 - 0.0595522 -0.40942 0.472612 - 0.0614604 -0.41337 0.477222 - 0.104211 -0.410549 0.580985 - 0.114035 -0.375189 0.605012 - 0.115215 -0.374806 0.607875 - 0.389758 -0.947048 1.27113 - 0.386796 -0.837518 1.26452 - 0.387888 -0.780399 1.26747 - 0.385573 -0.692856 1.26231 - 0.413322 -0.661709 1.32982 - 0.434445 -0.664586 1.38106 - 0.489325 -0.665867 1.51424 - 0.520398 -0.666176 1.58965 - 0.787676 -0.629719 2.23847 - 0.788812 -0.351895 2.24268 - 0.793838 -0.324776 2.25502 - 0.788361 -0.264829 2.24205 - 0.791128 -0.0935077 2.24966 - 0.78785 0.153367 2.243 - 0.78821 0.220288 2.24423 - 0.789035 0.444176 2.24741 - 0.78813 0.604468 2.24605 - 0.787853 0.71841 2.24598 - 0.788633 0.793698 2.24826 - 0.78274 1.276 2.23649 - 0.64791 1.28027 1.90931 - 0.583543 1.27154 1.75306 - 0.578967 1.28518 1.74203 - 0.496239 1.28323 1.54125 - 0.478395 1.2736 1.4979 - 0.439104 1.28476 1.4026 - 0.410238 1.28372 1.33255 - 0.397435 1.28053 1.30146 - 0.381615 1.27853 1.26306 - 0.291004 1.27061 1.04312 - 0.262501 1.27774 0.973986 - 0.251795 1.28202 0.948028 - 0.153267 1.28213 0.70892 - 0.143499 1.28242 0.685217 - 0.113938 1.16719 0.612872 - 0.111749 1.16706 0.607558 - 0.0944731 1.16599 0.565629 - 0.0823139 1.25689 0.536598 - 0.0527233 1.16124 0.464285 - 0.0468462 1.16338 0.450034 - 0.0390902 1.16722 0.431232 - 0.0136874 1.17627 0.369631 --0.00410476 1.17602 0.326452 - -0.0698219 1.21867 0.167193 - -0.0743469 1.16672 0.155939 - -0.0988582 1.18633 0.0965582 - -0.12938 1.16206 0.0223602 - -0.135487 1.16284 0.00754386 - -0.137666 1.16467 0.0022658 - -0.172669 1.16375 -0.0826837 - -0.217176 1.26637 -0.190156 - -0.243327 1.07586 -0.254619 - -0.243591 1.04298 -0.255432 - -0.243384 1.00938 -0.255106 - -0.240404 0.71574 -0.249415 - -0.240262 0.665566 -0.249335 - -0.2406 0.544876 -0.250788 - -0.181621 -0.404081 -0.123379 - -0.178168 -0.397778 -0.114708 - -0.163579 -0.399415 -0.0782198 - -0.161332 -0.399269 -0.0725983 - -0.146793 -0.399402 -0.036226 - -0.122807 -0.448341 0.0235154 - -0.114811 -0.448772 0.043516 - -0.0969249 -0.429806 0.0883634 - -0.0900093 -0.43725 0.105624 - -0.214052 -2.23137 -0.214359 - -0.132449 -2.15103 -0.00978079 - -0.0840985 -2.192 0.110956 - -0.0746805 -2.27245 0.134083 - -0.0374185 -0.421994 0.237271 - -0.0315858 -0.443644 0.251746 - -0.0297109 -0.465446 0.256319 - 0.0359447 -2.27302 0.410828 - 0.0433012 -2.27127 0.429241 - 0.0468264 -2.26635 0.438087 - 0.0613519 -2.1786 0.474897 - 0.100263 -2.11276 0.572594 - 0.102882 -2.09934 0.579218 - 0.10967 -2.09601 0.596219 - 0.147645 -2.25607 0.690357 - 0.159947 -2.26503 0.721085 - 0.191095 -2.26465 0.79901 - 0.00961199 -0.440569 0.354826 - 0.010324 -0.440003 0.35661 - 0.0145609 -0.44276 0.367195 - 0.0163268 -0.450693 0.37157 - 0.0214352 -0.45235 0.38434 - 0.0236912 -0.444797 0.390025 - 0.0237421 -0.439392 0.390181 - 0.0265239 -0.420238 0.397243 - 0.0258152 -0.391627 0.395625 - 0.0234949 -0.344846 0.390072 - 0.0273652 -0.339596 0.399783 - 0.0322012 -0.353098 0.411808 - 0.0364514 -0.36282 0.422388 - 0.0609311 -0.410754 0.48337 - 0.0689384 -0.415543 0.503376 - 0.0805138 -0.416277 0.53233 - 0.0936817 -0.411856 0.565296 - 0.101639 -0.414248 0.585189 - 0.102305 -0.4126 0.586865 - 0.104923 -0.392007 0.593524 - 0.104685 -0.381295 0.592987 - 0.386722 -0.97399 1.29536 - 0.388286 -0.968998 1.2993 - 0.388522 -0.952569 1.29998 - 0.390241 -0.898643 1.30457 - 0.387495 -0.822959 1.29811 - 0.386611 -0.748137 1.2963 - 0.388304 -0.681741 1.30089 - 0.389395 -0.676727 1.30365 - 0.423768 -0.66695 1.38969 - 0.49157 -0.663741 1.55932 - 0.588154 -0.671335 1.80091 - 0.710357 -0.69232 2.1065 - 0.76354 -0.576891 2.24017 - 0.761441 -0.456256 2.23557 - 0.765767 -0.439029 2.24649 - 0.76276 -0.340241 2.2395 - 0.763796 -0.321393 2.24219 - 0.765836 -0.254892 2.24765 - 0.761752 -0.215541 2.23765 - 0.763844 -0.0267413 2.2439 - 0.764998 0.374143 2.24895 - 0.764568 0.413046 2.24808 - 0.761713 0.530182 2.24157 - 0.763585 0.581844 2.24653 - 0.762692 0.694222 2.2449 - 0.761517 1.02149 2.24372 - 0.763086 1.05848 2.24785 - 0.761832 1.22623 2.24562 - 0.707697 1.28776 2.11052 - 0.604245 1.27731 1.85166 - 0.5652 1.27868 1.75399 - 0.553202 1.27607 1.72396 - 0.527222 1.28733 1.65903 - 0.451642 1.27335 1.46987 - 0.447705 1.27426 1.46003 - 0.409489 1.28189 1.36447 - 0.340447 1.27216 1.19169 - 0.321402 1.27563 1.14407 - 0.303209 1.27973 1.09858 - 0.29962 1.27808 1.08959 - 0.287272 1.2783 1.0587 - 0.252812 1.2829 0.972519 - 0.187422 1.28034 0.808921 - 0.175912 1.28711 0.780164 - 0.15182 1.27485 0.719828 - 0.119107 1.20596 0.637619 - 0.113614 1.18049 0.62374 - 0.0966933 1.16314 0.581316 - 0.0861939 1.16138 0.555041 - -0.0377058 1.16296 0.245092 - -0.0710206 1.21034 0.162005 - -0.0850631 1.16602 0.126636 - -0.0888362 1.16494 0.117191 - -0.121354 1.16107 0.035823 - -0.155844 1.23399 -0.0500683 - -0.156801 1.17957 -0.0527553 - -0.171444 1.16319 -0.0894756 - -0.219882 1.26676 -0.210094 - -0.238608 1.24966 -0.257033 - -0.236192 1.20555 -0.251225 - -0.236472 1.19318 -0.251994 - -0.238343 1.16345 -0.256834 - -0.237371 1.08266 -0.254838 - -0.236798 0.991165 -0.253897 - -0.235911 0.976524 -0.251757 - -0.236678 0.86906 -0.254254 - -0.234965 0.747504 -0.250625 - -0.23354 0.721921 -0.247197 - -0.232284 0.564377 -0.244905 - -0.17113 -0.397534 -0.107198 - -0.171955 -0.403558 -0.109359 - -0.164224 -0.397223 -0.0893946 - -0.162324 -0.401743 -0.0845226 - -0.157332 -0.406686 -0.0716812 - -0.151642 -0.401324 -0.0569852 - -0.147987 -0.399016 -0.0475507 - -0.147354 -0.400335 -0.0459258 - -0.146463 -0.415742 -0.0437137 - -0.146384 -0.423237 -0.0435513 - -0.137223 -0.417505 -0.0199051 - -0.134988 -0.569096 -0.0149833 - -0.115844 -0.466032 0.0349362 - -0.111158 -0.453264 0.0470858 - -0.104109 -0.434488 0.0653602 - -0.10351 -0.447033 0.0668332 - -0.101963 -0.447658 0.0708171 - -0.0983756 -0.433301 0.0801449 - -0.0856561 -0.435789 0.112918 - -0.213283 -2.23119 -0.225996 - -0.172717 -2.16685 -0.121073 - -0.136796 -2.14668 -0.0283668 - -0.124231 -2.17709 0.0038531 - -0.105078 -2.23361 0.052913 - -0.0936292 -2.20105 0.0826044 - -0.0901539 -2.20173 0.0915591 - -0.0444931 -0.441671 0.218992 - -0.0409102 -0.418941 0.228354 - 0.0181469 -2.21813 0.370637 - 0.061812 -2.16951 0.483463 - 0.116835 -2.15338 0.625387 - 0.125387 -2.22115 0.647055 - 0.146069 -2.24999 0.700207 - 0.017732 -0.45536 0.379315 - 0.0270994 -0.435939 0.40357 - 0.031526 -0.352303 0.415442 - 0.0404099 -0.362423 0.438287 - 0.0567474 -0.412227 0.480125 - 0.0667226 -0.406846 0.505868 - 0.0846122 -0.415601 0.551934 - 0.0985548 -0.4126 0.587891 - 0.101988 -0.381012 0.596915 - 0.254282 -0.726088 0.987578 - 0.365911 -0.976339 1.27394 - 0.390677 -0.956964 1.33789 - 0.387165 -0.867587 1.32933 - 0.388228 -0.861864 1.3321 - 0.389958 -0.674986 1.3376 - 0.466614 -0.664125 1.53525 - 0.736422 -0.502684 2.23163 - 0.73719 -0.493334 2.23367 - 0.744779 -0.302797 2.25428 - 0.740783 -0.25349 2.24425 - 0.741053 -0.139769 2.24558 - 0.741429 -0.120945 2.24665 - 0.740953 0.0580571 2.24641 - 0.741666 0.105297 2.24851 - 0.739244 0.133246 2.24242 - 0.739112 0.218371 2.24255 - 0.739076 0.237369 2.24257 - 0.738192 0.371252 2.24103 - 0.741644 0.402123 2.2501 - 0.740984 0.411548 2.24845 - 0.73962 0.430374 2.24504 - 0.742219 0.491078 2.25207 - 0.739944 0.569583 2.24664 - 0.740072 0.630622 2.24731 - 0.739384 0.660864 2.2457 - 0.73861 0.680858 2.24382 - 0.737668 0.711191 2.24156 - 0.738442 0.753918 2.24379 - 0.739395 0.776071 2.24637 - 0.73877 0.950436 2.24572 - 0.739403 0.985218 2.24755 - 0.738208 1.01808 2.24465 - 0.738848 1.11283 2.24682 - 0.736132 1.16917 2.24013 - 0.735929 1.24306 2.24002 - 0.666183 1.28497 2.06046 - 0.540918 1.28293 1.73755 - 0.508093 1.27704 1.65291 - 0.419724 1.26604 1.42506 - 0.316167 1.27926 1.15819 - 0.306384 1.27851 1.13297 - 0.243985 1.2778 0.972117 - 0.235495 1.27688 0.950225 - 0.219397 1.27733 0.908732 - 0.163927 1.27846 0.765753 - 0.156998 1.28027 0.747903 - 0.144158 1.27339 0.714766 - 0.0962268 1.15606 0.590564 - 0.0926749 1.16029 0.581432 - 0.0871615 1.16504 0.567246 - 0.0816265 1.16959 0.553003 - 0.0356853 1.18297 0.434654 - 0.028524 1.26425 0.416643 - 0.0122556 1.17166 0.374196 --0.00645672 1.17103 0.325957 - -0.0199241 1.26159 0.291743 - -0.0691686 1.23763 0.164672 - -0.0717595 1.18903 0.157725 - -0.0857845 1.16151 0.12142 - -0.095458 1.16946 0.0965284 - -0.116647 1.17571 0.0419449 - -0.134622 1.15965 -0.0044793 - -0.152199 1.20259 -0.0495505 - -0.155292 1.1724 -0.0576909 - -0.160825 1.16818 -0.0719762 - -0.177838 1.21164 -0.11559 - -0.231187 1.26348 -0.252822 - -0.23172 1.23677 -0.254345 - -0.228337 1.01448 -0.246852 - -0.232044 0.861633 -0.257255 - -0.229377 0.802227 -0.250707 - -0.227791 0.75205 -0.246896 - -0.227963 0.712366 -0.247559 - -0.228546 0.653099 -0.24939 - -0.226465 0.634553 -0.244128 - -0.226606 0.581563 -0.244784 - -0.227177 0.548815 -0.246438 - -0.166836 -0.397534 -0.109409 - -0.164611 -0.404624 -0.103484 - -0.163366 -0.407756 -0.100165 - -0.154303 -0.402256 -0.0758337 - -0.146319 -0.421187 -0.0545341 - -0.136886 -0.421759 -0.0292462 - -0.132605 -0.419032 -0.0177508 - -0.121454 -0.428735 0.0120897 - -0.123523 -0.458426 0.00637466 - -0.10381 -0.435642 0.0593572 - -0.0938873 -0.424427 0.0860274 - -0.212787 -2.25438 -0.24324 - -0.209417 -2.25756 -0.234224 - -0.126698 -2.1421 -0.011775 - -0.08169 -2.19998 0.108569 - -0.0416822 -0.423905 0.226003 - -0.0330216 -0.441719 0.249122 - 0.0126528 -2.21276 0.361449 - 0.0271104 -2.24293 0.40004 - 0.126257 -2.26133 0.665768 - 0.133139 -2.25721 0.684244 - 0.143754 -2.25462 0.71272 - 0.193975 -2.27963 0.847228 - 0.0268757 -0.511996 0.409317 - 0.0238979 -0.435799 0.401769 - 0.0265842 -0.408436 0.409128 - 0.0282909 -0.396167 0.413774 - 0.0364259 -0.367837 0.435748 - 0.0384437 -0.370243 0.441145 - 0.0468904 -0.402485 0.463608 - 0.0537748 -0.410234 0.482022 - 0.0577779 -0.415908 0.492723 - 0.0615169 -0.412258 0.502768 - 0.0939779 -0.385592 0.589956 - 0.0948939 -0.381559 0.592435 - 0.099055 -0.386615 0.603563 - 0.103296 -0.378213 0.614981 - 0.284693 -0.829719 1.09876 - 0.355691 -0.976709 1.28828 - 0.360095 -0.978964 1.30008 - 0.386697 -0.787753 1.3725 - 0.387589 -0.781904 1.37492 - 0.385976 -0.706416 1.37103 - 0.395796 -0.666004 1.39759 - 0.419771 -0.666413 1.46187 - 0.48882 -0.670019 1.64698 - 0.615853 -0.688797 1.98748 - 0.628071 -0.692231 2.02022 - 0.655599 -0.691566 2.09403 - 0.708173 -0.630949 2.23534 - 0.71019 -0.552283 2.2412 - 0.710447 -0.493109 2.24222 - 0.710193 -0.463536 2.24171 - 0.713225 -0.436049 2.25 - 0.710993 -0.376646 2.24435 - 0.709007 -0.261195 2.23969 - 0.711502 -0.148625 2.24702 - 0.711704 -0.139252 2.24762 - 0.709184 -0.00778993 2.24161 - 0.71159 0.0578419 2.24844 - 0.710302 0.076488 2.24509 - 0.71 0.113976 2.2445 - 0.708316 0.141845 2.24014 - 0.706656 0.235506 2.23623 - 0.708154 0.273892 2.24046 - 0.709728 0.379938 2.24529 - 0.708902 0.408552 2.24324 - 0.707841 0.535476 2.24112 - 0.706999 0.544813 2.23892 - 0.711817 0.62922 2.25232 - 0.708816 0.879644 2.24571 - 0.709488 0.913525 2.2477 - 0.708767 1.04883 2.24654 - 0.710666 1.1344 2.25212 - 0.708984 1.15599 2.24774 - 0.680313 1.28073 2.17158 - 0.461603 1.28753 1.58521 - 0.400761 1.27925 1.42203 - 0.312737 1.27717 1.18601 - 0.287287 1.28615 1.11782 - 0.266293 1.28463 1.06153 - 0.263934 1.28681 1.05521 - 0.239503 1.27763 0.989659 - 0.188014 1.27888 0.851613 - 0.154264 1.27726 0.761111 - 0.138448 1.27896 0.718715 - 0.133271 1.2741 0.704808 - 0.131323 1.27628 0.699596 - 0.127172 1.27868 0.688482 - 0.0810189 1.24856 0.564563 - 0.0719838 1.23902 0.540283 - 0.0358496 1.20071 0.44318 - 0.0305625 1.27633 0.429437 --0.00588603 1.17658 0.33114 - -0.0111563 1.26398 0.31751 - -0.0130846 1.26434 0.312342 - -0.0169426 1.26501 0.302001 - -0.0364944 1.16791 0.249023 - -0.0547102 1.19941 0.200363 - -0.0792421 1.16501 0.134391 - -0.0936038 1.1645 0.0958815 - -0.146987 1.18418 -0.0471365 - -0.150589 1.1815 -0.0568099 - -0.152202 1.1782 -0.0611533 - -0.192799 1.27046 -0.169475 - -0.222328 1.13343 -0.249434 - -0.222603 1.07325 -0.250513 - -0.221512 0.758432 -0.249391 - -0.220707 0.734404 -0.247371 - -0.218927 0.581552 -0.243472 - -0.220283 0.537064 -0.247363 - -0.220607 0.533374 -0.248254 - -0.169655 -0.396394 -0.128705 - -0.169063 -0.398073 -0.127075 - -0.163322 -0.397534 -0.111165 - -0.156469 -0.399493 -0.092187 - -0.148499 -0.403435 -0.0701269 - -0.14021 -0.439962 -0.0473729 - -0.11935 -0.420554 0.0105424 - -0.11683 -0.462848 0.017274 - -0.116587 -0.46654 0.0179269 - -0.1008 -0.437255 0.0618435 - -0.0965602 -0.433698 0.0736119 - -0.092336 -0.435192 0.0853078 - -0.0872803 -0.428746 0.0993546 - -0.0848771 -0.439407 0.105951 - -0.0802749 -0.414298 0.118851 - -0.209926 -2.23557 -0.251127 - -0.201084 -2.25776 -0.226758 - -0.193845 -2.2541 -0.206678 - -0.188861 -2.23161 -0.192736 - -0.174347 -2.21852 -0.152442 - -0.0754494 -2.29493 0.121142 - -0.0423446 -0.419863 0.223918 - 0.0209448 -2.20978 0.38874 - 0.146047 -2.26077 0.735084 - 0.237221 -2.23094 0.987892 - 0.256003 -2.17469 1.04026 - 0.0268713 -0.476432 0.415374 - 0.0268158 -0.408673 0.41562 - 0.0467445 -0.406285 0.470854 - 0.0497701 -0.412525 0.4792 - 0.0538291 -0.419136 0.490409 - 0.0661788 -0.416976 0.524641 - 0.0878951 -0.41366 0.584834 - 0.107918 -0.39882 0.640402 - 0.356011 -0.971693 1.32446 - 0.38154 -0.980807 1.39515 - 0.387046 -0.91621 1.41078 - 0.386181 -0.906044 1.40845 - 0.385441 -0.847802 1.40674 - 0.389372 -0.718598 1.4184 - 0.393523 -0.696509 1.43003 - 0.428431 -0.66927 1.52691 - 0.443388 -0.660366 1.56841 - 0.574569 -0.691413 1.93171 - 0.637554 -0.69354 2.10622 - 0.662465 -0.688954 2.17528 - 0.682065 -0.54729 2.23042 - 0.685583 -0.490867 2.2405 - 0.686115 -0.355776 2.24277 - 0.686026 -0.317568 2.24275 - 0.685639 -0.288918 2.24185 - 0.688214 -0.176481 2.24964 - 0.688564 -0.110807 2.251 - 0.686266 0.359708 2.24741 - 0.686221 0.388581 2.24745 - 0.683899 0.484435 2.24158 - 0.685752 0.82365 2.24871 - 0.684508 0.832984 2.24532 - 0.68472 0.876609 2.24617 - 0.685256 0.921306 2.24792 - 0.684771 1.03379 2.24723 - 0.683719 1.13814 2.24493 - 0.686852 1.1795 2.25386 - 0.684146 1.21193 2.24655 - 0.665458 1.27902 2.19516 - 0.645937 1.28054 2.14108 - 0.586409 1.27406 1.9761 - 0.557286 1.28442 1.89546 - 0.470255 1.27913 1.65428 - 0.434288 1.28734 1.55467 - 0.382733 1.27477 1.41174 - 0.376108 1.277 1.3934 - 0.369272 1.27826 1.37446 - 0.320872 1.27547 1.24034 - 0.202836 1.27646 0.913278 - 0.182718 1.27334 0.857515 - 0.165002 1.28031 0.808467 - 0.160766 1.28286 0.796747 - 0.125729 1.27255 0.699603 - 0.117456 1.27534 0.676694 - 0.0981841 1.16635 0.622652 - 0.0900769 1.16292 0.600168 - 0.0848889 1.16791 0.585822 - 0.0835549 1.17334 0.582158 - 0.0120231 1.16933 0.383928 - 0.00666184 1.16734 0.369061 - -0.0039775 1.1627 0.339553 - -0.0280648 1.17631 0.27289 - -0.0333781 1.16074 0.258076 - -0.0350976 1.16084 0.253312 - -0.0666666 1.2689 0.166474 - -0.0734372 1.17629 0.147168 - -0.0817388 1.16303 0.124088 - -0.116251 1.17974 0.0285556 - -0.218995 1.13116 -0.256421 - -0.217488 1.09673 -0.252449 - -0.217182 1.08272 -0.251683 - -0.217264 1.03685 -0.252181 - -0.218428 0.959288 -0.255863 - -0.215219 0.932463 -0.247129 - -0.216303 0.865905 -0.250525 - -0.215971 0.77764 -0.250124 - -0.217085 0.760911 -0.253309 - -0.214622 0.684699 -0.246935 - -0.214951 0.600347 -0.248342 - -0.214941 0.595072 -0.248347 - -0.215787 0.587563 -0.250736 - -0.213609 0.54595 -0.244945 - -0.213565 0.536406 -0.244879 - -0.163873 -0.386143 -0.12412 - -0.162751 -0.389435 -0.120928 - -0.158793 -0.39386 -0.109624 - -0.147773 -0.423401 -0.0782553 - -0.144157 -0.412971 -0.0678399 - -0.144493 -0.429704 -0.0689012 - -0.127226 -0.433874 -0.0194955 - -0.120868 -0.436016 -0.00130481 - -0.116444 -0.425235 0.0114239 - -0.119024 -0.458426 0.00383615 - -0.107193 -0.456041 0.0377227 - -0.103126 -0.4495 0.0494046 - -0.0990322 -0.441746 0.0611716 - -0.0983945 -0.442539 0.0629923 - -0.0948105 -0.431836 0.0733177 - -0.0912897 -0.426301 0.0834306 - -0.0869634 -0.430959 0.0957879 - -0.0803842 -0.419507 0.114692 - -0.0797792 -0.420052 0.116421 - -0.20694 -2.26091 -0.258784 - -0.203681 -2.26316 -0.249467 - -0.137559 -2.21446 -0.0598751 - -0.129949 -2.18733 -0.0379261 - -0.102045 -2.21481 0.0417924 - -0.0854835 -2.18976 0.0893576 - -0.0736409 -2.243 0.122938 - -0.0369247 -0.422959 0.239089 - -0.0335966 -0.443717 0.248491 - 0.0871356 -2.21196 0.583403 - 0.102072 -2.13964 0.626603 - 0.129508 -2.24804 0.704488 - 0.154203 -2.25692 0.775133 - 0.0261023 -0.398964 0.41967 - 0.0280314 -0.354945 0.42546 - 0.0285398 -0.354055 0.426921 - 0.0502609 -0.419481 0.488708 - 0.0614576 -0.414291 0.520793 - 0.0646217 -0.4121 0.529865 - 0.0704458 -0.416106 0.546514 - 0.0712488 -0.415435 0.548817 - 0.0770118 -0.421838 0.565277 - 0.0788596 -0.421044 0.570572 - 0.0794613 -0.419483 0.572304 - 0.08509 -0.420503 0.588411 - 0.332504 -0.974742 1.29335 - 0.367349 -0.975831 1.3931 - 0.369371 -0.896061 1.39938 - 0.373611 -0.872648 1.41166 - 0.368907 -0.777645 1.39877 - 0.387517 -0.601291 1.45311 - 0.383272 -0.548553 1.44128 - 0.387405 -0.534052 1.4532 - 0.661502 -0.64723 2.23721 - 0.664771 -0.530194 2.24728 - 0.662497 -0.489297 2.24101 - 0.66144 -0.382458 2.23864 - 0.66223 -0.316245 2.2413 - 0.663546 -0.278952 2.24529 - 0.660693 -0.146899 2.23793 - 0.661054 -0.128368 2.23907 - 0.663009 -0.110085 2.24478 - 0.659791 -0.00771356 2.23619 - 0.663149 0.0759892 2.24631 - 0.664186 0.0947656 2.24939 - 0.663463 0.13201 2.24755 - 0.660718 0.206174 2.24014 - 0.660616 0.290799 2.24036 - 0.66239 0.60306 2.24733 - 0.661392 0.873574 2.24612 - 0.661794 1.03075 2.24822 - 0.663871 1.18837 2.25512 - 0.627795 1.28375 2.15242 - 0.480418 1.28496 1.73051 - 0.41007 1.28042 1.52909 - 0.280039 1.27483 1.1568 - 0.270482 1.28284 1.12949 - 0.248251 1.28298 1.06585 - 0.231877 1.28125 1.01896 - 0.21844 1.27865 0.980476 - 0.161624 1.26864 0.81776 - 0.154271 1.27923 0.796775 - 0.144613 1.27389 0.769092 - 0.142643 1.27543 0.763461 - 0.0863642 1.16482 0.601674 - 0.0643431 1.18499 0.538754 - 0.0118871 1.16566 0.388464 - -0.0099845 1.24522 0.326331 - -0.0130277 1.27196 0.317781 - -0.0421293 1.165 0.23382 - -0.0661121 1.2689 0.165791 - -0.0678925 1.26657 0.16068 - -0.0710712 1.17968 0.151053 - -0.138024 1.16608 -0.0407045 - -0.151353 1.17395 -0.078814 - -0.214206 1.25794 -0.258242 - -0.213232 1.22113 -0.255679 - -0.210916 0.964687 -0.250604 - -0.210758 0.897343 -0.250561 - -0.168819 -0.40936 -0.150668 - -0.162221 -0.391853 -0.131048 - -0.146375 -0.422069 -0.0843783 - -0.145186 -0.424978 -0.080879 - -0.143795 -0.427061 -0.0767791 - -0.141192 -0.431902 -0.0691116 - -0.107957 -0.45781 0.0290074 - -0.105509 -0.462414 0.0362159 - -0.0999193 -0.443914 0.0528621 - -0.083713 -0.430929 0.100868 - -0.0798996 -0.43252 0.112135 - -0.0788556 -0.428272 0.115248 - -0.204039 -2.2411 -0.266253 - -0.155932 -2.1951 -0.123707 - -0.124466 -2.19253 -0.0306431 - -0.121398 -2.19372 -0.0215788 - -0.103333 -2.21292 0.0317231 - -0.0966507 -2.19575 0.0515909 - -0.0904611 -2.19533 0.0698968 - -0.0430712 -0.428808 0.221065 - -0.0325744 -0.447558 0.251988 - 0.0142146 -2.20151 0.379399 - 0.0933583 -2.11492 0.613979 - 0.137662 -2.24481 0.744181 - 0.159882 -2.26948 0.809735 - 0.174146 -2.27579 0.851876 - 0.19096 -2.2369 0.901841 - 0.196486 -2.22399 0.918261 - 0.242124 -2.16907 1.05356 - 0.028406 -0.407905 0.432563 - 0.032623 -0.368304 0.445281 - 0.0490057 -0.410546 0.493463 - 0.0582645 -0.409746 0.520847 - 0.0605741 -0.415624 0.527641 - 0.066184 -0.412195 0.544251 - 0.0729804 -0.423367 0.564279 - 0.0743201 -0.41723 0.568279 - 0.0786911 -0.414654 0.581221 - 0.327426 -0.972692 1.31328 - 0.33332 -0.971051 1.33072 - 0.359278 -0.804618 1.40852 - 0.359245 -0.759332 1.40871 - 0.357748 -0.741785 1.40439 - 0.365089 -0.682852 1.42647 - 0.373757 -0.599182 1.45262 - 0.380523 -0.581495 1.47274 - 0.517593 -0.664944 1.87755 - 0.590994 -0.694225 2.09443 - 0.636499 -0.682941 2.22906 - 0.63743 -0.67374 2.23187 - 0.63772 -0.653822 2.23286 - 0.637166 -0.544044 2.2319 - 0.641079 -0.4884 2.24382 - 0.639124 -0.419466 2.23847 - 0.639782 -0.118874 2.24229 - 0.641236 -0.0355593 2.24711 - 0.63863 0.233643 2.24109 - 0.639489 0.550876 2.24561 - 0.641063 0.735051 2.25141 - 0.63971 0.744006 2.24747 - 0.636876 0.782723 2.23933 - 0.6374 0.901392 2.24162 - 0.638714 0.958516 2.24586 - 0.638613 1.04932 2.24613 - 0.638085 1.0834 2.24478 - 0.6388 1.16794 2.24742 - 0.623504 1.2881 2.20294 - 0.572498 1.2842 2.05208 - 0.469387 1.28368 1.74717 - 0.454088 1.279 1.70189 - 0.416599 1.2802 1.59104 - 0.372206 1.27309 1.45972 - 0.358293 1.27406 1.41858 - 0.342269 1.2777 1.37122 - 0.331907 1.27634 1.34057 - 0.309427 1.27578 1.27409 - 0.268707 1.27829 1.15369 - 0.192268 1.28286 0.927682 - 0.169913 1.27423 0.861522 - 0.156492 1.27404 0.821831 - 0.127037 1.27811 0.734754 - 0.12095 1.27934 0.716762 - 0.071394 1.23932 0.569969 - 0.0366915 1.24185 0.467364 - 0.0343662 1.2636 0.460624 - 0.0290554 1.26662 0.444938 - 0.0181152 1.19129 0.412116 - 0.0121454 1.17187 0.394341 - 0.0102931 1.16764 0.388837 --0.00129358 1.16811 0.354577 --0.00450263 1.17116 0.345106 - -0.0194354 1.26701 0.301546 - -0.0748119 1.16149 0.137131 - -0.078023 1.15955 0.127624 - -0.0970885 1.17954 0.0713691 - -0.114594 1.27614 0.0202057 - -0.1317 1.16275 -0.0310878 - -0.138507 1.16156 -0.051223 - -0.140545 1.16506 -0.0572284 - -0.169317 1.27466 -0.141626 - -0.180781 1.27141 -0.175549 - -0.195184 1.27446 -0.21812 - -0.20003 1.26437 -0.232515 - -0.205306 1.25782 -0.248157 - -0.207289 1.17031 -0.254568 - -0.205737 0.992658 -0.251085 - -0.206835 0.97842 -0.254423 - -0.206245 0.907406 -0.25312 - -0.204176 0.74604 -0.248012 - -0.204125 0.725398 -0.247988 - -0.203173 0.701643 -0.245322 - -0.203441 0.659701 -0.246375 - -0.202915 0.596479 -0.245216 - -0.202803 0.575541 -0.245016 - -0.203031 0.561449 -0.245776 - -0.203376 0.557755 -0.24682 - -0.202619 0.526958 -0.244772 - -0.150399 -0.398585 -0.107876 - -0.1449 -0.42146 -0.0911793 - -0.134179 -0.430075 -0.0584012 - -0.133593 -0.431407 -0.0566153 - -0.133005 -0.432731 -0.054824 - -0.0931675 -0.437595 0.0671547 - -0.0878689 -0.438701 0.0833754 - -0.0832332 -0.432216 0.0976147 - -0.0774213 -0.431695 0.115418 - -0.213258 -2.1782 -0.311857 - -0.206643 -2.21558 -0.291838 - -0.190445 -2.25756 -0.242499 - -0.182817 -2.23834 -0.219014 - -0.169969 -2.23449 -0.17964 - -0.167049 -2.23833 -0.170723 - -0.0662922 -2.30787 0.137414 - -0.0390514 -0.410999 0.233065 - -0.0347732 -0.443782 0.245957 - 0.0125651 -2.2025 0.379606 - 0.0517987 -2.20403 0.499755 - 0.129557 -2.25298 0.737587 - 0.179503 -2.26115 0.890503 - 0.190814 -2.24016 0.92528 - 0.250293 -2.16712 1.10791 - 0.0198666 -0.421095 0.413446 - 0.0242717 -0.361048 0.427325 - 0.0467909 -0.417575 0.495929 - 0.0552815 -0.406815 0.522002 - 0.0664462 -0.419411 0.556115 - 0.072803 -0.417913 0.575593 - 0.0776138 -0.413508 0.590355 - 0.0789354 -0.410944 0.594419 - 0.0810255 -0.383406 0.600998 - 0.309773 -0.972776 1.29778 - 0.346514 -0.940935 1.41051 - 0.346289 -0.834532 1.4105 - 0.34388 -0.806191 1.40331 - 0.345766 -0.794873 1.40916 - 0.357877 -0.670952 1.44705 - 0.362278 -0.615122 1.46089 - 0.356688 -0.507478 1.44446 - 0.540983 -0.696605 2.00767 - 0.611539 -0.678932 2.22388 - 0.613561 -0.640813 2.23032 - 0.615831 -0.495144 2.23821 - 0.617167 -0.352325 2.24322 - 0.619002 -0.240147 2.24956 - 0.61202 -0.136082 2.22885 - 0.615887 0.0568734 2.24193 - 0.613706 0.344877 2.23711 - 0.616372 0.609043 2.24698 - 0.617929 0.630636 2.25189 - 0.61483 0.688479 2.24277 - 0.61562 0.751267 2.24559 - 0.61544 0.793005 2.24531 - 0.61195 0.917455 2.23542 - 0.614908 1.10373 2.24568 - 0.614129 1.26034 2.24431 - 0.607055 1.28425 2.22279 - 0.411465 1.28415 1.62377 - 0.39966 1.27287 1.58754 - 0.382306 1.27769 1.53442 - 0.326746 1.27707 1.36426 - 0.317354 1.27772 1.3355 - 0.305467 1.27969 1.2991 - 0.261381 1.27721 1.16407 - 0.248076 1.27809 1.12332 - 0.203002 1.2795 0.985285 - 0.175024 1.27877 0.899593 - 0.16388 1.27866 0.865464 - 0.154199 1.28657 0.835864 - 0.0582841 1.17008 0.541359 - 0.025295 1.24003 0.440775 - -0.0133853 1.26757 0.322488 - -0.0392464 1.16696 0.242636 - -0.0408223 1.16099 0.237771 - -0.0556044 1.20923 0.192809 - -0.0650487 1.2719 0.164288 - -0.068088 1.25325 0.15486 - -0.0739967 1.16348 0.136185 - -0.0754797 1.16003 0.131621 - -0.115656 1.1856 0.00873873 - -0.116492 1.17279 0.00609766 - -0.14697 1.17441 -0.0872386 - -0.169051 1.2721 -0.154235 - -0.172386 1.26754 -0.164477 - -0.201487 1.20641 -0.253997 - -0.199887 1.15292 -0.249442 - -0.200509 0.960274 -0.252588 - -0.201579 0.909146 -0.256195 - -0.1963 0.789546 -0.240799 - -0.198664 0.722942 -0.248468 - -0.198463 0.702454 -0.247984 - -0.197572 0.685917 -0.245363 - -0.198242 0.629778 -0.247775 - -0.199339 0.623015 -0.251179 - -0.197501 0.574038 -0.245864 - -0.196869 0.53791 -0.244161 - -0.159815 -0.401928 -0.150451 - -0.158864 -0.402254 -0.147432 - -0.145235 -0.38887 -0.104053 - -0.144024 -0.423875 -0.100439 - -0.13563 -0.430506 -0.0738194 - -0.119001 -0.434186 -0.021025 - -0.117281 -0.437626 -0.0155843 - -0.11173 -0.422987 0.00214709 - -0.110055 -0.42611 0.00744615 - -0.107547 -0.44745 0.0152688 - -0.0978928 -0.444983 0.0459522 - -0.0883994 -0.433086 0.0761864 - -0.0878301 -0.433796 0.0779899 - -0.0849703 -0.437223 0.0870511 - -0.0809733 -0.435345 0.0997598 - -0.165777 -2.23548 -0.181601 - -0.130393 -2.18142 -0.0688477 - -0.126012 -2.21876 -0.0551789 - -0.117413 -2.22647 -0.0279189 - -0.106017 -2.24082 0.00818589 - -0.0870388 -2.18437 0.0688442 - -0.0362961 -0.433889 0.241683 - 0.0083352 -2.21913 0.371561 - 0.0254888 -2.20556 0.426139 - 0.0472591 -2.23898 0.495068 - 0.0614682 -2.15977 0.540729 - 0.142945 -2.25375 0.798908 - 0.160354 -2.27098 0.854093 - 0.170665 -2.27756 0.886799 - 0.194687 -2.16374 0.963861 - 0.197513 -2.16037 0.972862 - 0.219633 -2.15609 1.04315 - 0.239194 -2.15423 1.1053 - 0.0228344 -0.479458 0.429203 - 0.0200692 -0.437502 0.420699 - 0.0238749 -0.434884 0.432805 - 0.0210915 -0.366325 0.424421 - 0.023787 -0.360066 0.433024 - 0.0244106 -0.360006 0.435006 - 0.0262869 -0.363279 0.440944 - 0.0447793 -0.414315 0.499343 - 0.045319 -0.41309 0.501066 - 0.0639288 -0.412618 0.560182 - 0.0746289 -0.413336 0.594165 - 0.0766754 -0.375828 0.600915 - 0.288867 -0.970728 1.27096 - 0.319855 -0.889439 1.36994 - 0.321007 -0.884225 1.37363 - 0.320605 -0.835978 1.37267 - 0.323196 -0.75899 1.38142 - 0.34557 -0.64406 1.45325 - 0.348573 -0.635073 1.46285 - 0.349391 -0.629437 1.46549 - 0.34613 -0.617283 1.45521 - 0.510958 -0.692016 1.97828 - 0.59251 -0.60129 2.23792 - 0.592695 -0.591568 2.23858 - 0.593011 -0.552484 2.23984 - 0.592096 -0.303393 2.23859 - 0.592055 -0.256712 2.23877 - 0.591473 -0.247182 2.23699 - 0.590739 -0.090162 2.2357 - 0.593829 -0.0353084 2.24588 - 0.592283 0.0199081 2.24134 - 0.592282 0.0842899 2.24177 - 0.592302 0.102716 2.24195 - 0.590792 0.148504 2.23746 - 0.590446 0.185338 2.23661 - 0.590801 0.2225 2.23798 - 0.58982 0.249999 2.23505 - 0.591808 0.354071 2.24206 - 0.590772 0.565495 2.24017 - 0.592917 0.637294 2.24747 - 0.593821 0.730157 2.25096 - 0.588294 0.95822 2.23492 - 0.592299 1.0784 2.24844 - 0.590519 1.23124 2.2438 - 0.590546 1.28134 2.24422 - 0.576452 1.27756 2.19943 - 0.529997 1.27586 2.05186 - 0.375882 1.27855 1.56234 - 0.32979 1.27448 1.41591 - 0.254342 1.26705 1.1762 - 0.250089 1.27166 1.16272 - 0.183544 1.28006 0.951404 - 0.169775 1.27746 0.907649 - 0.157437 1.28133 0.868487 - 0.127732 1.27572 0.774094 - 0.115924 1.27626 0.73659 - 0.100975 1.28078 0.689133 - 0.0862675 1.1956 0.64185 - 0.0648953 1.18956 0.573923 - 0.0356298 1.17467 0.480864 - 0.0348852 1.27115 0.479141 - 0.0332168 1.27226 0.473849 - 0.0315471 1.27335 0.468552 - 0.0232951 1.21446 0.441948 - 0.00974779 1.16518 0.398588 - 0.00821918 1.16593 0.393738 - 0.00209584 1.16869 0.374306 - -0.0144713 1.26757 0.32234 - -0.0318535 1.16448 0.26644 - -0.109486 1.26039 0.0204845 - -0.137791 1.1633 -0.0700706 - -0.166925 1.27221 -0.161888 - -0.168588 1.27039 -0.16718 - -0.177577 1.26752 -0.195754 - -0.187455 1.27143 -0.227103 - -0.195855 1.18762 -0.254345 - -0.194006 1.09485 -0.24909 - -0.194978 1.04223 -0.252526 - -0.193932 0.885193 -0.250251 - -0.19486 0.872966 -0.253278 - -0.192533 0.810869 -0.246302 - -0.192568 0.724326 -0.246989 - -0.192747 0.65037 -0.248049 - -0.193216 0.613073 -0.249788 - -0.143648 -0.375167 -0.111175 - -0.142292 -0.390352 -0.106812 - -0.129058 -0.429546 -0.06349 - -0.123644 -0.42673 -0.0456343 - -0.117273 -0.438451 -0.0247318 - -0.110419 -0.420001 -0.00202715 - -0.109348 -0.422119 0.00148764 - -0.10073 -0.454213 0.0296517 - -0.099913 -0.453314 0.0323505 - -0.0965632 -0.448645 0.0434166 - -0.0920421 -0.44439 0.0583382 - -0.0782082 -0.431765 0.103994 - -0.196537 -2.22432 -0.298119 - -0.16536 -2.24926 -0.195593 - -0.140324 -2.1543 -0.112473 - -0.0828303 -2.19107 0.0766562 - -0.0705766 -2.3199 0.116132 - 0.0417449 -2.24414 0.486637 - 0.0584917 -2.16669 0.542334 - 0.0641177 -2.16673 0.560865 - 0.0668602 -2.16521 0.56991 - 0.0823702 -2.13948 0.621176 - 0.127274 -2.24582 0.768356 - 0.155882 -2.25851 0.862503 - 0.174228 -2.22114 0.92319 - 0.214782 -2.15978 1.0572 - 0.0190523 -0.440274 0.424308 - 0.0468957 -0.415796 0.516191 - 0.053164 -0.410926 0.536873 - 0.0603442 -0.423294 0.560439 - 0.0608769 -0.421793 0.562204 - 0.0705132 -0.408742 0.594035 - 0.0803931 -0.387513 0.626726 - 0.288111 -0.975398 1.30689 - 0.317214 -0.972099 1.40278 - 0.322047 -0.950591 1.41885 - 0.31001 -0.808279 1.38018 - 0.307653 -0.78045 1.37261 - 0.324025 -0.608427 1.42772 - 0.32873 -0.575917 1.44344 - 0.333524 -0.563315 1.45932 - 0.335333 -0.546086 1.4654 - 0.333055 -0.53621 1.45796 - 0.55183 -0.698493 2.17748 - 0.567401 -0.66644 2.22899 - 0.568831 -0.395961 2.23557 - 0.570035 -0.321433 2.24005 - 0.571677 -0.18263 2.24641 - 0.571792 -0.164175 2.24691 - 0.570624 -0.0535226 2.24383 - 0.569239 0.0106785 2.23971 - 0.56965 0.0932135 2.24163 - 0.568776 0.111429 2.23888 - 0.568247 0.138869 2.23732 - 0.568538 0.175751 2.23854 - 0.570372 0.213325 2.24484 - 0.56836 0.277586 2.23865 - 0.570056 0.419996 2.24522 - 0.570977 0.656294 2.24988 - 0.570121 0.665487 2.24712 - 0.569137 0.694871 2.24408 - 0.570226 0.726895 2.24789 - 0.5691 0.766967 2.24446 - 0.571094 0.779949 2.25112 - 0.570142 0.799747 2.24812 - 0.568596 0.818823 2.24316 - 0.568394 0.959466 2.24346 - 0.56611 1.09217 2.23685 - 0.569399 1.24297 2.24872 - 0.553993 1.28548 2.19827 - 0.518117 1.27969 2.08005 - 0.483499 1.282 1.96604 - 0.455656 1.28286 1.87433 - 0.40214 1.28669 1.69807 - 0.293246 1.27475 1.3393 - 0.251146 1.27325 1.20062 - 0.216858 1.2777 1.0877 - 0.143684 1.27474 0.846649 - 0.067827 1.17102 0.596063 - 0.0646773 1.17238 0.585698 - 0.0478629 1.1632 0.530248 - 0.0403237 1.16776 0.505446 - -0.0008695 1.1723 0.369788 - -0.0170731 1.27096 0.317093 - -0.0900797 1.16146 0.0758582 - -0.115471 1.17848 -0.0076634 - -0.122019 1.16007 -0.0293568 - -0.13644 1.16383 -0.0768347 - -0.162726 1.26936 -0.162692 - -0.16433 1.26754 -0.167989 - -0.182966 1.27237 -0.229341 - -0.188445 0.838799 -0.250373 - -0.18605 0.742971 -0.243145 - -0.189187 0.724579 -0.253607 - -0.186565 0.667882 -0.24536 - -0.18617 0.660109 -0.244113 - -0.185779 0.602277 -0.243222 - -0.18613 0.582868 -0.244512 - -0.186281 0.548878 -0.245244 - -0.18597 0.515404 -0.24445 - -0.150933 -0.401543 -0.150005 - -0.138007 -0.394173 -0.105674 - -0.133568 -0.407661 -0.0905663 - -0.134134 -0.417572 -0.0925768 - -0.133104 -0.420503 -0.0890681 - -0.130106 -0.433713 -0.0788942 - -0.117317 -0.424198 -0.035018 - -0.115153 -0.424421 -0.0276045 - -0.108125 -0.43817 -0.00362937 - -0.103605 -0.421998 0.0119689 - -0.0891608 -0.434207 0.0613591 - -0.088628 -0.434976 0.0631789 - -0.0832065 -0.429552 0.0817886 - -0.0776552 -0.433086 0.100779 - -0.179572 -2.22583 -0.261126 - -0.0564046 -0.4318 0.173581 - -0.109744 -2.23658 -0.0220118 - -0.0813844 -2.19606 0.0754227 - -0.0366931 -0.439887 0.241044 - 0.00077552 -2.27823 0.356271 - 0.0234522 -2.19071 0.434574 - 0.0264002 -2.19871 0.444615 - 0.0650776 -2.14984 0.577452 - 0.0738097 -2.11076 0.607642 - 0.146904 -2.23356 0.857147 - 0.164111 -2.25883 0.915908 - 0.172451 -2.25024 0.944538 - 0.175922 -2.25456 0.956396 - 0.2207 -2.15515 1.11049 - 0.0147447 -0.368013 0.417755 - 0.0215791 -0.388974 0.441017 - 0.0280816 -0.400978 0.463205 - 0.029894 -0.407612 0.469366 - 0.0306861 -0.408232 0.472075 - 0.0319288 -0.411384 0.476309 - 0.042235 -0.412191 0.511607 - 0.0427358 -0.410914 0.513331 - 0.0628727 -0.427082 0.582194 - 0.0633909 -0.425484 0.58398 - 0.0663333 -0.401057 0.594234 - 0.0671577 -0.377075 0.597229 - 0.131885 -0.563639 0.817619 - 0.269856 -0.971925 1.28732 - 0.27497 -0.970809 1.30484 - 0.300534 -0.986772 1.3923 - 0.296238 -0.87486 1.37838 - 0.29473 -0.80901 1.37368 - 0.29719 -0.73376 1.38265 - 0.322759 -0.547256 1.47157 - 0.433811 -0.654786 1.8512 - 0.542897 -0.60376 2.22524 - 0.544046 -0.585341 2.2293 - 0.546093 -0.433053 2.2374 - 0.549616 -0.388091 2.24979 - 0.545534 -0.366616 2.23596 - 0.544865 -0.26388 2.2344 - 0.545453 -0.245663 2.23655 - 0.545997 -0.227428 2.23854 - 0.544646 -0.180988 2.23424 - 0.54608 -0.117251 2.23961 - 0.545639 -0.0349739 2.23869 - 0.544334 0.16581 2.23565 - 0.546994 0.21272 2.2451 - 0.546711 0.221869 2.24419 - 0.545238 0.249053 2.23934 - 0.547008 0.324482 2.24594 - 0.545483 0.333004 2.24078 - 0.548649 0.615474 2.25364 - 0.54727 0.715121 2.24963 - 0.545837 1.08302 2.24734 - 0.544737 1.09263 2.24364 - 0.543227 1.27096 2.23974 - 0.508335 1.27915 2.12028 - 0.503251 1.27948 2.10287 - 0.468415 1.27925 1.98354 - 0.418962 1.27767 1.81413 - 0.39117 1.27837 1.71893 - 0.213747 1.28534 1.11123 - 0.172166 1.27859 0.968748 - 0.168738 1.28351 0.957038 - 0.155595 1.27921 0.911987 - 0.1278 1.2785 0.816773 - 0.120702 1.28256 0.792485 - 0.100366 1.28305 0.72283 - 0.0908327 1.27797 0.690138 - 0.0727553 1.18135 0.627526 - 0.0546097 1.17385 0.565315 - 0.0358944 1.19356 0.501347 - 0.00596378 1.1642 0.398612 --0.00913515 1.19504 0.347111 - -0.0110962 1.23687 0.340692 - -0.0649472 1.27855 0.156525 - -0.0730973 1.17596 0.127876 - -0.0814267 1.16477 0.0992636 - -0.109048 1.27117 0.00540687 - -0.112734 1.2513 -0.00736204 - -0.114088 1.24726 -0.0120269 - -0.115715 1.17332 -0.0181268 - -0.151736 1.26873 -0.140835 - -0.183917 1.11836 -0.252143 - -0.184744 1.0872 -0.2552 - -0.184036 1.02386 -0.253225 - -0.183302 0.936019 -0.251337 - -0.181417 0.877826 -0.245297 - -0.181847 0.863063 -0.246874 - -0.182522 0.833658 -0.249397 - -0.183389 0.830606 -0.252387 - -0.183954 0.825839 -0.254357 - -0.183143 0.775402 -0.251941 - -0.182836 0.759303 -0.251002 - -0.181192 0.736652 -0.245534 - -0.180967 0.533525 -0.246213 - -0.134 -0.388175 -0.10488 - -0.133004 -0.387454 -0.101324 - -0.134821 -0.40934 -0.107962 - -0.119421 -0.430408 -0.0532461 - -0.108017 -0.42191 -0.0125545 - -0.106017 -0.413552 -0.00536686 - -0.0987134 -0.449555 0.0203902 - -0.0955954 -0.450589 0.0314918 - -0.0950618 -0.451489 0.0333861 - -0.162491 -2.25704 -0.220222 - -0.135947 -2.15568 -0.124896 - -0.130853 -2.15881 -0.106772 - -0.0395589 -0.413999 0.231416 - -0.0365663 -0.420847 0.242027 - -0.0352739 -0.446715 0.246441 - 0.062147 -2.1666 0.580814 - 0.126506 -2.23954 0.809578 - 0.133107 -2.25155 0.833009 - 0.138399 -2.246 0.851907 - 0.151617 -2.26593 0.898852 - 0.154281 -2.26288 0.908367 - 0.208989 -2.16005 1.10405 - 0.0140507 -0.434816 0.422268 - 0.0307018 -0.408012 0.481793 - 0.0323197 -0.39808 0.487631 - 0.0420883 -0.411873 0.522333 - 0.045481 -0.409934 0.534436 - 0.0620676 -0.417373 0.593477 - 0.0621891 -0.414248 0.593933 - 0.0623406 -0.380384 0.594724 - 0.0749607 -0.398468 0.639554 - 0.269645 -0.972692 1.32895 - 0.274408 -0.970409 1.34593 - 0.292717 -0.956461 1.41127 - 0.282342 -0.77826 1.37563 - 0.285484 -0.685394 1.38751 - 0.285807 -0.679162 1.3887 - 0.30638 -0.568501 1.46282 - 0.523056 -0.674307 2.23404 - 0.523641 -0.56637 2.23692 - 0.523007 -0.526978 2.23496 - 0.525878 -0.0533444 2.24869 - 0.525918 -0.0442014 2.2489 - 0.523563 0.0470661 2.24118 - 0.522741 0.129045 2.23886 - 0.52445 0.175334 2.24529 - 0.524248 0.193672 2.24471 - 0.523202 0.417059 2.24264 - 0.522313 0.65976 2.24126 - 0.522795 0.670389 2.24306 - 0.523732 0.858402 2.24779 - 0.522148 0.877416 2.24229 - 0.522156 1.06658 2.24372 - 0.521247 1.11134 2.24081 - 0.522284 1.12518 2.24461 - 0.408336 1.28326 1.83979 - 0.321194 1.26925 1.5292 - 0.261258 1.27404 1.31569 - 0.246235 1.27701 1.26219 - 0.220023 1.28147 1.16883 - 0.204729 1.27483 1.11429 - 0.198184 1.27607 1.09098 - 0.19394 1.27721 1.07587 - 0.188193 1.28191 1.05543 - 0.162302 1.27849 0.963154 - 0.142564 1.27955 0.892838 - 0.1195 1.27662 0.810643 - 0.101174 1.27394 0.745327 - 0.0709477 1.20779 0.637145 - 0.0612553 1.16936 0.602327 - 0.0517158 1.1637 0.568296 - 0.045774 1.16384 0.547127 - 0.0415058 1.1661 0.531937 - 0.0366799 1.18203 0.51486 - 0.0338836 1.25937 0.50547 - 0.0325649 1.26353 0.500802 - 0.0193328 1.18597 0.453083 - 0.00997631 1.16987 0.419628 - 0.00847077 1.16775 0.414248 - -0.0230101 1.20979 0.302396 - -0.0305395 1.16513 0.275238 - -0.0373992 1.17083 0.25084 - -0.0709281 1.1834 0.131473 - -0.0722686 1.18094 0.126678 - -0.116153 1.19655 -0.0295618 - -0.122657 1.16189 -0.0529927 - -0.173829 1.27611 -0.234469 - -0.177814 1.265 -0.248749 - -0.17915 1.20126 -0.253979 - -0.178573 1.14103 -0.252372 - -0.178509 1.0894 -0.252525 - -0.177666 1.05875 -0.249747 - -0.177217 0.928094 -0.249117 - -0.175274 0.717454 -0.24375 - -0.175345 0.655319 -0.244463 - -0.17643 0.615136 -0.248627 - -0.175126 0.553214 -0.244441 - -0.175402 0.540063 -0.24552 - -0.141534 -0.395147 -0.146961 - -0.136233 -0.391245 -0.127256 - -0.126767 -0.365194 -0.0919145 - -0.127999 -0.37702 -0.0965781 - -0.129354 -0.389706 -0.101706 - -0.111618 -0.426245 -0.0361504 - -0.101094 -0.464385 0.00262211 - -0.0928642 -0.44423 0.0333281 - -0.0805246 -0.426052 0.0792742 - -0.0730292 -0.440755 0.106985 - -0.0724579 -0.440349 0.109109 - -0.0701389 -0.445892 0.117675 - -0.177998 -2.19132 -0.296134 - -0.144421 -2.25392 -0.171972 - -0.125004 -2.16131 -0.0991796 - -0.122809 -2.16969 -0.0910984 - -0.119813 -2.22695 -0.080416 - -0.104663 -2.23658 -0.0242522 - -0.101767 -2.22479 -0.0134088 - -0.0784485 -2.20204 0.0733254 - -0.0441072 -0.438673 0.214363 - -0.0435813 -0.434745 0.216345 - -0.0420436 -0.418906 0.222175 - -0.040617 -0.418986 0.227471 - -0.0376041 -0.442926 0.238471 --0.00143141 -2.31617 0.358345 - 0.0584044 -2.16759 0.581605 - 0.0876463 -2.23276 0.689654 - 0.167521 -2.23786 0.98612 - 0.182844 -2.16257 1.04358 - 0.188419 -2.16164 1.06428 - 0.201837 -2.15331 1.11415 - 0.204271 -2.1493 1.12322 - 0.00953064 -0.434548 0.413505 - 0.0100218 -0.433718 0.415334 - 0.0206953 -0.479903 0.454601 - 0.02279 -0.480405 0.462373 - 0.0107767 -0.365398 0.418662 - 0.0236776 -0.421576 0.46612 - 0.024562 -0.414913 0.469454 - 0.0288038 -0.41307 0.485214 - 0.0322582 -0.417575 0.498003 - 0.0337874 -0.418458 0.503673 - 0.0352963 -0.423004 0.509239 - 0.0434678 -0.420056 0.539595 - 0.0488705 -0.416375 0.559679 - 0.0521289 -0.420301 0.571745 - 0.0614207 -0.378617 0.606557 - 0.250161 -0.972386 1.30262 - 0.26957 -0.884059 1.37535 - 0.268883 -0.789715 1.37352 - 0.270182 -0.763532 1.37855 - 0.270671 -0.735833 1.38057 - 0.271677 -0.709828 1.38451 - 0.273256 -0.699372 1.39045 - 0.283155 -0.637374 1.42767 - 0.282573 -0.58933 1.42588 - 0.284409 -0.586053 1.43272 - 0.285061 -0.580615 1.43518 - 0.296021 -0.559703 1.47603 - 0.498772 -0.621 2.22819 - 0.500937 -0.584258 2.23652 - 0.499908 -0.544359 2.233 - 0.49974 -0.496198 2.23275 - 0.499805 -0.45821 2.23328 - 0.500789 -0.440094 2.23708 - 0.502891 -0.403953 2.24515 - 0.502124 -0.337813 2.24282 - 0.502079 -0.126015 2.24428 - 0.501013 -0.0257399 2.24109 - 0.498602 0.0195962 2.23249 - 0.502317 0.12923 2.24712 - 0.502814 0.15685 2.24918 - 0.500933 0.2205 2.24269 - 0.5013 0.35059 2.24505 - 0.501648 0.360198 2.24641 - 0.501361 0.473808 2.24623 - 0.501082 0.619817 2.24631 - 0.50135 0.630072 2.24739 - 0.500343 0.658856 2.24387 - 0.498565 0.862929 2.23884 - 0.497823 0.904674 2.2364 - 0.497762 0.981336 2.23677 - 0.500358 1.03116 2.24679 - 0.500228 1.14723 2.24719 - 0.440986 1.28086 2.02831 - 0.432309 1.28155 1.9961 - 0.4044 1.28645 1.89254 - 0.386376 1.28012 1.82559 - 0.378759 1.28022 1.79731 - 0.371577 1.28117 1.77066 - 0.353851 1.28218 1.70487 - 0.338953 1.27841 1.64953 - 0.311726 1.2736 1.54842 - 0.274573 1.2773 1.41054 - 0.270227 1.28208 1.39444 - 0.260929 1.27707 1.35989 - 0.226499 1.28149 1.23211 - 0.21712 1.28203 1.1973 - 0.168747 1.28001 1.01772 - 0.15569 1.27345 0.969199 - 0.150543 1.27815 0.950128 - 0.137078 1.27742 0.90014 - 0.135136 1.27691 0.892926 - 0.113626 1.27934 0.813099 - 0.0796211 1.28097 0.68688 - 0.0470947 1.17001 0.565285 - 0.0119544 1.16919 0.434833 - 0.00208477 1.16024 0.398127 - -0.0005534 1.1617 0.388345 --0.00583866 1.16436 0.368746 - -0.0114582 1.26922 0.348692 - -0.0254489 1.19412 0.296179 - -0.0312224 1.15214 0.274425 - -0.041693 1.15599 0.235586 - -0.0524281 1.17942 0.195916 - -0.0802741 1.16613 0.0924464 - -0.113678 1.24772 -0.0309253 - -0.114819 1.17175 -0.0357456 - -0.148396 1.2815 -0.159544 - -0.161549 1.26649 -0.208484 - -0.171414 0.941265 -0.247606 - -0.170102 0.841881 -0.2435 - -0.170277 0.787477 -0.244567 - -0.170037 0.659073 -0.244665 - -0.169989 0.652925 -0.244533 - -0.170439 0.62103 -0.24645 - -0.135679 -0.390426 -0.140647 - -0.12302 -0.376217 -0.0914991 - -0.123813 -0.397124 -0.0947378 - -0.115824 -0.43898 -0.0641264 - -0.104825 -0.41658 -0.0213459 - -0.102905 -0.424729 -0.0139744 - -0.0954064 -0.418678 0.0151197 - -0.086887 -0.45017 0.0478671 - -0.0823206 -0.438166 0.0656506 - -0.0806223 -0.437544 0.0722336 - -0.143566 -2.26977 -0.18623 - -0.118076 -2.19684 -0.0869161 - -0.104083 -2.21953 -0.0328977 - -0.0836007 -2.17383 0.0468054 - -0.0728101 -2.25327 0.0879661 - -0.0679032 -2.25545 0.106955 - -0.040233 -0.421996 0.228802 - 0.0545658 -2.1666 0.582038 - 0.0576445 -2.12789 0.594273 - 0.0979851 -2.23119 0.749702 - 0.104276 -2.24873 0.773929 - 0.112377 -2.21443 0.805581 - 0.135471 -2.2766 0.894536 - 0.139886 -2.26384 0.911739 - 0.146626 -2.24681 0.937982 - 0.153459 -2.26309 0.964321 - 0.19225 -2.15147 1.11546 - 0.231599 -2.17055 1.26773 - 0.00865024 -0.368898 0.418571 - 0.00944979 -0.367187 0.421682 - 0.0242176 -0.417607 0.47848 - 0.0267886 -0.421824 0.488405 - 0.0381364 -0.413466 0.532427 - 0.0511925 -0.41475 0.582988 - 0.0543327 -0.414248 0.595155 - 0.0540277 -0.405807 0.594041 - 0.0539491 -0.395056 0.593823 - 0.0596355 -0.380734 0.615963 - 0.259229 -0.981237 1.38426 - 0.257226 -0.84406 1.3776 - 0.256471 -0.811366 1.37494 - 0.258699 -0.736359 1.38417 - 0.268213 -0.605925 1.42207 - 0.274677 -0.571777 1.44738 - 0.279972 -0.548159 1.46808 - 0.277793 -0.505628 1.45998 - 0.438118 -0.693596 2.07948 - 0.476602 -0.698916 2.2285 - 0.47832 -0.505478 2.2367 - 0.479175 -0.35531 2.24121 - 0.479978 -0.300109 2.24477 - 0.477103 -0.206887 2.23437 - 0.481596 -0.171966 2.25206 - 0.478452 -0.13453 2.24018 - 0.47864 -0.0982375 2.2412 - 0.478475 -0.0891325 2.24063 - 0.477365 -0.0708413 2.23648 - 0.479058 0.0468857 2.24398 - 0.477652 0.471594 2.24193 - 0.479255 0.599371 2.24916 - 0.47921 0.719717 2.24995 - 0.477192 0.894814 2.24353 - 0.476406 0.947837 2.24091 - 0.477261 0.982617 2.2445 - 0.477978 1.00638 2.24747 - 0.475448 1.21157 2.23931 - 0.47539 1.22366 2.23918 - 0.47629 1.25047 2.24288 - 0.469209 1.28283 2.21572 - 0.465895 1.28695 2.20291 - 0.461324 1.28776 2.18522 - 0.437564 1.28698 2.09318 - 0.422818 1.28313 2.03603 - 0.414474 1.28384 2.00371 - 0.385246 1.28166 1.89049 - 0.363562 1.28456 1.80652 - 0.356263 1.2843 1.77824 - 0.318143 1.28057 1.63056 - 0.307149 1.28599 1.58802 - 0.243658 1.27607 1.34201 - 0.242089 1.28032 1.33597 - 0.228402 1.27371 1.2829 - 0.226521 1.27614 1.27564 - 0.200224 1.28227 1.17382 - 0.125039 1.28106 0.882593 - 0.107715 1.28205 0.815497 - 0.090323 1.27579 0.748082 - 0.0797026 1.28309 0.707003 - 0.0355885 1.19743 0.535446 - 0.0331369 1.275 0.52657 - 0.0166467 1.17608 0.461906 - -0.0317144 1.16213 0.274472 - -0.0508691 1.17757 0.200402 - -0.0667109 1.25846 0.139687 - -0.0892371 1.16435 0.0516814 - -0.113536 1.21776 -0.0420104 - -0.150942 1.26762 -0.186502 - -0.153865 1.2657 -0.197838 - -0.167589 1.14504 -0.25196 - -0.166968 0.985486 -0.250834 - -0.166352 0.875216 -0.24933 - -0.166266 0.824233 -0.249405 - -0.163496 0.521832 -0.241095 - -0.165006 0.514686 -0.247001 - -0.130198 -0.386359 -0.134958 - -0.117082 -0.356942 -0.0816423 - -0.118603 -0.39092 -0.0880797 - -0.111086 -0.440434 -0.0580807 - -0.0990705 -0.41893 -0.00928612 - -0.0992245 -0.424322 -0.00995412 - -0.0986813 -0.429067 -0.0077959 - -0.0957319 -0.424504 0.00417522 - -0.095285 -0.425514 0.00597502 - -0.0944387 -0.442006 0.00926146 - -0.0930323 -0.45495 0.014844 - -0.0925537 -0.455912 0.0167727 - -0.089719 -0.446054 0.028324 - -0.0846547 -0.440136 0.0488633 - -0.0829745 -0.445178 0.0556194 - -0.0769948 -0.43117 0.07993 - -0.0711124 -0.432916 0.103716 - -0.0696691 -0.440894 0.109489 - -0.0697649 -0.450105 0.109024 - -0.0682788 -0.442479 0.115101 - -0.171326 -2.21994 -0.316647 - -0.123651 -2.11921 -0.12291 - -0.119824 -2.13907 -0.107594 - -0.0937082 -2.19107 -0.00236182 --0.00428251 -2.31816 0.358396 - 0.0284905 -2.19333 0.492036 - 0.0431678 -2.21021 0.55128 - 0.0516268 -2.13149 0.586161 - 0.0553188 -2.11147 0.601266 - 0.0661917 -2.19362 0.644573 - 0.069608 -2.21429 0.658223 - 0.082395 -2.22657 0.709857 - 0.0938217 -2.21232 0.756209 - 0.185695 -2.15205 1.12843 - 0.00742774 -0.447443 0.421369 - 0.00674916 -0.366281 0.4193 - 0.0186785 -0.414265 0.467166 - 0.0251162 -0.40924 0.493255 - 0.0274611 -0.415972 0.502686 - 0.0304593 -0.410914 0.514859 - 0.0351665 -0.407555 0.533933 - 0.0374835 -0.408915 0.543296 - 0.0408899 -0.415528 0.557023 - 0.217027 -0.967432 1.26507 - 0.223174 -0.97339 1.2899 - 0.251565 -0.961526 1.40486 - 0.244245 -0.84116 1.37625 - 0.244522 -0.834269 1.37743 - 0.244302 -0.8108 1.37674 - 0.243383 -0.77114 1.37335 - 0.245256 -0.718675 1.38136 - 0.244342 -0.709377 1.37774 - 0.255426 -0.585462 1.42362 - 0.262389 -0.539883 1.45217 - 0.448947 -0.689293 2.20574 - 0.457655 -0.671533 2.24112 - 0.453878 -0.627104 2.22621 - 0.454067 -0.569058 2.22746 - 0.455923 -0.325915 2.237 - 0.456779 -0.252836 2.24107 - 0.457613 -0.19833 2.2449 - 0.456812 -0.0890039 2.24257 - 0.456275 0.192012 2.24274 - 0.456292 0.219448 2.24303 - 0.456079 0.320661 2.24302 - 0.455675 0.376254 2.24185 - 0.455035 0.566232 2.24084 - 0.454256 0.584827 2.23784 - 0.456932 0.627472 2.24903 - 0.456133 0.716781 2.24654 - 0.456663 0.768851 2.24912 - 0.455527 1.25099 2.24854 - 0.404191 1.2837 2.04111 - 0.386262 1.27884 1.96852 - 0.332955 1.283 1.75288 - 0.289163 1.28258 1.57569 - 0.284498 1.27565 1.55676 - 0.257056 1.27549 1.44573 - 0.242882 1.28073 1.38842 - 0.204463 1.27682 1.23295 - 0.201333 1.27195 1.22024 - 0.143222 1.28293 0.985217 - 0.133595 1.27879 0.946231 - 0.125693 1.28579 0.91432 - 0.115953 1.27689 0.874836 - 0.107537 1.2767 0.840782 - 0.101644 1.28295 0.816994 - 0.0805562 1.27989 0.731645 - 0.0733081 1.28523 0.702364 - 0.0681285 1.27832 0.681349 - 0.0356488 1.18647 0.549171 - 0.0355584 1.22793 0.549151 - 0.0340814 1.27283 0.543549 - 0.0167494 1.17689 0.472624 - 0.0154211 1.17601 0.467242 - 0.0110173 1.16339 0.449319 --0.00895686 1.21065 0.368897 - -0.0127421 1.27166 0.354091 - -0.0359242 1.16362 0.259395 - -0.0407986 1.16096 0.239652 - -0.0671505 1.25604 0.133824 - -0.086272 1.16515 0.0557007 - -0.138238 1.2718 -0.153664 - -0.149531 1.2657 -0.199408 - -0.151262 1.26847 -0.206388 - -0.163909 1.25817 -0.257644 - -0.161066 0.863497 -0.24943 - -0.161599 0.858735 -0.251627 - -0.160506 0.79472 -0.247739 - -0.160794 0.73168 -0.249431 - -0.161418 0.72869 -0.25198 - -0.159927 0.61712 -0.246878 - -0.160153 0.586431 -0.248047 - -0.15954 0.525486 -0.246074 - -0.158678 0.503902 -0.242767 - -0.12496 -0.389794 -0.130019 - -0.114049 -0.357686 -0.0835102 - -0.113687 -0.359086 -0.0819889 - -0.114154 -0.374471 -0.0841012 - -0.112683 -0.424092 -0.0782984 - -0.107835 -0.422077 -0.0577418 - -0.106982 -0.424636 -0.0541472 - -0.106425 -0.425076 -0.0517942 - -0.104009 -0.421314 -0.0415238 - -0.0955199 -0.43206 -0.00564601 - -0.0919284 -0.434799 0.00954796 - -0.0889783 -0.447836 0.0219343 - -0.0772045 -0.433796 0.0719444 - -0.0755905 -0.432112 0.0787979 - -0.0726307 -0.424951 0.0914011 - -0.0718228 -0.43344 0.0947505 - -0.0700704 -0.450358 0.102028 - -0.163232 -2.13613 -0.307393 - -0.165772 -2.22188 -0.318901 - -0.117975 -2.12274 -0.115512 - -0.106147 -2.23957 -0.0664121 - -0.0425189 -0.420863 0.219026 - 0.0372518 -2.2057 0.541487 - 0.0873742 -2.19872 0.753925 - 0.125477 -2.26479 0.914798 - 0.127739 -2.26169 0.924411 - 0.144882 -2.2558 0.997099 - 0.148166 -2.17602 1.01171 - 0.0203061 -0.415906 0.485269 - 0.0324231 -0.410727 0.536656 - 0.0368982 -0.413197 0.555597 - 0.0490523 -0.381012 0.607376 - 0.106188 -0.591512 0.847636 - 0.211371 -0.971394 1.29001 - 0.23943 -0.96277 1.40897 - 0.233288 -0.755117 1.38476 - 0.241567 -0.596171 1.42122 - 0.247465 -0.52347 1.44685 - 0.379434 -0.689541 2.00458 - 0.388121 -0.685342 2.04142 - 0.431221 -0.634888 2.22448 - 0.434509 -0.600131 2.23871 - 0.435088 -0.591117 2.24125 - 0.43455 -0.580738 2.23906 - 0.433312 -0.550305 2.23408 - 0.432789 -0.39863 2.23318 - 0.434666 -0.381557 2.24128 - 0.43511 -0.197854 2.24476 - 0.433971 -0.124869 2.24057 - 0.43325 -0.106627 2.23768 - 0.433371 0.412947 2.24272 - 0.432689 0.497572 2.24056 - 0.432327 0.53556 2.23936 - 0.433009 0.978772 2.24611 - 0.432626 0.989094 2.24457 - 0.380488 1.28212 2.02621 - 0.305874 1.27768 1.71002 - 0.292987 1.28613 1.65549 - 0.280143 1.28121 1.60102 - 0.25687 1.28642 1.50245 - 0.240613 1.2709 1.43344 - 0.22412 1.27265 1.36357 - 0.184119 1.26941 1.19405 - 0.177323 1.27692 1.16532 - 0.166063 1.26834 1.11753 - 0.145172 1.27813 1.0291 - 0.137849 1.27695 0.99806 - 0.129424 1.2792 0.962379 - 0.124759 1.28286 0.942645 - 0.111277 1.28195 0.885513 - 0.0809065 1.27713 0.756785 - 0.0463751 1.16767 0.609517 - 0.0125024 1.16915 0.466005 --0.00897419 1.22292 0.375473 - -0.0209358 1.24921 0.325019 - -0.0363529 1.15962 0.258914 - -0.0491546 1.1617 0.204689 - -0.062754 1.2742 0.148045 - -0.0737563 1.16238 0.100453 - -0.0942867 1.16797 0.0135109 - -0.0955008 1.16797 0.00836657 - -0.0986497 1.18259 -0.0048485 - -0.109704 1.17997 -0.0517117 - -0.135493 1.2691 -0.160205 - -0.138026 1.26555 -0.17097 - -0.140702 1.26381 -0.182324 - -0.144793 1.26192 -0.199676 - -0.148426 1.27119 -0.214987 - -0.155003 1.26371 -0.242922 - -0.15632 1.15856 -0.249417 - -0.155876 1.10138 -0.248034 - -0.156128 1.07885 -0.249296 - -0.157188 1.06455 -0.253915 - -0.156852 1.04971 -0.252617 - -0.155573 0.932418 -0.24822 - -0.155713 0.843608 -0.249589 - -0.155558 0.772187 -0.249551 - -0.154492 0.671937 -0.245909 - -0.154335 0.664961 -0.245304 - -0.15445 0.608733 -0.246279 - -0.155622 0.578309 -0.251511 - -0.103247 -0.286586 -0.0500913 - -0.11163 -0.374572 -0.0881423 - -0.108012 -0.381802 -0.0721318 - -0.110668 -0.415345 -0.0842374 - -0.110611 -0.430506 -0.0841224 - -0.0981396 -0.423367 -0.0286414 - -0.0876446 -0.416165 0.0180582 - -0.0707478 -0.417363 0.093127 - -0.070603 -0.428075 0.0936728 - -0.069513 -0.43904 0.0984162 - -0.069518 -0.469192 0.0981195 - -0.0660733 -0.450729 0.113594 - -0.145443 -2.24388 -0.255415 - -0.104655 -2.21545 -0.0739142 - -0.0975825 -2.19253 -0.0422812 - -0.0826681 -2.19102 0.0240038 - -0.0763623 -2.19357 0.0519999 - -0.0429648 -0.432807 0.216438 - -0.037953 -0.437888 0.238662 --0.00320211 -2.28897 0.376213 - 0.00199672 -2.21602 0.399978 - 0.0112195 -2.15494 0.441515 - 0.0153426 -2.15295 0.459854 - 0.0407765 -2.21611 0.572293 - 0.0524356 -2.1326 0.62486 - 0.0634054 -2.23095 0.672707 - 0.0701856 -2.23262 0.70282 - 0.0989864 -2.25811 0.830562 - 0.105886 -2.25657 0.861235 - 0.125 -2.25917 0.94614 - 0.131101 -2.27637 0.973095 - 0.137386 -2.26335 1.00114 - 0.135151 -2.17543 0.992009 - 0.145576 -2.15876 1.03848 - 0.15497 -2.15692 1.08024 - 0.00275247 -0.379467 0.420066 - 0.0116219 -0.420371 0.459104 - 0.018061 -0.415599 0.487759 - 0.0246698 -0.40963 0.517179 - 0.0274169 -0.41162 0.529368 - 0.0304537 -0.411107 0.542866 - 0.0422301 -0.401971 0.595277 - 0.203062 -0.965798 1.30479 - 0.225444 -0.965549 1.40424 - 0.217644 -0.833618 1.37078 - 0.218997 -0.770592 1.37737 - 0.219068 -0.741934 1.37795 - 0.220202 -0.682139 1.38353 - 0.221035 -0.677464 1.38727 - 0.224518 -0.659041 1.40292 - 0.230213 -0.592123 1.42884 - 0.241235 -0.568907 1.47802 - 0.288813 -0.59588 1.68918 - 0.373082 -0.691906 2.06275 - 0.388252 -0.698071 2.13011 - 0.398899 -0.695843 2.17744 - 0.411471 -0.675879 2.23348 - 0.411938 -0.569058 2.23653 - 0.412067 -0.464395 2.23805 - 0.412235 -0.436364 2.23905 - 0.412372 -0.269996 2.24118 - 0.412609 -0.260994 2.24231 - 0.410832 -0.151317 2.23542 - 0.410517 -0.142205 2.2341 - 0.410615 -0.115237 2.23478 - 0.410923 -0.106317 2.23623 - 0.411237 -0.0614132 2.23804 - 0.412211 -0.0255174 2.24269 - 0.412208 -0.00750626 2.24284 - 0.411479 0.0194827 2.23985 - 0.411234 0.0824505 2.23933 - 0.411875 0.118683 2.24251 - 0.411595 0.136687 2.24143 - 0.411806 0.172995 2.2427 - 0.411066 0.554595 2.24289 - 0.410347 0.612129 2.24022 - 0.412777 0.715476 2.25196 - 0.410211 0.834997 2.24164 - 0.409626 1.06376 2.24113 - 0.409469 1.08638 2.24064 - 0.407653 1.28602 2.23438 - 0.266407 1.2839 1.60675 - 0.244134 1.27791 1.50772 - 0.178578 1.27325 1.21639 - 0.167872 1.27931 1.16887 - 0.13324 1.27763 1.01497 - 0.114829 1.27646 0.933156 - 0.111738 1.27746 0.919428 - 0.110299 1.27877 0.913047 - 0.0668902 1.27876 0.720162 - 0.0600521 1.28097 0.689798 - 0.0158248 1.16944 0.492261 - 0.0110644 1.16809 0.471096 - -0.0098026 1.20738 0.378733 - -0.022269 1.23325 0.323575 - -0.0566136 1.23553 0.170988 - -0.0737046 1.16477 0.0944005 - -0.0794983 1.16839 0.0686897 - -0.125193 1.27371 -0.133394 - -0.137011 1.27044 -0.185934 - -0.139434 1.26668 -0.196736 - -0.143741 1.26931 -0.215847 - -0.144952 1.26731 -0.221247 - -0.152612 1.21395 -0.255771 - -0.150455 0.960147 -0.248497 - -0.150902 0.934188 -0.250721 - -0.150458 0.911364 -0.248956 - -0.150899 0.905701 -0.250969 - -0.150378 0.865646 -0.249018 - -0.150969 0.804532 -0.252198 - -0.149686 0.743938 -0.247053 - -0.14887 0.71134 -0.243721 - -0.149233 0.694286 -0.24549 - -0.14869 0.553 -0.244365 - -0.0918257 -0.243063 -0.0107307 - -0.102193 -0.30321 -0.0597544 - -0.103223 -0.381882 -0.0653192 - -0.104502 -0.423338 -0.0716945 - -0.103721 -0.426002 -0.0680717 - -0.0988154 -0.41555 -0.045044 - -0.0949437 -0.427362 -0.0270637 - -0.0897744 -0.42786 -0.00291045 - -0.0880092 -0.425635 0.00536016 - -0.0857769 -0.457768 0.0154848 - -0.0853567 -0.458715 0.0174396 - -0.0849357 -0.459653 0.0193985 - -0.0781022 -0.43805 0.0515399 - -0.0752249 -0.448787 0.0648837 - -0.070308 -0.424328 0.0880954 - -0.0682843 -0.439997 0.0974032 - -0.0660879 -0.463734 0.107441 - -0.14102 -2.25756 -0.259883 - -0.060796 -0.499291 0.131832 - -0.0841416 -2.16623 0.00679778 - -0.0405636 -0.423996 0.227103 - -0.0397955 -0.421994 0.230712 - -0.0394141 -0.42098 0.232504 - 0.0167872 -2.15278 0.478597 - 0.0412322 -2.16204 0.592748 - 0.0560294 -2.22017 0.661344 - 0.0646182 -2.22285 0.701457 - 0.090082 -2.25403 0.820158 - 0.150777 -2.1603 1.1047 - 0.00194428 -0.441184 0.425591 - 0.00678475 -0.439993 0.448224 - 0.0125607 -0.415303 0.475453 - 0.0132008 -0.412234 0.478473 - 0.0135745 -0.411116 0.48023 - 0.0148546 -0.416752 0.486159 - 0.0214044 -0.412542 0.516808 - 0.0217779 -0.411252 0.518566 - 0.0376768 -0.405968 0.592917 - 0.0384718 -0.392692 0.596759 - 0.215084 -0.639799 1.41976 - 0.216866 -0.590822 1.42856 - 0.217393 -0.585462 1.43107 - 0.226052 -0.551741 1.47186 - 0.220064 -0.526583 1.44412 - 0.353797 -0.692251 2.06751 - 0.386981 -0.690576 2.2226 - 0.389183 -0.664441 2.23314 - 0.390813 -0.233398 2.24488 - 0.391188 -0.215397 2.2468 - 0.390585 -0.133625 2.24477 - 0.388395 -0.0701578 2.23514 - 0.387844 -0.0521737 2.23274 - 0.388831 0.028392 2.23812 - 0.390682 0.0645615 2.24712 - 0.387932 0.280902 2.23633 - 0.38993 0.291396 2.24577 - 0.38976 0.30968 2.24515 - 0.389455 0.318674 2.24381 - 0.388287 0.345452 2.23861 - 0.388633 0.364245 2.24041 - 0.390058 0.412164 2.24752 - 0.389692 0.487403 2.24653 - 0.389962 0.603692 2.24891 - 0.388802 0.70127 2.24442 - 0.388175 1.04077 2.24473 - 0.388565 1.13423 2.24744 - 0.38731 1.20249 2.24223 - 0.385953 1.2723 2.23656 - 0.339141 1.2827 2.01789 - 0.299357 1.28238 1.83196 - 0.293604 1.27217 1.80498 - 0.27165 1.27719 1.70243 - 0.233187 1.27913 1.5227 - 0.195599 1.28255 1.34708 - 0.171025 1.27975 1.23221 - 0.143108 1.27607 1.10171 - 0.13328 1.27896 1.0558 - 0.122376 1.28376 1.00489 - 0.113834 1.2792 0.964929 - 0.082705 1.28205 0.819482 - 0.0813551 1.28286 0.813181 - 0.0753004 1.27846 0.784844 - 0.0698762 1.27989 0.759509 - 0.0586727 1.27562 0.70711 - 0.0539825 1.28396 0.685271 - 0.0414014 1.16247 0.625314 - 0.0382 1.16767 0.610403 - 0.0265818 1.25401 0.556933 - 0.0203134 1.20303 0.527151 - 0.00812193 1.16124 0.469778 --0.00697717 1.16914 0.399291 - -0.0123592 1.26726 0.375076 - -0.0168644 1.27664 0.354112 - -0.0272761 1.1885 0.304612 - -0.028458 1.17985 0.299006 - -0.0296043 1.17316 0.293586 - -0.0677964 1.25264 0.115862 - -0.072801 1.18065 0.0917855 - -0.075705 1.16781 0.0780915 - -0.0940984 1.16195 -0.00792256 - -0.102233 1.19024 -0.0456659 - -0.106239 1.17933 -0.0644929 - -0.145723 1.16438 -0.249156 - -0.146272 1.04338 -0.25288 - -0.146564 0.969945 -0.254946 - -0.145612 0.903066 -0.251136 - -0.143774 0.810927 -0.243424 - -0.144309 0.694286 -0.24704 - -0.144366 0.629033 -0.247932 - -0.14305 0.59938 -0.242067 - -0.144192 0.569949 -0.247682 - -0.106345 -0.360069 -0.100638 - -0.101784 -0.340848 -0.0776796 - -0.0998486 -0.384239 -0.0684629 - -0.100176 -0.427631 -0.0705396 - -0.0922405 -0.423367 -0.0308897 - -0.0865798 -0.429766 -0.00270261 - -0.0830994 -0.457768 0.0143823 - -0.0827048 -0.458715 0.0163424 - -0.0759026 -0.432643 0.0505568 - -0.0713111 -0.434252 0.0734564 - -0.145355 -2.1802 -0.313862 - -0.14348 -2.18259 -0.30453 - -0.140952 -2.21447 -0.292237 - -0.120049 -2.29915 -0.188777 - -0.10919 -2.14878 -0.133049 - -0.0929365 -2.17841 -0.05223 - -0.0421068 -0.423905 0.219318 - -0.0387916 -0.431928 0.235782 --0.00674076 -2.29895 0.376738 - -0.0033197 -2.26662 0.394142 - 0.00976802 -2.15693 0.460578 - 0.0134347 -2.15378 0.47891 - 0.0211452 -2.16086 0.51732 - 0.0661989 -2.21989 0.741579 - 0.0950288 -2.25849 0.885073 - 0.102073 -2.26957 0.92012 - 0.132918 -2.16257 1.07515 - 0.175062 -2.16048 1.28551 --0.00232271 -0.364516 0.418481 - 0.00217088 -0.394369 0.440605 - 0.00861702 -0.418349 0.472533 - 0.0125475 -0.414107 0.492192 - 0.0165827 -0.417185 0.5123 - 0.0197526 -0.412959 0.528164 - 0.0249856 -0.413876 0.554272 - 0.0323783 -0.410689 0.591201 - 0.0323643 -0.383138 0.591412 - 0.0336541 -0.376613 0.597915 - 0.188344 -0.979327 1.36382 - 0.192648 -0.971704 1.38538 - 0.198073 -0.985508 1.41232 - 0.192817 -0.930257 1.38665 - 0.18994 -0.886511 1.37273 - 0.190213 -0.879605 1.37417 - 0.18947 -0.845562 1.3708 - 0.190125 -0.787611 1.37467 - 0.190281 -0.76621 1.37566 - 0.192599 -0.688806 1.38802 - 0.19454 -0.667077 1.39792 - 0.203015 -0.569315 1.44122 - 0.21005 -0.552538 1.4765 - 0.328905 -0.690869 2.06829 - 0.362698 -0.61525 2.23772 - 0.364004 -0.588093 2.24451 - 0.362683 -0.566926 2.23813 - 0.361892 -0.546691 2.23439 - 0.361914 -0.508725 2.23489 - 0.362353 -0.49038 2.23727 - 0.362577 -0.406443 2.23924 - 0.362904 -0.397489 2.24096 - 0.364395 -0.334132 2.24905 - 0.364917 -0.316134 2.25183 - 0.362398 -0.241341 2.24003 - 0.360982 -0.034238 2.23507 - 0.361731 0.0104393 2.23926 - 0.362484 0.055313 2.24348 - 0.362372 0.136224 2.24374 - 0.361102 0.262342 2.23868 - 0.36034 0.289157 2.23515 - 0.361586 0.523584 2.24376 - 0.3619 0.710582 2.24723 - 0.360295 0.789182 2.24002 - 0.360327 0.799578 2.24028 - 0.360904 0.831994 2.24349 - 0.360692 0.852579 2.24265 - 0.361399 0.939945 2.24706 - 0.360684 1.09536 2.24508 - 0.361599 1.1566 2.25027 - 0.321873 1.28086 2.05326 - 0.310061 1.2864 1.99437 - 0.239814 1.27858 1.64369 - 0.232 1.2765 1.60467 - 0.227492 1.27782 1.58219 - 0.225102 1.27769 1.57026 - 0.193741 1.27536 1.41371 - 0.143384 1.27709 1.1624 - 0.124881 1.27402 1.07003 - 0.121569 1.28514 1.05361 - 0.0975133 1.28571 0.933554 - 0.0812215 1.27753 0.852159 - 0.0668175 1.28093 0.780305 - 0.0514799 1.28149 0.703762 - 0.00701524 1.16295 0.480636 --0.00214308 1.16821 0.434981 --0.00330687 1.16419 0.429132 - -0.010525 1.24465 0.393926 - -0.0416342 1.16296 0.237831 - -0.0446132 1.15898 0.222923 - -0.0748452 1.16712 0.0721201 - -0.0766302 1.15876 0.0631261 - -0.0821672 1.17156 0.0356219 - -0.0901202 1.163 -0.00415789 - -0.102112 1.17158 -0.0639224 - -0.110269 1.22067 -0.104131 - -0.133271 1.26743 -0.218457 - -0.139325 1.07067 -0.250673 - -0.138324 0.816081 -0.248272 - -0.137955 0.616119 -0.248463 - -0.136869 0.557975 -0.243635 - -0.136556 0.532485 -0.242336 - -0.13748 0.506024 -0.247214 - -0.0841036 -0.236968 -0.00072816 - -0.0839087 -0.23798 0.00028951 - -0.0837129 -0.238988 0.00131153 - -0.0837708 -0.241437 0.00097948 - -0.0953208 -0.320928 -0.0608091 - -0.0941941 -0.356141 -0.055243 - -0.0966546 -0.390028 -0.068588 - -0.0943853 -0.422162 -0.0569607 - -0.0872666 -0.4321 -0.019511 - -0.0807172 -0.45506 0.0147955 - -0.0799575 -0.451477 0.018842 - -0.0795885 -0.4524 0.0207791 - -0.0683584 -0.430613 0.0802601 - -0.0652287 -0.4517 0.0965451 - -0.0600957 -0.514075 0.122956 - -0.0900722 -2.17742 -0.0530559 - -0.0385353 -0.442887 0.237468 - -0.0196599 -2.29416 0.317169 - 0.0158165 -2.14429 0.505943 - 0.0665726 -2.22157 0.77289 - 0.0944853 -2.26479 0.919687 - 0.104601 -2.26404 0.973063 - 0.110099 -2.16541 1.00313 - 0.00247772 -0.48091 0.453434 --0.00325918 -0.368078 0.42438 - 0.00428462 -0.423688 0.463582 - 0.00496733 -0.421576 0.467206 - 0.00555018 -0.418572 0.470313 - 0.0104593 -0.416271 0.496238 - 0.0174397 -0.419387 0.533031 - 0.0185634 -0.416078 0.538995 - 0.0247559 -0.420301 0.57162 - 0.0280512 -0.411556 0.589099 - 0.0282301 -0.381701 0.590363 - 0.0330808 -0.38108 0.615961 - 0.164685 -0.967953 1.30397 - 0.167723 -0.973704 1.31993 - 0.174053 -0.977235 1.35329 - 0.181073 -0.974246 1.39036 - 0.180639 -0.682638 1.3912 - 0.182045 -0.673261 1.39872 - 0.182783 -0.661865 1.40274 - 0.186168 -0.604607 1.42121 - 0.197427 -0.566877 1.48102 - 0.280709 -0.676775 1.91921 - 0.34009 -0.593432 2.23339 - 0.340633 -0.527316 2.23696 - 0.34104 -0.518387 2.2392 - 0.340178 -0.432842 2.23557 - 0.341024 -0.387413 2.24053 - 0.341082 -0.286598 2.24192 - 0.338354 -0.266491 2.22774 - 0.340318 0.0014887 2.24098 - 0.339581 0.0908189 2.23805 - 0.3399 0.126759 2.24012 - 0.33981 0.271286 2.2412 - 0.339314 0.371788 2.23966 - 0.34062 0.601167 2.24901 - 0.339879 0.780223 2.24703 - 0.338561 0.798125 2.24027 - 0.3064 1.28231 2.07579 - 0.295175 1.28835 2.01663 - 0.233962 1.28702 1.69368 - 0.208624 1.27679 1.55989 - 0.20201 1.27635 1.52499 - 0.172845 1.27117 1.37107 - 0.16989 1.27607 1.35553 - 0.166448 1.27779 1.33739 - 0.146525 1.27507 1.23225 - 0.13504 1.27612 1.17167 - 0.129613 1.27163 1.14299 - 0.12279 1.27934 1.10708 - 0.119222 1.28763 1.08834 - 0.113015 1.27395 1.05545 - 0.106791 1.28355 1.02272 - 0.0896259 1.28134 0.932132 - 0.0850805 1.27654 0.908101 - 0.0770423 1.2755 0.865682 - 0.0759172 1.27742 0.859767 - 0.074629 1.27753 0.852972 - 0.0735843 1.28029 0.84749 - 0.0711724 1.28214 0.834785 - 0.063062 1.27597 0.79193 - 0.0609746 1.28093 0.780971 - 0.056908 1.27621 0.759466 - 0.041631 1.28033 0.678912 - 0.0186676 1.18887 0.556781 - 0.00148907 1.1672 0.465918 --0.00952423 1.19506 0.408114 - -0.0107523 1.26767 0.402415 - -0.0117382 1.27041 0.397243 - -0.040873 1.16191 0.242369 - -0.0536025 1.20581 0.175683 - -0.0594668 1.27221 0.145457 - -0.0665888 1.26406 0.107796 - -0.0771742 1.16712 0.0509087 - -0.0781831 1.1683 0.0455986 - -0.0888817 1.16586 -0.0108704 - -0.130179 1.272 -0.227606 - -0.135167 1.25972 -0.254052 - -0.134135 1.13068 -0.249993 - -0.132926 0.852596 -0.246602 - -0.133034 0.655593 -0.249286 - -0.132896 0.637244 -0.248754 - -0.13262 0.607734 -0.247618 - -0.131427 0.535321 -0.2421 - -0.131905 0.528906 -0.244691 - -0.0810457 -0.24099 0.00250776 - -0.0945934 -0.404592 -0.0751569 - -0.0944829 -0.411265 -0.0746142 - -0.0920672 -0.42711 -0.0612776 - -0.0892641 -0.431654 -0.0456451 - -0.0772918 -0.455131 0.0210778 - -0.0747031 -0.437729 0.0357604 - -0.0738218 -0.436658 0.0407039 - -0.0689904 -0.446471 0.067626 - -0.0680713 -0.43776 0.072868 - -0.0669462 -0.437884 0.0791616 - -0.0637106 -0.505861 0.0964933 - -0.0884482 -2.15633 -0.0606859 - -0.0709333 -2.22564 0.0365291 - -0.0592891 -2.27343 0.10114 - -0.0423862 -0.414865 0.216846 - 0.00055147 -2.20066 0.436799 - 0.003372 -2.17187 0.452908 - 0.00493062 -2.16587 0.461697 - 0.0550459 -2.17384 0.742022 - 0.0680254 -2.25858 0.813684 - 0.0766925 -2.246 0.862323 - 0.0802291 -2.24219 0.882155 - 0.092339 -2.25537 0.949765 - 0.104866 -2.18164 1.02069 --0.00619574 -0.375063 0.419799 - 0.00035638 -0.414266 0.456015 - 0.0136293 -0.419127 0.530227 - 0.0173642 -0.416764 0.551152 - 0.0183314 -0.416215 0.556571 - 0.0194339 -0.420188 0.562694 - 0.0307632 -0.387644 0.626456 - 0.163998 -0.97739 1.36526 - 0.167843 -0.927783 1.38733 - 0.164356 -0.87239 1.36845 - 0.164587 -0.865529 1.36982 - 0.16573 -0.816496 1.37677 - 0.165718 -0.74331 1.37754 - 0.17077 -0.642843 1.40695 - 0.173301 -0.630328 1.42125 - 0.179007 -0.566809 1.4539 - 0.178314 -0.53279 1.45041 - 0.295377 -0.692231 2.10361 - 0.317889 -0.639926 2.23017 - 0.319325 -0.593991 2.23873 - 0.317888 -0.562927 2.23104 - 0.318021 -0.54411 2.232 - 0.317708 -0.496472 2.23079 - 0.318422 -0.478692 2.23499 - 0.318733 -0.441755 2.23714 - 0.317128 -0.230361 2.23057 - 0.318813 -0.15051 2.2409 - 0.317941 -0.132266 2.23623 - 0.318849 -0.0789171 2.24192 - 0.316598 0.152809 2.23196 - 0.318874 0.381816 2.2473 - 0.319206 0.610706 2.25176 - 0.316868 0.786669 2.24067 - 0.317402 0.839815 2.24427 - 0.317396 0.914204 2.24508 - 0.317215 1.09207 2.24609 - 0.317014 1.24654 2.24672 - 0.313062 1.28215 2.22501 - 0.289393 1.27969 2.09254 - 0.221837 1.28042 1.71455 - 0.198088 1.27307 1.58158 - 0.188082 1.27496 1.52562 - 0.125483 1.27931 1.1754 - 0.120451 1.27567 1.14721 - 0.110626 1.27968 1.09228 - 0.098563 1.28525 1.02484 - 0.0657939 1.28033 0.841428 - 0.0550275 1.28001 0.781182 - 0.0476478 1.27392 0.739821 - 0.0456164 1.27748 0.728495 - 0.0380998 1.28302 0.686499 - 0.0194068 1.17556 0.580683 - 0.00268348 1.16767 0.48702 --0.00105263 1.16818 0.46612 --0.00876648 1.19158 0.423224 - -0.0275234 1.17643 0.3181 - -0.0284602 1.17382 0.312828 - -0.0357293 1.16613 0.272067 - -0.0375239 1.16548 0.262018 - -0.0671225 1.252 0.0973858 - -0.0752838 1.16317 0.0507102 - -0.08092 1.16692 0.019216 - -0.0818136 1.16598 0.0142055 - -0.0890133 1.15965 -0.0261517 - -0.093032 1.16567 -0.0485694 - -0.12827 1.13187 -0.246125 - -0.129438 1.09498 -0.253079 - -0.128681 1.01505 -0.24975 - -0.128672 1.00392 -0.249826 - -0.127512 0.864649 -0.244923 - -0.127641 0.727631 -0.247201 - -0.126712 0.662708 -0.242738 - -0.127136 0.515985 -0.246779 - -0.0891355 -0.297637 -0.0611936 - -0.0813324 -0.269617 -0.0143213 - -0.0815718 -0.273656 -0.0157976 - -0.0935238 -0.378032 -0.0883354 - -0.0929707 -0.380806 -0.0850708 - -0.0856118 -0.432364 -0.0418093 - -0.0801223 -0.427696 -0.00901641 - -0.0764916 -0.426949 0.0126438 - -0.0737061 -0.451436 0.0289592 - -0.0689082 -0.441896 0.0576866 - -0.0685876 -0.44264 0.0595896 - -0.0671909 -0.443651 0.0679068 - -0.0632024 -0.442273 0.0917086 - -0.0631599 -0.448606 0.0918851 - -0.0632901 -0.474364 0.0907971 - -0.0618604 -0.502562 0.0989822 - -0.122226 -2.23947 -0.282009 - -0.118982 -2.24388 -0.262718 - -0.0594969 -0.534629 0.112689 - -0.107468 -2.25405 -0.194178 - -0.0868487 -2.14811 -0.0699349 - -0.0825816 -2.17269 -0.0447857 - -0.0691863 -2.24357 0.0342397 - -0.0423523 -0.415864 0.216367 - -0.0420506 -0.414907 0.218178 - -0.0417495 -0.412941 0.219997 - -0.0218337 -2.28017 0.316183 - 0.0281199 -2.12354 0.615974 - 0.0436901 -2.23946 0.707425 - 0.046949 -2.23609 0.7269 - 0.0645448 -2.24557 0.831718 - 0.0734762 -2.2489 0.884939 - 0.0926582 -2.27056 0.999069 - 0.100262 -2.18761 1.04542 --0.00837235 -0.446466 0.418635 --0.00585894 -0.382976 0.434392 --0.00047875 -0.415328 0.466085 - 0.00606148 -0.417629 0.50506 - 0.0106019 -0.414023 0.53218 - 0.0134008 -0.413624 0.548876 - 0.0157438 -0.416375 0.562815 - 0.137254 -0.969447 1.28075 - 0.15519 -0.910734 1.38842 - 0.153226 -0.728849 1.37891 - 0.167787 -0.559161 1.46779 - 0.163567 -0.516136 1.44315 - 0.2255 -0.639526 1.81099 - 0.259245 -0.693201 2.01158 - 0.296478 -0.496946 2.23599 - 0.29633 -0.132266 2.23952 - 0.297066 -0.123602 2.24401 - 0.295364 0.324675 2.23929 - 0.295266 0.407465 2.2397 - 0.29564 0.588041 2.24412 - 0.29506 0.606435 2.24088 - 0.294601 0.615339 2.23825 - 0.296006 0.697082 2.24762 - 0.296017 0.809257 2.24904 - 0.295412 0.818194 2.24554 - 0.294953 0.827491 2.24292 - 0.29588 0.882556 2.24911 - 0.292404 1.28535 2.23325 - 0.278973 1.28223 2.15312 - 0.249966 1.28138 1.98013 - 0.166521 1.27442 1.48242 - 0.14188 1.27179 1.33544 - 0.135305 1.28225 1.29636 - 0.13145 1.27705 1.27331 - 0.112119 1.27721 1.15803 - 0.0946337 1.28012 1.05379 - 0.0743644 1.2796 0.932908 - 0.0701787 1.27303 0.907867 - 0.058065 1.28124 0.835727 - 0.0368095 1.27469 0.708891 - 0.0329379 1.2802 0.685869 - -0.0046574 1.1653 0.460281 - -0.0104312 1.24771 0.426846 - -0.0203528 1.25796 0.367803 - -0.033786 1.16145 0.286527 - -0.0489213 1.16757 0.196342 - -0.049792 1.17142 0.191196 - -0.0506369 1.17125 0.186155 - -0.054251 1.19232 0.164858 - -0.0677341 1.25676 0.0852312 - -0.0885105 1.16905 -0.0397291 - -0.091784 1.1622 -0.0593338 - -0.0926624 1.16189 -0.0645759 - -0.0998792 1.21874 -0.106926 - -0.123935 1.22687 -0.250286 - -0.124236 1.15885 -0.252903 - -0.122687 1.08521 -0.244553 - -0.122613 0.920367 -0.246104 - -0.122626 0.823748 -0.247354 - -0.121677 0.732651 -0.242796 - -0.122165 0.723463 -0.245817 - -0.121652 0.621641 -0.243991 - -0.122168 0.582998 -0.247532 - -0.122998 0.578775 -0.252533 - -0.121783 0.541146 -0.24574 - -0.121349 0.506599 -0.24357 - -0.0863351 -0.401822 -0.0642275 - -0.0770014 -0.418968 -0.00501205 - -0.0686662 -0.426324 0.0479713 - -0.0683758 -0.427108 0.0498105 - -0.0665118 -0.441504 0.061495 - -0.0624142 -0.426516 0.0877815 - -0.0520629 -0.442895 0.153487 - -0.0872475 -2.16914 -0.0928219 - -0.0781033 -2.15898 -0.0344611 - -0.0642131 -2.24518 0.0528801 - -0.0396915 -0.436957 0.232345 - -0.0229043 -2.27118 0.315599 - -0.0132397 -2.30494 0.376707 - 0.0369453 -2.23667 0.697165 - 0.0459385 -2.22245 0.754617 - 0.0971482 -2.16628 1.08144 --0.00283577 -0.421576 0.46724 - 0.00069772 -0.421824 0.489738 - 0.00091987 -0.416119 0.491226 - 0.00147697 -0.413764 0.494804 - 0.00375945 -0.412258 0.509358 - 0.00568984 -0.414496 0.521622 - 0.00615314 -0.414806 0.524568 - 0.0119058 -0.417858 0.561162 - 0.0134466 -0.418765 0.570962 - 0.0171506 -0.409809 0.594665 - 0.0190762 -0.37513 0.607374 - 0.123737 -0.963301 1.26627 - 0.133815 -0.970154 1.33036 - 0.141905 -0.980042 1.38175 - 0.140925 -0.892205 1.37664 - 0.140145 -0.880464 1.37182 - 0.139746 -0.855108 1.36961 - 0.140459 -0.783142 1.37507 - 0.141218 -0.764567 1.38015 - 0.14282 -0.673004 1.39153 - 0.147369 -0.641827 1.4209 - 0.274311 -0.686407 2.22869 - 0.274837 -0.638726 2.23266 - 0.275104 -0.600634 2.23485 - 0.274444 -0.589803 2.23078 - 0.274823 -0.580945 2.23331 - 0.275045 -0.571804 2.23485 - 0.274962 -0.562128 2.23444 - 0.27442 -0.551679 2.23113 - 0.275521 -0.506313 2.23872 - 0.274513 -0.365976 2.23411 - 0.274661 -0.18555 2.23738 - 0.274958 -0.15889 2.23961 - 0.275045 -0.149996 2.24028 - 0.273889 -0.0961112 2.23362 - 0.274256 0.0993069 2.23847 - 0.272892 0.125524 2.23012 - 0.272829 0.143288 2.22995 - 0.273713 0.224328 2.23662 - 0.274156 0.23366 2.23957 - 0.273977 0.242549 2.23854 - 0.273999 0.333413 2.23985 - 0.274873 0.352715 2.24567 - 0.273925 0.379254 2.23997 - 0.273653 0.453189 2.23919 - 0.274309 0.482345 2.24375 - 0.274112 0.491484 2.24261 - 0.274199 0.596959 2.24453 - 0.27496 0.608143 2.24951 - 0.274532 0.626868 2.24703 - 0.274163 0.705362 2.24569 - 0.273737 0.965955 2.24634 - 0.27405 1.00009 2.24877 - 0.273614 1.02105 2.24627 - 0.273728 1.03266 2.24714 - 0.272508 1.06258 2.23976 - 0.25788 1.29018 2.14954 - 0.246163 1.27555 2.07474 - 0.223438 1.28944 1.93021 - 0.187992 1.2792 1.70436 - 0.181072 1.27425 1.66022 - 0.1427 1.28135 1.41596 - 0.135462 1.27549 1.36979 - 0.133564 1.27309 1.35768 - 0.105352 1.26793 1.17796 - 0.10274 1.28043 1.16149 - 0.101864 1.28454 1.15596 - 0.0966557 1.27312 1.12265 - 0.0912482 1.28267 1.08834 - 0.089691 1.27983 1.07838 - 0.0786137 1.2795 1.00784 - 0.0494731 1.28024 0.822282 - 0.0433033 1.28184 0.783013 - 0.0392778 1.28317 0.757396 - 0.0269274 1.27656 0.678663 - 0.0158248 1.16841 0.606568 - 0.01503 1.17007 0.601529 - 0.0142342 1.17172 0.596482 - 0.0134373 1.17334 0.591428 - -0.0119368 1.27535 0.431161 - -0.017231 1.27537 0.397448 - -0.0201135 1.26064 0.378903 - -0.0262714 1.1846 0.338709 - -0.0344927 1.15845 0.286019 - -0.0407669 1.16983 0.246211 - -0.0586694 1.26145 0.13339 - -0.064028 1.27247 0.0994083 - -0.0664103 1.26074 0.0840865 - -0.067757 1.24255 0.0752765 - -0.0807318 1.16594 -0.00833476 - -0.0905285 1.16156 -0.0707759 - -0.106087 1.26624 -0.168503 - -0.115825 1.26919 -0.230476 - -0.119437 1.20313 -0.254327 - -0.119215 1.17112 -0.253329 - -0.118268 0.966177 -0.249937 - -0.118322 0.880757 -0.251384 - -0.118161 0.819918 -0.251145 - -0.117241 0.76459 -0.245996 - -0.11694 0.68737 -0.245076 - -0.117309 0.684461 -0.247468 - -0.117585 0.680728 -0.249273 - -0.117307 0.603823 -0.248493 - -0.116947 0.565206 -0.246696 - -0.0640661 -0.174066 0.0698124 - -0.0637303 -0.176117 0.0720796 - -0.0860002 -0.372524 -0.0828651 - -0.0834357 -0.422077 -0.0660199 - -0.0823163 -0.430909 -0.0584898 - -0.0797756 -0.4327 -0.041147 - -0.0721452 -0.426949 0.0110919 - -0.071601 -0.428828 0.0147861 - -0.0676783 -0.434723 0.041519 - -0.0659091 -0.437595 0.0535732 - -0.0642336 -0.442006 0.0649653 - -0.0620579 -0.429372 0.0800129 - -0.101937 -2.26103 -0.217897 - -0.0810469 -2.16296 -0.0737444 - -0.0750164 -2.22367 -0.03336 - -0.0736094 -2.22479 -0.0237575 - -0.0693848 -2.22789 0.00507784 - -0.0033499 -2.20866 0.456741 - 0.0311208 -2.25733 0.691701 - 0.0448117 -2.223 0.785763 - 0.0730324 -2.26783 0.978053 - -0.0129606 -0.434633 0.415556 - 0.117302 -2.16158 1.28214 - 0.118523 -2.15511 1.29058 - -0.0127322 -0.364516 0.418086 --0.00266714 -0.412227 0.486229 --0.00092295 -0.418779 0.498062 - -0.0003881 -0.412657 0.501802 - 0.00139364 -0.418828 0.513897 - 0.00165524 -0.417554 0.515702 - 0.00269338 -0.41238 0.52287 - 0.00992578 -0.416473 0.572253 - 0.0124662 -0.407719 0.589739 - 0.117915 -0.970063 1.30279 - 0.125239 -0.971395 1.35284 - 0.127838 -0.848277 1.3723 - 0.129876 -0.69092 1.38841 - 0.138933 -0.570151 1.45199 - 0.228066 -0.691363 2.0596 - 0.239712 -0.692675 2.13919 - 0.251879 -0.634826 2.22316 - 0.252121 -0.625717 2.22494 - 0.253381 -0.580395 2.23418 - 0.253087 -0.560795 2.23245 - 0.253151 -0.513724 2.23354 - 0.253613 -0.495761 2.23694 - 0.253913 -0.366685 2.24078 - 0.253276 -0.212283 2.23855 - 0.25344 -0.158734 2.24041 - 0.252942 -0.149556 2.23714 - 0.252579 -0.0960639 2.23539 - 0.25167 -0.0692351 2.22955 - 0.252466 0.0813309 2.23707 - 0.251618 0.125462 2.23189 - 0.25265 0.170573 2.23956 - 0.252947 0.224657 2.24234 - 0.252694 0.260566 2.24111 - 0.253177 0.27914 2.24467 - 0.252852 0.491484 2.24538 - 0.251667 0.85611 2.24231 - 0.251993 0.878207 2.24485 - 0.250788 0.993509 2.2382 - 0.251461 1.16809 2.24522 - 0.251427 1.1919 2.24531 - 0.248624 1.29045 2.22751 - 0.223483 1.2844 2.05558 - 0.216671 1.27507 2.00888 - 0.195204 1.28196 1.86223 - 0.170593 1.27983 1.69397 - 0.165757 1.28455 1.66098 - 0.161129 1.2784 1.62925 - 0.118746 1.27329 1.33947 - 0.11499 1.27729 1.31385 - 0.108158 1.2778 1.26715 - 0.100324 1.27888 1.21362 - 0.0738335 1.28086 1.03256 - 0.067747 1.27523 0.990877 - 0.0656131 1.27591 0.9763 - 0.0408676 1.27546 0.80714 - 0.0317336 1.28318 0.744809 - 0.00630511 1.15412 0.569203 --0.00042007 1.16393 0.523367 --0.00260431 1.16873 0.508503 --0.00366294 1.16024 0.501149 - -0.0336188 1.17286 0.296553 - -0.0366488 1.15893 0.275648 - -0.0410457 1.15684 0.245563 - -0.0556329 1.21633 0.146671 - -0.0619072 1.27003 0.104523 - -0.0711259 1.18212 0.0402922 - -0.0737477 1.16586 0.022145 - -0.0744264 1.16298 0.0174662 - -0.0789684 1.16195 -0.0135962 - -0.0881609 1.15926 -0.0764708 - -0.110238 1.27025 -0.225849 - -0.11358 1.20339 -0.249622 - -0.114268 1.04462 -0.256516 - -0.113185 0.995821 -0.249784 - -0.113025 0.98293 -0.24887 - -0.113513 0.831519 -0.254302 - -0.112453 0.811305 -0.247335 - -0.112618 0.782373 -0.248858 - -0.113371 0.768412 -0.254197 - -0.111925 0.655765 -0.245875 - -0.112486 0.56387 -0.250978 - -0.111589 0.551918 -0.245008 - -0.111739 0.548326 -0.246088 - -0.111456 0.522988 -0.244502 - -0.0705775 -0.240729 0.00924723 - -0.0820609 -0.367728 -0.0770327 - -0.0792366 -0.351476 -0.0560345 - -0.0784503 -0.414721 -0.051194 - -0.0757207 -0.419411 -0.0312031 - -0.0753341 -0.418832 -0.028353 - -0.0715559 -0.421118 -0.00061972 - -0.07112 -0.419467 0.00260867 - -0.0693655 -0.426142 0.0154038 - -0.0623264 -0.440831 0.0669185 - -0.0612451 -0.436279 0.074933 - -0.0599391 -0.4259 0.0846857 - -0.0587213 -0.444409 0.0933609 - -0.0583453 -0.510309 0.0951472 - -0.0581373 -0.513786 0.0966242 - -0.111228 -2.20782 -0.31869 - -0.105083 -2.23292 -0.273896 - -0.0409961 -0.415996 0.224052 - -0.0222089 -2.2683 0.334648 --0.00670883 -2.22956 0.449138 - 0.0160035 -2.12846 0.617559 - 0.0480672 -2.27178 0.851081 - 0.0653408 -2.26594 0.978117 - 0.0850348 -2.16005 1.12443 - -0.0146228 -0.42481 0.417748 - -0.006302 -0.416754 0.47902 --0.00589064 -0.413659 0.482089 --0.00564987 -0.412525 0.483875 - -0.0024296 -0.41722 0.507472 --0.00155235 -0.418828 0.513896 - 0.00136184 -0.418027 0.535325 - 0.00282151 -0.41347 0.54612 - 0.0040707 -0.41767 0.555239 - 0.00514291 -0.416375 0.563138 - 0.00665918 -0.41877 0.574246 - 0.00887661 -0.384751 0.591047 - 0.00843323 -0.378106 0.587887 - 0.0105611 -0.380853 0.603485 - 0.0112189 -0.375828 0.608394 - 0.10675 -0.968067 1.3017 - 0.116731 -0.980618 1.37487 - 0.119397 -0.962751 1.39473 - 0.119556 -0.938514 1.39626 - 0.117046 -0.891597 1.3785 - 0.119172 -0.654602 1.39765 - 0.122645 -0.601933 1.42395 - 0.122033 -0.573856 1.41987 - 0.233033 -0.561062 2.23584 - 0.232078 -0.540238 2.22913 - 0.232098 -0.391977 2.23147 - 0.232883 -0.338357 2.23804 - 0.232928 -0.329332 2.2385 - 0.232952 -0.239122 2.24002 - 0.232252 -0.184915 2.23568 - 0.232341 -0.176061 2.23646 - 0.232458 -0.104975 2.23838 - 0.232509 -0.0251341 2.23994 - 0.232565 0.0192275 2.24101 - 0.232003 0.0546404 2.23741 - 0.231951 0.0634985 2.23715 - 0.231763 0.090065 2.23616 - 0.232873 0.11719 2.24472 - 0.232515 0.125956 2.24222 - 0.232286 0.134769 2.24067 - 0.231838 0.161296 2.23777 - 0.23186 0.224 2.23886 - 0.231087 0.259296 2.23371 - 0.230915 0.268136 2.23257 - 0.23207 0.278326 2.24121 - 0.23183 0.29621 2.23971 - 0.232348 0.333252 2.24407 - 0.231765 0.387581 2.24059 - 0.231755 0.452537 2.24148 - 0.231731 0.461852 2.24144 - 0.232995 0.627161 2.25319 - 0.231509 0.742978 2.24398 - 0.230661 1.00503 2.24163 - 0.230702 1.07286 2.24294 - 0.228935 1.24293 2.23248 - 0.22725 1.28453 2.22072 - 0.182595 1.28081 1.89247 - 0.176283 1.2793 1.84606 - 0.143965 1.2691 1.6084 - 0.133601 1.27496 1.53231 - 0.116451 1.27927 1.40634 - 0.0901154 1.27651 1.21274 - 0.0709253 1.27942 1.07175 - 0.0542042 1.27852 0.948849 - 0.0339541 1.27345 0.799949 - 0.0249501 1.2877 0.733987 - 0.00492657 1.17016 0.585083 - -0.0124922 1.27152 0.45857 - -0.0131547 1.27647 0.453774 - -0.0155168 1.27443 0.436384 - -0.0177921 1.27611 0.419687 - -0.0330622 1.16421 0.305801 - -0.0565052 1.23054 0.134494 - -0.0583744 1.26157 0.121217 - -0.0591846 1.26608 0.115329 - -0.065216 1.26637 0.0710072 - -0.068482 1.20844 0.0461448 - -0.0775446 1.1687 -0.0210493 - -0.0782297 1.1676 -0.0261001 - -0.0796294 1.16631 -0.0364064 - -0.0966879 1.2716 -0.160214 - -0.100707 1.26944 -0.189786 - -0.103299 1.2714 -0.208801 - -0.105716 1.26931 -0.226596 - -0.107393 1.26903 -0.238929 - -0.108494 1.12727 -0.24912 - -0.108283 1.07307 -0.248372 - -0.108956 1.05975 -0.253521 - -0.108992 1.04855 -0.253946 - -0.107429 0.815113 -0.245925 - -0.106895 0.670117 -0.244149 - -0.10666 0.632646 -0.242983 - -0.106475 0.538724 -0.243014 - -0.106887 0.523727 -0.246262 - -0.106578 0.507945 -0.244227 - -0.0669578 -0.24348 0.0191097 - -0.0781034 -0.425688 -0.0729558 - -0.0673596 -0.429723 0.0128952 - -0.0646478 -0.448509 0.0342776 - -0.0629904 -0.43791 0.0477022 - -0.0615514 -0.44244 0.0591365 - -0.0576364 -0.460331 0.0901557 - -0.099854 -2.2378 -0.276098 - -0.0741261 -2.19102 -0.0696035 - -0.0602654 -2.25735 0.040168 --0.00917568 -2.23055 0.449152 --0.00344744 -2.20821 0.49532 - 0.00695778 -2.12913 0.579803 - 0.0120418 -2.14222 0.620247 - 0.0189702 -2.26626 0.673653 - 0.0464123 -2.26807 0.893071 - 0.0475204 -2.26224 0.902026 - 0.0487139 -2.22564 0.912161 - 0.0521821 -2.21353 0.940091 - 0.0537001 -2.21796 0.952158 - 0.0622519 -2.25798 1.0199 - 0.0677092 -2.17282 1.06491 - -0.0127658 -0.4038 0.449886 --0.00693055 -0.416271 0.496349 --0.00287741 -0.416709 0.528753 --0.00160122 -0.419053 0.538921 - -0.0005442 -0.418829 0.547377 --0.00032064 -0.417408 0.549188 - 0.0010256 -0.412505 0.560033 - 0.00481893 -0.415402 0.59032 - 0.0837588 -0.927474 1.21333 - 0.102545 -0.977883 1.36275 - 0.106057 -0.967256 1.39101 - 0.105924 -0.932917 1.39049 - 0.103195 -0.883691 1.36946 - 0.102962 -0.874417 1.36775 - 0.104347 -0.813632 1.3798 - 0.104249 -0.761829 1.37986 - 0.104099 -0.746781 1.3789 - 0.108538 -0.637139 1.41617 - 0.108083 -0.615427 1.41287 - 0.10885 -0.612012 1.41906 - 0.113963 -0.566395 1.46069 - 0.114257 -0.560956 1.46313 - 0.158933 -0.64765 1.81899 - 0.176681 -0.687384 1.96028 - 0.209661 -0.682237 2.22409 - 0.21001 -0.67344 2.22703 - 0.210365 -0.578195 2.2314 - 0.209736 -0.318596 2.23056 - 0.210303 -0.292257 2.23551 - 0.209627 -0.03387 2.23427 - 0.210564 0.0103477 2.24248 - 0.209923 0.143429 2.2395 - 0.210004 0.188139 2.24087 - 0.20948 0.341142 2.23914 - 0.209553 0.359537 2.24002 - 0.208918 0.478896 2.23687 - 0.210102 0.6545 2.24917 - 0.208908 1.0393 2.24582 - 0.20818 1.22366 2.24297 - 0.193885 1.2842 2.12963 - 0.111182 1.2762 1.46815 - 0.103879 1.27042 1.40966 - 0.0983171 1.27756 1.36529 - 0.0789841 1.27257 1.21061 - 0.0584677 1.27622 1.0466 - 0.0577032 1.27897 1.04053 - 0.0542522 1.2718 1.01282 - 0.0511453 1.28116 0.988127 - 0.0479436 1.27556 0.962433 - 0.0464863 1.28112 0.950869 - 0.0212079 1.27533 0.748631 - 0.0122536 1.26997 0.676938 - 0.00631129 1.16341 0.627702 - 0.00206463 1.16219 0.593723 --0.00080942 1.15891 0.570687 --0.00144028 1.16042 0.565666 --0.00896698 1.20525 0.506199 - -0.0307901 1.16716 0.331071 - -0.0364926 1.17044 0.285522 - -0.0422031 1.17191 0.23988 - -0.0453317 1.15795 0.214637 - -0.0491486 1.16626 0.184248 - -0.0696909 1.1973 0.0204763 - -0.0772969 1.1593 -0.0409593 - -0.0780437 1.16201 -0.0468879 - -0.088235 1.25574 -0.126874 - -0.100145 1.27035 -0.221883 - -0.103145 1.08429 -0.248867 - -0.102839 0.88935 -0.249567 - -0.103073 0.849116 -0.252081 - -0.102314 0.628493 -0.249572 - -0.100664 0.595397 -0.236913 - -0.101761 0.580448 -0.245924 - -0.101894 0.571671 -0.247124 - -0.101774 0.532338 -0.246805 - -0.101391 0.493752 -0.244361 - -0.0713975 -0.337093 -0.0388799 - -0.0734932 -0.377961 -0.0578018 - -0.0717142 -0.428133 -0.0432236 - -0.0656193 -0.420661 0.00985676 - -0.0653072 -0.419818 0.0125832 - -0.0649964 -0.41896 0.0152982 - -0.0642637 -0.456029 0.0210156 - -0.0598255 -0.445039 0.0597652 - -0.082047 -2.2289 -0.164486 - -0.0670329 -2.20778 -0.03368 - -0.0585367 -2.26234 0.039177 - -0.0563265 -2.27185 0.0582115 - -0.0506603 -2.27796 0.107331 - -0.0293511 -2.22391 0.293402 - -0.028224 -2.22658 0.303147 - -0.0175701 -2.28557 0.394673 - -0.0114215 -2.23055 0.449051 --0.00311299 -2.18959 0.521949 - 0.00127048 -2.13019 0.561069 - 0.0152267 -2.24761 0.680261 - 0.0458671 -2.23255 0.946717 - 0.05509 -2.274 1.02612 - 0.055453 -2.22366 1.03015 - 0.0639866 -2.16327 1.10534 - -0.0174945 -0.442117 0.427571 - -0.0171755 -0.443033 0.430326 - 0.0827524 -2.17442 1.26818 - -0.0149033 -0.405545 0.450722 - -0.0130072 -0.421576 0.466914 - -0.0127993 -0.420509 0.468739 - -0.0123 -0.415544 0.473163 - -0.0081723 -0.42343 0.508885 --0.00625024 -0.412679 0.525771 --0.00515016 -0.414264 0.535301 --0.00411149 -0.414878 0.544313 --0.00085736 -0.420301 0.572489 --0.00065107 -0.41877 0.574308 - 0.00139232 -0.413792 0.592147 - 0.00266772 -0.377778 0.603857 - 0.0889752 -0.977364 1.34318 - 0.0920813 -0.974808 1.37021 - 0.0933568 -0.975547 1.38127 - 0.0923288 -0.780349 1.37576 - 0.0928893 -0.769105 1.38082 - 0.0926612 -0.753479 1.37911 - 0.0922801 -0.730208 1.37621 - 0.0941288 -0.657805 1.39354 - 0.0974204 -0.63329 1.42256 - 0.0985006 -0.579014 1.4329 - 0.119164 -0.570365 1.61256 - 0.1503 -0.67233 1.88128 - 0.191689 -0.590362 2.24228 - 0.190969 -0.447855 2.23852 - 0.190095 -0.354857 2.23255 - 0.190252 -0.346035 2.23407 - 0.190446 -0.265193 2.23717 - 0.189417 0.0544252 2.23382 - 0.189431 0.0897989 2.23456 - 0.19018 0.20606 2.2431 - 0.190393 0.30567 2.2467 - 0.189339 0.377242 2.23879 - 0.189784 0.527525 2.24528 - 0.189474 0.613316 2.24409 - 0.189206 0.661535 2.24261 - 0.188562 0.810769 2.23962 - 0.189163 0.844145 2.24543 - 0.190052 0.868515 2.25358 - 0.188229 0.936338 2.23892 - 0.188631 1.22521 2.24747 - 0.143229 1.283 1.85405 - 0.138174 1.28242 1.81012 - 0.116871 1.28188 1.62504 - 0.107874 1.27542 1.54676 - 0.100063 1.27499 1.47889 - 0.0940912 1.27681 1.42705 - 0.0859895 1.27808 1.35668 - 0.080603 1.26895 1.30973 - 0.0783052 1.2793 1.28995 - 0.0623399 1.27324 1.15114 - 0.0542306 1.279 1.08079 - 0.0365718 1.27746 0.927352 - 0.035768 1.2779 0.920377 - 0.0325647 1.27929 0.892572 - 0.0300251 1.27728 0.870474 - 0.0273107 1.27132 0.846788 - 0.0217009 1.28327 0.798261 - 0.0174758 1.27437 0.761399 - 0.0161088 1.27718 0.749573 - 0.00867115 1.27456 0.684912 - 0.0024575 1.16719 0.629052 - -0.0107316 1.24711 0.515868 - -0.0294523 1.17407 0.351953 - -0.0336556 1.16446 0.315268 - -0.0464443 1.16081 0.204101 - -0.0531204 1.19138 0.146637 - -0.0629397 1.27659 0.0628209 - -0.0675199 1.24643 0.0225023 - -0.0699232 1.18565 0.00056072 - -0.0730829 1.16565 -0.0272392 - -0.0745964 1.15443 -0.0405846 - -0.0786396 1.1664 -0.0755009 - -0.0870274 1.27947 -0.146393 - -0.0907487 1.26734 -0.178935 - -0.098648 1.13765 -0.249829 - -0.0979668 1.06119 -0.245248 - -0.0985224 1.04793 -0.250307 - -0.0982876 0.977539 -0.249498 - -0.0979279 0.921564 -0.247352 - -0.0975176 0.860601 -0.244854 - -0.0972899 0.727621 -0.245201 - -0.0970685 0.718026 -0.243445 - -0.0975789 0.711391 -0.247996 - -0.0969125 0.636311 -0.24352 - -0.0967831 0.551711 -0.243876 - -0.0963476 0.497864 -0.241033 - -0.0692878 -0.36118 -0.0459987 - -0.0699854 -0.384485 -0.0531254 - -0.0662913 -0.419137 -0.0184287 - -0.0631611 -0.450545 0.0109332 - -0.0607485 -0.440327 0.0342267 - -0.0591275 -0.434976 0.0498479 - -0.0588555 -0.433879 0.0524733 - -0.0560296 -0.480171 0.0786346 - -0.09231 -2.25667 -0.302886 - -0.0608122 -2.26769 -0.00156173 - -0.056657 -2.26632 0.0382437 - -0.040507 -0.42598 0.228281 - -0.0260232 -2.23234 0.332164 - -0.016683 -2.24926 0.421255 - -0.0158041 -2.23642 0.429916 --0.00189763 -2.15291 0.564654 - 0.00037006 -2.11572 0.587079 - 0.00323412 -2.11076 0.614593 - 0.0176975 -2.28256 0.749747 - 0.0206552 -2.19393 0.779769 - 0.0216443 -2.19147 0.789285 - 0.0439856 -2.29668 1.00114 - 0.0507405 -2.15144 1.0686 - -0.0197877 -0.395464 0.427219 - -0.0206739 -0.368046 0.419264 - -0.0156045 -0.421576 0.466763 - -0.0157946 -0.414464 0.46508 - -0.0141088 -0.412811 0.481251 - -0.0135566 -0.409394 0.486604 - -0.0121933 -0.421286 0.499425 - -0.0105798 -0.413007 0.515032 --0.00915618 -0.412959 0.528661 - -0.0064405 -0.416888 0.554583 --0.00228593 -0.419893 0.594298 --0.00236834 -0.401404 0.593865 --0.00239276 -0.387639 0.593897 --0.00222064 -0.386014 0.595576 --0.00135493 -0.374708 0.604081 - 0.0019708 -0.395244 0.635524 - 0.0673828 -0.952963 1.25099 - 0.0812945 -0.976831 1.38372 - 0.0796417 -0.836167 1.3706 - 0.0805143 -0.789895 1.37984 - 0.0802834 -0.752391 1.37836 - 0.0801707 -0.744619 1.37743 - 0.0819589 -0.658781 1.3962 - 0.0854095 -0.629867 1.42979 - 0.0855263 -0.514881 1.43312 - 0.0879994 -0.512277 1.45685 - 0.133977 -0.676817 1.89383 - 0.157349 -0.691207 2.1173 - 0.169567 -0.626308 2.23552 - 0.169352 -0.549581 2.23494 - 0.169164 -0.428284 2.23547 - 0.169326 -0.391977 2.23773 - 0.16928 -0.382768 2.23746 - 0.169011 -0.327891 2.23594 - 0.167962 -0.174851 2.22885 - 0.16813 -0.148455 2.23096 - 0.1689 -0.0869879 2.23951 - 0.168843 -0.0604294 2.23949 - 0.168916 0.0368848 2.24206 - 0.168943 0.0546135 2.24266 - 0.168588 0.0633735 2.23942 - 0.169067 0.116846 2.24504 - 0.167951 0.169487 2.23537 - 0.167742 0.358317 2.23701 - 0.167794 0.432056 2.23892 - 0.167603 0.563473 2.23962 - 0.168223 0.574758 2.24577 - 0.167245 0.75932 2.23996 - 0.167127 0.862252 2.24082 - 0.167666 0.961256 2.24788 - 0.167477 1.04955 2.24777 - 0.16721 1.07099 2.24563 - 0.134564 1.27595 1.93705 - 0.110464 1.28571 1.70652 - 0.097753 1.27701 1.58466 - 0.0828178 1.28019 1.44175 - 0.0748846 1.27607 1.36572 - 0.0590846 1.27572 1.21446 - 0.0467415 1.27721 1.09632 - 0.0428488 1.2818 1.05914 - 0.0132571 1.27695 0.775762 - 0.0110039 1.2721 0.754098 - 0.0102511 1.28688 0.747175 --0.00026698 1.19557 0.644725 --0.00142676 1.17946 0.633312 --0.00316498 1.16311 0.616357 - -0.0180202 1.27716 0.476339 - -0.0195304 1.25967 0.461545 - -0.02516 1.19308 0.406369 - -0.0262712 1.19265 0.395723 - -0.030403 1.16357 0.355608 - -0.0362759 1.15857 0.299289 - -0.0494683 1.16585 0.173135 - -0.0540138 1.19523 0.130185 - -0.0575258 1.25755 0.0977639 - -0.0618282 1.27388 0.0568894 - -0.065869 1.26912 0.0181141 - -0.0842236 1.27329 -0.157519 - -0.0853041 1.26798 -0.167965 - -0.090463 1.26947 -0.217324 - -0.0925109 0.912677 -0.243798 - -0.0931275 0.904994 -0.249848 - -0.0927484 0.871441 -0.246865 - -0.0926582 0.81978 -0.246996 - -0.0925478 0.772146 -0.246856 - -0.092427 0.741839 -0.246283 - -0.0914845 0.581453 -0.240348 - -0.0912762 0.5219 -0.2395 - -0.0906859 0.498269 -0.234304 - -0.090619 0.48913 -0.233839 - -0.0780699 -0.419555 -0.17199 - -0.0650734 -0.347452 -0.0317379 - -0.0665424 -0.380014 -0.048114 - -0.0661231 -0.403458 -0.0441415 - -0.0653069 -0.405569 -0.0354764 - -0.0623524 -0.409366 -0.00402579 - -0.0621836 -0.410361 -0.0022454 - -0.0607067 -0.450572 0.0126555 - -0.0603355 -0.452406 0.016578 - -0.0591188 -0.4495 0.0296248 - -0.0572632 -0.439453 0.0496451 - -0.0539886 -0.430929 0.0847756 - -0.0537119 -0.473404 0.0868185 - -0.0535891 -0.476884 0.0880546 - -0.0533937 -0.477475 0.0901275 - -0.0755844 -2.28032 -0.185355 - -0.0611111 -2.25162 -0.0302727 - -0.0421505 -0.421812 0.211314 - -0.0407934 -0.414994 0.225944 - -0.0406245 -0.414981 0.227747 - -0.0205611 -2.26087 0.402301 - -0.0190096 -2.23133 0.419494 --0.00598897 -2.18205 0.559514 --0.00510404 -2.18056 0.56899 - 0.0123449 -2.25396 0.753642 - 0.0144646 -2.22254 0.776938 - 0.0277412 -2.17857 0.919576 - 0.03903 -2.24433 1.03865 - -0.0175086 -0.418114 0.474385 - -0.0172405 -0.418721 0.477234 - -0.0113694 -0.416874 0.539933 --0.00817194 -0.414942 0.5741 --0.00784153 -0.411856 0.577692 --0.00637627 -0.387639 0.59385 --0.00517508 -0.37751 0.606887 - 0.0627808 -0.963822 1.31958 - 0.0690174 -0.919742 1.38709 - 0.0668332 -0.870184 1.36484 - 0.0671993 -0.81236 1.36998 - 0.068387 -0.791582 1.38311 - 0.0677562 -0.779791 1.37663 - 0.0684057 -0.692976 1.38542 - 0.148018 -0.684161 2.23528 - 0.147512 -0.548531 2.23279 - 0.147497 -0.492444 2.23383 - 0.147496 -0.483165 2.23401 - 0.147338 -0.327571 2.23567 - 0.147278 -0.228899 2.23714 - 0.146771 -0.210518 2.23213 - 0.1469 -0.122094 2.2354 - 0.146747 -0.016168 2.23604 - 0.147142 0.045691 2.24157 - 0.146507 0.133975 2.23669 - 0.14703 0.187862 2.24343 - 0.146884 0.232521 2.24283 - 0.146442 0.331315 2.24023 - 0.146274 0.497522 2.242 - 0.14612 0.592471 2.24238 - 0.14577 0.62042 2.23925 - 0.146118 0.631327 2.2432 - 0.14631 0.671332 2.24611 - 0.146447 0.74195 2.24908 - 0.145473 0.969261 2.24356 - 0.145392 0.979842 2.24292 - 0.14327 1.28346 2.22679 - 0.126336 1.28327 2.04605 - 0.116779 1.28012 1.94399 - 0.0950159 1.2779 1.71167 - 0.0778389 1.27791 1.52835 - 0.0662036 1.27268 1.40406 - 0.0522524 1.26921 1.25509 - 0.0393951 1.27216 1.11793 - 0.0323574 1.28066 1.043 --0.00927391 1.17076 0.596334 - -0.0123425 1.26122 0.565524 - -0.0141397 1.27962 0.546737 - -0.0158713 1.27597 0.528178 - -0.0308316 1.16932 0.366227 - -0.036584 1.17219 0.304896 - -0.0370619 1.17254 0.299803 - -0.0451467 1.15895 0.213226 - -0.0456216 1.15989 0.208178 - -0.0460972 1.16081 0.203121 - -0.0536372 1.20477 0.123593 - -0.0558783 1.2277 0.100167 - -0.0633656 1.27989 0.0213765 - -0.0661931 1.2328 -0.00981013 - -0.0695216 1.17392 -0.0465956 - -0.0714683 1.17093 -0.0674365 - -0.08011 1.27042 -0.157532 - -0.08222 1.26544 -0.180159 - -0.0884873 1.13304 -0.249885 - -0.0888498 1.07855 -0.254922 - -0.0871931 0.811124 -0.242974 - -0.0864237 0.686105 -0.237442 - -0.0867543 0.678739 -0.241129 - -0.086167 0.586294 -0.236843 - -0.0862746 0.577556 -0.238178 - -0.0861595 0.537533 -0.237808 - -0.086146 0.528205 -0.237864 - -0.0851894 0.495119 -0.228364 - -0.0512092 -0.141292 0.107557 - -0.0595717 -0.288147 0.00342007 - -0.0626626 -0.379286 -0.0359595 - -0.0607865 -0.405138 -0.0140169 - -0.0598674 -0.397799 -0.00278386 - -0.0594978 -0.398019 0.00165682 - -0.0593208 -0.416028 0.00335126 - -0.0551715 -0.435559 0.0527902 - -0.0550198 -0.44264 0.0544446 - -0.0530961 -0.48304 0.0766095 - -0.0522755 -0.489026 0.0863353 - -0.0518399 -0.486348 0.0916395 - -0.0510792 -0.49591 0.10056 - -0.0505883 -0.500401 0.106355 - -0.0492355 -0.474474 0.123254 - -0.0711149 -2.26359 -0.183119 - -0.0416 -0.42094 0.216393 - -0.0414478 -0.420967 0.218223 - -0.0406813 -0.42298 0.227395 - -0.0403196 -0.438927 0.23136 - -0.0242205 -2.24739 0.381356 - -0.0212109 -2.21938 0.418235 - -0.0139234 -2.21791 0.505929 - -0.0123259 -2.21535 0.525207 - -0.0107307 -2.21262 0.544462 --0.00742822 -2.16266 0.585393 --0.00664349 -2.11312 0.596028 --0.00159488 -2.17212 0.655332 - 0.00106155 -2.22503 0.686009 - 0.0043558 -2.26268 0.724726 - 0.0102439 -2.21857 0.796617 - 0.0138902 -2.26197 0.839431 - 0.015684 -2.26323 0.860977 - 0.0219314 -2.20117 0.937624 - 0.0271517 -2.28627 0.998364 - 0.0380524 -2.17112 1.13227 - -0.0249036 -0.375063 0.418338 - -0.0246365 -0.373342 0.421592 - -0.0202491 -0.412739 0.473417 - -0.0192968 -0.415061 0.484816 - -0.018992 -0.405405 0.488714 - -0.018177 -0.404828 0.498532 - -0.0164203 -0.412063 0.519489 - -0.015774 -0.415097 0.527189 - -0.0148987 -0.406975 0.537915 - -0.0113123 -0.415642 0.580845 - -0.008355 -0.38108 0.617253 - 0.0560329 -0.970409 1.37754 - 0.0561023 -0.726732 1.38425 - 0.0600287 -0.572424 1.43521 - 0.0602241 -0.567113 1.43769 - 0.0613714 -0.560598 1.45165 - 0.0615624 -0.555215 1.45407 - 0.0599826 -0.503109 1.43633 - 0.108916 -0.690697 2.02041 - 0.122401 -0.694558 2.18252 - 0.126846 -0.654883 2.23695 - 0.126293 -0.623941 2.23104 - 0.125256 -0.298888 2.22642 - 0.126034 -0.0692351 2.24132 - 0.125235 0.169403 2.23747 - 0.125483 0.187493 2.24089 - 0.124623 0.222137 2.23138 - 0.124785 0.403549 2.2377 - 0.124619 0.412364 2.23593 - 0.12467 0.51519 2.23902 - 0.12468 0.543695 2.23983 - 0.124994 0.602449 2.24503 - 0.124724 0.679869 2.24365 - 0.12485 0.710308 2.2459 - 0.124961 0.720828 2.24749 - 0.125132 0.908908 2.25409 - 0.123647 1.11255 2.24114 - 0.12356 1.17097 2.2415 - 0.12373 1.22057 2.24474 - 0.124106 1.23564 2.24963 - 0.123518 1.25596 2.24305 - 0.109004 1.28669 2.06921 - 0.100031 1.28027 1.96111 - 0.083886 1.27837 1.76686 - 0.0752111 1.27924 1.66253 - 0.0606917 1.27018 1.48766 - 0.052354 1.27634 1.38752 - 0.0315209 1.27483 1.13689 - 0.0309121 1.27638 1.1296 - 0.0263525 1.28025 1.07485 - 0.0230869 1.28086 1.03558 - 0.0222764 1.27763 1.02575 - 0.0140863 1.27571 0.92719 - 0.00498749 1.28104 0.817872 - 0.00097945 1.27752 0.769574 - 0.00048199 1.27897 0.763626 --0.00369605 1.28309 0.713468 - -0.0091977 1.21535 0.645655 - -0.011418 1.16785 0.6178 - -0.0122704 1.17126 0.60763 - -0.0186548 1.27365 0.533304 - -0.0191529 1.27305 0.527299 - -0.0306115 1.17259 0.38704 - -0.0336842 1.16413 0.349875 - -0.0379368 1.16056 0.298634 - -0.03878 1.16018 0.288483 - -0.0438028 1.15099 0.227842 - -0.0442189 1.151 0.222837 - -0.0446519 1.15798 0.217798 - -0.0475899 1.15926 0.182488 - -0.0497696 1.17106 0.156554 - -0.0501922 1.17076 0.151462 - -0.0573391 1.26637 0.0678021 - -0.0588523 1.27512 0.0498114 - -0.0616948 1.27603 0.0156418 - -0.0735471 1.26595 -0.127171 - -0.0771118 1.26893 -0.169978 - -0.0805709 1.26573 -0.211664 - -0.083713 1.26697 -0.249429 - -0.0836035 1.24806 -0.24857 - -0.0831055 1.10794 -0.245962 - -0.0831986 1.07331 -0.247917 - -0.0833687 1.06576 -0.250145 - -0.0828475 0.888783 -0.248149 - -0.0827672 0.852409 -0.248061 - -0.0828627 0.837806 -0.249562 - -0.081729 0.783745 -0.23723 - -0.0820079 0.78172 -0.240634 - -0.0823446 0.766181 -0.245059 - -0.0821586 0.748485 -0.243248 - -0.081688 0.639593 -0.240217 - -0.0815979 0.621434 -0.239571 - -0.0805076 0.539731 -0.228429 - -0.0799502 0.471892 -0.223362 - -0.0684338 -0.39923 -0.154338 - -0.0498313 -0.133153 0.109757 - -0.0586951 -0.339661 -0.0182873 - -0.0589425 -0.380096 -0.0228202 - -0.0581605 -0.40169 -0.0126258 - -0.0570835 -0.399861 0.00228894 - -0.0556764 -0.415389 0.0212787 - -0.0516021 -0.52015 0.0746075 - -0.0471673 -0.465141 0.137333 - -0.0494197 -2.26587 0.0564159 - -0.0411645 -0.418996 0.221455 - -0.0155634 -2.21535 0.525059 - -0.0115882 -2.19284 0.580544 --0.00746888 -2.1827 0.637675 --0.00456436 -2.22801 0.676506 - 0.00650557 -2.25982 0.8284 - 0.00798221 -2.25733 0.848848 - 0.0123182 -2.2449 0.909032 - -0.0263349 -0.430372 0.425801 - -0.0233222 -0.415988 0.467777 - -0.0214407 -0.421163 0.4936 - -0.0211806 -0.418779 0.497255 - -0.0202816 -0.417622 0.509695 - -0.0137356 -0.381804 0.601027 - 0.0397244 -0.973911 1.32243 - 0.0413222 -0.976053 1.34443 - 0.0433922 -0.831714 1.37699 - 0.0443208 -0.663425 1.39446 - 0.0447752 -0.660245 1.40082 - 0.0451007 -0.656054 1.40543 - 0.0486334 -0.562668 1.45677 - 0.0848433 -0.681897 1.9532 - 0.0881064 -0.6906 1.99799 - 0.105463 -0.635726 2.23905 - 0.105379 -0.549843 2.24026 - 0.104918 -0.520075 2.23472 - 0.104496 -0.490785 2.22971 - 0.104243 -0.453176 2.22725 - 0.1043 -0.380539 2.23005 - 0.104166 -0.25472 2.23169 - 0.103428 -0.165235 2.22397 - 0.104164 -0.11311 2.23557 - 0.104431 -0.0779923 2.24023 - 0.103925 -0.0337362 2.23448 - 0.103761 -0.01612 2.2327 - 0.10405 0.0190951 2.23767 - 0.103428 0.0541561 2.23005 - 0.104205 0.0898433 2.24176 - 0.103684 0.312866 2.24074 - 0.103663 0.4508 2.24427 - 0.103241 0.51519 2.24023 - 0.103338 0.525014 2.24183 - 0.103263 0.730021 2.24648 - 0.102926 0.789411 2.24347 - 0.102842 0.819985 2.24316 - 0.10254 0.924161 2.24187 - 0.102116 0.975926 2.23745 - 0.103083 1.02725 2.25222 - 0.102362 1.0561 2.24306 - 0.102325 1.06726 2.24286 - 0.102074 1.13507 2.24128 - 0.101733 1.24083 2.23949 - 0.101694 1.27787 2.23999 - 0.0838214 1.27963 1.99337 - 0.075308 1.28502 1.87603 - 0.0679049 1.28346 1.77382 - 0.059222 1.2822 1.65395 - 0.0512557 1.26919 1.54365 - 0.0507419 1.27357 1.53668 - 0.0412638 1.27341 1.40587 - 0.0259866 1.27166 1.19498 - 0.021791 1.27483 1.13717 - 0.018452 1.28019 1.09124 - 0.0168582 1.2711 1.06899 - 0.0105443 1.28107 0.982127 - 0.00054274 1.27854 0.844028 --0.00135616 1.28104 0.817891 --0.00821332 1.27503 0.72309 - -0.0108683 1.27926 0.686566 - -0.0155315 1.17259 0.619257 - -0.0259501 1.19743 0.47616 - -0.026946 1.18098 0.461961 - -0.0327919 1.16834 0.380931 - -0.0347413 1.15562 0.353676 - -0.043163 1.15591 0.237457 - -0.0442814 1.168 0.222358 - -0.0509738 1.1743 0.130171 - -0.0620182 1.25041 -0.0201448 - -0.0639584 1.26748 -0.0464487 - -0.0661025 1.16736 -0.0788103 - -0.0784798 1.17069 -0.249535 - -0.0780561 1.13049 -0.2448 - -0.0775043 0.837254 -0.2453 - -0.0771632 0.775396 -0.242305 - -0.0770674 0.711339 -0.242755 - -0.0772457 0.708461 -0.245295 - -0.0759654 0.597466 -0.230698 - -0.0752895 0.510173 -0.223786 - -0.0643619 -0.375746 -0.151933 - -0.0631201 -0.385043 -0.132183 - -0.0478593 -0.127294 0.122572 - -0.0533365 -0.254064 0.0300297 - -0.0558787 -0.341977 -0.0138631 - -0.0554528 -0.393932 -0.00866809 - -0.0537341 -0.430681 0.0178944 - -0.0535934 -0.446938 0.0196403 - -0.0523484 -0.425532 0.0404355 - -0.052232 -0.426324 0.0422903 - -0.0516579 -0.424774 0.0516102 - -0.0511333 -0.443882 0.0594632 - -0.051879 -0.580782 0.0429933 - -0.0506158 -0.544462 0.0645643 - -0.0496756 -0.513717 0.0807398 - -0.0454938 -0.461302 0.149959 - -0.0444089 -0.44867 0.167887 - -0.0440376 -2.28244 0.114549 - -0.0417448 -0.413865 0.212029 - -0.0408514 -0.413981 0.226451 - -0.0260696 -2.20825 0.407077 - -0.0153423 -2.19482 0.580725 --0.00817062 -2.22298 0.695613 --0.00555576 -2.22898 0.737641 - 0.00171304 -2.24013 0.854649 - 0.0142047 -2.17743 1.05838 - -0.0289768 -0.432944 0.417575 - -0.0283211 -0.435797 0.428072 - -0.0288727 -0.366321 0.421412 - -0.0256501 -0.40738 0.472118 - -0.0207886 -0.415979 0.550339 - -0.0198662 -0.419471 0.565119 - -0.01918 -0.417993 0.576247 - 0.0279301 -0.970601 1.31905 - 0.0283251 -0.967774 1.32552 - 0.0309121 -0.873207 1.37035 - 0.0307321 -0.863371 1.36776 - 0.0308839 -0.84237 1.37089 - 0.0311004 -0.837342 1.37455 - 0.0309598 -0.755804 1.37492 - 0.0325644 -0.655086 1.40409 - 0.0337601 -0.625717 1.42435 - 0.0339903 -0.569443 1.42988 - 0.0351801 -0.552755 1.44963 - 0.0337635 -0.517815 1.42789 - 0.0690009 -0.687706 1.99137 - 0.0835491 -0.491259 2.23263 - 0.0837742 -0.473665 2.23684 - 0.0836482 -0.436468 2.23601 - 0.0835627 -0.336385 2.23787 - 0.0833166 -0.069201 2.24253 - 0.0824881 -0.0248745 2.23059 - 0.0828988 0.0190951 2.23865 - 0.0826319 0.0630921 2.23576 - 0.0827212 0.098479 2.23835 - 0.0827991 0.107396 2.23989 - 0.0822756 0.321375 2.23836 - 0.0822308 0.330346 2.23793 - 0.0820866 0.582238 2.24375 - 0.0822354 0.631624 2.24775 - 0.0820462 0.640471 2.24498 - 0.0812723 0.725619 2.23524 - 0.0760671 1.28058 2.16915 - 0.0744936 1.27582 2.14359 - 0.0740311 1.28309 2.13636 - 0.0689399 1.2747 2.05388 - 0.0619106 1.27536 1.9404 - 0.0583559 1.27839 1.8831 - 0.0518823 1.2754 1.77847 - 0.0499729 1.28411 1.74793 - 0.0411195 1.27044 1.60453 - 0.0339443 1.27018 1.48866 - 0.0307551 1.27296 1.43726 - 0.0225588 1.28302 1.30524 - 0.0137201 1.27399 1.16223 - 0.00620231 1.27645 1.04092 - 0.00272754 1.27259 0.984686 - 0.00036077 1.2707 0.946409 --0.00391037 1.27621 0.877622 - -0.006523 1.27493 0.835394 --0.00687255 1.2776 0.829836 --0.00762217 1.28104 0.817844 - -0.0252468 1.19588 0.530505 - -0.0296145 1.16824 0.459086 - -0.0308756 1.17318 0.438882 - -0.0345525 1.15645 0.378971 - -0.0461671 1.16058 0.191565 - -0.0510304 1.17995 0.113665 - -0.0534284 1.19492 0.0754276 - -0.0537591 1.19525 0.0700985 - -0.0546493 1.21765 0.0564491 - -0.0634741 1.17667 -0.0873694 - -0.0664126 1.27655 -0.131585 - -0.0735032 1.27091 -0.24626 - -0.0732748 1.12105 -0.247419 - -0.0722428 0.834924 -0.240014 - -0.0724858 0.802161 -0.244997 - -0.0716741 0.627884 -0.237531 - -0.0718181 0.614611 -0.240285 - -0.0710776 0.58399 -0.229318 - -0.0710646 0.573737 -0.229441 - -0.0706461 0.546395 -0.223568 - -0.0702115 0.502659 -0.217965 - -0.0477989 -0.140521 0.103529 - -0.0465427 -0.113496 0.128862 - -0.0528623 -0.38889 -0.00398393 - -0.0518379 -0.402875 0.0152804 - -0.0518992 -0.440613 0.0126349 - -0.0501784 -0.419728 0.0467123 - -0.0495175 -0.438481 0.0587643 - -0.0495531 -0.453991 0.057477 - -0.0503024 -0.597021 0.0374502 - -0.0469937 -0.487241 0.105673 - -0.0466702 -0.489701 0.111832 - -0.0463358 -0.491105 0.118243 - -0.0457004 -0.483431 0.130823 - -0.0455096 -0.488147 0.134331 - -0.0445189 -0.453017 0.154845 - -0.043919 -0.458596 0.166227 - -0.0434662 -0.448563 0.17537 - -0.0434736 -2.27596 0.104472 - -0.0419417 -0.416689 0.20608 - -0.0418476 -0.416756 0.207895 - -0.0405277 -0.447885 0.232209 - -0.0345111 -2.1942 0.280917 - -0.0330297 -2.19324 0.309595 - -0.0309776 -2.20735 0.348724 - -0.0294275 -2.21647 0.378341 - -0.012628 -2.25232 0.701753 - 0.00986363 -2.16159 1.14012 - -0.0310779 -0.415853 0.416151 - -0.028584 -0.475782 0.462048 - -0.0286053 -0.470276 0.46185 - -0.0310265 -0.362807 0.419199 - -0.0277489 -0.417334 0.480456 - -0.0262918 -0.416799 0.508648 - -0.0259918 -0.410101 0.514709 - -0.0255886 -0.413189 0.522384 - -0.025466 -0.412679 0.524773 - -0.0249098 -0.4121 0.53555 - -0.0247206 -0.413106 0.539168 - -0.0245072 -0.411107 0.543372 - -0.0216405 -0.381094 0.599958 - -0.021318 -0.37751 0.606334 - 0.0190938 -0.863972 1.36881 - 0.0188347 -0.830295 1.36511 - 0.0195889 -0.725673 1.38374 - 0.0211107 -0.648066 1.41617 - 0.0216762 -0.582146 1.42966 - 0.0217963 -0.576865 1.43218 - 0.0221697 -0.535974 1.44098 - 0.0632548 -0.604325 2.23267 - 0.0628241 -0.398862 2.2323 - 0.0627728 -0.281891 2.23584 - 0.0624701 -0.0602207 2.23857 - 0.0620536 0.16932 2.23941 - 0.0618368 0.222465 2.23727 - 0.0620038 0.240775 2.24121 - 0.0618345 0.32169 2.24107 - 0.0614599 0.375229 2.2359 - 0.0615767 0.421784 2.23996 - 0.0612798 0.448412 2.23525 - 0.0617105 0.652056 2.25146 - 0.0605916 0.775179 2.2346 - 0.0603956 1.0775 2.24251 - 0.0578529 1.27651 2.20106 - 0.0554612 1.283 2.15507 - 0.0499301 1.28212 2.0481 - 0.0487221 1.27738 2.02456 - 0.043897 1.27986 1.93137 - 0.0266567 1.27511 1.59786 - 0.0219995 1.27802 1.50793 - 0.0186985 1.26836 1.44374 - 0.0150998 1.27179 1.37429 - 0.00730122 1.27373 1.22359 - 0.00587265 1.27245 1.19592 --0.00185695 1.27286 1.04649 - -0.0137052 1.28104 0.817735 - -0.0197895 1.28265 0.700166 - -0.031772 1.16818 0.464063 - -0.0342851 1.15902 0.415121 - -0.0366656 1.16373 0.369279 - -0.0379947 1.16368 0.343581 - -0.0395961 1.15649 0.312341 - -0.0414274 1.1577 0.276982 - -0.048495 1.16011 0.140429 - -0.054112 1.21851 0.0340937 - -0.0565788 1.23575 -0.0129332 - -0.0646683 1.27447 -0.167835 - -0.0658001 1.26746 -0.189989 - -0.0683357 1.04271 -0.247714 - -0.0684913 1.00541 -0.252167 - -0.0680636 0.978963 -0.244921 - -0.0655314 0.506493 -0.214259 - -0.0544824 -0.319136 -0.0966938 - -0.0549661 -0.337608 -0.109296 - -0.0548857 -0.357854 -0.10833 - -0.0487361 -0.203915 0.0479617 - -0.0467882 -0.14663 0.0978785 - -0.0455109 -0.116293 0.130261 - -0.0501583 -0.352296 0.00635292 - -0.0501223 -0.374279 0.00615913 - -0.0500529 -0.375217 0.0077928 - -0.0497891 -0.375362 0.0141697 - -0.049862 -0.396596 0.0113763 - -0.0459737 -0.485235 0.101189 - -0.0450631 -0.501253 0.122451 - -0.0433705 -0.462567 0.165289 - -0.0417121 -0.429748 0.207017 - -0.023341 -2.17365 0.567152 - -0.0152279 -2.23897 0.760341 - -0.0130668 -2.24021 0.812585 - -0.0120491 -2.28493 0.835048 --0.00929608 -2.19986 0.905799 --0.00733888 -2.21321 0.952521 --0.00253572 -2.15516 1.07158 --0.00127418 -2.15031 1.10235 - -0.0333512 -0.426398 0.409529 - -0.0321829 -0.423961 0.437922 - -0.0321085 -0.423013 0.439769 - -0.032921 -0.366325 0.422852 - -0.0308059 -0.411885 0.471835 - -0.0296834 -0.407306 0.499223 - -0.0280971 -0.418255 0.537086 - -0.0278989 -0.41707 0.541938 - -0.0259199 -0.402285 0.590551 - -0.0258508 -0.40067 0.592301 - -0.0255435 -0.372607 0.6011 - 0.00706558 -0.972692 1.36124 - 0.00811879 -0.968541 1.38693 - 0.00753505 -0.818125 1.38009 - 0.00970422 -0.550705 1.44554 - 0.00881105 -0.516633 1.42558 - 0.00889313 -0.511371 1.42782 - 0.034794 -0.690248 2.04601 - 0.0408209 -0.696557 2.19157 - 0.0419472 -0.686797 2.2193 - 0.0426388 -0.653958 2.23763 - 0.0424534 -0.502213 2.24049 - 0.0420045 -0.372117 2.23593 - 0.0417825 -0.237253 2.23709 - 0.0414171 -0.148088 2.23257 - 0.0413582 -0.11283 2.23285 - 0.0410296 -0.00730988 2.23001 - 0.0412504 0.169654 2.24392 - 0.0412014 0.178483 2.24317 - 0.0410143 0.222794 2.24079 - 0.0408263 0.294335 2.2397 - 0.0404052 0.751164 2.25164 - 0.039714 0.978972 2.24595 - 0.039357 1.01959 2.23928 - 0.0391509 1.23044 2.2445 - 0.0255651 1.28129 1.91816 - 0.0155649 1.27821 1.67598 - 0.0143701 1.27487 1.64691 - 0.00433641 1.27049 1.40386 - 0.00127907 1.26615 1.32965 --0.00010556 1.27232 1.29644 --0.00136808 1.26931 1.26574 --0.00555927 1.27721 1.16469 - -0.0179834 1.27742 0.864005 - -0.0210809 1.27755 0.789046 - -0.0321292 1.16329 0.516118 - -0.0339131 1.16113 0.472839 - -0.0345166 1.16922 0.458625 - -0.0390674 1.16214 0.348143 - -0.042017 1.1637 0.276832 - -0.0470324 1.15908 0.155224 - -0.0487816 1.17099 0.113467 - -0.0521769 1.192 0.0323119 - -0.0536324 1.20531 -0.00227153 - -0.0558819 1.1844 -0.0577269 - -0.059891 1.27467 -0.150382 - -0.0621393 1.27329 -0.204862 - -0.0637585 1.27764 -0.243839 - -0.0633903 0.986182 -0.249048 - -0.0628817 0.872013 -0.242269 - -0.0621285 0.711491 -0.231818 - -0.0621326 0.663089 -0.234261 - -0.0608951 0.533584 -0.210584 - -0.0602486 0.481954 -0.19744 - -0.0491888 -0.25514 -0.0311697 - -0.0472992 -0.280342 0.0289822 - -0.047461 -0.301177 0.022328 - -0.0472943 -0.37363 0.0230387 - -0.0472433 -0.398389 0.0230836 - -0.0473533 -0.422575 0.0179053 - -0.0462341 -0.459836 0.0520716 - -0.0461515 -0.581372 0.0468171 - -0.0450125 -0.491751 0.0899336 - -0.0447832 -0.500762 0.0968436 - -0.0446836 -0.508637 0.0995873 - -0.0446499 -0.515978 0.100208 - -0.0444587 -0.521425 0.106106 - -0.0439341 -0.516839 0.123562 - -0.0437213 -0.517089 0.130505 - -0.0419391 -2.26325 0.0745242 - -0.0410218 -0.41898 0.225217 - -0.0408897 -0.426929 0.229017 - -0.0407657 -0.451884 0.23144 - -0.0349201 -2.19124 0.308798 - -0.0270123 -2.13856 0.570873 - -0.026057 -2.1095 0.60402 - -0.0250713 -2.16109 0.632883 - -0.0213811 -2.23449 0.748769 - -0.0166475 -2.22865 0.903966 - -0.0118769 -2.23803 1.05938 - -0.0351613 -0.362819 0.420562 - -0.034317 -0.400312 0.445723 - -0.0338909 -0.411189 0.458947 - -0.0334533 -0.410789 0.473284 - -0.0312241 -0.408284 0.546356 - -0.0308403 -0.412505 0.558633 - -0.0296765 -0.399601 0.59754 --0.00684882 -0.968067 1.30693 - -0.0042324 -0.940535 1.39431 --0.00514308 -0.879434 1.36852 --0.00486306 -0.668048 1.39151 --0.00478454 -0.662933 1.39442 --0.00388538 -0.594442 1.42831 --0.00335883 -0.551935 1.44831 - 0.017542 -0.690865 2.12279 - 0.0183531 -0.690989 2.14931 - 0.0207755 -0.680312 2.22924 - 0.020442 -0.499559 2.23016 - 0.0203106 -0.380724 2.23364 - 0.0200047 -0.334249 2.22667 - 0.0200124 -0.272151 2.23099 - 0.0200731 -0.219317 2.23643 - 0.0199716 -0.201317 2.23429 - 0.0196864 -0.0863874 2.23249 - 0.019549 0.010251 2.23432 - 0.0196356 0.0897546 2.24235 - 0.0191357 0.195262 2.23291 - 0.0190311 0.20384 2.23005 - 0.0190425 0.257646 2.23394 - 0.0194512 0.286639 2.24921 - 0.0191108 0.395109 2.24517 - 0.0188802 0.496807 2.24429 - 0.0187957 0.505633 2.2421 - 0.0185798 0.619834 2.24251 - 0.0182216 0.725958 2.23774 - 0.0181686 0.915321 2.2484 - 0.0176171 1.05287 2.23936 - 0.0175369 1.06306 2.23741 - 0.0174572 1.16897 2.24173 - 0.01731 1.203 2.23915 - 0.0173997 1.26798 2.24633 - 0.0150583 1.28058 2.17058 - 0.0124231 1.28313 2.08456 - 0.0108334 1.28258 2.03253 - 0.00759945 1.27567 1.92631 - 0.0073908 1.2825 1.91993 - 0.00577446 1.27644 1.86667 - 0.00506229 1.28146 1.84371 --0.00147625 1.28188 1.62989 --0.00511262 1.26888 1.51011 --0.00651926 1.26692 1.46397 - -0.0076156 1.27463 1.42862 --0.00934545 1.26883 1.37167 - -0.0104027 1.27518 1.33751 - -0.0162809 1.27406 1.14518 - -0.0166861 1.27964 1.13229 - -0.0189001 1.2818 1.06002 - -0.021699 1.26972 0.967694 - -0.0243285 1.27156 0.881815 - -0.0258662 1.28392 0.832331 - -0.0271849 1.27755 0.788787 - -0.0279891 1.27805 0.762516 - -0.0293962 1.27628 0.716381 - -0.0311378 1.23235 0.656546 - -0.03562 1.16582 0.505598 - -0.035778 1.16704 0.500511 - -0.0364529 1.16295 0.47817 - -0.0386977 1.16462 0.404859 - -0.0398048 1.16571 0.368723 - -0.0407522 1.1632 0.337575 - -0.0432446 1.16248 0.25601 - -0.0466506 1.16045 0.144484 - -0.0476118 1.16601 0.11341 - -0.0479105 1.16303 0.103445 - -0.0480749 1.16449 0.0981637 - -0.049231 1.17307 0.0609148 - -0.0501263 1.18706 0.032548 - -0.0517814 1.18945 -0.0214269 - -0.0547121 1.24676 -0.113525 - -0.0557366 1.27533 -0.145164 - -0.0580941 0.915614 -0.245809 - -0.057477 0.802136 -0.233052 - -0.0572387 0.697443 -0.232108 - -0.0571873 0.677317 -0.231745 - -0.0556448 0.485597 -0.193843 - -0.0557234 0.480445 -0.19675 - -0.0555453 0.470351 -0.191587 - -0.0545366 0.404479 -0.162908 - -0.0438722 -0.106604 0.115325 - -0.0457234 -0.222117 0.0103911 - -0.0439085 -0.131073 0.111029 - -0.0435732 -0.109241 0.130126 - -0.0434301 -0.100371 0.138229 - -0.045128 -0.291976 0.0333529 - -0.0452003 -0.31647 0.0272421 - -0.045142 -0.318147 0.0300105 - -0.0450819 -0.327494 0.0320957 - -0.0450195 -0.32484 0.0355082 - -0.0450716 -0.396559 0.0256528 - -0.044997 -0.427822 0.0262599 - -0.0440686 -0.431263 0.0726999 - -0.0438335 -0.528175 0.0747785 - -0.0437472 -0.517227 0.0802318 - -0.0434595 -0.516845 0.0947645 - -0.0421827 -0.45264 0.165583 - -0.0419038 -0.460092 0.178884 - -0.0410323 -0.421959 0.226646 - -0.0288742 -2.20056 0.660041 - -0.0268097 -2.18082 0.766065 - -0.0248624 -2.25072 0.857154 - -0.0230437 -2.2392 0.949963 - -0.0193613 -2.16804 1.1427 - -0.0365534 -0.410638 0.453494 - -0.0362883 -0.423308 0.465576 - -0.035736 -0.416271 0.494116 - -0.0352538 -0.41661 0.518381 - -0.035134 -0.417231 0.524358 - -0.0347988 -0.41707 0.541266 - -0.0339647 -0.413247 0.583686 - -0.0339321 -0.41166 0.585486 - -0.0337887 -0.405968 0.593289 - -0.0338443 -0.393778 0.591715 - -0.019226 -0.961276 1.27117 - -0.0177214 -0.968529 1.34626 - -0.0168194 -0.925309 1.39607 - -0.0174064 -0.830546 1.37605 - -0.0175827 -0.775881 1.37267 - -0.016885 -0.599706 1.42559 --0.00343081 -0.689833 2.09451 --0.00239729 -0.689977 2.14657 --0.00089506 -0.612812 2.23006 --0.00153549 -0.228224 2.23655 --0.00196333 -0.016128 2.23637 --0.00205439 0.0366667 2.2371 --0.00205789 0.0543175 2.23871 --0.00206632 0.161138 2.24905 --0.00232595 0.222904 2.24219 --0.00252006 0.266955 2.23685 --0.00284108 0.515931 2.24577 --0.00293171 0.573125 2.24697 --0.00318367 0.628652 2.23987 --0.00336111 0.811141 2.24933 --0.00392539 1.03248 2.2432 --0.00606726 1.28632 2.16086 --0.00948778 1.27378 1.98722 - -0.0111856 1.28081 1.90237 - -0.0156184 1.28085 1.67899 - -0.017573 1.26882 1.57928 - -0.0177733 1.27062 1.56937 - -0.0187318 1.2808 1.52209 - -0.020018 1.27018 1.4562 - -0.0201636 1.27412 1.44926 - -0.0204566 1.26935 1.43402 - -0.0229079 1.27903 1.31146 - -0.0231299 1.27691 1.30006 - -0.0271763 1.27556 1.09602 - -0.0283078 1.27393 1.03883 - -0.0302722 1.27298 0.939741 - -0.0324519 1.28121 0.830729 - -0.0325683 1.28386 0.825134 - -0.039318 1.16602 0.473111 - -0.0395244 1.16818 0.462928 - -0.0403654 1.16606 0.420334 - -0.0408839 1.16518 0.394119 - -0.0431243 1.16245 0.280942 - -0.0435155 1.15332 0.260308 - -0.0443885 1.14098 0.215073 - -0.0446245 1.15789 0.204884 - -0.0452101 1.15208 0.174785 - -0.048684 1.17581 0.00211531 - -0.048872 1.17189 -0.00775231 - -0.0492058 1.17467 -0.0242951 - -0.0499443 1.15763 -0.0632273 - -0.0518644 1.26603 -0.149058 - -0.052115 1.26754 -0.161534 - -0.0536352 1.27402 -0.237491 - -0.0535144 1.12587 -0.246339 - -0.0535982 1.1229 -0.250859 - -0.0531098 0.986633 -0.239985 - -0.0531808 0.983708 -0.243857 - -0.052998 0.907598 -0.242315 - -0.0530724 0.905568 -0.24627 - -0.0526656 0.820061 -0.234392 - -0.0525588 0.784288 -0.232616 - -0.0523427 0.717969 -0.228413 - -0.0523517 0.71262 -0.229404 - -0.0515563 0.563527 -0.204351 - -0.051622 0.55396 -0.208627 - -0.0513317 0.508195 -0.198609 - -0.0506481 0.452739 -0.169751 - -0.0505296 0.439545 -0.16511 - -0.0501994 0.39669 -0.15279 - -0.0424638 -0.0905752 0.129857 - -0.0424671 -0.0946186 0.128262 - -0.0424555 -0.0969393 0.129242 - -0.0425811 -0.142284 0.098958 - -0.0423548 -0.0929821 0.144444 - -0.0423441 -0.093967 0.145667 - -0.0426951 -0.23994 0.0556512 - -0.0426701 -0.255076 0.054916 - -0.0426009 -0.3287 0.0439907 - -0.042229 -0.439383 0.0650632 - -0.0418688 -0.505186 0.0970666 - -0.0417154 -0.513555 0.1162 - -0.0385877 -2.26558 0.0635011 - -0.0383721 -2.26744 0.0931693 - -0.0411628 -0.416999 0.220597 - -0.0411286 -0.42098 0.224274 - -0.0371582 -2.2082 0.279697 - -0.0363839 -2.18711 0.393993 - -0.0360027 -2.12706 0.464177 - -0.0352073 -2.10094 0.582841 - -0.0345709 -2.18871 0.647353 - -0.0329554 -2.21244 0.866866 - -0.0327176 -2.16238 0.91417 - -0.0316259 -2.2872 1.03206 - -0.0315781 -2.17841 1.06921 - -0.0310091 -2.14982 1.15687 - -0.0394311 -0.498684 0.440147 - -0.0397606 -0.410574 0.418695 - -0.0397643 -0.407009 0.419167 - -0.0397167 -0.407048 0.42583 - -0.0398213 -0.377744 0.419382 - -0.0391513 -0.408973 0.504443 - -0.0390629 -0.413355 0.515584 - -0.0390411 -0.413685 0.518555 - -0.0388391 -0.413624 0.546849 - -0.03868 -0.420283 0.567254 - -0.0386132 -0.420281 0.576605 - -0.038481 -0.376525 0.607362 - -0.0322251 -0.529449 1.44034 - -0.0263337 -0.660568 2.22838 - -0.0264962 -0.574621 2.2297 - -0.0267533 -0.435411 2.23268 - -0.0270592 -0.298594 2.22816 - -0.0272433 -0.20948 2.22734 - -0.0272074 -0.192718 2.23706 - -0.0272312 -0.175111 2.23866 - -0.0274648 -0.0514356 2.24059 - -0.0277232 0.0719636 2.23897 - -0.0278935 0.160425 2.23989 - -0.0281678 0.30359 2.24158 - -0.0284765 0.468918 2.24466 - -0.0287525 0.600741 2.24293 - -0.0288193 0.639868 2.24453 - -0.0288384 0.649611 2.24458 - -0.0288901 0.668507 2.24263 - -0.0290784 0.768509 2.24427 - -0.0292312 0.863035 2.24935 - -0.0302676 1.27593 2.21987 - -0.0313915 1.28098 2.06394 - -0.0318023 1.27478 2.0047 - -0.0325831 1.27596 1.89573 - -0.0330742 1.28106 1.82839 - -0.0336561 1.28347 1.74761 - -0.0339159 1.2727 1.70823 - -0.0341514 1.27953 1.67717 - -0.0346235 1.27517 1.60986 - -0.0349213 1.26788 1.56612 - -0.0362297 1.27191 1.38408 - -0.036369 1.27309 1.36492 - -0.0376418 1.27271 1.18663 - -0.0379954 1.27727 1.13839 - -0.0393415 1.28025 0.950793 - -0.0396458 1.28484 0.909468 - -0.0401617 1.27673 0.834984 - -0.0419099 1.16478 0.558895 - -0.0423363 1.16121 0.4982 - -0.0426412 1.16334 0.456116 - -0.0430934 1.16716 0.39388 - -0.0431681 1.16764 0.38355 - -0.0432018 1.16438 0.377917 - -0.0432363 1.16208 0.372446 - -0.0435719 1.16616 0.326615 - -0.043706 1.15787 0.305513 - -0.0437428 1.15823 0.300461 - -0.0441418 1.15874 0.244758 - -0.0446323 1.15208 0.174214 - -0.045154 1.15806 0.10286 - -0.0452729 1.16139 0.087142 - -0.0457643 1.16478 0.0193047 - -0.0462586 1.1552 -0.0525764 - -0.0464704 1.16059 -0.0807243 - -0.0476025 1.26478 -0.210033 - -0.0475657 1.12125 -0.245064 - -0.0474737 1.06325 -0.248437 - -0.0474412 1.04932 -0.247776 - -0.0469428 0.851713 -0.233335 - -0.0468999 0.832788 -0.232628 - -0.0455233 0.443353 -0.148962 - -0.0455383 0.439351 -0.152171 - -0.0428271 0.0942334 0.130749 - -0.0428292 0.0938418 0.130339 - -0.0415219 -0.0908843 0.128318 - -0.041506 -0.0964589 0.126851 - -0.0415083 -0.0980676 0.128549 - -0.0415633 -0.0955332 0.143988 - -0.0415647 -0.0961917 0.144825 - -0.0413044 -0.160775 0.104301 - -0.0410797 -0.221278 0.0722457 - -0.0409827 -0.258119 0.065028 - -0.0405735 -0.40095 0.0268312 - -0.0404656 -0.43339 0.0135379 - -0.0401671 -0.571524 0.006658 - -0.0405705 -0.450231 0.0563677 - -0.0402538 -0.590759 0.0453449 - -0.0402606 -0.591515 0.0479243 - -0.0403462 -0.565338 0.0582049 - -0.0406325 -0.495534 0.103565 - -0.0406936 -0.500135 0.125291 - -0.0407874 -0.483034 0.143723 - -0.0408255 -0.476071 0.151194 - -0.0370471 -2.25588 0.0835491 - -0.0410475 -0.439413 0.197159 - -0.0411317 -0.416864 0.209254 - -0.0411396 -0.415907 0.211094 - -0.0411672 -0.410986 0.216579 - -0.039024 -2.10655 0.602384 - -0.039354 -2.19387 0.758402 - -0.0393828 -2.19732 0.769426 - -0.0395105 -2.26214 0.848995 - -0.0418978 -0.368046 0.415903 - -0.0419278 -0.388102 0.437584 - -0.0421127 -0.420829 0.51499 - -0.0422602 -0.417858 0.558743 - -0.0426876 -0.476518 0.727157 - -0.0438412 -0.971735 1.38998 - -0.0439366 -0.951166 1.40676 - -0.0443042 -0.723556 1.37967 - -0.0445579 -0.64473 1.40937 - -0.0446541 -0.608838 1.41693 - -0.0448419 -0.556044 1.44234 - -0.0448928 -0.50494 1.42647 - -0.0451563 -0.532945 1.52526 - -0.0466702 -0.688106 2.08924 - -0.0467622 -0.6895 2.11854 - -0.0470396 -0.691895 2.20578 - -0.0472227 -0.642411 2.23179 - -0.0472633 -0.62335 2.23254 - -0.047477 -0.508324 2.2275 - -0.048008 -0.245203 2.22895 - -0.0481308 -0.183099 2.22853 - -0.0482973 -0.113054 2.23669 - -0.0485092 -0.00733534 2.23684 - -0.0487293 0.098479 2.23945 - -0.0487988 0.142301 2.23383 - -0.0489714 0.222465 2.23763 - -0.0491311 0.302996 2.23722 - -0.0491786 0.321532 2.24043 - -0.0494785 0.468467 2.2423 - -0.0496486 0.553045 2.24261 - -0.0496621 0.562134 2.24114 - -0.0497345 0.59191 2.24513 - -0.0498857 0.669135 2.24412 - -0.0502983 0.872276 2.24607 - -0.0503186 0.882706 2.24591 - -0.0503438 0.901982 2.24178 - -0.0505555 1.00943 2.24077 - -0.0506929 1.08537 2.2363 - -0.0508948 1.17147 2.24549 - -0.0510504 1.27146 2.23175 - -0.0508916 1.28388 2.17499 - -0.0507637 1.28254 2.13628 - -0.0499487 1.28022 1.88575 - -0.0497178 1.28117 1.81378 - -0.0491984 1.27394 1.65767 - -0.0488602 1.26961 1.55579 - -0.0482148 1.27285 1.35425 - -0.047909 1.27385 1.25909 - -0.0477667 1.27493 1.21445 - -0.0475755 1.27647 1.15438 - -0.0463235 1.2766 0.767225 - -0.0462164 1.27618 0.734385 - -0.0461892 1.28062 0.723229 - -0.0455302 1.1641 0.591554 - -0.0448634 1.16098 0.387329 - -0.0446535 1.16363 0.320809 - -0.0446111 1.15948 0.310262 - -0.0445708 1.16356 0.295271 - -0.0445506 1.16188 0.290073 - -0.0444487 1.16032 0.259532 - -0.0444103 1.15762 0.249329 - -0.0443315 1.15096 0.229065 - -0.0440513 1.15811 0.138029 - -0.0435871 1.14734 0.0011645 - -0.043451 1.16028 -0.0489013 - -0.0434323 1.15909 -0.0539615 - -0.0433404 1.15478 -0.0796838 - -0.0426543 1.0774 -0.243957 - -0.0423281 0.895328 -0.232238 - -0.0422351 0.849066 -0.232387 - -0.0418175 0.586672 -0.19925 - -0.0417347 0.441936 -0.135356 - -0.041887 0.130234 0.104474 - -0.0401867 -0.113429 0.105175 - -0.0401926 -0.113927 0.105671 - -0.0404442 -0.109838 0.123246 - -0.0404092 -0.114892 0.121448 - -0.040657 -0.102224 0.137508 - -0.0407695 -0.0965182 0.144808 - -0.0396071 -0.226295 0.0796298 - -0.0395563 -0.236681 0.0774602 - -0.0385569 -0.377083 0.0255831 - -0.0380277 -0.553722 0.0128835 - -0.0385789 -0.48142 0.0422406 - -0.038269 -0.605316 0.0377525 - -0.0391379 -0.501412 0.0854826 - -0.0392971 -0.49591 0.0961824 - -0.0395993 -0.505176 0.119338 - -0.0401799 -0.468725 0.155994 - -0.0403689 -0.456086 0.167807 - -0.0406381 -0.449783 0.186338 - -0.0410106 -0.418863 0.208767 - -0.0412293 -0.423959 0.225288 - -0.0394973 -2.18681 0.354812 - -0.0417702 -2.1569 0.514588 - -0.0425593 -2.11685 0.565775 - -0.0438418 -2.22801 0.674418 - -0.0460224 -2.25329 0.8355 - -0.0466056 -2.25084 0.877252 - -0.0467473 -2.24794 0.887066 - -0.0470069 -2.23151 0.903432 - -0.0482642 -2.25449 0.997525 - -0.0484959 -2.28222 1.01826 - -0.0486434 -2.27966 1.02854 - -0.0506984 -2.15716 1.15921 - -0.0438016 -0.424741 0.411116 - -0.0438132 -0.420262 0.411306 - -0.0438187 -0.407699 0.409886 - -0.0440277 -0.3672 0.419129 - -0.0454353 -0.416173 0.527821 - -0.0456215 -0.419449 0.541739 - -0.0461604 -0.414073 0.579873 - -0.0465 -0.37944 0.599385 - -0.0560214 -0.965271 1.3714 - -0.0563881 -0.824917 1.3776 - -0.0564572 -0.787084 1.37713 - -0.0566334 -0.724614 1.38083 - -0.0662189 -0.689615 2.06782 - -0.0684123 -0.689396 2.22614 - -0.0687421 -0.566119 2.23215 - -0.0688162 -0.528363 2.23205 - -0.0688891 -0.462164 2.22775 - -0.0690777 -0.389505 2.23087 - -0.0692119 -0.363318 2.23678 - -0.069275 -0.299329 2.2321 - -0.0693929 -0.254846 2.23418 - -0.069764 -0.051232 2.23158 - -0.0698098 -0.0248745 2.23107 - -0.0701613 0.107237 2.23737 - -0.0705563 0.28552 2.24015 - -0.070626 0.303888 2.24252 - -0.0711057 0.516425 2.24647 - -0.0713803 0.641375 2.24825 - -0.0714469 0.689673 2.24608 - -0.0717489 0.870694 2.24175 - -0.0721225 1.04451 2.24362 - -0.0722555 1.1018 2.24495 - -0.0722638 1.14487 2.23933 - -0.0724884 1.24136 2.2416 - -0.0720034 1.27706 2.20144 - -0.0701907 1.27462 2.07092 - -0.0691354 1.27963 1.99401 - -0.0609867 1.27488 1.40638 - -0.0604484 1.27681 1.36724 - -0.0600116 1.27518 1.33594 - -0.0587967 1.27293 1.24856 - -0.0577377 1.27709 1.1715 - -0.0570901 1.2723 1.12543 - -0.0561615 1.28012 1.05726 - -0.0555551 1.27434 1.01432 - -0.0551844 1.27945 0.986817 - -0.0531183 1.27224 0.838695 - -0.0519991 1.28317 0.756314 - -0.0518833 1.27996 0.748419 - -0.0517467 1.27392 0.739429 - -0.0500072 1.1738 0.6283 - -0.0497835 1.16406 0.613552 - -0.0490703 1.16138 0.562452 - -0.048907 1.15952 0.550931 - -0.0476612 1.16328 0.460445 - -0.0471333 1.15926 0.422909 - -0.0467785 1.16046 0.397119 - -0.0466737 1.15233 0.390731 - -0.0457743 1.1582 0.324951 - -0.0445012 1.15391 0.233652 - -0.0435239 1.15363 0.163139 - -0.0405917 1.16223 -0.0497988 - -0.0403768 1.15666 -0.0645105 - -0.0393973 1.26891 -0.151437 - -0.0377239 1.04037 -0.239245 - -0.0375913 0.9537 -0.236307 - -0.0375087 0.859186 -0.228621 - -0.0374591 0.639453 -0.200468 - -0.0373709 0.579159 -0.198132 - -0.0391349 0.309898 -0.0318899 - -0.0410307 0.0980313 0.135574 - -0.0381405 -0.13821 0.085657 - -0.038943 -0.122501 0.114448 - -0.0394117 -0.114306 0.131335 - -0.0377387 -0.245802 0.0786886 - -0.0368805 -0.317831 0.052028 - -0.0364493 -0.379096 0.0405032 - -0.0366 -0.376096 0.0459061 - -0.0368039 -0.372846 0.0532775 - -0.0367898 -0.401803 0.0549146 - -0.0361654 -0.565498 0.0438272 - -0.0371775 -0.518192 0.0780828 - -0.0376592 -0.50713 0.0952438 - -0.0377174 -0.507665 0.0974569 - -0.0379632 -0.524367 0.107884 - -0.0399113 -0.467063 0.176341 - -0.040371 -0.446185 0.191945 - -0.0407353 -0.428749 0.204244 - -0.042263 -2.18312 0.392342 - -0.0473689 -2.1528 0.580725 - -0.0482928 -2.11469 0.612373 - -0.0542163 -2.24577 0.843337 - -0.0555813 -2.23639 0.893605 - -0.0603822 -2.18121 1.06874 - -0.0466551 -0.410625 0.423928 - -0.0467049 -0.409726 0.425717 - -0.0485622 -0.422122 0.495994 - -0.0495561 -0.41586 0.532634 - -0.0496073 -0.414487 0.534444 - -0.0512593 -0.38817 0.59416 - -0.0512648 -0.377546 0.593572 - -0.0527658 -0.410632 0.652089 - -0.069261 -0.972724 1.30998 - -0.0715453 -0.94116 1.39292 - -0.0710293 -0.873207 1.36857 - -0.0714893 -0.781466 1.37889 - -0.0730091 -0.619542 1.42355 - -0.0733774 -0.519391 1.42981 - -0.0734483 -0.514101 1.43207 - -0.0870679 -0.690939 1.95381 - -0.0879365 -0.685897 1.98586 - -0.0946563 -0.68352 2.23659 - -0.0947533 -0.674706 2.23956 - -0.094646 -0.653341 2.23395 - -0.0948649 -0.596668 2.23789 - -0.0949517 -0.58785 2.24047 - -0.0952476 -0.363141 2.23474 - -0.095177 -0.353474 2.23138 - -0.0954565 -0.318596 2.23921 - -0.0954071 -0.300065 2.23598 - -0.0955615 -0.156946 2.23105 - -0.0957631 -0.077684 2.23266 - -0.0959637 -0.0337696 2.23687 - -0.096015 0.00146618 2.23615 - -0.0962574 0.10729 2.2373 - -0.0968791 0.376327 2.24041 - -0.0971257 0.53333 2.2379 - -0.0972451 0.553045 2.24088 - -0.09833 1.0241 2.2462 - -0.0983217 1.04542 2.24429 - -0.0943634 1.28086 2.07891 - -0.092468 1.27884 2.00829 - -0.0892349 1.28265 1.88729 - -0.0845389 1.2779 1.7123 - -0.0838562 1.27841 1.68677 - -0.0779426 1.27192 1.46646 - -0.0751167 1.27086 1.36102 - -0.074507 1.27819 1.33771 - -0.0728383 1.2732 1.27578 - -0.071216 1.2773 1.21489 - -0.0648557 1.27763 0.977389 - -0.0612053 1.27854 0.841019 - -0.0606266 1.27662 0.819553 - -0.0592785 1.28303 0.76874 - -0.0586727 1.27718 0.746559 - -0.0544674 1.16912 0.59761 - -0.053301 1.17202 0.553843 - -0.052728 1.17383 0.532313 - -0.0522388 1.16814 0.514473 - -0.0517018 1.17312 0.494049 - -0.0468916 1.16705 0.314899 - -0.0458903 1.15446 0.278454 - -0.0453582 1.15732 0.258373 - -0.0421095 1.15711 0.137085 - -0.0401866 1.16384 0.0647854 - -0.0375196 1.16467 -0.0348575 - -0.0359893 1.15405 -0.0912021 - -0.0338314 1.26148 -0.179799 - -0.03198 1.13176 -0.239237 - -0.0317172 1.10999 -0.247423 - -0.0318442 0.952063 -0.230883 - -0.0319699 0.769227 -0.212534 - -0.0319583 0.597675 -0.200151 - -0.0394942 0.132761 0.115957 - -0.0393033 0.122274 0.109615 - -0.0390084 0.133151 0.0977894 - -0.0382973 0.157297 0.0694338 - -0.0355462 -0.167733 0.0553979 - -0.0358104 -0.170424 0.0626167 - -0.039148 -0.102242 0.148329 - -0.0386956 -0.125021 0.137438 - -0.0371726 -0.202223 0.100794 - -0.0344718 -0.357425 0.0367956 - -0.0349828 -0.396666 0.0525806 - -0.0357588 -0.534517 0.0807474 - -0.0363194 -0.561018 0.0971769 - -0.0379377 -0.51168 0.137866 - -0.0400091 -0.444067 0.189704 - -0.0403662 -0.445589 0.199349 - -0.0408771 -0.416941 0.211494 - -0.0413993 -0.432928 0.226331 - -0.0469247 -2.17176 0.467462 - -0.0487333 -2.17572 0.516101 - -0.0491193 -2.18331 0.526844 - -0.0536034 -2.20147 0.647882 - -0.0608402 -2.25155 0.844337 - -0.0624884 -2.17319 0.884271 - -0.0687238 -2.19789 1.05255 - -0.0693947 -2.18587 1.06987 - -0.048484 -0.432997 0.416036 - -0.0485213 -0.403415 0.415447 - -0.0502476 -0.4089 0.461966 - -0.0502987 -0.406976 0.463231 - -0.050996 -0.409394 0.482032 - -0.0513728 -0.413408 0.492334 - -0.0523455 -0.41238 0.518325 - -0.0532614 -0.415045 0.542993 - -0.0535258 -0.420688 0.550373 - -0.0540355 -0.41874 0.563918 - -0.0551688 -0.394331 0.592953 - -0.079713 -0.964072 1.28068 - -0.0839454 -0.977485 1.39472 - -0.0841145 -0.97234 1.39897 - -0.0841429 -0.946163 1.39833 - -0.0833752 -0.878045 1.37413 - -0.0831052 -0.855965 1.36571 - -0.0834592 -0.784273 1.37135 - -0.0844574 -0.67003 1.39196 - -0.0849283 -0.649434 1.40346 - -0.0856746 -0.619085 1.42182 - -0.0857772 -0.600151 1.42355 - -0.11598 -0.595251 2.23199 - -0.116317 -0.568826 2.2396 - -0.116107 -0.557597 2.23339 - -0.115882 -0.508324 2.22472 - -0.116402 -0.464631 2.23629 - -0.116368 -0.399251 2.23188 - -0.11653 -0.381653 2.23529 - -0.117289 -0.0691326 2.23885 - -0.117453 -0.0250229 2.24087 - -0.117654 0.107449 2.23916 - -0.117579 0.116157 2.23668 - -0.118271 0.376693 2.24124 - -0.118367 0.422601 2.24135 - -0.118497 0.469144 2.24236 - -0.118332 0.514203 2.23552 - -0.119235 0.662774 2.25175 - -0.119247 0.800445 2.24469 - -0.118996 0.838012 2.23596 - -0.119142 0.859904 2.23869 - -0.119494 0.925823 2.24458 - -0.119651 1.01256 2.24413 - -0.119627 1.03384 2.24234 - -0.119697 1.05657 2.243 - -0.119984 1.11592 2.2475 - -0.120178 1.17547 2.2495 - -0.120159 1.19825 2.24778 - -0.107615 1.27587 1.90774 - -0.106109 1.27951 1.86722 - -0.100627 1.2746 1.7207 - -0.100165 1.2753 1.70829 - -0.0979531 1.27953 1.64884 - -0.0926825 1.27028 1.50821 - -0.0898396 1.28117 1.43151 - -0.0863248 1.27894 1.33752 - -0.0850564 1.27371 1.30383 - -0.0844038 1.27547 1.28627 - -0.0824308 1.26805 1.23383 - -0.0819847 1.2753 1.2215 - -0.0746969 1.27158 1.02656 - -0.0743454 1.26917 1.01728 - -0.0735628 1.28379 0.995541 - -0.0659822 1.27871 0.792836 - -0.0648844 1.27292 0.763753 - -0.0642749 1.27996 0.747055 - -0.0578586 1.21988 0.578472 - -0.0573695 1.21529 0.565623 - -0.0543149 1.18523 0.485445 - -0.0541242 1.18639 0.480274 - -0.0507737 1.16617 0.391645 - -0.0478754 1.16406 0.314153 - -0.0474835 1.16186 0.303779 - -0.0467452 1.16717 0.283726 - -0.0455787 1.15948 0.252904 - -0.0440579 1.15398 0.212477 - -0.0421775 1.15662 0.161987 - -0.0403011 1.1451 0.112362 - -0.0395119 1.16196 0.0903258 - -0.0352742 1.15608 -0.0228262 - -0.0339042 1.154 -0.0593978 - -0.0337139 1.15278 -0.0644268 - -0.0333193 1.1522 -0.0749621 - -0.0319821 1.21732 -0.114256 - -0.0270399 1.04695 -0.23746 - -0.027183 1.02299 -0.232343 - -0.0268794 0.977573 -0.238037 - -0.0273475 0.755018 -0.213579 - -0.0369624 0.165803 0.0754453 - -0.0357435 0.187791 0.0416284 - -0.0346617 -0.155249 0.0723408 - -0.034318 -0.163934 0.0655321 - -0.0341135 -0.169742 0.0615062 - -0.0342194 -0.174618 0.0639199 - -0.0352729 -0.162719 0.0854078 - -0.0365939 -0.133903 0.111772 - -0.0373411 -0.120262 0.126794 - -0.0382068 -0.10199 0.144098 - -0.0384445 -0.0980471 0.148893 - -0.0385498 -0.102075 0.151259 - -0.0373266 -0.153435 0.127878 - -0.0362284 -0.204845 0.107108 - -0.0322836 -0.370721 0.0317178 - -0.0330621 -0.354999 0.0473064 - -0.0336813 -0.397401 0.0619998 - -0.0304688 -0.571524 0.00223574 - -0.0348101 -0.382452 0.0849325 - -0.0325708 -0.589594 0.0468562 - -0.03474 -0.510878 0.0888356 - -0.0384521 -0.458836 0.164127 - -0.0392761 -0.450474 0.180974 - -0.0404728 -0.431807 0.205167 - -0.0468211 -2.1885 0.41105 - -0.0477384 -2.18673 0.430118 - -0.0523451 -2.18133 0.526029 - -0.053735 -2.18008 0.554981 - -0.055313 -2.13346 0.585964 - -0.0697733 -2.19518 0.89031 - -0.0501897 -0.420184 0.40746 - -0.0505901 -0.408773 0.415338 - -0.0509965 -0.407941 0.423784 - -0.0512814 -0.40163 0.429467 - -0.0508901 -0.380403 0.420413 - -0.0552252 -0.404294 0.511878 - -0.0567562 -0.413624 0.544218 - -0.0579298 -0.418004 0.568893 - -0.0598584 -0.379314 0.607523 - -0.0950217 -0.980479 1.36645 - -0.0966447 -0.947413 1.39894 - -0.0961744 -0.762377 1.38139 - -0.0964419 -0.743846 1.3862 - -0.0965675 -0.738203 1.38859 - -0.0970631 -0.673004 1.39621 - -0.0973355 -0.669326 1.40174 - -0.100205 -0.577662 1.45778 - -0.137391 -0.586733 2.23418 - -0.137878 -0.391216 2.23619 - -0.13793 -0.345529 2.23536 - -0.137965 -0.291115 2.23382 - -0.137814 -0.263635 2.22952 - -0.138805 -0.0870308 2.24281 - -0.139274 0.258789 2.23816 - -0.139293 0.276699 2.2378 - -0.139832 0.469144 2.241 - -0.140019 0.535117 2.24216 - -0.140367 0.612739 2.24617 - -0.140547 0.671646 2.24747 - -0.140423 0.680505 2.24452 - -0.141677 1.19977 2.24898 - -0.117392 1.27961 1.73886 - -0.116203 1.28115 1.71398 - -0.110646 1.27918 1.59808 - -0.0915685 1.27214 1.20026 - -0.0879529 1.27475 1.1247 - -0.0818167 1.27441 0.996662 - -0.0804874 1.27834 0.968757 - -0.0735724 1.27579 0.824557 - -0.0682637 1.27907 0.713635 - -0.062458 1.17102 0.596992 - -0.0619421 1.17238 0.586171 - -0.0603045 1.2603 0.548321 - -0.0583371 1.23835 0.508182 - -0.0567679 1.22091 0.476164 - -0.0549483 1.19973 0.439077 - -0.0522439 1.18448 0.383277 - -0.0486182 1.16347 0.308491 - -0.0471406 1.16045 0.277781 - -0.0459131 1.15648 0.252333 - -0.0454185 1.15274 0.242167 - -0.0434992 1.15789 0.201899 - -0.0418045 1.16085 0.166409 - -0.0410759 1.16008 0.151236 - -0.040833 1.15978 0.14618 - -0.0389072 1.15059 0.106374 - -0.036919 1.15988 0.0644966 - -0.0321984 1.15686 -0.0338907 - -0.0273398 1.26633 -0.139856 - -0.0268052 1.26316 -0.150881 - -0.0262717 1.25989 -0.161877 - -0.0226103 1.27025 -0.238718 - -0.0223014 1.11494 -0.238675 - -0.0224493 0.92289 -0.227564 - -0.0226098 0.862173 -0.221677 - -0.0228519 0.812879 -0.214566 - -0.0230762 0.72704 -0.206299 - -0.0365595 0.175976 0.0981054 - -0.0373168 0.129503 0.11585 - -0.0341256 0.199114 0.0463474 - -0.0329593 -0.145607 0.0748524 - -0.0316268 -0.185111 0.0542423 - -0.032126 -0.186941 0.0625121 - -0.0333005 -0.167368 0.0811803 - -0.0364084 -0.119797 0.130721 - -0.0365876 -0.116928 0.133573 - -0.0374054 -0.120988 0.147155 - -0.0371241 -0.133546 0.142943 - -0.0361737 -0.163136 0.12829 - -0.0353846 -0.193001 0.116298 - -0.0309982 -0.342727 0.0490984 - -0.0326523 -0.31313 0.0753246 - -0.0322487 -0.369773 0.0705541 - -0.0318853 -0.476013 0.0680784 - -0.0309812 -0.565338 0.0561537 - -0.0339794 -0.515566 0.103818 - -0.0357357 -0.510957 0.132547 - -0.0382826 -0.466872 0.172977 - -0.0387364 -0.455457 0.180063 - -0.0516893 -2.20568 0.450735 - -0.0522801 -2.20563 0.460449 - -0.0540325 -2.20127 0.489122 - -0.0679872 -2.21171 0.718942 - -0.0723715 -2.2147 0.791139 - -0.0874892 -2.22854 1.0402 - -0.0919294 -2.15568 1.11081 - -0.0533806 -0.414196 0.419518 - -0.0564273 -0.407135 0.469387 - -0.0576687 -0.411741 0.489954 - -0.057891 -0.409343 0.493529 - -0.0580016 -0.408132 0.49531 - -0.0599253 -0.414823 0.527163 - -0.0618844 -0.414884 0.559381 - -0.0623345 -0.416473 0.566835 - -0.0634339 -0.415402 0.584879 - -0.109076 -0.970746 1.35374 - -0.112415 -0.815327 1.40352 - -0.115484 -0.606366 1.4471 - -0.115716 -0.594726 1.45054 - -0.115821 -0.549009 1.45075 - -0.159016 -0.689561 2.16571 - -0.163854 -0.465752 2.23788 - -0.163606 -0.381468 2.23103 - -0.164061 -0.346204 2.23736 - -0.164111 -0.282722 2.23609 - -0.164004 -0.237486 2.23284 - -0.164332 -0.166548 2.2359 - -0.164512 -0.148969 2.23826 - -0.16487 0.0191424 2.23862 - -0.164539 0.0719279 2.23144 - -0.16478 0.0808911 2.2351 - -0.165486 0.10798 2.24582 - -0.164928 0.169403 2.23462 - -0.164869 0.187032 2.23306 - -0.164961 0.258281 2.23224 - -0.165522 0.304333 2.23995 - -0.16566 0.349824 2.24071 - -0.165822 0.423214 2.24096 - -0.165726 0.432056 2.23909 - -0.166125 0.451886 2.24499 - -0.166351 0.583896 2.24436 - -0.166305 0.641074 2.24172 - -0.166988 0.664012 2.25219 - -0.166801 0.7021 2.24786 - -0.166574 0.73036 2.24321 - -0.166886 0.772059 2.24697 - -0.166597 0.87188 2.23891 - -0.16714 0.970554 2.2446 - -0.167348 1.07052 2.24473 - -0.166811 1.09941 2.23495 - -0.152205 1.27963 1.98882 - -0.150825 1.275 1.96628 - -0.134638 1.27075 1.70023 - -0.133987 1.28366 1.6891 - -0.108765 1.27551 1.27461 - -0.108035 1.2724 1.2627 - -0.107059 1.27527 1.24655 - -0.10308 1.27191 1.18125 - -0.0968297 1.28066 1.07817 - -0.0927567 1.27519 1.01137 - -0.0919597 1.27867 0.99815 - -0.0915279 1.27951 0.991022 - -0.079812 1.27983 0.798351 - -0.0777216 1.27752 0.764052 - -0.0750093 1.27969 0.719378 - -0.0654304 1.27087 0.562149 - -0.0603625 1.26512 0.479 - -0.0599455 1.26037 0.472298 - -0.0472241 1.15194 0.266676 - -0.0414188 1.16407 0.170812 - -0.0411178 1.15286 0.166231 - -0.0389577 1.15874 0.130515 - -0.0374164 1.15756 0.105208 - -0.0343004 1.15849 0.0539379 - -0.0336842 1.15702 0.0438533 - -0.0312353 1.14927 0.00383745 - -0.0306232 1.14736 -0.00616483 - -0.0298999 1.15614 -0.0183482 - -0.0234603 1.26458 -0.127818 - -0.01975 1.26829 -0.188953 - -0.0180044 1.26195 -0.21745 - -0.0167524 1.14594 -0.234216 - -0.0168545 0.939405 -0.225732 - -0.0171249 0.836133 -0.217883 - -0.0168998 0.834222 -0.22152 - -0.0183599 0.696758 -0.19298 - -0.0326085 0.256137 0.055847 - -0.0380437 0.0946816 0.150545 - -0.0372811 0.111127 0.137462 - -0.0370805 0.11482 0.134042 - -0.0316754 0.196085 0.042481 - -0.0308591 -0.152089 0.0668626 - -0.0338037 -0.146709 0.107919 - -0.0353182 -0.124624 0.128493 - -0.0363859 -0.109164 0.143 - -0.0369091 -0.104337 0.150187 - -0.0372723 -0.100386 0.155158 - -0.0365954 -0.125382 0.146387 - -0.0350006 -0.176582 0.125506 - -0.0314725 -0.293143 0.0794042 - -0.0320321 -0.283435 0.0869629 - -0.0313416 -0.3278 0.0785445 - -0.0312775 -0.357991 0.0784949 - -0.0302697 -0.406625 0.0657559 - -0.0322528 -0.350208 0.0919251 - -0.0320095 -0.485132 0.0923061 - -0.0336747 -0.499834 0.116021 - -0.0398597 -0.428681 0.200579 - -0.0404452 -0.413907 0.208357 - -0.041467 -0.421959 0.222882 - -0.0417203 -0.445886 0.227098 - -0.0430991 -2.20859 0.295854 - -0.0603966 -2.20471 0.537807 - -0.0713098 -2.22689 0.691149 - -0.0840927 -2.24028 0.87041 - -0.0900481 -2.19767 0.952554 - -0.100034 -2.16433 1.09137 - -0.0560654 -0.416868 0.42703 - -0.0585631 -0.420509 0.462085 - -0.0589746 -0.409084 0.467523 - -0.0610935 -0.415972 0.497368 - -0.0631782 -0.414823 0.52651 - -0.0648222 -0.414656 0.549511 - -0.0663182 -0.421832 0.570648 - -0.0681119 -0.417207 0.595619 - -0.125039 -0.880066 1.40525 - -0.125548 -0.86905 1.41206 - -0.125828 -0.863815 1.41583 - -0.126659 -0.6271 1.42082 - -0.125452 -0.559221 1.40202 - -0.158848 -0.660609 1.87221 - -0.184558 -0.67439 2.23238 - -0.184893 -0.549581 2.23357 - -0.185449 -0.429112 2.23797 - -0.185815 -0.411614 2.2426 - -0.185719 -0.346878 2.23944 - -0.18554 -0.300947 2.23565 - -0.185553 -0.175284 2.2323 - -0.185833 -0.157801 2.23574 - -0.186255 0.0986251 2.23445 - -0.18624 0.107449 2.234 - -0.186912 0.187954 2.24113 - -0.187561 0.414965 2.24384 - -0.187809 0.461852 2.246 - -0.187551 0.479586 2.2419 - -0.187346 0.525516 2.23773 - -0.187187 0.543695 2.235 - -0.18831 0.576391 2.2498 - -0.188299 0.653278 2.24748 - -0.188221 0.721497 2.24449 - -0.188485 0.95912 2.24151 - -0.188513 1.03521 2.23977 - -0.189203 1.18786 2.24514 - -0.183508 1.28113 2.16282 - -0.166543 1.28106 1.92542 - -0.158671 1.27669 1.81539 - -0.152759 1.27704 1.73263 - -0.145387 1.27706 1.62947 - -0.144623 1.27852 1.61874 - -0.130223 1.27028 1.41746 - -0.1287 1.26976 1.39616 - -0.126404 1.26809 1.36407 - -0.112655 1.27212 1.17156 - -0.109621 1.2724 1.12909 - -0.10481 1.28146 1.06151 - -0.103767 1.27176 1.04719 - -0.100204 1.27867 0.997131 - -0.0996193 1.2778 0.988975 - -0.0991129 1.27859 0.981867 - -0.0906435 1.27461 0.863457 - -0.0865842 1.28454 0.806372 - -0.0854523 1.27962 0.79067 - -0.0839979 1.27878 0.77034 - -0.0814191 1.27114 0.734467 - -0.0801595 1.27503 0.716731 - -0.0723378 1.16501 0.610361 - -0.0706137 1.22787 0.58447 - -0.0598932 1.26857 0.433305 - -0.0584655 1.25253 0.413775 - -0.0492913 1.17386 0.287599 - -0.0489268 1.17415 0.28249 - -0.0430637 1.15889 0.200869 - -0.0401658 1.16661 0.160099 - -0.0322678 1.14688 0.0501271 - -0.0285031 1.1552 -0.00278956 - -0.0244732 1.14817 -0.0589869 - -0.0194271 1.26017 -0.132745 - -0.0147823 1.2571 -0.197658 - -0.0118889 1.11693 -0.234215 - -0.0118696 1.0332 -0.232137 - -0.0119966 0.990759 -0.229169 - -0.0119352 0.968662 -0.229407 - -0.0123674 0.85861 -0.220272 - -0.0123441 0.84958 -0.220344 - -0.0137093 0.718498 -0.197561 - -0.0383996 0.0811525 0.16584 - -0.0365768 0.115179 0.139377 - -0.0299458 0.195351 0.0443333 - -0.0295756 -0.145838 0.0701831 - -0.0284455 -0.173416 0.057063 - -0.027955 -0.18442 0.0513445 - -0.0275677 -0.197848 0.0469453 - -0.030666 -0.168939 0.0840604 - -0.030844 -0.170666 0.086276 - -0.0316356 -0.164075 0.0957782 - -0.0322413 -0.155726 0.102968 - -0.0337747 -0.138106 0.121254 - -0.0356379 -0.113274 0.143391 - -0.0367813 -0.100594 0.157039 - -0.0369117 -0.103869 0.158712 - -0.0301851 -0.322868 0.0819608 - -0.0304954 -0.337481 0.0861062 - -0.0339153 -0.486556 0.131507 - -0.0394372 -0.440593 0.19779 - -0.0406438 -0.404968 0.211647 - -0.0462574 -2.21237 0.324451 - -0.0470535 -2.21487 0.334231 - -0.0678342 -2.14725 0.586258 - -0.069812 -2.11764 0.609676 - -0.0812339 -2.22828 0.751819 - -0.0820319 -2.22592 0.761504 - -0.086745 -2.20796 0.818599 - -0.0984964 -2.19633 0.961771 - -0.114598 -2.16632 1.15759 - -0.0585321 -0.434826 0.430751 - -0.059096 -0.424717 0.437388 - -0.0574708 -0.368078 0.41616 - -0.0620062 -0.410268 0.47256 - -0.0632179 -0.413764 0.487438 - -0.0638415 -0.413486 0.495044 - -0.0669964 -0.417669 0.533661 - -0.0724778 -0.41608 0.600536 - -0.0717899 -0.388889 0.591472 - -0.0779661 -0.425169 0.667757 - -0.0827925 -0.477707 0.727963 - -0.137443 -0.840611 1.40401 - -0.137769 -0.819853 1.40747 - -0.138629 -0.79612 1.41739 - -0.138648 -0.758457 1.4167 - -0.139041 -0.710183 1.42031 - -0.138075 -0.681924 1.40783 - -0.142728 -0.622429 1.46317 - -0.138454 -0.556986 1.4094 - -0.205996 -0.646973 2.23613 - -0.206105 -0.588966 2.23604 - -0.205941 -0.578745 2.23379 - -0.206835 -0.402361 2.24038 - -0.206994 -0.393497 2.24211 - -0.206824 -0.374659 2.23957 - -0.206015 -0.327251 2.22853 - -0.206897 -0.229461 2.2369 - -0.206994 -0.220615 2.23787 - -0.206851 -0.148969 2.23436 - -0.206699 0.00146691 2.22883 - -0.207068 0.0632484 2.23182 - -0.208872 0.471175 2.24385 - -0.208391 0.525768 2.23664 - -0.208482 0.718152 2.23303 - -0.209555 1.02455 2.23863 - -0.210505 1.22521 2.24532 - -0.207287 1.28518 2.20455 - -0.199845 1.27419 2.11398 - -0.195208 1.28326 2.05715 - -0.192151 1.28084 2.01989 - -0.175574 1.27981 1.81755 - -0.146352 1.27263 1.46099 - -0.143858 1.27441 1.43051 - -0.142738 1.28208 1.41665 - -0.13846 1.27031 1.3647 - -0.133029 1.27295 1.29834 - -0.127827 1.27507 1.23478 - -0.126412 1.27608 1.21749 - -0.125002 1.27689 1.20026 - -0.120602 1.27486 1.14659 - -0.119313 1.27646 1.13081 - -0.117143 1.27443 1.10437 - -0.108993 1.28035 1.00474 - -0.10335 1.2782 0.935902 - -0.0999138 1.28077 0.893896 - -0.0986562 1.27866 0.878595 - -0.0947379 1.28034 0.830721 - -0.0903381 1.28093 0.776996 - -0.0898863 1.28337 0.77142 - -0.0853508 1.27596 0.716235 - -0.083422 1.28078 0.69257 - -0.0795624 1.2069 0.647263 - -0.0711526 1.21105 0.544499 - -0.0689771 1.25944 0.516756 - -0.0678159 1.27205 0.502271 - -0.0636404 1.27643 0.451191 - -0.0512992 1.17981 0.302902 - -0.049943 1.16687 0.286663 - -0.0486913 1.16669 0.271387 - -0.0449164 1.15496 0.225592 - -0.0424495 1.15881 0.195383 - -0.0420365 1.1587 0.190344 - -0.0399651 1.16185 0.16498 - -0.0387223 1.16108 0.149827 - -0.0282909 1.15677 0.0225902 - -0.0239713 1.1599 -0.0302181 - -0.0228236 1.15071 -0.0440034 - -0.0211077 1.14986 -0.0649297 - -0.0208031 1.1428 -0.0684755 - -0.0169528 1.2487 -0.118073 - -0.0148354 1.25803 -0.14415 - -0.0127921 1.26204 -0.169191 --0.00891475 1.25817 -0.21643 --0.00722698 1.13003 -0.233895 --0.00882472 0.861584 -0.207814 - -0.0370256 0.0994463 0.155122 - -0.0354284 0.122166 0.135067 - -0.028102 0.218221 0.0432759 - -0.0277858 0.207462 0.0396798 - -0.028047 0.194594 0.0431837 - -0.0279764 0.193833 0.0423392 - -0.0283797 0.178319 0.0476431 - -0.0285268 0.173239 0.0495638 - -0.0260288 -0.188128 0.0492175 - -0.0274109 -0.190402 0.0642326 - -0.0280149 -0.184019 0.0706339 - -0.0315549 -0.154898 0.108332 - -0.0309835 -0.258692 0.104402 - -0.0297789 -0.501829 0.096646 - -0.0394315 -0.431678 0.199641 - -0.0407176 -0.404986 0.212986 - -0.0437858 -2.21891 0.28566 - -0.0509107 -2.21514 0.362728 - -0.0563841 -2.23144 0.422349 - -0.0739479 -2.12452 0.610208 - -0.0820039 -2.22675 0.699663 - -0.0846935 -2.22021 0.728644 - -0.107283 -2.2342 0.973548 - -0.117105 -2.19422 1.07904 - -0.119102 -2.16419 1.10001 - -0.121189 -2.16559 1.12264 - -0.060535 -0.43576 0.428243 - -0.0638377 -0.484332 0.465061 - -0.0657186 -0.413269 0.483882 - -0.0655937 -0.407076 0.482395 - -0.0658746 -0.403897 0.485368 - -0.0691329 -0.416709 0.520928 - -0.0700788 -0.415283 0.53114 - -0.0757878 -0.404895 0.592732 - -0.0762317 -0.392255 0.597263 - -0.149053 -0.91685 1.39719 - -0.150412 -0.761557 1.40853 - -0.150957 -0.72852 1.41371 - -0.152962 -0.662838 1.43399 - -0.19005 -0.647293 1.83526 - -0.201099 -0.686652 1.95576 - -0.226962 -0.541013 2.23263 - -0.226047 -0.491259 2.22164 - -0.226836 -0.428076 2.22882 - -0.226715 -0.327091 2.22531 - -0.227819 -0.175802 2.23397 - -0.227905 -0.166959 2.23472 - -0.228482 -0.0605785 2.23864 - -0.228209 -0.0073717 2.23454 - -0.228936 0.0991121 2.24009 - -0.229028 0.197097 2.23895 - -0.228687 0.250329 2.2341 - -0.228856 0.304482 2.23475 - -0.229956 0.342634 2.24584 - -0.22971 0.360409 2.24278 - -0.230571 0.615339 2.24656 - -0.230553 0.703078 2.24446 - -0.230434 0.772414 2.24167 - -0.230529 0.813368 2.2418 - -0.231149 0.962965 2.24527 - -0.230563 1.00326 2.23804 - -0.231449 1.10849 2.24535 - -0.231265 1.11881 2.24313 - -0.218412 1.27857 2.10048 - -0.207383 1.28971 1.98082 - -0.176932 1.27725 1.65136 - -0.174674 1.27773 1.62689 - -0.167272 1.27029 1.54691 - -0.154737 1.2777 1.41102 - -0.15094 1.27772 1.3699 - -0.149051 1.2664 1.34969 - -0.135534 1.27099 1.20323 - -0.133722 1.26848 1.18367 - -0.130191 1.27486 1.14529 - -0.12673 1.28098 1.10768 - -0.122914 1.28025 1.06638 - -0.121831 1.27479 1.05477 - -0.120754 1.26925 1.04322 - -0.119387 1.27056 1.0284 - -0.117114 1.28035 1.00357 - -0.114053 1.27591 0.970524 - -0.103599 1.2801 0.857235 - -0.101692 1.28033 0.836572 - -0.101099 1.28124 0.830139 - -0.0992026 1.28104 0.809605 - -0.0883796 1.28265 0.692377 - -0.0772181 1.16156 0.574151 - -0.0733332 1.18639 0.531545 - -0.0711132 1.22053 0.506763 - -0.0699595 1.23791 0.493893 - -0.0670506 1.27433 0.461602 - -0.0543126 1.20401 0.325202 - -0.0463341 1.14774 0.240034 - -0.0458738 1.14784 0.235047 - -0.0310655 1.14827 0.0746907 - -0.0286116 1.15777 0.0479124 - -0.0218705 1.18847 -0.025749 - -0.0213917 1.1874 -0.0309102 --0.00779423 1.25671 -0.179653 --0.00492642 0.776641 -0.200266 - -0.0353764 0.120808 0.143716 - -0.035517 0.110124 0.145471 - -0.0277228 0.221324 0.0586552 - -0.0276328 0.220632 0.0576952 - -0.0269682 0.20277 0.0508876 - -0.0245873 -0.192502 0.0524317 - -0.0272215 -0.180985 0.0777997 - -0.0308711 -0.149615 0.112645 - -0.0320558 -0.147627 0.124116 - -0.0321211 -0.148027 0.124757 - -0.0358269 -0.101497 0.159852 - -0.0327177 -0.186603 0.131308 - -0.0316683 -0.212924 0.121626 - -0.0300003 -0.259662 0.106334 - -0.0295848 -0.315375 0.103385 - -0.0303726 -0.298894 0.110717 - -0.0352431 -0.465788 0.161297 - -0.0356847 -0.46426 0.165557 - -0.0369285 -0.465423 0.177664 - -0.0634901 -2.22641 0.47012 - -0.0769485 -2.11836 0.598764 - -0.0848543 -2.22209 0.677599 - -0.0858506 -2.22005 0.687239 - -0.0959759 -2.16383 0.784512 - -0.113069 -2.2379 0.952024 - -0.12492 -2.16353 1.06571 - -0.132973 -2.16675 1.14402 - -0.0652164 -0.476826 0.452716 - -0.0619723 -0.368066 0.419074 - -0.0655566 -0.415517 0.454824 - -0.0679696 -0.417597 0.478308 - -0.0693665 -0.402796 0.491591 - -0.0698537 -0.398316 0.496236 - -0.0740093 -0.420242 0.537038 - -0.0750155 -0.41767 0.546763 - -0.0797521 -0.394857 0.592336 - -0.0803572 -0.383679 0.597997 - -0.106061 -0.590091 0.851751 - -0.157667 -0.840598 1.35802 - -0.158072 -0.753066 1.36025 - -0.15643 -0.707147 1.34339 - -0.156645 -0.694619 1.34524 - -0.159043 -0.681289 1.36828 - -0.16683 -0.669033 1.4437 - -0.235096 -0.690524 2.10735 - -0.247593 -0.67534 2.22847 - -0.248896 -0.256477 2.23294 - -0.249464 -0.140548 2.2362 - -0.249776 -0.0695085 2.23784 - -0.249629 0.0014749 2.23503 - -0.249253 0.0279913 2.23085 - -0.250668 0.17074 2.24182 - -0.251401 0.288458 2.24663 - -0.251026 0.324204 2.24229 - -0.250923 0.433934 2.23915 - -0.251803 0.548366 2.24547 - -0.251936 0.56776 2.24638 - -0.251698 0.576663 2.24389 - -0.252049 0.587212 2.2471 - -0.251495 0.614472 2.24118 - -0.251072 0.632516 2.23672 - -0.252947 1.03131 2.24714 - -0.25406 1.20943 2.25448 - -0.239219 1.28585 2.1088 - -0.228758 1.27507 2.00737 - -0.21938 1.27866 1.9162 - -0.199039 1.28107 1.71853 - -0.187919 1.27582 1.61059 - -0.160182 1.26986 1.34123 - -0.158442 1.27292 1.32427 - -0.148742 1.27273 1.23004 - -0.147856 1.27325 1.22141 - -0.147035 1.27451 1.21341 - -0.134474 1.28298 1.09121 - -0.116955 1.28183 0.921025 - -0.108755 1.265 0.841691 - -0.0997554 1.27805 0.753999 - -0.0850433 1.16422 0.613288 - -0.0819874 1.15933 0.583695 - -0.0745214 1.17298 0.510892 - -0.0735559 1.17844 0.501405 - -0.072532 1.18188 0.491391 - -0.068738 1.26262 0.452953 - -0.0596318 1.27223 0.364294 - -0.0574626 1.23728 0.343903 - -0.0568135 1.22987 0.337741 - -0.0486858 1.16313 0.26008 - -0.0439836 1.151 0.214632 - -0.0419274 1.15781 0.194523 - -0.021665 1.17876 -0.00274539 - -0.0168451 1.14761 -0.0489641 - -0.0164384 1.14158 -0.0527979 - -0.0158161 1.14525 -0.0589156 --0.00354871 1.25862 -0.180313 --0.00235906 1.257 -0.191839 --0.00173382 1.2571 -0.197916 - 0.00137386 1.25621 -0.228091 --0.00020911 1.08176 -0.209304 - -0.0365903 0.0966315 0.163399 - -0.0365566 0.094191 0.163119 - -0.0364294 0.0934913 0.161897 - -0.0272267 0.220873 0.0700005 - -0.0255179 0.214006 0.0535332 - -0.0250367 0.210399 0.0489285 - -0.024535 0.196105 0.0443332 - -0.0249102 0.175412 0.0483827 - -0.0248306 0.174677 0.0476231 - -0.0217403 -0.183646 0.0423949 - -0.0222185 -0.190368 0.0467273 - -0.0219688 -0.197858 0.0446601 - -0.0232097 -0.195338 0.0555474 - -0.0248909 -0.190511 0.0702733 - -0.0249836 -0.191146 0.0711008 - -0.0268584 -0.175898 0.087347 - -0.0281355 -0.16668 0.0984349 - -0.0303875 -0.151032 0.117997 - -0.0351796 -0.104867 0.159397 - -0.0348497 -0.11358 0.156644 - -0.0326001 -0.158803 0.137628 - -0.0317806 -0.190992 0.130979 - -0.0292294 -0.266645 0.109845 - -0.0296648 -0.308725 0.114427 - -0.0249597 -0.46104 0.0756762 - -0.0242357 -0.503172 0.0700453 - -0.0346488 -0.449663 0.160835 - -0.0348091 -0.45387 0.162322 - -0.0355961 -0.462693 0.169412 - -0.0357473 -0.468863 0.170852 - -0.0415507 -0.422959 0.221166 - -0.0528407 -2.22474 0.35258 - -0.0966089 -2.17967 0.737374 - -0.119109 -2.19232 0.935822 - -0.127384 -2.25139 1.00977 - -0.1308 -2.18106 1.03862 - -0.13188 -2.17743 1.04806 - -0.135869 -2.18392 1.08332 - -0.0652151 -0.442049 0.429985 - -0.0742283 -0.40963 0.508815 - -0.0830669 -0.418266 0.586836 - -0.0839898 -0.416283 0.594931 - -0.0857062 -0.382468 0.609453 - -0.164257 -0.9322 1.31122 - -0.162282 -0.900819 1.29327 - -0.157121 -0.7379 1.24491 - -0.155852 -0.716225 1.23335 - -0.162789 -0.663829 1.29353 - -0.179028 -0.666174 1.43664 - -0.181871 -0.665737 1.46168 - -0.183297 -0.665373 1.47423 - -0.185857 -0.662979 1.49674 - -0.205696 -0.66659 1.67159 - -0.212135 -0.66866 1.72835 - -0.230341 -0.679061 1.88893 - -0.24885 -0.689615 2.05218 - -0.25482 -0.690524 2.10479 - -0.27035 -0.375385 2.23602 - -0.270439 -0.366331 2.23664 - -0.270193 -0.274834 2.23285 - -0.271457 -0.15007 2.24177 - -0.270901 0.134504 2.23183 - -0.271804 0.19758 2.23866 - -0.273677 0.38145 2.25191 - -0.27291 0.435603 2.24419 - -0.27295 0.454275 2.24421 - -0.272864 0.482115 2.24296 - -0.273176 0.577479 2.24402 - -0.27331 0.704383 2.24295 - -0.274059 0.91176 2.24587 - -0.273433 0.951947 2.23964 - -0.273244 1.04955 2.23625 - -0.274221 1.09911 2.24397 - -0.274067 1.16759 2.24141 - -0.260331 1.28198 2.11836 - -0.257917 1.27969 2.09714 - -0.245893 1.2771 1.99125 - -0.218477 1.28639 1.74956 - -0.183849 1.27233 1.44473 - -0.15832 1.27325 1.21981 - -0.148912 1.27892 1.13683 - -0.147818 1.27727 1.12721 - -0.146239 1.28115 1.11324 - -0.137468 1.27454 1.03608 - -0.127967 1.27469 0.952381 - -0.122416 1.2783 0.903414 - -0.116291 1.2829 0.84937 - -0.114627 1.28123 0.834743 - -0.106374 1.28395 0.761986 - -0.0883151 1.15933 0.605097 - -0.0872905 1.16556 0.595959 - -0.080232 1.16044 0.533866 - -0.0780434 1.16877 0.514436 - -0.0735468 1.18248 0.474579 - -0.071467 1.19666 0.456005 - -0.0619028 1.2805 0.370259 - -0.0555103 1.22186 0.314981 - -0.0473176 1.14963 0.244086 - -0.0405114 1.16458 0.183858 - -0.038804 1.15907 0.168914 - -0.0371199 1.15137 0.154214 - -0.0354573 1.14349 0.139706 - -0.034894 1.14315 0.134749 - -0.0343308 1.14278 0.129794 - -0.0337121 1.15037 0.124209 - -0.0314458 1.1486 0.104275 - -0.0297377 1.14804 0.0892367 - -0.0130453 1.13942 -0.0576686 --0.00207139 1.25866 -0.156462 --0.00380701 0.968565 -0.136027 - 0.00597663 1.10682 -0.224672 - 0.00480284 0.999331 -0.212425 - 0.00529791 0.997444 -0.216753 - 0.00579209 0.995538 -0.221073 - 0.00648597 0.962307 -0.226596 - 0.00659543 0.953111 -0.227397 - -0.0362464 0.0944387 0.165261 - -0.0361528 0.0939961 0.164444 - -0.0355358 0.10005 0.158901 - -0.0354491 0.0973222 0.158185 - -0.0257667 0.22151 0.0706828 - -0.0242144 0.210724 0.0571983 - -0.0239007 0.208624 0.0544716 - -0.022942 0.183457 0.0464721 - -0.0180053 -0.193428 0.0265223 - -0.0183131 -0.195896 0.0290518 - -0.0202131 -0.197858 0.044449 - -0.0222657 -0.193524 0.0609773 - -0.0247995 -0.178992 0.0812314 - -0.0261742 -0.173496 0.0922589 - -0.029405 -0.154839 0.118082 - -0.0296358 -0.154833 0.119949 - -0.0308161 -0.146539 0.129358 - -0.0326186 -0.127124 0.143618 - -0.0347385 -0.110117 0.160485 - -0.0353008 -0.105639 0.164959 - -0.0350918 -0.111513 0.163365 - -0.0335738 -0.143473 0.15161 - -0.0278936 -0.274551 0.107811 - -0.0278203 -0.282953 0.107355 - -0.0281335 -0.333877 0.110717 - -0.025242 -0.465119 0.0894728 - -0.0289367 -0.484577 0.119668 - -0.0345784 -0.463266 0.164945 - -0.0388164 -0.426682 0.198621 - -0.0395476 -0.417864 0.204391 - -0.0404692 -0.408986 0.211699 - -0.0406882 -0.408996 0.21347 - -0.0408996 -0.412999 0.215245 - -0.0417895 -0.433927 0.222782 - -0.0446587 -2.25818 0.275715 - -0.0565826 -2.22844 0.371658 - -0.0638828 -2.23749 0.430841 - -0.067389 -2.2265 0.459016 - -0.069714 -2.21931 0.477701 - -0.0886313 -2.13768 0.629353 - -0.0911041 -2.19468 0.650279 - -0.098 -2.22462 0.706534 - -0.100466 -2.22313 0.726453 - -0.11635 -2.24215 0.855214 - -0.117556 -2.23932 0.864917 - -0.130105 -2.19021 0.965602 - -0.139684 -2.25855 1.04418 - -0.139869 -2.23148 1.04524 - -0.148736 -2.15913 1.11576 - -0.156656 -2.15287 1.17971 - -0.0727613 -0.415354 0.472945 - -0.0781407 -0.406014 0.516296 - -0.0817619 -0.414656 0.545721 - -0.0845804 -0.424129 0.568669 - -0.0881561 -0.398234 0.597163 - -0.0910126 -0.383405 0.620021 - -0.152973 -0.74972 1.12706 - -0.152157 -0.737529 1.12026 - -0.15133 -0.725412 1.11337 - -0.156967 -0.670528 1.15807 - -0.164 -0.659412 1.21476 - -0.18125 -0.661665 1.3543 - -0.182986 -0.663092 1.36836 - -0.195946 -0.665838 1.47321 - -0.206946 -0.668195 1.5622 - -0.212438 -0.667564 1.60661 - -0.214019 -0.666124 1.61937 - -0.23722 -0.671324 1.80708 - -0.245674 -0.674573 1.87549 - -0.252165 -0.68724 1.92819 - -0.258721 -0.6906 1.98127 - -0.289946 -0.669005 2.23343 - -0.290203 -0.659816 2.23536 - -0.289887 -0.639326 2.23247 - -0.290025 -0.562128 2.23232 - -0.290078 -0.52407 2.23213 - -0.289367 -0.475493 2.2256 - -0.290193 -0.402555 2.23109 - -0.290511 -0.375385 2.23321 - -0.290336 -0.329332 2.23105 - -0.290715 -0.311591 2.23382 - -0.29125 -0.257732 2.23727 - -0.291552 -0.239939 2.23942 - -0.29086 -0.221263 2.23353 - -0.292241 -0.0698502 2.24223 - -0.291108 -0.0251341 2.23233 - -0.292142 -0.00742262 2.24041 - -0.292053 0.126142 2.23751 - -0.292179 0.360409 2.23471 - -0.29285 0.416565 2.23923 - -0.293657 0.445786 2.24527 - -0.293433 0.454709 2.24332 - -0.292612 0.490547 2.23609 - -0.294007 0.598081 2.24562 - -0.293465 0.635488 2.24063 - -0.294265 1.0869 2.23974 - -0.294712 1.16958 2.24201 - -0.293588 1.25965 2.23145 - -0.252678 1.28189 1.90026 - -0.229283 1.27848 1.71112 - -0.219621 1.27753 1.63299 - -0.199098 1.27499 1.46707 - -0.176279 1.27309 1.28256 - -0.165137 1.27451 1.19244 - -0.163254 1.27749 1.17716 - -0.16205 1.27612 1.16745 - -0.157858 1.27649 1.13354 - -0.157035 1.27889 1.12685 - -0.151989 1.27968 1.08603 - -0.142855 1.27594 1.01222 - -0.135226 1.27383 0.950565 - -0.129189 1.27742 0.901683 - -0.123036 1.27653 0.851941 - -0.121509 1.2794 0.839546 - -0.112019 1.27328 0.762896 - -0.102996 1.28359 0.689763 - -0.0956209 1.17395 0.631908 - -0.0929482 1.16138 0.610499 - -0.0901887 1.16151 0.588181 - -0.0895695 1.16314 0.583147 - -0.0780907 1.16121 0.490351 - -0.0762294 1.16475 0.475241 - -0.074636 1.17787 0.462141 - -0.0710036 1.21742 0.432122 - -0.0661561 1.27856 0.391925 - -0.0633023 1.27454 0.368912 - -0.0528498 1.18783 0.285797 - -0.0475716 1.15262 0.243686 - -0.0463375 1.15284 0.233702 - -0.0444857 1.15299 0.218725 - -0.0413987 1.15181 0.19378 - -0.0377045 1.14887 0.163952 - -0.0346336 1.14648 0.139158 - -0.0340191 1.14614 0.134194 - -0.0237588 1.1674 0.0508729 - -0.0186271 1.23665 0.00824553 - -0.0167171 1.22989 -0.00709084 - -0.015397 1.22789 -0.0177334 - -0.0129459 1.2453 -0.0378389 --0.00027639 1.26537 -0.140623 --0.00237526 0.973638 -0.118896 - 0.0107688 1.14418 -0.22797 - -0.0371519 0.0869266 0.17679 - -0.0360807 0.0893494 0.168088 - -0.0342773 0.107342 0.153211 - -0.0278465 0.190561 0.0998498 - -0.0254044 0.213279 0.0797306 - -0.0236223 0.227541 0.0650862 - -0.0235581 0.217626 0.0647283 - -0.0232061 0.215628 0.0619145 - -0.0223972 0.210824 0.0554518 - -0.0224562 0.193561 0.0562101 - -0.021162 -0.18923 0.0680906 - -0.0252066 -0.167497 0.0972395 - -0.0276694 -0.159069 0.115059 - -0.0276605 -0.163779 0.115064 - -0.0281898 -0.159083 0.118851 - -0.0213621 -0.487808 0.0739402 - -0.0219392 -0.489026 0.0781633 - -0.0261995 -0.446395 0.108576 - -0.0267275 -0.439068 0.112315 - -0.0280744 -0.478119 0.122703 - -0.0283301 -0.479501 0.124587 - -0.0333138 -0.432553 0.160207 - -0.0382195 -0.4336 0.195964 - -0.0387404 -0.432746 0.199747 - -0.0397971 -0.42594 0.207346 - -0.0587036 -2.24141 0.371799 - -0.0640256 -2.2383 0.410529 - -0.0679422 -2.22956 0.438937 - -0.112603 -2.21672 0.764145 - -0.131956 -2.20353 0.904952 - -0.142354 -2.24126 0.981265 - -0.153214 -2.15888 1.05918 - -0.0691204 -0.426775 0.421005 - -0.0744068 -0.49185 0.460478 - -0.0757748 -0.49565 0.470501 - -0.0752899 -0.413345 0.465757 - -0.0759244 -0.412811 0.470373 - -0.0806003 -0.417554 0.504511 - -0.0831322 -0.416425 0.522941 - -0.0849467 -0.415045 0.536141 - -0.0916321 -0.422139 0.584955 - -0.0921376 -0.418859 0.588589 - -0.0934761 -0.411247 0.59823 - -0.0929207 -0.372341 0.593611 - -0.100214 -0.406835 0.647256 - -0.16339 -0.713156 1.11206 - -0.162014 -0.692378 1.10172 - -0.177793 -0.655554 1.21615 - -0.186513 -0.664352 1.27981 - -0.195642 -0.665158 1.34633 - -0.201121 -0.661221 1.3862 - -0.210078 -0.669786 1.45158 - -0.215286 -0.661607 1.48941 - -0.227745 -0.663698 1.58022 - -0.236211 -0.662946 1.64188 - -0.26941 -0.679435 1.88401 - -0.311172 -0.694198 2.1885 - -0.318091 -0.348733 2.23384 - -0.318046 -0.339507 2.23337 - -0.317598 -0.293399 2.22943 - -0.318553 -0.26714 2.236 - -0.318306 -0.194715 2.23313 - -0.318739 -0.141169 2.2355 - -0.318838 -0.132266 2.23609 - -0.318931 -0.123361 2.23664 - -0.318554 0.108139 2.23049 - -0.320835 0.135959 2.2467 - -0.319157 0.242667 2.2329 - -0.320536 0.316534 2.24186 - -0.321109 0.607859 2.24175 - -0.320969 0.636677 2.24031 - -0.321475 0.767039 2.24208 - -0.321993 1.04476 2.24177 - -0.323019 1.10527 2.24835 - -0.322378 1.11422 2.24355 - -0.322457 1.14926 2.24361 - -0.322244 1.19543 2.24138 - -0.322022 1.20638 2.2396 - -0.322496 1.23243 2.24267 - -0.286145 1.28313 1.97707 - -0.27988 1.27316 1.93158 - -0.274457 1.27828 1.89199 - -0.206111 1.26823 1.39418 - -0.199128 1.26789 1.3433 - -0.195704 1.27292 1.31828 - -0.180869 1.26621 1.21029 - -0.174783 1.27692 1.16579 - -0.156428 1.2737 1.03211 - -0.152091 1.27265 1.00052 - -0.139924 1.27308 0.911873 - -0.111379 1.27441 0.703877 - -0.109823 1.27774 0.692489 - -0.0991242 1.1653 0.616193 - -0.0899178 1.16382 0.549138 - -0.050028 1.16513 0.258486 - -0.0493304 1.16432 0.253415 - -0.0301079 1.14854 0.113593 - -0.0279679 1.15507 0.0979058 - -0.0149328 1.24164 0.00165936 --0.00326713 1.13026 -0.081697 - -0.0365711 0.0890947 0.176266 - -0.0357596 0.0973334 0.170233 - -0.0309439 0.140589 0.134509 - -0.0224159 0.219838 0.0712095 - -0.0221532 0.21857 0.0693146 - -0.0208488 0.208212 0.0599633 - -0.0207241 0.207531 0.0590649 - -0.0215327 0.195849 0.0651276 - -0.0213473 0.192292 0.0638293 - -0.0202129 0.185487 0.0556646 - -0.0199692 0.182627 0.0539306 - -0.0166141 0.196441 0.029283 - -0.0125781 -0.203848 0.0211496 - -0.0147857 -0.200036 0.0359942 - -0.016076 -0.197103 0.0446612 - -0.0168366 -0.196271 0.049782 - -0.0273824 -0.159059 0.120437 - -0.0330169 -0.110279 0.157792 - -0.0327839 -0.138372 0.156603 - -0.030626 -0.185522 0.142685 - -0.0263643 -0.315752 0.115705 - -0.022163 -0.455888 0.0892665 - -0.0243023 -0.44108 0.1035 - -0.0250751 -0.44445 0.108761 - -0.0286717 -0.453701 0.133157 - -0.0297257 -0.47118 0.140507 - -0.0374339 -0.430425 0.191966 - -0.040504 -0.414996 0.212472 - -0.0545505 -2.23784 0.332126 - -0.0675676 -2.24339 0.42004 - -0.0689188 -2.2355 0.42905 - -0.0702605 -2.22757 0.437995 - -0.0757632 -2.21038 0.474892 - -0.0770029 -2.19829 0.483092 - -0.0783444 -2.19312 0.492074 - -0.0881933 -2.11981 0.557534 - -0.113073 -2.23677 0.727015 - -0.149453 -2.21952 0.972265 - -0.156493 -2.26387 1.02038 - -0.16765 -2.16974 1.09438 - -0.0707863 -0.44484 0.417221 - -0.0717101 -0.433064 0.423294 - -0.0720518 -0.433033 0.425599 - -0.0730122 -0.380025 0.431357 - -0.0783651 -0.431235 0.468176 - -0.0810627 -0.415074 0.486159 - -0.0835991 -0.409287 0.503196 - -0.0894928 -0.421473 0.543132 - -0.0903971 -0.421671 0.549237 - -0.0917571 -0.417996 0.558363 - -0.0970901 -0.415346 0.594314 - -0.0972995 -0.37821 0.595221 - -0.0975442 -0.376525 0.596849 - -0.171742 -0.808324 1.10342 - -0.172795 -0.751961 1.10976 - -0.173217 -0.651947 1.11124 - -0.178214 -0.664186 1.14512 - -0.189131 -0.664889 1.2188 - -0.205643 -0.663547 1.3302 - -0.221735 -0.664113 1.4388 - -0.229484 -0.670905 1.49118 - -0.230617 -0.660519 1.49868 - -0.280309 -0.668638 1.83411 - -0.28494 -0.673078 1.86543 - -0.297085 -0.688847 1.94759 - -0.340657 -0.634592 2.24087 - -0.339701 -0.40411 2.23128 - -0.340717 -0.331572 2.23714 - -0.340955 -0.150437 2.23627 - -0.341603 0.0639988 2.23772 - -0.341454 0.243258 2.23427 - -0.342673 0.307898 2.24161 - -0.342796 0.363024 2.2417 - -0.342037 0.39894 2.23608 - -0.342935 0.503005 2.24073 - -0.343478 0.609282 2.24294 - -0.342617 0.636677 2.23675 - -0.344043 0.779513 2.24443 - -0.345041 0.86502 2.25 - -0.345588 0.877125 2.25352 - -0.344734 0.971082 2.24648 - -0.343782 0.98985 2.23979 - -0.344918 1.09442 2.24603 - -0.345051 1.19997 2.24549 - -0.339192 1.28453 2.20481 - -0.319491 1.28118 2.07191 - -0.31277 1.27356 2.02666 - -0.308142 1.27507 1.99541 - -0.28132 1.27775 1.81438 - -0.235672 1.27511 1.50639 - -0.229081 1.27499 1.46191 - -0.196601 1.2754 1.24274 - -0.191321 1.27608 1.2071 - -0.177243 1.27556 1.11211 - -0.160373 1.2718 0.998324 - -0.155818 1.27087 0.967598 - -0.154781 1.27161 0.96059 - -0.137076 1.27485 0.841075 - -0.133627 1.28302 0.817693 - -0.126662 1.28276 0.770698 - -0.123264 1.27529 0.747869 - -0.121466 1.27718 0.735706 - -0.119951 1.2836 0.725399 - -0.114884 1.27774 0.691284 - -0.0852837 1.15901 0.493167 - -0.0829937 1.16067 0.477691 - -0.079801 1.1583 0.456179 - -0.0770191 1.1683 0.437271 - -0.0729781 1.19059 0.409699 - -0.0689429 1.25555 0.381583 - -0.0593603 1.2677 0.316755 - -0.0370632 1.15307 0.16786 - -0.034873 1.14838 0.153145 - -0.0251215 1.15798 0.0872119 - -0.018435 1.23375 0.0410587 - -0.0116055 1.21513 -0.00477238 - 0.00462836 1.14943 -0.113421 - -0.0367144 0.102394 0.179841 - -0.0365474 0.0871295 0.178923 - -0.0360511 0.0845982 0.175608 - -0.0357182 0.0846358 0.173361 - -0.0328688 0.110423 0.153782 - -0.0274261 0.170535 0.116235 - -0.0200833 0.212871 0.0661092 - -0.0200797 0.199404 0.0662683 - -0.0209236 0.186334 0.0721414 - -0.0208034 0.185707 0.0713387 - -0.0133407 0.203564 0.0207374 - -0.0113831 -0.199615 0.0266619 - -0.0123867 -0.201472 0.032998 - -0.0241826 -0.156191 0.10661 - -0.0284729 -0.144893 0.13345 - -0.0337919 -0.103563 0.166377 - -0.0345948 -0.0970538 0.171344 - -0.0343209 -0.10832 0.169765 - -0.0309791 -0.169025 0.14952 - -0.0308076 -0.173983 0.148504 - -0.0303022 -0.184574 0.145461 - -0.0232727 -0.414462 0.104177 - -0.02384 -0.422662 0.10785 - -0.0266205 -0.405227 0.125115 - -0.032986 -0.462487 0.16588 - -0.0349866 -0.456613 0.178388 - -0.0357913 -0.44294 0.183275 - -0.0383742 -0.422752 0.199262 - -0.0409898 -0.415994 0.215627 - -0.042166 -0.438888 0.223316 - -0.0496824 -2.26456 0.293843 - -0.0526618 -2.23879 0.312253 - -0.0754143 -2.21259 0.455019 - -0.0951795 -2.1374 0.578373 - -0.106415 -2.21037 0.649964 - -0.129616 -2.19125 0.795641 - -0.148153 -2.20333 0.912383 - -0.149667 -2.20022 0.92187 - -0.166904 -2.26781 1.03114 - -0.177965 -2.18732 1.09968 - -0.178128 -2.16215 1.10038 - -0.0798563 -0.464928 0.460697 - -0.0824234 -0.420978 0.476283 - -0.0842928 -0.419242 0.488018 - -0.0859066 -0.414722 0.498111 - -0.0864782 -0.412191 0.501673 - -0.088903 -0.414566 0.516954 - -0.0919406 -0.413624 0.536047 - -0.095323 -0.417996 0.557376 - -0.0991525 -0.416775 0.581446 - -0.101609 -0.411975 0.596833 - -0.10136 -0.406654 0.595201 - -0.107238 -0.394569 0.632013 - -0.126563 -0.501564 0.754924 - -0.183079 -0.798463 1.11415 - -0.182249 -0.772833 1.10861 - -0.182706 -0.702164 1.11058 - -0.192244 -0.65834 1.17001 - -0.197117 -0.660493 1.20069 - -0.198619 -0.660507 1.21014 - -0.207827 -0.659622 1.26804 - -0.223195 -0.665075 1.36476 - -0.2944 -0.669284 1.81265 - -0.318554 -0.688068 1.9648 - -0.360963 -0.681989 2.23146 - -0.360622 -0.631929 2.22867 - -0.361211 -0.488751 2.23056 - -0.361987 -0.29497 2.23297 - -0.362203 -0.286045 2.23421 - -0.36274 -0.0699869 2.23484 - -0.364025 0.0104545 2.2419 - -0.364032 0.0194165 2.24183 - -0.3638 0.126945 2.239 - -0.363649 0.144839 2.23782 - -0.364259 0.381633 2.23864 - -0.363808 0.408836 2.23546 - -0.365926 0.505627 2.24754 - -0.365747 0.514853 2.2463 - -0.365211 0.561748 2.24233 - -0.365598 0.669587 2.24339 - -0.365374 0.799941 2.24032 - -0.36484 0.80889 2.23685 - -0.366103 0.971082 2.24273 - -0.366345 1.0493 2.24326 - -0.366828 1.21349 2.2442 - -0.367628 1.24068 2.24889 - -0.355796 1.27922 2.17398 - -0.24935 1.27581 1.50454 - -0.231374 1.27042 1.39155 - -0.195059 1.27851 1.16305 - -0.1775 1.27443 1.05267 - -0.162507 1.27075 0.958411 - -0.154847 1.27571 0.910173 - -0.10663 1.16517 0.608328 - -0.102084 1.18002 0.579547 - -0.0949986 1.15999 0.535237 - -0.0885533 1.16873 0.494589 - -0.0815311 1.16034 0.45053 - -0.076671 1.16329 0.419925 - -0.07164 1.1909 0.387932 - -0.0665206 1.2679 0.354753 - -0.0594678 1.26516 0.31043 - -0.0492128 1.16148 0.247253 - -0.0459828 1.14991 0.227085 - -0.0420429 1.14895 0.202318 - -0.0294968 1.1414 0.123507 - -0.0217484 1.17966 0.0742861 - -0.0144895 1.24899 0.0277494 - -0.0136324 1.24816 0.0223693 - -0.0127304 1.24928 0.0166818 --0.00643886 1.13748 -0.0214644 - -0.0361621 0.111559 0.178544 - -0.0367778 0.0887216 0.182707 - -0.025379 0.183113 0.109814 - -0.0229734 0.196019 0.0945192 - -0.0194986 0.21733 0.0723933 - -0.0128611 0.204973 0.0308048 - -0.0126592 0.195716 0.0296532 --0.00984423 -0.200673 0.0319899 - -0.0113003 -0.201634 0.0404591 - -0.0139146 -0.192326 0.0555354 - -0.0216169 -0.153924 0.0998242 - -0.0234867 -0.145802 0.11059 - -0.0246933 -0.13975 0.117527 - -0.0262673 -0.145782 0.126741 - -0.0274607 -0.138272 0.133585 - -0.0280385 -0.13791 0.136937 - -0.0285831 -0.149831 0.140241 - -0.0308837 -0.169719 0.15384 - -0.0306052 -0.176589 0.152303 - -0.026613 -0.267101 0.13018 - -0.0235282 -0.404686 0.113883 - -0.0238365 -0.412356 0.115764 - -0.0287343 -0.452719 0.14469 - -0.0329149 -0.447768 0.168916 - -0.0337094 -0.46027 0.173678 - -0.0472433 -2.25518 0.273454 - -0.0604946 -2.23971 0.350245 - -0.0750751 -2.21065 0.434598 - -0.0918661 -2.14692 0.531383 - -0.097045 -2.1583 0.5616 - -0.117461 -2.22298 0.680953 - -0.124556 -2.22801 0.722231 - -0.16007 -2.19327 0.928111 - -0.173698 -2.23941 1.00782 - -0.201137 -2.16714 1.16636 - -0.0781187 -0.443726 0.431449 - -0.0841116 -0.478136 0.466666 - -0.0892449 -0.416799 0.495761 - -0.0901525 -0.416735 0.501033 - -0.093516 -0.413466 0.520532 - -0.094946 -0.41707 0.528882 - -0.095257 -0.415668 0.530671 - -0.100808 -0.422598 0.562996 - -0.104644 -0.418859 0.585236 - -0.105316 -0.408549 0.589016 - -0.106319 -0.376525 0.594468 - -0.106721 -0.375527 0.596792 - -0.193864 -0.7604 1.10753 - -0.194782 -0.744662 1.11267 - -0.194668 -0.654865 1.11095 - -0.222518 -0.664352 1.27284 - -0.236745 -0.668157 1.35552 - -0.24419 -0.665738 1.39875 - -0.308452 -0.670126 1.77208 - -0.318244 -0.669394 1.82895 - -0.341181 -0.688791 1.96242 - -0.363585 -0.692572 2.0926 - -0.387168 -0.682938 2.22948 - -0.388084 -0.359526 2.23099 - -0.389509 -0.00746262 2.23512 - -0.391562 0.457966 2.24155 - -0.391084 0.533049 2.23789 - -0.391634 0.689727 2.23924 - -0.393688 0.826361 2.24956 - -0.392468 0.907674 2.24151 - -0.392277 0.917871 2.24029 - -0.393954 1.17002 2.24705 - -0.373052 1.274 2.12441 - -0.331407 1.27888 1.88245 - -0.302386 1.28025 1.71385 - -0.29476 1.27591 1.6696 - -0.284057 1.27639 1.60743 - -0.245072 1.27341 1.38101 - -0.240872 1.27994 1.35653 - -0.239128 1.27979 1.3464 - -0.211075 1.27451 1.18351 - -0.203903 1.2764 1.14183 - -0.188434 1.27692 1.05196 - -0.177445 1.28635 0.988023 - -0.168362 1.28547 0.935272 - -0.15664 1.27866 0.867259 - -0.136171 1.28358 0.748303 - -0.123429 1.27346 0.674403 - -0.0936545 1.16329 0.502749 - -0.0829351 1.1673 0.440435 - -0.0772293 1.1562 0.407422 - -0.0734344 1.17804 0.385121 - -0.0664234 1.27209 0.343286 - -0.0654826 1.27266 0.337815 - -0.0617786 1.27867 0.316228 - -0.0514125 1.17712 0.25721 - -0.0451953 1.14296 0.221498 - -0.0392686 1.14471 0.187051 - -0.038421 1.14458 0.182129 - -0.036726 1.14427 0.172287 - -0.0325215 1.13912 0.147924 - -0.0264386 1.15053 0.112455 --0.00896816 1.15503 0.0109193 --0.00508766 1.11107 -0.0111036 --0.00752309 0.98973 0.00447381 --0.00488139 0.978101 -0.0107342 - -0.0368339 0.108412 0.185124 - -0.0372324 0.0873459 0.187687 - -0.0367034 0.0968197 0.184503 - -0.0362183 0.0927761 0.181732 - -0.0365773 0.0850752 0.183909 - -0.0363251 0.0845498 0.18245 - -0.036137 0.0841388 0.181362 - -0.0361321 0.0798543 0.181385 - -0.0346636 0.0935104 0.172693 - -0.0345247 0.0931513 0.171891 - -0.0339115 0.100261 0.168245 - -0.0202784 0.202591 0.0878462 - -0.0174644 0.208399 0.0714314 - -0.0187844 0.180985 0.0794226 --0.00959864 -0.176252 0.0408877 --0.00923117 -0.191052 0.0390419 - -0.0129796 -0.190613 0.0595444 - -0.0246751 -0.13275 0.122886 - -0.0272057 -0.144859 0.136866 - -0.0268067 -0.150505 0.134746 - -0.0281115 -0.150784 0.141887 - -0.028425 -0.150498 0.143599 - -0.0333484 -0.10443 0.170022 - -0.0171199 -0.439233 0.0849613 - -0.0229314 -0.394011 0.116252 - -0.0285384 -0.445104 0.147496 - -0.0369008 -0.421528 0.192985 - -0.0392561 -0.413941 0.205786 - -0.0412056 -0.410981 0.216418 - -0.0565503 -2.24033 0.320716 - -0.058286 -2.23684 0.330174 - -0.0635721 -2.23709 0.359096 - -0.0670839 -2.23571 0.378294 - -0.0723203 -2.23133 0.406893 - -0.107397 -2.15378 0.597933 - -0.134566 -2.21135 0.747215 - -0.0784638 -0.427654 0.420441 - -0.0872409 -0.415354 0.468323 - -0.092841 -0.415098 0.498958 - -0.0939071 -0.415796 0.504798 - -0.0945626 -0.413189 0.508356 - -0.100539 -0.415435 0.541075 - -0.10535 -0.421762 0.567471 - -0.105684 -0.420184 0.569277 - -0.107451 -0.412917 0.578865 - -0.108375 -0.414987 0.583945 - -0.109272 -0.413145 0.588829 - -0.111143 -0.385214 0.598757 - -0.114776 -0.384347 0.618622 - -0.197672 -0.789604 1.07665 - -0.205494 -0.711951 1.11858 - -0.204565 -0.657783 1.11289 - -0.239681 -0.666166 1.30511 - -0.245804 -0.659667 1.33853 - -0.248968 -0.663092 1.35588 - -0.257014 -0.660963 1.39987 - -0.259269 -0.660932 1.41221 - -0.296106 -0.662897 1.61377 - -0.376589 -0.689142 2.05438 - -0.380341 -0.687452 2.07488 - -0.386626 -0.690651 2.10931 - -0.409658 -0.656402 2.23493 - -0.409853 -0.627104 2.23567 - -0.411137 -0.371116 2.23985 - -0.410288 -0.324046 2.23468 - -0.409649 -0.214047 2.22996 - -0.411103 -0.079341 2.23642 - -0.41071 -0.0612939 2.23406 - -0.411623 0.0733886 2.23756 - -0.41158 0.0823706 2.23723 - -0.413412 0.564122 2.24189 - -0.413287 0.671445 2.24001 - -0.415001 0.879865 2.24707 - -0.415711 1.02319 2.24936 - -0.416054 1.03534 2.25111 - -0.338382 1.28176 1.82342 - -0.326621 1.27551 1.75915 - -0.32507 1.27983 1.75061 - -0.294213 1.27788 1.58182 - -0.286592 1.27199 1.54019 - -0.281652 1.27913 1.51309 - -0.24668 1.27704 1.32178 - -0.214494 1.27308 1.14574 - -0.213285 1.2756 1.13909 - -0.20455 1.27852 1.09127 - -0.201002 1.27391 1.07192 - -0.19789 1.27236 1.0549 - -0.196897 1.27609 1.04943 - -0.188347 1.27594 1.00265 - -0.187061 1.27689 0.995608 - -0.15864 1.2829 0.840051 - -0.149809 1.28091 0.791762 - -0.143684 1.2797 0.758263 - -0.129423 1.27609 0.680286 - -0.117765 1.16729 0.617712 - -0.113244 1.26643 0.591879 - -0.105646 1.22449 0.550778 - -0.0994281 1.18195 0.517232 - -0.0969781 1.17201 0.503939 - -0.0748769 1.16914 0.383056 - -0.0488661 1.15362 0.240925 - -0.0299987 1.1375 0.137882 - -0.0282245 1.1358 0.128194 - -0.0273328 1.13542 0.12332 --0.00763629 1.12746 0.0156505 --0.00660219 0.975959 0.0116781 - -0.0366099 0.0899918 0.185703 - -0.0364374 0.0917847 0.18474 - -0.0358057 0.0916922 0.181285 - -0.0362389 0.0809198 0.183774 - -0.0350549 0.0944225 0.177147 - -0.0330655 0.100566 0.166194 - -0.0324527 0.105566 0.162786 - -0.0214704 0.18678 0.101799 - -0.0213231 0.186288 0.100999 - -0.0157981 0.211502 0.0704913 - -0.0157879 0.185707 0.0707227 - -0.0152753 0.186013 0.0679147 - -0.0106249 0.202142 0.0422936 --0.00991302 0.201364 0.0384074 - -0.0110729 0.187151 0.044911 - -0.0102387 -0.162749 0.0539114 --0.00783771 -0.179961 0.0417127 - -0.0135739 -0.165385 0.0711359 - -0.012266 -0.179363 0.064539 - -0.0158706 -0.159822 0.0829188 - -0.0262175 -0.133087 0.135987 - -0.0273304 -0.13634 0.14176 - -0.0281253 -0.138463 0.145881 - -0.0246394 -0.276433 0.129356 - -0.0214367 -0.381088 0.113942 - -0.0282044 -0.430268 0.149353 - -0.0286197 -0.428563 0.151477 - -0.0336068 -0.453622 0.177454 - -0.035731 -0.435316 0.188214 - -0.0483947 -2.26618 0.27274 - -0.0669618 -2.23941 0.368192 - -0.110172 -2.17122 0.590269 - -0.151402 -2.19927 0.80315 - -0.15959 -2.20476 0.845425 - -0.0864376 -0.47473 0.450073 - -0.082931 -0.381653 0.431016 - -0.0871113 -0.411477 0.452883 - -0.0909601 -0.420133 0.472818 - -0.0950669 -0.413079 0.493919 - -0.101667 -0.418656 0.528008 - -0.103063 -0.416764 0.535185 - -0.106941 -0.419533 0.55521 - -0.11419 -0.411247 0.5925 - -0.114638 -0.399413 0.594685 - -0.115272 -0.382103 0.597774 - -0.214705 -0.723052 1.11404 - -0.214267 -0.701844 1.11155 - -0.215501 -0.656685 1.11744 - -0.227868 -0.652223 1.18116 - -0.249418 -0.659993 1.29235 - -0.25339 -0.66591 1.3129 - -0.377316 -0.687706 1.95209 - -0.432694 -0.550821 2.23618 - -0.433012 -0.446196 2.23673 - -0.431983 -0.324046 2.23014 - -0.432718 -0.251261 2.23316 - -0.432626 -0.0793024 2.23089 - -0.434605 0.0375574 2.23986 - -0.434563 0.055582 2.23945 - -0.433628 0.0914397 2.23426 - -0.433053 0.13629 2.23082 - -0.434557 0.154904 2.23838 - -0.434419 0.30968 2.23604 - -0.434984 0.337773 2.23866 - -0.435394 0.403153 2.24009 - -0.435073 0.412164 2.23834 - -0.436118 0.441444 2.24342 - -0.436898 0.470708 2.24713 - -0.435818 0.623428 2.23996 - -0.434802 0.641433 2.23453 - -0.43648 0.693861 2.24263 - -0.43629 0.743904 2.24113 - -0.436225 0.753945 2.24068 - -0.436603 0.77511 2.24241 - -0.436231 0.910498 2.23907 - -0.438253 0.958562 2.24899 - -0.43759 1.05703 2.24454 - -0.436329 1.12234 2.23735 - -0.438984 1.2373 2.24984 - -0.435861 1.27651 2.23332 - -0.42462 1.27646 2.17536 - -0.40816 1.28087 2.09045 - -0.384425 1.27826 1.9681 - -0.369891 1.28106 1.89313 - -0.357757 1.27889 1.83059 - -0.31759 1.28553 1.62342 - -0.295576 1.27913 1.50998 - -0.287076 1.26886 1.46626 - -0.246591 1.27164 1.25749 - -0.239946 1.27449 1.2232 - -0.205199 1.28313 1.04395 - -0.189378 1.27516 0.96246 - -0.178144 1.27571 0.90453 - -0.144333 1.27811 0.730175 - -0.14185 1.27803 0.71737 - -0.119281 1.15855 0.602261 - -0.0755728 1.16692 0.37681 - -0.0592312 1.25836 0.291592 - -0.0581594 1.2567 0.286083 - -0.054469 1.20665 0.267581 - -0.0490684 1.15062 0.240323 - -0.0357118 1.14427 0.171523 - -0.0261578 1.14539 0.12225 --0.00686584 0.976579 0.0245532 --0.00411087 0.960391 0.0105185 --0.00251305 0.958566 0.0022992 - -0.0373183 0.087405 0.190908 - -0.0365494 0.0779681 0.187042 - -0.0346383 0.101936 0.176937 - -0.0341796 0.0989317 0.174603 - -0.0339096 0.0962274 0.173239 - -0.0319871 0.111416 0.163168 - -0.027976 0.145553 0.142127 - -0.0162727 0.182741 0.0813942 --0.00958066 0.202083 0.0466864 --0.00929065 0.202112 0.0451908 - -0.010112 -0.156313 0.0613727 - -0.0103827 -0.163202 0.0627652 - -0.0141892 -0.151968 0.0812673 - -0.0147181 -0.152936 0.0838635 - -0.0177019 -0.150821 0.0984339 - -0.0237127 -0.138669 0.127706 - -0.025431 -0.143641 0.136159 - -0.0281002 -0.146776 0.149243 - -0.0300235 -0.13123 0.158492 - -0.0331914 -0.105105 0.173724 - -0.0320243 -0.130708 0.168272 - -0.0283083 -0.200599 0.150798 - -0.0223674 -0.390787 0.123644 - -0.0314788 -0.439807 0.16869 - -0.0400652 -0.402997 0.210311 - -0.0645112 -2.23771 0.348171 - -0.0845862 -2.15792 0.445545 - -0.0864742 -2.15686 0.454767 - -0.103019 -2.19933 0.536096 - -0.129185 -2.20839 0.664144 - -0.151178 -2.20018 0.771609 - -0.179756 -2.18976 0.911259 - -0.183592 -2.18345 0.929952 - -0.193836 -2.20804 0.980295 - -0.198105 -2.20675 1.00116 - -0.210856 -2.17185 1.06316 - -0.226151 -2.16816 1.13792 - -0.0819328 -0.434894 0.415369 - -0.0913261 -0.489444 0.461848 - -0.0951366 -0.412574 0.479714 - -0.0956089 -0.412208 0.48202 - -0.0971869 -0.420115 0.489816 - -0.101523 -0.415903 0.510978 - -0.102859 -0.409714 0.517448 - -0.107724 -0.414751 0.541291 - -0.119624 -0.394985 0.599284 - -0.119098 -0.382103 0.596586 - -0.142193 -0.461545 0.710319 - -0.222561 -0.799781 1.1067 - -0.222561 -0.744662 1.10615 - -0.256382 -0.661219 1.27071 - -0.286258 -0.66665 1.41687 - -0.41258 -0.694159 2.03487 - -0.450809 -0.694746 2.22182 - -0.451619 -0.686105 2.2257 - -0.452406 -0.588643 2.22858 - -0.453841 -0.362293 2.23333 - -0.453291 -0.287983 2.2299 - -0.453557 -0.278992 2.23111 - -0.45491 -0.0887036 2.23583 - -0.454382 -0.025505 2.23261 - -0.454867 0.00150033 2.23472 - -0.45548 0.0105258 2.23763 - -0.455427 0.245978 2.23502 - -0.456086 0.301402 2.23769 - -0.458225 0.405452 2.24711 - -0.458475 0.415101 2.24823 - -0.457335 0.547116 2.24134 - -0.459155 0.727818 2.24844 - -0.458076 0.807929 2.24236 - -0.459737 0.874317 2.24982 - -0.458967 0.894023 2.24586 - -0.459517 0.938359 2.24811 - -0.43301 1.27619 2.11511 - -0.424165 1.28305 2.07179 - -0.373117 1.27522 1.82223 - -0.3542 1.27964 1.72968 - -0.325537 1.27986 1.58951 - -0.309226 1.28191 1.50973 - -0.301807 1.26818 1.47359 - -0.285629 1.27463 1.39441 - -0.261402 1.27447 1.27594 - -0.221159 1.27912 1.0791 - -0.18567 1.28096 0.905532 - -0.182077 1.27478 0.88802 - -0.155944 1.27635 0.760212 - -0.14079 1.28242 0.686044 - -0.117161 1.26273 0.570696 - -0.0939325 1.16504 0.458078 - -0.0751783 1.17033 0.366314 - -0.0741283 1.17001 0.361182 - -0.0678077 1.26324 0.329343 - -0.0657158 1.27023 0.319043 - -0.0549146 1.20365 0.266888 - -0.0492085 1.14163 0.239604 - -0.0472074 1.14084 0.229826 - -0.0441968 1.13399 0.215172 - -0.0190123 0.901135 0.0943405 - -0.0346296 0.0984562 0.178724 - -0.0345433 0.0983091 0.178304 - -0.0344571 0.0981601 0.177884 - -0.031918 0.108179 0.165367 - -0.025197 0.157297 0.13201 - -0.0154895 0.180075 0.0843117 - -0.0146335 0.184358 0.0800827 - -0.0097369 0.185424 0.056127 --0.00790536 0.189364 0.0471312 - -0.0077518 0.181989 0.0464538 --0.00973178 0.166721 0.0562886 - -0.0119938 -0.143127 0.0774707 --0.00978228 -0.156706 0.067324 - -0.0173567 -0.143986 0.102397 - -0.0227498 -0.137446 0.127394 - -0.0241337 -0.132061 0.133772 - -0.0232921 -0.141367 0.12995 - -0.0238771 -0.154398 0.132792 - -0.0243703 -0.163424 0.13517 - -0.0305158 -0.121496 0.163326 - -0.0331553 -0.107976 0.175462 - -0.0220638 -0.356545 0.126289 - -0.0244904 -0.379618 0.137783 - -0.0274066 -0.422625 0.151742 - -0.0285701 -0.423386 0.157155 - -0.0320201 -0.447319 0.173412 - -0.0324305 -0.447484 0.175321 - -0.0956661 -2.18716 0.485677 - -0.113026 -2.21653 0.566617 - -0.124876 -2.14357 0.620987 - -0.212457 -2.16996 1.02817 - -0.230599 -2.16528 1.11242 - -0.083402 -0.429481 0.411985 - -0.0837977 -0.428581 0.413815 - -0.0861391 -0.427524 0.424684 - -0.094274 -0.478136 0.462964 - -0.120796 -0.420905 0.585652 - -0.122725 -0.412453 0.594536 - -0.233359 -0.686207 1.11119 - -0.262018 -0.658981 1.24409 - -0.28068 -0.666667 1.33088 - -0.377466 -0.67171 1.78063 - -0.40473 -0.681897 1.90741 - -0.464941 -0.69427 2.18729 - -0.475706 -0.661573 2.237 - -0.473168 -0.579114 2.22443 - -0.47469 -0.542328 2.23115 - -0.473423 -0.502397 2.22488 - -0.473489 -0.49294 2.2251 - -0.475807 -0.344766 2.23446 - -0.477188 -0.0527845 2.2381 - -0.476619 -0.0436742 2.23537 - -0.476673 -0.0346394 2.23554 - -0.477447 0.0286545 2.23853 - -0.477014 0.0376665 2.23643 - -0.4773 0.0738873 2.23742 - -0.477246 0.0829304 2.23708 - -0.477576 0.119257 2.23827 - -0.47748 0.128304 2.23774 - -0.47851 0.201539 2.24183 - -0.478808 0.22915 2.24295 - -0.478891 0.330647 2.24237 - -0.478601 0.33971 2.24093 - -0.478718 0.349099 2.24139 - -0.477996 0.357817 2.23795 - -0.477681 0.36686 2.2364 - -0.479131 0.509919 2.24178 - -0.478382 0.838374 2.23518 - -0.48033 0.938359 2.24328 - -0.480294 1.11807 2.2414 - -0.453873 1.28058 2.1171 - -0.404142 1.28166 1.88601 - -0.346388 1.27526 1.61772 - -0.33733 1.28126 1.57558 - -0.325858 1.27512 1.52233 - -0.323163 1.27404 1.50983 - -0.317493 1.27022 1.48351 - -0.27692 1.27777 1.29492 - -0.260912 1.2776 1.22055 - -0.248284 1.27007 1.16194 - -0.229731 1.27748 1.07567 - -0.218819 1.27259 1.02501 - -0.213351 1.28102 0.999523 - -0.211615 1.28028 0.991464 - -0.206102 1.27523 0.965898 - -0.190402 1.27439 0.892955 - -0.181702 1.2771 0.852508 - -0.167212 1.27727 0.785178 - -0.147835 1.27721 0.695144 - -0.127201 1.16044 0.600381 - -0.118516 1.2272 0.559392 - -0.0891306 1.15159 0.423574 - -0.085538 1.17197 0.406687 - -0.0785026 1.159 0.374121 - -0.0764363 1.1624 0.364488 - -0.0733731 1.16932 0.350189 - -0.0679369 1.27172 0.323957 - -0.0216061 1.17145 0.109638 - -0.0125724 1.02581 0.0690474 - -0.0375838 0.0984679 0.194076 - -0.0351738 0.098864 0.182874 - -0.0255648 0.153639 0.137706 - -0.0244174 0.163172 0.132284 - -0.0239674 0.162103 0.130203 - -0.0220322 0.167388 0.121162 - -0.0216228 0.167451 0.119259 - -0.0209583 0.171389 0.116134 - -0.0190549 0.176499 0.107241 - -0.0187298 0.175565 0.10574 --0.00931565 0.191628 0.0618447 --0.00818801 0.184664 0.0566714 --0.00877541 0.164499 0.0595924 - -0.0112997 -0.13821 0.0808057 - -0.0104367 -0.152444 0.0771182 - -0.0104343 -0.153787 0.0771199 --0.00999523 -0.158739 0.0752233 - -0.015167 -0.146938 0.097986 - -0.017638 -0.145347 0.108898 - -0.0206992 -0.143839 0.122421 - -0.0262721 -0.150445 0.147125 - -0.0288706 -0.131466 0.158444 - -0.0327136 -0.100573 0.175157 - -0.0328101 -0.100732 0.175586 - -0.0331096 -0.105442 0.176953 - -0.0303073 -0.153999 0.165001 - -0.0216261 -0.340635 0.128305 - -0.0219617 -0.347196 0.129848 - -0.0226137 -0.369451 0.132933 - -0.0263063 -0.410215 0.149632 - -0.0320035 -0.445491 0.175145 - -0.0337834 -0.442072 0.182985 - -0.0773718 -2.20128 0.391686 - -0.118314 -2.2021 0.572743 - -0.185666 -2.20379 0.870589 - -0.194948 -2.20307 0.911628 - -0.211177 -2.22971 0.983636 - -0.217617 -2.15956 1.01148 - -0.219778 -2.1569 1.02101 - -0.23904 -2.1831 1.10642 - -0.0856547 -0.422283 0.412182 - -0.086926 -0.429447 0.417869 - -0.0963361 -0.479254 0.459932 - -0.0971443 -0.421016 0.462978 - -0.105926 -0.417424 0.50178 - -0.117223 -0.419533 0.551754 - -0.127333 -0.384195 0.59614 - -0.244176 -0.76389 1.11626 - -0.242759 -0.745074 1.10983 - -0.251092 -0.663919 1.14594 - -0.251918 -0.660296 1.14956 - -0.261412 -0.651746 1.19147 - -0.294403 -0.66566 1.33748 - -0.317359 -0.661188 1.43896 - -0.351785 -0.666124 1.59123 - -0.362716 -0.666176 1.63957 - -0.382468 -0.666381 1.72691 - -0.445709 -0.686819 2.00676 - -0.454214 -0.63637 2.04391 - -0.459598 -0.607735 2.06746 - -0.468687 -0.402613 2.10579 - -0.469047 -0.385256 2.10722 - -0.468997 -0.376389 2.10692 - -0.470254 -0.324717 2.11201 - -0.472082 -0.273584 2.11963 - -0.475104 -0.0673214 2.13112 - -0.481081 0.193427 2.15519 - -0.482043 0.211449 2.15928 - -0.48221 0.291163 2.1593 - -0.481819 0.317604 2.15733 - -0.480778 0.424546 2.15175 - -0.474265 0.544986 2.12186 - -0.468674 0.611235 2.09654 - -0.465831 0.625609 2.08384 - -0.461798 0.722008 2.06513 - -0.501772 1.03892 2.23902 - -0.501592 1.1539 2.23718 - -0.492176 1.27328 2.19446 - -0.434749 1.27904 1.94046 - -0.422328 1.27298 1.88559 - -0.384155 1.27518 1.71677 - -0.376415 1.27977 1.6825 - -0.374349 1.2831 1.67333 - -0.359043 1.27886 1.60569 - -0.326462 1.27379 1.46166 - -0.303925 1.27931 1.36195 - -0.296516 1.27607 1.32922 - -0.28455 1.27047 1.27636 - -0.276242 1.27089 1.23961 - -0.274742 1.27394 1.23295 - -0.245571 1.27483 1.10395 - -0.24435 1.27882 1.09852 - -0.241769 1.2859 1.08703 - -0.188997 1.28333 0.8537 - -0.173276 1.27909 0.784221 - -0.127666 1.16366 0.583576 - -0.115697 1.27045 0.529684 - -0.106196 1.23765 0.487965 - -0.0927024 1.15848 0.429014 - -0.0882826 1.1632 0.409427 - -0.0781259 1.16834 0.364467 - -0.0676455 1.26524 0.317243 - -0.0653255 1.27214 0.306922 - -0.0640112 1.26757 0.301151 - -0.0508127 1.15448 0.243812 - -0.0408135 1.13195 0.1998 - -0.0221116 1.14 0.117026 - -0.0372759 0.0943795 0.193564 - -0.0361399 0.0943032 0.188541 - -0.0359983 0.0951744 0.187907 - -0.0351964 0.102487 0.184295 - -0.0343244 0.104489 0.180421 - -0.0330522 0.103664 0.174803 - -0.0306018 0.118644 0.163831 - -0.0309523 0.111756 0.165444 - -0.0223546 0.159379 0.126992 - -0.0184956 0.173525 0.109799 - -0.0133653 0.189483 0.0869682 - -0.0107838 0.188607 0.0755608 --0.00912189 0.17519 0.0683335 - -0.011927 -0.130116 0.0893489 - -0.0188125 -0.138935 0.118474 - -0.0196089 -0.147177 0.121905 - -0.0209842 -0.159875 0.127817 - -0.0209266 -0.162014 0.127592 - -0.0219979 -0.176591 0.132238 - -0.0310288 -0.110376 0.169763 - -0.0320074 -0.107653 0.173868 - -0.0328064 -0.0993041 0.177166 - -0.0309842 -0.134688 0.169785 - -0.0188666 -0.324012 0.120306 - -0.0216974 -0.329343 0.132295 - -0.0223814 -0.363926 0.13548 - -0.0239004 -0.356076 0.141821 - -0.0253355 -0.394844 0.148211 - -0.0422374 -0.420892 0.219741 - -0.0705367 -2.22412 0.354764 - -0.0809018 -2.17555 0.398071 - -0.0828605 -2.16274 0.406223 - -0.0993772 -2.20424 0.476262 - -0.166384 -2.20943 0.758992 - -0.180319 -2.20357 0.817726 - -0.192583 -2.20666 0.869491 - -0.227233 -2.17639 1.01541 - -0.0896709 -0.435723 0.419979 - -0.0905161 -0.438358 0.423567 - -0.0898696 -0.376641 0.420305 - -0.101533 -0.421824 0.4699 - -0.10828 -0.417905 0.498332 - -0.122362 -0.417203 0.557734 - -0.254381 -0.669457 1.11687 - -0.258206 -0.656516 1.1329 - -0.270396 -0.65503 1.18431 - -0.283997 -0.661098 1.24174 - -0.28623 -0.660673 1.25116 - -0.317864 -0.667675 1.38467 - -0.318745 -0.662884 1.38835 - -0.327447 -0.662455 1.42505 - -0.413649 -0.67043 1.78879 - -0.435388 -0.67458 1.88053 - -0.438491 -0.543622 1.89249 - -0.438816 -0.226121 1.89111 - -0.439837 -0.0742914 1.8941 - -0.440467 -0.028986 1.89636 - -0.440567 0.0768945 1.89586 - -0.4405 0.0844523 1.89552 - -0.439698 0.114534 1.89187 - -0.443972 0.254389 1.90869 - -0.440338 0.298464 1.89298 - -0.442025 0.315332 1.89995 - -0.442172 0.323272 1.9005 - -0.442896 0.339568 1.90342 - -0.441612 0.401672 1.89746 - -0.442176 0.607231 1.89805 - -0.443219 0.660244 1.902 - -0.445033 0.733698 1.90901 - -0.504049 1.02066 2.1555 - -0.503733 1.08651 2.15359 - -0.503294 1.11941 2.15145 - -0.502986 1.13008 2.15006 - -0.504413 1.22723 2.15524 - -0.500643 1.26517 2.13901 - -0.49267 1.26715 2.10535 - -0.327533 1.27772 1.40859 - -0.318583 1.27042 1.3709 - -0.295917 1.27275 1.27526 - -0.276886 1.27482 1.19495 - -0.274888 1.2753 1.18652 - -0.23676 1.28096 1.02562 - -0.233305 1.28234 1.01103 - -0.224823 1.27355 0.975328 - -0.217307 1.26989 0.943648 - -0.202101 1.28307 0.879386 - -0.174576 1.28029 0.763291 - -0.156889 1.28496 0.688631 - -0.139551 1.15143 0.616646 - -0.125893 1.1587 0.558966 - -0.0610205 1.26868 0.284332 - -0.0597442 1.26901 0.278944 - -0.0486511 1.14274 0.23324 - -0.0371651 1.13771 0.184828 - -0.0258002 1.12952 0.136953 - -0.037922 0.0930172 0.19708 - -0.0371742 0.0975576 0.193886 - -0.0371142 0.0964986 0.193642 - -0.033658 0.108323 0.178958 - -0.0317725 0.103423 0.171046 - -0.0281342 0.135769 0.155417 - -0.0244554 0.151581 0.13976 - -0.0204229 0.167304 0.122612 - -0.0163071 0.181256 0.105127 - -0.0136352 0.189356 0.0937851 - -0.0086968 0.175371 0.0730726 - -0.0105675 0.149695 0.0811874 --0.00974236 -0.126815 0.0859642 --0.00825371 -0.150054 0.0801599 --0.00588831 -0.168154 0.0707809 --0.00624072 -0.169399 0.072211 - -0.0118489 -0.146967 0.0946181 - -0.0120027 -0.147484 0.0952418 - -0.0130645 -0.144581 0.0994954 - -0.0173021 -0.136449 0.116499 - -0.0167457 -0.151871 0.114386 - -0.0173542 -0.1523 0.116841 - -0.0192528 -0.155857 0.124519 - -0.0193259 -0.161766 0.124863 - -0.0209036 -0.159549 0.131201 - -0.0211059 -0.166687 0.132075 - -0.0224153 -0.170302 0.13738 - -0.0288851 -0.126068 0.163077 - -0.0321253 -0.106392 0.175967 - -0.0270089 -0.197343 0.15611 - -0.0253638 -0.356815 0.150807 - -0.0271708 -0.393412 0.15839 - -0.028765 -0.396268 0.164836 - -0.0325935 -0.438949 0.180614 - -0.0337467 -0.425223 0.185146 - -0.0607173 -2.27975 0.309196 - -0.0762794 -2.20081 0.371234 - -0.107398 -2.22458 0.496796 - -0.147826 -2.21426 0.659581 - -0.157496 -2.21268 0.698522 - -0.177374 -2.21507 0.778625 - -0.190932 -2.19324 0.833062 - -0.237882 -2.20163 1.02228 - -0.250129 -2.16234 1.07129 - -0.263558 -2.16266 1.12539 - -0.0922847 -0.382798 0.420621 - -0.0931692 -0.373786 0.42411 - -0.107216 -0.417194 0.481059 - -0.112954 -0.416423 0.50417 - -0.126544 -0.420243 0.558948 - -0.132955 -0.420704 0.584782 - -0.146871 -0.402425 0.640691 - -0.253191 -0.784558 1.07219 - -0.263413 -0.765797 1.11321 - -0.26377 -0.663066 1.1138 - -0.310484 -0.661519 1.30198 - -0.322032 -0.662441 1.34851 - -0.35841 -0.666083 1.49509 - -0.382171 -0.662053 1.59078 - -0.387455 -0.664618 1.61209 - -0.40739 -0.670671 1.69245 - -0.440083 -0.67046 1.82415 - -0.453127 -0.674946 1.87674 - -0.457118 -0.503552 1.8914 - -0.458177 -0.415438 1.89493 - -0.460452 -0.243816 1.90267 - -0.460045 -0.0823608 1.8997 - -0.459911 -0.01392 1.89859 - -0.458927 0.0467039 1.89412 - -0.460176 0.10008 1.89871 - -0.461306 0.138571 1.90294 - -0.460913 0.443355 1.89882 - -0.460691 0.451196 1.89787 - -0.463963 0.735635 1.90869 - -0.463194 0.825399 1.90484 - -0.500053 0.938146 2.0524 - -0.476284 1.28408 1.95377 - -0.428958 1.27545 1.76318 - -0.408422 1.27382 1.68046 - -0.396108 1.27513 1.63085 - -0.390351 1.27659 1.60764 - -0.382742 1.28188 1.57694 - -0.343574 1.27049 1.41925 - -0.280027 1.27135 1.16323 - -0.266901 1.27973 1.11028 - -0.263997 1.27483 1.09862 - -0.253461 1.2835 1.05611 - -0.239257 1.27917 0.998919 - -0.231328 1.27611 0.967003 - -0.211265 1.27351 0.886196 - -0.196523 1.27843 0.826768 - -0.190093 1.28031 0.800847 - -0.184624 1.27546 0.778854 - -0.124663 1.16574 0.538205 - -0.119107 1.18155 0.515692 - -0.117078 1.23444 0.507078 - -0.116224 1.26624 0.503373 - -0.104504 1.22888 0.456466 - -0.102069 1.20744 0.446836 - -0.0872529 1.16462 0.387504 - -0.0527059 1.17331 0.248255 - -0.0488163 1.14674 0.232806 - -0.0451226 1.12696 0.218089 - -0.0269227 0.986833 0.145932 - -0.0384673 0.0974555 0.199824 - -0.0387472 0.0784855 0.201109 - -0.0378075 0.0920853 0.197211 - -0.0361975 0.109214 0.190582 - -0.0354106 0.11876 0.187333 - -0.0355737 0.0944014 0.188192 - -0.0349606 0.0958284 0.185711 - -0.0323451 0.0966076 0.175167 - -0.0267259 0.143158 0.152143 - -0.0252935 0.155804 0.146268 - -0.021467 0.159431 0.130822 - -0.0131525 0.189201 0.0970791 - -0.0121741 0.190201 0.0931292 - -0.0118455 0.190518 0.0918026 - -0.0110549 0.135568 0.0890737 --0.00321229 -0.149175 0.0678284 - -0.0127411 -0.142089 0.104115 - -0.0136719 -0.141097 0.107657 - -0.0140008 -0.161555 0.109073 - -0.0151213 -0.160788 0.11334 - -0.018674 -0.164159 0.126916 - -0.0192187 -0.165261 0.129002 - -0.018598 -0.171889 0.126687 - -0.0267117 -0.133553 0.15733 - -0.0300984 -0.118219 0.170126 - -0.0304555 -0.134435 0.171616 - -0.0303893 -0.137489 0.171387 - -0.0256507 -0.218594 0.153954 - -0.0244624 -0.339538 0.150376 - -0.03005 -0.404158 0.172196 - -0.0390374 -0.400986 0.206448 - -0.0688955 -2.2343 0.334782 - -0.0805481 -2.19209 0.378891 - -0.097958 -2.20265 0.445374 - -0.121665 -2.17316 0.535559 - -0.144416 -2.13093 0.621997 - -0.184264 -2.16904 0.774273 - -0.206459 -2.22299 0.859349 - -0.22584 -2.19538 0.93305 - -0.239761 -2.19829 0.986167 - -0.244284 -2.18747 1.00333 - -0.245828 -2.17452 1.00912 - -0.284443 -2.16654 1.15633 - -0.287157 -2.16499 1.16667 - -0.0937176 -0.430344 0.415226 - -0.0947842 -0.429365 0.419286 - -0.105106 -0.464235 0.458926 - -0.0936551 -0.362656 0.414454 - -0.115451 -0.417424 0.498013 - -0.136956 -0.4248 0.58009 - -0.137428 -0.423124 0.581879 - -0.139589 -0.413902 0.590048 - -0.14005 -0.412182 0.59179 - -0.140277 -0.398836 0.59255 - -0.140727 -0.380043 0.594118 - -0.27275 -0.799721 1.10096 - -0.276352 -0.762995 1.1144 - -0.275001 -0.712183 1.10885 - -0.287166 -0.658018 1.15482 - -0.343587 -0.663801 1.37005 - -0.478489 -0.569326 1.88381 - -0.481519 -0.498188 1.89481 - -0.480292 -0.464094 1.88986 - -0.480816 -0.45651 1.8918 - -0.480457 -0.383783 1.88985 - -0.482486 -0.243816 1.89649 - -0.481572 -0.158589 1.89233 - -0.481659 -0.120391 1.89236 - -0.483031 -0.0367994 1.89693 - -0.483385 0.046973 1.89762 - -0.48225 0.092486 1.89293 - -0.482962 0.115526 1.89547 - -0.483596 0.13865 1.89771 - -0.484352 0.239146 1.8998 - -0.484762 0.309669 1.9008 - -0.48374 0.332534 1.89673 - -0.485347 0.373433 1.90253 - -0.481765 0.410154 1.88858 - -0.484721 0.619812 1.8982 - -0.48599 0.638797 1.90289 - -0.484319 0.67975 1.8962 - -0.486677 0.745615 1.90467 - -0.48677 0.772935 1.90481 - -0.49261 0.858015 1.92641 - -0.498637 0.988294 1.94837 - -0.499143 1.07246 1.94964 - -0.50015 1.08546 1.95338 - -0.500367 1.10744 1.95403 - -0.498926 1.18068 1.94795 - -0.501138 1.22035 1.95608 - -0.473293 1.28009 1.84941 - -0.461791 1.28012 1.80554 - -0.451959 1.28417 1.76801 - -0.425366 1.27783 1.66664 - -0.367244 1.26886 1.44504 - -0.36053 1.27549 1.41938 - -0.24973 1.28086 0.996751 - -0.191065 1.28256 0.772994 - -0.187497 1.2812 0.759397 - -0.145069 1.17273 0.598434 - -0.142775 1.16311 0.589762 - -0.133808 1.15774 0.555604 - -0.132529 1.1593 0.550714 - -0.0868272 1.16518 0.376365 - -0.0582176 1.26259 0.266482 - -0.0463509 1.12891 0.222277 - -0.0376186 1.12381 0.189013 - -0.0376905 0.0962154 0.197391 - -0.0363726 0.104533 0.192299 - -0.036706 0.0824448 0.193744 - -0.0358933 0.0868762 0.19061 - -0.0353171 0.0863405 0.188417 - -0.0308314 0.111203 0.171112 - -0.0288254 0.128497 0.163325 - -0.027482 0.139296 0.158116 - -0.0211856 0.161168 0.13393 - -0.0167053 0.17223 0.116755 - -0.0155832 0.176609 0.112441 - -0.0124288 0.188987 0.100313 --0.00799518 0.194469 0.0833601 - -0.0078464 0.191674 0.0828147 --0.00757837 0.186098 0.0818364 --0.00514011 0.178949 0.0725934 --0.00950649 0.134832 0.0895944 --0.00532282 -0.133473 0.0826422 --0.00597362 -0.134453 0.0850034 - -0.0103949 -0.148627 0.101101 - -0.0119048 -0.14906 0.106566 - -0.012405 -0.149161 0.108376 - -0.0121318 -0.165381 0.107509 - -0.0117637 -0.177511 0.106269 - -0.0148627 -0.171494 0.117433 - -0.0180313 -0.168672 0.128873 - -0.0199411 -0.168731 0.135781 - -0.028514 -0.121252 0.166433 - -0.0315895 -0.117586 0.177529 - -0.0262864 -0.204545 0.159 - -0.0258983 -0.36126 0.158773 - -0.0272254 -0.372035 0.163654 - -0.0281084 -0.385537 0.166949 - -0.0343987 -0.418531 0.189948 - -0.0354816 -0.409695 0.193799 - -0.0656161 -2.2713 0.316767 - -0.146387 -2.1151 0.607742 - -0.214049 -2.2115 0.853197 - -0.24779 -2.17575 0.974968 - -0.266029 -2.15607 1.04079 - -0.278181 -2.16005 1.08477 - -0.0979956 -0.370341 0.419615 - -0.111459 -0.414107 0.468642 - -0.118835 -0.415796 0.495331 - -0.121709 -0.41537 0.505724 - -0.123631 -0.417457 0.512691 - -0.13846 -0.418396 0.566336 - -0.146251 -0.399224 0.59437 - -0.146581 -0.386633 0.59547 - -0.149793 -0.381185 0.607045 - -0.288148 -0.684057 1.10975 - -0.287298 -0.663066 1.10651 - -0.306985 -0.657769 1.17768 - -0.30986 -0.652217 1.18804 - -0.350818 -0.660474 1.33625 - -0.368902 -0.663641 1.40168 - -0.402186 -0.663141 1.52206 - -0.45951 -0.668175 1.72944 - -0.504426 -0.482433 1.89051 - -0.507217 -0.315821 1.89935 - -0.505864 -0.228847 1.89381 - -0.507702 -0.129082 1.8997 - -0.506739 -0.0216354 1.89541 - -0.507653 0.270834 1.89652 - -0.507875 0.278787 1.89727 - -0.508581 0.504035 1.89813 - -0.509639 0.530116 1.90176 - -0.507789 0.569861 1.89477 - -0.507137 0.57749 1.89236 - -0.509672 0.606181 1.90131 - -0.507122 0.663083 1.89166 - -0.509102 0.718812 1.8984 - -0.503055 0.790002 1.876 - -0.503118 0.799221 1.87616 - -0.500761 1.0148 1.86601 - -0.500706 1.03493 1.86566 - -0.499735 1.09465 1.8617 - -0.497263 1.1203 1.85257 - -0.499592 1.27 1.85987 - -0.472105 1.28293 1.76035 - -0.434467 1.27907 1.62425 - -0.320828 1.26699 1.21331 - -0.28681 1.27321 1.09022 - -0.25889 1.27411 0.989223 - -0.249229 1.2778 0.954255 - -0.239359 1.27879 0.918546 - -0.237475 1.27939 0.911728 - -0.21618 1.27817 0.834714 - -0.214455 1.27921 0.828466 - -0.206506 1.27493 0.799748 - -0.0944435 1.16494 0.395245 - -0.0875869 1.16692 0.37043 - -0.0804573 1.16039 0.344691 - -0.0765022 1.16512 0.33035 - -0.0739072 1.17017 0.320926 - -0.0364826 0.10179 0.193581 - -0.0360072 0.0852406 0.191985 - -0.0343161 0.0971167 0.185779 - -0.0335124 0.107683 0.182793 - -0.0335148 0.105626 0.182817 - -0.0331367 0.107321 0.181437 - -0.0247456 0.150423 0.150763 - -0.0247226 0.145005 0.150721 - -0.0247565 0.142897 0.150859 - -0.0195806 0.155868 0.13204 --0.00642473 0.204572 0.0840906 --0.00639408 0.187807 0.0841056 --0.00210403 0.174421 0.068689 --0.00460939 0.141485 0.077998 --0.00194409 -0.144573 0.0756584 --0.00353745 -0.156559 0.0812934 - -0.0130199 -0.149766 0.114263 - -0.0120526 -0.172399 0.111059 - -0.0130577 -0.180228 0.114615 - -0.0150645 -0.170474 0.121532 - -0.0201041 -0.162663 0.139024 - -0.0243432 -0.249728 0.154416 - -0.0247266 -0.326499 0.156307 - -0.0255775 -0.344214 0.159398 - -0.0275419 -0.348225 0.166268 - -0.0275267 -0.373425 0.166397 - -0.0362372 -0.406818 0.19697 - -0.0529736 -2.28917 0.268886 - -0.128641 -2.16525 0.531468 - -0.130753 -2.15192 0.538726 - -0.147825 -2.11983 0.597939 - -0.167656 -2.23472 0.667823 - -0.170407 -2.23359 0.677394 - -0.235966 -2.22304 0.9056 - -0.245434 -2.19683 0.93838 - -0.246833 -2.18029 0.943131 - -0.25209 -2.17354 0.961387 - -0.296941 -2.16816 1.11752 - -0.099417 -0.366896 0.416677 - -0.102019 -0.371722 0.425771 - -0.134636 -0.417198 0.539678 - -0.134966 -0.414923 0.540808 - -0.137177 -0.413403 0.548498 - -0.148149 -0.413902 0.586705 - -0.150346 -0.400637 0.594262 - -0.14951 -0.383856 0.591228 - -0.295775 -0.800911 1.10356 - -0.29857 -0.781349 1.11315 - -0.297737 -0.705247 1.10969 - -0.352306 -0.66063 1.29938 - -0.364359 -0.658781 1.34134 - -0.374153 -0.664805 1.37549 - -0.380366 -0.663168 1.39711 - -0.505395 -0.655509 1.83242 - -0.506734 -0.631943 1.83691 - -0.506205 -0.572861 1.83464 - -0.508691 -0.526608 1.84296 - -0.522753 -0.451414 1.89138 - -0.522552 -0.291358 1.88952 - -0.522355 -0.252138 1.88855 - -0.525364 -0.106229 1.89797 - -0.526817 0.0628078 1.9018 - -0.526752 0.0704948 1.90152 - -0.527271 0.132305 1.90288 - -0.526642 0.194082 1.90024 - -0.526766 0.217475 1.90051 - -0.526364 0.335155 1.89825 - -0.525844 0.39065 1.89604 - -0.527599 0.506522 1.90131 - -0.527727 0.695065 1.90039 - -0.500444 0.86606 1.80415 - -0.499904 0.987999 1.80139 - -0.49775 1.14575 1.79274 - -0.487586 1.27217 1.75644 - -0.37316 1.27406 1.35798 - -0.371064 1.27707 1.35066 - -0.337803 1.27547 1.23486 - -0.327273 1.27449 1.1982 - -0.318041 1.27809 1.16602 - -0.304159 1.26987 1.11775 - -0.2818 1.27358 1.03986 - -0.263002 1.27859 0.974372 - -0.222142 1.27728 0.832104 - -0.206579 1.2747 0.77793 - -0.185953 1.27022 0.706142 - -0.144482 1.17334 0.562439 - -0.130081 1.16569 0.512347 - -0.123627 1.15941 0.489919 - -0.121307 1.16873 0.481773 - -0.0624255 1.26801 0.276024 - -0.0573761 1.23486 0.258682 - -0.0409442 1.11298 0.202348 - -0.0383576 0.0896516 0.200756 - -0.0380921 0.0915698 0.199817 - -0.0374643 0.106405 0.197524 - -0.0374946 0.089321 0.197753 - -0.0367102 0.102049 0.19493 - -0.0358885 0.106658 0.192035 - -0.0352975 0.0910373 0.19009 - -0.0337407 0.096905 0.184627 - -0.0310932 0.108699 0.175323 - -0.0285233 0.12875 0.166229 - -0.0230976 0.153318 0.147158 - -0.0221758 0.151893 0.143959 - -0.0138083 0.179208 0.114624 - -0.0069633 0.199429 0.0906431 --0.00388287 0.192168 0.0799694 --0.00225549 0.182979 0.0743694 --0.00220097 0.181576 0.0741897 - 0.00119104 -0.153062 0.0703044 --0.00969495 -0.140636 0.10667 - -0.0100592 -0.144081 0.107914 --0.00930926 -0.185407 0.105691 - -0.0100037 -0.18679 0.108026 - -0.0275438 -0.126731 0.166341 - -0.0317833 -0.106147 0.180393 - -0.0244727 -0.302374 0.157285 - -0.0270494 -0.346241 0.16622 - -0.0274814 -0.346429 0.167668 - -0.0287342 -0.37712 0.172077 - -0.0308967 -0.406899 0.179526 - -0.0328933 -0.409357 0.186229 - -0.0385869 -0.393987 0.205187 - -0.0938592 -2.18066 0.402758 - -0.16456 -2.1996 0.639638 - -0.229483 -2.2057 0.857078 - -0.269417 -2.17623 0.990593 - -0.109796 -0.429579 0.443883 - -0.115488 -0.424678 0.462909 - -0.126506 -0.414291 0.499732 - -0.139431 -0.419533 0.543049 - -0.140481 -0.416468 0.546543 - -0.146991 -0.420503 0.568369 - -0.154552 -0.423326 0.593709 - -0.154787 -0.398883 0.594326 - -0.307951 -0.79534 1.10998 - -0.30618 -0.762362 1.10382 - -0.3071 -0.731339 1.10668 - -0.309814 -0.705932 1.11559 - -0.30924 -0.666492 1.11339 - -0.433956 -0.664566 1.531 - -0.447825 -0.665007 1.57744 - -0.474927 -0.669062 1.66822 - -0.540457 -0.509135 1.88654 - -0.540502 -0.476128 1.88645 - -0.543429 -0.429644 1.89593 - -0.541816 -0.379795 1.89018 - -0.544099 0.0396951 1.8949 - -0.544523 0.0628078 1.89615 - -0.544741 0.0705348 1.89683 - -0.543557 0.116517 1.89254 - -0.543276 0.131856 1.8915 - -0.544483 0.178612 1.89521 - -0.544623 0.431965 1.89391 - -0.547294 0.550479 1.90202 - -0.547074 0.592739 1.90099 - -0.549356 0.709423 1.90782 - -0.506005 0.723949 1.76255 - -0.501799 0.802984 1.74791 - -0.501067 1.22022 1.74255 - -0.495437 1.27177 1.72334 - -0.488455 1.28601 1.69986 - -0.459149 1.27821 1.60178 - -0.447948 1.27706 1.56428 - -0.432184 1.28228 1.51146 - -0.365948 1.26762 1.28976 - -0.360633 1.28004 1.27188 - -0.350626 1.27309 1.23842 - -0.261721 1.27602 0.940695 - -0.224624 1.27753 0.816462 - -0.205136 1.27755 0.751203 - -0.201139 1.27603 0.737831 - -0.164841 1.16179 0.617084 - -0.13087 1.15644 0.503367 - -0.11301 1.26942 0.442772 - -0.098891 1.1827 0.396099 - -0.0969862 1.17466 0.389777 - -0.0952884 1.17054 0.384121 - -0.0864718 1.17398 0.354574 - -0.0335856 0.946535 0.179071 - -0.0377742 0.0955511 0.199044 - -0.0359132 0.10885 0.19272 - -0.0347786 0.109214 0.188918 - -0.034208 0.106796 0.187024 - -0.0342173 0.0976137 0.187119 - -0.0334681 0.10316 0.184572 - -0.0331747 0.0977643 0.183627 - -0.0318516 0.102703 0.179162 - -0.0251563 0.143272 0.156459 - -0.0230296 0.151086 0.149283 - -0.0229473 0.149893 0.149016 - -0.0201418 0.154332 0.13959 - -0.0161899 0.168711 0.126257 - -0.0152501 0.171516 0.12309 - -0.0112109 0.188871 0.109443 - -0.0105033 0.18751 0.107083 --0.00352599 0.21136 0.0835527 --0.00280803 0.191925 0.0812843 --0.00118037 0.184188 0.0758881 --0.00073969 0.171648 0.0745001 - 0.00207835 0.17121 0.0650667 - 0.0004674 0.157562 0.0705565 - 0.00262892 -0.156289 0.0722652 - 0.00081838 -0.152294 0.0780135 - 0.00160469 -0.159344 0.0755525 - 0.0002181 -0.155398 0.0799489 --0.00329798 -0.150855 0.0911335 - -0.009636 -0.193441 0.111634 - -0.012063 -0.181832 0.119298 - -0.0135253 -0.174194 0.123911 - -0.0154467 -0.170647 0.130016 - -0.0200274 -0.157744 0.14454 - -0.0287632 -0.121477 0.172162 - -0.031031 -0.101787 0.179264 - -0.0306793 -0.112902 0.178216 - -0.0241512 -0.307758 0.158697 - -0.0252648 -0.338705 0.162456 - -0.0254966 -0.343864 0.16323 - -0.0319167 -0.408254 0.184138 - -0.0739648 -2.21533 0.330337 - -0.197897 -2.20649 0.725577 - -0.272963 -2.17199 0.964778 - -0.297429 -2.15877 1.04273 - -0.117063 -0.478765 0.456196 - -0.117453 -0.471229 0.45739 - -0.117925 -0.469211 0.458881 - -0.117535 -0.45735 0.457557 - -0.140096 -0.415528 0.52924 - -0.144936 -0.420301 0.544708 - -0.151417 -0.412028 0.565325 - -0.157914 -0.413626 0.586061 - -0.321306 -0.777872 1.10966 - -0.320742 -0.742226 1.10762 - -0.32146 -0.698229 1.10961 - -0.320877 -0.684083 1.10766 - -0.350052 -0.661733 1.20057 - -0.35319 -0.661985 1.21058 - -0.358473 -0.660147 1.22742 - -0.393313 -0.669326 1.33861 - -0.399501 -0.66719 1.35833 - -0.408944 -0.663641 1.38842 - -0.480553 -0.66388 1.61683 - -0.503347 -0.533129 1.68866 - -0.550262 -0.5129 1.83817 - -0.570098 -0.391981 1.90063 - -0.566156 -0.348907 1.88777 - -0.571191 -0.320074 1.90364 - -0.56782 -0.254708 1.89245 - -0.56609 -0.246032 1.88687 - -0.568534 -0.207932 1.89441 - -0.568615 -0.137823 1.8942 - -0.56697 -0.067935 1.88849 - -0.567303 -0.0371789 1.88935 - -0.56895 0.132604 1.89346 - -0.568787 0.140313 1.89289 - -0.569977 0.187346 1.89637 - -0.572859 0.227693 1.9053 - -0.571088 0.242671 1.89955 - -0.572325 0.452489 1.90209 - -0.569897 0.491666 1.89408 - -0.570418 0.500464 1.89569 - -0.573436 0.520095 1.90518 - -0.572204 0.664931 1.90028 - -0.509944 0.723325 1.70131 - -0.505474 0.724648 1.68704 - -0.498375 0.762768 1.66414 - -0.501062 0.826584 1.67229 - -0.498994 0.910699 1.66513 - -0.498491 1.02113 1.66278 - -0.498085 1.08876 1.66104 - -0.496676 1.14636 1.65616 - -0.490887 1.27072 1.63686 - -0.477905 1.27821 1.59541 - -0.426781 1.2752 1.43236 - -0.386944 1.28053 1.30526 - -0.382272 1.27434 1.2904 - -0.370887 1.27578 1.25407 - -0.342077 1.27215 1.1622 - -0.333976 1.27166 1.13637 - -0.331774 1.27351 1.12933 - -0.323738 1.27238 1.10371 - -0.286762 1.2714 0.985772 - -0.260303 1.27591 0.901347 - -0.241432 1.27955 0.841132 - -0.168506 1.16176 0.609312 - -0.166581 1.15983 0.603186 - -0.118229 1.17286 0.448874 - -0.114375 1.27048 0.435925 - -0.0753507 1.15673 0.312214 - -0.0416899 0.953998 0.206204 - -0.0396124 0.0959754 0.205313 - -0.035978 0.105021 0.19366 - -0.0329327 0.0979819 0.183994 - -0.0323254 0.100553 0.18204 - -0.0319317 0.100197 0.180786 - -0.0285797 0.126034 0.169922 - -0.0218052 0.159328 0.148091 - -0.0182644 0.156417 0.136817 --0.00036715 0.21218 0.0793582 - 0.00479193 0.186405 0.0630749 - 0.00523603 0.180012 0.0617012 - 0.00766402 0.178238 0.0539686 - 0.00593998 0.167313 0.0595407 - 0.00557777 0.160253 0.0607432 - 0.00704099 -0.16526 0.0633099 - -0.0061516 -0.151031 0.10387 --0.00581259 -0.153947 0.102844 --0.00554818 -0.159479 0.102065 - -0.007867 -0.157296 0.109196 --0.00904812 -0.157377 0.112836 --0.00909455 -0.158657 0.112988 - -0.0070384 -0.196515 0.106897 - -0.0132329 -0.177499 0.125862 - -0.0147134 -0.17533 0.13041 - -0.0273546 -0.179667 0.169391 - -0.0245885 -0.273811 0.161477 - -0.026789 -0.332532 0.168638 - -0.0321065 -0.408358 0.185515 - -0.036593 -0.39891 0.199279 - -0.112829 -2.26825 0.446306 - -0.145944 -2.181 0.547783 - -0.196358 -2.20238 0.703269 - -0.203154 -2.20941 0.724257 - -0.209555 -2.2104 0.743985 - -0.246076 -2.18841 0.856382 - -0.280495 -2.17293 0.96234 - -0.313436 -2.16676 1.06381 - -0.11033 -0.44245 0.426776 - -0.116256 -0.469546 0.445213 - -0.119623 -0.474995 0.455623 - -0.120813 -0.462557 0.459209 - -0.110791 -0.373986 0.427753 - -0.123703 -0.417107 0.467819 - -0.129578 -0.413824 0.485901 - -0.130492 -0.414169 0.488722 - -0.152514 -0.41081 0.556557 - -0.154722 -0.404339 0.56332 - -0.163687 -0.420844 0.591052 - -0.330271 -0.799213 1.10682 - -0.330654 -0.779143 1.10787 - -0.330445 -0.757931 1.10709 - -0.332599 -0.71667 1.11346 - -0.332518 -0.697052 1.11308 - -0.341576 -0.660811 1.14076 - -0.347331 -0.654483 1.15845 - -0.372302 -0.661219 1.23544 - -0.386555 -0.656101 1.27933 - -0.427023 -0.660723 1.40406 - -0.475198 -0.665698 1.55254 - -0.506531 -0.64983 1.64899 - -0.50602 -0.61799 1.64721 - -0.505976 -0.602537 1.64697 - -0.505886 -0.512239 1.64611 - -0.55921 -0.513934 1.81043 - -0.585544 -0.48963 1.89142 - -0.585515 -0.374826 1.89059 - -0.585022 -0.358375 1.88896 - -0.585515 -0.278888 1.88997 - -0.587542 -0.122807 1.8952 - -0.587853 0.00128963 1.89536 - -0.588978 0.0478608 1.89852 - -0.588725 0.258859 1.89637 - -0.588036 0.27435 1.89415 - -0.590166 0.363544 1.90014 - -0.589094 0.444249 1.89631 - -0.588169 0.476479 1.89325 - -0.581871 0.726839 1.87222 - -0.540731 0.7302 1.74543 - -0.531308 0.724792 1.71643 - -0.499873 0.928966 1.61824 - -0.496498 1.0138 1.60729 - -0.493903 1.0948 1.59877 - -0.475534 1.2765 1.54099 - -0.469705 1.27044 1.52307 - -0.426787 1.28022 1.39076 - -0.394652 1.26938 1.2918 - -0.349767 1.27651 1.15345 - -0.331947 1.28131 1.09851 - -0.312914 1.27721 1.03988 - -0.291477 1.28102 0.9738 - -0.277851 1.27173 0.931875 - -0.238496 1.27664 0.810572 - -0.208645 1.27161 0.718622 - -0.208023 1.28225 0.716637 - -0.198789 1.27284 0.688244 - -0.196963 1.2741 0.682608 - -0.174056 1.16085 0.612756 - -0.100183 1.19129 0.384924 - -0.0751298 1.17114 0.307855 - -0.073553 1.1716 0.302993 - -0.0527963 1.15648 0.23913 - -0.0428409 0.955992 0.209753 - -0.0373251 0.0935605 0.198344 - -0.0359591 0.106134 0.194053 - -0.0350569 0.106731 0.191269 - -0.0349377 0.0975576 0.190961 - -0.0325025 0.10922 0.183382 - -0.0243279 0.151471 0.157919 - -0.0179017 0.154926 0.138094 - -0.0142581 0.172507 0.126753 --0.00960298 0.192844 0.112277 --0.00285148 0.205841 0.0913884 - 0.00026446 0.21022 0.0817585 - 0.00629886 0.187842 0.0633089 - 0.0102124 0.186337 0.0512594 - 0.00695125 0.160922 0.061473 - 0.00482629 -0.176797 0.074815 --0.00548725 -0.144772 0.105324 --0.00618489 -0.164537 0.107525 --0.00636401 -0.168445 0.108083 - -0.0121024 -0.180579 0.125246 - -0.0123528 -0.180953 0.125994 - -0.0128552 -0.181689 0.127495 - -0.0199747 -0.154227 0.148522 - -0.0205433 -0.151701 0.150199 - -0.0235518 -0.140271 0.159085 - -0.0237464 -0.140489 0.159666 - -0.0269521 -0.12064 0.169087 - -0.0286228 -0.109702 0.173993 - -0.0290221 -0.109043 0.175177 - -0.0298966 -0.106722 0.177767 - -0.0271552 -0.321781 0.170955 - -0.0375521 -0.38797 0.202329 - -0.0550419 -2.28217 0.266307 - -0.0645525 -2.28117 0.294619 - -0.100641 -2.20456 0.401595 - -0.124533 -2.18121 0.472593 - -0.138947 -2.15878 0.51537 - -0.142556 -2.17019 0.526187 - -0.150766 -2.21061 0.550888 - -0.173576 -2.11926 0.618234 - -0.21249 -2.22157 0.73475 - -0.250606 -2.16836 0.847909 - -0.307612 -2.16353 1.01762 - -0.329771 -2.17172 1.08365 - -0.333041 -2.1695 1.09338 - -0.347149 -2.16746 1.13537 - -0.111984 -0.380415 0.423912 - -0.125136 -0.432307 0.463399 - -0.133249 -0.410441 0.487422 - -0.134391 -0.407843 0.490805 - -0.142031 -0.417248 0.513614 - -0.15317 -0.41181 0.546745 - -0.160859 -0.406152 0.569606 - -0.170187 -0.386829 0.597259 - -0.170495 -0.384347 0.59816 - -0.308962 -0.731125 1.01264 - -0.348057 -0.654667 1.12857 - -0.394775 -0.657971 1.2677 - -0.411951 -0.662441 1.31888 - -0.426495 -0.660456 1.36217 - -0.507894 -0.64735 1.60446 - -0.507321 -0.600981 1.60247 - -0.533004 -0.510581 1.67837 - -0.59982 -0.512205 1.87734 - -0.604005 -0.499246 1.88972 - -0.606232 -0.426377 1.89589 - -0.603849 -0.383813 1.88853 - -0.605444 -0.36056 1.89313 - -0.604293 -0.327645 1.8895 - -0.604757 -0.319897 1.89083 - -0.604738 -0.232482 1.89022 - -0.608045 -0.170649 1.89968 - -0.607334 0.267498 1.89481 - -0.608335 0.299867 1.89759 - -0.608327 0.445947 1.89665 - -0.608644 0.454464 1.89754 - -0.613275 0.709385 1.90973 - -0.498998 0.765812 1.5691 - -0.497676 0.845584 1.56466 - -0.498065 0.914987 1.56538 - -0.496118 0.937521 1.55944 - -0.497489 0.97638 1.56328 - -0.49772 0.986019 1.56391 - -0.498203 1.02424 1.56511 - -0.497186 1.06965 1.56179 - -0.487563 1.27246 1.53186 - -0.472082 1.27199 1.48577 - -0.412519 1.27117 1.30842 - -0.400345 1.27329 1.27216 - -0.382459 1.27547 1.21888 - -0.268221 1.28271 0.87868 - -0.255994 1.27841 0.842299 - -0.223755 1.28303 0.746274 - -0.219679 1.28429 0.734129 - -0.16721 1.16122 0.57867 - -0.164105 1.2003 0.569181 - -0.105626 1.22994 0.394863 - -0.0942729 1.17358 0.361413 - -0.0839919 1.16456 0.330857 - -0.0663129 1.25371 0.277655 - -0.0370865 0.116632 0.197772 - -0.0362833 0.106355 0.195445 - -0.0361934 0.0932396 0.19526 - -0.0326483 0.108557 0.184608 - -0.02913 0.12332 0.174039 - -0.0271288 0.139177 0.167981 - -0.0269353 0.138999 0.167405 - -0.0250338 0.149699 0.161676 - -0.0217823 0.155698 0.151957 - -0.0181503 0.151003 0.141172 --0.00313725 0.207569 0.0961129 --0.00214463 0.204642 0.0931756 - 0.00028253 0.201191 0.0859701 - 0.0005004 0.198392 0.0853389 - 0.00724044 0.186935 0.0653415 - 0.0075009 0.186283 0.06457 - 0.00801911 0.18497 0.0630353 - 0.0145048 0.187143 0.0437096 - 0.0118751 0.168926 0.0516542 - 0.0194321 -0.176132 0.0387982 - 0.0206556 -0.189391 0.0353906 - 0.0193804 -0.19028 0.0390312 - 0.0127364 -0.173325 0.0578673 - 0.0125709 -0.180489 0.0583825 - 0.0139493 -0.200547 0.0545744 --0.00399382 -0.148595 0.105408 --0.00343361 -0.152318 0.103833 --0.00115839 -0.174366 0.0974809 --0.00611001 -0.16722 0.111552 --0.00355282 -0.203156 0.10448 - -0.014913 -0.171867 0.136673 - -0.0219397 -0.146861 0.156552 - -0.0224877 -0.144261 0.158098 - -0.029482 -0.106854 0.17781 - -0.0295792 -0.117298 0.17815 - -0.0270695 -0.178213 0.171364 - -0.0253752 -0.221081 0.166793 - -0.0312187 -0.384298 0.184436 - -0.0317124 -0.387391 0.185862 - -0.0745843 -2.22586 0.319176 - -0.125217 -2.19432 0.463315 - -0.162335 -2.22116 0.569282 - -0.193225 -2.18669 0.657124 - -0.197786 -2.20412 0.670233 - -0.230344 -2.19029 0.762954 - -0.249565 -2.17701 0.817664 - -0.293462 -2.16508 0.942722 - -0.32575 -2.16526 1.03476 - -0.374403 -2.16633 1.17345 - -0.113336 -0.436343 0.418826 - -0.121752 -0.465808 0.442994 - -0.124087 -0.464235 0.449642 - -0.131322 -0.413486 0.469959 - -0.134987 -0.418007 0.480431 - -0.140535 -0.418321 0.496247 - -0.143344 -0.414487 0.504233 - -0.147363 -0.415194 0.515692 - -0.177317 -0.410428 0.601049 - -0.175546 -0.384347 0.595842 - -0.354905 -0.681049 1.1089 - -0.388341 -0.65951 1.20408 - -0.462922 -0.659321 1.41667 - -0.486848 -0.66687 1.48492 - -0.503522 -0.661439 1.53241 - -0.507886 -0.645061 1.54475 - -0.504024 -0.617596 1.53358 - -0.505844 -0.569125 1.53847 - -0.505261 -0.518843 1.53651 - -0.516226 -0.509675 1.56771 - -0.526017 -0.512917 1.59564 - -0.605564 -0.51405 1.82239 - -0.627169 -0.508361 1.88394 - -0.628408 -0.484261 1.88733 - -0.631117 -0.403459 1.89456 - -0.630075 -0.36195 1.89134 - -0.630803 -0.346164 1.89332 - -0.630597 -0.24977 1.89215 - -0.632658 -0.226739 1.89789 - -0.629689 -0.201904 1.88928 - -0.632814 -0.0534533 1.89729 - -0.6329 -0.0456329 1.89749 - -0.633435 0.0404389 1.89849 - -0.634219 0.390861 1.89861 - -0.633865 0.423489 1.8974 - -0.634805 0.490804 1.89967 - -0.634989 0.507812 1.9001 - -0.63393 0.575056 1.89667 - -0.639054 0.61494 1.91104 - -0.576399 0.721504 1.73179 - -0.510392 0.723782 1.54363 - -0.497903 0.750618 1.50787 - -0.497973 0.88874 1.50723 - -0.496436 0.981804 1.50229 - -0.496196 1.00859 1.50144 - -0.495992 1.12278 1.50017 - -0.491793 1.26882 1.48732 - -0.469796 1.27169 1.4246 - -0.463304 1.27442 1.40608 - -0.446904 1.26836 1.35937 - -0.371081 1.27415 1.14319 - -0.362329 1.2743 1.11825 - -0.351205 1.27567 1.08653 - -0.294228 1.27002 0.92415 - -0.287544 1.27383 0.905076 - -0.258007 1.28263 0.820827 - -0.255706 1.28278 0.814268 - -0.241409 1.27934 0.773533 - -0.214333 1.27485 0.696381 - -0.182927 1.15804 0.607564 - -0.175454 1.15869 0.586258 - -0.167071 1.16722 0.56231 - -0.150016 1.2014 0.513488 - -0.137733 1.16553 0.478693 - -0.0855088 1.16555 0.329827 - -0.040131 0.109996 0.206854 - -0.0399721 0.109999 0.206401 - -0.0398132 0.11 0.205949 - -0.0380054 0.0948431 0.200887 - -0.0371065 0.0976573 0.198308 - -0.0361575 0.100391 0.195586 - -0.0351591 0.10304 0.192724 - -0.0350102 0.102977 0.1923 - -0.0349171 0.0928318 0.192096 - -0.0332917 0.106177 0.187382 - -0.0325914 0.104742 0.185395 - -0.03244 0.104645 0.184964 - -0.0319456 0.109432 0.183525 - -0.0318467 0.0980879 0.183312 - -0.0317049 0.0979819 0.182908 - -0.0302054 0.110222 0.17856 - -0.0285985 0.122356 0.173906 - -0.0233807 0.144628 0.158898 - -0.0216511 0.153371 0.153915 - -0.0195728 0.149893 0.148012 --0.00113364 0.218375 0.0950375 - 0.00133935 0.191965 0.0881478 - 0.00870084 0.211878 0.0670435 - 0.0095555 0.203921 0.0646554 - 0.00994843 0.201806 0.0635481 - 0.0170359 0.18937 0.0434204 - 0.0220562 -0.190963 0.0371821 - 0.0169142 -0.184395 0.0513163 - 0.0157317 -0.182113 0.054562 - 0.0217277 -0.218508 0.0382491 --0.00555736 -0.156531 0.11309 --0.00117916 -0.21385 0.101359 - -0.0169053 -0.158031 0.144376 - -0.0194146 -0.153404 0.151265 - -0.0198845 -0.151782 0.152551 - -0.0307082 -0.10709 0.182122 - -0.0257458 -0.202243 0.169002 - -0.02571 -0.212411 0.168963 - -0.0262813 -0.21373 0.170545 - -0.0245028 -0.276772 0.166013 - -0.0304583 -0.37621 0.183011 - -0.0329283 -0.396634 0.189939 - -0.0400356 -0.411981 0.209618 - -0.0911758 -2.17987 0.360939 - -0.155693 -2.21809 0.538989 - -0.170174 -2.17641 0.578658 - -0.229741 -2.19728 0.74296 - -0.250881 -2.16157 0.801017 - -0.254101 -2.15879 0.809876 - -0.357711 -2.16907 1.09551 - -0.372424 -2.16408 1.13603 - -0.377204 -2.16973 1.14924 - -0.388485 -2.16635 1.18031 - -0.117103 -0.460723 0.422319 - -0.124455 -0.47771 0.442684 - -0.130974 -0.468322 0.460596 - -0.138605 -0.413824 0.481309 - -0.139838 -0.411252 0.484691 - -0.153362 -0.407173 0.521944 - -0.160405 -0.417203 0.541414 - -0.184975 -0.378707 0.608909 - -0.361217 -0.80115 1.09715 - -0.368381 -0.664257 1.1161 - -0.430941 -0.663662 1.28852 - -0.451043 -0.662884 1.34392 - -0.483289 -0.663693 1.4328 - -0.505191 -0.637158 1.49302 - -0.502712 -0.597894 1.48595 - -0.505884 -0.531787 1.49431 - -0.59324 -0.511521 1.73496 - -0.629889 -0.512239 1.83598 - -0.645083 -0.33613 1.87683 - -0.649431 -0.0377273 1.88706 - -0.644261 0.377814 1.87037 - -0.644142 0.393907 1.86995 - -0.627252 0.722464 1.82147 - -0.512438 0.728759 1.50498 - -0.49713 0.869669 1.46196 - -0.496862 1.09238 1.45992 - -0.495195 1.10783 1.45523 - -0.465184 1.27592 1.37153 - -0.394214 1.2776 1.17591 - -0.380885 1.27415 1.13919 - -0.360205 1.27486 1.08219 - -0.357707 1.27649 1.07529 - -0.354809 1.27646 1.06731 - -0.3408 1.27721 1.02869 - -0.329578 1.27646 0.997764 - -0.310951 1.27695 0.946422 - -0.241001 1.28347 0.753583 - -0.228432 1.27568 0.718987 - -0.160293 1.25586 0.531295 - -0.131334 1.16572 0.452005 - -0.129072 1.16002 0.445805 - -0.121745 1.15844 0.425618 - -0.116556 1.24791 0.410793 - -0.110113 1.26932 0.392909 - -0.0865924 1.16357 0.3287 - -0.0388471 0.0869683 0.203416 - -0.0376227 0.104827 0.199937 - -0.0365033 0.10559 0.196847 - -0.0351775 0.0961043 0.193248 - -0.0341007 0.102708 0.190242 - -0.0331599 0.105278 0.187634 - -0.0326265 0.106001 0.186159 - -0.0292678 0.120162 0.176819 - -0.0265835 0.138735 0.169311 - -0.0211739 0.151489 0.154326 - -0.013288 0.172266 0.132469 --0.00276687 0.222821 0.103174 --0.00131643 0.224055 0.099169 - 0.0109079 0.200856 0.065612 - 0.0144715 0.205463 0.0557628 - 0.0195906 0.207471 0.0416416 - 0.0203384 0.208234 0.0395758 - 0.0206492 0.207462 0.0387238 - 0.0209673 0.196028 0.0379142 - 0.0266858 -0.187624 0.0315494 - 0.0263974 -0.188432 0.0323175 - 0.02705 -0.193638 0.0306193 - 0.0261532 -0.196065 0.0330071 - 0.0184847 -0.211943 0.0533993 - 0.00049524 -0.165888 0.100766 --0.00543838 -0.155249 0.116415 --0.00403215 -0.171545 0.112784 --0.00285798 -0.190346 0.109782 --0.00076889 -0.212138 0.104374 --0.00335332 -0.211278 0.111212 - -0.0158495 -0.164447 0.14403 - -0.0167578 -0.160077 0.14641 - -0.0257479 -0.125469 0.170015 - -0.0280453 -0.114832 0.176037 - -0.0288732 -0.108205 0.178192 - -0.0314145 -0.0965746 0.184854 - -0.0260358 -0.224074 0.171336 - -0.0243467 -0.266887 0.167106 - -0.0255813 -0.267399 0.170378 - -0.0261412 -0.264587 0.171844 - -0.0268678 -0.286028 0.173889 - -0.0321059 -0.386567 0.188326 - -0.0600407 -2.25989 0.272886 - -0.0896524 -2.18056 0.350834 - -0.168119 -2.23958 0.558908 - -0.276471 -2.15967 0.845316 - -0.377837 -2.17353 1.11376 - -0.132963 -0.47706 0.455855 - -0.140444 -0.470447 0.475625 - -0.141171 -0.469182 0.477542 - -0.142018 -0.413824 0.47947 - -0.149186 -0.418827 0.498478 - -0.151923 -0.402809 0.505632 - -0.156897 -0.40941 0.518837 - -0.175813 -0.408828 0.568914 - -0.179273 -0.411892 0.578093 - -0.183207 -0.377794 0.588316 - -0.187499 -0.38227 0.599704 - -0.379284 -0.733518 1.10944 - -0.381231 -0.71123 1.11447 - -0.408485 -0.660386 1.18634 - -0.422477 -0.659088 1.22337 - -0.442771 -0.660167 1.27711 - -0.504519 -0.635502 1.44044 - -0.505208 -0.608189 1.44211 - -0.503121 -0.57779 1.43641 - -0.504911 -0.545894 1.44097 - -0.505759 -0.540127 1.44319 - -0.534536 -0.509957 1.5192 - -0.577294 -0.509117 1.6324 - -0.583783 -0.507769 1.64957 - -0.637934 -0.429535 1.79249 - -0.637309 -0.38212 1.79057 - -0.635359 -0.326964 1.7851 - -0.635475 -0.243571 1.78493 - -0.635877 -0.206194 1.78578 - -0.637311 -0.161803 1.78933 - -0.637629 -0.117216 1.78992 - -0.63675 -0.0948086 1.78746 - -0.634709 -0.0723612 1.78193 - -0.639591 0.0308858 1.79427 - -0.638505 0.142088 1.79077 - -0.637491 0.194014 1.78779 - -0.637141 0.345137 1.78601 - -0.635382 0.405784 1.78101 - -0.636539 0.42217 1.78398 - -0.637639 0.438642 1.7868 - -0.640118 0.504224 1.79299 - -0.636832 0.54175 1.78408 - -0.640888 0.722523 1.79379 - -0.615372 0.725578 1.72622 - -0.556231 0.728808 1.56963 - -0.497309 0.785322 1.41331 - -0.498884 0.900395 1.41683 - -0.496016 1.09094 1.40816 - -0.379672 1.27132 1.09912 - -0.341117 1.2823 0.996985 - -0.331331 1.27645 0.971109 - -0.320632 1.2778 0.942775 - -0.288296 1.27439 0.857186 - -0.226532 1.28133 0.693627 - -0.190663 1.1627 0.599334 - -0.168582 1.16156 0.540882 - -0.160394 1.25788 0.51866 - -0.135914 1.16164 0.454393 - -0.116939 1.2459 0.403682 - -0.11058 1.27315 0.38669 - -0.0392968 0.0829988 0.204706 - -0.0375351 0.103853 0.199924 - -0.0363412 0.0955907 0.19681 - -0.0335045 0.100589 0.189271 - -0.0324771 0.112253 0.186485 - -0.0321509 0.109037 0.18564 - -0.0314789 0.108657 0.183863 - -0.02069 0.157151 0.155025 - -0.0193813 0.16115 0.151537 - -0.0121099 0.176598 0.132199 - -0.0075427 0.201433 0.119967 --0.00391406 0.214282 0.110287 - 0.0017881 0.225215 0.0951291 - 0.00232219 0.21193 0.0937903 - 0.00197435 0.188181 0.0948456 - 0.0118705 0.21398 0.0684997 - 0.0122011 0.213342 0.067628 - 0.0170229 0.214619 0.0548551 - 0.0270469 -0.194671 0.0359928 - 0.0279094 -0.200673 0.0338125 - 0.0259674 -0.2263 0.0389373 - 0.0180124 -0.207758 0.0592487 - 0.0157173 -0.201223 0.0651026 - 0.00262624 -0.172697 0.098539 - 0.00235317 -0.173193 0.0992425 --0.00076635 -0.163237 0.107193 --0.00129418 -0.182849 0.108655 --0.00041508 -0.203202 0.106512 --0.00269121 -0.208569 0.112382 - -0.0072167 -0.195562 0.123924 --0.00916036 -0.190249 0.128882 - -0.0231905 -0.139464 0.164606 - -0.0238537 -0.140017 0.166311 - -0.0298114 -0.105034 0.181406 - -0.0285661 -0.153408 0.178477 - -0.0249058 -0.27037 0.169729 - -0.02662 -0.270989 0.174131 - -0.0287805 -0.325896 0.179977 - -0.0306503 -0.356349 0.184943 - -0.032135 -0.367588 0.188815 - -0.0410287 -0.399933 0.211816 - -0.0874677 -2.17722 0.340776 - -0.110335 -2.2414 0.399809 - -0.173879 -2.21623 0.562734 - -0.217182 -2.20976 0.673821 - -0.246289 -2.20347 0.748481 - -0.275804 -2.16268 0.823995 - -0.291265 -2.16599 0.863689 - -0.329659 -2.16499 0.96221 - -0.337422 -2.16436 0.982126 - -0.34494 -2.16167 1.0014 - -0.378077 -2.16816 1.08647 - -0.391034 -2.17201 1.11975 - -0.139633 -0.408959 0.4649 - -0.148981 -0.422608 0.488964 - -0.152538 -0.412896 0.498038 - -0.153194 -0.41152 0.499713 - -0.165394 -0.412654 0.531027 - -0.168886 -0.405672 0.53995 - -0.177644 -0.410741 0.562452 - -0.185066 -0.410538 0.581497 - -0.188042 -0.408028 0.589119 - -0.191854 -0.376581 0.598729 - -0.390878 -0.786572 1.11171 - -0.388822 -0.682059 1.10586 - -0.42878 -0.65861 1.20827 - -0.467536 -0.668343 1.30778 - -0.505161 -0.661607 1.40429 - -0.5038 -0.63154 1.40064 - -0.504824 -0.605219 1.40312 - -0.5007 -0.572847 1.39236 - -0.501883 -0.514904 1.39507 - -0.543839 -0.512625 1.50273 - -0.575602 -0.508438 1.58421 - -0.651656 -0.326964 1.77838 - -0.653237 -0.199054 1.78173 - -0.65356 -0.191668 1.78252 - -0.654338 -0.117285 1.78411 - -0.655197 -0.0580263 1.78598 - -0.652383 0.0233353 1.77831 - -0.636599 0.130652 1.73722 - -0.639711 0.160401 1.74504 - -0.655682 0.202104 1.7858 - -0.652137 0.2609 1.77638 - -0.655757 0.338738 1.78524 - -0.655479 0.527592 1.78348 - -0.638553 0.601099 1.73964 - -0.636585 0.607243 1.73456 - -0.650244 0.714303 1.76902 - -0.62527 0.726909 1.70486 - -0.597073 0.716183 1.63256 - -0.520518 0.719083 1.4361 - -0.510602 0.718943 1.41065 - -0.500027 0.731918 1.38344 - -0.496227 0.74791 1.3736 - -0.499478 1.05151 1.38027 - -0.496651 1.08253 1.37285 - -0.496138 1.11013 1.37138 - -0.496687 1.13107 1.37267 - -0.452671 1.27061 1.25895 - -0.446723 1.27443 1.24367 - -0.41908 1.27463 1.17273 - -0.404197 1.26901 1.13457 - -0.37774 1.27649 1.06664 - -0.360362 1.27968 1.02202 - -0.33674 1.27833 0.961412 - -0.317236 1.27849 0.911362 - -0.25552 1.28091 0.752977 - -0.233767 1.28088 0.697154 - -0.223459 1.2589 0.670822 - -0.202065 1.17111 0.616407 - -0.164634 1.1874 0.520264 - -0.131216 1.16906 0.434608 - -0.127069 1.1653 0.423986 - -0.119349 1.19281 0.404026 - -0.110076 1.27003 0.379803 - -0.0971252 1.17398 0.347099 - -0.0871197 1.16015 0.3215 - -0.0359457 0.0955511 0.196043 - -0.0341866 0.107066 0.191465 - -0.0311725 0.107678 0.183728 - -0.0281504 0.12833 0.175859 - -0.0263172 0.136327 0.17111 - -0.0239988 0.150112 0.165085 - -0.0215854 0.15542 0.158862 - -0.0185362 0.15145 0.15106 - -0.0149176 0.166844 0.141689 - -0.0124578 0.174842 0.135333 --0.00681862 0.201828 0.120713 - 0.00193958 0.216739 0.098156 - 0.003111 0.209313 0.0951909 - 0.00255615 0.204449 0.0966415 - 0.00729237 0.205982 0.0844792 - 0.0130229 0.218373 0.0697055 - 0.0161224 0.218602 0.0617504 - 0.0196915 0.220138 0.052583 - 0.0294845 0.220313 0.0274519 - 0.0295974 0.218727 0.0271708 - 0.031715 -0.188934 0.0294242 - 0.0295416 -0.194608 0.0348639 - 0.030028 -0.225482 0.0338189 - 0.0300929 -0.231785 0.0336914 - 0.0117249 -0.186172 0.0791623 - 0.0048017 -0.174693 0.0963316 - 0.00327547 -0.170194 0.100106 - -0.0021738 -0.15696 0.113598 --0.00268428 -0.157808 0.114873 --0.00287921 -0.161638 0.115378 --0.00029842 -0.195657 0.109138 --0.00624682 -0.199982 0.123966 --0.00822148 -0.192444 0.12884 - -0.0176009 -0.149662 0.151955 - -0.0261309 -0.126561 0.173061 - -0.0303422 -0.10458 0.183424 - -0.0255011 -0.249572 0.172153 - -0.0415784 -0.397898 0.212963 - -0.042193 -0.393857 0.214471 - -0.119216 -2.23155 0.41603 - -0.138477 -2.1703 0.463639 - -0.209587 -2.19658 0.640763 - -0.257746 -2.14846 0.760369 - -0.314097 -2.16942 0.900732 - -0.36013 -2.15414 1.01522 - -0.42218 -2.17357 1.16976 - -0.450362 -2.1595 1.23982 - -0.13446 -0.475251 0.444548 - -0.135873 -0.467467 0.448024 - -0.154327 -0.474783 0.493994 - -0.146566 -0.426308 0.474417 - -0.146475 -0.418007 0.474146 - -0.147157 -0.416735 0.475835 - -0.177943 -0.412028 0.552435 - -0.21119 -0.399151 0.635112 - -0.361116 -0.727004 1.01002 - -0.401292 -0.774943 1.11027 - -0.401974 -0.769441 1.11194 - -0.399578 -0.730499 1.10576 - -0.397713 -0.662559 1.10076 - -0.398795 -0.65834 1.10343 - -0.491274 -0.666246 1.33364 - -0.507523 -0.654766 1.37402 - -0.501954 -0.520768 1.35944 - -0.502807 -0.515333 1.36153 - -0.64169 -0.470615 1.70696 - -0.635304 -0.458047 1.69099 - -0.634631 -0.419949 1.68911 - -0.63841 -0.392675 1.69837 - -0.660906 -0.37662 1.75428 - -0.667345 -0.372781 1.77028 - -0.671581 -0.328865 1.78059 - -0.671391 -0.321079 1.78008 - -0.671611 -0.260114 1.7803 - -0.671077 -0.162088 1.77844 - -0.672969 -0.140117 1.78303 - -0.640509 0.0786565 1.70107 - -0.638045 0.148759 1.69456 - -0.671372 0.216905 1.77714 - -0.672148 0.239775 1.77895 - -0.673062 0.278033 1.78102 - -0.673353 0.285777 1.7817 - -0.670944 0.368934 1.77526 - -0.671676 0.392646 1.77696 - -0.672579 0.408828 1.77912 - -0.671819 0.576607 1.77632 - -0.643102 0.679465 1.7043 - -0.506669 0.723408 1.3645 - -0.497155 0.874846 1.34001 - -0.495987 0.921663 1.33685 - -0.495325 0.945536 1.33507 - -0.496778 1.05509 1.3381 - -0.495599 1.071 1.33508 - -0.492989 1.17207 1.32805 - -0.49763 1.21531 1.33936 - -0.493181 1.2679 1.32801 - -0.472182 1.26306 1.27577 - -0.431562 1.27162 1.17463 - -0.419296 1.27639 1.14407 - -0.401604 1.27271 1.10006 - -0.319537 1.28161 0.895756 - -0.309577 1.27385 0.87101 - -0.21272 1.1708 0.630497 - -0.210271 1.16907 0.624412 - -0.195269 1.17012 0.587069 - -0.192994 1.16908 0.581412 - -0.163196 1.18357 0.50717 - -0.136592 1.15905 0.441088 - -0.130624 1.15838 0.426237 - -0.12874 1.15942 0.421544 - -0.115269 1.25846 0.387484 - -0.113223 1.25931 0.382386 - -0.108355 1.24709 0.370337 - -0.0942543 1.16734 0.33567 - -0.0923105 1.16695 0.330834 - -0.0845582 1.16519 0.311549 - -0.0652772 1.24534 0.263131 - -0.0399476 0.085972 0.206309 - -0.0388152 0.0939956 0.203447 - -0.0358188 0.101605 0.195949 - -0.0354882 0.101523 0.195126 - -0.0350831 0.103422 0.194108 - -0.0318461 0.10823 0.186026 - -0.0285675 0.120678 0.177799 - -0.0189728 0.159991 0.153708 - -0.0179331 0.159017 0.151125 - -0.0161183 0.159328 0.146607 - -0.0112952 0.181025 0.134487 --0.00969659 0.186804 0.130477 - 0.00271327 0.241902 0.0992946 - 0.00596881 0.199961 0.091417 - 0.0101761 0.208221 0.0809013 - 0.0186199 0.230359 0.0597669 - 0.0194124 0.23133 0.0577894 - 0.0207527 0.230064 0.0544604 - 0.0206999 0.227726 0.0546042 - 0.0281432 0.231543 0.0360584 - 0.0270501 0.223696 0.038821 - 0.031254 0.223489 0.0283591 - 0.0313417 0.214063 0.0281915 - 0.0317907 -0.185491 0.0344306 - 0.0314068 -0.203011 0.0354492 - 0.033325 -0.215983 0.030885 - 0.0317449 -0.216891 0.0347055 - 0.030864 -0.22787 0.0368901 - 0.0196652 -0.207366 0.0638251 - 0.0111692 -0.183838 0.084218 - -0.0009933 -0.155685 0.11344 --0.00243339 -0.160331 0.116942 --0.00013255 -0.194767 0.111566 - 0.00041823 -0.199659 0.110262 --0.00278297 -0.204809 0.118019 --0.00775175 -0.194073 0.129961 - -0.0112953 -0.176216 0.138424 - -0.0232784 -0.137316 0.167157 - -0.026153 -0.125883 0.174039 - -0.0258845 -0.13087 0.173416 - -0.0263214 -0.131154 0.174473 - -0.0296107 -0.106433 0.182287 - -0.0302846 -0.10067 0.183884 - -0.0296134 -0.12991 0.182416 - -0.0241035 -0.250248 0.16974 - -0.0257755 -0.250859 0.173781 - -0.0260945 -0.252984 0.174562 - -0.0333728 -0.363787 0.192716 - -0.0351651 -0.366918 0.197061 - -0.0407913 -0.388935 0.210762 - -0.0829565 -2.19038 0.321997 - -0.170686 -2.23389 0.53407 - -0.174417 -2.23232 0.543071 - -0.18479 -2.1587 0.567734 - -0.234403 -2.20919 0.687801 - -0.256936 -2.16035 0.741958 - -0.273219 -2.16719 0.781311 - -0.366876 -2.17092 1.00749 - -0.423467 -2.1744 1.14416 - -0.136479 -0.483667 0.44232 - -0.176403 -0.411745 0.538351 - -0.186966 -0.409553 0.563846 - -0.199304 -0.402845 0.593603 - -0.203042 -0.377491 0.602497 - -0.4035 -0.794765 1.08874 - -0.41228 -0.771297 1.10981 - -0.412802 -0.70506 1.11073 - -0.412977 -0.692437 1.11108 - -0.434677 -0.660123 1.16332 - -0.478127 -0.663662 1.26826 - -0.504874 -0.621079 1.33262 - -0.502126 -0.590918 1.32583 - -0.576228 -0.510981 1.50435 - -0.646913 -0.508271 1.67502 - -0.636509 -0.425236 1.64946 - -0.634975 -0.409539 1.64568 - -0.705702 0.0088716 1.81428 - -0.718301 0.0245373 1.84462 - -0.635873 0.0760752 1.64531 - -0.635479 0.0964904 1.64425 - -0.736387 0.322572 1.88673 - -0.735223 0.463104 1.88319 - -0.738863 0.577479 1.89138 - -0.727856 0.620536 1.86458 - -0.637522 0.664204 1.64621 - -0.554598 0.723735 1.44566 - -0.533335 0.723118 1.39432 - -0.496641 0.775887 1.30544 - -0.497848 0.800333 1.30823 - -0.496676 0.821021 1.30529 - -0.497796 0.995194 1.30708 - -0.496527 1.01011 1.30394 - -0.49639 1.04593 1.30342 - -0.497966 1.13527 1.30676 - -0.498322 1.15608 1.30751 - -0.421941 1.27572 1.12244 - -0.401529 1.2748 1.07316 - -0.381397 1.27197 1.02456 - -0.371804 1.28315 1.00134 - -0.268806 1.27832 0.752645 - -0.214498 1.15405 0.622154 - -0.189351 1.17886 0.561302 - -0.183526 1.16695 0.547297 - -0.168667 1.16721 0.511416 - -0.164657 1.18885 0.50162 - -0.162644 1.25441 0.496415 - -0.130708 1.15746 0.419806 - -0.113296 1.26805 0.377182 - -0.101322 1.20373 0.348603 - -0.0391023 0.0919992 0.204169 - -0.0384364 0.10699 0.202483 - -0.0351532 0.0944721 0.19462 - -0.0284818 0.123969 0.178356 - -0.0280678 0.123724 0.177358 - -0.0248036 0.141161 0.169384 - -0.0240802 0.145826 0.167613 - -0.0222316 0.150696 0.163124 - -0.0195167 0.154764 0.156547 - 0.00618876 0.245804 0.0939986 - 0.00560655 0.232089 0.0954762 - 0.00609278 0.2247 0.0943407 - 0.0211263 0.23133 0.0580037 - 0.0282255 0.231508 0.0408601 - 0.0352678 0.225613 0.0238854 - 0.0368511 0.216615 0.0201092 - 0.0393932 0.219988 0.013953 - 0.0350085 -0.187519 0.0314041 - 0.0331505 -0.197665 0.0358227 - 0.00576285 -0.173686 0.100068 - 0.00206739 -0.165444 0.108712 --0.00049561 -0.156535 0.11469 --0.00241829 -0.167521 0.119265 --0.00351478 -0.204569 0.122031 --0.00498568 -0.200732 0.125468 - -0.0100748 -0.18117 0.137329 - -0.0112671 -0.178063 0.140116 - -0.0127164 -0.173047 0.143496 - -0.0269112 -0.127664 0.176626 - -0.0252257 -0.244768 0.173263 - -0.026676 -0.259343 0.176746 - -0.0300107 -0.317334 0.184879 - -0.180462 -2.2169 0.548183 - -0.247101 -2.21135 0.704773 - -0.264645 -2.14815 0.745684 - -0.282441 -2.16541 0.787598 - -0.290731 -2.16746 0.807092 - -0.331643 -2.16707 0.903243 - -0.373892 -2.16721 1.00254 - -0.432375 -2.1744 1.14003 - -0.463666 -2.17003 1.21355 - -0.488625 -1.8869 1.27076 - -0.151186 -0.412642 0.470161 - -0.159113 -0.406531 0.48876 - -0.175509 -0.407314 0.527298 - -0.176462 -0.406531 0.529534 - -0.206419 -0.390332 0.599858 - -0.425105 -0.679533 1.11531 - -0.425814 -0.655531 1.11685 - -0.442453 -0.657977 1.15597 - -0.476169 -0.658985 1.23521 - -0.483036 -0.662642 1.25137 - -0.505235 -0.64759 1.30347 - -0.602887 -0.510009 1.53227 - -0.63785 -0.51165 1.61445 - -0.652969 -0.486668 1.64986 - -0.649091 -0.373545 1.64017 - -0.750481 -0.149803 1.87732 - -0.749083 -0.0858574 1.87371 - -0.749379 -0.0700158 1.87432 - -0.736335 0.00129471 1.8433 - -0.642086 0.0549346 1.62152 - -0.632794 0.073981 1.59958 - -0.737613 0.204609 1.84526 - -0.755189 0.225934 1.88646 - -0.754014 0.249857 1.88358 - -0.758915 0.276113 1.89496 - -0.758361 0.292302 1.89358 - -0.753378 0.414028 1.88125 - -0.757967 0.57989 1.89118 - -0.757106 0.596806 1.88907 - -0.642467 0.678537 1.61922 - -0.639637 0.723719 1.61234 - -0.571444 0.723032 1.45207 - -0.540204 0.716757 1.37868 - -0.495288 0.770795 1.27285 - -0.492873 0.962554 1.26619 - -0.495146 1.0747 1.27096 - -0.495746 1.226 1.2716 - -0.481463 1.2624 1.23784 - -0.443474 1.27138 1.14851 - -0.439336 1.26961 1.13879 - -0.413803 1.27709 1.07875 - -0.364751 1.27538 0.96347 - -0.321714 1.2695 0.862353 - -0.313208 1.2827 0.842294 - -0.297338 1.27355 0.805041 - -0.248802 1.26841 0.690995 - -0.211029 1.16553 0.602744 - -0.208766 1.16554 0.597425 - -0.207589 1.17304 0.59462 - -0.204638 1.18426 0.587629 - -0.179419 1.16121 0.528476 - -0.177323 1.16179 0.523545 - -0.170381 1.1576 0.507251 - -0.166426 1.16044 0.497942 - -0.161021 1.25714 0.484744 - -0.12479 1.16236 0.400076 - -0.0922201 1.16059 0.323538 - -0.0656075 1.22137 0.260681 - -0.0400352 0.0819389 0.2064 - -0.0366036 0.0988365 0.198249 - -0.0341131 0.10531 0.192362 - -0.0308904 0.104038 0.184794 - -0.0282903 0.124089 0.178581 - -0.0233317 0.15083 0.16679 - -0.0173251 0.155495 0.15265 --0.00963294 0.187565 0.134407 --0.00490402 0.207432 0.123191 - 0.00199611 0.232423 0.106847 - 0.00327785 0.234222 0.103825 - 0.00568306 0.212211 0.0982846 - 0.0129371 0.214192 0.0812256 - 0.0154969 0.218337 0.0751881 - 0.0245904 0.234051 0.0537359 - 0.0343556 0.225134 0.0308306 - 0.036647 0.220148 0.0254708 - 0.0400973 0.220299 0.017361 - 0.0407919 0.214562 0.0157576 - 0.037307 -0.188227 0.0311425 - 0.0249859 -0.214628 0.0593938 - 0.0109857 -0.176743 0.0911569 - 0.00920863 -0.178537 0.0952215 - 0.0054302 -0.169127 0.103798 - 0.00263989 -0.174568 0.110193 --0.00039401 -0.188899 0.117189 - 0.00142455 -0.20453 0.113116 - -0.001019 -0.198548 0.118663 --0.00375905 -0.19723 0.12491 --0.00426391 -0.196682 0.12606 --0.00529804 -0.197769 0.128425 - -0.0243716 -0.138777 0.171662 - -0.0282093 -0.279948 0.181124 - -0.0326581 -0.33575 0.191555 - -0.0360237 -0.359972 0.199357 - -0.0425738 -0.382812 0.214419 - -0.109633 -2.23715 0.376705 - -0.121162 -2.22853 0.402974 - -0.167877 -2.21416 0.509519 - -0.288603 -2.16637 0.784805 - -0.297446 -2.17129 0.805013 - -0.374185 -2.17189 0.980153 - -0.467425 -2.15958 1.19289 - -0.138353 -0.481464 0.433503 - -0.495015 -2.00297 1.25507 - -0.198743 -0.407687 0.570959 - -0.203868 -0.406226 0.582649 - -0.209318 -0.412316 0.595117 - -0.210044 -0.382569 0.596626 - -0.213189 -0.382762 0.603804 - -0.434034 -0.704254 1.10943 - -0.439381 -0.662147 1.12142 - -0.471006 -0.661219 1.19359 - -0.502221 -0.641045 1.26473 - -0.502805 -0.596224 1.26584 - -0.501982 -0.576092 1.26386 - -0.499837 -0.548494 1.25883 - -0.498128 -0.5342 1.25486 - -0.501836 -0.514087 1.26322 - -0.524379 -0.507643 1.31464 - -0.591179 -0.507789 1.46709 - -0.598476 -0.507568 1.48374 - -0.618011 -0.511008 1.52835 - -0.652337 -0.511333 1.60669 - -0.779806 -0.391609 1.897 - -0.77461 -0.380494 1.88509 - -0.777051 -0.339988 1.89046 - -0.775954 -0.119137 1.88686 - -0.777083 -0.0388239 1.88903 - -0.774512 0.00133249 1.88296 - -0.645797 0.0539371 1.58894 - -0.633979 0.0658526 1.56191 - -0.636525 0.0987291 1.56756 - -0.634155 0.137415 1.56196 - -0.782029 0.36121 1.89833 - -0.780493 0.419342 1.89453 - -0.780549 0.427848 1.89462 - -0.77718 0.661285 1.88577 - -0.732258 0.638108 1.78336 - -0.685973 0.603526 1.6779 - -0.657595 0.592425 1.61319 - -0.649754 0.718165 1.59467 - -0.641446 0.724439 1.57567 - -0.604028 0.725377 1.49027 - -0.538676 0.718902 1.34116 - -0.494718 0.994455 1.23946 - -0.497557 1.03627 1.24573 - -0.395696 1.27666 1.01206 - -0.387818 1.27192 0.994104 - -0.341487 1.27403 0.888354 - -0.261422 1.26686 0.705664 - -0.216712 1.16082 0.604154 - -0.207075 1.24165 0.581756 - -0.164842 1.17905 0.485682 - -0.148992 1.19694 0.449418 - -0.137603 1.16622 0.42358 - -0.11499 1.17548 0.371926 - -0.101758 1.20341 0.341588 - -0.0632433 1.09753 0.254215 - -0.0400705 0.10294 0.206286 - -0.0369481 0.106914 0.19914 - -0.0366445 0.102878 0.198467 - -0.0364838 0.101856 0.198105 - -0.0363691 0.0988365 0.197859 - -0.0360229 0.0987831 0.197069 - -0.0351968 0.0926035 0.195214 - -0.034169 0.101385 0.192825 - -0.032863 0.0959239 0.189871 - -0.0282642 0.119203 0.17926 - -0.02797 0.120065 0.178584 - -0.0260235 0.131247 0.174086 - -0.0224255 0.141276 0.165825 - -0.017807 0.153364 0.155224 - -0.0114159 0.17733 0.140518 - 0.00069334 0.221006 0.112664 - 0.00108076 0.220574 0.111782 - 0.00708766 0.234502 0.0980037 - 0.00868534 0.215588 0.0944517 - 0.0413578 0.223672 0.019845 - 0.0363296 -0.197768 0.0394798 - 0.0393236 -0.216799 0.0329828 - 0.0401437 -0.226945 0.031227 - 0.0078377 -0.16901 0.102043 - 0.00843942 -0.172847 0.100738 - 0.00142451 -0.173661 0.11618 --0.00135015 -0.17381 0.122286 --0.00210169 -0.194648 0.124041 - -0.0184784 -0.139233 0.159814 - -0.0257674 -0.133774 0.175829 - -0.0314217 -0.318643 0.189166 - -0.0364215 -0.353988 0.20034 - -0.0370406 -0.359997 0.201731 - -0.0403979 -0.378937 0.209211 - -0.0445672 -0.382622 0.218405 - -0.251516 -2.22379 0.682743 - -0.291627 -2.16334 0.770724 - -0.344174 -2.17036 0.886398 - -0.388814 -2.17097 0.984641 - -0.409943 -2.16098 1.03109 - -0.4729 -2.16981 1.16968 - -0.495335 -1.92523 1.21788 - -0.493305 -1.80508 1.21283 - -0.494837 -1.79343 1.21614 - -0.154486 -0.414742 0.460461 - -0.207278 -0.409823 0.576618 - -0.216572 -0.389119 0.59697 - -0.449501 -0.792358 1.11153 - -0.450354 -0.758916 1.11325 - -0.451728 -0.754548 1.11625 - -0.453094 -0.750165 1.11923 - -0.454466 -0.660507 1.12182 - -0.482232 -0.664878 1.18295 - -0.486252 -0.664351 1.19179 - -0.500948 -0.6398 1.22401 - -0.503678 -0.624099 1.22995 - -0.501936 -0.590048 1.22595 - -0.518355 -0.510643 1.2617 - -0.549008 -0.504975 1.32913 - -0.651181 -0.509737 1.55401 - -0.65498 -0.498352 1.56231 - -0.654815 -0.483762 1.56188 - -0.805062 -0.376055 1.89201 - -0.803015 -0.34988 1.88738 - -0.804182 -0.300367 1.88971 - -0.808191 -0.21079 1.89809 - -0.807414 -0.161368 1.89615 - -0.805347 -0.0715186 1.89116 - -0.805606 -0.0553315 1.89165 - -0.804059 -0.0471345 1.88821 - -0.80605 0.00134848 1.89236 - -0.708595 0.05068 1.67765 - -0.80905 0.312962 1.89745 - -0.808557 0.354628 1.89617 - -0.808992 0.40555 1.89688 - -0.810692 0.414971 1.90058 - -0.812918 0.645331 1.90436 - -0.657678 0.590052 1.56299 - -0.634306 0.604313 1.51148 - -0.632886 0.617631 1.50829 - -0.632553 0.632145 1.50749 - -0.626151 0.723782 1.49296 - -0.583377 0.722437 1.39883 - -0.578815 0.723797 1.38879 - -0.495451 0.787071 1.20502 - -0.496934 0.953177 1.20748 - -0.49683 0.986971 1.20709 - -0.473298 1.27085 1.15393 - -0.46943 1.27075 1.14542 - -0.451759 1.27415 1.10651 - -0.426088 1.28458 1.04996 - -0.418185 1.26996 1.03264 - -0.403372 1.27803 1.00001 - -0.379452 1.27561 0.947375 - -0.354708 1.27849 0.892906 - -0.351346 1.27748 0.885514 - -0.317549 1.27487 0.811149 - -0.305323 1.27206 0.784255 - -0.225161 1.15135 0.608424 - -0.206177 1.23571 0.566239 - -0.203948 1.23745 0.561325 - -0.168594 1.1603 0.483894 - -0.164405 1.16296 0.474662 - -0.163593 1.22022 0.472599 - -0.129038 1.16138 0.396836 - -0.105328 1.23913 0.344283 - -0.100444 1.18917 0.333775 - -0.0688924 1.14291 0.264562 - -0.0408444 0.121863 0.207773 - -0.0345379 0.0844879 0.194075 - -0.0327704 0.0879541 0.190168 - -0.026741 0.124823 0.176721 - -0.022763 0.144062 0.167873 - -0.0206771 0.149925 0.163255 - -0.0114451 0.17727 0.142805 - 0.009027 0.238601 0.0974555 - 0.035198 0.232322 0.0398908 - 0.038993 0.231453 0.0315433 - 0.0368988 -0.178385 0.0423702 - 0.0129562 -0.174802 0.0936866 - 0.0109603 -0.169534 0.0979409 - 0.00823251 -0.167813 0.103781 - 0.00668046 -0.184134 0.107186 - 0.00058488 -0.178267 0.120227 - -0.0116651 -0.17228 0.146463 - -0.0194307 -0.136224 0.162942 - -0.0192316 -0.148649 0.162574 - -0.0224657 -0.138314 0.169459 - -0.0291111 -0.107012 0.183559 - -0.0304234 -0.111621 0.186395 - -0.026171 -0.23947 0.177882 - -0.029325 -0.281327 0.184843 - -0.0296981 -0.286399 0.185666 - -0.0301943 -0.308515 0.186835 - -0.0321632 -0.325757 0.191138 - -0.0327152 -0.328807 0.192336 - -0.0343952 -0.341923 0.196 - -0.0356353 -0.344973 0.198673 - -0.0381879 -0.366995 0.20425 - -0.0388648 -0.366983 0.205701 - -0.040289 -0.378937 0.208811 - -0.0409879 -0.378903 0.21031 - -0.0451235 -0.375553 0.219161 - -0.0831778 -2.18491 0.309311 - -0.0873428 -2.19038 0.318267 - -0.0957624 -2.20216 0.336374 - -0.0999645 -2.20649 0.345404 - -0.109054 -2.23496 0.365026 - -0.230374 -2.13002 0.624644 - -0.241236 -2.20314 0.648278 - -0.331064 -2.15648 0.840651 - -0.342071 -2.17208 0.864323 - -0.35408 -2.16235 0.890025 - -0.36761 -2.1626 0.919034 - -0.372616 -2.1657 0.929782 - -0.409329 -2.16512 1.00849 - -0.472087 -2.16816 1.14306 - -0.488525 -2.17593 1.17834 - -0.492543 -2.17121 1.18693 - -0.496551 -2.16646 1.19551 - -0.497502 -2.14742 1.19746 - -0.499737 -2.13462 1.20219 - -0.500299 -2.06971 1.20308 - -0.152341 -0.426558 0.44928 - -0.151854 -0.416622 0.448188 - -0.151999 -0.40924 0.448463 - -0.15497 -0.408132 0.454828 - -0.168446 -0.414823 0.483754 - -0.171239 -0.408556 0.489711 - -0.171217 -0.404807 0.489645 - -0.19841 -0.411677 0.547981 - -0.208857 -0.408771 0.570366 - -0.212315 -0.406226 0.577769 - -0.221024 -0.397606 0.596399 - -0.221179 -0.380785 0.596652 - -0.231766 -0.385338 0.619373 - -0.457987 -0.791736 1.10632 - -0.464295 -0.761162 1.1197 - -0.460324 -0.74042 1.11109 - -0.462365 -0.690849 1.11523 - -0.49838 -0.668004 1.19234 - -0.502983 -0.591321 1.20184 - -0.49998 -0.581348 1.19536 - -0.498594 -0.555344 1.19226 - -0.532312 -0.508351 1.26433 - -0.650336 -0.477146 1.51723 - -0.631619 -0.42205 1.47684 - -0.82162 -0.435507 1.88427 - -0.825614 -0.369511 1.89252 - -0.824901 -0.352295 1.89091 - -0.825561 -0.28555 1.89201 - -0.826693 -0.145519 1.89378 - -0.826386 -0.129089 1.89304 - -0.828608 0.280717 1.89586 - -0.829706 0.356687 1.89786 - -0.831364 0.408531 1.90117 - -0.829857 0.424877 1.89786 - -0.831767 0.530399 1.90146 - -0.829329 0.608885 1.89586 - -0.829017 0.617663 1.89515 - -0.667125 0.59397 1.54816 - -0.637319 0.594629 1.48425 - -0.632458 0.611504 1.47375 - -0.633689 0.63476 1.47628 - -0.652081 0.700509 1.5154 - -0.620851 0.725029 1.44833 - -0.613163 0.723032 1.43185 - -0.494725 0.888746 1.17714 - -0.499312 0.938151 1.18674 - -0.492988 0.958315 1.17308 - -0.493533 0.976382 1.17417 - -0.49268 1.14973 1.17151 - -0.495521 1.19799 1.17738 - -0.40447 1.279 0.981779 - -0.357927 1.27748 0.881998 - -0.355145 1.27902 0.876027 - -0.314786 1.27639 0.789508 - -0.301802 1.27044 0.761698 - -0.288979 1.27818 0.734168 - -0.249721 1.22888 0.65023 - -0.222325 1.15523 0.591843 - -0.213789 1.16257 0.573506 - -0.12027 1.16874 0.37297 - -0.118453 1.17449 0.369048 - -0.0846684 1.15521 0.296703 - -0.0582333 0.790757 0.24175 - -0.039828 0.0809094 0.205647 - -0.0351153 0.0876923 0.195511 - -0.0300552 0.104211 0.184584 - -0.0281664 0.122686 0.180447 - -0.0223025 0.146162 0.167764 - -0.0218235 0.14276 0.166752 - -0.0189234 0.15222 0.16049 --0.00697972 0.19852 0.134663 - 0.00058746 0.217172 0.118351 - 0.00698175 0.235601 0.104554 - 0.00995743 0.22445 0.098227 - 0.00998744 0.222171 0.0981734 - 0.0124045 0.212279 0.0930381 - 0.0271689 0.236556 0.0612679 - 0.028766 0.240043 0.0578271 - 0.0278538 0.225839 0.0598502 - 0.0310553 0.230275 0.0529651 - 0.0386391 0.218987 0.0367587 - 0.059577 0.248491 -0.00827236 - 0.0305504 -0.172584 0.0609238 - 0.0416038 -0.220816 0.0382527 - 0.0430776 -0.23098 0.035247 - 0.0332101 -0.22189 0.0556419 - 0.00558306 -0.162073 0.112586 - 0.00689513 -0.171955 0.109914 - 0.00800518 -0.179754 0.107651 - 0.00870386 -0.188074 0.106242 - 0.00313427 -0.17795 0.117731 - 0.00159583 -0.190905 0.120977 - 0.00158349 -0.199741 0.121043 --0.00188577 -0.195566 0.128209 - -0.0051236 -0.194238 0.134909 - -0.0232039 -0.1381 0.172097 - -0.0253593 -0.129992 0.176524 - -0.0313288 -0.0898271 0.188703 - -0.0271236 -0.176391 0.180392 - -0.0279786 -0.249064 0.182497 - -0.0287223 -0.269271 0.18413 - -0.0379694 -0.356995 0.203685 - -0.0393871 -0.371964 0.206691 - -0.0457782 -0.373472 0.219934 - -0.115262 -2.23516 0.372408 - -0.119503 -2.23432 0.381188 - -0.0686896 -0.535013 0.26813 - -0.272439 -2.15323 0.697566 - -0.285243 -2.15069 0.724071 - -0.406374 -2.17004 0.975039 - -0.425617 -2.17046 1.0149 - -0.4352 -2.16988 1.03474 - -0.460686 -2.17475 1.08755 - -0.501406 -2.15243 1.17178 - -0.499353 -1.86758 1.16622 - -0.152146 -0.414756 0.440426 - -0.157082 -0.408514 0.450621 - -0.169116 -0.406014 0.475533 - -0.171423 -0.402005 0.480292 - -0.179583 -0.411413 0.497237 - -0.180365 -0.409979 0.498849 - -0.193171 -0.408739 0.525366 - -0.203931 -0.403754 0.547628 - -0.261307 -0.424525 0.666558 - -0.499652 -0.570996 1.16087 - -0.847396 -0.186198 1.87933 - -0.850943 -0.0966661 1.88626 - -0.851902 -0.0722122 1.88814 - -0.841566 0.049744 1.86617 - -0.631757 0.0964886 1.43141 - -0.68932 0.184989 1.55022 - -0.851638 0.247662 1.88612 - -0.854644 0.298745 1.89211 - -0.854085 0.306934 1.89091 - -0.855842 0.400971 1.89412 - -0.855593 0.418011 1.89353 - -0.857002 0.462002 1.89624 - -0.856495 0.658109 1.89429 - -0.630611 0.614191 1.42666 - -0.62945 0.620123 1.42423 - -0.648609 0.700209 1.46354 - -0.597467 0.727749 1.35749 - -0.56502 0.720778 1.29032 - -0.562537 0.724502 1.28516 - -0.518509 0.723999 1.19397 - -0.49864 0.727466 1.15281 - -0.495922 0.750449 1.14707 - -0.496247 0.764883 1.14768 - -0.495055 0.86519 1.14475 - -0.499435 0.896941 1.15367 - -0.497278 0.916622 1.14911 - -0.49406 0.98468 1.14214 - -0.497099 1.0353 1.1482 - -0.49459 1.21513 1.14218 - -0.490321 1.26921 1.13309 - -0.427769 1.27525 1.0035 - -0.264926 1.26651 0.666274 - -0.211476 1.21669 0.555803 - -0.191467 1.1796 0.51453 - -0.180033 1.16526 0.490915 - -0.163868 1.2623 0.45699 - -0.148429 1.20343 0.425285 - -0.120231 1.17153 0.367029 - -0.116307 1.21641 0.358695 - -0.0392395 0.0959571 0.204233 - -0.0386117 0.109991 0.202868 - -0.0377815 0.0989985 0.201199 - -0.0243316 0.136389 0.17317 - -0.0215617 0.149234 0.167374 - -0.0179612 0.151062 0.159909 --0.00985859 0.185938 0.142967 --0.00950559 0.185652 0.142237 - 0.00103575 0.214807 0.120271 - 0.0106307 0.230009 0.100328 - 0.0163996 0.215003 0.0884492 - 0.025846 0.230982 0.068811 - 0.0354357 0.232873 0.0489406 - 0.0397959 0.22526 0.0399451 - 0.0675325 0.265243 -0.017685 - 0.0317227 -0.158454 0.0621799 - 0.0277024 -0.151887 0.0702591 - 0.0389078 -0.204658 0.0478961 - 0.0384534 -0.228481 0.0489199 - 0.00496826 -0.179307 0.116236 - 0.00053353 -0.180953 0.125187 --0.00075153 -0.196488 0.127849 --0.00168286 -0.196272 0.129727 - -0.011389 -0.172383 0.149196 - -0.0192751 -0.140197 0.164956 - -0.0209548 -0.136062 0.168326 - -0.0217464 -0.136534 0.169925 - -0.0225648 -0.131839 0.171554 - -0.0265178 -0.230746 0.179972 - -0.0306841 -0.280625 0.1886 - -0.0311824 -0.282683 0.189614 - -0.0335298 -0.312898 0.194485 - -0.0377923 -0.347995 0.20324 - -0.0426112 -0.354774 0.21299 - -0.133441 -2.21463 0.404561 - -0.177339 -2.15186 0.492816 - -0.216039 -2.20612 0.571117 - -0.224764 -2.10456 0.588257 - -0.23913 -2.12123 0.617306 - -0.295714 -2.15683 0.731592 - -0.30598 -2.167 0.752345 - -0.394728 -2.16874 0.93135 - -0.408604 -2.16537 0.959321 - -0.470649 -2.1793 1.08452 - -0.478357 -2.16701 1.10001 - -0.499809 -1.83027 1.14177 - -0.157785 -0.457006 0.445746 - -0.16729 -0.410914 0.464711 - -0.177356 -0.407765 0.484998 - -0.193895 -0.409585 0.518364 - -0.20021 -0.407719 0.531092 - -0.215431 -0.4084 0.561795 - -0.223319 -0.411829 0.577721 - -0.234701 -0.418323 0.600706 - -0.231769 -0.404925 0.594733 - -0.231699 -0.397722 0.594559 - -0.230497 -0.391793 0.592107 - -0.236084 -0.378948 0.603318 - -0.239534 -0.382127 0.610292 - -0.487049 -0.763566 1.11123 - -0.498894 -0.649453 1.1346 - -0.500459 -0.536784 1.13725 - -0.499766 -0.524507 1.1358 - -0.600884 -0.505628 1.33966 - -0.61549 -0.512154 1.36915 - -0.65216 -0.50313 1.44307 - -0.651481 -0.468617 1.44155 - -0.877604 -0.155795 1.89621 - -0.877913 -0.14754 1.8968 - -0.874848 -0.0233044 1.89006 - -0.872255 0.0259604 1.8846 - -0.630983 0.111933 1.39759 - -0.628528 0.158348 1.39243 - -0.859342 0.244774 1.85757 - -0.883485 0.362679 1.90574 - -0.88854 0.623131 1.91476 - -0.881931 0.673665 1.9012 - -0.812135 0.704775 1.76029 - -0.635849 0.599692 1.40521 - -0.631115 0.644381 1.39546 - -0.624419 0.724363 1.38159 - -0.565155 0.727132 1.26205 - -0.52756 0.722352 1.18625 - -0.511248 0.725101 1.15333 - -0.495476 0.754665 1.12139 - -0.493976 0.766 1.11831 - -0.492839 0.813745 1.1158 - -0.497061 0.843511 1.12418 - -0.494748 0.908533 1.11923 - -0.498818 0.974395 1.12714 - -0.495166 1.09184 1.11925 - -0.492748 1.10516 1.11431 - -0.494674 1.15938 1.11795 - -0.493448 1.18709 1.11535 - -0.49647 1.23781 1.12122 - -0.451516 1.2773 1.03037 - -0.428223 1.27391 0.983405 - -0.418322 1.27692 0.963424 - -0.406751 1.2737 0.940101 - -0.400853 1.27748 0.928188 - -0.380391 1.27773 0.886916 - -0.295109 1.27779 0.714908 - -0.25069 1.17787 0.625768 - -0.219765 1.16341 0.563459 - -0.163894 1.19064 0.45065 - -0.161064 1.26082 0.444626 - -0.148059 1.20254 0.418658 - -0.123158 1.15887 0.368632 - -0.118942 1.16442 0.360102 - -0.0791751 1.14054 0.280004 - -0.0768617 1.13792 0.27535 - -0.0739425 1.11633 0.269559 - -0.0400758 0.0988679 0.205834 - -0.0383574 0.0999922 0.202363 - -0.0381636 0.0999966 0.201972 - -0.0379698 0.0999991 0.201581 - -0.0367249 0.0889676 0.199119 - -0.0366129 0.0839588 0.198916 - -0.0365203 0.0789497 0.198752 - -0.0356131 0.0848596 0.196896 - -0.0355256 0.0818432 0.196733 - -0.0328881 0.089321 0.19138 - -0.0256278 0.129095 0.176557 - -0.0215492 0.144388 0.168262 - -0.0120904 0.173501 0.149053 - 0.0127314 0.214473 0.0988049 - 0.0141946 0.216103 0.0958463 - 0.0169161 0.213818 0.0903677 - 0.0393763 0.226772 0.0450088 - 0.0406288 0.22838 0.0424753 - 0.0424262 0.221344 0.0388819 - 0.0441327 0.222061 0.0354367 - 0.0538205 0.237583 0.0158272 - 0.0557407 0.240435 0.0119416 - 0.0355735 -0.18351 0.0592495 - 0.0450056 -0.222394 0.0410086 - 0.03161 -0.213252 0.0671167 - 0.00848561 -0.18814 0.112145 - 0.00371604 -0.177767 0.12141 - -0.0122602 -0.163151 0.152531 - -0.014779 -0.153371 0.157405 - -0.0161918 -0.145952 0.160131 - -0.0217426 -0.141018 0.170944 - -0.0306967 -0.102008 0.188251 - -0.0275902 -0.164688 0.182462 - -0.0288185 -0.242344 0.185201 - -0.035059 -0.312975 0.197692 - -0.0423707 -0.34478 0.212104 - -0.0466046 -0.377376 0.220511 - -0.136476 -2.22856 0.40406 - -0.269917 -2.15245 0.664204 - -0.331995 -2.16938 0.785453 - -0.351435 -2.17286 0.823415 - -0.379081 -2.16519 0.877347 - -0.42858 -2.16721 0.973979 - -0.448768 -2.16743 1.01339 - -0.493628 -2.1599 1.10092 - -0.501444 -2.09973 1.11591 - -0.499487 -2.04507 1.11185 - -0.496989 -1.86675 1.10619 - -0.165138 -0.409385 0.452029 - -0.172662 -0.409954 0.466718 - -0.186332 -0.40842 0.493395 - -0.213987 -0.405685 0.547367 - -0.213381 -0.397265 0.546146 - -0.234067 -0.413901 0.586598 - -0.239925 -0.383498 0.5979 - -0.493339 -0.607273 1.09355 - -0.501847 -0.536111 1.10984 - -0.498313 -0.520782 1.10288 - -0.530045 -0.503819 1.16474 - -0.653599 -0.511675 1.40595 - -0.65278 -0.490842 1.40426 - -0.652678 -0.470805 1.40398 - -0.632337 -0.39215 1.36392 - -0.982049 -0.515479 2.0471 - -1.03339 -0.403521 2.14684 - -1.03814 -0.385639 2.15602 - -1.03793 -0.306951 2.15527 - -1.03521 -0.27693 2.14982 - -1.03773 0.00159405 2.15352 - -0.631453 0.0578261 1.36023 - -1.04568 0.371477 2.16742 - -1.04937 0.412734 2.17444 - -1.0536 0.454781 2.18252 - -1.05442 0.485596 2.18398 - -1.05325 0.546392 2.18144 - -1.05805 0.621884 2.19046 - -1.05776 0.642756 2.18981 - -1.06539 0.755233 2.20421 - -0.640615 0.59609 1.37575 - -0.647205 0.688695 1.38821 - -0.610981 0.725911 1.31733 - -0.530506 0.721913 1.16026 - -0.525285 0.721015 1.15008 - -0.520455 0.720594 1.14065 - -0.51308 0.722941 1.12625 - -0.511646 0.727474 1.12342 - -0.502738 0.720438 1.10607 - -0.494453 0.781999 1.08963 - -0.496273 0.857999 1.09285 - -0.496175 1.02139 1.09194 - -0.495104 1.0279 1.08982 - -0.493698 1.03369 1.08705 - -0.491724 1.27099 1.08215 - -0.485272 1.27563 1.06954 - -0.478857 1.26873 1.05705 - -0.470181 1.27801 1.04007 - -0.46321 1.28054 1.02645 - -0.433888 1.27192 0.969253 - -0.415187 1.27034 0.932756 - -0.389364 1.27859 0.882314 - -0.380104 1.28247 0.864222 - -0.369278 1.27995 0.843099 - -0.359201 1.27965 0.82343 - -0.331664 1.27296 0.769709 - -0.328929 1.27485 0.764362 - -0.326395 1.2776 0.759403 - -0.282559 1.25779 0.673922 - -0.266734 1.19092 0.643325 - -0.165218 1.17507 0.445235 - -0.162985 1.17723 0.440867 - -0.0398097 0.0888603 0.205203 - -0.0393153 0.0999255 0.204189 - -0.0358683 0.0819192 0.19754 - -0.0333163 0.0804725 0.192564 - -0.0323873 0.0882801 0.190717 - -0.0307844 0.0988906 0.187541 - -0.0292713 0.105441 0.184559 - -0.024988 0.12702 0.176103 --0.00033375 0.219121 0.127574 - 0.0102216 0.233334 0.106908 - 0.011688 0.229652 0.104062 - 0.0124047 0.227796 0.102671 - 0.0199922 0.221298 0.0878884 - 0.0352262 0.239346 0.0580726 - 0.0382701 0.23353 0.0521564 - 0.0390005 0.233611 0.0507304 - 0.0403921 0.231386 0.0480237 - 0.103312 0.331809 -0.0752371 - 0.0360906 -0.161282 0.061736 - 0.035593 -0.18261 0.0627745 - 0.0360518 -0.187028 0.0619205 - 0.0395646 -0.218146 0.05537 - 0.0311919 -0.205263 0.0712465 - 0.0291577 -0.200997 0.0750988 - 0.0207852 -0.180573 0.0909426 - 0.0184838 -0.176671 0.0953048 - 0.0124624 -0.163618 0.106706 - 0.0134599 -0.171761 0.104843 - 0.0148397 -0.185229 0.102276 - 0.00501002 -0.180842 0.120961 --0.00476674 -0.189868 0.139603 - -0.0160218 -0.147303 0.160837 - -0.0280862 -0.10629 0.183617 - -0.0310842 -0.0941414 0.18927 - -0.0270918 -0.208958 0.182166 - -0.0312918 -0.27075 0.190424 - -0.120346 -2.23416 0.368321 - -0.1241 -2.2134 0.375373 - -0.274535 -2.15245 0.661365 - -0.306846 -2.15008 0.722837 - -0.311827 -2.15231 0.732325 - -0.316822 -2.15449 0.741839 - -0.361694 -2.16694 0.827276 - -0.386828 -2.17085 0.875118 - -0.425084 -2.16071 0.94787 - -0.430826 -2.16446 0.958812 - -0.486536 -2.15834 1.06479 - -0.501835 -1.9294 1.09292 - -0.499556 -1.85971 1.08828 - -0.153699 -0.402639 0.423912 - -0.18693 -0.4097 0.487175 - -0.190003 -0.406984 0.493011 - -0.198996 -0.419533 0.510176 - -0.209564 -0.40907 0.530241 - -0.245171 -0.389372 0.597909 - -0.246045 -0.384145 0.59955 - -0.30463 -0.462138 0.711363 - -0.493212 -0.767014 1.07151 - -0.495714 -0.723635 1.07609 - -0.491574 -0.610814 1.06773 - -0.495277 -0.597946 1.07472 - -0.495308 -0.586246 1.07473 - -0.500061 -0.512551 1.08345 - -0.503798 -0.50563 1.09053 - -0.549098 -0.501392 1.17671 - -0.645188 -0.507911 1.35959 - -0.799551 -0.438282 1.65301 - -1.08962 -0.326522 2.20449 - -1.08263 -0.165407 2.19049 - -1.08152 0.031017 2.18753 - -1.08092 0.0505825 2.18631 - -0.624972 0.111431 1.31845 - -0.604579 0.129037 1.27957 - -0.586211 0.140491 1.24457 - -1.11033 0.502201 2.24032 - -1.11398 0.643051 2.24667 - -1.1147 0.7202 2.2477 - -0.979419 0.808542 1.98991 - -0.631186 0.657516 1.32793 - -0.614884 0.723815 1.29663 - -0.495418 0.932744 1.0684 - -0.495147 0.990709 1.06764 - -0.494775 0.998548 1.0669 - -0.498369 1.15729 1.07305 - -0.490693 1.2661 1.05798 - -0.412603 1.2734 0.909356 - -0.384682 1.27469 0.856222 - -0.321794 1.27489 0.736555 - -0.299808 1.27452 0.694722 - -0.261545 1.15612 0.622422 - -0.256675 1.15932 0.613142 - -0.24316 1.1749 0.587359 - -0.237748 1.17492 0.57706 - -0.179441 1.16877 0.466139 - -0.171759 1.16776 0.451526 - -0.144843 1.17223 0.40029 - -0.126704 1.15986 0.365827 - -0.113363 1.25698 0.340023 - -0.0920806 1.13733 0.300041 - -0.0897724 1.13781 0.295647 - -0.0358464 0.0899427 0.19754 - -0.0339697 0.0776674 0.194022 - -0.0325358 0.0833663 0.191269 - -0.0301047 0.100801 0.186568 - -0.0273329 0.119053 0.181215 - -0.0256523 0.126503 0.177985 - -0.0139565 0.167538 0.155553 - -0.0132141 0.164955 0.154152 - 0.00079221 0.211506 0.1273 - 0.0150919 0.221778 0.100046 - 0.0162366 0.217121 0.0978879 - 0.0226874 0.217335 0.0856123 - 0.0363984 0.237684 0.059435 - 0.0602526 0.243783 0.0140183 - 0.105655 0.335974 -0.0727709 - 0.107018 0.333271 -0.0753534 - 0.030825 -0.14891 0.0749122 - 0.030208 -0.150147 0.076062 - 0.0270588 -0.150801 0.0819078 - 0.0269939 -0.195415 0.0822162 - 0.0143222 -0.162686 0.105589 - 0.0139586 -0.18321 0.10635 - 0.0123484 -0.196542 0.109394 - 0.00304757 -0.188251 0.126616 - 0.00265812 -0.188614 0.12734 - -0.0186786 -0.139922 0.166722 - -0.0217217 -0.132265 0.172336 - -0.0234427 -0.126939 0.175506 - -0.0284707 -0.10251 0.184732 - -0.0265677 -0.202898 0.181625 - -0.0273799 -0.213116 0.183175 - -0.0278961 -0.222247 0.184171 - -0.0289316 -0.232444 0.186135 - -0.0365175 -0.320999 0.200583 - -0.0378602 -0.325985 0.203096 - -0.187349 -2.16373 0.4882 - -0.2237 -2.15795 0.555621 - -0.317803 -2.15713 0.730214 - -0.448735 -2.16341 0.973169 - -0.503304 -2.14522 1.07434 - -0.50341 -2.05017 1.07413 - -0.152376 -0.423308 0.415975 - -0.153439 -0.410403 0.417894 - -0.169185 -0.403224 0.447077 - -0.20186 -0.408084 0.507724 - -0.207271 -0.414073 0.517788 - -0.224112 -0.405855 0.549 - -0.229472 -0.403104 0.558933 - -0.248658 -0.402491 0.594528 - -0.250438 -0.395279 0.5978 - -0.263185 -0.386684 0.621414 - -0.492108 -0.710708 1.04752 - -0.502206 -0.543726 1.06555 - -0.500633 -0.514257 1.06251 - -0.50381 -0.501396 1.06835 - -0.556316 -0.504525 1.16578 - -0.64488 -0.465925 1.32994 - -0.645402 -0.459985 1.33088 - -0.62851 -0.434943 1.29943 - -0.629178 -0.393016 1.3005 - -0.681084 -0.375818 1.39673 - -1.13346 -0.564249 2.23686 - -1.13464 -0.55415 2.239 - -1.14113 -0.503926 2.25083 - -1.13911 -0.471211 2.24694 - -1.13968 -0.263206 2.24711 - -1.13885 -0.191338 2.24527 - -0.662838 0.0527811 1.36107 - -0.630859 0.0610258 1.3017 - -0.582019 0.141837 1.21074 - -0.625988 0.158776 1.29225 - -1.13966 0.369621 2.24442 - -1.14174 0.422526 2.24805 - -1.14516 0.637967 2.25348 - -1.14705 0.650017 2.25694 - -1.14157 0.69071 2.2466 - -1.14646 0.749528 2.25542 - -1.09456 0.845183 2.15873 - -1.05557 0.824727 2.08647 - -1.01712 0.803935 2.01523 - -0.646049 0.68961 1.32723 - -0.649225 0.715059 1.33302 - -0.646261 0.72627 1.32747 - -0.591528 0.722812 1.22594 - -0.499856 0.721036 1.05586 - -0.497062 1.04638 1.0493 - -0.49798 1.11465 1.05072 - -0.455315 1.27803 0.97087 - -0.439698 1.27729 0.941897 - -0.402631 1.27688 0.873127 - -0.374838 1.27833 0.821553 - -0.363273 1.27338 0.800117 - -0.247378 1.19276 0.585428 - -0.218371 1.16627 0.53172 - -0.208919 1.23104 0.513911 - -0.0341709 0.0827671 0.194527 - -0.0326309 0.0824594 0.191671 - -0.0315248 0.0892213 0.189591 - -0.0286703 0.112583 0.184196 - -0.0210023 0.141941 0.169845 --0.00623627 0.195307 0.142224 - 0.00547281 0.220213 0.120394 - 0.0151716 0.224137 0.102383 - 0.0204211 0.2263 0.0926336 - 0.0413477 0.228022 0.0537995 - 0.0455745 0.21746 0.0460018 - 0.0866589 0.272863 -0.0304589 - 0.0241068 -0.133928 0.090723 - 0.0262854 -0.151414 0.0868751 - 0.0382564 -0.193415 0.0655096 - 0.0365273 -0.201223 0.0686527 - 0.0320914 -0.194266 0.0766052 - 0.0288828 -0.190375 0.0823622 - 0.0164252 -0.192427 0.104785 - 0.01845 -0.203868 0.101189 - 0.0161871 -0.19957 0.105242 --0.00693958 -0.184285 0.14679 - -0.0179557 -0.145084 0.166449 - -0.0212212 -0.136434 0.172289 - -0.0216189 -0.135595 0.173001 - -0.0252351 -0.119775 0.179442 - -0.031065 -0.249769 0.190466 - -0.0389778 -0.319946 0.204992 - -0.0459154 -0.351419 0.217604 - -0.178756 -2.19455 0.464202 - -0.191579 -2.1746 0.487192 - -0.21905 -2.22116 0.536809 - -0.225488 -2.18329 0.548236 - -0.247547 -2.11539 0.587647 - -0.279235 -2.14593 0.644787 - -0.328824 -2.15353 0.734039 - -0.50482 -2.10255 1.05049 - -0.50557 -1.80512 1.05061 - -0.180059 -0.407528 0.459189 - -0.186991 -0.408123 0.471664 - -0.199045 -0.410184 0.49336 - -0.202892 -0.408817 0.500276 - -0.204385 -0.40884 0.502963 - -0.214057 -0.410065 0.52037 - -0.229027 -0.407286 0.547294 - -0.238835 -0.402598 0.56492 - -0.301101 -0.433495 0.677078 - -0.481312 -0.715962 1.00248 - -0.491601 -0.706449 1.02095 - -0.491936 -0.700553 1.02153 - -0.49373 -0.690554 1.02472 - -0.494622 -0.648414 1.02615 - -0.495503 -0.63155 1.02767 - -0.492905 -0.616145 1.02293 - -0.497303 -0.569971 1.03065 - -0.498396 -0.554466 1.03255 - -0.511085 -0.50295 1.05517 - -0.594945 -0.505415 1.20607 - -0.652633 -0.511913 1.30989 - -0.629223 -0.384016 1.26724 - -1.1772 -0.562296 2.2539 - -1.17816 -0.465922 2.25523 - -1.17614 -0.203547 2.25052 - -1.17639 -0.110996 2.2506 - -1.17383 -0.0698202 2.24582 - -1.17347 -0.00851001 2.24491 - -1.17538 0.0323848 2.24819 - -0.62581 0.0803455 1.25919 - -0.626612 0.0857755 1.26061 - -0.624605 0.13337 1.2568 - -1.16918 0.349931 2.23572 - -1.1765 0.425742 2.24858 - -1.17585 0.510503 2.24707 - -0.804177 0.662807 1.57771 - -0.651735 0.59047 1.30373 - -0.631435 0.630463 1.26704 - -0.632356 0.66557 1.26856 - -0.651822 0.723408 1.30334 - -0.613899 0.727656 1.23509 - -0.576441 0.727841 1.1677 - -0.496248 0.778608 1.0232 - -0.49854 0.796458 1.02725 - -0.495016 0.966256 1.02021 - -0.494308 1.12934 1.01827 - -0.495014 1.18242 1.01932 - -0.493259 1.22085 1.016 - -0.49063 1.27002 1.01107 - -0.418478 1.27697 0.881224 - -0.412735 1.2701 0.87092 - -0.399965 1.27642 0.847918 - -0.397506 1.28052 0.843476 - -0.354763 1.27817 0.766581 - -0.331725 1.28024 0.725123 - -0.251867 1.17584 0.58187 - -0.251662 1.2229 0.581308 - -0.224547 1.16271 0.53277 - -0.211192 1.16408 0.508734 - -0.140337 1.16132 0.381262 - -0.0885574 1.12633 0.288243 - -0.083241 1.11423 0.278727 - -0.0399092 0.102812 0.204928 - -0.0390372 0.102905 0.203358 - -0.0376944 0.0819816 0.201028 - -0.0350769 0.0679041 0.196377 - -0.0293999 0.105881 0.186006 - -0.0278891 0.113491 0.183257 - -0.027408 0.113325 0.182392 - -0.0255693 0.119741 0.179057 --0.00192337 0.206703 0.136155 - 0.00069663 0.204738 0.131449 - 0.0107174 0.223264 0.113343 - 0.0144286 0.221959 0.106671 - 0.0246897 0.226756 0.0881893 - 0.0251708 0.226199 0.087326 - 0.0270831 0.223927 0.0838947 - 0.0327539 0.232041 0.0736582 - 0.0470245 0.221305 0.0480264 - 0.0510258 0.223686 0.0408172 - 0.113352 0.3206 -0.0717204 - 0.0250804 -0.144027 0.0916767 - 0.0298899 -0.159434 0.0832941 - 0.0363199 -0.196413 0.0721534 - 0.0174127 -0.160912 0.105208 - 0.0142487 -0.154343 0.110737 - 0.0127091 -0.153982 0.113439 - 0.0116593 -0.19206 0.115436 - 0.0114669 -0.193375 0.11578 - 0.0038109 -0.181854 0.129176 --0.00058983 -0.187702 0.136927 --0.00435375 -0.192556 0.143555 - -0.0190082 -0.142812 0.169085 - -0.0295638 -0.0869264 0.187394 - -0.0303694 -0.0952411 0.188842 - -0.0273518 -0.19519 0.183947 - -0.0279407 -0.201318 0.185006 - -0.030359 -0.2247 0.189347 - -0.0347986 -0.29799 0.197438 - -0.0360856 -0.297999 0.199698 - -0.0510287 -0.386781 0.226295 - -0.152222 -2.28523 0.411649 - -0.0670882 -0.515084 0.255012 - -0.221186 -2.20737 0.532426 - -0.226383 -2.15476 0.541337 - -0.228994 -2.13042 0.545824 - -0.263684 -2.05373 0.606426 - -0.309963 -2.15953 0.688113 - -0.159068 -0.463167 0.416307 - -0.152167 -0.414988 0.403994 - -0.169016 -0.402235 0.433526 - -0.200324 -0.406314 0.488515 - -0.228948 -0.407129 0.53878 - -0.492245 -0.66362 1.00213 - -0.542237 -0.503907 1.08926 - -0.5897 -0.509258 1.17262 - -0.628009 -0.50708 1.23988 - -0.65571 -0.505182 1.28851 - -0.64744 -0.479694 1.27389 - -0.637149 -0.447338 1.25569 - -1.20526 -0.576571 2.25373 - -1.19682 -0.475581 2.23851 - -1.20179 -0.434924 2.24708 - -1.20215 -0.318963 2.24724 - -1.20197 -0.266693 2.2467 - -1.20365 -0.235831 2.24953 - -1.20464 -0.122007 2.25081 - -1.19984 -0.0290656 2.242 - -1.19751 0.00170449 2.23778 - -0.629265 0.0583958 1.2398 - -0.628853 0.0897995 1.23895 - -0.625046 0.131068 1.2321 - -0.629087 0.147844 1.23913 - -0.628771 0.153065 1.23855 - -1.20237 0.353644 2.2449 - -1.20458 0.396507 2.24861 - -1.20742 0.461376 2.25332 - -1.20545 0.61214 2.24926 - -1.21055 0.659127 2.25804 - -1.20914 0.669462 2.25551 - -1.2093 0.725631 2.25556 - -1.20946 0.748371 2.25576 - -1.20978 0.817267 2.25604 - -0.836229 0.661534 1.60076 - -0.766685 0.649491 1.4787 - -0.649932 0.715398 1.27343 - -0.623038 0.71884 1.2262 - -0.613313 0.727893 1.20909 - -0.557502 0.72293 1.11111 - -0.554315 0.725223 1.1055 - -0.492518 0.799746 0.996695 - -0.497027 0.858677 1.00437 - -0.49503 0.900819 1.0007 - -0.494894 0.932432 1.00033 - -0.496279 1.24021 1.00152 - -0.490169 1.26915 0.990673 - -0.474918 1.27255 0.96388 - -0.466622 1.27192 0.949317 - -0.4636 1.27485 0.943999 - -0.403734 1.26692 0.838914 - -0.369837 1.27398 0.779368 - -0.361119 1.28085 0.764032 - -0.325777 1.27527 0.701999 - -0.317504 1.28276 0.687443 - -0.272894 1.16004 0.609608 - -0.254641 1.18619 0.577454 - -0.128826 1.1577 0.356654 - -0.121467 1.16197 0.343716 - -0.118958 1.16269 0.339308 - -0.109614 1.26591 0.322485 - -0.0991553 1.17362 0.304493 - -0.0862536 1.11381 0.282081 - -0.0404809 0.110735 0.205764 - -0.0370856 0.0749941 0.199946 - -0.0367794 0.0799993 0.199389 - -0.0361088 0.0759926 0.198227 - -0.0359592 0.0739876 0.197973 - -0.0277498 0.113571 0.183398 - -0.0275046 0.113491 0.182968 - -0.0255133 0.115815 0.179462 - -0.024332 0.122472 0.177361 - 0.00769029 0.222458 0.12073 - 0.0141646 0.223328 0.109359 - 0.0165164 0.223294 0.105229 - 0.0179156 0.224137 0.102769 - 0.0212641 0.222931 0.0968947 - 0.0306861 0.22244 0.0803529 - 0.0413928 0.229816 0.0615235 - 0.0387093 0.217783 0.0662841 - 0.0536724 0.233906 0.0399458 - 0.0566156 0.233006 0.0347816 - 0.0656907 0.248954 0.0187825 - 0.0684482 0.253406 0.0139226 - 0.0886212 0.262374 -0.0215346 - 0.0323049 -0.135155 0.0824803 - 0.0286645 -0.15652 0.0887692 - 0.0214489 -0.168377 0.101114 - 0.0164982 -0.156846 0.109506 - 0.0186829 -0.18714 0.105903 - 0.0198876 -0.207572 0.10393 - 0.00931662 -0.185608 0.12186 - 0.00196389 -0.183311 0.134383 --0.00119638 -0.181466 0.139762 --0.00211321 -0.186401 0.141344 --0.00756826 -0.183651 0.15063 - -0.0117871 -0.164203 0.157744 - -0.0179483 -0.148798 0.168184 - -0.0212596 -0.131821 0.17376 - -0.0253727 -0.114073 0.1807 - -0.0309769 -0.223793 0.190685 - -0.0324866 -0.255917 0.193385 - -0.0441913 -0.316553 0.213574 - -0.0500343 -0.380928 0.223787 - -0.139583 -2.18175 0.383527 - -0.162759 -2.24727 0.423286 - -0.175995 -2.14131 0.445426 - -0.211563 -2.225 0.506378 - -0.253974 -2.04988 0.577968 - -0.275208 -2.06921 0.614236 - -0.33106 -2.1578 0.709778 - -0.43824 -2.16851 0.892492 - -0.500048 -1.93176 0.996899 - -0.501736 -1.89578 0.999634 - -0.165919 -0.403797 0.421386 - -0.170523 -0.406241 0.429243 - -0.175517 -0.405654 0.437752 - -0.181414 -0.407294 0.44781 - -0.237447 -0.41261 0.54333 - -0.243222 -0.402724 0.553134 - -0.246814 -0.402598 0.559256 - -0.264569 -0.417812 0.589576 - -0.268213 -0.388632 0.595672 - -0.278816 -0.385219 0.61373 - -0.491999 -0.661018 0.97816 - -0.491418 -0.654136 0.977142 - -0.493697 -0.598744 0.980808 - -0.648951 -0.501199 1.24503 - -0.624842 -0.422916 1.20363 - -0.626063 -0.395165 1.2056 - -1.23532 -0.578467 2.24472 - -1.23933 -0.536551 2.25139 - -1.23875 -0.460411 2.2501 - -1.24022 -0.143811 2.25135 - -1.24037 -0.102172 2.25143 - -1.2396 -0.0086482 2.24977 - -0.638942 0.0528594 1.22578 - -0.622718 0.122617 1.19785 - -0.622585 0.143063 1.19755 - -0.965023 0.275519 1.78066 - -1.23762 0.366972 2.24491 - -1.23732 0.377478 2.24435 - -1.23618 0.570627 2.24165 - -1.23908 0.63816 2.24632 - -1.2443 0.719628 2.2549 - -0.816863 0.663103 1.52661 - -0.642149 0.684157 1.22875 - -0.559524 0.723455 1.08777 - -0.516966 0.721592 1.01525 - -0.498602 0.72589 0.983931 - -0.493023 0.763079 0.974276 - -0.49426 0.778744 0.976323 - -0.496681 0.803753 0.98035 - -0.490287 0.820815 0.969386 - -0.496489 0.981712 0.97932 - -0.493174 0.991804 0.973629 - -0.495804 1.04215 0.977913 - -0.495705 1.11819 0.977444 - -0.496333 1.23613 0.978048 - -0.414757 1.27729 0.838852 - -0.362304 1.27206 0.749473 - -0.349933 1.27854 0.728363 - -0.339515 1.27832 0.710608 - -0.311609 1.25913 0.663122 - -0.295697 1.20071 0.636234 - -0.256232 1.17024 0.56909 - -0.220434 1.16252 0.50811 - -0.213827 1.15604 0.496875 - -0.16634 1.16993 0.415884 - -0.16399 1.19853 0.411767 - -0.160549 1.24684 0.40571 - -0.146527 1.18789 0.382045 - -0.136448 1.16494 0.364957 - -0.115978 1.21333 0.329877 - -0.0933086 1.13981 0.291532 - -0.0895054 1.11338 0.285154 - -0.0411111 0.11864 0.206604 - -0.0378727 0.0979562 0.201167 - -0.0358776 0.0659936 0.197893 - -0.0333931 0.0627314 0.193671 - -0.0297361 0.0961043 0.187306 - -0.0250582 0.117878 0.179247 --0.00847272 0.183813 0.150719 --0.00156896 0.200399 0.138887 --0.00112627 0.200096 0.138134 - 0.0136358 0.217408 0.112906 - 0.0175011 0.223763 0.106293 - 0.018574 0.218284 0.104486 - 0.0282582 0.223902 0.0879583 - 0.03046 0.220195 0.0842204 - 0.0376555 0.227815 0.0719265 - 0.0420125 0.213467 0.0645573 - 0.05565 0.239464 0.0412115 - 0.0630643 0.249587 0.0285348 - 0.0678583 0.24575 0.0203793 - 0.0939935 0.281452 -0.0243056 - 0.0907616 0.269686 -0.0187507 - 0.0883553 0.257704 -0.0146021 - 0.0321569 -0.13677 0.0854608 - 0.0284096 -0.151329 0.0917541 - 0.0325788 -0.173047 0.0848994 - 0.0166173 -0.162899 0.111426 - 0.0166954 -0.166338 0.111309 - 0.0223756 -0.193581 0.101961 - 0.0193542 -0.185407 0.106958 - 0.0204419 -0.196868 0.105192 - 0.0196853 -0.206751 0.10649 - 0.00693198 -0.179872 0.127611 --0.00223124 -0.183862 0.142878 --0.00710741 -0.184851 0.150997 --0.00796534 -0.182215 0.152415 - -0.0163309 -0.15447 0.16623 - -0.0276281 -0.0956811 0.184804 - -0.0283531 -0.0948931 0.186008 - -0.0306817 -0.0823885 0.189835 - -0.0343038 -0.29099 0.196674 - -0.0349577 -0.290998 0.197762 - -0.0453626 -0.335445 0.215252 - -0.049666 -0.369959 0.222548 - -0.218398 -2.20962 0.510522 - -0.227119 -2.13577 0.524749 - -0.261976 -2.04502 0.582412 - -0.309963 -2.1556 0.662708 - -0.395486 -2.16504 0.805085 - -0.504574 -2.05481 0.986218 - -0.152059 -0.408282 0.393114 - -0.165099 -0.402639 0.414796 - -0.20303 -0.401547 0.477923 - -0.214544 -0.414176 0.497136 - -0.215476 -0.412654 0.49868 - -0.219598 -0.411056 0.505534 - -0.226368 -0.411432 0.516804 - -0.2325 -0.410011 0.527004 - -0.243578 -0.407352 0.545432 - -0.249599 -0.40121 0.555428 - -0.254213 -0.4063 0.563127 - -0.273449 -0.4085 0.595151 - -0.346087 -0.466682 0.716273 - -0.487701 -0.667605 0.952748 - -0.490697 -0.659906 0.957706 - -0.493048 -0.645329 0.961561 - -0.497791 -0.588213 0.969234 - -0.499784 -0.546649 0.972389 - -0.498879 -0.524277 0.970796 - -0.504184 -0.514412 0.979587 - -0.64538 -0.465694 1.2144 - -0.624611 -0.387467 1.17953 - -1.24258 -0.637461 2.20902 - -1.26819 -0.528969 2.25122 - -1.26939 -0.518517 2.25317 - -1.26461 -0.386941 2.24471 - -1.26701 -0.37699 2.24867 - -1.26835 -0.270967 2.25048 - -1.26662 -0.102601 2.24696 - -1.26686 -0.0921727 2.24731 - -1.26692 -0.0608524 2.24728 - -1.25133 0.042902 2.22093 - -0.732066 0.202889 1.35608 - -1.27293 0.511958 2.25507 - -1.27574 0.57929 2.25947 - -1.27265 0.678443 2.25396 - -1.27256 0.701034 2.25372 - -1.27256 0.910497 2.25291 - -0.652055 0.589995 1.22141 - -0.640579 0.58537 1.20233 - -0.623368 0.72618 1.17313 - -0.594521 0.724137 1.12513 - -0.534228 0.721681 1.02479 - -0.495528 0.741116 0.960306 - -0.492017 0.775371 0.954328 - -0.494577 1.16758 0.957065 - -0.494546 1.25582 0.956672 - -0.451041 1.27255 0.884199 - -0.417284 1.27705 0.827998 - -0.285301 1.16166 0.60878 - -0.258601 1.16367 0.564334 - -0.216852 1.157 0.494876 - -0.208825 1.199 0.481352 - -0.177906 1.15754 0.430054 - -0.16322 1.17307 0.40555 - -0.107983 1.24664 0.31333 - -0.0391163 0.10184 0.203158 - -0.0371873 0.0799739 0.200032 - -0.0360901 0.0659999 0.19826 - -0.0349443 0.0559551 0.196392 - -0.0337187 0.0658357 0.194314 - -0.0318015 0.0795555 0.19107 - -0.0316227 0.079518 0.190773 - -0.020721 0.132624 0.172422 --0.00436162 0.19642 0.144947 --0.00195049 0.199099 0.140923 - 0.012374 0.228129 0.11697 - 0.0112829 0.21493 0.118837 - 0.0346826 0.206104 0.0799256 - 0.0351461 0.2055 0.0791565 - 0.0597535 0.238631 0.0380724 - 0.0759455 0.252868 0.0110681 - 0.0909844 0.269663 -0.0140271 - 0.0351085 -0.142271 0.0833166 - 0.027597 -0.136397 0.0955042 - 0.030353 -0.167006 0.0911411 - 0.0310701 -0.173478 0.0900002 - 0.0154438 -0.157386 0.11534 - 0.0213815 -0.184467 0.105791 - 0.0222031 -0.19282 0.104488 - 0.0096641 -0.18714 0.124848 - 0.00336428 -0.179286 0.135059 - 0.00392669 -0.186418 0.134172 --0.00097332 -0.188865 0.142146 - -0.0110454 -0.168669 0.158442 - -0.0131461 -0.162494 0.161833 - -0.0180185 -0.145205 0.169687 - -0.022626 -0.124577 0.177098 - -0.0295374 -0.0831908 0.188175 - -0.0296649 -0.129513 0.188559 - -0.0280509 -0.181449 0.186133 - -0.0300243 -0.199733 0.189411 - -0.0336541 -0.25898 0.195537 - -0.184156 -2.19286 0.447565 - -0.212333 -2.22554 0.493492 - -0.2329 -2.16433 0.52669 - -0.237849 -2.16263 0.534728 - -0.362818 -2.15965 0.737858 - -0.463034 -2.16611 0.900786 - -0.474633 -2.16723 0.919644 - -0.496973 -2.16419 0.955947 - -0.503149 -2.08776 0.965694 - -0.504097 -2.01828 0.966971 - -0.151575 -0.417472 0.387825 - -0.151789 -0.413856 0.38816 - -0.15437 -0.410031 0.392341 - -0.188281 -0.409287 0.447462 - -0.20868 -0.408537 0.480618 - -0.209615 -0.407088 0.482132 - -0.216021 -0.407315 0.492546 - -0.234136 -0.403241 0.521977 - -0.238296 -0.408103 0.528758 - -0.273578 -0.416508 0.586142 - -0.287867 -0.383118 0.609242 - -0.490212 -0.630649 0.939103 - -0.497616 -0.594898 0.951003 - -0.49454 -0.526246 0.945741 - -0.495746 -0.522413 0.947686 - -0.509184 -0.506042 0.969468 - -0.653251 -0.505993 1.20365 - -0.645707 -0.475871 1.19127 - -0.644371 -0.468911 1.18908 - -0.628977 -0.445574 1.16396 - -1.29246 -0.497381 2.24268 - -1.29585 -0.304284 2.24744 - -0.625742 0.0993036 1.15663 - -0.618001 0.117565 1.14397 - -1.29868 0.394122 2.24938 - -1.29842 0.415639 2.24887 - -1.29997 0.602926 2.25068 - -1.30025 0.625447 2.25104 - -1.30279 0.752004 2.2547 - -1.30432 0.870201 2.25674 - -0.833344 0.662229 1.49194 - -0.81839 0.65756 1.46765 - -0.806827 0.655506 1.44886 - -0.742711 0.643731 1.34468 - -0.637746 0.731559 1.17372 - -0.632986 0.732764 1.16598 - -0.493516 1.03862 0.938104 - -0.492106 1.0539 0.935753 - -0.490491 1.16943 0.932686 - -0.495281 1.19256 0.940384 - -0.490708 1.27109 0.932652 - -0.388051 1.28576 0.765724 - -0.385113 1.28866 0.760937 - -0.379539 1.28174 0.751902 - -0.343192 1.28074 0.692823 - -0.284708 1.15449 0.598237 - -0.208438 1.23999 0.473933 - -0.171922 1.15905 0.414884 - -0.158016 1.24202 0.391961 - -0.155177 1.243 0.387343 - -0.0979799 1.15027 0.294722 - -0.0393464 0.0887599 0.203463 - -0.0352272 0.0539862 0.1969 - -0.0343678 0.0589299 0.195484 - -0.033933 0.0598853 0.194774 - -0.0326685 0.069729 0.192681 - -0.029393 0.0911504 0.187275 - -0.021456 0.130073 0.174224 - -0.0203358 0.131649 0.172397 --0.00626328 0.191722 0.149293 - 0.00255465 0.205122 0.134908 - 0.0030238 0.204798 0.134146 - 0.0106508 0.220604 0.121688 - 0.0137731 0.226792 0.116589 - 0.0215181 0.227796 0.103996 - 0.0239383 0.219895 0.100092 - 0.0289298 0.228402 0.0919454 - 0.0357969 0.217252 0.0808253 - 0.0426722 0.22059 0.0696365 - 0.0692238 0.243687 0.026388 - 0.0775494 0.253817 0.0128158 - 0.0863735 0.243989 -0.0014904 - 0.0230192 -0.126116 0.105123 - 0.0290301 -0.16327 0.0957199 - 0.0269508 -0.162399 0.0990176 - 0.0156891 -0.148933 0.116846 - 0.0253492 -0.201134 0.101706 - 0.0232995 -0.208936 0.104989 - 0.00550932 -0.178301 0.133118 - 0.0021724 -0.18086 0.138425 --0.00953072 -0.174452 0.156981 - -0.0144452 -0.157216 0.164719 - -0.0305032 -0.0754401 0.189906 - -0.0305551 -0.0835072 0.190018 - -0.0294865 -0.191699 0.188728 - -0.0312585 -0.214874 0.191628 - -0.0401733 -0.267829 0.20598 - -0.0443273 -0.303498 0.212709 - -0.0455641 -0.320386 0.214736 - -0.202148 -2.19283 0.470356 - -0.254169 -2.18859 0.552928 - -0.33559 -2.15803 0.682079 - -0.356925 -2.15642 0.715944 - -0.361941 -2.15373 0.723898 - -0.385807 -2.1665 0.761835 - -0.459198 -2.16851 0.878359 - -0.502494 -1.97809 0.946381 - -0.50451 -1.91826 0.949357 - -0.503943 -1.79041 0.947977 - -0.150641 -0.412246 0.381901 - -0.1516 -0.411294 0.38342 - -0.156958 -0.412653 0.391931 - -0.174841 -0.407712 0.420304 - -0.185637 -0.411033 0.437456 - -0.203046 -0.406975 0.46508 - -0.218552 -0.406552 0.489695 - -0.240728 -0.413665 0.52493 - -0.625983 -0.402777 1.13652 - -0.629673 -0.383359 1.14231 - -0.641284 -0.368757 1.16069 - -0.650767 -0.36896 1.17574 - -0.665849 -0.372315 1.1997 - -0.822956 -0.436876 1.44937 - -0.837269 -0.437677 1.47209 - -1.32311 -0.348652 2.24309 - -1.32729 -0.306668 2.24956 - -1.3283 0.561438 2.24791 - -1.33106 0.641324 2.25199 - -1.32884 0.720035 2.24817 - -1.31525 1.00758 2.22551 - -0.764693 0.652785 1.35278 - -0.648954 0.592865 1.16925 - -0.637689 0.594477 1.15136 - -0.628784 0.655531 1.137 - -0.517808 0.725474 0.960549 - -0.493852 0.746561 0.922436 - -0.494548 0.859757 0.923117 - -0.496533 1.05612 0.925531 - -0.493804 1.07827 0.921115 - -0.480457 1.28125 0.899165 - -0.463791 1.26917 0.87275 - -0.44786 1.28288 0.847406 - -0.416266 1.28358 0.797245 - -0.390594 1.27423 0.756524 - -0.336425 1.27635 0.670517 - -0.294864 1.16813 0.604939 - -0.279846 1.15684 0.581139 - -0.261073 1.15519 0.551342 - -0.258388 1.157 0.547072 - -0.232419 1.16284 0.505822 - -0.223524 1.16274 0.4917 - -0.208967 1.16333 0.468588 - -0.205612 1.24472 0.462955 - -0.19176 1.18622 0.441184 - -0.157997 1.25383 0.387328 - -0.145848 1.18774 0.368288 - -0.134763 1.1577 0.350802 - -0.132071 1.15849 0.346525 - -0.0857718 0.95465 0.273785 - -0.0397878 0.0886668 0.20403 - -0.0360597 0.0629951 0.198208 - -0.0346846 0.056972 0.196047 - -0.033726 0.0538817 0.194537 - -0.0295351 0.0902639 0.187747 - -0.0217019 0.126278 0.175176 - -0.0187349 0.135276 0.170431 - 0.0128185 0.217573 0.120028 - 0.0140391 0.217685 0.11809 - 0.0193247 0.229688 0.109654 - 0.025336 0.227626 0.100118 - 0.0258656 0.227122 0.0992787 - 0.0295451 0.221189 0.0934594 - 0.0323923 0.221609 0.0889377 - 0.0622961 0.225214 0.0414487 - 0.0383257 -0.133861 0.0841548 - 0.0359063 -0.134043 0.0878879 - 0.0337609 -0.132284 0.091191 - 0.0350004 -0.137027 0.0892963 - 0.0270189 -0.131402 0.101588 - 0.0247846 -0.133571 0.105043 - 0.0179889 -0.138083 0.115543 - 0.0184349 -0.147241 0.114889 - 0.0173509 -0.16036 0.116609 - 0.0169705 -0.160778 0.117198 - 0.0129631 -0.182905 0.123461 - 0.00858579 -0.182205 0.130211 - 0.00472297 -0.180854 0.136165 - 0.00221762 -0.178363 0.140021 --0.00093078 -0.189985 0.144921 - -0.0163308 -0.149103 0.168527 - -0.0212843 -0.12752 0.17609 - -0.0233975 -0.116039 0.179307 - -0.0317665 -0.223927 0.192614 - -0.0361335 -0.256988 0.199473 - -0.0402816 -0.250799 0.205849 - -0.0464579 -0.326284 0.215655 - -0.175163 -2.21733 0.421155 - -0.184474 -2.19708 0.435445 - -0.231848 -2.13247 0.508289 - -0.253481 -2.19236 0.541883 - -0.285784 -2.05665 0.591216 - -0.375703 -2.16445 0.730327 - -0.421526 -2.16859 0.801031 - -0.427189 -2.16828 0.809766 - -0.502441 -1.80905 0.924534 - -0.501093 -1.78365 0.922361 - -0.154958 -0.448275 0.383483 - -0.191687 -0.40811 0.439995 - -0.200701 -0.408417 0.453902 - -0.204279 -0.409714 0.459426 - -0.229916 -0.412564 0.498986 - -0.234651 -0.411556 0.506286 - -0.246269 -0.409553 0.524201 - -0.262003 -0.396188 0.548425 - -0.486412 -0.619857 0.895433 - -0.489194 -0.618007 0.899719 - -0.490663 -0.614351 0.901971 - -0.492692 -0.605838 0.905071 - -0.499356 -0.586741 0.91528 - -0.4999 -0.571059 0.916062 - -0.499726 -0.544199 0.915694 - -0.50823 -0.50717 0.928677 - -0.522478 -0.50165 0.950636 - -0.543214 -0.507016 0.982646 - -0.553033 -0.511438 0.99781 - -0.565791 -0.496863 1.01744 - -0.631371 -0.414785 1.1183 - -0.623485 -0.387817 1.10604 - -1.36422 -0.653293 2.24971 - -1.36209 -0.64084 2.24639 - -1.35976 -0.571917 2.24253 - -1.36559 -0.266143 2.25041 - -1.36472 -0.23362 2.24895 - -1.35143 -0.0721754 2.22784 - -0.279427 -0.00750994 0.573876 - -0.625883 0.0862305 1.10799 - -0.621961 0.137961 1.10175 - -0.621299 0.147365 1.1007 - -1.36679 0.41126 2.24977 - -1.36482 0.432595 2.24665 - -1.37014 0.489702 2.25464 - -1.37259 0.512925 2.25834 - -1.36935 0.624301 2.25294 - -1.36585 0.645409 2.24745 - -1.36801 0.68083 2.25066 - -1.36786 0.750249 2.25017 - -1.3666 0.784667 2.24811 - -1.36436 0.878328 2.2443 - -1.36811 0.929311 2.2499 - -1.35984 1.02191 2.23681 - -1.35298 1.04151 2.22614 - -0.856661 0.657037 1.46191 - -0.679117 0.596788 1.18824 - -0.667028 0.591937 1.16961 - -0.63163 0.595334 1.11499 - -0.592319 0.723327 1.05387 - -0.541093 0.719416 0.974864 - -0.499769 0.734972 0.911057 - -0.491194 0.794279 0.897611 - -0.493187 0.87029 0.900407 - -0.494606 1.12797 0.901648 - -0.489303 1.26925 0.892948 - -0.486293 1.27286 0.888291 - -0.450161 1.27763 0.832535 - -0.39528 1.27977 0.747863 - -0.35313 1.27619 0.682853 - -0.302367 1.17922 0.604899 - -0.29874 1.17763 0.599311 - -0.293147 1.18179 0.590668 - -0.284758 1.17279 0.577759 - -0.244559 1.19363 0.515669 - -0.121806 1.14952 0.326465 - -0.0360454 0.0609863 0.198168 - -0.0351898 0.0489993 0.196892 - -0.0345048 0.0569793 0.195806 - -0.0302406 0.09352 0.189093 - -0.0301176 0.0844464 0.188937 - -0.0240664 0.115117 0.179489 - -0.0205684 0.131172 0.174034 --0.00958872 0.171491 0.156948 - 0.00534984 0.203532 0.133785 - 0.00602236 0.204139 0.132745 - 0.0168343 0.218689 0.116013 - 0.0221355 0.219693 0.107831 - 0.0259616 0.221778 0.101921 - 0.0298788 0.221374 0.0958795 - 0.0355133 0.204849 0.087248 - 0.0731156 0.267473 0.0290102 - 0.0665682 0.21962 0.0392867 - 0.0330782 -0.121884 0.0946099 - 0.0341097 -0.132654 0.0930941 - 0.03379 -0.133196 0.093578 - 0.0267867 -0.141438 0.104164 - 0.0233975 -0.137326 0.109258 - 0.0158284 -0.138491 0.120671 - 0.0163683 -0.142641 0.119872 - 0.0136515 -0.150371 0.123995 - 0.0159551 -0.160683 0.12056 - 0.016661 -0.164564 0.11951 - 0.0285949 -0.213258 0.101698 - 0.0224825 -0.203224 0.110875 - 0.0137475 -0.182004 0.123965 - 0.0104389 -0.17155 0.128914 - 0.00961074 -0.172256 0.130165 - 0.0131426 -0.194648 0.124922 --0.00461888 -0.184133 0.151656 --0.00919091 -0.169836 0.158496 - -0.0186173 -0.13794 0.172589 - -0.0274239 -0.0930368 0.185701 - -0.0289785 -0.0813061 0.188001 - -0.0295297 -0.0763913 0.188815 - -0.0306881 -0.0726055 0.190547 - -0.0308632 -0.0726379 0.190811 - -0.0291622 -0.178719 0.188631 - -0.0293819 -0.185752 0.188987 - -0.186685 -2.19609 0.433364 - -0.274004 -2.05574 0.564472 - -0.341079 -2.15953 0.665951 - -0.397396 -2.15981 0.750839 - -0.501126 -2.15236 0.907165 - -0.501851 -1.9518 0.907532 - -0.156568 -0.452831 0.381663 - -0.156356 -0.405852 0.381172 - -0.157865 -0.406638 0.38345 - -0.175979 -0.40942 0.410763 - -0.183083 -0.405906 0.421459 - -0.19724 -0.412542 0.442822 - -0.204782 -0.401212 0.454149 - -0.270617 -0.397976 0.55337 - -0.286733 -0.410514 0.577707 - -0.300062 -0.420972 0.597836 - -0.30209 -0.416761 0.600877 - -0.298222 -0.389399 0.594949 - -0.299237 -0.383968 0.596459 - -0.483971 -0.601368 0.875695 - -0.496468 -0.595773 0.894512 - -0.499924 -0.572885 0.899638 - -0.494842 -0.550779 0.891898 - -0.499882 -0.525597 0.899405 - -0.524408 -0.505992 0.936302 - -0.586286 -0.502484 1.02956 - -0.625989 -0.420698 1.08911 - -0.624552 -0.382421 1.0868 - -0.675971 -0.376157 1.16428 - -1.391 -0.632929 2.24297 - -1.39659 -0.601217 2.25128 - -1.39233 -0.376241 2.24405 - -1.39718 -0.322697 2.25117 - -1.38957 -0.288301 2.23958 - -1.39027 -0.277603 2.2406 - -1.39447 -0.235047 2.24677 - -0.290962 0.0023566 0.582587 - -0.642047 0.0487353 1.11161 - -0.628114 0.0710876 1.09053 - -0.623625 0.0985884 1.08366 - -0.619866 0.116603 1.07793 - -1.39397 0.468281 2.24347 - -1.39919 0.5036 2.25121 - -1.39765 0.910345 2.24741 - -1.3839 1.06164 2.22615 - -0.761207 0.64802 1.28905 - -0.624224 0.603006 1.08274 - -0.622771 0.607643 1.08054 - -0.646967 0.698236 1.11668 - -0.617723 0.724064 1.07251 - -0.548213 0.71819 0.967753 - -0.506798 0.721692 0.905317 - -0.503311 0.729093 0.900033 - -0.489529 0.779123 0.879079 - -0.492935 0.879014 0.883851 - -0.494819 1.09112 0.885923 - -0.494341 1.17248 0.884909 - -0.482362 1.27848 0.866469 - -0.475751 1.2718 0.856529 - -0.429 1.28096 0.786027 - -0.358492 1.27801 0.679761 - -0.304082 1.19827 0.598037 - -0.298705 1.2043 0.589911 - -0.295801 1.20636 0.585526 - -0.278878 1.17303 0.560139 - -0.249531 1.18624 0.515855 - -0.214046 1.15851 0.462469 - -0.204234 1.23965 0.447387 - -0.18968 1.17701 0.425675 - -0.167744 1.16726 0.392647 - -0.122855 1.14852 0.325053 - -0.0353089 0.0509983 0.197065 - -0.0336274 0.0599409 0.194498 - -0.0299291 0.0975418 0.188787 - -0.030028 0.0774525 0.189009 - -0.0271277 0.0938836 0.184578 - -0.0143259 0.151338 0.165074 - -0.0091794 0.175764 0.157228 - 0.00387138 0.199788 0.13747 - 0.00577424 0.203859 0.134587 - 0.00842499 0.20312 0.130594 - 0.0229406 0.231053 0.108614 - 0.026269 0.228212 0.103607 - 0.0352088 0.220743 0.0901589 - 0.0327191 0.196657 0.0939989 - 0.0354429 0.200634 0.0898789 - 0.0715731 0.266026 0.0351831 - 0.0669197 0.2323 0.0423192 - 0.0563111 0.193783 0.0584489 - 0.0461068 -0.149007 0.0776666 - 0.0385417 -0.141084 0.088798 - 0.0219808 -0.126856 0.113177 - 0.0241651 -0.137784 0.109994 - 0.0161035 -0.140519 0.121896 - 0.0160621 -0.141755 0.121961 - 0.0131898 -0.14605 0.126213 - 0.0133956 -0.148152 0.125917 - 0.0243243 -0.203661 0.109994 - 0.0230583 -0.201442 0.111853 - 0.0134804 -0.177499 0.125897 - 0.0130459 -0.177871 0.126539 - 0.0116978 -0.176789 0.128524 - 0.00842718 -0.182651 0.133369 - 9.221e-05 -0.181855 0.145662 --0.00138468 -0.193216 0.147881 --0.00530646 -0.181716 0.153625 --0.00926477 -0.171199 0.159427 - -0.0297256 -0.0744864 0.189265 - -0.0305724 -0.0696217 0.190497 - -0.0309684 -0.068687 0.191078 - -0.031084 -0.0697108 0.191252 - -0.0305574 -0.201882 0.190946 - -0.206926 -2.21797 0.458301 - -0.256929 -2.16188 0.531862 - -0.302909 -2.08967 0.599434 - -0.380065 -2.16238 0.713508 - -0.421406 -2.16714 0.77451 - -0.444203 -2.1632 0.808124 - -0.45186 -2.17225 0.819452 - -0.507343 -2.14957 0.901217 - -0.506611 -2.11892 0.900028 - -0.503788 -2.00333 0.895451 - -0.154635 -0.444788 0.374845 - -0.150918 -0.416887 0.369261 - -0.168244 -0.409284 0.394792 - -0.175985 -0.407985 0.406208 - -0.195765 -0.414722 0.43541 - -0.196781 -0.41346 0.436904 - -0.239636 -0.406233 0.500096 - -0.242379 -0.404495 0.504136 - -0.257827 -0.408718 0.526939 - -0.300263 -0.419093 0.589575 - -0.499701 -0.575092 0.884331 - -0.50233 -0.505715 0.887962 - -0.527366 -0.50686 0.924899 - -0.62444 -0.506667 1.0681 - -0.646215 -0.48485 1.10014 - -0.641704 -0.453211 1.09337 - -0.62676 -0.436639 1.07127 - -0.626836 -0.378374 1.07117 - -0.63966 -0.370689 1.09006 - -0.803233 -0.437703 1.3316 - -1.42178 -0.456525 2.24411 - -1.42961 -0.325552 2.25519 - -1.42666 -0.171681 2.25029 - -1.42748 -0.150024 2.25143 - -0.286704 0.00424441 0.568065 - -0.648668 0.0485579 1.10186 - -0.619467 0.114849 1.05855 - -0.620825 0.128965 1.0605 - -0.621551 0.156994 1.06147 - -1.42513 0.528231 2.24555 - -1.4299 0.586953 2.25237 - -1.42518 0.83028 2.24453 - -1.42497 0.964432 2.24376 - -1.42551 1.06563 2.24418 - -0.785016 0.652388 1.30084 - -0.637646 0.589509 1.08367 - -0.629376 0.599555 1.07143 - -0.644613 0.73277 1.09344 - -0.497534 0.728816 0.876487 - -0.493959 0.735966 0.871189 - -0.494495 0.749822 0.87193 - -0.492183 1.20518 0.866896 - -0.490145 1.25794 0.863701 - -0.31191 1.26322 0.600759 - -0.215552 1.17245 0.458942 - -0.18123 1.16588 0.408334 - -0.169119 1.16432 0.390475 - -0.156624 1.24787 0.371746 - -0.0417457 0.111343 0.206334 - -0.0392192 0.103719 0.202634 - -0.0367714 0.0779281 0.199115 - -0.0357371 0.0609801 0.19765 - -0.033907 0.0539735 0.194975 - -0.0298468 0.0754665 0.188909 - -0.0258686 0.0986878 0.182958 - -0.0105419 0.165333 0.160111 - 0.0118588 0.212074 0.1269 - 0.0330071 0.197724 0.0957547 - 0.0383881 0.197535 0.0878176 - 0.0465475 0.215444 0.0757174 - 0.0542542 0.231463 0.0642919 - 0.0682176 0.260374 0.0435908 - 0.0761567 0.253595 0.0319036 - 0.0624044 0.1961 0.0523952 - 0.0441797 0.145923 0.0794582 - 0.028966 -0.13184 0.105523 - 0.0222095 -0.137227 0.115228 - 0.0218671 -0.137657 0.11572 - 0.0175275 -0.135595 0.121934 - 0.0171892 -0.135988 0.12242 - 0.0144477 -0.139042 0.126361 - 0.0268414 -0.207218 0.108832 - 0.00167258 -0.177262 0.144809 - 0.00041229 -0.17591 0.146611 - -0.0009918 -0.17884 0.148635 --0.00173523 -0.188682 0.149735 - -0.0407418 -0.239715 0.205833 - -0.0530077 -0.361452 0.223843 - -0.0558218 -0.379054 0.227939 - -0.0638068 -0.458991 0.239666 - -0.392171 -2.16061 0.716357 - -0.4242 -2.17493 0.762324 - -0.441002 -2.16859 0.78639 - -0.502562 -2.06135 0.874267 - -0.505779 -1.99867 0.878661 - -0.150806 -0.418689 0.364247 - -0.153423 -0.40971 0.367967 - -0.169411 -0.40583 0.390874 - -0.172018 -0.405464 0.394611 - -0.192688 -0.407306 0.424249 - -0.23179 -0.41188 0.480322 - -0.252969 -0.413879 0.510692 - -0.27082 -0.403021 0.536245 - -0.300889 -0.412472 0.579384 - -0.31433 -0.385958 0.598561 - -0.319415 -0.385946 0.60585 - -0.499125 -0.558451 0.864086 - -0.492834 -0.535541 0.854988 - -0.495024 -0.527968 0.858101 - -0.499766 -0.513278 0.864847 - -0.570804 -0.498365 0.966636 - -0.587728 -0.508678 0.990933 - -0.602446 -0.500236 1.012 - -0.627226 -0.505126 1.04755 - -0.634713 -0.450428 1.05809 - -0.627993 -0.434681 1.0484 - -0.622623 -0.399383 1.04058 - -1.45284 -0.721274 2.2319 - -1.46533 -0.360931 2.24855 - -1.46882 -0.283902 2.25329 - -1.46513 -0.184046 2.24764 - -1.46603 -0.129335 2.24874 - -0.322709 0.0135592 0.609176 - -0.690308 0.0408625 1.13607 - -0.620662 0.0723841 1.03612 - -0.623513 0.0862886 1.04016 - -0.617596 0.143949 1.03147 - -0.723661 0.202398 1.18332 - -1.46607 0.442883 2.2468 - -1.47028 0.546481 2.25248 - -1.47473 0.640841 2.25852 - -1.46984 0.685438 2.25136 - -1.47356 0.710827 2.25661 - -1.46725 0.839183 2.24711 - -1.47063 0.877809 2.25181 - -1.47098 0.915015 2.25219 - -1.46747 0.93757 2.24707 - -1.4662 0.949189 2.24522 - -1.46828 1.00084 2.24801 - -1.46865 1.03927 2.24841 - -0.808194 0.652648 1.30293 - -0.678733 0.598923 1.11753 - -0.62466 0.619823 1.03993 - -0.625465 0.632971 1.04104 - -0.621017 0.653024 1.0346 - -0.644535 0.705596 1.06813 - -0.597285 0.720927 1.00034 - -0.509421 0.720953 0.874375 - -0.492097 0.8271 0.849167 - -0.491445 0.958554 0.847773 - -0.495109 1.04701 0.852717 - -0.493822 1.08257 0.850748 - -0.490868 1.26071 0.845889 - -0.487722 1.26416 0.841367 - -0.432114 1.27566 0.761608 - -0.408469 1.27817 0.727701 - -0.384279 1.2767 0.693027 - -0.357441 1.27726 0.654551 - -0.325806 1.27005 0.609224 - -0.318836 1.27162 0.599226 - -0.276935 1.158 0.539554 - -0.267113 1.15774 0.525473 - -0.256431 1.16936 0.510119 - -0.22926 1.15998 0.471201 - -0.209342 1.23868 0.442371 - -0.203156 1.24127 0.433493 - -0.166225 1.17223 0.38079 - -0.141482 1.1656 0.345342 - -0.0395048 0.0986293 0.202877 - -0.0363063 0.0709345 0.198388 - -0.0338957 0.0629895 0.19496 - -0.0338961 0.0489874 0.19501 - -0.0289928 0.140649 0.18766 - -0.02864 0.132582 0.187182 - -0.030255 0.0816504 0.189676 - -0.0300718 0.0776017 0.189427 - -0.0255538 0.096714 0.182883 - -0.0219241 0.113852 0.17762 - -0.0179588 0.139982 0.171844 --0.00260398 0.180458 0.14969 - 0.00679113 0.199162 0.136155 - 0.0238779 0.224686 0.111571 - 0.0303679 0.228125 0.102255 - 0.0317646 0.228013 0.100253 - 0.0349009 0.221723 0.0957783 - 0.0528574 0.224721 0.0700254 - 0.0610701 0.206599 0.0583151 - 0.0658441 0.207471 0.051468 - 0.0402084 0.137726 0.0884632 - 0.0354607 -0.131845 0.0984061 - 0.0382797 -0.139603 0.0944804 - 0.0386975 -0.141643 0.0939016 - 0.0274877 -0.125247 0.109562 - 0.0281426 -0.134686 0.108676 - 0.0185385 -0.146326 0.122182 - 0.0252982 -0.196103 0.112876 - 0.0134601 -0.179321 0.129416 - 0.0116408 -0.182896 0.131979 - 0.00748777 -0.183657 0.137804 --0.00143159 -0.180539 0.150299 --0.00052152 -0.188433 0.14905 --0.00310096 -0.182448 0.152646 --0.00573996 -0.175416 0.156322 - -0.0131062 -0.155925 0.166583 - -0.0293326 -0.0695206 0.189035 - -0.0302733 -0.0937756 0.190438 - -0.0299215 -0.146836 0.190127 - -0.0312944 -0.208953 0.192266 - -0.0433875 -0.249452 0.209361 - -0.0535252 -0.35334 0.223933 - -0.0572788 -0.385844 0.229307 - -0.27095 -2.07111 0.534692 - -0.324542 -2.14204 0.610075 - -0.447094 -2.16954 0.781995 - -0.464316 -2.16375 0.806121 - -0.481716 -2.15849 0.8305 - -0.50254 -2.03164 0.859259 - -0.505742 -2.01974 0.863707 - -0.505763 -1.83198 0.863089 - -0.151324 -0.41062 0.36125 - -0.180065 -0.407135 0.401534 - -0.194753 -0.411 0.422141 - -0.20813 -0.405729 0.440878 - -0.220312 -0.411107 0.457976 - -0.224152 -0.40842 0.463352 - -0.229826 -0.409486 0.471311 - -0.250503 -0.414403 0.500317 - -0.257446 -0.412934 0.510047 - -0.500112 -0.551661 0.850757 - -0.52741 -0.500321 0.888855 - -0.651504 -0.506798 1.06286 - -0.628096 -0.376869 1.0296 - -0.810125 -0.439962 1.28503 - -1.49155 -0.694597 2.24131 - -1.49881 -0.615673 2.25121 - -1.4934 -0.362644 2.24276 - -1.49371 -0.173959 2.24255 - -1.49881 -0.130368 2.24953 - -1.49185 -0.0858433 2.23963 - -0.273966 0.00930952 0.531755 - -1.50112 0.101084 2.25199 - -0.620639 0.0935161 1.01752 - -0.623189 0.14325 1.02092 - -0.624753 0.152686 1.02308 - -0.658092 0.180517 1.06973 - -1.49812 0.457543 2.24654 - -1.50358 0.504975 2.25404 - -1.50231 0.516005 2.25222 - -1.50256 0.585358 2.25233 - -0.647389 0.585445 1.05333 - -0.630824 0.599228 1.03006 - -0.62778 0.608157 1.02576 - -0.619971 0.630275 1.01474 - -0.579585 0.720236 0.957802 - -0.569059 0.725626 0.943026 - -0.493408 0.846748 0.836541 - -0.491983 0.88958 0.834396 - -0.493961 0.909242 0.837102 - -0.494535 1.09863 0.837254 - -0.496195 1.23354 0.839117 - -0.404423 1.27395 0.710307 - -0.361505 1.27543 0.650129 - -0.263866 1.15838 0.513636 - -0.257397 1.17578 0.504507 - -0.191976 1.19011 0.412733 - -0.173364 1.16628 0.38672 - -0.117608 1.11115 0.308737 - -0.0354608 0.0589654 0.197185 - -0.0325012 0.0579182 0.193039 - -0.0294684 0.148754 0.188474 - -0.0296763 0.107697 0.188907 - -0.0264921 0.0899905 0.184504 - -0.0241498 0.10757 0.181159 - -0.012424 0.157496 0.164547 - -0.0095885 0.159346 0.160565 - 0.0154633 0.210035 0.125266 - 0.0224601 0.220093 0.115422 - 0.0239675 0.223308 0.113297 - 0.0316 0.228125 0.102579 - 0.0328032 0.186993 0.101034 - 0.0736573 0.253894 0.0435237 - 0.0690667 0.226041 0.0500559 - 0.0696863 0.221356 0.0492033 - 0.039129 0.1321 0.0923539 - 0.018472 -0.123809 0.124203 - 0.0204488 -0.148027 0.121589 - 0.00923516 -0.132438 0.136828 - 0.0136079 -0.148928 0.130921 - 0.0193384 -0.192202 0.123252 - 0.0137252 -0.180026 0.130866 - 0.0142168 -0.186222 0.130217 - 0.00305254 -0.175376 0.145405 - 0.00123873 -0.176431 0.147882 - 0.00078358 -0.176686 0.148504 --0.00964994 -0.169221 0.162707 - -0.0219193 -0.119355 0.17927 - -0.0229008 -0.112531 0.180586 - -0.0280108 -0.0794106 0.187442 - -0.0285691 -0.0744864 0.188187 - -0.0306748 -0.0708084 0.191046 - -0.0303228 -0.0888135 0.190627 - -0.0383428 -0.202837 0.20195 - -0.0427188 -0.235483 0.208028 - -0.0473942 -0.28201 0.214561 - -0.0565475 -0.371922 0.227348 - -0.291478 -2.11441 0.553622 - -0.350329 -2.16336 0.634045 - -0.372774 -2.15456 0.664624 - -0.385614 -2.16002 0.682152 - -0.396755 -2.1547 0.697328 - -0.415277 -2.15693 0.722595 - -0.478349 -2.16424 0.808633 - -0.490306 -2.16131 0.824929 - -0.511485 -2.0871 0.85356 - -0.503417 -1.9257 0.842012 - -0.500409 -1.84435 0.837635 - -0.176245 -0.409959 0.390712 - -0.206797 -0.410914 0.432379 - -0.294599 -0.411605 0.55212 - -0.295849 -0.406382 0.553807 - -0.299862 -0.401864 0.559265 - -0.316771 -0.416248 0.582371 - -0.323722 -0.400778 0.591799 - -0.577637 -0.504368 0.93842 - -1.38671 -0.709145 2.04247 - -1.4981 -0.732094 2.19445 - -1.51928 -0.730765 2.22333 - -1.53076 -0.664961 2.23877 - -1.53098 -0.52498 2.2386 - -1.53694 -0.209396 2.24566 - -1.54085 -0.176376 2.25087 - -0.273954 0.00029498 0.522572 - -0.273949 0.00383793 0.522553 - -0.669216 0.0382974 1.06147 - -0.625248 0.0794208 1.00137 - -0.620044 0.126793 0.994117 - -0.622983 0.149567 0.998049 - -1.53686 0.530295 2.24305 - -1.54092 0.601667 2.24833 - -1.53971 0.695724 2.24637 - -1.53892 0.890033 2.24463 - -1.5382 0.914558 2.24357 - -1.54419 0.930779 2.25168 - -1.53829 0.977681 2.24348 - -1.5391 1.04237 2.24437 - -1.5424 1.08378 2.24872 - -1.54015 1.09529 2.24562 - -0.643972 0.589756 1.02518 - -0.621922 0.615338 0.995026 - -0.6421 0.693585 1.02228 - -0.645832 0.711023 1.02731 - -0.605667 0.721681 0.972499 - -0.599578 0.727045 0.964177 - -0.590185 0.721454 0.951387 - -0.564612 0.719836 0.916517 - -0.551207 0.727036 0.898213 - -0.530187 0.722559 0.869562 - -0.523334 0.72522 0.860207 - -0.504835 0.722698 0.834989 - -0.493448 0.91644 0.818803 - -0.492193 0.946867 0.816989 - -0.491548 0.979849 0.815999 - -0.49229 1.19063 0.816297 - -0.490182 1.19651 0.813402 - -0.490311 1.26839 0.813336 - -0.45897 1.2796 0.770558 - -0.374916 1.27506 0.655946 - -0.370902 1.27481 0.650473 - -0.346402 1.28596 0.617023 - -0.341081 1.27989 0.609787 - -0.303324 1.24542 0.558414 - -0.280814 1.17295 0.527962 - -0.271272 1.15949 0.514995 - -0.222359 1.16087 0.448285 - -0.213513 1.16587 0.436205 - -0.164473 1.17908 0.369283 - -0.129193 1.131 0.321333 - -0.0395076 0.0854955 0.202563 - -0.0348364 0.0579811 0.196286 - -0.034715 0.0599865 0.196114 - -0.033178 0.173992 0.193632 - -0.0293706 0.119737 0.188623 - -0.0292826 0.0785966 0.188642 - -0.0286087 0.079479 0.18772 - -0.0283353 0.0804314 0.187344 - -0.0281278 0.0803889 0.187061 - -0.0187951 0.129445 0.174168 - 0.019022 0.21165 0.122318 - 0.0293798 0.220126 0.108164 - 0.033287 0.221282 0.102832 - 0.0338581 0.220782 0.102055 - 0.0343643 0.206697 0.101412 - 0.0325106 0.170031 0.104064 - 0.0630374 0.230275 0.0622299 - 0.0503697 0.16857 0.0797139 - 0.0350479 -0.12592 0.103559 - 0.0343192 -0.133648 0.104557 - 0.0273575 -0.127639 0.113833 - 0.0260157 -0.129388 0.11563 - 0.0207232 -0.122252 0.122673 - 0.0228913 -0.128293 0.119798 - 0.0174108 -0.121296 0.127093 - 0.0154935 -0.123474 0.12966 - 0.0119439 -0.140997 0.134458 - 0.0241427 -0.194691 0.118349 - 0.00877304 -0.178691 0.138818 - 0.00160247 -0.179792 0.148396 - 0.00120554 -0.183155 0.148937 - -0.0190624 -0.132863 0.175832 - -0.0272222 -0.077295 0.186542 - -0.0292098 -0.0716428 0.189177 - -0.0293972 -0.0716734 0.189427 - -0.0436544 -0.231349 0.208997 - -0.0602917 -0.368201 0.231668 - -0.254729 -2.1709 0.497304 - -0.279586 -2.08288 0.5302 - -0.151938 -0.424913 0.354228 - -0.152712 -0.39989 0.355178 - -0.171178 -0.415276 0.379885 - -0.173574 -0.401512 0.383039 - -0.186254 -0.408573 0.399993 - -0.191392 -0.410234 0.406859 - -0.192465 -0.409077 0.408288 - -0.237131 -0.412571 0.46794 - -0.238211 -0.411081 0.469376 - -0.243063 -0.413417 0.475863 - -0.244922 -0.413403 0.478345 - -0.259927 -0.4126 0.498378 - -0.262082 -0.40928 0.501245 - -0.329272 -0.38905 0.590891 - -0.501247 -0.511537 0.820929 - -0.514453 -0.501249 0.838528 - -0.53607 -0.503611 0.867399 - -0.569651 -0.500674 0.912228 - -0.615519 -0.510538 0.973506 - -0.624652 -0.423237 0.985409 - -0.624028 -0.402544 0.984507 - -0.687395 -0.380329 1.06904 - -1.43022 -0.722163 2.06203 - -1.56955 -0.685042 2.24795 - -1.56911 -0.519484 2.24681 - -1.56593 -0.312077 2.24187 - -1.57816 -0.246272 2.25799 - -0.282891 -0.0105874 0.527699 - -0.272194 0.00376231 0.513368 - -0.638296 0.053592 1.00204 - -0.618404 0.0560974 0.975468 - -0.620097 0.107835 0.977555 - -0.622501 0.116958 0.980735 - -1.57518 0.775384 2.2506 - -1.57332 0.8359 2.24791 - -1.57096 1.02423 2.24412 - -0.801451 0.645919 1.21791 - -0.640689 0.596584 1.00342 - -0.616985 0.596353 0.97177 - -0.62587 0.629356 0.983524 - -0.651106 0.714382 1.01694 - -0.586193 0.726245 0.930223 - -0.573021 0.721715 0.91265 - -0.570202 0.724366 0.908876 - -0.537097 0.729489 0.864656 - -0.528418 0.72324 0.853088 - -0.491558 0.73689 0.803825 - -0.49634 0.805271 0.809983 - -0.494052 0.897834 0.806619 - -0.49424 0.981628 0.80659 - -0.492183 1.09002 0.803482 - -0.486253 1.26559 0.794979 - -0.407728 1.27494 0.690098 - -0.343646 1.27432 0.604534 - -0.332102 1.27441 0.589121 - -0.27198 1.16501 0.509208 - -0.257033 1.19309 0.489156 - -0.201744 1.22913 0.415213 - -0.163489 1.24688 0.364073 - -0.126104 1.1178 0.314585 - -0.0372706 0.0847971 0.199418 - -0.0357685 0.184974 0.197078 - -0.0333608 0.176997 0.19389 - -0.0329304 0.168992 0.193342 - -0.0299747 0.131843 0.18952 - -0.0295782 0.113782 0.18905 - -0.0298367 0.0927685 0.189466 - -0.0295643 0.0716633 0.189172 - -0.0288098 0.0745481 0.188155 - -0.0244477 0.0977697 0.182253 - -0.013681 0.148227 0.167709 --0.00740891 0.167267 0.15927 --0.00164393 0.172819 0.151554 - 0.00210422 0.184461 0.146511 - 0.012977 0.203463 0.13193 - 0.0299232 0.187919 0.109354 - 0.0304149 0.187453 0.108699 - 0.0318825 0.186032 0.106744 - 0.0290612 0.158362 0.110604 - 0.0673817 0.228172 0.0592038 - 0.063392 0.209414 0.0645936 - 0.0632036 0.207129 0.0648527 - 0.0550155 0.17968 0.0758774 - 0.0432006 0.141288 0.0917813 - 0.0391288 -0.143091 0.100293 - 0.0368384 -0.144866 0.103289 - 0.0345679 -0.142711 0.106247 - 0.0225845 -0.128697 0.12185 - 0.0141144 -0.137572 0.13294 - 0.0137496 -0.13791 0.133418 - 0.0116092 -0.132995 0.136196 - 0.0182809 -0.183506 0.12765 - 0.0117627 -0.178362 0.136145 - 0.00988818 -0.177454 0.13859 - 0.0116565 -0.187067 0.136313 - 0.00859673 -0.183637 0.140297 - -5.705e-05 -0.172662 0.151562 --0.00146467 -0.181716 0.15343 - -0.0217795 -0.115492 0.17974 - -0.0268261 -0.0803145 0.186215 - -0.0291412 -0.0646487 0.189187 - -0.0303893 -0.0638273 0.190814 - -0.0302805 -0.0928759 0.190767 - -0.0299508 -0.111875 0.190399 - -0.0300344 -0.167925 0.190693 - -0.0324685 -0.230998 0.194079 - -0.0348107 -0.214979 0.197085 - -0.0380912 -0.186816 0.201276 - -0.0391743 -0.189732 0.2027 - -0.0420535 -0.210475 0.206528 - -0.265113 -2.185 0.504311 - -0.270701 -2.07661 0.511252 - -0.411976 -2.15005 0.695981 - -0.439409 -2.16358 0.731849 - -0.507662 -2.06888 0.820668 - -0.508164 -2.04397 0.821242 - -0.506353 -1.84044 0.818207 - -0.513661 -1.80258 0.827625 - -0.150405 -0.405119 0.348661 - -0.15902 -0.407038 0.359918 - -0.210488 -0.405574 0.427125 - -0.244127 -0.406564 0.471056 - -0.281558 -0.41232 0.519956 - -0.33931 -0.400532 0.595334 - -0.372361 -0.401557 0.638497 - -0.497482 -0.515019 0.802262 - -0.544009 -0.50464 0.862987 - -0.596463 -0.502728 0.931479 - -0.649942 -0.488881 1.00127 - -0.645543 -0.469218 0.995461 - -0.623853 -0.42701 0.966998 - -0.62358 -0.386896 0.966509 - -0.625172 -0.383018 0.968576 - -0.817548 -0.437183 1.21997 - -1.5229 -0.736 2.14206 - -1.60044 -0.511018 2.24257 - -1.60263 -0.476673 2.24532 - -1.6003 -0.269064 2.24159 - -1.60412 -0.246938 2.24651 - -1.60417 -0.235569 2.24654 - -1.60536 -0.201644 2.24798 - -1.6059 -0.190358 2.24865 - -1.6064 -0.111094 2.24904 - -0.274079 0.00719881 0.508808 - -0.320805 0.0147882 0.569802 - -0.621294 0.064078 0.962041 - -0.618902 0.0891815 0.958834 - -0.624971 0.14176 0.966587 - -1.60576 0.551388 2.24603 - -1.60645 0.610863 2.24674 - -1.60735 0.707328 2.24759 - -1.60762 0.956469 2.24712 - -1.60974 1.12835 2.24932 - -1.61151 1.15661 2.25155 - -0.817595 0.64346 1.21648 - -0.639609 0.593311 0.984217 - -0.589458 0.720668 0.918306 - -0.576595 0.723106 0.901502 - -0.513356 0.722777 0.818921 - -0.487317 0.76555 0.784776 - -0.495606 0.858104 0.795297 - -0.491632 0.945935 0.789818 - -0.49008 0.97716 0.787688 - -0.488094 1.26627 0.784143 - -0.278345 1.16422 0.510573 - -0.254945 1.18512 0.479948 - -0.235864 1.17347 0.455068 - -0.210132 1.17942 0.421445 - -0.207631 1.23181 0.418007 - -0.0422005 0.109069 0.205669 - -0.0339995 0.171999 0.194752 - -0.0335432 0.172 0.194157 - -0.0301742 0.124877 0.189912 - -0.0287276 0.0735888 0.188192 - -0.0202849 0.120037 0.177014 - -0.0188623 0.126718 0.175134 - -0.0128619 0.153253 0.167211 - -0.0119134 0.153924 0.16597 --0.00113368 0.177112 0.151817 - 0.00057285 0.183569 0.149567 - 0.0071249 0.191601 0.140985 - 0.0259008 0.222349 0.116364 - 0.0279184 0.221957 0.113731 - 0.0323885 0.210618 0.107931 - 0.0283075 0.189317 0.11333 - 0.0275625 0.183162 0.114323 - 0.0265832 0.155112 0.115694 - 0.0264148 0.151727 0.115926 - 0.0389944 0.17515 0.0994211 - 0.0383869 0.128937 0.100366 - 0.0488904 -0.140671 0.0903444 - 0.0331419 -0.128474 0.11033 - 0.0329971 -0.138914 0.110548 - 0.00984852 -0.12866 0.13995 - 0.0121484 -0.141406 0.137067 - 0.0166904 -0.159008 0.131349 - 0.0177527 -0.165981 0.13002 - 0.0209484 -0.182385 0.12601 - 0.0132727 -0.171544 0.135735 - 0.0128101 -0.171867 0.136324 - 0.0129618 -0.187998 0.136183 - 0.00722281 -0.182919 0.143465 --0.00305362 -0.179697 0.156521 - -0.0133679 -0.154851 0.169557 - -0.0151243 -0.144196 0.171755 - -0.0301494 -0.101906 0.190724 - -0.0333416 -0.207997 0.195127 - -0.03637 -0.188907 0.198916 - -0.0586947 -0.34339 0.227803 - -0.241408 -2.15291 0.465992 - -0.279801 -2.0729 0.514552 - -0.313988 -2.15648 0.558295 - -0.327209 -2.16409 0.575131 - -0.444877 -2.15785 0.724734 - -0.450882 -2.15586 0.732364 - -0.148828 -0.417449 0.342655 - -0.151419 -0.412229 0.345932 - -0.155595 -0.403447 0.351213 - -0.159433 -0.407048 0.356105 - -0.17241 -0.4038 0.372596 - -0.185205 -0.406758 0.388876 - -0.189795 -0.406877 0.394713 - -0.221917 -0.406282 0.435557 - -0.224133 -0.407327 0.438378 - -0.225983 -0.407555 0.440731 - -0.251349 -0.414163 0.473007 - -0.253272 -0.414128 0.475451 - -0.272285 -0.411975 0.499622 - -0.346578 -0.414685 0.5941 - -0.344904 -0.390839 0.591895 - -0.374788 -0.394475 0.629905 - -0.528378 -0.50072 0.825551 - -0.60667 -0.503681 0.925115 - -0.627112 -0.505423 0.951114 - -0.801718 -0.433627 1.17291 - -0.83388 -0.439108 1.21382 - -1.48685 -0.728967 2.04506 - -1.63911 -0.634157 2.23836 - -1.64082 -0.622808 2.24051 - -1.6384 -0.467882 2.23693 - -1.63784 -0.432683 2.2361 - -1.63797 -0.305473 2.23585 - -0.273481 0.00197995 0.499803 - -0.273434 0.00876853 0.499721 - -0.65322 0.0401457 0.982548 - -0.625414 0.0593027 0.947128 - -0.617254 0.116706 0.936565 - -0.621723 0.164283 0.942094 - -0.681677 0.19045 1.01825 - -1.64658 0.568409 2.24397 - -1.64989 0.788673 2.24747 - -1.6452 0.823721 2.24139 - -1.65165 1.05904 2.24883 - -0.807521 0.645594 1.17679 - -0.621349 0.72341 0.93981 - -0.494234 0.806091 0.777906 - -0.491498 1.07684 0.773551 - -0.48941 1.11294 0.77078 - -0.490036 1.26432 0.771086 - -0.464511 1.28182 0.738572 - -0.412355 1.28211 0.672251 - -0.354482 1.28174 0.598662 - -0.213328 1.16165 0.419562 - -0.188043 1.17004 0.387383 - -0.171189 1.16633 0.365963 - -0.159813 1.24573 0.351241 - -0.0379952 0.0786081 0.200117 - -0.0368327 0.0727535 0.198657 - -0.0350395 0.0559121 0.196432 - -0.0283152 0.0735888 0.187824 --0.00748241 0.163769 0.161042 --0.00078593 0.174239 0.152493 - 0.0039499 0.182298 0.146445 - 0.0115338 0.2045 0.136729 - 0.0129733 0.202595 0.134905 - 0.0236016 0.214011 0.121354 - 0.0287536 0.194621 0.114865 - 0.0268545 0.182699 0.117318 - 0.0320433 0.179142 0.110732 - 0.0296907 0.170948 0.11375 - 0.0223823 0.138315 0.123149 - 0.0475488 0.183081 0.0910029 - 0.0687262 0.214878 0.0639713 - 0.0465572 0.159221 0.092341 - 0.0463074 0.150467 0.0926869 - 0.0499652 0.150606 0.0880353 - 0.0492206 -0.13533 0.09214 - 0.0400275 -0.124414 0.103544 - 0.0406183 -0.127634 0.102819 - 0.0339918 -0.130175 0.111073 - 0.0241656 -0.128278 0.123294 - 0.0174548 -0.117434 0.131609 - 0.0156433 -0.156111 0.133987 - 0.0171458 -0.162739 0.132138 - 0.0132442 -0.176514 0.137037 - 0.00996134 -0.183934 0.141146 - 0.00070216 -0.170987 0.152626 --0.00117085 -0.171885 0.154959 - -0.0024532 -0.170389 0.15655 - -0.0104622 -0.159162 0.16648 - -0.0164888 -0.138657 0.173914 - -0.0205506 -0.121499 0.178913 - -0.029554 -0.0668192 0.189941 - -0.029867 -0.100907 0.19044 - -0.0309147 -0.195985 0.192047 - -0.0324965 -0.219 0.194089 - -0.0554411 -0.310803 0.222932 - -0.373756 -2.15807 0.624912 - -0.417654 -2.15566 0.679526 - -0.444093 -2.15981 0.712438 - -0.449997 -2.1569 0.719775 - -0.509608 -1.9917 0.793423 - -0.150841 -0.430058 0.34202 - -0.149346 -0.414715 0.340111 - -0.159189 -0.406152 0.35233 - -0.168792 -0.396998 0.364251 - -0.182501 -0.411011 0.381353 - -0.23318 -0.40656 0.4444 - -0.254731 -0.411856 0.471232 - -0.299722 -0.408373 0.527205 - -0.324576 -0.412472 0.558144 - -0.353101 -0.414349 0.593644 - -0.498719 -0.506545 0.775132 - -0.591031 -0.504085 0.889989 - -0.603365 -0.499565 0.905322 - -0.650317 -0.496641 0.963735 - -0.625093 -0.430592 0.932138 - -0.623923 -0.400203 0.930585 - -0.622306 -0.37506 0.928493 - -0.623332 -0.370946 0.929757 - -0.653124 -0.369799 0.966823 - -1.6706 -0.554054 2.23347 - -1.67629 -0.425507 2.24014 - -1.6735 -0.389643 2.23655 - -1.67457 -0.378206 2.23784 - -0.270131 -0.00468561 0.489095 - -0.621643 0.0622926 0.926271 - -0.617727 0.0905815 0.921308 - -0.61748 0.0946543 0.920988 - -0.618198 0.103014 0.921855 - -0.620432 0.115848 0.924594 - -0.620229 0.140804 0.924261 - -0.61883 0.148823 0.922495 - -1.68068 0.513087 2.24261 - -1.68286 0.56161 2.24516 - -1.67743 0.71735 2.2379 - -1.68401 0.883384 2.24557 - -1.68459 1.07992 2.24566 - -1.69077 1.17942 2.25304 - -1.68892 1.29029 2.25037 - -0.622257 0.616963 0.925264 - -0.619917 0.626251 0.922324 - -0.62872 0.666037 0.933149 - -0.580225 0.720037 0.872635 - -0.517649 0.727539 0.794747 - -0.490243 0.824379 0.760337 - -0.492335 0.937475 0.762578 - -0.490488 1.26233 0.759242 - -0.407169 1.27742 0.65552 - -0.393834 1.27506 0.638934 - -0.385844 1.27635 0.628989 - -0.350296 1.28155 0.584739 - -0.329674 1.27909 0.559087 - -0.300046 1.23326 0.522366 - -0.279112 1.16956 0.496522 - -0.234064 1.17148 0.440461 - -0.216491 1.16844 0.418606 - -0.172131 1.16141 0.363429 - -0.0393294 0.098465 0.201577 - -0.0367107 0.0677191 0.198417 - -0.03608 0.0597753 0.197658 - -0.0340702 0.057966 0.195162 - -0.034264 0.163987 0.195065 - -0.0329203 0.165 0.19339 - -0.0300188 0.130917 0.189888 - -0.029785 0.101879 0.18969 - -0.0298277 0.0728401 0.189836 - -0.0275461 0.0684794 0.187011 - -0.0249837 0.0921412 0.183747 - -0.0142907 0.145987 0.17027 - -0.00951 0.158633 0.164281 --0.00879101 0.157329 0.16339 --0.00628144 0.161465 0.160254 - -0.0027964 0.173418 0.15588 - 0.0278612 0.188401 0.117684 - 0.0247842 0.148744 0.12164 - 0.053892 0.182183 0.0853137 - 0.0547705 0.182369 0.0842199 - 0.0612916 0.190722 0.0760789 - 0.0488805 0.150092 0.091652 - 0.0513492 0.149274 0.0885827 - 0.0440173 0.131554 0.0977625 - 0.0477377 -0.135392 0.0960793 - 0.0386526 -0.125419 0.107115 - 0.0343994 -0.131097 0.112314 - 0.0261709 -0.124665 0.122318 - 0.0177209 -0.118126 0.132591 - 0.0167634 -0.122686 0.133771 - 0.0133306 -0.133947 0.137989 - 0.013558 -0.145032 0.137747 - 0.00924985 -0.184805 0.14312 --0.00206625 -0.174661 0.156873 - -0.0092138 -0.164044 0.165547 - -0.0117499 -0.155691 0.16861 - -0.0163931 -0.138768 0.174213 - -0.0214597 -0.114738 0.180309 - -0.0269953 -0.0745239 0.186926 - -0.0332957 -0.186991 0.194955 - -0.0348487 -0.186952 0.196847 - -0.0376351 -0.160773 0.200159 - -0.0678787 -0.402007 0.237761 - -0.271852 -2.16039 0.491779 - -0.321005 -2.15648 0.551644 - -0.348111 -2.17053 0.584709 - -0.354987 -2.17415 0.593096 - -0.36702 -2.16959 0.60774 - -0.5033 -1.96698 0.773114 - -0.505487 -1.90029 0.775569 - -0.213858 -0.416799 0.415637 - -0.221863 -0.404122 0.425348 - -0.243505 -0.404088 0.451712 - -0.261862 -0.405591 0.474079 - -0.282549 -0.412182 0.4993 - -0.294052 -0.405526 0.513291 - -0.295175 -0.403718 0.514654 - -0.331594 -0.413725 0.559051 - -0.342723 -0.417888 0.57262 - -0.34388 -0.415746 0.574023 - -0.35863 -0.398179 0.591936 - -0.360325 -0.393064 0.593985 - -0.358478 -0.380312 0.591694 - -0.604332 -0.504578 0.89158 - -0.640875 -0.509617 0.936113 - -0.663221 -0.371197 0.962898 - -1.58666 -0.724161 2.08892 - -1.62702 -0.731044 2.13812 - -1.67701 -0.717253 2.19897 - -1.70381 -0.679618 2.23149 - -1.70139 -0.654179 2.22846 - -1.70714 -0.523264 2.23505 - -1.71 -0.5002 2.23847 - -1.71139 -0.488654 2.24013 - -1.70098 -0.43827 2.22728 - -1.70219 -0.426787 2.22872 - -1.70377 -0.391849 2.23053 - -1.70485 -0.380348 2.23182 - -1.70465 -0.368563 2.23154 - -1.70597 -0.217276 2.23266 - -0.269065 -0.007866 0.481599 - -0.273559 -0.00304 0.487058 - -0.615329 0.0810247 0.903131 - -0.622032 0.122978 0.911164 - -0.62688 0.165819 0.916935 - -0.674005 0.188072 0.974272 - -1.71472 0.613791 2.24071 - -1.7126 0.698767 2.23786 - -0.829077 0.64697 1.16173 - -0.814803 0.649029 1.14434 - -0.804035 0.646874 1.13122 - -0.622286 0.626969 0.909884 - -0.620551 0.631013 0.907758 - -0.597839 0.721217 0.879807 - -0.511579 0.728548 0.774703 - -0.497156 0.879315 0.756658 - -0.494291 0.889529 0.753136 - -0.489425 0.954091 0.747005 - -0.492784 1.02459 0.750875 - -0.486705 1.1321 0.743131 - -0.493901 1.18399 0.751733 - -0.491936 1.26375 0.749088 - -0.446053 1.2755 0.693157 - -0.442809 1.27921 0.689193 - -0.373681 1.27763 0.604989 - -0.212368 1.17288 0.408811 - -0.180033 1.15945 0.369464 - -0.0339968 0.0589561 0.195034 - -0.0298814 0.0738778 0.189974 - -0.0295937 0.0708445 0.189633 - -0.0285522 0.0757342 0.188349 - -0.0283425 0.0757058 0.188093 - -0.0279234 0.0756446 0.187583 - -0.0262157 0.0844034 0.185475 - -0.0160436 0.137524 0.172916 - 0.00221739 0.179745 0.150538 - 0.00946816 0.192837 0.141664 - 0.0127853 0.194153 0.137619 - 0.0280897 0.210131 0.118925 - 0.0226028 0.165429 0.12575 - 0.0546362 0.179197 0.086684 - 0.0573993 0.178331 0.0833208 - 0.0548266 0.154333 0.0865306 - 0.0568522 0.145923 0.0840895 - 0.0496267 -0.126111 0.0958347 - 0.0344342 -0.133701 0.113978 - 0.0356274 -0.137326 0.112566 - 0.0302307 -0.129873 0.118979 - 0.0336899 -0.139589 0.114884 - 0.0284006 -0.133181 0.121172 - 0.0166204 -0.135292 0.135229 - 0.0142499 -0.132753 0.138048 - 0.0121116 -0.13787 0.140614 --0.00065676 -0.170178 0.155943 --0.00308105 -0.180507 0.158867 --0.00729188 -0.166645 0.163846 - -0.0102058 -0.156381 0.167289 - -0.0178336 -0.132178 0.176311 - -0.0187258 -0.127337 0.17736 - -0.0319711 -0.2 0.193384 - -0.0362672 -0.168865 0.198411 - -0.0398653 -0.164537 0.202688 - -0.0403759 -0.165478 0.2033 - -0.046619 -0.226836 0.210937 - -0.283791 -2.08054 0.499575 - -0.389101 -2.16146 0.625426 - -0.395161 -2.159 0.632646 - -0.454606 -2.16172 0.703552 - -0.512056 -2.11851 0.771937 - -0.503994 -1.92077 0.761706 - -0.155901 -0.409577 0.341844 - -0.165343 -0.407929 0.353099 - -0.182418 -0.405995 0.373457 - -0.217527 -0.408926 0.41534 - -0.225503 -0.411067 0.42486 - -0.230873 -0.414823 0.431276 - -0.25979 -0.408039 0.465743 - -0.280746 -0.408103 0.490737 - -0.286193 -0.402698 0.497217 - -0.293436 -0.406997 0.505869 - -0.299374 -0.409027 0.512956 - -0.344908 -0.415941 0.567285 - -0.365727 -0.394878 0.59205 - -0.368372 -0.394409 0.595203 - -0.371234 -0.379962 0.598571 - -0.528659 -0.506608 0.786721 - -0.570811 -0.503611 0.836985 - -0.586107 -0.502642 0.855225 - -0.602291 -0.506983 0.87454 - -0.610975 -0.509495 0.884906 - -0.644211 -0.485076 0.924469 - -0.642705 -0.478663 0.922653 - -0.622216 -0.457576 0.89815 - -0.636158 -0.369848 0.914506 - -1.67005 -0.753626 2.14879 - -1.74811 -0.614873 2.24145 - -1.75152 -0.458007 2.24503 - -1.75175 -0.386202 2.24508 - -1.75093 -0.138264 2.24334 - -1.75168 -0.114911 2.24416 - -0.618708 0.0644902 0.892341 - -0.623215 0.0892295 0.89764 - -0.619094 0.141225 0.892564 - -1.75723 0.511533 2.24883 - -1.76064 0.53689 2.25281 - -1.76077 0.785753 2.25219 - -1.75737 0.912907 2.24774 - -1.75586 0.938267 2.24587 - -1.75504 1.00389 2.24468 - -1.76768 1.13386 2.25935 - -1.76188 1.15776 2.25236 - -1.75793 1.19694 2.24752 - -1.76296 1.25713 2.25334 - -0.812901 0.646404 1.12214 - -0.611697 0.723594 0.881928 - -0.492693 0.781295 0.739816 - -0.4931 0.788851 0.740278 - -0.49175 0.793453 0.738654 - -0.496254 0.844572 0.743866 - -0.493167 1.10253 0.739382 - -0.440915 1.27216 0.676534 - -0.420258 1.27662 0.651883 - -0.385317 1.27476 0.610217 - -0.377416 1.27671 0.600787 - -0.332183 1.27738 0.546837 - -0.324153 1.2776 0.53726 - -0.275843 1.16151 0.480004 - -0.272587 1.16314 0.476115 - -0.264912 1.16061 0.466969 - -0.161157 1.15718 0.343234 - -0.0387698 0.085411 0.200604 - -0.0367644 0.0696527 0.198261 - -0.0303194 0.143963 0.190343 - -0.0299158 0.143948 0.189862 - -0.0296213 0.119924 0.189585 - -0.0282736 0.0747377 0.188119 - -0.0242316 0.0891148 0.183253 - -0.0191653 0.122284 0.177107 - -0.0183693 0.123085 0.176156 - -0.0151675 0.137408 0.172292 --0.00054251 0.169892 0.154748 - 0.00211129 0.181178 0.151548 - 0.00211707 0.172819 0.151567 - 0.014276 0.19165 0.137007 - 0.0189335 0.202773 0.131418 - 0.02592 0.201433 0.123089 - 0.0238239 0.169738 0.125688 - 0.0217948 0.142969 0.128191 - 0.0221956 0.142599 0.127714 - 0.0238447 0.139864 0.125756 - 0.0275962 0.140859 0.121279 - 0.057067 0.170265 0.0860383 - 0.0556518 0.161705 0.0877528 - 0.0561052 0.161106 0.0872139 - 0.048944 -0.126335 0.0986921 - 0.0342898 -0.128865 0.115807 - 0.0347988 -0.139589 0.115246 - 0.0279428 -0.132352 0.123227 - 0.0167414 -0.127902 0.13629 - 0.0146669 -0.13426 0.138731 - 0.0114898 -0.137855 0.142451 - 0.0113795 -0.139046 0.142583 - 0.00796495 -0.1747 0.146679 --0.00151095 -0.159402 0.157694 --0.00046289 -0.170389 0.156504 --0.00108652 -0.172731 0.15724 - -0.0105364 -0.156671 0.168222 - -0.0128336 -0.146158 0.170871 - -0.0183272 -0.13039 0.177236 - -0.0292045 -0.0708886 0.189751 - -0.04434 -0.193009 0.207795 - -0.0567024 -0.303525 0.222567 - -0.271571 -2.16401 0.479121 - -0.322023 -2.16042 0.538007 - -0.506672 -1.90864 0.752789 - -0.506689 -1.88398 0.752734 - -0.1482 -0.412546 0.329715 - -0.156074 -0.40596 0.338887 - -0.171276 -0.399767 0.356615 - -0.219204 -0.40811 0.412591 - -0.234266 -0.409714 0.430178 - -0.240101 -0.40656 0.43698 - -0.257809 -0.421825 0.457699 - -0.279045 -0.407818 0.482447 - -0.371056 -0.414837 0.58988 - -0.372233 -0.412554 0.591248 - -0.383202 -0.381676 0.603958 - -0.608916 -0.501626 0.867822 - -0.631961 -0.505809 0.894737 - -0.637396 -0.50511 0.90108 - -0.621318 -0.446494 0.882131 - -0.638017 -0.366556 0.901379 - -0.729807 -0.400557 1.00864 - -0.844011 -0.435272 1.14206 - -0.991565 -0.507138 1.31454 - -1.41804 -0.71175 1.81302 - -1.77746 -0.605408 2.23228 - -1.77988 -0.435748 2.23459 - -1.78204 -0.352292 2.23686 - -0.275791 -0.00790817 0.477419 - -0.271274 0.0066898 0.472101 - -0.622532 0.0641378 0.881978 - -0.619846 0.0996163 0.878733 - -0.621723 0.152337 0.880762 - -0.625516 0.165616 0.885149 - -1.79177 0.701274 2.24497 - -1.79368 0.868389 2.24669 - -0.826413 0.649695 1.11819 - -0.751341 0.645128 1.03056 - -0.502007 0.56947 0.739725 - -0.553653 0.66083 0.799735 - -0.54251 0.71872 0.786549 - -0.535562 0.721432 0.77843 - -0.508998 0.72637 0.747405 - -0.503949 0.731305 0.741494 - -0.492438 0.738768 0.728035 - -0.490122 0.754535 0.725282 - -0.490674 0.839328 0.725666 - -0.491291 0.85547 0.726336 - -0.495405 0.886463 0.731044 - -0.496065 0.920087 0.73171 - -0.49399 0.932631 0.72925 - -0.492165 0.97214 0.726997 - -0.493645 1.00253 0.728632 - -0.490627 1.14816 0.724661 - -0.491114 1.19559 0.725084 - -0.45469 1.27193 0.682329 - -0.349006 1.28149 0.558925 - -0.343538 1.27609 0.552559 - -0.327706 1.27855 0.534069 - -0.257415 1.18303 0.452306 - -0.257123 1.20086 0.45191 - -0.224796 1.16038 0.414297 - -0.180212 1.16339 0.36224 - -0.0428973 0.108732 0.205184 - -0.0388853 0.086359 0.200569 - -0.0383302 0.0824316 0.199933 - -0.0377228 0.0775049 0.199239 - -0.0393953 0.17164 0.200902 - -0.0295141 0.0789061 0.189652 - -0.0293231 0.07789 0.189432 - -0.0250117 0.0873361 0.18437 - -0.0246828 0.0882801 0.183983 - -0.0144163 0.139371 0.171841 - -0.0118935 0.142653 0.168886 - 0.00571011 0.178756 0.148225 - 0.0100696 0.19654 0.143081 - 0.0113928 0.196912 0.141535 - 0.0125099 0.19632 0.140233 - 0.0126286 0.188828 0.140117 - 0.0259234 0.207582 0.12454 - 0.0256114 0.196876 0.124937 - 0.0261852 0.194277 0.124275 - 0.0216465 0.151975 0.129703 - 0.022051 0.134295 0.129285 - 0.0290378 0.14045 0.12111 - 0.0569822 0.14161 0.0884847 - 0.0479409 -0.124533 0.102249 - 0.0429713 -0.127404 0.10791 - 0.0471264 -0.141804 0.103228 - 0.0458997 -0.144634 0.104632 - 0.0345751 -0.133882 0.117478 - 0.0380509 -0.146159 0.113563 - 0.0368613 -0.144987 0.114912 - 0.0284277 -0.133146 0.124468 - 0.0207398 -0.124036 0.133183 - 0.0196647 -0.125058 0.134409 - 0.0171226 -0.127359 0.137307 - 0.0115773 -0.139618 0.143651 - 0.0152293 -0.162371 0.139566 - 0.0174114 -0.176194 0.137127 - 0.00934948 -0.176589 0.146297 - 0.00183308 -0.164521 0.154808 - 0.00135908 -0.164738 0.155348 --0.00079864 -0.161525 0.157792 - -0.0058211 -0.167619 0.163523 --0.00678746 -0.16795 0.164623 --0.00851144 -0.166463 0.166579 - -0.0196705 -0.115651 0.179116 - -0.024615 -0.0843738 0.184645 - -0.0279492 -0.0677941 0.188387 - -0.0294588 -0.13497 0.190307 - -0.0299949 -0.159987 0.190992 - -0.0401344 -0.151412 0.202498 - -0.0541789 -0.272776 0.218838 - -0.0648192 -0.351288 0.231177 - -0.0684339 -0.36664 0.235335 - -0.331923 -2.1555 0.540417 - -0.352853 -2.1649 0.564249 - -0.47129 -2.15499 0.698916 - -0.50233 -1.84019 0.733265 - -0.148557 -0.408879 0.326586 - -0.156704 -0.407699 0.335848 - -0.1833 -0.407158 0.366093 - -0.184473 -0.406147 0.367424 - -0.185314 -0.404263 0.368375 - -0.19233 -0.406119 0.37636 - -0.199435 -0.407725 0.384446 - -0.204019 -0.406872 0.389657 - -0.209708 -0.408407 0.396131 - -0.216339 -0.400361 0.403648 - -0.248047 -0.405431 0.439725 - -0.286575 -0.407378 0.483548 - -0.299097 -0.412676 0.497805 - -0.300071 -0.406997 0.498896 - -0.359924 -0.406467 0.566965 - -0.383164 -0.408699 0.593403 - -0.649047 -0.496959 0.896056 - -0.650479 -0.492869 0.897672 - -0.635467 -0.460685 0.880502 - -0.622879 -0.431621 0.866098 - -0.649843 -0.368385 0.896571 - -0.728899 -0.39958 0.986576 - -0.787539 -0.42747 1.05335 - -0.824097 -0.436228 1.09495 - -1.65878 -0.716808 2.04508 - -1.82414 -0.687747 2.23305 - -1.82634 -0.600807 2.23529 - -1.82218 -0.513021 2.23029 - -1.81869 -0.366445 2.22589 - -1.82534 -0.319608 2.23331 - -1.82319 -0.211594 2.23053 - -0.271834 -0.0076762 0.465573 - -0.271167 0.00976586 0.464761 - -0.61749 0.0704731 0.858448 - -0.61955 0.109963 0.86067 - -0.623627 0.138627 0.86522 - -0.623194 0.166667 0.864643 - -1.84143 0.931913 2.24782 - -1.82981 1.29997 2.23348 - -0.847999 0.650894 1.11885 - -0.796851 0.642728 1.0607 - -0.793847 0.646794 1.05727 - -0.78322 0.650868 1.04517 - -0.648123 0.583588 0.891733 - -0.646442 0.587651 0.889808 - -0.492962 0.480252 0.715581 - -0.482829 0.573218 0.703776 - -0.487154 0.61011 0.708584 - -0.49605 0.638585 0.718614 - -0.530895 0.717124 0.758005 - -0.494246 0.744173 0.716243 - -0.492194 0.753919 0.71388 - -0.49071 0.880843 0.711807 - -0.492917 0.9011 0.714256 - -0.493232 0.960808 0.714434 - -0.485904 0.981022 0.706038 - -0.493381 1.04483 0.714349 - -0.496469 1.25428 0.717226 - -0.433958 1.27399 0.646073 - -0.348273 1.27797 0.548612 - -0.0409975 0.104051 0.202706 - -0.0404361 0.101137 0.202076 - -0.0388796 0.0863122 0.200351 - -0.035014 0.053755 0.196053 - -0.0408988 0.167433 0.202402 - -0.0382786 0.162703 0.199436 - -0.0347195 0.149933 0.195427 - -0.0301656 0.130978 0.190305 - -0.0291499 0.0779073 0.189311 - -0.0285054 0.0718423 0.188596 - -0.0276814 0.0757612 0.187647 - -0.0263302 0.0795915 0.186099 - -0.0250306 0.0844034 0.184606 - -0.0135187 0.13827 0.171351 --0.00867329 0.154078 0.165792 --0.00734281 0.153607 0.164281 --0.00580852 0.160243 0.162515 - 0.00054449 0.173206 0.155251 - 0.00104354 0.172991 0.154684 - 0.0208624 0.199636 0.132064 - 0.0250775 0.178275 0.127334 - 0.0248272 0.166184 0.127656 - 0.022729 0.148625 0.130095 - 0.0292671 0.146244 0.122667 - 0.0807107 0.192357 0.0640206 - 0.0547429 -0.133171 0.0965688 - 0.0419193 -0.123657 0.110822 - 0.0379559 -0.131223 0.115258 - 0.0424839 -0.157357 0.110294 - 0.0142837 -0.152611 0.141686 - 0.0067919 -0.171936 0.150087 - 0.00407494 -0.166938 0.153098 --0.00263254 -0.170803 0.160579 - -0.0195806 -0.115727 0.179289 - -0.0231464 -0.094249 0.183196 - -0.0243322 -0.0864042 0.184493 - -0.0260091 -0.0736001 0.186322 - -0.0289906 -0.0829382 0.189671 - -0.0348332 -0.141886 0.196354 - -0.0356391 -0.118803 0.197182 - -0.036417 -0.120735 0.198055 - -0.381153 -2.15308 0.588064 - -0.427074 -2.1475 0.639189 - -0.490634 -2.15762 0.710004 - -0.500841 -1.91246 0.720638 - -0.152681 -0.404689 0.328386 - -0.1511 -0.394792 0.326594 - -0.157902 -0.407699 0.334209 - -0.183622 -0.408161 0.362854 - -0.191233 -0.407375 0.371328 - -0.226406 -0.406385 0.410496 - -0.22759 -0.405103 0.411811 - -0.245455 -0.403591 0.431703 - -0.267973 -0.408039 0.456794 - -0.29937 -0.412297 0.491772 - -0.32548 -0.410924 0.520847 - -0.333008 -0.410487 0.529229 - -0.344282 -0.41109 0.541786 - -0.390588 -0.401682 0.593328 - -0.425775 -0.398274 0.632505 - -0.641121 -0.459786 0.872516 - -0.61692 -0.399126 0.845382 - -0.622504 -0.375239 0.85153 - -1.51775 -0.700229 1.84952 - -0.722784 -0.276701 0.962914 - -1.86715 -0.670652 2.23855 - -1.86001 -0.370603 2.2297 - -1.86145 -0.153574 2.23065 - -1.8637 -0.105775 2.23301 - -0.269702 -0.00752858 0.457521 - -0.273745 0.00659891 0.46198 - -0.507813 0.152085 0.722222 - -0.521509 0.228276 0.737247 - -0.524626 0.236806 0.740692 - -0.52232 0.271543 0.738021 - -0.524479 0.280071 0.740399 - -0.52845 0.3086 0.744736 - -0.498132 0.367876 0.710794 - -0.531321 0.406605 0.74764 - -0.521817 0.419835 0.737016 - -0.542088 0.506128 0.759333 - -0.495289 0.486322 0.707273 - -0.495162 0.577277 0.706859 - -0.493446 0.595818 0.704893 - -0.490439 0.613108 0.701493 - -0.492199 0.739166 0.703076 - -0.494382 0.961404 0.704841 - -0.489421 1.09532 0.698916 - -0.489511 1.22199 0.698636 - -0.489797 1.27426 0.698799 - -0.432944 1.27119 0.635492 - -0.382151 1.27947 0.5789 - -0.368238 1.27596 0.563416 - -0.219111 1.16413 0.397671 - -0.042933 0.103572 0.20464 - -0.0408263 0.0949556 0.202319 - -0.0361431 0.147834 0.196946 - -0.0358328 0.15186 0.196588 - -0.0345044 0.151932 0.195108 - -0.0302752 0.125988 0.190476 - -0.0287374 0.0738956 0.188919 - -0.028426 0.0708643 0.188581 - -0.0243341 0.0853512 0.183981 - -0.0175906 0.12327 0.176358 - -0.0172313 0.123179 0.175958 - -0.0126106 0.135088 0.170776 - 0.00841153 0.18351 0.147219 - 0.0140347 0.186949 0.140946 - 0.0183864 0.199457 0.136063 - 0.0195484 0.198797 0.13477 - 0.0244168 0.196927 0.129354 - 0.0233166 0.162462 0.130683 - 0.0245657 0.155856 0.129311 - 0.026488 0.142707 0.12721 - 0.035998 0.153803 0.116586 - 0.0531497 0.177385 0.0974135 - 0.0748482 0.20171 0.0731755 - 0.0766062 0.199609 0.0712239 - 0.0783458 0.197473 0.069293 - 0.0793299 0.192301 0.0682125 - 0.0411448 -0.105679 0.113299 - 0.0529915 -0.131925 0.100457 - 0.0478597 -0.129391 0.106046 - 0.0440361 -0.136858 0.110238 - 0.0203564 -0.124872 0.136026 - 0.0205842 -0.130494 0.135794 - 0.0123651 -0.126849 0.144747 - 0.017524 -0.181483 0.139283 - 0.0156154 -0.183637 0.14137 - 0.00106125 -0.16441 0.157185 - -0.0046414 -0.167619 0.163414 --0.00612577 -0.16811 0.165034 - -0.0171919 -0.127426 0.176982 - -0.0239552 -0.0833811 0.184227 - -0.0267469 -0.0667232 0.187222 - -0.0272294 -0.0687911 0.187754 - -0.0287844 -0.0649273 0.189439 - -0.0291673 -0.0649516 0.189856 - -0.0298962 -0.153995 0.190915 - -0.038434 -0.135524 0.200171 - -0.0409085 -0.155271 0.202928 - -0.28085 -2.11411 0.470389 - -0.392791 -2.15948 0.592599 - -0.425268 -2.15104 0.627992 - -0.472653 -2.14738 0.679657 - -0.506969 -2.14485 0.717071 - -0.14842 -0.415785 0.320944 - -0.160619 -0.403315 0.33421 - -0.194005 -0.406323 0.370628 - -0.199352 -0.40738 0.376462 - -0.207246 -0.402371 0.385056 - -0.222832 -0.406092 0.402064 - -0.265052 -0.409603 0.448117 - -0.282142 -0.405968 0.466744 - -0.333512 -0.410432 0.522778 - -0.411021 -0.38286 0.607222 - -0.412709 -0.380958 0.609058 - -0.462807 -0.42287 0.663816 - -0.528154 -0.441882 0.735136 - -0.515083 -0.356883 0.720629 - -0.526729 -0.353539 0.73332 - -0.528621 -0.323675 0.735295 - -0.487483 -0.193282 0.690046 - -0.486753 -0.189789 0.689239 - -0.480961 -0.171777 0.68287 - -0.488458 -0.137271 0.690944 - -0.489453 -0.113059 0.691957 - -0.488061 -0.10061 0.690402 - -0.490381 -0.0829863 0.69288 - -0.489065 -0.0528595 0.691356 - -0.49793 0.054874 0.700705 - -0.503011 0.117361 0.706061 - -0.498668 0.160218 0.701198 - -0.495742 0.165545 0.697991 - -0.499676 0.205846 0.702161 - -0.501702 0.216684 0.70434 - -0.495107 0.295372 0.696915 - -0.495832 0.302961 0.697683 - -0.50135 0.328536 0.703625 - -0.497627 0.344519 0.699517 - -0.494863 0.388527 0.696373 - -0.495431 0.450647 0.696809 - -0.496773 0.469316 0.698217 - -0.500111 0.48158 0.70182 - -0.499439 0.522276 0.700968 - -0.490316 0.617052 0.690738 - -0.489712 0.690204 0.689862 - -0.496145 0.731054 0.696757 - -0.491824 0.737018 0.692028 - -0.489346 1.10466 0.688237 - -0.492592 1.13452 0.691689 - -0.497374 1.25509 0.696547 - -0.4338 1.2747 0.627159 - -0.411106 1.27452 0.602411 - -0.169765 1.12687 0.339656 - -0.0410428 0.0989121 0.202322 - -0.0372065 0.0744474 0.198211 - -0.0410163 0.167371 0.202091 - -0.040029 0.167491 0.201013 - -0.0367326 0.146769 0.19748 - -0.0362998 0.146804 0.197008 - -0.0340911 0.144935 0.194605 - -0.0282305 0.0728794 0.188427 --0.00664903 0.150691 0.164661 - 0.0142042 0.189422 0.141805 - 0.0248892 0.202633 0.130114 - 0.0238461 0.184833 0.131304 - 0.0507913 0.176275 0.101945 - 0.0569212 0.180886 0.095246 - 0.064726 0.184748 0.0867232 - 0.0934879 0.215821 0.0552653 - 0.0458678 -0.115895 0.109864 - 0.0506465 -0.137963 0.104822 - 0.0411729 -0.127394 0.114914 - 0.03283 -0.14016 0.123866 - 0.0214802 -0.129299 0.135961 - 0.015562 -0.118124 0.142252 - 0.0136763 -0.142001 0.144337 - 0.0152601 -0.176789 0.142747 - 0.014733 -0.177079 0.143311 - 0.0108825 -0.17591 0.147422 - 0.0103579 -0.176172 0.147983 --0.00013358 -0.163081 0.159155 - -0.0029071 -0.168249 0.162133 --0.00340874 -0.168423 0.16267 --0.00502056 -0.16486 0.164382 - -0.0161522 -0.129312 0.176172 - -0.0170285 -0.128501 0.177106 - -0.0206107 -0.107024 0.180871 - -0.0229162 -0.0913222 0.183288 - -0.0231885 -0.0913699 0.183579 - -0.0272617 -0.0698329 0.187868 - -0.0273329 -0.072847 0.187953 - -0.0290444 -0.085972 0.189821 - -0.0344151 -0.129872 0.195688 - -0.0345631 -0.111842 0.195793 - -0.0355632 -0.111755 0.196861 - -0.0420108 -0.160105 0.203892 - -0.363517 -2.16587 0.553295 - -0.506406 -2.05906 0.705661 - -0.503718 -1.90895 0.70235 - -0.151092 -0.401692 0.321154 - -0.156842 -0.411069 0.327325 - -0.1696 -0.40437 0.340937 - -0.172008 -0.402573 0.343505 - -0.203224 -0.408835 0.376878 - -0.237966 -0.410549 0.414005 - -0.257322 -0.410091 0.434686 - -0.324692 -0.408569 0.506668 - -0.335568 -0.409082 0.518291 - -0.359356 -0.407353 0.543703 - -0.408707 -0.383775 0.596366 - -0.494525 -0.41995 0.688169 - -0.494807 -0.388043 0.688377 - -0.493473 -0.190601 0.686373 - -0.497905 -0.157418 0.691012 - -0.502168 -0.143066 0.695526 - -0.505328 -0.118886 0.698831 - -0.502987 -0.115196 0.696319 - -0.500403 -0.0778369 0.693449 - -0.498435 -0.0563917 0.691282 - -0.498912 -0.0474247 0.691766 - -0.497482 -0.0323206 0.690194 - -0.499766 0.0274702 0.692459 - -0.50154 0.0366124 0.694329 - -0.502795 0.0397333 0.695661 - -0.508253 0.120576 0.701255 - -0.499341 0.146244 0.691658 - -0.499127 0.152438 0.691411 - -0.505535 0.160894 0.698234 - -0.503709 0.176256 0.696237 - -0.497243 0.262462 0.689076 - -0.50156 0.29996 0.693579 - -0.502257 0.322113 0.694259 - -0.497859 0.35995 0.689448 - -0.499118 0.392012 0.690701 - -0.497916 0.406974 0.689372 - -0.494576 0.466644 0.685628 - -0.497947 0.478858 0.689195 - -0.495441 0.507872 0.686432 - -0.493926 0.51083 0.684805 - -0.495213 0.521592 0.686148 - -0.490159 0.632225 0.680424 - -0.489168 0.725261 0.679093 - -0.493519 0.785327 0.683566 - -0.486268 0.815143 0.675731 - -0.493383 0.922255 0.68302 - -0.49345 0.930859 0.683066 - -0.497041 1.01026 0.686672 - -0.490982 1.02577 0.680152 - -0.495206 1.09659 0.684458 - -0.493308 1.21883 0.682072 - -0.494054 1.25928 0.682751 - -0.42565 1.27962 0.609601 - -0.366889 1.27749 0.54682 - -0.26622 1.1585 0.439603 - -0.25541 1.20043 0.427929 - -0.235656 1.17492 0.406897 - -0.218312 1.15949 0.38841 - -0.0433824 0.107439 0.204575 - -0.0356231 0.0605823 0.196421 - -0.0350509 0.0556445 0.195824 - -0.034885 0.0556715 0.195647 - -0.0345198 0.0577369 0.19525 - -0.03887 0.158571 0.199604 - -0.0333612 0.142953 0.193763 - -0.030786 0.125 0.191064 - -0.0254326 0.0846376 0.185462 - -0.0234843 0.0933878 0.183355 - -0.0231266 0.0943332 0.18297 - -0.0092101 0.142516 0.167959 - 0.00021985 0.163784 0.15782 - 0.00691895 0.180701 0.150613 - 0.00881397 0.184025 0.148578 - 0.0107515 0.187313 0.146498 - 0.0191597 0.195711 0.137489 - 0.0240609 0.193956 0.132258 - 0.021491 0.178189 0.13505 - 0.0259716 0.135509 0.130387 - 0.0544782 0.174944 0.0998121 - 0.0747978 0.201399 0.078023 - 0.0854649 0.212004 0.066594 - 0.0978111 0.224314 0.0533659 - 0.0598638 0.137297 0.0941677 - 0.037098 -0.0992124 0.120758 - 0.0476651 -0.121979 0.109779 - 0.0473922 -0.130382 0.110089 - 0.0452619 -0.129065 0.112312 - 0.0357378 -0.122211 0.122246 - 0.0319446 -0.137216 0.126255 - 0.0232548 -0.123871 0.135299 - 0.0158013 -0.126601 0.143097 - 0.0182998 -0.134876 0.140509 - 0.00121355 -0.16385 0.158452 --0.00192786 -0.1671 0.161744 --0.00359804 -0.166645 0.163489 --0.00475446 -0.165997 0.164696 --0.00662431 -0.160441 0.166634 - -0.0148186 -0.133164 0.17512 - -0.020866 -0.10312 0.181353 - -0.0249046 -0.0806326 0.185509 - -0.0271629 -0.0688554 0.187836 - -0.0282695 -0.0739449 0.189007 - -0.0341181 -0.116861 0.195244 - -0.0380583 -0.129497 0.199399 - -0.0451263 -0.182708 0.20694 - -0.0493353 -0.21822 0.211442 - -0.0647633 -0.317011 0.227853 - -0.352622 -2.16031 0.534055 - -0.510214 -1.94019 0.698132 - -0.165417 -0.406072 0.333314 - -0.182034 -0.404974 0.350679 - -0.1886 -0.405418 0.357543 - -0.207517 -0.402954 0.377307 - -0.222474 -0.412657 0.392969 - -0.248774 -0.408556 0.420446 - -0.272853 -0.411123 0.445621 - -0.278835 -0.410242 0.45187 - -0.296451 -0.405929 0.47027 - -0.326838 -0.414398 0.502055 - -0.330334 -0.412008 0.505701 - -0.362515 -0.414152 0.539344 - -0.38974 -0.413593 0.567798 - -0.409255 -0.413047 0.588193 - -0.410501 -0.410648 0.589488 - -0.416277 -0.380049 0.595437 - -0.501304 -0.425559 0.684438 - -0.499651 -0.41995 0.682694 - -0.495617 -0.412284 0.678455 - -0.499856 -0.380141 0.682794 - -0.502321 -0.358957 0.685308 - -0.503403 -0.355972 0.686431 - -0.501394 -0.328379 0.684251 - -0.50437 -0.31218 0.687315 - -0.503373 -0.300756 0.686239 - -0.503349 -0.28307 0.686164 - -0.505048 -0.277084 0.687921 - -0.508018 -0.200974 0.690806 - -0.499609 -0.181456 0.68196 - -0.501224 -0.17255 0.683622 - -0.499022 -0.156073 0.681273 - -0.502128 -0.135287 0.68446 - -0.504457 -0.111217 0.686824 - -0.504792 -0.108223 0.687166 - -0.503385 -0.101787 0.685676 - -0.503298 -0.0714183 0.685497 - -0.283336 0.00665344 0.455368 - -0.371711 0.0154447 0.547712 - -0.506145 0.0335569 0.688169 - -0.501956 0.183221 0.683359 - -0.505078 0.200576 0.686571 - -0.501962 0.2155 0.683271 - -0.500619 0.228001 0.681831 - -0.501807 0.318303 0.682812 - -0.498993 0.349391 0.679781 - -0.494731 0.399807 0.67518 - -0.500591 0.412918 0.681267 - -0.495311 0.432726 0.675691 - -0.496806 0.481311 0.677114 - -0.494423 0.553238 0.674414 - -0.491758 0.574912 0.671566 - -0.490336 0.676643 0.669786 - -0.490847 0.739168 0.670139 - -0.492879 0.928112 0.671716 - -0.495052 0.967564 0.673873 - -0.49331 0.972952 0.672037 - -0.491692 0.987865 0.670303 - -0.491877 1.18969 0.669912 - -0.493664 1.20658 0.671731 - -0.385072 1.28213 0.558013 - -0.325704 1.27201 0.495991 - -0.285462 1.18353 0.454186 - -0.271712 1.15508 0.439897 - -0.259445 1.16962 0.427033 - -0.254782 1.20571 0.422055 - -0.205776 1.21224 0.370815 - -0.0426869 0.100463 0.203572 - -0.0405329 0.0948931 0.201336 - -0.0353984 0.0686271 0.196046 - -0.0412337 0.161265 0.201877 - -0.0367762 0.148728 0.197254 - -0.0363275 0.148766 0.196785 - -0.0304645 0.124 0.190729 - -0.0301133 0.112998 0.190393 - -0.0191454 0.112808 0.17893 - -0.0160882 0.124257 0.175702 - -0.0102082 0.140961 0.169508 - -0.0089338 0.140564 0.168177 - 0.00373271 0.169892 0.154853 - 0.00522237 0.174467 0.153283 - 0.0140657 0.195591 0.143979 - 0.0219971 0.203202 0.135667 - 0.0235442 0.16761 0.134153 - 0.0245543 0.16692 0.133099 - 0.0237469 0.160827 0.13396 - 0.0247161 0.160135 0.13295 - 0.0479134 0.163425 0.108694 - 0.0778359 0.20605 0.077296 - 0.0971592 0.225988 0.0570417 - 0.0978034 0.213447 0.0564047 - 0.099902 0.209429 0.0542229 - 0.0504054 -0.126661 0.108645 - 0.0516198 -0.13316 0.10742 - 0.0424909 -0.119319 0.116727 - 0.0300242 -0.118179 0.129488 - 0.0273715 -0.117198 0.132201 - 0.0263279 -0.130162 0.133307 - 0.0223122 -0.133546 0.137428 - 0.0120268 -0.114207 0.147903 - 0.0134201 -0.141003 0.146553 - 0.0133895 -0.144295 0.146594 - 0.0174642 -0.165721 0.142484 - 0.0162026 -0.167523 0.14378 - 0.00462681 -0.161651 0.155616 --0.00132832 -0.164009 0.16172 - -0.0104261 -0.150458 0.170996 - -0.0164902 -0.121499 0.177122 - -0.0280222 -0.0799531 0.18881 - -0.0313092 -0.111981 0.192267 - -0.0359286 -0.122694 0.197027 - -0.0363027 -0.122655 0.19741 - -0.0522542 -0.235802 0.214066 - -0.0754461 -0.371224 0.238199 - -0.342084 -2.16042 0.516321 - -0.383898 -2.16247 0.559138 - -0.430977 -2.15166 0.607311 - -0.474563 -2.15688 0.651951 - -0.482542 -2.16076 0.660131 - -0.505587 -2.07174 0.683472 - -0.505234 -1.90068 0.68262 - -0.152665 -0.435648 0.317445 - -0.155458 -0.409012 0.320229 - -0.164135 -0.403315 0.329097 - -0.172766 -0.406156 0.337942 - -0.174542 -0.398116 0.339736 - -0.185611 -0.406638 0.351094 - -0.228007 -0.408973 0.394509 - -0.232509 -0.410559 0.399123 - -0.239554 -0.409455 0.406333 - -0.245367 -0.405736 0.412274 - -0.283847 -0.410912 0.451687 - -0.301416 -0.409553 0.469671 - -0.309802 -0.407687 0.478252 - -0.325459 -0.412086 0.494295 - -0.367049 -0.412048 0.536878 - -0.388225 -0.411484 0.558558 - -0.402181 -0.408699 0.572838 - -0.409539 -0.41302 0.580384 - -0.414143 -0.41425 0.585101 - -0.416661 -0.40943 0.587665 - -0.506506 -0.296173 0.67933 - -0.503607 -0.22638 0.676162 - -0.502994 -0.18094 0.675404 - -0.503543 -0.152892 0.675886 - -0.498897 -0.114839 0.671021 - -0.499588 -0.108977 0.671711 - -0.500466 -0.0941482 0.672568 - -0.504765 -0.0859524 0.676946 - -0.505523 -0.0770495 0.677697 - -0.501906 -0.028996 0.673856 - -0.275281 0.00484944 0.441727 - -0.499775 0.0327776 0.671497 - -0.500641 0.0951267 0.672206 - -0.504258 0.107963 0.675872 - -0.505109 0.163672 0.676584 - -0.504122 0.185403 0.675512 - -0.503834 0.240499 0.675058 - -0.507267 0.259128 0.67852 - -0.502918 0.266937 0.674045 - -0.503915 0.284724 0.675015 - -0.504739 0.292208 0.675837 - -0.505282 0.317457 0.676321 - -0.50326 0.352805 0.674149 - -0.500856 0.369888 0.671639 - -0.501705 0.382117 0.672473 - -0.497752 0.426564 0.668299 - -0.499812 0.506613 0.670179 - -0.494267 0.533142 0.664426 - -0.4955 0.584003 0.665542 - -0.492211 0.595336 0.662142 - -0.489838 0.680971 0.659468 - -0.494515 0.956877 0.663467 - -0.491261 1.0546 0.659855 - -0.490876 1.22491 0.658974 - -0.467399 1.28033 0.634778 - -0.384112 1.28248 0.549497 - -0.348902 1.28421 0.513442 - -0.332854 1.27204 0.497046 - -0.0409727 0.0927219 0.201575 - -0.0395282 0.09001 0.200104 - -0.0439811 0.179938 0.204406 - -0.0390989 0.15348 0.199483 - -0.0380048 0.150593 0.198371 - -0.0353329 0.140812 0.195663 - -0.0317258 0.127982 0.192007 - -0.0308963 0.120996 0.191177 - -0.0268332 0.0768528 0.187144 - -0.0178228 0.114637 0.17781 - -0.0136693 0.133916 0.173502 - -0.0113761 0.13839 0.171142 --0.00535475 0.153924 0.164932 - 0.0242156 0.200325 0.134523 - 0.0202292 0.165935 0.138703 - 0.0203132 0.160417 0.138633 - 0.0246413 0.166362 0.134185 - 0.0226569 0.15331 0.136254 - 0.0201743 0.132649 0.138855 - 0.0260877 0.130045 0.132808 - 0.0958834 0.226825 0.0610695 - 0.100652 0.217285 0.0562139 - 0.0297339 -0.085651 0.130953 - 0.0379429 -0.103609 0.122773 - 0.0474878 -0.129065 0.113275 - 0.0311286 -0.122935 0.12966 - 0.0283959 -0.120742 0.132394 - 0.0295921 -0.130422 0.131222 - 0.0241393 -0.129299 0.136686 - 0.0237409 -0.12963 0.137087 - 0.0233414 -0.129958 0.137488 - 0.0190245 -0.123072 0.141797 - 0.0186055 -0.124545 0.142221 - 0.017837 -0.125135 0.142994 - 0.0174514 -0.125427 0.143381 - 0.0136961 -0.119173 0.147129 - 0.012548 -0.126667 0.148301 - 0.0167017 -0.162304 0.144237 - 0.0123228 -0.177379 0.14867 - 0.0108882 -0.173836 0.150099 - 0.00842615 -0.170754 0.152559 - 0.00726918 -0.168121 0.153711 --0.00191106 -0.166476 0.162911 - -0.0178804 -0.114811 0.178777 - -0.0252257 -0.0757434 0.186031 - -0.0271644 -0.0739172 0.18797 - -0.0286536 -0.0819884 0.189486 - -0.0323262 -0.108931 0.193245 - -0.0341994 -0.113812 0.195137 - -0.0734194 -0.362639 0.235166 - -0.40807 -2.15948 0.575799 - -0.43555 -2.15456 0.603338 - -0.442373 -2.15297 0.610175 - -0.506189 -2.11573 0.674056 - -0.512222 -1.9632 0.679673 - -0.161731 -0.411165 0.323851 - -0.16961 -0.402551 0.331727 - -0.173643 -0.400804 0.335765 - -0.1752 -0.400796 0.337326 - -0.221609 -0.407221 0.383878 - -0.263938 -0.406314 0.426317 - -0.270044 -0.409544 0.432448 - -0.293671 -0.408179 0.456134 - -0.320998 -0.405526 0.483527 - -0.324268 -0.406508 0.486809 - -0.400921 -0.41441 0.563688 - -0.402754 -0.412724 0.565521 - -0.429709 -0.415278 0.592556 - -0.502699 -0.382591 0.665648 - -0.50402 -0.309319 0.666764 - -0.498804 -0.281624 0.661456 - -0.501667 -0.252832 0.664245 - -0.501891 -0.246295 0.664451 - -0.505035 -0.215049 0.667516 - -0.505698 -0.212109 0.668172 - -0.504295 -0.205048 0.666745 - -0.506162 -0.196229 0.668592 - -0.503169 -0.0997274 0.665317 - -0.507842 -0.0886572 0.669972 - -0.507661 -0.0646832 0.669722 - -0.505939 -0.0585143 0.667979 - -0.491974 -0.0223835 0.653874 - -0.272647 -0.002752 0.433906 - -0.272658 0.00175091 0.433904 - -0.505342 0.0594064 0.667046 - -0.503633 0.0739725 0.665291 - -0.500413 0.194685 0.661721 - -0.496624 0.231263 0.657818 - -0.506324 0.266203 0.667445 - -0.505677 0.332647 0.666607 - -0.502573 0.341432 0.663471 - -0.497988 0.360258 0.65882 - -0.497823 0.414347 0.658502 - -0.49578 0.479523 0.656268 - -0.501243 0.50772 0.661667 - -0.497079 0.517019 0.657465 - -0.4946 0.567072 0.654838 - -0.493147 0.638953 0.653177 - -0.490204 0.646053 0.650206 - -0.494713 0.658086 0.654693 - -0.492549 0.672365 0.652483 - -0.495091 0.750813 0.65481 - -0.485286 0.802967 0.644831 - -0.496021 0.829259 0.65552 - -0.496127 0.844437 0.655583 - -0.491719 0.859359 0.651121 - -0.490297 0.921643 0.649519 - -0.466535 1.27944 0.62468 - -0.451391 1.27742 0.609501 - -0.429634 1.28367 0.587668 - -0.421715 1.28854 0.579715 - -0.316994 1.26603 0.474778 - -0.257014 1.21677 0.414777 - -0.0413042 0.094625 0.20167 - -0.0370435 0.0753131 0.197453 - -0.0357679 0.13675 0.196 - -0.0353465 0.136785 0.195577 - -0.0330083 0.127925 0.193258 - -0.0241952 0.0826119 0.18455 - -0.0227825 0.0874269 0.183119 --0.00755205 0.142516 0.167692 --0.00478726 0.150848 0.164897 --0.00186475 0.159099 0.161943 - 0.00973675 0.183569 0.150241 - 0.0249514 0.197192 0.134947 - 0.0193937 0.160434 0.140624 - 0.0227148 0.156093 0.137306 - 0.0238395 0.142982 0.136216 - 0.0241042 0.133647 0.135977 - 0.0228628 0.125419 0.137245 - 0.029542 0.137214 0.130514 - 0.0589311 0.173038 0.100945 - 0.104703 0.235336 0.0548743 - 0.0961007 0.199813 0.0636006 - 0.034086 -0.0921399 0.127908 - 0.0325276 -0.09146 0.129437 - 0.0460657 -0.1294 0.116247 - 0.0456628 -0.129859 0.116644 - 0.0322049 -0.116622 0.129825 - 0.0298596 -0.115304 0.132125 - 0.0221173 -0.120056 0.139742 - 0.0217435 -0.120369 0.14011 - 0.0213687 -0.120679 0.140479 - 0.0146667 -0.158486 0.147168 - 0.0156613 -0.170796 0.146226 - 0.0137395 -0.180225 0.14814 - 0.0131784 -0.180486 0.148692 --0.00334433 -0.164044 0.164874 --0.00604255 -0.163814 0.167524 --0.00751149 -0.157082 0.168948 - -0.0120292 -0.140952 0.17334 - -0.0157555 -0.123559 0.176951 - -0.0220592 -0.0864042 0.183038 - -0.0272867 -0.0669382 0.188118 - -0.0308401 -0.0959754 0.19169 - -0.0681252 -0.335538 0.228982 - -0.384599 -2.1676 0.544958 - -0.397921 -2.16217 0.558028 - -0.460926 -2.15353 0.619886 - -0.506216 -2.00426 0.663952 - -0.507146 -1.89704 0.664565 - -0.156647 -0.406267 0.316127 - -0.171993 -0.410602 0.331212 - -0.186582 -0.402256 0.345517 - -0.191866 -0.407289 0.350721 - -0.201407 -0.401835 0.360077 - -0.208276 -0.401791 0.366824 - -0.210287 -0.402381 0.3688 - -0.238327 -0.403486 0.396344 - -0.255318 -0.409346 0.413049 - -0.265679 -0.409314 0.423226 - -0.272221 -0.409544 0.429652 - -0.280195 -0.411883 0.43749 - -0.368278 -0.412971 0.524009 - -0.374636 -0.413346 0.530254 - -0.384691 -0.410543 0.540122 - -0.434821 -0.412799 0.589367 - -0.439475 -0.394933 0.593888 - -0.502416 -0.394235 0.655706 - -0.498728 -0.38728 0.652064 - -0.503105 -0.360249 0.656287 - -0.503523 -0.331041 0.656616 - -0.502674 -0.281234 0.655642 - -0.504534 -0.242008 0.657359 - -0.505455 -0.178359 0.658086 - -0.504927 -0.123071 0.657412 - -0.501071 -0.10129 0.653563 - -0.503338 -0.0781496 0.655725 - -0.270558 -0.002704 0.426878 - -0.50502 0.0441735 0.657035 - -0.504414 0.0557994 0.656407 - -0.50832 0.0621596 0.660225 - -0.504383 0.0999591 0.656252 - -0.507165 0.130618 0.658899 - -0.502882 0.162821 0.654602 - -0.506707 0.185949 0.658295 - -0.506128 0.188865 0.657717 - -0.504942 0.194685 0.656536 - -0.504524 0.229683 0.656028 - -0.508119 0.251235 0.659498 - -0.502592 0.299074 0.653935 - -0.50137 0.319362 0.652678 - -0.502573 0.327332 0.653837 - -0.497585 0.345496 0.648888 - -0.503697 0.387884 0.654771 - -0.501468 0.47201 0.652347 - -0.496677 0.498026 0.647568 - -0.498751 0.513938 0.64956 - -0.498272 0.518038 0.649079 - -0.500037 0.543688 0.65074 - -0.498284 0.551345 0.648997 - -0.492475 0.579121 0.643214 - -0.495733 0.593501 0.646373 - -0.488935 0.666574 0.639491 - -0.490349 0.704567 0.640774 - -0.49065 0.743102 0.640961 - -0.488909 0.780578 0.639146 - -0.48967 0.839834 0.639728 - -0.488962 0.918735 0.638811 - -0.491199 1.03424 0.640684 - -0.492092 1.19214 0.641118 - -0.407321 1.27533 0.557624 - -0.398301 1.27618 0.548762 - -0.281923 1.17136 0.43475 - -0.197936 1.20757 0.352156 - -0.0422806 0.101448 0.202373 - -0.0400633 0.0989121 0.200202 - -0.0422576 0.169081 0.202161 - -0.0414419 0.165176 0.20137 - -0.0405121 0.159274 0.200474 - -0.0371711 0.143611 0.197236 - -0.0295068 0.0859998 0.18987 - -0.029239 0.0859987 0.189607 - -0.0255689 0.0788034 0.186022 - -0.0135976 0.130077 0.17412 - 0.0177819 0.192837 0.143123 - 0.0183822 0.192545 0.142535 - 0.0203581 0.166867 0.140666 - 0.025161 0.157233 0.135976 - 0.0240767 0.152413 0.137054 - 0.0375208 0.147525 0.123863 - 0.0410616 0.153838 0.120368 - 0.0482541 0.154266 0.113302 - 0.0629259 0.175146 0.0988328 - 0.0967486 0.220578 0.0654849 - 0.101918 0.227569 0.0603878 - 0.0590732 0.13429 0.102731 - 0.0320917 -0.0852834 0.13142 - 0.0428563 -0.121652 0.121224 - 0.0366175 -0.118275 0.127182 - 0.0234981 -0.124445 0.139748 - 0.0214215 -0.128358 0.141745 - 0.0202043 -0.129257 0.142912 - 0.012016 -0.113698 0.150701 - 0.0189922 -0.162017 0.144162 - 0.0169254 -0.161008 0.146136 - 0.0076618 -0.165477 0.155009 - 0.00196567 -0.159408 0.160441 - 0.00012784 -0.167276 0.162221 --0.00319609 -0.167289 0.1654 - -0.0188085 -0.10306 0.180156 - -0.0192287 -0.102128 0.180555 - -0.0241161 -0.0767117 0.18516 - -0.0248965 -0.0757949 0.185904 - -0.0256137 -0.0758614 0.18659 - -0.0336172 -0.105797 0.194328 - -0.0346177 -0.105703 0.195285 - -0.0427937 -0.168893 0.20328 - -0.452196 -2.15683 0.600384 - -0.481361 -2.15581 0.628278 - -0.505095 -1.84046 0.650107 - -0.166168 -0.403248 0.321939 - -0.178939 -0.407929 0.334168 - -0.21045 -0.406285 0.364304 - -0.247472 -0.408942 0.399723 - -0.251763 -0.405736 0.40382 - -0.267438 -0.407761 0.418818 - -0.301511 -0.401057 0.451391 - -0.319908 -0.39572 0.468973 - -0.355512 -0.410487 0.50307 - -0.375965 -0.410101 0.522633 - -0.401533 -0.406369 0.547079 - -0.424588 -0.412446 0.569148 - -0.439089 -0.412212 0.583018 - -0.444031 -0.409558 0.587738 - -0.451738 -0.383379 0.595038 - -0.482201 -0.387889 0.624188 - -0.501305 -0.396385 0.642486 - -0.503442 -0.327031 0.644337 - -0.506792 -0.32216 0.647529 - -0.508439 -0.29852 0.649038 - -0.504822 -0.272374 0.645506 - -0.498648 -0.258917 0.639563 - -0.502533 -0.247881 0.643249 - -0.505129 -0.213669 0.645638 - -0.507767 -0.202132 0.648129 - -0.507712 -0.19895 0.648068 - -0.505036 -0.115692 0.645277 - -0.506101 -0.107057 0.646272 - -0.507626 -0.077916 0.64765 - -0.510052 -0.0548321 0.649907 - -0.511665 -0.0520822 0.651442 - -0.271114 -0.00121831 0.421209 - -0.341079 0.0135063 0.488092 - -0.507432 0.0525777 0.647103 - -0.498079 0.0629628 0.638129 - -0.511979 0.121309 0.651263 - -0.504752 0.167616 0.644221 - -0.503138 0.176214 0.642654 - -0.504712 0.204795 0.644081 - -0.503145 0.242412 0.642478 - -0.510139 0.259264 0.649121 - -0.502965 0.265323 0.642242 - -0.505434 0.307721 0.644486 - -0.504459 0.399413 0.6433 - -0.502847 0.421894 0.641695 - -0.500967 0.492156 0.639703 - -0.501068 0.51494 0.639737 - -0.501196 0.524371 0.639832 - -0.50068 0.53321 0.639314 - -0.498998 0.536049 0.637698 - -0.49352 0.636894 0.632179 - -0.489341 0.665036 0.628104 - -0.490771 0.721706 0.629315 - -0.488784 0.978349 0.626704 - -0.49333 1.24509 0.630314 - -0.38492 1.27936 0.526523 - -0.353434 1.28145 0.4964 - -0.322404 1.28304 0.466715 - -0.30964 1.26547 0.454555 - -0.214739 1.15319 0.36409 - -0.200777 1.21542 0.350564 - -0.0412181 0.105695 0.201013 - -0.039413 0.15436 0.199152 - -0.0388624 0.153423 0.198628 - -0.0255046 0.0758335 0.186066 - -0.0226087 0.0855222 0.183269 - -0.0217457 0.0894139 0.182433 - -0.0200873 0.0981992 0.180822 - -0.0171634 0.110758 0.177991 - -0.0122598 0.135989 0.17323 - -0.0111471 0.137747 0.172161 --0.00885144 0.141212 0.169956 - -0.0066154 0.14363 0.16781 - 4.64e-06 0.158924 0.161436 - 0.00442721 0.167638 0.157181 - 0.0139097 0.18351 0.148067 - 0.019267 0.194728 0.142912 - 0.0230615 0.178894 0.139326 - 0.0240272 0.165298 0.13844 - 0.0252342 0.144528 0.137343 - 0.0259155 0.141768 0.136699 - 0.0255828 0.135182 0.137035 - 0.0238784 0.129629 0.138681 - 0.0293366 0.133307 0.13345 - 0.0370175 0.139593 0.126086 - 0.0408396 0.140855 0.122426 - 0.045915 0.14692 0.117555 - 0.0562056 0.162526 0.107668 - 0.0676666 0.179383 0.0966591 - 0.0798992 0.196641 0.0849105 - 0.0971923 0.212069 0.0683266 - 0.0699628 0.153588 0.0945341 - 0.0286572 -0.0799409 0.135841 - 0.0284025 -0.0802824 0.13608 - 0.0304633 -0.0899791 0.134177 - 0.0344036 -0.117803 0.130563 - 0.030598 -0.121453 0.134137 - 0.0137273 -0.116383 0.149922 - 0.0187599 -0.162588 0.145336 - 0.0127132 -0.174084 0.15103 - 0.0121587 -0.174329 0.15155 --0.00250726 -0.161114 0.165248 - -0.0188105 -0.102128 0.180354 - -0.0200897 -0.0952927 0.181533 - -0.0291517 -0.0799963 0.189978 - -0.0396514 -0.144194 0.199986 - -0.0437471 -0.175758 0.203908 - -0.0645916 -0.303958 0.22378 - -0.361831 -2.15843 0.507218 - -0.463449 -2.15617 0.602375 - -0.486668 -2.16061 0.624131 - -0.507496 -2.15312 0.643616 - -0.147586 -0.404133 0.301777 - -0.154142 -0.405817 0.307921 - -0.2651 -0.407502 0.411835 - -0.279613 -0.402764 0.425413 - -0.289346 -0.411056 0.43455 - -0.349477 -0.41353 0.490868 - -0.417352 -0.412246 0.554428 - -0.426935 -0.414834 0.563409 - -0.441582 -0.414687 0.577125 - -0.452644 -0.414199 0.587483 - -0.504312 -0.372184 0.635754 - -0.502304 -0.29196 0.633654 - -0.50405 -0.211203 0.635067 - -0.50366 -0.189251 0.634642 - -0.504963 -0.186683 0.635855 - -0.506233 -0.138617 0.636913 - -0.507645 -0.100533 0.638131 - -0.275394 -0.00417872 0.42037 - -0.506005 0.127553 0.63597 - -0.505182 0.133253 0.635184 - -0.504391 0.147899 0.634402 - -0.505996 0.160437 0.635871 - -0.506719 0.172841 0.636515 - -0.504853 0.196735 0.634702 - -0.505529 0.241371 0.635212 - -0.50349 0.273103 0.633216 - -0.509055 0.293328 0.638372 - -0.508786 0.296605 0.638111 - -0.500091 0.332885 0.629869 - -0.50462 0.346943 0.634072 - -0.503829 0.455891 0.633033 - -0.500037 0.464946 0.629457 - -0.496024 0.495747 0.625615 - -0.496748 0.500997 0.626277 - -0.499339 0.51748 0.628659 - -0.494235 0.569125 0.623738 - -0.495235 0.595847 0.624601 - -0.487665 0.691818 0.617249 - -0.489881 0.719968 0.619247 - -0.489101 0.731506 0.618485 - -0.488195 0.736528 0.617623 - -0.488728 0.87452 0.617743 - -0.489338 0.883771 0.61829 - -0.489354 0.943342 0.618142 - -0.492659 0.97751 0.621143 - -0.491147 1.11799 0.619342 - -0.486254 1.26863 0.614347 - -0.434337 1.27511 0.565711 - -0.413399 1.28503 0.546076 - -0.360412 1.27949 0.496469 - -0.314245 1.27503 0.453248 - -0.250451 1.21309 0.393676 - -0.207099 1.1947 0.353128 - -0.042956 0.107274 0.202392 - -0.0364924 0.0752679 0.196427 - -0.0347638 0.0604487 0.194848 - -0.0435649 0.17687 0.202771 - -0.0409866 0.165176 0.200389 - -0.0367272 0.137582 0.196476 - -0.0337447 0.128828 0.193707 - -0.0265391 0.0779375 0.187098 - -0.0246753 0.0858116 0.185331 - -0.0103342 0.136654 0.171762 --0.00931286 0.134348 0.170812 --0.00080703 0.151172 0.1628 - 0.0100589 0.177112 0.152553 - 0.0106229 0.176877 0.152026 - 0.0294484 0.20813 0.134311 - 0.0219597 0.165945 0.141439 - 0.0243608 0.165618 0.139192 - 0.0241283 0.15919 0.139427 - 0.0263588 0.149965 0.137363 - 0.0250349 0.131693 0.138653 - 0.0375626 0.139992 0.126899 - 0.0380084 0.139593 0.126482 - 0.056256 0.157471 0.109345 - 0.0844288 0.202192 0.0828392 - 0.0320634 0.08626 0.132196 - 0.0294802 -0.0813423 0.136133 - 0.0319483 -0.0878217 0.133885 - 0.0353683 -0.0944341 0.130762 - 0.0329806 -0.0933174 0.132952 - 0.0280029 -0.0872688 0.137506 - 0.0356519 -0.107309 0.130537 - 0.035336 -0.118988 0.130859 - 0.0332294 -0.116116 0.132785 - 0.03431 -0.127276 0.131823 - 0.0198752 -0.119282 0.145056 - 0.0123285 -0.114429 0.151972 - 0.017346 -0.157285 0.147481 - 0.00563148 -0.160564 0.158246 - 0.00255202 -0.164799 0.161085 - -0.020716 -0.0873973 0.182239 - -0.0232703 -0.0787042 0.184561 - -0.0249267 -0.0758614 0.186074 - -0.0283409 -0.0799998 0.18922 - -0.0322959 -0.0948431 0.192892 - -0.320351 -2.15107 0.462965 - -0.438652 -2.16243 0.571619 - -0.488975 -2.15293 0.617799 - -0.148999 -0.422079 0.300936 - -0.155433 -0.402304 0.30679 - -0.173059 -0.403415 0.322978 - -0.190806 -0.406731 0.339281 - -0.254596 -0.407878 0.397856 - -0.267273 -0.40077 0.409476 - -0.286874 -0.411123 0.427502 - -0.339368 -0.411388 0.475703 - -0.400731 -0.409319 0.53204 - -0.468281 -0.406473 0.594056 - -0.505618 -0.362574 0.628219 - -0.498072 -0.257265 0.621004 - -0.507879 -0.1955 0.629842 - -0.509408 -0.0797153 0.630931 - -0.509537 -0.0595503 0.630995 - -0.294248 -0.00761293 0.433177 - -0.272219 0.00024049 0.41293 - -0.275885 0.00464219 0.416283 - -0.506667 0.0316574 0.628112 - -0.505025 0.0513899 0.62655 - -0.510513 0.22895 0.631108 - -0.509425 0.264197 0.630013 - -0.510272 0.284782 0.630735 - -0.506411 0.289254 0.627177 - -0.504541 0.294901 0.625445 - -0.505938 0.355921 0.626562 - -0.500208 0.373761 0.621252 - -0.504789 0.42822 0.625311 - -0.50348 0.443397 0.624067 - -0.499996 0.523078 0.620652 - -0.500589 0.528409 0.621183 - -0.495542 0.62844 0.616277 - -0.490859 0.66127 0.611888 - -0.489816 0.695293 0.610837 - -0.490999 0.832632 0.611551 - -0.496168 0.85737 0.61623 - -0.494284 0.86174 0.614488 - -0.495603 0.921831 0.615536 - -0.49143 1.13221 0.611133 - -0.493411 1.17292 0.612842 - -0.490223 1.22826 0.609764 - -0.487821 1.26235 0.607466 - -0.396806 1.2828 0.523841 - -0.382345 1.28171 0.510566 - -0.227867 1.16749 0.369036 - -0.039612 0.0927884 0.1991 - -0.03667 0.140573 0.196269 - -0.0351398 0.128692 0.194896 - -0.0305569 0.106965 0.190747 - -0.0279462 0.0819962 0.188418 - -0.0263404 0.0829471 0.186941 - -0.0260176 0.0849319 0.186639 - -0.0224745 0.0846026 0.183387 - -0.0215798 0.0854819 0.182563 - -0.0177661 0.107003 0.179003 --0.00811437 0.139251 0.170053 --0.00052081 0.155387 0.163037 - 0.00033337 0.157159 0.162248 - 0.00348939 0.162244 0.159336 - 0.012625 0.185728 0.150884 - 0.0233119 0.198846 0.141036 - 0.0244274 0.177967 0.140069 - 0.0215945 0.162258 0.142712 - 0.0215418 0.160118 0.142767 - 0.0217516 0.125621 0.142668 - 0.0278349 0.132446 0.137063 - 0.0367824 0.139095 0.12883 - 0.0772656 0.187127 0.0915282 - 0.074532 0.169655 0.0940856 - 0.0566738 0.136534 0.110573 - 0.0347537 -0.0881895 0.132548 - 0.0404629 -0.121059 0.127506 - 0.0321792 -0.115559 0.134934 - 0.030292 -0.117294 0.136635 - 0.0263306 -0.126492 0.140219 - 0.013908 -0.119429 0.151361 - 0.0195033 -0.146776 0.146408 - 0.0190191 -0.152486 0.146858 - 0.0184006 -0.158216 0.147429 - 0.017887 -0.158486 0.147891 - 0.0163001 -0.16569 0.149337 - 0.0007087 -0.160469 0.163331 --0.00943795 -0.144894 0.172406 - -0.0134861 -0.126524 0.175994 - -0.0176955 -0.105103 0.179719 - -0.0183207 -0.102186 0.180273 - -0.025791 -0.0759434 0.186914 - -0.0260107 -0.0769549 0.187114 - -0.0318361 -0.0908497 0.192386 - -0.0723633 -0.339714 0.229469 - -0.398486 -2.16663 0.527404 - -0.434482 -2.16001 0.559728 - -0.49303 -2.15197 0.612312 - -0.503814 -1.8896 0.621296 - -0.508567 -1.82919 0.625405 - -0.168896 -0.406793 0.316384 - -0.199754 -0.404412 0.344104 - -0.226661 -0.411592 0.368299 - -0.232883 -0.404828 0.373871 - -0.338913 -0.407205 0.469147 - -0.340234 -0.405374 0.470329 - -0.378953 -0.413725 0.50514 - -0.38332 -0.411543 0.509058 - -0.411957 -0.410483 0.534786 - -0.44451 -0.414183 0.564045 - -0.4695 -0.415411 0.586502 - -0.47484 -0.404977 0.591271 - -0.510194 -0.370202 0.622944 - -0.505572 -0.362941 0.618771 - -0.505452 -0.359158 0.618653 - -0.507121 -0.353058 0.620136 - -0.507657 -0.32822 0.620551 - -0.505983 -0.26907 0.618888 - -0.505126 -0.258761 0.61809 - -0.509412 -0.23835 0.621887 - -0.508236 -0.225039 0.620794 - -0.49925 -0.157514 0.612538 - -0.505234 -0.10978 0.617787 - -0.506795 -0.0899946 0.619136 - -0.507086 -0.087185 0.61939 - -0.508015 -0.0588241 0.620149 - -0.287592 0.00938921 0.421914 - -0.457026 0.0205559 0.574121 - -0.512224 0.0977312 0.62351 - -0.507962 0.10841 0.619651 - -0.505376 0.122266 0.617291 - -0.504025 0.136439 0.616039 - -0.499257 0.2372 0.611483 - -0.506761 0.263628 0.618155 - -0.503048 0.287966 0.614754 - -0.508983 0.301796 0.620049 - -0.505304 0.385713 0.616518 - -0.497165 0.475289 0.608964 - -0.501498 0.4973 0.612797 - -0.499883 0.500068 0.611339 - -0.492261 0.597227 0.60423 - -0.49279 0.613748 0.604661 - -0.490376 0.621289 0.602471 - -0.494803 0.753919 0.606093 - -0.49218 0.923998 0.603278 - -0.492708 0.960729 0.603654 - -0.489472 1.04119 0.60053 - -0.489996 1.17837 0.600632 - -0.441669 1.27603 0.556948 - -0.366284 1.28043 0.489202 - -0.0407504 0.0914548 0.199905 - -0.0352685 0.0683353 0.195042 - -0.0374295 0.149494 0.196765 - -0.0274183 0.0729929 0.187976 - -0.0271814 0.0729878 0.187763 - -0.024234 0.0858356 0.18508 - -0.0225548 0.0816504 0.183583 - -0.0179592 0.104092 0.179393 - 0.0272275 0.204798 0.138522 - 0.0249457 0.181379 0.140635 - 0.0206141 0.131507 0.144661 - 0.0356767 0.137321 0.131112 - 0.0361223 0.136945 0.130713 - 0.0358339 0.132447 0.130984 - 0.0396423 0.133841 0.127558 - 0.0703448 0.167961 0.0998801 - 0.033749 0.0891645 0.132973 - 0.0292119 0.0811857 0.137072 - 0.0375776 -0.088506 0.131232 - 0.0373513 -0.0996844 0.131461 - 0.0363904 -0.118552 0.132357 - 0.035338 -0.128012 0.133308 - 0.0295943 -0.117469 0.138333 - 0.0244036 -0.125121 0.142921 - 0.025583 -0.133376 0.141905 - 0.025146 -0.133684 0.14229 - 0.0191157 -0.148519 0.147635 - 0.0137288 -0.155576 0.152394 - 0.0137156 -0.157703 0.152411 - 0.0131989 -0.157941 0.152866 - 0.00797906 -0.165371 0.157479 --0.00691765 -0.152546 0.170551 - -0.0165221 -0.109006 0.178885 - -0.0220704 -0.0776462 0.183683 - -0.024763 -0.0809094 0.186061 - -0.0261704 -0.0769749 0.187289 - -0.0267025 -0.0749894 0.187751 - -0.0272525 -0.0669977 0.188214 - -0.031133 -0.0878759 0.191684 - -0.0487427 -0.20707 0.207495 - -0.0598483 -0.279674 0.217459 - -0.064438 -0.301984 0.221557 - -0.371505 -2.1643 0.496682 - -0.392918 -2.15905 0.515507 - -0.444517 -2.15469 0.560893 - -0.451575 -2.15223 0.567096 - -0.473299 -2.1475 0.586197 - -0.48942 -2.15181 0.600392 - -0.50799 -1.94546 0.616181 - -0.15228 -0.396425 0.299093 - -0.170843 -0.409511 0.31546 - -0.202362 -0.403398 0.343175 - -0.2143 -0.402035 0.353675 - -0.250723 -0.409146 0.385739 - -0.29882 -0.415581 0.428073 - -0.347948 -0.408373 0.471278 - -0.398382 -0.414238 0.515666 - -0.406679 -0.40869 0.522952 - -0.480823 -0.418508 0.588211 - -0.506311 -0.356718 0.610471 - -0.511934 -0.321239 0.615324 - -0.507794 -0.291064 0.611601 - -0.505773 -0.256891 0.609732 - -0.508571 -0.239076 0.612146 - -0.509353 -0.236277 0.612827 - -0.509421 -0.233133 0.612878 - -0.508869 -0.220269 0.612358 - -0.504339 -0.151978 0.608191 - -0.507627 -0.132513 0.611032 - -0.507347 -0.0950205 0.610685 - -0.506182 -0.0580979 0.609562 - -0.504103 -0.0244689 0.607643 - -0.503363 0.0447555 0.606808 - -0.501183 0.066729 0.604831 - -0.500963 0.0694793 0.604631 - -0.505409 0.0870363 0.608496 - -0.507411 0.162679 0.610055 - -0.501195 0.199224 0.604489 - -0.500542 0.201972 0.603907 - -0.508261 0.258943 0.610547 - -0.506554 0.264514 0.60903 - -0.499361 0.286594 0.602643 - -0.500591 0.297349 0.603696 - -0.506395 0.335705 0.6087 - -0.499493 0.416064 0.602414 - -0.498002 0.422644 0.601085 - -0.504101 0.444408 0.606393 - -0.492366 0.629535 0.595575 - -0.493449 0.636525 0.596509 - -0.495505 0.650578 0.598281 - -0.489271 0.822531 0.592338 - -0.493091 0.852343 0.595619 - -0.490116 0.862593 0.592974 - -0.490459 1.01437 0.592872 - -0.489236 1.0526 0.591694 - -0.489924 1.06479 0.592267 - -0.493029 1.10503 0.594892 - -0.451153 1.2791 0.557584 - -0.398691 1.28403 0.511414 - -0.323097 1.28269 0.444909 - -0.0403325 0.0945534 0.199292 - -0.0398882 0.0987111 0.19889 - -0.0335581 0.0564848 0.193433 - -0.0333731 0.0565176 0.19327 - -0.0383029 0.151372 0.197355 - -0.0338025 0.129763 0.193453 - -0.0312299 0.103904 0.191258 - -0.0280513 0.0759993 0.188536 - -0.0127538 0.12336 0.174951 --0.00750922 0.139371 0.170294 - 0.00651798 0.170935 0.157868 - 0.0179366 0.19356 0.147762 - 0.0237189 0.181366 0.142707 - 0.0227116 0.14948 0.143678 - 0.0262301 0.138321 0.140612 - 0.0280381 0.130175 0.139043 - 0.0318128 0.128345 0.135727 - 0.0362923 0.134037 0.13177 - 0.0397692 0.13097 0.12872 - 0.0432185 0.132632 0.12568 - 0.0654392 0.160419 0.106056 - 0.0311802 0.0879775 0.136391 - 0.0331328 -0.0842012 0.136225 - 0.0356779 -0.0892854 0.134046 - 0.0316872 -0.0913051 0.13749 - 0.0338355 -0.0954625 0.13565 - 0.0293998 -0.0950776 0.139471 - 0.0367872 -0.11656 0.133162 - 0.0364557 -0.118108 0.133451 - 0.0305896 -0.111312 0.138489 - 0.0284529 -0.116764 0.140344 - 0.0276798 -0.117401 0.141012 - 0.0263915 -0.125382 0.142144 - 0.0176263 -0.119069 0.149681 - 0.015661 -0.162424 0.151489 - 0.0124987 -0.161717 0.154212 - 0.0111325 -0.168569 0.155407 - 0.00671376 -0.161922 0.159198 --0.00093762 -0.160291 0.165787 --0.00454526 -0.151062 0.168872 - -0.0134415 -0.122651 0.176463 - -0.0194599 -0.091416 0.181567 - -0.019762 -0.0914603 0.181828 - -0.0213296 -0.0826235 0.183155 - -0.0231306 -0.079809 0.1847 - -0.0238974 -0.0698533 0.185335 - -0.0259568 -0.0709769 0.187112 - -0.0265859 -0.0779939 0.187673 - -0.0271097 -0.0759993 0.188119 - -0.0275866 -0.065999 0.188504 - -0.0633341 -0.30121 0.219931 - -0.405273 -2.16955 0.519536 - -0.471912 -2.15973 0.576938 - -0.149008 -0.413694 0.294059 - -0.153796 -0.403613 0.298158 - -0.173489 -0.409577 0.315145 - -0.178845 -0.397229 0.319728 - -0.246147 -0.408926 0.377758 - -0.248845 -0.406385 0.380076 - -0.285772 -0.410313 0.411909 - -0.308262 -0.40833 0.431285 - -0.314357 -0.406356 0.436532 - -0.384774 -0.413725 0.497235 - -0.391731 -0.41075 0.503223 - -0.423307 -0.411936 0.530437 - -0.445148 -0.415452 0.549269 - -0.449711 -0.412401 0.553192 - -0.504385 -0.378094 0.600219 - -0.5074 -0.336619 0.602707 - -0.508208 -0.305822 0.603322 - -0.508616 -0.249858 0.603526 - -0.511063 -0.241516 0.605613 - -0.508479 -0.202882 0.603284 - -0.501769 -0.173249 0.597423 - -0.50463 -0.127736 0.599769 - -0.506188 -0.0996586 0.601037 - -0.511948 -0.0894408 0.605973 - -0.504875 -0.0574624 0.599794 - -0.503328 -0.0297217 0.598388 - -0.281133 0.00755131 0.406809 - -0.31288 0.0117868 0.434155 - -0.499009 0.0249111 0.594522 - -0.507926 0.0783351 0.602065 - -0.506792 0.120581 0.600976 - -0.50648 0.137738 0.600662 - -0.504639 0.184025 0.598953 - -0.503873 0.223105 0.59819 - -0.501883 0.285763 0.59631 - -0.499902 0.356736 0.594415 - -0.495817 0.500758 0.590514 - -0.499303 0.551088 0.593385 - -0.497661 0.578784 0.591898 - -0.492891 0.598451 0.587735 - -0.490947 0.644575 0.585938 - -0.490904 0.715984 0.585712 - -0.493457 0.786879 0.587725 - -0.490855 0.78955 0.585476 - -0.493051 0.927725 0.587004 - -0.48929 0.956003 0.583687 - -0.490866 0.997178 0.584938 - -0.489124 1.12093 0.583109 - -0.491569 1.20063 0.585006 - -0.491092 1.26682 0.58442 - -0.438621 1.27621 0.539177 - -0.429303 1.27811 0.531142 - -0.212239 1.14265 0.34444 - -0.0395469 0.097724 0.198378 - -0.0330064 0.0575415 0.192848 - -0.0310008 0.105902 0.190992 - -0.0282079 0.0739942 0.188669 - -0.0229874 0.0797755 0.184155 - -0.0213826 0.0836072 0.182762 - -0.0136267 0.122624 0.175975 - -0.0129925 0.124519 0.175424 - 0.0173649 0.19096 0.149087 - 0.0210666 0.194641 0.145888 - 0.0253812 0.181997 0.142203 - 0.0249446 0.169323 0.142612 - 0.0246366 0.166248 0.142886 - 0.0230475 0.146455 0.144308 - 0.0477165 0.137895 0.123071 - 0.0499683 0.13944 0.121127 - 0.0316517 0.0843902 0.137057 - 0.0361311 0.0884345 0.133186 - 0.0379931 0.0902325 0.131576 - 0.0462493 -0.0993383 0.126276 - 0.035002 -0.0870899 0.135735 - 0.0300116 -0.0822183 0.139934 - 0.0319347 -0.0880211 0.138326 - 0.0305347 -0.0973093 0.139532 - 0.0296876 -0.0994092 0.140252 - 0.0290233 -0.100052 0.140814 - 0.0300225 -0.114952 0.14001 - 0.0260806 -0.112297 0.14333 - 0.0197211 -0.12265 0.148723 - 0.012671 -0.112647 0.154646 - 0.014836 -0.120154 0.152839 - 0.0180835 -0.132507 0.150131 - 0.0124692 -0.166211 0.154957 - 0.0015818 -0.158688 0.164125 --0.00170808 -0.155549 0.166893 --0.00530943 -0.149353 0.169915 --0.00510754 -0.154391 0.169758 - -0.0148399 -0.116933 0.177873 - -0.0209802 -0.0786081 0.182954 - -0.0262171 -0.0809937 0.18738 - -0.0270303 -0.0769998 0.188055 - -0.0282185 -0.0709818 0.189042 - -0.030228 -0.0798871 0.190761 - -0.0305796 -0.0818646 0.191063 - -0.0333653 -0.105667 0.193476 - -0.046805 -0.204334 0.205076 - -0.0506437 -0.220807 0.208358 - -0.370222 -2.16825 0.483134 - -0.384675 -2.16422 0.495319 - -0.416114 -2.17026 0.521865 - -0.50483 -2.08322 0.596501 - -0.508685 -2.00425 0.599548 - -0.155473 -0.406384 0.297305 - -0.16027 -0.401545 0.30134 - -0.170842 -0.404075 0.310268 - -0.175538 -0.403371 0.314229 - -0.206768 -0.407726 0.340595 - -0.247769 -0.408926 0.375197 - -0.282865 -0.402629 0.404797 - -0.315544 -0.404895 0.432379 - -0.339419 -0.405214 0.452526 - -0.3655 -0.412968 0.474555 - -0.426071 -0.407803 0.525655 - -0.503483 -0.412395 0.590992 - -0.509931 -0.290927 0.596116 - -0.504744 -0.261735 0.591662 - -0.505279 -0.221192 0.592008 - -0.507041 -0.150349 0.593309 - -0.510351 -0.131093 0.596052 - -0.508541 -0.127736 0.594516 - -0.509434 -0.116536 0.59524 - -0.506051 -0.107251 0.592361 - -0.504414 -0.073477 0.590891 - -0.501463 0.0411316 0.588101 - -0.503486 0.127251 0.589582 - -0.510558 0.166969 0.595447 - -0.507536 0.177707 0.592868 - -0.506942 0.180447 0.59236 - -0.507927 0.186771 0.593174 - -0.516376 0.230248 0.600191 - -0.500484 0.228887 0.586783 - -0.506083 0.305999 0.591307 - -0.505749 0.358226 0.590888 - -0.500274 0.441783 0.586049 - -0.495364 0.591598 0.581513 - -0.491971 0.652076 0.578492 - -0.490009 0.81796 0.576403 - -0.487242 0.828059 0.574041 - -0.491412 0.908404 0.577349 - -0.492624 0.992913 0.578152 - -0.446458 1.27476 0.538456 - -0.419127 1.28305 0.515371 - -0.397893 1.27774 0.497467 - -0.359421 1.27772 0.465001 - -0.0325877 0.052521 0.192406 - -0.038991 0.153236 0.197546 - -0.0351187 0.139622 0.194314 - -0.0330716 0.117753 0.192644 - -0.0254681 0.0839694 0.186316 - -0.0235924 0.0888745 0.18472 - -0.0229997 0.0888299 0.18422 - 0.00477296 0.164738 0.160585 - 0.0122896 0.174467 0.154217 - 0.0184426 0.186626 0.148993 - 0.0234665 0.164063 0.144812 - 0.0239759 0.16163 0.144389 - 0.0220648 0.132076 0.146079 - 0.0386007 0.124006 0.132146 - 0.0275458 0.0808351 0.141588 - 0.0433358 0.0971329 0.128221 - 0.0315618 -0.102144 0.139712 - 0.0278557 -0.107932 0.142789 - 0.0288371 -0.113067 0.141991 - 0.0265427 -0.118395 0.143901 - 0.0213436 -0.120951 0.148203 - 0.0134401 -0.157687 0.154827 - 0.00486661 -0.160922 0.161918 - 0.00022698 -0.157209 0.165742 - -0.0200026 -0.0825514 0.18226 - -0.0259614 -0.0729943 0.187158 - -0.0277695 -0.0799866 0.18867 - -0.0285766 -0.0799607 0.189337 - -0.0335977 -0.102601 0.193544 - -0.038734 -0.143132 0.197892 - -0.0460521 -0.205438 0.204099 - -0.0471295 -0.209293 0.205 - -0.0488327 -0.219088 0.206432 - -0.394975 -2.16312 0.497434 - -0.432923 -2.16085 0.528779 - -0.486092 -2.1552 0.572689 - -0.16525 -0.409012 0.303101 - -0.164748 -0.402742 0.30267 - -0.1895 -0.406096 0.323127 - -0.202002 -0.406417 0.333456 - -0.212907 -0.406323 0.342465 - -0.219408 -0.408232 0.347841 - -0.231561 -0.401739 0.357863 - -0.234259 -0.399399 0.360086 - -0.252584 -0.403486 0.375236 - -0.259415 -0.408139 0.380892 - -0.281659 -0.408537 0.399269 - -0.302828 -0.404924 0.416747 - -0.348961 -0.407205 0.454866 - -0.381911 -0.411179 0.482097 - -0.420446 -0.40613 0.513919 - -0.436525 -0.415184 0.527226 - -0.445137 -0.408839 0.534324 - -0.47598 -0.411657 0.559812 - -0.506291 -0.263682 0.584469 - -0.506231 -0.21986 0.584306 - -0.506136 -0.15462 0.584058 - -0.50802 -0.115266 0.585512 - -0.503826 -0.0509741 0.581881 - -0.338098 -0.010282 0.444862 - -0.278784 -0.00689593 0.395852 - -0.275732 0.00587176 0.393297 - -0.503104 0.143067 0.580781 - -0.506249 0.16416 0.583324 - -0.504562 0.172284 0.581909 - -0.504539 0.247611 0.581695 - -0.510045 0.28933 0.586136 - -0.508554 0.311899 0.584845 - -0.502608 0.335413 0.579872 - -0.500889 0.351767 0.57841 - -0.49885 0.504853 0.576328 - -0.494749 0.541801 0.572844 - -0.492526 0.620038 0.570805 - -0.499016 0.639735 0.576115 - -0.495759 0.646505 0.573407 - -0.493877 0.678604 0.571769 - -0.49159 0.744165 0.569709 - -0.491018 0.749904 0.569222 - -0.48959 0.781887 0.567959 - -0.490496 0.819782 0.568609 - -0.488918 0.839786 0.567254 - -0.491257 0.900917 0.569028 - -0.492764 0.97579 0.570078 - -0.491395 0.992133 0.568905 - -0.489647 0.998176 0.567445 - -0.492308 1.0553 0.569495 - -0.49068 1.10686 0.568016 - -0.475888 1.27619 0.555357 - -0.421903 1.28213 0.510743 - -0.412147 1.2828 0.502682 - -0.362706 1.28056 0.461842 - -0.25721 1.17298 0.374968 - -0.247076 1.20914 0.366502 - -0.208888 1.13097 0.335157 - -0.0412933 0.101289 0.199372 - -0.0429144 0.175788 0.200518 - -0.0381643 0.152306 0.196655 - -0.0312668 0.109853 0.191067 - -0.0243563 0.0809351 0.185433 - -0.0230956 0.0848596 0.184381 - -0.0225745 0.083816 0.183953 - -0.0150255 0.108918 0.177652 - 0.0228453 0.195591 0.146141 - 0.0292048 0.205443 0.140861 - 0.0231363 0.168931 0.145969 - 0.0239832 0.169577 0.145268 - 0.0226381 0.1476 0.146436 - 0.0284329 0.136236 0.141679 - 0.0288911 0.135921 0.141301 - 0.0274484 0.124409 0.142523 - 0.0278667 0.124101 0.142178 - 0.0298235 0.127252 0.140553 - 0.037743 0.132718 0.133996 - 0.0338359 0.0865482 0.137344 - 0.0568823 -0.108026 0.120277 - 0.0331386 -0.0912147 0.139431 - 0.0370588 -0.117554 0.136329 - 0.0284042 -0.110535 0.143309 - 0.0237654 -0.108332 0.147054 - 0.0188243 -0.115236 0.151066 - 0.0178421 -0.1291 0.151896 - 0.018352 -0.135356 0.1515 - 0.0188437 -0.151282 0.151143 - 0.0167744 -0.158647 0.152835 - 0.010366 -0.159198 0.158018 - 0.00650853 -0.157476 0.161132 --0.00143811 -0.153733 0.167548 - -0.0116066 -0.126607 0.175699 - -0.0173821 -0.0973289 0.180294 - -0.0182135 -0.0954368 0.180961 - -0.0215932 -0.0667232 0.18362 - -0.0218196 -0.0667491 0.183803 - -0.0230246 -0.0889004 0.184834 - -0.0247018 -0.0809736 0.18617 - -0.0253797 -0.0719898 0.186695 - -0.025624 -0.0719944 0.186892 - -0.0266146 -0.0769989 0.187706 - -0.0284695 -0.0779503 0.189208 - -0.0290798 -0.0729132 0.189689 - -0.0293272 -0.072897 0.189889 - -0.0322579 -0.0966952 0.192319 - -0.0530224 -0.237491 0.20947 - -0.483081 -2.16069 0.562126 - -0.507917 -1.96897 0.581713 - -0.148446 -0.404376 0.287051 - -0.156766 -0.40546 0.29378 - -0.174733 -0.405056 0.308306 - -0.176107 -0.404217 0.309415 - -0.19644 -0.403217 0.325852 - -0.223512 -0.40603 0.347747 - -0.245029 -0.409385 0.365152 - -0.297038 -0.414942 0.407217 - -0.298838 -0.410363 0.408661 - -0.329825 -0.414887 0.433726 - -0.331232 -0.413177 0.434859 - -0.362873 -0.410632 0.460434 - -0.400037 -0.406708 0.490472 - -0.454638 -0.414851 0.534639 - -0.456667 -0.413039 0.536275 - -0.503463 -0.402 0.574081 - -0.502936 -0.39017 0.573625 - -0.501367 -0.334804 0.572214 - -0.507227 -0.325014 0.576927 - -0.508039 -0.318687 0.577567 - -0.505687 -0.306982 0.575635 - -0.512497 -0.291152 0.5811 - -0.509511 -0.273013 0.57864 - -0.502594 -0.265919 0.573029 - -0.509097 -0.234798 0.578206 - -0.511455 -0.226648 0.580092 - -0.506299 -0.203107 0.575863 - -0.503887 -0.193208 0.573887 - -0.508966 -0.15143 0.577886 - -0.339676 -0.0102566 0.44065 - -0.289178 -0.0071279 0.399813 - -0.274452 0.00440732 0.387877 - -0.317112 0.011693 0.42235 - -0.404116 0.017314 0.492679 - -0.507363 0.140371 0.57584 - -0.507801 0.163395 0.576135 - -0.513184 0.203787 0.580383 - -0.515498 0.213892 0.582228 - -0.517565 0.233395 0.583849 - -0.508331 0.247611 0.576347 - -0.502041 0.256833 0.571238 - -0.504905 0.271092 0.573516 - -0.504699 0.283879 0.573317 - -0.507406 0.383006 0.575251 - -0.499295 0.450127 0.56852 - -0.496764 0.507597 0.566326 - -0.496834 0.530552 0.566323 - -0.494417 0.571082 0.564265 - -0.496937 0.589373 0.566255 - -0.496003 0.609066 0.56545 - -0.489832 0.622387 0.560426 - -0.48971 0.748604 0.560003 - -0.49323 0.818169 0.56267 - -0.494341 0.917004 0.563314 - -0.487902 1.11471 0.5576 - -0.490864 1.22279 0.559716 - -0.48005 1.27801 0.55083 - -0.446497 1.28594 0.523682 - -0.410477 1.28403 0.494564 - -0.394414 1.28003 0.481588 - -0.38058 1.28326 0.470395 - -0.335602 1.27715 0.434045 - -0.260268 1.15909 0.37344 - -0.223613 1.13952 0.343854 - -0.214739 1.13482 0.336691 - -0.0421497 0.114252 0.199774 - -0.0323361 0.0595257 0.191981 - -0.030587 0.100865 0.19046 - -0.0288732 0.0789412 0.189131 - -0.0272981 0.0819936 0.18785 - -0.0264649 0.0839998 0.187171 - -0.024696 0.0869683 0.185733 - -0.0243778 0.0879568 0.185473 - -0.0214531 0.0867559 0.183112 - -0.0206991 0.0806546 0.182518 - -0.0197658 0.0855608 0.18175 - -0.0188953 0.0854399 0.181047 --0.00968288 0.129187 0.173486 --0.00556475 0.135329 0.170141 --0.00042349 0.151301 0.165943 - 0.00772898 0.167267 0.15931 - 0.0135099 0.176611 0.154612 - 0.0213485 0.192339 0.148234 - 0.0257556 0.187245 0.144684 - 0.027025 0.18665 0.143659 - 0.0244899 0.168645 0.145755 - 0.0218111 0.133182 0.148012 - 0.0269372 0.126499 0.143885 - 0.0325398 0.132779 0.139339 - 0.0261964 0.0866318 0.144587 - 0.0294264 0.0871412 0.141974 - 0.0317605 0.0845774 0.140093 - 0.0318132 0.0831776 0.140054 - 0.0529275 0.105669 0.122925 - 0.0504151 -0.0992124 0.126815 - 0.0515674 -0.106118 0.125921 - 0.0409725 -0.0940695 0.134272 - 0.0335481 -0.0929821 0.140143 - 0.0317742 -0.0960491 0.141554 - 0.0271831 -0.0916887 0.145175 - 0.0327817 -0.111145 0.140795 - 0.0346747 -0.119147 0.139318 - 0.0237265 -0.119244 0.14798 - 0.0203049 -0.115873 0.150678 - 0.0174952 -0.127511 0.15293 - 0.0211578 -0.145092 0.150078 - 0.0191056 -0.155781 0.151729 - 0.0135672 -0.142375 0.156076 - 0.0166872 -0.157941 0.153647 - 0.0156053 -0.158408 0.154504 - 0.0121401 -0.163993 0.15726 - 0.0128994 -0.169964 0.156675 --0.00291216 -0.151192 0.169135 - -0.014565 -0.107024 0.178242 - -0.0211448 -0.0787608 0.183375 - -0.026005 -0.0799998 0.187223 - -0.0262787 -0.0799988 0.18744 - -0.0267974 -0.0769925 0.187842 - -0.0277115 -0.0709651 0.18855 - -0.030942 -0.0847615 0.191141 - -0.0316505 -0.0866958 0.191706 - -0.0715947 -0.330852 0.223929 - -0.439735 -2.16279 0.519843 - -0.499126 -2.14487 0.566783 - -0.514107 -1.73695 0.577595 - -0.18115 -0.410574 0.310804 - -0.204207 -0.401938 0.329023 - -0.25951 -0.406231 0.372785 - -0.369925 -0.408879 0.460143 - -0.402678 -0.410101 0.486058 - -0.422556 -0.409319 0.501781 - -0.453846 -0.41843 0.526558 - -0.463138 -0.416028 0.533903 - -0.468502 -0.413506 0.538141 - -0.507562 -0.413915 0.569043 - -0.503004 -0.361553 0.565303 - -0.498438 -0.333595 0.561619 - -0.503373 -0.293242 0.565421 - -0.50448 -0.280895 0.566265 - -0.506842 -0.256717 0.568072 - -0.505085 -0.246421 0.566655 - -0.50393 -0.236591 0.565717 - -0.504047 -0.177248 0.565658 - -0.51037 -0.159293 0.570614 - -0.51147 -0.145321 0.571449 - -0.51037 -0.0644633 0.570373 - -0.506505 -0.0531555 0.567286 - -0.502621 -0.0393889 0.564179 - -0.269955 0.00293989 0.380004 - -0.5001 0.0268288 0.562015 - -0.506588 0.0406026 0.567113 - -0.499868 0.0692663 0.561723 - -0.503524 0.0724925 0.564607 - -0.506376 0.0974341 0.5668 - -0.50148 0.10459 0.562908 - -0.506545 0.113978 0.566892 - -0.505457 0.135935 0.565975 - -0.505714 0.196167 0.566025 - -0.504164 0.240501 0.564685 - -0.508828 0.268007 0.568305 - -0.503601 0.268268 0.564169 - -0.506843 0.326258 0.566586 - -0.502234 0.347295 0.562886 - -0.506522 0.390524 0.566168 - -0.509103 0.400211 0.568185 - -0.497022 0.44858 0.558505 - -0.495181 0.520032 0.556866 - -0.500566 0.554422 0.561038 - -0.493193 0.590395 0.555114 - -0.492604 0.605267 0.55461 - -0.491297 0.63047 0.553512 - -0.496174 0.665548 0.55728 - -0.493452 0.679342 0.555092 - -0.490382 0.764234 0.552446 - -0.491138 0.79367 0.55297 - -0.492679 0.915419 0.553878 - -0.490395 0.919683 0.55206 - -0.488981 1.15695 0.550337 - -0.492487 1.24509 0.552886 - -0.477545 1.27597 0.540986 - -0.473177 1.27846 0.537524 - -0.458473 1.28119 0.525885 - -0.440782 1.27441 0.511906 - -0.422423 1.28062 0.497366 - -0.361116 1.27391 0.448883 - -0.34514 1.26793 0.436259 - -0.337155 1.27428 0.429925 - -0.311821 1.2672 0.409902 - -0.258108 1.16135 0.367678 - -0.223551 1.13171 0.340415 - -0.0407811 0.103338 0.198445 - -0.0373372 0.0878529 0.19576 - -0.0328146 0.121709 0.192096 - -0.0243707 0.0849691 0.185509 - -0.0237892 0.0849459 0.185049 - -0.0232079 0.0849162 0.18459 - -0.0203055 0.084671 0.182294 - -0.0134746 0.114859 0.176813 - -0.0106839 0.124434 0.174581 --0.00861458 0.130077 0.172929 - 0.029513 0.209219 0.142564 - 0.0251838 0.17511 0.146076 - 0.0252453 0.162209 0.14606 - 0.0263413 0.134191 0.145265 - 0.0261921 0.130929 0.145391 - 0.0311072 0.126386 0.141514 - 0.0308132 0.120808 0.141761 - 0.0374505 0.120151 0.136512 - 0.0382333 0.118257 0.135897 - 0.0332664 0.0878223 0.139904 - 0.051233 0.102074 0.125654 - 0.0428521 -0.0859526 0.133922 - 0.0521878 -0.1038 0.126739 - 0.0290798 -0.0855362 0.144584 - 0.0302496 -0.0982516 0.143711 - 0.0279843 -0.0978251 0.145464 - 0.0169563 -0.111725 0.154037 - 0.0193196 -0.132347 0.15226 - 0.0174808 -0.165287 0.153767 - 0.0151309 -0.160992 0.155575 - 0.014019 -0.161434 0.156437 - 0.0124519 -0.165163 0.15766 - 0.008214 -0.162494 0.160934 --0.00630308 -0.145988 0.172132 - -0.0139773 -0.112044 0.177988 - -0.0179938 -0.0884779 0.181038 - -0.0216388 -0.0728257 0.183821 - -0.025101 -0.0809973 0.186522 - -0.0259282 -0.0769989 0.187152 - -0.0262063 -0.0789963 0.187373 - -0.0272964 -0.0789713 0.188217 - -0.0310286 -0.0817133 0.191113 - -0.0351801 -0.125411 0.194438 - -0.048181 -0.210042 0.204718 - -0.0548865 -0.248215 0.210006 - -0.0602901 -0.277508 0.214264 - -0.0636501 -0.296063 0.216912 - -0.0742006 -0.332295 0.225173 - -0.373478 -2.17021 0.461534 - -0.450118 -2.15948 0.520845 - -0.497637 -2.15809 0.557633 - -0.508755 -1.91291 0.56562 - -0.509294 -1.77996 0.565702 - -0.156039 -0.453751 0.288842 - -0.162162 -0.402304 0.293453 - -0.205104 -0.405545 0.326709 - -0.21567 -0.408237 0.334896 - -0.283212 -0.402324 0.387175 - -0.301426 -0.401251 0.401275 - -0.310623 -0.410993 0.40842 - -0.344704 -0.403464 0.434788 - -0.376148 -0.409672 0.459149 - -0.406642 -0.411399 0.482763 - -0.426096 -0.409948 0.497821 - -0.437572 -0.414215 0.506718 - -0.441483 -0.41441 0.509745 - -0.502151 -0.421713 0.556736 - -0.50292 -0.391701 0.557255 - -0.504937 -0.38216 0.558793 - -0.502342 -0.32021 0.556627 - -0.508324 -0.277815 0.561151 - -0.507431 -0.239615 0.560364 - -0.51076 -0.222893 0.562898 - -0.50856 -0.215863 0.561177 - -0.505364 -0.196712 0.558655 - -0.503158 -0.164218 0.556864 - -0.506897 -0.154142 0.559733 - -0.502986 -0.116909 0.556611 - -0.503388 -0.114273 0.556916 - -0.507509 -0.0960771 0.560061 - -0.509627 -0.0774199 0.561653 - -0.507538 -0.0743848 0.560029 - -0.495092 -0.0202989 0.550255 - -0.294484 -0.00717008 0.394903 - -0.273953 -0.00525194 0.379002 - -0.505269 0.056165 0.557941 - -0.503711 0.0746574 0.556688 - -0.507385 0.121593 0.559414 - -0.506095 0.129554 0.558395 - -0.51117 0.185179 0.562184 - -0.509881 0.190527 0.561172 - -0.505493 0.289743 0.557524 - -0.507483 0.331113 0.55896 - -0.505301 0.371936 0.557168 - -0.504074 0.435704 0.556056 - -0.498667 0.46327 0.5518 - -0.500829 0.499837 0.553381 - -0.498857 0.548337 0.551732 - -0.497041 0.575609 0.550257 - -0.490676 0.603552 0.545258 - -0.49299 0.611867 0.547029 - -0.496759 0.649972 0.54985 - -0.493693 0.750406 0.547222 - -0.489704 0.778295 0.544064 - -0.492302 0.826754 0.545953 - -0.488227 0.842611 0.542758 - -0.492555 0.934956 0.545875 - -0.487698 1.04218 0.541843 - -0.476474 1.27846 0.532555 - -0.45568 1.27897 0.516454 - -0.445935 1.28088 0.508904 - -0.440914 1.28133 0.505016 - -0.427044 1.2862 0.494265 - -0.364749 1.27865 0.446053 - -0.360337 1.2805 0.442632 - -0.040109 0.105467 0.19767 - -0.0358704 0.0830315 0.194445 - -0.0361513 0.142409 0.194512 - -0.0232335 0.0919414 0.184639 - -0.014328 0.11004 0.177698 --0.00852135 0.127121 0.173159 - 0.00054531 0.150325 0.16608 - 0.00631718 0.16607 0.161572 - 0.00940764 0.1692 0.159171 - 0.0140576 0.175874 0.155554 - 0.0176934 0.182856 0.152721 - 0.0212431 0.188792 0.149958 - 0.0260491 0.168645 0.146288 - 0.0261675 0.14253 0.146262 - 0.0242141 0.128207 0.147811 - 0.0308088 0.120265 0.142725 - 0.0279637 0.087717 0.14501 - 0.0298515 0.0883834 0.143547 - 0.0448421 -0.0888369 0.133564 - 0.0461272 -0.0928597 0.1326 - 0.0517137 -0.105501 0.1284 - 0.0338409 -0.0994092 0.141924 - 0.0305204 -0.114304 0.144477 - 0.0256131 -0.106335 0.148174 - 0.0258775 -0.123341 0.148016 - 0.0176019 -0.11948 0.154276 - 0.0171862 -0.119713 0.154591 - 0.0213335 -0.154339 0.151536 - 0.0110541 -0.132405 0.159268 - 0.00467039 -0.153499 0.164157 - 0.0046965 -0.156579 0.164145 - 0.00360658 -0.1569 0.164971 - 0.00147562 -0.15135 0.166572 --0.00124591 -0.14492 0.168617 --0.00192134 -0.154266 0.169152 - -0.0296494 -0.0778059 0.189965 - -0.0459419 -0.197278 0.202607 - -0.0471624 -0.202116 0.203543 - -0.0572097 -0.260898 0.211302 - -0.0712585 -0.31977 0.222092 - -0.0723706 -0.319514 0.222934 - -0.521235 -1.73601 0.566513 - -0.160282 -0.399375 0.289729 - -0.161671 -0.39863 0.290779 - -0.216253 -0.402886 0.332137 - -0.219464 -0.401631 0.334566 - -0.246788 -0.404443 0.355272 - -0.259824 -0.408818 0.365158 - -0.26928 -0.406282 0.372315 - -0.279841 -0.412507 0.380331 - -0.284624 -0.409067 0.383945 - -0.321293 -0.405232 0.411714 - -0.352017 -0.409823 0.434999 - -0.439507 -0.409462 0.501273 - -0.503786 -0.385819 0.549907 - -0.506985 -0.34856 0.552237 - -0.506195 -0.261938 0.551421 - -0.502747 -0.238574 0.548751 - -0.506082 -0.207274 0.551198 - -0.505292 -0.203997 0.550592 - -0.507229 -0.12257 0.551855 - -0.507654 -0.119931 0.55217 - -0.506505 -0.116909 0.551292 - -0.50809 -0.111817 0.55248 - -0.509149 -0.0984154 0.553249 - -0.508431 -0.0686135 0.55263 - -0.496787 -0.0253929 0.543701 - -0.271668 0.00157276 0.3731 - -0.27799 0.00714557 0.377876 - -0.499912 0.0290274 0.545931 - -0.500105 0.0420772 0.546045 - -0.502979 0.0475891 0.548208 - -0.508008 0.0560727 0.551997 - -0.503525 0.0714282 0.548562 - -0.50546 0.120223 0.549905 - -0.511636 0.127312 0.554567 - -0.506533 0.150914 0.550641 - -0.507261 0.170903 0.551143 - -0.503153 0.177945 0.548013 - -0.502532 0.180557 0.547536 - -0.504742 0.201608 0.549157 - -0.51029 0.284018 0.553153 - -0.503583 0.339715 0.547933 - -0.513341 0.364484 0.555263 - -0.514123 0.368697 0.555845 - -0.505588 0.38037 0.54935 - -0.50331 0.408468 0.547553 - -0.50701 0.419385 0.550329 - -0.499363 0.477384 0.544391 - -0.499674 0.508299 0.544549 - -0.491937 0.649932 0.538333 - -0.486689 0.701825 0.534227 - -0.492167 0.762836 0.538224 - -0.495794 0.891016 0.54065 - -0.492079 0.909586 0.537789 - -0.488914 0.912126 0.535385 - -0.492347 1.02403 0.537704 - -0.490062 1.07258 0.535851 - -0.491209 1.09793 0.536657 - -0.491807 1.22523 0.536791 - -0.488611 1.27345 0.534249 - -0.422252 1.27814 0.483968 - -0.417233 1.27843 0.480165 - -0.401933 1.27816 0.468576 - -0.227416 1.13952 0.336724 - -0.040517 0.0931064 0.197769 - -0.0359025 0.0880318 0.194286 - -0.0365488 0.13831 0.194649 - -0.0291182 0.0818713 0.189162 - -0.0230846 0.0959529 0.184556 - -0.0220886 0.0868966 0.183824 - -0.019578 0.0836748 0.181931 - -0.0110052 0.117602 0.175351 - 0.00903643 0.164366 0.160052 - 0.0188596 0.18477 0.15256 - 0.0265221 0.169864 0.146793 - 0.0271907 0.136858 0.146369 - 0.0293976 0.132114 0.144709 - 0.0290038 0.124445 0.145027 - 0.0345215 0.123907 0.140848 - 0.027672 0.0924708 0.146116 - 0.0551912 0.10934 0.125227 - 0.0455324 -0.0989255 0.134491 - 0.033258 -0.0958885 0.143533 - 0.0263179 -0.0934506 0.148645 - 0.0274037 -0.109192 0.147883 - 0.02702 -0.109473 0.148167 - 0.00413731 -0.155925 0.165154 --0.00141336 -0.153283 0.16924 - -0.0200162 -0.0727535 0.182757 - -0.0223066 -0.103954 0.184523 - -0.0248761 -0.0819998 0.186363 - -0.0254006 -0.0739966 0.18673 - -0.0274789 -0.0739271 0.188262 - -0.0287112 -0.0778509 0.189181 - -0.0392269 -0.156971 0.197131 - -0.0412064 -0.16574 0.198612 - -0.0453994 -0.194304 0.201775 - -0.0471612 -0.204098 0.203098 - -0.0630127 -0.284015 0.214985 - -0.0674028 -0.30844 0.218282 - -0.0702813 -0.312883 0.220416 - -0.0783171 -0.342539 0.226415 - -0.409314 -2.16117 0.474989 - -0.43408 -2.16539 0.493261 - -0.506433 -1.99227 0.54618 - -0.150431 -0.41228 0.27976 - -0.157043 -0.406913 0.284622 - -0.19812 -0.405115 0.314905 - -0.215632 -0.398591 0.327801 - -0.227129 -0.406285 0.336297 - -0.249811 -0.410611 0.353032 - -0.249023 -0.401582 0.352429 - -0.358492 -0.403718 0.433149 - -0.505909 -0.373158 0.54177 - -0.506534 -0.370019 0.542223 - -0.502931 -0.360115 0.539541 - -0.505448 -0.354914 0.541385 - -0.504113 -0.312925 0.540295 - -0.503418 -0.299333 0.53975 - -0.504468 -0.296734 0.540517 - -0.503758 -0.280249 0.539953 - -0.506375 -0.265977 0.541847 - -0.507307 -0.263363 0.542528 - -0.51005 -0.25549 0.544531 - -0.507337 -0.214817 0.542429 - -0.504672 -0.190411 0.540403 - -0.506646 -0.182589 0.541839 - -0.509571 -0.166586 0.543956 - -0.509277 -0.152424 0.543704 - -0.505963 -0.0623872 0.541037 - -0.506491 -0.0440303 0.541381 - -0.268797 -0.00110194 0.366014 - -0.28079 0.00855521 0.374833 - -0.5089 0.120027 0.54275 - -0.508045 0.125268 0.542106 - -0.502686 0.153914 0.538083 - -0.505488 0.171604 0.540106 - -0.503145 0.18488 0.538345 - -0.5004 0.192328 0.536303 - -0.510812 0.291516 0.543733 - -0.508752 0.296769 0.542201 - -0.512728 0.332803 0.545044 - -0.508184 0.364614 0.541614 - -0.504926 0.369308 0.5392 - -0.509417 0.429576 0.542361 - -0.505049 0.462044 0.53906 - -0.503425 0.464639 0.537856 - -0.499447 0.569352 0.534663 - -0.493799 0.931577 0.529598 - -0.490045 1.02047 0.526609 - -0.492011 1.11362 0.527828 - -0.481388 1.27206 0.519602 - -0.4574 1.27948 0.501896 - -0.363698 1.27385 0.43282 - -0.330411 1.27838 0.408265 - -0.0363338 0.0726505 0.194427 - -0.0316361 0.067499 0.190976 - -0.0401496 0.164946 0.197011 - -0.0298237 0.0918072 0.189579 - -0.0277822 0.0799262 0.188104 - -0.0249754 0.0829998 0.186026 - -0.021124 0.0998811 0.183145 - -0.0209179 0.088853 0.18302 - -0.0188625 0.0826461 0.18152 - -0.013226 0.111031 0.177294 - -0.0106697 0.115625 0.175397 --0.00844135 0.12632 0.173728 - 0.0104251 0.167267 0.159715 - 0.0296664 0.209183 0.145424 - 0.0218096 0.130594 0.151412 - 0.0280003 0.121229 0.146871 - 0.0273259 0.113687 0.147387 - 0.0289307 0.115998 0.146197 - 0.0326245 0.117926 0.143469 - 0.0325235 0.112119 0.143558 - 0.028227 0.0988966 0.146759 - 0.0261182 0.0897842 0.148336 - 0.0326401 0.0899477 0.143527 - 0.0898716 -0.146128 0.103733 - 0.0452764 -0.0948102 0.13578 - 0.0322119 -0.0887914 0.14519 - 0.0313978 -0.0883071 0.145776 - 0.0274036 -0.112044 0.148716 - 0.027007 -0.112322 0.149003 - 0.0262107 -0.112871 0.149579 - 0.0176474 -0.111513 0.155754 - 0.0223048 -0.150348 0.152489 - 0.0201709 -0.15133 0.154031 - 0.0141435 -0.13274 0.158334 - 0.0144462 -0.162075 0.158188 - 0.0117128 -0.160958 0.160157 - -0.0017262 -0.151441 0.169829 --0.00993969 -0.127757 0.175697 - -0.0163091 -0.0924544 0.180205 - -0.0195012 -0.0787608 0.182474 - -0.0206166 -0.078856 0.183279 - -0.0203878 -0.105881 0.18318 - -0.0218362 -0.107952 0.184231 - -0.0278876 -0.0728794 0.18851 - -0.0381666 -0.14803 0.196111 - -0.0733991 -0.318269 0.221949 - -0.412111 -2.16214 0.470861 - -0.443796 -2.15925 0.493713 - -0.46649 -2.15129 0.510066 - -0.164079 -0.405817 0.287587 - -0.183236 -0.406072 0.301408 - -0.186106 -0.404344 0.303474 - -0.20572 -0.407515 0.317632 - -0.235669 -0.408855 0.339242 - -0.273246 -0.40708 0.366349 - -0.306115 -0.406564 0.39006 - -0.362139 -0.409027 0.430485 - -0.404193 -0.410431 0.460829 - -0.452503 -0.412109 0.495686 - -0.496715 -0.422781 0.527609 - -0.507912 -0.350783 0.53551 - -0.509152 -0.348176 0.536398 - -0.509288 -0.327599 0.536445 - -0.510166 -0.321421 0.537063 - -0.508202 -0.199151 0.535344 - -0.503721 -0.166235 0.532031 - -0.506102 -0.104278 0.533596 - -0.503158 -0.0668138 0.531379 - -0.507272 -0.0568831 0.534323 - -0.502356 -0.0459412 0.53075 - -0.501451 -0.0329647 0.530065 - -0.270259 -0.00506796 0.363202 - -0.267045 -0.002392 0.360876 - -0.488108 0.0228718 0.5203 - -0.496845 0.0283943 0.52659 - -0.506325 0.0602437 0.533351 - -0.505073 0.161931 0.532197 - -0.513193 0.216704 0.53792 - -0.500129 0.31869 0.528244 - -0.510784 0.346435 0.535862 - -0.504665 0.363043 0.531407 - -0.509652 0.374027 0.534978 - -0.502241 0.390094 0.529591 - -0.50659 0.440005 0.532605 - -0.503773 0.465987 0.530509 - -0.503461 0.508927 0.530178 - -0.493557 0.534635 0.522969 - -0.497428 0.563095 0.525692 - -0.496285 0.581663 0.524821 - -0.492843 0.619143 0.522246 - -0.497589 0.720059 0.525421 - -0.488693 0.824525 0.518746 - -0.491548 0.929851 0.520546 - -0.493134 0.980089 0.521566 - -0.489664 0.982595 0.519056 - -0.495325 1.12591 0.522787 - -0.492445 1.1311 0.520697 - -0.474141 1.28854 0.507103 - -0.453283 1.27441 0.492089 - -0.435191 1.28341 0.479015 - -0.391856 1.27666 0.447767 - -0.034163 0.0811598 0.192657 - -0.0404925 0.164863 0.197017 - -0.0343704 0.130459 0.192685 - -0.0328372 0.121588 0.191601 - -0.024932 0.0869993 0.185983 - -0.0228797 0.0989747 0.184473 - -0.0215242 0.10993 0.183468 - -0.0204147 0.0848375 0.182729 - -0.011997 0.110898 0.176592 - -0.0075142 0.126229 0.17332 --0.00401933 0.140699 0.170763 - 0.016627 0.174692 0.155784 - 0.0226933 0.188096 0.151375 - 0.0274374 0.197773 0.147928 - 0.0283905 0.198439 0.147239 - 0.0348177 0.198843 0.142601 - 0.0259748 0.130829 0.149148 - 0.0299881 0.135086 0.146242 - 0.0342349 0.11613 0.143225 - 0.0243873 0.0808825 0.150417 - 0.0513408 0.1106 0.130898 - 0.143435 0.22218 0.0641813 - 0.133568 -0.207113 0.074804 - 0.0301948 -0.103496 0.147526 - 0.0294556 -0.104072 0.14805 - 0.0334463 -0.113998 0.145257 - 0.0233258 -0.121891 0.152421 - 0.0200077 -0.14851 0.154828 - 0.0105905 -0.121818 0.161411 - 0.0145582 -0.154955 0.158691 - 0.00307742 -0.153449 0.166792 - 0.00231658 -0.155691 0.167335 - 0.0008861 -0.154005 0.16834 --0.00857399 -0.127597 0.174954 --0.00971255 -0.125777 0.175753 - -0.0164009 -0.0905082 0.180389 - -0.0184989 -0.0756861 0.181833 - -0.0187687 -0.0757154 0.182024 - -0.0190386 -0.0757434 0.182215 - -0.019244 -0.0767669 0.182362 - -0.0268066 -0.0819343 0.187713 - -0.0381604 -0.144975 0.195883 - -0.0556481 -0.251015 0.208488 - -0.511042 -1.89364 0.533993 - -0.152225 -0.408793 0.277052 - -0.200708 -0.402409 0.311263 - -0.21924 -0.413786 0.324374 - -0.220715 -0.412737 0.325412 - -0.234985 -0.409144 0.335477 - -0.267943 -0.407037 0.358739 - -0.274745 -0.410819 0.36355 - -0.303359 -0.407286 0.383741 - -0.307315 -0.405804 0.386531 - -0.319556 -0.408666 0.395179 - -0.343742 -0.408573 0.412253 - -0.352095 -0.4084 0.418149 - -0.41735 -0.418215 0.46424 - -0.483684 -0.415966 0.511062 - -0.502472 -0.409681 0.52431 - -0.502836 -0.394923 0.524531 - -0.505639 -0.38979 0.526497 - -0.506359 -0.350829 0.52691 - -0.502489 -0.320874 0.524104 - -0.50713 -0.244487 0.527194 - -0.506874 -0.226417 0.526969 - -0.512343 -0.21709 0.530807 - -0.508161 -0.192087 0.527793 - -0.508472 -0.166776 0.527951 - -0.503822 -0.132433 0.524584 - -0.507438 -0.080076 0.527009 - -0.51014 -0.0699726 0.528892 - -0.510057 -0.0385481 0.528756 - -0.270932 0.00285482 0.359845 - -0.28311 0.00852831 0.368428 - -0.50052 0.0488663 0.52181 - -0.508069 0.0968756 0.527021 - -0.503524 0.160349 0.523657 - -0.502368 0.165461 0.522829 - -0.505662 0.220708 0.525019 - -0.504874 0.223276 0.524456 - -0.506598 0.297943 0.52549 - -0.504806 0.30006 0.52422 - -0.509701 0.357352 0.527535 - -0.501792 0.402006 0.521843 - -0.501801 0.461029 0.521705 - -0.50159 0.499199 0.521462 - -0.498123 0.633004 0.518687 - -0.4984 0.650236 0.51884 - -0.49608 0.652758 0.517197 - -0.493749 0.928149 0.514877 - -0.488633 1.01425 0.511054 - -0.487793 1.12467 0.510191 - -0.460273 1.27118 0.490405 - -0.36827 1.2748 0.425446 - -0.359173 1.27841 0.419016 - -0.0408548 0.102016 0.19718 - -0.0400617 0.104239 0.196615 - -0.0349578 0.0850084 0.193059 - -0.0404474 0.166849 0.196734 - -0.0328335 0.119551 0.191475 - -0.0195168 0.088805 0.182149 - -0.01452 0.0972606 0.178601 --0.00925196 0.119578 0.174827 --0.00166875 0.139251 0.169426 --0.00052316 0.143048 0.168608 - 0.00098156 0.148792 0.167532 - 0.00676958 0.161553 0.163414 - 0.00734535 0.161385 0.163008 - 0.0155959 0.173206 0.157155 - 0.0207068 0.189089 0.153508 - 0.0311993 0.209183 0.146052 - 0.034482 0.195091 0.143769 - 0.0298042 0.174822 0.147121 - 0.0232188 0.140387 0.151854 - 0.029901 0.134482 0.147151 - 0.0303802 0.134191 0.146814 - 0.0386715 0.132111 0.140965 - 0.0276804 0.0933582 0.148819 - 0.028013 0.0930795 0.148585 - 0.0262682 0.083556 0.14984 - 0.0311628 0.0852548 0.146381 - 0.0568885 0.11627 0.128144 - 0.0594874 0.114818 0.126313 - 0.0626275 0.118082 0.124088 - 0.211372 -0.298543 0.0238456 - 0.0600237 -0.118254 0.127841 - 0.0545083 -0.113443 0.131635 - 0.048069 -0.106929 0.136063 - 0.0340922 -0.0884856 0.145662 - 0.029302 -0.114063 0.14903 - 0.0235336 -0.116635 0.153016 - 0.0179463 -0.108794 0.156853 - 0.0178474 -0.111052 0.156926 - 0.0144651 -0.159402 0.159378 - -0.0184269 -0.0787333 0.181878 - -0.0184492 -0.0827487 0.181903 - -0.0306703 -0.0865932 0.190345 - -0.0390192 -0.150853 0.196262 - -0.040181 -0.156722 0.197078 - -0.0655755 -0.288511 0.214921 - -0.0674871 -0.294189 0.216254 - -0.425952 -2.1649 0.468149 - -0.482664 -2.16049 0.50727 - -0.50268 -1.93674 0.520538 - -0.517616 -1.72063 0.530319 - -0.147841 -0.408941 0.271979 - -0.164637 -0.40841 0.283567 - -0.169027 -0.406128 0.286591 - -0.180612 -0.399706 0.294569 - -0.208388 -0.404785 0.313748 - -0.20944 -0.402928 0.314469 - -0.2817 -0.4121 0.364352 - -0.285181 -0.413899 0.366759 - -0.312685 -0.407314 0.385721 - -0.325071 -0.410065 0.394274 - -0.350104 -0.410454 0.411549 - -0.353044 -0.406974 0.413569 - -0.383933 -0.411476 0.434894 - -0.434326 -0.414632 0.469674 - -0.454946 -0.409033 0.483888 - -0.489417 -0.418343 0.507697 - -0.505462 -0.387034 0.518692 - -0.504748 -0.262846 0.517898 - -0.499081 -0.235857 0.513922 - -0.502292 -0.231546 0.516127 - -0.504383 -0.189312 0.517468 - -0.505731 -0.184207 0.518385 - -0.503615 -0.161255 0.516869 - -0.513306 -0.0990914 0.523405 - -0.512075 -0.0750358 0.522497 - -0.504559 -0.0327409 0.517208 - -0.495921 -0.0221184 0.511222 - -0.494353 -0.0195471 0.510134 - -0.265814 -0.00363474 0.352398 - -0.278892 0.00969204 0.36139 - -0.505293 0.0361993 0.517548 - -0.503546 0.0514094 0.516305 - -0.508278 0.0545049 0.519562 - -0.501228 0.0845079 0.514625 - -0.500608 0.0895649 0.514185 - -0.505849 0.116894 0.517735 - -0.504453 0.129855 0.51674 - -0.504421 0.143273 0.516685 - -0.502202 0.161567 0.51511 - -0.506153 0.19078 0.517765 - -0.507893 0.197156 0.518951 - -0.505309 0.288796 0.516945 - -0.506955 0.309128 0.518031 - -0.504904 0.324277 0.516579 - -0.500679 0.358772 0.51358 - -0.500162 0.452315 0.512995 - -0.501618 0.536673 0.513796 - -0.49072 0.618986 0.506076 - -0.497597 0.65051 0.510744 - -0.495259 0.653011 0.509125 - -0.493496 0.679894 0.507843 - -0.491052 0.682373 0.506151 - -0.488336 0.728633 0.504164 - -0.4895 0.854308 0.504662 - -0.491777 0.891875 0.506142 - -0.488592 0.977284 0.503736 - -0.490002 1.087 0.504443 - -0.489707 1.14661 0.504095 - -0.447564 1.27247 0.474709 - -0.390602 1.2739 0.435401 - -0.381178 1.27677 0.42889 - -0.320117 1.27359 0.386765 - -0.0331044 0.127521 0.191505 - -0.0270158 0.0789116 0.187421 - -0.0252961 0.0779825 0.186237 - -0.0247812 0.0819936 0.185872 - -0.0222636 0.114981 0.184055 - -0.0202111 0.102898 0.182668 - -0.0197274 0.0968632 0.182349 - -0.0106856 0.110829 0.176076 --0.00406073 0.13687 0.171441 - 0.00031325 0.148077 0.168396 - 0.00530568 0.150848 0.164944 - 0.0403125 0.230047 0.140596 - 0.0240645 0.142491 0.15202 - 0.027417 0.135268 0.149725 - 0.0288615 0.13 0.148741 - 0.0314749 0.130636 0.146936 - 0.0324118 0.130043 0.146291 - 0.0263343 0.0985963 0.150561 - 0.0247424 0.0927299 0.151673 - 0.0262979 0.0878717 0.150612 - 0.0580313 0.113455 0.128653 - 0.346971 0.478939 -0.07161 - 0.480663 0.63473 -0.164239 - 0.103254 -0.162537 0.100059 - 0.0367436 -0.0905192 0.144761 - 0.0302164 -0.10464 0.149199 - 0.0271296 -0.105699 0.151284 - 0.023446 -0.115985 0.153794 - 0.0209147 -0.117424 0.155506 - 0.0186345 -0.115366 0.157039 - 0.0248914 -0.147978 0.152896 - 0.0262001 -0.155951 0.152033 - 0.0100602 -0.12254 0.162842 - 0.011415 -0.159593 0.162017 - 0.00475659 -0.153303 0.166494 --0.00489896 -0.137208 0.17297 - -0.0179931 -0.0717026 0.181647 - -0.0185975 -0.0787868 0.182072 - -0.0188242 -0.079809 0.182227 - -0.0205983 -0.11195 0.183502 - -0.0222069 -0.112991 0.18459 - -0.0295696 -0.07664 0.18947 - -0.485223 -2.15856 0.50193 - -0.513658 -1.77009 0.520179 - -0.511282 -1.73624 0.518494 - -0.521101 -1.72158 0.525083 - -0.150574 -0.421809 0.271947 - -0.171301 -0.400916 0.285881 - -0.193421 -0.407048 0.30082 - -0.206023 -0.405852 0.309321 - -0.218723 -0.404103 0.317885 - -0.221641 -0.402027 0.319849 - -0.329079 -0.413047 0.392366 - -0.343624 -0.41052 0.402174 - -0.372118 -0.406068 0.421388 - -0.378051 -0.405817 0.425391 - -0.419921 -0.415593 0.453665 - -0.452102 -0.411105 0.475367 - -0.504757 -0.358981 0.510768 - -0.502124 -0.323047 0.508905 - -0.503291 -0.320523 0.509686 - -0.506787 -0.306416 0.512011 - -0.50994 -0.276416 0.514066 - -0.50528 -0.234455 0.510821 - -0.506963 -0.229372 0.511944 - -0.510038 -0.145936 0.513818 - -0.505134 -0.117803 0.510441 - -0.509991 -0.103068 0.513682 - -0.508327 -0.0688044 0.512477 - -0.272159 0.00414482 0.352955 - -0.275412 0.00817857 0.35514 - -0.507251 0.0540438 0.511454 - -0.51013 0.119848 0.513239 - -0.508334 0.130072 0.512002 - -0.502397 0.155193 0.507936 - -0.500463 0.159959 0.506619 - -0.500887 0.165525 0.506892 - -0.504921 0.180719 0.509577 - -0.504197 0.222967 0.508987 - -0.506019 0.259513 0.510128 - -0.506354 0.30033 0.510255 - -0.510414 0.306104 0.512981 - -0.507381 0.317257 0.510907 - -0.503915 0.365946 0.508451 - -0.501556 0.454833 0.506645 - -0.497837 0.552668 0.5039 - -0.498644 0.609333 0.504307 - -0.493827 0.664245 0.500925 - -0.492139 0.777874 0.499512 - -0.490268 0.909433 0.497932 - -0.490626 0.937291 0.498106 - -0.487149 1.05111 0.495486 - -0.491603 1.1316 0.498297 - -0.487879 1.27177 0.495446 - -0.483609 1.27511 0.492557 - -0.456996 1.2767 0.474597 - -0.30956 1.26315 0.375152 - -0.271492 1.15425 0.34973 - -0.249424 1.15462 0.334839 - -0.0416596 0.10067 0.1972 - -0.0389031 0.0931879 0.195358 - -0.0372569 0.0915276 0.194251 - -0.0365101 0.09878 0.19373 - -0.0361098 0.150251 0.193335 - -0.0282753 0.0818042 0.188214 - -0.0238841 0.0949992 0.18522 - -0.0231379 0.113998 0.18467 - -0.015653 0.0904944 0.179677 --0.00432855 0.135004 0.171929 - 0.0105015 0.161831 0.161858 - 0.0407677 0.235468 0.141259 - 0.0408923 0.222748 0.141206 - 0.0324446 0.180728 0.147007 - 0.0235608 0.132264 0.153118 - 0.028661 0.130555 0.149681 - 0.0298764 0.117434 0.148893 - 0.0193583 0.0796359 0.15608 - 0.0263886 0.085967 0.151322 - 0.0295435 0.0819064 0.149203 - 0.058078 0.11833 0.129862 - 0.0917771 0.157179 0.107031 - 0.291203 0.417946 -0.0281543 - 0.334135 0.462632 -0.0572288 - 0.452091 0.604544 -0.137158 - 0.494376 0.652561 -0.165805 - 0.0478444 -0.104976 0.138378 - 0.0460377 -0.104147 0.139567 - 0.0191606 -0.111052 0.157313 - 0.0183505 -0.111488 0.157848 - 0.0243537 -0.138872 0.153954 - 0.00925298 -0.120982 0.163872 - 0.0135791 -0.141375 0.161067 - 0.0156818 -0.154202 0.159711 - 0.0161959 -0.161322 0.159389 - 0.0138407 -0.162116 0.160944 - 0.00966623 -0.157216 0.163686 - 0.00351328 -0.146607 0.167719 --0.00819349 -0.126767 0.175394 - -0.0188559 -0.0828487 0.182322 - -0.020346 -0.106952 0.183363 - -0.0222787 -0.108996 0.184642 - -0.0249206 -0.0839694 0.186325 - -0.0254176 -0.0799491 0.186643 - -0.0268262 -0.0788695 0.18757 - -0.027063 -0.0778509 0.187724 - -0.0285906 -0.071693 0.188717 - -0.0307618 -0.087511 0.190187 - -0.0310805 -0.0874698 0.190397 - -0.0422917 -0.169421 0.197988 - -0.0610175 -0.272181 0.210587 - -0.511027 -1.91505 0.511362 - -0.513059 -1.89337 0.512651 - -0.149398 -0.416173 0.26923 - -0.157791 -0.404843 0.274739 - -0.237022 -0.410268 0.327015 - -0.291655 -0.40813 0.363048 - -0.300733 -0.407088 0.369033 - -0.31281 -0.402771 0.376989 - -0.32493 -0.408666 0.384998 - -0.343793 -0.408336 0.39744 - -0.390444 -0.410242 0.428217 - -0.403813 -0.410514 0.437036 - -0.426116 -0.419526 0.451769 - -0.429161 -0.415292 0.453768 - -0.439869 -0.407731 0.460813 - -0.455192 -0.415236 0.470938 - -0.498467 -0.424994 0.499508 - -0.508479 -0.422194 0.506105 - -0.50339 -0.410138 0.502719 - -0.503519 -0.406468 0.502795 - -0.507362 -0.391013 0.505293 - -0.507414 -0.380093 0.505301 - -0.508065 -0.37339 0.505715 - -0.508719 -0.370313 0.506139 - -0.501287 -0.327086 0.501133 - -0.505841 -0.323535 0.504129 - -0.508478 -0.321975 0.505864 - -0.507437 -0.174225 0.504824 - -0.511227 -0.129222 0.507215 - -0.506802 -0.1254 0.504287 - -0.504759 -0.0755468 0.50282 - -0.50248 -0.0650141 0.501292 - -0.508582 -0.0402454 0.505257 - -0.501709 -0.0271228 0.500693 - -0.271029 0.00410337 0.348454 - -0.273517 0.00545364 0.350092 - -0.285988 0.00847451 0.358311 - -0.508302 0.0308817 0.504902 - -0.509803 0.0488663 0.50585 - -0.501117 0.0631232 0.500086 - -0.507451 0.161299 0.504028 - -0.508409 0.175357 0.504627 - -0.502732 0.187063 0.500855 - -0.503289 0.209734 0.501168 - -0.499852 0.236913 0.498835 - -0.499757 0.239788 0.498766 - -0.50295 0.277593 0.500781 - -0.501983 0.302134 0.500084 - -0.505654 0.310917 0.502485 - -0.506923 0.33492 0.503265 - -0.508489 0.381485 0.504186 - -0.505781 0.493999 0.50213 - -0.498855 0.565032 0.497391 - -0.498842 0.574953 0.497359 - -0.497913 0.594195 0.4967 - -0.495747 0.596668 0.495266 - -0.49249 0.635521 0.493024 - -0.486315 0.729539 0.488725 - -0.486935 1.10144 0.488243 - -0.492417 1.24678 0.491511 - -0.481122 1.27568 0.483992 - -0.407949 1.28221 0.435709 - -0.364005 1.27365 0.406742 - -0.0383042 0.0932675 0.194729 - -0.0276483 0.0768162 0.187739 - -0.0266174 0.0728854 0.187069 - -0.0260422 0.0789271 0.186675 - -0.0235444 0.100999 0.184974 - -0.0195438 0.110911 0.182312 - -0.0141021 0.0953748 0.178759 - -0.0125363 0.100183 0.177715 --0.00788764 0.122624 0.174595 - 9.185e-05 0.140232 0.169289 - 0.00110034 0.143048 0.168617 - 0.00815188 0.162692 0.163919 - 0.0121143 0.163586 0.161303 - 0.0425238 0.222406 0.141103 - 0.0405175 0.21265 0.14245 - 0.0299396 0.123527 0.149641 - 0.0313377 0.121515 0.148723 - 0.0310182 0.118311 0.148942 - 0.0326819 0.110235 0.147864 - 0.0220737 0.0875467 0.154915 - 0.0256671 0.0883492 0.152543 - 0.0272422 0.089492 0.151501 - 0.0726462 0.13199 0.12145 - 0.480451 0.641255 -0.14877 - 0.0455235 -0.0977017 0.140889 - 0.0443944 -0.101364 0.141626 - 0.0301732 -0.0828298 0.150755 - 0.0226969 -0.08654 0.155586 - 0.019974 -0.106542 0.15739 - 0.0187991 -0.107197 0.15815 - 0.0218146 -0.12638 0.15625 - 0.0242493 -0.134927 0.1547 - 0.0272986 -0.155017 0.152781 - 0.0235793 -0.15133 0.155171 - 0.0123106 -0.121056 0.162368 - 0.00918891 -0.12227 0.164385 - 0.0028011 -0.1459 0.168561 - -0.0186056 -0.101886 0.182264 - -0.0207353 -0.107976 0.183653 - -0.040597 -0.156541 0.196579 - -0.0758971 -0.318708 0.219735 - -0.0840355 -0.351423 0.225062 - -0.458623 -2.16509 0.470999 - -0.475503 -2.1653 0.481888 - -0.507852 -2.15842 0.502737 - -0.508467 -2.01919 0.502803 - -0.513101 -1.74638 0.505143 - -0.14932 -0.414294 0.267323 - -0.162145 -0.400842 0.275563 - -0.172968 -0.401829 0.282546 - -0.204349 -0.402409 0.302789 - -0.211333 -0.409267 0.307311 - -0.222574 -0.412054 0.314568 - -0.288042 -0.407765 0.356787 - -0.306702 -0.402693 0.368811 - -0.325099 -0.410242 0.380696 - -0.371104 -0.410842 0.410372 - -0.375913 -0.409297 0.41347 - -0.478773 -0.412415 0.479825 - -0.508156 -0.415565 0.498786 - -0.505289 -0.394367 0.496885 - -0.505344 -0.390731 0.496912 - -0.507523 -0.336101 0.498188 - -0.507298 -0.33258 0.498035 - -0.509724 -0.327532 0.499587 - -0.506387 -0.299256 0.497368 - -0.508151 -0.198502 0.498265 - -0.504062 -0.14506 0.4955 - -0.511818 -0.102203 0.500402 - -0.509004 -0.0706292 0.498511 - -0.509508 -0.0655765 0.498825 - -0.501619 -0.0594806 0.493721 - -0.50853 -0.032405 0.498114 - -0.507807 -0.0298307 0.497642 - -0.504557 -0.0271228 0.49554 - -0.500545 -0.0219257 0.492939 - -0.268953 0.00532639 0.343491 - -0.509686 0.0434779 0.49868 - -0.511686 0.0513215 0.499951 - -0.502909 0.116646 0.494134 - -0.503303 0.137681 0.494338 - -0.506491 0.190195 0.49627 - -0.506813 0.201529 0.49645 - -0.506854 0.227282 0.496415 - -0.506564 0.238829 0.496201 - -0.507121 0.245016 0.496545 - -0.511911 0.259513 0.499601 - -0.503596 0.31748 0.4941 - -0.50325 0.510479 0.493417 - -0.505717 0.522173 0.49498 - -0.5038 0.524673 0.493738 - -0.501875 0.527162 0.49249 - -0.496623 0.563972 0.489015 - -0.497113 0.616035 0.489207 - -0.495817 0.636271 0.488323 - -0.489884 0.64509 0.484475 - -0.493566 0.66763 0.486796 - -0.497895 0.691942 0.489531 - -0.492359 0.71513 0.485905 - -0.490569 0.731928 0.48471 - -0.489721 0.793341 0.484017 - -0.495227 0.899337 0.487317 - -0.493193 1.19945 0.48529 - -0.492409 1.22521 0.484723 - -0.492407 1.23949 0.484688 - -0.43126 1.28149 0.445146 - -0.37733 1.27765 0.410369 - -0.339369 1.26975 0.385902 - -0.332602 1.28355 0.381504 - -0.242964 1.13241 0.324044 - -0.0300465 0.0614027 0.189255 - -0.0371064 0.149048 0.193601 - -0.0266467 0.0698533 0.187042 - -0.0251206 0.0789537 0.186036 - -0.0198191 0.116943 0.182526 - -0.018474 0.0908497 0.181721 - -0.0149031 0.0894999 0.179421 - 0.0131347 0.165522 0.161154 - 0.0400429 0.237421 0.143627 - 0.0399688 0.211097 0.143737 - 0.039892 0.207945 0.143794 - 0.0255187 0.146033 0.153213 - 0.0264862 0.143416 0.152595 - 0.026563 0.140132 0.152553 - 0.0310092 0.142188 0.14968 - 0.0283657 0.103351 0.151478 - 0.0224821 0.0806132 0.155327 - 0.248857 0.371836 0.00861552 - 0.0485279 -0.10228 0.140285 - 0.0282447 -0.0828237 0.152944 - 0.0256797 -0.089688 0.154567 - 0.021073 -0.0859776 0.157444 - 0.028555 -0.10284 0.152797 - 0.0322126 -0.122175 0.150551 - 0.0238751 -0.155814 0.155853 - 0.00582456 -0.146325 0.167138 --0.00645699 -0.124629 0.174779 - -0.0141943 -0.0905082 0.179545 - -0.0168579 -0.07674 0.181181 - -0.0171417 -0.0767669 0.181359 - -0.0171726 -0.0807814 0.181388 - -0.0206655 -0.106985 0.183638 - -0.0231298 -0.119994 0.185212 - -0.0306513 -0.0904517 0.189854 - -0.0376101 -0.137797 0.194324 - -0.0675371 -0.281924 0.213411 - -0.510564 -1.88732 0.494707 - -0.152124 -0.404801 0.266685 - -0.161165 -0.405986 0.272351 - -0.168976 -0.403223 0.277237 - -0.191162 -0.404344 0.291137 - -0.194529 -0.403478 0.293244 - -0.19712 -0.400796 0.294861 - -0.210553 -0.409366 0.303295 - -0.212066 -0.408391 0.30424 - -0.224273 -0.404791 0.311878 - -0.272674 -0.40672 0.342201 - -0.30007 -0.40842 0.359365 - -0.329666 -0.406337 0.377899 - -0.342163 -0.411863 0.38574 - -0.396794 -0.415584 0.419969 - -0.400188 -0.415694 0.422096 - -0.424159 -0.415702 0.437111 - -0.450208 -0.40869 0.453411 - -0.487575 -0.417253 0.476837 - -0.501359 -0.41045 0.485455 - -0.512375 -0.364571 0.492248 - -0.508743 -0.331082 0.489894 - -0.508403 -0.276324 0.489552 - -0.513798 -0.257856 0.492888 - -0.511648 -0.253713 0.491531 - -0.512026 -0.141003 0.491502 - -0.506315 -0.100301 0.487828 - -0.509009 -0.0548856 0.489409 - -0.508386 -0.0396931 0.488982 - -0.506974 -0.0345652 0.488086 - -0.3349 -0.00939127 0.380241 - -0.268909 0.00021143 0.338882 - -0.505437 0.0327857 0.486964 - -0.509205 0.130408 0.489094 - -0.499602 0.1513 0.48303 - -0.511879 0.177012 0.490659 - -0.505696 0.202367 0.486726 - -0.509187 0.244233 0.488814 - -0.504569 0.256701 0.485892 - -0.507065 0.267087 0.487431 - -0.505309 0.269152 0.486326 - -0.506305 0.323444 0.486822 - -0.508426 0.344976 0.4881 - -0.506585 0.350488 0.486933 - -0.505022 0.395421 0.485848 - -0.504615 0.409971 0.485559 - -0.500105 0.469117 0.482595 - -0.498351 0.561849 0.481277 - -0.497749 0.571006 0.480878 - -0.495565 0.648122 0.479328 - -0.493758 0.705617 0.47806 - -0.48941 0.864874 0.474961 - -0.491147 1.05088 0.47561 - -0.331908 1.27201 0.375343 - -0.310636 1.26754 0.362029 - -0.0397705 0.0988983 0.195119 - -0.0375711 0.099401 0.19374 - -0.0351423 0.0927884 0.192234 - -0.033735 0.0849508 0.191371 - -0.0257005 0.0758986 0.18636 - -0.0231035 0.102996 0.184669 - -0.0185707 0.101899 0.181833 - -0.0180899 0.0818432 0.181579 - -0.0162022 0.0826787 0.180394 - -0.0126767 0.0963191 0.178154 - -0.0119646 0.0962154 0.177708 --0.00347238 0.133132 0.172302 --0.00079394 0.140699 0.170606 - 0.00210873 0.145135 0.168777 - 0.0124324 0.158746 0.162278 - 0.0158186 0.171134 0.160128 - 0.0490823 0.259577 0.139083 - 0.0319741 0.169212 0.150013 - 0.0279539 0.150684 0.152575 - 0.0305834 0.152668 0.150923 - 0.0272818 0.131508 0.153041 - 0.0313153 0.120312 0.150541 - 0.0339387 0.119774 0.148899 - 0.0297026 0.104212 0.151589 - 0.0247456 0.0855038 0.154738 - 0.0242297 0.0799002 0.155075 - 0.0281709 0.0827371 0.152599 - 0.532822 0.702353 -0.164972 - 0.0721561 -0.126871 0.12692 - 0.0450172 -0.0935142 0.143444 - 0.0451149 -0.102399 0.143405 - 0.0284215 -0.0917159 0.153592 - 0.0251084 -0.0964099 0.15563 - 0.0269523 -0.111168 0.154537 - 0.0201114 -0.110575 0.15872 - 0.0251191 -0.15133 0.155752 - 0.014055 -0.124078 0.162457 - 0.0155325 -0.152872 0.161621 - 0.0124622 -0.152822 0.163499 - 0.00244011 -0.143215 0.169607 --0.00717894 -0.11877 0.175434 --0.00948945 -0.114091 0.176837 - -0.0178912 -0.106901 0.18196 - -0.0182891 -0.10692 0.182203 - -0.0235089 -0.109982 0.185404 - -0.0244124 -0.0849459 0.185898 - -0.0255612 -0.0758745 0.186579 - -0.0260151 -0.0738379 0.186852 - -0.0301456 -0.0884638 0.189413 - -0.0383076 -0.141679 0.194531 - -0.0587931 -0.25227 0.207322 - -0.430881 -2.16702 0.439437 - -0.508761 -1.96096 0.486597 - -0.510952 -1.87776 0.487742 - -0.167891 -0.39863 0.274406 - -0.173371 -0.399089 0.27776 - -0.196407 -0.401694 0.291858 - -0.220079 -0.402532 0.306341 - -0.231507 -0.405049 0.313339 - -0.240694 -0.406608 0.318962 - -0.242206 -0.405483 0.319885 - -0.247186 -0.402897 0.322925 - -0.300461 -0.406861 0.355525 - -0.318537 -0.403528 0.366576 - -0.32884 -0.410242 0.372895 - -0.391465 -0.414592 0.411215 - -0.407274 -0.413807 0.420885 - -0.436473 -0.411227 0.438741 - -0.447824 -0.407731 0.445677 - -0.47212 -0.412109 0.46055 - -0.50705 -0.409145 0.481912 - -0.505484 -0.378486 0.480882 - -0.506179 -0.375456 0.4813 - -0.511706 -0.365483 0.484657 - -0.505852 -0.357642 0.481058 - -0.508357 -0.349136 0.482571 - -0.508084 -0.322122 0.482341 - -0.503358 -0.290339 0.479374 - -0.508613 -0.184995 0.482342 - -0.510208 -0.0928146 0.483102 - -0.509708 -0.0901599 0.48279 - -0.512375 -0.0676362 0.484369 - -0.511185 -0.0522881 0.483605 - -0.510027 -0.0295727 0.482843 - -0.264995 -0.00476689 0.332886 - -0.50582 0.0450553 0.480094 - -0.504622 0.0499155 0.47935 - -0.511833 0.0658486 0.483724 - -0.505549 0.113174 0.479769 - -0.5062 0.128858 0.48013 - -0.505654 0.152338 0.479742 - -0.504963 0.162761 0.479294 - -0.509399 0.2112 0.481894 - -0.504572 0.223243 0.478913 - -0.500901 0.241596 0.476624 - -0.508461 0.251325 0.481226 - -0.507474 0.306177 0.480494 - -0.507753 0.316024 0.480642 - -0.507418 0.328913 0.480407 - -0.507898 0.335896 0.480683 - -0.506471 0.348396 0.479781 - -0.509209 0.396562 0.481344 - -0.501488 0.427745 0.476547 - -0.505764 0.455457 0.479098 - -0.49892 0.465277 0.474888 - -0.503289 0.512752 0.477449 - -0.493483 0.577569 0.471299 - -0.492274 0.80963 0.470015 - -0.493687 1.08475 0.470235 - -0.489996 1.16262 0.467794 - -0.494584 1.27328 0.470341 - -0.436811 1.28242 0.434977 - -0.426366 1.28379 0.428584 - -0.359402 1.27237 0.387646 - -0.312122 1.26754 0.358733 - -0.0409394 0.104678 0.195564 - -0.0400273 0.101836 0.195012 - -0.0284023 0.0595257 0.188 - -0.0310218 0.105474 0.189495 - -0.020747 0.108989 0.183201 - -0.015552 0.0816504 0.180087 - -0.0143491 0.0885455 0.179335 - -0.0136902 0.0884638 0.178932 - -0.0048302 0.12336 0.17343 - 0.0114688 0.160243 0.163373 - 0.032679 0.171364 0.150371 - 0.0317888 0.150273 0.150965 - 0.0316168 0.142743 0.151088 - 0.0339136 0.143726 0.149681 - 0.034982 0.143148 0.149028 - 0.0267184 0.0998012 0.154185 - 0.0218571 0.0845988 0.157195 - 0.0265224 0.0917965 0.154324 - 0.0252856 0.0844245 0.155098 - 0.0244921 0.0814443 0.15559 - 0.0330291 0.0903198 0.150347 - 0.0565762 0.122124 0.135867 - 0.0517199 0.107561 0.138872 - 0.0529158 0.10642 0.138143 - 0.583749 0.748069 -0.188098 - 0.301129 -0.389435 -0.00812516 - 0.0430222 -0.0896816 0.145541 - 0.0427512 -0.0925346 0.145709 - 0.0319487 -0.0858009 0.152154 - 0.0258705 -0.0928558 0.155806 - 0.022907 -0.0879236 0.157567 - 0.0276259 -0.105499 0.154786 - 0.0291403 -0.115873 0.153904 - 0.0266243 -0.142394 0.155471 - 0.0274568 -0.150598 0.154992 - 0.0278189 -0.15791 0.154792 - 0.0100474 -0.113202 0.165317 - 0.0170384 -0.161922 0.161249 - 0.0118822 -0.153166 0.164312 --0.00851702 -0.115018 0.176424 - -0.0162743 -0.0777638 0.180976 - -0.0163735 -0.0807814 0.181042 - -0.0199582 -0.103985 0.18324 - -0.0231173 -0.106982 0.185137 - -0.0309018 -0.0923472 0.189758 - -0.0503373 -0.212328 0.201662 - -0.442305 -2.17075 0.440648 - -0.458551 -2.16637 0.450353 - -0.504372 -1.99764 0.477364 - -0.510522 -1.89557 0.480804 - -0.51022 -1.83608 0.480485 - -0.514393 -1.76949 0.482826 - -0.51565 -1.74797 0.483527 - -0.16308 -0.403415 0.269534 - -0.165246 -0.404537 0.270833 - -0.219324 -0.41165 0.303191 - -0.222219 -0.405129 0.304907 - -0.226118 -0.404791 0.307238 - -0.231986 -0.404194 0.310746 - -0.241216 -0.405762 0.31627 - -0.276642 -0.401711 0.337448 - -0.298212 -0.408915 0.350365 - -0.34821 -0.411677 0.380273 - -0.403302 -0.411029 0.41322 - -0.428154 -0.41166 0.428085 - -0.429694 -0.409587 0.429001 - -0.505649 -0.359043 0.474309 - -0.50109 -0.325535 0.471504 - -0.502307 -0.323092 0.472227 - -0.512033 -0.293997 0.477976 - -0.500982 -0.275139 0.471322 - -0.503474 -0.252594 0.47276 - -0.510471 -0.241448 0.476919 - -0.506001 -0.230565 0.474221 - -0.508558 -0.223153 0.475732 - -0.508613 -0.217475 0.475752 - -0.507003 -0.180678 0.474703 - -0.508024 -0.135686 0.475209 - -0.508448 -0.115022 0.475415 - -0.509078 -0.0946545 0.475744 - -0.502793 -0.0834003 0.471959 - -0.508776 -0.0692966 0.475504 - -0.500665 -0.0435314 0.470593 - -0.51054 -0.0369311 0.476484 - -0.273813 -0.00620001 0.334834 - -0.272982 0.00532639 0.33431 - -0.333767 0.0129677 0.370646 - -0.5007 0.0443426 0.470409 - -0.500355 0.0492124 0.470192 - -0.504558 0.0845122 0.472623 - -0.506602 0.243177 0.473475 - -0.50462 0.250958 0.472272 - -0.510924 0.284642 0.475964 - -0.508119 0.295469 0.474261 - -0.505834 0.313111 0.472854 - -0.496961 0.346439 0.467469 - -0.503766 0.358249 0.471512 - -0.507605 0.371605 0.473776 - -0.507409 0.419165 0.473548 - -0.50491 0.460385 0.471958 - -0.499336 0.49273 0.468549 - -0.497402 0.545008 0.46727 - -0.496579 0.548828 0.466769 - -0.49695 0.554066 0.466979 - -0.495976 0.577569 0.466342 - -0.494725 0.591333 0.465561 - -0.490987 0.612909 0.463275 - -0.493912 0.644462 0.464951 - -0.491693 0.760841 0.463353 - -0.491318 0.867266 0.46288 - -0.49101 0.919101 0.462576 - -0.494105 0.934404 0.464391 - -0.487004 0.96799 0.460066 - -0.488803 1.00224 0.461062 - -0.49074 1.01694 0.462186 - -0.491509 1.04026 0.462592 - -0.492752 1.06544 0.463276 - -0.470851 1.27855 0.449681 - -0.350534 1.27193 0.37774 - -0.314164 1.27044 0.355992 - -0.30262 1.24192 0.349154 - -0.228357 1.04177 0.305206 - -0.0385532 0.109243 0.193865 - -0.034626 0.0907491 0.191559 - -0.0342861 0.0908142 0.191355 - -0.0293386 0.0663944 0.188453 - -0.0285922 0.0665064 0.188007 - -0.0327992 0.11024 0.190421 - -0.0256847 0.072847 0.186253 - -0.0208421 0.100995 0.183291 - -0.0204639 0.10099 0.183065 - -0.0176843 0.0948871 0.181417 - -0.0158684 0.0847329 0.180355 - -0.0156218 0.0837063 0.18021 - -0.0115554 0.0952757 0.177751 --0.00291271 0.130174 0.1725 - 0.00114946 0.136427 0.170056 - 0.00390206 0.139853 0.168402 - 0.0118321 0.159271 0.163614 - 0.0340463 0.152756 0.150344 - 0.0347874 0.130327 0.149953 - 0.0352752 0.130038 0.149662 - 0.0328275 0.117993 0.151154 - 0.0220178 0.0907025 0.157682 - 0.0201428 0.085048 0.158817 - 0.0268246 0.0885149 0.154813 - 0.0229371 0.0783474 0.157161 - 0.0251362 0.0814443 0.155839 - 0.0291237 0.0867488 0.153442 - 0.0294483 0.0864898 0.153248 - 0.0519064 0.115693 0.139749 - 0.136117 0.222865 0.0891357 - 0.274946 0.408077 0.00567546 - 0.569891 0.738896 -0.171492 - 0.0470103 -0.0957385 0.144184 - 0.0302476 -0.0865763 0.153939 - 0.0281707 -0.0940816 0.155168 - 0.0195933 -0.082513 0.160143 - 0.0247289 -0.107663 0.157206 - 0.0243229 -0.107893 0.157444 - 0.0223249 -0.107887 0.158609 - 0.0224511 -0.113316 0.158548 - 0.0156249 -0.101473 0.162502 - 0.0235454 -0.127989 0.157944 - 0.0275585 -0.148727 0.155651 - 0.00962348 -0.114628 0.166032 - 0.0124219 -0.150091 0.164482 - 0.00634084 -0.152754 0.168035 - 0.00576497 -0.152891 0.168371 - 0.00306532 -0.147388 0.169933 --0.00868879 -0.113099 0.176708 - -0.0154784 -0.0787333 0.180589 - -0.0194902 -0.107985 0.182996 - -0.0203121 -0.106996 0.183473 - -0.0235605 -0.107961 0.18537 - -0.025614 -0.0698036 0.186479 - -0.0260793 -0.0727706 0.186757 - -0.0263536 -0.0727447 0.186917 - -0.0272951 -0.0776674 0.187478 - -0.0283113 -0.0825762 0.188082 - -0.0356733 -0.123846 0.192471 - -0.0658483 -0.273083 0.210414 - -0.461852 -2.17026 0.445758 - -0.507879 -2.00053 0.472208 - -0.509861 -1.79639 0.472891 - -0.151078 -0.397322 0.260408 - -0.200632 -0.412404 0.289343 - -0.211022 -0.404974 0.295386 - -0.212547 -0.404009 0.296273 - -0.219041 -0.40094 0.300053 - -0.225972 -0.406693 0.304108 - -0.242262 -0.405762 0.313607 - -0.279973 -0.404925 0.335598 - -0.310022 -0.405631 0.353125 - -0.325902 -0.405776 0.362386 - -0.338912 -0.408461 0.36998 - -0.357312 -0.406407 0.380706 - -0.392282 -0.411137 0.401112 - -0.420184 -0.4085 0.417378 - -0.440079 -0.413994 0.428993 - -0.502325 -0.4233 0.465317 - -0.503918 -0.420863 0.466241 - -0.50831 -0.35551 0.468651 - -0.508674 -0.315727 0.468771 - -0.509423 -0.191488 0.46892 - -0.506867 -0.187753 0.467421 - -0.506488 -0.179461 0.46718 - -0.508285 -0.134988 0.468126 - -0.508792 -0.132526 0.468415 - -0.509099 -0.117091 0.468559 - -0.512932 -0.110255 0.470779 - -0.509503 -0.104374 0.468765 - -0.503694 -0.0905742 0.465345 - -0.511014 -0.0742488 0.469576 - -0.504715 -0.0362843 0.465815 - -0.507022 -0.024149 0.467133 - -0.441527 0.019473 0.428834 - -0.509286 0.0473627 0.468287 - -0.514196 0.124326 0.470972 - -0.513245 0.129301 0.470406 - -0.508388 0.135808 0.467559 - -0.509063 0.225709 0.467744 - -0.508648 0.300402 0.467329 - -0.501376 0.311655 0.463062 - -0.501264 0.317982 0.462982 - -0.509546 0.333355 0.467777 - -0.501989 0.408407 0.463195 - -0.503536 0.43263 0.464041 - -0.49353 0.546989 0.457941 - -0.488387 0.66796 0.454662 - -0.491026 0.696207 0.456136 - -0.491026 0.708858 0.456106 - -0.488352 0.711221 0.454542 - -0.489799 0.753533 0.455287 - -0.490513 1.01077 0.455108 - -0.487919 1.01578 0.453584 - -0.489692 1.07554 0.45448 - -0.486408 1.07968 0.452554 - -0.488375 1.18607 0.453456 - -0.487809 1.19844 0.453097 - -0.268029 1.12354 0.325094 - -0.263165 1.12186 0.322261 - -0.0335958 0.0858171 0.190774 - -0.0279129 0.0554605 0.18753 - -0.0273947 0.0565494 0.187225 - -0.0310741 0.100359 0.189269 - -0.0245785 0.0748999 0.18554 - -0.0223865 0.104992 0.184192 - -0.0207798 0.111998 0.183239 --0.00464923 0.124519 0.173802 - 0.00322264 0.142193 0.169171 - 0.00608332 0.148655 0.167487 - 0.00664351 0.148515 0.167161 - 0.0208037 0.181558 0.158826 - 0.0367669 0.230363 0.149403 - 0.0402791 0.203871 0.147416 - 0.0241386 0.0815425 0.157113 - 0.02694 0.0817917 0.155478 - 0.0568955 0.12212 0.137915 - 0.0608837 0.124903 0.135582 - 0.0532767 0.106406 0.140062 - 0.0629638 0.119185 0.134382 - 0.456912 0.636571 -0.0965676 - 0.348041 -0.424571 -0.025559 - 0.0250343 -0.0931661 0.157625 - 0.0180025 -0.0804972 0.1616 - 0.0209015 -0.108957 0.160015 - 0.0201587 -0.113671 0.160449 - 0.0265989 -0.136574 0.156834 - 0.0318804 -0.166369 0.153895 - 0.0101085 -0.119878 0.166186 - 0.0150306 -0.153612 0.163461 - 0.0114328 -0.148482 0.165498 - 0.0111349 -0.158849 0.165691 - 0.0089564 -0.157359 0.166929 - -0.0178799 -0.107952 0.182098 - -0.0268149 -0.0796903 0.187121 - -0.0838961 -0.342298 0.220232 - -0.0889305 -0.354338 0.223127 - -0.0906566 -0.355941 0.224114 - -0.463954 -2.16929 0.440873 - -0.504711 -1.85249 0.463355 - -0.14984 -0.425675 0.257978 - -0.153274 -0.413631 0.259906 - -0.154548 -0.401327 0.260603 - -0.183259 -0.405803 0.276964 - -0.203608 -0.404323 0.288549 - -0.216537 -0.406533 0.295916 - -0.220897 -0.407158 0.298401 - -0.225514 -0.404103 0.301023 - -0.315135 -0.407239 0.352068 - -0.353699 -0.410741 0.374038 - -0.37549 -0.404511 0.386433 - -0.384147 -0.407205 0.391369 - -0.402928 -0.41353 0.402079 - -0.410807 -0.411107 0.40656 - -0.434459 -0.413626 0.420036 - -0.443529 -0.415292 0.425205 - -0.507121 -0.421465 0.461434 - -0.506629 -0.417223 0.461143 - -0.504717 -0.411807 0.460042 - -0.508208 -0.363955 0.46192 - -0.509364 -0.255871 0.46233 - -0.509007 -0.179461 0.46195 - -0.511342 -0.177607 0.463276 - -0.506672 -0.1679 0.460594 - -0.509451 -0.137211 0.462106 - -0.510477 -0.132297 0.462679 - -0.508665 -0.108735 0.461593 - -0.510826 -0.0889141 0.462778 - -0.510972 -0.0738594 0.462827 - -0.509474 -0.0537441 0.461927 - -0.26493 0.00510824 0.322528 - -0.503778 0.0368333 0.458475 - -0.50498 0.05651 0.459114 - -0.506259 0.091386 0.459762 - -0.509178 0.112195 0.461376 - -0.506343 0.131967 0.459717 - -0.509867 0.140723 0.461703 - -0.497595 0.147408 0.454699 - -0.506707 0.249328 0.459654 - -0.504967 0.251353 0.458658 - -0.508554 0.324407 0.460533 - -0.506814 0.356635 0.459468 - -0.502728 0.437482 0.456955 - -0.497718 0.444698 0.454085 - -0.504656 0.463357 0.457993 - -0.505245 0.497817 0.458249 - -0.495552 0.541783 0.452628 - -0.499405 0.565561 0.454768 - -0.494841 0.600712 0.452087 - -0.492847 0.714407 0.450691 - -0.491204 0.738288 0.4497 - -0.490331 0.808579 0.449041 - -0.487103 0.850344 0.447107 - -0.488878 0.870299 0.448071 - -0.490067 1.09457 0.448232 - -0.490875 1.1728 0.448512 - -0.487053 1.20444 0.446263 - -0.497329 1.26044 0.451986 - -0.454928 1.28373 0.427786 - -0.378089 1.28317 0.384029 - -0.327541 1.27128 0.35527 - -0.0328806 0.0808255 0.190206 - -0.0263528 0.07674 0.186498 - -0.0257192 0.071782 0.186148 - -0.0192594 0.102983 0.182398 - -0.0188689 0.102974 0.182175 - -0.0154215 0.0887785 0.180245 - -0.0138184 0.0836072 0.179344 --0.00952586 0.102167 0.176857 - 0.00340766 0.140232 0.169404 - 0.00773948 0.151447 0.166911 - 0.0116168 0.155552 0.164693 - 0.036278 0.225563 0.150488 - 0.0301558 0.111466 0.154237 - 0.0243131 0.0830708 0.15763 - 0.0537453 0.118054 0.140788 - 0.0546384 0.1173 0.140281 - 0.0550828 0.116919 0.140029 - 0.499212 0.682234 -0.114196 - 0.593508 0.757898 -0.16807 - 0.65843 0.823455 -0.205193 - 0.701462 0.860444 -0.229784 - 0.32914 -0.410731 -0.0101975 - 0.0446514 -0.0903339 0.14731 - 0.0309192 -0.0846721 0.154936 - 0.026256 -0.0822283 0.157524 - 0.02518 -0.108121 0.158182 - 0.0110934 -0.109241 0.166019 - 0.00524406 -0.14407 0.169353 --0.00301182 -0.125451 0.173902 --0.00504944 -0.124786 0.175034 - -0.0112839 -0.091416 0.178426 - -0.0249754 -0.0858356 0.186028 - -0.0257465 -0.0737412 0.18643 - -0.0298721 -0.0853043 0.188751 - -0.0378094 -0.133502 0.193276 - -0.0500966 -0.198072 0.200258 - -0.0510031 -0.198905 0.200765 - -0.155261 -0.40226 0.259221 - -0.158325 -0.400894 0.260923 - -0.177744 -0.404569 0.271732 - -0.182726 -0.40308 0.2745 - -0.187584 -0.410417 0.277219 - -0.192213 -0.412338 0.279798 - -0.335292 -0.407169 0.359371 - -0.348542 -0.409652 0.366747 - -0.36076 -0.410278 0.373544 - -0.417463 -0.412502 0.405089 - -0.42477 -0.409162 0.409146 - -0.437364 -0.410891 0.416155 - -0.446487 -0.412518 0.421233 - -0.506922 -0.396795 0.454813 - -0.506307 -0.343739 0.454349 - -0.512236 -0.334487 0.457626 - -0.50634 -0.314254 0.454301 - -0.500317 -0.304061 0.450927 - -0.507609 -0.299206 0.454972 - -0.505501 -0.232396 0.453646 - -0.503963 -0.228825 0.452783 - -0.504833 -0.226407 0.453261 - -0.504884 -0.223611 0.453283 - -0.506592 -0.210398 0.454203 - -0.509422 -0.189564 0.455729 - -0.505168 -0.15084 0.453274 - -0.511193 -0.13184 0.456582 - -0.272976 0.00020997 0.323777 - -0.272974 0.00147096 0.323773 - -0.428223 0.0186733 0.410087 - -0.500303 0.0315799 0.450151 - -0.509975 0.0741541 0.455433 - -0.513208 0.102371 0.457167 - -0.509428 0.109167 0.455049 - -0.518197 0.169119 0.45979 - -0.505412 0.188766 0.452633 - -0.507507 0.222739 0.453721 - -0.504225 0.224042 0.451892 - -0.506375 0.236405 0.45306 - -0.506546 0.250942 0.453122 - -0.501864 0.26018 0.450496 - -0.505127 0.279913 0.452266 - -0.505897 0.301967 0.452644 - -0.502408 0.309209 0.450687 - -0.509563 0.374304 0.454517 - -0.498628 0.435534 0.448295 - -0.499408 0.476696 0.448634 - -0.505748 0.504677 0.452097 - -0.501109 0.555053 0.449401 - -0.496647 0.579449 0.446864 - -0.498378 0.612909 0.44775 - -0.496244 0.637614 0.446507 - -0.487205 0.70246 0.44133 - -0.498661 0.746357 0.447602 - -0.488224 0.757414 0.441771 - -0.495375 0.79073 0.445673 - -0.489595 0.920373 0.442161 - -0.491952 0.953429 0.443396 - -0.489818 0.999318 0.442104 - -0.489731 1.04232 0.441958 - -0.490916 1.05623 0.442585 - -0.492337 1.11906 0.443232 - -0.491833 1.13043 0.442925 - -0.420989 1.27562 0.403187 - -0.393808 1.2758 0.388068 - -0.264981 1.12089 0.316765 - -0.0386941 0.104959 0.193223 - -0.0372467 0.10629 0.192414 - -0.0274898 0.0574413 0.187099 - -0.0279587 0.0785365 0.187312 - -0.0261175 0.0707067 0.186305 - -0.0256508 0.0717569 0.186043 - -0.022531 0.108976 0.184223 - -0.0148754 0.0857587 0.180018 --0.00405375 0.125591 0.173907 - -0.0006293 0.132048 0.171988 - 0.0107888 0.154898 0.165584 - 0.0188901 0.177336 0.161027 - 0.0197846 0.178105 0.160528 - 0.0410723 0.210476 0.148613 - 0.0195866 0.084333 0.160852 - 0.0234657 0.0852646 0.158693 - 0.0527492 0.112114 0.142343 - 0.0448239 0.0964096 0.146787 - 0.462357 0.646702 -0.0867168 - 0.725371 0.883446 -0.233555 - 0.324724 -0.409864 -0.00304607 - 0.304066 -0.399004 0.00813816 - 0.044507 -0.0898827 0.148271 - 0.0468843 -0.0992242 0.147002 - 0.0301291 -0.0846031 0.15606 - 0.0280841 -0.091996 0.157187 - 0.0228483 -0.090767 0.160025 - 0.0221509 -0.0911884 0.160404 - 0.0278939 -0.105832 0.157321 - 0.0230918 -0.105167 0.159925 - 0.0194313 -0.107008 0.161916 - 0.0128704 -0.115105 0.165494 - 0.00960354 -0.121442 0.167281 - 0.0122519 -0.144442 0.165896 --0.00645621 -0.117001 0.175985 - -0.0111986 -0.0914603 0.1785 - -0.0136523 -0.0786737 0.179802 - -0.0160494 -0.102905 0.181158 - -0.0225497 -0.11096 0.184704 - -0.0240849 -0.0758547 0.185457 - -0.0249573 -0.0757867 0.18593 - -0.0388253 -0.135297 0.19359 - -0.0501896 -0.194967 0.199892 - -0.510551 -1.7716 0.453271 - -0.150289 -0.413068 0.254702 - -0.151326 -0.405189 0.255247 - -0.209306 -0.405115 0.286706 - -0.217018 -0.41288 0.290908 - -0.2186 -0.411896 0.291765 - -0.2618 -0.404002 0.315187 - -0.269958 -0.406092 0.319618 - -0.278206 -0.408007 0.324098 - -0.31196 -0.410091 0.342417 - -0.366095 -0.407579 0.371785 - -0.374471 -0.406642 0.376328 - -0.505448 -0.404645 0.447391 - -0.50913 -0.403991 0.449387 - -0.505236 -0.37909 0.447218 - -0.504636 -0.250903 0.446601 - -0.50962 -0.230353 0.449259 - -0.509 -0.218763 0.448896 - -0.511633 -0.184047 0.450245 - -0.512925 -0.126493 0.450815 - -0.504474 -0.11425 0.446202 - -0.515202 -0.104011 0.452 - -0.509683 -0.0655336 0.448917 - -0.509932 -0.0631019 0.449047 - -0.477679 -0.0178043 0.431444 - -0.509822 0.0296083 0.448776 - -0.509706 0.0320393 0.448708 - -0.510739 0.0443426 0.449241 - -0.507369 0.0537888 0.44739 - -0.506233 0.0658701 0.446746 - -0.508595 0.0686505 0.448022 - -0.506148 0.100406 0.446622 - -0.504096 0.107444 0.445492 - -0.504904 0.122689 0.445896 - -0.510303 0.131737 0.448805 - -0.510962 0.17115 0.449073 - -0.506685 0.21847 0.446644 - -0.501644 0.227329 0.443889 - -0.508619 0.292809 0.447525 - -0.507853 0.327257 0.447031 - -0.502768 0.336887 0.44425 - -0.507649 0.381593 0.446796 - -0.506892 0.425317 0.446286 - -0.500224 0.541783 0.442403 - -0.497111 0.624538 0.440526 - -0.496511 0.646168 0.440151 - -0.493254 0.701714 0.438258 - -0.493057 0.761499 0.438014 - -0.490725 0.848652 0.436551 - -0.496756 0.920612 0.43966 - -0.49188 0.929633 0.436993 - -0.493988 1.03553 0.437896 - -0.491626 1.04143 0.436601 - -0.491413 1.16281 0.436209 - -0.491963 1.26424 0.436277 - -0.490854 1.27671 0.435647 - -0.308431 1.24482 0.336737 - -0.0420118 0.108173 0.194765 - -0.0267605 0.0726055 0.186571 - -0.026482 0.0726379 0.186419 - -0.0208692 0.104996 0.1833 - -0.0200648 0.108 0.182857 - -0.0166912 0.10993 0.181022 --0.00531089 0.115777 0.174834 --0.00428988 0.116613 0.174278 - 2.201e-05 0.133033 0.171901 - 0.0283595 0.205702 0.15636 - 0.0393898 0.211382 0.150362 - 0.0431443 0.208907 0.14833 - 0.0356651 0.151195 0.15252 - 0.0253652 0.0981959 0.158229 - 0.0257416 0.0979691 0.158025 - 0.0256462 0.0900287 0.158095 - 0.03247 0.0911116 0.15439 - 0.045001 0.0981782 0.147575 - 0.0453772 0.0978539 0.147371 - 0.34489 0.503568 -0.0160667 - 0.479808 0.665701 -0.0896418 - 0.511608 0.701822 -0.106978 - 0.0458638 -0.093184 0.148428 - 0.0397709 -0.0884048 0.151641 - 0.0431549 -0.0942904 0.149864 - 0.0440346 -0.101002 0.149414 - 0.0351054 -0.0909697 0.154115 - 0.0296344 -0.0866673 0.157 - 0.0266049 -0.0829191 0.158595 - 0.0274887 -0.0905096 0.158144 - 0.0273158 -0.0929356 0.158241 - 0.0225007 -0.105799 0.160818 - 0.0213192 -0.111823 0.161457 - 0.0317884 -0.155529 0.156016 - 0.02907 -0.157703 0.157459 - 0.00959166 -0.108086 0.167653 - 0.0035944 -0.141607 0.170902 - -0.0140747 -0.0717304 0.180093 - -0.020429 -0.105995 0.183532 - -0.0256864 -0.0746802 0.186243 - -0.0268264 -0.0775666 0.186853 - -0.0438452 -0.15964 0.196043 - -0.0722469 -0.292954 0.211372 - -0.0833102 -0.332205 0.217314 - -0.090326 -0.346817 0.221059 - -0.486043 -2.1589 0.434532 - -0.512948 -2.08502 0.4486 - -0.15888 -0.405308 0.257464 - -0.187687 -0.403248 0.2727 - -0.190001 -0.404217 0.273927 - -0.191943 -0.404271 0.274955 - -0.209164 -0.40335 0.284064 - -0.244354 -0.406877 0.302691 - -0.286599 -0.404413 0.325037 - -0.31795 -0.405702 0.341628 - -0.319514 -0.404224 0.342452 - -0.333974 -0.412614 0.350121 - -0.361466 -0.407378 0.364655 - -0.363646 -0.406407 0.365807 - -0.379844 -0.403807 0.374371 - -0.426123 -0.413857 0.39888 - -0.449932 -0.411872 0.411473 - -0.502886 -0.415439 0.439499 - -0.503222 -0.375695 0.439586 - -0.512579 -0.365306 0.444514 - -0.509317 -0.352602 0.442759 - -0.50265 -0.290205 0.43909 - -0.504573 -0.249661 0.440016 - -0.498195 -0.20746 0.436546 - -0.503877 -0.201734 0.43954 - -0.511931 -0.194112 0.443783 - -0.505951 -0.152193 0.440524 - -0.507378 -0.142315 0.441257 - -0.504219 -0.108657 0.43951 - -0.510428 -0.0925182 0.442758 - -0.508038 -0.0772569 0.441459 - -0.513417 -0.0509264 0.444246 - -0.510166 -0.0335397 0.442486 - -0.498255 -0.0232482 0.436161 - -0.478987 -0.0177701 0.425954 - -0.260043 -0.00336276 0.310079 - -0.505185 0.04363 0.439676 - -0.506432 0.0607122 0.440298 - -0.510082 0.0685279 0.442211 - -0.509254 0.0757839 0.441756 - -0.51149 0.0985153 0.442888 - -0.510801 0.170271 0.442361 - -0.511321 0.178444 0.442618 - -0.505744 0.211478 0.439592 - -0.512181 0.263171 0.442881 - -0.504091 0.270636 0.438584 - -0.509408 0.336567 0.441248 - -0.501016 0.395974 0.436673 - -0.497948 0.400708 0.435039 - -0.505609 0.410849 0.43907 - -0.501228 0.433665 0.4367 - -0.505427 0.445328 0.438895 - -0.50398 0.511214 0.437981 - -0.496686 0.539913 0.434057 - -0.491888 0.609377 0.431361 - -0.491545 0.647779 0.431092 - -0.488093 0.946168 0.428591 - -0.486037 1.01335 0.427351 - -0.486639 1.03662 0.427617 - -0.489772 1.12733 0.429069 - -0.470052 1.27655 0.418298 - -0.401022 1.27014 0.381789 - -0.370463 1.27715 0.365605 - -0.342347 1.27201 0.35074 - -0.0352713 0.07804 0.190969 - -0.0377789 0.102997 0.192239 - -0.0332904 0.0896966 0.189894 - -0.0378211 0.141535 0.192174 - -0.0273353 0.0825514 0.18676 - -0.0231012 0.0809094 0.184523 - -0.021737 0.106976 0.183742 - -0.0204991 0.106996 0.183087 - -0.0200823 0.105999 0.182869 - -0.0192504 0.109998 0.18242 - -0.0188262 0.109995 0.182195 - -0.0162203 0.111929 0.180812 - -0.0155054 0.089873 0.180484 --0.00552902 0.113869 0.175151 --0.00508992 0.113798 0.174919 - 0.00270743 0.136654 0.170742 - 0.0168639 0.168983 0.163178 - 0.0262086 0.197239 0.15817 - 0.0449137 0.206385 0.148253 - 0.0338479 0.142634 0.154252 - 0.0342711 0.123724 0.154071 - 0.0259774 0.0867623 0.158543 - 0.0314953 0.0899489 0.155616 - 0.0472061 0.0994451 0.147282 - 0.0539212 0.107473 0.143711 - 0.248764 0.381691 0.0399996 - 0.438757 0.634624 -0.0610971 - 0.57809 0.750826 -0.135081 - 0.317073 -0.413149 0.0100796 - 0.313859 -0.416432 0.0117451 - 0.144427 -0.225482 0.0987318 - 0.0258714 -0.0965003 0.159609 - 0.0177232 -0.102947 0.163827 - 0.0280087 -0.140309 0.158604 - 0.0297194 -0.15133 0.157747 - 0.0291323 -0.151569 0.15805 - 0.0107385 -0.11206 0.167451 - 0.00718609 -0.109042 0.169277 - 0.00906585 -0.118832 0.168329 - 0.0100315 -0.137128 0.167872 --0.00774884 -0.105219 0.176974 --0.00868052 -0.100308 0.177444 - -0.0180077 -0.104992 0.182267 - -0.0229272 -0.105915 0.184807 - -0.0232665 -0.0798678 0.184923 - -0.0237382 -0.0828413 0.185173 - -0.1721 -0.400467 0.262433 - -0.192115 -0.403371 0.272767 - -0.197988 -0.40793 0.275807 - -0.219193 -0.410144 0.286752 - -0.221934 -0.407289 0.28816 - -0.230237 -0.403069 0.292434 - -0.277696 -0.40766 0.31693 - -0.356737 -0.407087 0.357709 - -0.357705 -0.404697 0.358203 - -0.495811 -0.422451 0.429497 - -0.508235 -0.392154 0.435839 - -0.509595 -0.293018 0.436318 - -0.510598 -0.284395 0.436816 - -0.503228 -0.265257 0.43297 - -0.507648 -0.23008 0.435171 - -0.507735 -0.199682 0.435148 - -0.511958 -0.179754 0.437282 - -0.504907 -0.161491 0.433603 - -0.510387 -0.112042 0.436319 - -0.519346 -0.0836945 0.440877 - -0.506645 -0.0620896 0.434276 - -0.264514 -0.00341221 0.30922 - -0.510799 0.0463603 0.436175 - -0.505796 0.0627726 0.433557 - -0.50598 0.154847 0.433444 - -0.503058 0.159058 0.431927 - -0.502873 0.166754 0.431814 - -0.510468 0.218103 0.435618 - -0.504126 0.240433 0.432296 - -0.504007 0.257617 0.432195 - -0.5092 0.26628 0.434855 - -0.506055 0.31979 0.433112 - -0.510611 0.362823 0.435366 - -0.507858 0.381726 0.433903 - -0.505528 0.435534 0.43258 - -0.502823 0.448829 0.431154 - -0.505935 0.484772 0.432679 - -0.502307 0.502706 0.430767 - -0.500867 0.519027 0.429987 - -0.501459 0.571988 0.430173 - -0.499239 0.574347 0.429022 - -0.497009 0.576696 0.427867 - -0.495374 0.579768 0.427016 - -0.498158 0.60395 0.428398 - -0.494529 0.620833 0.426488 - -0.488816 0.635446 0.423507 - -0.495034 0.667189 0.426644 - -0.487951 0.687425 0.422944 - -0.490447 0.71662 0.424166 - -0.492191 0.732545 0.42503 - -0.493504 0.741353 0.425688 - -0.492872 0.754146 0.425333 - -0.491571 0.766159 0.424635 - -0.492068 0.827126 0.424754 - -0.491663 1.01015 0.424133 - -0.493587 1.03609 0.425067 - -0.490626 1.27996 0.422991 - -0.450012 1.27868 0.402039 - -0.40933 1.27393 0.381061 - -0.405818 1.28056 0.379234 - -0.343435 1.27105 0.34707 - -0.0364728 0.0838097 0.191368 - -0.0353172 0.0973551 0.190742 - -0.0297876 0.0791297 0.18793 - -0.0308843 0.0991537 0.188451 - -0.0227318 0.0889179 0.184267 - -0.0217758 0.106965 0.183734 - -0.020579 0.110991 0.183107 - -0.0201486 0.110996 0.182885 - -0.0196974 0.105999 0.182664 - -0.0134928 0.0827392 0.179515 - 0.0408008 0.205085 0.151227 - 0.0415957 0.204788 0.150818 - 0.0318637 0.115404 0.15604 - 0.0257757 0.0953213 0.159226 - 0.023274 0.0854696 0.160539 - 0.0396737 0.101142 0.152043 - 0.0415365 0.103352 0.151077 - 0.045234 0.106577 0.149162 - 0.0531473 0.117436 0.145055 - 0.475363 0.681059 -0.0740506 - 0.561655 0.732152 -0.118686 - 0.348806 -0.418976 -0.00148506 - 0.0316052 -0.0861783 0.157287 - 0.0267518 -0.0825211 0.15972 - 0.0254129 -0.0903386 0.160411 - 0.0294211 -0.103819 0.158425 - 0.0290161 -0.104054 0.158629 - 0.0215468 -0.113347 0.162406 - 0.0285487 -0.138208 0.158941 - 0.0273325 -0.156738 0.159594 - 0.0115266 -0.153303 0.167535 - 0.0103306 -0.153593 0.168137 - 0.00913228 -0.153871 0.16874 --0.00842755 -0.102346 0.177455 - -0.0139996 -0.082826 0.180214 - -0.0172225 -0.103985 0.181882 - -0.0188428 -0.109 0.182708 - -0.0215076 -0.113959 0.184059 - -0.023539 -0.0858356 0.185018 - -0.0315655 -0.0898691 0.189063 - -0.065116 -0.254742 0.206305 - -0.505438 -2.14645 0.431973 - -0.515966 -1.76588 0.436415 - -0.149248 -0.418124 0.24898 - -0.151424 -0.402375 0.250039 - -0.154874 -0.401997 0.251772 - -0.167274 -0.406191 0.258018 - -0.173588 -0.403223 0.261186 - -0.178165 -0.405352 0.263493 - -0.212862 -0.40417 0.280939 - -0.222628 -0.407289 0.285857 - -0.228716 -0.40686 0.288918 - -0.255244 -0.407401 0.30226 - -0.319828 -0.404934 0.334733 - -0.344568 -0.404748 0.347174 - -0.366586 -0.406407 0.35825 - -0.462718 -0.409272 0.406601 - -0.504368 -0.398147 0.427521 - -0.505449 -0.314104 0.427877 - -0.506725 -0.293061 0.428471 - -0.510117 -0.285884 0.430161 - -0.506803 -0.123193 0.42813 - -0.506637 -0.0934227 0.42798 - -0.507351 -0.0886539 0.428328 - -0.512443 -0.0846354 0.43088 - -0.50567 -0.0665102 0.427433 - -0.510612 -0.0623145 0.429909 - -0.510853 -0.059912 0.430025 - -0.309048 0.0115783 0.32838 - -0.506779 0.0457756 0.42774 - -0.515188 0.0710749 0.431912 - -0.507194 0.0967716 0.427834 - -0.505189 0.118578 0.426777 - -0.50425 0.123323 0.426294 - -0.503274 0.128058 0.425793 - -0.508677 0.137084 0.42849 - -0.51021 0.150327 0.429231 - -0.507893 0.186189 0.427986 - -0.508752 0.241643 0.428293 - -0.511617 0.302942 0.429597 - -0.508754 0.336364 0.428082 - -0.508105 0.352571 0.42772 - -0.511484 0.386417 0.429343 - -0.505547 0.388885 0.426352 - -0.5031 0.471443 0.424937 - -0.506423 0.509166 0.426523 - -0.496273 0.525368 0.421383 - -0.493559 0.585157 0.419884 - -0.493556 0.656296 0.419723 - -0.489311 0.67413 0.417549 - -0.486169 0.775528 0.415742 - -0.483144 0.7778 0.414215 - -0.490549 0.861548 0.417752 - -0.489385 0.930791 0.417011 - -0.48595 0.972881 0.41519 - -0.491324 1.121 0.417561 - -0.48892 1.22421 0.416121 - -0.46247 1.27628 0.402702 - -0.446886 1.28078 0.394856 - -0.39465 1.2748 0.3686 - -0.389126 1.27471 0.365822 - -0.37864 1.27636 0.360545 - -0.0373941 0.109067 0.191549 - -0.0285686 0.0630833 0.187214 - -0.0295861 0.0801188 0.187687 - -0.026267 0.0785731 0.186022 - -0.0235057 0.0788344 0.184632 - -0.0227891 0.0768792 0.184276 - -0.0209623 0.105976 0.183293 - -0.0180096 0.113995 0.18179 - -0.0176339 0.107989 0.181614 - -0.0153749 0.112928 0.180467 - 0.00026684 0.128201 0.172567 - 0.00372623 0.136654 0.170808 - 0.0343284 0.204447 0.155267 - 0.0387798 0.198723 0.153041 - 0.0482322 0.215197 0.148251 - 0.0396854 0.164351 0.152663 - 0.0409651 0.163772 0.152021 - 0.0288144 0.0915276 0.158293 - 0.0527725 0.113455 0.146195 - 0.0259638 0.0647999 0.159786 - 0.544676 0.719051 -0.102533 - 0.349268 -0.416835 0.00318192 - 0.329137 -0.418844 0.0130416 - 0.314441 -0.422802 0.0202451 - 0.297776 -0.412395 0.0283799 - 0.11481 -0.18494 0.117444 - 0.027072 -0.0827427 0.160168 - 0.023445 -0.0816444 0.161942 - 0.0313234 -0.106481 0.15814 - 0.0272284 -0.104297 0.16014 - 0.0268194 -0.104517 0.160341 - 0.0255512 -0.106288 0.160965 - 0.0237253 -0.122333 0.161895 - 0.0286261 -0.154387 0.159567 - 0.0284742 -0.160766 0.159656 - 0.00939077 -0.101391 0.168866 - 0.00899328 -0.101525 0.169061 - 0.0168733 -0.152027 0.165315 - 0.00624293 -0.141374 0.170496 --0.00184474 -0.12364 0.174416 --0.00369086 -0.116863 0.175304 - -0.0130237 -0.0767669 0.179784 - -0.0211216 -0.113959 0.183831 - -0.0257837 -0.0745481 0.186026 - -0.0287638 -0.0872386 0.187513 - -0.0725563 -0.283618 0.209389 - -0.500346 -2.15366 0.422976 - -0.50903 -1.93798 0.426747 - -0.512185 -1.8276 0.428046 - -0.15829 -0.465513 0.251765 - -0.183002 -0.402069 0.263721 - -0.21023 -0.401585 0.277049 - -0.222882 -0.406417 0.283253 - -0.228289 -0.408751 0.285906 - -0.257577 -0.409915 0.300246 - -0.291904 -0.407616 0.317046 - -0.302142 -0.41152 0.322067 - -0.305359 -0.408745 0.323635 - -0.357958 -0.408742 0.349385 - -0.360537 -0.404697 0.350638 - -0.376497 -0.41261 0.358469 - -0.383496 -0.413389 0.361898 - -0.388967 -0.408732 0.364565 - -0.404405 -0.411137 0.372128 - -0.427242 -0.413174 0.383313 - -0.430861 -0.413188 0.385085 - -0.457092 -0.413163 0.397926 - -0.464689 -0.409272 0.401636 - -0.50389 -0.42195 0.420855 - -0.502938 -0.286454 0.420087 - -0.505614 -0.258342 0.421335 - -0.501852 -0.190212 0.419341 - -0.503329 -0.185507 0.420054 - -0.509739 -0.179985 0.42318 - -0.503712 -0.164797 0.420195 - -0.506863 -0.14532 0.421695 - -0.512884 -0.0966691 0.424534 - -0.483422 -0.0177018 0.409935 - -0.266318 -0.00461636 0.303623 - -0.267218 0.00503553 0.304042 - -0.501799 0.0309483 0.418823 - -0.506289 0.045525 0.420988 - -0.509289 0.0626587 0.422419 - -0.507931 0.0818387 0.421712 - -0.503387 0.0883182 0.419473 - -0.501796 0.0928556 0.418683 - -0.503724 0.194356 0.419401 - -0.509874 0.210401 0.422376 - -0.507372 0.212059 0.421148 - -0.503111 0.223879 0.419036 - -0.511797 0.311118 0.423094 - -0.507328 0.317772 0.420891 - -0.504823 0.322507 0.419654 - -0.504517 0.355138 0.419431 - -0.500441 0.379573 0.417382 - -0.502863 0.429303 0.418457 - -0.492921 0.670258 0.413053 - -0.489366 0.88127 0.410843 - -0.491045 0.902224 0.411618 - -0.486831 1.03445 0.409261 - -0.49118 1.07893 0.411291 - -0.462938 1.2887 0.396998 - -0.438374 1.28396 0.384983 - -0.428298 1.28798 0.380042 - -0.414973 1.2815 0.373532 - -0.394811 1.27005 0.363688 - -0.388999 1.26901 0.360845 - -0.0396804 0.106433 0.192426 - -0.0371457 0.0998775 0.191199 - -0.0330311 0.0895593 0.189208 - -0.0314904 0.102998 0.188424 - -0.0286599 0.0832408 0.187082 - -0.0234762 0.0747976 0.184563 - -0.0146093 0.089893 0.180189 - -0.0106582 0.0865557 0.178262 --0.00667013 0.107185 0.176264 - 0.00970402 0.144607 0.168165 - 0.0411584 0.204428 0.152633 - 0.0457678 0.188845 0.150411 - 0.0430169 0.176099 0.151786 - 0.0435655 0.146471 0.151584 - 0.0222878 0.0890675 0.162128 - 0.0270501 0.0953213 0.159783 - 0.0460189 0.109501 0.150465 - 0.0483717 0.111363 0.149309 - 0.0522743 0.115665 0.147389 - 0.0473647 0.0999456 0.149827 - 0.0587048 0.11297 0.144247 - 0.502471 0.709695 -0.0743265 - 0.560557 0.697136 -0.102734 - 0.561912 0.680655 -0.103361 - 0.347954 -0.40865 0.00963493 - 0.350397 -0.418615 0.00849985 - 0.028668 -0.0960544 0.160162 - 0.0280086 -0.100943 0.160486 - 0.0279815 -0.105418 0.160508 - 0.0233484 -0.113149 0.16272 - 0.0256191 -0.1484 0.161722 - 0.0071602 -0.100238 0.170358 - 0.0101047 -0.134485 0.169039 - 0.0106231 -0.14563 0.168819 --0.00090548 -0.12257 0.174228 --0.00683363 -0.100256 0.176986 - -0.0132458 -0.0918556 0.180004 - -0.0219001 -0.0999014 0.184121 - -0.0227496 -0.0808225 0.184481 - -0.0234932 -0.0777549 0.184826 - -0.0250476 -0.0715662 0.185549 - -0.0323404 -0.0977009 0.189061 - -0.511739 -1.78789 0.419853 - -0.156682 -0.458876 0.24875 - -0.174869 -0.404141 0.257243 - -0.180006 -0.402742 0.259673 - -0.187028 -0.405803 0.263005 - -0.198556 -0.409704 0.268474 - -0.202169 -0.40437 0.270173 - -0.239235 -0.411477 0.287744 - -0.293653 -0.404686 0.313502 - -0.319815 -0.408636 0.325901 - -0.407302 -0.408569 0.367337 - -0.425974 -0.409815 0.376183 - -0.452458 -0.406708 0.38872 - -0.508591 -0.390468 0.415269 - -0.508665 -0.365876 0.41525 - -0.506687 -0.334278 0.414243 - -0.509888 -0.310732 0.415707 - -0.508374 -0.255546 0.414868 - -0.509668 -0.227764 0.415419 - -0.51065 -0.219872 0.415867 - -0.512364 -0.209606 0.416656 - -0.50904 -0.157988 0.414967 - -0.507054 -0.15479 0.41402 - -0.510432 -0.132946 0.415571 - -0.509888 -0.117787 0.41528 - -0.511925 -0.0837269 0.416169 - -0.51127 -0.0353789 0.415752 - -0.498317 -0.0228193 0.409589 - -0.264683 -0.00337512 0.298893 - -0.262895 0.00137935 0.298036 - -0.262888 0.00256177 0.29803 - -0.381013 0.0160743 0.353946 - -0.508664 0.0670568 0.414291 - -0.501275 0.0755418 0.410773 - -0.508944 0.0864334 0.414381 - -0.508601 0.0888026 0.414213 - -0.507514 0.0958998 0.413683 - -0.501103 0.116449 0.410601 - -0.505459 0.122437 0.412651 - -0.501531 0.136265 0.41076 - -0.506868 0.145331 0.413267 - -0.509191 0.151117 0.414355 - -0.505113 0.152398 0.41242 - -0.507985 0.155853 0.413773 - -0.508701 0.163801 0.414095 - -0.510334 0.237252 0.414706 - -0.507647 0.291485 0.413313 - -0.506495 0.293845 0.412762 - -0.507541 0.316259 0.413208 - -0.500131 0.333706 0.40966 - -0.507221 0.341906 0.413 - -0.510721 0.354411 0.41463 - -0.505814 0.364426 0.412283 - -0.505183 0.377804 0.411955 - -0.506339 0.414958 0.41242 - -0.493809 0.536032 0.406218 - -0.499574 0.602546 0.408801 - -0.491851 0.695991 0.404936 - -0.488142 1.10291 0.402279 - -0.49067 1.18845 0.403287 - -0.351045 1.26369 0.336992 - -0.0362134 0.0928514 0.190473 - -0.0279876 0.0812589 0.186603 - -0.0225446 0.0768386 0.184035 - -0.0103886 0.083571 0.178263 --0.00561233 0.104092 0.175955 --0.00422852 0.111957 0.175282 - 0.00559498 0.137524 0.170573 - 0.0293224 0.188833 0.159222 - 0.0302892 0.18333 0.158776 - 0.0395671 0.199004 0.154348 - 0.0684935 0.225454 0.140589 - 0.0250849 0.0935208 0.16144 - 0.0241612 0.0815766 0.161904 - 0.0485473 0.107083 0.150298 - 0.0379754 0.0859817 0.155351 - 0.865875 1.30934 -0.239463 - 0.560602 0.749293 -0.0936411 - 0.63407 0.829654 -0.128615 - 0.356174 -0.430105 0.010557 - 0.295982 -0.411616 0.0382562 - 0.234879 -0.34647 0.0662724 - 0.208057 -0.31244 0.0785585 - 0.037749 -0.0831079 0.156541 - 0.0373422 -0.0931361 0.15675 - 0.0320071 -0.0873884 0.159196 - 0.0250831 -0.114801 0.162448 - 0.0290941 -0.143096 0.160661 - 0.00992113 -0.100567 0.169404 - 0.00859683 -0.113421 0.170042 - 0.0105801 -0.142698 0.169193 - 0.00774677 -0.143337 0.1705 - 0.00468198 -0.138875 0.171903 - -0.0105142 -0.0806326 0.178778 - -0.0115486 -0.0797299 0.179252 - -0.0128132 -0.0798323 0.179835 - -0.0234078 -0.0817424 0.184722 - -0.0341711 -0.106427 0.189737 - -0.0351755 -0.107246 0.190201 - -0.15179 -0.435479 0.244667 - -0.179384 -0.409795 0.257327 - -0.189459 -0.405887 0.261961 - -0.193061 -0.405119 0.26362 - -0.200273 -0.40793 0.26695 - -0.217577 -0.40138 0.27491 - -0.252223 -0.405483 0.290885 - -0.258519 -0.404569 0.293785 - -0.299516 -0.408123 0.312687 - -0.303895 -0.410727 0.314711 - -0.319183 -0.406314 0.321746 - -0.347287 -0.410163 0.334706 - -0.369095 -0.411247 0.344759 - -0.372343 -0.407851 0.346249 - -0.381317 -0.403804 0.350375 - -0.420986 -0.410351 0.368672 - -0.42261 -0.408407 0.369416 - -0.449323 -0.412971 0.381737 - -0.471616 -0.411814 0.392008 - -0.498431 -0.424616 0.404394 - -0.503473 -0.314792 0.406476 - -0.508285 -0.286923 0.408632 - -0.514081 -0.281195 0.411291 - -0.510173 -0.210544 0.409334 - -0.508184 -0.193571 0.40838 - -0.506749 -0.141422 0.407604 - -0.508361 -0.107102 0.408271 - -0.505598 -0.0703546 0.406916 - -0.504675 -0.0418212 0.406428 - -0.508117 -0.0302783 0.40799 - -0.490381 -0.0200761 0.399793 - -0.267323 -0.0022 0.296956 - -0.505911 0.0379893 0.406822 - -0.507354 0.0546936 0.407451 - -0.501911 0.0635049 0.404923 - -0.504722 0.0710042 0.406202 - -0.507101 0.152398 0.407119 - -0.508577 0.321995 0.407425 - -0.503139 0.395945 0.404756 - -0.507791 0.43353 0.406818 - -0.511012 0.440289 0.408287 - -0.500154 0.442237 0.403279 - -0.501695 0.48449 0.403896 - -0.496518 0.546361 0.401374 - -0.499324 0.564143 0.402628 - -0.497922 0.57242 0.401964 - -0.495771 0.656264 0.400788 - -0.487973 0.775304 0.396932 - -0.493723 0.84733 0.399423 - -0.491102 0.86783 0.39817 - -0.487341 0.942855 0.396271 - -0.487038 1.02551 0.39595 - -0.492301 1.13374 0.398137 - -0.492558 1.2624 0.397972 - -0.399489 1.2748 0.355053 - -0.352759 1.26561 0.333538 - -0.0286309 0.0689452 0.186797 - -0.0274839 0.0651026 0.186277 - -0.0249026 0.0765839 0.185062 - -0.0220289 0.0798542 0.183731 - -0.0129385 0.0978617 0.179502 --0.00713529 0.0973121 0.176828 - 0.00079291 0.124347 0.173115 - 0.0188575 0.167218 0.164696 - 0.028951 0.178757 0.160019 - 0.0454414 0.204486 0.152362 - 0.0828526 0.248403 0.135024 - 0.0266069 0.0896038 0.161295 - 0.0323546 0.0952226 0.158634 - 0.0445288 0.110496 0.15299 - 0.0461404 0.106993 0.152255 - 0.0455617 0.105019 0.152526 - 0.371313 -0.425987 0.00843787 - 0.308413 -0.425413 0.0366358 - 0.196905 -0.300402 0.0863534 - 0.0546364 -0.103537 0.149704 - 0.0414753 -0.0893196 0.155574 - 0.0462032 -0.103984 0.153486 - 0.0288003 -0.08642 0.16125 - 0.0250679 -0.0818469 0.162913 - 0.0230873 -0.0796223 0.163796 - 0.0248365 -0.101039 0.163059 - 0.0239496 -0.10366 0.163462 - 0.0226322 -0.110751 0.164068 - 0.0205985 -0.113733 0.164987 - 0.0300366 -0.154614 0.160845 - 0.0120219 -0.133238 0.168875 - 0.00989606 -0.133774 0.169829 - 0.00758358 -0.136349 0.170871 - -8.947e-05 -0.121582 0.174279 - -0.0163704 -0.0999966 0.181531 - -0.0198163 -0.11096 0.1831 - -0.0208903 -0.084899 0.183524 - -0.02575 -0.0794385 0.185691 - -0.0260662 -0.0793964 0.185832 - -0.0826139 -0.310771 0.211691 - -0.0876127 -0.327972 0.21397 - -0.511783 -1.98899 0.407776 - -0.512906 -1.75015 0.407756 - -0.147182 -0.402403 0.24084 - -0.162596 -0.404615 0.247755 - -0.214178 -0.405998 0.270883 - -0.244871 -0.399248 0.284629 - -0.274578 -0.406509 0.297963 - -0.347661 -0.405591 0.330726 - -0.379418 -0.407286 0.344967 - -0.408655 -0.410446 0.358081 - -0.510135 -0.425543 0.40361 - -0.501396 -0.385201 0.399604 - -0.506255 -0.324881 0.40165 - -0.507546 -0.322538 0.402224 - -0.503024 -0.313271 0.400176 - -0.504269 -0.310944 0.400729 - -0.505127 -0.260442 0.401003 - -0.506142 -0.218848 0.401367 - -0.507857 -0.216881 0.402132 - -0.506242 -0.168607 0.401302 - -0.506781 -0.133393 0.401466 - -0.50731 -0.13105 0.401698 - -0.506887 -0.0822129 0.401402 - -0.502699 -0.0791347 0.399517 - -0.513117 -0.0399942 0.404102 - -0.507958 -0.0348614 0.401778 - -0.497509 -0.024902 0.397071 - -0.259885 0.00367507 0.290477 - -0.5107 0.0358414 0.402852 - -0.504035 0.0517608 0.399829 - -0.504711 0.0636232 0.400106 - -0.509485 0.0906728 0.402187 - -0.504088 0.111372 0.399722 - -0.507858 0.149509 0.401329 - -0.504348 0.166154 0.399719 - -0.508252 0.188314 0.401421 - -0.513079 0.245183 0.40346 - -0.506028 0.261658 0.400263 - -0.504984 0.263992 0.39979 - -0.504983 0.281619 0.399751 - -0.509647 0.299519 0.401802 - -0.504297 0.395349 0.399194 - -0.505701 0.414859 0.399781 - -0.504281 0.424942 0.399122 - -0.509204 0.460849 0.40125 - -0.500999 0.535154 0.397409 - -0.499664 0.55747 0.396761 - -0.503189 0.586638 0.398278 - -0.490291 0.776136 0.39208 - -0.487378 0.8493 0.390613 - -0.488067 0.867514 0.390883 - -0.49617 0.956888 0.394319 - -0.488159 1.05825 0.390506 - -0.49071 1.1793 0.391384 - -0.448488 1.28097 0.372232 - -0.41159 1.27299 0.355708 - -0.359473 1.26591 0.332358 - -0.328435 1.25061 0.318476 - -0.322036 1.24628 0.315617 - -0.0373358 0.09755 0.190497 - -0.0289381 0.0749115 0.186782 - -0.0255617 0.0804858 0.185256 - -0.0253027 0.0845406 0.185131 - -0.0241036 0.0786416 0.184606 - -0.018951 0.109984 0.182227 - -0.0121225 0.0848138 0.179221 - -0.0118521 0.0787783 0.179113 - -0.0104316 0.0806546 0.178472 - 0.0068298 0.132387 0.17062 - 0.0077203 0.13423 0.170217 - 0.0101113 0.143898 0.169124 - 0.0114423 0.147677 0.168519 - 0.0142103 0.152128 0.167268 - 0.0264817 0.178661 0.161708 - 0.0275614 0.171069 0.161241 - 0.0351207 0.190515 0.157809 - 0.0433677 0.201288 0.154088 - 0.0457674 0.200399 0.153014 - 0.0438919 0.176692 0.153907 - 0.0636346 0.216512 0.144969 - 0.0465924 0.151609 0.152752 - 0.0237494 0.0870909 0.163134 - 0.0312109 0.0882495 0.159786 - 0.0457349 0.112498 0.153222 - 0.0545766 0.11333 0.149256 - 0.488876 0.703239 -0.0467437 - 0.674261 0.894719 -0.130276 - 0.363683 -0.422545 0.0166602 - 0.336126 -0.41664 0.0286534 - 1.0108 -1.25643 -0.263453 - 0.318488 -0.428373 0.0363634 - 1.0366 -1.35786 -0.274473 - 0.276048 -0.401709 0.0547954 - 0.0316158 -0.0861548 0.160601 - 0.0312709 -0.086384 0.160751 - 0.0310472 -0.0876971 0.160852 - 0.0235505 -0.0785564 0.164098 - 0.0256324 -0.0898241 0.163215 - 0.0273545 -0.0944815 0.162475 - 0.0254273 -0.109775 0.163348 - 0.0245478 -0.110172 0.163732 - 0.0212862 -0.104057 0.16514 - 0.0208698 -0.104236 0.165322 - -0.011521 -0.0818042 0.179385 - -0.021203 -0.0738379 0.183586 - -0.0217258 -0.0727952 0.183811 - -0.023838 -0.0766068 0.18474 - -0.0261364 -0.0803448 0.185749 - -0.0322881 -0.0985431 0.188469 - -0.0332391 -0.0993748 0.188885 - -0.10248 -0.368239 0.219638 - -0.500323 -1.96913 0.396462 - -0.518943 -1.94279 0.404517 - -0.51375 -1.77355 0.401885 - -0.154371 -0.412415 0.242343 - -0.158271 -0.396922 0.244008 - -0.171088 -0.406384 0.249613 - -0.193092 -0.407769 0.259202 - -0.213505 -0.407822 0.268096 - -0.241003 -0.406976 0.280074 - -0.260512 -0.405405 0.28857 - -0.265784 -0.40639 0.29087 - -0.287745 -0.399301 0.300422 - -0.337639 -0.409604 0.322182 - -0.344149 -0.403427 0.325005 - -0.347592 -0.4041 0.326506 - -0.414728 -0.415283 0.35578 - -0.465234 -0.413809 0.377782 - -0.475118 -0.411814 0.382083 - -0.509169 -0.423069 0.396943 - -0.502007 -0.402135 0.393777 - -0.505209 -0.397498 0.395162 - -0.507855 -0.378217 0.396273 - -0.507863 -0.374729 0.396269 - -0.509809 -0.29163 0.396935 - -0.509641 -0.225061 0.396717 - -0.509735 -0.206029 0.396716 - -0.508974 -0.181866 0.396332 - -0.506996 -0.155476 0.395413 - -0.507942 -0.128239 0.395766 - -0.506829 -0.1108 0.395242 - -0.514893 -0.107685 0.398749 - -0.50475 -0.0626132 0.394232 - -0.500561 -0.0365177 0.39235 - -0.503024 0.0258617 0.393286 - -0.506411 0.0730725 0.394659 - -0.5064 0.109043 0.394576 - -0.514039 0.113211 0.397895 - -0.506701 0.126219 0.39467 - -0.510632 0.149777 0.396331 - -0.508168 0.159154 0.395237 - -0.505181 0.234785 0.393771 - -0.512181 0.249495 0.396788 - -0.51118 0.251849 0.396347 - -0.506024 0.252063 0.3941 - -0.506619 0.266768 0.394328 - -0.505727 0.283948 0.393901 - -0.506341 0.299423 0.394135 - -0.502616 0.31252 0.392483 - -0.509957 0.394793 0.395503 - -0.505183 0.401797 0.393407 - -0.5023 0.414108 0.392124 - -0.504289 0.504949 0.392793 - -0.498776 0.535319 0.390325 - -0.500211 0.546361 0.390926 - -0.499498 0.579972 0.390542 - -0.490056 0.615507 0.386351 - -0.494569 0.643854 0.388255 - -0.488544 0.676974 0.385558 - -0.488376 0.708262 0.385416 - -0.490682 0.724937 0.386385 - -0.489061 0.85754 0.385389 - -0.48891 0.865794 0.385305 - -0.48591 0.868892 0.383991 - -0.487592 0.945978 0.384556 - -0.489015 0.979168 0.385103 - -0.384975 1.2735 0.339134 - -0.0414084 0.107722 0.191993 - -0.0390151 0.0990943 0.190969 - -0.0386185 0.0991988 0.190796 - -0.0370284 0.099598 0.190102 - -0.0269726 0.0630356 0.185801 - -0.0176541 0.107996 0.181643 --0.00870465 0.0875506 0.177788 - 0.00333114 0.13116 0.17245 - 0.00437984 0.130962 0.171993 - 0.0108274 0.138745 0.169167 - 0.0113822 0.138611 0.168926 - 0.0266062 0.173627 0.162216 - 0.0402883 0.200508 0.156197 - 0.0758117 0.24383 0.140626 - 0.0282041 0.102859 0.161675 - 0.0284037 0.0926735 0.16161 - 0.0308843 0.0900287 0.160535 - 0.0440443 0.108237 0.154762 - 0.0422607 0.0927991 0.155572 - 0.853115 1.29365 -0.200318 - 0.762718 1.01286 -0.160322 - 0.920217 1.19613 -0.22934 - 0.923243 1.07052 -0.230384 - 0.365773 -0.422545 0.0204445 - 0.35026 -0.423472 0.0270148 - 1.07143 -1.39604 -0.276206 - 0.0410335 -0.0882424 0.157209 - 0.0334086 -0.08654 0.160434 - 0.027289 -0.133889 0.163128 - 0.0292108 -0.143754 0.162335 - 0.0122982 -0.10344 0.169408 - 0.0105225 -0.107112 0.170168 - 0.0108384 -0.116329 0.170054 - 0.00780555 -0.141607 0.171393 - 0.00618681 -0.138875 0.172073 --0.00220641 -0.11297 0.17557 - -0.0219623 -0.0817699 0.183867 - -0.022467 -0.0797203 0.184076 - -0.0431638 -0.143048 0.192976 - -0.511269 -1.81465 0.394797 - -0.513998 -1.7406 0.395791 - -0.513377 -1.6863 0.395411 - -0.152784 -0.436426 0.240025 - -0.169458 -0.396425 0.246998 - -0.185015 -0.406512 0.253607 - -0.190681 -0.405887 0.256004 - -0.19718 -0.402516 0.258748 - -0.226009 -0.406417 0.270963 - -0.232734 -0.40686 0.273811 - -0.236222 -0.409284 0.275293 - -0.263345 -0.405073 0.286767 - -0.290179 -0.412874 0.298146 - -0.301159 -0.406531 0.30278 - -0.30279 -0.405177 0.303468 - -0.352541 -0.412408 0.324548 - -0.354809 -0.411556 0.325506 - -0.359745 -0.406705 0.327585 - -0.391393 -0.406997 0.340985 - -0.442281 -0.41251 0.362543 - -0.503965 -0.424616 0.388685 - -0.504693 -0.413954 0.38897 - -0.509646 -0.406973 0.391052 - -0.511078 -0.386382 0.391614 - -0.509863 -0.315299 0.390945 - -0.509989 -0.30911 0.390985 - -0.508446 -0.29583 0.390303 - -0.506297 -0.285498 0.389371 - -0.508576 -0.280842 0.390326 - -0.503022 -0.210463 0.387821 - -0.503743 -0.156392 0.388009 - -0.514428 -0.119514 0.392453 - -0.507554 -0.0698354 0.389435 - -0.494767 -0.0223046 0.383917 - -0.50077 0.0325547 0.38634 - -0.506565 0.0539872 0.388747 - -0.512283 0.0617473 0.391151 - -0.506371 0.0728014 0.388624 - -0.509246 0.131353 0.389714 - -0.507333 0.168482 0.388823 - -0.504557 0.177758 0.387628 - -0.504766 0.21735 0.38763 - -0.510479 0.250579 0.389977 - -0.509469 0.252917 0.389544 - -0.50296 0.2696 0.386752 - -0.508317 0.284418 0.388988 - -0.507742 0.350198 0.388602 - -0.49294 0.61704 0.381755 - -0.490978 0.659938 0.380831 - -0.492449 0.698926 0.381369 - -0.491236 0.764746 0.380713 - -0.490379 0.832017 0.380204 - -0.487616 0.904669 0.378876 - -0.489967 0.937592 0.3798 - -0.487515 0.942461 0.378752 - -0.489733 1.10244 0.379343 - -0.482265 1.28434 0.375786 - -0.403236 1.27385 0.342349 - -0.280727 1.1097 0.290837 - -0.0449046 0.12422 0.193133 - -0.0379127 0.105457 0.190213 - -0.0358894 0.101836 0.189365 - -0.0292658 0.0736938 0.186621 - -0.0238573 0.0805982 0.184317 - -0.0206 0.0748633 0.18295 - -0.0168254 0.108999 0.181278 - -0.0147314 0.102983 0.180404 - -0.0124097 0.0989024 0.17943 - -0.0106682 0.0887785 0.178715 --0.00575362 0.101336 0.176607 - 0.0068039 0.129556 0.171229 - 0.0123272 0.146699 0.168853 - 0.0415924 0.180275 0.156389 - 0.0296004 0.104663 0.161631 - 0.0300206 0.104444 0.161453 - 0.0263297 0.0862934 0.163056 - 0.0289605 0.0869996 0.16194 - 0.0293099 0.0867836 0.161793 - 0.471234 0.702413 -0.0266496 - 0.525927 0.733442 -0.0498733 - 0.959065 1.10589 -0.234067 - 0.366964 -0.417889 0.0246962 - 1.07294 -1.25219 -0.263613 - 1.10203 -1.379 -0.275292 - 0.048279 -0.103984 0.154977 - 0.0308622 -0.0851178 0.162094 - 0.0281708 -0.0810276 0.163191 - 0.0237255 -0.0870276 0.165031 - 0.0269727 -0.103063 0.163731 - 0.0265565 -0.103264 0.163902 - 0.0280506 -0.14018 0.163368 - 0.0141672 -0.108229 0.169004 - 0.00658435 -0.0959714 0.172094 - 0.00411902 -0.13326 0.173187 - -2.707e-05 -0.11877 0.17486 --0.00677107 -0.0944866 0.177579 - -0.0133885 -0.105965 0.180323 - -0.0138161 -0.105976 0.180499 - -0.015132 -0.101997 0.181031 - -0.0155478 -0.100999 0.1812 - -0.0195055 -0.10993 0.182845 - -0.0290419 -0.0919071 0.186725 - -0.0359845 -0.108851 0.189615 - -0.0757237 -0.274445 0.206303 - -0.512831 -1.81369 0.389255 - -0.15064 -0.40554 0.237372 - -0.17061 -0.403613 0.245575 - -0.193128 -0.40151 0.254824 - -0.273088 -0.408132 0.287696 - -0.290451 -0.412063 0.29484 - -0.339548 -0.4058 0.315003 - -0.416817 -0.414592 0.346774 - -0.453616 -0.411004 0.361888 - -0.462279 -0.415456 0.365458 - -0.503862 -0.379378 0.382468 - -0.50852 -0.345458 0.384309 - -0.504273 -0.335965 0.382543 - -0.508304 -0.329022 0.384184 - -0.513018 -0.306767 0.386074 - -0.504181 -0.295232 0.382417 - -0.509969 -0.257237 0.384714 - -0.513173 -0.227796 0.385966 - -0.508803 -0.139898 0.383981 - -0.50713 -0.122212 0.383255 - -0.508366 -0.0839312 0.38368 - -0.511444 -0.0820615 0.384941 - -0.510569 -0.0747648 0.384565 - -0.499855 -0.0293269 0.380064 - -0.499153 -0.024713 0.379766 - -0.500081 0.0255208 0.380039 - -0.507214 0.0726658 0.382868 - -0.510358 0.174055 0.383941 - -0.506515 0.21735 0.382268 - -0.503036 0.298298 0.380663 - -0.503151 0.342415 0.380615 - -0.505878 0.395876 0.38162 - -0.508485 0.420132 0.382639 - -0.506229 0.453049 0.381641 - -0.499748 0.501034 0.378874 - -0.500244 0.514847 0.379048 - -0.49882 0.517829 0.378456 - -0.492494 0.642218 0.375588 - -0.495504 0.66388 0.376777 - -0.49434 0.732085 0.376152 - -0.487235 0.770045 0.37315 - -0.485139 0.773932 0.37228 - -0.492998 0.850155 0.375345 - -0.488959 0.859776 0.373665 - -0.485024 0.95395 0.371844 - -0.494631 1.24946 0.375153 - -0.438964 1.27374 0.352224 - -0.41656 1.27583 0.343013 - -0.324414 1.24435 0.305215 - -0.0297995 0.0918013 0.186639 - -0.0198055 0.0949124 0.182526 - -0.0150941 0.108995 0.180559 - 0.0247802 0.170362 0.164041 - 0.026154 0.169969 0.163477 - 0.042293 0.185552 0.156811 - 0.0421383 0.182439 0.156881 - 0.0445265 0.17727 0.155911 - 0.0589353 0.205563 0.149929 - 0.0677212 0.221138 0.146285 - 0.0273698 0.0871739 0.163156 - 0.0540112 0.115352 0.152147 - 0.839376 1.28405 -0.173115 - 0.515944 0.72914 -0.0390053 - 0.363773 -0.434405 0.0306108 - 1.13363 -1.32757 -0.274554 - 1.09936 -1.46989 -0.260579 - 0.232651 -0.354787 0.082743 - 0.192747 -0.303216 0.0985493 - 0.041939 -0.0981492 0.158264 - 0.0407414 -0.0989501 0.158744 - 0.0263474 -0.0915136 0.164469 - 0.02109 -0.0886424 0.16656 - 0.025977 -0.113543 0.164664 - 0.0292242 -0.1484 0.163444 - 0.00945391 -0.135368 0.171302 --0.00833176 -0.0846489 0.178288 - -0.0151413 -0.101999 0.181041 - -0.0159562 -0.0989985 0.18136 - -0.0194936 -0.0808857 0.182732 - -0.0209337 -0.0827934 0.18331 - -0.0219308 -0.0746802 0.183691 - -0.0380625 -0.116489 0.190216 - -0.515241 -1.68058 0.383926 - -0.159997 -0.40506 0.239476 - -0.168876 -0.403415 0.243014 - -0.180251 -0.398176 0.24754 - -0.205713 -0.401694 0.257704 - -0.231697 -0.407015 0.268081 - -0.23499 -0.404966 0.269389 - -0.244603 -0.402266 0.273218 - -0.262531 -0.405405 0.280377 - -0.32083 -0.412977 0.303648 - -0.32759 -0.410957 0.30634 - -0.329254 -0.409486 0.307001 - -0.347467 -0.407237 0.314261 - -0.367739 -0.406356 0.322345 - -0.393841 -0.406997 0.332759 - -0.418437 -0.41132 0.342579 - -0.4275 -0.409672 0.34619 - -0.450317 -0.413797 0.355301 - -0.46215 -0.406708 0.360006 - -0.484978 -0.416263 0.369132 - -0.510028 -0.342049 0.378965 - -0.512345 -0.330599 0.379864 - -0.508188 -0.308931 0.37816 - -0.510597 -0.259566 0.379014 - -0.506094 -0.232001 0.377159 - -0.507031 -0.229693 0.377528 - -0.507959 -0.227382 0.377893 - -0.508119 -0.205841 0.37791 - -0.501482 -0.184882 0.375217 - -0.505732 -0.143494 0.376824 - -0.501606 -0.115631 0.375118 - -0.507522 -0.109785 0.377465 - -0.50886 -0.0789876 0.377932 - -0.504674 -0.059615 0.376221 - -0.512969 -0.0511758 0.379511 - -0.504849 -0.0480215 0.376266 - -0.495966 -0.0426016 0.372711 - -0.500782 0.0254721 0.374485 - -0.506491 0.0396614 0.376732 - -0.510258 0.0895125 0.378127 - -0.509892 0.0918352 0.377976 - -0.504944 0.131746 0.375917 - -0.513219 0.148973 0.37918 - -0.507791 0.17513 0.376959 - -0.51056 0.248886 0.377905 - -0.505681 0.283901 0.375883 - -0.50528 0.326635 0.375631 - -0.509741 0.352522 0.377355 - -0.507708 0.421826 0.376395 - -0.503378 0.50311 0.374492 - -0.499409 0.568818 0.372768 - -0.494514 0.609433 0.370727 - -0.49691 0.634603 0.371629 - -0.49205 0.64524 0.369668 - -0.4934 0.670756 0.370151 - -0.49242 0.681608 0.369737 - -0.492254 0.74703 0.36953 - -0.490269 0.750913 0.36873 - -0.494174 0.793755 0.370195 - -0.490833 0.983178 0.368454 - -0.48637 1.00586 0.366625 - -0.491209 1.05016 0.36846 - -0.490293 1.08391 0.368022 - -0.491984 1.26968 0.368297 - -0.381426 1.26855 0.324198 - -0.0409176 0.105548 0.190876 - -0.0376449 0.0971513 0.189589 - -0.0389863 0.10709 0.190103 - -0.0235551 0.0785365 0.184009 - -0.0208798 0.0818042 0.182935 - -0.0204874 0.0808302 0.18278 - -0.0191326 0.0879188 0.182224 - -0.0151548 0.101998 0.180607 - -0.0133601 0.108972 0.179876 --0.00966392 0.0807455 0.178463 --0.00295967 0.1031 0.17574 --0.00204115 0.107003 0.175366 - 0.00096262 0.115625 0.174149 - 0.0180647 0.153767 0.167245 - 0.0186877 0.153607 0.166997 - 0.0205527 0.15311 0.166254 - 0.0697315 0.221664 0.146489 - 0.0562786 0.177853 0.15195 - 0.0261791 0.0881768 0.164149 - 0.0275169 0.0862934 0.16362 - 0.0406259 0.104745 0.158351 - 0.0433197 0.10652 0.157273 - 0.045186 0.108812 0.156523 - 0.0503866 0.113587 0.154438 - 0.816048 1.31445 -0.153564 - 0.834409 1.28238 -0.160819 - 0.511697 0.719722 -0.0308799 - 1.01397 1.15714 -0.232174 - 0.36731 -0.428659 0.0337854 - 0.364448 -0.432947 0.0349016 - 1.16623 -1.37116 -0.273269 - 1.12558 -1.52478 -0.257216 - 1.11937 -1.5301 -0.254801 - 0.300698 -0.429813 0.0595578 - 0.272205 -0.405388 0.0705284 - 0.199385 -0.313873 0.098504 - 0.115377 -0.196303 0.130752 - 0.0854213 -0.154079 0.14225 - 0.0440472 -0.0959428 0.158132 - 0.0276046 -0.0786422 0.164456 - 0.0275599 -0.0809762 0.164478 - 0.0242898 -0.0961382 0.165776 - 0.0242327 -0.11449 0.165837 - 0.0240856 -0.115612 0.165897 - 0.0239013 -0.119929 0.165977 - 0.0144165 -0.105356 0.169615 - 0.0116848 -0.102041 0.170665 - 0.0112857 -0.122791 0.170864 - 0.0097847 -0.12315 0.171445 - 0.0013118 -0.12174 0.17472 --0.00755244 -0.0846144 0.17807 - -0.0107668 -0.0768596 0.179297 - -0.0121021 -0.106952 0.179878 - -0.0180299 -0.117957 0.182195 - -0.0187383 -0.0979214 0.182426 - -0.0191328 -0.0888942 0.182559 - -0.0202904 -0.0788034 0.182985 - -0.0327677 -0.0971672 0.187852 - -0.0604615 -0.210428 0.198808 - -0.514328 -1.83618 0.377881 - -0.162458 -0.400894 0.238676 - -0.165367 -0.398571 0.239797 - -0.17786 -0.405978 0.244646 - -0.179512 -0.405212 0.245283 - -0.212803 -0.406983 0.258166 - -0.268912 -0.410907 0.279881 - -0.283141 -0.410185 0.285385 - -0.336323 -0.406552 0.305951 - -0.34966 -0.408739 0.311115 - -0.385782 -0.404123 0.32508 - -0.407907 -0.402845 0.333637 - -0.433493 -0.407127 0.343544 - -0.509224 -0.327446 0.372671 - -0.50709 -0.319699 0.371829 - -0.506079 -0.24788 0.371284 - -0.511261 -0.164787 0.373111 - -0.500103 -0.0913082 0.368636 - -0.508744 -0.090556 0.371978 - -0.501854 -0.0799418 0.369289 - -0.502163 -0.0706869 0.369389 - -0.504659 -0.0571002 0.370325 - -0.490347 -0.0218756 0.364713 - -0.350646 0.0143949 0.31059 - -0.467987 0.0215517 0.35597 - -0.507166 0.0395866 0.371088 - -0.507932 0.0419671 0.371379 - -0.50924 0.0490637 0.37187 - -0.505365 0.100172 0.370261 - -0.507758 0.117477 0.37115 - -0.505098 0.133796 0.370086 - -0.503091 0.138119 0.3693 - -0.506449 0.151432 0.370571 - -0.5057 0.161186 0.37026 - -0.512241 0.356507 0.372372 - -0.506766 0.39758 0.370165 - -0.499431 0.624675 0.366841 - -0.496886 0.626933 0.365852 - -0.492513 0.711309 0.363979 - -0.488211 0.752304 0.362227 - -0.488008 0.924436 0.361779 - -0.484131 0.946 0.360233 - -0.490615 1.08119 0.362451 - -0.494534 1.24114 0.363624 - -0.490357 1.26134 0.361965 - -0.446473 1.2708 0.344968 - -0.42664 1.2815 0.337272 - -0.387648 1.26682 0.322219 - -0.0352388 0.0863718 0.188414 - -0.035343 0.0996931 0.188426 - -0.022446 0.0776131 0.183484 - -0.0208726 0.0737501 0.182883 - -0.0199955 0.0698111 0.182552 - -0.0199718 0.0738233 0.182535 --0.00969312 0.0837909 0.178537 --0.00949032 0.0817699 0.178463 - -0.0091576 0.0817424 0.178334 - -3.675e-05 0.111819 0.174741 - 0.00904188 0.133482 0.171182 - 0.026598 0.167072 0.164318 - 0.0370332 0.191969 0.160228 - 0.0259127 0.0863954 0.164756 - 0.0403761 0.10414 0.159123 - 0.0431366 0.095291 0.158074 - 0.830948 1.2831 -0.149252 - 0.469416 0.714792 -0.0081684 - 0.475218 0.710226 -0.0104033 - 0.758284 1.03274 -0.120604 - 0.941485 1.266 -0.191979 - 0.262469 -0.403436 0.0784187 - 0.0445427 -0.102088 0.158838 - 0.0437058 -0.102634 0.15915 - 0.0366346 -0.091996 0.161758 - 0.0252013 -0.0759379 0.165976 - 0.0275363 -0.104775 0.165169 - 0.0280411 -0.109975 0.164993 - 0.0231852 -0.110913 0.166801 - 0.0233648 -0.11297 0.166739 - 0.0264569 -0.125595 0.165615 - 0.0255709 -0.13014 0.165955 - 0.0142088 -0.105628 0.170129 - 0.0137767 -0.105761 0.17029 - 0.0119088 -0.102165 0.170977 - 0.0107033 -0.104579 0.17143 - 0.0102755 -0.104696 0.17159 - 0.0131511 -0.133774 0.170582 --0.00073817 -0.109006 0.175696 --0.00494787 -0.0944427 0.17723 --0.00769806 -0.0846817 0.178233 - -0.0109984 -0.0989263 0.179491 - -0.0110757 -0.108936 0.179541 - -0.0138151 -0.100997 0.180543 - -0.0146412 -0.101 0.18085 - -0.0185784 -0.106914 0.182327 - -0.0197294 -0.0828182 0.182704 - -0.021966 -0.0776017 0.183525 - -0.0234546 -0.0794385 0.184082 - -0.0468986 -0.149053 0.192951 - -0.163741 -0.482331 0.237125 - -0.149168 -0.405231 0.231539 - -0.205317 -0.403478 0.252421 - -0.206965 -0.402585 0.253033 - -0.216929 -0.401528 0.256736 - -0.229709 -0.405418 0.261498 - -0.252358 -0.409685 0.269932 - -0.258012 -0.403509 0.272022 - -0.364387 -0.410549 0.311606 - -0.405709 -0.409728 0.326975 - -0.437541 -0.413132 0.338822 - -0.439227 -0.411158 0.339445 - -0.455321 -0.408382 0.345426 - -0.498465 -0.42516 0.36151 - -0.509798 -0.298517 0.365455 - -0.506602 -0.255627 0.364175 - -0.515445 -0.254474 0.367462 - -0.510396 -0.235116 0.365542 - -0.504383 -0.174455 0.363176 - -0.510427 -0.138883 0.365348 - -0.50464 -0.134825 0.363187 - -0.506034 -0.11106 0.363655 - -0.506009 -0.106281 0.363635 - -0.507275 -0.0994082 0.364092 - -0.499379 -0.0838532 0.361122 - -0.502842 -0.0728264 0.362386 - -0.500052 -0.0563432 0.361313 - -0.503105 -0.0292149 0.362391 - -0.495086 -0.0197678 0.359388 - -0.292914 -0.00755882 0.28416 - -0.34805 0.0142349 0.304622 - -0.482827 0.0221726 0.354738 - -0.510209 0.0676481 0.364827 - -0.506537 0.0811587 0.363432 - -0.506202 0.0834476 0.363302 - -0.516122 0.114116 0.366927 - -0.508604 0.12691 0.364103 - -0.508742 0.164074 0.364075 - -0.503888 0.216595 0.362158 - -0.510823 0.258585 0.364648 - -0.502884 0.298108 0.36161 - -0.503425 0.31683 0.361772 - -0.504508 0.369752 0.362061 - -0.506728 0.406893 0.362808 - -0.507567 0.418711 0.363095 - -0.50481 0.49234 0.361912 - -0.499172 0.545131 0.359702 - -0.503647 0.559863 0.361336 - -0.499581 0.580061 0.35978 - -0.496732 0.592065 0.358695 - -0.490429 0.632854 0.356263 - -0.490339 0.655849 0.356181 - -0.486547 0.8551 0.354345 - -0.491399 0.908636 0.356035 - -0.484747 1.08832 0.353178 - -0.48584 1.11636 0.353524 - -0.495263 1.19388 0.356864 - -0.490744 1.19702 0.355176 - -0.44508 1.27939 0.338015 - -0.38154 1.26091 0.314419 - -0.364711 1.26112 0.308159 - -0.0399391 0.102526 0.189826 - -0.0260941 0.0750204 0.184735 - -0.0146446 0.104 0.180414 --0.00675646 0.083571 0.177523 --0.00607317 0.0834939 0.177269 - 0.040031 0.184978 0.159903 - 0.0407871 0.184721 0.159623 - 0.0648496 0.207259 0.150624 - 0.0261542 0.0933179 0.165261 - 0.0256955 0.0835362 0.165452 - 0.0260369 0.0833473 0.165326 - 0.0267173 0.0829648 0.165073 - 0.03443 0.0944207 0.16218 - 0.810865 1.29297 -0.129188 - 0.473719 0.703798 -0.0025225 - 0.557186 0.780474 -0.0337334 - 0.966037 1.26856 -0.186855 - 1.07381 1.26653 -0.226941 - 1.09055 1.25267 -0.233138 - 0.380104 -0.426827 0.0393481 - 0.363758 -0.419984 0.0452218 - 0.369465 -0.437645 0.0432036 - 1.24965 -1.47993 -0.271633 - 1.2369 -1.53076 -0.26693 - 1.2306 -1.53654 -0.264651 - 0.322088 -0.437791 0.0602695 - 0.31187 -0.443901 0.0639632 - 0.295615 -0.429442 0.0697877 - 0.029705 -0.0907135 0.164851 - 0.0274458 -0.10832 0.165702 - 0.026296 -0.106657 0.166113 - 0.0266843 -0.111872 0.165984 - 0.0258186 -0.115428 0.166304 --0.00023509 -0.113035 0.175683 - -0.0102127 -0.0979096 0.179245 - -0.0138117 -0.102999 0.180552 - -0.015113 -0.106995 0.18103 - -0.0155522 -0.10699 0.181188 - -0.0184689 -0.0858787 0.182194 - -0.0203611 -0.0827392 0.182868 - -0.0233021 -0.0814244 0.183925 - -0.023063 -0.0764191 0.183828 - -0.0236901 -0.0763338 0.184054 - -0.0257095 -0.0841113 0.184798 - -0.0292967 -0.0956579 0.186115 - -0.0317154 -0.105361 0.187006 - -0.0309371 -0.0892384 0.186692 - -0.511846 -1.72957 0.363407 - -0.156695 -0.465907 0.232792 - -0.151958 -0.402081 0.23095 - -0.162908 -0.40624 0.234903 - -0.180958 -0.402607 0.241397 - -0.241286 -0.405464 0.263134 - -0.258538 -0.403509 0.269344 - -0.317617 -0.405156 0.290628 - -0.346927 -0.406531 0.301189 - -0.352124 -0.405672 0.303059 - -0.362155 -0.40685 0.306675 - -0.371365 -0.403241 0.309985 - -0.506306 -0.423152 0.358634 - -0.508139 -0.360419 0.359161 - -0.509456 -0.325343 0.359561 - -0.503102 -0.299622 0.357218 - -0.503369 -0.284848 0.357283 - -0.514369 -0.264655 0.361202 - -0.51577 -0.245365 0.361666 - -0.509299 -0.233897 0.35931 - -0.51284 -0.232805 0.360583 - -0.507049 -0.219271 0.358469 - -0.504628 -0.136851 0.357421 - -0.503361 -0.0565595 0.356794 - -0.504555 -0.0292149 0.357166 - -0.496418 -0.0220043 0.35422 - -0.257887 -0.00320204 0.268259 - -0.26355 0.00134881 0.270289 - -0.260615 0.00819134 0.269217 - -0.275624 0.0099039 0.27462 - -0.498094 0.0273266 0.354719 - -0.507332 0.0554672 0.357987 - -0.50895 0.0742828 0.358529 - -0.503944 0.082819 0.356708 - -0.509377 0.0908148 0.358648 - -0.506507 0.121179 0.35755 - -0.504691 0.152326 0.35683 - -0.504063 0.154598 0.356598 - -0.503019 0.186907 0.356153 - -0.509321 0.191913 0.358413 - -0.50692 0.198783 0.357533 - -0.510533 0.205523 0.358821 - -0.50883 0.210117 0.358197 - -0.507872 0.223097 0.357825 - -0.507578 0.233847 0.357696 - -0.503532 0.268233 0.356165 - -0.507347 0.282005 0.35751 - -0.506362 0.296326 0.357125 - -0.512019 0.384795 0.358975 - -0.509473 0.411643 0.358001 - -0.510736 0.416414 0.358445 - -0.509225 0.426431 0.35788 - -0.509723 0.438397 0.358034 - -0.502418 0.471705 0.355332 - -0.502077 0.483912 0.355183 - -0.499478 0.494114 0.354225 - -0.506921 0.506091 0.356881 - -0.500051 0.568861 0.354273 - -0.495366 0.573342 0.352575 - -0.494985 0.583046 0.352418 - -0.500613 0.595085 0.354419 - -0.491551 0.692297 0.350948 - -0.492308 0.782847 0.351028 - -0.488646 0.90078 0.349459 - -0.490201 1.00407 0.349799 - -0.490815 1.05058 0.349922 - -0.487874 1.10506 0.348746 - -0.445962 1.27845 0.333281 - -0.425897 1.27109 0.326069 - -0.0379535 0.105034 0.188806 - -0.0295007 0.0854848 0.185803 - -0.0244936 0.0752213 0.184021 - -0.0218059 0.0765839 0.18305 - -0.0191155 0.084845 0.182064 - -0.0164704 0.108976 0.181059 - -0.0124107 0.110981 0.179593 --0.00980114 0.107894 0.178659 --0.00955564 0.094866 0.178599 - 0.00346075 0.115465 0.173866 - 0.00852649 0.1216 0.172028 - 0.0206883 0.154579 0.167578 - 0.0267552 0.168426 0.165363 - 0.0368545 0.189329 0.16168 - 0.053439 0.171477 0.155745 - 0.0275131 0.0973334 0.165241 - 0.0250551 0.0875202 0.166147 - 0.0356415 0.098621 0.16231 - 0.0483199 0.112825 0.157713 - 0.0501926 0.112798 0.157039 - 0.945066 1.26969 -0.167763 - 0.96781 1.26547 -0.175947 - 1.09508 1.27466 -0.22181 - 0.387467 -0.436536 0.041457 - 1.25814 -1.67929 -0.259248 - 0.286758 -0.426497 0.0765221 - 0.127382 -0.217677 0.131606 - 0.0454385 -0.0976059 0.1599 - 0.040652 -0.0960444 0.161564 - 0.0307882 -0.087037 0.164982 - 0.0313994 -0.0900952 0.164775 - 0.030034 -0.0942052 0.16526 - 0.0230254 -0.0866455 0.167686 - 0.030825 -0.120058 0.165039 - 0.0263267 -0.112247 0.16659 - 0.0290737 -0.14194 0.165696 - 0.0116674 -0.0973461 0.171665 - 0.0082239 -0.0972537 0.172865 - 0.00047659 -0.115018 0.175602 - -0.0070717 -0.081693 0.178161 - -0.0142373 -0.100998 0.180698 - -0.020301 -0.0746802 0.182755 - -0.0221588 -0.077492 0.183408 - -0.0294934 -0.0965722 0.186004 - -0.0823942 -0.280709 0.204824 - -0.511115 -1.72192 0.357241 - -0.154375 -0.403313 0.230162 - -0.155705 -0.401722 0.230622 - -0.217408 -0.409592 0.252135 - -0.265574 -0.402572 0.268901 - -0.270996 -0.403543 0.270792 - -0.368547 -0.409652 0.304792 - -0.416651 -0.411622 0.321555 - -0.418345 -0.409755 0.322141 - -0.46069 -0.411004 0.336897 - -0.464062 -0.406857 0.338063 - -0.50641 -0.429609 0.352865 - -0.508163 -0.373011 0.353356 - -0.506438 -0.285809 0.35257 - -0.508572 -0.266565 0.353272 - -0.5059 -0.256591 0.352321 - -0.501861 -0.251687 0.350903 - -0.509034 -0.249745 0.353398 - -0.511779 -0.228897 0.35431 - -0.50977 -0.172798 0.353491 - -0.503982 -0.141133 0.351408 - -0.50456 -0.138867 0.351605 - -0.498737 -0.13482 0.349567 - -0.503922 -0.0911353 0.351281 - -0.501637 -0.0380128 0.350373 - -0.493928 0.0247902 0.347554 - -0.505965 0.0299722 0.351736 - -0.507091 0.0622041 0.35206 - -0.502402 0.119825 0.350305 - -0.49589 0.122929 0.348029 - -0.503108 0.129562 0.35053 - -0.504654 0.164262 0.350995 - -0.511348 0.24049 0.353166 - -0.512608 0.249499 0.353586 - -0.505039 0.256905 0.350933 - -0.507662 0.324001 0.351705 - -0.506324 0.326279 0.351234 - -0.509552 0.361181 0.352284 - -0.50806 0.363467 0.35176 - -0.501653 0.39321 0.349465 - -0.505687 0.445249 0.35076 - -0.502041 0.461831 0.349454 - -0.503644 0.467429 0.350001 - -0.503953 0.475992 0.350091 - -0.501538 0.499139 0.3492 - -0.501366 0.512193 0.349113 - -0.495927 0.567389 0.347101 - -0.497762 0.627629 0.347613 - -0.495172 0.629857 0.346706 - -0.492933 0.67983 0.34582 - -0.492695 0.704813 0.345684 - -0.487024 0.750348 0.343612 - -0.493278 0.797372 0.345691 - -0.494317 0.822658 0.345999 - -0.492226 0.886797 0.345135 - -0.492215 0.914344 0.345073 - -0.489491 0.947767 0.344053 - -0.491854 1.23781 0.344262 - -0.369486 1.25182 0.3016 - -0.354932 1.23968 0.296555 - -0.0299157 0.0802203 0.185777 - -0.0259509 0.0728849 0.184411 - -0.0191518 0.0808066 0.182025 - -0.0094903 0.104896 0.178608 - -0.008858 0.0858356 0.178428 --0.00572185 0.0815444 0.177345 - -6.218e-05 0.107003 0.175319 - 0.00149683 0.111819 0.174766 - 0.00804069 0.124856 0.172458 - 0.00855501 0.124754 0.172279 - 0.0090689 0.124649 0.1721 - 0.021458 0.155552 0.167719 - 0.0389845 0.185728 0.161549 - 0.0397494 0.185482 0.161283 - 0.0462889 0.187446 0.159 - 0.0275332 0.0887584 0.165744 - 0.0327919 0.0937726 0.163901 - 0.0386028 0.091435 0.161881 - 0.0370788 0.0853792 0.162425 - 0.415882 0.680642 0.0291911 - 0.454725 0.708205 0.0156001 - 0.472002 0.701232 0.00959566 - 1.0552 1.26747 -0.194786 - 1.3003 -1.5957 -0.258751 - 1.29741 -1.60628 -0.257754 - 0.299891 -0.427212 0.0756137 - 0.298123 -0.428649 0.0762122 - 0.295049 -0.436118 0.0772628 - 0.0388214 -0.0917567 0.162806 - 0.0384416 -0.091996 0.162934 - 0.0410209 -0.0985188 0.16208 - 0.0294431 -0.082445 0.165944 - 0.0262877 -0.0919363 0.167026 - 0.0282508 -0.119182 0.166423 - 0.0144388 -0.100826 0.171035 - 0.0137605 -0.0999918 0.171261 - 0.0136041 -0.101078 0.171316 - 0.0088938 -0.0961798 0.172892 --0.00524071 -0.0855734 0.177628 --0.00916153 -0.078876 0.178934 - -0.0108521 -0.102966 0.179554 - -0.0117037 -0.102985 0.179841 - -0.0179196 -0.0838612 0.181894 - -0.0230977 -0.0863893 0.183642 - -0.0273949 -0.0836978 0.185084 - -0.498854 -1.78565 0.347412 - -0.506235 -1.78339 0.349892 - -0.15826 -0.463341 0.229946 - -0.146716 -0.408361 0.225943 - -0.163185 -0.40624 0.231484 - -0.266595 -0.403406 0.266295 - -0.3117 -0.409934 0.281495 - -0.347486 -0.408828 0.293542 - -0.388021 -0.409016 0.30719 - -0.402778 -0.403424 0.312147 - -0.46475 -0.413626 0.333034 - -0.466457 -0.411543 0.333604 - -0.505674 -0.416487 0.346819 - -0.506498 -0.40246 0.347067 - -0.504138 -0.372374 0.346208 - -0.508719 -0.365561 0.347737 - -0.50704 -0.35759 0.347154 - -0.504812 -0.339564 0.346366 - -0.508956 -0.313793 0.347707 - -0.505782 -0.287599 0.346583 - -0.509461 -0.286769 0.34782 - -0.505271 -0.247166 0.346326 - -0.5028 -0.203033 0.345401 - -0.512223 -0.193789 0.348554 - -0.50797 -0.112923 0.346951 - -0.509263 -0.101321 0.347362 - -0.502841 -0.0883637 0.345173 - -0.503054 -0.0584902 0.345181 - -0.508492 -0.024713 0.346941 - -0.462351 -0.0161982 0.331387 - -0.264528 -0.00327622 0.264755 - -0.260737 0.00360599 0.263464 - -0.508868 0.0484181 0.346913 - -0.506426 0.0781255 0.346028 - -0.51086 0.0929356 0.34749 - -0.506969 0.103971 0.346156 - -0.506093 0.108511 0.345852 - -0.504624 0.16879 0.34523 - -0.504593 0.209781 0.345133 - -0.504593 0.215061 0.345122 - -0.502772 0.257831 0.344419 - -0.506258 0.276896 0.345552 - -0.505278 0.285122 0.345205 - -0.50748 0.301378 0.345912 - -0.50712 0.329084 0.345732 - -0.50332 0.37597 0.344354 - -0.502615 0.449118 0.343962 - -0.506455 0.456644 0.345239 - -0.498956 0.521757 0.342577 - -0.493865 0.632073 0.34063 - -0.49753 0.672195 0.341779 - -0.491919 0.748986 0.339728 - -0.492883 0.779491 0.339988 - -0.493569 0.905144 0.339954 - -0.490562 1.13133 0.338464 - -0.490617 1.23133 0.338272 - -0.489891 1.2769 0.337931 - -0.453521 1.27644 0.325687 - -0.371959 1.25756 0.298265 - -0.0380762 0.0955326 0.188302 - -0.0353363 0.0983279 0.187373 - -0.0341042 0.0965746 0.186962 - -0.0294584 0.0833057 0.185426 - -0.0263984 0.0798398 0.184403 - -0.0251105 0.0780362 0.183973 - -0.0178038 0.0818713 0.181505 - -0.0174899 0.0898993 0.181382 - -0.0169321 0.0949293 0.181184 - -0.0168037 0.10294 0.181124 - -0.0152655 0.112984 0.180585 - -0.0147365 0.107992 0.180417 - -0.0109566 0.11797 0.179123 --0.00865375 0.0818432 0.178424 --0.00602684 0.0846376 0.177534 --0.00561209 0.0815813 0.177401 - 5.65e-05 0.100997 0.175451 - 0.00217369 0.106731 0.174726 - 0.0120798 0.129214 0.171343 - 0.0375468 0.187407 0.162646 - 0.0383214 0.18717 0.162386 - 0.0489343 0.190947 0.158805 - 0.0585676 0.208556 0.155524 - 0.0613277 0.20533 0.154601 - 0.0586006 0.19035 0.155551 - 0.052996 0.173332 0.157474 - 0.037857 0.125835 0.162672 - 0.0472311 0.116558 0.159535 - 0.0440051 0.10701 0.160641 - 0.0352759 0.0845988 0.163628 - 0.0356254 0.0843736 0.16351 - 0.387045 0.656543 0.0439826 - 0.957735 1.27592 -0.149471 - 1.05486 1.27315 -0.182166 - 1.06599 1.264 -0.185894 - 1.33421 -1.53356 -0.254514 - 1.29756 -1.61458 -0.242434 - 0.328168 -0.43934 0.0701174 - 0.299654 -0.424838 0.0793532 - 0.288852 -0.437099 0.0828891 - 0.640841 -0.96441 -0.0303874 - 0.039143 -0.0930956 0.163313 - 0.0365645 -0.0911985 0.164147 - 0.0284268 -0.0810734 0.166771 - 0.0281572 -0.117305 0.166934 - 0.025083 -0.128956 0.167958 - 0.0113809 -0.0956451 0.172341 - 0.007635 -0.117023 0.173603 - 0.00175951 -0.113961 0.175506 --0.00139775 -0.0992633 0.176501 --0.00875689 -0.101906 0.178898 --0.00988096 -0.106952 0.179274 - -0.0116195 -0.109991 0.179845 - -0.022228 -0.0763772 0.183222 - -0.025217 -0.0860348 0.184214 - -0.0261341 -0.0848715 0.184509 - -0.0325427 -0.092733 0.186608 - -0.0999259 -0.329494 0.209004 - -0.504106 -1.80006 0.343442 - -0.511572 -1.79779 0.345864 - -0.510829 -1.7114 0.345441 - -0.515671 -1.70146 0.346993 - -0.157226 -0.405468 0.227784 - -0.175201 -0.406566 0.233628 - -0.193379 -0.41125 0.239545 - -0.211622 -0.40971 0.24547 - -0.234342 -0.407015 0.252848 - -0.241323 -0.407375 0.255117 - -0.249047 -0.404823 0.257622 - -0.264082 -0.410234 0.262519 - -0.270086 -0.412092 0.264474 - -0.280261 -0.404867 0.267766 - -0.294168 -0.410441 0.272297 - -0.309476 -0.409714 0.27727 - -0.334335 -0.413279 0.285355 - -0.338691 -0.404263 0.286752 - -0.362582 -0.411556 0.294532 - -0.370249 -0.409652 0.297019 - -0.418012 -0.410927 0.312543 - -0.50836 -0.428973 0.341941 - -0.510136 -0.426695 0.342514 - -0.502809 -0.39125 0.340058 - -0.50905 -0.35475 0.342009 - -0.511576 -0.311507 0.34274 - -0.500083 -0.286448 0.338952 - -0.506889 -0.241782 0.34107 - -0.508312 -0.228784 0.341505 - -0.504337 -0.169985 0.340089 - -0.504495 -0.152708 0.340104 - -0.50741 -0.107756 0.340957 - -0.502037 -0.0833731 0.33916 - -0.508955 -0.0822183 0.341406 - -0.501424 -0.0377926 0.338865 - -0.504831 -0.028991 0.339953 - -0.481485 -0.0189971 0.332346 - -0.471105 -0.0164715 0.328967 - -0.266849 -0.00563062 0.262568 - -0.268809 -0.00097829 0.263195 - -0.268811 0.00019544 0.263193 - -0.505821 0.0434367 0.340123 - -0.506664 0.0641147 0.340353 - -0.509369 0.0924125 0.341173 - -0.501315 0.104842 0.338529 - -0.504532 0.122081 0.339539 - -0.513038 0.151155 0.342241 - -0.504377 0.185891 0.339354 - -0.509929 0.233033 0.341059 - -0.504268 0.241267 0.339202 - -0.51152 0.273274 0.341491 - -0.503813 0.292381 0.338947 - -0.505747 0.324156 0.339508 - -0.507051 0.331353 0.339917 - -0.50525 0.359473 0.339273 - -0.504266 0.39321 0.338882 - -0.512607 0.414555 0.341547 - -0.49776 0.542277 0.336454 - -0.494234 0.56737 0.335256 - -0.497159 0.652053 0.336028 - -0.493195 0.676624 0.334688 - -0.491198 0.705388 0.333979 - -0.495357 0.820106 0.335089 - -0.491988 0.830484 0.333972 - -0.488283 0.902094 0.332618 - -0.491179 1.1709 0.332993 - -0.493584 1.26726 0.333573 - -0.474167 1.28055 0.327235 - -0.449634 1.27939 0.319265 - -0.437434 1.27862 0.315302 - -0.0382393 0.0974626 0.18806 - -0.0374296 0.0976901 0.187796 - -0.0403517 0.115486 0.188708 - -0.0276984 0.0815545 0.184668 - -0.0256894 0.0798987 0.184018 - -0.0223631 0.0804032 0.182936 - -0.021806 0.078459 0.182759 - -0.0195233 0.0787042 0.182017 - -0.0165955 0.0969278 0.181027 - -0.014716 0.104985 0.180399 - -0.0142803 0.104992 0.180258 - -0.0116911 0.10299 0.179421 --0.00854772 0.0968847 0.178412 - -0.0042544 0.0804725 0.177051 - 0.00651596 0.119237 0.17347 - 0.00834559 0.120924 0.172872 - 0.0252182 0.167218 0.167291 - 0.0284678 0.171522 0.166226 - 0.033062 0.180593 0.164714 - 0.0569766 0.196647 0.156909 - 0.0583849 0.192871 0.156459 - 0.0532582 0.176728 0.158159 - 0.0539911 0.176422 0.157922 - 0.0281878 0.086777 0.166495 - 0.412553 0.695213 0.0403089 - 0.471731 0.701046 0.0210657 - 0.477449 0.702843 0.0192037 - 0.997831 1.27704 -0.151112 - 1.02106 1.27213 -0.158651 - 1.07192 1.27716 -0.17519 - 0.365667 -0.429131 0.0622615 - 0.347509 -0.419407 0.0679329 - 0.336419 -0.413688 0.0713975 - 0.334694 -0.415279 0.0719415 - 0.622331 -0.942069 -0.0171176 - 0.0262281 -0.0902938 0.167953 - 0.0306566 -0.116534 0.166619 - 0.0307442 -0.128232 0.166617 - 0.0283639 -0.13014 0.167367 - 0.0126733 -0.0954184 0.172212 - 0.0106952 -0.122616 0.172889 - 0.00963858 -0.119775 0.173215 - -0.0112739 -0.103992 0.179737 - -0.0184964 -0.0747377 0.181939 - -0.0256086 -0.0838846 0.184188 - -0.0384136 -0.112775 0.188263 - -0.0448944 -0.135816 0.190342 - -0.168452 -0.404133 0.229635 - -0.187642 -0.411875 0.235667 - -0.194586 -0.399706 0.237818 - -0.198745 -0.399821 0.239122 - -0.207544 -0.400804 0.241882 - -0.226022 -0.407515 0.247688 - -0.240708 -0.405653 0.252288 - -0.266982 -0.402572 0.260517 - -0.271308 -0.405559 0.26188 - -0.272994 -0.404371 0.262406 - -0.310018 -0.40597 0.274015 - -0.309953 -0.402234 0.273987 - -0.313293 -0.399496 0.275028 - -0.360164 -0.407828 0.289737 - -0.372089 -0.407274 0.293474 - -0.459554 -0.410431 0.320898 - -0.470451 -0.409452 0.324312 - -0.483349 -0.413596 0.328364 - -0.499854 -0.398577 0.333506 - -0.503157 -0.394103 0.334532 - -0.508942 -0.381016 0.336318 - -0.509673 -0.360999 0.336505 - -0.502943 -0.330161 0.334331 - -0.504504 -0.282446 0.33472 - -0.511859 -0.238068 0.336932 - -0.502164 -0.18637 0.333785 - -0.508958 -0.181281 0.335904 - -0.507175 -0.168037 0.335317 - -0.501162 -0.144034 0.333382 - -0.506356 -0.143131 0.335008 - -0.505337 -0.135582 0.334673 - -0.502481 -0.122886 0.333751 - -0.503527 -0.11369 0.33406 - -0.507021 -0.0840132 0.335093 - -0.504231 -0.069748 0.334188 - -0.506011 -0.0631181 0.334733 - -0.512311 -0.0362416 0.336651 - -0.267279 -0.00563062 0.259779 - -0.510049 0.0620858 0.335736 - -0.511169 0.0761436 0.336058 - -0.504525 0.0820332 0.333962 - -0.503976 0.112192 0.333727 - -0.501412 0.128107 0.33289 - -0.507563 0.146683 0.334779 - -0.505178 0.198552 0.333923 - -0.511887 0.252792 0.335912 - -0.502387 0.324276 0.332784 - -0.507614 0.347052 0.334375 - -0.509692 0.368596 0.334982 - -0.505023 0.378812 0.333496 - -0.506243 0.470359 0.333687 - -0.503819 0.4805 0.332906 - -0.501225 0.490654 0.332072 - -0.497917 0.53642 0.330939 - -0.497295 0.5548 0.330705 - -0.494982 0.55701 0.329976 - -0.492711 0.863335 0.328622 - -0.493608 1.14633 0.32831 - -0.48838 1.25054 0.326452 - -0.474247 1.27774 0.321965 - -0.439978 1.28334 0.311212 - -0.404619 1.2652 0.300166 - -0.0354975 0.100171 0.186902 - -0.0290722 0.0832313 0.184923 - -0.0264787 0.0807018 0.184116 - -0.0217425 0.078418 0.182636 - -0.0213038 0.0774658 0.1825 - -0.0165834 0.0879015 0.180999 - -0.0121244 0.102998 0.17957 - -0.0108044 0.104982 0.179152 --0.00805752 0.107894 0.178284 --0.00290943 0.0853963 0.176718 - 0.0104674 0.118553 0.172455 - 0.0260037 0.16201 0.167494 - 0.0336375 0.180593 0.165062 - 0.0376908 0.189797 0.163772 - 0.0487887 0.197773 0.160277 - 0.0507364 0.198151 0.159666 - 0.0293928 0.0953229 0.166572 - 0.390775 0.669508 0.0520885 - 0.41957 0.703619 0.0429909 - 0.435173 0.708461 0.0380899 - 0.438119 0.706405 0.0371705 - 0.446672 0.706383 0.0344895 - 0.350271 -0.424034 0.0722786 - 0.291086 -0.427881 0.0899892 - 0.0315979 -0.0924108 0.166903 - 0.0245922 -0.0935072 0.169001 - 0.032573 -0.124611 0.166679 - 0.0253414 -0.116672 0.168825 - 0.0259771 -0.125919 0.168654 - 0.00581859 -0.111464 0.174654 - 0.00088801 -0.106154 0.176117 --0.00459487 -0.0846489 0.177713 --0.00522362 -0.0857096 0.177903 - -0.0111627 -0.105996 0.179722 - -0.0319485 -0.0998473 0.185926 - -0.0326885 -0.0914818 0.18613 - -0.0361867 -0.102944 0.1872 - -0.0852946 -0.275542 0.202249 - -0.152659 -0.403021 0.222664 - -0.171571 -0.401766 0.228318 - -0.178111 -0.403223 0.230277 - -0.182248 -0.403522 0.231515 - -0.194765 -0.404152 0.235261 - -0.199387 -0.405171 0.236645 - -0.220336 -0.408646 0.242918 - -0.222679 -0.400503 0.243602 - -0.274496 -0.409715 0.25912 - -0.274599 -0.406028 0.259143 - -0.293079 -0.407196 0.264673 - -0.302724 -0.409746 0.267563 - -0.33555 -0.405702 0.277373 - -0.346666 -0.405043 0.280697 - -0.362513 -0.413157 0.285454 - -0.392163 -0.403411 0.294302 - -0.502748 -0.414349 0.327401 - -0.509576 -0.327261 0.329262 - -0.507407 -0.319562 0.328597 - -0.50269 -0.310372 0.327167 - -0.506448 -0.309677 0.32829 - -0.514473 -0.299333 0.330668 - -0.505779 -0.276517 0.32802 - -0.502194 -0.2274 0.326845 - -0.50941 -0.222653 0.328994 - -0.509927 -0.138867 0.328974 - -0.508676 -0.119297 0.328559 - -0.508235 -0.0724111 0.328329 - -0.506253 -0.0652485 0.327721 - -0.507473 -0.0631181 0.328082 - -0.506782 -0.0607441 0.32787 - -0.264942 0.00364744 0.2554 - -0.508327 0.0456972 0.32811 - -0.50622 0.0866945 0.327394 - -0.504402 0.1026 0.326817 - -0.510818 0.139881 0.328658 - -0.511154 0.142415 0.328754 - -0.507488 0.148668 0.327644 - -0.510674 0.161993 0.328569 - -0.509455 0.215445 0.328093 - -0.508417 0.225669 0.327761 - -0.506422 0.232841 0.327149 - -0.509804 0.237167 0.328152 - -0.509541 0.242537 0.328062 - -0.509391 0.245227 0.328011 - -0.5102 0.291595 0.328156 - -0.508977 0.293861 0.327786 - -0.511046 0.304154 0.328383 - -0.507273 0.369121 0.327119 - -0.506504 0.371957 0.326883 - -0.50482 0.384497 0.326354 - -0.500097 0.405626 0.324897 - -0.490288 0.574695 0.32161 - -0.49351 0.583689 0.322555 - -0.495571 0.701565 0.322925 - -0.488355 0.803942 0.320553 - -0.490003 0.864654 0.320919 - -0.495035 0.90078 0.322349 - -0.491634 0.913034 0.321306 - -0.494775 1.15953 0.321731 - -0.473508 1.27213 0.315135 - -0.462194 1.2744 0.311746 - -0.457191 1.27738 0.310243 - -0.370826 1.24511 0.284478 - -0.0265171 0.0816209 0.183923 - -0.0207836 0.0744474 0.182223 - -0.0173059 0.0788114 0.181173 - -0.0156337 0.107937 0.180612 - -0.012462 0.104999 0.17967 --0.00767698 0.103897 0.178241 --0.00053822 0.0942316 0.176126 - 0.0133429 0.127256 0.171905 - 0.0311638 0.174233 0.166476 - 0.0365884 0.189284 0.164823 - 0.0381694 0.188833 0.164351 - 0.054261 0.206684 0.1595 - 0.0592832 0.201657 0.158009 - 0.0460253 0.148042 0.162086 - 0.0304206 0.100652 0.166852 - 0.0284647 0.0905999 0.167458 - 0.0269583 0.0824825 0.167926 - 0.0418593 0.0944936 0.163444 - 0.367488 0.646012 0.0648952 - 0.422894 0.7053 0.0481992 - 0.444754 0.699774 0.0416721 - 0.521388 0.738332 0.0186701 - 1.00424 1.2632 -0.126849 - 1.06416 1.26866 -0.144783 - 1.14156 1.2678 -0.167933 - 0.384407 -0.430827 0.0666157 - 1.28848 -1.62785 -0.190956 - 1.27113 -1.63493 -0.185953 - 0.203985 -0.345695 0.118338 - 0.188173 -0.326543 0.122847 - 0.166532 -0.308714 0.129035 - 0.0305332 -0.0842977 0.167689 - 0.0284198 -0.0809307 0.16829 - 0.0309899 -0.0929983 0.167576 - 0.0274034 -0.0881192 0.168597 - 0.023682 -0.0876356 0.169667 - 0.0247646 -0.0925813 0.169366 - 0.0292306 -0.112247 0.168122 - 0.0237124 -0.113202 0.169711 - 0.0139055 -0.0974626 0.1725 - 0.0104252 -0.0994022 0.173505 - 0.00970526 -0.106732 0.173727 - 0.0107892 -0.114668 0.173432 --0.00517283 -0.0767117 0.177944 --0.00574113 -0.0777638 0.17811 - -0.008428 -0.108951 0.178948 - -0.0138699 -0.106973 0.180509 - -0.0144197 -0.11096 0.180676 - -0.0148849 -0.110946 0.180809 - -0.015596 -0.0788886 0.180947 - -0.0176058 -0.0837643 0.181536 - -0.0237954 -0.090105 0.183329 - -0.0313123 -0.102967 0.185518 - -0.102016 -0.322508 0.206314 - -0.152038 -0.39581 0.220856 - -0.172385 -0.403613 0.226725 - -0.198299 -0.40247 0.234177 - -0.216611 -0.405168 0.23945 - -0.217857 -0.40335 0.239805 - -0.225689 -0.405762 0.242063 - -0.376084 -0.406356 0.285326 - -0.410605 -0.407627 0.295259 - -0.433382 -0.408879 0.301814 - -0.499768 -0.425798 0.320945 - -0.505086 -0.41911 0.322461 - -0.510046 -0.36953 0.323785 - -0.506117 -0.340171 0.322594 - -0.510033 -0.311221 0.32366 - -0.504651 -0.27239 0.322031 - -0.513635 -0.187164 0.324438 - -0.510651 -0.180952 0.323566 - -0.507083 -0.142598 0.32246 - -0.507677 -0.140346 0.322627 - -0.501764 -0.136286 0.320917 - -0.507961 -0.114121 0.322654 - -0.50999 -0.0748132 0.323155 - -0.5083 -0.0471137 0.322612 - -0.507091 0.0386886 0.322085 - -0.505415 0.0475881 0.321585 - -0.503094 0.0997828 0.320808 - -0.504175 0.114003 0.32109 - -0.503541 0.125632 0.320883 - -0.505438 0.138065 0.321403 - -0.508119 0.160804 0.322127 - -0.503724 0.171716 0.32084 - -0.510334 0.228734 0.322623 - -0.518914 0.238189 0.325071 - -0.516899 0.242785 0.324482 - -0.507893 0.243945 0.321889 - -0.507119 0.289149 0.321572 - -0.500117 0.299816 0.319536 - -0.505633 0.334236 0.321051 - -0.506817 0.374793 0.321307 - -0.503982 0.469906 0.320293 - -0.500024 0.474357 0.319146 - -0.49822 0.489406 0.318595 - -0.506488 0.502084 0.320948 - -0.501379 0.514543 0.319452 - -0.498897 0.583758 0.318594 - -0.495147 0.650311 0.317377 - -0.492133 0.664028 0.316481 - -0.495121 0.680427 0.317307 - -0.490894 0.699686 0.31605 - -0.489361 0.744525 0.315516 - -0.497563 0.867656 0.317619 - -0.487166 0.884196 0.314594 - -0.487057 1.06164 0.314193 - -0.473857 1.28733 0.309927 - -0.386754 1.25804 0.284932 - -0.341864 1.14263 0.272259 - -0.019335 0.0765839 0.181699 - -0.0188978 0.0826571 0.181561 - -0.0168288 0.0778138 0.180976 --0.00697052 0.0918702 0.178111 --0.00650819 0.0808225 0.178001 - 0.00449039 0.10567 0.174785 - 0.0080977 0.116192 0.173726 - 0.0368461 0.118708 0.165451 - 0.0350666 0.112976 0.165975 - 0.033821 0.0937282 0.166373 - 0.421202 0.706433 0.0536645 - 0.459787 0.700017 0.0425785 - 0.985597 1.23564 -0.10979 - 1.02742 1.25374 -0.121857 - 1.03645 1.25353 -0.124455 - 1.11115 1.2739 -0.145985 - 1.11909 1.27172 -0.148266 - 0.368213 -0.426192 0.075529 - 0.348949 -0.422682 0.0808466 - 0.34862 -0.433598 0.0809601 - 0.288438 -0.428195 0.0975843 - 0.286635 -0.429546 0.0980855 - 0.253506 -0.419178 0.107221 - 0.236418 -0.399679 0.111904 - 0.187574 -0.333487 0.125268 - 0.0415966 -0.0988716 0.165132 - 0.040345 -0.0995793 0.16548 - 0.031425 -0.0897192 0.167925 - 0.028765 -0.0910261 0.168663 - 0.0249009 -0.0927454 0.169734 - 0.0287099 -0.105167 0.168707 - 0.0122031 -0.0939278 0.173247 - 0.00389371 -0.104847 0.175566 - 0.00127162 -0.0951323 0.176271 --0.00434047 -0.0857096 0.177803 --0.00883316 -0.112975 0.179101 - -0.0174192 -0.0867559 0.18142 - -0.0188776 -0.086629 0.181823 - -0.019427 -0.0885839 0.181979 - -0.0211345 -0.0904073 0.182455 - -0.112916 -0.350394 0.208364 - -0.148904 -0.432958 0.218483 - -0.148963 -0.403346 0.218438 - -0.165277 -0.405545 0.222952 - -0.199281 -0.399821 0.232339 - -0.202241 -0.401654 0.233161 - -0.251668 -0.402885 0.246826 - -0.265712 -0.410234 0.250724 - -0.279311 -0.404443 0.254471 - -0.316864 -0.405594 0.264853 - -0.341949 -0.405026 0.271786 - -0.400078 -0.406642 0.287857 - -0.498132 -0.419743 0.314988 - -0.502125 -0.419441 0.316091 - -0.507478 -0.299875 0.317323 - -0.50981 -0.283407 0.317933 - -0.512693 -0.282099 0.318727 - -0.512459 -0.178684 0.318448 - -0.506005 -0.163949 0.316634 - -0.51568 -0.132542 0.319243 - -0.507517 -0.120873 0.316962 - -0.498136 -0.104712 0.314335 - -0.506575 -0.0787306 0.316614 - -0.504731 -0.0309458 0.316006 - -0.502933 -0.0285993 0.315504 - -0.503157 -0.0241459 0.315556 - -0.293504 -0.00745702 0.25757 - -0.506242 0.0498295 0.316256 - -0.512281 0.057315 0.317909 - -0.511625 0.071039 0.3177 - -0.504638 0.102209 0.315704 - -0.504807 0.132823 0.315687 - -0.515181 0.142943 0.318533 - -0.50617 0.167242 0.315992 - -0.511215 0.261884 0.31719 - -0.511003 0.273226 0.317108 - -0.503849 0.382102 0.314905 - -0.505106 0.438099 0.315136 - -0.505606 0.454266 0.31524 - -0.505458 0.495663 0.315114 - -0.496026 0.516818 0.312463 - -0.505657 0.536366 0.315084 - -0.499342 0.598741 0.313209 - -0.494932 0.625831 0.311934 - -0.493243 0.682614 0.311349 - -0.494219 0.729714 0.311522 - -0.490247 0.773274 0.310333 - -0.491926 0.847342 0.310644 - -0.491882 0.928819 0.310462 - -0.459641 1.27926 0.300823 - -0.452955 1.27751 0.298979 - -0.346628 1.13921 0.269875 - -0.0415937 0.115797 0.187682 - -0.0338545 0.0961798 0.185583 - -0.0323825 0.0934602 0.185182 - -0.0217744 0.078239 0.182281 - -0.0197969 0.0784985 0.181734 - -0.0184752 0.0786416 0.181369 - -0.014872 0.109936 0.180308 - -0.0124476 0.100992 0.179656 - -0.010238 0.110995 0.179025 --0.00740402 0.111929 0.178239 --0.00592663 0.103853 0.177848 --0.00532624 0.0867835 0.177717 - 0.00143362 0.0961043 0.175829 - 0.00510351 0.109696 0.174787 - 0.0112671 0.119741 0.173062 - 0.0174908 0.142919 0.171294 - 0.0344842 0.179836 0.16652 - 0.0414355 0.18717 0.164583 - 0.050579 0.203095 0.162023 - 0.0552576 0.197264 0.160742 - 0.0550002 0.183537 0.160841 - 0.0460622 0.150684 0.16338 - 0.395694 0.681674 0.065634 - 0.440054 0.706794 0.05332 - 0.461609 0.700017 0.0473757 - 0.505865 0.731054 0.0350782 - 0.525091 0.73112 0.0297636 - 1.10175 1.27011 -0.130753 - 0.387913 -0.416467 0.0745077 - 0.385852 -0.436591 0.075096 - 1.14905 -1.65288 -0.124841 - 0.195158 -0.344547 0.125491 - 0.174001 -0.321556 0.131056 - 0.0473237 -0.109634 0.164221 - 0.0276128 -0.0852216 0.169399 - 0.0280451 -0.118395 0.169353 - 0.0264402 -0.116841 0.169775 - 0.0147292 -0.0985434 0.172844 - 0.0114978 -0.0942367 0.173692 - 0.00890117 -0.0938288 0.17438 - 0.00676638 -0.111544 0.174983 - 0.00629583 -0.111621 0.175108 - -0.0068886 -0.0768972 0.178534 --0.00718003 -0.106937 0.178673 - -0.0103543 -0.102999 0.179507 - -0.0107887 -0.103 0.179622 - -0.013152 -0.111971 0.180268 - -0.0145685 -0.111929 0.180644 - -0.0220956 -0.0952757 0.182606 - -0.0238222 -0.0990766 0.183072 - -0.0246575 -0.0989545 0.183293 - -0.0243451 -0.0838239 0.183179 - -0.0314562 -0.102784 0.185104 - -0.0305025 -0.0866157 0.184818 - -0.0369261 -0.10454 0.186559 - -0.51653 -1.65813 0.316998 - -0.150394 -0.437705 0.217348 - -0.212262 -0.40882 0.2337 - -0.224847 -0.407609 0.237036 - -0.279475 -0.411829 0.251536 - -0.32614 -0.409849 0.26391 - -0.362908 -0.407828 0.273659 - -0.418645 -0.410691 0.288451 - -0.437818 -0.411605 0.293539 - -0.509141 -0.39879 0.312432 - -0.503403 -0.380163 0.310871 - -0.516018 -0.368992 0.314195 - -0.512178 -0.330062 0.313095 - -0.510533 -0.292123 0.312581 - -0.503663 -0.256635 0.310685 - -0.515352 -0.215836 0.313701 - -0.504576 -0.203435 0.310817 - -0.509676 -0.154962 0.312069 - -0.510326 -0.152708 0.312237 - -0.503845 -0.143492 0.310499 - -0.505674 -0.120187 0.310936 - -0.507462 -0.0856163 0.311339 - -0.50788 -0.0764871 0.31143 - -0.509157 -0.0492734 0.311713 - -0.49272 -0.0192283 0.307291 - -0.254309 -0.00421493 0.244016 - -0.492422 0.0264776 0.307117 - -0.503388 0.0742688 0.309927 - -0.511054 0.0939742 0.31192 - -0.50757 0.116681 0.310949 - -0.502213 0.153401 0.309452 - -0.508767 0.195588 0.311103 - -0.501161 0.239673 0.308994 - -0.507076 0.302865 0.310432 - -0.504505 0.307333 0.309741 - -0.50684 0.314916 0.310345 - -0.508679 0.385096 0.310688 - -0.505415 0.389575 0.309812 - -0.502112 0.394024 0.308927 - -0.503391 0.447406 0.309156 - -0.503029 0.523269 0.308903 - -0.500818 0.525485 0.308312 - -0.499814 0.56737 0.307959 - -0.495899 0.588157 0.306877 - -0.498279 0.628952 0.307424 - -0.49645 0.685842 0.306821 - -0.494916 0.74318 0.306296 - -0.494179 0.884643 0.305807 - -0.491459 0.998211 0.304851 - -0.474271 1.28359 0.299701 - -0.0303214 0.0877078 0.184409 - -0.0279807 0.0821002 0.1838 - -0.0271669 0.087377 0.183573 - -0.0226996 0.0780362 0.182407 - -0.0209731 0.0803145 0.181945 - -0.0170479 0.0827487 0.180898 - -0.0120528 0.102992 0.179532 --0.00983776 0.107995 0.178934 --0.00378928 0.0866958 0.177373 --0.00050463 0.0863436 0.176503 - 0.00588395 0.108633 0.174762 - 0.00998542 0.112966 0.173665 - 0.0126771 0.124649 0.172927 - 0.0308471 0.175781 0.168001 - 0.0347718 0.0904407 0.167136 - 0.406942 0.697824 0.0671542 - 0.436424 0.698459 0.0593322 - 0.459317 0.70051 0.0532552 - 0.531721 0.737485 0.0339723 - 0.601406 0.747506 0.0154661 - 1.02826 1.20335 -0.0987094 - 0.383353 -0.432218 0.0801132 - 1.29632 -1.60814 -0.149524 - 0.320186 -0.429116 0.0961628 - 1.15067 -1.66541 -0.112383 - 0.604281 -0.92348 0.0249698 - 0.244377 -0.408935 0.115391 - 0.187176 -0.336128 0.12978 - 0.185753 -0.337013 0.130144 - 0.175521 -0.325834 0.132722 - 0.0357279 -0.0913965 0.167771 - 0.0335667 -0.0880454 0.168314 - 0.0328206 -0.0884371 0.168504 - 0.0278482 -0.0875576 0.169766 - 0.029052 -0.0935695 0.169473 - 0.0205218 -0.0799006 0.171613 - 0.0290833 -0.12349 0.169527 - 0.0239836 -0.117807 0.170811 - 0.0178619 -0.105057 0.172341 - 0.0149673 -0.0975773 0.173061 - 0.0126104 -0.095106 0.173655 - 0.00722562 -0.108504 0.175052 - 0.00204897 -0.0941414 0.176338 - 0.00125234 -0.094249 0.176541 --0.00155173 -0.0865298 0.177237 --0.00591365 -0.0808729 0.178334 - -0.0136559 -0.110946 0.180365 - -0.025344 -0.0876365 0.183287 - -0.0319609 -0.102593 0.185 - -0.0323996 -0.100444 0.185107 - -0.0328756 -0.0931313 0.185213 - -0.0468305 -0.137937 0.188853 - -0.504598 -1.66647 0.308365 - -0.145661 -0.393922 0.214502 - -0.148989 -0.392687 0.215346 - -0.152998 -0.398624 0.216377 - -0.240614 -0.411189 0.238674 - -0.258157 -0.404917 0.24312 - -0.287324 -0.396651 0.250517 - -0.313727 -0.411305 0.257258 - -0.32004 -0.40499 0.25885 - -0.328916 -0.4092 0.261115 - -0.457288 -0.411179 0.293749 - -0.506679 -0.403276 0.306288 - -0.510533 -0.384945 0.307229 - -0.504398 -0.369934 0.305639 - -0.50751 -0.365469 0.306421 - -0.508771 -0.324063 0.306656 - -0.509022 -0.317985 0.306707 - -0.503046 -0.305048 0.305162 - -0.506447 -0.211634 0.305833 - -0.504481 -0.177662 0.305263 - -0.509638 -0.174488 0.306568 - -0.507229 -0.141798 0.305888 - -0.506177 -0.134312 0.305605 - -0.508377 -0.125362 0.306146 - -0.513288 -0.112289 0.307367 - -0.507075 -0.103897 0.30577 - -0.511337 -0.0562351 0.306756 - -0.507371 0.0474958 0.305533 - -0.507167 0.0497329 0.305477 - -0.502308 0.0671981 0.304206 - -0.503941 0.0696833 0.304616 - -0.502356 0.080776 0.30419 - -0.507787 0.128349 0.305472 - -0.513832 0.161696 0.30694 - -0.512448 0.166222 0.306579 - -0.515523 0.184974 0.307322 - -0.509232 0.254247 0.30558 - -0.510891 0.266399 0.305976 - -0.505053 0.292146 0.304439 - -0.50712 0.336475 0.304873 - -0.504233 0.374077 0.304062 - -0.509876 0.414109 0.305413 - -0.50101 0.548171 0.302883 - -0.496185 0.678014 0.301389 - -0.489148 0.69317 0.299569 - -0.488373 0.821523 0.299107 - -0.490425 0.983528 0.299294 - -0.490985 1.06436 0.29927 - -0.491035 1.1694 0.299066 - -0.487298 1.28309 0.297881 - -0.475073 1.28359 0.294773 - -0.408406 1.2652 0.277865 - -0.3974 1.26778 0.275062 - -0.0510974 0.139836 0.189364 - -0.0395034 0.101657 0.186496 - -0.0306008 0.0854931 0.184266 - -0.0223286 0.0739802 0.182187 - -0.0224197 0.0810545 0.182196 - -0.0193078 0.0754401 0.181417 - -0.0155942 0.0888378 0.180445 --0.00576913 0.0828629 0.17796 - 0.00358081 0.0989545 0.17555 - 0.00892701 0.10716 0.174174 - 0.0258781 0.161718 0.169753 - 0.0338549 0.176169 0.167695 - 0.0345995 0.175968 0.167507 - 0.0381049 0.186387 0.166594 - 0.0447403 0.144173 0.164995 - 0.0314587 0.0968043 0.168468 - 0.0302216 0.0896939 0.168797 - 0.0380734 0.0979742 0.166784 - 0.0459424 0.101537 0.164777 - 0.45307 0.76459 0.0599222 - 0.437558 0.71791 0.0639614 - 0.451259 0.698947 0.060518 - 0.518451 0.736739 0.0433609 - 0.612963 0.745733 0.0193186 - 1.15008 1.26055 -0.118271 - 0.381945 -0.400173 0.084721 - 0.387948 -0.431894 0.0833265 - 0.373348 -0.430856 0.0868749 - 0.24841 -0.417671 0.117229 - 0.211388 -0.368367 0.12613 - 0.188606 -0.336983 0.131606 - 0.0795423 -0.166244 0.157776 - 0.0284666 -0.110146 0.17008 - 0.0273728 -0.12003 0.170367 - 0.0124563 -0.0942367 0.173941 - 0.00940325 -0.0898335 0.174674 - 0.00864085 -0.0900033 0.17486 - 0.00330572 -0.097056 0.176172 --0.00628716 -0.107937 0.178527 - -0.0103717 -0.0999985 0.179504 - -0.0134235 -0.116943 0.180281 - -0.0161373 -0.0857587 0.180877 - -0.0196779 -0.0914457 0.181749 - -0.0210251 -0.0963191 0.182087 - -0.0275753 -0.0911996 0.183669 - -0.0313632 -0.103667 0.184616 - -0.0318025 -0.10357 0.184723 - -0.0333369 -0.10424 0.185097 - -0.1487 -0.420332 0.213801 - -0.147316 -0.410251 0.213444 - -0.147923 -0.39519 0.21356 - -0.161147 -0.40506 0.216796 - -0.229543 -0.407408 0.233433 - -0.2767 -0.410546 0.244907 - -0.279626 -0.407306 0.245612 - -0.315838 -0.409934 0.254423 - -0.457303 -0.410514 0.288825 - -0.516291 -0.371271 0.303088 - -0.500889 -0.346839 0.299293 - -0.504421 -0.326919 0.30011 - -0.501705 -0.322011 0.29944 - -0.512102 -0.280193 0.301882 - -0.514461 -0.275671 0.302446 - -0.511423 -0.232091 0.301618 - -0.510706 -0.226371 0.301432 - -0.505494 -0.216094 0.300143 - -0.512957 -0.185478 0.301895 - -0.505752 -0.160507 0.300092 - -0.506429 -0.158278 0.300252 - -0.508936 -0.10878 0.300759 - -0.507417 -0.0784278 0.300327 - -0.515306 -0.0634815 0.302215 - -0.287732 -0.00727887 0.24676 - -0.256693 0.00461742 0.239187 - -0.506491 0.0316281 0.299876 - -0.501256 0.0490569 0.298567 - -0.510252 0.056767 0.300739 - -0.499578 0.0644751 0.298127 - -0.499015 0.0688698 0.297981 - -0.509632 0.0772344 0.300546 - -0.505966 0.0880938 0.299632 - -0.506956 0.118471 0.29981 - -0.505935 0.122929 0.299553 - -0.510223 0.145594 0.300549 - -0.51147 0.148392 0.300846 - -0.510362 0.190392 0.30049 - -0.50362 0.210845 0.298809 - -0.510759 0.219183 0.300528 - -0.508896 0.245333 0.300021 - -0.501 0.325492 0.297936 - -0.504505 0.330965 0.298777 - -0.503498 0.366109 0.29846 - -0.510909 0.396069 0.3002 - -0.509226 0.398314 0.299786 - -0.51041 0.406499 0.300057 - -0.509175 0.424001 0.299721 - -0.503001 0.473675 0.298117 - -0.503026 0.512411 0.298044 - -0.50002 0.518252 0.297301 - -0.49647 0.519007 0.296436 - -0.498202 0.548898 0.296796 - -0.497778 0.65488 0.296474 - -0.487954 0.703188 0.293986 - -0.490977 0.91257 0.29429 - -0.490094 0.970663 0.293956 - -0.478999 0.979734 0.291239 - -0.485512 1.10026 0.292575 - -0.492889 1.26294 0.294034 - -0.480228 1.27868 0.290923 - -0.0247794 0.0826043 0.182632 - -0.0210603 0.0791803 0.181734 - -0.017626 0.0755893 0.180907 - -0.0162626 0.0787333 0.180569 - -0.0141259 0.0828892 0.18004 --0.00793016 0.115981 0.178466 --0.00707512 0.11096 0.178268 - -0.0066047 0.110946 0.178154 - 0.0012556 0.0902639 0.176285 - 0.0109448 0.112966 0.173882 - 0.0166469 0.13729 0.172445 - 0.0399757 0.184979 0.166674 - 0.049728 0.194513 0.164283 - 0.0519763 0.195871 0.163734 - 0.0503458 0.165746 0.164192 - 0.0372806 0.112976 0.167478 - 0.556921 0.739343 0.0398262 - 0.812985 0.891593 -0.022755 - 0.379453 -0.41391 0.0895641 - 1.29614 -1.62756 -0.120939 - 1.30223 -1.69454 -0.122216 - 0.605339 -0.92789 0.038134 - 0.601391 -0.930634 0.0390571 - 0.204158 -0.358268 0.13018 - 0.16021 -0.308232 0.140289 - 0.153666 -0.299387 0.141791 - 0.0253376 -0.0804178 0.171159 - 0.0247712 -0.0871807 0.171305 - 0.0232842 -0.0877808 0.171651 - 0.019464 -0.103838 0.172572 - 0.0100854 -0.114252 0.174772 - 0.00373509 -0.100087 0.176219 --0.00112648 -0.0895917 0.177327 --0.00341241 -0.0797578 0.177838 --0.00597356 -0.075915 0.178425 --0.00908245 -0.105999 0.179209 --0.00999248 -0.107998 0.179425 - -0.0104165 -0.103995 0.179515 - -0.0148665 -0.0737924 0.180487 - -0.0170841 -0.0886555 0.181033 - -0.0316685 -0.102494 0.18445 - -0.032104 -0.102394 0.184551 - -0.032539 -0.102291 0.184652 - -0.0348266 -0.0986196 0.185176 - -0.149569 -0.423172 0.212503 - -0.175547 -0.401215 0.218494 - -0.178951 -0.399711 0.219282 - -0.21347 -0.410601 0.227325 - -0.217853 -0.41053 0.228343 - -0.284914 -0.411033 0.243926 - -0.298167 -0.407528 0.246998 - -0.327344 -0.409849 0.253782 - -0.367851 -0.404631 0.263183 - -0.446962 -0.411107 0.281578 - -0.478458 -0.41075 0.288896 - -0.510507 -0.353063 0.296224 - -0.513821 -0.339017 0.296965 - -0.50887 -0.30762 0.29575 - -0.50981 -0.275572 0.295903 - -0.506064 -0.195298 0.294868 - -0.505909 -0.117279 0.294671 - -0.509736 -0.10878 0.295543 - -0.498253 -0.079104 0.292814 - -0.505746 -0.0599264 0.294516 - -0.514708 -0.0587151 0.296596 - -0.254931 -0.00421493 0.236124 - -0.265679 0.00133863 0.23861 - -0.507412 0.0540989 0.294669 - -0.511519 0.0613762 0.295608 - -0.504828 0.122461 0.293928 - -0.507042 0.219848 0.294242 - -0.505157 0.224296 0.293795 - -0.513146 0.269575 0.295559 - -0.511698 0.274545 0.295212 - -0.503775 0.34593 0.293224 - -0.501882 0.377909 0.292719 - -0.507494 0.414463 0.293948 - -0.502557 0.480838 0.292664 - -0.503098 0.52986 0.292689 - -0.502597 0.57778 0.292475 - -0.499596 0.600177 0.291731 - -0.495948 0.645564 0.290791 - -0.495901 0.694257 0.29068 - -0.485789 1.12559 0.287444 - -0.484963 1.27282 0.28695 - -0.0335376 0.0938212 0.184481 - -0.0275426 0.081942 0.183113 - -0.0268454 0.0821002 0.18295 - -0.0197837 0.0803145 0.181313 - -0.0140132 0.0818713 0.179969 --0.00587555 0.105932 0.178029 --0.00400532 0.0858116 0.177636 --0.00342097 0.0837643 0.177504 --0.00286435 0.0776981 0.177387 - 0.00219593 0.0942316 0.176177 - 0.00339132 0.097095 0.175894 - 0.0039397 0.0980263 0.175764 - 0.0109762 0.116101 0.174092 - 0.0186963 0.139003 0.172252 - 0.0418216 0.183562 0.166787 - 0.0509203 0.202691 0.164634 - 0.0539033 0.194359 0.163958 - 0.0547288 0.194072 0.163766 - 0.0495466 0.159864 0.165041 - 0.029623 0.0860699 0.169821 - 0.0462716 0.111085 0.165902 - 0.0384654 0.0915767 0.167756 - 0.704185 1.21836 0.0107601 - 0.702281 1.20318 0.0112338 - 0.459626 0.700156 0.0686483 - 0.500318 0.733136 0.0591255 - 0.598635 0.743374 0.0362602 - 0.60873 0.742454 0.0339166 - 0.616333 0.744976 0.0321448 - 0.67861 0.743719 0.0176772 - 0.716127 0.777443 0.00889072 - 0.381584 -0.400512 0.0933672 - 1.33791 -1.5746 -0.115843 - 1.28901 -1.62874 -0.104912 - 0.261771 -0.431654 0.119943 - 0.212265 -0.366666 0.130765 - 0.204071 -0.360076 0.132565 - 0.158409 -0.309739 0.142566 - 0.0477346 -0.109528 0.166646 - 0.0278349 -0.084987 0.170999 - 0.0263814 -0.0856332 0.171322 - 0.0260163 -0.0857906 0.171403 - 0.026023 -0.0879523 0.171406 - 0.0264194 -0.115426 0.171374 - 0.017179 -0.100476 0.173388 - 0.0117125 -0.0905396 0.174578 - 0.0100795 -0.0868195 0.174931 --0.00552039 -0.0839225 0.178377 - -0.0152486 -0.0847615 0.180532 - -0.0165021 -0.0866632 0.180813 - -0.0199675 -0.0792132 0.181565 - -0.0265181 -0.112583 0.183083 - -0.0262116 -0.10757 0.183004 - -0.0245712 -0.0946717 0.182615 - -0.027193 -0.0890795 0.183184 - -0.0300075 -0.0843073 0.183797 - -0.0303665 -0.0842128 0.183876 - -0.149538 -0.429485 0.210954 - -0.158594 -0.398527 0.212894 - -0.177229 -0.400467 0.217022 - -0.181029 -0.399862 0.217861 - -0.191499 -0.404895 0.220188 - -0.206067 -0.399907 0.223402 - -0.225216 -0.403133 0.227646 - -0.263778 -0.40519 0.236183 - -0.342696 -0.414113 0.253664 - -0.393078 -0.40686 0.264798 - -0.394478 -0.401272 0.265096 - -0.398188 -0.394662 0.265904 - -0.429175 -0.407881 0.272788 - -0.445112 -0.412386 0.276323 - -0.446866 -0.410432 0.276707 - -0.449334 -0.409143 0.277251 - -0.507188 -0.420076 0.290075 - -0.510065 -0.286936 0.290439 - -0.51464 -0.272008 0.291421 - -0.50284 -0.251734 0.288768 - -0.515167 -0.206394 0.291403 - -0.510998 -0.186711 0.29044 - -0.504282 -0.166861 0.288914 - -0.512947 -0.133077 0.290762 - -0.510509 -0.113474 0.290182 - -0.504072 -0.0958779 0.288722 - -0.504137 -0.0708881 0.288685 - -0.513281 -0.0516223 0.290669 - -0.511955 -0.0446852 0.290361 - -0.264728 0.00933389 0.235544 - -0.484018 0.0237187 0.284039 - -0.51052 0.0817189 0.289785 - -0.509806 0.0861972 0.289618 - -0.509435 0.0884339 0.289531 - -0.504713 0.108275 0.288445 - -0.508967 0.144778 0.289312 - -0.507209 0.238304 0.288731 - -0.510563 0.25649 0.289436 - -0.504498 0.293368 0.288019 - -0.504505 0.299308 0.288008 - -0.509517 0.336475 0.289041 - -0.504055 0.355411 0.287794 - -0.506578 0.377487 0.288307 - -0.503172 0.388757 0.28753 - -0.50583 0.401542 0.288092 - -0.506188 0.462957 0.288045 - -0.502227 0.467381 0.28716 - -0.508798 0.47777 0.288593 - -0.500352 0.540103 0.286596 - -0.496168 0.616638 0.285513 - -0.496708 0.634112 0.285597 - -0.490836 0.711903 0.284138 - -0.490796 0.725276 0.284102 - -0.493917 0.954782 0.284323 - -0.475804 1.27984 0.279649 - -0.0298372 0.0854013 0.183411 - -0.0234405 0.0776241 0.182012 - -0.0218247 0.0850084 0.181639 - -0.0198414 0.076211 0.181218 - -0.0175642 0.0765112 0.180714 - -0.0151178 0.0747468 0.180176 --0.00395659 0.091848 0.177671 - 0.00216329 0.0902639 0.17632 - 0.00254775 0.0902127 0.176235 - 0.011633 0.117085 0.17417 - 0.0142472 0.122686 0.17358 - 0.0495003 0.195998 0.165629 - 0.0523199 0.187722 0.165022 - 0.0473016 0.150264 0.166209 - 0.0449989 0.140453 0.166739 - 0.0445107 0.137424 0.166853 - 0.0354323 0.102284 0.168934 - 0.0289646 0.0844288 0.170402 - 0.029324 0.0842579 0.170323 - 0.0296826 0.0840853 0.170244 - 0.0410529 0.101762 0.167691 - 0.0414861 0.101537 0.167596 - 0.681078 1.22318 0.0237691 - 0.698913 1.22988 0.0198088 - 0.434382 0.692114 0.0794461 - 0.525442 0.739149 0.0591997 - 0.528587 0.736752 0.0585088 - 0.581752 0.733374 0.0467514 - 0.629755 0.745348 0.0361047 - 0.676669 0.73937 0.0257358 - 0.679814 0.736297 0.0250462 - 0.38358 -0.40122 0.0972235 - 0.388455 -0.424322 0.0962454 - 0.782744 -0.899048 0.0142858 - 1.31057 -1.62246 -0.0952526 - 0.55536 -0.839378 0.061989 - 0.162055 -0.314989 0.14364 - 0.0415091 -0.099607 0.168554 - 0.0309312 -0.0848722 0.170749 - 0.022789 -0.0776291 0.172447 - 0.0273246 -0.10687 0.171552 - 0.0269269 -0.115426 0.171653 - 0.0244971 -0.11826 0.17217 - 0.014818 -0.0981228 0.174165 - 0.00986161 -0.0931064 0.175197 - 0.0118809 -0.119177 0.174826 - 0.00385755 -0.0911138 0.176456 - 0.00151939 -0.091416 0.176948 - 0.00027907 -0.0835072 0.177193 --0.00107181 -0.0806326 0.177471 - -0.0147619 -0.0837643 0.180357 - -0.0260079 -0.100437 0.182757 - -0.0727981 -0.214164 0.19283 - -0.0996618 -0.29463 0.198645 - -0.119434 -0.353256 0.202923 - -0.152715 -0.398624 0.210016 - -0.157849 -0.401997 0.211103 - -0.160921 -0.399718 0.211744 - -0.252447 -0.410176 0.231016 - -0.337541 -0.410957 0.248915 - -0.370874 -0.410689 0.255926 - -0.395845 -0.412904 0.261182 - -0.482032 -0.412697 0.279309 - -0.501721 -0.426075 0.283478 - -0.506148 -0.396731 0.284349 - -0.511628 -0.287424 0.285278 - -0.512851 -0.285178 0.285531 - -0.508451 -0.226994 0.284486 - -0.506819 -0.157686 0.284001 - -0.507181 -0.126639 0.284014 - -0.505365 -0.086846 0.283551 - -0.509678 -0.0784278 0.284441 - -0.509124 -0.051125 0.284268 - -0.510268 -0.0377192 0.284482 - -0.498254 -0.0258568 0.281931 - -0.496406 -0.0235789 0.281537 - -0.435054 -0.0148996 0.268615 - -0.295147 0.0117158 0.239135 - -0.508335 0.0495398 0.283897 - -0.513108 0.150642 0.284694 - -0.507664 0.168539 0.283512 - -0.50694 0.170762 0.283356 - -0.511179 0.179724 0.284229 - -0.515559 0.196653 0.285115 - -0.507644 0.211611 0.28342 - -0.502692 0.233141 0.282335 - -0.499921 0.270156 0.281676 - -0.508572 0.295371 0.283444 - -0.507265 0.377487 0.283002 - -0.506403 0.416056 0.282741 - -0.510298 0.462072 0.283466 - -0.499714 0.476705 0.28121 - -0.503507 0.603243 0.28175 - -0.496462 0.63865 0.280196 - -0.496814 0.674797 0.280196 - -0.491348 0.890719 0.278605 - -0.489095 0.985677 0.277937 - -0.482348 1.05107 0.276384 - -0.491387 1.13568 0.278112 - -0.488761 1.18569 0.277458 - -0.485916 1.19337 0.276844 - -0.488509 1.21496 0.277345 - -0.450234 1.27572 0.26917 - -0.0398297 0.109469 0.185235 - -0.0250087 0.0823257 0.182173 - -0.0239322 0.0805046 0.18195 - -0.0235883 0.0805719 0.181878 - -0.0232442 0.0806376 0.181805 - -0.0228998 0.0807018 0.181733 - -0.0152743 0.0777079 0.180135 - -0.0126094 0.103923 0.179521 --0.00724233 0.10699 0.178386 --0.00415363 0.115907 0.177718 --0.00330793 0.0828182 0.177608 --0.00154755 0.0786632 0.177246 - 0.0147553 0.128789 0.173714 - 0.0276238 0.166919 0.17093 - 0.0354897 0.177336 0.169254 - 0.0491679 0.181609 0.166369 - 0.0350371 0.103791 0.1695 - 0.0299661 0.0875003 0.1706 - 0.0364624 0.0965429 0.169215 - 0.0450953 0.110037 0.167371 - 0.695763 1.27106 0.0281451 - 0.703614 1.27225 0.0264914 - 0.565913 0.744052 0.0565333 - 0.569085 0.741482 0.0558712 - 0.607417 0.736374 0.0478196 - 0.622033 0.740655 0.0447366 - 0.63612 0.743982 0.0417669 - 0.654024 0.738258 0.038013 - 0.375573 -0.402129 0.103149 - 0.396699 -0.435524 0.0990071 - 0.784371 -0.875163 0.0226475 - 0.776509 -0.905318 0.0242758 - 1.35235 -1.7935 -0.0886672 - 1.34466 -1.79953 -0.0871233 - 0.277608 -0.453531 0.122777 - 0.191279 -0.349137 0.139768 - 0.0304553 -0.0886424 0.171286 - 0.00879135 -0.0873023 0.1756 - 0.00120077 -0.0844604 0.177107 --0.00344477 -0.0798542 0.178023 --0.00736041 -0.102996 0.178851 - -0.0082432 -0.107 0.179035 --0.00915893 -0.106995 0.179218 - -0.0125198 -0.0908918 0.179854 - -0.0133251 -0.0848375 0.180003 - -0.0141218 -0.0807727 0.180153 - -0.0185949 -0.100439 0.181085 - -0.0210315 -0.106193 0.181582 - -0.0193733 -0.0862473 0.181211 - -0.0193512 -0.078174 0.18119 - -0.0260137 -0.105441 0.182573 - -0.0250998 -0.0974833 0.182375 - -0.0293023 -0.0801561 0.183177 - -0.0299876 -0.079965 0.183313 - -0.0436504 -0.12382 0.186125 - -0.081717 -0.237421 0.193943 - -0.149214 -0.394566 0.207714 - -0.151581 -0.39581 0.208189 - -0.157354 -0.395727 0.209339 - -0.166679 -0.399498 0.211205 - -0.172554 -0.39919 0.212375 - -0.174644 -0.399375 0.212792 - -0.187585 -0.4056 0.215384 - -0.190228 -0.402172 0.215903 - -0.203523 -0.407907 0.218564 - -0.279348 -0.405654 0.23367 - -0.295371 -0.410101 0.236873 - -0.506802 -0.396731 0.27898 - -0.504732 -0.388021 0.27855 - -0.507335 -0.362569 0.279017 - -0.508883 -0.360344 0.27932 - -0.511074 -0.335731 0.279707 - -0.511185 -0.316934 0.279691 - -0.510101 -0.257534 0.279354 - -0.516546 -0.244047 0.28061 - -0.509276 -0.219106 0.279111 - -0.51021 -0.216874 0.279292 - -0.511134 -0.214638 0.279472 - -0.513595 -0.19484 0.279922 - -0.507477 -0.179885 0.278672 - -0.499102 -0.164673 0.276972 - -0.508901 -0.163036 0.278922 - -0.509595 -0.160807 0.279055 - -0.506891 -0.138248 0.278471 - -0.505055 -0.037279 0.277899 - -0.506335 -0.0329211 0.278145 - -0.268955 0.0083164 0.230755 - -0.474485 0.023183 0.271683 - -0.502665 0.0289961 0.277287 - -0.509038 0.0585574 0.278497 - -0.502204 0.0734036 0.277105 - -0.502041 0.125923 0.276965 - -0.500534 0.139596 0.276637 - -0.516215 0.15629 0.279728 - -0.512233 0.172352 0.278902 - -0.506476 0.210845 0.277676 - -0.508234 0.219453 0.278009 - -0.511195 0.264565 0.278507 - -0.509184 0.274896 0.278085 - -0.507143 0.276644 0.277675 - -0.507674 0.279824 0.277774 - -0.508398 0.334829 0.277806 - -0.508092 0.398703 0.277615 - -0.506382 0.400922 0.277269 - -0.503999 0.524046 0.276544 - -0.502981 0.541567 0.276305 - -0.502656 0.545967 0.276231 - -0.488606 0.639004 0.273242 - -0.493937 0.68236 0.274216 - -0.491927 0.698586 0.273782 - -0.493196 0.713547 0.274004 - -0.49347 0.720644 0.274044 - -0.49084 0.751341 0.273458 - -0.493399 1.25735 0.272936 - -0.0374793 0.0933563 0.184453 - -0.0217388 0.0848915 0.181333 - -0.0213754 0.0849508 0.181261 - -0.0182356 0.0753131 0.180655 - -0.0139557 0.0747729 0.179803 --0.00171838 0.0837361 0.177346 - 0.0068915 0.0998131 0.175597 - 0.0367841 0.177137 0.169482 - 0.0464813 0.112965 0.167681 - 0.0394202 0.0942003 0.169126 - 0.648809 1.21991 0.0453902 - 0.706649 1.26127 0.0337794 - 0.649521 0.905458 0.0458897 - 0.596562 0.740714 0.0567794 - 0.638539 0.738116 0.0484193 - 0.377443 -0.395857 0.106953 - 0.391517 -0.436181 0.104383 - 1.20553 -1.68556 -0.0464431 - 1.16464 -1.65891 -0.0387923 - 0.262658 -0.436595 0.128662 - 0.204689 -0.356655 0.139421 - 0.104681 -0.220061 0.157986 - 0.0316482 -0.0861282 0.171473 - 0.025312 -0.0823974 0.17266 - 0.026464 -0.110656 0.1725 - 0.0262812 -0.119071 0.172552 - 0.0145394 -0.0912241 0.174707 - 0.0081409 -0.0854848 0.175901 - 0.00777423 -0.0855545 0.17597 --0.00121299 -0.0807265 0.177654 --0.00431357 -0.10194 0.178281 --0.00591116 -0.110984 0.178601 - -0.0116217 -0.110929 0.179676 - -0.0181874 -0.0964156 0.180884 - -0.0184715 -0.0853043 0.180915 - -0.0353088 -0.0959844 0.184109 - -0.142165 -0.402345 0.204865 - -0.143569 -0.400799 0.205127 - -0.186314 -0.402866 0.213184 - -0.20917 -0.406156 0.217497 - -0.215348 -0.409683 0.218669 - -0.227237 -0.406638 0.220902 - -0.23245 -0.403678 0.221878 - -0.262945 -0.407169 0.227631 - -0.293203 -0.410559 0.233339 - -0.294961 -0.409287 0.233668 - -0.356708 -0.408039 0.245299 - -0.375723 -0.408179 0.248882 - -0.382964 -0.405424 0.250241 - -0.389515 -0.401828 0.251467 - -0.455282 -0.413174 0.263882 - -0.464978 -0.411148 0.265704 - -0.503758 -0.386805 0.272961 - -0.507591 -0.349102 0.273607 - -0.507137 -0.339084 0.273501 - -0.508384 -0.33354 0.273725 - -0.508439 -0.314831 0.273697 - -0.509785 -0.312605 0.273946 - -0.512551 -0.275572 0.274392 - -0.505593 -0.26329 0.273056 - -0.506718 -0.261077 0.273263 - -0.507185 -0.255736 0.27334 - -0.507984 -0.200106 0.273378 - -0.510671 -0.198606 0.273881 - -0.511615 -0.178649 0.274018 - -0.504378 -0.142139 0.27258 - -0.510817 -0.0968069 0.273701 - -0.50898 -0.0781249 0.273317 - -0.508171 -0.0621489 0.273132 - -0.508433 -0.0599264 0.273177 - -0.504809 -0.034999 0.272443 - -0.498351 -0.0279836 0.271212 - -0.262297 -0.00094192 0.226682 - -0.511313 0.123398 0.273346 - -0.512353 0.135566 0.273518 - -0.506871 0.197897 0.272358 - -0.506069 0.202692 0.272197 - -0.506132 0.207867 0.272198 - -0.50977 0.266338 0.272765 - -0.507169 0.273474 0.27226 - -0.50739 0.279342 0.27229 - -0.514763 0.310427 0.273616 - -0.511748 0.311636 0.273045 - -0.505321 0.375105 0.271705 - -0.503709 0.37731 0.271397 - -0.503719 0.45892 0.271233 - -0.503529 0.513906 0.271085 - -0.504351 0.528414 0.27121 - -0.487949 0.910313 0.267343 - -0.484817 0.933486 0.266706 - -0.485485 1.05561 0.266583 - -0.490935 1.09265 0.267534 - -0.484535 1.26535 0.265977 - -0.445927 1.26063 0.258713 - -0.0371967 0.099609 0.184067 - -0.034702 0.102408 0.183591 - -0.0258763 0.0799116 0.181974 - -0.025317 0.0790155 0.18187 - -0.0244306 0.0781906 0.181705 - -0.0198582 0.0800661 0.18084 --0.00682237 0.106995 0.178329 --0.00376752 0.102917 0.177761 - 0.00387737 0.084164 0.176359 - 0.0294179 0.163666 0.171385 - 0.040357 0.182524 0.169286 - 0.0445705 0.188602 0.16848 - 0.0442901 0.167815 0.168575 - 0.0424886 0.131376 0.168988 - 0.0375247 0.0965429 0.169995 - 0.41598 0.696124 0.0974694 - 0.714857 1.00187 0.0405357 - 0.717393 0.996244 0.0400694 - 0.711659 0.9794 0.041184 - 0.600684 0.750339 0.0625589 - 0.678608 0.741701 0.047895 - 0.693102 0.744238 0.0451589 - 1.20083 -1.66005 -0.03266 - 0.239291 -0.401308 0.135638 - 0.148867 -0.301895 0.151503 - 0.0533196 -0.122383 0.168116 - 0.0314085 -0.0864747 0.171937 - 0.0252984 -0.100692 0.173051 - 0.0251695 -0.101787 0.173077 - 0.0176246 -0.101899 0.174417 - 0.0109738 -0.111464 0.175619 - 0.0100211 -0.108582 0.175782 - 0.0067436 -0.0989754 0.176345 --0.00142807 -0.0767669 0.177752 --0.00382559 -0.0919315 0.178209 --0.00470578 -0.103966 0.178389 --0.00551505 -0.108985 0.178543 - -0.006963 -0.0979992 0.178778 - -0.0182019 -0.078223 0.180735 - -0.161297 -0.401581 0.206819 - -0.173882 -0.402878 0.209057 - -0.176381 -0.403976 0.209504 - -0.178116 -0.403223 0.20981 - -0.186233 -0.402866 0.211252 - -0.246337 -0.403549 0.221933 - -0.31206 -0.410273 0.233625 - -0.383932 -0.406152 0.246388 - -0.389136 -0.401109 0.247302 - -0.390856 -0.399413 0.247605 - -0.406063 -0.408062 0.250324 - -0.413722 -0.401627 0.251672 - -0.507913 -0.411205 0.268428 - -0.511626 -0.403276 0.269072 - -0.505154 -0.383994 0.267883 - -0.510063 -0.377341 0.268741 - -0.515854 -0.344633 0.269704 - -0.499031 -0.326968 0.266679 - -0.508131 -0.314306 0.26827 - -0.508119 -0.261534 0.268161 - -0.50736 -0.231029 0.267964 - -0.509328 -0.226588 0.268305 - -0.506535 -0.194225 0.267743 - -0.510031 -0.190492 0.268356 - -0.50428 -0.144343 0.267241 - -0.507483 -0.0846303 0.267688 - -0.508192 -0.080194 0.267805 - -0.505492 -0.0639938 0.267293 - -0.506518 -0.0551536 0.267457 - -0.507731 -0.0530447 0.267668 - -0.505811 -0.0416987 0.267304 - -0.506455 -0.0328564 0.267401 - -0.506592 -0.0306442 0.26742 - -0.267239 -0.00441564 0.224837 - -0.508902 0.0404626 0.267686 - -0.517972 0.0594688 0.26926 - -0.50292 0.0688698 0.266566 - -0.517617 0.101123 0.269112 - -0.517179 0.103384 0.269029 - -0.512001 0.166932 0.26798 - -0.505674 0.179622 0.26683 - -0.505281 0.189479 0.26674 - -0.507483 0.221276 0.267067 - -0.500335 0.280832 0.265676 - -0.499875 0.391308 0.26537 - -0.512101 0.426877 0.26747 - -0.507882 0.450287 0.266673 - -0.501473 0.480965 0.265472 - -0.503621 0.500216 0.265814 - -0.503018 0.521886 0.265663 - -0.503719 0.545967 0.265739 - -0.497609 0.594045 0.264555 - -0.498747 0.606087 0.264733 - -0.496799 0.812073 0.263968 - -0.49189 0.926568 0.262864 - -0.489921 1.1152 0.262131 - -0.389873 1.14607 0.24429 - -0.0334417 0.102643 0.183076 - -0.0158601 0.0825514 0.179993 - -0.0143549 0.081693 0.179727 - -0.0128818 0.0808066 0.179467 - -0.0043684 0.113959 0.177887 - 0.0184386 0.134464 0.173793 - 0.0244365 0.151589 0.172692 - 0.0257153 0.154378 0.172459 - 0.038339 0.175968 0.170172 - 0.0406846 0.126931 0.169855 - 0.0363556 0.112548 0.170653 - 0.0334278 0.0986452 0.171202 - 0.035558 0.0955141 0.17083 - 0.632957 1.19647 0.0624419 - 0.714811 1.26906 0.0477498 - 0.41671 0.695274 0.101885 - 0.657964 0.991415 0.0584148 - 0.71878 0.986607 0.0476183 - 0.634978 0.756332 0.0629767 - 0.674624 0.748504 0.055948 - 0.684893 0.740095 0.0541403 - 0.38945 -0.42391 0.113334 - 0.28995 -0.430273 0.129939 - 0.200164 -0.360371 0.144771 - 0.183334 -0.344775 0.147546 - 0.0295677 -0.0831593 0.172658 - 0.0245191 -0.0831116 0.1735 - 0.01585 -0.0962812 0.174972 - 0.0107169 -0.094328 0.175824 - 0.00438371 -0.0902806 0.176872 --0.00599655 -0.110996 0.178645 - -0.0128797 -0.0917984 0.179754 - -0.0188979 -0.106303 0.180787 - -0.0246079 -0.094302 0.181715 - -0.0246187 -0.0861428 0.1817 - -0.0304345 -0.0991642 0.182696 - -0.030497 -0.0939978 0.182696 - -0.045861 -0.126989 0.185325 - -0.143717 -0.385781 0.202169 - -0.152437 -0.388908 0.203629 - -0.162038 -0.3937 0.20524 - -0.176049 -0.39863 0.207587 - -0.218691 -0.40335 0.214707 - -0.27504 -0.40639 0.22411 - -0.281861 -0.408959 0.225253 - -0.325751 -0.405938 0.232566 - -0.34148 -0.411029 0.2352 - -0.407751 -0.409481 0.246248 - -0.416524 -0.407627 0.247707 - -0.435297 -0.415283 0.250853 - -0.508811 -0.355821 0.262992 - -0.507521 -0.329137 0.262723 - -0.510095 -0.306076 0.263106 - -0.50892 -0.275905 0.262848 - -0.508382 -0.239362 0.262685 - -0.510022 -0.21348 0.262906 - -0.510769 -0.198245 0.262999 - -0.504753 -0.144343 0.261887 - -0.497251 -0.130504 0.260608 - -0.511339 -0.127121 0.26295 - -0.505646 -0.0865088 0.261918 - -0.510153 -0.06227 0.262621 - -0.508432 -0.0508266 0.262311 - -0.442629 -0.0151046 0.251265 - -0.266316 0.00248615 0.221827 - -0.504728 0.0735478 0.261441 - -0.504555 0.0984422 0.261361 - -0.508096 0.115352 0.261918 - -0.503101 0.163835 0.260986 - -0.497933 0.166946 0.260118 - -0.49721 0.169117 0.259993 - -0.509224 0.237881 0.261857 - -0.51076 0.274896 0.262038 - -0.508895 0.282528 0.261712 - -0.505954 0.283767 0.261219 - -0.504831 0.297784 0.261003 - -0.506004 0.307481 0.261179 - -0.502644 0.345872 0.260541 - -0.5124 0.390181 0.262078 - -0.510382 0.44033 0.26164 - -0.507655 0.490797 0.261083 - -0.498367 0.503172 0.259509 - -0.503651 0.517535 0.260361 - -0.503451 0.535717 0.260291 - -0.501615 0.572513 0.25991 - -0.495201 0.611972 0.25876 - -0.497894 0.626447 0.25918 - -0.494801 0.669167 0.258578 - -0.4899 0.713224 0.257671 - -0.485186 0.761933 0.256786 - -0.488189 0.82924 0.25715 - -0.487867 0.927819 0.256897 - -0.492418 0.988363 0.257533 - -0.48951 1.00431 0.257016 - -0.49142 1.09173 0.257157 - -0.490888 1.17155 0.256906 - -0.485986 1.21895 0.255993 - -0.0330755 0.0974626 0.182738 - -0.0248751 0.0840549 0.181398 - -0.0224652 0.0794549 0.181005 - -0.0197399 0.0779259 0.180554 - -0.015776 0.0734548 0.179902 - -0.0154688 0.0795307 0.179838 - -0.0133312 0.0787333 0.179484 - -0.0111333 0.0898993 0.179094 --0.00775563 0.102996 0.178505 - 0.00741661 0.0969128 0.175987 - 0.0245262 0.149633 0.173027 - 0.0394876 0.15605 0.170519 - 0.0370364 0.136919 0.170966 - 0.0464087 0.107118 0.169464 - 0.707104 1.27802 0.05691 - 0.469419 0.802813 0.0975105 - 0.416745 0.686606 0.10653 - 0.713525 0.968212 0.0564674 - 0.712963 0.861157 0.0567782 - 0.672308 0.744101 0.0637952 - 0.379065 -0.397563 0.119011 - 1.33946 -1.58278 -0.0287899 - 0.288809 -0.419486 0.133171 - 0.604233 -0.908869 0.0848307 - 0.167776 -0.332116 0.151923 - 0.15898 -0.322106 0.153278 - 0.0340095 -0.0890276 0.172351 - 0.0296857 -0.0833198 0.173015 - 0.0242804 -0.081244 0.173857 - 0.0235687 -0.0825828 0.173971 - 0.0213764 -0.0844211 0.174317 - 0.0237729 -0.103575 0.173981 - 0.0127741 -0.0960466 0.175686 - 0.0011473 -0.0806326 0.177473 --0.00562765 -0.104996 0.178582 --0.00937984 -0.10996 0.179179 - -0.0100679 -0.116943 0.179301 - -0.0131136 -0.0847329 0.179712 - -0.0159249 -0.0904944 0.180163 - -0.0187318 -0.0780182 0.180577 - -0.019068 -0.0779633 0.180629 - -0.0212915 -0.0826484 0.180987 - -0.0245892 -0.0962666 0.18153 - -0.0248391 -0.0931609 0.181563 - -0.025545 -0.0817497 0.18165 - -0.0323567 -0.0975393 0.182747 - -0.0331967 -0.0973068 0.182878 - -0.0325149 -0.0902254 0.182757 - -0.0384674 -0.104073 0.183716 - -0.192511 -0.398727 0.208404 - -0.212939 -0.405239 0.211612 - -0.225551 -0.399539 0.213573 - -0.241582 -0.407557 0.216097 - -0.278363 -0.411377 0.221857 - -0.280134 -0.410172 0.222131 - -0.291193 -0.407294 0.223855 - -0.296437 -0.403486 0.224667 - -0.306363 -0.406014 0.226225 - -0.386825 -0.405204 0.238807 - -0.389935 -0.404963 0.239293 - -0.392365 -0.403984 0.239671 - -0.40484 -0.409825 0.241634 - -0.412916 -0.407325 0.242892 - -0.513323 -0.426132 0.258633 - -0.506979 -0.364203 0.257515 - -0.509295 -0.359191 0.257867 - -0.505065 -0.349611 0.257187 - -0.508982 -0.332992 0.257765 - -0.50449 -0.284746 0.256965 - -0.510195 -0.276381 0.257841 - -0.50672 -0.14241 0.257026 - -0.50733 -0.140199 0.257117 - -0.512425 -0.106132 0.257845 - -0.507611 -0.0890601 0.257057 - -0.503693 -0.061422 0.256388 - -0.509592 -0.0531485 0.257294 - -0.513575 -0.0422732 0.257895 - -0.514738 -0.0401111 0.258073 - -0.268307 0.00019254 0.219451 - -0.505468 0.0312574 0.256478 - -0.512167 0.0474036 0.257494 - -0.512258 0.0564383 0.257489 - -0.511029 0.0585574 0.257293 - -0.506697 0.131316 0.256468 - -0.505351 0.147557 0.256225 - -0.507256 0.194962 0.256427 - -0.510011 0.268564 0.256709 - -0.50929 0.282528 0.256568 - -0.504408 0.430949 0.255504 - -0.50622 0.444106 0.25576 - -0.504492 0.487321 0.255403 - -0.502217 0.506726 0.255008 - -0.503856 0.521886 0.255233 - -0.498865 0.544472 0.254407 - -0.507369 0.563671 0.255698 - -0.504809 0.59645 0.255231 - -0.499649 0.600827 0.254415 - -0.500451 0.634898 0.254472 - -0.492621 0.758514 0.252997 - -0.490308 0.769527 0.252613 - -0.495727 0.922651 0.253151 - -0.488141 0.968341 0.251872 - -0.489103 1.0732 0.25181 - -0.490407 1.14149 0.251876 - -0.028133 0.0914185 0.181704 - -0.0163262 0.0844179 0.179872 - -0.0161851 0.0864477 0.179846 - -0.0140805 0.076618 0.179536 - -0.0127517 0.085768 0.17931 - -0.0111069 0.0898799 0.179045 --0.00349509 0.113959 0.177805 - 0.00058101 0.0856993 0.177225 - 0.0010472 0.0826461 0.177158 - 0.00102302 0.0786306 0.17717 - 0.00376479 0.0873823 0.176724 - 0.0131331 0.115295 0.175202 - 0.017122 0.131844 0.174545 - 0.0227214 0.145007 0.173642 - 0.0366043 0.174621 0.171411 - 0.0426823 0.185421 0.170439 - 0.0369288 0.141311 0.171428 - 0.0360345 0.134256 0.171582 - 0.0341077 0.104177 0.171944 - 0.0317671 0.0900132 0.172339 - 0.0345332 0.0942467 0.171898 - 0.0420591 0.100629 0.170708 - 0.0358657 0.0858824 0.171706 - 0.692395 1.27468 0.0666226 - 0.703269 1.23044 0.0650113 - 0.425314 0.726559 0.109502 - 0.406901 0.688754 0.112458 - 0.420299 0.683879 0.110373 - 0.717752 0.99865 0.0632155 - 0.722239 0.870311 0.0627736 - 0.726302 0.852281 0.0621747 - 0.723032 0.819151 0.0627531 - 0.712752 0.773 0.0644544 - 0.707913 0.761116 0.0652351 - 0.711189 0.757953 0.0647293 - 0.378705 -0.403112 0.123155 - 0.380382 -0.408419 0.122921 - 1.32199 -1.60124 -0.0119544 - 0.292564 -0.423559 0.135756 - 0.308956 -0.486113 0.133492 - 0.199523 -0.363926 0.149201 - 0.143047 -0.302597 0.157311 - 0.0225997 -0.0745815 0.174412 - 0.0178374 -0.0970469 0.175151 - 0.0128425 -0.092044 0.17587 - 0.012214 -0.0952311 0.175968 - 0.0114343 -0.0933455 0.176077 - 0.01137 -0.105545 0.176111 - -0.0175569 -0.0942833 0.180306 - -0.0258282 -0.0846693 0.181493 - -0.026425 -0.0855534 0.181582 - -0.0330797 -0.0920267 0.182565 - -0.12581 -0.355957 0.196619 - -0.129206 -0.35583 0.197113 - -0.138635 -0.372608 0.198522 - -0.152421 -0.389843 0.200567 - -0.174035 -0.399375 0.203738 - -0.18761 -0.402069 0.205722 - -0.271003 -0.407912 0.217893 - -0.297039 -0.408007 0.221689 - -0.328309 -0.405303 0.226243 - -0.334303 -0.40554 0.227117 - -0.383888 -0.405424 0.234347 - -0.388362 -0.406654 0.235001 - -0.393537 -0.408573 0.23576 - -0.419122 -0.409728 0.239492 - -0.443673 -0.408316 0.243069 - -0.510338 -0.387017 0.252746 - -0.493041 -0.367013 0.250183 - -0.508947 -0.36537 0.252499 - -0.501219 -0.343444 0.251328 - -0.502526 -0.337947 0.251508 - -0.507208 -0.325298 0.252165 - -0.507098 -0.294843 0.252087 - -0.508292 -0.286714 0.252245 - -0.515259 -0.26744 0.253222 - -0.50526 -0.218945 0.251666 - -0.506225 -0.20896 0.251786 - -0.504294 -0.200476 0.251488 - -0.503871 -0.187695 0.2514 - -0.515576 -0.184466 0.2531 - -0.507039 -0.178886 0.251844 - -0.508178 -0.169389 0.251991 - -0.503514 -0.136674 0.251245 - -0.499658 -0.0786368 0.250565 - -0.505561 -0.03493 0.251338 - -0.500771 -0.0324037 0.250634 - -0.491268 -0.0253407 0.249234 - -0.269113 0.00947639 0.216774 - -0.504971 0.0622758 0.251055 - -0.506378 0.0669356 0.251251 - -0.505782 0.0713451 0.251155 - -0.510224 0.0879237 0.251769 - -0.50984 0.0901458 0.251709 - -0.507833 0.119782 0.251356 - -0.501487 0.136877 0.250396 - -0.506955 0.150328 0.251167 - -0.511978 0.173948 0.251851 - -0.514194 0.179724 0.252163 - -0.505446 0.186577 0.250873 - -0.50853 0.195321 0.251305 - -0.511767 0.238728 0.251689 - -0.508271 0.250704 0.251156 - -0.506253 0.263563 0.250835 - -0.503585 0.27913 0.250415 - -0.506748 0.351485 0.25073 - -0.514604 0.39485 0.251788 - -0.508985 0.394024 0.25097 - -0.511177 0.399319 0.251279 - -0.511363 0.41035 0.251284 - -0.510715 0.443866 0.251121 - -0.503448 0.449169 0.250051 - -0.505787 0.467381 0.250355 - -0.502015 0.488817 0.249762 - -0.50023 0.513234 0.249453 - -0.503073 0.529887 0.249833 - -0.50216 0.552566 0.249654 - -0.500034 0.59034 0.249268 - -0.493666 0.620182 0.248279 - -0.491626 0.895493 0.247426 - -0.489735 0.920385 0.2471 - -0.486907 0.97583 0.246575 - -0.486957 1.09295 0.246346 - -0.491186 1.15651 0.246834 - -0.488616 1.25577 0.246258 - -0.0422276 0.10482 0.183501 - -0.0341906 0.0917024 0.182356 - -0.0248497 0.0808041 0.181016 - -0.006905 0.102996 0.178355 - 0.00230382 0.083571 0.177051 - 0.0035008 0.078404 0.176887 - 0.00789699 0.0969754 0.176209 - 0.0121158 0.109464 0.175568 - 0.0347912 0.134809 0.172211 - 0.036534 0.134256 0.171958 - 0.0360688 0.127044 0.17204 - 0.0362723 0.120627 0.172024 - 0.0362676 0.114243 0.172037 - 0.0306099 0.0939451 0.172903 - 0.0329851 0.0951307 0.172554 - 0.521466 1.01204 0.0994803 - 0.418455 0.685758 0.115159 - 0.797163 1.07597 0.0591543 - 0.799404 1.06923 0.0588411 - 0.804425 1.02853 0.0581913 - 0.799953 0.961079 0.0589797 - 0.803053 0.947875 0.0585543 - 0.832142 0.891593 0.0544269 - 0.837748 0.882009 0.0536289 - 1.39429 -1.51858 -0.0187546 - 1.38112 -1.53087 -0.0168466 - 0.772955 -0.914193 0.0688802 - 0.320492 -0.430236 0.132609 - 1.18395 -1.64118 0.0115732 - 0.288677 -0.421602 0.137141 - 0.250161 -0.41856 0.142643 - 0.204413 -0.361176 0.149069 - 0.0292157 -0.0837916 0.173564 - 0.0224122 -0.0821564 0.174534 - 0.0217806 -0.0876406 0.174635 - 0.02375 -0.104799 0.174388 - 0.023636 -0.107948 0.174411 - 0.0236894 -0.110007 0.174407 - 0.0205294 -0.103611 0.174846 - 0.0153417 -0.0915131 0.175564 - 0.00847444 -0.103989 0.176571 - 0.00499281 -0.0903296 0.177041 --0.00120634 -0.078856 0.177905 --0.00143562 -0.0808729 0.177941 --0.00296536 -0.116962 0.178233 --0.00507674 -0.105996 0.178513 - -0.0184333 -0.110277 0.180432 - -0.0170956 -0.0852559 0.18019 - -0.017726 -0.0770834 0.180263 - -0.0182141 -0.0780182 0.180335 - -0.027284 -0.116008 0.181709 - -0.0248385 -0.0859 0.181298 - -0.033001 -0.0951449 0.182484 - -0.131104 -0.361494 0.197052 - -0.157885 -0.394127 0.200948 - -0.2049 -0.407033 0.207698 - -0.209302 -0.407048 0.208327 - -0.211058 -0.406148 0.208576 - -0.242263 -0.404791 0.213036 - -0.27231 -0.402235 0.217328 - -0.275775 -0.399871 0.217819 - -0.292362 -0.408926 0.220209 - -0.336306 -0.411644 0.226499 - -0.339851 -0.408715 0.227 - -0.359427 -0.410302 0.229803 - -0.361196 -0.408739 0.230053 - -0.42165 -0.408599 0.238698 - -0.466543 -0.411148 0.245123 - -0.505945 -0.412156 0.25076 - -0.506951 -0.409319 0.250898 - -0.506595 -0.401776 0.250832 - -0.509721 -0.382986 0.251241 - -0.50423 -0.375381 0.25044 - -0.503994 -0.35181 0.250359 - -0.504223 -0.326417 0.250341 - -0.507184 -0.294843 0.2507 - -0.509311 -0.29313 0.251001 - -0.513068 -0.286448 0.251525 - -0.510146 -0.253516 0.25104 - -0.505778 -0.235031 0.250378 - -0.506315 -0.21155 0.250408 - -0.50581 -0.188395 0.250289 - -0.500415 -0.174043 0.249488 - -0.501163 -0.171862 0.249591 - -0.508414 -0.152375 0.250588 - -0.505886 -0.127879 0.250177 - -0.500127 -0.0279836 0.249152 - -0.497278 -0.0256503 0.24874 - -0.271238 -0.002144 0.216366 - -0.508418 0.0380899 0.250204 - -0.503594 0.0732594 0.249443 - -0.503582 0.0799902 0.249428 - -0.510058 0.237881 0.250035 - -0.509608 0.245831 0.249955 - -0.501727 0.28668 0.248745 - -0.508608 0.302543 0.249697 - -0.516502 0.325879 0.250779 - -0.503135 0.372128 0.248774 - -0.505022 0.394389 0.248999 - -0.503314 0.396584 0.24875 - -0.501353 0.483845 0.248293 - -0.504221 0.490911 0.248689 - -0.501947 0.547423 0.24825 - -0.49559 0.622532 0.247189 - -0.493868 0.731568 0.246722 - -0.490693 0.769527 0.246191 - -0.496542 0.817654 0.246931 - -0.494714 0.920007 0.246462 - -0.486095 0.974039 0.245121 - -0.49123 1.17063 0.245458 - -0.0526184 0.137134 0.184821 - -0.0401611 0.106543 0.183101 - -0.0340078 0.0990304 0.182236 - -0.0258928 0.0794914 0.181115 - -0.0258754 0.0856718 0.1811 - -0.0205212 0.0837192 0.180338 - -0.0177574 0.0851716 0.17994 - -0.0029951 0.111959 0.177775 - -0.0012011 0.0988823 0.177545 --0.00130852 0.0818646 0.177594 - 0.00122335 0.0866958 0.177223 - 0.00106189 0.0766717 0.177266 - 0.00787411 0.0990165 0.176247 - 0.0153991 0.12515 0.175118 - 0.0190082 0.135671 0.17458 - 0.0247108 0.151866 0.173732 - 0.0264341 0.153545 0.173482 - 0.0281888 0.155206 0.173228 - 0.0407305 0.181977 0.17138 - 0.033446 0.127944 0.172531 - 0.0304595 0.0875822 0.17304 - 0.683303 1.28081 0.0772666 - 0.843614 1.19076 0.0545226 - 0.909821 1.09151 0.0452549 - 0.931687 1.08836 0.0421343 - 0.962816 1.05745 0.0377451 - 0.975075 1.04309 0.0360209 -VERTICES 36674 73348 -1 0 -1 1 -1 2 -1 3 -1 4 -1 5 -1 6 -1 7 -1 8 -1 9 -1 10 -1 11 -1 12 -1 13 -1 14 -1 15 -1 16 -1 17 -1 18 -1 19 -1 20 -1 21 -1 22 -1 23 -1 24 -1 25 -1 26 -1 27 -1 28 -1 29 -1 30 -1 31 -1 32 -1 33 -1 34 -1 35 -1 36 -1 37 -1 38 -1 39 -1 40 -1 41 -1 42 -1 43 -1 44 -1 45 -1 46 -1 47 -1 48 -1 49 -1 50 -1 51 -1 52 -1 53 -1 54 -1 55 -1 56 -1 57 -1 58 -1 59 -1 60 -1 61 -1 62 -1 63 -1 64 -1 65 -1 66 -1 67 -1 68 -1 69 -1 70 -1 71 -1 72 -1 73 -1 74 -1 75 -1 76 -1 77 -1 78 -1 79 -1 80 -1 81 -1 82 -1 83 -1 84 -1 85 -1 86 -1 87 -1 88 -1 89 -1 90 -1 91 -1 92 -1 93 -1 94 -1 95 -1 96 -1 97 -1 98 -1 99 -1 100 -1 101 -1 102 -1 103 -1 104 -1 105 -1 106 -1 107 -1 108 -1 109 -1 110 -1 111 -1 112 -1 113 -1 114 -1 115 -1 116 -1 117 -1 118 -1 119 -1 120 -1 121 -1 122 -1 123 -1 124 -1 125 -1 126 -1 127 -1 128 -1 129 -1 130 -1 131 -1 132 -1 133 -1 134 -1 135 -1 136 -1 137 -1 138 -1 139 -1 140 -1 141 -1 142 -1 143 -1 144 -1 145 -1 146 -1 147 -1 148 -1 149 -1 150 -1 151 -1 152 -1 153 -1 154 -1 155 -1 156 -1 157 -1 158 -1 159 -1 160 -1 161 -1 162 -1 163 -1 164 -1 165 -1 166 -1 167 -1 168 -1 169 -1 170 -1 171 -1 172 -1 173 -1 174 -1 175 -1 176 -1 177 -1 178 -1 179 -1 180 -1 181 -1 182 -1 183 -1 184 -1 185 -1 186 -1 187 -1 188 -1 189 -1 190 -1 191 -1 192 -1 193 -1 194 -1 195 -1 196 -1 197 -1 198 -1 199 -1 200 -1 201 -1 202 -1 203 -1 204 -1 205 -1 206 -1 207 -1 208 -1 209 -1 210 -1 211 -1 212 -1 213 -1 214 -1 215 -1 216 -1 217 -1 218 -1 219 -1 220 -1 221 -1 222 -1 223 -1 224 -1 225 -1 226 -1 227 -1 228 -1 229 -1 230 -1 231 -1 232 -1 233 -1 234 -1 235 -1 236 -1 237 -1 238 -1 239 -1 240 -1 241 -1 242 -1 243 -1 244 -1 245 -1 246 -1 247 -1 248 -1 249 -1 250 -1 251 -1 252 -1 253 -1 254 -1 255 -1 256 -1 257 -1 258 -1 259 -1 260 -1 261 -1 262 -1 263 -1 264 -1 265 -1 266 -1 267 -1 268 -1 269 -1 270 -1 271 -1 272 -1 273 -1 274 -1 275 -1 276 -1 277 -1 278 -1 279 -1 280 -1 281 -1 282 -1 283 -1 284 -1 285 -1 286 -1 287 -1 288 -1 289 -1 290 -1 291 -1 292 -1 293 -1 294 -1 295 -1 296 -1 297 -1 298 -1 299 -1 300 -1 301 -1 302 -1 303 -1 304 -1 305 -1 306 -1 307 -1 308 -1 309 -1 310 -1 311 -1 312 -1 313 -1 314 -1 315 -1 316 -1 317 -1 318 -1 319 -1 320 -1 321 -1 322 -1 323 -1 324 -1 325 -1 326 -1 327 -1 328 -1 329 -1 330 -1 331 -1 332 -1 333 -1 334 -1 335 -1 336 -1 337 -1 338 -1 339 -1 340 -1 341 -1 342 -1 343 -1 344 -1 345 -1 346 -1 347 -1 348 -1 349 -1 350 -1 351 -1 352 -1 353 -1 354 -1 355 -1 356 -1 357 -1 358 -1 359 -1 360 -1 361 -1 362 -1 363 -1 364 -1 365 -1 366 -1 367 -1 368 -1 369 -1 370 -1 371 -1 372 -1 373 -1 374 -1 375 -1 376 -1 377 -1 378 -1 379 -1 380 -1 381 -1 382 -1 383 -1 384 -1 385 -1 386 -1 387 -1 388 -1 389 -1 390 -1 391 -1 392 -1 393 -1 394 -1 395 -1 396 -1 397 -1 398 -1 399 -1 400 -1 401 -1 402 -1 403 -1 404 -1 405 -1 406 -1 407 -1 408 -1 409 -1 410 -1 411 -1 412 -1 413 -1 414 -1 415 -1 416 -1 417 -1 418 -1 419 -1 420 -1 421 -1 422 -1 423 -1 424 -1 425 -1 426 -1 427 -1 428 -1 429 -1 430 -1 431 -1 432 -1 433 -1 434 -1 435 -1 436 -1 437 -1 438 -1 439 -1 440 -1 441 -1 442 -1 443 -1 444 -1 445 -1 446 -1 447 -1 448 -1 449 -1 450 -1 451 -1 452 -1 453 -1 454 -1 455 -1 456 -1 457 -1 458 -1 459 -1 460 -1 461 -1 462 -1 463 -1 464 -1 465 -1 466 -1 467 -1 468 -1 469 -1 470 -1 471 -1 472 -1 473 -1 474 -1 475 -1 476 -1 477 -1 478 -1 479 -1 480 -1 481 -1 482 -1 483 -1 484 -1 485 -1 486 -1 487 -1 488 -1 489 -1 490 -1 491 -1 492 -1 493 -1 494 -1 495 -1 496 -1 497 -1 498 -1 499 -1 500 -1 501 -1 502 -1 503 -1 504 -1 505 -1 506 -1 507 -1 508 -1 509 -1 510 -1 511 -1 512 -1 513 -1 514 -1 515 -1 516 -1 517 -1 518 -1 519 -1 520 -1 521 -1 522 -1 523 -1 524 -1 525 -1 526 -1 527 -1 528 -1 529 -1 530 -1 531 -1 532 -1 533 -1 534 -1 535 -1 536 -1 537 -1 538 -1 539 -1 540 -1 541 -1 542 -1 543 -1 544 -1 545 -1 546 -1 547 -1 548 -1 549 -1 550 -1 551 -1 552 -1 553 -1 554 -1 555 -1 556 -1 557 -1 558 -1 559 -1 560 -1 561 -1 562 -1 563 -1 564 -1 565 -1 566 -1 567 -1 568 -1 569 -1 570 -1 571 -1 572 -1 573 -1 574 -1 575 -1 576 -1 577 -1 578 -1 579 -1 580 -1 581 -1 582 -1 583 -1 584 -1 585 -1 586 -1 587 -1 588 -1 589 -1 590 -1 591 -1 592 -1 593 -1 594 -1 595 -1 596 -1 597 -1 598 -1 599 -1 600 -1 601 -1 602 -1 603 -1 604 -1 605 -1 606 -1 607 -1 608 -1 609 -1 610 -1 611 -1 612 -1 613 -1 614 -1 615 -1 616 -1 617 -1 618 -1 619 -1 620 -1 621 -1 622 -1 623 -1 624 -1 625 -1 626 -1 627 -1 628 -1 629 -1 630 -1 631 -1 632 -1 633 -1 634 -1 635 -1 636 -1 637 -1 638 -1 639 -1 640 -1 641 -1 642 -1 643 -1 644 -1 645 -1 646 -1 647 -1 648 -1 649 -1 650 -1 651 -1 652 -1 653 -1 654 -1 655 -1 656 -1 657 -1 658 -1 659 -1 660 -1 661 -1 662 -1 663 -1 664 -1 665 -1 666 -1 667 -1 668 -1 669 -1 670 -1 671 -1 672 -1 673 -1 674 -1 675 -1 676 -1 677 -1 678 -1 679 -1 680 -1 681 -1 682 -1 683 -1 684 -1 685 -1 686 -1 687 -1 688 -1 689 -1 690 -1 691 -1 692 -1 693 -1 694 -1 695 -1 696 -1 697 -1 698 -1 699 -1 700 -1 701 -1 702 -1 703 -1 704 -1 705 -1 706 -1 707 -1 708 -1 709 -1 710 -1 711 -1 712 -1 713 -1 714 -1 715 -1 716 -1 717 -1 718 -1 719 -1 720 -1 721 -1 722 -1 723 -1 724 -1 725 -1 726 -1 727 -1 728 -1 729 -1 730 -1 731 -1 732 -1 733 -1 734 -1 735 -1 736 -1 737 -1 738 -1 739 -1 740 -1 741 -1 742 -1 743 -1 744 -1 745 -1 746 -1 747 -1 748 -1 749 -1 750 -1 751 -1 752 -1 753 -1 754 -1 755 -1 756 -1 757 -1 758 -1 759 -1 760 -1 761 -1 762 -1 763 -1 764 -1 765 -1 766 -1 767 -1 768 -1 769 -1 770 -1 771 -1 772 -1 773 -1 774 -1 775 -1 776 -1 777 -1 778 -1 779 -1 780 -1 781 -1 782 -1 783 -1 784 -1 785 -1 786 -1 787 -1 788 -1 789 -1 790 -1 791 -1 792 -1 793 -1 794 -1 795 -1 796 -1 797 -1 798 -1 799 -1 800 -1 801 -1 802 -1 803 -1 804 -1 805 -1 806 -1 807 -1 808 -1 809 -1 810 -1 811 -1 812 -1 813 -1 814 -1 815 -1 816 -1 817 -1 818 -1 819 -1 820 -1 821 -1 822 -1 823 -1 824 -1 825 -1 826 -1 827 -1 828 -1 829 -1 830 -1 831 -1 832 -1 833 -1 834 -1 835 -1 836 -1 837 -1 838 -1 839 -1 840 -1 841 -1 842 -1 843 -1 844 -1 845 -1 846 -1 847 -1 848 -1 849 -1 850 -1 851 -1 852 -1 853 -1 854 -1 855 -1 856 -1 857 -1 858 -1 859 -1 860 -1 861 -1 862 -1 863 -1 864 -1 865 -1 866 -1 867 -1 868 -1 869 -1 870 -1 871 -1 872 -1 873 -1 874 -1 875 -1 876 -1 877 -1 878 -1 879 -1 880 -1 881 -1 882 -1 883 -1 884 -1 885 -1 886 -1 887 -1 888 -1 889 -1 890 -1 891 -1 892 -1 893 -1 894 -1 895 -1 896 -1 897 -1 898 -1 899 -1 900 -1 901 -1 902 -1 903 -1 904 -1 905 -1 906 -1 907 -1 908 -1 909 -1 910 -1 911 -1 912 -1 913 -1 914 -1 915 -1 916 -1 917 -1 918 -1 919 -1 920 -1 921 -1 922 -1 923 -1 924 -1 925 -1 926 -1 927 -1 928 -1 929 -1 930 -1 931 -1 932 -1 933 -1 934 -1 935 -1 936 -1 937 -1 938 -1 939 -1 940 -1 941 -1 942 -1 943 -1 944 -1 945 -1 946 -1 947 -1 948 -1 949 -1 950 -1 951 -1 952 -1 953 -1 954 -1 955 -1 956 -1 957 -1 958 -1 959 -1 960 -1 961 -1 962 -1 963 -1 964 -1 965 -1 966 -1 967 -1 968 -1 969 -1 970 -1 971 -1 972 -1 973 -1 974 -1 975 -1 976 -1 977 -1 978 -1 979 -1 980 -1 981 -1 982 -1 983 -1 984 -1 985 -1 986 -1 987 -1 988 -1 989 -1 990 -1 991 -1 992 -1 993 -1 994 -1 995 -1 996 -1 997 -1 998 -1 999 -1 1000 -1 1001 -1 1002 -1 1003 -1 1004 -1 1005 -1 1006 -1 1007 -1 1008 -1 1009 -1 1010 -1 1011 -1 1012 -1 1013 -1 1014 -1 1015 -1 1016 -1 1017 -1 1018 -1 1019 -1 1020 -1 1021 -1 1022 -1 1023 -1 1024 -1 1025 -1 1026 -1 1027 -1 1028 -1 1029 -1 1030 -1 1031 -1 1032 -1 1033 -1 1034 -1 1035 -1 1036 -1 1037 -1 1038 -1 1039 -1 1040 -1 1041 -1 1042 -1 1043 -1 1044 -1 1045 -1 1046 -1 1047 -1 1048 -1 1049 -1 1050 -1 1051 -1 1052 -1 1053 -1 1054 -1 1055 -1 1056 -1 1057 -1 1058 -1 1059 -1 1060 -1 1061 -1 1062 -1 1063 -1 1064 -1 1065 -1 1066 -1 1067 -1 1068 -1 1069 -1 1070 -1 1071 -1 1072 -1 1073 -1 1074 -1 1075 -1 1076 -1 1077 -1 1078 -1 1079 -1 1080 -1 1081 -1 1082 -1 1083 -1 1084 -1 1085 -1 1086 -1 1087 -1 1088 -1 1089 -1 1090 -1 1091 -1 1092 -1 1093 -1 1094 -1 1095 -1 1096 -1 1097 -1 1098 -1 1099 -1 1100 -1 1101 -1 1102 -1 1103 -1 1104 -1 1105 -1 1106 -1 1107 -1 1108 -1 1109 -1 1110 -1 1111 -1 1112 -1 1113 -1 1114 -1 1115 -1 1116 -1 1117 -1 1118 -1 1119 -1 1120 -1 1121 -1 1122 -1 1123 -1 1124 -1 1125 -1 1126 -1 1127 -1 1128 -1 1129 -1 1130 -1 1131 -1 1132 -1 1133 -1 1134 -1 1135 -1 1136 -1 1137 -1 1138 -1 1139 -1 1140 -1 1141 -1 1142 -1 1143 -1 1144 -1 1145 -1 1146 -1 1147 -1 1148 -1 1149 -1 1150 -1 1151 -1 1152 -1 1153 -1 1154 -1 1155 -1 1156 -1 1157 -1 1158 -1 1159 -1 1160 -1 1161 -1 1162 -1 1163 -1 1164 -1 1165 -1 1166 -1 1167 -1 1168 -1 1169 -1 1170 -1 1171 -1 1172 -1 1173 -1 1174 -1 1175 -1 1176 -1 1177 -1 1178 -1 1179 -1 1180 -1 1181 -1 1182 -1 1183 -1 1184 -1 1185 -1 1186 -1 1187 -1 1188 -1 1189 -1 1190 -1 1191 -1 1192 -1 1193 -1 1194 -1 1195 -1 1196 -1 1197 -1 1198 -1 1199 -1 1200 -1 1201 -1 1202 -1 1203 -1 1204 -1 1205 -1 1206 -1 1207 -1 1208 -1 1209 -1 1210 -1 1211 -1 1212 -1 1213 -1 1214 -1 1215 -1 1216 -1 1217 -1 1218 -1 1219 -1 1220 -1 1221 -1 1222 -1 1223 -1 1224 -1 1225 -1 1226 -1 1227 -1 1228 -1 1229 -1 1230 -1 1231 -1 1232 -1 1233 -1 1234 -1 1235 -1 1236 -1 1237 -1 1238 -1 1239 -1 1240 -1 1241 -1 1242 -1 1243 -1 1244 -1 1245 -1 1246 -1 1247 -1 1248 -1 1249 -1 1250 -1 1251 -1 1252 -1 1253 -1 1254 -1 1255 -1 1256 -1 1257 -1 1258 -1 1259 -1 1260 -1 1261 -1 1262 -1 1263 -1 1264 -1 1265 -1 1266 -1 1267 -1 1268 -1 1269 -1 1270 -1 1271 -1 1272 -1 1273 -1 1274 -1 1275 -1 1276 -1 1277 -1 1278 -1 1279 -1 1280 -1 1281 -1 1282 -1 1283 -1 1284 -1 1285 -1 1286 -1 1287 -1 1288 -1 1289 -1 1290 -1 1291 -1 1292 -1 1293 -1 1294 -1 1295 -1 1296 -1 1297 -1 1298 -1 1299 -1 1300 -1 1301 -1 1302 -1 1303 -1 1304 -1 1305 -1 1306 -1 1307 -1 1308 -1 1309 -1 1310 -1 1311 -1 1312 -1 1313 -1 1314 -1 1315 -1 1316 -1 1317 -1 1318 -1 1319 -1 1320 -1 1321 -1 1322 -1 1323 -1 1324 -1 1325 -1 1326 -1 1327 -1 1328 -1 1329 -1 1330 -1 1331 -1 1332 -1 1333 -1 1334 -1 1335 -1 1336 -1 1337 -1 1338 -1 1339 -1 1340 -1 1341 -1 1342 -1 1343 -1 1344 -1 1345 -1 1346 -1 1347 -1 1348 -1 1349 -1 1350 -1 1351 -1 1352 -1 1353 -1 1354 -1 1355 -1 1356 -1 1357 -1 1358 -1 1359 -1 1360 -1 1361 -1 1362 -1 1363 -1 1364 -1 1365 -1 1366 -1 1367 -1 1368 -1 1369 -1 1370 -1 1371 -1 1372 -1 1373 -1 1374 -1 1375 -1 1376 -1 1377 -1 1378 -1 1379 -1 1380 -1 1381 -1 1382 -1 1383 -1 1384 -1 1385 -1 1386 -1 1387 -1 1388 -1 1389 -1 1390 -1 1391 -1 1392 -1 1393 -1 1394 -1 1395 -1 1396 -1 1397 -1 1398 -1 1399 -1 1400 -1 1401 -1 1402 -1 1403 -1 1404 -1 1405 -1 1406 -1 1407 -1 1408 -1 1409 -1 1410 -1 1411 -1 1412 -1 1413 -1 1414 -1 1415 -1 1416 -1 1417 -1 1418 -1 1419 -1 1420 -1 1421 -1 1422 -1 1423 -1 1424 -1 1425 -1 1426 -1 1427 -1 1428 -1 1429 -1 1430 -1 1431 -1 1432 -1 1433 -1 1434 -1 1435 -1 1436 -1 1437 -1 1438 -1 1439 -1 1440 -1 1441 -1 1442 -1 1443 -1 1444 -1 1445 -1 1446 -1 1447 -1 1448 -1 1449 -1 1450 -1 1451 -1 1452 -1 1453 -1 1454 -1 1455 -1 1456 -1 1457 -1 1458 -1 1459 -1 1460 -1 1461 -1 1462 -1 1463 -1 1464 -1 1465 -1 1466 -1 1467 -1 1468 -1 1469 -1 1470 -1 1471 -1 1472 -1 1473 -1 1474 -1 1475 -1 1476 -1 1477 -1 1478 -1 1479 -1 1480 -1 1481 -1 1482 -1 1483 -1 1484 -1 1485 -1 1486 -1 1487 -1 1488 -1 1489 -1 1490 -1 1491 -1 1492 -1 1493 -1 1494 -1 1495 -1 1496 -1 1497 -1 1498 -1 1499 -1 1500 -1 1501 -1 1502 -1 1503 -1 1504 -1 1505 -1 1506 -1 1507 -1 1508 -1 1509 -1 1510 -1 1511 -1 1512 -1 1513 -1 1514 -1 1515 -1 1516 -1 1517 -1 1518 -1 1519 -1 1520 -1 1521 -1 1522 -1 1523 -1 1524 -1 1525 -1 1526 -1 1527 -1 1528 -1 1529 -1 1530 -1 1531 -1 1532 -1 1533 -1 1534 -1 1535 -1 1536 -1 1537 -1 1538 -1 1539 -1 1540 -1 1541 -1 1542 -1 1543 -1 1544 -1 1545 -1 1546 -1 1547 -1 1548 -1 1549 -1 1550 -1 1551 -1 1552 -1 1553 -1 1554 -1 1555 -1 1556 -1 1557 -1 1558 -1 1559 -1 1560 -1 1561 -1 1562 -1 1563 -1 1564 -1 1565 -1 1566 -1 1567 -1 1568 -1 1569 -1 1570 -1 1571 -1 1572 -1 1573 -1 1574 -1 1575 -1 1576 -1 1577 -1 1578 -1 1579 -1 1580 -1 1581 -1 1582 -1 1583 -1 1584 -1 1585 -1 1586 -1 1587 -1 1588 -1 1589 -1 1590 -1 1591 -1 1592 -1 1593 -1 1594 -1 1595 -1 1596 -1 1597 -1 1598 -1 1599 -1 1600 -1 1601 -1 1602 -1 1603 -1 1604 -1 1605 -1 1606 -1 1607 -1 1608 -1 1609 -1 1610 -1 1611 -1 1612 -1 1613 -1 1614 -1 1615 -1 1616 -1 1617 -1 1618 -1 1619 -1 1620 -1 1621 -1 1622 -1 1623 -1 1624 -1 1625 -1 1626 -1 1627 -1 1628 -1 1629 -1 1630 -1 1631 -1 1632 -1 1633 -1 1634 -1 1635 -1 1636 -1 1637 -1 1638 -1 1639 -1 1640 -1 1641 -1 1642 -1 1643 -1 1644 -1 1645 -1 1646 -1 1647 -1 1648 -1 1649 -1 1650 -1 1651 -1 1652 -1 1653 -1 1654 -1 1655 -1 1656 -1 1657 -1 1658 -1 1659 -1 1660 -1 1661 -1 1662 -1 1663 -1 1664 -1 1665 -1 1666 -1 1667 -1 1668 -1 1669 -1 1670 -1 1671 -1 1672 -1 1673 -1 1674 -1 1675 -1 1676 -1 1677 -1 1678 -1 1679 -1 1680 -1 1681 -1 1682 -1 1683 -1 1684 -1 1685 -1 1686 -1 1687 -1 1688 -1 1689 -1 1690 -1 1691 -1 1692 -1 1693 -1 1694 -1 1695 -1 1696 -1 1697 -1 1698 -1 1699 -1 1700 -1 1701 -1 1702 -1 1703 -1 1704 -1 1705 -1 1706 -1 1707 -1 1708 -1 1709 -1 1710 -1 1711 -1 1712 -1 1713 -1 1714 -1 1715 -1 1716 -1 1717 -1 1718 -1 1719 -1 1720 -1 1721 -1 1722 -1 1723 -1 1724 -1 1725 -1 1726 -1 1727 -1 1728 -1 1729 -1 1730 -1 1731 -1 1732 -1 1733 -1 1734 -1 1735 -1 1736 -1 1737 -1 1738 -1 1739 -1 1740 -1 1741 -1 1742 -1 1743 -1 1744 -1 1745 -1 1746 -1 1747 -1 1748 -1 1749 -1 1750 -1 1751 -1 1752 -1 1753 -1 1754 -1 1755 -1 1756 -1 1757 -1 1758 -1 1759 -1 1760 -1 1761 -1 1762 -1 1763 -1 1764 -1 1765 -1 1766 -1 1767 -1 1768 -1 1769 -1 1770 -1 1771 -1 1772 -1 1773 -1 1774 -1 1775 -1 1776 -1 1777 -1 1778 -1 1779 -1 1780 -1 1781 -1 1782 -1 1783 -1 1784 -1 1785 -1 1786 -1 1787 -1 1788 -1 1789 -1 1790 -1 1791 -1 1792 -1 1793 -1 1794 -1 1795 -1 1796 -1 1797 -1 1798 -1 1799 -1 1800 -1 1801 -1 1802 -1 1803 -1 1804 -1 1805 -1 1806 -1 1807 -1 1808 -1 1809 -1 1810 -1 1811 -1 1812 -1 1813 -1 1814 -1 1815 -1 1816 -1 1817 -1 1818 -1 1819 -1 1820 -1 1821 -1 1822 -1 1823 -1 1824 -1 1825 -1 1826 -1 1827 -1 1828 -1 1829 -1 1830 -1 1831 -1 1832 -1 1833 -1 1834 -1 1835 -1 1836 -1 1837 -1 1838 -1 1839 -1 1840 -1 1841 -1 1842 -1 1843 -1 1844 -1 1845 -1 1846 -1 1847 -1 1848 -1 1849 -1 1850 -1 1851 -1 1852 -1 1853 -1 1854 -1 1855 -1 1856 -1 1857 -1 1858 -1 1859 -1 1860 -1 1861 -1 1862 -1 1863 -1 1864 -1 1865 -1 1866 -1 1867 -1 1868 -1 1869 -1 1870 -1 1871 -1 1872 -1 1873 -1 1874 -1 1875 -1 1876 -1 1877 -1 1878 -1 1879 -1 1880 -1 1881 -1 1882 -1 1883 -1 1884 -1 1885 -1 1886 -1 1887 -1 1888 -1 1889 -1 1890 -1 1891 -1 1892 -1 1893 -1 1894 -1 1895 -1 1896 -1 1897 -1 1898 -1 1899 -1 1900 -1 1901 -1 1902 -1 1903 -1 1904 -1 1905 -1 1906 -1 1907 -1 1908 -1 1909 -1 1910 -1 1911 -1 1912 -1 1913 -1 1914 -1 1915 -1 1916 -1 1917 -1 1918 -1 1919 -1 1920 -1 1921 -1 1922 -1 1923 -1 1924 -1 1925 -1 1926 -1 1927 -1 1928 -1 1929 -1 1930 -1 1931 -1 1932 -1 1933 -1 1934 -1 1935 -1 1936 -1 1937 -1 1938 -1 1939 -1 1940 -1 1941 -1 1942 -1 1943 -1 1944 -1 1945 -1 1946 -1 1947 -1 1948 -1 1949 -1 1950 -1 1951 -1 1952 -1 1953 -1 1954 -1 1955 -1 1956 -1 1957 -1 1958 -1 1959 -1 1960 -1 1961 -1 1962 -1 1963 -1 1964 -1 1965 -1 1966 -1 1967 -1 1968 -1 1969 -1 1970 -1 1971 -1 1972 -1 1973 -1 1974 -1 1975 -1 1976 -1 1977 -1 1978 -1 1979 -1 1980 -1 1981 -1 1982 -1 1983 -1 1984 -1 1985 -1 1986 -1 1987 -1 1988 -1 1989 -1 1990 -1 1991 -1 1992 -1 1993 -1 1994 -1 1995 -1 1996 -1 1997 -1 1998 -1 1999 -1 2000 -1 2001 -1 2002 -1 2003 -1 2004 -1 2005 -1 2006 -1 2007 -1 2008 -1 2009 -1 2010 -1 2011 -1 2012 -1 2013 -1 2014 -1 2015 -1 2016 -1 2017 -1 2018 -1 2019 -1 2020 -1 2021 -1 2022 -1 2023 -1 2024 -1 2025 -1 2026 -1 2027 -1 2028 -1 2029 -1 2030 -1 2031 -1 2032 -1 2033 -1 2034 -1 2035 -1 2036 -1 2037 -1 2038 -1 2039 -1 2040 -1 2041 -1 2042 -1 2043 -1 2044 -1 2045 -1 2046 -1 2047 -1 2048 -1 2049 -1 2050 -1 2051 -1 2052 -1 2053 -1 2054 -1 2055 -1 2056 -1 2057 -1 2058 -1 2059 -1 2060 -1 2061 -1 2062 -1 2063 -1 2064 -1 2065 -1 2066 -1 2067 -1 2068 -1 2069 -1 2070 -1 2071 -1 2072 -1 2073 -1 2074 -1 2075 -1 2076 -1 2077 -1 2078 -1 2079 -1 2080 -1 2081 -1 2082 -1 2083 -1 2084 -1 2085 -1 2086 -1 2087 -1 2088 -1 2089 -1 2090 -1 2091 -1 2092 -1 2093 -1 2094 -1 2095 -1 2096 -1 2097 -1 2098 -1 2099 -1 2100 -1 2101 -1 2102 -1 2103 -1 2104 -1 2105 -1 2106 -1 2107 -1 2108 -1 2109 -1 2110 -1 2111 -1 2112 -1 2113 -1 2114 -1 2115 -1 2116 -1 2117 -1 2118 -1 2119 -1 2120 -1 2121 -1 2122 -1 2123 -1 2124 -1 2125 -1 2126 -1 2127 -1 2128 -1 2129 -1 2130 -1 2131 -1 2132 -1 2133 -1 2134 -1 2135 -1 2136 -1 2137 -1 2138 -1 2139 -1 2140 -1 2141 -1 2142 -1 2143 -1 2144 -1 2145 -1 2146 -1 2147 -1 2148 -1 2149 -1 2150 -1 2151 -1 2152 -1 2153 -1 2154 -1 2155 -1 2156 -1 2157 -1 2158 -1 2159 -1 2160 -1 2161 -1 2162 -1 2163 -1 2164 -1 2165 -1 2166 -1 2167 -1 2168 -1 2169 -1 2170 -1 2171 -1 2172 -1 2173 -1 2174 -1 2175 -1 2176 -1 2177 -1 2178 -1 2179 -1 2180 -1 2181 -1 2182 -1 2183 -1 2184 -1 2185 -1 2186 -1 2187 -1 2188 -1 2189 -1 2190 -1 2191 -1 2192 -1 2193 -1 2194 -1 2195 -1 2196 -1 2197 -1 2198 -1 2199 -1 2200 -1 2201 -1 2202 -1 2203 -1 2204 -1 2205 -1 2206 -1 2207 -1 2208 -1 2209 -1 2210 -1 2211 -1 2212 -1 2213 -1 2214 -1 2215 -1 2216 -1 2217 -1 2218 -1 2219 -1 2220 -1 2221 -1 2222 -1 2223 -1 2224 -1 2225 -1 2226 -1 2227 -1 2228 -1 2229 -1 2230 -1 2231 -1 2232 -1 2233 -1 2234 -1 2235 -1 2236 -1 2237 -1 2238 -1 2239 -1 2240 -1 2241 -1 2242 -1 2243 -1 2244 -1 2245 -1 2246 -1 2247 -1 2248 -1 2249 -1 2250 -1 2251 -1 2252 -1 2253 -1 2254 -1 2255 -1 2256 -1 2257 -1 2258 -1 2259 -1 2260 -1 2261 -1 2262 -1 2263 -1 2264 -1 2265 -1 2266 -1 2267 -1 2268 -1 2269 -1 2270 -1 2271 -1 2272 -1 2273 -1 2274 -1 2275 -1 2276 -1 2277 -1 2278 -1 2279 -1 2280 -1 2281 -1 2282 -1 2283 -1 2284 -1 2285 -1 2286 -1 2287 -1 2288 -1 2289 -1 2290 -1 2291 -1 2292 -1 2293 -1 2294 -1 2295 -1 2296 -1 2297 -1 2298 -1 2299 -1 2300 -1 2301 -1 2302 -1 2303 -1 2304 -1 2305 -1 2306 -1 2307 -1 2308 -1 2309 -1 2310 -1 2311 -1 2312 -1 2313 -1 2314 -1 2315 -1 2316 -1 2317 -1 2318 -1 2319 -1 2320 -1 2321 -1 2322 -1 2323 -1 2324 -1 2325 -1 2326 -1 2327 -1 2328 -1 2329 -1 2330 -1 2331 -1 2332 -1 2333 -1 2334 -1 2335 -1 2336 -1 2337 -1 2338 -1 2339 -1 2340 -1 2341 -1 2342 -1 2343 -1 2344 -1 2345 -1 2346 -1 2347 -1 2348 -1 2349 -1 2350 -1 2351 -1 2352 -1 2353 -1 2354 -1 2355 -1 2356 -1 2357 -1 2358 -1 2359 -1 2360 -1 2361 -1 2362 -1 2363 -1 2364 -1 2365 -1 2366 -1 2367 -1 2368 -1 2369 -1 2370 -1 2371 -1 2372 -1 2373 -1 2374 -1 2375 -1 2376 -1 2377 -1 2378 -1 2379 -1 2380 -1 2381 -1 2382 -1 2383 -1 2384 -1 2385 -1 2386 -1 2387 -1 2388 -1 2389 -1 2390 -1 2391 -1 2392 -1 2393 -1 2394 -1 2395 -1 2396 -1 2397 -1 2398 -1 2399 -1 2400 -1 2401 -1 2402 -1 2403 -1 2404 -1 2405 -1 2406 -1 2407 -1 2408 -1 2409 -1 2410 -1 2411 -1 2412 -1 2413 -1 2414 -1 2415 -1 2416 -1 2417 -1 2418 -1 2419 -1 2420 -1 2421 -1 2422 -1 2423 -1 2424 -1 2425 -1 2426 -1 2427 -1 2428 -1 2429 -1 2430 -1 2431 -1 2432 -1 2433 -1 2434 -1 2435 -1 2436 -1 2437 -1 2438 -1 2439 -1 2440 -1 2441 -1 2442 -1 2443 -1 2444 -1 2445 -1 2446 -1 2447 -1 2448 -1 2449 -1 2450 -1 2451 -1 2452 -1 2453 -1 2454 -1 2455 -1 2456 -1 2457 -1 2458 -1 2459 -1 2460 -1 2461 -1 2462 -1 2463 -1 2464 -1 2465 -1 2466 -1 2467 -1 2468 -1 2469 -1 2470 -1 2471 -1 2472 -1 2473 -1 2474 -1 2475 -1 2476 -1 2477 -1 2478 -1 2479 -1 2480 -1 2481 -1 2482 -1 2483 -1 2484 -1 2485 -1 2486 -1 2487 -1 2488 -1 2489 -1 2490 -1 2491 -1 2492 -1 2493 -1 2494 -1 2495 -1 2496 -1 2497 -1 2498 -1 2499 -1 2500 -1 2501 -1 2502 -1 2503 -1 2504 -1 2505 -1 2506 -1 2507 -1 2508 -1 2509 -1 2510 -1 2511 -1 2512 -1 2513 -1 2514 -1 2515 -1 2516 -1 2517 -1 2518 -1 2519 -1 2520 -1 2521 -1 2522 -1 2523 -1 2524 -1 2525 -1 2526 -1 2527 -1 2528 -1 2529 -1 2530 -1 2531 -1 2532 -1 2533 -1 2534 -1 2535 -1 2536 -1 2537 -1 2538 -1 2539 -1 2540 -1 2541 -1 2542 -1 2543 -1 2544 -1 2545 -1 2546 -1 2547 -1 2548 -1 2549 -1 2550 -1 2551 -1 2552 -1 2553 -1 2554 -1 2555 -1 2556 -1 2557 -1 2558 -1 2559 -1 2560 -1 2561 -1 2562 -1 2563 -1 2564 -1 2565 -1 2566 -1 2567 -1 2568 -1 2569 -1 2570 -1 2571 -1 2572 -1 2573 -1 2574 -1 2575 -1 2576 -1 2577 -1 2578 -1 2579 -1 2580 -1 2581 -1 2582 -1 2583 -1 2584 -1 2585 -1 2586 -1 2587 -1 2588 -1 2589 -1 2590 -1 2591 -1 2592 -1 2593 -1 2594 -1 2595 -1 2596 -1 2597 -1 2598 -1 2599 -1 2600 -1 2601 -1 2602 -1 2603 -1 2604 -1 2605 -1 2606 -1 2607 -1 2608 -1 2609 -1 2610 -1 2611 -1 2612 -1 2613 -1 2614 -1 2615 -1 2616 -1 2617 -1 2618 -1 2619 -1 2620 -1 2621 -1 2622 -1 2623 -1 2624 -1 2625 -1 2626 -1 2627 -1 2628 -1 2629 -1 2630 -1 2631 -1 2632 -1 2633 -1 2634 -1 2635 -1 2636 -1 2637 -1 2638 -1 2639 -1 2640 -1 2641 -1 2642 -1 2643 -1 2644 -1 2645 -1 2646 -1 2647 -1 2648 -1 2649 -1 2650 -1 2651 -1 2652 -1 2653 -1 2654 -1 2655 -1 2656 -1 2657 -1 2658 -1 2659 -1 2660 -1 2661 -1 2662 -1 2663 -1 2664 -1 2665 -1 2666 -1 2667 -1 2668 -1 2669 -1 2670 -1 2671 -1 2672 -1 2673 -1 2674 -1 2675 -1 2676 -1 2677 -1 2678 -1 2679 -1 2680 -1 2681 -1 2682 -1 2683 -1 2684 -1 2685 -1 2686 -1 2687 -1 2688 -1 2689 -1 2690 -1 2691 -1 2692 -1 2693 -1 2694 -1 2695 -1 2696 -1 2697 -1 2698 -1 2699 -1 2700 -1 2701 -1 2702 -1 2703 -1 2704 -1 2705 -1 2706 -1 2707 -1 2708 -1 2709 -1 2710 -1 2711 -1 2712 -1 2713 -1 2714 -1 2715 -1 2716 -1 2717 -1 2718 -1 2719 -1 2720 -1 2721 -1 2722 -1 2723 -1 2724 -1 2725 -1 2726 -1 2727 -1 2728 -1 2729 -1 2730 -1 2731 -1 2732 -1 2733 -1 2734 -1 2735 -1 2736 -1 2737 -1 2738 -1 2739 -1 2740 -1 2741 -1 2742 -1 2743 -1 2744 -1 2745 -1 2746 -1 2747 -1 2748 -1 2749 -1 2750 -1 2751 -1 2752 -1 2753 -1 2754 -1 2755 -1 2756 -1 2757 -1 2758 -1 2759 -1 2760 -1 2761 -1 2762 -1 2763 -1 2764 -1 2765 -1 2766 -1 2767 -1 2768 -1 2769 -1 2770 -1 2771 -1 2772 -1 2773 -1 2774 -1 2775 -1 2776 -1 2777 -1 2778 -1 2779 -1 2780 -1 2781 -1 2782 -1 2783 -1 2784 -1 2785 -1 2786 -1 2787 -1 2788 -1 2789 -1 2790 -1 2791 -1 2792 -1 2793 -1 2794 -1 2795 -1 2796 -1 2797 -1 2798 -1 2799 -1 2800 -1 2801 -1 2802 -1 2803 -1 2804 -1 2805 -1 2806 -1 2807 -1 2808 -1 2809 -1 2810 -1 2811 -1 2812 -1 2813 -1 2814 -1 2815 -1 2816 -1 2817 -1 2818 -1 2819 -1 2820 -1 2821 -1 2822 -1 2823 -1 2824 -1 2825 -1 2826 -1 2827 -1 2828 -1 2829 -1 2830 -1 2831 -1 2832 -1 2833 -1 2834 -1 2835 -1 2836 -1 2837 -1 2838 -1 2839 -1 2840 -1 2841 -1 2842 -1 2843 -1 2844 -1 2845 -1 2846 -1 2847 -1 2848 -1 2849 -1 2850 -1 2851 -1 2852 -1 2853 -1 2854 -1 2855 -1 2856 -1 2857 -1 2858 -1 2859 -1 2860 -1 2861 -1 2862 -1 2863 -1 2864 -1 2865 -1 2866 -1 2867 -1 2868 -1 2869 -1 2870 -1 2871 -1 2872 -1 2873 -1 2874 -1 2875 -1 2876 -1 2877 -1 2878 -1 2879 -1 2880 -1 2881 -1 2882 -1 2883 -1 2884 -1 2885 -1 2886 -1 2887 -1 2888 -1 2889 -1 2890 -1 2891 -1 2892 -1 2893 -1 2894 -1 2895 -1 2896 -1 2897 -1 2898 -1 2899 -1 2900 -1 2901 -1 2902 -1 2903 -1 2904 -1 2905 -1 2906 -1 2907 -1 2908 -1 2909 -1 2910 -1 2911 -1 2912 -1 2913 -1 2914 -1 2915 -1 2916 -1 2917 -1 2918 -1 2919 -1 2920 -1 2921 -1 2922 -1 2923 -1 2924 -1 2925 -1 2926 -1 2927 -1 2928 -1 2929 -1 2930 -1 2931 -1 2932 -1 2933 -1 2934 -1 2935 -1 2936 -1 2937 -1 2938 -1 2939 -1 2940 -1 2941 -1 2942 -1 2943 -1 2944 -1 2945 -1 2946 -1 2947 -1 2948 -1 2949 -1 2950 -1 2951 -1 2952 -1 2953 -1 2954 -1 2955 -1 2956 -1 2957 -1 2958 -1 2959 -1 2960 -1 2961 -1 2962 -1 2963 -1 2964 -1 2965 -1 2966 -1 2967 -1 2968 -1 2969 -1 2970 -1 2971 -1 2972 -1 2973 -1 2974 -1 2975 -1 2976 -1 2977 -1 2978 -1 2979 -1 2980 -1 2981 -1 2982 -1 2983 -1 2984 -1 2985 -1 2986 -1 2987 -1 2988 -1 2989 -1 2990 -1 2991 -1 2992 -1 2993 -1 2994 -1 2995 -1 2996 -1 2997 -1 2998 -1 2999 -1 3000 -1 3001 -1 3002 -1 3003 -1 3004 -1 3005 -1 3006 -1 3007 -1 3008 -1 3009 -1 3010 -1 3011 -1 3012 -1 3013 -1 3014 -1 3015 -1 3016 -1 3017 -1 3018 -1 3019 -1 3020 -1 3021 -1 3022 -1 3023 -1 3024 -1 3025 -1 3026 -1 3027 -1 3028 -1 3029 -1 3030 -1 3031 -1 3032 -1 3033 -1 3034 -1 3035 -1 3036 -1 3037 -1 3038 -1 3039 -1 3040 -1 3041 -1 3042 -1 3043 -1 3044 -1 3045 -1 3046 -1 3047 -1 3048 -1 3049 -1 3050 -1 3051 -1 3052 -1 3053 -1 3054 -1 3055 -1 3056 -1 3057 -1 3058 -1 3059 -1 3060 -1 3061 -1 3062 -1 3063 -1 3064 -1 3065 -1 3066 -1 3067 -1 3068 -1 3069 -1 3070 -1 3071 -1 3072 -1 3073 -1 3074 -1 3075 -1 3076 -1 3077 -1 3078 -1 3079 -1 3080 -1 3081 -1 3082 -1 3083 -1 3084 -1 3085 -1 3086 -1 3087 -1 3088 -1 3089 -1 3090 -1 3091 -1 3092 -1 3093 -1 3094 -1 3095 -1 3096 -1 3097 -1 3098 -1 3099 -1 3100 -1 3101 -1 3102 -1 3103 -1 3104 -1 3105 -1 3106 -1 3107 -1 3108 -1 3109 -1 3110 -1 3111 -1 3112 -1 3113 -1 3114 -1 3115 -1 3116 -1 3117 -1 3118 -1 3119 -1 3120 -1 3121 -1 3122 -1 3123 -1 3124 -1 3125 -1 3126 -1 3127 -1 3128 -1 3129 -1 3130 -1 3131 -1 3132 -1 3133 -1 3134 -1 3135 -1 3136 -1 3137 -1 3138 -1 3139 -1 3140 -1 3141 -1 3142 -1 3143 -1 3144 -1 3145 -1 3146 -1 3147 -1 3148 -1 3149 -1 3150 -1 3151 -1 3152 -1 3153 -1 3154 -1 3155 -1 3156 -1 3157 -1 3158 -1 3159 -1 3160 -1 3161 -1 3162 -1 3163 -1 3164 -1 3165 -1 3166 -1 3167 -1 3168 -1 3169 -1 3170 -1 3171 -1 3172 -1 3173 -1 3174 -1 3175 -1 3176 -1 3177 -1 3178 -1 3179 -1 3180 -1 3181 -1 3182 -1 3183 -1 3184 -1 3185 -1 3186 -1 3187 -1 3188 -1 3189 -1 3190 -1 3191 -1 3192 -1 3193 -1 3194 -1 3195 -1 3196 -1 3197 -1 3198 -1 3199 -1 3200 -1 3201 -1 3202 -1 3203 -1 3204 -1 3205 -1 3206 -1 3207 -1 3208 -1 3209 -1 3210 -1 3211 -1 3212 -1 3213 -1 3214 -1 3215 -1 3216 -1 3217 -1 3218 -1 3219 -1 3220 -1 3221 -1 3222 -1 3223 -1 3224 -1 3225 -1 3226 -1 3227 -1 3228 -1 3229 -1 3230 -1 3231 -1 3232 -1 3233 -1 3234 -1 3235 -1 3236 -1 3237 -1 3238 -1 3239 -1 3240 -1 3241 -1 3242 -1 3243 -1 3244 -1 3245 -1 3246 -1 3247 -1 3248 -1 3249 -1 3250 -1 3251 -1 3252 -1 3253 -1 3254 -1 3255 -1 3256 -1 3257 -1 3258 -1 3259 -1 3260 -1 3261 -1 3262 -1 3263 -1 3264 -1 3265 -1 3266 -1 3267 -1 3268 -1 3269 -1 3270 -1 3271 -1 3272 -1 3273 -1 3274 -1 3275 -1 3276 -1 3277 -1 3278 -1 3279 -1 3280 -1 3281 -1 3282 -1 3283 -1 3284 -1 3285 -1 3286 -1 3287 -1 3288 -1 3289 -1 3290 -1 3291 -1 3292 -1 3293 -1 3294 -1 3295 -1 3296 -1 3297 -1 3298 -1 3299 -1 3300 -1 3301 -1 3302 -1 3303 -1 3304 -1 3305 -1 3306 -1 3307 -1 3308 -1 3309 -1 3310 -1 3311 -1 3312 -1 3313 -1 3314 -1 3315 -1 3316 -1 3317 -1 3318 -1 3319 -1 3320 -1 3321 -1 3322 -1 3323 -1 3324 -1 3325 -1 3326 -1 3327 -1 3328 -1 3329 -1 3330 -1 3331 -1 3332 -1 3333 -1 3334 -1 3335 -1 3336 -1 3337 -1 3338 -1 3339 -1 3340 -1 3341 -1 3342 -1 3343 -1 3344 -1 3345 -1 3346 -1 3347 -1 3348 -1 3349 -1 3350 -1 3351 -1 3352 -1 3353 -1 3354 -1 3355 -1 3356 -1 3357 -1 3358 -1 3359 -1 3360 -1 3361 -1 3362 -1 3363 -1 3364 -1 3365 -1 3366 -1 3367 -1 3368 -1 3369 -1 3370 -1 3371 -1 3372 -1 3373 -1 3374 -1 3375 -1 3376 -1 3377 -1 3378 -1 3379 -1 3380 -1 3381 -1 3382 -1 3383 -1 3384 -1 3385 -1 3386 -1 3387 -1 3388 -1 3389 -1 3390 -1 3391 -1 3392 -1 3393 -1 3394 -1 3395 -1 3396 -1 3397 -1 3398 -1 3399 -1 3400 -1 3401 -1 3402 -1 3403 -1 3404 -1 3405 -1 3406 -1 3407 -1 3408 -1 3409 -1 3410 -1 3411 -1 3412 -1 3413 -1 3414 -1 3415 -1 3416 -1 3417 -1 3418 -1 3419 -1 3420 -1 3421 -1 3422 -1 3423 -1 3424 -1 3425 -1 3426 -1 3427 -1 3428 -1 3429 -1 3430 -1 3431 -1 3432 -1 3433 -1 3434 -1 3435 -1 3436 -1 3437 -1 3438 -1 3439 -1 3440 -1 3441 -1 3442 -1 3443 -1 3444 -1 3445 -1 3446 -1 3447 -1 3448 -1 3449 -1 3450 -1 3451 -1 3452 -1 3453 -1 3454 -1 3455 -1 3456 -1 3457 -1 3458 -1 3459 -1 3460 -1 3461 -1 3462 -1 3463 -1 3464 -1 3465 -1 3466 -1 3467 -1 3468 -1 3469 -1 3470 -1 3471 -1 3472 -1 3473 -1 3474 -1 3475 -1 3476 -1 3477 -1 3478 -1 3479 -1 3480 -1 3481 -1 3482 -1 3483 -1 3484 -1 3485 -1 3486 -1 3487 -1 3488 -1 3489 -1 3490 -1 3491 -1 3492 -1 3493 -1 3494 -1 3495 -1 3496 -1 3497 -1 3498 -1 3499 -1 3500 -1 3501 -1 3502 -1 3503 -1 3504 -1 3505 -1 3506 -1 3507 -1 3508 -1 3509 -1 3510 -1 3511 -1 3512 -1 3513 -1 3514 -1 3515 -1 3516 -1 3517 -1 3518 -1 3519 -1 3520 -1 3521 -1 3522 -1 3523 -1 3524 -1 3525 -1 3526 -1 3527 -1 3528 -1 3529 -1 3530 -1 3531 -1 3532 -1 3533 -1 3534 -1 3535 -1 3536 -1 3537 -1 3538 -1 3539 -1 3540 -1 3541 -1 3542 -1 3543 -1 3544 -1 3545 -1 3546 -1 3547 -1 3548 -1 3549 -1 3550 -1 3551 -1 3552 -1 3553 -1 3554 -1 3555 -1 3556 -1 3557 -1 3558 -1 3559 -1 3560 -1 3561 -1 3562 -1 3563 -1 3564 -1 3565 -1 3566 -1 3567 -1 3568 -1 3569 -1 3570 -1 3571 -1 3572 -1 3573 -1 3574 -1 3575 -1 3576 -1 3577 -1 3578 -1 3579 -1 3580 -1 3581 -1 3582 -1 3583 -1 3584 -1 3585 -1 3586 -1 3587 -1 3588 -1 3589 -1 3590 -1 3591 -1 3592 -1 3593 -1 3594 -1 3595 -1 3596 -1 3597 -1 3598 -1 3599 -1 3600 -1 3601 -1 3602 -1 3603 -1 3604 -1 3605 -1 3606 -1 3607 -1 3608 -1 3609 -1 3610 -1 3611 -1 3612 -1 3613 -1 3614 -1 3615 -1 3616 -1 3617 -1 3618 -1 3619 -1 3620 -1 3621 -1 3622 -1 3623 -1 3624 -1 3625 -1 3626 -1 3627 -1 3628 -1 3629 -1 3630 -1 3631 -1 3632 -1 3633 -1 3634 -1 3635 -1 3636 -1 3637 -1 3638 -1 3639 -1 3640 -1 3641 -1 3642 -1 3643 -1 3644 -1 3645 -1 3646 -1 3647 -1 3648 -1 3649 -1 3650 -1 3651 -1 3652 -1 3653 -1 3654 -1 3655 -1 3656 -1 3657 -1 3658 -1 3659 -1 3660 -1 3661 -1 3662 -1 3663 -1 3664 -1 3665 -1 3666 -1 3667 -1 3668 -1 3669 -1 3670 -1 3671 -1 3672 -1 3673 -1 3674 -1 3675 -1 3676 -1 3677 -1 3678 -1 3679 -1 3680 -1 3681 -1 3682 -1 3683 -1 3684 -1 3685 -1 3686 -1 3687 -1 3688 -1 3689 -1 3690 -1 3691 -1 3692 -1 3693 -1 3694 -1 3695 -1 3696 -1 3697 -1 3698 -1 3699 -1 3700 -1 3701 -1 3702 -1 3703 -1 3704 -1 3705 -1 3706 -1 3707 -1 3708 -1 3709 -1 3710 -1 3711 -1 3712 -1 3713 -1 3714 -1 3715 -1 3716 -1 3717 -1 3718 -1 3719 -1 3720 -1 3721 -1 3722 -1 3723 -1 3724 -1 3725 -1 3726 -1 3727 -1 3728 -1 3729 -1 3730 -1 3731 -1 3732 -1 3733 -1 3734 -1 3735 -1 3736 -1 3737 -1 3738 -1 3739 -1 3740 -1 3741 -1 3742 -1 3743 -1 3744 -1 3745 -1 3746 -1 3747 -1 3748 -1 3749 -1 3750 -1 3751 -1 3752 -1 3753 -1 3754 -1 3755 -1 3756 -1 3757 -1 3758 -1 3759 -1 3760 -1 3761 -1 3762 -1 3763 -1 3764 -1 3765 -1 3766 -1 3767 -1 3768 -1 3769 -1 3770 -1 3771 -1 3772 -1 3773 -1 3774 -1 3775 -1 3776 -1 3777 -1 3778 -1 3779 -1 3780 -1 3781 -1 3782 -1 3783 -1 3784 -1 3785 -1 3786 -1 3787 -1 3788 -1 3789 -1 3790 -1 3791 -1 3792 -1 3793 -1 3794 -1 3795 -1 3796 -1 3797 -1 3798 -1 3799 -1 3800 -1 3801 -1 3802 -1 3803 -1 3804 -1 3805 -1 3806 -1 3807 -1 3808 -1 3809 -1 3810 -1 3811 -1 3812 -1 3813 -1 3814 -1 3815 -1 3816 -1 3817 -1 3818 -1 3819 -1 3820 -1 3821 -1 3822 -1 3823 -1 3824 -1 3825 -1 3826 -1 3827 -1 3828 -1 3829 -1 3830 -1 3831 -1 3832 -1 3833 -1 3834 -1 3835 -1 3836 -1 3837 -1 3838 -1 3839 -1 3840 -1 3841 -1 3842 -1 3843 -1 3844 -1 3845 -1 3846 -1 3847 -1 3848 -1 3849 -1 3850 -1 3851 -1 3852 -1 3853 -1 3854 -1 3855 -1 3856 -1 3857 -1 3858 -1 3859 -1 3860 -1 3861 -1 3862 -1 3863 -1 3864 -1 3865 -1 3866 -1 3867 -1 3868 -1 3869 -1 3870 -1 3871 -1 3872 -1 3873 -1 3874 -1 3875 -1 3876 -1 3877 -1 3878 -1 3879 -1 3880 -1 3881 -1 3882 -1 3883 -1 3884 -1 3885 -1 3886 -1 3887 -1 3888 -1 3889 -1 3890 -1 3891 -1 3892 -1 3893 -1 3894 -1 3895 -1 3896 -1 3897 -1 3898 -1 3899 -1 3900 -1 3901 -1 3902 -1 3903 -1 3904 -1 3905 -1 3906 -1 3907 -1 3908 -1 3909 -1 3910 -1 3911 -1 3912 -1 3913 -1 3914 -1 3915 -1 3916 -1 3917 -1 3918 -1 3919 -1 3920 -1 3921 -1 3922 -1 3923 -1 3924 -1 3925 -1 3926 -1 3927 -1 3928 -1 3929 -1 3930 -1 3931 -1 3932 -1 3933 -1 3934 -1 3935 -1 3936 -1 3937 -1 3938 -1 3939 -1 3940 -1 3941 -1 3942 -1 3943 -1 3944 -1 3945 -1 3946 -1 3947 -1 3948 -1 3949 -1 3950 -1 3951 -1 3952 -1 3953 -1 3954 -1 3955 -1 3956 -1 3957 -1 3958 -1 3959 -1 3960 -1 3961 -1 3962 -1 3963 -1 3964 -1 3965 -1 3966 -1 3967 -1 3968 -1 3969 -1 3970 -1 3971 -1 3972 -1 3973 -1 3974 -1 3975 -1 3976 -1 3977 -1 3978 -1 3979 -1 3980 -1 3981 -1 3982 -1 3983 -1 3984 -1 3985 -1 3986 -1 3987 -1 3988 -1 3989 -1 3990 -1 3991 -1 3992 -1 3993 -1 3994 -1 3995 -1 3996 -1 3997 -1 3998 -1 3999 -1 4000 -1 4001 -1 4002 -1 4003 -1 4004 -1 4005 -1 4006 -1 4007 -1 4008 -1 4009 -1 4010 -1 4011 -1 4012 -1 4013 -1 4014 -1 4015 -1 4016 -1 4017 -1 4018 -1 4019 -1 4020 -1 4021 -1 4022 -1 4023 -1 4024 -1 4025 -1 4026 -1 4027 -1 4028 -1 4029 -1 4030 -1 4031 -1 4032 -1 4033 -1 4034 -1 4035 -1 4036 -1 4037 -1 4038 -1 4039 -1 4040 -1 4041 -1 4042 -1 4043 -1 4044 -1 4045 -1 4046 -1 4047 -1 4048 -1 4049 -1 4050 -1 4051 -1 4052 -1 4053 -1 4054 -1 4055 -1 4056 -1 4057 -1 4058 -1 4059 -1 4060 -1 4061 -1 4062 -1 4063 -1 4064 -1 4065 -1 4066 -1 4067 -1 4068 -1 4069 -1 4070 -1 4071 -1 4072 -1 4073 -1 4074 -1 4075 -1 4076 -1 4077 -1 4078 -1 4079 -1 4080 -1 4081 -1 4082 -1 4083 -1 4084 -1 4085 -1 4086 -1 4087 -1 4088 -1 4089 -1 4090 -1 4091 -1 4092 -1 4093 -1 4094 -1 4095 -1 4096 -1 4097 -1 4098 -1 4099 -1 4100 -1 4101 -1 4102 -1 4103 -1 4104 -1 4105 -1 4106 -1 4107 -1 4108 -1 4109 -1 4110 -1 4111 -1 4112 -1 4113 -1 4114 -1 4115 -1 4116 -1 4117 -1 4118 -1 4119 -1 4120 -1 4121 -1 4122 -1 4123 -1 4124 -1 4125 -1 4126 -1 4127 -1 4128 -1 4129 -1 4130 -1 4131 -1 4132 -1 4133 -1 4134 -1 4135 -1 4136 -1 4137 -1 4138 -1 4139 -1 4140 -1 4141 -1 4142 -1 4143 -1 4144 -1 4145 -1 4146 -1 4147 -1 4148 -1 4149 -1 4150 -1 4151 -1 4152 -1 4153 -1 4154 -1 4155 -1 4156 -1 4157 -1 4158 -1 4159 -1 4160 -1 4161 -1 4162 -1 4163 -1 4164 -1 4165 -1 4166 -1 4167 -1 4168 -1 4169 -1 4170 -1 4171 -1 4172 -1 4173 -1 4174 -1 4175 -1 4176 -1 4177 -1 4178 -1 4179 -1 4180 -1 4181 -1 4182 -1 4183 -1 4184 -1 4185 -1 4186 -1 4187 -1 4188 -1 4189 -1 4190 -1 4191 -1 4192 -1 4193 -1 4194 -1 4195 -1 4196 -1 4197 -1 4198 -1 4199 -1 4200 -1 4201 -1 4202 -1 4203 -1 4204 -1 4205 -1 4206 -1 4207 -1 4208 -1 4209 -1 4210 -1 4211 -1 4212 -1 4213 -1 4214 -1 4215 -1 4216 -1 4217 -1 4218 -1 4219 -1 4220 -1 4221 -1 4222 -1 4223 -1 4224 -1 4225 -1 4226 -1 4227 -1 4228 -1 4229 -1 4230 -1 4231 -1 4232 -1 4233 -1 4234 -1 4235 -1 4236 -1 4237 -1 4238 -1 4239 -1 4240 -1 4241 -1 4242 -1 4243 -1 4244 -1 4245 -1 4246 -1 4247 -1 4248 -1 4249 -1 4250 -1 4251 -1 4252 -1 4253 -1 4254 -1 4255 -1 4256 -1 4257 -1 4258 -1 4259 -1 4260 -1 4261 -1 4262 -1 4263 -1 4264 -1 4265 -1 4266 -1 4267 -1 4268 -1 4269 -1 4270 -1 4271 -1 4272 -1 4273 -1 4274 -1 4275 -1 4276 -1 4277 -1 4278 -1 4279 -1 4280 -1 4281 -1 4282 -1 4283 -1 4284 -1 4285 -1 4286 -1 4287 -1 4288 -1 4289 -1 4290 -1 4291 -1 4292 -1 4293 -1 4294 -1 4295 -1 4296 -1 4297 -1 4298 -1 4299 -1 4300 -1 4301 -1 4302 -1 4303 -1 4304 -1 4305 -1 4306 -1 4307 -1 4308 -1 4309 -1 4310 -1 4311 -1 4312 -1 4313 -1 4314 -1 4315 -1 4316 -1 4317 -1 4318 -1 4319 -1 4320 -1 4321 -1 4322 -1 4323 -1 4324 -1 4325 -1 4326 -1 4327 -1 4328 -1 4329 -1 4330 -1 4331 -1 4332 -1 4333 -1 4334 -1 4335 -1 4336 -1 4337 -1 4338 -1 4339 -1 4340 -1 4341 -1 4342 -1 4343 -1 4344 -1 4345 -1 4346 -1 4347 -1 4348 -1 4349 -1 4350 -1 4351 -1 4352 -1 4353 -1 4354 -1 4355 -1 4356 -1 4357 -1 4358 -1 4359 -1 4360 -1 4361 -1 4362 -1 4363 -1 4364 -1 4365 -1 4366 -1 4367 -1 4368 -1 4369 -1 4370 -1 4371 -1 4372 -1 4373 -1 4374 -1 4375 -1 4376 -1 4377 -1 4378 -1 4379 -1 4380 -1 4381 -1 4382 -1 4383 -1 4384 -1 4385 -1 4386 -1 4387 -1 4388 -1 4389 -1 4390 -1 4391 -1 4392 -1 4393 -1 4394 -1 4395 -1 4396 -1 4397 -1 4398 -1 4399 -1 4400 -1 4401 -1 4402 -1 4403 -1 4404 -1 4405 -1 4406 -1 4407 -1 4408 -1 4409 -1 4410 -1 4411 -1 4412 -1 4413 -1 4414 -1 4415 -1 4416 -1 4417 -1 4418 -1 4419 -1 4420 -1 4421 -1 4422 -1 4423 -1 4424 -1 4425 -1 4426 -1 4427 -1 4428 -1 4429 -1 4430 -1 4431 -1 4432 -1 4433 -1 4434 -1 4435 -1 4436 -1 4437 -1 4438 -1 4439 -1 4440 -1 4441 -1 4442 -1 4443 -1 4444 -1 4445 -1 4446 -1 4447 -1 4448 -1 4449 -1 4450 -1 4451 -1 4452 -1 4453 -1 4454 -1 4455 -1 4456 -1 4457 -1 4458 -1 4459 -1 4460 -1 4461 -1 4462 -1 4463 -1 4464 -1 4465 -1 4466 -1 4467 -1 4468 -1 4469 -1 4470 -1 4471 -1 4472 -1 4473 -1 4474 -1 4475 -1 4476 -1 4477 -1 4478 -1 4479 -1 4480 -1 4481 -1 4482 -1 4483 -1 4484 -1 4485 -1 4486 -1 4487 -1 4488 -1 4489 -1 4490 -1 4491 -1 4492 -1 4493 -1 4494 -1 4495 -1 4496 -1 4497 -1 4498 -1 4499 -1 4500 -1 4501 -1 4502 -1 4503 -1 4504 -1 4505 -1 4506 -1 4507 -1 4508 -1 4509 -1 4510 -1 4511 -1 4512 -1 4513 -1 4514 -1 4515 -1 4516 -1 4517 -1 4518 -1 4519 -1 4520 -1 4521 -1 4522 -1 4523 -1 4524 -1 4525 -1 4526 -1 4527 -1 4528 -1 4529 -1 4530 -1 4531 -1 4532 -1 4533 -1 4534 -1 4535 -1 4536 -1 4537 -1 4538 -1 4539 -1 4540 -1 4541 -1 4542 -1 4543 -1 4544 -1 4545 -1 4546 -1 4547 -1 4548 -1 4549 -1 4550 -1 4551 -1 4552 -1 4553 -1 4554 -1 4555 -1 4556 -1 4557 -1 4558 -1 4559 -1 4560 -1 4561 -1 4562 -1 4563 -1 4564 -1 4565 -1 4566 -1 4567 -1 4568 -1 4569 -1 4570 -1 4571 -1 4572 -1 4573 -1 4574 -1 4575 -1 4576 -1 4577 -1 4578 -1 4579 -1 4580 -1 4581 -1 4582 -1 4583 -1 4584 -1 4585 -1 4586 -1 4587 -1 4588 -1 4589 -1 4590 -1 4591 -1 4592 -1 4593 -1 4594 -1 4595 -1 4596 -1 4597 -1 4598 -1 4599 -1 4600 -1 4601 -1 4602 -1 4603 -1 4604 -1 4605 -1 4606 -1 4607 -1 4608 -1 4609 -1 4610 -1 4611 -1 4612 -1 4613 -1 4614 -1 4615 -1 4616 -1 4617 -1 4618 -1 4619 -1 4620 -1 4621 -1 4622 -1 4623 -1 4624 -1 4625 -1 4626 -1 4627 -1 4628 -1 4629 -1 4630 -1 4631 -1 4632 -1 4633 -1 4634 -1 4635 -1 4636 -1 4637 -1 4638 -1 4639 -1 4640 -1 4641 -1 4642 -1 4643 -1 4644 -1 4645 -1 4646 -1 4647 -1 4648 -1 4649 -1 4650 -1 4651 -1 4652 -1 4653 -1 4654 -1 4655 -1 4656 -1 4657 -1 4658 -1 4659 -1 4660 -1 4661 -1 4662 -1 4663 -1 4664 -1 4665 -1 4666 -1 4667 -1 4668 -1 4669 -1 4670 -1 4671 -1 4672 -1 4673 -1 4674 -1 4675 -1 4676 -1 4677 -1 4678 -1 4679 -1 4680 -1 4681 -1 4682 -1 4683 -1 4684 -1 4685 -1 4686 -1 4687 -1 4688 -1 4689 -1 4690 -1 4691 -1 4692 -1 4693 -1 4694 -1 4695 -1 4696 -1 4697 -1 4698 -1 4699 -1 4700 -1 4701 -1 4702 -1 4703 -1 4704 -1 4705 -1 4706 -1 4707 -1 4708 -1 4709 -1 4710 -1 4711 -1 4712 -1 4713 -1 4714 -1 4715 -1 4716 -1 4717 -1 4718 -1 4719 -1 4720 -1 4721 -1 4722 -1 4723 -1 4724 -1 4725 -1 4726 -1 4727 -1 4728 -1 4729 -1 4730 -1 4731 -1 4732 -1 4733 -1 4734 -1 4735 -1 4736 -1 4737 -1 4738 -1 4739 -1 4740 -1 4741 -1 4742 -1 4743 -1 4744 -1 4745 -1 4746 -1 4747 -1 4748 -1 4749 -1 4750 -1 4751 -1 4752 -1 4753 -1 4754 -1 4755 -1 4756 -1 4757 -1 4758 -1 4759 -1 4760 -1 4761 -1 4762 -1 4763 -1 4764 -1 4765 -1 4766 -1 4767 -1 4768 -1 4769 -1 4770 -1 4771 -1 4772 -1 4773 -1 4774 -1 4775 -1 4776 -1 4777 -1 4778 -1 4779 -1 4780 -1 4781 -1 4782 -1 4783 -1 4784 -1 4785 -1 4786 -1 4787 -1 4788 -1 4789 -1 4790 -1 4791 -1 4792 -1 4793 -1 4794 -1 4795 -1 4796 -1 4797 -1 4798 -1 4799 -1 4800 -1 4801 -1 4802 -1 4803 -1 4804 -1 4805 -1 4806 -1 4807 -1 4808 -1 4809 -1 4810 -1 4811 -1 4812 -1 4813 -1 4814 -1 4815 -1 4816 -1 4817 -1 4818 -1 4819 -1 4820 -1 4821 -1 4822 -1 4823 -1 4824 -1 4825 -1 4826 -1 4827 -1 4828 -1 4829 -1 4830 -1 4831 -1 4832 -1 4833 -1 4834 -1 4835 -1 4836 -1 4837 -1 4838 -1 4839 -1 4840 -1 4841 -1 4842 -1 4843 -1 4844 -1 4845 -1 4846 -1 4847 -1 4848 -1 4849 -1 4850 -1 4851 -1 4852 -1 4853 -1 4854 -1 4855 -1 4856 -1 4857 -1 4858 -1 4859 -1 4860 -1 4861 -1 4862 -1 4863 -1 4864 -1 4865 -1 4866 -1 4867 -1 4868 -1 4869 -1 4870 -1 4871 -1 4872 -1 4873 -1 4874 -1 4875 -1 4876 -1 4877 -1 4878 -1 4879 -1 4880 -1 4881 -1 4882 -1 4883 -1 4884 -1 4885 -1 4886 -1 4887 -1 4888 -1 4889 -1 4890 -1 4891 -1 4892 -1 4893 -1 4894 -1 4895 -1 4896 -1 4897 -1 4898 -1 4899 -1 4900 -1 4901 -1 4902 -1 4903 -1 4904 -1 4905 -1 4906 -1 4907 -1 4908 -1 4909 -1 4910 -1 4911 -1 4912 -1 4913 -1 4914 -1 4915 -1 4916 -1 4917 -1 4918 -1 4919 -1 4920 -1 4921 -1 4922 -1 4923 -1 4924 -1 4925 -1 4926 -1 4927 -1 4928 -1 4929 -1 4930 -1 4931 -1 4932 -1 4933 -1 4934 -1 4935 -1 4936 -1 4937 -1 4938 -1 4939 -1 4940 -1 4941 -1 4942 -1 4943 -1 4944 -1 4945 -1 4946 -1 4947 -1 4948 -1 4949 -1 4950 -1 4951 -1 4952 -1 4953 -1 4954 -1 4955 -1 4956 -1 4957 -1 4958 -1 4959 -1 4960 -1 4961 -1 4962 -1 4963 -1 4964 -1 4965 -1 4966 -1 4967 -1 4968 -1 4969 -1 4970 -1 4971 -1 4972 -1 4973 -1 4974 -1 4975 -1 4976 -1 4977 -1 4978 -1 4979 -1 4980 -1 4981 -1 4982 -1 4983 -1 4984 -1 4985 -1 4986 -1 4987 -1 4988 -1 4989 -1 4990 -1 4991 -1 4992 -1 4993 -1 4994 -1 4995 -1 4996 -1 4997 -1 4998 -1 4999 -1 5000 -1 5001 -1 5002 -1 5003 -1 5004 -1 5005 -1 5006 -1 5007 -1 5008 -1 5009 -1 5010 -1 5011 -1 5012 -1 5013 -1 5014 -1 5015 -1 5016 -1 5017 -1 5018 -1 5019 -1 5020 -1 5021 -1 5022 -1 5023 -1 5024 -1 5025 -1 5026 -1 5027 -1 5028 -1 5029 -1 5030 -1 5031 -1 5032 -1 5033 -1 5034 -1 5035 -1 5036 -1 5037 -1 5038 -1 5039 -1 5040 -1 5041 -1 5042 -1 5043 -1 5044 -1 5045 -1 5046 -1 5047 -1 5048 -1 5049 -1 5050 -1 5051 -1 5052 -1 5053 -1 5054 -1 5055 -1 5056 -1 5057 -1 5058 -1 5059 -1 5060 -1 5061 -1 5062 -1 5063 -1 5064 -1 5065 -1 5066 -1 5067 -1 5068 -1 5069 -1 5070 -1 5071 -1 5072 -1 5073 -1 5074 -1 5075 -1 5076 -1 5077 -1 5078 -1 5079 -1 5080 -1 5081 -1 5082 -1 5083 -1 5084 -1 5085 -1 5086 -1 5087 -1 5088 -1 5089 -1 5090 -1 5091 -1 5092 -1 5093 -1 5094 -1 5095 -1 5096 -1 5097 -1 5098 -1 5099 -1 5100 -1 5101 -1 5102 -1 5103 -1 5104 -1 5105 -1 5106 -1 5107 -1 5108 -1 5109 -1 5110 -1 5111 -1 5112 -1 5113 -1 5114 -1 5115 -1 5116 -1 5117 -1 5118 -1 5119 -1 5120 -1 5121 -1 5122 -1 5123 -1 5124 -1 5125 -1 5126 -1 5127 -1 5128 -1 5129 -1 5130 -1 5131 -1 5132 -1 5133 -1 5134 -1 5135 -1 5136 -1 5137 -1 5138 -1 5139 -1 5140 -1 5141 -1 5142 -1 5143 -1 5144 -1 5145 -1 5146 -1 5147 -1 5148 -1 5149 -1 5150 -1 5151 -1 5152 -1 5153 -1 5154 -1 5155 -1 5156 -1 5157 -1 5158 -1 5159 -1 5160 -1 5161 -1 5162 -1 5163 -1 5164 -1 5165 -1 5166 -1 5167 -1 5168 -1 5169 -1 5170 -1 5171 -1 5172 -1 5173 -1 5174 -1 5175 -1 5176 -1 5177 -1 5178 -1 5179 -1 5180 -1 5181 -1 5182 -1 5183 -1 5184 -1 5185 -1 5186 -1 5187 -1 5188 -1 5189 -1 5190 -1 5191 -1 5192 -1 5193 -1 5194 -1 5195 -1 5196 -1 5197 -1 5198 -1 5199 -1 5200 -1 5201 -1 5202 -1 5203 -1 5204 -1 5205 -1 5206 -1 5207 -1 5208 -1 5209 -1 5210 -1 5211 -1 5212 -1 5213 -1 5214 -1 5215 -1 5216 -1 5217 -1 5218 -1 5219 -1 5220 -1 5221 -1 5222 -1 5223 -1 5224 -1 5225 -1 5226 -1 5227 -1 5228 -1 5229 -1 5230 -1 5231 -1 5232 -1 5233 -1 5234 -1 5235 -1 5236 -1 5237 -1 5238 -1 5239 -1 5240 -1 5241 -1 5242 -1 5243 -1 5244 -1 5245 -1 5246 -1 5247 -1 5248 -1 5249 -1 5250 -1 5251 -1 5252 -1 5253 -1 5254 -1 5255 -1 5256 -1 5257 -1 5258 -1 5259 -1 5260 -1 5261 -1 5262 -1 5263 -1 5264 -1 5265 -1 5266 -1 5267 -1 5268 -1 5269 -1 5270 -1 5271 -1 5272 -1 5273 -1 5274 -1 5275 -1 5276 -1 5277 -1 5278 -1 5279 -1 5280 -1 5281 -1 5282 -1 5283 -1 5284 -1 5285 -1 5286 -1 5287 -1 5288 -1 5289 -1 5290 -1 5291 -1 5292 -1 5293 -1 5294 -1 5295 -1 5296 -1 5297 -1 5298 -1 5299 -1 5300 -1 5301 -1 5302 -1 5303 -1 5304 -1 5305 -1 5306 -1 5307 -1 5308 -1 5309 -1 5310 -1 5311 -1 5312 -1 5313 -1 5314 -1 5315 -1 5316 -1 5317 -1 5318 -1 5319 -1 5320 -1 5321 -1 5322 -1 5323 -1 5324 -1 5325 -1 5326 -1 5327 -1 5328 -1 5329 -1 5330 -1 5331 -1 5332 -1 5333 -1 5334 -1 5335 -1 5336 -1 5337 -1 5338 -1 5339 -1 5340 -1 5341 -1 5342 -1 5343 -1 5344 -1 5345 -1 5346 -1 5347 -1 5348 -1 5349 -1 5350 -1 5351 -1 5352 -1 5353 -1 5354 -1 5355 -1 5356 -1 5357 -1 5358 -1 5359 -1 5360 -1 5361 -1 5362 -1 5363 -1 5364 -1 5365 -1 5366 -1 5367 -1 5368 -1 5369 -1 5370 -1 5371 -1 5372 -1 5373 -1 5374 -1 5375 -1 5376 -1 5377 -1 5378 -1 5379 -1 5380 -1 5381 -1 5382 -1 5383 -1 5384 -1 5385 -1 5386 -1 5387 -1 5388 -1 5389 -1 5390 -1 5391 -1 5392 -1 5393 -1 5394 -1 5395 -1 5396 -1 5397 -1 5398 -1 5399 -1 5400 -1 5401 -1 5402 -1 5403 -1 5404 -1 5405 -1 5406 -1 5407 -1 5408 -1 5409 -1 5410 -1 5411 -1 5412 -1 5413 -1 5414 -1 5415 -1 5416 -1 5417 -1 5418 -1 5419 -1 5420 -1 5421 -1 5422 -1 5423 -1 5424 -1 5425 -1 5426 -1 5427 -1 5428 -1 5429 -1 5430 -1 5431 -1 5432 -1 5433 -1 5434 -1 5435 -1 5436 -1 5437 -1 5438 -1 5439 -1 5440 -1 5441 -1 5442 -1 5443 -1 5444 -1 5445 -1 5446 -1 5447 -1 5448 -1 5449 -1 5450 -1 5451 -1 5452 -1 5453 -1 5454 -1 5455 -1 5456 -1 5457 -1 5458 -1 5459 -1 5460 -1 5461 -1 5462 -1 5463 -1 5464 -1 5465 -1 5466 -1 5467 -1 5468 -1 5469 -1 5470 -1 5471 -1 5472 -1 5473 -1 5474 -1 5475 -1 5476 -1 5477 -1 5478 -1 5479 -1 5480 -1 5481 -1 5482 -1 5483 -1 5484 -1 5485 -1 5486 -1 5487 -1 5488 -1 5489 -1 5490 -1 5491 -1 5492 -1 5493 -1 5494 -1 5495 -1 5496 -1 5497 -1 5498 -1 5499 -1 5500 -1 5501 -1 5502 -1 5503 -1 5504 -1 5505 -1 5506 -1 5507 -1 5508 -1 5509 -1 5510 -1 5511 -1 5512 -1 5513 -1 5514 -1 5515 -1 5516 -1 5517 -1 5518 -1 5519 -1 5520 -1 5521 -1 5522 -1 5523 -1 5524 -1 5525 -1 5526 -1 5527 -1 5528 -1 5529 -1 5530 -1 5531 -1 5532 -1 5533 -1 5534 -1 5535 -1 5536 -1 5537 -1 5538 -1 5539 -1 5540 -1 5541 -1 5542 -1 5543 -1 5544 -1 5545 -1 5546 -1 5547 -1 5548 -1 5549 -1 5550 -1 5551 -1 5552 -1 5553 -1 5554 -1 5555 -1 5556 -1 5557 -1 5558 -1 5559 -1 5560 -1 5561 -1 5562 -1 5563 -1 5564 -1 5565 -1 5566 -1 5567 -1 5568 -1 5569 -1 5570 -1 5571 -1 5572 -1 5573 -1 5574 -1 5575 -1 5576 -1 5577 -1 5578 -1 5579 -1 5580 -1 5581 -1 5582 -1 5583 -1 5584 -1 5585 -1 5586 -1 5587 -1 5588 -1 5589 -1 5590 -1 5591 -1 5592 -1 5593 -1 5594 -1 5595 -1 5596 -1 5597 -1 5598 -1 5599 -1 5600 -1 5601 -1 5602 -1 5603 -1 5604 -1 5605 -1 5606 -1 5607 -1 5608 -1 5609 -1 5610 -1 5611 -1 5612 -1 5613 -1 5614 -1 5615 -1 5616 -1 5617 -1 5618 -1 5619 -1 5620 -1 5621 -1 5622 -1 5623 -1 5624 -1 5625 -1 5626 -1 5627 -1 5628 -1 5629 -1 5630 -1 5631 -1 5632 -1 5633 -1 5634 -1 5635 -1 5636 -1 5637 -1 5638 -1 5639 -1 5640 -1 5641 -1 5642 -1 5643 -1 5644 -1 5645 -1 5646 -1 5647 -1 5648 -1 5649 -1 5650 -1 5651 -1 5652 -1 5653 -1 5654 -1 5655 -1 5656 -1 5657 -1 5658 -1 5659 -1 5660 -1 5661 -1 5662 -1 5663 -1 5664 -1 5665 -1 5666 -1 5667 -1 5668 -1 5669 -1 5670 -1 5671 -1 5672 -1 5673 -1 5674 -1 5675 -1 5676 -1 5677 -1 5678 -1 5679 -1 5680 -1 5681 -1 5682 -1 5683 -1 5684 -1 5685 -1 5686 -1 5687 -1 5688 -1 5689 -1 5690 -1 5691 -1 5692 -1 5693 -1 5694 -1 5695 -1 5696 -1 5697 -1 5698 -1 5699 -1 5700 -1 5701 -1 5702 -1 5703 -1 5704 -1 5705 -1 5706 -1 5707 -1 5708 -1 5709 -1 5710 -1 5711 -1 5712 -1 5713 -1 5714 -1 5715 -1 5716 -1 5717 -1 5718 -1 5719 -1 5720 -1 5721 -1 5722 -1 5723 -1 5724 -1 5725 -1 5726 -1 5727 -1 5728 -1 5729 -1 5730 -1 5731 -1 5732 -1 5733 -1 5734 -1 5735 -1 5736 -1 5737 -1 5738 -1 5739 -1 5740 -1 5741 -1 5742 -1 5743 -1 5744 -1 5745 -1 5746 -1 5747 -1 5748 -1 5749 -1 5750 -1 5751 -1 5752 -1 5753 -1 5754 -1 5755 -1 5756 -1 5757 -1 5758 -1 5759 -1 5760 -1 5761 -1 5762 -1 5763 -1 5764 -1 5765 -1 5766 -1 5767 -1 5768 -1 5769 -1 5770 -1 5771 -1 5772 -1 5773 -1 5774 -1 5775 -1 5776 -1 5777 -1 5778 -1 5779 -1 5780 -1 5781 -1 5782 -1 5783 -1 5784 -1 5785 -1 5786 -1 5787 -1 5788 -1 5789 -1 5790 -1 5791 -1 5792 -1 5793 -1 5794 -1 5795 -1 5796 -1 5797 -1 5798 -1 5799 -1 5800 -1 5801 -1 5802 -1 5803 -1 5804 -1 5805 -1 5806 -1 5807 -1 5808 -1 5809 -1 5810 -1 5811 -1 5812 -1 5813 -1 5814 -1 5815 -1 5816 -1 5817 -1 5818 -1 5819 -1 5820 -1 5821 -1 5822 -1 5823 -1 5824 -1 5825 -1 5826 -1 5827 -1 5828 -1 5829 -1 5830 -1 5831 -1 5832 -1 5833 -1 5834 -1 5835 -1 5836 -1 5837 -1 5838 -1 5839 -1 5840 -1 5841 -1 5842 -1 5843 -1 5844 -1 5845 -1 5846 -1 5847 -1 5848 -1 5849 -1 5850 -1 5851 -1 5852 -1 5853 -1 5854 -1 5855 -1 5856 -1 5857 -1 5858 -1 5859 -1 5860 -1 5861 -1 5862 -1 5863 -1 5864 -1 5865 -1 5866 -1 5867 -1 5868 -1 5869 -1 5870 -1 5871 -1 5872 -1 5873 -1 5874 -1 5875 -1 5876 -1 5877 -1 5878 -1 5879 -1 5880 -1 5881 -1 5882 -1 5883 -1 5884 -1 5885 -1 5886 -1 5887 -1 5888 -1 5889 -1 5890 -1 5891 -1 5892 -1 5893 -1 5894 -1 5895 -1 5896 -1 5897 -1 5898 -1 5899 -1 5900 -1 5901 -1 5902 -1 5903 -1 5904 -1 5905 -1 5906 -1 5907 -1 5908 -1 5909 -1 5910 -1 5911 -1 5912 -1 5913 -1 5914 -1 5915 -1 5916 -1 5917 -1 5918 -1 5919 -1 5920 -1 5921 -1 5922 -1 5923 -1 5924 -1 5925 -1 5926 -1 5927 -1 5928 -1 5929 -1 5930 -1 5931 -1 5932 -1 5933 -1 5934 -1 5935 -1 5936 -1 5937 -1 5938 -1 5939 -1 5940 -1 5941 -1 5942 -1 5943 -1 5944 -1 5945 -1 5946 -1 5947 -1 5948 -1 5949 -1 5950 -1 5951 -1 5952 -1 5953 -1 5954 -1 5955 -1 5956 -1 5957 -1 5958 -1 5959 -1 5960 -1 5961 -1 5962 -1 5963 -1 5964 -1 5965 -1 5966 -1 5967 -1 5968 -1 5969 -1 5970 -1 5971 -1 5972 -1 5973 -1 5974 -1 5975 -1 5976 -1 5977 -1 5978 -1 5979 -1 5980 -1 5981 -1 5982 -1 5983 -1 5984 -1 5985 -1 5986 -1 5987 -1 5988 -1 5989 -1 5990 -1 5991 -1 5992 -1 5993 -1 5994 -1 5995 -1 5996 -1 5997 -1 5998 -1 5999 -1 6000 -1 6001 -1 6002 -1 6003 -1 6004 -1 6005 -1 6006 -1 6007 -1 6008 -1 6009 -1 6010 -1 6011 -1 6012 -1 6013 -1 6014 -1 6015 -1 6016 -1 6017 -1 6018 -1 6019 -1 6020 -1 6021 -1 6022 -1 6023 -1 6024 -1 6025 -1 6026 -1 6027 -1 6028 -1 6029 -1 6030 -1 6031 -1 6032 -1 6033 -1 6034 -1 6035 -1 6036 -1 6037 -1 6038 -1 6039 -1 6040 -1 6041 -1 6042 -1 6043 -1 6044 -1 6045 -1 6046 -1 6047 -1 6048 -1 6049 -1 6050 -1 6051 -1 6052 -1 6053 -1 6054 -1 6055 -1 6056 -1 6057 -1 6058 -1 6059 -1 6060 -1 6061 -1 6062 -1 6063 -1 6064 -1 6065 -1 6066 -1 6067 -1 6068 -1 6069 -1 6070 -1 6071 -1 6072 -1 6073 -1 6074 -1 6075 -1 6076 -1 6077 -1 6078 -1 6079 -1 6080 -1 6081 -1 6082 -1 6083 -1 6084 -1 6085 -1 6086 -1 6087 -1 6088 -1 6089 -1 6090 -1 6091 -1 6092 -1 6093 -1 6094 -1 6095 -1 6096 -1 6097 -1 6098 -1 6099 -1 6100 -1 6101 -1 6102 -1 6103 -1 6104 -1 6105 -1 6106 -1 6107 -1 6108 -1 6109 -1 6110 -1 6111 -1 6112 -1 6113 -1 6114 -1 6115 -1 6116 -1 6117 -1 6118 -1 6119 -1 6120 -1 6121 -1 6122 -1 6123 -1 6124 -1 6125 -1 6126 -1 6127 -1 6128 -1 6129 -1 6130 -1 6131 -1 6132 -1 6133 -1 6134 -1 6135 -1 6136 -1 6137 -1 6138 -1 6139 -1 6140 -1 6141 -1 6142 -1 6143 -1 6144 -1 6145 -1 6146 -1 6147 -1 6148 -1 6149 -1 6150 -1 6151 -1 6152 -1 6153 -1 6154 -1 6155 -1 6156 -1 6157 -1 6158 -1 6159 -1 6160 -1 6161 -1 6162 -1 6163 -1 6164 -1 6165 -1 6166 -1 6167 -1 6168 -1 6169 -1 6170 -1 6171 -1 6172 -1 6173 -1 6174 -1 6175 -1 6176 -1 6177 -1 6178 -1 6179 -1 6180 -1 6181 -1 6182 -1 6183 -1 6184 -1 6185 -1 6186 -1 6187 -1 6188 -1 6189 -1 6190 -1 6191 -1 6192 -1 6193 -1 6194 -1 6195 -1 6196 -1 6197 -1 6198 -1 6199 -1 6200 -1 6201 -1 6202 -1 6203 -1 6204 -1 6205 -1 6206 -1 6207 -1 6208 -1 6209 -1 6210 -1 6211 -1 6212 -1 6213 -1 6214 -1 6215 -1 6216 -1 6217 -1 6218 -1 6219 -1 6220 -1 6221 -1 6222 -1 6223 -1 6224 -1 6225 -1 6226 -1 6227 -1 6228 -1 6229 -1 6230 -1 6231 -1 6232 -1 6233 -1 6234 -1 6235 -1 6236 -1 6237 -1 6238 -1 6239 -1 6240 -1 6241 -1 6242 -1 6243 -1 6244 -1 6245 -1 6246 -1 6247 -1 6248 -1 6249 -1 6250 -1 6251 -1 6252 -1 6253 -1 6254 -1 6255 -1 6256 -1 6257 -1 6258 -1 6259 -1 6260 -1 6261 -1 6262 -1 6263 -1 6264 -1 6265 -1 6266 -1 6267 -1 6268 -1 6269 -1 6270 -1 6271 -1 6272 -1 6273 -1 6274 -1 6275 -1 6276 -1 6277 -1 6278 -1 6279 -1 6280 -1 6281 -1 6282 -1 6283 -1 6284 -1 6285 -1 6286 -1 6287 -1 6288 -1 6289 -1 6290 -1 6291 -1 6292 -1 6293 -1 6294 -1 6295 -1 6296 -1 6297 -1 6298 -1 6299 -1 6300 -1 6301 -1 6302 -1 6303 -1 6304 -1 6305 -1 6306 -1 6307 -1 6308 -1 6309 -1 6310 -1 6311 -1 6312 -1 6313 -1 6314 -1 6315 -1 6316 -1 6317 -1 6318 -1 6319 -1 6320 -1 6321 -1 6322 -1 6323 -1 6324 -1 6325 -1 6326 -1 6327 -1 6328 -1 6329 -1 6330 -1 6331 -1 6332 -1 6333 -1 6334 -1 6335 -1 6336 -1 6337 -1 6338 -1 6339 -1 6340 -1 6341 -1 6342 -1 6343 -1 6344 -1 6345 -1 6346 -1 6347 -1 6348 -1 6349 -1 6350 -1 6351 -1 6352 -1 6353 -1 6354 -1 6355 -1 6356 -1 6357 -1 6358 -1 6359 -1 6360 -1 6361 -1 6362 -1 6363 -1 6364 -1 6365 -1 6366 -1 6367 -1 6368 -1 6369 -1 6370 -1 6371 -1 6372 -1 6373 -1 6374 -1 6375 -1 6376 -1 6377 -1 6378 -1 6379 -1 6380 -1 6381 -1 6382 -1 6383 -1 6384 -1 6385 -1 6386 -1 6387 -1 6388 -1 6389 -1 6390 -1 6391 -1 6392 -1 6393 -1 6394 -1 6395 -1 6396 -1 6397 -1 6398 -1 6399 -1 6400 -1 6401 -1 6402 -1 6403 -1 6404 -1 6405 -1 6406 -1 6407 -1 6408 -1 6409 -1 6410 -1 6411 -1 6412 -1 6413 -1 6414 -1 6415 -1 6416 -1 6417 -1 6418 -1 6419 -1 6420 -1 6421 -1 6422 -1 6423 -1 6424 -1 6425 -1 6426 -1 6427 -1 6428 -1 6429 -1 6430 -1 6431 -1 6432 -1 6433 -1 6434 -1 6435 -1 6436 -1 6437 -1 6438 -1 6439 -1 6440 -1 6441 -1 6442 -1 6443 -1 6444 -1 6445 -1 6446 -1 6447 -1 6448 -1 6449 -1 6450 -1 6451 -1 6452 -1 6453 -1 6454 -1 6455 -1 6456 -1 6457 -1 6458 -1 6459 -1 6460 -1 6461 -1 6462 -1 6463 -1 6464 -1 6465 -1 6466 -1 6467 -1 6468 -1 6469 -1 6470 -1 6471 -1 6472 -1 6473 -1 6474 -1 6475 -1 6476 -1 6477 -1 6478 -1 6479 -1 6480 -1 6481 -1 6482 -1 6483 -1 6484 -1 6485 -1 6486 -1 6487 -1 6488 -1 6489 -1 6490 -1 6491 -1 6492 -1 6493 -1 6494 -1 6495 -1 6496 -1 6497 -1 6498 -1 6499 -1 6500 -1 6501 -1 6502 -1 6503 -1 6504 -1 6505 -1 6506 -1 6507 -1 6508 -1 6509 -1 6510 -1 6511 -1 6512 -1 6513 -1 6514 -1 6515 -1 6516 -1 6517 -1 6518 -1 6519 -1 6520 -1 6521 -1 6522 -1 6523 -1 6524 -1 6525 -1 6526 -1 6527 -1 6528 -1 6529 -1 6530 -1 6531 -1 6532 -1 6533 -1 6534 -1 6535 -1 6536 -1 6537 -1 6538 -1 6539 -1 6540 -1 6541 -1 6542 -1 6543 -1 6544 -1 6545 -1 6546 -1 6547 -1 6548 -1 6549 -1 6550 -1 6551 -1 6552 -1 6553 -1 6554 -1 6555 -1 6556 -1 6557 -1 6558 -1 6559 -1 6560 -1 6561 -1 6562 -1 6563 -1 6564 -1 6565 -1 6566 -1 6567 -1 6568 -1 6569 -1 6570 -1 6571 -1 6572 -1 6573 -1 6574 -1 6575 -1 6576 -1 6577 -1 6578 -1 6579 -1 6580 -1 6581 -1 6582 -1 6583 -1 6584 -1 6585 -1 6586 -1 6587 -1 6588 -1 6589 -1 6590 -1 6591 -1 6592 -1 6593 -1 6594 -1 6595 -1 6596 -1 6597 -1 6598 -1 6599 -1 6600 -1 6601 -1 6602 -1 6603 -1 6604 -1 6605 -1 6606 -1 6607 -1 6608 -1 6609 -1 6610 -1 6611 -1 6612 -1 6613 -1 6614 -1 6615 -1 6616 -1 6617 -1 6618 -1 6619 -1 6620 -1 6621 -1 6622 -1 6623 -1 6624 -1 6625 -1 6626 -1 6627 -1 6628 -1 6629 -1 6630 -1 6631 -1 6632 -1 6633 -1 6634 -1 6635 -1 6636 -1 6637 -1 6638 -1 6639 -1 6640 -1 6641 -1 6642 -1 6643 -1 6644 -1 6645 -1 6646 -1 6647 -1 6648 -1 6649 -1 6650 -1 6651 -1 6652 -1 6653 -1 6654 -1 6655 -1 6656 -1 6657 -1 6658 -1 6659 -1 6660 -1 6661 -1 6662 -1 6663 -1 6664 -1 6665 -1 6666 -1 6667 -1 6668 -1 6669 -1 6670 -1 6671 -1 6672 -1 6673 -1 6674 -1 6675 -1 6676 -1 6677 -1 6678 -1 6679 -1 6680 -1 6681 -1 6682 -1 6683 -1 6684 -1 6685 -1 6686 -1 6687 -1 6688 -1 6689 -1 6690 -1 6691 -1 6692 -1 6693 -1 6694 -1 6695 -1 6696 -1 6697 -1 6698 -1 6699 -1 6700 -1 6701 -1 6702 -1 6703 -1 6704 -1 6705 -1 6706 -1 6707 -1 6708 -1 6709 -1 6710 -1 6711 -1 6712 -1 6713 -1 6714 -1 6715 -1 6716 -1 6717 -1 6718 -1 6719 -1 6720 -1 6721 -1 6722 -1 6723 -1 6724 -1 6725 -1 6726 -1 6727 -1 6728 -1 6729 -1 6730 -1 6731 -1 6732 -1 6733 -1 6734 -1 6735 -1 6736 -1 6737 -1 6738 -1 6739 -1 6740 -1 6741 -1 6742 -1 6743 -1 6744 -1 6745 -1 6746 -1 6747 -1 6748 -1 6749 -1 6750 -1 6751 -1 6752 -1 6753 -1 6754 -1 6755 -1 6756 -1 6757 -1 6758 -1 6759 -1 6760 -1 6761 -1 6762 -1 6763 -1 6764 -1 6765 -1 6766 -1 6767 -1 6768 -1 6769 -1 6770 -1 6771 -1 6772 -1 6773 -1 6774 -1 6775 -1 6776 -1 6777 -1 6778 -1 6779 -1 6780 -1 6781 -1 6782 -1 6783 -1 6784 -1 6785 -1 6786 -1 6787 -1 6788 -1 6789 -1 6790 -1 6791 -1 6792 -1 6793 -1 6794 -1 6795 -1 6796 -1 6797 -1 6798 -1 6799 -1 6800 -1 6801 -1 6802 -1 6803 -1 6804 -1 6805 -1 6806 -1 6807 -1 6808 -1 6809 -1 6810 -1 6811 -1 6812 -1 6813 -1 6814 -1 6815 -1 6816 -1 6817 -1 6818 -1 6819 -1 6820 -1 6821 -1 6822 -1 6823 -1 6824 -1 6825 -1 6826 -1 6827 -1 6828 -1 6829 -1 6830 -1 6831 -1 6832 -1 6833 -1 6834 -1 6835 -1 6836 -1 6837 -1 6838 -1 6839 -1 6840 -1 6841 -1 6842 -1 6843 -1 6844 -1 6845 -1 6846 -1 6847 -1 6848 -1 6849 -1 6850 -1 6851 -1 6852 -1 6853 -1 6854 -1 6855 -1 6856 -1 6857 -1 6858 -1 6859 -1 6860 -1 6861 -1 6862 -1 6863 -1 6864 -1 6865 -1 6866 -1 6867 -1 6868 -1 6869 -1 6870 -1 6871 -1 6872 -1 6873 -1 6874 -1 6875 -1 6876 -1 6877 -1 6878 -1 6879 -1 6880 -1 6881 -1 6882 -1 6883 -1 6884 -1 6885 -1 6886 -1 6887 -1 6888 -1 6889 -1 6890 -1 6891 -1 6892 -1 6893 -1 6894 -1 6895 -1 6896 -1 6897 -1 6898 -1 6899 -1 6900 -1 6901 -1 6902 -1 6903 -1 6904 -1 6905 -1 6906 -1 6907 -1 6908 -1 6909 -1 6910 -1 6911 -1 6912 -1 6913 -1 6914 -1 6915 -1 6916 -1 6917 -1 6918 -1 6919 -1 6920 -1 6921 -1 6922 -1 6923 -1 6924 -1 6925 -1 6926 -1 6927 -1 6928 -1 6929 -1 6930 -1 6931 -1 6932 -1 6933 -1 6934 -1 6935 -1 6936 -1 6937 -1 6938 -1 6939 -1 6940 -1 6941 -1 6942 -1 6943 -1 6944 -1 6945 -1 6946 -1 6947 -1 6948 -1 6949 -1 6950 -1 6951 -1 6952 -1 6953 -1 6954 -1 6955 -1 6956 -1 6957 -1 6958 -1 6959 -1 6960 -1 6961 -1 6962 -1 6963 -1 6964 -1 6965 -1 6966 -1 6967 -1 6968 -1 6969 -1 6970 -1 6971 -1 6972 -1 6973 -1 6974 -1 6975 -1 6976 -1 6977 -1 6978 -1 6979 -1 6980 -1 6981 -1 6982 -1 6983 -1 6984 -1 6985 -1 6986 -1 6987 -1 6988 -1 6989 -1 6990 -1 6991 -1 6992 -1 6993 -1 6994 -1 6995 -1 6996 -1 6997 -1 6998 -1 6999 -1 7000 -1 7001 -1 7002 -1 7003 -1 7004 -1 7005 -1 7006 -1 7007 -1 7008 -1 7009 -1 7010 -1 7011 -1 7012 -1 7013 -1 7014 -1 7015 -1 7016 -1 7017 -1 7018 -1 7019 -1 7020 -1 7021 -1 7022 -1 7023 -1 7024 -1 7025 -1 7026 -1 7027 -1 7028 -1 7029 -1 7030 -1 7031 -1 7032 -1 7033 -1 7034 -1 7035 -1 7036 -1 7037 -1 7038 -1 7039 -1 7040 -1 7041 -1 7042 -1 7043 -1 7044 -1 7045 -1 7046 -1 7047 -1 7048 -1 7049 -1 7050 -1 7051 -1 7052 -1 7053 -1 7054 -1 7055 -1 7056 -1 7057 -1 7058 -1 7059 -1 7060 -1 7061 -1 7062 -1 7063 -1 7064 -1 7065 -1 7066 -1 7067 -1 7068 -1 7069 -1 7070 -1 7071 -1 7072 -1 7073 -1 7074 -1 7075 -1 7076 -1 7077 -1 7078 -1 7079 -1 7080 -1 7081 -1 7082 -1 7083 -1 7084 -1 7085 -1 7086 -1 7087 -1 7088 -1 7089 -1 7090 -1 7091 -1 7092 -1 7093 -1 7094 -1 7095 -1 7096 -1 7097 -1 7098 -1 7099 -1 7100 -1 7101 -1 7102 -1 7103 -1 7104 -1 7105 -1 7106 -1 7107 -1 7108 -1 7109 -1 7110 -1 7111 -1 7112 -1 7113 -1 7114 -1 7115 -1 7116 -1 7117 -1 7118 -1 7119 -1 7120 -1 7121 -1 7122 -1 7123 -1 7124 -1 7125 -1 7126 -1 7127 -1 7128 -1 7129 -1 7130 -1 7131 -1 7132 -1 7133 -1 7134 -1 7135 -1 7136 -1 7137 -1 7138 -1 7139 -1 7140 -1 7141 -1 7142 -1 7143 -1 7144 -1 7145 -1 7146 -1 7147 -1 7148 -1 7149 -1 7150 -1 7151 -1 7152 -1 7153 -1 7154 -1 7155 -1 7156 -1 7157 -1 7158 -1 7159 -1 7160 -1 7161 -1 7162 -1 7163 -1 7164 -1 7165 -1 7166 -1 7167 -1 7168 -1 7169 -1 7170 -1 7171 -1 7172 -1 7173 -1 7174 -1 7175 -1 7176 -1 7177 -1 7178 -1 7179 -1 7180 -1 7181 -1 7182 -1 7183 -1 7184 -1 7185 -1 7186 -1 7187 -1 7188 -1 7189 -1 7190 -1 7191 -1 7192 -1 7193 -1 7194 -1 7195 -1 7196 -1 7197 -1 7198 -1 7199 -1 7200 -1 7201 -1 7202 -1 7203 -1 7204 -1 7205 -1 7206 -1 7207 -1 7208 -1 7209 -1 7210 -1 7211 -1 7212 -1 7213 -1 7214 -1 7215 -1 7216 -1 7217 -1 7218 -1 7219 -1 7220 -1 7221 -1 7222 -1 7223 -1 7224 -1 7225 -1 7226 -1 7227 -1 7228 -1 7229 -1 7230 -1 7231 -1 7232 -1 7233 -1 7234 -1 7235 -1 7236 -1 7237 -1 7238 -1 7239 -1 7240 -1 7241 -1 7242 -1 7243 -1 7244 -1 7245 -1 7246 -1 7247 -1 7248 -1 7249 -1 7250 -1 7251 -1 7252 -1 7253 -1 7254 -1 7255 -1 7256 -1 7257 -1 7258 -1 7259 -1 7260 -1 7261 -1 7262 -1 7263 -1 7264 -1 7265 -1 7266 -1 7267 -1 7268 -1 7269 -1 7270 -1 7271 -1 7272 -1 7273 -1 7274 -1 7275 -1 7276 -1 7277 -1 7278 -1 7279 -1 7280 -1 7281 -1 7282 -1 7283 -1 7284 -1 7285 -1 7286 -1 7287 -1 7288 -1 7289 -1 7290 -1 7291 -1 7292 -1 7293 -1 7294 -1 7295 -1 7296 -1 7297 -1 7298 -1 7299 -1 7300 -1 7301 -1 7302 -1 7303 -1 7304 -1 7305 -1 7306 -1 7307 -1 7308 -1 7309 -1 7310 -1 7311 -1 7312 -1 7313 -1 7314 -1 7315 -1 7316 -1 7317 -1 7318 -1 7319 -1 7320 -1 7321 -1 7322 -1 7323 -1 7324 -1 7325 -1 7326 -1 7327 -1 7328 -1 7329 -1 7330 -1 7331 -1 7332 -1 7333 -1 7334 -1 7335 -1 7336 -1 7337 -1 7338 -1 7339 -1 7340 -1 7341 -1 7342 -1 7343 -1 7344 -1 7345 -1 7346 -1 7347 -1 7348 -1 7349 -1 7350 -1 7351 -1 7352 -1 7353 -1 7354 -1 7355 -1 7356 -1 7357 -1 7358 -1 7359 -1 7360 -1 7361 -1 7362 -1 7363 -1 7364 -1 7365 -1 7366 -1 7367 -1 7368 -1 7369 -1 7370 -1 7371 -1 7372 -1 7373 -1 7374 -1 7375 -1 7376 -1 7377 -1 7378 -1 7379 -1 7380 -1 7381 -1 7382 -1 7383 -1 7384 -1 7385 -1 7386 -1 7387 -1 7388 -1 7389 -1 7390 -1 7391 -1 7392 -1 7393 -1 7394 -1 7395 -1 7396 -1 7397 -1 7398 -1 7399 -1 7400 -1 7401 -1 7402 -1 7403 -1 7404 -1 7405 -1 7406 -1 7407 -1 7408 -1 7409 -1 7410 -1 7411 -1 7412 -1 7413 -1 7414 -1 7415 -1 7416 -1 7417 -1 7418 -1 7419 -1 7420 -1 7421 -1 7422 -1 7423 -1 7424 -1 7425 -1 7426 -1 7427 -1 7428 -1 7429 -1 7430 -1 7431 -1 7432 -1 7433 -1 7434 -1 7435 -1 7436 -1 7437 -1 7438 -1 7439 -1 7440 -1 7441 -1 7442 -1 7443 -1 7444 -1 7445 -1 7446 -1 7447 -1 7448 -1 7449 -1 7450 -1 7451 -1 7452 -1 7453 -1 7454 -1 7455 -1 7456 -1 7457 -1 7458 -1 7459 -1 7460 -1 7461 -1 7462 -1 7463 -1 7464 -1 7465 -1 7466 -1 7467 -1 7468 -1 7469 -1 7470 -1 7471 -1 7472 -1 7473 -1 7474 -1 7475 -1 7476 -1 7477 -1 7478 -1 7479 -1 7480 -1 7481 -1 7482 -1 7483 -1 7484 -1 7485 -1 7486 -1 7487 -1 7488 -1 7489 -1 7490 -1 7491 -1 7492 -1 7493 -1 7494 -1 7495 -1 7496 -1 7497 -1 7498 -1 7499 -1 7500 -1 7501 -1 7502 -1 7503 -1 7504 -1 7505 -1 7506 -1 7507 -1 7508 -1 7509 -1 7510 -1 7511 -1 7512 -1 7513 -1 7514 -1 7515 -1 7516 -1 7517 -1 7518 -1 7519 -1 7520 -1 7521 -1 7522 -1 7523 -1 7524 -1 7525 -1 7526 -1 7527 -1 7528 -1 7529 -1 7530 -1 7531 -1 7532 -1 7533 -1 7534 -1 7535 -1 7536 -1 7537 -1 7538 -1 7539 -1 7540 -1 7541 -1 7542 -1 7543 -1 7544 -1 7545 -1 7546 -1 7547 -1 7548 -1 7549 -1 7550 -1 7551 -1 7552 -1 7553 -1 7554 -1 7555 -1 7556 -1 7557 -1 7558 -1 7559 -1 7560 -1 7561 -1 7562 -1 7563 -1 7564 -1 7565 -1 7566 -1 7567 -1 7568 -1 7569 -1 7570 -1 7571 -1 7572 -1 7573 -1 7574 -1 7575 -1 7576 -1 7577 -1 7578 -1 7579 -1 7580 -1 7581 -1 7582 -1 7583 -1 7584 -1 7585 -1 7586 -1 7587 -1 7588 -1 7589 -1 7590 -1 7591 -1 7592 -1 7593 -1 7594 -1 7595 -1 7596 -1 7597 -1 7598 -1 7599 -1 7600 -1 7601 -1 7602 -1 7603 -1 7604 -1 7605 -1 7606 -1 7607 -1 7608 -1 7609 -1 7610 -1 7611 -1 7612 -1 7613 -1 7614 -1 7615 -1 7616 -1 7617 -1 7618 -1 7619 -1 7620 -1 7621 -1 7622 -1 7623 -1 7624 -1 7625 -1 7626 -1 7627 -1 7628 -1 7629 -1 7630 -1 7631 -1 7632 -1 7633 -1 7634 -1 7635 -1 7636 -1 7637 -1 7638 -1 7639 -1 7640 -1 7641 -1 7642 -1 7643 -1 7644 -1 7645 -1 7646 -1 7647 -1 7648 -1 7649 -1 7650 -1 7651 -1 7652 -1 7653 -1 7654 -1 7655 -1 7656 -1 7657 -1 7658 -1 7659 -1 7660 -1 7661 -1 7662 -1 7663 -1 7664 -1 7665 -1 7666 -1 7667 -1 7668 -1 7669 -1 7670 -1 7671 -1 7672 -1 7673 -1 7674 -1 7675 -1 7676 -1 7677 -1 7678 -1 7679 -1 7680 -1 7681 -1 7682 -1 7683 -1 7684 -1 7685 -1 7686 -1 7687 -1 7688 -1 7689 -1 7690 -1 7691 -1 7692 -1 7693 -1 7694 -1 7695 -1 7696 -1 7697 -1 7698 -1 7699 -1 7700 -1 7701 -1 7702 -1 7703 -1 7704 -1 7705 -1 7706 -1 7707 -1 7708 -1 7709 -1 7710 -1 7711 -1 7712 -1 7713 -1 7714 -1 7715 -1 7716 -1 7717 -1 7718 -1 7719 -1 7720 -1 7721 -1 7722 -1 7723 -1 7724 -1 7725 -1 7726 -1 7727 -1 7728 -1 7729 -1 7730 -1 7731 -1 7732 -1 7733 -1 7734 -1 7735 -1 7736 -1 7737 -1 7738 -1 7739 -1 7740 -1 7741 -1 7742 -1 7743 -1 7744 -1 7745 -1 7746 -1 7747 -1 7748 -1 7749 -1 7750 -1 7751 -1 7752 -1 7753 -1 7754 -1 7755 -1 7756 -1 7757 -1 7758 -1 7759 -1 7760 -1 7761 -1 7762 -1 7763 -1 7764 -1 7765 -1 7766 -1 7767 -1 7768 -1 7769 -1 7770 -1 7771 -1 7772 -1 7773 -1 7774 -1 7775 -1 7776 -1 7777 -1 7778 -1 7779 -1 7780 -1 7781 -1 7782 -1 7783 -1 7784 -1 7785 -1 7786 -1 7787 -1 7788 -1 7789 -1 7790 -1 7791 -1 7792 -1 7793 -1 7794 -1 7795 -1 7796 -1 7797 -1 7798 -1 7799 -1 7800 -1 7801 -1 7802 -1 7803 -1 7804 -1 7805 -1 7806 -1 7807 -1 7808 -1 7809 -1 7810 -1 7811 -1 7812 -1 7813 -1 7814 -1 7815 -1 7816 -1 7817 -1 7818 -1 7819 -1 7820 -1 7821 -1 7822 -1 7823 -1 7824 -1 7825 -1 7826 -1 7827 -1 7828 -1 7829 -1 7830 -1 7831 -1 7832 -1 7833 -1 7834 -1 7835 -1 7836 -1 7837 -1 7838 -1 7839 -1 7840 -1 7841 -1 7842 -1 7843 -1 7844 -1 7845 -1 7846 -1 7847 -1 7848 -1 7849 -1 7850 -1 7851 -1 7852 -1 7853 -1 7854 -1 7855 -1 7856 -1 7857 -1 7858 -1 7859 -1 7860 -1 7861 -1 7862 -1 7863 -1 7864 -1 7865 -1 7866 -1 7867 -1 7868 -1 7869 -1 7870 -1 7871 -1 7872 -1 7873 -1 7874 -1 7875 -1 7876 -1 7877 -1 7878 -1 7879 -1 7880 -1 7881 -1 7882 -1 7883 -1 7884 -1 7885 -1 7886 -1 7887 -1 7888 -1 7889 -1 7890 -1 7891 -1 7892 -1 7893 -1 7894 -1 7895 -1 7896 -1 7897 -1 7898 -1 7899 -1 7900 -1 7901 -1 7902 -1 7903 -1 7904 -1 7905 -1 7906 -1 7907 -1 7908 -1 7909 -1 7910 -1 7911 -1 7912 -1 7913 -1 7914 -1 7915 -1 7916 -1 7917 -1 7918 -1 7919 -1 7920 -1 7921 -1 7922 -1 7923 -1 7924 -1 7925 -1 7926 -1 7927 -1 7928 -1 7929 -1 7930 -1 7931 -1 7932 -1 7933 -1 7934 -1 7935 -1 7936 -1 7937 -1 7938 -1 7939 -1 7940 -1 7941 -1 7942 -1 7943 -1 7944 -1 7945 -1 7946 -1 7947 -1 7948 -1 7949 -1 7950 -1 7951 -1 7952 -1 7953 -1 7954 -1 7955 -1 7956 -1 7957 -1 7958 -1 7959 -1 7960 -1 7961 -1 7962 -1 7963 -1 7964 -1 7965 -1 7966 -1 7967 -1 7968 -1 7969 -1 7970 -1 7971 -1 7972 -1 7973 -1 7974 -1 7975 -1 7976 -1 7977 -1 7978 -1 7979 -1 7980 -1 7981 -1 7982 -1 7983 -1 7984 -1 7985 -1 7986 -1 7987 -1 7988 -1 7989 -1 7990 -1 7991 -1 7992 -1 7993 -1 7994 -1 7995 -1 7996 -1 7997 -1 7998 -1 7999 -1 8000 -1 8001 -1 8002 -1 8003 -1 8004 -1 8005 -1 8006 -1 8007 -1 8008 -1 8009 -1 8010 -1 8011 -1 8012 -1 8013 -1 8014 -1 8015 -1 8016 -1 8017 -1 8018 -1 8019 -1 8020 -1 8021 -1 8022 -1 8023 -1 8024 -1 8025 -1 8026 -1 8027 -1 8028 -1 8029 -1 8030 -1 8031 -1 8032 -1 8033 -1 8034 -1 8035 -1 8036 -1 8037 -1 8038 -1 8039 -1 8040 -1 8041 -1 8042 -1 8043 -1 8044 -1 8045 -1 8046 -1 8047 -1 8048 -1 8049 -1 8050 -1 8051 -1 8052 -1 8053 -1 8054 -1 8055 -1 8056 -1 8057 -1 8058 -1 8059 -1 8060 -1 8061 -1 8062 -1 8063 -1 8064 -1 8065 -1 8066 -1 8067 -1 8068 -1 8069 -1 8070 -1 8071 -1 8072 -1 8073 -1 8074 -1 8075 -1 8076 -1 8077 -1 8078 -1 8079 -1 8080 -1 8081 -1 8082 -1 8083 -1 8084 -1 8085 -1 8086 -1 8087 -1 8088 -1 8089 -1 8090 -1 8091 -1 8092 -1 8093 -1 8094 -1 8095 -1 8096 -1 8097 -1 8098 -1 8099 -1 8100 -1 8101 -1 8102 -1 8103 -1 8104 -1 8105 -1 8106 -1 8107 -1 8108 -1 8109 -1 8110 -1 8111 -1 8112 -1 8113 -1 8114 -1 8115 -1 8116 -1 8117 -1 8118 -1 8119 -1 8120 -1 8121 -1 8122 -1 8123 -1 8124 -1 8125 -1 8126 -1 8127 -1 8128 -1 8129 -1 8130 -1 8131 -1 8132 -1 8133 -1 8134 -1 8135 -1 8136 -1 8137 -1 8138 -1 8139 -1 8140 -1 8141 -1 8142 -1 8143 -1 8144 -1 8145 -1 8146 -1 8147 -1 8148 -1 8149 -1 8150 -1 8151 -1 8152 -1 8153 -1 8154 -1 8155 -1 8156 -1 8157 -1 8158 -1 8159 -1 8160 -1 8161 -1 8162 -1 8163 -1 8164 -1 8165 -1 8166 -1 8167 -1 8168 -1 8169 -1 8170 -1 8171 -1 8172 -1 8173 -1 8174 -1 8175 -1 8176 -1 8177 -1 8178 -1 8179 -1 8180 -1 8181 -1 8182 -1 8183 -1 8184 -1 8185 -1 8186 -1 8187 -1 8188 -1 8189 -1 8190 -1 8191 -1 8192 -1 8193 -1 8194 -1 8195 -1 8196 -1 8197 -1 8198 -1 8199 -1 8200 -1 8201 -1 8202 -1 8203 -1 8204 -1 8205 -1 8206 -1 8207 -1 8208 -1 8209 -1 8210 -1 8211 -1 8212 -1 8213 -1 8214 -1 8215 -1 8216 -1 8217 -1 8218 -1 8219 -1 8220 -1 8221 -1 8222 -1 8223 -1 8224 -1 8225 -1 8226 -1 8227 -1 8228 -1 8229 -1 8230 -1 8231 -1 8232 -1 8233 -1 8234 -1 8235 -1 8236 -1 8237 -1 8238 -1 8239 -1 8240 -1 8241 -1 8242 -1 8243 -1 8244 -1 8245 -1 8246 -1 8247 -1 8248 -1 8249 -1 8250 -1 8251 -1 8252 -1 8253 -1 8254 -1 8255 -1 8256 -1 8257 -1 8258 -1 8259 -1 8260 -1 8261 -1 8262 -1 8263 -1 8264 -1 8265 -1 8266 -1 8267 -1 8268 -1 8269 -1 8270 -1 8271 -1 8272 -1 8273 -1 8274 -1 8275 -1 8276 -1 8277 -1 8278 -1 8279 -1 8280 -1 8281 -1 8282 -1 8283 -1 8284 -1 8285 -1 8286 -1 8287 -1 8288 -1 8289 -1 8290 -1 8291 -1 8292 -1 8293 -1 8294 -1 8295 -1 8296 -1 8297 -1 8298 -1 8299 -1 8300 -1 8301 -1 8302 -1 8303 -1 8304 -1 8305 -1 8306 -1 8307 -1 8308 -1 8309 -1 8310 -1 8311 -1 8312 -1 8313 -1 8314 -1 8315 -1 8316 -1 8317 -1 8318 -1 8319 -1 8320 -1 8321 -1 8322 -1 8323 -1 8324 -1 8325 -1 8326 -1 8327 -1 8328 -1 8329 -1 8330 -1 8331 -1 8332 -1 8333 -1 8334 -1 8335 -1 8336 -1 8337 -1 8338 -1 8339 -1 8340 -1 8341 -1 8342 -1 8343 -1 8344 -1 8345 -1 8346 -1 8347 -1 8348 -1 8349 -1 8350 -1 8351 -1 8352 -1 8353 -1 8354 -1 8355 -1 8356 -1 8357 -1 8358 -1 8359 -1 8360 -1 8361 -1 8362 -1 8363 -1 8364 -1 8365 -1 8366 -1 8367 -1 8368 -1 8369 -1 8370 -1 8371 -1 8372 -1 8373 -1 8374 -1 8375 -1 8376 -1 8377 -1 8378 -1 8379 -1 8380 -1 8381 -1 8382 -1 8383 -1 8384 -1 8385 -1 8386 -1 8387 -1 8388 -1 8389 -1 8390 -1 8391 -1 8392 -1 8393 -1 8394 -1 8395 -1 8396 -1 8397 -1 8398 -1 8399 -1 8400 -1 8401 -1 8402 -1 8403 -1 8404 -1 8405 -1 8406 -1 8407 -1 8408 -1 8409 -1 8410 -1 8411 -1 8412 -1 8413 -1 8414 -1 8415 -1 8416 -1 8417 -1 8418 -1 8419 -1 8420 -1 8421 -1 8422 -1 8423 -1 8424 -1 8425 -1 8426 -1 8427 -1 8428 -1 8429 -1 8430 -1 8431 -1 8432 -1 8433 -1 8434 -1 8435 -1 8436 -1 8437 -1 8438 -1 8439 -1 8440 -1 8441 -1 8442 -1 8443 -1 8444 -1 8445 -1 8446 -1 8447 -1 8448 -1 8449 -1 8450 -1 8451 -1 8452 -1 8453 -1 8454 -1 8455 -1 8456 -1 8457 -1 8458 -1 8459 -1 8460 -1 8461 -1 8462 -1 8463 -1 8464 -1 8465 -1 8466 -1 8467 -1 8468 -1 8469 -1 8470 -1 8471 -1 8472 -1 8473 -1 8474 -1 8475 -1 8476 -1 8477 -1 8478 -1 8479 -1 8480 -1 8481 -1 8482 -1 8483 -1 8484 -1 8485 -1 8486 -1 8487 -1 8488 -1 8489 -1 8490 -1 8491 -1 8492 -1 8493 -1 8494 -1 8495 -1 8496 -1 8497 -1 8498 -1 8499 -1 8500 -1 8501 -1 8502 -1 8503 -1 8504 -1 8505 -1 8506 -1 8507 -1 8508 -1 8509 -1 8510 -1 8511 -1 8512 -1 8513 -1 8514 -1 8515 -1 8516 -1 8517 -1 8518 -1 8519 -1 8520 -1 8521 -1 8522 -1 8523 -1 8524 -1 8525 -1 8526 -1 8527 -1 8528 -1 8529 -1 8530 -1 8531 -1 8532 -1 8533 -1 8534 -1 8535 -1 8536 -1 8537 -1 8538 -1 8539 -1 8540 -1 8541 -1 8542 -1 8543 -1 8544 -1 8545 -1 8546 -1 8547 -1 8548 -1 8549 -1 8550 -1 8551 -1 8552 -1 8553 -1 8554 -1 8555 -1 8556 -1 8557 -1 8558 -1 8559 -1 8560 -1 8561 -1 8562 -1 8563 -1 8564 -1 8565 -1 8566 -1 8567 -1 8568 -1 8569 -1 8570 -1 8571 -1 8572 -1 8573 -1 8574 -1 8575 -1 8576 -1 8577 -1 8578 -1 8579 -1 8580 -1 8581 -1 8582 -1 8583 -1 8584 -1 8585 -1 8586 -1 8587 -1 8588 -1 8589 -1 8590 -1 8591 -1 8592 -1 8593 -1 8594 -1 8595 -1 8596 -1 8597 -1 8598 -1 8599 -1 8600 -1 8601 -1 8602 -1 8603 -1 8604 -1 8605 -1 8606 -1 8607 -1 8608 -1 8609 -1 8610 -1 8611 -1 8612 -1 8613 -1 8614 -1 8615 -1 8616 -1 8617 -1 8618 -1 8619 -1 8620 -1 8621 -1 8622 -1 8623 -1 8624 -1 8625 -1 8626 -1 8627 -1 8628 -1 8629 -1 8630 -1 8631 -1 8632 -1 8633 -1 8634 -1 8635 -1 8636 -1 8637 -1 8638 -1 8639 -1 8640 -1 8641 -1 8642 -1 8643 -1 8644 -1 8645 -1 8646 -1 8647 -1 8648 -1 8649 -1 8650 -1 8651 -1 8652 -1 8653 -1 8654 -1 8655 -1 8656 -1 8657 -1 8658 -1 8659 -1 8660 -1 8661 -1 8662 -1 8663 -1 8664 -1 8665 -1 8666 -1 8667 -1 8668 -1 8669 -1 8670 -1 8671 -1 8672 -1 8673 -1 8674 -1 8675 -1 8676 -1 8677 -1 8678 -1 8679 -1 8680 -1 8681 -1 8682 -1 8683 -1 8684 -1 8685 -1 8686 -1 8687 -1 8688 -1 8689 -1 8690 -1 8691 -1 8692 -1 8693 -1 8694 -1 8695 -1 8696 -1 8697 -1 8698 -1 8699 -1 8700 -1 8701 -1 8702 -1 8703 -1 8704 -1 8705 -1 8706 -1 8707 -1 8708 -1 8709 -1 8710 -1 8711 -1 8712 -1 8713 -1 8714 -1 8715 -1 8716 -1 8717 -1 8718 -1 8719 -1 8720 -1 8721 -1 8722 -1 8723 -1 8724 -1 8725 -1 8726 -1 8727 -1 8728 -1 8729 -1 8730 -1 8731 -1 8732 -1 8733 -1 8734 -1 8735 -1 8736 -1 8737 -1 8738 -1 8739 -1 8740 -1 8741 -1 8742 -1 8743 -1 8744 -1 8745 -1 8746 -1 8747 -1 8748 -1 8749 -1 8750 -1 8751 -1 8752 -1 8753 -1 8754 -1 8755 -1 8756 -1 8757 -1 8758 -1 8759 -1 8760 -1 8761 -1 8762 -1 8763 -1 8764 -1 8765 -1 8766 -1 8767 -1 8768 -1 8769 -1 8770 -1 8771 -1 8772 -1 8773 -1 8774 -1 8775 -1 8776 -1 8777 -1 8778 -1 8779 -1 8780 -1 8781 -1 8782 -1 8783 -1 8784 -1 8785 -1 8786 -1 8787 -1 8788 -1 8789 -1 8790 -1 8791 -1 8792 -1 8793 -1 8794 -1 8795 -1 8796 -1 8797 -1 8798 -1 8799 -1 8800 -1 8801 -1 8802 -1 8803 -1 8804 -1 8805 -1 8806 -1 8807 -1 8808 -1 8809 -1 8810 -1 8811 -1 8812 -1 8813 -1 8814 -1 8815 -1 8816 -1 8817 -1 8818 -1 8819 -1 8820 -1 8821 -1 8822 -1 8823 -1 8824 -1 8825 -1 8826 -1 8827 -1 8828 -1 8829 -1 8830 -1 8831 -1 8832 -1 8833 -1 8834 -1 8835 -1 8836 -1 8837 -1 8838 -1 8839 -1 8840 -1 8841 -1 8842 -1 8843 -1 8844 -1 8845 -1 8846 -1 8847 -1 8848 -1 8849 -1 8850 -1 8851 -1 8852 -1 8853 -1 8854 -1 8855 -1 8856 -1 8857 -1 8858 -1 8859 -1 8860 -1 8861 -1 8862 -1 8863 -1 8864 -1 8865 -1 8866 -1 8867 -1 8868 -1 8869 -1 8870 -1 8871 -1 8872 -1 8873 -1 8874 -1 8875 -1 8876 -1 8877 -1 8878 -1 8879 -1 8880 -1 8881 -1 8882 -1 8883 -1 8884 -1 8885 -1 8886 -1 8887 -1 8888 -1 8889 -1 8890 -1 8891 -1 8892 -1 8893 -1 8894 -1 8895 -1 8896 -1 8897 -1 8898 -1 8899 -1 8900 -1 8901 -1 8902 -1 8903 -1 8904 -1 8905 -1 8906 -1 8907 -1 8908 -1 8909 -1 8910 -1 8911 -1 8912 -1 8913 -1 8914 -1 8915 -1 8916 -1 8917 -1 8918 -1 8919 -1 8920 -1 8921 -1 8922 -1 8923 -1 8924 -1 8925 -1 8926 -1 8927 -1 8928 -1 8929 -1 8930 -1 8931 -1 8932 -1 8933 -1 8934 -1 8935 -1 8936 -1 8937 -1 8938 -1 8939 -1 8940 -1 8941 -1 8942 -1 8943 -1 8944 -1 8945 -1 8946 -1 8947 -1 8948 -1 8949 -1 8950 -1 8951 -1 8952 -1 8953 -1 8954 -1 8955 -1 8956 -1 8957 -1 8958 -1 8959 -1 8960 -1 8961 -1 8962 -1 8963 -1 8964 -1 8965 -1 8966 -1 8967 -1 8968 -1 8969 -1 8970 -1 8971 -1 8972 -1 8973 -1 8974 -1 8975 -1 8976 -1 8977 -1 8978 -1 8979 -1 8980 -1 8981 -1 8982 -1 8983 -1 8984 -1 8985 -1 8986 -1 8987 -1 8988 -1 8989 -1 8990 -1 8991 -1 8992 -1 8993 -1 8994 -1 8995 -1 8996 -1 8997 -1 8998 -1 8999 -1 9000 -1 9001 -1 9002 -1 9003 -1 9004 -1 9005 -1 9006 -1 9007 -1 9008 -1 9009 -1 9010 -1 9011 -1 9012 -1 9013 -1 9014 -1 9015 -1 9016 -1 9017 -1 9018 -1 9019 -1 9020 -1 9021 -1 9022 -1 9023 -1 9024 -1 9025 -1 9026 -1 9027 -1 9028 -1 9029 -1 9030 -1 9031 -1 9032 -1 9033 -1 9034 -1 9035 -1 9036 -1 9037 -1 9038 -1 9039 -1 9040 -1 9041 -1 9042 -1 9043 -1 9044 -1 9045 -1 9046 -1 9047 -1 9048 -1 9049 -1 9050 -1 9051 -1 9052 -1 9053 -1 9054 -1 9055 -1 9056 -1 9057 -1 9058 -1 9059 -1 9060 -1 9061 -1 9062 -1 9063 -1 9064 -1 9065 -1 9066 -1 9067 -1 9068 -1 9069 -1 9070 -1 9071 -1 9072 -1 9073 -1 9074 -1 9075 -1 9076 -1 9077 -1 9078 -1 9079 -1 9080 -1 9081 -1 9082 -1 9083 -1 9084 -1 9085 -1 9086 -1 9087 -1 9088 -1 9089 -1 9090 -1 9091 -1 9092 -1 9093 -1 9094 -1 9095 -1 9096 -1 9097 -1 9098 -1 9099 -1 9100 -1 9101 -1 9102 -1 9103 -1 9104 -1 9105 -1 9106 -1 9107 -1 9108 -1 9109 -1 9110 -1 9111 -1 9112 -1 9113 -1 9114 -1 9115 -1 9116 -1 9117 -1 9118 -1 9119 -1 9120 -1 9121 -1 9122 -1 9123 -1 9124 -1 9125 -1 9126 -1 9127 -1 9128 -1 9129 -1 9130 -1 9131 -1 9132 -1 9133 -1 9134 -1 9135 -1 9136 -1 9137 -1 9138 -1 9139 -1 9140 -1 9141 -1 9142 -1 9143 -1 9144 -1 9145 -1 9146 -1 9147 -1 9148 -1 9149 -1 9150 -1 9151 -1 9152 -1 9153 -1 9154 -1 9155 -1 9156 -1 9157 -1 9158 -1 9159 -1 9160 -1 9161 -1 9162 -1 9163 -1 9164 -1 9165 -1 9166 -1 9167 -1 9168 -1 9169 -1 9170 -1 9171 -1 9172 -1 9173 -1 9174 -1 9175 -1 9176 -1 9177 -1 9178 -1 9179 -1 9180 -1 9181 -1 9182 -1 9183 -1 9184 -1 9185 -1 9186 -1 9187 -1 9188 -1 9189 -1 9190 -1 9191 -1 9192 -1 9193 -1 9194 -1 9195 -1 9196 -1 9197 -1 9198 -1 9199 -1 9200 -1 9201 -1 9202 -1 9203 -1 9204 -1 9205 -1 9206 -1 9207 -1 9208 -1 9209 -1 9210 -1 9211 -1 9212 -1 9213 -1 9214 -1 9215 -1 9216 -1 9217 -1 9218 -1 9219 -1 9220 -1 9221 -1 9222 -1 9223 -1 9224 -1 9225 -1 9226 -1 9227 -1 9228 -1 9229 -1 9230 -1 9231 -1 9232 -1 9233 -1 9234 -1 9235 -1 9236 -1 9237 -1 9238 -1 9239 -1 9240 -1 9241 -1 9242 -1 9243 -1 9244 -1 9245 -1 9246 -1 9247 -1 9248 -1 9249 -1 9250 -1 9251 -1 9252 -1 9253 -1 9254 -1 9255 -1 9256 -1 9257 -1 9258 -1 9259 -1 9260 -1 9261 -1 9262 -1 9263 -1 9264 -1 9265 -1 9266 -1 9267 -1 9268 -1 9269 -1 9270 -1 9271 -1 9272 -1 9273 -1 9274 -1 9275 -1 9276 -1 9277 -1 9278 -1 9279 -1 9280 -1 9281 -1 9282 -1 9283 -1 9284 -1 9285 -1 9286 -1 9287 -1 9288 -1 9289 -1 9290 -1 9291 -1 9292 -1 9293 -1 9294 -1 9295 -1 9296 -1 9297 -1 9298 -1 9299 -1 9300 -1 9301 -1 9302 -1 9303 -1 9304 -1 9305 -1 9306 -1 9307 -1 9308 -1 9309 -1 9310 -1 9311 -1 9312 -1 9313 -1 9314 -1 9315 -1 9316 -1 9317 -1 9318 -1 9319 -1 9320 -1 9321 -1 9322 -1 9323 -1 9324 -1 9325 -1 9326 -1 9327 -1 9328 -1 9329 -1 9330 -1 9331 -1 9332 -1 9333 -1 9334 -1 9335 -1 9336 -1 9337 -1 9338 -1 9339 -1 9340 -1 9341 -1 9342 -1 9343 -1 9344 -1 9345 -1 9346 -1 9347 -1 9348 -1 9349 -1 9350 -1 9351 -1 9352 -1 9353 -1 9354 -1 9355 -1 9356 -1 9357 -1 9358 -1 9359 -1 9360 -1 9361 -1 9362 -1 9363 -1 9364 -1 9365 -1 9366 -1 9367 -1 9368 -1 9369 -1 9370 -1 9371 -1 9372 -1 9373 -1 9374 -1 9375 -1 9376 -1 9377 -1 9378 -1 9379 -1 9380 -1 9381 -1 9382 -1 9383 -1 9384 -1 9385 -1 9386 -1 9387 -1 9388 -1 9389 -1 9390 -1 9391 -1 9392 -1 9393 -1 9394 -1 9395 -1 9396 -1 9397 -1 9398 -1 9399 -1 9400 -1 9401 -1 9402 -1 9403 -1 9404 -1 9405 -1 9406 -1 9407 -1 9408 -1 9409 -1 9410 -1 9411 -1 9412 -1 9413 -1 9414 -1 9415 -1 9416 -1 9417 -1 9418 -1 9419 -1 9420 -1 9421 -1 9422 -1 9423 -1 9424 -1 9425 -1 9426 -1 9427 -1 9428 -1 9429 -1 9430 -1 9431 -1 9432 -1 9433 -1 9434 -1 9435 -1 9436 -1 9437 -1 9438 -1 9439 -1 9440 -1 9441 -1 9442 -1 9443 -1 9444 -1 9445 -1 9446 -1 9447 -1 9448 -1 9449 -1 9450 -1 9451 -1 9452 -1 9453 -1 9454 -1 9455 -1 9456 -1 9457 -1 9458 -1 9459 -1 9460 -1 9461 -1 9462 -1 9463 -1 9464 -1 9465 -1 9466 -1 9467 -1 9468 -1 9469 -1 9470 -1 9471 -1 9472 -1 9473 -1 9474 -1 9475 -1 9476 -1 9477 -1 9478 -1 9479 -1 9480 -1 9481 -1 9482 -1 9483 -1 9484 -1 9485 -1 9486 -1 9487 -1 9488 -1 9489 -1 9490 -1 9491 -1 9492 -1 9493 -1 9494 -1 9495 -1 9496 -1 9497 -1 9498 -1 9499 -1 9500 -1 9501 -1 9502 -1 9503 -1 9504 -1 9505 -1 9506 -1 9507 -1 9508 -1 9509 -1 9510 -1 9511 -1 9512 -1 9513 -1 9514 -1 9515 -1 9516 -1 9517 -1 9518 -1 9519 -1 9520 -1 9521 -1 9522 -1 9523 -1 9524 -1 9525 -1 9526 -1 9527 -1 9528 -1 9529 -1 9530 -1 9531 -1 9532 -1 9533 -1 9534 -1 9535 -1 9536 -1 9537 -1 9538 -1 9539 -1 9540 -1 9541 -1 9542 -1 9543 -1 9544 -1 9545 -1 9546 -1 9547 -1 9548 -1 9549 -1 9550 -1 9551 -1 9552 -1 9553 -1 9554 -1 9555 -1 9556 -1 9557 -1 9558 -1 9559 -1 9560 -1 9561 -1 9562 -1 9563 -1 9564 -1 9565 -1 9566 -1 9567 -1 9568 -1 9569 -1 9570 -1 9571 -1 9572 -1 9573 -1 9574 -1 9575 -1 9576 -1 9577 -1 9578 -1 9579 -1 9580 -1 9581 -1 9582 -1 9583 -1 9584 -1 9585 -1 9586 -1 9587 -1 9588 -1 9589 -1 9590 -1 9591 -1 9592 -1 9593 -1 9594 -1 9595 -1 9596 -1 9597 -1 9598 -1 9599 -1 9600 -1 9601 -1 9602 -1 9603 -1 9604 -1 9605 -1 9606 -1 9607 -1 9608 -1 9609 -1 9610 -1 9611 -1 9612 -1 9613 -1 9614 -1 9615 -1 9616 -1 9617 -1 9618 -1 9619 -1 9620 -1 9621 -1 9622 -1 9623 -1 9624 -1 9625 -1 9626 -1 9627 -1 9628 -1 9629 -1 9630 -1 9631 -1 9632 -1 9633 -1 9634 -1 9635 -1 9636 -1 9637 -1 9638 -1 9639 -1 9640 -1 9641 -1 9642 -1 9643 -1 9644 -1 9645 -1 9646 -1 9647 -1 9648 -1 9649 -1 9650 -1 9651 -1 9652 -1 9653 -1 9654 -1 9655 -1 9656 -1 9657 -1 9658 -1 9659 -1 9660 -1 9661 -1 9662 -1 9663 -1 9664 -1 9665 -1 9666 -1 9667 -1 9668 -1 9669 -1 9670 -1 9671 -1 9672 -1 9673 -1 9674 -1 9675 -1 9676 -1 9677 -1 9678 -1 9679 -1 9680 -1 9681 -1 9682 -1 9683 -1 9684 -1 9685 -1 9686 -1 9687 -1 9688 -1 9689 -1 9690 -1 9691 -1 9692 -1 9693 -1 9694 -1 9695 -1 9696 -1 9697 -1 9698 -1 9699 -1 9700 -1 9701 -1 9702 -1 9703 -1 9704 -1 9705 -1 9706 -1 9707 -1 9708 -1 9709 -1 9710 -1 9711 -1 9712 -1 9713 -1 9714 -1 9715 -1 9716 -1 9717 -1 9718 -1 9719 -1 9720 -1 9721 -1 9722 -1 9723 -1 9724 -1 9725 -1 9726 -1 9727 -1 9728 -1 9729 -1 9730 -1 9731 -1 9732 -1 9733 -1 9734 -1 9735 -1 9736 -1 9737 -1 9738 -1 9739 -1 9740 -1 9741 -1 9742 -1 9743 -1 9744 -1 9745 -1 9746 -1 9747 -1 9748 -1 9749 -1 9750 -1 9751 -1 9752 -1 9753 -1 9754 -1 9755 -1 9756 -1 9757 -1 9758 -1 9759 -1 9760 -1 9761 -1 9762 -1 9763 -1 9764 -1 9765 -1 9766 -1 9767 -1 9768 -1 9769 -1 9770 -1 9771 -1 9772 -1 9773 -1 9774 -1 9775 -1 9776 -1 9777 -1 9778 -1 9779 -1 9780 -1 9781 -1 9782 -1 9783 -1 9784 -1 9785 -1 9786 -1 9787 -1 9788 -1 9789 -1 9790 -1 9791 -1 9792 -1 9793 -1 9794 -1 9795 -1 9796 -1 9797 -1 9798 -1 9799 -1 9800 -1 9801 -1 9802 -1 9803 -1 9804 -1 9805 -1 9806 -1 9807 -1 9808 -1 9809 -1 9810 -1 9811 -1 9812 -1 9813 -1 9814 -1 9815 -1 9816 -1 9817 -1 9818 -1 9819 -1 9820 -1 9821 -1 9822 -1 9823 -1 9824 -1 9825 -1 9826 -1 9827 -1 9828 -1 9829 -1 9830 -1 9831 -1 9832 -1 9833 -1 9834 -1 9835 -1 9836 -1 9837 -1 9838 -1 9839 -1 9840 -1 9841 -1 9842 -1 9843 -1 9844 -1 9845 -1 9846 -1 9847 -1 9848 -1 9849 -1 9850 -1 9851 -1 9852 -1 9853 -1 9854 -1 9855 -1 9856 -1 9857 -1 9858 -1 9859 -1 9860 -1 9861 -1 9862 -1 9863 -1 9864 -1 9865 -1 9866 -1 9867 -1 9868 -1 9869 -1 9870 -1 9871 -1 9872 -1 9873 -1 9874 -1 9875 -1 9876 -1 9877 -1 9878 -1 9879 -1 9880 -1 9881 -1 9882 -1 9883 -1 9884 -1 9885 -1 9886 -1 9887 -1 9888 -1 9889 -1 9890 -1 9891 -1 9892 -1 9893 -1 9894 -1 9895 -1 9896 -1 9897 -1 9898 -1 9899 -1 9900 -1 9901 -1 9902 -1 9903 -1 9904 -1 9905 -1 9906 -1 9907 -1 9908 -1 9909 -1 9910 -1 9911 -1 9912 -1 9913 -1 9914 -1 9915 -1 9916 -1 9917 -1 9918 -1 9919 -1 9920 -1 9921 -1 9922 -1 9923 -1 9924 -1 9925 -1 9926 -1 9927 -1 9928 -1 9929 -1 9930 -1 9931 -1 9932 -1 9933 -1 9934 -1 9935 -1 9936 -1 9937 -1 9938 -1 9939 -1 9940 -1 9941 -1 9942 -1 9943 -1 9944 -1 9945 -1 9946 -1 9947 -1 9948 -1 9949 -1 9950 -1 9951 -1 9952 -1 9953 -1 9954 -1 9955 -1 9956 -1 9957 -1 9958 -1 9959 -1 9960 -1 9961 -1 9962 -1 9963 -1 9964 -1 9965 -1 9966 -1 9967 -1 9968 -1 9969 -1 9970 -1 9971 -1 9972 -1 9973 -1 9974 -1 9975 -1 9976 -1 9977 -1 9978 -1 9979 -1 9980 -1 9981 -1 9982 -1 9983 -1 9984 -1 9985 -1 9986 -1 9987 -1 9988 -1 9989 -1 9990 -1 9991 -1 9992 -1 9993 -1 9994 -1 9995 -1 9996 -1 9997 -1 9998 -1 9999 -1 10000 -1 10001 -1 10002 -1 10003 -1 10004 -1 10005 -1 10006 -1 10007 -1 10008 -1 10009 -1 10010 -1 10011 -1 10012 -1 10013 -1 10014 -1 10015 -1 10016 -1 10017 -1 10018 -1 10019 -1 10020 -1 10021 -1 10022 -1 10023 -1 10024 -1 10025 -1 10026 -1 10027 -1 10028 -1 10029 -1 10030 -1 10031 -1 10032 -1 10033 -1 10034 -1 10035 -1 10036 -1 10037 -1 10038 -1 10039 -1 10040 -1 10041 -1 10042 -1 10043 -1 10044 -1 10045 -1 10046 -1 10047 -1 10048 -1 10049 -1 10050 -1 10051 -1 10052 -1 10053 -1 10054 -1 10055 -1 10056 -1 10057 -1 10058 -1 10059 -1 10060 -1 10061 -1 10062 -1 10063 -1 10064 -1 10065 -1 10066 -1 10067 -1 10068 -1 10069 -1 10070 -1 10071 -1 10072 -1 10073 -1 10074 -1 10075 -1 10076 -1 10077 -1 10078 -1 10079 -1 10080 -1 10081 -1 10082 -1 10083 -1 10084 -1 10085 -1 10086 -1 10087 -1 10088 -1 10089 -1 10090 -1 10091 -1 10092 -1 10093 -1 10094 -1 10095 -1 10096 -1 10097 -1 10098 -1 10099 -1 10100 -1 10101 -1 10102 -1 10103 -1 10104 -1 10105 -1 10106 -1 10107 -1 10108 -1 10109 -1 10110 -1 10111 -1 10112 -1 10113 -1 10114 -1 10115 -1 10116 -1 10117 -1 10118 -1 10119 -1 10120 -1 10121 -1 10122 -1 10123 -1 10124 -1 10125 -1 10126 -1 10127 -1 10128 -1 10129 -1 10130 -1 10131 -1 10132 -1 10133 -1 10134 -1 10135 -1 10136 -1 10137 -1 10138 -1 10139 -1 10140 -1 10141 -1 10142 -1 10143 -1 10144 -1 10145 -1 10146 -1 10147 -1 10148 -1 10149 -1 10150 -1 10151 -1 10152 -1 10153 -1 10154 -1 10155 -1 10156 -1 10157 -1 10158 -1 10159 -1 10160 -1 10161 -1 10162 -1 10163 -1 10164 -1 10165 -1 10166 -1 10167 -1 10168 -1 10169 -1 10170 -1 10171 -1 10172 -1 10173 -1 10174 -1 10175 -1 10176 -1 10177 -1 10178 -1 10179 -1 10180 -1 10181 -1 10182 -1 10183 -1 10184 -1 10185 -1 10186 -1 10187 -1 10188 -1 10189 -1 10190 -1 10191 -1 10192 -1 10193 -1 10194 -1 10195 -1 10196 -1 10197 -1 10198 -1 10199 -1 10200 -1 10201 -1 10202 -1 10203 -1 10204 -1 10205 -1 10206 -1 10207 -1 10208 -1 10209 -1 10210 -1 10211 -1 10212 -1 10213 -1 10214 -1 10215 -1 10216 -1 10217 -1 10218 -1 10219 -1 10220 -1 10221 -1 10222 -1 10223 -1 10224 -1 10225 -1 10226 -1 10227 -1 10228 -1 10229 -1 10230 -1 10231 -1 10232 -1 10233 -1 10234 -1 10235 -1 10236 -1 10237 -1 10238 -1 10239 -1 10240 -1 10241 -1 10242 -1 10243 -1 10244 -1 10245 -1 10246 -1 10247 -1 10248 -1 10249 -1 10250 -1 10251 -1 10252 -1 10253 -1 10254 -1 10255 -1 10256 -1 10257 -1 10258 -1 10259 -1 10260 -1 10261 -1 10262 -1 10263 -1 10264 -1 10265 -1 10266 -1 10267 -1 10268 -1 10269 -1 10270 -1 10271 -1 10272 -1 10273 -1 10274 -1 10275 -1 10276 -1 10277 -1 10278 -1 10279 -1 10280 -1 10281 -1 10282 -1 10283 -1 10284 -1 10285 -1 10286 -1 10287 -1 10288 -1 10289 -1 10290 -1 10291 -1 10292 -1 10293 -1 10294 -1 10295 -1 10296 -1 10297 -1 10298 -1 10299 -1 10300 -1 10301 -1 10302 -1 10303 -1 10304 -1 10305 -1 10306 -1 10307 -1 10308 -1 10309 -1 10310 -1 10311 -1 10312 -1 10313 -1 10314 -1 10315 -1 10316 -1 10317 -1 10318 -1 10319 -1 10320 -1 10321 -1 10322 -1 10323 -1 10324 -1 10325 -1 10326 -1 10327 -1 10328 -1 10329 -1 10330 -1 10331 -1 10332 -1 10333 -1 10334 -1 10335 -1 10336 -1 10337 -1 10338 -1 10339 -1 10340 -1 10341 -1 10342 -1 10343 -1 10344 -1 10345 -1 10346 -1 10347 -1 10348 -1 10349 -1 10350 -1 10351 -1 10352 -1 10353 -1 10354 -1 10355 -1 10356 -1 10357 -1 10358 -1 10359 -1 10360 -1 10361 -1 10362 -1 10363 -1 10364 -1 10365 -1 10366 -1 10367 -1 10368 -1 10369 -1 10370 -1 10371 -1 10372 -1 10373 -1 10374 -1 10375 -1 10376 -1 10377 -1 10378 -1 10379 -1 10380 -1 10381 -1 10382 -1 10383 -1 10384 -1 10385 -1 10386 -1 10387 -1 10388 -1 10389 -1 10390 -1 10391 -1 10392 -1 10393 -1 10394 -1 10395 -1 10396 -1 10397 -1 10398 -1 10399 -1 10400 -1 10401 -1 10402 -1 10403 -1 10404 -1 10405 -1 10406 -1 10407 -1 10408 -1 10409 -1 10410 -1 10411 -1 10412 -1 10413 -1 10414 -1 10415 -1 10416 -1 10417 -1 10418 -1 10419 -1 10420 -1 10421 -1 10422 -1 10423 -1 10424 -1 10425 -1 10426 -1 10427 -1 10428 -1 10429 -1 10430 -1 10431 -1 10432 -1 10433 -1 10434 -1 10435 -1 10436 -1 10437 -1 10438 -1 10439 -1 10440 -1 10441 -1 10442 -1 10443 -1 10444 -1 10445 -1 10446 -1 10447 -1 10448 -1 10449 -1 10450 -1 10451 -1 10452 -1 10453 -1 10454 -1 10455 -1 10456 -1 10457 -1 10458 -1 10459 -1 10460 -1 10461 -1 10462 -1 10463 -1 10464 -1 10465 -1 10466 -1 10467 -1 10468 -1 10469 -1 10470 -1 10471 -1 10472 -1 10473 -1 10474 -1 10475 -1 10476 -1 10477 -1 10478 -1 10479 -1 10480 -1 10481 -1 10482 -1 10483 -1 10484 -1 10485 -1 10486 -1 10487 -1 10488 -1 10489 -1 10490 -1 10491 -1 10492 -1 10493 -1 10494 -1 10495 -1 10496 -1 10497 -1 10498 -1 10499 -1 10500 -1 10501 -1 10502 -1 10503 -1 10504 -1 10505 -1 10506 -1 10507 -1 10508 -1 10509 -1 10510 -1 10511 -1 10512 -1 10513 -1 10514 -1 10515 -1 10516 -1 10517 -1 10518 -1 10519 -1 10520 -1 10521 -1 10522 -1 10523 -1 10524 -1 10525 -1 10526 -1 10527 -1 10528 -1 10529 -1 10530 -1 10531 -1 10532 -1 10533 -1 10534 -1 10535 -1 10536 -1 10537 -1 10538 -1 10539 -1 10540 -1 10541 -1 10542 -1 10543 -1 10544 -1 10545 -1 10546 -1 10547 -1 10548 -1 10549 -1 10550 -1 10551 -1 10552 -1 10553 -1 10554 -1 10555 -1 10556 -1 10557 -1 10558 -1 10559 -1 10560 -1 10561 -1 10562 -1 10563 -1 10564 -1 10565 -1 10566 -1 10567 -1 10568 -1 10569 -1 10570 -1 10571 -1 10572 -1 10573 -1 10574 -1 10575 -1 10576 -1 10577 -1 10578 -1 10579 -1 10580 -1 10581 -1 10582 -1 10583 -1 10584 -1 10585 -1 10586 -1 10587 -1 10588 -1 10589 -1 10590 -1 10591 -1 10592 -1 10593 -1 10594 -1 10595 -1 10596 -1 10597 -1 10598 -1 10599 -1 10600 -1 10601 -1 10602 -1 10603 -1 10604 -1 10605 -1 10606 -1 10607 -1 10608 -1 10609 -1 10610 -1 10611 -1 10612 -1 10613 -1 10614 -1 10615 -1 10616 -1 10617 -1 10618 -1 10619 -1 10620 -1 10621 -1 10622 -1 10623 -1 10624 -1 10625 -1 10626 -1 10627 -1 10628 -1 10629 -1 10630 -1 10631 -1 10632 -1 10633 -1 10634 -1 10635 -1 10636 -1 10637 -1 10638 -1 10639 -1 10640 -1 10641 -1 10642 -1 10643 -1 10644 -1 10645 -1 10646 -1 10647 -1 10648 -1 10649 -1 10650 -1 10651 -1 10652 -1 10653 -1 10654 -1 10655 -1 10656 -1 10657 -1 10658 -1 10659 -1 10660 -1 10661 -1 10662 -1 10663 -1 10664 -1 10665 -1 10666 -1 10667 -1 10668 -1 10669 -1 10670 -1 10671 -1 10672 -1 10673 -1 10674 -1 10675 -1 10676 -1 10677 -1 10678 -1 10679 -1 10680 -1 10681 -1 10682 -1 10683 -1 10684 -1 10685 -1 10686 -1 10687 -1 10688 -1 10689 -1 10690 -1 10691 -1 10692 -1 10693 -1 10694 -1 10695 -1 10696 -1 10697 -1 10698 -1 10699 -1 10700 -1 10701 -1 10702 -1 10703 -1 10704 -1 10705 -1 10706 -1 10707 -1 10708 -1 10709 -1 10710 -1 10711 -1 10712 -1 10713 -1 10714 -1 10715 -1 10716 -1 10717 -1 10718 -1 10719 -1 10720 -1 10721 -1 10722 -1 10723 -1 10724 -1 10725 -1 10726 -1 10727 -1 10728 -1 10729 -1 10730 -1 10731 -1 10732 -1 10733 -1 10734 -1 10735 -1 10736 -1 10737 -1 10738 -1 10739 -1 10740 -1 10741 -1 10742 -1 10743 -1 10744 -1 10745 -1 10746 -1 10747 -1 10748 -1 10749 -1 10750 -1 10751 -1 10752 -1 10753 -1 10754 -1 10755 -1 10756 -1 10757 -1 10758 -1 10759 -1 10760 -1 10761 -1 10762 -1 10763 -1 10764 -1 10765 -1 10766 -1 10767 -1 10768 -1 10769 -1 10770 -1 10771 -1 10772 -1 10773 -1 10774 -1 10775 -1 10776 -1 10777 -1 10778 -1 10779 -1 10780 -1 10781 -1 10782 -1 10783 -1 10784 -1 10785 -1 10786 -1 10787 -1 10788 -1 10789 -1 10790 -1 10791 -1 10792 -1 10793 -1 10794 -1 10795 -1 10796 -1 10797 -1 10798 -1 10799 -1 10800 -1 10801 -1 10802 -1 10803 -1 10804 -1 10805 -1 10806 -1 10807 -1 10808 -1 10809 -1 10810 -1 10811 -1 10812 -1 10813 -1 10814 -1 10815 -1 10816 -1 10817 -1 10818 -1 10819 -1 10820 -1 10821 -1 10822 -1 10823 -1 10824 -1 10825 -1 10826 -1 10827 -1 10828 -1 10829 -1 10830 -1 10831 -1 10832 -1 10833 -1 10834 -1 10835 -1 10836 -1 10837 -1 10838 -1 10839 -1 10840 -1 10841 -1 10842 -1 10843 -1 10844 -1 10845 -1 10846 -1 10847 -1 10848 -1 10849 -1 10850 -1 10851 -1 10852 -1 10853 -1 10854 -1 10855 -1 10856 -1 10857 -1 10858 -1 10859 -1 10860 -1 10861 -1 10862 -1 10863 -1 10864 -1 10865 -1 10866 -1 10867 -1 10868 -1 10869 -1 10870 -1 10871 -1 10872 -1 10873 -1 10874 -1 10875 -1 10876 -1 10877 -1 10878 -1 10879 -1 10880 -1 10881 -1 10882 -1 10883 -1 10884 -1 10885 -1 10886 -1 10887 -1 10888 -1 10889 -1 10890 -1 10891 -1 10892 -1 10893 -1 10894 -1 10895 -1 10896 -1 10897 -1 10898 -1 10899 -1 10900 -1 10901 -1 10902 -1 10903 -1 10904 -1 10905 -1 10906 -1 10907 -1 10908 -1 10909 -1 10910 -1 10911 -1 10912 -1 10913 -1 10914 -1 10915 -1 10916 -1 10917 -1 10918 -1 10919 -1 10920 -1 10921 -1 10922 -1 10923 -1 10924 -1 10925 -1 10926 -1 10927 -1 10928 -1 10929 -1 10930 -1 10931 -1 10932 -1 10933 -1 10934 -1 10935 -1 10936 -1 10937 -1 10938 -1 10939 -1 10940 -1 10941 -1 10942 -1 10943 -1 10944 -1 10945 -1 10946 -1 10947 -1 10948 -1 10949 -1 10950 -1 10951 -1 10952 -1 10953 -1 10954 -1 10955 -1 10956 -1 10957 -1 10958 -1 10959 -1 10960 -1 10961 -1 10962 -1 10963 -1 10964 -1 10965 -1 10966 -1 10967 -1 10968 -1 10969 -1 10970 -1 10971 -1 10972 -1 10973 -1 10974 -1 10975 -1 10976 -1 10977 -1 10978 -1 10979 -1 10980 -1 10981 -1 10982 -1 10983 -1 10984 -1 10985 -1 10986 -1 10987 -1 10988 -1 10989 -1 10990 -1 10991 -1 10992 -1 10993 -1 10994 -1 10995 -1 10996 -1 10997 -1 10998 -1 10999 -1 11000 -1 11001 -1 11002 -1 11003 -1 11004 -1 11005 -1 11006 -1 11007 -1 11008 -1 11009 -1 11010 -1 11011 -1 11012 -1 11013 -1 11014 -1 11015 -1 11016 -1 11017 -1 11018 -1 11019 -1 11020 -1 11021 -1 11022 -1 11023 -1 11024 -1 11025 -1 11026 -1 11027 -1 11028 -1 11029 -1 11030 -1 11031 -1 11032 -1 11033 -1 11034 -1 11035 -1 11036 -1 11037 -1 11038 -1 11039 -1 11040 -1 11041 -1 11042 -1 11043 -1 11044 -1 11045 -1 11046 -1 11047 -1 11048 -1 11049 -1 11050 -1 11051 -1 11052 -1 11053 -1 11054 -1 11055 -1 11056 -1 11057 -1 11058 -1 11059 -1 11060 -1 11061 -1 11062 -1 11063 -1 11064 -1 11065 -1 11066 -1 11067 -1 11068 -1 11069 -1 11070 -1 11071 -1 11072 -1 11073 -1 11074 -1 11075 -1 11076 -1 11077 -1 11078 -1 11079 -1 11080 -1 11081 -1 11082 -1 11083 -1 11084 -1 11085 -1 11086 -1 11087 -1 11088 -1 11089 -1 11090 -1 11091 -1 11092 -1 11093 -1 11094 -1 11095 -1 11096 -1 11097 -1 11098 -1 11099 -1 11100 -1 11101 -1 11102 -1 11103 -1 11104 -1 11105 -1 11106 -1 11107 -1 11108 -1 11109 -1 11110 -1 11111 -1 11112 -1 11113 -1 11114 -1 11115 -1 11116 -1 11117 -1 11118 -1 11119 -1 11120 -1 11121 -1 11122 -1 11123 -1 11124 -1 11125 -1 11126 -1 11127 -1 11128 -1 11129 -1 11130 -1 11131 -1 11132 -1 11133 -1 11134 -1 11135 -1 11136 -1 11137 -1 11138 -1 11139 -1 11140 -1 11141 -1 11142 -1 11143 -1 11144 -1 11145 -1 11146 -1 11147 -1 11148 -1 11149 -1 11150 -1 11151 -1 11152 -1 11153 -1 11154 -1 11155 -1 11156 -1 11157 -1 11158 -1 11159 -1 11160 -1 11161 -1 11162 -1 11163 -1 11164 -1 11165 -1 11166 -1 11167 -1 11168 -1 11169 -1 11170 -1 11171 -1 11172 -1 11173 -1 11174 -1 11175 -1 11176 -1 11177 -1 11178 -1 11179 -1 11180 -1 11181 -1 11182 -1 11183 -1 11184 -1 11185 -1 11186 -1 11187 -1 11188 -1 11189 -1 11190 -1 11191 -1 11192 -1 11193 -1 11194 -1 11195 -1 11196 -1 11197 -1 11198 -1 11199 -1 11200 -1 11201 -1 11202 -1 11203 -1 11204 -1 11205 -1 11206 -1 11207 -1 11208 -1 11209 -1 11210 -1 11211 -1 11212 -1 11213 -1 11214 -1 11215 -1 11216 -1 11217 -1 11218 -1 11219 -1 11220 -1 11221 -1 11222 -1 11223 -1 11224 -1 11225 -1 11226 -1 11227 -1 11228 -1 11229 -1 11230 -1 11231 -1 11232 -1 11233 -1 11234 -1 11235 -1 11236 -1 11237 -1 11238 -1 11239 -1 11240 -1 11241 -1 11242 -1 11243 -1 11244 -1 11245 -1 11246 -1 11247 -1 11248 -1 11249 -1 11250 -1 11251 -1 11252 -1 11253 -1 11254 -1 11255 -1 11256 -1 11257 -1 11258 -1 11259 -1 11260 -1 11261 -1 11262 -1 11263 -1 11264 -1 11265 -1 11266 -1 11267 -1 11268 -1 11269 -1 11270 -1 11271 -1 11272 -1 11273 -1 11274 -1 11275 -1 11276 -1 11277 -1 11278 -1 11279 -1 11280 -1 11281 -1 11282 -1 11283 -1 11284 -1 11285 -1 11286 -1 11287 -1 11288 -1 11289 -1 11290 -1 11291 -1 11292 -1 11293 -1 11294 -1 11295 -1 11296 -1 11297 -1 11298 -1 11299 -1 11300 -1 11301 -1 11302 -1 11303 -1 11304 -1 11305 -1 11306 -1 11307 -1 11308 -1 11309 -1 11310 -1 11311 -1 11312 -1 11313 -1 11314 -1 11315 -1 11316 -1 11317 -1 11318 -1 11319 -1 11320 -1 11321 -1 11322 -1 11323 -1 11324 -1 11325 -1 11326 -1 11327 -1 11328 -1 11329 -1 11330 -1 11331 -1 11332 -1 11333 -1 11334 -1 11335 -1 11336 -1 11337 -1 11338 -1 11339 -1 11340 -1 11341 -1 11342 -1 11343 -1 11344 -1 11345 -1 11346 -1 11347 -1 11348 -1 11349 -1 11350 -1 11351 -1 11352 -1 11353 -1 11354 -1 11355 -1 11356 -1 11357 -1 11358 -1 11359 -1 11360 -1 11361 -1 11362 -1 11363 -1 11364 -1 11365 -1 11366 -1 11367 -1 11368 -1 11369 -1 11370 -1 11371 -1 11372 -1 11373 -1 11374 -1 11375 -1 11376 -1 11377 -1 11378 -1 11379 -1 11380 -1 11381 -1 11382 -1 11383 -1 11384 -1 11385 -1 11386 -1 11387 -1 11388 -1 11389 -1 11390 -1 11391 -1 11392 -1 11393 -1 11394 -1 11395 -1 11396 -1 11397 -1 11398 -1 11399 -1 11400 -1 11401 -1 11402 -1 11403 -1 11404 -1 11405 -1 11406 -1 11407 -1 11408 -1 11409 -1 11410 -1 11411 -1 11412 -1 11413 -1 11414 -1 11415 -1 11416 -1 11417 -1 11418 -1 11419 -1 11420 -1 11421 -1 11422 -1 11423 -1 11424 -1 11425 -1 11426 -1 11427 -1 11428 -1 11429 -1 11430 -1 11431 -1 11432 -1 11433 -1 11434 -1 11435 -1 11436 -1 11437 -1 11438 -1 11439 -1 11440 -1 11441 -1 11442 -1 11443 -1 11444 -1 11445 -1 11446 -1 11447 -1 11448 -1 11449 -1 11450 -1 11451 -1 11452 -1 11453 -1 11454 -1 11455 -1 11456 -1 11457 -1 11458 -1 11459 -1 11460 -1 11461 -1 11462 -1 11463 -1 11464 -1 11465 -1 11466 -1 11467 -1 11468 -1 11469 -1 11470 -1 11471 -1 11472 -1 11473 -1 11474 -1 11475 -1 11476 -1 11477 -1 11478 -1 11479 -1 11480 -1 11481 -1 11482 -1 11483 -1 11484 -1 11485 -1 11486 -1 11487 -1 11488 -1 11489 -1 11490 -1 11491 -1 11492 -1 11493 -1 11494 -1 11495 -1 11496 -1 11497 -1 11498 -1 11499 -1 11500 -1 11501 -1 11502 -1 11503 -1 11504 -1 11505 -1 11506 -1 11507 -1 11508 -1 11509 -1 11510 -1 11511 -1 11512 -1 11513 -1 11514 -1 11515 -1 11516 -1 11517 -1 11518 -1 11519 -1 11520 -1 11521 -1 11522 -1 11523 -1 11524 -1 11525 -1 11526 -1 11527 -1 11528 -1 11529 -1 11530 -1 11531 -1 11532 -1 11533 -1 11534 -1 11535 -1 11536 -1 11537 -1 11538 -1 11539 -1 11540 -1 11541 -1 11542 -1 11543 -1 11544 -1 11545 -1 11546 -1 11547 -1 11548 -1 11549 -1 11550 -1 11551 -1 11552 -1 11553 -1 11554 -1 11555 -1 11556 -1 11557 -1 11558 -1 11559 -1 11560 -1 11561 -1 11562 -1 11563 -1 11564 -1 11565 -1 11566 -1 11567 -1 11568 -1 11569 -1 11570 -1 11571 -1 11572 -1 11573 -1 11574 -1 11575 -1 11576 -1 11577 -1 11578 -1 11579 -1 11580 -1 11581 -1 11582 -1 11583 -1 11584 -1 11585 -1 11586 -1 11587 -1 11588 -1 11589 -1 11590 -1 11591 -1 11592 -1 11593 -1 11594 -1 11595 -1 11596 -1 11597 -1 11598 -1 11599 -1 11600 -1 11601 -1 11602 -1 11603 -1 11604 -1 11605 -1 11606 -1 11607 -1 11608 -1 11609 -1 11610 -1 11611 -1 11612 -1 11613 -1 11614 -1 11615 -1 11616 -1 11617 -1 11618 -1 11619 -1 11620 -1 11621 -1 11622 -1 11623 -1 11624 -1 11625 -1 11626 -1 11627 -1 11628 -1 11629 -1 11630 -1 11631 -1 11632 -1 11633 -1 11634 -1 11635 -1 11636 -1 11637 -1 11638 -1 11639 -1 11640 -1 11641 -1 11642 -1 11643 -1 11644 -1 11645 -1 11646 -1 11647 -1 11648 -1 11649 -1 11650 -1 11651 -1 11652 -1 11653 -1 11654 -1 11655 -1 11656 -1 11657 -1 11658 -1 11659 -1 11660 -1 11661 -1 11662 -1 11663 -1 11664 -1 11665 -1 11666 -1 11667 -1 11668 -1 11669 -1 11670 -1 11671 -1 11672 -1 11673 -1 11674 -1 11675 -1 11676 -1 11677 -1 11678 -1 11679 -1 11680 -1 11681 -1 11682 -1 11683 -1 11684 -1 11685 -1 11686 -1 11687 -1 11688 -1 11689 -1 11690 -1 11691 -1 11692 -1 11693 -1 11694 -1 11695 -1 11696 -1 11697 -1 11698 -1 11699 -1 11700 -1 11701 -1 11702 -1 11703 -1 11704 -1 11705 -1 11706 -1 11707 -1 11708 -1 11709 -1 11710 -1 11711 -1 11712 -1 11713 -1 11714 -1 11715 -1 11716 -1 11717 -1 11718 -1 11719 -1 11720 -1 11721 -1 11722 -1 11723 -1 11724 -1 11725 -1 11726 -1 11727 -1 11728 -1 11729 -1 11730 -1 11731 -1 11732 -1 11733 -1 11734 -1 11735 -1 11736 -1 11737 -1 11738 -1 11739 -1 11740 -1 11741 -1 11742 -1 11743 -1 11744 -1 11745 -1 11746 -1 11747 -1 11748 -1 11749 -1 11750 -1 11751 -1 11752 -1 11753 -1 11754 -1 11755 -1 11756 -1 11757 -1 11758 -1 11759 -1 11760 -1 11761 -1 11762 -1 11763 -1 11764 -1 11765 -1 11766 -1 11767 -1 11768 -1 11769 -1 11770 -1 11771 -1 11772 -1 11773 -1 11774 -1 11775 -1 11776 -1 11777 -1 11778 -1 11779 -1 11780 -1 11781 -1 11782 -1 11783 -1 11784 -1 11785 -1 11786 -1 11787 -1 11788 -1 11789 -1 11790 -1 11791 -1 11792 -1 11793 -1 11794 -1 11795 -1 11796 -1 11797 -1 11798 -1 11799 -1 11800 -1 11801 -1 11802 -1 11803 -1 11804 -1 11805 -1 11806 -1 11807 -1 11808 -1 11809 -1 11810 -1 11811 -1 11812 -1 11813 -1 11814 -1 11815 -1 11816 -1 11817 -1 11818 -1 11819 -1 11820 -1 11821 -1 11822 -1 11823 -1 11824 -1 11825 -1 11826 -1 11827 -1 11828 -1 11829 -1 11830 -1 11831 -1 11832 -1 11833 -1 11834 -1 11835 -1 11836 -1 11837 -1 11838 -1 11839 -1 11840 -1 11841 -1 11842 -1 11843 -1 11844 -1 11845 -1 11846 -1 11847 -1 11848 -1 11849 -1 11850 -1 11851 -1 11852 -1 11853 -1 11854 -1 11855 -1 11856 -1 11857 -1 11858 -1 11859 -1 11860 -1 11861 -1 11862 -1 11863 -1 11864 -1 11865 -1 11866 -1 11867 -1 11868 -1 11869 -1 11870 -1 11871 -1 11872 -1 11873 -1 11874 -1 11875 -1 11876 -1 11877 -1 11878 -1 11879 -1 11880 -1 11881 -1 11882 -1 11883 -1 11884 -1 11885 -1 11886 -1 11887 -1 11888 -1 11889 -1 11890 -1 11891 -1 11892 -1 11893 -1 11894 -1 11895 -1 11896 -1 11897 -1 11898 -1 11899 -1 11900 -1 11901 -1 11902 -1 11903 -1 11904 -1 11905 -1 11906 -1 11907 -1 11908 -1 11909 -1 11910 -1 11911 -1 11912 -1 11913 -1 11914 -1 11915 -1 11916 -1 11917 -1 11918 -1 11919 -1 11920 -1 11921 -1 11922 -1 11923 -1 11924 -1 11925 -1 11926 -1 11927 -1 11928 -1 11929 -1 11930 -1 11931 -1 11932 -1 11933 -1 11934 -1 11935 -1 11936 -1 11937 -1 11938 -1 11939 -1 11940 -1 11941 -1 11942 -1 11943 -1 11944 -1 11945 -1 11946 -1 11947 -1 11948 -1 11949 -1 11950 -1 11951 -1 11952 -1 11953 -1 11954 -1 11955 -1 11956 -1 11957 -1 11958 -1 11959 -1 11960 -1 11961 -1 11962 -1 11963 -1 11964 -1 11965 -1 11966 -1 11967 -1 11968 -1 11969 -1 11970 -1 11971 -1 11972 -1 11973 -1 11974 -1 11975 -1 11976 -1 11977 -1 11978 -1 11979 -1 11980 -1 11981 -1 11982 -1 11983 -1 11984 -1 11985 -1 11986 -1 11987 -1 11988 -1 11989 -1 11990 -1 11991 -1 11992 -1 11993 -1 11994 -1 11995 -1 11996 -1 11997 -1 11998 -1 11999 -1 12000 -1 12001 -1 12002 -1 12003 -1 12004 -1 12005 -1 12006 -1 12007 -1 12008 -1 12009 -1 12010 -1 12011 -1 12012 -1 12013 -1 12014 -1 12015 -1 12016 -1 12017 -1 12018 -1 12019 -1 12020 -1 12021 -1 12022 -1 12023 -1 12024 -1 12025 -1 12026 -1 12027 -1 12028 -1 12029 -1 12030 -1 12031 -1 12032 -1 12033 -1 12034 -1 12035 -1 12036 -1 12037 -1 12038 -1 12039 -1 12040 -1 12041 -1 12042 -1 12043 -1 12044 -1 12045 -1 12046 -1 12047 -1 12048 -1 12049 -1 12050 -1 12051 -1 12052 -1 12053 -1 12054 -1 12055 -1 12056 -1 12057 -1 12058 -1 12059 -1 12060 -1 12061 -1 12062 -1 12063 -1 12064 -1 12065 -1 12066 -1 12067 -1 12068 -1 12069 -1 12070 -1 12071 -1 12072 -1 12073 -1 12074 -1 12075 -1 12076 -1 12077 -1 12078 -1 12079 -1 12080 -1 12081 -1 12082 -1 12083 -1 12084 -1 12085 -1 12086 -1 12087 -1 12088 -1 12089 -1 12090 -1 12091 -1 12092 -1 12093 -1 12094 -1 12095 -1 12096 -1 12097 -1 12098 -1 12099 -1 12100 -1 12101 -1 12102 -1 12103 -1 12104 -1 12105 -1 12106 -1 12107 -1 12108 -1 12109 -1 12110 -1 12111 -1 12112 -1 12113 -1 12114 -1 12115 -1 12116 -1 12117 -1 12118 -1 12119 -1 12120 -1 12121 -1 12122 -1 12123 -1 12124 -1 12125 -1 12126 -1 12127 -1 12128 -1 12129 -1 12130 -1 12131 -1 12132 -1 12133 -1 12134 -1 12135 -1 12136 -1 12137 -1 12138 -1 12139 -1 12140 -1 12141 -1 12142 -1 12143 -1 12144 -1 12145 -1 12146 -1 12147 -1 12148 -1 12149 -1 12150 -1 12151 -1 12152 -1 12153 -1 12154 -1 12155 -1 12156 -1 12157 -1 12158 -1 12159 -1 12160 -1 12161 -1 12162 -1 12163 -1 12164 -1 12165 -1 12166 -1 12167 -1 12168 -1 12169 -1 12170 -1 12171 -1 12172 -1 12173 -1 12174 -1 12175 -1 12176 -1 12177 -1 12178 -1 12179 -1 12180 -1 12181 -1 12182 -1 12183 -1 12184 -1 12185 -1 12186 -1 12187 -1 12188 -1 12189 -1 12190 -1 12191 -1 12192 -1 12193 -1 12194 -1 12195 -1 12196 -1 12197 -1 12198 -1 12199 -1 12200 -1 12201 -1 12202 -1 12203 -1 12204 -1 12205 -1 12206 -1 12207 -1 12208 -1 12209 -1 12210 -1 12211 -1 12212 -1 12213 -1 12214 -1 12215 -1 12216 -1 12217 -1 12218 -1 12219 -1 12220 -1 12221 -1 12222 -1 12223 -1 12224 -1 12225 -1 12226 -1 12227 -1 12228 -1 12229 -1 12230 -1 12231 -1 12232 -1 12233 -1 12234 -1 12235 -1 12236 -1 12237 -1 12238 -1 12239 -1 12240 -1 12241 -1 12242 -1 12243 -1 12244 -1 12245 -1 12246 -1 12247 -1 12248 -1 12249 -1 12250 -1 12251 -1 12252 -1 12253 -1 12254 -1 12255 -1 12256 -1 12257 -1 12258 -1 12259 -1 12260 -1 12261 -1 12262 -1 12263 -1 12264 -1 12265 -1 12266 -1 12267 -1 12268 -1 12269 -1 12270 -1 12271 -1 12272 -1 12273 -1 12274 -1 12275 -1 12276 -1 12277 -1 12278 -1 12279 -1 12280 -1 12281 -1 12282 -1 12283 -1 12284 -1 12285 -1 12286 -1 12287 -1 12288 -1 12289 -1 12290 -1 12291 -1 12292 -1 12293 -1 12294 -1 12295 -1 12296 -1 12297 -1 12298 -1 12299 -1 12300 -1 12301 -1 12302 -1 12303 -1 12304 -1 12305 -1 12306 -1 12307 -1 12308 -1 12309 -1 12310 -1 12311 -1 12312 -1 12313 -1 12314 -1 12315 -1 12316 -1 12317 -1 12318 -1 12319 -1 12320 -1 12321 -1 12322 -1 12323 -1 12324 -1 12325 -1 12326 -1 12327 -1 12328 -1 12329 -1 12330 -1 12331 -1 12332 -1 12333 -1 12334 -1 12335 -1 12336 -1 12337 -1 12338 -1 12339 -1 12340 -1 12341 -1 12342 -1 12343 -1 12344 -1 12345 -1 12346 -1 12347 -1 12348 -1 12349 -1 12350 -1 12351 -1 12352 -1 12353 -1 12354 -1 12355 -1 12356 -1 12357 -1 12358 -1 12359 -1 12360 -1 12361 -1 12362 -1 12363 -1 12364 -1 12365 -1 12366 -1 12367 -1 12368 -1 12369 -1 12370 -1 12371 -1 12372 -1 12373 -1 12374 -1 12375 -1 12376 -1 12377 -1 12378 -1 12379 -1 12380 -1 12381 -1 12382 -1 12383 -1 12384 -1 12385 -1 12386 -1 12387 -1 12388 -1 12389 -1 12390 -1 12391 -1 12392 -1 12393 -1 12394 -1 12395 -1 12396 -1 12397 -1 12398 -1 12399 -1 12400 -1 12401 -1 12402 -1 12403 -1 12404 -1 12405 -1 12406 -1 12407 -1 12408 -1 12409 -1 12410 -1 12411 -1 12412 -1 12413 -1 12414 -1 12415 -1 12416 -1 12417 -1 12418 -1 12419 -1 12420 -1 12421 -1 12422 -1 12423 -1 12424 -1 12425 -1 12426 -1 12427 -1 12428 -1 12429 -1 12430 -1 12431 -1 12432 -1 12433 -1 12434 -1 12435 -1 12436 -1 12437 -1 12438 -1 12439 -1 12440 -1 12441 -1 12442 -1 12443 -1 12444 -1 12445 -1 12446 -1 12447 -1 12448 -1 12449 -1 12450 -1 12451 -1 12452 -1 12453 -1 12454 -1 12455 -1 12456 -1 12457 -1 12458 -1 12459 -1 12460 -1 12461 -1 12462 -1 12463 -1 12464 -1 12465 -1 12466 -1 12467 -1 12468 -1 12469 -1 12470 -1 12471 -1 12472 -1 12473 -1 12474 -1 12475 -1 12476 -1 12477 -1 12478 -1 12479 -1 12480 -1 12481 -1 12482 -1 12483 -1 12484 -1 12485 -1 12486 -1 12487 -1 12488 -1 12489 -1 12490 -1 12491 -1 12492 -1 12493 -1 12494 -1 12495 -1 12496 -1 12497 -1 12498 -1 12499 -1 12500 -1 12501 -1 12502 -1 12503 -1 12504 -1 12505 -1 12506 -1 12507 -1 12508 -1 12509 -1 12510 -1 12511 -1 12512 -1 12513 -1 12514 -1 12515 -1 12516 -1 12517 -1 12518 -1 12519 -1 12520 -1 12521 -1 12522 -1 12523 -1 12524 -1 12525 -1 12526 -1 12527 -1 12528 -1 12529 -1 12530 -1 12531 -1 12532 -1 12533 -1 12534 -1 12535 -1 12536 -1 12537 -1 12538 -1 12539 -1 12540 -1 12541 -1 12542 -1 12543 -1 12544 -1 12545 -1 12546 -1 12547 -1 12548 -1 12549 -1 12550 -1 12551 -1 12552 -1 12553 -1 12554 -1 12555 -1 12556 -1 12557 -1 12558 -1 12559 -1 12560 -1 12561 -1 12562 -1 12563 -1 12564 -1 12565 -1 12566 -1 12567 -1 12568 -1 12569 -1 12570 -1 12571 -1 12572 -1 12573 -1 12574 -1 12575 -1 12576 -1 12577 -1 12578 -1 12579 -1 12580 -1 12581 -1 12582 -1 12583 -1 12584 -1 12585 -1 12586 -1 12587 -1 12588 -1 12589 -1 12590 -1 12591 -1 12592 -1 12593 -1 12594 -1 12595 -1 12596 -1 12597 -1 12598 -1 12599 -1 12600 -1 12601 -1 12602 -1 12603 -1 12604 -1 12605 -1 12606 -1 12607 -1 12608 -1 12609 -1 12610 -1 12611 -1 12612 -1 12613 -1 12614 -1 12615 -1 12616 -1 12617 -1 12618 -1 12619 -1 12620 -1 12621 -1 12622 -1 12623 -1 12624 -1 12625 -1 12626 -1 12627 -1 12628 -1 12629 -1 12630 -1 12631 -1 12632 -1 12633 -1 12634 -1 12635 -1 12636 -1 12637 -1 12638 -1 12639 -1 12640 -1 12641 -1 12642 -1 12643 -1 12644 -1 12645 -1 12646 -1 12647 -1 12648 -1 12649 -1 12650 -1 12651 -1 12652 -1 12653 -1 12654 -1 12655 -1 12656 -1 12657 -1 12658 -1 12659 -1 12660 -1 12661 -1 12662 -1 12663 -1 12664 -1 12665 -1 12666 -1 12667 -1 12668 -1 12669 -1 12670 -1 12671 -1 12672 -1 12673 -1 12674 -1 12675 -1 12676 -1 12677 -1 12678 -1 12679 -1 12680 -1 12681 -1 12682 -1 12683 -1 12684 -1 12685 -1 12686 -1 12687 -1 12688 -1 12689 -1 12690 -1 12691 -1 12692 -1 12693 -1 12694 -1 12695 -1 12696 -1 12697 -1 12698 -1 12699 -1 12700 -1 12701 -1 12702 -1 12703 -1 12704 -1 12705 -1 12706 -1 12707 -1 12708 -1 12709 -1 12710 -1 12711 -1 12712 -1 12713 -1 12714 -1 12715 -1 12716 -1 12717 -1 12718 -1 12719 -1 12720 -1 12721 -1 12722 -1 12723 -1 12724 -1 12725 -1 12726 -1 12727 -1 12728 -1 12729 -1 12730 -1 12731 -1 12732 -1 12733 -1 12734 -1 12735 -1 12736 -1 12737 -1 12738 -1 12739 -1 12740 -1 12741 -1 12742 -1 12743 -1 12744 -1 12745 -1 12746 -1 12747 -1 12748 -1 12749 -1 12750 -1 12751 -1 12752 -1 12753 -1 12754 -1 12755 -1 12756 -1 12757 -1 12758 -1 12759 -1 12760 -1 12761 -1 12762 -1 12763 -1 12764 -1 12765 -1 12766 -1 12767 -1 12768 -1 12769 -1 12770 -1 12771 -1 12772 -1 12773 -1 12774 -1 12775 -1 12776 -1 12777 -1 12778 -1 12779 -1 12780 -1 12781 -1 12782 -1 12783 -1 12784 -1 12785 -1 12786 -1 12787 -1 12788 -1 12789 -1 12790 -1 12791 -1 12792 -1 12793 -1 12794 -1 12795 -1 12796 -1 12797 -1 12798 -1 12799 -1 12800 -1 12801 -1 12802 -1 12803 -1 12804 -1 12805 -1 12806 -1 12807 -1 12808 -1 12809 -1 12810 -1 12811 -1 12812 -1 12813 -1 12814 -1 12815 -1 12816 -1 12817 -1 12818 -1 12819 -1 12820 -1 12821 -1 12822 -1 12823 -1 12824 -1 12825 -1 12826 -1 12827 -1 12828 -1 12829 -1 12830 -1 12831 -1 12832 -1 12833 -1 12834 -1 12835 -1 12836 -1 12837 -1 12838 -1 12839 -1 12840 -1 12841 -1 12842 -1 12843 -1 12844 -1 12845 -1 12846 -1 12847 -1 12848 -1 12849 -1 12850 -1 12851 -1 12852 -1 12853 -1 12854 -1 12855 -1 12856 -1 12857 -1 12858 -1 12859 -1 12860 -1 12861 -1 12862 -1 12863 -1 12864 -1 12865 -1 12866 -1 12867 -1 12868 -1 12869 -1 12870 -1 12871 -1 12872 -1 12873 -1 12874 -1 12875 -1 12876 -1 12877 -1 12878 -1 12879 -1 12880 -1 12881 -1 12882 -1 12883 -1 12884 -1 12885 -1 12886 -1 12887 -1 12888 -1 12889 -1 12890 -1 12891 -1 12892 -1 12893 -1 12894 -1 12895 -1 12896 -1 12897 -1 12898 -1 12899 -1 12900 -1 12901 -1 12902 -1 12903 -1 12904 -1 12905 -1 12906 -1 12907 -1 12908 -1 12909 -1 12910 -1 12911 -1 12912 -1 12913 -1 12914 -1 12915 -1 12916 -1 12917 -1 12918 -1 12919 -1 12920 -1 12921 -1 12922 -1 12923 -1 12924 -1 12925 -1 12926 -1 12927 -1 12928 -1 12929 -1 12930 -1 12931 -1 12932 -1 12933 -1 12934 -1 12935 -1 12936 -1 12937 -1 12938 -1 12939 -1 12940 -1 12941 -1 12942 -1 12943 -1 12944 -1 12945 -1 12946 -1 12947 -1 12948 -1 12949 -1 12950 -1 12951 -1 12952 -1 12953 -1 12954 -1 12955 -1 12956 -1 12957 -1 12958 -1 12959 -1 12960 -1 12961 -1 12962 -1 12963 -1 12964 -1 12965 -1 12966 -1 12967 -1 12968 -1 12969 -1 12970 -1 12971 -1 12972 -1 12973 -1 12974 -1 12975 -1 12976 -1 12977 -1 12978 -1 12979 -1 12980 -1 12981 -1 12982 -1 12983 -1 12984 -1 12985 -1 12986 -1 12987 -1 12988 -1 12989 -1 12990 -1 12991 -1 12992 -1 12993 -1 12994 -1 12995 -1 12996 -1 12997 -1 12998 -1 12999 -1 13000 -1 13001 -1 13002 -1 13003 -1 13004 -1 13005 -1 13006 -1 13007 -1 13008 -1 13009 -1 13010 -1 13011 -1 13012 -1 13013 -1 13014 -1 13015 -1 13016 -1 13017 -1 13018 -1 13019 -1 13020 -1 13021 -1 13022 -1 13023 -1 13024 -1 13025 -1 13026 -1 13027 -1 13028 -1 13029 -1 13030 -1 13031 -1 13032 -1 13033 -1 13034 -1 13035 -1 13036 -1 13037 -1 13038 -1 13039 -1 13040 -1 13041 -1 13042 -1 13043 -1 13044 -1 13045 -1 13046 -1 13047 -1 13048 -1 13049 -1 13050 -1 13051 -1 13052 -1 13053 -1 13054 -1 13055 -1 13056 -1 13057 -1 13058 -1 13059 -1 13060 -1 13061 -1 13062 -1 13063 -1 13064 -1 13065 -1 13066 -1 13067 -1 13068 -1 13069 -1 13070 -1 13071 -1 13072 -1 13073 -1 13074 -1 13075 -1 13076 -1 13077 -1 13078 -1 13079 -1 13080 -1 13081 -1 13082 -1 13083 -1 13084 -1 13085 -1 13086 -1 13087 -1 13088 -1 13089 -1 13090 -1 13091 -1 13092 -1 13093 -1 13094 -1 13095 -1 13096 -1 13097 -1 13098 -1 13099 -1 13100 -1 13101 -1 13102 -1 13103 -1 13104 -1 13105 -1 13106 -1 13107 -1 13108 -1 13109 -1 13110 -1 13111 -1 13112 -1 13113 -1 13114 -1 13115 -1 13116 -1 13117 -1 13118 -1 13119 -1 13120 -1 13121 -1 13122 -1 13123 -1 13124 -1 13125 -1 13126 -1 13127 -1 13128 -1 13129 -1 13130 -1 13131 -1 13132 -1 13133 -1 13134 -1 13135 -1 13136 -1 13137 -1 13138 -1 13139 -1 13140 -1 13141 -1 13142 -1 13143 -1 13144 -1 13145 -1 13146 -1 13147 -1 13148 -1 13149 -1 13150 -1 13151 -1 13152 -1 13153 -1 13154 -1 13155 -1 13156 -1 13157 -1 13158 -1 13159 -1 13160 -1 13161 -1 13162 -1 13163 -1 13164 -1 13165 -1 13166 -1 13167 -1 13168 -1 13169 -1 13170 -1 13171 -1 13172 -1 13173 -1 13174 -1 13175 -1 13176 -1 13177 -1 13178 -1 13179 -1 13180 -1 13181 -1 13182 -1 13183 -1 13184 -1 13185 -1 13186 -1 13187 -1 13188 -1 13189 -1 13190 -1 13191 -1 13192 -1 13193 -1 13194 -1 13195 -1 13196 -1 13197 -1 13198 -1 13199 -1 13200 -1 13201 -1 13202 -1 13203 -1 13204 -1 13205 -1 13206 -1 13207 -1 13208 -1 13209 -1 13210 -1 13211 -1 13212 -1 13213 -1 13214 -1 13215 -1 13216 -1 13217 -1 13218 -1 13219 -1 13220 -1 13221 -1 13222 -1 13223 -1 13224 -1 13225 -1 13226 -1 13227 -1 13228 -1 13229 -1 13230 -1 13231 -1 13232 -1 13233 -1 13234 -1 13235 -1 13236 -1 13237 -1 13238 -1 13239 -1 13240 -1 13241 -1 13242 -1 13243 -1 13244 -1 13245 -1 13246 -1 13247 -1 13248 -1 13249 -1 13250 -1 13251 -1 13252 -1 13253 -1 13254 -1 13255 -1 13256 -1 13257 -1 13258 -1 13259 -1 13260 -1 13261 -1 13262 -1 13263 -1 13264 -1 13265 -1 13266 -1 13267 -1 13268 -1 13269 -1 13270 -1 13271 -1 13272 -1 13273 -1 13274 -1 13275 -1 13276 -1 13277 -1 13278 -1 13279 -1 13280 -1 13281 -1 13282 -1 13283 -1 13284 -1 13285 -1 13286 -1 13287 -1 13288 -1 13289 -1 13290 -1 13291 -1 13292 -1 13293 -1 13294 -1 13295 -1 13296 -1 13297 -1 13298 -1 13299 -1 13300 -1 13301 -1 13302 -1 13303 -1 13304 -1 13305 -1 13306 -1 13307 -1 13308 -1 13309 -1 13310 -1 13311 -1 13312 -1 13313 -1 13314 -1 13315 -1 13316 -1 13317 -1 13318 -1 13319 -1 13320 -1 13321 -1 13322 -1 13323 -1 13324 -1 13325 -1 13326 -1 13327 -1 13328 -1 13329 -1 13330 -1 13331 -1 13332 -1 13333 -1 13334 -1 13335 -1 13336 -1 13337 -1 13338 -1 13339 -1 13340 -1 13341 -1 13342 -1 13343 -1 13344 -1 13345 -1 13346 -1 13347 -1 13348 -1 13349 -1 13350 -1 13351 -1 13352 -1 13353 -1 13354 -1 13355 -1 13356 -1 13357 -1 13358 -1 13359 -1 13360 -1 13361 -1 13362 -1 13363 -1 13364 -1 13365 -1 13366 -1 13367 -1 13368 -1 13369 -1 13370 -1 13371 -1 13372 -1 13373 -1 13374 -1 13375 -1 13376 -1 13377 -1 13378 -1 13379 -1 13380 -1 13381 -1 13382 -1 13383 -1 13384 -1 13385 -1 13386 -1 13387 -1 13388 -1 13389 -1 13390 -1 13391 -1 13392 -1 13393 -1 13394 -1 13395 -1 13396 -1 13397 -1 13398 -1 13399 -1 13400 -1 13401 -1 13402 -1 13403 -1 13404 -1 13405 -1 13406 -1 13407 -1 13408 -1 13409 -1 13410 -1 13411 -1 13412 -1 13413 -1 13414 -1 13415 -1 13416 -1 13417 -1 13418 -1 13419 -1 13420 -1 13421 -1 13422 -1 13423 -1 13424 -1 13425 -1 13426 -1 13427 -1 13428 -1 13429 -1 13430 -1 13431 -1 13432 -1 13433 -1 13434 -1 13435 -1 13436 -1 13437 -1 13438 -1 13439 -1 13440 -1 13441 -1 13442 -1 13443 -1 13444 -1 13445 -1 13446 -1 13447 -1 13448 -1 13449 -1 13450 -1 13451 -1 13452 -1 13453 -1 13454 -1 13455 -1 13456 -1 13457 -1 13458 -1 13459 -1 13460 -1 13461 -1 13462 -1 13463 -1 13464 -1 13465 -1 13466 -1 13467 -1 13468 -1 13469 -1 13470 -1 13471 -1 13472 -1 13473 -1 13474 -1 13475 -1 13476 -1 13477 -1 13478 -1 13479 -1 13480 -1 13481 -1 13482 -1 13483 -1 13484 -1 13485 -1 13486 -1 13487 -1 13488 -1 13489 -1 13490 -1 13491 -1 13492 -1 13493 -1 13494 -1 13495 -1 13496 -1 13497 -1 13498 -1 13499 -1 13500 -1 13501 -1 13502 -1 13503 -1 13504 -1 13505 -1 13506 -1 13507 -1 13508 -1 13509 -1 13510 -1 13511 -1 13512 -1 13513 -1 13514 -1 13515 -1 13516 -1 13517 -1 13518 -1 13519 -1 13520 -1 13521 -1 13522 -1 13523 -1 13524 -1 13525 -1 13526 -1 13527 -1 13528 -1 13529 -1 13530 -1 13531 -1 13532 -1 13533 -1 13534 -1 13535 -1 13536 -1 13537 -1 13538 -1 13539 -1 13540 -1 13541 -1 13542 -1 13543 -1 13544 -1 13545 -1 13546 -1 13547 -1 13548 -1 13549 -1 13550 -1 13551 -1 13552 -1 13553 -1 13554 -1 13555 -1 13556 -1 13557 -1 13558 -1 13559 -1 13560 -1 13561 -1 13562 -1 13563 -1 13564 -1 13565 -1 13566 -1 13567 -1 13568 -1 13569 -1 13570 -1 13571 -1 13572 -1 13573 -1 13574 -1 13575 -1 13576 -1 13577 -1 13578 -1 13579 -1 13580 -1 13581 -1 13582 -1 13583 -1 13584 -1 13585 -1 13586 -1 13587 -1 13588 -1 13589 -1 13590 -1 13591 -1 13592 -1 13593 -1 13594 -1 13595 -1 13596 -1 13597 -1 13598 -1 13599 -1 13600 -1 13601 -1 13602 -1 13603 -1 13604 -1 13605 -1 13606 -1 13607 -1 13608 -1 13609 -1 13610 -1 13611 -1 13612 -1 13613 -1 13614 -1 13615 -1 13616 -1 13617 -1 13618 -1 13619 -1 13620 -1 13621 -1 13622 -1 13623 -1 13624 -1 13625 -1 13626 -1 13627 -1 13628 -1 13629 -1 13630 -1 13631 -1 13632 -1 13633 -1 13634 -1 13635 -1 13636 -1 13637 -1 13638 -1 13639 -1 13640 -1 13641 -1 13642 -1 13643 -1 13644 -1 13645 -1 13646 -1 13647 -1 13648 -1 13649 -1 13650 -1 13651 -1 13652 -1 13653 -1 13654 -1 13655 -1 13656 -1 13657 -1 13658 -1 13659 -1 13660 -1 13661 -1 13662 -1 13663 -1 13664 -1 13665 -1 13666 -1 13667 -1 13668 -1 13669 -1 13670 -1 13671 -1 13672 -1 13673 -1 13674 -1 13675 -1 13676 -1 13677 -1 13678 -1 13679 -1 13680 -1 13681 -1 13682 -1 13683 -1 13684 -1 13685 -1 13686 -1 13687 -1 13688 -1 13689 -1 13690 -1 13691 -1 13692 -1 13693 -1 13694 -1 13695 -1 13696 -1 13697 -1 13698 -1 13699 -1 13700 -1 13701 -1 13702 -1 13703 -1 13704 -1 13705 -1 13706 -1 13707 -1 13708 -1 13709 -1 13710 -1 13711 -1 13712 -1 13713 -1 13714 -1 13715 -1 13716 -1 13717 -1 13718 -1 13719 -1 13720 -1 13721 -1 13722 -1 13723 -1 13724 -1 13725 -1 13726 -1 13727 -1 13728 -1 13729 -1 13730 -1 13731 -1 13732 -1 13733 -1 13734 -1 13735 -1 13736 -1 13737 -1 13738 -1 13739 -1 13740 -1 13741 -1 13742 -1 13743 -1 13744 -1 13745 -1 13746 -1 13747 -1 13748 -1 13749 -1 13750 -1 13751 -1 13752 -1 13753 -1 13754 -1 13755 -1 13756 -1 13757 -1 13758 -1 13759 -1 13760 -1 13761 -1 13762 -1 13763 -1 13764 -1 13765 -1 13766 -1 13767 -1 13768 -1 13769 -1 13770 -1 13771 -1 13772 -1 13773 -1 13774 -1 13775 -1 13776 -1 13777 -1 13778 -1 13779 -1 13780 -1 13781 -1 13782 -1 13783 -1 13784 -1 13785 -1 13786 -1 13787 -1 13788 -1 13789 -1 13790 -1 13791 -1 13792 -1 13793 -1 13794 -1 13795 -1 13796 -1 13797 -1 13798 -1 13799 -1 13800 -1 13801 -1 13802 -1 13803 -1 13804 -1 13805 -1 13806 -1 13807 -1 13808 -1 13809 -1 13810 -1 13811 -1 13812 -1 13813 -1 13814 -1 13815 -1 13816 -1 13817 -1 13818 -1 13819 -1 13820 -1 13821 -1 13822 -1 13823 -1 13824 -1 13825 -1 13826 -1 13827 -1 13828 -1 13829 -1 13830 -1 13831 -1 13832 -1 13833 -1 13834 -1 13835 -1 13836 -1 13837 -1 13838 -1 13839 -1 13840 -1 13841 -1 13842 -1 13843 -1 13844 -1 13845 -1 13846 -1 13847 -1 13848 -1 13849 -1 13850 -1 13851 -1 13852 -1 13853 -1 13854 -1 13855 -1 13856 -1 13857 -1 13858 -1 13859 -1 13860 -1 13861 -1 13862 -1 13863 -1 13864 -1 13865 -1 13866 -1 13867 -1 13868 -1 13869 -1 13870 -1 13871 -1 13872 -1 13873 -1 13874 -1 13875 -1 13876 -1 13877 -1 13878 -1 13879 -1 13880 -1 13881 -1 13882 -1 13883 -1 13884 -1 13885 -1 13886 -1 13887 -1 13888 -1 13889 -1 13890 -1 13891 -1 13892 -1 13893 -1 13894 -1 13895 -1 13896 -1 13897 -1 13898 -1 13899 -1 13900 -1 13901 -1 13902 -1 13903 -1 13904 -1 13905 -1 13906 -1 13907 -1 13908 -1 13909 -1 13910 -1 13911 -1 13912 -1 13913 -1 13914 -1 13915 -1 13916 -1 13917 -1 13918 -1 13919 -1 13920 -1 13921 -1 13922 -1 13923 -1 13924 -1 13925 -1 13926 -1 13927 -1 13928 -1 13929 -1 13930 -1 13931 -1 13932 -1 13933 -1 13934 -1 13935 -1 13936 -1 13937 -1 13938 -1 13939 -1 13940 -1 13941 -1 13942 -1 13943 -1 13944 -1 13945 -1 13946 -1 13947 -1 13948 -1 13949 -1 13950 -1 13951 -1 13952 -1 13953 -1 13954 -1 13955 -1 13956 -1 13957 -1 13958 -1 13959 -1 13960 -1 13961 -1 13962 -1 13963 -1 13964 -1 13965 -1 13966 -1 13967 -1 13968 -1 13969 -1 13970 -1 13971 -1 13972 -1 13973 -1 13974 -1 13975 -1 13976 -1 13977 -1 13978 -1 13979 -1 13980 -1 13981 -1 13982 -1 13983 -1 13984 -1 13985 -1 13986 -1 13987 -1 13988 -1 13989 -1 13990 -1 13991 -1 13992 -1 13993 -1 13994 -1 13995 -1 13996 -1 13997 -1 13998 -1 13999 -1 14000 -1 14001 -1 14002 -1 14003 -1 14004 -1 14005 -1 14006 -1 14007 -1 14008 -1 14009 -1 14010 -1 14011 -1 14012 -1 14013 -1 14014 -1 14015 -1 14016 -1 14017 -1 14018 -1 14019 -1 14020 -1 14021 -1 14022 -1 14023 -1 14024 -1 14025 -1 14026 -1 14027 -1 14028 -1 14029 -1 14030 -1 14031 -1 14032 -1 14033 -1 14034 -1 14035 -1 14036 -1 14037 -1 14038 -1 14039 -1 14040 -1 14041 -1 14042 -1 14043 -1 14044 -1 14045 -1 14046 -1 14047 -1 14048 -1 14049 -1 14050 -1 14051 -1 14052 -1 14053 -1 14054 -1 14055 -1 14056 -1 14057 -1 14058 -1 14059 -1 14060 -1 14061 -1 14062 -1 14063 -1 14064 -1 14065 -1 14066 -1 14067 -1 14068 -1 14069 -1 14070 -1 14071 -1 14072 -1 14073 -1 14074 -1 14075 -1 14076 -1 14077 -1 14078 -1 14079 -1 14080 -1 14081 -1 14082 -1 14083 -1 14084 -1 14085 -1 14086 -1 14087 -1 14088 -1 14089 -1 14090 -1 14091 -1 14092 -1 14093 -1 14094 -1 14095 -1 14096 -1 14097 -1 14098 -1 14099 -1 14100 -1 14101 -1 14102 -1 14103 -1 14104 -1 14105 -1 14106 -1 14107 -1 14108 -1 14109 -1 14110 -1 14111 -1 14112 -1 14113 -1 14114 -1 14115 -1 14116 -1 14117 -1 14118 -1 14119 -1 14120 -1 14121 -1 14122 -1 14123 -1 14124 -1 14125 -1 14126 -1 14127 -1 14128 -1 14129 -1 14130 -1 14131 -1 14132 -1 14133 -1 14134 -1 14135 -1 14136 -1 14137 -1 14138 -1 14139 -1 14140 -1 14141 -1 14142 -1 14143 -1 14144 -1 14145 -1 14146 -1 14147 -1 14148 -1 14149 -1 14150 -1 14151 -1 14152 -1 14153 -1 14154 -1 14155 -1 14156 -1 14157 -1 14158 -1 14159 -1 14160 -1 14161 -1 14162 -1 14163 -1 14164 -1 14165 -1 14166 -1 14167 -1 14168 -1 14169 -1 14170 -1 14171 -1 14172 -1 14173 -1 14174 -1 14175 -1 14176 -1 14177 -1 14178 -1 14179 -1 14180 -1 14181 -1 14182 -1 14183 -1 14184 -1 14185 -1 14186 -1 14187 -1 14188 -1 14189 -1 14190 -1 14191 -1 14192 -1 14193 -1 14194 -1 14195 -1 14196 -1 14197 -1 14198 -1 14199 -1 14200 -1 14201 -1 14202 -1 14203 -1 14204 -1 14205 -1 14206 -1 14207 -1 14208 -1 14209 -1 14210 -1 14211 -1 14212 -1 14213 -1 14214 -1 14215 -1 14216 -1 14217 -1 14218 -1 14219 -1 14220 -1 14221 -1 14222 -1 14223 -1 14224 -1 14225 -1 14226 -1 14227 -1 14228 -1 14229 -1 14230 -1 14231 -1 14232 -1 14233 -1 14234 -1 14235 -1 14236 -1 14237 -1 14238 -1 14239 -1 14240 -1 14241 -1 14242 -1 14243 -1 14244 -1 14245 -1 14246 -1 14247 -1 14248 -1 14249 -1 14250 -1 14251 -1 14252 -1 14253 -1 14254 -1 14255 -1 14256 -1 14257 -1 14258 -1 14259 -1 14260 -1 14261 -1 14262 -1 14263 -1 14264 -1 14265 -1 14266 -1 14267 -1 14268 -1 14269 -1 14270 -1 14271 -1 14272 -1 14273 -1 14274 -1 14275 -1 14276 -1 14277 -1 14278 -1 14279 -1 14280 -1 14281 -1 14282 -1 14283 -1 14284 -1 14285 -1 14286 -1 14287 -1 14288 -1 14289 -1 14290 -1 14291 -1 14292 -1 14293 -1 14294 -1 14295 -1 14296 -1 14297 -1 14298 -1 14299 -1 14300 -1 14301 -1 14302 -1 14303 -1 14304 -1 14305 -1 14306 -1 14307 -1 14308 -1 14309 -1 14310 -1 14311 -1 14312 -1 14313 -1 14314 -1 14315 -1 14316 -1 14317 -1 14318 -1 14319 -1 14320 -1 14321 -1 14322 -1 14323 -1 14324 -1 14325 -1 14326 -1 14327 -1 14328 -1 14329 -1 14330 -1 14331 -1 14332 -1 14333 -1 14334 -1 14335 -1 14336 -1 14337 -1 14338 -1 14339 -1 14340 -1 14341 -1 14342 -1 14343 -1 14344 -1 14345 -1 14346 -1 14347 -1 14348 -1 14349 -1 14350 -1 14351 -1 14352 -1 14353 -1 14354 -1 14355 -1 14356 -1 14357 -1 14358 -1 14359 -1 14360 -1 14361 -1 14362 -1 14363 -1 14364 -1 14365 -1 14366 -1 14367 -1 14368 -1 14369 -1 14370 -1 14371 -1 14372 -1 14373 -1 14374 -1 14375 -1 14376 -1 14377 -1 14378 -1 14379 -1 14380 -1 14381 -1 14382 -1 14383 -1 14384 -1 14385 -1 14386 -1 14387 -1 14388 -1 14389 -1 14390 -1 14391 -1 14392 -1 14393 -1 14394 -1 14395 -1 14396 -1 14397 -1 14398 -1 14399 -1 14400 -1 14401 -1 14402 -1 14403 -1 14404 -1 14405 -1 14406 -1 14407 -1 14408 -1 14409 -1 14410 -1 14411 -1 14412 -1 14413 -1 14414 -1 14415 -1 14416 -1 14417 -1 14418 -1 14419 -1 14420 -1 14421 -1 14422 -1 14423 -1 14424 -1 14425 -1 14426 -1 14427 -1 14428 -1 14429 -1 14430 -1 14431 -1 14432 -1 14433 -1 14434 -1 14435 -1 14436 -1 14437 -1 14438 -1 14439 -1 14440 -1 14441 -1 14442 -1 14443 -1 14444 -1 14445 -1 14446 -1 14447 -1 14448 -1 14449 -1 14450 -1 14451 -1 14452 -1 14453 -1 14454 -1 14455 -1 14456 -1 14457 -1 14458 -1 14459 -1 14460 -1 14461 -1 14462 -1 14463 -1 14464 -1 14465 -1 14466 -1 14467 -1 14468 -1 14469 -1 14470 -1 14471 -1 14472 -1 14473 -1 14474 -1 14475 -1 14476 -1 14477 -1 14478 -1 14479 -1 14480 -1 14481 -1 14482 -1 14483 -1 14484 -1 14485 -1 14486 -1 14487 -1 14488 -1 14489 -1 14490 -1 14491 -1 14492 -1 14493 -1 14494 -1 14495 -1 14496 -1 14497 -1 14498 -1 14499 -1 14500 -1 14501 -1 14502 -1 14503 -1 14504 -1 14505 -1 14506 -1 14507 -1 14508 -1 14509 -1 14510 -1 14511 -1 14512 -1 14513 -1 14514 -1 14515 -1 14516 -1 14517 -1 14518 -1 14519 -1 14520 -1 14521 -1 14522 -1 14523 -1 14524 -1 14525 -1 14526 -1 14527 -1 14528 -1 14529 -1 14530 -1 14531 -1 14532 -1 14533 -1 14534 -1 14535 -1 14536 -1 14537 -1 14538 -1 14539 -1 14540 -1 14541 -1 14542 -1 14543 -1 14544 -1 14545 -1 14546 -1 14547 -1 14548 -1 14549 -1 14550 -1 14551 -1 14552 -1 14553 -1 14554 -1 14555 -1 14556 -1 14557 -1 14558 -1 14559 -1 14560 -1 14561 -1 14562 -1 14563 -1 14564 -1 14565 -1 14566 -1 14567 -1 14568 -1 14569 -1 14570 -1 14571 -1 14572 -1 14573 -1 14574 -1 14575 -1 14576 -1 14577 -1 14578 -1 14579 -1 14580 -1 14581 -1 14582 -1 14583 -1 14584 -1 14585 -1 14586 -1 14587 -1 14588 -1 14589 -1 14590 -1 14591 -1 14592 -1 14593 -1 14594 -1 14595 -1 14596 -1 14597 -1 14598 -1 14599 -1 14600 -1 14601 -1 14602 -1 14603 -1 14604 -1 14605 -1 14606 -1 14607 -1 14608 -1 14609 -1 14610 -1 14611 -1 14612 -1 14613 -1 14614 -1 14615 -1 14616 -1 14617 -1 14618 -1 14619 -1 14620 -1 14621 -1 14622 -1 14623 -1 14624 -1 14625 -1 14626 -1 14627 -1 14628 -1 14629 -1 14630 -1 14631 -1 14632 -1 14633 -1 14634 -1 14635 -1 14636 -1 14637 -1 14638 -1 14639 -1 14640 -1 14641 -1 14642 -1 14643 -1 14644 -1 14645 -1 14646 -1 14647 -1 14648 -1 14649 -1 14650 -1 14651 -1 14652 -1 14653 -1 14654 -1 14655 -1 14656 -1 14657 -1 14658 -1 14659 -1 14660 -1 14661 -1 14662 -1 14663 -1 14664 -1 14665 -1 14666 -1 14667 -1 14668 -1 14669 -1 14670 -1 14671 -1 14672 -1 14673 -1 14674 -1 14675 -1 14676 -1 14677 -1 14678 -1 14679 -1 14680 -1 14681 -1 14682 -1 14683 -1 14684 -1 14685 -1 14686 -1 14687 -1 14688 -1 14689 -1 14690 -1 14691 -1 14692 -1 14693 -1 14694 -1 14695 -1 14696 -1 14697 -1 14698 -1 14699 -1 14700 -1 14701 -1 14702 -1 14703 -1 14704 -1 14705 -1 14706 -1 14707 -1 14708 -1 14709 -1 14710 -1 14711 -1 14712 -1 14713 -1 14714 -1 14715 -1 14716 -1 14717 -1 14718 -1 14719 -1 14720 -1 14721 -1 14722 -1 14723 -1 14724 -1 14725 -1 14726 -1 14727 -1 14728 -1 14729 -1 14730 -1 14731 -1 14732 -1 14733 -1 14734 -1 14735 -1 14736 -1 14737 -1 14738 -1 14739 -1 14740 -1 14741 -1 14742 -1 14743 -1 14744 -1 14745 -1 14746 -1 14747 -1 14748 -1 14749 -1 14750 -1 14751 -1 14752 -1 14753 -1 14754 -1 14755 -1 14756 -1 14757 -1 14758 -1 14759 -1 14760 -1 14761 -1 14762 -1 14763 -1 14764 -1 14765 -1 14766 -1 14767 -1 14768 -1 14769 -1 14770 -1 14771 -1 14772 -1 14773 -1 14774 -1 14775 -1 14776 -1 14777 -1 14778 -1 14779 -1 14780 -1 14781 -1 14782 -1 14783 -1 14784 -1 14785 -1 14786 -1 14787 -1 14788 -1 14789 -1 14790 -1 14791 -1 14792 -1 14793 -1 14794 -1 14795 -1 14796 -1 14797 -1 14798 -1 14799 -1 14800 -1 14801 -1 14802 -1 14803 -1 14804 -1 14805 -1 14806 -1 14807 -1 14808 -1 14809 -1 14810 -1 14811 -1 14812 -1 14813 -1 14814 -1 14815 -1 14816 -1 14817 -1 14818 -1 14819 -1 14820 -1 14821 -1 14822 -1 14823 -1 14824 -1 14825 -1 14826 -1 14827 -1 14828 -1 14829 -1 14830 -1 14831 -1 14832 -1 14833 -1 14834 -1 14835 -1 14836 -1 14837 -1 14838 -1 14839 -1 14840 -1 14841 -1 14842 -1 14843 -1 14844 -1 14845 -1 14846 -1 14847 -1 14848 -1 14849 -1 14850 -1 14851 -1 14852 -1 14853 -1 14854 -1 14855 -1 14856 -1 14857 -1 14858 -1 14859 -1 14860 -1 14861 -1 14862 -1 14863 -1 14864 -1 14865 -1 14866 -1 14867 -1 14868 -1 14869 -1 14870 -1 14871 -1 14872 -1 14873 -1 14874 -1 14875 -1 14876 -1 14877 -1 14878 -1 14879 -1 14880 -1 14881 -1 14882 -1 14883 -1 14884 -1 14885 -1 14886 -1 14887 -1 14888 -1 14889 -1 14890 -1 14891 -1 14892 -1 14893 -1 14894 -1 14895 -1 14896 -1 14897 -1 14898 -1 14899 -1 14900 -1 14901 -1 14902 -1 14903 -1 14904 -1 14905 -1 14906 -1 14907 -1 14908 -1 14909 -1 14910 -1 14911 -1 14912 -1 14913 -1 14914 -1 14915 -1 14916 -1 14917 -1 14918 -1 14919 -1 14920 -1 14921 -1 14922 -1 14923 -1 14924 -1 14925 -1 14926 -1 14927 -1 14928 -1 14929 -1 14930 -1 14931 -1 14932 -1 14933 -1 14934 -1 14935 -1 14936 -1 14937 -1 14938 -1 14939 -1 14940 -1 14941 -1 14942 -1 14943 -1 14944 -1 14945 -1 14946 -1 14947 -1 14948 -1 14949 -1 14950 -1 14951 -1 14952 -1 14953 -1 14954 -1 14955 -1 14956 -1 14957 -1 14958 -1 14959 -1 14960 -1 14961 -1 14962 -1 14963 -1 14964 -1 14965 -1 14966 -1 14967 -1 14968 -1 14969 -1 14970 -1 14971 -1 14972 -1 14973 -1 14974 -1 14975 -1 14976 -1 14977 -1 14978 -1 14979 -1 14980 -1 14981 -1 14982 -1 14983 -1 14984 -1 14985 -1 14986 -1 14987 -1 14988 -1 14989 -1 14990 -1 14991 -1 14992 -1 14993 -1 14994 -1 14995 -1 14996 -1 14997 -1 14998 -1 14999 -1 15000 -1 15001 -1 15002 -1 15003 -1 15004 -1 15005 -1 15006 -1 15007 -1 15008 -1 15009 -1 15010 -1 15011 -1 15012 -1 15013 -1 15014 -1 15015 -1 15016 -1 15017 -1 15018 -1 15019 -1 15020 -1 15021 -1 15022 -1 15023 -1 15024 -1 15025 -1 15026 -1 15027 -1 15028 -1 15029 -1 15030 -1 15031 -1 15032 -1 15033 -1 15034 -1 15035 -1 15036 -1 15037 -1 15038 -1 15039 -1 15040 -1 15041 -1 15042 -1 15043 -1 15044 -1 15045 -1 15046 -1 15047 -1 15048 -1 15049 -1 15050 -1 15051 -1 15052 -1 15053 -1 15054 -1 15055 -1 15056 -1 15057 -1 15058 -1 15059 -1 15060 -1 15061 -1 15062 -1 15063 -1 15064 -1 15065 -1 15066 -1 15067 -1 15068 -1 15069 -1 15070 -1 15071 -1 15072 -1 15073 -1 15074 -1 15075 -1 15076 -1 15077 -1 15078 -1 15079 -1 15080 -1 15081 -1 15082 -1 15083 -1 15084 -1 15085 -1 15086 -1 15087 -1 15088 -1 15089 -1 15090 -1 15091 -1 15092 -1 15093 -1 15094 -1 15095 -1 15096 -1 15097 -1 15098 -1 15099 -1 15100 -1 15101 -1 15102 -1 15103 -1 15104 -1 15105 -1 15106 -1 15107 -1 15108 -1 15109 -1 15110 -1 15111 -1 15112 -1 15113 -1 15114 -1 15115 -1 15116 -1 15117 -1 15118 -1 15119 -1 15120 -1 15121 -1 15122 -1 15123 -1 15124 -1 15125 -1 15126 -1 15127 -1 15128 -1 15129 -1 15130 -1 15131 -1 15132 -1 15133 -1 15134 -1 15135 -1 15136 -1 15137 -1 15138 -1 15139 -1 15140 -1 15141 -1 15142 -1 15143 -1 15144 -1 15145 -1 15146 -1 15147 -1 15148 -1 15149 -1 15150 -1 15151 -1 15152 -1 15153 -1 15154 -1 15155 -1 15156 -1 15157 -1 15158 -1 15159 -1 15160 -1 15161 -1 15162 -1 15163 -1 15164 -1 15165 -1 15166 -1 15167 -1 15168 -1 15169 -1 15170 -1 15171 -1 15172 -1 15173 -1 15174 -1 15175 -1 15176 -1 15177 -1 15178 -1 15179 -1 15180 -1 15181 -1 15182 -1 15183 -1 15184 -1 15185 -1 15186 -1 15187 -1 15188 -1 15189 -1 15190 -1 15191 -1 15192 -1 15193 -1 15194 -1 15195 -1 15196 -1 15197 -1 15198 -1 15199 -1 15200 -1 15201 -1 15202 -1 15203 -1 15204 -1 15205 -1 15206 -1 15207 -1 15208 -1 15209 -1 15210 -1 15211 -1 15212 -1 15213 -1 15214 -1 15215 -1 15216 -1 15217 -1 15218 -1 15219 -1 15220 -1 15221 -1 15222 -1 15223 -1 15224 -1 15225 -1 15226 -1 15227 -1 15228 -1 15229 -1 15230 -1 15231 -1 15232 -1 15233 -1 15234 -1 15235 -1 15236 -1 15237 -1 15238 -1 15239 -1 15240 -1 15241 -1 15242 -1 15243 -1 15244 -1 15245 -1 15246 -1 15247 -1 15248 -1 15249 -1 15250 -1 15251 -1 15252 -1 15253 -1 15254 -1 15255 -1 15256 -1 15257 -1 15258 -1 15259 -1 15260 -1 15261 -1 15262 -1 15263 -1 15264 -1 15265 -1 15266 -1 15267 -1 15268 -1 15269 -1 15270 -1 15271 -1 15272 -1 15273 -1 15274 -1 15275 -1 15276 -1 15277 -1 15278 -1 15279 -1 15280 -1 15281 -1 15282 -1 15283 -1 15284 -1 15285 -1 15286 -1 15287 -1 15288 -1 15289 -1 15290 -1 15291 -1 15292 -1 15293 -1 15294 -1 15295 -1 15296 -1 15297 -1 15298 -1 15299 -1 15300 -1 15301 -1 15302 -1 15303 -1 15304 -1 15305 -1 15306 -1 15307 -1 15308 -1 15309 -1 15310 -1 15311 -1 15312 -1 15313 -1 15314 -1 15315 -1 15316 -1 15317 -1 15318 -1 15319 -1 15320 -1 15321 -1 15322 -1 15323 -1 15324 -1 15325 -1 15326 -1 15327 -1 15328 -1 15329 -1 15330 -1 15331 -1 15332 -1 15333 -1 15334 -1 15335 -1 15336 -1 15337 -1 15338 -1 15339 -1 15340 -1 15341 -1 15342 -1 15343 -1 15344 -1 15345 -1 15346 -1 15347 -1 15348 -1 15349 -1 15350 -1 15351 -1 15352 -1 15353 -1 15354 -1 15355 -1 15356 -1 15357 -1 15358 -1 15359 -1 15360 -1 15361 -1 15362 -1 15363 -1 15364 -1 15365 -1 15366 -1 15367 -1 15368 -1 15369 -1 15370 -1 15371 -1 15372 -1 15373 -1 15374 -1 15375 -1 15376 -1 15377 -1 15378 -1 15379 -1 15380 -1 15381 -1 15382 -1 15383 -1 15384 -1 15385 -1 15386 -1 15387 -1 15388 -1 15389 -1 15390 -1 15391 -1 15392 -1 15393 -1 15394 -1 15395 -1 15396 -1 15397 -1 15398 -1 15399 -1 15400 -1 15401 -1 15402 -1 15403 -1 15404 -1 15405 -1 15406 -1 15407 -1 15408 -1 15409 -1 15410 -1 15411 -1 15412 -1 15413 -1 15414 -1 15415 -1 15416 -1 15417 -1 15418 -1 15419 -1 15420 -1 15421 -1 15422 -1 15423 -1 15424 -1 15425 -1 15426 -1 15427 -1 15428 -1 15429 -1 15430 -1 15431 -1 15432 -1 15433 -1 15434 -1 15435 -1 15436 -1 15437 -1 15438 -1 15439 -1 15440 -1 15441 -1 15442 -1 15443 -1 15444 -1 15445 -1 15446 -1 15447 -1 15448 -1 15449 -1 15450 -1 15451 -1 15452 -1 15453 -1 15454 -1 15455 -1 15456 -1 15457 -1 15458 -1 15459 -1 15460 -1 15461 -1 15462 -1 15463 -1 15464 -1 15465 -1 15466 -1 15467 -1 15468 -1 15469 -1 15470 -1 15471 -1 15472 -1 15473 -1 15474 -1 15475 -1 15476 -1 15477 -1 15478 -1 15479 -1 15480 -1 15481 -1 15482 -1 15483 -1 15484 -1 15485 -1 15486 -1 15487 -1 15488 -1 15489 -1 15490 -1 15491 -1 15492 -1 15493 -1 15494 -1 15495 -1 15496 -1 15497 -1 15498 -1 15499 -1 15500 -1 15501 -1 15502 -1 15503 -1 15504 -1 15505 -1 15506 -1 15507 -1 15508 -1 15509 -1 15510 -1 15511 -1 15512 -1 15513 -1 15514 -1 15515 -1 15516 -1 15517 -1 15518 -1 15519 -1 15520 -1 15521 -1 15522 -1 15523 -1 15524 -1 15525 -1 15526 -1 15527 -1 15528 -1 15529 -1 15530 -1 15531 -1 15532 -1 15533 -1 15534 -1 15535 -1 15536 -1 15537 -1 15538 -1 15539 -1 15540 -1 15541 -1 15542 -1 15543 -1 15544 -1 15545 -1 15546 -1 15547 -1 15548 -1 15549 -1 15550 -1 15551 -1 15552 -1 15553 -1 15554 -1 15555 -1 15556 -1 15557 -1 15558 -1 15559 -1 15560 -1 15561 -1 15562 -1 15563 -1 15564 -1 15565 -1 15566 -1 15567 -1 15568 -1 15569 -1 15570 -1 15571 -1 15572 -1 15573 -1 15574 -1 15575 -1 15576 -1 15577 -1 15578 -1 15579 -1 15580 -1 15581 -1 15582 -1 15583 -1 15584 -1 15585 -1 15586 -1 15587 -1 15588 -1 15589 -1 15590 -1 15591 -1 15592 -1 15593 -1 15594 -1 15595 -1 15596 -1 15597 -1 15598 -1 15599 -1 15600 -1 15601 -1 15602 -1 15603 -1 15604 -1 15605 -1 15606 -1 15607 -1 15608 -1 15609 -1 15610 -1 15611 -1 15612 -1 15613 -1 15614 -1 15615 -1 15616 -1 15617 -1 15618 -1 15619 -1 15620 -1 15621 -1 15622 -1 15623 -1 15624 -1 15625 -1 15626 -1 15627 -1 15628 -1 15629 -1 15630 -1 15631 -1 15632 -1 15633 -1 15634 -1 15635 -1 15636 -1 15637 -1 15638 -1 15639 -1 15640 -1 15641 -1 15642 -1 15643 -1 15644 -1 15645 -1 15646 -1 15647 -1 15648 -1 15649 -1 15650 -1 15651 -1 15652 -1 15653 -1 15654 -1 15655 -1 15656 -1 15657 -1 15658 -1 15659 -1 15660 -1 15661 -1 15662 -1 15663 -1 15664 -1 15665 -1 15666 -1 15667 -1 15668 -1 15669 -1 15670 -1 15671 -1 15672 -1 15673 -1 15674 -1 15675 -1 15676 -1 15677 -1 15678 -1 15679 -1 15680 -1 15681 -1 15682 -1 15683 -1 15684 -1 15685 -1 15686 -1 15687 -1 15688 -1 15689 -1 15690 -1 15691 -1 15692 -1 15693 -1 15694 -1 15695 -1 15696 -1 15697 -1 15698 -1 15699 -1 15700 -1 15701 -1 15702 -1 15703 -1 15704 -1 15705 -1 15706 -1 15707 -1 15708 -1 15709 -1 15710 -1 15711 -1 15712 -1 15713 -1 15714 -1 15715 -1 15716 -1 15717 -1 15718 -1 15719 -1 15720 -1 15721 -1 15722 -1 15723 -1 15724 -1 15725 -1 15726 -1 15727 -1 15728 -1 15729 -1 15730 -1 15731 -1 15732 -1 15733 -1 15734 -1 15735 -1 15736 -1 15737 -1 15738 -1 15739 -1 15740 -1 15741 -1 15742 -1 15743 -1 15744 -1 15745 -1 15746 -1 15747 -1 15748 -1 15749 -1 15750 -1 15751 -1 15752 -1 15753 -1 15754 -1 15755 -1 15756 -1 15757 -1 15758 -1 15759 -1 15760 -1 15761 -1 15762 -1 15763 -1 15764 -1 15765 -1 15766 -1 15767 -1 15768 -1 15769 -1 15770 -1 15771 -1 15772 -1 15773 -1 15774 -1 15775 -1 15776 -1 15777 -1 15778 -1 15779 -1 15780 -1 15781 -1 15782 -1 15783 -1 15784 -1 15785 -1 15786 -1 15787 -1 15788 -1 15789 -1 15790 -1 15791 -1 15792 -1 15793 -1 15794 -1 15795 -1 15796 -1 15797 -1 15798 -1 15799 -1 15800 -1 15801 -1 15802 -1 15803 -1 15804 -1 15805 -1 15806 -1 15807 -1 15808 -1 15809 -1 15810 -1 15811 -1 15812 -1 15813 -1 15814 -1 15815 -1 15816 -1 15817 -1 15818 -1 15819 -1 15820 -1 15821 -1 15822 -1 15823 -1 15824 -1 15825 -1 15826 -1 15827 -1 15828 -1 15829 -1 15830 -1 15831 -1 15832 -1 15833 -1 15834 -1 15835 -1 15836 -1 15837 -1 15838 -1 15839 -1 15840 -1 15841 -1 15842 -1 15843 -1 15844 -1 15845 -1 15846 -1 15847 -1 15848 -1 15849 -1 15850 -1 15851 -1 15852 -1 15853 -1 15854 -1 15855 -1 15856 -1 15857 -1 15858 -1 15859 -1 15860 -1 15861 -1 15862 -1 15863 -1 15864 -1 15865 -1 15866 -1 15867 -1 15868 -1 15869 -1 15870 -1 15871 -1 15872 -1 15873 -1 15874 -1 15875 -1 15876 -1 15877 -1 15878 -1 15879 -1 15880 -1 15881 -1 15882 -1 15883 -1 15884 -1 15885 -1 15886 -1 15887 -1 15888 -1 15889 -1 15890 -1 15891 -1 15892 -1 15893 -1 15894 -1 15895 -1 15896 -1 15897 -1 15898 -1 15899 -1 15900 -1 15901 -1 15902 -1 15903 -1 15904 -1 15905 -1 15906 -1 15907 -1 15908 -1 15909 -1 15910 -1 15911 -1 15912 -1 15913 -1 15914 -1 15915 -1 15916 -1 15917 -1 15918 -1 15919 -1 15920 -1 15921 -1 15922 -1 15923 -1 15924 -1 15925 -1 15926 -1 15927 -1 15928 -1 15929 -1 15930 -1 15931 -1 15932 -1 15933 -1 15934 -1 15935 -1 15936 -1 15937 -1 15938 -1 15939 -1 15940 -1 15941 -1 15942 -1 15943 -1 15944 -1 15945 -1 15946 -1 15947 -1 15948 -1 15949 -1 15950 -1 15951 -1 15952 -1 15953 -1 15954 -1 15955 -1 15956 -1 15957 -1 15958 -1 15959 -1 15960 -1 15961 -1 15962 -1 15963 -1 15964 -1 15965 -1 15966 -1 15967 -1 15968 -1 15969 -1 15970 -1 15971 -1 15972 -1 15973 -1 15974 -1 15975 -1 15976 -1 15977 -1 15978 -1 15979 -1 15980 -1 15981 -1 15982 -1 15983 -1 15984 -1 15985 -1 15986 -1 15987 -1 15988 -1 15989 -1 15990 -1 15991 -1 15992 -1 15993 -1 15994 -1 15995 -1 15996 -1 15997 -1 15998 -1 15999 -1 16000 -1 16001 -1 16002 -1 16003 -1 16004 -1 16005 -1 16006 -1 16007 -1 16008 -1 16009 -1 16010 -1 16011 -1 16012 -1 16013 -1 16014 -1 16015 -1 16016 -1 16017 -1 16018 -1 16019 -1 16020 -1 16021 -1 16022 -1 16023 -1 16024 -1 16025 -1 16026 -1 16027 -1 16028 -1 16029 -1 16030 -1 16031 -1 16032 -1 16033 -1 16034 -1 16035 -1 16036 -1 16037 -1 16038 -1 16039 -1 16040 -1 16041 -1 16042 -1 16043 -1 16044 -1 16045 -1 16046 -1 16047 -1 16048 -1 16049 -1 16050 -1 16051 -1 16052 -1 16053 -1 16054 -1 16055 -1 16056 -1 16057 -1 16058 -1 16059 -1 16060 -1 16061 -1 16062 -1 16063 -1 16064 -1 16065 -1 16066 -1 16067 -1 16068 -1 16069 -1 16070 -1 16071 -1 16072 -1 16073 -1 16074 -1 16075 -1 16076 -1 16077 -1 16078 -1 16079 -1 16080 -1 16081 -1 16082 -1 16083 -1 16084 -1 16085 -1 16086 -1 16087 -1 16088 -1 16089 -1 16090 -1 16091 -1 16092 -1 16093 -1 16094 -1 16095 -1 16096 -1 16097 -1 16098 -1 16099 -1 16100 -1 16101 -1 16102 -1 16103 -1 16104 -1 16105 -1 16106 -1 16107 -1 16108 -1 16109 -1 16110 -1 16111 -1 16112 -1 16113 -1 16114 -1 16115 -1 16116 -1 16117 -1 16118 -1 16119 -1 16120 -1 16121 -1 16122 -1 16123 -1 16124 -1 16125 -1 16126 -1 16127 -1 16128 -1 16129 -1 16130 -1 16131 -1 16132 -1 16133 -1 16134 -1 16135 -1 16136 -1 16137 -1 16138 -1 16139 -1 16140 -1 16141 -1 16142 -1 16143 -1 16144 -1 16145 -1 16146 -1 16147 -1 16148 -1 16149 -1 16150 -1 16151 -1 16152 -1 16153 -1 16154 -1 16155 -1 16156 -1 16157 -1 16158 -1 16159 -1 16160 -1 16161 -1 16162 -1 16163 -1 16164 -1 16165 -1 16166 -1 16167 -1 16168 -1 16169 -1 16170 -1 16171 -1 16172 -1 16173 -1 16174 -1 16175 -1 16176 -1 16177 -1 16178 -1 16179 -1 16180 -1 16181 -1 16182 -1 16183 -1 16184 -1 16185 -1 16186 -1 16187 -1 16188 -1 16189 -1 16190 -1 16191 -1 16192 -1 16193 -1 16194 -1 16195 -1 16196 -1 16197 -1 16198 -1 16199 -1 16200 -1 16201 -1 16202 -1 16203 -1 16204 -1 16205 -1 16206 -1 16207 -1 16208 -1 16209 -1 16210 -1 16211 -1 16212 -1 16213 -1 16214 -1 16215 -1 16216 -1 16217 -1 16218 -1 16219 -1 16220 -1 16221 -1 16222 -1 16223 -1 16224 -1 16225 -1 16226 -1 16227 -1 16228 -1 16229 -1 16230 -1 16231 -1 16232 -1 16233 -1 16234 -1 16235 -1 16236 -1 16237 -1 16238 -1 16239 -1 16240 -1 16241 -1 16242 -1 16243 -1 16244 -1 16245 -1 16246 -1 16247 -1 16248 -1 16249 -1 16250 -1 16251 -1 16252 -1 16253 -1 16254 -1 16255 -1 16256 -1 16257 -1 16258 -1 16259 -1 16260 -1 16261 -1 16262 -1 16263 -1 16264 -1 16265 -1 16266 -1 16267 -1 16268 -1 16269 -1 16270 -1 16271 -1 16272 -1 16273 -1 16274 -1 16275 -1 16276 -1 16277 -1 16278 -1 16279 -1 16280 -1 16281 -1 16282 -1 16283 -1 16284 -1 16285 -1 16286 -1 16287 -1 16288 -1 16289 -1 16290 -1 16291 -1 16292 -1 16293 -1 16294 -1 16295 -1 16296 -1 16297 -1 16298 -1 16299 -1 16300 -1 16301 -1 16302 -1 16303 -1 16304 -1 16305 -1 16306 -1 16307 -1 16308 -1 16309 -1 16310 -1 16311 -1 16312 -1 16313 -1 16314 -1 16315 -1 16316 -1 16317 -1 16318 -1 16319 -1 16320 -1 16321 -1 16322 -1 16323 -1 16324 -1 16325 -1 16326 -1 16327 -1 16328 -1 16329 -1 16330 -1 16331 -1 16332 -1 16333 -1 16334 -1 16335 -1 16336 -1 16337 -1 16338 -1 16339 -1 16340 -1 16341 -1 16342 -1 16343 -1 16344 -1 16345 -1 16346 -1 16347 -1 16348 -1 16349 -1 16350 -1 16351 -1 16352 -1 16353 -1 16354 -1 16355 -1 16356 -1 16357 -1 16358 -1 16359 -1 16360 -1 16361 -1 16362 -1 16363 -1 16364 -1 16365 -1 16366 -1 16367 -1 16368 -1 16369 -1 16370 -1 16371 -1 16372 -1 16373 -1 16374 -1 16375 -1 16376 -1 16377 -1 16378 -1 16379 -1 16380 -1 16381 -1 16382 -1 16383 -1 16384 -1 16385 -1 16386 -1 16387 -1 16388 -1 16389 -1 16390 -1 16391 -1 16392 -1 16393 -1 16394 -1 16395 -1 16396 -1 16397 -1 16398 -1 16399 -1 16400 -1 16401 -1 16402 -1 16403 -1 16404 -1 16405 -1 16406 -1 16407 -1 16408 -1 16409 -1 16410 -1 16411 -1 16412 -1 16413 -1 16414 -1 16415 -1 16416 -1 16417 -1 16418 -1 16419 -1 16420 -1 16421 -1 16422 -1 16423 -1 16424 -1 16425 -1 16426 -1 16427 -1 16428 -1 16429 -1 16430 -1 16431 -1 16432 -1 16433 -1 16434 -1 16435 -1 16436 -1 16437 -1 16438 -1 16439 -1 16440 -1 16441 -1 16442 -1 16443 -1 16444 -1 16445 -1 16446 -1 16447 -1 16448 -1 16449 -1 16450 -1 16451 -1 16452 -1 16453 -1 16454 -1 16455 -1 16456 -1 16457 -1 16458 -1 16459 -1 16460 -1 16461 -1 16462 -1 16463 -1 16464 -1 16465 -1 16466 -1 16467 -1 16468 -1 16469 -1 16470 -1 16471 -1 16472 -1 16473 -1 16474 -1 16475 -1 16476 -1 16477 -1 16478 -1 16479 -1 16480 -1 16481 -1 16482 -1 16483 -1 16484 -1 16485 -1 16486 -1 16487 -1 16488 -1 16489 -1 16490 -1 16491 -1 16492 -1 16493 -1 16494 -1 16495 -1 16496 -1 16497 -1 16498 -1 16499 -1 16500 -1 16501 -1 16502 -1 16503 -1 16504 -1 16505 -1 16506 -1 16507 -1 16508 -1 16509 -1 16510 -1 16511 -1 16512 -1 16513 -1 16514 -1 16515 -1 16516 -1 16517 -1 16518 -1 16519 -1 16520 -1 16521 -1 16522 -1 16523 -1 16524 -1 16525 -1 16526 -1 16527 -1 16528 -1 16529 -1 16530 -1 16531 -1 16532 -1 16533 -1 16534 -1 16535 -1 16536 -1 16537 -1 16538 -1 16539 -1 16540 -1 16541 -1 16542 -1 16543 -1 16544 -1 16545 -1 16546 -1 16547 -1 16548 -1 16549 -1 16550 -1 16551 -1 16552 -1 16553 -1 16554 -1 16555 -1 16556 -1 16557 -1 16558 -1 16559 -1 16560 -1 16561 -1 16562 -1 16563 -1 16564 -1 16565 -1 16566 -1 16567 -1 16568 -1 16569 -1 16570 -1 16571 -1 16572 -1 16573 -1 16574 -1 16575 -1 16576 -1 16577 -1 16578 -1 16579 -1 16580 -1 16581 -1 16582 -1 16583 -1 16584 -1 16585 -1 16586 -1 16587 -1 16588 -1 16589 -1 16590 -1 16591 -1 16592 -1 16593 -1 16594 -1 16595 -1 16596 -1 16597 -1 16598 -1 16599 -1 16600 -1 16601 -1 16602 -1 16603 -1 16604 -1 16605 -1 16606 -1 16607 -1 16608 -1 16609 -1 16610 -1 16611 -1 16612 -1 16613 -1 16614 -1 16615 -1 16616 -1 16617 -1 16618 -1 16619 -1 16620 -1 16621 -1 16622 -1 16623 -1 16624 -1 16625 -1 16626 -1 16627 -1 16628 -1 16629 -1 16630 -1 16631 -1 16632 -1 16633 -1 16634 -1 16635 -1 16636 -1 16637 -1 16638 -1 16639 -1 16640 -1 16641 -1 16642 -1 16643 -1 16644 -1 16645 -1 16646 -1 16647 -1 16648 -1 16649 -1 16650 -1 16651 -1 16652 -1 16653 -1 16654 -1 16655 -1 16656 -1 16657 -1 16658 -1 16659 -1 16660 -1 16661 -1 16662 -1 16663 -1 16664 -1 16665 -1 16666 -1 16667 -1 16668 -1 16669 -1 16670 -1 16671 -1 16672 -1 16673 -1 16674 -1 16675 -1 16676 -1 16677 -1 16678 -1 16679 -1 16680 -1 16681 -1 16682 -1 16683 -1 16684 -1 16685 -1 16686 -1 16687 -1 16688 -1 16689 -1 16690 -1 16691 -1 16692 -1 16693 -1 16694 -1 16695 -1 16696 -1 16697 -1 16698 -1 16699 -1 16700 -1 16701 -1 16702 -1 16703 -1 16704 -1 16705 -1 16706 -1 16707 -1 16708 -1 16709 -1 16710 -1 16711 -1 16712 -1 16713 -1 16714 -1 16715 -1 16716 -1 16717 -1 16718 -1 16719 -1 16720 -1 16721 -1 16722 -1 16723 -1 16724 -1 16725 -1 16726 -1 16727 -1 16728 -1 16729 -1 16730 -1 16731 -1 16732 -1 16733 -1 16734 -1 16735 -1 16736 -1 16737 -1 16738 -1 16739 -1 16740 -1 16741 -1 16742 -1 16743 -1 16744 -1 16745 -1 16746 -1 16747 -1 16748 -1 16749 -1 16750 -1 16751 -1 16752 -1 16753 -1 16754 -1 16755 -1 16756 -1 16757 -1 16758 -1 16759 -1 16760 -1 16761 -1 16762 -1 16763 -1 16764 -1 16765 -1 16766 -1 16767 -1 16768 -1 16769 -1 16770 -1 16771 -1 16772 -1 16773 -1 16774 -1 16775 -1 16776 -1 16777 -1 16778 -1 16779 -1 16780 -1 16781 -1 16782 -1 16783 -1 16784 -1 16785 -1 16786 -1 16787 -1 16788 -1 16789 -1 16790 -1 16791 -1 16792 -1 16793 -1 16794 -1 16795 -1 16796 -1 16797 -1 16798 -1 16799 -1 16800 -1 16801 -1 16802 -1 16803 -1 16804 -1 16805 -1 16806 -1 16807 -1 16808 -1 16809 -1 16810 -1 16811 -1 16812 -1 16813 -1 16814 -1 16815 -1 16816 -1 16817 -1 16818 -1 16819 -1 16820 -1 16821 -1 16822 -1 16823 -1 16824 -1 16825 -1 16826 -1 16827 -1 16828 -1 16829 -1 16830 -1 16831 -1 16832 -1 16833 -1 16834 -1 16835 -1 16836 -1 16837 -1 16838 -1 16839 -1 16840 -1 16841 -1 16842 -1 16843 -1 16844 -1 16845 -1 16846 -1 16847 -1 16848 -1 16849 -1 16850 -1 16851 -1 16852 -1 16853 -1 16854 -1 16855 -1 16856 -1 16857 -1 16858 -1 16859 -1 16860 -1 16861 -1 16862 -1 16863 -1 16864 -1 16865 -1 16866 -1 16867 -1 16868 -1 16869 -1 16870 -1 16871 -1 16872 -1 16873 -1 16874 -1 16875 -1 16876 -1 16877 -1 16878 -1 16879 -1 16880 -1 16881 -1 16882 -1 16883 -1 16884 -1 16885 -1 16886 -1 16887 -1 16888 -1 16889 -1 16890 -1 16891 -1 16892 -1 16893 -1 16894 -1 16895 -1 16896 -1 16897 -1 16898 -1 16899 -1 16900 -1 16901 -1 16902 -1 16903 -1 16904 -1 16905 -1 16906 -1 16907 -1 16908 -1 16909 -1 16910 -1 16911 -1 16912 -1 16913 -1 16914 -1 16915 -1 16916 -1 16917 -1 16918 -1 16919 -1 16920 -1 16921 -1 16922 -1 16923 -1 16924 -1 16925 -1 16926 -1 16927 -1 16928 -1 16929 -1 16930 -1 16931 -1 16932 -1 16933 -1 16934 -1 16935 -1 16936 -1 16937 -1 16938 -1 16939 -1 16940 -1 16941 -1 16942 -1 16943 -1 16944 -1 16945 -1 16946 -1 16947 -1 16948 -1 16949 -1 16950 -1 16951 -1 16952 -1 16953 -1 16954 -1 16955 -1 16956 -1 16957 -1 16958 -1 16959 -1 16960 -1 16961 -1 16962 -1 16963 -1 16964 -1 16965 -1 16966 -1 16967 -1 16968 -1 16969 -1 16970 -1 16971 -1 16972 -1 16973 -1 16974 -1 16975 -1 16976 -1 16977 -1 16978 -1 16979 -1 16980 -1 16981 -1 16982 -1 16983 -1 16984 -1 16985 -1 16986 -1 16987 -1 16988 -1 16989 -1 16990 -1 16991 -1 16992 -1 16993 -1 16994 -1 16995 -1 16996 -1 16997 -1 16998 -1 16999 -1 17000 -1 17001 -1 17002 -1 17003 -1 17004 -1 17005 -1 17006 -1 17007 -1 17008 -1 17009 -1 17010 -1 17011 -1 17012 -1 17013 -1 17014 -1 17015 -1 17016 -1 17017 -1 17018 -1 17019 -1 17020 -1 17021 -1 17022 -1 17023 -1 17024 -1 17025 -1 17026 -1 17027 -1 17028 -1 17029 -1 17030 -1 17031 -1 17032 -1 17033 -1 17034 -1 17035 -1 17036 -1 17037 -1 17038 -1 17039 -1 17040 -1 17041 -1 17042 -1 17043 -1 17044 -1 17045 -1 17046 -1 17047 -1 17048 -1 17049 -1 17050 -1 17051 -1 17052 -1 17053 -1 17054 -1 17055 -1 17056 -1 17057 -1 17058 -1 17059 -1 17060 -1 17061 -1 17062 -1 17063 -1 17064 -1 17065 -1 17066 -1 17067 -1 17068 -1 17069 -1 17070 -1 17071 -1 17072 -1 17073 -1 17074 -1 17075 -1 17076 -1 17077 -1 17078 -1 17079 -1 17080 -1 17081 -1 17082 -1 17083 -1 17084 -1 17085 -1 17086 -1 17087 -1 17088 -1 17089 -1 17090 -1 17091 -1 17092 -1 17093 -1 17094 -1 17095 -1 17096 -1 17097 -1 17098 -1 17099 -1 17100 -1 17101 -1 17102 -1 17103 -1 17104 -1 17105 -1 17106 -1 17107 -1 17108 -1 17109 -1 17110 -1 17111 -1 17112 -1 17113 -1 17114 -1 17115 -1 17116 -1 17117 -1 17118 -1 17119 -1 17120 -1 17121 -1 17122 -1 17123 -1 17124 -1 17125 -1 17126 -1 17127 -1 17128 -1 17129 -1 17130 -1 17131 -1 17132 -1 17133 -1 17134 -1 17135 -1 17136 -1 17137 -1 17138 -1 17139 -1 17140 -1 17141 -1 17142 -1 17143 -1 17144 -1 17145 -1 17146 -1 17147 -1 17148 -1 17149 -1 17150 -1 17151 -1 17152 -1 17153 -1 17154 -1 17155 -1 17156 -1 17157 -1 17158 -1 17159 -1 17160 -1 17161 -1 17162 -1 17163 -1 17164 -1 17165 -1 17166 -1 17167 -1 17168 -1 17169 -1 17170 -1 17171 -1 17172 -1 17173 -1 17174 -1 17175 -1 17176 -1 17177 -1 17178 -1 17179 -1 17180 -1 17181 -1 17182 -1 17183 -1 17184 -1 17185 -1 17186 -1 17187 -1 17188 -1 17189 -1 17190 -1 17191 -1 17192 -1 17193 -1 17194 -1 17195 -1 17196 -1 17197 -1 17198 -1 17199 -1 17200 -1 17201 -1 17202 -1 17203 -1 17204 -1 17205 -1 17206 -1 17207 -1 17208 -1 17209 -1 17210 -1 17211 -1 17212 -1 17213 -1 17214 -1 17215 -1 17216 -1 17217 -1 17218 -1 17219 -1 17220 -1 17221 -1 17222 -1 17223 -1 17224 -1 17225 -1 17226 -1 17227 -1 17228 -1 17229 -1 17230 -1 17231 -1 17232 -1 17233 -1 17234 -1 17235 -1 17236 -1 17237 -1 17238 -1 17239 -1 17240 -1 17241 -1 17242 -1 17243 -1 17244 -1 17245 -1 17246 -1 17247 -1 17248 -1 17249 -1 17250 -1 17251 -1 17252 -1 17253 -1 17254 -1 17255 -1 17256 -1 17257 -1 17258 -1 17259 -1 17260 -1 17261 -1 17262 -1 17263 -1 17264 -1 17265 -1 17266 -1 17267 -1 17268 -1 17269 -1 17270 -1 17271 -1 17272 -1 17273 -1 17274 -1 17275 -1 17276 -1 17277 -1 17278 -1 17279 -1 17280 -1 17281 -1 17282 -1 17283 -1 17284 -1 17285 -1 17286 -1 17287 -1 17288 -1 17289 -1 17290 -1 17291 -1 17292 -1 17293 -1 17294 -1 17295 -1 17296 -1 17297 -1 17298 -1 17299 -1 17300 -1 17301 -1 17302 -1 17303 -1 17304 -1 17305 -1 17306 -1 17307 -1 17308 -1 17309 -1 17310 -1 17311 -1 17312 -1 17313 -1 17314 -1 17315 -1 17316 -1 17317 -1 17318 -1 17319 -1 17320 -1 17321 -1 17322 -1 17323 -1 17324 -1 17325 -1 17326 -1 17327 -1 17328 -1 17329 -1 17330 -1 17331 -1 17332 -1 17333 -1 17334 -1 17335 -1 17336 -1 17337 -1 17338 -1 17339 -1 17340 -1 17341 -1 17342 -1 17343 -1 17344 -1 17345 -1 17346 -1 17347 -1 17348 -1 17349 -1 17350 -1 17351 -1 17352 -1 17353 -1 17354 -1 17355 -1 17356 -1 17357 -1 17358 -1 17359 -1 17360 -1 17361 -1 17362 -1 17363 -1 17364 -1 17365 -1 17366 -1 17367 -1 17368 -1 17369 -1 17370 -1 17371 -1 17372 -1 17373 -1 17374 -1 17375 -1 17376 -1 17377 -1 17378 -1 17379 -1 17380 -1 17381 -1 17382 -1 17383 -1 17384 -1 17385 -1 17386 -1 17387 -1 17388 -1 17389 -1 17390 -1 17391 -1 17392 -1 17393 -1 17394 -1 17395 -1 17396 -1 17397 -1 17398 -1 17399 -1 17400 -1 17401 -1 17402 -1 17403 -1 17404 -1 17405 -1 17406 -1 17407 -1 17408 -1 17409 -1 17410 -1 17411 -1 17412 -1 17413 -1 17414 -1 17415 -1 17416 -1 17417 -1 17418 -1 17419 -1 17420 -1 17421 -1 17422 -1 17423 -1 17424 -1 17425 -1 17426 -1 17427 -1 17428 -1 17429 -1 17430 -1 17431 -1 17432 -1 17433 -1 17434 -1 17435 -1 17436 -1 17437 -1 17438 -1 17439 -1 17440 -1 17441 -1 17442 -1 17443 -1 17444 -1 17445 -1 17446 -1 17447 -1 17448 -1 17449 -1 17450 -1 17451 -1 17452 -1 17453 -1 17454 -1 17455 -1 17456 -1 17457 -1 17458 -1 17459 -1 17460 -1 17461 -1 17462 -1 17463 -1 17464 -1 17465 -1 17466 -1 17467 -1 17468 -1 17469 -1 17470 -1 17471 -1 17472 -1 17473 -1 17474 -1 17475 -1 17476 -1 17477 -1 17478 -1 17479 -1 17480 -1 17481 -1 17482 -1 17483 -1 17484 -1 17485 -1 17486 -1 17487 -1 17488 -1 17489 -1 17490 -1 17491 -1 17492 -1 17493 -1 17494 -1 17495 -1 17496 -1 17497 -1 17498 -1 17499 -1 17500 -1 17501 -1 17502 -1 17503 -1 17504 -1 17505 -1 17506 -1 17507 -1 17508 -1 17509 -1 17510 -1 17511 -1 17512 -1 17513 -1 17514 -1 17515 -1 17516 -1 17517 -1 17518 -1 17519 -1 17520 -1 17521 -1 17522 -1 17523 -1 17524 -1 17525 -1 17526 -1 17527 -1 17528 -1 17529 -1 17530 -1 17531 -1 17532 -1 17533 -1 17534 -1 17535 -1 17536 -1 17537 -1 17538 -1 17539 -1 17540 -1 17541 -1 17542 -1 17543 -1 17544 -1 17545 -1 17546 -1 17547 -1 17548 -1 17549 -1 17550 -1 17551 -1 17552 -1 17553 -1 17554 -1 17555 -1 17556 -1 17557 -1 17558 -1 17559 -1 17560 -1 17561 -1 17562 -1 17563 -1 17564 -1 17565 -1 17566 -1 17567 -1 17568 -1 17569 -1 17570 -1 17571 -1 17572 -1 17573 -1 17574 -1 17575 -1 17576 -1 17577 -1 17578 -1 17579 -1 17580 -1 17581 -1 17582 -1 17583 -1 17584 -1 17585 -1 17586 -1 17587 -1 17588 -1 17589 -1 17590 -1 17591 -1 17592 -1 17593 -1 17594 -1 17595 -1 17596 -1 17597 -1 17598 -1 17599 -1 17600 -1 17601 -1 17602 -1 17603 -1 17604 -1 17605 -1 17606 -1 17607 -1 17608 -1 17609 -1 17610 -1 17611 -1 17612 -1 17613 -1 17614 -1 17615 -1 17616 -1 17617 -1 17618 -1 17619 -1 17620 -1 17621 -1 17622 -1 17623 -1 17624 -1 17625 -1 17626 -1 17627 -1 17628 -1 17629 -1 17630 -1 17631 -1 17632 -1 17633 -1 17634 -1 17635 -1 17636 -1 17637 -1 17638 -1 17639 -1 17640 -1 17641 -1 17642 -1 17643 -1 17644 -1 17645 -1 17646 -1 17647 -1 17648 -1 17649 -1 17650 -1 17651 -1 17652 -1 17653 -1 17654 -1 17655 -1 17656 -1 17657 -1 17658 -1 17659 -1 17660 -1 17661 -1 17662 -1 17663 -1 17664 -1 17665 -1 17666 -1 17667 -1 17668 -1 17669 -1 17670 -1 17671 -1 17672 -1 17673 -1 17674 -1 17675 -1 17676 -1 17677 -1 17678 -1 17679 -1 17680 -1 17681 -1 17682 -1 17683 -1 17684 -1 17685 -1 17686 -1 17687 -1 17688 -1 17689 -1 17690 -1 17691 -1 17692 -1 17693 -1 17694 -1 17695 -1 17696 -1 17697 -1 17698 -1 17699 -1 17700 -1 17701 -1 17702 -1 17703 -1 17704 -1 17705 -1 17706 -1 17707 -1 17708 -1 17709 -1 17710 -1 17711 -1 17712 -1 17713 -1 17714 -1 17715 -1 17716 -1 17717 -1 17718 -1 17719 -1 17720 -1 17721 -1 17722 -1 17723 -1 17724 -1 17725 -1 17726 -1 17727 -1 17728 -1 17729 -1 17730 -1 17731 -1 17732 -1 17733 -1 17734 -1 17735 -1 17736 -1 17737 -1 17738 -1 17739 -1 17740 -1 17741 -1 17742 -1 17743 -1 17744 -1 17745 -1 17746 -1 17747 -1 17748 -1 17749 -1 17750 -1 17751 -1 17752 -1 17753 -1 17754 -1 17755 -1 17756 -1 17757 -1 17758 -1 17759 -1 17760 -1 17761 -1 17762 -1 17763 -1 17764 -1 17765 -1 17766 -1 17767 -1 17768 -1 17769 -1 17770 -1 17771 -1 17772 -1 17773 -1 17774 -1 17775 -1 17776 -1 17777 -1 17778 -1 17779 -1 17780 -1 17781 -1 17782 -1 17783 -1 17784 -1 17785 -1 17786 -1 17787 -1 17788 -1 17789 -1 17790 -1 17791 -1 17792 -1 17793 -1 17794 -1 17795 -1 17796 -1 17797 -1 17798 -1 17799 -1 17800 -1 17801 -1 17802 -1 17803 -1 17804 -1 17805 -1 17806 -1 17807 -1 17808 -1 17809 -1 17810 -1 17811 -1 17812 -1 17813 -1 17814 -1 17815 -1 17816 -1 17817 -1 17818 -1 17819 -1 17820 -1 17821 -1 17822 -1 17823 -1 17824 -1 17825 -1 17826 -1 17827 -1 17828 -1 17829 -1 17830 -1 17831 -1 17832 -1 17833 -1 17834 -1 17835 -1 17836 -1 17837 -1 17838 -1 17839 -1 17840 -1 17841 -1 17842 -1 17843 -1 17844 -1 17845 -1 17846 -1 17847 -1 17848 -1 17849 -1 17850 -1 17851 -1 17852 -1 17853 -1 17854 -1 17855 -1 17856 -1 17857 -1 17858 -1 17859 -1 17860 -1 17861 -1 17862 -1 17863 -1 17864 -1 17865 -1 17866 -1 17867 -1 17868 -1 17869 -1 17870 -1 17871 -1 17872 -1 17873 -1 17874 -1 17875 -1 17876 -1 17877 -1 17878 -1 17879 -1 17880 -1 17881 -1 17882 -1 17883 -1 17884 -1 17885 -1 17886 -1 17887 -1 17888 -1 17889 -1 17890 -1 17891 -1 17892 -1 17893 -1 17894 -1 17895 -1 17896 -1 17897 -1 17898 -1 17899 -1 17900 -1 17901 -1 17902 -1 17903 -1 17904 -1 17905 -1 17906 -1 17907 -1 17908 -1 17909 -1 17910 -1 17911 -1 17912 -1 17913 -1 17914 -1 17915 -1 17916 -1 17917 -1 17918 -1 17919 -1 17920 -1 17921 -1 17922 -1 17923 -1 17924 -1 17925 -1 17926 -1 17927 -1 17928 -1 17929 -1 17930 -1 17931 -1 17932 -1 17933 -1 17934 -1 17935 -1 17936 -1 17937 -1 17938 -1 17939 -1 17940 -1 17941 -1 17942 -1 17943 -1 17944 -1 17945 -1 17946 -1 17947 -1 17948 -1 17949 -1 17950 -1 17951 -1 17952 -1 17953 -1 17954 -1 17955 -1 17956 -1 17957 -1 17958 -1 17959 -1 17960 -1 17961 -1 17962 -1 17963 -1 17964 -1 17965 -1 17966 -1 17967 -1 17968 -1 17969 -1 17970 -1 17971 -1 17972 -1 17973 -1 17974 -1 17975 -1 17976 -1 17977 -1 17978 -1 17979 -1 17980 -1 17981 -1 17982 -1 17983 -1 17984 -1 17985 -1 17986 -1 17987 -1 17988 -1 17989 -1 17990 -1 17991 -1 17992 -1 17993 -1 17994 -1 17995 -1 17996 -1 17997 -1 17998 -1 17999 -1 18000 -1 18001 -1 18002 -1 18003 -1 18004 -1 18005 -1 18006 -1 18007 -1 18008 -1 18009 -1 18010 -1 18011 -1 18012 -1 18013 -1 18014 -1 18015 -1 18016 -1 18017 -1 18018 -1 18019 -1 18020 -1 18021 -1 18022 -1 18023 -1 18024 -1 18025 -1 18026 -1 18027 -1 18028 -1 18029 -1 18030 -1 18031 -1 18032 -1 18033 -1 18034 -1 18035 -1 18036 -1 18037 -1 18038 -1 18039 -1 18040 -1 18041 -1 18042 -1 18043 -1 18044 -1 18045 -1 18046 -1 18047 -1 18048 -1 18049 -1 18050 -1 18051 -1 18052 -1 18053 -1 18054 -1 18055 -1 18056 -1 18057 -1 18058 -1 18059 -1 18060 -1 18061 -1 18062 -1 18063 -1 18064 -1 18065 -1 18066 -1 18067 -1 18068 -1 18069 -1 18070 -1 18071 -1 18072 -1 18073 -1 18074 -1 18075 -1 18076 -1 18077 -1 18078 -1 18079 -1 18080 -1 18081 -1 18082 -1 18083 -1 18084 -1 18085 -1 18086 -1 18087 -1 18088 -1 18089 -1 18090 -1 18091 -1 18092 -1 18093 -1 18094 -1 18095 -1 18096 -1 18097 -1 18098 -1 18099 -1 18100 -1 18101 -1 18102 -1 18103 -1 18104 -1 18105 -1 18106 -1 18107 -1 18108 -1 18109 -1 18110 -1 18111 -1 18112 -1 18113 -1 18114 -1 18115 -1 18116 -1 18117 -1 18118 -1 18119 -1 18120 -1 18121 -1 18122 -1 18123 -1 18124 -1 18125 -1 18126 -1 18127 -1 18128 -1 18129 -1 18130 -1 18131 -1 18132 -1 18133 -1 18134 -1 18135 -1 18136 -1 18137 -1 18138 -1 18139 -1 18140 -1 18141 -1 18142 -1 18143 -1 18144 -1 18145 -1 18146 -1 18147 -1 18148 -1 18149 -1 18150 -1 18151 -1 18152 -1 18153 -1 18154 -1 18155 -1 18156 -1 18157 -1 18158 -1 18159 -1 18160 -1 18161 -1 18162 -1 18163 -1 18164 -1 18165 -1 18166 -1 18167 -1 18168 -1 18169 -1 18170 -1 18171 -1 18172 -1 18173 -1 18174 -1 18175 -1 18176 -1 18177 -1 18178 -1 18179 -1 18180 -1 18181 -1 18182 -1 18183 -1 18184 -1 18185 -1 18186 -1 18187 -1 18188 -1 18189 -1 18190 -1 18191 -1 18192 -1 18193 -1 18194 -1 18195 -1 18196 -1 18197 -1 18198 -1 18199 -1 18200 -1 18201 -1 18202 -1 18203 -1 18204 -1 18205 -1 18206 -1 18207 -1 18208 -1 18209 -1 18210 -1 18211 -1 18212 -1 18213 -1 18214 -1 18215 -1 18216 -1 18217 -1 18218 -1 18219 -1 18220 -1 18221 -1 18222 -1 18223 -1 18224 -1 18225 -1 18226 -1 18227 -1 18228 -1 18229 -1 18230 -1 18231 -1 18232 -1 18233 -1 18234 -1 18235 -1 18236 -1 18237 -1 18238 -1 18239 -1 18240 -1 18241 -1 18242 -1 18243 -1 18244 -1 18245 -1 18246 -1 18247 -1 18248 -1 18249 -1 18250 -1 18251 -1 18252 -1 18253 -1 18254 -1 18255 -1 18256 -1 18257 -1 18258 -1 18259 -1 18260 -1 18261 -1 18262 -1 18263 -1 18264 -1 18265 -1 18266 -1 18267 -1 18268 -1 18269 -1 18270 -1 18271 -1 18272 -1 18273 -1 18274 -1 18275 -1 18276 -1 18277 -1 18278 -1 18279 -1 18280 -1 18281 -1 18282 -1 18283 -1 18284 -1 18285 -1 18286 -1 18287 -1 18288 -1 18289 -1 18290 -1 18291 -1 18292 -1 18293 -1 18294 -1 18295 -1 18296 -1 18297 -1 18298 -1 18299 -1 18300 -1 18301 -1 18302 -1 18303 -1 18304 -1 18305 -1 18306 -1 18307 -1 18308 -1 18309 -1 18310 -1 18311 -1 18312 -1 18313 -1 18314 -1 18315 -1 18316 -1 18317 -1 18318 -1 18319 -1 18320 -1 18321 -1 18322 -1 18323 -1 18324 -1 18325 -1 18326 -1 18327 -1 18328 -1 18329 -1 18330 -1 18331 -1 18332 -1 18333 -1 18334 -1 18335 -1 18336 -1 18337 -1 18338 -1 18339 -1 18340 -1 18341 -1 18342 -1 18343 -1 18344 -1 18345 -1 18346 -1 18347 -1 18348 -1 18349 -1 18350 -1 18351 -1 18352 -1 18353 -1 18354 -1 18355 -1 18356 -1 18357 -1 18358 -1 18359 -1 18360 -1 18361 -1 18362 -1 18363 -1 18364 -1 18365 -1 18366 -1 18367 -1 18368 -1 18369 -1 18370 -1 18371 -1 18372 -1 18373 -1 18374 -1 18375 -1 18376 -1 18377 -1 18378 -1 18379 -1 18380 -1 18381 -1 18382 -1 18383 -1 18384 -1 18385 -1 18386 -1 18387 -1 18388 -1 18389 -1 18390 -1 18391 -1 18392 -1 18393 -1 18394 -1 18395 -1 18396 -1 18397 -1 18398 -1 18399 -1 18400 -1 18401 -1 18402 -1 18403 -1 18404 -1 18405 -1 18406 -1 18407 -1 18408 -1 18409 -1 18410 -1 18411 -1 18412 -1 18413 -1 18414 -1 18415 -1 18416 -1 18417 -1 18418 -1 18419 -1 18420 -1 18421 -1 18422 -1 18423 -1 18424 -1 18425 -1 18426 -1 18427 -1 18428 -1 18429 -1 18430 -1 18431 -1 18432 -1 18433 -1 18434 -1 18435 -1 18436 -1 18437 -1 18438 -1 18439 -1 18440 -1 18441 -1 18442 -1 18443 -1 18444 -1 18445 -1 18446 -1 18447 -1 18448 -1 18449 -1 18450 -1 18451 -1 18452 -1 18453 -1 18454 -1 18455 -1 18456 -1 18457 -1 18458 -1 18459 -1 18460 -1 18461 -1 18462 -1 18463 -1 18464 -1 18465 -1 18466 -1 18467 -1 18468 -1 18469 -1 18470 -1 18471 -1 18472 -1 18473 -1 18474 -1 18475 -1 18476 -1 18477 -1 18478 -1 18479 -1 18480 -1 18481 -1 18482 -1 18483 -1 18484 -1 18485 -1 18486 -1 18487 -1 18488 -1 18489 -1 18490 -1 18491 -1 18492 -1 18493 -1 18494 -1 18495 -1 18496 -1 18497 -1 18498 -1 18499 -1 18500 -1 18501 -1 18502 -1 18503 -1 18504 -1 18505 -1 18506 -1 18507 -1 18508 -1 18509 -1 18510 -1 18511 -1 18512 -1 18513 -1 18514 -1 18515 -1 18516 -1 18517 -1 18518 -1 18519 -1 18520 -1 18521 -1 18522 -1 18523 -1 18524 -1 18525 -1 18526 -1 18527 -1 18528 -1 18529 -1 18530 -1 18531 -1 18532 -1 18533 -1 18534 -1 18535 -1 18536 -1 18537 -1 18538 -1 18539 -1 18540 -1 18541 -1 18542 -1 18543 -1 18544 -1 18545 -1 18546 -1 18547 -1 18548 -1 18549 -1 18550 -1 18551 -1 18552 -1 18553 -1 18554 -1 18555 -1 18556 -1 18557 -1 18558 -1 18559 -1 18560 -1 18561 -1 18562 -1 18563 -1 18564 -1 18565 -1 18566 -1 18567 -1 18568 -1 18569 -1 18570 -1 18571 -1 18572 -1 18573 -1 18574 -1 18575 -1 18576 -1 18577 -1 18578 -1 18579 -1 18580 -1 18581 -1 18582 -1 18583 -1 18584 -1 18585 -1 18586 -1 18587 -1 18588 -1 18589 -1 18590 -1 18591 -1 18592 -1 18593 -1 18594 -1 18595 -1 18596 -1 18597 -1 18598 -1 18599 -1 18600 -1 18601 -1 18602 -1 18603 -1 18604 -1 18605 -1 18606 -1 18607 -1 18608 -1 18609 -1 18610 -1 18611 -1 18612 -1 18613 -1 18614 -1 18615 -1 18616 -1 18617 -1 18618 -1 18619 -1 18620 -1 18621 -1 18622 -1 18623 -1 18624 -1 18625 -1 18626 -1 18627 -1 18628 -1 18629 -1 18630 -1 18631 -1 18632 -1 18633 -1 18634 -1 18635 -1 18636 -1 18637 -1 18638 -1 18639 -1 18640 -1 18641 -1 18642 -1 18643 -1 18644 -1 18645 -1 18646 -1 18647 -1 18648 -1 18649 -1 18650 -1 18651 -1 18652 -1 18653 -1 18654 -1 18655 -1 18656 -1 18657 -1 18658 -1 18659 -1 18660 -1 18661 -1 18662 -1 18663 -1 18664 -1 18665 -1 18666 -1 18667 -1 18668 -1 18669 -1 18670 -1 18671 -1 18672 -1 18673 -1 18674 -1 18675 -1 18676 -1 18677 -1 18678 -1 18679 -1 18680 -1 18681 -1 18682 -1 18683 -1 18684 -1 18685 -1 18686 -1 18687 -1 18688 -1 18689 -1 18690 -1 18691 -1 18692 -1 18693 -1 18694 -1 18695 -1 18696 -1 18697 -1 18698 -1 18699 -1 18700 -1 18701 -1 18702 -1 18703 -1 18704 -1 18705 -1 18706 -1 18707 -1 18708 -1 18709 -1 18710 -1 18711 -1 18712 -1 18713 -1 18714 -1 18715 -1 18716 -1 18717 -1 18718 -1 18719 -1 18720 -1 18721 -1 18722 -1 18723 -1 18724 -1 18725 -1 18726 -1 18727 -1 18728 -1 18729 -1 18730 -1 18731 -1 18732 -1 18733 -1 18734 -1 18735 -1 18736 -1 18737 -1 18738 -1 18739 -1 18740 -1 18741 -1 18742 -1 18743 -1 18744 -1 18745 -1 18746 -1 18747 -1 18748 -1 18749 -1 18750 -1 18751 -1 18752 -1 18753 -1 18754 -1 18755 -1 18756 -1 18757 -1 18758 -1 18759 -1 18760 -1 18761 -1 18762 -1 18763 -1 18764 -1 18765 -1 18766 -1 18767 -1 18768 -1 18769 -1 18770 -1 18771 -1 18772 -1 18773 -1 18774 -1 18775 -1 18776 -1 18777 -1 18778 -1 18779 -1 18780 -1 18781 -1 18782 -1 18783 -1 18784 -1 18785 -1 18786 -1 18787 -1 18788 -1 18789 -1 18790 -1 18791 -1 18792 -1 18793 -1 18794 -1 18795 -1 18796 -1 18797 -1 18798 -1 18799 -1 18800 -1 18801 -1 18802 -1 18803 -1 18804 -1 18805 -1 18806 -1 18807 -1 18808 -1 18809 -1 18810 -1 18811 -1 18812 -1 18813 -1 18814 -1 18815 -1 18816 -1 18817 -1 18818 -1 18819 -1 18820 -1 18821 -1 18822 -1 18823 -1 18824 -1 18825 -1 18826 -1 18827 -1 18828 -1 18829 -1 18830 -1 18831 -1 18832 -1 18833 -1 18834 -1 18835 -1 18836 -1 18837 -1 18838 -1 18839 -1 18840 -1 18841 -1 18842 -1 18843 -1 18844 -1 18845 -1 18846 -1 18847 -1 18848 -1 18849 -1 18850 -1 18851 -1 18852 -1 18853 -1 18854 -1 18855 -1 18856 -1 18857 -1 18858 -1 18859 -1 18860 -1 18861 -1 18862 -1 18863 -1 18864 -1 18865 -1 18866 -1 18867 -1 18868 -1 18869 -1 18870 -1 18871 -1 18872 -1 18873 -1 18874 -1 18875 -1 18876 -1 18877 -1 18878 -1 18879 -1 18880 -1 18881 -1 18882 -1 18883 -1 18884 -1 18885 -1 18886 -1 18887 -1 18888 -1 18889 -1 18890 -1 18891 -1 18892 -1 18893 -1 18894 -1 18895 -1 18896 -1 18897 -1 18898 -1 18899 -1 18900 -1 18901 -1 18902 -1 18903 -1 18904 -1 18905 -1 18906 -1 18907 -1 18908 -1 18909 -1 18910 -1 18911 -1 18912 -1 18913 -1 18914 -1 18915 -1 18916 -1 18917 -1 18918 -1 18919 -1 18920 -1 18921 -1 18922 -1 18923 -1 18924 -1 18925 -1 18926 -1 18927 -1 18928 -1 18929 -1 18930 -1 18931 -1 18932 -1 18933 -1 18934 -1 18935 -1 18936 -1 18937 -1 18938 -1 18939 -1 18940 -1 18941 -1 18942 -1 18943 -1 18944 -1 18945 -1 18946 -1 18947 -1 18948 -1 18949 -1 18950 -1 18951 -1 18952 -1 18953 -1 18954 -1 18955 -1 18956 -1 18957 -1 18958 -1 18959 -1 18960 -1 18961 -1 18962 -1 18963 -1 18964 -1 18965 -1 18966 -1 18967 -1 18968 -1 18969 -1 18970 -1 18971 -1 18972 -1 18973 -1 18974 -1 18975 -1 18976 -1 18977 -1 18978 -1 18979 -1 18980 -1 18981 -1 18982 -1 18983 -1 18984 -1 18985 -1 18986 -1 18987 -1 18988 -1 18989 -1 18990 -1 18991 -1 18992 -1 18993 -1 18994 -1 18995 -1 18996 -1 18997 -1 18998 -1 18999 -1 19000 -1 19001 -1 19002 -1 19003 -1 19004 -1 19005 -1 19006 -1 19007 -1 19008 -1 19009 -1 19010 -1 19011 -1 19012 -1 19013 -1 19014 -1 19015 -1 19016 -1 19017 -1 19018 -1 19019 -1 19020 -1 19021 -1 19022 -1 19023 -1 19024 -1 19025 -1 19026 -1 19027 -1 19028 -1 19029 -1 19030 -1 19031 -1 19032 -1 19033 -1 19034 -1 19035 -1 19036 -1 19037 -1 19038 -1 19039 -1 19040 -1 19041 -1 19042 -1 19043 -1 19044 -1 19045 -1 19046 -1 19047 -1 19048 -1 19049 -1 19050 -1 19051 -1 19052 -1 19053 -1 19054 -1 19055 -1 19056 -1 19057 -1 19058 -1 19059 -1 19060 -1 19061 -1 19062 -1 19063 -1 19064 -1 19065 -1 19066 -1 19067 -1 19068 -1 19069 -1 19070 -1 19071 -1 19072 -1 19073 -1 19074 -1 19075 -1 19076 -1 19077 -1 19078 -1 19079 -1 19080 -1 19081 -1 19082 -1 19083 -1 19084 -1 19085 -1 19086 -1 19087 -1 19088 -1 19089 -1 19090 -1 19091 -1 19092 -1 19093 -1 19094 -1 19095 -1 19096 -1 19097 -1 19098 -1 19099 -1 19100 -1 19101 -1 19102 -1 19103 -1 19104 -1 19105 -1 19106 -1 19107 -1 19108 -1 19109 -1 19110 -1 19111 -1 19112 -1 19113 -1 19114 -1 19115 -1 19116 -1 19117 -1 19118 -1 19119 -1 19120 -1 19121 -1 19122 -1 19123 -1 19124 -1 19125 -1 19126 -1 19127 -1 19128 -1 19129 -1 19130 -1 19131 -1 19132 -1 19133 -1 19134 -1 19135 -1 19136 -1 19137 -1 19138 -1 19139 -1 19140 -1 19141 -1 19142 -1 19143 -1 19144 -1 19145 -1 19146 -1 19147 -1 19148 -1 19149 -1 19150 -1 19151 -1 19152 -1 19153 -1 19154 -1 19155 -1 19156 -1 19157 -1 19158 -1 19159 -1 19160 -1 19161 -1 19162 -1 19163 -1 19164 -1 19165 -1 19166 -1 19167 -1 19168 -1 19169 -1 19170 -1 19171 -1 19172 -1 19173 -1 19174 -1 19175 -1 19176 -1 19177 -1 19178 -1 19179 -1 19180 -1 19181 -1 19182 -1 19183 -1 19184 -1 19185 -1 19186 -1 19187 -1 19188 -1 19189 -1 19190 -1 19191 -1 19192 -1 19193 -1 19194 -1 19195 -1 19196 -1 19197 -1 19198 -1 19199 -1 19200 -1 19201 -1 19202 -1 19203 -1 19204 -1 19205 -1 19206 -1 19207 -1 19208 -1 19209 -1 19210 -1 19211 -1 19212 -1 19213 -1 19214 -1 19215 -1 19216 -1 19217 -1 19218 -1 19219 -1 19220 -1 19221 -1 19222 -1 19223 -1 19224 -1 19225 -1 19226 -1 19227 -1 19228 -1 19229 -1 19230 -1 19231 -1 19232 -1 19233 -1 19234 -1 19235 -1 19236 -1 19237 -1 19238 -1 19239 -1 19240 -1 19241 -1 19242 -1 19243 -1 19244 -1 19245 -1 19246 -1 19247 -1 19248 -1 19249 -1 19250 -1 19251 -1 19252 -1 19253 -1 19254 -1 19255 -1 19256 -1 19257 -1 19258 -1 19259 -1 19260 -1 19261 -1 19262 -1 19263 -1 19264 -1 19265 -1 19266 -1 19267 -1 19268 -1 19269 -1 19270 -1 19271 -1 19272 -1 19273 -1 19274 -1 19275 -1 19276 -1 19277 -1 19278 -1 19279 -1 19280 -1 19281 -1 19282 -1 19283 -1 19284 -1 19285 -1 19286 -1 19287 -1 19288 -1 19289 -1 19290 -1 19291 -1 19292 -1 19293 -1 19294 -1 19295 -1 19296 -1 19297 -1 19298 -1 19299 -1 19300 -1 19301 -1 19302 -1 19303 -1 19304 -1 19305 -1 19306 -1 19307 -1 19308 -1 19309 -1 19310 -1 19311 -1 19312 -1 19313 -1 19314 -1 19315 -1 19316 -1 19317 -1 19318 -1 19319 -1 19320 -1 19321 -1 19322 -1 19323 -1 19324 -1 19325 -1 19326 -1 19327 -1 19328 -1 19329 -1 19330 -1 19331 -1 19332 -1 19333 -1 19334 -1 19335 -1 19336 -1 19337 -1 19338 -1 19339 -1 19340 -1 19341 -1 19342 -1 19343 -1 19344 -1 19345 -1 19346 -1 19347 -1 19348 -1 19349 -1 19350 -1 19351 -1 19352 -1 19353 -1 19354 -1 19355 -1 19356 -1 19357 -1 19358 -1 19359 -1 19360 -1 19361 -1 19362 -1 19363 -1 19364 -1 19365 -1 19366 -1 19367 -1 19368 -1 19369 -1 19370 -1 19371 -1 19372 -1 19373 -1 19374 -1 19375 -1 19376 -1 19377 -1 19378 -1 19379 -1 19380 -1 19381 -1 19382 -1 19383 -1 19384 -1 19385 -1 19386 -1 19387 -1 19388 -1 19389 -1 19390 -1 19391 -1 19392 -1 19393 -1 19394 -1 19395 -1 19396 -1 19397 -1 19398 -1 19399 -1 19400 -1 19401 -1 19402 -1 19403 -1 19404 -1 19405 -1 19406 -1 19407 -1 19408 -1 19409 -1 19410 -1 19411 -1 19412 -1 19413 -1 19414 -1 19415 -1 19416 -1 19417 -1 19418 -1 19419 -1 19420 -1 19421 -1 19422 -1 19423 -1 19424 -1 19425 -1 19426 -1 19427 -1 19428 -1 19429 -1 19430 -1 19431 -1 19432 -1 19433 -1 19434 -1 19435 -1 19436 -1 19437 -1 19438 -1 19439 -1 19440 -1 19441 -1 19442 -1 19443 -1 19444 -1 19445 -1 19446 -1 19447 -1 19448 -1 19449 -1 19450 -1 19451 -1 19452 -1 19453 -1 19454 -1 19455 -1 19456 -1 19457 -1 19458 -1 19459 -1 19460 -1 19461 -1 19462 -1 19463 -1 19464 -1 19465 -1 19466 -1 19467 -1 19468 -1 19469 -1 19470 -1 19471 -1 19472 -1 19473 -1 19474 -1 19475 -1 19476 -1 19477 -1 19478 -1 19479 -1 19480 -1 19481 -1 19482 -1 19483 -1 19484 -1 19485 -1 19486 -1 19487 -1 19488 -1 19489 -1 19490 -1 19491 -1 19492 -1 19493 -1 19494 -1 19495 -1 19496 -1 19497 -1 19498 -1 19499 -1 19500 -1 19501 -1 19502 -1 19503 -1 19504 -1 19505 -1 19506 -1 19507 -1 19508 -1 19509 -1 19510 -1 19511 -1 19512 -1 19513 -1 19514 -1 19515 -1 19516 -1 19517 -1 19518 -1 19519 -1 19520 -1 19521 -1 19522 -1 19523 -1 19524 -1 19525 -1 19526 -1 19527 -1 19528 -1 19529 -1 19530 -1 19531 -1 19532 -1 19533 -1 19534 -1 19535 -1 19536 -1 19537 -1 19538 -1 19539 -1 19540 -1 19541 -1 19542 -1 19543 -1 19544 -1 19545 -1 19546 -1 19547 -1 19548 -1 19549 -1 19550 -1 19551 -1 19552 -1 19553 -1 19554 -1 19555 -1 19556 -1 19557 -1 19558 -1 19559 -1 19560 -1 19561 -1 19562 -1 19563 -1 19564 -1 19565 -1 19566 -1 19567 -1 19568 -1 19569 -1 19570 -1 19571 -1 19572 -1 19573 -1 19574 -1 19575 -1 19576 -1 19577 -1 19578 -1 19579 -1 19580 -1 19581 -1 19582 -1 19583 -1 19584 -1 19585 -1 19586 -1 19587 -1 19588 -1 19589 -1 19590 -1 19591 -1 19592 -1 19593 -1 19594 -1 19595 -1 19596 -1 19597 -1 19598 -1 19599 -1 19600 -1 19601 -1 19602 -1 19603 -1 19604 -1 19605 -1 19606 -1 19607 -1 19608 -1 19609 -1 19610 -1 19611 -1 19612 -1 19613 -1 19614 -1 19615 -1 19616 -1 19617 -1 19618 -1 19619 -1 19620 -1 19621 -1 19622 -1 19623 -1 19624 -1 19625 -1 19626 -1 19627 -1 19628 -1 19629 -1 19630 -1 19631 -1 19632 -1 19633 -1 19634 -1 19635 -1 19636 -1 19637 -1 19638 -1 19639 -1 19640 -1 19641 -1 19642 -1 19643 -1 19644 -1 19645 -1 19646 -1 19647 -1 19648 -1 19649 -1 19650 -1 19651 -1 19652 -1 19653 -1 19654 -1 19655 -1 19656 -1 19657 -1 19658 -1 19659 -1 19660 -1 19661 -1 19662 -1 19663 -1 19664 -1 19665 -1 19666 -1 19667 -1 19668 -1 19669 -1 19670 -1 19671 -1 19672 -1 19673 -1 19674 -1 19675 -1 19676 -1 19677 -1 19678 -1 19679 -1 19680 -1 19681 -1 19682 -1 19683 -1 19684 -1 19685 -1 19686 -1 19687 -1 19688 -1 19689 -1 19690 -1 19691 -1 19692 -1 19693 -1 19694 -1 19695 -1 19696 -1 19697 -1 19698 -1 19699 -1 19700 -1 19701 -1 19702 -1 19703 -1 19704 -1 19705 -1 19706 -1 19707 -1 19708 -1 19709 -1 19710 -1 19711 -1 19712 -1 19713 -1 19714 -1 19715 -1 19716 -1 19717 -1 19718 -1 19719 -1 19720 -1 19721 -1 19722 -1 19723 -1 19724 -1 19725 -1 19726 -1 19727 -1 19728 -1 19729 -1 19730 -1 19731 -1 19732 -1 19733 -1 19734 -1 19735 -1 19736 -1 19737 -1 19738 -1 19739 -1 19740 -1 19741 -1 19742 -1 19743 -1 19744 -1 19745 -1 19746 -1 19747 -1 19748 -1 19749 -1 19750 -1 19751 -1 19752 -1 19753 -1 19754 -1 19755 -1 19756 -1 19757 -1 19758 -1 19759 -1 19760 -1 19761 -1 19762 -1 19763 -1 19764 -1 19765 -1 19766 -1 19767 -1 19768 -1 19769 -1 19770 -1 19771 -1 19772 -1 19773 -1 19774 -1 19775 -1 19776 -1 19777 -1 19778 -1 19779 -1 19780 -1 19781 -1 19782 -1 19783 -1 19784 -1 19785 -1 19786 -1 19787 -1 19788 -1 19789 -1 19790 -1 19791 -1 19792 -1 19793 -1 19794 -1 19795 -1 19796 -1 19797 -1 19798 -1 19799 -1 19800 -1 19801 -1 19802 -1 19803 -1 19804 -1 19805 -1 19806 -1 19807 -1 19808 -1 19809 -1 19810 -1 19811 -1 19812 -1 19813 -1 19814 -1 19815 -1 19816 -1 19817 -1 19818 -1 19819 -1 19820 -1 19821 -1 19822 -1 19823 -1 19824 -1 19825 -1 19826 -1 19827 -1 19828 -1 19829 -1 19830 -1 19831 -1 19832 -1 19833 -1 19834 -1 19835 -1 19836 -1 19837 -1 19838 -1 19839 -1 19840 -1 19841 -1 19842 -1 19843 -1 19844 -1 19845 -1 19846 -1 19847 -1 19848 -1 19849 -1 19850 -1 19851 -1 19852 -1 19853 -1 19854 -1 19855 -1 19856 -1 19857 -1 19858 -1 19859 -1 19860 -1 19861 -1 19862 -1 19863 -1 19864 -1 19865 -1 19866 -1 19867 -1 19868 -1 19869 -1 19870 -1 19871 -1 19872 -1 19873 -1 19874 -1 19875 -1 19876 -1 19877 -1 19878 -1 19879 -1 19880 -1 19881 -1 19882 -1 19883 -1 19884 -1 19885 -1 19886 -1 19887 -1 19888 -1 19889 -1 19890 -1 19891 -1 19892 -1 19893 -1 19894 -1 19895 -1 19896 -1 19897 -1 19898 -1 19899 -1 19900 -1 19901 -1 19902 -1 19903 -1 19904 -1 19905 -1 19906 -1 19907 -1 19908 -1 19909 -1 19910 -1 19911 -1 19912 -1 19913 -1 19914 -1 19915 -1 19916 -1 19917 -1 19918 -1 19919 -1 19920 -1 19921 -1 19922 -1 19923 -1 19924 -1 19925 -1 19926 -1 19927 -1 19928 -1 19929 -1 19930 -1 19931 -1 19932 -1 19933 -1 19934 -1 19935 -1 19936 -1 19937 -1 19938 -1 19939 -1 19940 -1 19941 -1 19942 -1 19943 -1 19944 -1 19945 -1 19946 -1 19947 -1 19948 -1 19949 -1 19950 -1 19951 -1 19952 -1 19953 -1 19954 -1 19955 -1 19956 -1 19957 -1 19958 -1 19959 -1 19960 -1 19961 -1 19962 -1 19963 -1 19964 -1 19965 -1 19966 -1 19967 -1 19968 -1 19969 -1 19970 -1 19971 -1 19972 -1 19973 -1 19974 -1 19975 -1 19976 -1 19977 -1 19978 -1 19979 -1 19980 -1 19981 -1 19982 -1 19983 -1 19984 -1 19985 -1 19986 -1 19987 -1 19988 -1 19989 -1 19990 -1 19991 -1 19992 -1 19993 -1 19994 -1 19995 -1 19996 -1 19997 -1 19998 -1 19999 -1 20000 -1 20001 -1 20002 -1 20003 -1 20004 -1 20005 -1 20006 -1 20007 -1 20008 -1 20009 -1 20010 -1 20011 -1 20012 -1 20013 -1 20014 -1 20015 -1 20016 -1 20017 -1 20018 -1 20019 -1 20020 -1 20021 -1 20022 -1 20023 -1 20024 -1 20025 -1 20026 -1 20027 -1 20028 -1 20029 -1 20030 -1 20031 -1 20032 -1 20033 -1 20034 -1 20035 -1 20036 -1 20037 -1 20038 -1 20039 -1 20040 -1 20041 -1 20042 -1 20043 -1 20044 -1 20045 -1 20046 -1 20047 -1 20048 -1 20049 -1 20050 -1 20051 -1 20052 -1 20053 -1 20054 -1 20055 -1 20056 -1 20057 -1 20058 -1 20059 -1 20060 -1 20061 -1 20062 -1 20063 -1 20064 -1 20065 -1 20066 -1 20067 -1 20068 -1 20069 -1 20070 -1 20071 -1 20072 -1 20073 -1 20074 -1 20075 -1 20076 -1 20077 -1 20078 -1 20079 -1 20080 -1 20081 -1 20082 -1 20083 -1 20084 -1 20085 -1 20086 -1 20087 -1 20088 -1 20089 -1 20090 -1 20091 -1 20092 -1 20093 -1 20094 -1 20095 -1 20096 -1 20097 -1 20098 -1 20099 -1 20100 -1 20101 -1 20102 -1 20103 -1 20104 -1 20105 -1 20106 -1 20107 -1 20108 -1 20109 -1 20110 -1 20111 -1 20112 -1 20113 -1 20114 -1 20115 -1 20116 -1 20117 -1 20118 -1 20119 -1 20120 -1 20121 -1 20122 -1 20123 -1 20124 -1 20125 -1 20126 -1 20127 -1 20128 -1 20129 -1 20130 -1 20131 -1 20132 -1 20133 -1 20134 -1 20135 -1 20136 -1 20137 -1 20138 -1 20139 -1 20140 -1 20141 -1 20142 -1 20143 -1 20144 -1 20145 -1 20146 -1 20147 -1 20148 -1 20149 -1 20150 -1 20151 -1 20152 -1 20153 -1 20154 -1 20155 -1 20156 -1 20157 -1 20158 -1 20159 -1 20160 -1 20161 -1 20162 -1 20163 -1 20164 -1 20165 -1 20166 -1 20167 -1 20168 -1 20169 -1 20170 -1 20171 -1 20172 -1 20173 -1 20174 -1 20175 -1 20176 -1 20177 -1 20178 -1 20179 -1 20180 -1 20181 -1 20182 -1 20183 -1 20184 -1 20185 -1 20186 -1 20187 -1 20188 -1 20189 -1 20190 -1 20191 -1 20192 -1 20193 -1 20194 -1 20195 -1 20196 -1 20197 -1 20198 -1 20199 -1 20200 -1 20201 -1 20202 -1 20203 -1 20204 -1 20205 -1 20206 -1 20207 -1 20208 -1 20209 -1 20210 -1 20211 -1 20212 -1 20213 -1 20214 -1 20215 -1 20216 -1 20217 -1 20218 -1 20219 -1 20220 -1 20221 -1 20222 -1 20223 -1 20224 -1 20225 -1 20226 -1 20227 -1 20228 -1 20229 -1 20230 -1 20231 -1 20232 -1 20233 -1 20234 -1 20235 -1 20236 -1 20237 -1 20238 -1 20239 -1 20240 -1 20241 -1 20242 -1 20243 -1 20244 -1 20245 -1 20246 -1 20247 -1 20248 -1 20249 -1 20250 -1 20251 -1 20252 -1 20253 -1 20254 -1 20255 -1 20256 -1 20257 -1 20258 -1 20259 -1 20260 -1 20261 -1 20262 -1 20263 -1 20264 -1 20265 -1 20266 -1 20267 -1 20268 -1 20269 -1 20270 -1 20271 -1 20272 -1 20273 -1 20274 -1 20275 -1 20276 -1 20277 -1 20278 -1 20279 -1 20280 -1 20281 -1 20282 -1 20283 -1 20284 -1 20285 -1 20286 -1 20287 -1 20288 -1 20289 -1 20290 -1 20291 -1 20292 -1 20293 -1 20294 -1 20295 -1 20296 -1 20297 -1 20298 -1 20299 -1 20300 -1 20301 -1 20302 -1 20303 -1 20304 -1 20305 -1 20306 -1 20307 -1 20308 -1 20309 -1 20310 -1 20311 -1 20312 -1 20313 -1 20314 -1 20315 -1 20316 -1 20317 -1 20318 -1 20319 -1 20320 -1 20321 -1 20322 -1 20323 -1 20324 -1 20325 -1 20326 -1 20327 -1 20328 -1 20329 -1 20330 -1 20331 -1 20332 -1 20333 -1 20334 -1 20335 -1 20336 -1 20337 -1 20338 -1 20339 -1 20340 -1 20341 -1 20342 -1 20343 -1 20344 -1 20345 -1 20346 -1 20347 -1 20348 -1 20349 -1 20350 -1 20351 -1 20352 -1 20353 -1 20354 -1 20355 -1 20356 -1 20357 -1 20358 -1 20359 -1 20360 -1 20361 -1 20362 -1 20363 -1 20364 -1 20365 -1 20366 -1 20367 -1 20368 -1 20369 -1 20370 -1 20371 -1 20372 -1 20373 -1 20374 -1 20375 -1 20376 -1 20377 -1 20378 -1 20379 -1 20380 -1 20381 -1 20382 -1 20383 -1 20384 -1 20385 -1 20386 -1 20387 -1 20388 -1 20389 -1 20390 -1 20391 -1 20392 -1 20393 -1 20394 -1 20395 -1 20396 -1 20397 -1 20398 -1 20399 -1 20400 -1 20401 -1 20402 -1 20403 -1 20404 -1 20405 -1 20406 -1 20407 -1 20408 -1 20409 -1 20410 -1 20411 -1 20412 -1 20413 -1 20414 -1 20415 -1 20416 -1 20417 -1 20418 -1 20419 -1 20420 -1 20421 -1 20422 -1 20423 -1 20424 -1 20425 -1 20426 -1 20427 -1 20428 -1 20429 -1 20430 -1 20431 -1 20432 -1 20433 -1 20434 -1 20435 -1 20436 -1 20437 -1 20438 -1 20439 -1 20440 -1 20441 -1 20442 -1 20443 -1 20444 -1 20445 -1 20446 -1 20447 -1 20448 -1 20449 -1 20450 -1 20451 -1 20452 -1 20453 -1 20454 -1 20455 -1 20456 -1 20457 -1 20458 -1 20459 -1 20460 -1 20461 -1 20462 -1 20463 -1 20464 -1 20465 -1 20466 -1 20467 -1 20468 -1 20469 -1 20470 -1 20471 -1 20472 -1 20473 -1 20474 -1 20475 -1 20476 -1 20477 -1 20478 -1 20479 -1 20480 -1 20481 -1 20482 -1 20483 -1 20484 -1 20485 -1 20486 -1 20487 -1 20488 -1 20489 -1 20490 -1 20491 -1 20492 -1 20493 -1 20494 -1 20495 -1 20496 -1 20497 -1 20498 -1 20499 -1 20500 -1 20501 -1 20502 -1 20503 -1 20504 -1 20505 -1 20506 -1 20507 -1 20508 -1 20509 -1 20510 -1 20511 -1 20512 -1 20513 -1 20514 -1 20515 -1 20516 -1 20517 -1 20518 -1 20519 -1 20520 -1 20521 -1 20522 -1 20523 -1 20524 -1 20525 -1 20526 -1 20527 -1 20528 -1 20529 -1 20530 -1 20531 -1 20532 -1 20533 -1 20534 -1 20535 -1 20536 -1 20537 -1 20538 -1 20539 -1 20540 -1 20541 -1 20542 -1 20543 -1 20544 -1 20545 -1 20546 -1 20547 -1 20548 -1 20549 -1 20550 -1 20551 -1 20552 -1 20553 -1 20554 -1 20555 -1 20556 -1 20557 -1 20558 -1 20559 -1 20560 -1 20561 -1 20562 -1 20563 -1 20564 -1 20565 -1 20566 -1 20567 -1 20568 -1 20569 -1 20570 -1 20571 -1 20572 -1 20573 -1 20574 -1 20575 -1 20576 -1 20577 -1 20578 -1 20579 -1 20580 -1 20581 -1 20582 -1 20583 -1 20584 -1 20585 -1 20586 -1 20587 -1 20588 -1 20589 -1 20590 -1 20591 -1 20592 -1 20593 -1 20594 -1 20595 -1 20596 -1 20597 -1 20598 -1 20599 -1 20600 -1 20601 -1 20602 -1 20603 -1 20604 -1 20605 -1 20606 -1 20607 -1 20608 -1 20609 -1 20610 -1 20611 -1 20612 -1 20613 -1 20614 -1 20615 -1 20616 -1 20617 -1 20618 -1 20619 -1 20620 -1 20621 -1 20622 -1 20623 -1 20624 -1 20625 -1 20626 -1 20627 -1 20628 -1 20629 -1 20630 -1 20631 -1 20632 -1 20633 -1 20634 -1 20635 -1 20636 -1 20637 -1 20638 -1 20639 -1 20640 -1 20641 -1 20642 -1 20643 -1 20644 -1 20645 -1 20646 -1 20647 -1 20648 -1 20649 -1 20650 -1 20651 -1 20652 -1 20653 -1 20654 -1 20655 -1 20656 -1 20657 -1 20658 -1 20659 -1 20660 -1 20661 -1 20662 -1 20663 -1 20664 -1 20665 -1 20666 -1 20667 -1 20668 -1 20669 -1 20670 -1 20671 -1 20672 -1 20673 -1 20674 -1 20675 -1 20676 -1 20677 -1 20678 -1 20679 -1 20680 -1 20681 -1 20682 -1 20683 -1 20684 -1 20685 -1 20686 -1 20687 -1 20688 -1 20689 -1 20690 -1 20691 -1 20692 -1 20693 -1 20694 -1 20695 -1 20696 -1 20697 -1 20698 -1 20699 -1 20700 -1 20701 -1 20702 -1 20703 -1 20704 -1 20705 -1 20706 -1 20707 -1 20708 -1 20709 -1 20710 -1 20711 -1 20712 -1 20713 -1 20714 -1 20715 -1 20716 -1 20717 -1 20718 -1 20719 -1 20720 -1 20721 -1 20722 -1 20723 -1 20724 -1 20725 -1 20726 -1 20727 -1 20728 -1 20729 -1 20730 -1 20731 -1 20732 -1 20733 -1 20734 -1 20735 -1 20736 -1 20737 -1 20738 -1 20739 -1 20740 -1 20741 -1 20742 -1 20743 -1 20744 -1 20745 -1 20746 -1 20747 -1 20748 -1 20749 -1 20750 -1 20751 -1 20752 -1 20753 -1 20754 -1 20755 -1 20756 -1 20757 -1 20758 -1 20759 -1 20760 -1 20761 -1 20762 -1 20763 -1 20764 -1 20765 -1 20766 -1 20767 -1 20768 -1 20769 -1 20770 -1 20771 -1 20772 -1 20773 -1 20774 -1 20775 -1 20776 -1 20777 -1 20778 -1 20779 -1 20780 -1 20781 -1 20782 -1 20783 -1 20784 -1 20785 -1 20786 -1 20787 -1 20788 -1 20789 -1 20790 -1 20791 -1 20792 -1 20793 -1 20794 -1 20795 -1 20796 -1 20797 -1 20798 -1 20799 -1 20800 -1 20801 -1 20802 -1 20803 -1 20804 -1 20805 -1 20806 -1 20807 -1 20808 -1 20809 -1 20810 -1 20811 -1 20812 -1 20813 -1 20814 -1 20815 -1 20816 -1 20817 -1 20818 -1 20819 -1 20820 -1 20821 -1 20822 -1 20823 -1 20824 -1 20825 -1 20826 -1 20827 -1 20828 -1 20829 -1 20830 -1 20831 -1 20832 -1 20833 -1 20834 -1 20835 -1 20836 -1 20837 -1 20838 -1 20839 -1 20840 -1 20841 -1 20842 -1 20843 -1 20844 -1 20845 -1 20846 -1 20847 -1 20848 -1 20849 -1 20850 -1 20851 -1 20852 -1 20853 -1 20854 -1 20855 -1 20856 -1 20857 -1 20858 -1 20859 -1 20860 -1 20861 -1 20862 -1 20863 -1 20864 -1 20865 -1 20866 -1 20867 -1 20868 -1 20869 -1 20870 -1 20871 -1 20872 -1 20873 -1 20874 -1 20875 -1 20876 -1 20877 -1 20878 -1 20879 -1 20880 -1 20881 -1 20882 -1 20883 -1 20884 -1 20885 -1 20886 -1 20887 -1 20888 -1 20889 -1 20890 -1 20891 -1 20892 -1 20893 -1 20894 -1 20895 -1 20896 -1 20897 -1 20898 -1 20899 -1 20900 -1 20901 -1 20902 -1 20903 -1 20904 -1 20905 -1 20906 -1 20907 -1 20908 -1 20909 -1 20910 -1 20911 -1 20912 -1 20913 -1 20914 -1 20915 -1 20916 -1 20917 -1 20918 -1 20919 -1 20920 -1 20921 -1 20922 -1 20923 -1 20924 -1 20925 -1 20926 -1 20927 -1 20928 -1 20929 -1 20930 -1 20931 -1 20932 -1 20933 -1 20934 -1 20935 -1 20936 -1 20937 -1 20938 -1 20939 -1 20940 -1 20941 -1 20942 -1 20943 -1 20944 -1 20945 -1 20946 -1 20947 -1 20948 -1 20949 -1 20950 -1 20951 -1 20952 -1 20953 -1 20954 -1 20955 -1 20956 -1 20957 -1 20958 -1 20959 -1 20960 -1 20961 -1 20962 -1 20963 -1 20964 -1 20965 -1 20966 -1 20967 -1 20968 -1 20969 -1 20970 -1 20971 -1 20972 -1 20973 -1 20974 -1 20975 -1 20976 -1 20977 -1 20978 -1 20979 -1 20980 -1 20981 -1 20982 -1 20983 -1 20984 -1 20985 -1 20986 -1 20987 -1 20988 -1 20989 -1 20990 -1 20991 -1 20992 -1 20993 -1 20994 -1 20995 -1 20996 -1 20997 -1 20998 -1 20999 -1 21000 -1 21001 -1 21002 -1 21003 -1 21004 -1 21005 -1 21006 -1 21007 -1 21008 -1 21009 -1 21010 -1 21011 -1 21012 -1 21013 -1 21014 -1 21015 -1 21016 -1 21017 -1 21018 -1 21019 -1 21020 -1 21021 -1 21022 -1 21023 -1 21024 -1 21025 -1 21026 -1 21027 -1 21028 -1 21029 -1 21030 -1 21031 -1 21032 -1 21033 -1 21034 -1 21035 -1 21036 -1 21037 -1 21038 -1 21039 -1 21040 -1 21041 -1 21042 -1 21043 -1 21044 -1 21045 -1 21046 -1 21047 -1 21048 -1 21049 -1 21050 -1 21051 -1 21052 -1 21053 -1 21054 -1 21055 -1 21056 -1 21057 -1 21058 -1 21059 -1 21060 -1 21061 -1 21062 -1 21063 -1 21064 -1 21065 -1 21066 -1 21067 -1 21068 -1 21069 -1 21070 -1 21071 -1 21072 -1 21073 -1 21074 -1 21075 -1 21076 -1 21077 -1 21078 -1 21079 -1 21080 -1 21081 -1 21082 -1 21083 -1 21084 -1 21085 -1 21086 -1 21087 -1 21088 -1 21089 -1 21090 -1 21091 -1 21092 -1 21093 -1 21094 -1 21095 -1 21096 -1 21097 -1 21098 -1 21099 -1 21100 -1 21101 -1 21102 -1 21103 -1 21104 -1 21105 -1 21106 -1 21107 -1 21108 -1 21109 -1 21110 -1 21111 -1 21112 -1 21113 -1 21114 -1 21115 -1 21116 -1 21117 -1 21118 -1 21119 -1 21120 -1 21121 -1 21122 -1 21123 -1 21124 -1 21125 -1 21126 -1 21127 -1 21128 -1 21129 -1 21130 -1 21131 -1 21132 -1 21133 -1 21134 -1 21135 -1 21136 -1 21137 -1 21138 -1 21139 -1 21140 -1 21141 -1 21142 -1 21143 -1 21144 -1 21145 -1 21146 -1 21147 -1 21148 -1 21149 -1 21150 -1 21151 -1 21152 -1 21153 -1 21154 -1 21155 -1 21156 -1 21157 -1 21158 -1 21159 -1 21160 -1 21161 -1 21162 -1 21163 -1 21164 -1 21165 -1 21166 -1 21167 -1 21168 -1 21169 -1 21170 -1 21171 -1 21172 -1 21173 -1 21174 -1 21175 -1 21176 -1 21177 -1 21178 -1 21179 -1 21180 -1 21181 -1 21182 -1 21183 -1 21184 -1 21185 -1 21186 -1 21187 -1 21188 -1 21189 -1 21190 -1 21191 -1 21192 -1 21193 -1 21194 -1 21195 -1 21196 -1 21197 -1 21198 -1 21199 -1 21200 -1 21201 -1 21202 -1 21203 -1 21204 -1 21205 -1 21206 -1 21207 -1 21208 -1 21209 -1 21210 -1 21211 -1 21212 -1 21213 -1 21214 -1 21215 -1 21216 -1 21217 -1 21218 -1 21219 -1 21220 -1 21221 -1 21222 -1 21223 -1 21224 -1 21225 -1 21226 -1 21227 -1 21228 -1 21229 -1 21230 -1 21231 -1 21232 -1 21233 -1 21234 -1 21235 -1 21236 -1 21237 -1 21238 -1 21239 -1 21240 -1 21241 -1 21242 -1 21243 -1 21244 -1 21245 -1 21246 -1 21247 -1 21248 -1 21249 -1 21250 -1 21251 -1 21252 -1 21253 -1 21254 -1 21255 -1 21256 -1 21257 -1 21258 -1 21259 -1 21260 -1 21261 -1 21262 -1 21263 -1 21264 -1 21265 -1 21266 -1 21267 -1 21268 -1 21269 -1 21270 -1 21271 -1 21272 -1 21273 -1 21274 -1 21275 -1 21276 -1 21277 -1 21278 -1 21279 -1 21280 -1 21281 -1 21282 -1 21283 -1 21284 -1 21285 -1 21286 -1 21287 -1 21288 -1 21289 -1 21290 -1 21291 -1 21292 -1 21293 -1 21294 -1 21295 -1 21296 -1 21297 -1 21298 -1 21299 -1 21300 -1 21301 -1 21302 -1 21303 -1 21304 -1 21305 -1 21306 -1 21307 -1 21308 -1 21309 -1 21310 -1 21311 -1 21312 -1 21313 -1 21314 -1 21315 -1 21316 -1 21317 -1 21318 -1 21319 -1 21320 -1 21321 -1 21322 -1 21323 -1 21324 -1 21325 -1 21326 -1 21327 -1 21328 -1 21329 -1 21330 -1 21331 -1 21332 -1 21333 -1 21334 -1 21335 -1 21336 -1 21337 -1 21338 -1 21339 -1 21340 -1 21341 -1 21342 -1 21343 -1 21344 -1 21345 -1 21346 -1 21347 -1 21348 -1 21349 -1 21350 -1 21351 -1 21352 -1 21353 -1 21354 -1 21355 -1 21356 -1 21357 -1 21358 -1 21359 -1 21360 -1 21361 -1 21362 -1 21363 -1 21364 -1 21365 -1 21366 -1 21367 -1 21368 -1 21369 -1 21370 -1 21371 -1 21372 -1 21373 -1 21374 -1 21375 -1 21376 -1 21377 -1 21378 -1 21379 -1 21380 -1 21381 -1 21382 -1 21383 -1 21384 -1 21385 -1 21386 -1 21387 -1 21388 -1 21389 -1 21390 -1 21391 -1 21392 -1 21393 -1 21394 -1 21395 -1 21396 -1 21397 -1 21398 -1 21399 -1 21400 -1 21401 -1 21402 -1 21403 -1 21404 -1 21405 -1 21406 -1 21407 -1 21408 -1 21409 -1 21410 -1 21411 -1 21412 -1 21413 -1 21414 -1 21415 -1 21416 -1 21417 -1 21418 -1 21419 -1 21420 -1 21421 -1 21422 -1 21423 -1 21424 -1 21425 -1 21426 -1 21427 -1 21428 -1 21429 -1 21430 -1 21431 -1 21432 -1 21433 -1 21434 -1 21435 -1 21436 -1 21437 -1 21438 -1 21439 -1 21440 -1 21441 -1 21442 -1 21443 -1 21444 -1 21445 -1 21446 -1 21447 -1 21448 -1 21449 -1 21450 -1 21451 -1 21452 -1 21453 -1 21454 -1 21455 -1 21456 -1 21457 -1 21458 -1 21459 -1 21460 -1 21461 -1 21462 -1 21463 -1 21464 -1 21465 -1 21466 -1 21467 -1 21468 -1 21469 -1 21470 -1 21471 -1 21472 -1 21473 -1 21474 -1 21475 -1 21476 -1 21477 -1 21478 -1 21479 -1 21480 -1 21481 -1 21482 -1 21483 -1 21484 -1 21485 -1 21486 -1 21487 -1 21488 -1 21489 -1 21490 -1 21491 -1 21492 -1 21493 -1 21494 -1 21495 -1 21496 -1 21497 -1 21498 -1 21499 -1 21500 -1 21501 -1 21502 -1 21503 -1 21504 -1 21505 -1 21506 -1 21507 -1 21508 -1 21509 -1 21510 -1 21511 -1 21512 -1 21513 -1 21514 -1 21515 -1 21516 -1 21517 -1 21518 -1 21519 -1 21520 -1 21521 -1 21522 -1 21523 -1 21524 -1 21525 -1 21526 -1 21527 -1 21528 -1 21529 -1 21530 -1 21531 -1 21532 -1 21533 -1 21534 -1 21535 -1 21536 -1 21537 -1 21538 -1 21539 -1 21540 -1 21541 -1 21542 -1 21543 -1 21544 -1 21545 -1 21546 -1 21547 -1 21548 -1 21549 -1 21550 -1 21551 -1 21552 -1 21553 -1 21554 -1 21555 -1 21556 -1 21557 -1 21558 -1 21559 -1 21560 -1 21561 -1 21562 -1 21563 -1 21564 -1 21565 -1 21566 -1 21567 -1 21568 -1 21569 -1 21570 -1 21571 -1 21572 -1 21573 -1 21574 -1 21575 -1 21576 -1 21577 -1 21578 -1 21579 -1 21580 -1 21581 -1 21582 -1 21583 -1 21584 -1 21585 -1 21586 -1 21587 -1 21588 -1 21589 -1 21590 -1 21591 -1 21592 -1 21593 -1 21594 -1 21595 -1 21596 -1 21597 -1 21598 -1 21599 -1 21600 -1 21601 -1 21602 -1 21603 -1 21604 -1 21605 -1 21606 -1 21607 -1 21608 -1 21609 -1 21610 -1 21611 -1 21612 -1 21613 -1 21614 -1 21615 -1 21616 -1 21617 -1 21618 -1 21619 -1 21620 -1 21621 -1 21622 -1 21623 -1 21624 -1 21625 -1 21626 -1 21627 -1 21628 -1 21629 -1 21630 -1 21631 -1 21632 -1 21633 -1 21634 -1 21635 -1 21636 -1 21637 -1 21638 -1 21639 -1 21640 -1 21641 -1 21642 -1 21643 -1 21644 -1 21645 -1 21646 -1 21647 -1 21648 -1 21649 -1 21650 -1 21651 -1 21652 -1 21653 -1 21654 -1 21655 -1 21656 -1 21657 -1 21658 -1 21659 -1 21660 -1 21661 -1 21662 -1 21663 -1 21664 -1 21665 -1 21666 -1 21667 -1 21668 -1 21669 -1 21670 -1 21671 -1 21672 -1 21673 -1 21674 -1 21675 -1 21676 -1 21677 -1 21678 -1 21679 -1 21680 -1 21681 -1 21682 -1 21683 -1 21684 -1 21685 -1 21686 -1 21687 -1 21688 -1 21689 -1 21690 -1 21691 -1 21692 -1 21693 -1 21694 -1 21695 -1 21696 -1 21697 -1 21698 -1 21699 -1 21700 -1 21701 -1 21702 -1 21703 -1 21704 -1 21705 -1 21706 -1 21707 -1 21708 -1 21709 -1 21710 -1 21711 -1 21712 -1 21713 -1 21714 -1 21715 -1 21716 -1 21717 -1 21718 -1 21719 -1 21720 -1 21721 -1 21722 -1 21723 -1 21724 -1 21725 -1 21726 -1 21727 -1 21728 -1 21729 -1 21730 -1 21731 -1 21732 -1 21733 -1 21734 -1 21735 -1 21736 -1 21737 -1 21738 -1 21739 -1 21740 -1 21741 -1 21742 -1 21743 -1 21744 -1 21745 -1 21746 -1 21747 -1 21748 -1 21749 -1 21750 -1 21751 -1 21752 -1 21753 -1 21754 -1 21755 -1 21756 -1 21757 -1 21758 -1 21759 -1 21760 -1 21761 -1 21762 -1 21763 -1 21764 -1 21765 -1 21766 -1 21767 -1 21768 -1 21769 -1 21770 -1 21771 -1 21772 -1 21773 -1 21774 -1 21775 -1 21776 -1 21777 -1 21778 -1 21779 -1 21780 -1 21781 -1 21782 -1 21783 -1 21784 -1 21785 -1 21786 -1 21787 -1 21788 -1 21789 -1 21790 -1 21791 -1 21792 -1 21793 -1 21794 -1 21795 -1 21796 -1 21797 -1 21798 -1 21799 -1 21800 -1 21801 -1 21802 -1 21803 -1 21804 -1 21805 -1 21806 -1 21807 -1 21808 -1 21809 -1 21810 -1 21811 -1 21812 -1 21813 -1 21814 -1 21815 -1 21816 -1 21817 -1 21818 -1 21819 -1 21820 -1 21821 -1 21822 -1 21823 -1 21824 -1 21825 -1 21826 -1 21827 -1 21828 -1 21829 -1 21830 -1 21831 -1 21832 -1 21833 -1 21834 -1 21835 -1 21836 -1 21837 -1 21838 -1 21839 -1 21840 -1 21841 -1 21842 -1 21843 -1 21844 -1 21845 -1 21846 -1 21847 -1 21848 -1 21849 -1 21850 -1 21851 -1 21852 -1 21853 -1 21854 -1 21855 -1 21856 -1 21857 -1 21858 -1 21859 -1 21860 -1 21861 -1 21862 -1 21863 -1 21864 -1 21865 -1 21866 -1 21867 -1 21868 -1 21869 -1 21870 -1 21871 -1 21872 -1 21873 -1 21874 -1 21875 -1 21876 -1 21877 -1 21878 -1 21879 -1 21880 -1 21881 -1 21882 -1 21883 -1 21884 -1 21885 -1 21886 -1 21887 -1 21888 -1 21889 -1 21890 -1 21891 -1 21892 -1 21893 -1 21894 -1 21895 -1 21896 -1 21897 -1 21898 -1 21899 -1 21900 -1 21901 -1 21902 -1 21903 -1 21904 -1 21905 -1 21906 -1 21907 -1 21908 -1 21909 -1 21910 -1 21911 -1 21912 -1 21913 -1 21914 -1 21915 -1 21916 -1 21917 -1 21918 -1 21919 -1 21920 -1 21921 -1 21922 -1 21923 -1 21924 -1 21925 -1 21926 -1 21927 -1 21928 -1 21929 -1 21930 -1 21931 -1 21932 -1 21933 -1 21934 -1 21935 -1 21936 -1 21937 -1 21938 -1 21939 -1 21940 -1 21941 -1 21942 -1 21943 -1 21944 -1 21945 -1 21946 -1 21947 -1 21948 -1 21949 -1 21950 -1 21951 -1 21952 -1 21953 -1 21954 -1 21955 -1 21956 -1 21957 -1 21958 -1 21959 -1 21960 -1 21961 -1 21962 -1 21963 -1 21964 -1 21965 -1 21966 -1 21967 -1 21968 -1 21969 -1 21970 -1 21971 -1 21972 -1 21973 -1 21974 -1 21975 -1 21976 -1 21977 -1 21978 -1 21979 -1 21980 -1 21981 -1 21982 -1 21983 -1 21984 -1 21985 -1 21986 -1 21987 -1 21988 -1 21989 -1 21990 -1 21991 -1 21992 -1 21993 -1 21994 -1 21995 -1 21996 -1 21997 -1 21998 -1 21999 -1 22000 -1 22001 -1 22002 -1 22003 -1 22004 -1 22005 -1 22006 -1 22007 -1 22008 -1 22009 -1 22010 -1 22011 -1 22012 -1 22013 -1 22014 -1 22015 -1 22016 -1 22017 -1 22018 -1 22019 -1 22020 -1 22021 -1 22022 -1 22023 -1 22024 -1 22025 -1 22026 -1 22027 -1 22028 -1 22029 -1 22030 -1 22031 -1 22032 -1 22033 -1 22034 -1 22035 -1 22036 -1 22037 -1 22038 -1 22039 -1 22040 -1 22041 -1 22042 -1 22043 -1 22044 -1 22045 -1 22046 -1 22047 -1 22048 -1 22049 -1 22050 -1 22051 -1 22052 -1 22053 -1 22054 -1 22055 -1 22056 -1 22057 -1 22058 -1 22059 -1 22060 -1 22061 -1 22062 -1 22063 -1 22064 -1 22065 -1 22066 -1 22067 -1 22068 -1 22069 -1 22070 -1 22071 -1 22072 -1 22073 -1 22074 -1 22075 -1 22076 -1 22077 -1 22078 -1 22079 -1 22080 -1 22081 -1 22082 -1 22083 -1 22084 -1 22085 -1 22086 -1 22087 -1 22088 -1 22089 -1 22090 -1 22091 -1 22092 -1 22093 -1 22094 -1 22095 -1 22096 -1 22097 -1 22098 -1 22099 -1 22100 -1 22101 -1 22102 -1 22103 -1 22104 -1 22105 -1 22106 -1 22107 -1 22108 -1 22109 -1 22110 -1 22111 -1 22112 -1 22113 -1 22114 -1 22115 -1 22116 -1 22117 -1 22118 -1 22119 -1 22120 -1 22121 -1 22122 -1 22123 -1 22124 -1 22125 -1 22126 -1 22127 -1 22128 -1 22129 -1 22130 -1 22131 -1 22132 -1 22133 -1 22134 -1 22135 -1 22136 -1 22137 -1 22138 -1 22139 -1 22140 -1 22141 -1 22142 -1 22143 -1 22144 -1 22145 -1 22146 -1 22147 -1 22148 -1 22149 -1 22150 -1 22151 -1 22152 -1 22153 -1 22154 -1 22155 -1 22156 -1 22157 -1 22158 -1 22159 -1 22160 -1 22161 -1 22162 -1 22163 -1 22164 -1 22165 -1 22166 -1 22167 -1 22168 -1 22169 -1 22170 -1 22171 -1 22172 -1 22173 -1 22174 -1 22175 -1 22176 -1 22177 -1 22178 -1 22179 -1 22180 -1 22181 -1 22182 -1 22183 -1 22184 -1 22185 -1 22186 -1 22187 -1 22188 -1 22189 -1 22190 -1 22191 -1 22192 -1 22193 -1 22194 -1 22195 -1 22196 -1 22197 -1 22198 -1 22199 -1 22200 -1 22201 -1 22202 -1 22203 -1 22204 -1 22205 -1 22206 -1 22207 -1 22208 -1 22209 -1 22210 -1 22211 -1 22212 -1 22213 -1 22214 -1 22215 -1 22216 -1 22217 -1 22218 -1 22219 -1 22220 -1 22221 -1 22222 -1 22223 -1 22224 -1 22225 -1 22226 -1 22227 -1 22228 -1 22229 -1 22230 -1 22231 -1 22232 -1 22233 -1 22234 -1 22235 -1 22236 -1 22237 -1 22238 -1 22239 -1 22240 -1 22241 -1 22242 -1 22243 -1 22244 -1 22245 -1 22246 -1 22247 -1 22248 -1 22249 -1 22250 -1 22251 -1 22252 -1 22253 -1 22254 -1 22255 -1 22256 -1 22257 -1 22258 -1 22259 -1 22260 -1 22261 -1 22262 -1 22263 -1 22264 -1 22265 -1 22266 -1 22267 -1 22268 -1 22269 -1 22270 -1 22271 -1 22272 -1 22273 -1 22274 -1 22275 -1 22276 -1 22277 -1 22278 -1 22279 -1 22280 -1 22281 -1 22282 -1 22283 -1 22284 -1 22285 -1 22286 -1 22287 -1 22288 -1 22289 -1 22290 -1 22291 -1 22292 -1 22293 -1 22294 -1 22295 -1 22296 -1 22297 -1 22298 -1 22299 -1 22300 -1 22301 -1 22302 -1 22303 -1 22304 -1 22305 -1 22306 -1 22307 -1 22308 -1 22309 -1 22310 -1 22311 -1 22312 -1 22313 -1 22314 -1 22315 -1 22316 -1 22317 -1 22318 -1 22319 -1 22320 -1 22321 -1 22322 -1 22323 -1 22324 -1 22325 -1 22326 -1 22327 -1 22328 -1 22329 -1 22330 -1 22331 -1 22332 -1 22333 -1 22334 -1 22335 -1 22336 -1 22337 -1 22338 -1 22339 -1 22340 -1 22341 -1 22342 -1 22343 -1 22344 -1 22345 -1 22346 -1 22347 -1 22348 -1 22349 -1 22350 -1 22351 -1 22352 -1 22353 -1 22354 -1 22355 -1 22356 -1 22357 -1 22358 -1 22359 -1 22360 -1 22361 -1 22362 -1 22363 -1 22364 -1 22365 -1 22366 -1 22367 -1 22368 -1 22369 -1 22370 -1 22371 -1 22372 -1 22373 -1 22374 -1 22375 -1 22376 -1 22377 -1 22378 -1 22379 -1 22380 -1 22381 -1 22382 -1 22383 -1 22384 -1 22385 -1 22386 -1 22387 -1 22388 -1 22389 -1 22390 -1 22391 -1 22392 -1 22393 -1 22394 -1 22395 -1 22396 -1 22397 -1 22398 -1 22399 -1 22400 -1 22401 -1 22402 -1 22403 -1 22404 -1 22405 -1 22406 -1 22407 -1 22408 -1 22409 -1 22410 -1 22411 -1 22412 -1 22413 -1 22414 -1 22415 -1 22416 -1 22417 -1 22418 -1 22419 -1 22420 -1 22421 -1 22422 -1 22423 -1 22424 -1 22425 -1 22426 -1 22427 -1 22428 -1 22429 -1 22430 -1 22431 -1 22432 -1 22433 -1 22434 -1 22435 -1 22436 -1 22437 -1 22438 -1 22439 -1 22440 -1 22441 -1 22442 -1 22443 -1 22444 -1 22445 -1 22446 -1 22447 -1 22448 -1 22449 -1 22450 -1 22451 -1 22452 -1 22453 -1 22454 -1 22455 -1 22456 -1 22457 -1 22458 -1 22459 -1 22460 -1 22461 -1 22462 -1 22463 -1 22464 -1 22465 -1 22466 -1 22467 -1 22468 -1 22469 -1 22470 -1 22471 -1 22472 -1 22473 -1 22474 -1 22475 -1 22476 -1 22477 -1 22478 -1 22479 -1 22480 -1 22481 -1 22482 -1 22483 -1 22484 -1 22485 -1 22486 -1 22487 -1 22488 -1 22489 -1 22490 -1 22491 -1 22492 -1 22493 -1 22494 -1 22495 -1 22496 -1 22497 -1 22498 -1 22499 -1 22500 -1 22501 -1 22502 -1 22503 -1 22504 -1 22505 -1 22506 -1 22507 -1 22508 -1 22509 -1 22510 -1 22511 -1 22512 -1 22513 -1 22514 -1 22515 -1 22516 -1 22517 -1 22518 -1 22519 -1 22520 -1 22521 -1 22522 -1 22523 -1 22524 -1 22525 -1 22526 -1 22527 -1 22528 -1 22529 -1 22530 -1 22531 -1 22532 -1 22533 -1 22534 -1 22535 -1 22536 -1 22537 -1 22538 -1 22539 -1 22540 -1 22541 -1 22542 -1 22543 -1 22544 -1 22545 -1 22546 -1 22547 -1 22548 -1 22549 -1 22550 -1 22551 -1 22552 -1 22553 -1 22554 -1 22555 -1 22556 -1 22557 -1 22558 -1 22559 -1 22560 -1 22561 -1 22562 -1 22563 -1 22564 -1 22565 -1 22566 -1 22567 -1 22568 -1 22569 -1 22570 -1 22571 -1 22572 -1 22573 -1 22574 -1 22575 -1 22576 -1 22577 -1 22578 -1 22579 -1 22580 -1 22581 -1 22582 -1 22583 -1 22584 -1 22585 -1 22586 -1 22587 -1 22588 -1 22589 -1 22590 -1 22591 -1 22592 -1 22593 -1 22594 -1 22595 -1 22596 -1 22597 -1 22598 -1 22599 -1 22600 -1 22601 -1 22602 -1 22603 -1 22604 -1 22605 -1 22606 -1 22607 -1 22608 -1 22609 -1 22610 -1 22611 -1 22612 -1 22613 -1 22614 -1 22615 -1 22616 -1 22617 -1 22618 -1 22619 -1 22620 -1 22621 -1 22622 -1 22623 -1 22624 -1 22625 -1 22626 -1 22627 -1 22628 -1 22629 -1 22630 -1 22631 -1 22632 -1 22633 -1 22634 -1 22635 -1 22636 -1 22637 -1 22638 -1 22639 -1 22640 -1 22641 -1 22642 -1 22643 -1 22644 -1 22645 -1 22646 -1 22647 -1 22648 -1 22649 -1 22650 -1 22651 -1 22652 -1 22653 -1 22654 -1 22655 -1 22656 -1 22657 -1 22658 -1 22659 -1 22660 -1 22661 -1 22662 -1 22663 -1 22664 -1 22665 -1 22666 -1 22667 -1 22668 -1 22669 -1 22670 -1 22671 -1 22672 -1 22673 -1 22674 -1 22675 -1 22676 -1 22677 -1 22678 -1 22679 -1 22680 -1 22681 -1 22682 -1 22683 -1 22684 -1 22685 -1 22686 -1 22687 -1 22688 -1 22689 -1 22690 -1 22691 -1 22692 -1 22693 -1 22694 -1 22695 -1 22696 -1 22697 -1 22698 -1 22699 -1 22700 -1 22701 -1 22702 -1 22703 -1 22704 -1 22705 -1 22706 -1 22707 -1 22708 -1 22709 -1 22710 -1 22711 -1 22712 -1 22713 -1 22714 -1 22715 -1 22716 -1 22717 -1 22718 -1 22719 -1 22720 -1 22721 -1 22722 -1 22723 -1 22724 -1 22725 -1 22726 -1 22727 -1 22728 -1 22729 -1 22730 -1 22731 -1 22732 -1 22733 -1 22734 -1 22735 -1 22736 -1 22737 -1 22738 -1 22739 -1 22740 -1 22741 -1 22742 -1 22743 -1 22744 -1 22745 -1 22746 -1 22747 -1 22748 -1 22749 -1 22750 -1 22751 -1 22752 -1 22753 -1 22754 -1 22755 -1 22756 -1 22757 -1 22758 -1 22759 -1 22760 -1 22761 -1 22762 -1 22763 -1 22764 -1 22765 -1 22766 -1 22767 -1 22768 -1 22769 -1 22770 -1 22771 -1 22772 -1 22773 -1 22774 -1 22775 -1 22776 -1 22777 -1 22778 -1 22779 -1 22780 -1 22781 -1 22782 -1 22783 -1 22784 -1 22785 -1 22786 -1 22787 -1 22788 -1 22789 -1 22790 -1 22791 -1 22792 -1 22793 -1 22794 -1 22795 -1 22796 -1 22797 -1 22798 -1 22799 -1 22800 -1 22801 -1 22802 -1 22803 -1 22804 -1 22805 -1 22806 -1 22807 -1 22808 -1 22809 -1 22810 -1 22811 -1 22812 -1 22813 -1 22814 -1 22815 -1 22816 -1 22817 -1 22818 -1 22819 -1 22820 -1 22821 -1 22822 -1 22823 -1 22824 -1 22825 -1 22826 -1 22827 -1 22828 -1 22829 -1 22830 -1 22831 -1 22832 -1 22833 -1 22834 -1 22835 -1 22836 -1 22837 -1 22838 -1 22839 -1 22840 -1 22841 -1 22842 -1 22843 -1 22844 -1 22845 -1 22846 -1 22847 -1 22848 -1 22849 -1 22850 -1 22851 -1 22852 -1 22853 -1 22854 -1 22855 -1 22856 -1 22857 -1 22858 -1 22859 -1 22860 -1 22861 -1 22862 -1 22863 -1 22864 -1 22865 -1 22866 -1 22867 -1 22868 -1 22869 -1 22870 -1 22871 -1 22872 -1 22873 -1 22874 -1 22875 -1 22876 -1 22877 -1 22878 -1 22879 -1 22880 -1 22881 -1 22882 -1 22883 -1 22884 -1 22885 -1 22886 -1 22887 -1 22888 -1 22889 -1 22890 -1 22891 -1 22892 -1 22893 -1 22894 -1 22895 -1 22896 -1 22897 -1 22898 -1 22899 -1 22900 -1 22901 -1 22902 -1 22903 -1 22904 -1 22905 -1 22906 -1 22907 -1 22908 -1 22909 -1 22910 -1 22911 -1 22912 -1 22913 -1 22914 -1 22915 -1 22916 -1 22917 -1 22918 -1 22919 -1 22920 -1 22921 -1 22922 -1 22923 -1 22924 -1 22925 -1 22926 -1 22927 -1 22928 -1 22929 -1 22930 -1 22931 -1 22932 -1 22933 -1 22934 -1 22935 -1 22936 -1 22937 -1 22938 -1 22939 -1 22940 -1 22941 -1 22942 -1 22943 -1 22944 -1 22945 -1 22946 -1 22947 -1 22948 -1 22949 -1 22950 -1 22951 -1 22952 -1 22953 -1 22954 -1 22955 -1 22956 -1 22957 -1 22958 -1 22959 -1 22960 -1 22961 -1 22962 -1 22963 -1 22964 -1 22965 -1 22966 -1 22967 -1 22968 -1 22969 -1 22970 -1 22971 -1 22972 -1 22973 -1 22974 -1 22975 -1 22976 -1 22977 -1 22978 -1 22979 -1 22980 -1 22981 -1 22982 -1 22983 -1 22984 -1 22985 -1 22986 -1 22987 -1 22988 -1 22989 -1 22990 -1 22991 -1 22992 -1 22993 -1 22994 -1 22995 -1 22996 -1 22997 -1 22998 -1 22999 -1 23000 -1 23001 -1 23002 -1 23003 -1 23004 -1 23005 -1 23006 -1 23007 -1 23008 -1 23009 -1 23010 -1 23011 -1 23012 -1 23013 -1 23014 -1 23015 -1 23016 -1 23017 -1 23018 -1 23019 -1 23020 -1 23021 -1 23022 -1 23023 -1 23024 -1 23025 -1 23026 -1 23027 -1 23028 -1 23029 -1 23030 -1 23031 -1 23032 -1 23033 -1 23034 -1 23035 -1 23036 -1 23037 -1 23038 -1 23039 -1 23040 -1 23041 -1 23042 -1 23043 -1 23044 -1 23045 -1 23046 -1 23047 -1 23048 -1 23049 -1 23050 -1 23051 -1 23052 -1 23053 -1 23054 -1 23055 -1 23056 -1 23057 -1 23058 -1 23059 -1 23060 -1 23061 -1 23062 -1 23063 -1 23064 -1 23065 -1 23066 -1 23067 -1 23068 -1 23069 -1 23070 -1 23071 -1 23072 -1 23073 -1 23074 -1 23075 -1 23076 -1 23077 -1 23078 -1 23079 -1 23080 -1 23081 -1 23082 -1 23083 -1 23084 -1 23085 -1 23086 -1 23087 -1 23088 -1 23089 -1 23090 -1 23091 -1 23092 -1 23093 -1 23094 -1 23095 -1 23096 -1 23097 -1 23098 -1 23099 -1 23100 -1 23101 -1 23102 -1 23103 -1 23104 -1 23105 -1 23106 -1 23107 -1 23108 -1 23109 -1 23110 -1 23111 -1 23112 -1 23113 -1 23114 -1 23115 -1 23116 -1 23117 -1 23118 -1 23119 -1 23120 -1 23121 -1 23122 -1 23123 -1 23124 -1 23125 -1 23126 -1 23127 -1 23128 -1 23129 -1 23130 -1 23131 -1 23132 -1 23133 -1 23134 -1 23135 -1 23136 -1 23137 -1 23138 -1 23139 -1 23140 -1 23141 -1 23142 -1 23143 -1 23144 -1 23145 -1 23146 -1 23147 -1 23148 -1 23149 -1 23150 -1 23151 -1 23152 -1 23153 -1 23154 -1 23155 -1 23156 -1 23157 -1 23158 -1 23159 -1 23160 -1 23161 -1 23162 -1 23163 -1 23164 -1 23165 -1 23166 -1 23167 -1 23168 -1 23169 -1 23170 -1 23171 -1 23172 -1 23173 -1 23174 -1 23175 -1 23176 -1 23177 -1 23178 -1 23179 -1 23180 -1 23181 -1 23182 -1 23183 -1 23184 -1 23185 -1 23186 -1 23187 -1 23188 -1 23189 -1 23190 -1 23191 -1 23192 -1 23193 -1 23194 -1 23195 -1 23196 -1 23197 -1 23198 -1 23199 -1 23200 -1 23201 -1 23202 -1 23203 -1 23204 -1 23205 -1 23206 -1 23207 -1 23208 -1 23209 -1 23210 -1 23211 -1 23212 -1 23213 -1 23214 -1 23215 -1 23216 -1 23217 -1 23218 -1 23219 -1 23220 -1 23221 -1 23222 -1 23223 -1 23224 -1 23225 -1 23226 -1 23227 -1 23228 -1 23229 -1 23230 -1 23231 -1 23232 -1 23233 -1 23234 -1 23235 -1 23236 -1 23237 -1 23238 -1 23239 -1 23240 -1 23241 -1 23242 -1 23243 -1 23244 -1 23245 -1 23246 -1 23247 -1 23248 -1 23249 -1 23250 -1 23251 -1 23252 -1 23253 -1 23254 -1 23255 -1 23256 -1 23257 -1 23258 -1 23259 -1 23260 -1 23261 -1 23262 -1 23263 -1 23264 -1 23265 -1 23266 -1 23267 -1 23268 -1 23269 -1 23270 -1 23271 -1 23272 -1 23273 -1 23274 -1 23275 -1 23276 -1 23277 -1 23278 -1 23279 -1 23280 -1 23281 -1 23282 -1 23283 -1 23284 -1 23285 -1 23286 -1 23287 -1 23288 -1 23289 -1 23290 -1 23291 -1 23292 -1 23293 -1 23294 -1 23295 -1 23296 -1 23297 -1 23298 -1 23299 -1 23300 -1 23301 -1 23302 -1 23303 -1 23304 -1 23305 -1 23306 -1 23307 -1 23308 -1 23309 -1 23310 -1 23311 -1 23312 -1 23313 -1 23314 -1 23315 -1 23316 -1 23317 -1 23318 -1 23319 -1 23320 -1 23321 -1 23322 -1 23323 -1 23324 -1 23325 -1 23326 -1 23327 -1 23328 -1 23329 -1 23330 -1 23331 -1 23332 -1 23333 -1 23334 -1 23335 -1 23336 -1 23337 -1 23338 -1 23339 -1 23340 -1 23341 -1 23342 -1 23343 -1 23344 -1 23345 -1 23346 -1 23347 -1 23348 -1 23349 -1 23350 -1 23351 -1 23352 -1 23353 -1 23354 -1 23355 -1 23356 -1 23357 -1 23358 -1 23359 -1 23360 -1 23361 -1 23362 -1 23363 -1 23364 -1 23365 -1 23366 -1 23367 -1 23368 -1 23369 -1 23370 -1 23371 -1 23372 -1 23373 -1 23374 -1 23375 -1 23376 -1 23377 -1 23378 -1 23379 -1 23380 -1 23381 -1 23382 -1 23383 -1 23384 -1 23385 -1 23386 -1 23387 -1 23388 -1 23389 -1 23390 -1 23391 -1 23392 -1 23393 -1 23394 -1 23395 -1 23396 -1 23397 -1 23398 -1 23399 -1 23400 -1 23401 -1 23402 -1 23403 -1 23404 -1 23405 -1 23406 -1 23407 -1 23408 -1 23409 -1 23410 -1 23411 -1 23412 -1 23413 -1 23414 -1 23415 -1 23416 -1 23417 -1 23418 -1 23419 -1 23420 -1 23421 -1 23422 -1 23423 -1 23424 -1 23425 -1 23426 -1 23427 -1 23428 -1 23429 -1 23430 -1 23431 -1 23432 -1 23433 -1 23434 -1 23435 -1 23436 -1 23437 -1 23438 -1 23439 -1 23440 -1 23441 -1 23442 -1 23443 -1 23444 -1 23445 -1 23446 -1 23447 -1 23448 -1 23449 -1 23450 -1 23451 -1 23452 -1 23453 -1 23454 -1 23455 -1 23456 -1 23457 -1 23458 -1 23459 -1 23460 -1 23461 -1 23462 -1 23463 -1 23464 -1 23465 -1 23466 -1 23467 -1 23468 -1 23469 -1 23470 -1 23471 -1 23472 -1 23473 -1 23474 -1 23475 -1 23476 -1 23477 -1 23478 -1 23479 -1 23480 -1 23481 -1 23482 -1 23483 -1 23484 -1 23485 -1 23486 -1 23487 -1 23488 -1 23489 -1 23490 -1 23491 -1 23492 -1 23493 -1 23494 -1 23495 -1 23496 -1 23497 -1 23498 -1 23499 -1 23500 -1 23501 -1 23502 -1 23503 -1 23504 -1 23505 -1 23506 -1 23507 -1 23508 -1 23509 -1 23510 -1 23511 -1 23512 -1 23513 -1 23514 -1 23515 -1 23516 -1 23517 -1 23518 -1 23519 -1 23520 -1 23521 -1 23522 -1 23523 -1 23524 -1 23525 -1 23526 -1 23527 -1 23528 -1 23529 -1 23530 -1 23531 -1 23532 -1 23533 -1 23534 -1 23535 -1 23536 -1 23537 -1 23538 -1 23539 -1 23540 -1 23541 -1 23542 -1 23543 -1 23544 -1 23545 -1 23546 -1 23547 -1 23548 -1 23549 -1 23550 -1 23551 -1 23552 -1 23553 -1 23554 -1 23555 -1 23556 -1 23557 -1 23558 -1 23559 -1 23560 -1 23561 -1 23562 -1 23563 -1 23564 -1 23565 -1 23566 -1 23567 -1 23568 -1 23569 -1 23570 -1 23571 -1 23572 -1 23573 -1 23574 -1 23575 -1 23576 -1 23577 -1 23578 -1 23579 -1 23580 -1 23581 -1 23582 -1 23583 -1 23584 -1 23585 -1 23586 -1 23587 -1 23588 -1 23589 -1 23590 -1 23591 -1 23592 -1 23593 -1 23594 -1 23595 -1 23596 -1 23597 -1 23598 -1 23599 -1 23600 -1 23601 -1 23602 -1 23603 -1 23604 -1 23605 -1 23606 -1 23607 -1 23608 -1 23609 -1 23610 -1 23611 -1 23612 -1 23613 -1 23614 -1 23615 -1 23616 -1 23617 -1 23618 -1 23619 -1 23620 -1 23621 -1 23622 -1 23623 -1 23624 -1 23625 -1 23626 -1 23627 -1 23628 -1 23629 -1 23630 -1 23631 -1 23632 -1 23633 -1 23634 -1 23635 -1 23636 -1 23637 -1 23638 -1 23639 -1 23640 -1 23641 -1 23642 -1 23643 -1 23644 -1 23645 -1 23646 -1 23647 -1 23648 -1 23649 -1 23650 -1 23651 -1 23652 -1 23653 -1 23654 -1 23655 -1 23656 -1 23657 -1 23658 -1 23659 -1 23660 -1 23661 -1 23662 -1 23663 -1 23664 -1 23665 -1 23666 -1 23667 -1 23668 -1 23669 -1 23670 -1 23671 -1 23672 -1 23673 -1 23674 -1 23675 -1 23676 -1 23677 -1 23678 -1 23679 -1 23680 -1 23681 -1 23682 -1 23683 -1 23684 -1 23685 -1 23686 -1 23687 -1 23688 -1 23689 -1 23690 -1 23691 -1 23692 -1 23693 -1 23694 -1 23695 -1 23696 -1 23697 -1 23698 -1 23699 -1 23700 -1 23701 -1 23702 -1 23703 -1 23704 -1 23705 -1 23706 -1 23707 -1 23708 -1 23709 -1 23710 -1 23711 -1 23712 -1 23713 -1 23714 -1 23715 -1 23716 -1 23717 -1 23718 -1 23719 -1 23720 -1 23721 -1 23722 -1 23723 -1 23724 -1 23725 -1 23726 -1 23727 -1 23728 -1 23729 -1 23730 -1 23731 -1 23732 -1 23733 -1 23734 -1 23735 -1 23736 -1 23737 -1 23738 -1 23739 -1 23740 -1 23741 -1 23742 -1 23743 -1 23744 -1 23745 -1 23746 -1 23747 -1 23748 -1 23749 -1 23750 -1 23751 -1 23752 -1 23753 -1 23754 -1 23755 -1 23756 -1 23757 -1 23758 -1 23759 -1 23760 -1 23761 -1 23762 -1 23763 -1 23764 -1 23765 -1 23766 -1 23767 -1 23768 -1 23769 -1 23770 -1 23771 -1 23772 -1 23773 -1 23774 -1 23775 -1 23776 -1 23777 -1 23778 -1 23779 -1 23780 -1 23781 -1 23782 -1 23783 -1 23784 -1 23785 -1 23786 -1 23787 -1 23788 -1 23789 -1 23790 -1 23791 -1 23792 -1 23793 -1 23794 -1 23795 -1 23796 -1 23797 -1 23798 -1 23799 -1 23800 -1 23801 -1 23802 -1 23803 -1 23804 -1 23805 -1 23806 -1 23807 -1 23808 -1 23809 -1 23810 -1 23811 -1 23812 -1 23813 -1 23814 -1 23815 -1 23816 -1 23817 -1 23818 -1 23819 -1 23820 -1 23821 -1 23822 -1 23823 -1 23824 -1 23825 -1 23826 -1 23827 -1 23828 -1 23829 -1 23830 -1 23831 -1 23832 -1 23833 -1 23834 -1 23835 -1 23836 -1 23837 -1 23838 -1 23839 -1 23840 -1 23841 -1 23842 -1 23843 -1 23844 -1 23845 -1 23846 -1 23847 -1 23848 -1 23849 -1 23850 -1 23851 -1 23852 -1 23853 -1 23854 -1 23855 -1 23856 -1 23857 -1 23858 -1 23859 -1 23860 -1 23861 -1 23862 -1 23863 -1 23864 -1 23865 -1 23866 -1 23867 -1 23868 -1 23869 -1 23870 -1 23871 -1 23872 -1 23873 -1 23874 -1 23875 -1 23876 -1 23877 -1 23878 -1 23879 -1 23880 -1 23881 -1 23882 -1 23883 -1 23884 -1 23885 -1 23886 -1 23887 -1 23888 -1 23889 -1 23890 -1 23891 -1 23892 -1 23893 -1 23894 -1 23895 -1 23896 -1 23897 -1 23898 -1 23899 -1 23900 -1 23901 -1 23902 -1 23903 -1 23904 -1 23905 -1 23906 -1 23907 -1 23908 -1 23909 -1 23910 -1 23911 -1 23912 -1 23913 -1 23914 -1 23915 -1 23916 -1 23917 -1 23918 -1 23919 -1 23920 -1 23921 -1 23922 -1 23923 -1 23924 -1 23925 -1 23926 -1 23927 -1 23928 -1 23929 -1 23930 -1 23931 -1 23932 -1 23933 -1 23934 -1 23935 -1 23936 -1 23937 -1 23938 -1 23939 -1 23940 -1 23941 -1 23942 -1 23943 -1 23944 -1 23945 -1 23946 -1 23947 -1 23948 -1 23949 -1 23950 -1 23951 -1 23952 -1 23953 -1 23954 -1 23955 -1 23956 -1 23957 -1 23958 -1 23959 -1 23960 -1 23961 -1 23962 -1 23963 -1 23964 -1 23965 -1 23966 -1 23967 -1 23968 -1 23969 -1 23970 -1 23971 -1 23972 -1 23973 -1 23974 -1 23975 -1 23976 -1 23977 -1 23978 -1 23979 -1 23980 -1 23981 -1 23982 -1 23983 -1 23984 -1 23985 -1 23986 -1 23987 -1 23988 -1 23989 -1 23990 -1 23991 -1 23992 -1 23993 -1 23994 -1 23995 -1 23996 -1 23997 -1 23998 -1 23999 -1 24000 -1 24001 -1 24002 -1 24003 -1 24004 -1 24005 -1 24006 -1 24007 -1 24008 -1 24009 -1 24010 -1 24011 -1 24012 -1 24013 -1 24014 -1 24015 -1 24016 -1 24017 -1 24018 -1 24019 -1 24020 -1 24021 -1 24022 -1 24023 -1 24024 -1 24025 -1 24026 -1 24027 -1 24028 -1 24029 -1 24030 -1 24031 -1 24032 -1 24033 -1 24034 -1 24035 -1 24036 -1 24037 -1 24038 -1 24039 -1 24040 -1 24041 -1 24042 -1 24043 -1 24044 -1 24045 -1 24046 -1 24047 -1 24048 -1 24049 -1 24050 -1 24051 -1 24052 -1 24053 -1 24054 -1 24055 -1 24056 -1 24057 -1 24058 -1 24059 -1 24060 -1 24061 -1 24062 -1 24063 -1 24064 -1 24065 -1 24066 -1 24067 -1 24068 -1 24069 -1 24070 -1 24071 -1 24072 -1 24073 -1 24074 -1 24075 -1 24076 -1 24077 -1 24078 -1 24079 -1 24080 -1 24081 -1 24082 -1 24083 -1 24084 -1 24085 -1 24086 -1 24087 -1 24088 -1 24089 -1 24090 -1 24091 -1 24092 -1 24093 -1 24094 -1 24095 -1 24096 -1 24097 -1 24098 -1 24099 -1 24100 -1 24101 -1 24102 -1 24103 -1 24104 -1 24105 -1 24106 -1 24107 -1 24108 -1 24109 -1 24110 -1 24111 -1 24112 -1 24113 -1 24114 -1 24115 -1 24116 -1 24117 -1 24118 -1 24119 -1 24120 -1 24121 -1 24122 -1 24123 -1 24124 -1 24125 -1 24126 -1 24127 -1 24128 -1 24129 -1 24130 -1 24131 -1 24132 -1 24133 -1 24134 -1 24135 -1 24136 -1 24137 -1 24138 -1 24139 -1 24140 -1 24141 -1 24142 -1 24143 -1 24144 -1 24145 -1 24146 -1 24147 -1 24148 -1 24149 -1 24150 -1 24151 -1 24152 -1 24153 -1 24154 -1 24155 -1 24156 -1 24157 -1 24158 -1 24159 -1 24160 -1 24161 -1 24162 -1 24163 -1 24164 -1 24165 -1 24166 -1 24167 -1 24168 -1 24169 -1 24170 -1 24171 -1 24172 -1 24173 -1 24174 -1 24175 -1 24176 -1 24177 -1 24178 -1 24179 -1 24180 -1 24181 -1 24182 -1 24183 -1 24184 -1 24185 -1 24186 -1 24187 -1 24188 -1 24189 -1 24190 -1 24191 -1 24192 -1 24193 -1 24194 -1 24195 -1 24196 -1 24197 -1 24198 -1 24199 -1 24200 -1 24201 -1 24202 -1 24203 -1 24204 -1 24205 -1 24206 -1 24207 -1 24208 -1 24209 -1 24210 -1 24211 -1 24212 -1 24213 -1 24214 -1 24215 -1 24216 -1 24217 -1 24218 -1 24219 -1 24220 -1 24221 -1 24222 -1 24223 -1 24224 -1 24225 -1 24226 -1 24227 -1 24228 -1 24229 -1 24230 -1 24231 -1 24232 -1 24233 -1 24234 -1 24235 -1 24236 -1 24237 -1 24238 -1 24239 -1 24240 -1 24241 -1 24242 -1 24243 -1 24244 -1 24245 -1 24246 -1 24247 -1 24248 -1 24249 -1 24250 -1 24251 -1 24252 -1 24253 -1 24254 -1 24255 -1 24256 -1 24257 -1 24258 -1 24259 -1 24260 -1 24261 -1 24262 -1 24263 -1 24264 -1 24265 -1 24266 -1 24267 -1 24268 -1 24269 -1 24270 -1 24271 -1 24272 -1 24273 -1 24274 -1 24275 -1 24276 -1 24277 -1 24278 -1 24279 -1 24280 -1 24281 -1 24282 -1 24283 -1 24284 -1 24285 -1 24286 -1 24287 -1 24288 -1 24289 -1 24290 -1 24291 -1 24292 -1 24293 -1 24294 -1 24295 -1 24296 -1 24297 -1 24298 -1 24299 -1 24300 -1 24301 -1 24302 -1 24303 -1 24304 -1 24305 -1 24306 -1 24307 -1 24308 -1 24309 -1 24310 -1 24311 -1 24312 -1 24313 -1 24314 -1 24315 -1 24316 -1 24317 -1 24318 -1 24319 -1 24320 -1 24321 -1 24322 -1 24323 -1 24324 -1 24325 -1 24326 -1 24327 -1 24328 -1 24329 -1 24330 -1 24331 -1 24332 -1 24333 -1 24334 -1 24335 -1 24336 -1 24337 -1 24338 -1 24339 -1 24340 -1 24341 -1 24342 -1 24343 -1 24344 -1 24345 -1 24346 -1 24347 -1 24348 -1 24349 -1 24350 -1 24351 -1 24352 -1 24353 -1 24354 -1 24355 -1 24356 -1 24357 -1 24358 -1 24359 -1 24360 -1 24361 -1 24362 -1 24363 -1 24364 -1 24365 -1 24366 -1 24367 -1 24368 -1 24369 -1 24370 -1 24371 -1 24372 -1 24373 -1 24374 -1 24375 -1 24376 -1 24377 -1 24378 -1 24379 -1 24380 -1 24381 -1 24382 -1 24383 -1 24384 -1 24385 -1 24386 -1 24387 -1 24388 -1 24389 -1 24390 -1 24391 -1 24392 -1 24393 -1 24394 -1 24395 -1 24396 -1 24397 -1 24398 -1 24399 -1 24400 -1 24401 -1 24402 -1 24403 -1 24404 -1 24405 -1 24406 -1 24407 -1 24408 -1 24409 -1 24410 -1 24411 -1 24412 -1 24413 -1 24414 -1 24415 -1 24416 -1 24417 -1 24418 -1 24419 -1 24420 -1 24421 -1 24422 -1 24423 -1 24424 -1 24425 -1 24426 -1 24427 -1 24428 -1 24429 -1 24430 -1 24431 -1 24432 -1 24433 -1 24434 -1 24435 -1 24436 -1 24437 -1 24438 -1 24439 -1 24440 -1 24441 -1 24442 -1 24443 -1 24444 -1 24445 -1 24446 -1 24447 -1 24448 -1 24449 -1 24450 -1 24451 -1 24452 -1 24453 -1 24454 -1 24455 -1 24456 -1 24457 -1 24458 -1 24459 -1 24460 -1 24461 -1 24462 -1 24463 -1 24464 -1 24465 -1 24466 -1 24467 -1 24468 -1 24469 -1 24470 -1 24471 -1 24472 -1 24473 -1 24474 -1 24475 -1 24476 -1 24477 -1 24478 -1 24479 -1 24480 -1 24481 -1 24482 -1 24483 -1 24484 -1 24485 -1 24486 -1 24487 -1 24488 -1 24489 -1 24490 -1 24491 -1 24492 -1 24493 -1 24494 -1 24495 -1 24496 -1 24497 -1 24498 -1 24499 -1 24500 -1 24501 -1 24502 -1 24503 -1 24504 -1 24505 -1 24506 -1 24507 -1 24508 -1 24509 -1 24510 -1 24511 -1 24512 -1 24513 -1 24514 -1 24515 -1 24516 -1 24517 -1 24518 -1 24519 -1 24520 -1 24521 -1 24522 -1 24523 -1 24524 -1 24525 -1 24526 -1 24527 -1 24528 -1 24529 -1 24530 -1 24531 -1 24532 -1 24533 -1 24534 -1 24535 -1 24536 -1 24537 -1 24538 -1 24539 -1 24540 -1 24541 -1 24542 -1 24543 -1 24544 -1 24545 -1 24546 -1 24547 -1 24548 -1 24549 -1 24550 -1 24551 -1 24552 -1 24553 -1 24554 -1 24555 -1 24556 -1 24557 -1 24558 -1 24559 -1 24560 -1 24561 -1 24562 -1 24563 -1 24564 -1 24565 -1 24566 -1 24567 -1 24568 -1 24569 -1 24570 -1 24571 -1 24572 -1 24573 -1 24574 -1 24575 -1 24576 -1 24577 -1 24578 -1 24579 -1 24580 -1 24581 -1 24582 -1 24583 -1 24584 -1 24585 -1 24586 -1 24587 -1 24588 -1 24589 -1 24590 -1 24591 -1 24592 -1 24593 -1 24594 -1 24595 -1 24596 -1 24597 -1 24598 -1 24599 -1 24600 -1 24601 -1 24602 -1 24603 -1 24604 -1 24605 -1 24606 -1 24607 -1 24608 -1 24609 -1 24610 -1 24611 -1 24612 -1 24613 -1 24614 -1 24615 -1 24616 -1 24617 -1 24618 -1 24619 -1 24620 -1 24621 -1 24622 -1 24623 -1 24624 -1 24625 -1 24626 -1 24627 -1 24628 -1 24629 -1 24630 -1 24631 -1 24632 -1 24633 -1 24634 -1 24635 -1 24636 -1 24637 -1 24638 -1 24639 -1 24640 -1 24641 -1 24642 -1 24643 -1 24644 -1 24645 -1 24646 -1 24647 -1 24648 -1 24649 -1 24650 -1 24651 -1 24652 -1 24653 -1 24654 -1 24655 -1 24656 -1 24657 -1 24658 -1 24659 -1 24660 -1 24661 -1 24662 -1 24663 -1 24664 -1 24665 -1 24666 -1 24667 -1 24668 -1 24669 -1 24670 -1 24671 -1 24672 -1 24673 -1 24674 -1 24675 -1 24676 -1 24677 -1 24678 -1 24679 -1 24680 -1 24681 -1 24682 -1 24683 -1 24684 -1 24685 -1 24686 -1 24687 -1 24688 -1 24689 -1 24690 -1 24691 -1 24692 -1 24693 -1 24694 -1 24695 -1 24696 -1 24697 -1 24698 -1 24699 -1 24700 -1 24701 -1 24702 -1 24703 -1 24704 -1 24705 -1 24706 -1 24707 -1 24708 -1 24709 -1 24710 -1 24711 -1 24712 -1 24713 -1 24714 -1 24715 -1 24716 -1 24717 -1 24718 -1 24719 -1 24720 -1 24721 -1 24722 -1 24723 -1 24724 -1 24725 -1 24726 -1 24727 -1 24728 -1 24729 -1 24730 -1 24731 -1 24732 -1 24733 -1 24734 -1 24735 -1 24736 -1 24737 -1 24738 -1 24739 -1 24740 -1 24741 -1 24742 -1 24743 -1 24744 -1 24745 -1 24746 -1 24747 -1 24748 -1 24749 -1 24750 -1 24751 -1 24752 -1 24753 -1 24754 -1 24755 -1 24756 -1 24757 -1 24758 -1 24759 -1 24760 -1 24761 -1 24762 -1 24763 -1 24764 -1 24765 -1 24766 -1 24767 -1 24768 -1 24769 -1 24770 -1 24771 -1 24772 -1 24773 -1 24774 -1 24775 -1 24776 -1 24777 -1 24778 -1 24779 -1 24780 -1 24781 -1 24782 -1 24783 -1 24784 -1 24785 -1 24786 -1 24787 -1 24788 -1 24789 -1 24790 -1 24791 -1 24792 -1 24793 -1 24794 -1 24795 -1 24796 -1 24797 -1 24798 -1 24799 -1 24800 -1 24801 -1 24802 -1 24803 -1 24804 -1 24805 -1 24806 -1 24807 -1 24808 -1 24809 -1 24810 -1 24811 -1 24812 -1 24813 -1 24814 -1 24815 -1 24816 -1 24817 -1 24818 -1 24819 -1 24820 -1 24821 -1 24822 -1 24823 -1 24824 -1 24825 -1 24826 -1 24827 -1 24828 -1 24829 -1 24830 -1 24831 -1 24832 -1 24833 -1 24834 -1 24835 -1 24836 -1 24837 -1 24838 -1 24839 -1 24840 -1 24841 -1 24842 -1 24843 -1 24844 -1 24845 -1 24846 -1 24847 -1 24848 -1 24849 -1 24850 -1 24851 -1 24852 -1 24853 -1 24854 -1 24855 -1 24856 -1 24857 -1 24858 -1 24859 -1 24860 -1 24861 -1 24862 -1 24863 -1 24864 -1 24865 -1 24866 -1 24867 -1 24868 -1 24869 -1 24870 -1 24871 -1 24872 -1 24873 -1 24874 -1 24875 -1 24876 -1 24877 -1 24878 -1 24879 -1 24880 -1 24881 -1 24882 -1 24883 -1 24884 -1 24885 -1 24886 -1 24887 -1 24888 -1 24889 -1 24890 -1 24891 -1 24892 -1 24893 -1 24894 -1 24895 -1 24896 -1 24897 -1 24898 -1 24899 -1 24900 -1 24901 -1 24902 -1 24903 -1 24904 -1 24905 -1 24906 -1 24907 -1 24908 -1 24909 -1 24910 -1 24911 -1 24912 -1 24913 -1 24914 -1 24915 -1 24916 -1 24917 -1 24918 -1 24919 -1 24920 -1 24921 -1 24922 -1 24923 -1 24924 -1 24925 -1 24926 -1 24927 -1 24928 -1 24929 -1 24930 -1 24931 -1 24932 -1 24933 -1 24934 -1 24935 -1 24936 -1 24937 -1 24938 -1 24939 -1 24940 -1 24941 -1 24942 -1 24943 -1 24944 -1 24945 -1 24946 -1 24947 -1 24948 -1 24949 -1 24950 -1 24951 -1 24952 -1 24953 -1 24954 -1 24955 -1 24956 -1 24957 -1 24958 -1 24959 -1 24960 -1 24961 -1 24962 -1 24963 -1 24964 -1 24965 -1 24966 -1 24967 -1 24968 -1 24969 -1 24970 -1 24971 -1 24972 -1 24973 -1 24974 -1 24975 -1 24976 -1 24977 -1 24978 -1 24979 -1 24980 -1 24981 -1 24982 -1 24983 -1 24984 -1 24985 -1 24986 -1 24987 -1 24988 -1 24989 -1 24990 -1 24991 -1 24992 -1 24993 -1 24994 -1 24995 -1 24996 -1 24997 -1 24998 -1 24999 -1 25000 -1 25001 -1 25002 -1 25003 -1 25004 -1 25005 -1 25006 -1 25007 -1 25008 -1 25009 -1 25010 -1 25011 -1 25012 -1 25013 -1 25014 -1 25015 -1 25016 -1 25017 -1 25018 -1 25019 -1 25020 -1 25021 -1 25022 -1 25023 -1 25024 -1 25025 -1 25026 -1 25027 -1 25028 -1 25029 -1 25030 -1 25031 -1 25032 -1 25033 -1 25034 -1 25035 -1 25036 -1 25037 -1 25038 -1 25039 -1 25040 -1 25041 -1 25042 -1 25043 -1 25044 -1 25045 -1 25046 -1 25047 -1 25048 -1 25049 -1 25050 -1 25051 -1 25052 -1 25053 -1 25054 -1 25055 -1 25056 -1 25057 -1 25058 -1 25059 -1 25060 -1 25061 -1 25062 -1 25063 -1 25064 -1 25065 -1 25066 -1 25067 -1 25068 -1 25069 -1 25070 -1 25071 -1 25072 -1 25073 -1 25074 -1 25075 -1 25076 -1 25077 -1 25078 -1 25079 -1 25080 -1 25081 -1 25082 -1 25083 -1 25084 -1 25085 -1 25086 -1 25087 -1 25088 -1 25089 -1 25090 -1 25091 -1 25092 -1 25093 -1 25094 -1 25095 -1 25096 -1 25097 -1 25098 -1 25099 -1 25100 -1 25101 -1 25102 -1 25103 -1 25104 -1 25105 -1 25106 -1 25107 -1 25108 -1 25109 -1 25110 -1 25111 -1 25112 -1 25113 -1 25114 -1 25115 -1 25116 -1 25117 -1 25118 -1 25119 -1 25120 -1 25121 -1 25122 -1 25123 -1 25124 -1 25125 -1 25126 -1 25127 -1 25128 -1 25129 -1 25130 -1 25131 -1 25132 -1 25133 -1 25134 -1 25135 -1 25136 -1 25137 -1 25138 -1 25139 -1 25140 -1 25141 -1 25142 -1 25143 -1 25144 -1 25145 -1 25146 -1 25147 -1 25148 -1 25149 -1 25150 -1 25151 -1 25152 -1 25153 -1 25154 -1 25155 -1 25156 -1 25157 -1 25158 -1 25159 -1 25160 -1 25161 -1 25162 -1 25163 -1 25164 -1 25165 -1 25166 -1 25167 -1 25168 -1 25169 -1 25170 -1 25171 -1 25172 -1 25173 -1 25174 -1 25175 -1 25176 -1 25177 -1 25178 -1 25179 -1 25180 -1 25181 -1 25182 -1 25183 -1 25184 -1 25185 -1 25186 -1 25187 -1 25188 -1 25189 -1 25190 -1 25191 -1 25192 -1 25193 -1 25194 -1 25195 -1 25196 -1 25197 -1 25198 -1 25199 -1 25200 -1 25201 -1 25202 -1 25203 -1 25204 -1 25205 -1 25206 -1 25207 -1 25208 -1 25209 -1 25210 -1 25211 -1 25212 -1 25213 -1 25214 -1 25215 -1 25216 -1 25217 -1 25218 -1 25219 -1 25220 -1 25221 -1 25222 -1 25223 -1 25224 -1 25225 -1 25226 -1 25227 -1 25228 -1 25229 -1 25230 -1 25231 -1 25232 -1 25233 -1 25234 -1 25235 -1 25236 -1 25237 -1 25238 -1 25239 -1 25240 -1 25241 -1 25242 -1 25243 -1 25244 -1 25245 -1 25246 -1 25247 -1 25248 -1 25249 -1 25250 -1 25251 -1 25252 -1 25253 -1 25254 -1 25255 -1 25256 -1 25257 -1 25258 -1 25259 -1 25260 -1 25261 -1 25262 -1 25263 -1 25264 -1 25265 -1 25266 -1 25267 -1 25268 -1 25269 -1 25270 -1 25271 -1 25272 -1 25273 -1 25274 -1 25275 -1 25276 -1 25277 -1 25278 -1 25279 -1 25280 -1 25281 -1 25282 -1 25283 -1 25284 -1 25285 -1 25286 -1 25287 -1 25288 -1 25289 -1 25290 -1 25291 -1 25292 -1 25293 -1 25294 -1 25295 -1 25296 -1 25297 -1 25298 -1 25299 -1 25300 -1 25301 -1 25302 -1 25303 -1 25304 -1 25305 -1 25306 -1 25307 -1 25308 -1 25309 -1 25310 -1 25311 -1 25312 -1 25313 -1 25314 -1 25315 -1 25316 -1 25317 -1 25318 -1 25319 -1 25320 -1 25321 -1 25322 -1 25323 -1 25324 -1 25325 -1 25326 -1 25327 -1 25328 -1 25329 -1 25330 -1 25331 -1 25332 -1 25333 -1 25334 -1 25335 -1 25336 -1 25337 -1 25338 -1 25339 -1 25340 -1 25341 -1 25342 -1 25343 -1 25344 -1 25345 -1 25346 -1 25347 -1 25348 -1 25349 -1 25350 -1 25351 -1 25352 -1 25353 -1 25354 -1 25355 -1 25356 -1 25357 -1 25358 -1 25359 -1 25360 -1 25361 -1 25362 -1 25363 -1 25364 -1 25365 -1 25366 -1 25367 -1 25368 -1 25369 -1 25370 -1 25371 -1 25372 -1 25373 -1 25374 -1 25375 -1 25376 -1 25377 -1 25378 -1 25379 -1 25380 -1 25381 -1 25382 -1 25383 -1 25384 -1 25385 -1 25386 -1 25387 -1 25388 -1 25389 -1 25390 -1 25391 -1 25392 -1 25393 -1 25394 -1 25395 -1 25396 -1 25397 -1 25398 -1 25399 -1 25400 -1 25401 -1 25402 -1 25403 -1 25404 -1 25405 -1 25406 -1 25407 -1 25408 -1 25409 -1 25410 -1 25411 -1 25412 -1 25413 -1 25414 -1 25415 -1 25416 -1 25417 -1 25418 -1 25419 -1 25420 -1 25421 -1 25422 -1 25423 -1 25424 -1 25425 -1 25426 -1 25427 -1 25428 -1 25429 -1 25430 -1 25431 -1 25432 -1 25433 -1 25434 -1 25435 -1 25436 -1 25437 -1 25438 -1 25439 -1 25440 -1 25441 -1 25442 -1 25443 -1 25444 -1 25445 -1 25446 -1 25447 -1 25448 -1 25449 -1 25450 -1 25451 -1 25452 -1 25453 -1 25454 -1 25455 -1 25456 -1 25457 -1 25458 -1 25459 -1 25460 -1 25461 -1 25462 -1 25463 -1 25464 -1 25465 -1 25466 -1 25467 -1 25468 -1 25469 -1 25470 -1 25471 -1 25472 -1 25473 -1 25474 -1 25475 -1 25476 -1 25477 -1 25478 -1 25479 -1 25480 -1 25481 -1 25482 -1 25483 -1 25484 -1 25485 -1 25486 -1 25487 -1 25488 -1 25489 -1 25490 -1 25491 -1 25492 -1 25493 -1 25494 -1 25495 -1 25496 -1 25497 -1 25498 -1 25499 -1 25500 -1 25501 -1 25502 -1 25503 -1 25504 -1 25505 -1 25506 -1 25507 -1 25508 -1 25509 -1 25510 -1 25511 -1 25512 -1 25513 -1 25514 -1 25515 -1 25516 -1 25517 -1 25518 -1 25519 -1 25520 -1 25521 -1 25522 -1 25523 -1 25524 -1 25525 -1 25526 -1 25527 -1 25528 -1 25529 -1 25530 -1 25531 -1 25532 -1 25533 -1 25534 -1 25535 -1 25536 -1 25537 -1 25538 -1 25539 -1 25540 -1 25541 -1 25542 -1 25543 -1 25544 -1 25545 -1 25546 -1 25547 -1 25548 -1 25549 -1 25550 -1 25551 -1 25552 -1 25553 -1 25554 -1 25555 -1 25556 -1 25557 -1 25558 -1 25559 -1 25560 -1 25561 -1 25562 -1 25563 -1 25564 -1 25565 -1 25566 -1 25567 -1 25568 -1 25569 -1 25570 -1 25571 -1 25572 -1 25573 -1 25574 -1 25575 -1 25576 -1 25577 -1 25578 -1 25579 -1 25580 -1 25581 -1 25582 -1 25583 -1 25584 -1 25585 -1 25586 -1 25587 -1 25588 -1 25589 -1 25590 -1 25591 -1 25592 -1 25593 -1 25594 -1 25595 -1 25596 -1 25597 -1 25598 -1 25599 -1 25600 -1 25601 -1 25602 -1 25603 -1 25604 -1 25605 -1 25606 -1 25607 -1 25608 -1 25609 -1 25610 -1 25611 -1 25612 -1 25613 -1 25614 -1 25615 -1 25616 -1 25617 -1 25618 -1 25619 -1 25620 -1 25621 -1 25622 -1 25623 -1 25624 -1 25625 -1 25626 -1 25627 -1 25628 -1 25629 -1 25630 -1 25631 -1 25632 -1 25633 -1 25634 -1 25635 -1 25636 -1 25637 -1 25638 -1 25639 -1 25640 -1 25641 -1 25642 -1 25643 -1 25644 -1 25645 -1 25646 -1 25647 -1 25648 -1 25649 -1 25650 -1 25651 -1 25652 -1 25653 -1 25654 -1 25655 -1 25656 -1 25657 -1 25658 -1 25659 -1 25660 -1 25661 -1 25662 -1 25663 -1 25664 -1 25665 -1 25666 -1 25667 -1 25668 -1 25669 -1 25670 -1 25671 -1 25672 -1 25673 -1 25674 -1 25675 -1 25676 -1 25677 -1 25678 -1 25679 -1 25680 -1 25681 -1 25682 -1 25683 -1 25684 -1 25685 -1 25686 -1 25687 -1 25688 -1 25689 -1 25690 -1 25691 -1 25692 -1 25693 -1 25694 -1 25695 -1 25696 -1 25697 -1 25698 -1 25699 -1 25700 -1 25701 -1 25702 -1 25703 -1 25704 -1 25705 -1 25706 -1 25707 -1 25708 -1 25709 -1 25710 -1 25711 -1 25712 -1 25713 -1 25714 -1 25715 -1 25716 -1 25717 -1 25718 -1 25719 -1 25720 -1 25721 -1 25722 -1 25723 -1 25724 -1 25725 -1 25726 -1 25727 -1 25728 -1 25729 -1 25730 -1 25731 -1 25732 -1 25733 -1 25734 -1 25735 -1 25736 -1 25737 -1 25738 -1 25739 -1 25740 -1 25741 -1 25742 -1 25743 -1 25744 -1 25745 -1 25746 -1 25747 -1 25748 -1 25749 -1 25750 -1 25751 -1 25752 -1 25753 -1 25754 -1 25755 -1 25756 -1 25757 -1 25758 -1 25759 -1 25760 -1 25761 -1 25762 -1 25763 -1 25764 -1 25765 -1 25766 -1 25767 -1 25768 -1 25769 -1 25770 -1 25771 -1 25772 -1 25773 -1 25774 -1 25775 -1 25776 -1 25777 -1 25778 -1 25779 -1 25780 -1 25781 -1 25782 -1 25783 -1 25784 -1 25785 -1 25786 -1 25787 -1 25788 -1 25789 -1 25790 -1 25791 -1 25792 -1 25793 -1 25794 -1 25795 -1 25796 -1 25797 -1 25798 -1 25799 -1 25800 -1 25801 -1 25802 -1 25803 -1 25804 -1 25805 -1 25806 -1 25807 -1 25808 -1 25809 -1 25810 -1 25811 -1 25812 -1 25813 -1 25814 -1 25815 -1 25816 -1 25817 -1 25818 -1 25819 -1 25820 -1 25821 -1 25822 -1 25823 -1 25824 -1 25825 -1 25826 -1 25827 -1 25828 -1 25829 -1 25830 -1 25831 -1 25832 -1 25833 -1 25834 -1 25835 -1 25836 -1 25837 -1 25838 -1 25839 -1 25840 -1 25841 -1 25842 -1 25843 -1 25844 -1 25845 -1 25846 -1 25847 -1 25848 -1 25849 -1 25850 -1 25851 -1 25852 -1 25853 -1 25854 -1 25855 -1 25856 -1 25857 -1 25858 -1 25859 -1 25860 -1 25861 -1 25862 -1 25863 -1 25864 -1 25865 -1 25866 -1 25867 -1 25868 -1 25869 -1 25870 -1 25871 -1 25872 -1 25873 -1 25874 -1 25875 -1 25876 -1 25877 -1 25878 -1 25879 -1 25880 -1 25881 -1 25882 -1 25883 -1 25884 -1 25885 -1 25886 -1 25887 -1 25888 -1 25889 -1 25890 -1 25891 -1 25892 -1 25893 -1 25894 -1 25895 -1 25896 -1 25897 -1 25898 -1 25899 -1 25900 -1 25901 -1 25902 -1 25903 -1 25904 -1 25905 -1 25906 -1 25907 -1 25908 -1 25909 -1 25910 -1 25911 -1 25912 -1 25913 -1 25914 -1 25915 -1 25916 -1 25917 -1 25918 -1 25919 -1 25920 -1 25921 -1 25922 -1 25923 -1 25924 -1 25925 -1 25926 -1 25927 -1 25928 -1 25929 -1 25930 -1 25931 -1 25932 -1 25933 -1 25934 -1 25935 -1 25936 -1 25937 -1 25938 -1 25939 -1 25940 -1 25941 -1 25942 -1 25943 -1 25944 -1 25945 -1 25946 -1 25947 -1 25948 -1 25949 -1 25950 -1 25951 -1 25952 -1 25953 -1 25954 -1 25955 -1 25956 -1 25957 -1 25958 -1 25959 -1 25960 -1 25961 -1 25962 -1 25963 -1 25964 -1 25965 -1 25966 -1 25967 -1 25968 -1 25969 -1 25970 -1 25971 -1 25972 -1 25973 -1 25974 -1 25975 -1 25976 -1 25977 -1 25978 -1 25979 -1 25980 -1 25981 -1 25982 -1 25983 -1 25984 -1 25985 -1 25986 -1 25987 -1 25988 -1 25989 -1 25990 -1 25991 -1 25992 -1 25993 -1 25994 -1 25995 -1 25996 -1 25997 -1 25998 -1 25999 -1 26000 -1 26001 -1 26002 -1 26003 -1 26004 -1 26005 -1 26006 -1 26007 -1 26008 -1 26009 -1 26010 -1 26011 -1 26012 -1 26013 -1 26014 -1 26015 -1 26016 -1 26017 -1 26018 -1 26019 -1 26020 -1 26021 -1 26022 -1 26023 -1 26024 -1 26025 -1 26026 -1 26027 -1 26028 -1 26029 -1 26030 -1 26031 -1 26032 -1 26033 -1 26034 -1 26035 -1 26036 -1 26037 -1 26038 -1 26039 -1 26040 -1 26041 -1 26042 -1 26043 -1 26044 -1 26045 -1 26046 -1 26047 -1 26048 -1 26049 -1 26050 -1 26051 -1 26052 -1 26053 -1 26054 -1 26055 -1 26056 -1 26057 -1 26058 -1 26059 -1 26060 -1 26061 -1 26062 -1 26063 -1 26064 -1 26065 -1 26066 -1 26067 -1 26068 -1 26069 -1 26070 -1 26071 -1 26072 -1 26073 -1 26074 -1 26075 -1 26076 -1 26077 -1 26078 -1 26079 -1 26080 -1 26081 -1 26082 -1 26083 -1 26084 -1 26085 -1 26086 -1 26087 -1 26088 -1 26089 -1 26090 -1 26091 -1 26092 -1 26093 -1 26094 -1 26095 -1 26096 -1 26097 -1 26098 -1 26099 -1 26100 -1 26101 -1 26102 -1 26103 -1 26104 -1 26105 -1 26106 -1 26107 -1 26108 -1 26109 -1 26110 -1 26111 -1 26112 -1 26113 -1 26114 -1 26115 -1 26116 -1 26117 -1 26118 -1 26119 -1 26120 -1 26121 -1 26122 -1 26123 -1 26124 -1 26125 -1 26126 -1 26127 -1 26128 -1 26129 -1 26130 -1 26131 -1 26132 -1 26133 -1 26134 -1 26135 -1 26136 -1 26137 -1 26138 -1 26139 -1 26140 -1 26141 -1 26142 -1 26143 -1 26144 -1 26145 -1 26146 -1 26147 -1 26148 -1 26149 -1 26150 -1 26151 -1 26152 -1 26153 -1 26154 -1 26155 -1 26156 -1 26157 -1 26158 -1 26159 -1 26160 -1 26161 -1 26162 -1 26163 -1 26164 -1 26165 -1 26166 -1 26167 -1 26168 -1 26169 -1 26170 -1 26171 -1 26172 -1 26173 -1 26174 -1 26175 -1 26176 -1 26177 -1 26178 -1 26179 -1 26180 -1 26181 -1 26182 -1 26183 -1 26184 -1 26185 -1 26186 -1 26187 -1 26188 -1 26189 -1 26190 -1 26191 -1 26192 -1 26193 -1 26194 -1 26195 -1 26196 -1 26197 -1 26198 -1 26199 -1 26200 -1 26201 -1 26202 -1 26203 -1 26204 -1 26205 -1 26206 -1 26207 -1 26208 -1 26209 -1 26210 -1 26211 -1 26212 -1 26213 -1 26214 -1 26215 -1 26216 -1 26217 -1 26218 -1 26219 -1 26220 -1 26221 -1 26222 -1 26223 -1 26224 -1 26225 -1 26226 -1 26227 -1 26228 -1 26229 -1 26230 -1 26231 -1 26232 -1 26233 -1 26234 -1 26235 -1 26236 -1 26237 -1 26238 -1 26239 -1 26240 -1 26241 -1 26242 -1 26243 -1 26244 -1 26245 -1 26246 -1 26247 -1 26248 -1 26249 -1 26250 -1 26251 -1 26252 -1 26253 -1 26254 -1 26255 -1 26256 -1 26257 -1 26258 -1 26259 -1 26260 -1 26261 -1 26262 -1 26263 -1 26264 -1 26265 -1 26266 -1 26267 -1 26268 -1 26269 -1 26270 -1 26271 -1 26272 -1 26273 -1 26274 -1 26275 -1 26276 -1 26277 -1 26278 -1 26279 -1 26280 -1 26281 -1 26282 -1 26283 -1 26284 -1 26285 -1 26286 -1 26287 -1 26288 -1 26289 -1 26290 -1 26291 -1 26292 -1 26293 -1 26294 -1 26295 -1 26296 -1 26297 -1 26298 -1 26299 -1 26300 -1 26301 -1 26302 -1 26303 -1 26304 -1 26305 -1 26306 -1 26307 -1 26308 -1 26309 -1 26310 -1 26311 -1 26312 -1 26313 -1 26314 -1 26315 -1 26316 -1 26317 -1 26318 -1 26319 -1 26320 -1 26321 -1 26322 -1 26323 -1 26324 -1 26325 -1 26326 -1 26327 -1 26328 -1 26329 -1 26330 -1 26331 -1 26332 -1 26333 -1 26334 -1 26335 -1 26336 -1 26337 -1 26338 -1 26339 -1 26340 -1 26341 -1 26342 -1 26343 -1 26344 -1 26345 -1 26346 -1 26347 -1 26348 -1 26349 -1 26350 -1 26351 -1 26352 -1 26353 -1 26354 -1 26355 -1 26356 -1 26357 -1 26358 -1 26359 -1 26360 -1 26361 -1 26362 -1 26363 -1 26364 -1 26365 -1 26366 -1 26367 -1 26368 -1 26369 -1 26370 -1 26371 -1 26372 -1 26373 -1 26374 -1 26375 -1 26376 -1 26377 -1 26378 -1 26379 -1 26380 -1 26381 -1 26382 -1 26383 -1 26384 -1 26385 -1 26386 -1 26387 -1 26388 -1 26389 -1 26390 -1 26391 -1 26392 -1 26393 -1 26394 -1 26395 -1 26396 -1 26397 -1 26398 -1 26399 -1 26400 -1 26401 -1 26402 -1 26403 -1 26404 -1 26405 -1 26406 -1 26407 -1 26408 -1 26409 -1 26410 -1 26411 -1 26412 -1 26413 -1 26414 -1 26415 -1 26416 -1 26417 -1 26418 -1 26419 -1 26420 -1 26421 -1 26422 -1 26423 -1 26424 -1 26425 -1 26426 -1 26427 -1 26428 -1 26429 -1 26430 -1 26431 -1 26432 -1 26433 -1 26434 -1 26435 -1 26436 -1 26437 -1 26438 -1 26439 -1 26440 -1 26441 -1 26442 -1 26443 -1 26444 -1 26445 -1 26446 -1 26447 -1 26448 -1 26449 -1 26450 -1 26451 -1 26452 -1 26453 -1 26454 -1 26455 -1 26456 -1 26457 -1 26458 -1 26459 -1 26460 -1 26461 -1 26462 -1 26463 -1 26464 -1 26465 -1 26466 -1 26467 -1 26468 -1 26469 -1 26470 -1 26471 -1 26472 -1 26473 -1 26474 -1 26475 -1 26476 -1 26477 -1 26478 -1 26479 -1 26480 -1 26481 -1 26482 -1 26483 -1 26484 -1 26485 -1 26486 -1 26487 -1 26488 -1 26489 -1 26490 -1 26491 -1 26492 -1 26493 -1 26494 -1 26495 -1 26496 -1 26497 -1 26498 -1 26499 -1 26500 -1 26501 -1 26502 -1 26503 -1 26504 -1 26505 -1 26506 -1 26507 -1 26508 -1 26509 -1 26510 -1 26511 -1 26512 -1 26513 -1 26514 -1 26515 -1 26516 -1 26517 -1 26518 -1 26519 -1 26520 -1 26521 -1 26522 -1 26523 -1 26524 -1 26525 -1 26526 -1 26527 -1 26528 -1 26529 -1 26530 -1 26531 -1 26532 -1 26533 -1 26534 -1 26535 -1 26536 -1 26537 -1 26538 -1 26539 -1 26540 -1 26541 -1 26542 -1 26543 -1 26544 -1 26545 -1 26546 -1 26547 -1 26548 -1 26549 -1 26550 -1 26551 -1 26552 -1 26553 -1 26554 -1 26555 -1 26556 -1 26557 -1 26558 -1 26559 -1 26560 -1 26561 -1 26562 -1 26563 -1 26564 -1 26565 -1 26566 -1 26567 -1 26568 -1 26569 -1 26570 -1 26571 -1 26572 -1 26573 -1 26574 -1 26575 -1 26576 -1 26577 -1 26578 -1 26579 -1 26580 -1 26581 -1 26582 -1 26583 -1 26584 -1 26585 -1 26586 -1 26587 -1 26588 -1 26589 -1 26590 -1 26591 -1 26592 -1 26593 -1 26594 -1 26595 -1 26596 -1 26597 -1 26598 -1 26599 -1 26600 -1 26601 -1 26602 -1 26603 -1 26604 -1 26605 -1 26606 -1 26607 -1 26608 -1 26609 -1 26610 -1 26611 -1 26612 -1 26613 -1 26614 -1 26615 -1 26616 -1 26617 -1 26618 -1 26619 -1 26620 -1 26621 -1 26622 -1 26623 -1 26624 -1 26625 -1 26626 -1 26627 -1 26628 -1 26629 -1 26630 -1 26631 -1 26632 -1 26633 -1 26634 -1 26635 -1 26636 -1 26637 -1 26638 -1 26639 -1 26640 -1 26641 -1 26642 -1 26643 -1 26644 -1 26645 -1 26646 -1 26647 -1 26648 -1 26649 -1 26650 -1 26651 -1 26652 -1 26653 -1 26654 -1 26655 -1 26656 -1 26657 -1 26658 -1 26659 -1 26660 -1 26661 -1 26662 -1 26663 -1 26664 -1 26665 -1 26666 -1 26667 -1 26668 -1 26669 -1 26670 -1 26671 -1 26672 -1 26673 -1 26674 -1 26675 -1 26676 -1 26677 -1 26678 -1 26679 -1 26680 -1 26681 -1 26682 -1 26683 -1 26684 -1 26685 -1 26686 -1 26687 -1 26688 -1 26689 -1 26690 -1 26691 -1 26692 -1 26693 -1 26694 -1 26695 -1 26696 -1 26697 -1 26698 -1 26699 -1 26700 -1 26701 -1 26702 -1 26703 -1 26704 -1 26705 -1 26706 -1 26707 -1 26708 -1 26709 -1 26710 -1 26711 -1 26712 -1 26713 -1 26714 -1 26715 -1 26716 -1 26717 -1 26718 -1 26719 -1 26720 -1 26721 -1 26722 -1 26723 -1 26724 -1 26725 -1 26726 -1 26727 -1 26728 -1 26729 -1 26730 -1 26731 -1 26732 -1 26733 -1 26734 -1 26735 -1 26736 -1 26737 -1 26738 -1 26739 -1 26740 -1 26741 -1 26742 -1 26743 -1 26744 -1 26745 -1 26746 -1 26747 -1 26748 -1 26749 -1 26750 -1 26751 -1 26752 -1 26753 -1 26754 -1 26755 -1 26756 -1 26757 -1 26758 -1 26759 -1 26760 -1 26761 -1 26762 -1 26763 -1 26764 -1 26765 -1 26766 -1 26767 -1 26768 -1 26769 -1 26770 -1 26771 -1 26772 -1 26773 -1 26774 -1 26775 -1 26776 -1 26777 -1 26778 -1 26779 -1 26780 -1 26781 -1 26782 -1 26783 -1 26784 -1 26785 -1 26786 -1 26787 -1 26788 -1 26789 -1 26790 -1 26791 -1 26792 -1 26793 -1 26794 -1 26795 -1 26796 -1 26797 -1 26798 -1 26799 -1 26800 -1 26801 -1 26802 -1 26803 -1 26804 -1 26805 -1 26806 -1 26807 -1 26808 -1 26809 -1 26810 -1 26811 -1 26812 -1 26813 -1 26814 -1 26815 -1 26816 -1 26817 -1 26818 -1 26819 -1 26820 -1 26821 -1 26822 -1 26823 -1 26824 -1 26825 -1 26826 -1 26827 -1 26828 -1 26829 -1 26830 -1 26831 -1 26832 -1 26833 -1 26834 -1 26835 -1 26836 -1 26837 -1 26838 -1 26839 -1 26840 -1 26841 -1 26842 -1 26843 -1 26844 -1 26845 -1 26846 -1 26847 -1 26848 -1 26849 -1 26850 -1 26851 -1 26852 -1 26853 -1 26854 -1 26855 -1 26856 -1 26857 -1 26858 -1 26859 -1 26860 -1 26861 -1 26862 -1 26863 -1 26864 -1 26865 -1 26866 -1 26867 -1 26868 -1 26869 -1 26870 -1 26871 -1 26872 -1 26873 -1 26874 -1 26875 -1 26876 -1 26877 -1 26878 -1 26879 -1 26880 -1 26881 -1 26882 -1 26883 -1 26884 -1 26885 -1 26886 -1 26887 -1 26888 -1 26889 -1 26890 -1 26891 -1 26892 -1 26893 -1 26894 -1 26895 -1 26896 -1 26897 -1 26898 -1 26899 -1 26900 -1 26901 -1 26902 -1 26903 -1 26904 -1 26905 -1 26906 -1 26907 -1 26908 -1 26909 -1 26910 -1 26911 -1 26912 -1 26913 -1 26914 -1 26915 -1 26916 -1 26917 -1 26918 -1 26919 -1 26920 -1 26921 -1 26922 -1 26923 -1 26924 -1 26925 -1 26926 -1 26927 -1 26928 -1 26929 -1 26930 -1 26931 -1 26932 -1 26933 -1 26934 -1 26935 -1 26936 -1 26937 -1 26938 -1 26939 -1 26940 -1 26941 -1 26942 -1 26943 -1 26944 -1 26945 -1 26946 -1 26947 -1 26948 -1 26949 -1 26950 -1 26951 -1 26952 -1 26953 -1 26954 -1 26955 -1 26956 -1 26957 -1 26958 -1 26959 -1 26960 -1 26961 -1 26962 -1 26963 -1 26964 -1 26965 -1 26966 -1 26967 -1 26968 -1 26969 -1 26970 -1 26971 -1 26972 -1 26973 -1 26974 -1 26975 -1 26976 -1 26977 -1 26978 -1 26979 -1 26980 -1 26981 -1 26982 -1 26983 -1 26984 -1 26985 -1 26986 -1 26987 -1 26988 -1 26989 -1 26990 -1 26991 -1 26992 -1 26993 -1 26994 -1 26995 -1 26996 -1 26997 -1 26998 -1 26999 -1 27000 -1 27001 -1 27002 -1 27003 -1 27004 -1 27005 -1 27006 -1 27007 -1 27008 -1 27009 -1 27010 -1 27011 -1 27012 -1 27013 -1 27014 -1 27015 -1 27016 -1 27017 -1 27018 -1 27019 -1 27020 -1 27021 -1 27022 -1 27023 -1 27024 -1 27025 -1 27026 -1 27027 -1 27028 -1 27029 -1 27030 -1 27031 -1 27032 -1 27033 -1 27034 -1 27035 -1 27036 -1 27037 -1 27038 -1 27039 -1 27040 -1 27041 -1 27042 -1 27043 -1 27044 -1 27045 -1 27046 -1 27047 -1 27048 -1 27049 -1 27050 -1 27051 -1 27052 -1 27053 -1 27054 -1 27055 -1 27056 -1 27057 -1 27058 -1 27059 -1 27060 -1 27061 -1 27062 -1 27063 -1 27064 -1 27065 -1 27066 -1 27067 -1 27068 -1 27069 -1 27070 -1 27071 -1 27072 -1 27073 -1 27074 -1 27075 -1 27076 -1 27077 -1 27078 -1 27079 -1 27080 -1 27081 -1 27082 -1 27083 -1 27084 -1 27085 -1 27086 -1 27087 -1 27088 -1 27089 -1 27090 -1 27091 -1 27092 -1 27093 -1 27094 -1 27095 -1 27096 -1 27097 -1 27098 -1 27099 -1 27100 -1 27101 -1 27102 -1 27103 -1 27104 -1 27105 -1 27106 -1 27107 -1 27108 -1 27109 -1 27110 -1 27111 -1 27112 -1 27113 -1 27114 -1 27115 -1 27116 -1 27117 -1 27118 -1 27119 -1 27120 -1 27121 -1 27122 -1 27123 -1 27124 -1 27125 -1 27126 -1 27127 -1 27128 -1 27129 -1 27130 -1 27131 -1 27132 -1 27133 -1 27134 -1 27135 -1 27136 -1 27137 -1 27138 -1 27139 -1 27140 -1 27141 -1 27142 -1 27143 -1 27144 -1 27145 -1 27146 -1 27147 -1 27148 -1 27149 -1 27150 -1 27151 -1 27152 -1 27153 -1 27154 -1 27155 -1 27156 -1 27157 -1 27158 -1 27159 -1 27160 -1 27161 -1 27162 -1 27163 -1 27164 -1 27165 -1 27166 -1 27167 -1 27168 -1 27169 -1 27170 -1 27171 -1 27172 -1 27173 -1 27174 -1 27175 -1 27176 -1 27177 -1 27178 -1 27179 -1 27180 -1 27181 -1 27182 -1 27183 -1 27184 -1 27185 -1 27186 -1 27187 -1 27188 -1 27189 -1 27190 -1 27191 -1 27192 -1 27193 -1 27194 -1 27195 -1 27196 -1 27197 -1 27198 -1 27199 -1 27200 -1 27201 -1 27202 -1 27203 -1 27204 -1 27205 -1 27206 -1 27207 -1 27208 -1 27209 -1 27210 -1 27211 -1 27212 -1 27213 -1 27214 -1 27215 -1 27216 -1 27217 -1 27218 -1 27219 -1 27220 -1 27221 -1 27222 -1 27223 -1 27224 -1 27225 -1 27226 -1 27227 -1 27228 -1 27229 -1 27230 -1 27231 -1 27232 -1 27233 -1 27234 -1 27235 -1 27236 -1 27237 -1 27238 -1 27239 -1 27240 -1 27241 -1 27242 -1 27243 -1 27244 -1 27245 -1 27246 -1 27247 -1 27248 -1 27249 -1 27250 -1 27251 -1 27252 -1 27253 -1 27254 -1 27255 -1 27256 -1 27257 -1 27258 -1 27259 -1 27260 -1 27261 -1 27262 -1 27263 -1 27264 -1 27265 -1 27266 -1 27267 -1 27268 -1 27269 -1 27270 -1 27271 -1 27272 -1 27273 -1 27274 -1 27275 -1 27276 -1 27277 -1 27278 -1 27279 -1 27280 -1 27281 -1 27282 -1 27283 -1 27284 -1 27285 -1 27286 -1 27287 -1 27288 -1 27289 -1 27290 -1 27291 -1 27292 -1 27293 -1 27294 -1 27295 -1 27296 -1 27297 -1 27298 -1 27299 -1 27300 -1 27301 -1 27302 -1 27303 -1 27304 -1 27305 -1 27306 -1 27307 -1 27308 -1 27309 -1 27310 -1 27311 -1 27312 -1 27313 -1 27314 -1 27315 -1 27316 -1 27317 -1 27318 -1 27319 -1 27320 -1 27321 -1 27322 -1 27323 -1 27324 -1 27325 -1 27326 -1 27327 -1 27328 -1 27329 -1 27330 -1 27331 -1 27332 -1 27333 -1 27334 -1 27335 -1 27336 -1 27337 -1 27338 -1 27339 -1 27340 -1 27341 -1 27342 -1 27343 -1 27344 -1 27345 -1 27346 -1 27347 -1 27348 -1 27349 -1 27350 -1 27351 -1 27352 -1 27353 -1 27354 -1 27355 -1 27356 -1 27357 -1 27358 -1 27359 -1 27360 -1 27361 -1 27362 -1 27363 -1 27364 -1 27365 -1 27366 -1 27367 -1 27368 -1 27369 -1 27370 -1 27371 -1 27372 -1 27373 -1 27374 -1 27375 -1 27376 -1 27377 -1 27378 -1 27379 -1 27380 -1 27381 -1 27382 -1 27383 -1 27384 -1 27385 -1 27386 -1 27387 -1 27388 -1 27389 -1 27390 -1 27391 -1 27392 -1 27393 -1 27394 -1 27395 -1 27396 -1 27397 -1 27398 -1 27399 -1 27400 -1 27401 -1 27402 -1 27403 -1 27404 -1 27405 -1 27406 -1 27407 -1 27408 -1 27409 -1 27410 -1 27411 -1 27412 -1 27413 -1 27414 -1 27415 -1 27416 -1 27417 -1 27418 -1 27419 -1 27420 -1 27421 -1 27422 -1 27423 -1 27424 -1 27425 -1 27426 -1 27427 -1 27428 -1 27429 -1 27430 -1 27431 -1 27432 -1 27433 -1 27434 -1 27435 -1 27436 -1 27437 -1 27438 -1 27439 -1 27440 -1 27441 -1 27442 -1 27443 -1 27444 -1 27445 -1 27446 -1 27447 -1 27448 -1 27449 -1 27450 -1 27451 -1 27452 -1 27453 -1 27454 -1 27455 -1 27456 -1 27457 -1 27458 -1 27459 -1 27460 -1 27461 -1 27462 -1 27463 -1 27464 -1 27465 -1 27466 -1 27467 -1 27468 -1 27469 -1 27470 -1 27471 -1 27472 -1 27473 -1 27474 -1 27475 -1 27476 -1 27477 -1 27478 -1 27479 -1 27480 -1 27481 -1 27482 -1 27483 -1 27484 -1 27485 -1 27486 -1 27487 -1 27488 -1 27489 -1 27490 -1 27491 -1 27492 -1 27493 -1 27494 -1 27495 -1 27496 -1 27497 -1 27498 -1 27499 -1 27500 -1 27501 -1 27502 -1 27503 -1 27504 -1 27505 -1 27506 -1 27507 -1 27508 -1 27509 -1 27510 -1 27511 -1 27512 -1 27513 -1 27514 -1 27515 -1 27516 -1 27517 -1 27518 -1 27519 -1 27520 -1 27521 -1 27522 -1 27523 -1 27524 -1 27525 -1 27526 -1 27527 -1 27528 -1 27529 -1 27530 -1 27531 -1 27532 -1 27533 -1 27534 -1 27535 -1 27536 -1 27537 -1 27538 -1 27539 -1 27540 -1 27541 -1 27542 -1 27543 -1 27544 -1 27545 -1 27546 -1 27547 -1 27548 -1 27549 -1 27550 -1 27551 -1 27552 -1 27553 -1 27554 -1 27555 -1 27556 -1 27557 -1 27558 -1 27559 -1 27560 -1 27561 -1 27562 -1 27563 -1 27564 -1 27565 -1 27566 -1 27567 -1 27568 -1 27569 -1 27570 -1 27571 -1 27572 -1 27573 -1 27574 -1 27575 -1 27576 -1 27577 -1 27578 -1 27579 -1 27580 -1 27581 -1 27582 -1 27583 -1 27584 -1 27585 -1 27586 -1 27587 -1 27588 -1 27589 -1 27590 -1 27591 -1 27592 -1 27593 -1 27594 -1 27595 -1 27596 -1 27597 -1 27598 -1 27599 -1 27600 -1 27601 -1 27602 -1 27603 -1 27604 -1 27605 -1 27606 -1 27607 -1 27608 -1 27609 -1 27610 -1 27611 -1 27612 -1 27613 -1 27614 -1 27615 -1 27616 -1 27617 -1 27618 -1 27619 -1 27620 -1 27621 -1 27622 -1 27623 -1 27624 -1 27625 -1 27626 -1 27627 -1 27628 -1 27629 -1 27630 -1 27631 -1 27632 -1 27633 -1 27634 -1 27635 -1 27636 -1 27637 -1 27638 -1 27639 -1 27640 -1 27641 -1 27642 -1 27643 -1 27644 -1 27645 -1 27646 -1 27647 -1 27648 -1 27649 -1 27650 -1 27651 -1 27652 -1 27653 -1 27654 -1 27655 -1 27656 -1 27657 -1 27658 -1 27659 -1 27660 -1 27661 -1 27662 -1 27663 -1 27664 -1 27665 -1 27666 -1 27667 -1 27668 -1 27669 -1 27670 -1 27671 -1 27672 -1 27673 -1 27674 -1 27675 -1 27676 -1 27677 -1 27678 -1 27679 -1 27680 -1 27681 -1 27682 -1 27683 -1 27684 -1 27685 -1 27686 -1 27687 -1 27688 -1 27689 -1 27690 -1 27691 -1 27692 -1 27693 -1 27694 -1 27695 -1 27696 -1 27697 -1 27698 -1 27699 -1 27700 -1 27701 -1 27702 -1 27703 -1 27704 -1 27705 -1 27706 -1 27707 -1 27708 -1 27709 -1 27710 -1 27711 -1 27712 -1 27713 -1 27714 -1 27715 -1 27716 -1 27717 -1 27718 -1 27719 -1 27720 -1 27721 -1 27722 -1 27723 -1 27724 -1 27725 -1 27726 -1 27727 -1 27728 -1 27729 -1 27730 -1 27731 -1 27732 -1 27733 -1 27734 -1 27735 -1 27736 -1 27737 -1 27738 -1 27739 -1 27740 -1 27741 -1 27742 -1 27743 -1 27744 -1 27745 -1 27746 -1 27747 -1 27748 -1 27749 -1 27750 -1 27751 -1 27752 -1 27753 -1 27754 -1 27755 -1 27756 -1 27757 -1 27758 -1 27759 -1 27760 -1 27761 -1 27762 -1 27763 -1 27764 -1 27765 -1 27766 -1 27767 -1 27768 -1 27769 -1 27770 -1 27771 -1 27772 -1 27773 -1 27774 -1 27775 -1 27776 -1 27777 -1 27778 -1 27779 -1 27780 -1 27781 -1 27782 -1 27783 -1 27784 -1 27785 -1 27786 -1 27787 -1 27788 -1 27789 -1 27790 -1 27791 -1 27792 -1 27793 -1 27794 -1 27795 -1 27796 -1 27797 -1 27798 -1 27799 -1 27800 -1 27801 -1 27802 -1 27803 -1 27804 -1 27805 -1 27806 -1 27807 -1 27808 -1 27809 -1 27810 -1 27811 -1 27812 -1 27813 -1 27814 -1 27815 -1 27816 -1 27817 -1 27818 -1 27819 -1 27820 -1 27821 -1 27822 -1 27823 -1 27824 -1 27825 -1 27826 -1 27827 -1 27828 -1 27829 -1 27830 -1 27831 -1 27832 -1 27833 -1 27834 -1 27835 -1 27836 -1 27837 -1 27838 -1 27839 -1 27840 -1 27841 -1 27842 -1 27843 -1 27844 -1 27845 -1 27846 -1 27847 -1 27848 -1 27849 -1 27850 -1 27851 -1 27852 -1 27853 -1 27854 -1 27855 -1 27856 -1 27857 -1 27858 -1 27859 -1 27860 -1 27861 -1 27862 -1 27863 -1 27864 -1 27865 -1 27866 -1 27867 -1 27868 -1 27869 -1 27870 -1 27871 -1 27872 -1 27873 -1 27874 -1 27875 -1 27876 -1 27877 -1 27878 -1 27879 -1 27880 -1 27881 -1 27882 -1 27883 -1 27884 -1 27885 -1 27886 -1 27887 -1 27888 -1 27889 -1 27890 -1 27891 -1 27892 -1 27893 -1 27894 -1 27895 -1 27896 -1 27897 -1 27898 -1 27899 -1 27900 -1 27901 -1 27902 -1 27903 -1 27904 -1 27905 -1 27906 -1 27907 -1 27908 -1 27909 -1 27910 -1 27911 -1 27912 -1 27913 -1 27914 -1 27915 -1 27916 -1 27917 -1 27918 -1 27919 -1 27920 -1 27921 -1 27922 -1 27923 -1 27924 -1 27925 -1 27926 -1 27927 -1 27928 -1 27929 -1 27930 -1 27931 -1 27932 -1 27933 -1 27934 -1 27935 -1 27936 -1 27937 -1 27938 -1 27939 -1 27940 -1 27941 -1 27942 -1 27943 -1 27944 -1 27945 -1 27946 -1 27947 -1 27948 -1 27949 -1 27950 -1 27951 -1 27952 -1 27953 -1 27954 -1 27955 -1 27956 -1 27957 -1 27958 -1 27959 -1 27960 -1 27961 -1 27962 -1 27963 -1 27964 -1 27965 -1 27966 -1 27967 -1 27968 -1 27969 -1 27970 -1 27971 -1 27972 -1 27973 -1 27974 -1 27975 -1 27976 -1 27977 -1 27978 -1 27979 -1 27980 -1 27981 -1 27982 -1 27983 -1 27984 -1 27985 -1 27986 -1 27987 -1 27988 -1 27989 -1 27990 -1 27991 -1 27992 -1 27993 -1 27994 -1 27995 -1 27996 -1 27997 -1 27998 -1 27999 -1 28000 -1 28001 -1 28002 -1 28003 -1 28004 -1 28005 -1 28006 -1 28007 -1 28008 -1 28009 -1 28010 -1 28011 -1 28012 -1 28013 -1 28014 -1 28015 -1 28016 -1 28017 -1 28018 -1 28019 -1 28020 -1 28021 -1 28022 -1 28023 -1 28024 -1 28025 -1 28026 -1 28027 -1 28028 -1 28029 -1 28030 -1 28031 -1 28032 -1 28033 -1 28034 -1 28035 -1 28036 -1 28037 -1 28038 -1 28039 -1 28040 -1 28041 -1 28042 -1 28043 -1 28044 -1 28045 -1 28046 -1 28047 -1 28048 -1 28049 -1 28050 -1 28051 -1 28052 -1 28053 -1 28054 -1 28055 -1 28056 -1 28057 -1 28058 -1 28059 -1 28060 -1 28061 -1 28062 -1 28063 -1 28064 -1 28065 -1 28066 -1 28067 -1 28068 -1 28069 -1 28070 -1 28071 -1 28072 -1 28073 -1 28074 -1 28075 -1 28076 -1 28077 -1 28078 -1 28079 -1 28080 -1 28081 -1 28082 -1 28083 -1 28084 -1 28085 -1 28086 -1 28087 -1 28088 -1 28089 -1 28090 -1 28091 -1 28092 -1 28093 -1 28094 -1 28095 -1 28096 -1 28097 -1 28098 -1 28099 -1 28100 -1 28101 -1 28102 -1 28103 -1 28104 -1 28105 -1 28106 -1 28107 -1 28108 -1 28109 -1 28110 -1 28111 -1 28112 -1 28113 -1 28114 -1 28115 -1 28116 -1 28117 -1 28118 -1 28119 -1 28120 -1 28121 -1 28122 -1 28123 -1 28124 -1 28125 -1 28126 -1 28127 -1 28128 -1 28129 -1 28130 -1 28131 -1 28132 -1 28133 -1 28134 -1 28135 -1 28136 -1 28137 -1 28138 -1 28139 -1 28140 -1 28141 -1 28142 -1 28143 -1 28144 -1 28145 -1 28146 -1 28147 -1 28148 -1 28149 -1 28150 -1 28151 -1 28152 -1 28153 -1 28154 -1 28155 -1 28156 -1 28157 -1 28158 -1 28159 -1 28160 -1 28161 -1 28162 -1 28163 -1 28164 -1 28165 -1 28166 -1 28167 -1 28168 -1 28169 -1 28170 -1 28171 -1 28172 -1 28173 -1 28174 -1 28175 -1 28176 -1 28177 -1 28178 -1 28179 -1 28180 -1 28181 -1 28182 -1 28183 -1 28184 -1 28185 -1 28186 -1 28187 -1 28188 -1 28189 -1 28190 -1 28191 -1 28192 -1 28193 -1 28194 -1 28195 -1 28196 -1 28197 -1 28198 -1 28199 -1 28200 -1 28201 -1 28202 -1 28203 -1 28204 -1 28205 -1 28206 -1 28207 -1 28208 -1 28209 -1 28210 -1 28211 -1 28212 -1 28213 -1 28214 -1 28215 -1 28216 -1 28217 -1 28218 -1 28219 -1 28220 -1 28221 -1 28222 -1 28223 -1 28224 -1 28225 -1 28226 -1 28227 -1 28228 -1 28229 -1 28230 -1 28231 -1 28232 -1 28233 -1 28234 -1 28235 -1 28236 -1 28237 -1 28238 -1 28239 -1 28240 -1 28241 -1 28242 -1 28243 -1 28244 -1 28245 -1 28246 -1 28247 -1 28248 -1 28249 -1 28250 -1 28251 -1 28252 -1 28253 -1 28254 -1 28255 -1 28256 -1 28257 -1 28258 -1 28259 -1 28260 -1 28261 -1 28262 -1 28263 -1 28264 -1 28265 -1 28266 -1 28267 -1 28268 -1 28269 -1 28270 -1 28271 -1 28272 -1 28273 -1 28274 -1 28275 -1 28276 -1 28277 -1 28278 -1 28279 -1 28280 -1 28281 -1 28282 -1 28283 -1 28284 -1 28285 -1 28286 -1 28287 -1 28288 -1 28289 -1 28290 -1 28291 -1 28292 -1 28293 -1 28294 -1 28295 -1 28296 -1 28297 -1 28298 -1 28299 -1 28300 -1 28301 -1 28302 -1 28303 -1 28304 -1 28305 -1 28306 -1 28307 -1 28308 -1 28309 -1 28310 -1 28311 -1 28312 -1 28313 -1 28314 -1 28315 -1 28316 -1 28317 -1 28318 -1 28319 -1 28320 -1 28321 -1 28322 -1 28323 -1 28324 -1 28325 -1 28326 -1 28327 -1 28328 -1 28329 -1 28330 -1 28331 -1 28332 -1 28333 -1 28334 -1 28335 -1 28336 -1 28337 -1 28338 -1 28339 -1 28340 -1 28341 -1 28342 -1 28343 -1 28344 -1 28345 -1 28346 -1 28347 -1 28348 -1 28349 -1 28350 -1 28351 -1 28352 -1 28353 -1 28354 -1 28355 -1 28356 -1 28357 -1 28358 -1 28359 -1 28360 -1 28361 -1 28362 -1 28363 -1 28364 -1 28365 -1 28366 -1 28367 -1 28368 -1 28369 -1 28370 -1 28371 -1 28372 -1 28373 -1 28374 -1 28375 -1 28376 -1 28377 -1 28378 -1 28379 -1 28380 -1 28381 -1 28382 -1 28383 -1 28384 -1 28385 -1 28386 -1 28387 -1 28388 -1 28389 -1 28390 -1 28391 -1 28392 -1 28393 -1 28394 -1 28395 -1 28396 -1 28397 -1 28398 -1 28399 -1 28400 -1 28401 -1 28402 -1 28403 -1 28404 -1 28405 -1 28406 -1 28407 -1 28408 -1 28409 -1 28410 -1 28411 -1 28412 -1 28413 -1 28414 -1 28415 -1 28416 -1 28417 -1 28418 -1 28419 -1 28420 -1 28421 -1 28422 -1 28423 -1 28424 -1 28425 -1 28426 -1 28427 -1 28428 -1 28429 -1 28430 -1 28431 -1 28432 -1 28433 -1 28434 -1 28435 -1 28436 -1 28437 -1 28438 -1 28439 -1 28440 -1 28441 -1 28442 -1 28443 -1 28444 -1 28445 -1 28446 -1 28447 -1 28448 -1 28449 -1 28450 -1 28451 -1 28452 -1 28453 -1 28454 -1 28455 -1 28456 -1 28457 -1 28458 -1 28459 -1 28460 -1 28461 -1 28462 -1 28463 -1 28464 -1 28465 -1 28466 -1 28467 -1 28468 -1 28469 -1 28470 -1 28471 -1 28472 -1 28473 -1 28474 -1 28475 -1 28476 -1 28477 -1 28478 -1 28479 -1 28480 -1 28481 -1 28482 -1 28483 -1 28484 -1 28485 -1 28486 -1 28487 -1 28488 -1 28489 -1 28490 -1 28491 -1 28492 -1 28493 -1 28494 -1 28495 -1 28496 -1 28497 -1 28498 -1 28499 -1 28500 -1 28501 -1 28502 -1 28503 -1 28504 -1 28505 -1 28506 -1 28507 -1 28508 -1 28509 -1 28510 -1 28511 -1 28512 -1 28513 -1 28514 -1 28515 -1 28516 -1 28517 -1 28518 -1 28519 -1 28520 -1 28521 -1 28522 -1 28523 -1 28524 -1 28525 -1 28526 -1 28527 -1 28528 -1 28529 -1 28530 -1 28531 -1 28532 -1 28533 -1 28534 -1 28535 -1 28536 -1 28537 -1 28538 -1 28539 -1 28540 -1 28541 -1 28542 -1 28543 -1 28544 -1 28545 -1 28546 -1 28547 -1 28548 -1 28549 -1 28550 -1 28551 -1 28552 -1 28553 -1 28554 -1 28555 -1 28556 -1 28557 -1 28558 -1 28559 -1 28560 -1 28561 -1 28562 -1 28563 -1 28564 -1 28565 -1 28566 -1 28567 -1 28568 -1 28569 -1 28570 -1 28571 -1 28572 -1 28573 -1 28574 -1 28575 -1 28576 -1 28577 -1 28578 -1 28579 -1 28580 -1 28581 -1 28582 -1 28583 -1 28584 -1 28585 -1 28586 -1 28587 -1 28588 -1 28589 -1 28590 -1 28591 -1 28592 -1 28593 -1 28594 -1 28595 -1 28596 -1 28597 -1 28598 -1 28599 -1 28600 -1 28601 -1 28602 -1 28603 -1 28604 -1 28605 -1 28606 -1 28607 -1 28608 -1 28609 -1 28610 -1 28611 -1 28612 -1 28613 -1 28614 -1 28615 -1 28616 -1 28617 -1 28618 -1 28619 -1 28620 -1 28621 -1 28622 -1 28623 -1 28624 -1 28625 -1 28626 -1 28627 -1 28628 -1 28629 -1 28630 -1 28631 -1 28632 -1 28633 -1 28634 -1 28635 -1 28636 -1 28637 -1 28638 -1 28639 -1 28640 -1 28641 -1 28642 -1 28643 -1 28644 -1 28645 -1 28646 -1 28647 -1 28648 -1 28649 -1 28650 -1 28651 -1 28652 -1 28653 -1 28654 -1 28655 -1 28656 -1 28657 -1 28658 -1 28659 -1 28660 -1 28661 -1 28662 -1 28663 -1 28664 -1 28665 -1 28666 -1 28667 -1 28668 -1 28669 -1 28670 -1 28671 -1 28672 -1 28673 -1 28674 -1 28675 -1 28676 -1 28677 -1 28678 -1 28679 -1 28680 -1 28681 -1 28682 -1 28683 -1 28684 -1 28685 -1 28686 -1 28687 -1 28688 -1 28689 -1 28690 -1 28691 -1 28692 -1 28693 -1 28694 -1 28695 -1 28696 -1 28697 -1 28698 -1 28699 -1 28700 -1 28701 -1 28702 -1 28703 -1 28704 -1 28705 -1 28706 -1 28707 -1 28708 -1 28709 -1 28710 -1 28711 -1 28712 -1 28713 -1 28714 -1 28715 -1 28716 -1 28717 -1 28718 -1 28719 -1 28720 -1 28721 -1 28722 -1 28723 -1 28724 -1 28725 -1 28726 -1 28727 -1 28728 -1 28729 -1 28730 -1 28731 -1 28732 -1 28733 -1 28734 -1 28735 -1 28736 -1 28737 -1 28738 -1 28739 -1 28740 -1 28741 -1 28742 -1 28743 -1 28744 -1 28745 -1 28746 -1 28747 -1 28748 -1 28749 -1 28750 -1 28751 -1 28752 -1 28753 -1 28754 -1 28755 -1 28756 -1 28757 -1 28758 -1 28759 -1 28760 -1 28761 -1 28762 -1 28763 -1 28764 -1 28765 -1 28766 -1 28767 -1 28768 -1 28769 -1 28770 -1 28771 -1 28772 -1 28773 -1 28774 -1 28775 -1 28776 -1 28777 -1 28778 -1 28779 -1 28780 -1 28781 -1 28782 -1 28783 -1 28784 -1 28785 -1 28786 -1 28787 -1 28788 -1 28789 -1 28790 -1 28791 -1 28792 -1 28793 -1 28794 -1 28795 -1 28796 -1 28797 -1 28798 -1 28799 -1 28800 -1 28801 -1 28802 -1 28803 -1 28804 -1 28805 -1 28806 -1 28807 -1 28808 -1 28809 -1 28810 -1 28811 -1 28812 -1 28813 -1 28814 -1 28815 -1 28816 -1 28817 -1 28818 -1 28819 -1 28820 -1 28821 -1 28822 -1 28823 -1 28824 -1 28825 -1 28826 -1 28827 -1 28828 -1 28829 -1 28830 -1 28831 -1 28832 -1 28833 -1 28834 -1 28835 -1 28836 -1 28837 -1 28838 -1 28839 -1 28840 -1 28841 -1 28842 -1 28843 -1 28844 -1 28845 -1 28846 -1 28847 -1 28848 -1 28849 -1 28850 -1 28851 -1 28852 -1 28853 -1 28854 -1 28855 -1 28856 -1 28857 -1 28858 -1 28859 -1 28860 -1 28861 -1 28862 -1 28863 -1 28864 -1 28865 -1 28866 -1 28867 -1 28868 -1 28869 -1 28870 -1 28871 -1 28872 -1 28873 -1 28874 -1 28875 -1 28876 -1 28877 -1 28878 -1 28879 -1 28880 -1 28881 -1 28882 -1 28883 -1 28884 -1 28885 -1 28886 -1 28887 -1 28888 -1 28889 -1 28890 -1 28891 -1 28892 -1 28893 -1 28894 -1 28895 -1 28896 -1 28897 -1 28898 -1 28899 -1 28900 -1 28901 -1 28902 -1 28903 -1 28904 -1 28905 -1 28906 -1 28907 -1 28908 -1 28909 -1 28910 -1 28911 -1 28912 -1 28913 -1 28914 -1 28915 -1 28916 -1 28917 -1 28918 -1 28919 -1 28920 -1 28921 -1 28922 -1 28923 -1 28924 -1 28925 -1 28926 -1 28927 -1 28928 -1 28929 -1 28930 -1 28931 -1 28932 -1 28933 -1 28934 -1 28935 -1 28936 -1 28937 -1 28938 -1 28939 -1 28940 -1 28941 -1 28942 -1 28943 -1 28944 -1 28945 -1 28946 -1 28947 -1 28948 -1 28949 -1 28950 -1 28951 -1 28952 -1 28953 -1 28954 -1 28955 -1 28956 -1 28957 -1 28958 -1 28959 -1 28960 -1 28961 -1 28962 -1 28963 -1 28964 -1 28965 -1 28966 -1 28967 -1 28968 -1 28969 -1 28970 -1 28971 -1 28972 -1 28973 -1 28974 -1 28975 -1 28976 -1 28977 -1 28978 -1 28979 -1 28980 -1 28981 -1 28982 -1 28983 -1 28984 -1 28985 -1 28986 -1 28987 -1 28988 -1 28989 -1 28990 -1 28991 -1 28992 -1 28993 -1 28994 -1 28995 -1 28996 -1 28997 -1 28998 -1 28999 -1 29000 -1 29001 -1 29002 -1 29003 -1 29004 -1 29005 -1 29006 -1 29007 -1 29008 -1 29009 -1 29010 -1 29011 -1 29012 -1 29013 -1 29014 -1 29015 -1 29016 -1 29017 -1 29018 -1 29019 -1 29020 -1 29021 -1 29022 -1 29023 -1 29024 -1 29025 -1 29026 -1 29027 -1 29028 -1 29029 -1 29030 -1 29031 -1 29032 -1 29033 -1 29034 -1 29035 -1 29036 -1 29037 -1 29038 -1 29039 -1 29040 -1 29041 -1 29042 -1 29043 -1 29044 -1 29045 -1 29046 -1 29047 -1 29048 -1 29049 -1 29050 -1 29051 -1 29052 -1 29053 -1 29054 -1 29055 -1 29056 -1 29057 -1 29058 -1 29059 -1 29060 -1 29061 -1 29062 -1 29063 -1 29064 -1 29065 -1 29066 -1 29067 -1 29068 -1 29069 -1 29070 -1 29071 -1 29072 -1 29073 -1 29074 -1 29075 -1 29076 -1 29077 -1 29078 -1 29079 -1 29080 -1 29081 -1 29082 -1 29083 -1 29084 -1 29085 -1 29086 -1 29087 -1 29088 -1 29089 -1 29090 -1 29091 -1 29092 -1 29093 -1 29094 -1 29095 -1 29096 -1 29097 -1 29098 -1 29099 -1 29100 -1 29101 -1 29102 -1 29103 -1 29104 -1 29105 -1 29106 -1 29107 -1 29108 -1 29109 -1 29110 -1 29111 -1 29112 -1 29113 -1 29114 -1 29115 -1 29116 -1 29117 -1 29118 -1 29119 -1 29120 -1 29121 -1 29122 -1 29123 -1 29124 -1 29125 -1 29126 -1 29127 -1 29128 -1 29129 -1 29130 -1 29131 -1 29132 -1 29133 -1 29134 -1 29135 -1 29136 -1 29137 -1 29138 -1 29139 -1 29140 -1 29141 -1 29142 -1 29143 -1 29144 -1 29145 -1 29146 -1 29147 -1 29148 -1 29149 -1 29150 -1 29151 -1 29152 -1 29153 -1 29154 -1 29155 -1 29156 -1 29157 -1 29158 -1 29159 -1 29160 -1 29161 -1 29162 -1 29163 -1 29164 -1 29165 -1 29166 -1 29167 -1 29168 -1 29169 -1 29170 -1 29171 -1 29172 -1 29173 -1 29174 -1 29175 -1 29176 -1 29177 -1 29178 -1 29179 -1 29180 -1 29181 -1 29182 -1 29183 -1 29184 -1 29185 -1 29186 -1 29187 -1 29188 -1 29189 -1 29190 -1 29191 -1 29192 -1 29193 -1 29194 -1 29195 -1 29196 -1 29197 -1 29198 -1 29199 -1 29200 -1 29201 -1 29202 -1 29203 -1 29204 -1 29205 -1 29206 -1 29207 -1 29208 -1 29209 -1 29210 -1 29211 -1 29212 -1 29213 -1 29214 -1 29215 -1 29216 -1 29217 -1 29218 -1 29219 -1 29220 -1 29221 -1 29222 -1 29223 -1 29224 -1 29225 -1 29226 -1 29227 -1 29228 -1 29229 -1 29230 -1 29231 -1 29232 -1 29233 -1 29234 -1 29235 -1 29236 -1 29237 -1 29238 -1 29239 -1 29240 -1 29241 -1 29242 -1 29243 -1 29244 -1 29245 -1 29246 -1 29247 -1 29248 -1 29249 -1 29250 -1 29251 -1 29252 -1 29253 -1 29254 -1 29255 -1 29256 -1 29257 -1 29258 -1 29259 -1 29260 -1 29261 -1 29262 -1 29263 -1 29264 -1 29265 -1 29266 -1 29267 -1 29268 -1 29269 -1 29270 -1 29271 -1 29272 -1 29273 -1 29274 -1 29275 -1 29276 -1 29277 -1 29278 -1 29279 -1 29280 -1 29281 -1 29282 -1 29283 -1 29284 -1 29285 -1 29286 -1 29287 -1 29288 -1 29289 -1 29290 -1 29291 -1 29292 -1 29293 -1 29294 -1 29295 -1 29296 -1 29297 -1 29298 -1 29299 -1 29300 -1 29301 -1 29302 -1 29303 -1 29304 -1 29305 -1 29306 -1 29307 -1 29308 -1 29309 -1 29310 -1 29311 -1 29312 -1 29313 -1 29314 -1 29315 -1 29316 -1 29317 -1 29318 -1 29319 -1 29320 -1 29321 -1 29322 -1 29323 -1 29324 -1 29325 -1 29326 -1 29327 -1 29328 -1 29329 -1 29330 -1 29331 -1 29332 -1 29333 -1 29334 -1 29335 -1 29336 -1 29337 -1 29338 -1 29339 -1 29340 -1 29341 -1 29342 -1 29343 -1 29344 -1 29345 -1 29346 -1 29347 -1 29348 -1 29349 -1 29350 -1 29351 -1 29352 -1 29353 -1 29354 -1 29355 -1 29356 -1 29357 -1 29358 -1 29359 -1 29360 -1 29361 -1 29362 -1 29363 -1 29364 -1 29365 -1 29366 -1 29367 -1 29368 -1 29369 -1 29370 -1 29371 -1 29372 -1 29373 -1 29374 -1 29375 -1 29376 -1 29377 -1 29378 -1 29379 -1 29380 -1 29381 -1 29382 -1 29383 -1 29384 -1 29385 -1 29386 -1 29387 -1 29388 -1 29389 -1 29390 -1 29391 -1 29392 -1 29393 -1 29394 -1 29395 -1 29396 -1 29397 -1 29398 -1 29399 -1 29400 -1 29401 -1 29402 -1 29403 -1 29404 -1 29405 -1 29406 -1 29407 -1 29408 -1 29409 -1 29410 -1 29411 -1 29412 -1 29413 -1 29414 -1 29415 -1 29416 -1 29417 -1 29418 -1 29419 -1 29420 -1 29421 -1 29422 -1 29423 -1 29424 -1 29425 -1 29426 -1 29427 -1 29428 -1 29429 -1 29430 -1 29431 -1 29432 -1 29433 -1 29434 -1 29435 -1 29436 -1 29437 -1 29438 -1 29439 -1 29440 -1 29441 -1 29442 -1 29443 -1 29444 -1 29445 -1 29446 -1 29447 -1 29448 -1 29449 -1 29450 -1 29451 -1 29452 -1 29453 -1 29454 -1 29455 -1 29456 -1 29457 -1 29458 -1 29459 -1 29460 -1 29461 -1 29462 -1 29463 -1 29464 -1 29465 -1 29466 -1 29467 -1 29468 -1 29469 -1 29470 -1 29471 -1 29472 -1 29473 -1 29474 -1 29475 -1 29476 -1 29477 -1 29478 -1 29479 -1 29480 -1 29481 -1 29482 -1 29483 -1 29484 -1 29485 -1 29486 -1 29487 -1 29488 -1 29489 -1 29490 -1 29491 -1 29492 -1 29493 -1 29494 -1 29495 -1 29496 -1 29497 -1 29498 -1 29499 -1 29500 -1 29501 -1 29502 -1 29503 -1 29504 -1 29505 -1 29506 -1 29507 -1 29508 -1 29509 -1 29510 -1 29511 -1 29512 -1 29513 -1 29514 -1 29515 -1 29516 -1 29517 -1 29518 -1 29519 -1 29520 -1 29521 -1 29522 -1 29523 -1 29524 -1 29525 -1 29526 -1 29527 -1 29528 -1 29529 -1 29530 -1 29531 -1 29532 -1 29533 -1 29534 -1 29535 -1 29536 -1 29537 -1 29538 -1 29539 -1 29540 -1 29541 -1 29542 -1 29543 -1 29544 -1 29545 -1 29546 -1 29547 -1 29548 -1 29549 -1 29550 -1 29551 -1 29552 -1 29553 -1 29554 -1 29555 -1 29556 -1 29557 -1 29558 -1 29559 -1 29560 -1 29561 -1 29562 -1 29563 -1 29564 -1 29565 -1 29566 -1 29567 -1 29568 -1 29569 -1 29570 -1 29571 -1 29572 -1 29573 -1 29574 -1 29575 -1 29576 -1 29577 -1 29578 -1 29579 -1 29580 -1 29581 -1 29582 -1 29583 -1 29584 -1 29585 -1 29586 -1 29587 -1 29588 -1 29589 -1 29590 -1 29591 -1 29592 -1 29593 -1 29594 -1 29595 -1 29596 -1 29597 -1 29598 -1 29599 -1 29600 -1 29601 -1 29602 -1 29603 -1 29604 -1 29605 -1 29606 -1 29607 -1 29608 -1 29609 -1 29610 -1 29611 -1 29612 -1 29613 -1 29614 -1 29615 -1 29616 -1 29617 -1 29618 -1 29619 -1 29620 -1 29621 -1 29622 -1 29623 -1 29624 -1 29625 -1 29626 -1 29627 -1 29628 -1 29629 -1 29630 -1 29631 -1 29632 -1 29633 -1 29634 -1 29635 -1 29636 -1 29637 -1 29638 -1 29639 -1 29640 -1 29641 -1 29642 -1 29643 -1 29644 -1 29645 -1 29646 -1 29647 -1 29648 -1 29649 -1 29650 -1 29651 -1 29652 -1 29653 -1 29654 -1 29655 -1 29656 -1 29657 -1 29658 -1 29659 -1 29660 -1 29661 -1 29662 -1 29663 -1 29664 -1 29665 -1 29666 -1 29667 -1 29668 -1 29669 -1 29670 -1 29671 -1 29672 -1 29673 -1 29674 -1 29675 -1 29676 -1 29677 -1 29678 -1 29679 -1 29680 -1 29681 -1 29682 -1 29683 -1 29684 -1 29685 -1 29686 -1 29687 -1 29688 -1 29689 -1 29690 -1 29691 -1 29692 -1 29693 -1 29694 -1 29695 -1 29696 -1 29697 -1 29698 -1 29699 -1 29700 -1 29701 -1 29702 -1 29703 -1 29704 -1 29705 -1 29706 -1 29707 -1 29708 -1 29709 -1 29710 -1 29711 -1 29712 -1 29713 -1 29714 -1 29715 -1 29716 -1 29717 -1 29718 -1 29719 -1 29720 -1 29721 -1 29722 -1 29723 -1 29724 -1 29725 -1 29726 -1 29727 -1 29728 -1 29729 -1 29730 -1 29731 -1 29732 -1 29733 -1 29734 -1 29735 -1 29736 -1 29737 -1 29738 -1 29739 -1 29740 -1 29741 -1 29742 -1 29743 -1 29744 -1 29745 -1 29746 -1 29747 -1 29748 -1 29749 -1 29750 -1 29751 -1 29752 -1 29753 -1 29754 -1 29755 -1 29756 -1 29757 -1 29758 -1 29759 -1 29760 -1 29761 -1 29762 -1 29763 -1 29764 -1 29765 -1 29766 -1 29767 -1 29768 -1 29769 -1 29770 -1 29771 -1 29772 -1 29773 -1 29774 -1 29775 -1 29776 -1 29777 -1 29778 -1 29779 -1 29780 -1 29781 -1 29782 -1 29783 -1 29784 -1 29785 -1 29786 -1 29787 -1 29788 -1 29789 -1 29790 -1 29791 -1 29792 -1 29793 -1 29794 -1 29795 -1 29796 -1 29797 -1 29798 -1 29799 -1 29800 -1 29801 -1 29802 -1 29803 -1 29804 -1 29805 -1 29806 -1 29807 -1 29808 -1 29809 -1 29810 -1 29811 -1 29812 -1 29813 -1 29814 -1 29815 -1 29816 -1 29817 -1 29818 -1 29819 -1 29820 -1 29821 -1 29822 -1 29823 -1 29824 -1 29825 -1 29826 -1 29827 -1 29828 -1 29829 -1 29830 -1 29831 -1 29832 -1 29833 -1 29834 -1 29835 -1 29836 -1 29837 -1 29838 -1 29839 -1 29840 -1 29841 -1 29842 -1 29843 -1 29844 -1 29845 -1 29846 -1 29847 -1 29848 -1 29849 -1 29850 -1 29851 -1 29852 -1 29853 -1 29854 -1 29855 -1 29856 -1 29857 -1 29858 -1 29859 -1 29860 -1 29861 -1 29862 -1 29863 -1 29864 -1 29865 -1 29866 -1 29867 -1 29868 -1 29869 -1 29870 -1 29871 -1 29872 -1 29873 -1 29874 -1 29875 -1 29876 -1 29877 -1 29878 -1 29879 -1 29880 -1 29881 -1 29882 -1 29883 -1 29884 -1 29885 -1 29886 -1 29887 -1 29888 -1 29889 -1 29890 -1 29891 -1 29892 -1 29893 -1 29894 -1 29895 -1 29896 -1 29897 -1 29898 -1 29899 -1 29900 -1 29901 -1 29902 -1 29903 -1 29904 -1 29905 -1 29906 -1 29907 -1 29908 -1 29909 -1 29910 -1 29911 -1 29912 -1 29913 -1 29914 -1 29915 -1 29916 -1 29917 -1 29918 -1 29919 -1 29920 -1 29921 -1 29922 -1 29923 -1 29924 -1 29925 -1 29926 -1 29927 -1 29928 -1 29929 -1 29930 -1 29931 -1 29932 -1 29933 -1 29934 -1 29935 -1 29936 -1 29937 -1 29938 -1 29939 -1 29940 -1 29941 -1 29942 -1 29943 -1 29944 -1 29945 -1 29946 -1 29947 -1 29948 -1 29949 -1 29950 -1 29951 -1 29952 -1 29953 -1 29954 -1 29955 -1 29956 -1 29957 -1 29958 -1 29959 -1 29960 -1 29961 -1 29962 -1 29963 -1 29964 -1 29965 -1 29966 -1 29967 -1 29968 -1 29969 -1 29970 -1 29971 -1 29972 -1 29973 -1 29974 -1 29975 -1 29976 -1 29977 -1 29978 -1 29979 -1 29980 -1 29981 -1 29982 -1 29983 -1 29984 -1 29985 -1 29986 -1 29987 -1 29988 -1 29989 -1 29990 -1 29991 -1 29992 -1 29993 -1 29994 -1 29995 -1 29996 -1 29997 -1 29998 -1 29999 -1 30000 -1 30001 -1 30002 -1 30003 -1 30004 -1 30005 -1 30006 -1 30007 -1 30008 -1 30009 -1 30010 -1 30011 -1 30012 -1 30013 -1 30014 -1 30015 -1 30016 -1 30017 -1 30018 -1 30019 -1 30020 -1 30021 -1 30022 -1 30023 -1 30024 -1 30025 -1 30026 -1 30027 -1 30028 -1 30029 -1 30030 -1 30031 -1 30032 -1 30033 -1 30034 -1 30035 -1 30036 -1 30037 -1 30038 -1 30039 -1 30040 -1 30041 -1 30042 -1 30043 -1 30044 -1 30045 -1 30046 -1 30047 -1 30048 -1 30049 -1 30050 -1 30051 -1 30052 -1 30053 -1 30054 -1 30055 -1 30056 -1 30057 -1 30058 -1 30059 -1 30060 -1 30061 -1 30062 -1 30063 -1 30064 -1 30065 -1 30066 -1 30067 -1 30068 -1 30069 -1 30070 -1 30071 -1 30072 -1 30073 -1 30074 -1 30075 -1 30076 -1 30077 -1 30078 -1 30079 -1 30080 -1 30081 -1 30082 -1 30083 -1 30084 -1 30085 -1 30086 -1 30087 -1 30088 -1 30089 -1 30090 -1 30091 -1 30092 -1 30093 -1 30094 -1 30095 -1 30096 -1 30097 -1 30098 -1 30099 -1 30100 -1 30101 -1 30102 -1 30103 -1 30104 -1 30105 -1 30106 -1 30107 -1 30108 -1 30109 -1 30110 -1 30111 -1 30112 -1 30113 -1 30114 -1 30115 -1 30116 -1 30117 -1 30118 -1 30119 -1 30120 -1 30121 -1 30122 -1 30123 -1 30124 -1 30125 -1 30126 -1 30127 -1 30128 -1 30129 -1 30130 -1 30131 -1 30132 -1 30133 -1 30134 -1 30135 -1 30136 -1 30137 -1 30138 -1 30139 -1 30140 -1 30141 -1 30142 -1 30143 -1 30144 -1 30145 -1 30146 -1 30147 -1 30148 -1 30149 -1 30150 -1 30151 -1 30152 -1 30153 -1 30154 -1 30155 -1 30156 -1 30157 -1 30158 -1 30159 -1 30160 -1 30161 -1 30162 -1 30163 -1 30164 -1 30165 -1 30166 -1 30167 -1 30168 -1 30169 -1 30170 -1 30171 -1 30172 -1 30173 -1 30174 -1 30175 -1 30176 -1 30177 -1 30178 -1 30179 -1 30180 -1 30181 -1 30182 -1 30183 -1 30184 -1 30185 -1 30186 -1 30187 -1 30188 -1 30189 -1 30190 -1 30191 -1 30192 -1 30193 -1 30194 -1 30195 -1 30196 -1 30197 -1 30198 -1 30199 -1 30200 -1 30201 -1 30202 -1 30203 -1 30204 -1 30205 -1 30206 -1 30207 -1 30208 -1 30209 -1 30210 -1 30211 -1 30212 -1 30213 -1 30214 -1 30215 -1 30216 -1 30217 -1 30218 -1 30219 -1 30220 -1 30221 -1 30222 -1 30223 -1 30224 -1 30225 -1 30226 -1 30227 -1 30228 -1 30229 -1 30230 -1 30231 -1 30232 -1 30233 -1 30234 -1 30235 -1 30236 -1 30237 -1 30238 -1 30239 -1 30240 -1 30241 -1 30242 -1 30243 -1 30244 -1 30245 -1 30246 -1 30247 -1 30248 -1 30249 -1 30250 -1 30251 -1 30252 -1 30253 -1 30254 -1 30255 -1 30256 -1 30257 -1 30258 -1 30259 -1 30260 -1 30261 -1 30262 -1 30263 -1 30264 -1 30265 -1 30266 -1 30267 -1 30268 -1 30269 -1 30270 -1 30271 -1 30272 -1 30273 -1 30274 -1 30275 -1 30276 -1 30277 -1 30278 -1 30279 -1 30280 -1 30281 -1 30282 -1 30283 -1 30284 -1 30285 -1 30286 -1 30287 -1 30288 -1 30289 -1 30290 -1 30291 -1 30292 -1 30293 -1 30294 -1 30295 -1 30296 -1 30297 -1 30298 -1 30299 -1 30300 -1 30301 -1 30302 -1 30303 -1 30304 -1 30305 -1 30306 -1 30307 -1 30308 -1 30309 -1 30310 -1 30311 -1 30312 -1 30313 -1 30314 -1 30315 -1 30316 -1 30317 -1 30318 -1 30319 -1 30320 -1 30321 -1 30322 -1 30323 -1 30324 -1 30325 -1 30326 -1 30327 -1 30328 -1 30329 -1 30330 -1 30331 -1 30332 -1 30333 -1 30334 -1 30335 -1 30336 -1 30337 -1 30338 -1 30339 -1 30340 -1 30341 -1 30342 -1 30343 -1 30344 -1 30345 -1 30346 -1 30347 -1 30348 -1 30349 -1 30350 -1 30351 -1 30352 -1 30353 -1 30354 -1 30355 -1 30356 -1 30357 -1 30358 -1 30359 -1 30360 -1 30361 -1 30362 -1 30363 -1 30364 -1 30365 -1 30366 -1 30367 -1 30368 -1 30369 -1 30370 -1 30371 -1 30372 -1 30373 -1 30374 -1 30375 -1 30376 -1 30377 -1 30378 -1 30379 -1 30380 -1 30381 -1 30382 -1 30383 -1 30384 -1 30385 -1 30386 -1 30387 -1 30388 -1 30389 -1 30390 -1 30391 -1 30392 -1 30393 -1 30394 -1 30395 -1 30396 -1 30397 -1 30398 -1 30399 -1 30400 -1 30401 -1 30402 -1 30403 -1 30404 -1 30405 -1 30406 -1 30407 -1 30408 -1 30409 -1 30410 -1 30411 -1 30412 -1 30413 -1 30414 -1 30415 -1 30416 -1 30417 -1 30418 -1 30419 -1 30420 -1 30421 -1 30422 -1 30423 -1 30424 -1 30425 -1 30426 -1 30427 -1 30428 -1 30429 -1 30430 -1 30431 -1 30432 -1 30433 -1 30434 -1 30435 -1 30436 -1 30437 -1 30438 -1 30439 -1 30440 -1 30441 -1 30442 -1 30443 -1 30444 -1 30445 -1 30446 -1 30447 -1 30448 -1 30449 -1 30450 -1 30451 -1 30452 -1 30453 -1 30454 -1 30455 -1 30456 -1 30457 -1 30458 -1 30459 -1 30460 -1 30461 -1 30462 -1 30463 -1 30464 -1 30465 -1 30466 -1 30467 -1 30468 -1 30469 -1 30470 -1 30471 -1 30472 -1 30473 -1 30474 -1 30475 -1 30476 -1 30477 -1 30478 -1 30479 -1 30480 -1 30481 -1 30482 -1 30483 -1 30484 -1 30485 -1 30486 -1 30487 -1 30488 -1 30489 -1 30490 -1 30491 -1 30492 -1 30493 -1 30494 -1 30495 -1 30496 -1 30497 -1 30498 -1 30499 -1 30500 -1 30501 -1 30502 -1 30503 -1 30504 -1 30505 -1 30506 -1 30507 -1 30508 -1 30509 -1 30510 -1 30511 -1 30512 -1 30513 -1 30514 -1 30515 -1 30516 -1 30517 -1 30518 -1 30519 -1 30520 -1 30521 -1 30522 -1 30523 -1 30524 -1 30525 -1 30526 -1 30527 -1 30528 -1 30529 -1 30530 -1 30531 -1 30532 -1 30533 -1 30534 -1 30535 -1 30536 -1 30537 -1 30538 -1 30539 -1 30540 -1 30541 -1 30542 -1 30543 -1 30544 -1 30545 -1 30546 -1 30547 -1 30548 -1 30549 -1 30550 -1 30551 -1 30552 -1 30553 -1 30554 -1 30555 -1 30556 -1 30557 -1 30558 -1 30559 -1 30560 -1 30561 -1 30562 -1 30563 -1 30564 -1 30565 -1 30566 -1 30567 -1 30568 -1 30569 -1 30570 -1 30571 -1 30572 -1 30573 -1 30574 -1 30575 -1 30576 -1 30577 -1 30578 -1 30579 -1 30580 -1 30581 -1 30582 -1 30583 -1 30584 -1 30585 -1 30586 -1 30587 -1 30588 -1 30589 -1 30590 -1 30591 -1 30592 -1 30593 -1 30594 -1 30595 -1 30596 -1 30597 -1 30598 -1 30599 -1 30600 -1 30601 -1 30602 -1 30603 -1 30604 -1 30605 -1 30606 -1 30607 -1 30608 -1 30609 -1 30610 -1 30611 -1 30612 -1 30613 -1 30614 -1 30615 -1 30616 -1 30617 -1 30618 -1 30619 -1 30620 -1 30621 -1 30622 -1 30623 -1 30624 -1 30625 -1 30626 -1 30627 -1 30628 -1 30629 -1 30630 -1 30631 -1 30632 -1 30633 -1 30634 -1 30635 -1 30636 -1 30637 -1 30638 -1 30639 -1 30640 -1 30641 -1 30642 -1 30643 -1 30644 -1 30645 -1 30646 -1 30647 -1 30648 -1 30649 -1 30650 -1 30651 -1 30652 -1 30653 -1 30654 -1 30655 -1 30656 -1 30657 -1 30658 -1 30659 -1 30660 -1 30661 -1 30662 -1 30663 -1 30664 -1 30665 -1 30666 -1 30667 -1 30668 -1 30669 -1 30670 -1 30671 -1 30672 -1 30673 -1 30674 -1 30675 -1 30676 -1 30677 -1 30678 -1 30679 -1 30680 -1 30681 -1 30682 -1 30683 -1 30684 -1 30685 -1 30686 -1 30687 -1 30688 -1 30689 -1 30690 -1 30691 -1 30692 -1 30693 -1 30694 -1 30695 -1 30696 -1 30697 -1 30698 -1 30699 -1 30700 -1 30701 -1 30702 -1 30703 -1 30704 -1 30705 -1 30706 -1 30707 -1 30708 -1 30709 -1 30710 -1 30711 -1 30712 -1 30713 -1 30714 -1 30715 -1 30716 -1 30717 -1 30718 -1 30719 -1 30720 -1 30721 -1 30722 -1 30723 -1 30724 -1 30725 -1 30726 -1 30727 -1 30728 -1 30729 -1 30730 -1 30731 -1 30732 -1 30733 -1 30734 -1 30735 -1 30736 -1 30737 -1 30738 -1 30739 -1 30740 -1 30741 -1 30742 -1 30743 -1 30744 -1 30745 -1 30746 -1 30747 -1 30748 -1 30749 -1 30750 -1 30751 -1 30752 -1 30753 -1 30754 -1 30755 -1 30756 -1 30757 -1 30758 -1 30759 -1 30760 -1 30761 -1 30762 -1 30763 -1 30764 -1 30765 -1 30766 -1 30767 -1 30768 -1 30769 -1 30770 -1 30771 -1 30772 -1 30773 -1 30774 -1 30775 -1 30776 -1 30777 -1 30778 -1 30779 -1 30780 -1 30781 -1 30782 -1 30783 -1 30784 -1 30785 -1 30786 -1 30787 -1 30788 -1 30789 -1 30790 -1 30791 -1 30792 -1 30793 -1 30794 -1 30795 -1 30796 -1 30797 -1 30798 -1 30799 -1 30800 -1 30801 -1 30802 -1 30803 -1 30804 -1 30805 -1 30806 -1 30807 -1 30808 -1 30809 -1 30810 -1 30811 -1 30812 -1 30813 -1 30814 -1 30815 -1 30816 -1 30817 -1 30818 -1 30819 -1 30820 -1 30821 -1 30822 -1 30823 -1 30824 -1 30825 -1 30826 -1 30827 -1 30828 -1 30829 -1 30830 -1 30831 -1 30832 -1 30833 -1 30834 -1 30835 -1 30836 -1 30837 -1 30838 -1 30839 -1 30840 -1 30841 -1 30842 -1 30843 -1 30844 -1 30845 -1 30846 -1 30847 -1 30848 -1 30849 -1 30850 -1 30851 -1 30852 -1 30853 -1 30854 -1 30855 -1 30856 -1 30857 -1 30858 -1 30859 -1 30860 -1 30861 -1 30862 -1 30863 -1 30864 -1 30865 -1 30866 -1 30867 -1 30868 -1 30869 -1 30870 -1 30871 -1 30872 -1 30873 -1 30874 -1 30875 -1 30876 -1 30877 -1 30878 -1 30879 -1 30880 -1 30881 -1 30882 -1 30883 -1 30884 -1 30885 -1 30886 -1 30887 -1 30888 -1 30889 -1 30890 -1 30891 -1 30892 -1 30893 -1 30894 -1 30895 -1 30896 -1 30897 -1 30898 -1 30899 -1 30900 -1 30901 -1 30902 -1 30903 -1 30904 -1 30905 -1 30906 -1 30907 -1 30908 -1 30909 -1 30910 -1 30911 -1 30912 -1 30913 -1 30914 -1 30915 -1 30916 -1 30917 -1 30918 -1 30919 -1 30920 -1 30921 -1 30922 -1 30923 -1 30924 -1 30925 -1 30926 -1 30927 -1 30928 -1 30929 -1 30930 -1 30931 -1 30932 -1 30933 -1 30934 -1 30935 -1 30936 -1 30937 -1 30938 -1 30939 -1 30940 -1 30941 -1 30942 -1 30943 -1 30944 -1 30945 -1 30946 -1 30947 -1 30948 -1 30949 -1 30950 -1 30951 -1 30952 -1 30953 -1 30954 -1 30955 -1 30956 -1 30957 -1 30958 -1 30959 -1 30960 -1 30961 -1 30962 -1 30963 -1 30964 -1 30965 -1 30966 -1 30967 -1 30968 -1 30969 -1 30970 -1 30971 -1 30972 -1 30973 -1 30974 -1 30975 -1 30976 -1 30977 -1 30978 -1 30979 -1 30980 -1 30981 -1 30982 -1 30983 -1 30984 -1 30985 -1 30986 -1 30987 -1 30988 -1 30989 -1 30990 -1 30991 -1 30992 -1 30993 -1 30994 -1 30995 -1 30996 -1 30997 -1 30998 -1 30999 -1 31000 -1 31001 -1 31002 -1 31003 -1 31004 -1 31005 -1 31006 -1 31007 -1 31008 -1 31009 -1 31010 -1 31011 -1 31012 -1 31013 -1 31014 -1 31015 -1 31016 -1 31017 -1 31018 -1 31019 -1 31020 -1 31021 -1 31022 -1 31023 -1 31024 -1 31025 -1 31026 -1 31027 -1 31028 -1 31029 -1 31030 -1 31031 -1 31032 -1 31033 -1 31034 -1 31035 -1 31036 -1 31037 -1 31038 -1 31039 -1 31040 -1 31041 -1 31042 -1 31043 -1 31044 -1 31045 -1 31046 -1 31047 -1 31048 -1 31049 -1 31050 -1 31051 -1 31052 -1 31053 -1 31054 -1 31055 -1 31056 -1 31057 -1 31058 -1 31059 -1 31060 -1 31061 -1 31062 -1 31063 -1 31064 -1 31065 -1 31066 -1 31067 -1 31068 -1 31069 -1 31070 -1 31071 -1 31072 -1 31073 -1 31074 -1 31075 -1 31076 -1 31077 -1 31078 -1 31079 -1 31080 -1 31081 -1 31082 -1 31083 -1 31084 -1 31085 -1 31086 -1 31087 -1 31088 -1 31089 -1 31090 -1 31091 -1 31092 -1 31093 -1 31094 -1 31095 -1 31096 -1 31097 -1 31098 -1 31099 -1 31100 -1 31101 -1 31102 -1 31103 -1 31104 -1 31105 -1 31106 -1 31107 -1 31108 -1 31109 -1 31110 -1 31111 -1 31112 -1 31113 -1 31114 -1 31115 -1 31116 -1 31117 -1 31118 -1 31119 -1 31120 -1 31121 -1 31122 -1 31123 -1 31124 -1 31125 -1 31126 -1 31127 -1 31128 -1 31129 -1 31130 -1 31131 -1 31132 -1 31133 -1 31134 -1 31135 -1 31136 -1 31137 -1 31138 -1 31139 -1 31140 -1 31141 -1 31142 -1 31143 -1 31144 -1 31145 -1 31146 -1 31147 -1 31148 -1 31149 -1 31150 -1 31151 -1 31152 -1 31153 -1 31154 -1 31155 -1 31156 -1 31157 -1 31158 -1 31159 -1 31160 -1 31161 -1 31162 -1 31163 -1 31164 -1 31165 -1 31166 -1 31167 -1 31168 -1 31169 -1 31170 -1 31171 -1 31172 -1 31173 -1 31174 -1 31175 -1 31176 -1 31177 -1 31178 -1 31179 -1 31180 -1 31181 -1 31182 -1 31183 -1 31184 -1 31185 -1 31186 -1 31187 -1 31188 -1 31189 -1 31190 -1 31191 -1 31192 -1 31193 -1 31194 -1 31195 -1 31196 -1 31197 -1 31198 -1 31199 -1 31200 -1 31201 -1 31202 -1 31203 -1 31204 -1 31205 -1 31206 -1 31207 -1 31208 -1 31209 -1 31210 -1 31211 -1 31212 -1 31213 -1 31214 -1 31215 -1 31216 -1 31217 -1 31218 -1 31219 -1 31220 -1 31221 -1 31222 -1 31223 -1 31224 -1 31225 -1 31226 -1 31227 -1 31228 -1 31229 -1 31230 -1 31231 -1 31232 -1 31233 -1 31234 -1 31235 -1 31236 -1 31237 -1 31238 -1 31239 -1 31240 -1 31241 -1 31242 -1 31243 -1 31244 -1 31245 -1 31246 -1 31247 -1 31248 -1 31249 -1 31250 -1 31251 -1 31252 -1 31253 -1 31254 -1 31255 -1 31256 -1 31257 -1 31258 -1 31259 -1 31260 -1 31261 -1 31262 -1 31263 -1 31264 -1 31265 -1 31266 -1 31267 -1 31268 -1 31269 -1 31270 -1 31271 -1 31272 -1 31273 -1 31274 -1 31275 -1 31276 -1 31277 -1 31278 -1 31279 -1 31280 -1 31281 -1 31282 -1 31283 -1 31284 -1 31285 -1 31286 -1 31287 -1 31288 -1 31289 -1 31290 -1 31291 -1 31292 -1 31293 -1 31294 -1 31295 -1 31296 -1 31297 -1 31298 -1 31299 -1 31300 -1 31301 -1 31302 -1 31303 -1 31304 -1 31305 -1 31306 -1 31307 -1 31308 -1 31309 -1 31310 -1 31311 -1 31312 -1 31313 -1 31314 -1 31315 -1 31316 -1 31317 -1 31318 -1 31319 -1 31320 -1 31321 -1 31322 -1 31323 -1 31324 -1 31325 -1 31326 -1 31327 -1 31328 -1 31329 -1 31330 -1 31331 -1 31332 -1 31333 -1 31334 -1 31335 -1 31336 -1 31337 -1 31338 -1 31339 -1 31340 -1 31341 -1 31342 -1 31343 -1 31344 -1 31345 -1 31346 -1 31347 -1 31348 -1 31349 -1 31350 -1 31351 -1 31352 -1 31353 -1 31354 -1 31355 -1 31356 -1 31357 -1 31358 -1 31359 -1 31360 -1 31361 -1 31362 -1 31363 -1 31364 -1 31365 -1 31366 -1 31367 -1 31368 -1 31369 -1 31370 -1 31371 -1 31372 -1 31373 -1 31374 -1 31375 -1 31376 -1 31377 -1 31378 -1 31379 -1 31380 -1 31381 -1 31382 -1 31383 -1 31384 -1 31385 -1 31386 -1 31387 -1 31388 -1 31389 -1 31390 -1 31391 -1 31392 -1 31393 -1 31394 -1 31395 -1 31396 -1 31397 -1 31398 -1 31399 -1 31400 -1 31401 -1 31402 -1 31403 -1 31404 -1 31405 -1 31406 -1 31407 -1 31408 -1 31409 -1 31410 -1 31411 -1 31412 -1 31413 -1 31414 -1 31415 -1 31416 -1 31417 -1 31418 -1 31419 -1 31420 -1 31421 -1 31422 -1 31423 -1 31424 -1 31425 -1 31426 -1 31427 -1 31428 -1 31429 -1 31430 -1 31431 -1 31432 -1 31433 -1 31434 -1 31435 -1 31436 -1 31437 -1 31438 -1 31439 -1 31440 -1 31441 -1 31442 -1 31443 -1 31444 -1 31445 -1 31446 -1 31447 -1 31448 -1 31449 -1 31450 -1 31451 -1 31452 -1 31453 -1 31454 -1 31455 -1 31456 -1 31457 -1 31458 -1 31459 -1 31460 -1 31461 -1 31462 -1 31463 -1 31464 -1 31465 -1 31466 -1 31467 -1 31468 -1 31469 -1 31470 -1 31471 -1 31472 -1 31473 -1 31474 -1 31475 -1 31476 -1 31477 -1 31478 -1 31479 -1 31480 -1 31481 -1 31482 -1 31483 -1 31484 -1 31485 -1 31486 -1 31487 -1 31488 -1 31489 -1 31490 -1 31491 -1 31492 -1 31493 -1 31494 -1 31495 -1 31496 -1 31497 -1 31498 -1 31499 -1 31500 -1 31501 -1 31502 -1 31503 -1 31504 -1 31505 -1 31506 -1 31507 -1 31508 -1 31509 -1 31510 -1 31511 -1 31512 -1 31513 -1 31514 -1 31515 -1 31516 -1 31517 -1 31518 -1 31519 -1 31520 -1 31521 -1 31522 -1 31523 -1 31524 -1 31525 -1 31526 -1 31527 -1 31528 -1 31529 -1 31530 -1 31531 -1 31532 -1 31533 -1 31534 -1 31535 -1 31536 -1 31537 -1 31538 -1 31539 -1 31540 -1 31541 -1 31542 -1 31543 -1 31544 -1 31545 -1 31546 -1 31547 -1 31548 -1 31549 -1 31550 -1 31551 -1 31552 -1 31553 -1 31554 -1 31555 -1 31556 -1 31557 -1 31558 -1 31559 -1 31560 -1 31561 -1 31562 -1 31563 -1 31564 -1 31565 -1 31566 -1 31567 -1 31568 -1 31569 -1 31570 -1 31571 -1 31572 -1 31573 -1 31574 -1 31575 -1 31576 -1 31577 -1 31578 -1 31579 -1 31580 -1 31581 -1 31582 -1 31583 -1 31584 -1 31585 -1 31586 -1 31587 -1 31588 -1 31589 -1 31590 -1 31591 -1 31592 -1 31593 -1 31594 -1 31595 -1 31596 -1 31597 -1 31598 -1 31599 -1 31600 -1 31601 -1 31602 -1 31603 -1 31604 -1 31605 -1 31606 -1 31607 -1 31608 -1 31609 -1 31610 -1 31611 -1 31612 -1 31613 -1 31614 -1 31615 -1 31616 -1 31617 -1 31618 -1 31619 -1 31620 -1 31621 -1 31622 -1 31623 -1 31624 -1 31625 -1 31626 -1 31627 -1 31628 -1 31629 -1 31630 -1 31631 -1 31632 -1 31633 -1 31634 -1 31635 -1 31636 -1 31637 -1 31638 -1 31639 -1 31640 -1 31641 -1 31642 -1 31643 -1 31644 -1 31645 -1 31646 -1 31647 -1 31648 -1 31649 -1 31650 -1 31651 -1 31652 -1 31653 -1 31654 -1 31655 -1 31656 -1 31657 -1 31658 -1 31659 -1 31660 -1 31661 -1 31662 -1 31663 -1 31664 -1 31665 -1 31666 -1 31667 -1 31668 -1 31669 -1 31670 -1 31671 -1 31672 -1 31673 -1 31674 -1 31675 -1 31676 -1 31677 -1 31678 -1 31679 -1 31680 -1 31681 -1 31682 -1 31683 -1 31684 -1 31685 -1 31686 -1 31687 -1 31688 -1 31689 -1 31690 -1 31691 -1 31692 -1 31693 -1 31694 -1 31695 -1 31696 -1 31697 -1 31698 -1 31699 -1 31700 -1 31701 -1 31702 -1 31703 -1 31704 -1 31705 -1 31706 -1 31707 -1 31708 -1 31709 -1 31710 -1 31711 -1 31712 -1 31713 -1 31714 -1 31715 -1 31716 -1 31717 -1 31718 -1 31719 -1 31720 -1 31721 -1 31722 -1 31723 -1 31724 -1 31725 -1 31726 -1 31727 -1 31728 -1 31729 -1 31730 -1 31731 -1 31732 -1 31733 -1 31734 -1 31735 -1 31736 -1 31737 -1 31738 -1 31739 -1 31740 -1 31741 -1 31742 -1 31743 -1 31744 -1 31745 -1 31746 -1 31747 -1 31748 -1 31749 -1 31750 -1 31751 -1 31752 -1 31753 -1 31754 -1 31755 -1 31756 -1 31757 -1 31758 -1 31759 -1 31760 -1 31761 -1 31762 -1 31763 -1 31764 -1 31765 -1 31766 -1 31767 -1 31768 -1 31769 -1 31770 -1 31771 -1 31772 -1 31773 -1 31774 -1 31775 -1 31776 -1 31777 -1 31778 -1 31779 -1 31780 -1 31781 -1 31782 -1 31783 -1 31784 -1 31785 -1 31786 -1 31787 -1 31788 -1 31789 -1 31790 -1 31791 -1 31792 -1 31793 -1 31794 -1 31795 -1 31796 -1 31797 -1 31798 -1 31799 -1 31800 -1 31801 -1 31802 -1 31803 -1 31804 -1 31805 -1 31806 -1 31807 -1 31808 -1 31809 -1 31810 -1 31811 -1 31812 -1 31813 -1 31814 -1 31815 -1 31816 -1 31817 -1 31818 -1 31819 -1 31820 -1 31821 -1 31822 -1 31823 -1 31824 -1 31825 -1 31826 -1 31827 -1 31828 -1 31829 -1 31830 -1 31831 -1 31832 -1 31833 -1 31834 -1 31835 -1 31836 -1 31837 -1 31838 -1 31839 -1 31840 -1 31841 -1 31842 -1 31843 -1 31844 -1 31845 -1 31846 -1 31847 -1 31848 -1 31849 -1 31850 -1 31851 -1 31852 -1 31853 -1 31854 -1 31855 -1 31856 -1 31857 -1 31858 -1 31859 -1 31860 -1 31861 -1 31862 -1 31863 -1 31864 -1 31865 -1 31866 -1 31867 -1 31868 -1 31869 -1 31870 -1 31871 -1 31872 -1 31873 -1 31874 -1 31875 -1 31876 -1 31877 -1 31878 -1 31879 -1 31880 -1 31881 -1 31882 -1 31883 -1 31884 -1 31885 -1 31886 -1 31887 -1 31888 -1 31889 -1 31890 -1 31891 -1 31892 -1 31893 -1 31894 -1 31895 -1 31896 -1 31897 -1 31898 -1 31899 -1 31900 -1 31901 -1 31902 -1 31903 -1 31904 -1 31905 -1 31906 -1 31907 -1 31908 -1 31909 -1 31910 -1 31911 -1 31912 -1 31913 -1 31914 -1 31915 -1 31916 -1 31917 -1 31918 -1 31919 -1 31920 -1 31921 -1 31922 -1 31923 -1 31924 -1 31925 -1 31926 -1 31927 -1 31928 -1 31929 -1 31930 -1 31931 -1 31932 -1 31933 -1 31934 -1 31935 -1 31936 -1 31937 -1 31938 -1 31939 -1 31940 -1 31941 -1 31942 -1 31943 -1 31944 -1 31945 -1 31946 -1 31947 -1 31948 -1 31949 -1 31950 -1 31951 -1 31952 -1 31953 -1 31954 -1 31955 -1 31956 -1 31957 -1 31958 -1 31959 -1 31960 -1 31961 -1 31962 -1 31963 -1 31964 -1 31965 -1 31966 -1 31967 -1 31968 -1 31969 -1 31970 -1 31971 -1 31972 -1 31973 -1 31974 -1 31975 -1 31976 -1 31977 -1 31978 -1 31979 -1 31980 -1 31981 -1 31982 -1 31983 -1 31984 -1 31985 -1 31986 -1 31987 -1 31988 -1 31989 -1 31990 -1 31991 -1 31992 -1 31993 -1 31994 -1 31995 -1 31996 -1 31997 -1 31998 -1 31999 -1 32000 -1 32001 -1 32002 -1 32003 -1 32004 -1 32005 -1 32006 -1 32007 -1 32008 -1 32009 -1 32010 -1 32011 -1 32012 -1 32013 -1 32014 -1 32015 -1 32016 -1 32017 -1 32018 -1 32019 -1 32020 -1 32021 -1 32022 -1 32023 -1 32024 -1 32025 -1 32026 -1 32027 -1 32028 -1 32029 -1 32030 -1 32031 -1 32032 -1 32033 -1 32034 -1 32035 -1 32036 -1 32037 -1 32038 -1 32039 -1 32040 -1 32041 -1 32042 -1 32043 -1 32044 -1 32045 -1 32046 -1 32047 -1 32048 -1 32049 -1 32050 -1 32051 -1 32052 -1 32053 -1 32054 -1 32055 -1 32056 -1 32057 -1 32058 -1 32059 -1 32060 -1 32061 -1 32062 -1 32063 -1 32064 -1 32065 -1 32066 -1 32067 -1 32068 -1 32069 -1 32070 -1 32071 -1 32072 -1 32073 -1 32074 -1 32075 -1 32076 -1 32077 -1 32078 -1 32079 -1 32080 -1 32081 -1 32082 -1 32083 -1 32084 -1 32085 -1 32086 -1 32087 -1 32088 -1 32089 -1 32090 -1 32091 -1 32092 -1 32093 -1 32094 -1 32095 -1 32096 -1 32097 -1 32098 -1 32099 -1 32100 -1 32101 -1 32102 -1 32103 -1 32104 -1 32105 -1 32106 -1 32107 -1 32108 -1 32109 -1 32110 -1 32111 -1 32112 -1 32113 -1 32114 -1 32115 -1 32116 -1 32117 -1 32118 -1 32119 -1 32120 -1 32121 -1 32122 -1 32123 -1 32124 -1 32125 -1 32126 -1 32127 -1 32128 -1 32129 -1 32130 -1 32131 -1 32132 -1 32133 -1 32134 -1 32135 -1 32136 -1 32137 -1 32138 -1 32139 -1 32140 -1 32141 -1 32142 -1 32143 -1 32144 -1 32145 -1 32146 -1 32147 -1 32148 -1 32149 -1 32150 -1 32151 -1 32152 -1 32153 -1 32154 -1 32155 -1 32156 -1 32157 -1 32158 -1 32159 -1 32160 -1 32161 -1 32162 -1 32163 -1 32164 -1 32165 -1 32166 -1 32167 -1 32168 -1 32169 -1 32170 -1 32171 -1 32172 -1 32173 -1 32174 -1 32175 -1 32176 -1 32177 -1 32178 -1 32179 -1 32180 -1 32181 -1 32182 -1 32183 -1 32184 -1 32185 -1 32186 -1 32187 -1 32188 -1 32189 -1 32190 -1 32191 -1 32192 -1 32193 -1 32194 -1 32195 -1 32196 -1 32197 -1 32198 -1 32199 -1 32200 -1 32201 -1 32202 -1 32203 -1 32204 -1 32205 -1 32206 -1 32207 -1 32208 -1 32209 -1 32210 -1 32211 -1 32212 -1 32213 -1 32214 -1 32215 -1 32216 -1 32217 -1 32218 -1 32219 -1 32220 -1 32221 -1 32222 -1 32223 -1 32224 -1 32225 -1 32226 -1 32227 -1 32228 -1 32229 -1 32230 -1 32231 -1 32232 -1 32233 -1 32234 -1 32235 -1 32236 -1 32237 -1 32238 -1 32239 -1 32240 -1 32241 -1 32242 -1 32243 -1 32244 -1 32245 -1 32246 -1 32247 -1 32248 -1 32249 -1 32250 -1 32251 -1 32252 -1 32253 -1 32254 -1 32255 -1 32256 -1 32257 -1 32258 -1 32259 -1 32260 -1 32261 -1 32262 -1 32263 -1 32264 -1 32265 -1 32266 -1 32267 -1 32268 -1 32269 -1 32270 -1 32271 -1 32272 -1 32273 -1 32274 -1 32275 -1 32276 -1 32277 -1 32278 -1 32279 -1 32280 -1 32281 -1 32282 -1 32283 -1 32284 -1 32285 -1 32286 -1 32287 -1 32288 -1 32289 -1 32290 -1 32291 -1 32292 -1 32293 -1 32294 -1 32295 -1 32296 -1 32297 -1 32298 -1 32299 -1 32300 -1 32301 -1 32302 -1 32303 -1 32304 -1 32305 -1 32306 -1 32307 -1 32308 -1 32309 -1 32310 -1 32311 -1 32312 -1 32313 -1 32314 -1 32315 -1 32316 -1 32317 -1 32318 -1 32319 -1 32320 -1 32321 -1 32322 -1 32323 -1 32324 -1 32325 -1 32326 -1 32327 -1 32328 -1 32329 -1 32330 -1 32331 -1 32332 -1 32333 -1 32334 -1 32335 -1 32336 -1 32337 -1 32338 -1 32339 -1 32340 -1 32341 -1 32342 -1 32343 -1 32344 -1 32345 -1 32346 -1 32347 -1 32348 -1 32349 -1 32350 -1 32351 -1 32352 -1 32353 -1 32354 -1 32355 -1 32356 -1 32357 -1 32358 -1 32359 -1 32360 -1 32361 -1 32362 -1 32363 -1 32364 -1 32365 -1 32366 -1 32367 -1 32368 -1 32369 -1 32370 -1 32371 -1 32372 -1 32373 -1 32374 -1 32375 -1 32376 -1 32377 -1 32378 -1 32379 -1 32380 -1 32381 -1 32382 -1 32383 -1 32384 -1 32385 -1 32386 -1 32387 -1 32388 -1 32389 -1 32390 -1 32391 -1 32392 -1 32393 -1 32394 -1 32395 -1 32396 -1 32397 -1 32398 -1 32399 -1 32400 -1 32401 -1 32402 -1 32403 -1 32404 -1 32405 -1 32406 -1 32407 -1 32408 -1 32409 -1 32410 -1 32411 -1 32412 -1 32413 -1 32414 -1 32415 -1 32416 -1 32417 -1 32418 -1 32419 -1 32420 -1 32421 -1 32422 -1 32423 -1 32424 -1 32425 -1 32426 -1 32427 -1 32428 -1 32429 -1 32430 -1 32431 -1 32432 -1 32433 -1 32434 -1 32435 -1 32436 -1 32437 -1 32438 -1 32439 -1 32440 -1 32441 -1 32442 -1 32443 -1 32444 -1 32445 -1 32446 -1 32447 -1 32448 -1 32449 -1 32450 -1 32451 -1 32452 -1 32453 -1 32454 -1 32455 -1 32456 -1 32457 -1 32458 -1 32459 -1 32460 -1 32461 -1 32462 -1 32463 -1 32464 -1 32465 -1 32466 -1 32467 -1 32468 -1 32469 -1 32470 -1 32471 -1 32472 -1 32473 -1 32474 -1 32475 -1 32476 -1 32477 -1 32478 -1 32479 -1 32480 -1 32481 -1 32482 -1 32483 -1 32484 -1 32485 -1 32486 -1 32487 -1 32488 -1 32489 -1 32490 -1 32491 -1 32492 -1 32493 -1 32494 -1 32495 -1 32496 -1 32497 -1 32498 -1 32499 -1 32500 -1 32501 -1 32502 -1 32503 -1 32504 -1 32505 -1 32506 -1 32507 -1 32508 -1 32509 -1 32510 -1 32511 -1 32512 -1 32513 -1 32514 -1 32515 -1 32516 -1 32517 -1 32518 -1 32519 -1 32520 -1 32521 -1 32522 -1 32523 -1 32524 -1 32525 -1 32526 -1 32527 -1 32528 -1 32529 -1 32530 -1 32531 -1 32532 -1 32533 -1 32534 -1 32535 -1 32536 -1 32537 -1 32538 -1 32539 -1 32540 -1 32541 -1 32542 -1 32543 -1 32544 -1 32545 -1 32546 -1 32547 -1 32548 -1 32549 -1 32550 -1 32551 -1 32552 -1 32553 -1 32554 -1 32555 -1 32556 -1 32557 -1 32558 -1 32559 -1 32560 -1 32561 -1 32562 -1 32563 -1 32564 -1 32565 -1 32566 -1 32567 -1 32568 -1 32569 -1 32570 -1 32571 -1 32572 -1 32573 -1 32574 -1 32575 -1 32576 -1 32577 -1 32578 -1 32579 -1 32580 -1 32581 -1 32582 -1 32583 -1 32584 -1 32585 -1 32586 -1 32587 -1 32588 -1 32589 -1 32590 -1 32591 -1 32592 -1 32593 -1 32594 -1 32595 -1 32596 -1 32597 -1 32598 -1 32599 -1 32600 -1 32601 -1 32602 -1 32603 -1 32604 -1 32605 -1 32606 -1 32607 -1 32608 -1 32609 -1 32610 -1 32611 -1 32612 -1 32613 -1 32614 -1 32615 -1 32616 -1 32617 -1 32618 -1 32619 -1 32620 -1 32621 -1 32622 -1 32623 -1 32624 -1 32625 -1 32626 -1 32627 -1 32628 -1 32629 -1 32630 -1 32631 -1 32632 -1 32633 -1 32634 -1 32635 -1 32636 -1 32637 -1 32638 -1 32639 -1 32640 -1 32641 -1 32642 -1 32643 -1 32644 -1 32645 -1 32646 -1 32647 -1 32648 -1 32649 -1 32650 -1 32651 -1 32652 -1 32653 -1 32654 -1 32655 -1 32656 -1 32657 -1 32658 -1 32659 -1 32660 -1 32661 -1 32662 -1 32663 -1 32664 -1 32665 -1 32666 -1 32667 -1 32668 -1 32669 -1 32670 -1 32671 -1 32672 -1 32673 -1 32674 -1 32675 -1 32676 -1 32677 -1 32678 -1 32679 -1 32680 -1 32681 -1 32682 -1 32683 -1 32684 -1 32685 -1 32686 -1 32687 -1 32688 -1 32689 -1 32690 -1 32691 -1 32692 -1 32693 -1 32694 -1 32695 -1 32696 -1 32697 -1 32698 -1 32699 -1 32700 -1 32701 -1 32702 -1 32703 -1 32704 -1 32705 -1 32706 -1 32707 -1 32708 -1 32709 -1 32710 -1 32711 -1 32712 -1 32713 -1 32714 -1 32715 -1 32716 -1 32717 -1 32718 -1 32719 -1 32720 -1 32721 -1 32722 -1 32723 -1 32724 -1 32725 -1 32726 -1 32727 -1 32728 -1 32729 -1 32730 -1 32731 -1 32732 -1 32733 -1 32734 -1 32735 -1 32736 -1 32737 -1 32738 -1 32739 -1 32740 -1 32741 -1 32742 -1 32743 -1 32744 -1 32745 -1 32746 -1 32747 -1 32748 -1 32749 -1 32750 -1 32751 -1 32752 -1 32753 -1 32754 -1 32755 -1 32756 -1 32757 -1 32758 -1 32759 -1 32760 -1 32761 -1 32762 -1 32763 -1 32764 -1 32765 -1 32766 -1 32767 -1 32768 -1 32769 -1 32770 -1 32771 -1 32772 -1 32773 -1 32774 -1 32775 -1 32776 -1 32777 -1 32778 -1 32779 -1 32780 -1 32781 -1 32782 -1 32783 -1 32784 -1 32785 -1 32786 -1 32787 -1 32788 -1 32789 -1 32790 -1 32791 -1 32792 -1 32793 -1 32794 -1 32795 -1 32796 -1 32797 -1 32798 -1 32799 -1 32800 -1 32801 -1 32802 -1 32803 -1 32804 -1 32805 -1 32806 -1 32807 -1 32808 -1 32809 -1 32810 -1 32811 -1 32812 -1 32813 -1 32814 -1 32815 -1 32816 -1 32817 -1 32818 -1 32819 -1 32820 -1 32821 -1 32822 -1 32823 -1 32824 -1 32825 -1 32826 -1 32827 -1 32828 -1 32829 -1 32830 -1 32831 -1 32832 -1 32833 -1 32834 -1 32835 -1 32836 -1 32837 -1 32838 -1 32839 -1 32840 -1 32841 -1 32842 -1 32843 -1 32844 -1 32845 -1 32846 -1 32847 -1 32848 -1 32849 -1 32850 -1 32851 -1 32852 -1 32853 -1 32854 -1 32855 -1 32856 -1 32857 -1 32858 -1 32859 -1 32860 -1 32861 -1 32862 -1 32863 -1 32864 -1 32865 -1 32866 -1 32867 -1 32868 -1 32869 -1 32870 -1 32871 -1 32872 -1 32873 -1 32874 -1 32875 -1 32876 -1 32877 -1 32878 -1 32879 -1 32880 -1 32881 -1 32882 -1 32883 -1 32884 -1 32885 -1 32886 -1 32887 -1 32888 -1 32889 -1 32890 -1 32891 -1 32892 -1 32893 -1 32894 -1 32895 -1 32896 -1 32897 -1 32898 -1 32899 -1 32900 -1 32901 -1 32902 -1 32903 -1 32904 -1 32905 -1 32906 -1 32907 -1 32908 -1 32909 -1 32910 -1 32911 -1 32912 -1 32913 -1 32914 -1 32915 -1 32916 -1 32917 -1 32918 -1 32919 -1 32920 -1 32921 -1 32922 -1 32923 -1 32924 -1 32925 -1 32926 -1 32927 -1 32928 -1 32929 -1 32930 -1 32931 -1 32932 -1 32933 -1 32934 -1 32935 -1 32936 -1 32937 -1 32938 -1 32939 -1 32940 -1 32941 -1 32942 -1 32943 -1 32944 -1 32945 -1 32946 -1 32947 -1 32948 -1 32949 -1 32950 -1 32951 -1 32952 -1 32953 -1 32954 -1 32955 -1 32956 -1 32957 -1 32958 -1 32959 -1 32960 -1 32961 -1 32962 -1 32963 -1 32964 -1 32965 -1 32966 -1 32967 -1 32968 -1 32969 -1 32970 -1 32971 -1 32972 -1 32973 -1 32974 -1 32975 -1 32976 -1 32977 -1 32978 -1 32979 -1 32980 -1 32981 -1 32982 -1 32983 -1 32984 -1 32985 -1 32986 -1 32987 -1 32988 -1 32989 -1 32990 -1 32991 -1 32992 -1 32993 -1 32994 -1 32995 -1 32996 -1 32997 -1 32998 -1 32999 -1 33000 -1 33001 -1 33002 -1 33003 -1 33004 -1 33005 -1 33006 -1 33007 -1 33008 -1 33009 -1 33010 -1 33011 -1 33012 -1 33013 -1 33014 -1 33015 -1 33016 -1 33017 -1 33018 -1 33019 -1 33020 -1 33021 -1 33022 -1 33023 -1 33024 -1 33025 -1 33026 -1 33027 -1 33028 -1 33029 -1 33030 -1 33031 -1 33032 -1 33033 -1 33034 -1 33035 -1 33036 -1 33037 -1 33038 -1 33039 -1 33040 -1 33041 -1 33042 -1 33043 -1 33044 -1 33045 -1 33046 -1 33047 -1 33048 -1 33049 -1 33050 -1 33051 -1 33052 -1 33053 -1 33054 -1 33055 -1 33056 -1 33057 -1 33058 -1 33059 -1 33060 -1 33061 -1 33062 -1 33063 -1 33064 -1 33065 -1 33066 -1 33067 -1 33068 -1 33069 -1 33070 -1 33071 -1 33072 -1 33073 -1 33074 -1 33075 -1 33076 -1 33077 -1 33078 -1 33079 -1 33080 -1 33081 -1 33082 -1 33083 -1 33084 -1 33085 -1 33086 -1 33087 -1 33088 -1 33089 -1 33090 -1 33091 -1 33092 -1 33093 -1 33094 -1 33095 -1 33096 -1 33097 -1 33098 -1 33099 -1 33100 -1 33101 -1 33102 -1 33103 -1 33104 -1 33105 -1 33106 -1 33107 -1 33108 -1 33109 -1 33110 -1 33111 -1 33112 -1 33113 -1 33114 -1 33115 -1 33116 -1 33117 -1 33118 -1 33119 -1 33120 -1 33121 -1 33122 -1 33123 -1 33124 -1 33125 -1 33126 -1 33127 -1 33128 -1 33129 -1 33130 -1 33131 -1 33132 -1 33133 -1 33134 -1 33135 -1 33136 -1 33137 -1 33138 -1 33139 -1 33140 -1 33141 -1 33142 -1 33143 -1 33144 -1 33145 -1 33146 -1 33147 -1 33148 -1 33149 -1 33150 -1 33151 -1 33152 -1 33153 -1 33154 -1 33155 -1 33156 -1 33157 -1 33158 -1 33159 -1 33160 -1 33161 -1 33162 -1 33163 -1 33164 -1 33165 -1 33166 -1 33167 -1 33168 -1 33169 -1 33170 -1 33171 -1 33172 -1 33173 -1 33174 -1 33175 -1 33176 -1 33177 -1 33178 -1 33179 -1 33180 -1 33181 -1 33182 -1 33183 -1 33184 -1 33185 -1 33186 -1 33187 -1 33188 -1 33189 -1 33190 -1 33191 -1 33192 -1 33193 -1 33194 -1 33195 -1 33196 -1 33197 -1 33198 -1 33199 -1 33200 -1 33201 -1 33202 -1 33203 -1 33204 -1 33205 -1 33206 -1 33207 -1 33208 -1 33209 -1 33210 -1 33211 -1 33212 -1 33213 -1 33214 -1 33215 -1 33216 -1 33217 -1 33218 -1 33219 -1 33220 -1 33221 -1 33222 -1 33223 -1 33224 -1 33225 -1 33226 -1 33227 -1 33228 -1 33229 -1 33230 -1 33231 -1 33232 -1 33233 -1 33234 -1 33235 -1 33236 -1 33237 -1 33238 -1 33239 -1 33240 -1 33241 -1 33242 -1 33243 -1 33244 -1 33245 -1 33246 -1 33247 -1 33248 -1 33249 -1 33250 -1 33251 -1 33252 -1 33253 -1 33254 -1 33255 -1 33256 -1 33257 -1 33258 -1 33259 -1 33260 -1 33261 -1 33262 -1 33263 -1 33264 -1 33265 -1 33266 -1 33267 -1 33268 -1 33269 -1 33270 -1 33271 -1 33272 -1 33273 -1 33274 -1 33275 -1 33276 -1 33277 -1 33278 -1 33279 -1 33280 -1 33281 -1 33282 -1 33283 -1 33284 -1 33285 -1 33286 -1 33287 -1 33288 -1 33289 -1 33290 -1 33291 -1 33292 -1 33293 -1 33294 -1 33295 -1 33296 -1 33297 -1 33298 -1 33299 -1 33300 -1 33301 -1 33302 -1 33303 -1 33304 -1 33305 -1 33306 -1 33307 -1 33308 -1 33309 -1 33310 -1 33311 -1 33312 -1 33313 -1 33314 -1 33315 -1 33316 -1 33317 -1 33318 -1 33319 -1 33320 -1 33321 -1 33322 -1 33323 -1 33324 -1 33325 -1 33326 -1 33327 -1 33328 -1 33329 -1 33330 -1 33331 -1 33332 -1 33333 -1 33334 -1 33335 -1 33336 -1 33337 -1 33338 -1 33339 -1 33340 -1 33341 -1 33342 -1 33343 -1 33344 -1 33345 -1 33346 -1 33347 -1 33348 -1 33349 -1 33350 -1 33351 -1 33352 -1 33353 -1 33354 -1 33355 -1 33356 -1 33357 -1 33358 -1 33359 -1 33360 -1 33361 -1 33362 -1 33363 -1 33364 -1 33365 -1 33366 -1 33367 -1 33368 -1 33369 -1 33370 -1 33371 -1 33372 -1 33373 -1 33374 -1 33375 -1 33376 -1 33377 -1 33378 -1 33379 -1 33380 -1 33381 -1 33382 -1 33383 -1 33384 -1 33385 -1 33386 -1 33387 -1 33388 -1 33389 -1 33390 -1 33391 -1 33392 -1 33393 -1 33394 -1 33395 -1 33396 -1 33397 -1 33398 -1 33399 -1 33400 -1 33401 -1 33402 -1 33403 -1 33404 -1 33405 -1 33406 -1 33407 -1 33408 -1 33409 -1 33410 -1 33411 -1 33412 -1 33413 -1 33414 -1 33415 -1 33416 -1 33417 -1 33418 -1 33419 -1 33420 -1 33421 -1 33422 -1 33423 -1 33424 -1 33425 -1 33426 -1 33427 -1 33428 -1 33429 -1 33430 -1 33431 -1 33432 -1 33433 -1 33434 -1 33435 -1 33436 -1 33437 -1 33438 -1 33439 -1 33440 -1 33441 -1 33442 -1 33443 -1 33444 -1 33445 -1 33446 -1 33447 -1 33448 -1 33449 -1 33450 -1 33451 -1 33452 -1 33453 -1 33454 -1 33455 -1 33456 -1 33457 -1 33458 -1 33459 -1 33460 -1 33461 -1 33462 -1 33463 -1 33464 -1 33465 -1 33466 -1 33467 -1 33468 -1 33469 -1 33470 -1 33471 -1 33472 -1 33473 -1 33474 -1 33475 -1 33476 -1 33477 -1 33478 -1 33479 -1 33480 -1 33481 -1 33482 -1 33483 -1 33484 -1 33485 -1 33486 -1 33487 -1 33488 -1 33489 -1 33490 -1 33491 -1 33492 -1 33493 -1 33494 -1 33495 -1 33496 -1 33497 -1 33498 -1 33499 -1 33500 -1 33501 -1 33502 -1 33503 -1 33504 -1 33505 -1 33506 -1 33507 -1 33508 -1 33509 -1 33510 -1 33511 -1 33512 -1 33513 -1 33514 -1 33515 -1 33516 -1 33517 -1 33518 -1 33519 -1 33520 -1 33521 -1 33522 -1 33523 -1 33524 -1 33525 -1 33526 -1 33527 -1 33528 -1 33529 -1 33530 -1 33531 -1 33532 -1 33533 -1 33534 -1 33535 -1 33536 -1 33537 -1 33538 -1 33539 -1 33540 -1 33541 -1 33542 -1 33543 -1 33544 -1 33545 -1 33546 -1 33547 -1 33548 -1 33549 -1 33550 -1 33551 -1 33552 -1 33553 -1 33554 -1 33555 -1 33556 -1 33557 -1 33558 -1 33559 -1 33560 -1 33561 -1 33562 -1 33563 -1 33564 -1 33565 -1 33566 -1 33567 -1 33568 -1 33569 -1 33570 -1 33571 -1 33572 -1 33573 -1 33574 -1 33575 -1 33576 -1 33577 -1 33578 -1 33579 -1 33580 -1 33581 -1 33582 -1 33583 -1 33584 -1 33585 -1 33586 -1 33587 -1 33588 -1 33589 -1 33590 -1 33591 -1 33592 -1 33593 -1 33594 -1 33595 -1 33596 -1 33597 -1 33598 -1 33599 -1 33600 -1 33601 -1 33602 -1 33603 -1 33604 -1 33605 -1 33606 -1 33607 -1 33608 -1 33609 -1 33610 -1 33611 -1 33612 -1 33613 -1 33614 -1 33615 -1 33616 -1 33617 -1 33618 -1 33619 -1 33620 -1 33621 -1 33622 -1 33623 -1 33624 -1 33625 -1 33626 -1 33627 -1 33628 -1 33629 -1 33630 -1 33631 -1 33632 -1 33633 -1 33634 -1 33635 -1 33636 -1 33637 -1 33638 -1 33639 -1 33640 -1 33641 -1 33642 -1 33643 -1 33644 -1 33645 -1 33646 -1 33647 -1 33648 -1 33649 -1 33650 -1 33651 -1 33652 -1 33653 -1 33654 -1 33655 -1 33656 -1 33657 -1 33658 -1 33659 -1 33660 -1 33661 -1 33662 -1 33663 -1 33664 -1 33665 -1 33666 -1 33667 -1 33668 -1 33669 -1 33670 -1 33671 -1 33672 -1 33673 -1 33674 -1 33675 -1 33676 -1 33677 -1 33678 -1 33679 -1 33680 -1 33681 -1 33682 -1 33683 -1 33684 -1 33685 -1 33686 -1 33687 -1 33688 -1 33689 -1 33690 -1 33691 -1 33692 -1 33693 -1 33694 -1 33695 -1 33696 -1 33697 -1 33698 -1 33699 -1 33700 -1 33701 -1 33702 -1 33703 -1 33704 -1 33705 -1 33706 -1 33707 -1 33708 -1 33709 -1 33710 -1 33711 -1 33712 -1 33713 -1 33714 -1 33715 -1 33716 -1 33717 -1 33718 -1 33719 -1 33720 -1 33721 -1 33722 -1 33723 -1 33724 -1 33725 -1 33726 -1 33727 -1 33728 -1 33729 -1 33730 -1 33731 -1 33732 -1 33733 -1 33734 -1 33735 -1 33736 -1 33737 -1 33738 -1 33739 -1 33740 -1 33741 -1 33742 -1 33743 -1 33744 -1 33745 -1 33746 -1 33747 -1 33748 -1 33749 -1 33750 -1 33751 -1 33752 -1 33753 -1 33754 -1 33755 -1 33756 -1 33757 -1 33758 -1 33759 -1 33760 -1 33761 -1 33762 -1 33763 -1 33764 -1 33765 -1 33766 -1 33767 -1 33768 -1 33769 -1 33770 -1 33771 -1 33772 -1 33773 -1 33774 -1 33775 -1 33776 -1 33777 -1 33778 -1 33779 -1 33780 -1 33781 -1 33782 -1 33783 -1 33784 -1 33785 -1 33786 -1 33787 -1 33788 -1 33789 -1 33790 -1 33791 -1 33792 -1 33793 -1 33794 -1 33795 -1 33796 -1 33797 -1 33798 -1 33799 -1 33800 -1 33801 -1 33802 -1 33803 -1 33804 -1 33805 -1 33806 -1 33807 -1 33808 -1 33809 -1 33810 -1 33811 -1 33812 -1 33813 -1 33814 -1 33815 -1 33816 -1 33817 -1 33818 -1 33819 -1 33820 -1 33821 -1 33822 -1 33823 -1 33824 -1 33825 -1 33826 -1 33827 -1 33828 -1 33829 -1 33830 -1 33831 -1 33832 -1 33833 -1 33834 -1 33835 -1 33836 -1 33837 -1 33838 -1 33839 -1 33840 -1 33841 -1 33842 -1 33843 -1 33844 -1 33845 -1 33846 -1 33847 -1 33848 -1 33849 -1 33850 -1 33851 -1 33852 -1 33853 -1 33854 -1 33855 -1 33856 -1 33857 -1 33858 -1 33859 -1 33860 -1 33861 -1 33862 -1 33863 -1 33864 -1 33865 -1 33866 -1 33867 -1 33868 -1 33869 -1 33870 -1 33871 -1 33872 -1 33873 -1 33874 -1 33875 -1 33876 -1 33877 -1 33878 -1 33879 -1 33880 -1 33881 -1 33882 -1 33883 -1 33884 -1 33885 -1 33886 -1 33887 -1 33888 -1 33889 -1 33890 -1 33891 -1 33892 -1 33893 -1 33894 -1 33895 -1 33896 -1 33897 -1 33898 -1 33899 -1 33900 -1 33901 -1 33902 -1 33903 -1 33904 -1 33905 -1 33906 -1 33907 -1 33908 -1 33909 -1 33910 -1 33911 -1 33912 -1 33913 -1 33914 -1 33915 -1 33916 -1 33917 -1 33918 -1 33919 -1 33920 -1 33921 -1 33922 -1 33923 -1 33924 -1 33925 -1 33926 -1 33927 -1 33928 -1 33929 -1 33930 -1 33931 -1 33932 -1 33933 -1 33934 -1 33935 -1 33936 -1 33937 -1 33938 -1 33939 -1 33940 -1 33941 -1 33942 -1 33943 -1 33944 -1 33945 -1 33946 -1 33947 -1 33948 -1 33949 -1 33950 -1 33951 -1 33952 -1 33953 -1 33954 -1 33955 -1 33956 -1 33957 -1 33958 -1 33959 -1 33960 -1 33961 -1 33962 -1 33963 -1 33964 -1 33965 -1 33966 -1 33967 -1 33968 -1 33969 -1 33970 -1 33971 -1 33972 -1 33973 -1 33974 -1 33975 -1 33976 -1 33977 -1 33978 -1 33979 -1 33980 -1 33981 -1 33982 -1 33983 -1 33984 -1 33985 -1 33986 -1 33987 -1 33988 -1 33989 -1 33990 -1 33991 -1 33992 -1 33993 -1 33994 -1 33995 -1 33996 -1 33997 -1 33998 -1 33999 -1 34000 -1 34001 -1 34002 -1 34003 -1 34004 -1 34005 -1 34006 -1 34007 -1 34008 -1 34009 -1 34010 -1 34011 -1 34012 -1 34013 -1 34014 -1 34015 -1 34016 -1 34017 -1 34018 -1 34019 -1 34020 -1 34021 -1 34022 -1 34023 -1 34024 -1 34025 -1 34026 -1 34027 -1 34028 -1 34029 -1 34030 -1 34031 -1 34032 -1 34033 -1 34034 -1 34035 -1 34036 -1 34037 -1 34038 -1 34039 -1 34040 -1 34041 -1 34042 -1 34043 -1 34044 -1 34045 -1 34046 -1 34047 -1 34048 -1 34049 -1 34050 -1 34051 -1 34052 -1 34053 -1 34054 -1 34055 -1 34056 -1 34057 -1 34058 -1 34059 -1 34060 -1 34061 -1 34062 -1 34063 -1 34064 -1 34065 -1 34066 -1 34067 -1 34068 -1 34069 -1 34070 -1 34071 -1 34072 -1 34073 -1 34074 -1 34075 -1 34076 -1 34077 -1 34078 -1 34079 -1 34080 -1 34081 -1 34082 -1 34083 -1 34084 -1 34085 -1 34086 -1 34087 -1 34088 -1 34089 -1 34090 -1 34091 -1 34092 -1 34093 -1 34094 -1 34095 -1 34096 -1 34097 -1 34098 -1 34099 -1 34100 -1 34101 -1 34102 -1 34103 -1 34104 -1 34105 -1 34106 -1 34107 -1 34108 -1 34109 -1 34110 -1 34111 -1 34112 -1 34113 -1 34114 -1 34115 -1 34116 -1 34117 -1 34118 -1 34119 -1 34120 -1 34121 -1 34122 -1 34123 -1 34124 -1 34125 -1 34126 -1 34127 -1 34128 -1 34129 -1 34130 -1 34131 -1 34132 -1 34133 -1 34134 -1 34135 -1 34136 -1 34137 -1 34138 -1 34139 -1 34140 -1 34141 -1 34142 -1 34143 -1 34144 -1 34145 -1 34146 -1 34147 -1 34148 -1 34149 -1 34150 -1 34151 -1 34152 -1 34153 -1 34154 -1 34155 -1 34156 -1 34157 -1 34158 -1 34159 -1 34160 -1 34161 -1 34162 -1 34163 -1 34164 -1 34165 -1 34166 -1 34167 -1 34168 -1 34169 -1 34170 -1 34171 -1 34172 -1 34173 -1 34174 -1 34175 -1 34176 -1 34177 -1 34178 -1 34179 -1 34180 -1 34181 -1 34182 -1 34183 -1 34184 -1 34185 -1 34186 -1 34187 -1 34188 -1 34189 -1 34190 -1 34191 -1 34192 -1 34193 -1 34194 -1 34195 -1 34196 -1 34197 -1 34198 -1 34199 -1 34200 -1 34201 -1 34202 -1 34203 -1 34204 -1 34205 -1 34206 -1 34207 -1 34208 -1 34209 -1 34210 -1 34211 -1 34212 -1 34213 -1 34214 -1 34215 -1 34216 -1 34217 -1 34218 -1 34219 -1 34220 -1 34221 -1 34222 -1 34223 -1 34224 -1 34225 -1 34226 -1 34227 -1 34228 -1 34229 -1 34230 -1 34231 -1 34232 -1 34233 -1 34234 -1 34235 -1 34236 -1 34237 -1 34238 -1 34239 -1 34240 -1 34241 -1 34242 -1 34243 -1 34244 -1 34245 -1 34246 -1 34247 -1 34248 -1 34249 -1 34250 -1 34251 -1 34252 -1 34253 -1 34254 -1 34255 -1 34256 -1 34257 -1 34258 -1 34259 -1 34260 -1 34261 -1 34262 -1 34263 -1 34264 -1 34265 -1 34266 -1 34267 -1 34268 -1 34269 -1 34270 -1 34271 -1 34272 -1 34273 -1 34274 -1 34275 -1 34276 -1 34277 -1 34278 -1 34279 -1 34280 -1 34281 -1 34282 -1 34283 -1 34284 -1 34285 -1 34286 -1 34287 -1 34288 -1 34289 -1 34290 -1 34291 -1 34292 -1 34293 -1 34294 -1 34295 -1 34296 -1 34297 -1 34298 -1 34299 -1 34300 -1 34301 -1 34302 -1 34303 -1 34304 -1 34305 -1 34306 -1 34307 -1 34308 -1 34309 -1 34310 -1 34311 -1 34312 -1 34313 -1 34314 -1 34315 -1 34316 -1 34317 -1 34318 -1 34319 -1 34320 -1 34321 -1 34322 -1 34323 -1 34324 -1 34325 -1 34326 -1 34327 -1 34328 -1 34329 -1 34330 -1 34331 -1 34332 -1 34333 -1 34334 -1 34335 -1 34336 -1 34337 -1 34338 -1 34339 -1 34340 -1 34341 -1 34342 -1 34343 -1 34344 -1 34345 -1 34346 -1 34347 -1 34348 -1 34349 -1 34350 -1 34351 -1 34352 -1 34353 -1 34354 -1 34355 -1 34356 -1 34357 -1 34358 -1 34359 -1 34360 -1 34361 -1 34362 -1 34363 -1 34364 -1 34365 -1 34366 -1 34367 -1 34368 -1 34369 -1 34370 -1 34371 -1 34372 -1 34373 -1 34374 -1 34375 -1 34376 -1 34377 -1 34378 -1 34379 -1 34380 -1 34381 -1 34382 -1 34383 -1 34384 -1 34385 -1 34386 -1 34387 -1 34388 -1 34389 -1 34390 -1 34391 -1 34392 -1 34393 -1 34394 -1 34395 -1 34396 -1 34397 -1 34398 -1 34399 -1 34400 -1 34401 -1 34402 -1 34403 -1 34404 -1 34405 -1 34406 -1 34407 -1 34408 -1 34409 -1 34410 -1 34411 -1 34412 -1 34413 -1 34414 -1 34415 -1 34416 -1 34417 -1 34418 -1 34419 -1 34420 -1 34421 -1 34422 -1 34423 -1 34424 -1 34425 -1 34426 -1 34427 -1 34428 -1 34429 -1 34430 -1 34431 -1 34432 -1 34433 -1 34434 -1 34435 -1 34436 -1 34437 -1 34438 -1 34439 -1 34440 -1 34441 -1 34442 -1 34443 -1 34444 -1 34445 -1 34446 -1 34447 -1 34448 -1 34449 -1 34450 -1 34451 -1 34452 -1 34453 -1 34454 -1 34455 -1 34456 -1 34457 -1 34458 -1 34459 -1 34460 -1 34461 -1 34462 -1 34463 -1 34464 -1 34465 -1 34466 -1 34467 -1 34468 -1 34469 -1 34470 -1 34471 -1 34472 -1 34473 -1 34474 -1 34475 -1 34476 -1 34477 -1 34478 -1 34479 -1 34480 -1 34481 -1 34482 -1 34483 -1 34484 -1 34485 -1 34486 -1 34487 -1 34488 -1 34489 -1 34490 -1 34491 -1 34492 -1 34493 -1 34494 -1 34495 -1 34496 -1 34497 -1 34498 -1 34499 -1 34500 -1 34501 -1 34502 -1 34503 -1 34504 -1 34505 -1 34506 -1 34507 -1 34508 -1 34509 -1 34510 -1 34511 -1 34512 -1 34513 -1 34514 -1 34515 -1 34516 -1 34517 -1 34518 -1 34519 -1 34520 -1 34521 -1 34522 -1 34523 -1 34524 -1 34525 -1 34526 -1 34527 -1 34528 -1 34529 -1 34530 -1 34531 -1 34532 -1 34533 -1 34534 -1 34535 -1 34536 -1 34537 -1 34538 -1 34539 -1 34540 -1 34541 -1 34542 -1 34543 -1 34544 -1 34545 -1 34546 -1 34547 -1 34548 -1 34549 -1 34550 -1 34551 -1 34552 -1 34553 -1 34554 -1 34555 -1 34556 -1 34557 -1 34558 -1 34559 -1 34560 -1 34561 -1 34562 -1 34563 -1 34564 -1 34565 -1 34566 -1 34567 -1 34568 -1 34569 -1 34570 -1 34571 -1 34572 -1 34573 -1 34574 -1 34575 -1 34576 -1 34577 -1 34578 -1 34579 -1 34580 -1 34581 -1 34582 -1 34583 -1 34584 -1 34585 -1 34586 -1 34587 -1 34588 -1 34589 -1 34590 -1 34591 -1 34592 -1 34593 -1 34594 -1 34595 -1 34596 -1 34597 -1 34598 -1 34599 -1 34600 -1 34601 -1 34602 -1 34603 -1 34604 -1 34605 -1 34606 -1 34607 -1 34608 -1 34609 -1 34610 -1 34611 -1 34612 -1 34613 -1 34614 -1 34615 -1 34616 -1 34617 -1 34618 -1 34619 -1 34620 -1 34621 -1 34622 -1 34623 -1 34624 -1 34625 -1 34626 -1 34627 -1 34628 -1 34629 -1 34630 -1 34631 -1 34632 -1 34633 -1 34634 -1 34635 -1 34636 -1 34637 -1 34638 -1 34639 -1 34640 -1 34641 -1 34642 -1 34643 -1 34644 -1 34645 -1 34646 -1 34647 -1 34648 -1 34649 -1 34650 -1 34651 -1 34652 -1 34653 -1 34654 -1 34655 -1 34656 -1 34657 -1 34658 -1 34659 -1 34660 -1 34661 -1 34662 -1 34663 -1 34664 -1 34665 -1 34666 -1 34667 -1 34668 -1 34669 -1 34670 -1 34671 -1 34672 -1 34673 -1 34674 -1 34675 -1 34676 -1 34677 -1 34678 -1 34679 -1 34680 -1 34681 -1 34682 -1 34683 -1 34684 -1 34685 -1 34686 -1 34687 -1 34688 -1 34689 -1 34690 -1 34691 -1 34692 -1 34693 -1 34694 -1 34695 -1 34696 -1 34697 -1 34698 -1 34699 -1 34700 -1 34701 -1 34702 -1 34703 -1 34704 -1 34705 -1 34706 -1 34707 -1 34708 -1 34709 -1 34710 -1 34711 -1 34712 -1 34713 -1 34714 -1 34715 -1 34716 -1 34717 -1 34718 -1 34719 -1 34720 -1 34721 -1 34722 -1 34723 -1 34724 -1 34725 -1 34726 -1 34727 -1 34728 -1 34729 -1 34730 -1 34731 -1 34732 -1 34733 -1 34734 -1 34735 -1 34736 -1 34737 -1 34738 -1 34739 -1 34740 -1 34741 -1 34742 -1 34743 -1 34744 -1 34745 -1 34746 -1 34747 -1 34748 -1 34749 -1 34750 -1 34751 -1 34752 -1 34753 -1 34754 -1 34755 -1 34756 -1 34757 -1 34758 -1 34759 -1 34760 -1 34761 -1 34762 -1 34763 -1 34764 -1 34765 -1 34766 -1 34767 -1 34768 -1 34769 -1 34770 -1 34771 -1 34772 -1 34773 -1 34774 -1 34775 -1 34776 -1 34777 -1 34778 -1 34779 -1 34780 -1 34781 -1 34782 -1 34783 -1 34784 -1 34785 -1 34786 -1 34787 -1 34788 -1 34789 -1 34790 -1 34791 -1 34792 -1 34793 -1 34794 -1 34795 -1 34796 -1 34797 -1 34798 -1 34799 -1 34800 -1 34801 -1 34802 -1 34803 -1 34804 -1 34805 -1 34806 -1 34807 -1 34808 -1 34809 -1 34810 -1 34811 -1 34812 -1 34813 -1 34814 -1 34815 -1 34816 -1 34817 -1 34818 -1 34819 -1 34820 -1 34821 -1 34822 -1 34823 -1 34824 -1 34825 -1 34826 -1 34827 -1 34828 -1 34829 -1 34830 -1 34831 -1 34832 -1 34833 -1 34834 -1 34835 -1 34836 -1 34837 -1 34838 -1 34839 -1 34840 -1 34841 -1 34842 -1 34843 -1 34844 -1 34845 -1 34846 -1 34847 -1 34848 -1 34849 -1 34850 -1 34851 -1 34852 -1 34853 -1 34854 -1 34855 -1 34856 -1 34857 -1 34858 -1 34859 -1 34860 -1 34861 -1 34862 -1 34863 -1 34864 -1 34865 -1 34866 -1 34867 -1 34868 -1 34869 -1 34870 -1 34871 -1 34872 -1 34873 -1 34874 -1 34875 -1 34876 -1 34877 -1 34878 -1 34879 -1 34880 -1 34881 -1 34882 -1 34883 -1 34884 -1 34885 -1 34886 -1 34887 -1 34888 -1 34889 -1 34890 -1 34891 -1 34892 -1 34893 -1 34894 -1 34895 -1 34896 -1 34897 -1 34898 -1 34899 -1 34900 -1 34901 -1 34902 -1 34903 -1 34904 -1 34905 -1 34906 -1 34907 -1 34908 -1 34909 -1 34910 -1 34911 -1 34912 -1 34913 -1 34914 -1 34915 -1 34916 -1 34917 -1 34918 -1 34919 -1 34920 -1 34921 -1 34922 -1 34923 -1 34924 -1 34925 -1 34926 -1 34927 -1 34928 -1 34929 -1 34930 -1 34931 -1 34932 -1 34933 -1 34934 -1 34935 -1 34936 -1 34937 -1 34938 -1 34939 -1 34940 -1 34941 -1 34942 -1 34943 -1 34944 -1 34945 -1 34946 -1 34947 -1 34948 -1 34949 -1 34950 -1 34951 -1 34952 -1 34953 -1 34954 -1 34955 -1 34956 -1 34957 -1 34958 -1 34959 -1 34960 -1 34961 -1 34962 -1 34963 -1 34964 -1 34965 -1 34966 -1 34967 -1 34968 -1 34969 -1 34970 -1 34971 -1 34972 -1 34973 -1 34974 -1 34975 -1 34976 -1 34977 -1 34978 -1 34979 -1 34980 -1 34981 -1 34982 -1 34983 -1 34984 -1 34985 -1 34986 -1 34987 -1 34988 -1 34989 -1 34990 -1 34991 -1 34992 -1 34993 -1 34994 -1 34995 -1 34996 -1 34997 -1 34998 -1 34999 -1 35000 -1 35001 -1 35002 -1 35003 -1 35004 -1 35005 -1 35006 -1 35007 -1 35008 -1 35009 -1 35010 -1 35011 -1 35012 -1 35013 -1 35014 -1 35015 -1 35016 -1 35017 -1 35018 -1 35019 -1 35020 -1 35021 -1 35022 -1 35023 -1 35024 -1 35025 -1 35026 -1 35027 -1 35028 -1 35029 -1 35030 -1 35031 -1 35032 -1 35033 -1 35034 -1 35035 -1 35036 -1 35037 -1 35038 -1 35039 -1 35040 -1 35041 -1 35042 -1 35043 -1 35044 -1 35045 -1 35046 -1 35047 -1 35048 -1 35049 -1 35050 -1 35051 -1 35052 -1 35053 -1 35054 -1 35055 -1 35056 -1 35057 -1 35058 -1 35059 -1 35060 -1 35061 -1 35062 -1 35063 -1 35064 -1 35065 -1 35066 -1 35067 -1 35068 -1 35069 -1 35070 -1 35071 -1 35072 -1 35073 -1 35074 -1 35075 -1 35076 -1 35077 -1 35078 -1 35079 -1 35080 -1 35081 -1 35082 -1 35083 -1 35084 -1 35085 -1 35086 -1 35087 -1 35088 -1 35089 -1 35090 -1 35091 -1 35092 -1 35093 -1 35094 -1 35095 -1 35096 -1 35097 -1 35098 -1 35099 -1 35100 -1 35101 -1 35102 -1 35103 -1 35104 -1 35105 -1 35106 -1 35107 -1 35108 -1 35109 -1 35110 -1 35111 -1 35112 -1 35113 -1 35114 -1 35115 -1 35116 -1 35117 -1 35118 -1 35119 -1 35120 -1 35121 -1 35122 -1 35123 -1 35124 -1 35125 -1 35126 -1 35127 -1 35128 -1 35129 -1 35130 -1 35131 -1 35132 -1 35133 -1 35134 -1 35135 -1 35136 -1 35137 -1 35138 -1 35139 -1 35140 -1 35141 -1 35142 -1 35143 -1 35144 -1 35145 -1 35146 -1 35147 -1 35148 -1 35149 -1 35150 -1 35151 -1 35152 -1 35153 -1 35154 -1 35155 -1 35156 -1 35157 -1 35158 -1 35159 -1 35160 -1 35161 -1 35162 -1 35163 -1 35164 -1 35165 -1 35166 -1 35167 -1 35168 -1 35169 -1 35170 -1 35171 -1 35172 -1 35173 -1 35174 -1 35175 -1 35176 -1 35177 -1 35178 -1 35179 -1 35180 -1 35181 -1 35182 -1 35183 -1 35184 -1 35185 -1 35186 -1 35187 -1 35188 -1 35189 -1 35190 -1 35191 -1 35192 -1 35193 -1 35194 -1 35195 -1 35196 -1 35197 -1 35198 -1 35199 -1 35200 -1 35201 -1 35202 -1 35203 -1 35204 -1 35205 -1 35206 -1 35207 -1 35208 -1 35209 -1 35210 -1 35211 -1 35212 -1 35213 -1 35214 -1 35215 -1 35216 -1 35217 -1 35218 -1 35219 -1 35220 -1 35221 -1 35222 -1 35223 -1 35224 -1 35225 -1 35226 -1 35227 -1 35228 -1 35229 -1 35230 -1 35231 -1 35232 -1 35233 -1 35234 -1 35235 -1 35236 -1 35237 -1 35238 -1 35239 -1 35240 -1 35241 -1 35242 -1 35243 -1 35244 -1 35245 -1 35246 -1 35247 -1 35248 -1 35249 -1 35250 -1 35251 -1 35252 -1 35253 -1 35254 -1 35255 -1 35256 -1 35257 -1 35258 -1 35259 -1 35260 -1 35261 -1 35262 -1 35263 -1 35264 -1 35265 -1 35266 -1 35267 -1 35268 -1 35269 -1 35270 -1 35271 -1 35272 -1 35273 -1 35274 -1 35275 -1 35276 -1 35277 -1 35278 -1 35279 -1 35280 -1 35281 -1 35282 -1 35283 -1 35284 -1 35285 -1 35286 -1 35287 -1 35288 -1 35289 -1 35290 -1 35291 -1 35292 -1 35293 -1 35294 -1 35295 -1 35296 -1 35297 -1 35298 -1 35299 -1 35300 -1 35301 -1 35302 -1 35303 -1 35304 -1 35305 -1 35306 -1 35307 -1 35308 -1 35309 -1 35310 -1 35311 -1 35312 -1 35313 -1 35314 -1 35315 -1 35316 -1 35317 -1 35318 -1 35319 -1 35320 -1 35321 -1 35322 -1 35323 -1 35324 -1 35325 -1 35326 -1 35327 -1 35328 -1 35329 -1 35330 -1 35331 -1 35332 -1 35333 -1 35334 -1 35335 -1 35336 -1 35337 -1 35338 -1 35339 -1 35340 -1 35341 -1 35342 -1 35343 -1 35344 -1 35345 -1 35346 -1 35347 -1 35348 -1 35349 -1 35350 -1 35351 -1 35352 -1 35353 -1 35354 -1 35355 -1 35356 -1 35357 -1 35358 -1 35359 -1 35360 -1 35361 -1 35362 -1 35363 -1 35364 -1 35365 -1 35366 -1 35367 -1 35368 -1 35369 -1 35370 -1 35371 -1 35372 -1 35373 -1 35374 -1 35375 -1 35376 -1 35377 -1 35378 -1 35379 -1 35380 -1 35381 -1 35382 -1 35383 -1 35384 -1 35385 -1 35386 -1 35387 -1 35388 -1 35389 -1 35390 -1 35391 -1 35392 -1 35393 -1 35394 -1 35395 -1 35396 -1 35397 -1 35398 -1 35399 -1 35400 -1 35401 -1 35402 -1 35403 -1 35404 -1 35405 -1 35406 -1 35407 -1 35408 -1 35409 -1 35410 -1 35411 -1 35412 -1 35413 -1 35414 -1 35415 -1 35416 -1 35417 -1 35418 -1 35419 -1 35420 -1 35421 -1 35422 -1 35423 -1 35424 -1 35425 -1 35426 -1 35427 -1 35428 -1 35429 -1 35430 -1 35431 -1 35432 -1 35433 -1 35434 -1 35435 -1 35436 -1 35437 -1 35438 -1 35439 -1 35440 -1 35441 -1 35442 -1 35443 -1 35444 -1 35445 -1 35446 -1 35447 -1 35448 -1 35449 -1 35450 -1 35451 -1 35452 -1 35453 -1 35454 -1 35455 -1 35456 -1 35457 -1 35458 -1 35459 -1 35460 -1 35461 -1 35462 -1 35463 -1 35464 -1 35465 -1 35466 -1 35467 -1 35468 -1 35469 -1 35470 -1 35471 -1 35472 -1 35473 -1 35474 -1 35475 -1 35476 -1 35477 -1 35478 -1 35479 -1 35480 -1 35481 -1 35482 -1 35483 -1 35484 -1 35485 -1 35486 -1 35487 -1 35488 -1 35489 -1 35490 -1 35491 -1 35492 -1 35493 -1 35494 -1 35495 -1 35496 -1 35497 -1 35498 -1 35499 -1 35500 -1 35501 -1 35502 -1 35503 -1 35504 -1 35505 -1 35506 -1 35507 -1 35508 -1 35509 -1 35510 -1 35511 -1 35512 -1 35513 -1 35514 -1 35515 -1 35516 -1 35517 -1 35518 -1 35519 -1 35520 -1 35521 -1 35522 -1 35523 -1 35524 -1 35525 -1 35526 -1 35527 -1 35528 -1 35529 -1 35530 -1 35531 -1 35532 -1 35533 -1 35534 -1 35535 -1 35536 -1 35537 -1 35538 -1 35539 -1 35540 -1 35541 -1 35542 -1 35543 -1 35544 -1 35545 -1 35546 -1 35547 -1 35548 -1 35549 -1 35550 -1 35551 -1 35552 -1 35553 -1 35554 -1 35555 -1 35556 -1 35557 -1 35558 -1 35559 -1 35560 -1 35561 -1 35562 -1 35563 -1 35564 -1 35565 -1 35566 -1 35567 -1 35568 -1 35569 -1 35570 -1 35571 -1 35572 -1 35573 -1 35574 -1 35575 -1 35576 -1 35577 -1 35578 -1 35579 -1 35580 -1 35581 -1 35582 -1 35583 -1 35584 -1 35585 -1 35586 -1 35587 -1 35588 -1 35589 -1 35590 -1 35591 -1 35592 -1 35593 -1 35594 -1 35595 -1 35596 -1 35597 -1 35598 -1 35599 -1 35600 -1 35601 -1 35602 -1 35603 -1 35604 -1 35605 -1 35606 -1 35607 -1 35608 -1 35609 -1 35610 -1 35611 -1 35612 -1 35613 -1 35614 -1 35615 -1 35616 -1 35617 -1 35618 -1 35619 -1 35620 -1 35621 -1 35622 -1 35623 -1 35624 -1 35625 -1 35626 -1 35627 -1 35628 -1 35629 -1 35630 -1 35631 -1 35632 -1 35633 -1 35634 -1 35635 -1 35636 -1 35637 -1 35638 -1 35639 -1 35640 -1 35641 -1 35642 -1 35643 -1 35644 -1 35645 -1 35646 -1 35647 -1 35648 -1 35649 -1 35650 -1 35651 -1 35652 -1 35653 -1 35654 -1 35655 -1 35656 -1 35657 -1 35658 -1 35659 -1 35660 -1 35661 -1 35662 -1 35663 -1 35664 -1 35665 -1 35666 -1 35667 -1 35668 -1 35669 -1 35670 -1 35671 -1 35672 -1 35673 -1 35674 -1 35675 -1 35676 -1 35677 -1 35678 -1 35679 -1 35680 -1 35681 -1 35682 -1 35683 -1 35684 -1 35685 -1 35686 -1 35687 -1 35688 -1 35689 -1 35690 -1 35691 -1 35692 -1 35693 -1 35694 -1 35695 -1 35696 -1 35697 -1 35698 -1 35699 -1 35700 -1 35701 -1 35702 -1 35703 -1 35704 -1 35705 -1 35706 -1 35707 -1 35708 -1 35709 -1 35710 -1 35711 -1 35712 -1 35713 -1 35714 -1 35715 -1 35716 -1 35717 -1 35718 -1 35719 -1 35720 -1 35721 -1 35722 -1 35723 -1 35724 -1 35725 -1 35726 -1 35727 -1 35728 -1 35729 -1 35730 -1 35731 -1 35732 -1 35733 -1 35734 -1 35735 -1 35736 -1 35737 -1 35738 -1 35739 -1 35740 -1 35741 -1 35742 -1 35743 -1 35744 -1 35745 -1 35746 -1 35747 -1 35748 -1 35749 -1 35750 -1 35751 -1 35752 -1 35753 -1 35754 -1 35755 -1 35756 -1 35757 -1 35758 -1 35759 -1 35760 -1 35761 -1 35762 -1 35763 -1 35764 -1 35765 -1 35766 -1 35767 -1 35768 -1 35769 -1 35770 -1 35771 -1 35772 -1 35773 -1 35774 -1 35775 -1 35776 -1 35777 -1 35778 -1 35779 -1 35780 -1 35781 -1 35782 -1 35783 -1 35784 -1 35785 -1 35786 -1 35787 -1 35788 -1 35789 -1 35790 -1 35791 -1 35792 -1 35793 -1 35794 -1 35795 -1 35796 -1 35797 -1 35798 -1 35799 -1 35800 -1 35801 -1 35802 -1 35803 -1 35804 -1 35805 -1 35806 -1 35807 -1 35808 -1 35809 -1 35810 -1 35811 -1 35812 -1 35813 -1 35814 -1 35815 -1 35816 -1 35817 -1 35818 -1 35819 -1 35820 -1 35821 -1 35822 -1 35823 -1 35824 -1 35825 -1 35826 -1 35827 -1 35828 -1 35829 -1 35830 -1 35831 -1 35832 -1 35833 -1 35834 -1 35835 -1 35836 -1 35837 -1 35838 -1 35839 -1 35840 -1 35841 -1 35842 -1 35843 -1 35844 -1 35845 -1 35846 -1 35847 -1 35848 -1 35849 -1 35850 -1 35851 -1 35852 -1 35853 -1 35854 -1 35855 -1 35856 -1 35857 -1 35858 -1 35859 -1 35860 -1 35861 -1 35862 -1 35863 -1 35864 -1 35865 -1 35866 -1 35867 -1 35868 -1 35869 -1 35870 -1 35871 -1 35872 -1 35873 -1 35874 -1 35875 -1 35876 -1 35877 -1 35878 -1 35879 -1 35880 -1 35881 -1 35882 -1 35883 -1 35884 -1 35885 -1 35886 -1 35887 -1 35888 -1 35889 -1 35890 -1 35891 -1 35892 -1 35893 -1 35894 -1 35895 -1 35896 -1 35897 -1 35898 -1 35899 -1 35900 -1 35901 -1 35902 -1 35903 -1 35904 -1 35905 -1 35906 -1 35907 -1 35908 -1 35909 -1 35910 -1 35911 -1 35912 -1 35913 -1 35914 -1 35915 -1 35916 -1 35917 -1 35918 -1 35919 -1 35920 -1 35921 -1 35922 -1 35923 -1 35924 -1 35925 -1 35926 -1 35927 -1 35928 -1 35929 -1 35930 -1 35931 -1 35932 -1 35933 -1 35934 -1 35935 -1 35936 -1 35937 -1 35938 -1 35939 -1 35940 -1 35941 -1 35942 -1 35943 -1 35944 -1 35945 -1 35946 -1 35947 -1 35948 -1 35949 -1 35950 -1 35951 -1 35952 -1 35953 -1 35954 -1 35955 -1 35956 -1 35957 -1 35958 -1 35959 -1 35960 -1 35961 -1 35962 -1 35963 -1 35964 -1 35965 -1 35966 -1 35967 -1 35968 -1 35969 -1 35970 -1 35971 -1 35972 -1 35973 -1 35974 -1 35975 -1 35976 -1 35977 -1 35978 -1 35979 -1 35980 -1 35981 -1 35982 -1 35983 -1 35984 -1 35985 -1 35986 -1 35987 -1 35988 -1 35989 -1 35990 -1 35991 -1 35992 -1 35993 -1 35994 -1 35995 -1 35996 -1 35997 -1 35998 -1 35999 -1 36000 -1 36001 -1 36002 -1 36003 -1 36004 -1 36005 -1 36006 -1 36007 -1 36008 -1 36009 -1 36010 -1 36011 -1 36012 -1 36013 -1 36014 -1 36015 -1 36016 -1 36017 -1 36018 -1 36019 -1 36020 -1 36021 -1 36022 -1 36023 -1 36024 -1 36025 -1 36026 -1 36027 -1 36028 -1 36029 -1 36030 -1 36031 -1 36032 -1 36033 -1 36034 -1 36035 -1 36036 -1 36037 -1 36038 -1 36039 -1 36040 -1 36041 -1 36042 -1 36043 -1 36044 -1 36045 -1 36046 -1 36047 -1 36048 -1 36049 -1 36050 -1 36051 -1 36052 -1 36053 -1 36054 -1 36055 -1 36056 -1 36057 -1 36058 -1 36059 -1 36060 -1 36061 -1 36062 -1 36063 -1 36064 -1 36065 -1 36066 -1 36067 -1 36068 -1 36069 -1 36070 -1 36071 -1 36072 -1 36073 -1 36074 -1 36075 -1 36076 -1 36077 -1 36078 -1 36079 -1 36080 -1 36081 -1 36082 -1 36083 -1 36084 -1 36085 -1 36086 -1 36087 -1 36088 -1 36089 -1 36090 -1 36091 -1 36092 -1 36093 -1 36094 -1 36095 -1 36096 -1 36097 -1 36098 -1 36099 -1 36100 -1 36101 -1 36102 -1 36103 -1 36104 -1 36105 -1 36106 -1 36107 -1 36108 -1 36109 -1 36110 -1 36111 -1 36112 -1 36113 -1 36114 -1 36115 -1 36116 -1 36117 -1 36118 -1 36119 -1 36120 -1 36121 -1 36122 -1 36123 -1 36124 -1 36125 -1 36126 -1 36127 -1 36128 -1 36129 -1 36130 -1 36131 -1 36132 -1 36133 -1 36134 -1 36135 -1 36136 -1 36137 -1 36138 -1 36139 -1 36140 -1 36141 -1 36142 -1 36143 -1 36144 -1 36145 -1 36146 -1 36147 -1 36148 -1 36149 -1 36150 -1 36151 -1 36152 -1 36153 -1 36154 -1 36155 -1 36156 -1 36157 -1 36158 -1 36159 -1 36160 -1 36161 -1 36162 -1 36163 -1 36164 -1 36165 -1 36166 -1 36167 -1 36168 -1 36169 -1 36170 -1 36171 -1 36172 -1 36173 -1 36174 -1 36175 -1 36176 -1 36177 -1 36178 -1 36179 -1 36180 -1 36181 -1 36182 -1 36183 -1 36184 -1 36185 -1 36186 -1 36187 -1 36188 -1 36189 -1 36190 -1 36191 -1 36192 -1 36193 -1 36194 -1 36195 -1 36196 -1 36197 -1 36198 -1 36199 -1 36200 -1 36201 -1 36202 -1 36203 -1 36204 -1 36205 -1 36206 -1 36207 -1 36208 -1 36209 -1 36210 -1 36211 -1 36212 -1 36213 -1 36214 -1 36215 -1 36216 -1 36217 -1 36218 -1 36219 -1 36220 -1 36221 -1 36222 -1 36223 -1 36224 -1 36225 -1 36226 -1 36227 -1 36228 -1 36229 -1 36230 -1 36231 -1 36232 -1 36233 -1 36234 -1 36235 -1 36236 -1 36237 -1 36238 -1 36239 -1 36240 -1 36241 -1 36242 -1 36243 -1 36244 -1 36245 -1 36246 -1 36247 -1 36248 -1 36249 -1 36250 -1 36251 -1 36252 -1 36253 -1 36254 -1 36255 -1 36256 -1 36257 -1 36258 -1 36259 -1 36260 -1 36261 -1 36262 -1 36263 -1 36264 -1 36265 -1 36266 -1 36267 -1 36268 -1 36269 -1 36270 -1 36271 -1 36272 -1 36273 -1 36274 -1 36275 -1 36276 -1 36277 -1 36278 -1 36279 -1 36280 -1 36281 -1 36282 -1 36283 -1 36284 -1 36285 -1 36286 -1 36287 -1 36288 -1 36289 -1 36290 -1 36291 -1 36292 -1 36293 -1 36294 -1 36295 -1 36296 -1 36297 -1 36298 -1 36299 -1 36300 -1 36301 -1 36302 -1 36303 -1 36304 -1 36305 -1 36306 -1 36307 -1 36308 -1 36309 -1 36310 -1 36311 -1 36312 -1 36313 -1 36314 -1 36315 -1 36316 -1 36317 -1 36318 -1 36319 -1 36320 -1 36321 -1 36322 -1 36323 -1 36324 -1 36325 -1 36326 -1 36327 -1 36328 -1 36329 -1 36330 -1 36331 -1 36332 -1 36333 -1 36334 -1 36335 -1 36336 -1 36337 -1 36338 -1 36339 -1 36340 -1 36341 -1 36342 -1 36343 -1 36344 -1 36345 -1 36346 -1 36347 -1 36348 -1 36349 -1 36350 -1 36351 -1 36352 -1 36353 -1 36354 -1 36355 -1 36356 -1 36357 -1 36358 -1 36359 -1 36360 -1 36361 -1 36362 -1 36363 -1 36364 -1 36365 -1 36366 -1 36367 -1 36368 -1 36369 -1 36370 -1 36371 -1 36372 -1 36373 -1 36374 -1 36375 -1 36376 -1 36377 -1 36378 -1 36379 -1 36380 -1 36381 -1 36382 -1 36383 -1 36384 -1 36385 -1 36386 -1 36387 -1 36388 -1 36389 -1 36390 -1 36391 -1 36392 -1 36393 -1 36394 -1 36395 -1 36396 -1 36397 -1 36398 -1 36399 -1 36400 -1 36401 -1 36402 -1 36403 -1 36404 -1 36405 -1 36406 -1 36407 -1 36408 -1 36409 -1 36410 -1 36411 -1 36412 -1 36413 -1 36414 -1 36415 -1 36416 -1 36417 -1 36418 -1 36419 -1 36420 -1 36421 -1 36422 -1 36423 -1 36424 -1 36425 -1 36426 -1 36427 -1 36428 -1 36429 -1 36430 -1 36431 -1 36432 -1 36433 -1 36434 -1 36435 -1 36436 -1 36437 -1 36438 -1 36439 -1 36440 -1 36441 -1 36442 -1 36443 -1 36444 -1 36445 -1 36446 -1 36447 -1 36448 -1 36449 -1 36450 -1 36451 -1 36452 -1 36453 -1 36454 -1 36455 -1 36456 -1 36457 -1 36458 -1 36459 -1 36460 -1 36461 -1 36462 -1 36463 -1 36464 -1 36465 -1 36466 -1 36467 -1 36468 -1 36469 -1 36470 -1 36471 -1 36472 -1 36473 -1 36474 -1 36475 -1 36476 -1 36477 -1 36478 -1 36479 -1 36480 -1 36481 -1 36482 -1 36483 -1 36484 -1 36485 -1 36486 -1 36487 -1 36488 -1 36489 -1 36490 -1 36491 -1 36492 -1 36493 -1 36494 -1 36495 -1 36496 -1 36497 -1 36498 -1 36499 -1 36500 -1 36501 -1 36502 -1 36503 -1 36504 -1 36505 -1 36506 -1 36507 -1 36508 -1 36509 -1 36510 -1 36511 -1 36512 -1 36513 -1 36514 -1 36515 -1 36516 -1 36517 -1 36518 -1 36519 -1 36520 -1 36521 -1 36522 -1 36523 -1 36524 -1 36525 -1 36526 -1 36527 -1 36528 -1 36529 -1 36530 -1 36531 -1 36532 -1 36533 -1 36534 -1 36535 -1 36536 -1 36537 -1 36538 -1 36539 -1 36540 -1 36541 -1 36542 -1 36543 -1 36544 -1 36545 -1 36546 -1 36547 -1 36548 -1 36549 -1 36550 -1 36551 -1 36552 -1 36553 -1 36554 -1 36555 -1 36556 -1 36557 -1 36558 -1 36559 -1 36560 -1 36561 -1 36562 -1 36563 -1 36564 -1 36565 -1 36566 -1 36567 -1 36568 -1 36569 -1 36570 -1 36571 -1 36572 -1 36573 -1 36574 -1 36575 -1 36576 -1 36577 -1 36578 -1 36579 -1 36580 -1 36581 -1 36582 -1 36583 -1 36584 -1 36585 -1 36586 -1 36587 -1 36588 -1 36589 -1 36590 -1 36591 -1 36592 -1 36593 -1 36594 -1 36595 -1 36596 -1 36597 -1 36598 -1 36599 -1 36600 -1 36601 -1 36602 -1 36603 -1 36604 -1 36605 -1 36606 -1 36607 -1 36608 -1 36609 -1 36610 -1 36611 -1 36612 -1 36613 -1 36614 -1 36615 -1 36616 -1 36617 -1 36618 -1 36619 -1 36620 -1 36621 -1 36622 -1 36623 -1 36624 -1 36625 -1 36626 -1 36627 -1 36628 -1 36629 -1 36630 -1 36631 -1 36632 -1 36633 -1 36634 -1 36635 -1 36636 -1 36637 -1 36638 -1 36639 -1 36640 -1 36641 -1 36642 -1 36643 -1 36644 -1 36645 -1 36646 -1 36647 -1 36648 -1 36649 -1 36650 -1 36651 -1 36652 -1 36653 -1 36654 -1 36655 -1 36656 -1 36657 -1 36658 -1 36659 -1 36660 -1 36661 -1 36662 -1 36663 -1 36664 -1 36665 -1 36666 -1 36667 -1 36668 -1 36669 -1 36670 -1 36671 -1 36672 -1 36673 -POINT_DATA 36674 diff --git a/thirdparty/libpointmatcher/examples/icp_tutorial/cloud_1.vtk b/thirdparty/libpointmatcher/examples/icp_tutorial/cloud_1.vtk deleted file mode 100644 index 0a6d474..0000000 --- a/thirdparty/libpointmatcher/examples/icp_tutorial/cloud_1.vtk +++ /dev/null @@ -1,73347 +0,0 @@ -# vtk DataFile Version 3.0 -File created by libpointmatcher -ASCII -DATASET POLYDATA -POINTS 36670 float - -0.213803 -0.371922 0.454164 - -0.161025 -0.374834 0.409672 - -0.158085 -0.379701 0.40718 - -0.147344 -0.375471 0.398138 - -0.143329 -0.370457 0.394768 - -0.140076 -0.370658 0.392025 - -0.125383 -0.382445 0.37961 - -0.0251823 -0.375952 0.295171 - -0.023584 -0.383428 0.293804 - -0.010654 -0.384933 0.282902 --0.00775904 -0.396467 0.280432 --0.00643623 -0.396659 0.279316 - 0.00196148 -0.390676 0.272254 - 0.0112574 -0.387482 0.264427 - 0.0137069 -0.391638 0.262351 - 0.0149828 -0.392707 0.261273 - 0.0321128 -0.399933 0.246816 - 0.0441575 -0.400338 0.236663 - 0.0638659 -0.394997 0.220065 - 0.0764306 -0.398698 0.209465 - 0.100849 -0.403462 0.188871 - 0.119714 -0.410286 0.172953 - 0.146241 -0.406927 0.150603 - 0.153657 -0.410621 0.144342 - 0.173151 -0.410417 0.127911 - 0.304443 -0.43255 0.0171918 - 0.321622 -0.435611 0.00270437 - 0.402342 -0.441937 -0.0653483 - 0.434081 -0.450606 -0.0921227 - 0.464764 -0.455263 -0.117997 - 0.467482 -0.453995 -0.120284 - 0.505824 -0.467434 -0.152637 - 0.546692 -0.502725 -0.187176 - 0.61047 -0.462709 -0.240828 - 0.610703 -0.458343 -0.241012 - 0.612101 -0.406475 -0.242056 - 0.616695 -0.318979 -0.245699 - 0.606696 -0.260554 -0.237118 - 0.606092 -0.216651 -0.236494 - 0.610492 -0.214697 -0.240198 - 0.607206 -0.192186 -0.237369 - 0.607846 -0.188872 -0.2379 - 0.604281 0.013725 -0.234365 - 0.603597 0.0400614 -0.23372 - 0.603511 0.0698143 -0.233569 - 0.605883 0.0968395 -0.235498 - 0.605558 0.100141 -0.235216 - 0.605468 0.279519 -0.23467 - 0.610222 0.297028 -0.238631 - 0.608937 0.304039 -0.23753 - 0.333594 0.236296 -0.00562885 - 0.61233 0.487885 -0.239909 - 0.606073 0.525516 -0.234536 - 0.612659 0.561708 -0.239993 - 0.612152 0.608751 -0.239443 - 0.608821 0.67311 -0.236467 - 0.613645 0.71529 -0.240423 - 0.610319 0.730098 -0.23758 - 0.607879 0.843276 -0.235227 - 0.614813 0.99208 -0.240683 - 0.618328 1.09323 -0.243381 - 0.230055 0.412301 0.082101 - 0.228679 0.413452 0.0832638 - 0.227299 0.414596 0.0844298 - 0.171668 0.320662 0.131074 - 0.165485 0.319551 0.136283 - 0.160676 0.311607 0.140315 - 0.157589 0.317244 0.142932 - 0.148418 0.317816 0.150663 - 0.15159 0.344715 0.14806 - 0.215602 0.566004 0.0946849 - 0.377921 1.13335 -0.0406442 - 0.129951 0.384341 0.166403 - 0.108913 0.378322 0.184119 - 0.0960354 0.367232 0.194944 - 0.0963799 0.39898 0.194737 - 0.0855254 0.382561 0.203843 - 0.084249 0.382888 0.20492 - 0.0625067 0.403423 0.223299 - 0.0494399 0.548267 0.234692 - -0.0772323 1.30968 0.343451 - -0.103613 1.30759 0.365682 - -0.115465 0.844358 0.37446 - -0.102383 0.53036 0.362612 - -0.103004 0.481565 0.363008 - -0.213793 0.646901 0.456821 - -0.210877 0.562153 0.454142 - -0.212752 0.560785 0.455718 - -0.127369 0.273164 0.382999 - -0.12828 0.272278 0.383764 - -0.133783 0.279369 0.388422 - -0.134232 0.272634 0.388782 - -0.143506 0.273198 0.3966 - -0.153994 0.265424 0.40542 - -0.251539 -0.368299 0.482758 - -0.246562 -0.37455 0.478604 - -0.228123 -0.368097 0.463293 - -0.20404 -0.367279 0.443275 - -0.198129 -0.370881 0.438352 - -0.183371 -0.369168 0.426089 - -0.178292 -0.37027 0.421864 - -0.120951 -0.372637 0.374191 - -0.0978206 -0.381206 0.354941 - -0.0879784 -0.383163 0.346755 - -0.068377 -0.385809 0.330454 - -0.0305046 -0.381906 0.298981 - -0.0255063 -0.384123 0.29482 - -0.0124744 -0.385708 0.283983 - 0.00341978 -0.404905 0.270721 - 0.0213623 -0.387945 0.25585 - 0.0411022 -0.393532 0.239426 - 0.0454324 -0.401231 0.235806 - 0.0481245 -0.400999 0.233569 - 0.0614611 -0.414488 0.222447 - 0.0757599 -0.403917 0.210588 - 0.0771151 -0.403633 0.209463 - 0.0964826 -0.401774 0.193368 - 0.118439 -0.409854 0.175095 - 0.122337 -0.401017 0.171877 - 0.158683 -0.414696 0.141628 - 0.163455 -0.414245 0.137662 - 0.165457 -0.415296 0.135996 - 0.170737 -0.421007 0.131591 - 0.176045 -0.416759 0.12719 - 0.194147 -0.41851 0.112138 - 0.20298 -0.418031 0.104796 - 0.232128 -0.423514 0.0805514 - 0.241155 -0.425466 0.0730424 - 0.248136 -0.423004 0.0672462 - 0.251729 -0.42586 0.0642514 - 0.258661 -0.426883 0.0584865 - 0.267995 -0.427993 0.0507247 - 0.293195 -0.427954 0.0297765 - 0.316171 -0.43684 0.0106534 - 0.394146 -0.441551 -0.0541772 - 0.397892 -0.44216 -0.0572933 - 0.446955 -0.446292 -0.0980887 - 0.458929 -0.450881 -0.108055 - 0.463448 -0.451532 -0.111813 - 0.566493 -0.509686 -0.197623 - 0.592926 -0.520049 -0.219624 - 0.622639 -0.507703 -0.244291 - 0.619065 -0.346497 -0.240901 - 0.611977 -0.261529 -0.234788 - 0.613719 -0.254875 -0.236218 - 0.61692 -0.190802 -0.238713 - 0.613443 -0.161616 -0.235747 - 0.615032 -0.151614 -0.237042 - 0.614281 -0.117036 -0.236328 - 0.614673 -0.113701 -0.236644 - 0.617706 -0.10744 -0.23915 - 0.611443 -0.0927993 -0.233905 - 0.613105 -0.0829468 -0.235261 - 0.617496 -0.0531543 -0.238834 - 0.615901 0.00055654 -0.237368 - 0.615884 0.00724103 -0.237336 - 0.610643 0.0669641 -0.232825 - 0.61253 0.107577 -0.234288 - 0.614546 0.237788 -0.235625 - 0.620049 0.254849 -0.240155 - 0.615769 0.282987 -0.236524 - 0.614898 0.305523 -0.235742 - 0.506972 0.294785 -0.146053 - 0.444875 0.259562 -0.0945243 - 0.384193 0.231914 -0.044152 - 0.339839 0.223474 -0.00730342 - 0.338332 0.227014 -0.00604144 - 0.618023 0.513904 -0.237797 - 0.619827 0.618971 -0.239023 - 0.619796 0.664415 -0.23888 - 0.6201 1.05135 -0.238126 - 0.623812 1.06765 -0.241169 - 0.613227 1.11893 -0.232236 - 0.603012 1.10979 -0.223769 - 0.162917 0.309206 0.139991 - 0.158475 0.318125 0.143707 - 0.157407 0.318866 0.144596 - 0.149951 0.317123 0.15079 - 0.144275 0.319625 0.155515 - 0.368893 1.08505 -0.0292145 - 0.145392 0.428346 0.154869 - 0.115028 0.373997 0.179969 - 0.113995 0.375449 0.180831 - 0.103943 0.372919 0.18918 - 0.0872243 0.384186 0.203108 - 0.0820607 0.385487 0.207404 - 0.0767526 0.385684 0.211817 - 0.0616928 0.39448 0.224359 - 0.0560446 0.429386 0.229145 - 0.0536509 0.437671 0.231156 - 0.0519983 0.491967 0.232671 - -0.0651559 1.31537 0.3322 - -0.0783904 1.31366 0.343197 - -0.0957289 1.30806 0.357596 - -0.100021 1.30635 0.36116 - -0.118196 1.30917 0.376275 - -0.180024 1.29899 0.427646 - -0.160346 1.15012 0.410901 - -0.108263 0.707216 0.366453 - -0.107226 0.652837 0.36545 - -0.106873 0.553028 0.364897 - -0.212698 0.735255 0.453341 - -0.215165 0.733883 0.455388 - -0.11394 0.274251 0.370046 - -0.122522 0.275066 0.377182 - -0.123444 0.274214 0.377946 - -0.142416 0.276883 0.393724 - -0.146951 0.269483 0.397475 - -0.209088 -0.368285 0.443338 - -0.198963 -0.368524 0.435098 - -0.197715 -0.369786 0.434079 - -0.138756 -0.376147 0.386086 - -0.133643 -0.379798 0.381917 - -0.122356 -0.376143 0.372742 - -0.113936 -0.374821 0.365893 - -0.0897412 -0.379718 0.346193 - -0.0781002 -0.379981 0.33672 - -0.0573435 -0.382172 0.319824 - -0.0261532 -0.383138 0.294442 --0.00367731 -0.38309 0.276153 - 0.0117612 -0.388565 0.263576 - 0.018171 -0.396871 0.258339 - 0.032998 -0.399898 0.246266 - 0.0409331 -0.39453 0.239823 - 0.0690904 -0.393095 0.216914 - 0.070642 -0.394828 0.215647 - 0.145766 -0.406671 0.154487 - 0.155452 -0.407116 0.146604 - 0.183002 -0.409723 0.124179 - 0.22419 -0.42043 0.0906363 - 0.226421 -0.421016 0.0888188 - 0.259149 -0.41693 0.0621982 - 0.279737 -0.429603 0.0454125 - 0.28119 -0.428171 0.0442336 - 0.282639 -0.426731 0.0430586 - 0.29226 -0.430967 0.0352185 - 0.312371 -0.435537 0.0188425 - 0.323277 -0.432617 0.00997576 - 0.366253 -0.438087 -0.0250091 - 0.399272 -0.444264 -0.0518933 - 0.439748 -0.446992 -0.0848365 - 0.57209 -0.510861 -0.19269 - 0.583254 -0.516538 -0.201789 - 0.636544 -0.515371 -0.245149 - 0.632954 -0.419739 -0.241982 - 0.630987 -0.40531 -0.240344 - 0.632855 -0.385107 -0.241812 - 0.630951 -0.29867 -0.24004 - 0.632276 -0.264619 -0.24103 - 0.633024 -0.242299 -0.241581 - 0.633812 -0.198322 -0.242109 - 0.630117 -0.161329 -0.239007 - 0.631227 -0.0986257 -0.239749 - 0.628266 -0.0570926 -0.237232 - 0.624153 -0.0263476 -0.233806 - 0.623702 -0.00951957 -0.233396 - 0.622967 0.00726939 -0.232754 - 0.629415 0.0345005 -0.237931 - 0.624519 0.0409634 -0.233931 - 0.624846 0.0646538 -0.234135 - 0.623536 0.0916504 -0.232999 - 0.62872 0.102766 -0.237189 - 0.631588 0.138096 -0.239432 - 0.627082 0.158063 -0.235714 - 0.632069 0.16648 -0.23975 - 0.626866 0.226104 -0.235362 - 0.628838 0.245338 -0.236918 - 0.628385 0.260118 -0.236511 - 0.631673 0.284443 -0.239123 - 0.338799 0.221066 -0.00096962 - 0.337972 0.225057 -0.00028664 - 0.33981 0.231033 -0.00176689 - 0.35075 0.256327 -0.0106036 - 0.619861 0.482942 -0.229 - 0.631192 0.506535 -0.23816 - 0.62995 0.555135 -0.237024 - 0.631829 0.56719 -0.238522 - 0.634739 0.58573 -0.240841 - 0.633679 0.600806 -0.23994 - 0.631089 0.701813 -0.237572 - 0.552313 0.765923 -0.173306 - 0.475557 0.708213 -0.110996 - 0.525447 0.793931 -0.151372 - 0.635997 1.01423 -0.240761 - 0.229463 0.406411 0.088477 - 0.154233 0.315895 0.14946 - 0.156366 0.324612 0.147747 - 0.146717 0.33182 0.155617 - 0.21398 0.561555 0.101477 - 0.413574 1.21744 -0.0592465 - 0.404323 1.23408 -0.0516755 - 0.100278 0.373222 0.193513 - 0.0990142 0.373631 0.194542 - 0.0986645 0.386097 0.194858 - 0.0830557 0.382225 0.207549 - 0.0711455 0.38279 0.217243 - 0.0668756 0.392649 0.220742 - 0.0543626 0.427551 0.231015 - 0.0526315 0.447789 0.232475 - 0.036075 1.28096 0.248096 - 0.0186424 1.29594 0.26232 - -0.0122004 1.29996 0.287428 - -0.0256757 1.30615 0.298409 - -0.0972587 1.30905 0.356665 - -0.106116 1.30759 0.363869 - -0.12049 1.31511 0.375584 - -0.139018 1.31748 0.390667 - -0.153858 1.32538 0.402763 - -0.109868 0.734982 0.365445 - -0.111437 0.532827 0.3662 - -0.113258 0.470392 0.367522 - -0.219822 0.758739 0.454978 - -0.215391 0.58116 0.450915 - -0.448082 1.07178 0.641525 - -0.554056 1.27208 0.728275 - -0.125991 0.275842 0.377381 - -0.134338 0.272877 0.384165 - -0.156392 0.268987 0.402101 - -0.162095 0.267782 0.406738 - -0.176434 0.271 0.418415 - -0.255782 -0.357196 0.476396 - -0.256223 -0.360886 0.476738 - -0.255399 -0.366158 0.476068 - -0.252892 -0.369279 0.474065 - -0.220659 -0.359608 0.448428 - -0.224081 -0.374351 0.451115 - -0.222802 -0.375741 0.450093 - -0.214221 -0.369266 0.443279 - -0.211964 -0.369057 0.441482 - -0.188625 -0.370776 0.422899 - -0.156097 -0.372461 0.396999 - -0.151458 -0.37376 0.393302 - -0.142195 -0.376085 0.385922 - -0.13462 -0.37804 0.379887 - -0.115831 -0.375722 0.364935 - -0.108093 -0.380328 0.358763 - -0.106794 -0.381071 0.357727 - -0.105177 -0.38089 0.356441 - -0.102001 -0.376113 0.353924 - -0.0785199 -0.371861 0.335242 - -0.0651941 -0.386943 0.324595 - -0.0594952 -0.380738 0.320074 - -0.0564164 -0.385991 0.317609 - -0.0542859 -0.38258 0.315922 - -0.0232739 -0.38596 0.291225 - 0.0258929 -0.392999 0.252066 - 0.0405343 -0.389536 0.240419 - 0.0448521 -0.396241 0.236965 - 0.0652592 -0.409884 0.220684 - 0.066168 -0.4047 0.219974 - 0.109921 -0.40078 0.185153 - 0.122642 -0.404426 0.175016 - 0.130563 -0.411709 0.168691 - 0.187157 -0.413309 0.123633 - 0.188568 -0.412404 0.122513 - 0.218604 -0.422236 0.0985764 - 0.222281 -0.421785 0.0956503 - 0.226587 -0.418459 0.0922303 - 0.254236 -0.432545 0.0701837 - 0.261572 -0.426067 0.0643602 - 0.263026 -0.424747 0.0632062 - 0.268216 -0.426126 0.0590704 - 0.274435 -0.425234 0.0541223 - 0.299616 -0.431838 0.034059 - 0.403098 -0.441485 -0.0483464 - 0.41075 -0.442606 -0.0544414 - 0.41576 -0.444446 -0.058434 - 0.439911 -0.45163 -0.077679 - 0.44538 -0.449561 -0.0820275 - 0.624788 -0.525634 -0.225047 - 0.646681 -0.452964 -0.24229 - 0.648211 -0.38738 -0.24334 - 0.644326 -0.322791 -0.240082 - 0.646515 -0.315879 -0.241807 - 0.636591 -0.260574 -0.233765 - 0.638752 -0.238883 -0.23543 - 0.64265 -0.163359 -0.238341 - 0.643207 -0.159918 -0.238775 - 0.639425 -0.148276 -0.235734 - 0.641831 -0.131136 -0.237606 - 0.641193 -0.102936 -0.237026 - 0.643602 -0.0858667 -0.2389 - 0.644173 -0.0789752 -0.239337 - 0.639579 -0.0370931 -0.235573 - 0.638663 0.014234 -0.234712 - 0.638477 0.0244802 -0.234538 - 0.637514 0.0312688 -0.233754 - 0.638417 0.0484305 -0.23443 - 0.639806 0.0657397 -0.23549 - 0.640562 0.124936 -0.235941 - 0.640134 0.12836 -0.235591 - 0.635697 0.137921 -0.232035 - 0.640687 0.21099 -0.235821 - 0.642045 0.531245 -0.236083 - 0.642437 0.567293 -0.236303 - 0.646125 0.58124 -0.239204 - 0.648665 0.633051 -0.241093 - 0.64271 0.661356 -0.23628 - 0.651077 0.719225 -0.242792 - 0.646151 0.726158 -0.238854 - 0.645095 0.784141 -0.237865 - 0.478875 0.695451 -0.105766 - 0.26197 0.459339 0.0663062 - 0.172498 0.317215 0.137171 - 0.16228 0.323412 0.145321 - 0.147249 0.335216 0.157317 - 0.156881 0.374674 0.149751 - 0.424588 1.22728 -0.0611887 - 0.143907 0.412633 0.160176 - 0.133488 0.381275 0.16839 - 0.123122 0.380512 0.176641 - 0.0975266 0.393711 0.19705 - 0.0934901 0.394863 0.200267 - 0.0858376 0.390742 0.206348 - 0.075592 0.38596 0.214493 - 0.0721179 0.379572 0.217242 - 0.0577849 0.416104 0.228746 - 0.0358398 1.28996 0.24845 - 0.0270347 1.293 0.255467 - 0.0137933 1.29287 0.266008 - 0.00470448 1.30866 0.273284 - -0.0398858 1.30513 0.308773 - -0.0755624 1.30232 0.337167 - -0.17269 1.31323 0.414517 - -0.111906 0.53645 0.364143 - -0.113834 0.520849 0.365637 - -0.221287 0.664071 0.451545 - -0.2162 0.595845 0.447321 - -0.22106 0.576655 0.451141 - -0.60504 1.39891 0.758925 - -0.130007 0.27492 0.377884 - -0.135613 0.272082 0.38234 - -0.136066 0.270382 0.382696 - -0.138824 0.267639 0.384885 - -0.153424 0.266495 0.396504 - -0.182583 -0.372579 0.413612 - -0.178713 -0.375988 0.410607 - -0.169568 -0.372925 0.403531 - -0.155901 -0.370919 0.392949 - -0.152458 -0.374745 0.390273 - -0.0975593 -0.380509 0.347733 - -0.0909718 -0.383808 0.342622 - -0.0790276 -0.383976 0.33337 - -0.0432737 -0.384347 0.305674 - -0.0263405 -0.381457 0.292565 - -0.0152947 -0.391657 0.283983 - -0.0123977 -0.390105 0.281743 --0.00742693 -0.395849 0.277878 - 0.0163235 -0.378831 0.259524 - 0.0294343 -0.382963 0.249358 - 0.0308999 -0.393934 0.248195 - 0.0641989 -0.414073 0.22235 - 0.0862103 -0.404713 0.205324 - 0.0968082 -0.407049 0.197109 - 0.112586 -0.404165 0.184895 - 0.137533 -0.405854 0.165567 - 0.146995 -0.411086 0.158224 - 0.223914 -0.421785 0.0986156 - 0.23137 -0.420734 0.0928424 - 0.27756 -0.426836 0.0570484 - 0.319588 -0.431541 0.0244813 - 0.336927 -0.433481 0.0110456 - 0.348396 -0.437783 0.00215131 - 0.398567 -0.443655 -0.0367264 - 0.450209 -0.45448 -0.0767555 - 0.499282 -0.45535 -0.11477 - 0.522709 -0.460763 -0.13293 - 0.532929 -0.461674 -0.140849 - 0.658909 -0.529828 -0.238605 - 0.664218 -0.424518 -0.242451 - 0.655732 -0.388255 -0.235786 - 0.661793 -0.34521 -0.240372 - 0.65736 -0.314243 -0.23686 - 0.659217 -0.29116 -0.23824 - 0.664935 -0.285818 -0.242656 - 0.658505 -0.20274 -0.237465 - 0.661739 -0.18149 -0.239916 - 0.66018 -0.151807 -0.238634 - 0.656545 -0.143732 -0.235797 - 0.657211 -0.133108 -0.236287 - 0.651933 -0.11782 -0.232159 - 0.655831 -0.104364 -0.235145 - 0.658542 -0.101261 -0.237237 - 0.655172 -0.0655851 -0.234536 - 0.658654 -0.0238796 -0.237128 - 0.664129 0.0287854 -0.241235 - 0.655686 0.0597915 -0.234617 - 0.659506 0.0742411 -0.237539 - 0.659248 0.0777378 -0.237331 - 0.658096 0.0917095 -0.236403 - 0.657573 0.112893 -0.235944 - 0.647569 0.135712 -0.228138 - 0.658262 0.185266 -0.236295 - 0.657299 0.207143 -0.235493 - 0.656648 0.221853 -0.234952 - 0.653796 0.274054 -0.232611 - 0.649471 0.37254 -0.229012 - 0.336105 0.224574 0.0133471 - 0.529315 0.409979 -0.135844 - 0.654861 0.552333 -0.232732 - 0.663654 0.591894 -0.239443 - 0.66191 0.606611 -0.238055 - 0.661565 0.628557 -0.237732 - 0.659626 0.672936 -0.236118 - 0.6598 0.859921 -0.235779 - 0.659904 0.88292 -0.235802 - 0.501617 0.704571 -0.113644 - 0.226086 0.409202 0.0990353 - 0.16646 0.314327 0.144982 - 0.157709 0.320331 0.151775 - 0.141998 0.397899 0.164142 - 0.12475 0.37902 0.177454 - 0.108794 0.371583 0.189794 - 0.0734568 0.379315 0.217186 - 0.0686599 0.384262 0.220914 - 0.0493651 0.672379 0.236589 - 0.0482873 1.26072 0.238912 - 0.0397651 1.2769 0.245555 - -0.0230428 1.30645 0.29428 - -0.143199 1.31847 0.387384 - -0.171754 1.32121 0.40951 - -0.118583 0.734379 0.366839 - -0.118539 0.562891 0.366371 - -0.116257 0.474917 0.364381 - -0.124105 0.488233 0.370493 - -0.13565 0.506093 0.379481 - -0.230002 0.719143 0.453105 - -0.234092 0.705773 0.456239 - -0.226635 0.66268 0.450354 - -0.238499 0.597415 0.459379 - -0.112211 0.282189 0.360759 - -0.128321 0.275882 0.373222 - -0.133976 0.275657 0.377601 - -0.15501 0.272545 0.393887 - -0.156886 0.270536 0.395335 - -0.190397 0.298398 0.421362 - -0.200004 0.308941 0.428831 - -0.244254 -0.365937 0.45693 - -0.227158 -0.367648 0.443967 - -0.196108 -0.371983 0.42042 - -0.17368 -0.377097 0.403406 - -0.156696 -0.37989 0.390526 - -0.153334 -0.376582 0.387986 - -0.137441 -0.379811 0.375931 - -0.131823 -0.374492 0.371685 - -0.124924 -0.377798 0.366448 - -0.116963 -0.378191 0.360412 - -0.108387 -0.38089 0.353905 - -0.107063 -0.381617 0.352899 - -0.0796433 -0.387389 0.3321 - -0.0585078 -0.385026 0.316086 - -0.0506403 -0.388605 0.310113 - -0.0237416 -0.387218 0.289727 --0.00566291 -0.401172 0.275988 - 0.00074163 -0.388819 0.271165 - 0.02377 -0.389997 0.253706 - 0.0444367 -0.396241 0.238025 - 0.0608585 -0.409518 0.225544 - 0.0700676 -0.388891 0.218615 - 0.0845169 -0.402096 0.207629 - 0.0887075 -0.401082 0.204455 - 0.101953 -0.401518 0.194414 - 0.108721 -0.405577 0.189273 - 0.134353 -0.409575 0.169834 - 0.141363 -0.411827 0.164515 - 0.143952 -0.409597 0.162558 - 0.145376 -0.408941 0.16148 - 0.16811 -0.412546 0.144238 - 0.171946 -0.413701 0.141328 - 0.185115 -0.411501 0.131351 - 0.198397 -0.41313 0.121279 - 0.215129 -0.425604 0.108565 - 0.216608 -0.424558 0.107447 - 0.294949 -0.433159 0.0480417 - 0.299905 -0.43717 0.0442753 - 0.351197 -0.438514 0.00539199 - 0.358177 -0.444002 8.753e-05 - 0.403936 -0.442953 -0.0345953 - 0.405475 -0.440873 -0.0357568 - 0.449032 -0.449961 -0.0687961 - 0.475682 -0.453383 -0.0890054 - 0.537965 -0.462841 -0.13624 - 0.608656 -0.512244 -0.189949 - 0.676521 -0.525232 -0.241423 - 0.67601 -0.499959 -0.240973 - 0.675568 -0.447207 -0.240505 - 0.67808 -0.435073 -0.242379 - 0.676088 -0.389018 -0.240753 - 0.677302 -0.346765 -0.241567 - 0.672627 -0.259458 -0.237804 - 0.673633 -0.187243 -0.238386 - 0.674381 -0.117502 -0.238778 - 0.674593 -0.0922345 -0.238875 - 0.664932 0.0286073 -0.231249 - 0.664831 0.0321085 -0.231163 - 0.664717 0.0356092 -0.231068 - 0.665836 0.164065 -0.231594 - 0.664483 0.167365 -0.23056 - 0.664679 0.17107 -0.2307 - 0.668281 0.22048 -0.233306 - 0.675286 0.277351 -0.238473 - 0.669797 0.278948 -0.234308 - 0.667841 0.28599 -0.232808 - 0.671397 0.319811 -0.235419 - 0.676255 0.359842 -0.239 - 0.673184 0.370911 -0.236645 - 0.472974 0.27728 -0.0851196 - 0.342768 0.216442 0.0134255 - 0.342014 0.218176 0.014001 - 0.33577 0.231898 0.0187686 - 0.336876 0.237363 0.0179439 - 0.336408 0.244046 0.0183154 - 0.676967 0.541491 -0.239084 - 0.676586 0.710448 -0.238371 - 0.672151 0.743737 -0.234926 - 0.67898 0.805938 -0.239946 - 0.60802 0.818954 -0.186125 - 0.678579 1.04865 -0.239033 - 0.680464 1.15175 -0.240203 - 0.217303 0.400471 0.108991 - 0.160986 0.316363 0.151468 - 0.146747 0.315354 0.162258 - 0.307888 0.844069 0.0414399 - 0.420805 1.22609 -0.0431935 - 0.0900442 0.388739 0.205424 - 0.0886923 0.389087 0.20645 - 0.0728942 0.385503 0.218416 - 0.0715535 0.385757 0.219432 - 0.0639809 0.39209 0.225188 - 0.0504345 0.59121 0.235956 - 0.0486932 0.819519 0.237849 - 0.0351011 1.28296 0.249315 - -0.037395 1.3045 0.304322 - -0.069767 1.31039 0.328875 - -0.0744748 1.31184 0.332447 - -0.111732 1.31453 0.360695 - -0.149132 1.31456 0.389045 - -0.16884 1.32033 0.403998 - -0.17417 1.32416 0.408048 - -0.188761 1.32564 0.419112 - -0.173657 1.13037 0.407172 - -0.119444 0.744885 0.365111 - -0.117971 0.608718 0.363653 - -0.119361 0.586249 0.36465 - -0.119557 0.569399 0.364757 - -0.119032 0.550692 0.364311 - -0.118385 0.503397 0.363702 - -0.140289 0.515362 0.380336 - -0.237984 0.752144 0.454984 - -0.222815 0.618606 0.443151 - -0.107346 0.300747 0.354827 - -0.112693 0.28295 0.358835 - -0.124707 0.27677 0.367926 - -0.126628 0.275112 0.369378 - -0.131365 0.273357 0.372964 - -0.154261 0.268717 0.390308 - -0.182499 0.294898 0.411778 - -0.233824 -0.364226 0.444865 - -0.229454 -0.367648 0.441614 - -0.20043 -0.372367 0.42007 - -0.188567 -0.365868 0.411284 - -0.178146 -0.371322 0.40354 - -0.137518 -0.376286 0.373385 - -0.120954 -0.372232 0.361106 - -0.112417 -0.375027 0.354766 - -0.0954328 -0.375347 0.342164 - -0.0792418 -0.381706 0.330136 - -0.0633116 -0.382661 0.318315 - -0.05403 -0.379584 0.311437 - -0.0253425 -0.394132 0.290117 - -0.0138737 -0.39209 0.281613 - 0.00340016 -0.406147 0.268763 - 0.0138572 -0.389771 0.261045 - 0.0193217 -0.389945 0.256991 - 0.045689 -0.397128 0.237411 - 0.0783336 -0.39841 0.213188 - 0.0811245 -0.39781 0.211119 - 0.120289 -0.407934 0.182038 - 0.12573 -0.398561 0.178025 - 0.138369 -0.404911 0.168632 - 0.158352 -0.411548 0.153789 - 0.159794 -0.410817 0.152721 - 0.178189 -0.409511 0.139078 - 0.191403 -0.415993 0.129258 - 0.191416 -0.411512 0.129259 - 0.207872 -0.415402 0.11704 - 0.234382 -0.421584 0.0973574 - 0.250538 -0.420518 0.0853736 - 0.369405 -0.440213 -0.00286314 - 0.421268 -0.448109 -0.0413607 - 0.43655 -0.4493 -0.0527013 - 0.453822 -0.451898 -0.0655217 - 0.48894 -0.455232 -0.0915846 - 0.694216 -0.495348 -0.243979 - 0.687638 -0.4429 -0.238969 - 0.690409 -0.37274 -0.24085 - 0.686661 -0.340754 -0.23799 - 0.685819 -0.223767 -0.237074 - 0.68185 -0.162111 -0.233976 - 0.684829 -0.147986 -0.236151 - 0.682133 -0.0530359 -0.233914 - 0.683851 -0.0316362 -0.235135 - 0.684379 0.0005965 -0.235446 - 0.684329 0.011343 -0.235382 - 0.677393 0.0788001 -0.230069 - 0.681119 0.100892 -0.232778 - 0.689482 0.127928 -0.238916 - 0.684622 0.167667 -0.235211 - 0.684349 0.267277 -0.23476 - 0.694294 0.307957 -0.242037 - 0.68616 0.384334 -0.235812 - 0.655302 0.378971 -0.212932 - 0.473865 0.285057 -0.0785563 - 0.337608 0.220396 0.0223721 - 0.337249 0.229182 0.0226606 - 0.690596 0.636147 -0.238477 - 0.692475 0.667211 -0.239793 - 0.677664 0.694199 -0.228737 - 0.683011 0.718621 -0.232644 - 0.683275 0.902179 -0.232382 - 0.59558 0.795811 -0.167586 - 0.529696 0.722712 -0.118888 - 0.693166 1.10352 -0.239219 - 0.17347 0.323103 0.144403 - 0.164667 0.316624 0.150918 - 0.125102 0.37712 0.180422 - 0.120758 0.383049 0.183659 - 0.113753 0.372101 0.18883 - 0.108741 0.374927 0.192555 - 0.106791 0.372481 0.193995 - 0.104179 0.37335 0.195936 - 0.062645 0.393288 0.226799 - 0.0570327 0.430215 0.231055 - 0.00305685 1.29867 0.273263 --0.00157557 1.30253 0.276709 - -0.0567878 1.30688 0.317682 - -0.0844875 1.3067 0.338233 - -0.0892398 1.30807 0.341762 - -0.165243 1.31549 0.398167 - -0.195448 1.32445 0.420599 - -0.198757 1.3154 0.423032 - -0.155512 0.996634 0.390154 - -0.125272 0.623241 0.366789 - -0.121213 0.578772 0.363667 - -0.198307 0.67238 0.421096 - -0.214528 0.586064 0.432916 - -0.20715 0.555944 0.427367 - -0.103525 0.280311 0.349801 - -0.112441 0.279541 0.356414 - -0.124355 0.275934 0.365244 - -0.150247 0.27202 0.384443 - -0.160059 0.272306 0.391724 - -0.176629 0.291479 0.404065 - -0.913502 1.26439 0.953178 - -0.963333 1.27449 0.990173 - -0.241795 -0.368791 0.446421 - -0.217775 -0.366504 0.428997 - -0.164725 -0.370598 0.390495 - -0.149059 -0.375217 0.379118 - -0.135515 -0.379783 0.369279 - -0.127342 -0.380409 0.363348 - -0.0977757 -0.383441 0.341887 - -0.0716935 -0.376804 0.322979 - -0.0573701 -0.38399 0.312568 - -0.0560137 -0.384426 0.311583 - -0.0515496 -0.383748 0.308346 - -0.0486511 -0.383576 0.306243 - -0.0368242 -0.380599 0.297669 --0.00821665 -0.383914 0.276904 - -0.0068607 -0.384085 0.27592 - 0.00110498 -0.38795 0.270131 - 0.0145948 -0.397822 0.260318 - 0.0174232 -0.396911 0.258268 - 0.018928 -0.389945 0.257194 - 0.0244394 -0.385999 0.253205 - 0.0358132 -0.402743 0.244911 - 0.102526 -0.409722 0.196488 - 0.154086 -0.41183 0.159072 - 0.156725 -0.414847 0.15715 - 0.16998 -0.413462 0.147536 - 0.179721 -0.411323 0.140473 - 0.182622 -0.409631 0.138373 - 0.215199 -0.412222 0.114729 - 0.220142 -0.414464 0.111137 - 0.237349 -0.416752 0.0986466 - 0.240123 -0.418128 0.0966303 - 0.251631 -0.427974 0.0882559 - 0.295495 -0.428434 0.0564284 - 0.418256 -0.445535 -0.032686 - 0.457445 -0.452543 -0.0611378 - 0.543657 -0.465647 -0.123724 - 0.658464 -0.527867 -0.207179 - 0.691623 -0.53478 -0.231255 - 0.710608 -0.498801 -0.244942 - 0.702955 -0.35091 -0.239023 - 0.696966 -0.326681 -0.234617 - 0.699625 -0.315421 -0.236519 - 0.701908 -0.271326 -0.238067 - 0.695193 -0.236997 -0.233109 - 0.69451 -0.228956 -0.232594 - 0.703927 -0.216469 -0.239396 - 0.703817 -0.20475 -0.239287 - 0.703575 -0.193073 -0.239083 - 0.696212 -0.123409 -0.233568 - 0.696646 -0.119787 -0.233874 - 0.696731 -0.0320215 -0.233719 - 0.697264 0.00422966 -0.234016 - 0.698027 0.011495 -0.234552 - 0.69786 0.0223835 -0.234404 - 0.696907 0.139573 -0.233423 - 0.696877 0.24656 -0.233137 - 0.695881 0.273994 -0.232346 - 0.705886 0.375215 -0.239355 - 0.336799 0.2206 0.0280632 - 0.701743 0.596988 -0.235802 - 0.704942 0.622199 -0.23806 - 0.676846 0.688349 -0.217511 - 0.710093 0.854256 -0.241224 - 0.707325 0.896507 -0.239111 - 0.710715 1.11422 -0.241033 - 0.70816 1.13038 -0.239139 - 0.235389 0.408389 0.102107 - 0.166206 0.321773 0.152091 - 0.157506 0.321772 0.158404 - 0.197801 0.528649 0.129678 - 0.150208 0.403418 0.163901 - 0.13323 0.378096 0.176157 - 0.112308 0.370657 0.191319 - 0.107528 0.387859 0.19483 - 0.0740177 0.383266 0.219133 - 0.0651483 0.404994 0.225622 - 0.0603593 0.416736 0.229125 - 0.0545861 0.492667 0.233502 - 0.0513872 0.574098 0.236024 - 0.0208547 1.29398 0.259957 - -0.0440716 1.31012 0.307106 - -0.0578844 1.30788 0.317122 - -0.0857378 1.3067 0.337329 - -0.0906149 1.30907 0.340874 - -0.1096 1.31131 0.354654 - -0.11423 1.31056 0.358012 - -0.127384 0.645975 0.365914 - -0.123394 0.524779 0.362719 - -0.123821 0.511865 0.362998 - -0.124637 0.500859 0.363562 - -0.127312 0.496419 0.365492 - -0.235718 0.706804 0.444669 - -0.226727 0.644673 0.437992 - -0.106059 0.277173 0.34953 - -0.112193 0.276132 0.353978 - -0.115973 0.27558 0.356719 - -0.120291 0.273335 0.359847 - -0.124015 0.275082 0.362553 - -0.133942 0.280007 0.369768 - -0.148947 0.267344 0.380624 - -0.213153 0.335106 0.427378 - -0.268756 -0.371439 0.460334 - -0.245077 -0.362945 0.443631 - -0.215511 -0.362362 0.42275 - -0.199317 -0.366371 0.411302 - -0.198011 -0.367559 0.410376 - -0.18752 -0.363283 0.402977 - -0.181549 -0.376838 0.398726 - -0.166861 -0.363498 0.388385 - -0.136651 -0.378009 0.367012 - -0.102886 -0.375207 0.34317 - -0.0866617 -0.377509 0.331705 - 0.0144626 -0.382829 0.260267 - 0.0170813 -0.388913 0.258403 - 0.0425754 -0.400338 0.240368 - 0.0485799 -0.404861 0.236116 - 0.0500227 -0.404724 0.235098 - 0.0813098 -0.39781 0.213016 - 0.108247 -0.406032 0.19397 - 0.112793 -0.405609 0.19076 - 0.114239 -0.405129 0.18974 - 0.138882 -0.408361 0.172327 - 0.15572 -0.409266 0.160432 - 0.157178 -0.408557 0.159404 - 0.165823 -0.413941 0.153284 - 0.179934 -0.413974 0.143318 - 0.183577 -0.414098 0.140745 - 0.196801 -0.415054 0.131402 - 0.206791 -0.412002 0.124354 - 0.215967 -0.419499 0.117854 - 0.267612 -0.425741 0.0813613 - 0.292452 -0.431989 0.0638017 - 0.305682 -0.433313 0.0544538 - 0.333121 -0.43128 0.0350786 - 0.362462 -0.436373 0.0143426 - 0.40573 -0.447068 -0.0162443 - 0.41685 -0.444264 -0.0240914 - 0.476235 -0.451981 -0.0660544 - 0.477844 -0.449559 -0.0671851 - 0.727641 -0.47691 -0.243685 - 0.725282 -0.465559 -0.241991 - 0.717256 -0.359637 -0.236063 - 0.721039 -0.318418 -0.238634 - 0.725165 -0.307556 -0.241522 - 0.724719 -0.30314 -0.241196 - 0.727913 -0.291883 -0.243424 - 0.721981 -0.28527 -0.239219 - 0.715628 -0.19095 -0.2345 - 0.714428 -0.179021 -0.233624 - 0.716545 -0.118516 -0.23497 - 0.7182 -0.062523 -0.236002 - 0.716816 -0.0104839 -0.234897 - 0.715757 0.0264812 -0.234059 - 0.715915 0.0746974 -0.234052 - 0.711325 0.100165 -0.230748 - 0.713047 0.115371 -0.231927 - 0.713147 0.15311 -0.231905 - 0.716239 0.211813 -0.233945 - 0.717065 0.216 -0.234519 - 0.721039 0.221204 -0.237313 - 0.715793 0.25538 -0.233524 - 0.719491 0.323022 -0.23597 - 0.718591 0.339677 -0.235294 - 0.72069 0.349354 -0.236752 - 0.688849 0.397316 -0.214146 - 0.576043 0.333533 -0.134626 - 0.55399 0.348834 -0.119012 - 0.372273 0.236411 0.00906008 - 0.330385 0.236663 0.0386461 - 0.721086 0.597711 -0.236424 - 0.721944 0.61525 -0.236987 - 0.681065 0.680951 -0.207953 - 0.544758 0.720208 -0.111582 - 0.718872 1.04062 -0.233776 - 0.724741 1.06828 -0.237853 - 0.729443 1.11471 -0.241061 - 0.686869 1.19088 -0.210804 - 0.245116 0.416176 0.0993117 - 0.239651 0.409776 0.103156 - 0.219301 0.405138 0.117518 - 0.159809 0.318557 0.159326 - 0.157979 0.376113 0.16076 - 0.189383 0.481535 0.138836 - 0.132969 0.380564 0.178435 - 0.131612 0.381138 0.179395 - 0.129464 0.378865 0.180906 - 0.121707 0.377758 0.186382 - 0.106042 0.372919 0.197435 - 0.108257 0.389793 0.195912 - 0.102495 0.390548 0.199983 - 0.0766167 0.381738 0.21824 - 0.053862 0.51377 0.234635 - 0.0501054 0.714341 0.237779 - 0.0431649 1.27782 0.244061 - 0.0249536 1.29 0.256954 - -0.0029411 1.30452 0.276691 - -0.0587358 1.3019 0.316093 - -0.0918822 1.30608 0.339515 - -0.110896 1.30734 0.352948 - -0.129749 1.3062 0.36626 - -0.198919 1.31759 0.415144 - -0.140806 0.843868 0.372938 - -0.130144 0.649815 0.364933 - -0.129947 0.57348 0.364607 - -0.234042 0.755051 0.438574 - -0.225669 0.656849 0.43242 - -0.110143 0.32671 0.350015 - -0.0971554 0.288822 0.340749 - -0.10072 0.281988 0.343249 - -0.101724 0.281316 0.343957 - -0.116288 0.27549 0.354229 - -0.121431 0.277413 0.357867 - -0.125194 0.279186 0.360529 - -0.137385 0.265071 0.369105 - -0.973045 1.28665 0.961838 - -0.257702 -0.363705 0.448062 - -0.217671 -0.362362 0.420429 - -0.211202 -0.362238 0.415964 - -0.136315 -0.373572 0.364237 - -0.103663 -0.383038 0.341672 - -0.081887 -0.377917 0.326651 - -0.0472377 -0.388627 0.302704 - -0.0355848 -0.388437 0.294659 - -0.0115576 -0.390694 0.278066 --0.00616934 -0.394364 0.274337 - 0.00390665 -0.392284 0.267386 - 0.00817368 -0.391561 0.264442 - 0.00972547 -0.387642 0.26338 - 0.0437425 -0.399235 0.239868 - 0.049602 -0.400737 0.235819 - 0.0552759 -0.399125 0.231906 - 0.064762 -0.406907 0.225338 - 0.0735151 -0.405452 0.219299 - 0.0986233 -0.394553 0.201991 - 0.110597 -0.401246 0.193708 - 0.121282 -0.406974 0.186318 - 0.14204 -0.406173 0.171989 - 0.153686 -0.40624 0.163949 - 0.214639 -0.414266 0.12185 - 0.243639 -0.423514 0.101806 - 0.266012 -0.428331 0.0863488 - 0.299769 -0.425397 0.0630513 - 0.324583 -0.431723 0.045905 - 0.33942 -0.437291 0.0356484 - 0.339899 -0.434114 0.0353252 - 0.342552 -0.433923 0.0334942 - 0.353401 -0.440878 0.0259877 - 0.381819 -0.442611 0.00636421 - 0.437429 -0.448438 -0.032041 - 0.441875 -0.445348 -0.0351032 - 0.444714 -0.444435 -0.037061 - 0.463645 -0.448276 -0.0501393 - 0.46715 -0.447854 -0.0525581 - 0.47193 -0.448674 -0.05586 - 0.497977 -0.453995 -0.0738556 - 0.532656 -0.461456 -0.0978151 - 0.735895 -0.504151 -0.238229 - 0.74223 -0.463672 -0.242504 - 0.743893 -0.459856 -0.243643 - 0.7389 -0.404659 -0.240061 - 0.734404 -0.370431 -0.236874 - 0.738819 -0.34168 -0.239853 - 0.733164 -0.308905 -0.235869 - 0.732554 -0.295966 -0.235417 - 0.739969 -0.212334 -0.240332 - 0.732598 -0.159012 -0.235114 - 0.734031 -0.116828 -0.236 - 0.738932 -0.109919 -0.239368 - 0.737148 -0.0943019 -0.238098 - 0.732238 -0.0444881 -0.234587 - 0.732539 -0.0369741 -0.234777 - 0.734053 0.00439254 -0.235721 - 0.730796 0.0418852 -0.233381 - 0.732942 0.0495518 -0.234844 - 0.737419 0.118624 -0.237767 - 0.73657 0.145541 -0.237116 - 0.733034 0.231492 -0.234466 - 0.634443 0.366311 -0.166074 - 0.509812 0.304457 -0.0801826 - 0.333962 0.251946 0.0410917 - 0.735028 0.616752 -0.234906 - 0.742944 0.641021 -0.240312 - 0.68561 0.680951 -0.200633 - 0.742811 0.807727 -0.239815 - 0.23465 0.397996 0.110008 - 0.143962 0.389761 0.172597 - 0.142277 0.389453 0.173759 - 0.117793 0.384569 0.19065 - 0.0897616 0.383843 0.210001 - 0.0644944 0.400031 0.227484 - 0.0576848 0.444158 0.232292 - 0.0517049 1.26059 0.238405 --0.00813393 1.30036 0.279812 - -0.022316 1.30471 0.289614 - -0.116901 1.30561 0.354915 - -0.142679 1.3203 0.372747 - -0.176387 1.31738 0.396011 - -0.133645 0.55677 0.364654 - -0.134035 0.527966 0.364854 - -0.240182 0.766114 0.438713 - -0.0987209 0.286396 0.339887 - -0.105063 0.279957 0.34425 - -0.153331 0.28069 0.377574 - -0.182093 0.309121 0.397499 - -0.931879 1.31282 0.917569 - -0.965855 1.30108 0.940996 - -0.281698 -0.374723 0.459906 - -0.244161 -0.364975 0.434593 - -0.23346 -0.362938 0.427375 - -0.229762 -0.364092 0.424876 - -0.210312 -0.367527 0.41174 - -0.177109 -0.368977 0.389325 - -0.172201 -0.370419 0.386009 - -0.158849 -0.373244 0.37699 - -0.151905 -0.370005 0.372311 - -0.144782 -0.373644 0.367494 - -0.123139 -0.383364 0.352862 - -0.0923117 -0.378192 0.332067 - -0.0876463 -0.378096 0.328918 - -0.0752629 -0.383049 0.320548 - -0.0724897 -0.384069 0.318674 - -0.0559058 -0.383335 0.307482 - -0.0481091 -0.396818 0.302187 - -0.0466737 -0.397188 0.301217 - -0.0209954 -0.380301 0.283926 --0.00867165 -0.38309 0.275601 - 0.00361313 -0.388291 0.267296 - 0.0319273 -0.397855 0.248162 - 0.0449752 -0.399124 0.239352 - 0.0531765 -0.39232 0.233833 - 0.0545952 -0.392158 0.232876 - 0.0857517 -0.396854 0.211835 - 0.0887632 -0.406335 0.209779 - 0.114672 -0.411403 0.192279 - 0.113332 -0.398377 0.193215 - 0.125796 -0.404426 0.184787 - 0.142157 -0.410574 0.17373 - 0.152202 -0.40506 0.166963 - 0.160881 -0.415985 0.161078 - 0.162385 -0.415256 0.160065 - 0.177618 -0.408436 0.1498 - 0.185288 -0.409631 0.14462 - 0.248177 -0.425715 0.102132 - 0.326394 -0.431723 0.0493243 - 0.401877 -0.440775 -0.00164664 - 0.450759 -0.451935 -0.0346672 - 0.497442 -0.454642 -0.0661838 - 0.519732 -0.459179 -0.0812398 - 0.552332 -0.463298 -0.103253 - 0.590542 -0.465504 -0.12905 - 0.662571 -0.50998 -0.177774 - 0.722973 -0.537222 -0.218609 - 0.760948 -0.47258 -0.244086 - 0.755585 -0.430276 -0.240364 - 0.759462 -0.41352 -0.24294 - 0.758234 -0.3621 -0.241987 - 0.758122 -0.308935 -0.241783 - 0.755128 -0.281967 -0.239697 - 0.753558 -0.2645 -0.238596 - 0.75312 -0.123085 -0.237958 - 0.749432 -0.103031 -0.235421 - 0.754816 -0.0533257 -0.238935 - 0.755182 -0.0456235 -0.239164 - 0.753009 -0.0377891 -0.237678 - 0.751804 -0.0223711 -0.236828 - 0.75092 0.0504705 -0.236055 - 0.755056 0.0662271 -0.238808 - 0.748258 0.100254 -0.234138 - 0.748716 0.104186 -0.234437 - 0.739669 0.125896 -0.228279 - 0.748392 0.143053 -0.234125 - 0.741208 0.168922 -0.229214 - 0.748969 0.210736 -0.234351 - 0.751229 0.298611 -0.235665 - 0.750146 0.302438 -0.234925 - 0.758619 0.349919 -0.240529 - 0.756837 0.358017 -0.239307 - 0.753643 0.392733 -0.237067 - 0.737203 0.392924 -0.22597 - 0.73672 0.602879 -0.225137 - 0.752319 0.699721 -0.235432 - 0.5661 0.786999 -0.10953 - 0.760898 1.14872 -0.240139 - 0.744703 1.20825 -0.229065 - 0.737922 1.20796 -0.224488 - 0.30051 0.499955 0.0690428 - 0.235122 0.404442 0.112948 - 0.216198 0.398396 0.125706 - 0.169459 0.314226 0.15705 - 0.159528 0.318387 0.163764 - 0.152335 0.314914 0.16861 - 0.147409 0.316667 0.171939 - 0.164058 0.419209 0.160949 - 0.155467 0.398574 0.166698 - 0.141318 0.384761 0.176215 - 0.0928043 0.392297 0.208978 - 0.0902003 0.385801 0.21072 - 0.0839904 0.383208 0.214906 - 0.063553 0.406199 0.228756 - 0.0607953 0.408589 0.230623 - 0.0533901 0.680091 0.236276 - 0.0535795 0.909322 0.236702 - -0.0372913 1.30584 0.298993 - -0.0465739 1.30214 0.30525 - -0.0512829 1.30175 0.308428 - -0.0755583 1.30939 0.324831 - -0.153954 1.31946 0.37777 - -0.193472 1.31994 0.404445 - -0.135701 0.619667 0.363761 - -0.136885 0.525245 0.364333 - -0.136283 0.509507 0.363888 - -0.141497 0.506001 0.367399 - -0.143633 0.506053 0.368841 - -0.258783 0.793586 0.447257 - -0.185347 0.540881 0.397081 - -0.0937629 0.277891 0.33463 - -0.106077 0.288138 0.342966 - -0.108313 0.29008 0.34448 - -0.110408 0.288678 0.345891 - -0.110228 0.285359 0.345761 - -0.114817 0.27516 0.348834 - -0.115812 0.274427 0.349504 - -0.118111 0.27624 0.35106 - -0.127239 0.277514 0.357224 - -0.183518 0.31975 0.395313 - -0.947499 1.33592 0.913429 - -0.964472 1.31228 0.924828 - -0.968315 1.29447 0.927379 - -0.976554 1.24933 0.932831 - -0.248284 -0.364311 0.433258 - -0.235383 -0.365812 0.424743 - -0.143533 -0.36749 0.364138 - -0.13872 -0.376194 0.360941 - -0.127982 -0.379216 0.35385 - -0.0854845 -0.377355 0.325815 - -0.0760673 -0.382093 0.31959 - -0.0512274 -0.38494 0.303195 - -0.0395869 -0.376675 0.295534 - -0.0203174 -0.39364 0.28278 --0.00260293 -0.388819 0.271104 - 0.0301805 -0.397898 0.249452 - 0.0503749 -0.395612 0.236133 - 0.068683 -0.416366 0.224004 - 0.0701992 -0.416122 0.223005 - 0.0833831 -0.400451 0.214344 - 0.0991954 -0.403724 0.203903 - 0.101602 -0.408192 0.202305 - 0.111761 -0.404147 0.195611 - 0.116616 -0.404642 0.192407 - 0.135493 -0.402939 0.179957 - 0.159639 -0.410414 0.164008 - 0.164432 -0.409155 0.160848 - 0.188132 -0.419522 0.145187 - 0.201761 -0.411416 0.136214 - 0.22742 -0.424174 0.119254 - 0.316552 -0.434168 0.060422 - 0.342599 -0.432617 0.0432405 - 0.378925 -0.441364 0.0192521 - 0.431534 -0.448235 -0.0154748 - 0.465668 -0.44867 -0.0379969 - 0.477526 -0.456625 -0.0458396 - 0.557383 -0.460507 -0.098537 - 0.586645 -0.468046 -0.117862 - 0.726134 -0.536149 -0.210057 - 0.766703 -0.48319 -0.236697 - 0.774147 -0.472875 -0.241584 - 0.766781 -0.44855 -0.236665 - 0.767958 -0.429886 -0.237397 - 0.77221 -0.385012 -0.240095 - 0.771823 -0.343739 -0.239741 - 0.76372 -0.309264 -0.234312 - 0.775546 -0.292292 -0.242074 - 0.772084 -0.282311 -0.239766 - 0.770469 -0.23511 -0.238587 - 0.773704 -0.206976 -0.240654 - 0.77102 -0.193915 -0.238852 - 0.764802 -0.148062 -0.234639 - 0.762023 -0.123777 -0.232748 - 0.774068 -0.105835 -0.240652 - 0.76971 -0.0305851 -0.237597 - 0.767982 0.0552256 -0.23625 - 0.763436 0.113466 -0.233112 - 0.761688 0.128925 -0.231921 - 0.764563 0.189429 -0.233674 - 0.767532 0.227108 -0.235542 - 0.766666 0.235135 -0.234951 - 0.771451 0.240835 -0.238095 - 0.759397 0.266069 -0.230082 - 0.769603 0.274017 -0.236796 - 0.770564 0.37147 -0.237197 - 0.698207 0.439573 -0.189294 - 0.335187 0.224828 0.0497059 - 0.33484 0.231279 0.0499508 - 0.330179 0.234529 0.0530338 - 0.656537 0.531682 -0.16158 - 0.759616 0.623956 -0.229368 - 0.769961 0.644491 -0.236145 - 0.766739 0.671669 -0.233954 - 0.775676 0.95846 -0.239163 - 0.538917 0.717103 -0.083532 - 0.168966 0.314989 0.159592 - 0.154284 0.321882 0.169295 - 0.162771 0.398511 0.16388 - 0.130102 0.37697 0.185382 - 0.122964 0.378712 0.190096 - 0.118002 0.371128 0.193352 - 0.0773253 0.38667 0.220227 - 0.0523947 0.792269 0.237647 - 0.0511951 1.25559 0.239549 - -0.0768074 1.31138 0.324136 - -0.0957173 1.30708 0.336602 - -0.100477 1.30644 0.339741 - -0.144845 1.31239 0.369028 - -0.160682 1.32047 0.379497 - -0.204669 1.31564 0.408508 - -0.143742 0.760918 0.36698 - -0.142409 0.692924 0.365937 - -0.138158 0.604629 0.362921 - -0.138383 0.587722 0.363029 - -0.14151 0.50135 0.364885 - -0.287808 0.867985 0.462288 - -0.32609 0.929691 0.487694 - -0.129211 0.28662 0.356256 - -0.178146 0.320077 0.388622 - -0.186891 0.322113 0.394397 - -0.953633 1.33441 0.902706 - -0.966472 1.31673 0.911134 - -1.34009 -1.63602 1.1301 - -0.257527 -0.360794 0.435155 - -0.235898 -0.363521 0.421204 - -0.218539 -0.367421 0.410002 - -0.204378 -0.365146 0.400877 - -0.198606 -0.372579 0.397138 - -0.193539 -0.374339 0.393867 - -0.172054 -0.367213 0.380031 - -0.136346 -0.367301 0.357008 - -0.127937 -0.375605 0.351567 - -0.108397 -0.371759 0.338977 - -0.100177 -0.375704 0.333668 - -0.0910438 -0.381867 0.327765 - -0.089643 -0.382452 0.32686 - -0.0815666 -0.381463 0.321655 - -0.0801674 -0.381999 0.320752 - -0.0674887 -0.386493 0.312567 - -0.066071 -0.386955 0.311652 - -0.0535124 -0.38455 0.30356 - -0.0490942 -0.384722 0.300711 - -0.0448569 -0.385801 0.297976 - -0.041861 -0.385503 0.296046 - -0.016744 -0.395274 0.279828 - 0.00555395 -0.386483 0.265472 - 0.0125913 -0.388826 0.26093 - 0.019777 -0.381987 0.256313 - 0.0225767 -0.385999 0.254498 - 0.0326856 -0.393807 0.247962 - 0.0343605 -0.401744 0.246863 - 0.0471137 -0.392894 0.238661 - 0.0711069 -0.410918 0.223149 - 0.0893041 -0.399121 0.211444 - 0.0943874 -0.401956 0.20816 - 0.108977 -0.4123 0.198729 - 0.121253 -0.409411 0.190821 - 0.121815 -0.405054 0.190469 - 0.1233 -0.404534 0.189512 - 0.131719 -0.405625 0.184082 - 0.132169 -0.40125 0.183802 - 0.146391 -0.410245 0.174611 - 0.152095 -0.406671 0.170942 - 0.199564 -0.422255 0.140299 - 0.224522 -0.424558 0.124202 - 0.288515 -0.427421 0.0829355 - 0.297266 -0.429603 0.0772883 - 0.339602 -0.433683 0.0499824 - 0.405246 -0.439387 0.00764506 - 0.416988 -0.445023 6.047e-05 - 0.446417 -0.449769 -0.0189248 - 0.494776 -0.454589 -0.0501157 - 0.50898 -0.455851 -0.0592772 - 0.786136 -0.545279 -0.238186 - 0.798161 -0.526806 -0.245896 - 0.79424 -0.518839 -0.243348 - 0.794118 -0.477242 -0.24317 - 0.790786 -0.445158 -0.240946 - 0.79403 -0.437162 -0.243019 - 0.786715 -0.316831 -0.238016 - 0.784744 -0.192075 -0.236448 - 0.789171 -0.147863 -0.239197 - 0.782654 -0.110366 -0.234906 - 0.783056 -0.106419 -0.235156 - 0.787974 -0.0789986 -0.238262 - 0.789628 -0.0671462 -0.2393 - 0.790023 -0.0112875 -0.239422 - 0.782801 0.0361871 -0.234652 - 0.779384 0.0715025 -0.232365 - 0.782095 0.0916269 -0.234065 - 0.780552 0.131377 -0.232976 - 0.779568 0.139238 -0.232323 - 0.779054 0.143165 -0.231982 - 0.777534 0.171135 -0.230935 - 0.778894 0.183673 -0.231782 - 0.785857 0.197772 -0.236238 - 0.781223 0.234009 -0.233164 - 0.786135 0.358364 -0.236035 - 0.780103 0.415964 -0.232009 - 0.708091 0.398194 -0.185622 - 0.339014 0.228533 0.0519375 - 0.33304 0.228644 0.0557896 - 0.32932 0.23932 0.0582135 - 0.771604 0.635935 -0.226006 - 0.790728 0.664272 -0.238268 - 0.783367 0.676164 -0.233494 - 0.749434 0.713034 -0.211528 - 0.774651 0.864108 -0.227428 - 0.789575 0.97848 -0.236778 - 0.542679 0.699223 -0.078256 - 0.791872 1.14007 -0.237874 - 0.746627 1.20714 -0.208542 - 0.271609 0.447177 0.0959168 - 0.162613 0.316061 0.16588 - 0.159906 0.316608 0.167627 - 0.149548 0.316014 0.174304 - 0.148388 0.316667 0.175053 - 0.154806 0.378904 0.171063 - 0.142733 0.381328 0.178853 - 0.136563 0.381867 0.182833 - 0.130412 0.382266 0.186799 - 0.120385 0.373496 0.193244 - 0.0969838 0.397416 0.208388 - 0.0776627 0.39978 0.220851 - 0.0531407 0.546851 0.237012 - 0.0540374 0.64898 0.236677 - 0.0592404 1.08919 0.23437 - 0.0422459 1.28682 0.245797 - 0.0186071 1.29998 0.26107 - -0.0533657 1.30574 0.307488 - -0.219026 1.24893 0.414162 - -0.0953766 0.301698 0.332185 - -0.0965019 0.297749 0.332901 - -0.0986825 0.296496 0.334304 - -0.0997301 0.292537 0.33497 - -0.107275 0.282193 0.33981 - -0.109957 0.279269 0.341533 - -0.96656 1.25121 0.896141 - -1.33524 -1.64507 1.10283 - -0.247995 -0.36702 0.424189 - -0.245274 -0.369786 0.422476 - -0.155042 -0.373579 0.365895 - -0.146284 -0.370118 0.360412 - -0.134494 -0.375026 0.353009 - -0.133107 -0.375828 0.352138 - -0.123317 -0.376848 0.345997 - -0.114005 -0.369691 0.340176 - -0.0712752 -0.384584 0.313351 - -0.0658872 -0.381166 0.309981 - -0.0418268 -0.379618 0.2949 - -0.0312488 -0.386947 0.28825 - -0.0283864 -0.38748 0.286454 - -0.0205285 -0.395846 0.281508 - -0.0175006 -0.395274 0.279611 --0.00879963 -0.397352 0.274151 - 0.00217293 -0.385296 0.2673 - 0.0106644 -0.387773 0.261971 - 0.0122033 -0.383829 0.261015 - 0.0265677 -0.399961 0.251971 - 0.0621647 -0.399178 0.229655 - 0.0689725 -0.406214 0.22537 - 0.0734742 -0.405452 0.22255 - 0.114171 -0.398377 0.197051 - 0.127654 -0.407294 0.188577 - 0.144194 -0.412461 0.178195 - 0.211006 -0.414737 0.136301 - 0.215696 -0.416278 0.133357 - 0.264221 -0.42343 0.102917 - 0.267692 -0.425482 0.100736 - 0.300664 -0.42436 0.0800665 - 0.381846 -0.443222 0.029124 - 0.409913 -0.445555 0.0115219 - 0.608276 -0.470564 -0.112903 - 0.813887 -0.491009 -0.241861 - 0.814237 -0.470573 -0.242032 - 0.809212 -0.403257 -0.238722 - 0.807507 -0.369142 -0.237573 - 0.811648 -0.324727 -0.240064 - 0.808668 -0.287563 -0.238108 - 0.810538 -0.283801 -0.239272 - 0.810478 -0.239939 -0.23913 - 0.809683 -0.205375 -0.238551 - 0.807037 -0.196219 -0.23687 - 0.803 -0.10025 -0.234112 - 0.806376 -0.0802951 -0.236182 - 0.809747 -0.0683937 -0.238267 - 0.806616 -0.0640613 -0.236294 - 0.803468 -0.0597625 -0.23431 - 0.806487 -0.0276061 -0.236127 - 0.806793 -0.0114482 -0.236281 - 0.805604 0.081552 -0.235316 - 0.814293 0.152902 -0.240595 - 0.812762 0.169368 -0.239597 - 0.8091 0.210778 -0.237203 - 0.808361 0.284274 -0.236566 - 0.80067 0.312463 -0.231677 - 0.815939 0.327733 -0.241214 - 0.814724 0.331815 -0.240443 - 0.811328 0.362751 -0.238241 - 0.81035 0.405006 -0.237528 - 0.799587 0.428355 -0.230725 - 0.742813 0.401591 -0.195193 - 0.585954 0.357839 -0.0969523 - 0.713231 0.466539 -0.176493 - 0.412526 0.268845 0.01157 - 0.324803 0.236488 0.0664923 - 0.762197 0.676521 -0.206697 - 0.719064 0.696471 -0.179607 - 0.700372 0.683799 -0.167918 - 0.681908 0.682987 -0.156344 - 0.675571 0.682395 -0.152373 - 0.768672 0.8509 -0.210345 - 0.685065 1.13786 -0.15725 - 0.332877 0.543284 0.0621543 - 0.256312 0.417142 0.10986 - 0.239366 0.39436 0.12043 - 0.2369 0.39742 0.121983 - 0.22802 0.403901 0.127567 - 0.217565 0.403011 0.134119 - 0.164051 0.324612 0.167485 - 0.153492 0.32076 0.174096 - 0.156261 0.386064 0.172514 - 0.122224 0.379228 0.193838 - 0.105909 0.394981 0.204104 - 0.0884362 0.391389 0.21505 - 0.0740398 0.384254 0.224059 - 0.0276722 1.29399 0.255277 - 0.00371156 1.29678 0.270306 - -0.0493118 1.30015 0.303558 - -0.212434 1.27899 0.405779 - -0.220039 1.19386 0.410345 - -0.147494 0.646401 0.363571 - -0.147217 0.557971 0.363188 - -0.148256 0.505125 0.363715 - -0.0978494 0.287792 0.331599 - -0.0989128 0.287169 0.332264 - -0.139288 0.277591 0.357555 - -0.204727 0.346126 0.398744 - -0.206526 0.34574 0.399872 - -0.920732 1.3503 0.850021 - -0.971177 1.29083 0.881507 - -0.970796 1.27906 0.88124 - -0.974738 1.21842 0.883569 - -1.3265 -1.5787 1.07263 - -0.24946 -0.35898 0.420119 - -0.24025 -0.365625 0.414499 - -0.22266 -0.363023 0.403802 - -0.212932 -0.367974 0.397871 - -0.200922 -0.362151 0.390576 - -0.188143 -0.371257 0.382779 - -0.180277 -0.367705 0.378001 - -0.133737 -0.373131 0.349669 - -0.120077 -0.377228 0.341347 - -0.104652 -0.380366 0.331954 - -0.0921123 -0.381508 0.324321 - -0.0491993 -0.382157 0.298207 - -0.0344599 -0.382443 0.289238 - -0.0193505 -0.391097 0.280023 - -0.0148808 -0.390694 0.277305 --0.00912967 -0.392372 0.273801 - -0.0046725 -0.39181 0.27109 - 0.00560198 -0.391561 0.264839 - 0.00995138 -0.39277 0.26219 - 0.0158088 -0.392944 0.258625 - 0.0289556 -0.3909 0.25063 - 0.043959 -0.398126 0.241484 - 0.0608304 -0.402362 0.231208 - 0.0710009 -0.410918 0.224999 - 0.0767317 -0.395738 0.221547 - 0.0845954 -0.407338 0.216735 - 0.0874714 -0.405695 0.214989 - 0.0914937 -0.401709 0.212551 - 0.0972892 -0.39924 0.20903 - 0.130086 -0.408655 0.189051 - 0.172907 -0.407045 0.162999 - 0.174424 -0.406267 0.162078 - 0.190899 -0.410574 0.152043 - 0.234542 -0.422878 0.125457 - 0.239008 -0.423255 0.122739 - 0.240585 -0.422139 0.121782 - 0.268301 -0.42383 0.104913 - 0.274373 -0.426219 0.101213 - 0.287179 -0.431531 0.093408 - 0.287782 -0.428552 0.0930476 - 0.315736 -0.432531 0.0760285 - 0.343964 -0.437597 0.0588407 - 0.362834 -0.439398 0.0473537 - 0.399188 -0.44162 0.0252276 - 0.477399 -0.451252 -0.0223861 - 0.531981 -0.457962 -0.0556143 - 0.647816 -0.475481 -0.12614 - 0.840226 -0.541461 -0.243374 - 0.837828 -0.465293 -0.241737 - 0.837208 -0.41937 -0.241253 - 0.836182 -0.370081 -0.240513 - 0.830106 -0.306784 -0.236668 - 0.834977 -0.219085 -0.239426 - 0.833252 -0.209905 -0.238355 - 0.839506 -0.189712 -0.242113 - 0.840209 -0.185533 -0.242531 - 0.830972 -0.0946906 -0.236698 - 0.834541 -0.0700081 -0.238812 - 0.841008 -0.0621555 -0.242728 - 0.841236 -0.0579706 -0.242857 - 0.824723 -0.0157224 -0.23271 - 0.824778 -0.0116213 -0.232734 - 0.829794 0.021324 -0.235709 - 0.829281 0.137722 -0.235125 - 0.835554 0.155808 -0.2389 - 0.832284 0.172226 -0.236871 - 0.830798 0.17618 -0.235958 - 0.837529 0.288025 -0.239792 - 0.829665 0.317039 -0.234939 - 0.834143 0.323415 -0.237649 - 0.833361 0.3558 -0.237097 - 0.839412 0.387288 -0.240705 - 0.831766 0.393321 -0.236038 - 0.835024 0.399776 -0.238006 - 0.339726 0.223796 0.0629675 - 0.335135 0.22494 0.0657641 - 0.334898 0.229191 0.0659177 - 0.33174 0.231302 0.0678446 - 0.326273 0.233831 0.071177 - 0.781883 0.962606 -0.204352 - 0.54335 0.702322 -0.0598162 - 0.54485 0.723224 -0.0606794 - 0.556986 0.74658 -0.0680099 - 0.781501 1.20161 -0.20356 - 0.242538 0.397717 0.122513 - 0.225712 0.397041 0.13275 - 0.224209 0.414302 0.133705 - 0.166347 0.317983 0.168688 - 0.154964 0.315812 0.17561 - 0.144894 0.31586 0.181737 - 0.151615 0.385302 0.17781 - 0.144655 0.384139 0.182042 - 0.132931 0.382653 0.189173 - 0.126689 0.382951 0.192971 - 0.106319 0.395951 0.205397 - 0.0970679 0.396439 0.211027 - 0.0930423 0.391319 0.213465 - 0.081431 0.38481 0.220515 - 0.0736467 0.40455 0.225298 - 0.0563716 0.655802 0.236398 - 0.0559786 0.697903 0.236736 - 0.0175383 1.29798 0.261531 - -0.031068 1.30245 0.291118 - -0.0900825 1.30729 0.32704 - -0.115458 1.31401 0.342496 - -0.197179 1.32206 0.392242 - -0.199612 1.30621 0.393685 - -0.154788 0.734201 0.365071 - -0.149433 0.544004 0.361367 - -0.150447 0.499604 0.36188 - -0.102627 0.289219 0.332289 - -0.103216 0.284378 0.332637 - -0.105586 0.280668 0.33407 - -0.125749 0.27389 0.346323 - -0.127228 0.273975 0.347223 - -0.195 0.343062 0.388624 - -0.944748 1.39726 0.847308 - -0.955138 1.38732 0.853607 - -0.960101 1.35772 0.856558 - -0.969963 1.28925 0.862398 - -0.978182 1.21195 0.867219 - -0.255142 -0.360579 0.419695 - -0.198187 -0.368283 0.385819 - -0.159426 -0.371794 0.362769 - -0.156632 -0.373612 0.361104 - -0.148581 -0.371864 0.356322 - -0.131521 -0.372896 0.346178 - -0.111679 -0.383038 0.334359 - -0.110242 -0.383709 0.333503 - -0.106112 -0.381298 0.331053 - -0.051099 -0.388021 0.298335 - -0.0308642 -0.383266 0.286317 - -0.0199677 -0.391097 0.279821 - 0.0257928 -0.398961 0.2526 - 0.0318291 -0.400803 0.249007 - 0.0724866 -0.410661 0.224815 - 0.106772 -0.398718 0.204461 - 0.110405 -0.400737 0.202297 - 0.123179 -0.413256 0.194674 - 0.137052 -0.408272 0.186438 - 0.149684 -0.41589 0.178912 - 0.221223 -0.415138 0.136386 - 0.222779 -0.414118 0.135463 - 0.260885 -0.420909 0.112794 - 0.284351 -0.428816 0.0988267 - 0.317738 -0.433313 0.0789689 - 0.346727 -0.439112 0.0617223 - 0.36524 -0.444109 0.0507054 - 0.369723 -0.442071 0.0480453 - 0.416401 -0.443552 0.0202932 - 0.433881 -0.451186 0.00988454 - 0.502155 -0.460749 -0.0307244 - 0.553679 -0.462054 -0.0613567 - 0.561288 -0.460173 -0.0658756 - 0.581119 -0.464088 -0.0776734 - 0.793594 -0.544577 -0.204169 - 0.852662 -0.519001 -0.239224 - 0.857283 -0.500206 -0.241927 - 0.85257 -0.486753 -0.239094 - 0.856092 -0.462523 -0.241131 - 0.857603 -0.432467 -0.24196 - 0.852571 -0.390011 -0.23887 - 0.847478 -0.377897 -0.235814 - 0.859227 -0.358907 -0.242754 - 0.852998 -0.346675 -0.239023 - 0.853484 -0.342115 -0.239301 - 0.848727 -0.321364 -0.236425 - 0.855559 -0.309951 -0.24046 - 0.85177 -0.276313 -0.238129 - 0.854821 -0.263641 -0.239913 - 0.851248 -0.24001 -0.237734 - 0.853065 -0.222673 -0.238774 - 0.858552 -0.193017 -0.241967 - 0.848595 -0.143119 -0.235931 - 0.849398 -0.121839 -0.236359 - 0.847986 -0.0286794 -0.235303 - 0.846864 0.0594262 -0.234432 - 0.853368 0.184429 -0.238007 - 0.850725 0.227838 -0.236335 - 0.850663 0.236722 -0.236277 - 0.85103 0.259261 -0.236443 - 0.85012 0.281648 -0.23585 - 0.845183 0.373282 -0.232702 - 0.674159 0.387351 -0.131002 - 0.831402 0.539078 -0.224124 - 0.430833 0.283602 0.0134059 - 0.759286 0.629776 -0.181042 - 0.794725 0.678296 -0.201997 - 0.681632 0.685749 -0.13475 - 0.677779 0.68775 -0.132455 - 0.772237 0.858545 -0.188209 - 0.553197 0.687114 -0.0583962 - 0.814444 1.14944 -0.212623 - 0.806335 1.1899 -0.207708 - 0.801869 1.19386 -0.205044 - 0.499028 0.786011 -0.0259646 - 0.244546 0.395751 0.124407 - 0.16765 0.316363 0.169935 - 0.166464 0.323881 0.170658 - 0.149456 0.387543 0.180916 - 0.117516 0.395649 0.199922 - 0.11028 0.406182 0.204249 - 0.108756 0.406627 0.205156 - 0.092163 0.394614 0.214991 - 0.0878562 0.387465 0.217535 - 0.0805766 0.399199 0.22189 - 0.0024616 1.30078 0.270424 - -0.0671059 1.31685 0.311817 - -0.205434 1.30016 0.394009 - -0.210901 1.27433 0.397199 - -0.223343 1.21165 0.404449 - -0.159335 0.77264 0.365378 - -0.156788 0.611565 0.363488 - -0.148411 0.529075 0.358317 - -0.118472 0.276464 0.339931 - -0.125434 0.27624 0.34407 - -0.138068 0.285851 0.351602 - -0.878633 1.37712 0.794381 - -0.929936 1.39145 0.824912 - -0.942141 1.39674 0.83218 - -0.957789 1.38192 0.841447 - -0.955979 1.35507 0.840309 - -0.975802 1.25485 0.85186 - -0.281144 -0.381425 0.430859 - -0.265281 -0.37103 0.421676 - -0.228252 -0.368998 0.400188 - -0.215023 -0.365569 0.392518 - -0.199988 -0.371866 0.383777 - -0.163598 -0.37348 0.362652 - -0.158937 -0.375362 0.359943 - -0.145587 -0.370023 0.352206 - -0.129648 -0.373524 0.342947 - -0.124694 -0.378329 0.340061 - -0.0838704 -0.384435 0.316352 - -0.0459615 -0.380266 0.294359 - -0.025884 -0.385253 0.282694 - -0.0227486 -0.383725 0.280878 - -0.0187074 -0.387329 0.278524 --0.00823283 -0.385551 0.272449 - 0.00186421 -0.388389 0.266582 - 0.0119926 -0.394871 0.260688 - 0.0312379 -0.389809 0.24953 - 0.0328878 -0.395748 0.248558 - 0.0343812 -0.395683 0.247692 - 0.0420535 -0.399235 0.24323 - 0.049439 -0.396608 0.23895 - 0.0950173 -0.402934 0.212481 - 0.10206 -0.406243 0.208385 - 0.126615 -0.405921 0.194134 - 0.144785 -0.404288 0.183592 - 0.163865 -0.414128 0.172495 - 0.218601 -0.420786 0.14071 - 0.235576 -0.421155 0.130857 - 0.248024 -0.424134 0.123625 - 0.277441 -0.435396 0.106525 - 0.279083 -0.434097 0.105575 - 0.288733 -0.429908 0.0999835 - 0.30251 -0.431824 0.0919831 - 0.305708 -0.432785 0.0901247 - 0.310554 -0.432263 0.0873132 - 0.355656 -0.441048 0.0611148 - 0.359552 -0.438396 0.0588602 - 0.391607 -0.44352 0.040243 - 0.397974 -0.443324 0.0365481 - 0.46074 -0.449549 0.00010335 - 0.690899 -0.478817 -0.133551 - 0.874682 -0.540875 -0.240365 - 0.878907 -0.521232 -0.242772 - 0.876725 -0.42953 -0.241293 - 0.877231 -0.330546 -0.241358 - 0.8723 -0.319117 -0.238469 - 0.87253 -0.276968 -0.238505 - 0.873749 -0.235997 -0.239118 - 0.870451 -0.226037 -0.237181 - 0.878599 -0.196515 -0.241842 - 0.876035 -0.120663 -0.240178 - 0.875744 -0.0857403 -0.239929 - 0.879514 -0.0686864 -0.242077 - 0.861341 -0.0289775 -0.231438 - 0.873777 0.0653344 -0.238437 - 0.873945 0.126158 -0.238395 - 0.870528 0.147488 -0.236362 - 0.869391 0.156052 -0.235682 - 0.873927 0.237429 -0.238126 - 0.875385 0.316861 -0.238789 - 0.878081 0.366219 -0.24024 - 0.876911 0.375558 -0.239539 - 0.877105 0.380588 -0.23964 - 0.871418 0.407888 -0.236276 - 0.876255 0.430569 -0.239031 - 0.870306 0.453283 -0.235526 - 0.861211 0.463934 -0.230222 - 0.860929 0.561204 -0.229834 - 0.434862 0.287738 0.0168284 - 0.325108 0.246319 0.080435 - 0.674343 0.686361 -0.121248 - 0.764734 0.845218 -0.173344 - 0.782179 0.919484 -0.183297 - 0.783518 0.937323 -0.184034 - 0.717318 0.87868 -0.145746 - 0.547688 0.694389 -0.0477169 - 0.789467 1.1897 -0.186903 - 0.599945 0.921145 -0.0775234 - 0.486941 0.755074 -0.012318 - 0.440377 0.69875 0.014578 - 0.243091 0.444456 0.128496 - 0.241413 0.44557 0.129473 - 0.162577 0.317497 0.174935 - 0.14924 0.344653 0.182738 - 0.149748 0.38223 0.18253 - 0.14162 0.382555 0.187249 - 0.138729 0.383753 0.188929 - 0.127438 0.401736 0.195524 - 0.108519 0.397457 0.206495 - 0.102508 0.399153 0.209988 - 0.0961078 0.39058 0.213683 - 0.0869109 0.390742 0.219021 - 0.0789026 0.398507 0.223687 - 0.0637372 0.431245 0.232565 - 0.0571522 0.499308 0.236545 - 0.0578102 0.643648 0.236497 - 0.0117531 1.30094 0.264749 - -0.0773227 1.30692 0.316463 - -0.1487 1.31722 0.357915 - -0.174247 1.31752 0.372744 - -0.199393 1.31421 0.387331 - -0.229426 1.20844 0.404518 - -0.19856 0.983451 0.386082 - -0.159116 0.693129 0.362518 - -0.158701 0.680736 0.362248 - -0.161269 0.679819 0.363736 - -0.161769 0.641841 0.363938 - -0.156908 0.589905 0.360997 - -0.15087 0.546755 0.357393 - -0.0910238 0.291326 0.322067 - -0.0972337 0.29023 0.325669 - -0.103541 0.295598 0.329342 - -0.113756 0.287259 0.335251 - -0.114244 0.282388 0.335524 - -0.124104 0.285077 0.341253 - -0.865874 1.3734 0.774301 - -1.32262 -1.55784 1.01383 - -1.32907 -1.64943 1.01727 - -0.219594 -0.363177 0.391813 - -0.198745 -0.366918 0.379996 - -0.195952 -0.369102 0.378409 - -0.173479 -0.371315 0.365675 - -0.155055 -0.371885 0.355238 - -0.136068 -0.38181 0.344461 - -0.129883 -0.375188 0.340973 - -0.10621 -0.374772 0.327565 - -0.0791572 -0.374954 0.312242 - -0.074384 -0.386985 0.309511 - -0.0634273 -0.387217 0.303305 - -0.0519398 -0.375934 0.296824 - -0.0452988 -0.380599 0.293052 - -0.0295955 -0.385757 0.284146 - -0.0122976 -0.392213 0.274333 - 0.00280183 -0.389479 0.265787 - 0.026677 -0.402933 0.252233 - 0.0446561 -0.396012 0.242066 - 0.0798671 -0.407285 0.222096 - 0.0809721 -0.404027 0.221478 - 0.0906432 -0.39583 0.216019 - 0.130708 -0.413987 0.193284 - 0.192402 -0.418618 0.15833 - 0.202966 -0.424964 0.152332 - 0.2011 -0.411512 0.153419 - 0.216935 -0.415516 0.144441 - 0.240324 -0.424362 0.131174 - 0.241934 -0.423255 0.130264 - 0.297446 -0.429831 0.0988065 - 0.311969 -0.428434 0.0905841 - 0.332147 -0.434163 0.0791421 - 0.333794 -0.432595 0.0782129 - 0.343813 -0.438588 0.0725242 - 0.407379 -0.440389 0.0365161 - 0.423003 -0.446328 0.0276526 - 0.47628 -0.454923 -0.00254348 - 0.486741 -0.453189 -0.00846416 - 0.51659 -0.457135 -0.02538 - 0.593612 -0.469309 -0.0690336 - 0.839949 -0.554054 -0.208755 - 0.901413 -0.54895 -0.243556 - 0.898364 -0.530066 -0.241786 - 0.899601 -0.525196 -0.242476 - 0.89544 -0.385231 -0.239797 - 0.895452 -0.36523 -0.239757 - 0.900227 -0.318013 -0.242354 - 0.896451 -0.222417 -0.239995 - 0.893659 -0.198848 -0.23836 - 0.89474 -0.0827406 -0.238705 - 0.88092 -0.0510942 -0.230805 - 0.892744 -0.0386493 -0.237473 - 0.896771 -0.016843 -0.239704 - 0.887694 0.0355186 -0.234442 - 0.897467 0.0535389 -0.239936 - 0.890189 0.0749825 -0.235765 - 0.891672 0.101516 -0.236544 - 0.89133 0.204281 -0.236114 - 0.904242 0.230483 -0.243367 - 0.8871 0.244351 -0.233626 - 0.893863 0.326741 -0.237267 - 0.892619 0.331115 -0.236552 - 0.895992 0.356902 -0.238403 - 0.893759 0.406052 -0.237026 - 0.891815 0.456889 -0.235808 - 0.891476 0.467296 -0.235592 - 0.878253 0.475998 -0.228083 - 0.642907 0.372688 -0.0950193 - 0.623775 0.365079 -0.0841999 - 0.334388 0.225477 0.0793886 - 0.335458 0.232881 0.0787997 - 0.322283 0.242874 0.086285 - 0.340772 0.269904 0.075875 - 0.720888 0.601301 -0.138663 - 0.73945 0.712107 -0.148921 - 0.672727 0.686942 -0.111187 - 0.76748 0.851071 -0.164478 - 0.659971 0.801952 -0.103697 - 0.567372 0.691818 -0.0515021 - 0.650779 0.86309 -0.0983509 - 0.820379 1.17638 -0.193693 - 0.582051 0.871847 -0.0594027 - 0.240572 0.396577 0.13292 - 0.24452 0.454511 0.130817 - 0.184043 0.342059 0.164813 - 0.178173 0.333202 0.168117 - 0.155388 0.32076 0.180994 - 0.143032 0.311924 0.187972 - 0.141847 0.312533 0.188645 - 0.144869 0.324123 0.18696 - 0.129733 0.385268 0.195673 - 0.126414 0.403225 0.197594 - 0.0669663 0.41668 0.231297 - 0.0630096 0.442389 0.233597 - 0.0602844 0.492955 0.235257 - 0.0568131 0.555497 0.237367 - 0.058263 0.654625 0.236773 - 0.0575143 0.739837 0.237393 - 0.0664768 1.1939 0.233361 - 0.0162304 1.29798 0.26206 - -0.0636325 1.31131 0.307325 - -0.0735871 1.3104 0.312961 - -0.165416 1.31649 0.364987 - -0.234293 1.19939 0.403731 - -0.233592 1.17384 0.403275 - -0.225314 1.09477 0.398404 - -0.167872 0.720892 0.36501 - -0.166607 0.673186 0.364184 - -0.160555 0.632347 0.360662 - -0.123272 0.425806 0.339069 - -0.0899732 0.285847 0.319887 - -0.0983422 0.29023 0.324638 - -0.117552 0.27528 0.335484 - -0.122101 0.28149 0.338075 - -0.14356 0.29925 0.35027 - -0.199925 0.394262 0.382414 - -0.237718 0.45305 0.403955 - -0.882113 1.37689 0.771066 - -0.905778 1.38759 0.784494 - -0.961216 1.36881 0.815852 - -0.964184 1.36079 0.817515 - -0.970526 1.32188 0.821017 - -0.965625 1.29234 0.818173 - -0.976933 1.26198 0.824508 - -1.32854 -1.6245 0.998527 - -1.32721 -1.68063 0.997662 - -0.261877 -0.361325 0.411895 - -0.257143 -0.364754 0.409271 - -0.255749 -0.366132 0.408497 - -0.245906 -0.362559 0.403065 - -0.24452 -0.363881 0.402296 - -0.22017 -0.367974 0.388829 - -0.200407 -0.366918 0.377909 - -0.199004 -0.368014 0.377131 - -0.191389 -0.365417 0.372929 - -0.185769 -0.373136 0.369805 - -0.184343 -0.374158 0.369014 - -0.166992 -0.374348 0.359424 - -0.15855 -0.376281 0.354755 - -0.131874 -0.377005 0.340009 - -0.125389 -0.378144 0.336423 - -0.120076 -0.373145 0.333498 - -0.116545 -0.372682 0.331547 - -0.0853478 -0.382527 0.314283 - -0.0734126 -0.379284 0.307694 - -0.0261966 -0.389448 0.281576 - -0.0232208 -0.389893 0.27993 - -0.0143624 -0.392045 0.27503 --0.00265542 -0.398164 0.268545 - 0.00849073 -0.382776 0.26242 - 0.0337922 -0.395683 0.248407 - 0.0539061 -0.40012 0.237281 - 0.0584877 -0.399578 0.23475 - 0.0737384 -0.409407 0.226299 - 0.0779565 -0.416756 0.223951 - 0.084658 -0.407338 0.220268 - 0.0987969 -0.405097 0.212459 - 0.102085 -0.405269 0.210642 - 0.141435 -0.408025 0.188888 - 0.142993 -0.407416 0.188028 - 0.145701 -0.410574 0.186524 - 0.154126 -0.409214 0.181871 - 0.164178 -0.412271 0.176308 - 0.188366 -0.416697 0.16293 - 0.189956 -0.415853 0.162053 - 0.191544 -0.415002 0.161178 - 0.206925 -0.414126 0.152679 - 0.210121 -0.416736 0.150907 - 0.226306 -0.420371 0.141953 - 0.255093 -0.425205 0.126032 - 0.259948 -0.421651 0.123358 - 0.276139 -0.433373 0.114382 - 0.277793 -0.432092 0.113471 - 0.281086 -0.429504 0.111657 - 0.308367 -0.432785 0.0965719 - 0.316564 -0.429321 0.0920494 - 0.505332 -0.460632 -0.0123493 - 0.531224 -0.45578 -0.0266479 - 0.541264 -0.460566 -0.0322077 - 0.566123 -0.461128 -0.0459482 - 0.619181 -0.465504 -0.0752819 - 0.696681 -0.477766 -0.118143 - 0.710784 -0.478253 -0.125938 - 0.748257 -0.494326 -0.146685 - 0.920955 -0.540761 -0.242237 - 0.922062 -0.518664 -0.242799 - 0.919289 -0.500311 -0.241224 - 0.916466 -0.493219 -0.239647 - 0.918345 -0.488744 -0.240676 - 0.920124 -0.284396 -0.241192 - 0.919861 -0.203707 -0.240862 - 0.915833 -0.161322 -0.238539 - 0.908991 -0.105986 -0.234631 - 0.916358 -0.102349 -0.238695 - 0.91696 -0.0708954 -0.238955 - 0.911952 -0.0214891 -0.236075 - 0.917392 0.00968937 -0.23901 - 0.912042 0.0185242 -0.236033 - 0.909137 0.0851192 -0.234275 - 0.905045 0.188072 -0.231778 - 0.916898 0.265646 -0.238152 - 0.914317 0.312994 -0.236618 - 0.924084 0.371444 -0.241882 - 0.905876 0.419772 -0.231708 - 0.909112 0.426506 -0.233481 - 0.916247 0.472572 -0.237319 - 0.744978 0.413334 -0.142798 - 0.885694 0.554325 -0.220247 - 0.911123 0.588238 -0.234223 - 0.334707 0.231256 0.0835317 - 0.325098 0.244022 0.0888717 - 0.710278 0.627443 -0.123131 - 0.710819 0.692225 -0.123282 - 0.663882 0.680012 -0.0973697 - 0.675404 0.735796 -0.10361 - 0.729175 0.803163 -0.133174 - 0.477531 0.712468 0.00569624 - 0.435109 0.683131 0.029075 - 0.232535 0.41568 0.140421 - 0.2489 0.452254 0.13146 - 0.195562 0.364863 0.160739 - 0.147512 0.326241 0.187207 - 0.141677 0.380675 0.190556 - 0.140223 0.381275 0.191361 - 0.121048 0.400929 0.202003 - 0.113777 0.398038 0.206016 - 0.105949 0.399292 0.210345 - 0.0887456 0.39237 0.219837 - 0.0707586 0.409022 0.229816 --0.00409237 1.30067 0.273222 - -0.0140258 1.30036 0.278711 - -0.0897278 1.31084 0.320573 - -0.167764 1.32242 0.363729 - -0.205578 1.27077 0.38451 - -0.177315 0.801559 0.367817 - -0.166671 0.648488 0.361585 - -0.125588 0.440326 0.338403 - -0.0845113 0.285795 0.315348 - -0.0870806 0.282365 0.31676 - -0.106342 0.284125 0.32741 - -0.108202 0.276255 0.328419 - -0.216327 0.428587 0.388526 - -0.236292 0.460278 0.399632 - -0.238049 0.458992 0.4006 - -0.215452 0.399399 0.387975 - -0.212053 0.389957 0.386075 - -0.207974 0.372524 0.383781 - -0.898355 1.39285 0.767669 - -0.967212 1.28633 0.805481 - -0.9773 1.22199 0.810909 - -0.975367 1.20899 0.809812 - -1.32349 -1.66588 0.977149 - -0.322913 -0.428868 0.440753 - -0.254915 -0.368867 0.404245 - -0.220896 -0.366371 0.385918 - -0.218074 -0.368741 0.384392 - -0.184013 -0.374322 0.366024 - -0.166012 -0.377071 0.356317 - -0.130961 -0.375938 0.337431 - -0.114408 -0.377474 0.328507 - -0.113284 -0.379063 0.327898 - -0.0947953 -0.3836 0.317924 - -0.0493438 -0.386147 0.293424 - -0.0289582 -0.394166 0.28242 --0.00142497 -0.39428 0.267583 - 0.0168563 -0.383987 0.257754 - 0.0685892 -0.407205 0.229823 - 0.0782399 -0.40758 0.224621 - 0.106634 -0.403034 0.20933 - 0.115894 -0.400307 0.204346 - 0.158909 -0.40624 0.181152 - 0.16713 -0.408966 0.176716 - 0.221418 -0.421665 0.147431 - 0.230035 -0.421948 0.142787 - 0.233401 -0.424372 0.140967 - 0.274293 -0.428401 0.118922 - 0.281217 -0.427861 0.115192 - 0.378323 -0.440297 0.0628337 - 0.395871 -0.442083 0.0533731 - 0.42083 -0.443463 0.0399196 - 0.658057 -0.474842 -0.0879925 - 0.665045 -0.475481 -0.0917596 - 0.741519 -0.487177 -0.132998 - 0.93867 -0.560124 -0.239407 - 0.939831 -0.54913 -0.240008 - 0.935209 -0.506439 -0.23742 - 0.938008 -0.415377 -0.238722 - 0.937683 -0.394276 -0.238499 - 0.941084 -0.28946 -0.240093 - 0.940739 -0.150911 -0.239592 - 0.934953 -0.0719309 -0.236295 - 0.933299 -0.0536231 -0.235362 - 0.93723 0.046252 -0.237254 - 0.936021 0.096375 -0.236488 - 0.931751 0.105048 -0.234168 - 0.93163 0.249371 -0.233774 - 0.942312 0.413441 -0.239158 - 0.934033 0.446814 -0.234621 - 0.922758 0.598723 -0.2282 - 0.920454 0.60319 -0.226948 - 0.88485 0.590946 -0.207789 - 0.352233 0.282084 0.0785342 - 0.690691 0.686411 -0.102941 - 0.656199 0.680225 -0.0843671 - 0.653583 0.683369 -0.0829503 - 0.737655 0.859433 -0.127856 - 0.710365 0.84871 -0.113174 - 0.594073 0.770573 -0.0506822 - 0.47989 0.706164 0.0107041 - 0.46606 0.704001 0.0181523 - 0.243397 0.394631 0.137441 - 0.233619 0.412034 0.14275 - 0.383412 0.729656 0.062749 - 0.192791 0.357846 0.164629 - 0.16227 0.320696 0.180993 - 0.154563 0.320528 0.185145 - 0.151828 0.317572 0.186612 - 0.14979 0.389122 0.187873 - 0.113462 0.396106 0.207466 - 0.108891 0.397457 0.209932 - 0.108431 0.402745 0.210193 - 0.0814989 0.395943 0.224691 - 0.0799778 0.396242 0.225511 - 0.0603539 0.497935 0.236317 - 0.0592531 0.598381 0.237139 - 0.0674188 1.02263 0.233702 - 0.0636517 1.25307 0.236256 - 0.0401114 1.28782 0.24902 - -0.0199167 1.30917 0.281418 - -0.0248423 1.30595 0.284065 - -0.218024 1.24675 0.388035 - -0.2211 1.23677 0.38967 - -0.230424 1.18608 0.39458 - -0.234768 1.14057 0.396817 - -0.177257 0.733321 0.3649 - -0.0811099 0.287847 0.312074 - -0.0844984 0.283029 0.313889 - -0.085585 0.282507 0.314474 - -0.110739 0.294574 0.328056 - -0.110672 0.291251 0.328013 - -0.218386 0.412928 0.386336 - -0.788195 1.27512 0.695362 - -0.943814 1.40107 0.77951 - -0.976348 1.25658 0.796715 - -0.311992 -0.401784 0.430541 - -0.236529 -0.360516 0.390967 - -0.233737 -0.363023 0.389493 - -0.176141 -0.367884 0.359207 - -0.162361 -0.374511 0.351949 - -0.131077 -0.377592 0.335497 - -0.120292 -0.371998 0.32984 - -0.0876983 -0.378188 0.312693 - -0.0833087 -0.379736 0.310383 - -0.0793658 -0.376896 0.308316 - -0.0351265 -0.389193 0.285034 - -0.0209357 -0.385343 0.277583 - -0.016468 -0.385903 0.275234 --0.00355474 -0.396168 0.268422 --0.00218751 -0.399271 0.267697 - 0.0379118 -0.398437 0.24662 - 0.0516639 -0.396303 0.239396 - 0.066104 -0.400505 0.231796 - 0.0693192 -0.401017 0.230105 - 0.0724154 -0.400507 0.228479 - 0.107579 -0.406919 0.20998 - 0.139636 -0.405783 0.193132 - 0.152933 -0.414294 0.186123 - 0.167902 -0.409892 0.178264 - 0.209909 -0.417681 0.156166 - 0.215566 -0.416589 0.153195 - 0.268877 -0.429645 0.125142 - 0.28163 -0.430802 0.118436 - 0.339777 -0.434901 0.0878617 - 0.398798 -0.44352 0.0568174 - 0.506003 -0.456798 0.00043491 - 0.545725 -0.459954 -0.0204523 - 0.57545 -0.468629 -0.036097 - 0.604552 -0.471049 -0.0514002 - 0.645729 -0.472275 -0.0730474 - 0.704004 -0.482723 -0.103704 - 0.964538 -0.520008 -0.240738 - 0.954783 -0.475254 -0.235509 - 0.958231 -0.47145 -0.237313 - 0.962408 -0.418869 -0.23939 - 0.952354 -0.0176291 -0.233199 - 0.951578 -0.00842399 -0.23277 - 0.961121 0.0844885 -0.237576 - 0.955764 0.107268 -0.234709 - 0.951734 0.130068 -0.232539 - 0.957177 0.144925 -0.235367 - 0.960015 0.18333 -0.236772 - 0.956187 0.201655 -0.234718 - 0.958147 0.221314 -0.235704 - 0.958633 0.350574 -0.235667 - 0.962609 0.41504 -0.237612 - 0.964941 0.448586 -0.238762 - 0.964019 0.453631 -0.238266 - 0.757503 0.506408 -0.129591 - 0.375427 0.251473 0.070673 - 0.337491 0.231256 0.0905685 - 0.319174 0.243877 0.100225 - 0.739814 0.842936 -0.119532 - 0.548193 0.687218 -0.0191574 - 0.564722 0.721311 -0.0277692 - 0.482626 0.700674 0.0153385 - 0.469789 0.700168 0.0220848 - 0.236832 0.392824 0.143845 - 0.168006 0.318717 0.179857 - 0.162215 0.323188 0.182911 - 0.145775 0.331786 0.191571 - 0.152454 0.353582 0.18811 - 0.153486 0.36069 0.187584 - 0.119609 0.400463 0.205481 - 0.116109 0.406733 0.207335 - 0.0762925 0.40401 0.228258 - 0.0149023 1.29798 0.262548 - -0.035251 1.29746 0.28891 - -0.127422 1.30833 0.337385 - -0.159035 1.31338 0.354014 - -0.194943 1.30952 0.37288 - -0.174936 0.766925 0.361137 - -0.17985 0.761137 0.363707 - -0.165452 0.643712 0.355874 - -0.0825043 0.285488 0.311463 - -0.0904391 0.289328 0.315642 - -0.0982032 0.292 0.31973 - -0.0993304 0.291416 0.320321 - -0.102698 0.289629 0.322087 - -0.108969 0.285016 0.325373 - -0.111167 0.283735 0.326525 - -0.112109 0.279786 0.327012 - -0.115556 0.275394 0.328814 - -0.219572 0.445212 0.383873 - -0.243934 0.476386 0.39675 - -0.218921 0.399399 0.383428 - -0.220462 0.398218 0.384236 - -0.975186 1.22601 0.782829 - -0.274828 -0.376911 0.407374 - -0.246343 -0.362108 0.392792 - -0.234538 -0.365055 0.386728 - -0.223479 -0.361979 0.38106 - -0.22154 -0.362362 0.380064 - -0.214321 -0.364587 0.376355 - -0.203815 -0.37159 0.370949 - -0.126383 -0.376113 0.331208 - -0.117911 -0.381184 0.32685 - -0.0973719 -0.380193 0.316313 - -0.0948879 -0.388519 0.31502 - -0.0845199 -0.386943 0.309704 - -0.0657332 -0.382365 0.300075 - -0.0600631 -0.393127 0.297141 - -0.0482746 -0.380599 0.29112 - -0.0438372 -0.381553 0.288841 - -0.0383454 -0.385684 0.286014 - -0.0279613 -0.388457 0.28068 - -0.0149568 -0.39719 0.273988 - 0.016042 -0.389987 0.258098 - 0.0236688 -0.394962 0.254174 - 0.0391935 -0.398341 0.2462 - 0.0451791 -0.394889 0.243137 - 0.0516319 -0.398295 0.239818 - 0.0637566 -0.394781 0.233605 - 0.0668205 -0.394325 0.232034 - 0.0759918 -0.403917 0.227307 - 0.0847675 -0.408322 0.222794 - 0.105262 -0.403462 0.212289 - 0.110173 -0.403125 0.20977 - 0.115091 -0.402712 0.207247 - 0.134344 -0.404673 0.197364 - 0.148553 -0.410885 0.190059 - 0.15839 -0.413215 0.185007 - 0.165776 -0.4132 0.181217 - 0.16999 -0.414518 0.179052 - 0.182272 -0.411875 0.172756 - 0.204405 -0.422275 0.161376 - 0.208879 -0.423116 0.159078 - 0.231861 -0.418297 0.147297 - 0.241056 -0.419208 0.142577 - 0.245888 -0.424112 0.140087 - 0.296229 -0.428552 0.114246 - 0.332051 -0.434168 0.0958535 - 0.387374 -0.44363 0.067446 - 0.401125 -0.448275 0.0603801 - 0.426293 -0.445555 0.0474722 - 0.749263 -0.487687 -0.118339 - 0.769527 -0.486386 -0.128734 - 0.987756 -0.536146 -0.24082 - 0.987819 -0.501181 -0.240774 - 0.993003 -0.370788 -0.243141 - 0.992448 -0.323266 -0.242749 - 0.986749 -0.205691 -0.239561 - 0.978248 -0.179613 -0.23514 - 0.985547 -0.166394 -0.238855 - 0.987596 -0.108815 -0.239777 - 0.985389 -0.0799149 -0.23858 - 0.983919 -0.0750373 -0.237815 - 0.98125 -0.0369755 -0.23636 - 0.976274 -0.0226912 -0.233774 - 0.980057 -0.0039277 -0.235673 - 0.979625 0.128547 -0.235154 - 0.976611 0.304252 -0.233212 - 0.987888 0.491188 -0.238578 - 0.983718 0.529462 -0.236353 - 0.691618 0.419424 -0.0867228 - 0.945027 0.632102 -0.21627 - 0.366122 0.246279 0.0799011 - 0.329507 0.228891 0.0986497 - 0.328616 0.23041 0.0991098 - 0.324264 0.235874 0.101355 - 0.322488 0.252452 0.102304 - 0.708617 0.639184 -0.0949507 - 0.657633 0.681302 -0.0686962 - 0.744491 0.998008 -0.112551 - 0.504679 0.698572 0.0098241 - 0.459426 0.70022 0.0330472 - 0.236257 0.44011 0.146971 - 0.146109 0.324123 0.192966 - 0.136025 0.398018 0.198306 - 0.122773 0.405736 0.205123 - 0.105805 0.390129 0.213794 - 0.0955455 0.394863 0.219069 - 0.0940122 0.395232 0.219857 - 0.0833995 0.398588 0.22531 - 0.0815423 0.396927 0.226259 - 0.0446342 1.29371 0.247212 - -0.0259235 1.29996 0.28343 - -0.0360152 1.29945 0.288607 - -0.234228 1.04562 0.38974 - -0.16678 0.634246 0.354207 - -0.0813582 0.290704 0.309605 - -0.0903754 0.283281 0.314215 - -0.109819 0.294068 0.324216 - -0.111925 0.286156 0.325279 - -0.225897 0.463019 0.384155 - -0.234559 0.469993 0.388616 - -0.232332 0.448029 0.387424 - -0.226182 0.428728 0.384224 - -0.910981 1.39983 0.73778 - -0.941848 1.39478 0.753607 - -0.947258 1.39005 0.756372 - -0.959399 1.34587 0.762502 - -0.966631 1.28554 0.766078 - -1.31625 -1.48022 0.92155 - -0.268584 -0.372954 0.400368 - -0.235735 -0.364267 0.383968 - -0.17471 -0.36721 0.353459 - -0.14862 -0.36723 0.340419 - -0.147079 -0.375923 0.339629 - -0.125729 -0.375902 0.328957 - -0.0625025 -0.385523 0.297333 - -0.0499717 -0.377326 0.291088 - -0.0475371 -0.380924 0.289863 - -0.0360281 -0.38623 0.284099 - -0.0330117 -0.386746 0.28259 - -0.0153541 -0.395199 0.273745 - 0.0078368 -0.396823 0.26215 - 0.0125631 -0.391944 0.259798 - 0.0249096 -0.398933 0.253612 - 0.029553 -0.397805 0.251293 - 0.0597908 -0.403356 0.236167 - 0.085369 -0.412258 0.223362 - 0.0986376 -0.403144 0.21675 - 0.100211 -0.402749 0.215965 - 0.106699 -0.402063 0.212723 - 0.122353 -0.410883 0.204879 - 0.130087 -0.407294 0.201021 - 0.133263 -0.406189 0.199436 - 0.147966 -0.408058 0.192083 - 0.149558 -0.407422 0.191289 - 0.154281 -0.410817 0.188921 - 0.169059 -0.410817 0.181534 - 0.172372 -0.414696 0.17987 - 0.266427 -0.43041 0.132822 - 0.406276 -0.444508 0.0628897 - 0.443657 -0.450526 0.0441919 - 0.468692 -0.452635 0.0316737 - 0.474891 -0.450873 0.0285792 - 0.510651 -0.461121 0.0106821 - 0.516707 -0.45451 0.00767002 - 0.524733 -0.457733 0.00365099 - 0.665357 -0.478003 -0.0666828 - 0.976779 -0.574777 -0.222559 - 1.01568 -0.567131 -0.241985 - 1.01525 -0.536598 -0.241704 - 1.01086 -0.504704 -0.239436 - 1.01293 -0.398271 -0.240233 - 1.01175 -0.365281 -0.239568 - 1.02092 -0.283739 -0.243971 - 1.01709 -0.221201 -0.241918 - 1.01314 -0.190218 -0.239873 - 1.01304 -0.0866741 -0.23959 - 1.00271 0.00079921 -0.234235 - 0.998611 0.101447 -0.231959 - 1.00579 0.121644 -0.235501 - 1.00928 0.43138 -0.236555 - 1.01118 0.51809 -0.237309 - 1.0126 0.542633 -0.237967 - 0.999788 0.553516 -0.231537 - 0.32396 0.243562 0.105572 - 0.325186 0.246802 0.104967 - 0.687004 0.684914 -0.0749025 - 0.648776 0.686438 -0.0557917 - 0.714264 0.791558 -0.0882896 - 0.734456 0.843464 -0.0982661 - 0.549698 0.689056 -0.00626314 - 0.734268 0.953538 -0.0979261 - 0.495406 0.700867 0.0209005 - 0.170875 0.323143 0.182268 - 0.154063 0.388756 0.190818 - 0.149439 0.385381 0.193121 - 0.138772 0.394966 0.198474 - 0.130017 0.400243 0.202862 - 0.118666 0.395649 0.208526 - 0.116752 0.40143 0.209495 - 0.0814394 0.407085 0.227158 - 0.0760301 0.415157 0.22988 - 0.0729164 0.416686 0.23144 - 0.0712898 0.416944 0.232253 - 0.0704906 0.43826 0.232701 - -0.0112741 1.29653 0.275488 - -0.0624551 1.30375 0.301087 - -0.093726 1.30985 0.31673 - -0.10954 1.31304 0.324642 - -0.125122 1.31302 0.33243 - -0.178874 1.32245 0.359319 - -0.183278 1.31654 0.361507 - -0.203641 1.28084 0.371605 - -0.237127 1.17026 0.388095 - -0.176799 0.763081 0.357031 - -0.0801382 0.295907 0.307672 - -0.0913167 0.286573 0.313238 - -0.0987128 0.291668 0.316947 - -0.118623 0.277142 0.326866 - -0.233203 0.429645 0.384478 - -0.902784 1.40488 0.721338 - -0.908794 1.40117 0.724334 - -0.960112 1.31546 0.749793 - -0.973801 1.21054 0.756401 - -0.977123 1.19349 0.758023 - -0.324276 -0.430925 0.423629 - -0.24084 -0.362556 0.38316 - -0.238859 -0.363023 0.382195 - -0.237434 -0.364267 0.381498 - -0.219512 -0.364249 0.372773 - -0.198112 -0.367304 0.362348 - -0.188959 -0.365521 0.357895 - -0.188925 -0.372621 0.357863 - -0.166953 -0.371862 0.347168 - -0.151799 -0.379589 0.339773 - -0.124601 -0.379139 0.326532 - -0.118123 -0.385302 0.323365 - -0.108593 -0.377581 0.318742 - -0.0922789 -0.378609 0.310797 - -0.0457653 -0.384504 0.288139 - -0.0358648 -0.391434 0.283303 - -0.0320166 -0.386004 0.281442 - -0.0171031 -0.39105 0.27417 - -0.0111861 -0.394663 0.271281 --0.00775444 -0.389945 0.269621 --0.00469412 -0.390181 0.268131 - -5.314e-05 -0.389479 0.265873 - 0.0198284 -0.389994 0.256192 - 0.0710623 -0.404724 0.231216 - 0.0783964 -0.399396 0.227657 - 0.0850097 -0.41029 0.224413 - 0.095686 -0.40489 0.219227 - 0.101625 -0.401372 0.216344 - 0.114896 -0.408014 0.209868 - 0.127385 -0.403048 0.203799 - 0.131343 -0.404836 0.201868 - 0.137487 -0.407906 0.19887 - 0.194333 -0.415002 0.171178 - 0.197121 -0.416849 0.169817 - 0.217526 -0.416589 0.159883 - 0.234078 -0.415517 0.151827 - 0.239329 -0.421372 0.149258 - 0.403145 -0.446831 0.0694468 - 0.46064 -0.454438 0.0414379 - 0.472406 -0.450434 0.0357188 - 0.49618 -0.453577 0.0241372 - 0.537255 -0.454614 0.00413752 - 0.556444 -0.463013 -0.00522324 - 0.609329 -0.472764 -0.0309926 - 0.618894 -0.471618 -0.0356467 - 0.670185 -0.474842 -0.060625 - 0.950782 -0.568255 -0.197442 - 0.988358 -0.572909 -0.215747 - 1.01754 -0.577762 -0.229967 - 1.03558 -0.532814 -0.238648 - 1.03725 -0.509699 -0.239407 - 1.03924 -0.504748 -0.240367 - 1.03834 -0.46911 -0.239848 - 1.03816 -0.362268 -0.239526 - 1.0476 -0.316647 -0.244021 - 1.05126 -0.301632 -0.245765 - 1.04314 -0.179697 -0.241542 - 1.03837 -0.138472 -0.23913 - 1.03964 -0.0686478 -0.239593 - 1.03275 0.0648824 -0.235943 - 1.03222 0.0747246 -0.235658 - 1.03846 0.200867 -0.238419 - 1.03502 0.24631 -0.236641 - 1.03569 0.25683 -0.236943 - 1.03076 0.307775 -0.234432 - 1.03544 0.373799 -0.236562 - 1.03792 0.396781 -0.237721 - 1.03741 0.413299 -0.237432 - 1.0417 0.437676 -0.239466 - 1.03813 0.482204 -0.237633 - 1.03663 0.534886 -0.236784 - 1.03996 0.554925 -0.238361 - 0.996968 0.64181 -0.217236 - 0.333332 0.232067 0.104945 - 0.330389 0.238709 0.106393 - 0.329451 0.240219 0.106853 - 0.669422 0.687502 -0.0576677 - 0.649688 0.684343 -0.0480671 - 0.563818 0.668116 -0.00629759 - 0.489834 0.695991 0.0297842 - 0.249243 0.380714 0.146215 - 0.243237 0.385131 0.149149 - 0.239547 0.393672 0.150965 - 0.251553 0.435906 0.145213 - 0.259001 0.45889 0.141638 - 0.291101 0.530689 0.12617 - 0.156255 0.321431 0.191355 - 0.143038 0.385982 0.197933 - 0.137669 0.408099 0.200596 - 0.13179 0.405974 0.203454 - 0.127004 0.407585 0.205788 - 0.11528 0.401902 0.211483 - 0.0651805 0.474202 0.236035 - 0.0440331 1.29271 0.248151 - 0.0237408 1.29199 0.258029 - 0.00337432 1.29987 0.267962 - -0.0119227 1.29953 0.275408 - -0.0170207 1.29936 0.27789 - -0.0375338 1.30145 0.287882 - -0.173154 0.676029 0.352518 - -0.0908083 0.286188 0.31156 - -0.105376 0.285421 0.31865 - -0.122101 0.284822 0.326792 - -0.244477 0.450153 0.386739 - -1.34166 -1.68643 0.898562 - -0.262348 -0.366576 0.389993 - -0.257996 -0.364092 0.387937 - -0.20059 -0.368977 0.360721 - -0.19621 -0.372107 0.358638 - -0.188478 -0.365674 0.354989 - -0.183699 -0.364239 0.352727 - -0.174567 -0.369081 0.348388 - -0.160679 -0.379783 0.341783 - -0.153732 -0.376974 0.338497 - -0.136445 -0.370646 0.330319 - -0.129465 -0.375195 0.327001 - -0.127208 -0.378443 0.325924 - -0.114565 -0.372273 0.319946 - -0.113096 -0.372908 0.319249 - -0.0779626 -0.382638 0.302577 - -0.0730472 -0.389268 0.300233 - -0.0673611 -0.385691 0.297547 - -0.0428463 -0.391314 0.285916 - -0.0349852 -0.391692 0.28219 - -0.0213458 -0.396659 0.275716 - -0.0116501 -0.393666 0.271127 - 0.0194577 -0.392994 0.256387 - 0.0783115 -0.399396 0.228482 - 0.0953781 -0.412115 0.220366 - 0.106296 -0.407351 0.215202 - 0.141289 -0.413969 0.198604 - 0.14455 -0.412759 0.197061 - 0.147801 -0.411517 0.195523 - 0.16005 -0.404376 0.189734 - 0.165912 -0.410414 0.186943 - 0.173063 -0.409332 0.183557 - 0.174676 -0.408577 0.182794 - 0.179862 -0.407182 0.18034 - 0.198888 -0.415075 0.171305 - 0.220267 -0.421002 0.161161 - 0.233589 -0.417429 0.154855 - 0.271583 -0.427974 0.136827 - 0.284058 -0.428331 0.130914 - 0.344385 -0.438019 0.102303 - 0.440422 -0.451187 0.0567618 - 0.44481 -0.451905 0.0546811 - 0.47388 -0.453972 0.0409003 - 0.481059 -0.457087 0.0374908 - 0.589582 -0.467665 -0.0139615 - 0.614533 -0.470469 -0.0257924 - 1.06875 -0.486797 -0.241085 - 1.06579 -0.432713 -0.239559 - 1.06906 -0.411072 -0.241063 - 1.06962 -0.35497 -0.241202 - 1.07246 -0.29552 -0.242417 - 1.06335 -0.282243 -0.23807 - 1.06466 -0.271906 -0.23867 - 1.06102 -0.207889 -0.236804 - 1.06184 -0.115479 -0.236985 - 1.06217 -0.0748971 -0.237054 - 1.06065 -0.0193017 -0.236209 - 1.05978 0.0713485 -0.235598 - 1.05776 0.101501 -0.234575 - 1.06472 0.215515 -0.237618 - 1.0621 0.225421 -0.236355 - 1.06121 0.23046 -0.23592 - 1.05213 0.249291 -0.231578 - 1.05013 0.259266 -0.23061 - 1.06829 0.274509 -0.23918 - 1.06724 0.505659 -0.23817 - 1.06604 0.57272 -0.237453 - 1.06149 0.582815 -0.235275 - 1.05758 0.586936 -0.233411 - 0.862122 0.550849 -0.140865 - 0.32058 0.25714 0.115123 - 0.607818 0.51494 -0.020429 - 0.681038 0.678653 -0.0547659 - 0.65975 0.723037 -0.0445793 - 0.728522 0.828947 -0.0769359 - 0.554961 0.677838 0.00498042 - 0.53471 0.687758 0.0145994 - 0.526622 0.701523 0.0184628 - 0.488994 0.704556 0.0363016 - 0.243739 0.395981 0.151846 - 0.167848 0.318557 0.187639 - 0.153493 0.325223 0.194457 - 0.152948 0.356077 0.194783 - 0.153852 0.38158 0.194411 - 0.117898 0.40529 0.211502 - 0.0859934 0.395981 0.226602 - 0.0843177 0.405477 0.227417 - 0.0487835 1.29058 0.246215 - 0.0437145 1.29171 0.24862 - -0.0228774 1.30317 0.280203 - -0.0381165 1.29845 0.287415 - -0.132058 1.30734 0.331954 - -0.14285 1.30979 0.337073 - -0.175088 1.31353 0.352359 - -0.223164 1.23014 0.374958 - -0.193149 0.857524 0.359909 - -0.166664 0.648377 0.346895 - -0.0781834 0.304863 0.304204 - -0.0783847 0.293106 0.304273 - -0.0806932 0.292162 0.305365 - -0.0842945 0.287416 0.307061 - -0.085543 0.283634 0.307644 - -0.0876868 0.285906 0.308665 - -0.0939641 0.28841 0.311646 - -0.117291 0.281551 0.322685 - -0.121487 0.275596 0.324661 - -0.13106 0.285668 0.32922 - -0.806427 1.35232 0.651638 - -0.921852 1.40519 0.706456 - -0.955504 1.35391 0.72229 - -0.969273 1.31315 0.728725 - -0.970844 1.29212 0.729422 - -0.969162 1.23423 0.728497 - -0.977864 1.15064 0.732436 - -0.324114 -0.393238 0.4148 - -0.322554 -0.394875 0.414077 - -0.319415 -0.398125 0.412623 - -0.228625 -0.363164 0.370845 - -0.213438 -0.370217 0.363828 - -0.206941 -0.366613 0.360841 - -0.205487 -0.367687 0.360169 - -0.196202 -0.369576 0.355884 - -0.187942 -0.369357 0.352077 - -0.18206 -0.373244 0.349356 - -0.179207 -0.371606 0.348045 - -0.159022 -0.373572 0.338735 - -0.143295 -0.379871 0.331471 - -0.141789 -0.380639 0.330775 - -0.0995407 -0.379812 0.3113 - -0.0483769 -0.382225 0.287708 - -0.0426178 -0.3854 0.285046 - -0.0413905 -0.387656 0.284476 - -0.039854 -0.387935 0.283767 - -0.0336977 -0.388973 0.280926 - 0.0128787 -0.389969 0.259452 - 0.0221039 -0.385962 0.255208 - 0.0718769 -0.400507 0.232231 - 0.0953037 -0.402934 0.221425 - 0.106764 -0.409295 0.216128 - 0.132479 -0.413987 0.204263 - 0.166589 -0.411342 0.188544 - 0.220025 -0.419237 0.163893 - 0.25184 -0.429252 0.149204 - 0.267571 -0.427888 0.141955 - 0.326694 -0.435522 0.114682 - 0.331849 -0.431024 0.112315 - 0.484093 -0.454183 0.0420792 - 0.787863 -0.494089 -0.0980477 - 1.09766 -0.516312 -0.240916 - 1.09169 -0.501229 -0.23813 - 1.09367 -0.496061 -0.239032 - 1.09522 -0.413558 -0.239565 - 1.10222 -0.324764 -0.242595 - 1.10175 -0.319032 -0.242364 - 1.10315 -0.247777 -0.242853 - 1.09158 -0.20236 -0.23742 - 1.09529 -0.025032 -0.23874 - 1.09182 -0.0146255 -0.237119 - 1.09251 0.0577139 -0.237274 - 1.09079 0.088677 -0.236416 - 1.08374 0.176302 -0.232973 - 1.09112 0.182798 -0.236358 - 1.08738 0.224498 -0.234544 - 1.10279 0.332243 -0.241409 - 1.09091 0.345327 -0.235905 - 1.09034 0.424943 -0.235466 - 1.0916 0.466681 -0.235957 - 1.09477 0.54763 -0.23724 - 1.08758 0.569109 -0.233878 - 0.650841 0.448973 -0.0328034 - 0.32915 0.233813 0.115023 - 0.318395 0.245307 0.120007 - 0.695483 0.59955 -0.053052 - 0.710027 0.699113 -0.0595374 - 0.649894 0.684592 -0.0318479 - 0.64445 0.690636 -0.0293247 - 0.531388 0.692716 0.0228017 - 0.255829 0.385381 0.149159 - 0.242168 0.384534 0.155454 - 0.22252 0.411348 0.164572 - 0.166918 0.319276 0.190001 - 0.132379 0.406929 0.206117 - 0.130766 0.407475 0.206862 - 0.101413 0.399558 0.220376 - 0.0632864 0.521623 0.238222 - 0.0794239 1.19512 0.232265 - 0.0763576 1.23036 0.233757 - 0.0229535 1.29699 0.258523 - -0.0234504 1.30117 0.279924 - -0.172123 1.32038 0.348505 - -0.198885 1.31942 0.360841 - -0.213297 0.949318 0.366669 - -0.172794 0.756296 0.347573 - -0.17308 0.744786 0.347679 - -0.0919361 0.287638 0.309265 - -0.0957092 0.286948 0.311002 - -0.112942 0.294699 0.318964 - -0.11781 0.286396 0.32119 - -0.121054 0.275394 0.322661 - -0.128372 0.281179 0.326048 - -0.148292 0.310053 0.335294 - -0.236268 0.460593 0.376183 - -0.258964 0.496867 0.386726 - -0.260931 0.495531 0.38763 - -0.515787 0.912939 0.506039 - -0.976742 1.19433 0.71916 - -0.339009 -0.390606 0.417236 - -0.331451 -0.402859 0.413819 - -0.268203 -0.369631 0.385523 - -0.241499 -0.366294 0.373552 - -0.233446 -0.367974 0.369936 - -0.226192 -0.363899 0.366691 - -0.204301 -0.359978 0.356881 - -0.202867 -0.361032 0.356235 - -0.189322 -0.365815 0.350149 - -0.139104 -0.371554 0.327611 - -0.137253 -0.380157 0.326762 - -0.132766 -0.377947 0.324755 - -0.120955 -0.374691 0.319464 - -0.116606 -0.38194 0.317497 - -0.115084 -0.382575 0.316813 - -0.11356 -0.383202 0.316129 - -0.0882418 -0.377823 0.304784 - -0.0872632 -0.380238 0.30434 - -0.0842325 -0.38122 0.302978 - -0.0335389 -0.395156 0.280209 - -0.0301525 -0.39364 0.278693 - -0.0189802 -0.39304 0.273683 - 0.00326621 -0.386712 0.263719 - 0.0373024 -0.389356 0.248446 - 0.0444442 -0.402866 0.245213 - 0.068809 -0.402997 0.234284 - 0.0838558 -0.404387 0.227532 - 0.0966942 -0.401578 0.22178 - 0.0998892 -0.400799 0.220348 - 0.172854 -0.411925 0.187596 - 0.174493 -0.411175 0.186862 - 0.197328 -0.418618 0.176604 - 0.203566 -0.414206 0.173815 - 0.220592 -0.419237 0.166167 - 0.259844 -0.425526 0.148547 - 0.302852 -0.434775 0.129236 - 0.312542 -0.42943 0.124901 - 0.400869 -0.442897 0.0852529 - 0.422936 -0.444446 0.0753514 - 0.468504 -0.452961 0.0548936 - 0.738287 -0.483781 -0.0661837 - 1.12737 -0.540888 -0.240832 - 1.12704 -0.490599 -0.240571 - 1.12747 -0.424086 -0.24062 - 1.12674 -0.365125 -0.240161 - 1.13086 -0.28653 -0.241837 - 1.12508 -0.213225 -0.239083 - 1.12655 -0.148406 -0.239601 - 1.12741 -0.100225 -0.239882 - 1.1203 0.0008784 -0.236473 - 1.12461 0.027365 -0.238344 - 1.11917 0.074746 -0.235801 - 1.12139 0.13876 -0.236659 - 1.1204 0.197788 -0.236084 - 1.11887 0.29632 -0.235182 - 1.09782 0.329296 -0.225668 - 1.09078 0.338234 -0.22249 - 1.12401 0.454399 -0.237143 - 0.702803 0.412752 -0.0483025 - 0.324062 0.24682 0.121216 - 0.661059 0.687835 -0.0289756 - 0.654614 0.717524 -0.0260195 - 0.474693 0.582173 0.0543866 - 0.242761 0.388139 0.157993 - 0.161232 0.32368 0.194421 - 0.15262 0.386609 0.198422 - 0.144641 0.417363 0.202069 - 0.116672 0.406733 0.21459 - 0.111807 0.408121 0.216776 - 0.100787 0.396634 0.221693 - 0.0679649 0.45264 0.236538 - 0.0717466 0.802828 0.23561 - -0.0399539 1.30844 0.286821 - -0.0664295 1.31372 0.298708 - -0.0821134 1.31239 0.30574 - -0.220128 1.22445 0.367453 - -0.239405 1.14986 0.375936 - -0.16554 0.69869 0.341815 - -0.119594 0.468469 0.320702 - -0.0730978 0.291582 0.299458 - -0.108086 0.29445 0.315159 - -0.118218 0.291251 0.319696 - -0.491033 0.917768 0.488294 - -0.598547 1.06935 0.536851 - -0.631717 1.11613 0.551832 - -0.912011 1.40128 0.678181 - -0.976593 1.21976 0.706751 - -0.338565 -0.383968 0.411484 - -1.32097 -1.51023 0.834283 - -1.32471 -1.58205 0.835745 - -1.33299 -1.61992 0.839243 - -0.234102 -0.362778 0.366311 - -0.173613 -0.36657 0.340119 - -0.151403 -0.371438 0.330494 - -0.120255 -0.378787 0.316995 - -0.082775 -0.377854 0.300773 - -0.0583297 -0.376292 0.290195 - -0.0466307 -0.391018 0.285099 - 0.00070201 -0.397633 0.264596 - 0.0150691 -0.390997 0.258391 - 0.0229925 -0.396934 0.254948 - 0.0781288 -0.400382 0.231074 - 0.109704 -0.399249 0.217409 - 0.129037 -0.406878 0.209023 - 0.173139 -0.406566 0.189934 - 0.194263 -0.414947 0.180771 - 0.209944 -0.41776 0.173978 - 0.238403 -0.422636 0.161648 - 0.243463 -0.419433 0.159464 - 0.248705 -0.420684 0.157193 - 0.250388 -0.419576 0.156466 - 0.266132 -0.426558 0.149636 - 0.281591 -0.42383 0.14295 - 0.303482 -0.433964 0.133453 - 0.310393 -0.428437 0.130473 - 0.321103 -0.432136 0.125829 - 0.325079 -0.433843 0.124104 - 0.417499 -0.448087 0.0840672 - 0.494525 -0.452301 0.0507161 - 0.50511 -0.454226 0.0461299 - 0.532572 -0.458935 0.0342323 - 0.53512 -0.457104 0.0331334 - 0.59091 -0.466836 0.00896236 - 0.805025 -0.495375 -0.0837834 - 0.943672 -0.55922 -0.143939 - 1.06979 -0.583905 -0.198585 - 1.1662 -0.589886 -0.240331 - 1.17501 -0.439878 -0.243816 - 1.17421 -0.384721 -0.243349 - 1.15814 -0.0534023 -0.235673 - 1.16538 -0.0264027 -0.238749 - 1.15832 0.0715429 -0.23548 - 1.15772 0.0823955 -0.235193 - 1.16742 0.182716 -0.239173 - 1.1663 0.313231 -0.238405 - 1.08759 0.346494 -0.204263 - 1.15835 0.405097 -0.234766 - 1.16383 0.425207 -0.237093 - 1.16014 0.460548 -0.235417 - 1.16596 0.51322 -0.237823 - 1.15914 0.62834 -0.234622 - 0.711746 0.424672 -0.041401 - 0.73258 0.46925 -0.0503221 - 0.33134 0.235874 0.122853 - 0.327519 0.241818 0.12452 - 0.324341 0.248284 0.12591 - 0.712991 0.642797 -0.0414647 - 0.713642 0.666489 -0.0416945 - 0.716497 0.68708 -0.0428855 - 0.316809 0.357079 0.129408 - 0.315377 0.358501 0.13003 - 0.291671 0.363652 0.140303 - 0.279673 0.37025 0.145511 - 0.2817 0.379902 0.144655 - 0.266237 0.388475 0.151367 - 0.247188 0.383201 0.159601 - 0.238115 0.397708 0.16356 - 0.239153 0.432933 0.163188 - 0.236528 0.432235 0.164322 - 0.150686 0.320412 0.201237 - 0.152252 0.361067 0.200648 - 0.151942 0.374134 0.20081 - 0.136482 0.407719 0.207576 - 0.126207 0.40279 0.212013 - 0.102554 0.397206 0.222239 - 0.0997758 0.399955 0.223448 - 0.0740226 0.430543 0.234662 - 0.0842923 1.2018 0.231898 - 0.0809399 1.23007 0.23341 - -0.0300232 1.29996 0.281595 - -0.174371 1.31545 0.344113 - -0.226682 1.19674 0.366497 - -0.240265 1.1234 0.372217 - -0.180355 0.801561 0.345583 - -0.165469 0.728269 0.33898 - -0.0840611 0.282318 0.302769 - -0.085191 0.281835 0.303257 - -0.0893785 0.289704 0.305087 - -0.120826 0.297252 0.318716 - -0.848263 1.38385 0.635968 - -0.945783 1.39126 0.678198 - -0.964994 1.29709 0.686308 - -0.979252 1.17339 0.69221 - -0.983319 1.16791 0.693959 - -1.3165 -1.53791 0.816043 - -0.282731 -0.383377 0.38367 - -0.253766 -0.365198 0.371525 - -0.177567 -0.371794 0.339456 - -0.167867 -0.37188 0.335375 - -0.148437 -0.374702 0.327195 - -0.130699 -0.375681 0.319731 - -0.123277 -0.384372 0.31659 - -0.113729 -0.372285 0.3126 - -0.108061 -0.380924 0.310197 - -0.0726966 -0.380008 0.295322 - -0.0365297 -0.394912 0.280075 - -0.0263333 -0.390309 0.275796 --0.00928233 -0.396052 0.26861 --0.00768928 -0.396168 0.26794 - 0.0036345 -0.39177 0.263186 - 0.0131486 -0.384987 0.259198 - 0.0935796 -0.403305 0.225324 - 0.0953928 -0.403912 0.224559 - 0.0992376 -0.406073 0.222937 - 0.107823 -0.405948 0.219326 - 0.124061 -0.401215 0.212506 - 0.126459 -0.403575 0.211492 - 0.140656 -0.409221 0.205507 - 0.142301 -0.408627 0.204816 - 0.143944 -0.408025 0.204126 - 0.148858 -0.406173 0.202063 - 0.155662 -0.409879 0.199193 - 0.177235 -0.411338 0.190115 - 0.180538 -0.409795 0.188728 - 0.200051 -0.413275 0.180512 - 0.209547 -0.420466 0.176502 - 0.247441 -0.417257 0.160568 - 0.255124 -0.42272 0.157324 - 0.275003 -0.427974 0.14895 - 0.304897 -0.434775 0.13636 - 0.347506 -0.435706 0.118433 - 0.395309 -0.440706 0.0983132 - 0.474964 -0.455661 0.0647723 - 0.47884 -0.455499 0.0631419 - 0.512484 -0.459417 0.0489805 - 0.53446 -0.458935 0.0397367 - 0.545324 -0.460262 0.0351638 - 0.563184 -0.463161 0.027644 - 0.636898 -0.47099 -0.00338209 - 0.655486 -0.471688 -0.0112031 - 0.716677 -0.483554 -0.0369704 - 0.873321 -0.530771 -0.102969 - 1.20541 -0.513766 -0.242633 - 1.1992 -0.498144 -0.239985 - 1.19886 -0.485154 -0.239814 - 1.20401 -0.455377 -0.241917 - 1.20584 -0.449748 -0.242672 - 1.20767 -0.437825 -0.243419 - 1.21709 -0.409817 -0.247321 - 1.21414 -0.353358 -0.245957 - 1.21296 -0.334816 -0.24542 - 1.2109 -0.274541 -0.244423 - 1.20972 -0.250736 -0.243877 - 1.20721 -0.215273 -0.242742 - 1.20152 -0.196978 -0.240308 - 1.18911 -0.138425 -0.234962 - 1.19033 -0.0268667 -0.235231 - 1.19604 0.0176845 -0.237538 - 1.20035 0.0345706 -0.239313 - 1.19454 0.0847099 -0.236762 - 1.20214 0.130478 -0.239859 - 1.20182 0.175971 -0.239626 - 1.20111 0.18158 -0.239314 - 1.18867 0.191007 -0.234061 - 1.19902 0.209897 -0.238372 - 1.19982 0.25051 -0.238624 - 1.20083 0.279947 -0.238985 - 1.20265 0.315868 -0.239672 - 1.07851 0.353144 -0.187369 - 1.18139 0.411601 -0.230521 - 1.19205 0.433905 -0.234957 - 1.19889 0.455242 -0.237789 - 1.197 0.49261 -0.236909 - 1.19659 0.544436 -0.236625 - 1.19525 0.610962 -0.235918 - 0.696647 0.41811 -0.0265878 - 0.347747 0.245081 0.119809 - 0.318607 0.249619 0.132078 - 0.336579 0.335772 0.124704 - 0.29671 0.353245 0.141514 - 0.287492 0.366759 0.145421 - 0.256434 0.375681 0.158505 - 0.242973 0.393672 0.164207 - 0.21513 0.397381 0.175928 - 0.168168 0.326949 0.195531 - 0.118159 0.40529 0.216738 - 0.0913172 0.409046 0.228038 - 0.0779022 0.421791 0.233709 - 0.073291 0.439723 0.235688 - 0.0684581 0.460581 0.237766 - 0.0876439 1.04019 0.230953 - 0.0856872 1.22876 0.232185 - 0.0526504 1.28643 0.246208 - -0.137125 1.30932 0.32609 - -0.159356 1.31511 0.335455 - -0.185002 1.30568 0.346223 - -0.203964 1.28985 0.354166 - -0.218596 1.22558 0.360181 - -0.0736914 0.300462 0.297217 - -0.0766754 0.288817 0.298447 - -0.0850947 0.286529 0.301984 - -0.0920465 0.280263 0.304894 - -0.121551 0.278252 0.317302 - -0.12179 0.275839 0.317397 - -0.160131 0.315323 0.333612 - -0.757394 1.26773 0.58693 - -0.896992 1.40145 0.645945 - -0.902623 1.39711 0.648305 - -0.908237 1.39274 0.650657 - -0.916 1.39158 0.65392 - -0.931946 1.40246 0.660652 - -0.953206 1.37015 0.669525 - -0.970443 1.2639 0.676546 - -0.982112 1.15076 0.681209 - -0.9908 1.13073 0.68482 - -1.31519 -1.50284 0.79924 - -1.32708 -1.58398 0.803921 - -0.22257 -0.367986 0.35547 - -0.216444 -0.365269 0.352973 - -0.200031 -0.369752 0.346261 - -0.156534 -0.377718 0.32848 - -0.149856 -0.371217 0.325767 - -0.132156 -0.372226 0.318535 - -0.122744 -0.375347 0.314685 - -0.105018 -0.373953 0.307449 - -0.0957845 -0.382527 0.303659 - -0.0662682 -0.376761 0.291617 - -0.0647457 -0.377144 0.290995 - -0.057242 -0.388107 0.287907 - -0.0427842 -0.388922 0.282 - -0.0363594 -0.388973 0.279376 --0.00275748 -0.383487 0.265665 - 0.00026029 -0.385644 0.264428 - 0.0174107 -0.386994 0.257421 - 0.0221967 -0.392934 0.255454 - 0.038679 -0.403228 0.2487 - 0.0418069 -0.400999 0.247427 - 0.0457453 -0.388636 0.245846 - 0.0873348 -0.406677 0.228822 - 0.0971673 -0.404509 0.224811 - 0.111328 -0.406032 0.219024 - 0.122393 -0.407996 0.214501 - 0.1408 -0.409221 0.206981 - 0.1477 -0.407742 0.204166 - 0.153264 -0.407718 0.201894 - 0.162818 -0.41346 0.19798 - 0.181225 -0.410712 0.190468 - 0.197896 -0.41681 0.183647 - 0.209605 -0.415082 0.178869 - 0.214224 -0.415903 0.17698 - 0.250148 -0.425221 0.162289 - 0.271762 -0.429569 0.153452 - 0.287821 -0.431265 0.14689 - 0.328136 -0.435424 0.130417 - 0.33166 -0.42862 0.128992 - 0.383866 -0.445106 0.107636 - 0.400877 -0.441818 0.100696 - 0.783997 -0.488155 -0.0558697 - 0.905956 -0.537761 -0.105784 - 0.957512 -0.563093 -0.126895 - 0.961404 -0.559609 -0.128477 - 1.12096 -0.587818 -0.1937 - 1.23189 -0.556618 -0.238936 - 1.23255 -0.523383 -0.239132 - 1.23448 -0.504341 -0.239879 - 1.24407 -0.442944 -0.243664 - 1.24567 -0.411523 -0.244251 - 1.23464 -0.201671 -0.239292 - 1.23705 -0.161006 -0.240187 - 1.23649 -0.062373 -0.239745 - 1.2347 -0.0335184 -0.238954 - 1.23205 -0.0277102 -0.23786 - 1.23545 0.133606 -0.238897 - 1.23442 0.262767 -0.238197 - 1.09085 0.344785 -0.179388 - 1.23361 0.434687 -0.237499 - 1.23007 0.537497 -0.235827 - 1.22834 0.611634 -0.23496 - 1.20658 0.635175 -0.226026 - 1.12434 0.637472 -0.192432 - 0.69122 0.438826 -0.0159771 - 0.857618 0.579868 -0.0836288 - 0.76536 0.531335 -0.0460556 - 0.319775 0.247584 0.135307 - 0.318773 0.249013 0.135719 - 0.317616 0.25716 0.136209 - 0.31875 0.260448 0.135754 - 0.352546 0.313588 0.122066 - 0.335545 0.305718 0.128992 - 0.305793 0.333092 0.141202 - 0.294253 0.343057 0.145937 - 0.286822 0.361585 0.149011 - 0.252923 0.37269 0.16288 - 0.244143 0.390905 0.166505 - 0.243852 0.435356 0.166719 - 0.174966 0.326685 0.194618 - 0.171507 0.322993 0.196022 - 0.170202 0.323723 0.196557 - 0.146491 0.332404 0.206259 - 0.148763 0.346558 0.205362 - 0.149014 0.360482 0.205289 - 0.154005 0.378787 0.203291 - 0.187669 0.516839 0.189841 - 0.031632 1.2909 0.255238 - -0.010286 1.30067 0.272378 - -0.0365481 1.29972 0.283102 - -0.0417979 1.29945 0.285245 - -0.0475303 1.30915 0.287607 - -0.23048 1.20065 0.362089 - -0.0888384 0.370007 0.302448 - -0.0754195 0.299083 0.296815 - -0.105028 0.286542 0.30888 - -0.120691 0.289469 0.315283 - -0.126779 0.283745 0.317757 - -0.129286 0.266129 0.318743 - -0.818767 1.34882 0.602664 - -0.906523 1.3963 0.638606 - -0.9387 1.40569 0.651767 - -0.952227 1.36222 0.657198 - -0.970652 1.24705 0.664474 - -0.973409 1.22864 0.66556 - -1.31691 -1.53615 0.779731 - -0.263744 -0.367279 0.368064 - -0.259908 -0.365473 0.36656 - -0.242742 -0.358383 0.359824 - -0.241285 -0.359589 0.359248 - -0.239823 -0.360787 0.358671 - -0.228613 -0.361011 0.354262 - -0.224734 -0.365225 0.352727 - -0.212062 -0.362466 0.34775 - -0.203659 -0.369576 0.34443 - -0.187277 -0.369796 0.337987 - -0.181089 -0.377071 0.335537 - -0.160406 -0.370795 0.327417 - -0.131916 -0.372919 0.316208 - -0.118273 -0.384139 0.310819 - -0.0942088 -0.379228 0.301366 - -0.0882948 -0.38218 0.299033 - -0.0749054 -0.381947 0.293768 - -0.0614603 -0.380202 0.288485 - -0.0523472 -0.383208 0.284894 - -0.048736 -0.380873 0.283479 - -0.0471891 -0.381169 0.28287 - -0.0451672 -0.388643 0.282059 - -0.0425916 -0.393144 0.281036 - -0.0234638 -0.396844 0.273506 - -0.0212924 -0.39105 0.272664 - 0.00903198 -0.388945 0.260743 - 0.0106114 -0.38897 0.260122 - 0.0365586 -0.401336 0.249891 - 0.0426605 -0.394889 0.247505 - 0.0442639 -0.394756 0.246875 - 0.0694319 -0.400766 0.236964 - 0.0711964 -0.401496 0.236269 - 0.0728264 -0.401229 0.235629 - 0.101599 -0.401372 0.224313 - 0.109682 -0.406479 0.221123 - 0.115574 -0.408981 0.218801 - 0.117234 -0.408506 0.218149 - 0.118402 -0.406094 0.217694 - 0.146371 -0.414652 0.206677 - 0.178615 -0.413178 0.193999 - 0.180852 -0.408879 0.193129 - 0.195872 -0.415853 0.187207 - 0.19756 -0.415002 0.186545 - 0.24554 -0.423963 0.167657 - 0.259444 -0.427834 0.16218 - 0.26118 -0.426684 0.1615 - 0.305808 -0.42936 0.143944 - 0.373148 -0.445925 0.117425 - 0.452486 -0.45327 0.0862083 - 0.457503 -0.450526 0.084241 - 0.49209 -0.452859 0.070634 - 0.513311 -0.464756 0.062263 - 0.542153 -0.462095 0.0509261 - 0.544749 -0.460248 0.049909 - 0.595063 -0.468962 0.0301036 - 0.605985 -0.464899 0.0258169 - 0.694373 -0.482414 -0.00898087 - 0.741419 -0.486958 -0.0274926 - 0.747349 -0.486175 -0.0298228 - 1.07516 -0.585708 -0.158954 - 1.16861 -0.59019 -0.195716 - 1.28368 -0.598698 -0.240987 - 1.28207 -0.52151 -0.240187 - 1.28822 -0.483359 -0.242526 - 1.29123 -0.471077 -0.243682 - 1.30692 -0.390408 -0.24968 - 1.28817 -0.197313 -0.24189 - 1.28712 -0.191066 -0.241464 - 1.28517 -0.160505 -0.240633 - 1.28459 -0.148374 -0.240376 - 1.28333 -0.142214 -0.239869 - 1.28867 -0.100683 -0.241878 - 1.2892 -0.0767312 -0.242035 - 1.28513 -0.0645467 -0.240411 - 1.28009 0.00098738 -0.238285 - 1.27502 0.325939 -0.235595 - 1.07601 0.360171 -0.157257 - 1.27705 0.604581 -0.235794 - 1.20554 0.638544 -0.207599 - 0.765048 0.533755 -0.0345916 - 0.326015 0.23833 0.137432 - 0.323459 0.293118 0.138555 - 0.306298 0.323929 0.14537 - 0.297034 0.345314 0.149059 - 0.285671 0.362077 0.153564 - 0.245904 0.388983 0.169261 - 0.244323 0.390058 0.169885 - 0.248724 0.425826 0.168231 - 0.245442 0.437097 0.169546 - 0.149932 0.321045 0.206857 - 0.160009 0.394609 0.203053 - 0.192135 0.529078 0.190708 - 0.143627 0.417967 0.209545 - 0.0908626 0.41725 0.230294 - 0.0968183 1.17682 0.229585 - -0.0427339 1.30145 0.284734 - -0.0915377 1.31389 0.303954 - -0.163227 1.32401 0.332169 - -0.201986 1.29187 0.347343 - -0.217778 1.23158 0.353423 - -0.162528 0.726111 0.330609 - -0.141465 0.597561 0.322049 - -0.0729044 0.283479 0.294411 - -0.0790493 0.286489 0.296834 - -0.0836892 0.28467 0.298655 - -0.0851742 0.285137 0.29924 - -0.0863314 0.284662 0.299694 - -0.095154 0.279747 0.303153 - -0.115719 0.279399 0.31124 - -0.131714 0.279269 0.31753 - -0.172995 0.323807 0.333861 - -0.971845 1.20894 0.649926 - -0.981711 1.16854 0.653719 - -1.31393 -1.53944 0.762442 - -1.32064 -1.58839 0.764893 - -0.159752 -0.375113 0.325032 - -0.150125 -0.378964 0.321354 - -0.138194 -0.37703 0.316811 - -0.0954277 -0.386432 0.300491 - -0.0666122 -0.378118 0.289526 - -0.038644 -0.383779 0.278854 - -0.0312808 -0.388901 0.276037 - -0.0265205 -0.389512 0.274221 - 0.0102611 -0.38297 0.260217 - 0.0133841 -0.382997 0.259026 - 0.026274 -0.396805 0.254084 - 0.0406924 -0.394017 0.248594 - 0.0426448 -0.398878 0.24784 - 0.086465 -0.412911 0.231108 - 0.127243 -0.399219 0.215596 - 0.212632 -0.415054 0.183017 - 0.23158 -0.422413 0.17578 - 0.244196 -0.420509 0.170975 - 0.264756 -0.423514 0.163132 - 0.267485 -0.424029 0.162091 - 0.277776 -0.428809 0.158159 - 0.291222 -0.429978 0.153031 - 0.326027 -0.437558 0.13975 - 0.37116 -0.44214 0.122538 - 0.428733 -0.446384 0.100586 - 0.438996 -0.449535 0.0966674 - 0.5004 -0.455229 0.0732519 - 0.51142 -0.461478 0.0690381 - 0.552759 -0.461512 0.0532824 - 0.67187 -0.473684 0.00785887 - 1.20745 -0.60096 -0.196542 - 1.28098 -0.609342 -0.224585 - 1.31892 -0.591333 -0.239009 - 1.31766 -0.576455 -0.238496 - 1.32688 -0.552029 -0.241958 - 1.31518 -0.526173 -0.237444 - 1.33999 -0.459713 -0.246757 - 1.34028 -0.365775 -0.246667 - 1.34193 -0.320303 -0.247198 - 1.32475 -0.1773 -0.240342 - 1.33219 -0.0297347 -0.242864 - 1.33239 -0.0174319 -0.242914 - 1.32869 0.0562599 -0.241346 - 1.32516 0.105215 -0.239895 - 1.32152 0.166508 -0.238378 - 1.32906 0.248991 -0.241075 - 1.29157 0.328983 -0.226614 - 1.10631 0.324741 -0.156013 - 1.09644 0.332707 -0.152235 - 1.32098 0.502821 -0.237451 - 1.31918 0.572015 -0.236616 - 1.31922 0.607909 -0.236557 - 0.961199 0.556276 -0.100211 - 0.705453 0.418604 -0.00303125 - 0.326309 0.235717 0.141083 - 0.323824 0.236005 0.142031 - 0.318036 0.255921 0.144279 - 0.326067 0.300012 0.141313 - 0.317951 0.307929 0.144423 - 0.30347 0.337159 0.150005 - 0.295917 0.343057 0.152896 - 0.275313 0.383676 0.160836 - 0.272176 0.38609 0.162037 - 0.246997 0.386216 0.171634 - 0.246421 0.437968 0.171964 - 0.160446 0.315812 0.204471 - 0.152285 0.354876 0.207665 - 0.198714 0.519142 0.190321 - 0.190223 0.522488 0.193565 - 0.177797 0.492184 0.198236 - 0.140292 0.412855 0.21236 - 0.121502 0.404313 0.219504 - 0.0807617 0.432355 0.235091 - 0.0754452 0.446379 0.237148 - 0.069401 0.531861 0.239634 - 0.0714336 0.574876 0.238952 - 0.0910266 1.24139 0.232911 - -0.0275881 1.30517 0.278256 - -0.075576 1.30433 0.296544 - -0.107451 1.30132 0.308686 - -0.219733 1.23452 0.351338 - -0.225986 1.05372 0.353334 - -0.0963293 0.283951 0.30227 - -0.107095 0.286542 0.306378 - -0.114939 0.288122 0.309371 - -0.12248 0.288579 0.312247 - -0.125236 0.279133 0.313277 - -0.131139 0.279084 0.315526 - -0.881044 1.39455 0.603731 - -0.9442 1.39924 0.627812 - -0.969698 1.26628 0.637245 - -0.97005 1.25554 0.637357 - -0.978128 1.22185 0.640363 - -0.990476 1.11347 0.644837 - -1.35719 -1.46336 0.762914 - -1.31545 -1.4692 0.747484 - -0.246426 -0.362764 0.355014 - -0.223668 -0.359506 0.346615 - -0.201678 -0.361982 0.338488 - -0.195682 -0.369484 0.336258 - -0.170859 -0.371864 0.327085 - -0.146113 -0.375938 0.317936 - -0.12538 -0.378787 0.310273 - -0.116531 -0.373833 0.307015 - -0.113516 -0.380333 0.305888 - -0.104429 -0.384719 0.302522 - -0.0806259 -0.378716 0.293744 - -0.0715145 -0.382207 0.290371 - -0.0572683 -0.376346 0.285122 - -0.0328377 -0.383725 0.276083 - -0.0239882 -0.390876 0.272799 - -0.019014 -0.389385 0.270965 - 0.00184495 -0.387773 0.263265 - 0.024124 -0.389858 0.255032 - 0.0366526 -0.385262 0.250415 - 0.0705428 -0.411651 0.237841 - 0.0772514 -0.399396 0.23539 - 0.0858326 -0.409961 0.232198 - 0.0893971 -0.401082 0.2309 - 0.104989 -0.401518 0.225141 - 0.127778 -0.40741 0.216712 - 0.13305 -0.406746 0.214766 - 0.138325 -0.406004 0.212819 - 0.158109 -0.409214 0.205505 - 0.207058 -0.415999 0.187412 - 0.221579 -0.419323 0.182042 - 0.233829 -0.425918 0.177503 - 0.271337 -0.433659 0.163634 - 0.284695 -0.426744 0.158715 - 0.360027 -0.434774 0.130875 - 0.373955 -0.440471 0.125719 - 0.376993 -0.440296 0.124597 - 0.389904 -0.444109 0.119821 - 0.436251 -0.445314 0.1027 - 0.481386 -0.455661 0.0860083 - 0.502129 -0.45948 0.0783389 - 0.679472 -0.477594 0.0128011 - 0.760789 -0.486912 -0.0172521 - 0.803412 -0.494745 -0.0330108 - 0.890295 -0.522145 -0.0651586 - 1.08701 -0.587994 -0.137953 - 1.36235 -0.60145 -0.239673 - 1.36195 -0.543146 -0.239403 - 1.3707 -0.496742 -0.242537 - 1.37597 -0.470504 -0.244426 - 1.37629 -0.428944 -0.244456 - 1.38276 -0.389756 -0.246761 - 1.38258 -0.362548 -0.246636 - 1.37989 -0.308314 -0.245526 - 1.37451 -0.248059 -0.243413 - 1.36151 -0.055373 -0.2382 - 1.3676 0.159013 -0.23999 - 1.37253 0.165988 -0.241798 - 1.38044 0.17984 -0.244689 - 1.36286 0.273928 -0.237996 - 1.3698 0.308135 -0.240487 - 1.36761 0.314222 -0.239666 - 1.14084 0.322584 -0.155892 - 1.09076 0.335228 -0.137369 - 1.08938 0.34023 -0.136849 - 1.35804 0.50118 -0.235731 - 1.35971 0.522963 -0.236304 - 1.35856 0.587188 -0.23574 - 1.35803 0.601601 -0.235516 - 1.30862 0.629676 -0.217205 - 1.289 0.627301 -0.209963 - 1.266 0.630157 -0.201465 - 1.23884 0.630458 -0.191431 - 0.743257 0.485969 -0.0087027 - 0.806005 0.548519 -0.0317446 - 0.353402 0.246208 0.134774 - 0.336731 0.238508 0.140914 - 0.319715 0.243156 0.147209 - 0.318553 0.262661 0.14768 - 0.327901 0.295771 0.144298 - 0.323845 0.30502 0.145816 - 0.311014 0.313515 0.150573 - 0.312402 0.323332 0.150081 - 0.311077 0.324714 0.150573 - 0.304058 0.339984 0.153198 - 0.293971 0.352066 0.15695 - 0.291416 0.358247 0.157906 - 0.288475 0.360807 0.158998 - 0.249599 0.375174 0.173387 - 0.240156 0.438537 0.17701 - 0.169181 0.320165 0.202971 - 0.167869 0.32088 0.203457 - 0.165162 0.325681 0.204467 - 0.156608 0.321191 0.207617 - 0.148097 0.343786 0.210808 - 0.127254 0.405667 0.218638 - 0.116953 0.400465 0.222432 - 0.106312 0.407493 0.226377 - 0.101285 0.400532 0.228219 - 0.0766741 0.443126 0.237399 - 0.070627 0.524648 0.239807 - 0.0566018 1.28325 0.246604 --0.00666738 1.29678 0.27 - -0.198335 1.28698 0.340769 - -0.123617 0.540173 0.311581 - -0.104075 0.287315 0.303824 - -0.10525 0.28676 0.304257 - -0.119804 0.287169 0.309633 - -0.126652 0.289056 0.312166 - -0.139504 0.28149 0.316897 - -0.136527 0.270595 0.315775 - -0.849044 1.39025 0.58132 - -0.950799 1.36492 0.618847 - -0.963636 1.29853 0.623448 - -0.965926 1.27853 0.624251 - -0.981686 1.15823 0.629815 - -0.98642 1.15358 0.631553 - -1.33827 -1.46249 0.739699 - -1.31606 -1.52915 0.731623 - -1.33538 -1.69389 0.738176 - -0.208483 -0.367705 0.338317 - -0.192417 -0.368844 0.332574 - -0.164992 -0.373469 0.322765 - -0.151399 -0.360543 0.317935 - -0.152079 -0.370187 0.318157 - -0.130986 -0.376806 0.310606 - -0.11698 -0.367609 0.305621 - -0.106963 -0.373572 0.302029 - -0.104118 -0.38092 0.300997 - -0.0852957 -0.374471 0.294284 - -0.0356416 -0.388457 0.276512 - -0.0340451 -0.388683 0.275941 - -0.0295825 -0.392295 0.274338 --0.00508336 -0.389479 0.26559 - 0.0465564 -0.393471 0.247129 - 0.0535107 -0.397777 0.244635 - 0.0670847 -0.400027 0.23978 - 0.0763067 -0.394465 0.236496 - 0.0858015 -0.400784 0.23309 - 0.0905485 -0.398769 0.231398 - 0.112189 -0.409908 0.223642 - 0.114115 -0.40318 0.222968 - 0.126393 -0.408894 0.218568 - 0.130874 -0.405382 0.216974 - 0.155207 -0.411476 0.208267 - 0.170118 -0.415057 0.202931 - 0.176664 -0.416543 0.200589 - 0.178374 -0.415785 0.199979 - 0.200122 -0.418618 0.192202 - 0.205268 -0.415993 0.190369 - 0.218491 -0.425743 0.185623 - 0.224161 -0.423746 0.183601 - 0.241084 -0.417248 0.177568 - 0.252469 -0.425221 0.173483 - 0.270914 -0.431968 0.166877 - 0.316051 -0.433045 0.150746 - 0.363398 -0.441737 0.133809 - 0.410845 -0.443622 0.116851 - 0.476752 -0.45376 0.0932787 - 0.495386 -0.455757 0.0866161 - 0.499372 -0.455507 0.0851925 - 0.570259 -0.465129 0.0598418 - 0.618209 -0.474201 0.0426885 - 0.712668 -0.485796 0.00891078 - 0.940464 -0.538953 -0.0726007 - 1.30799 -0.610732 -0.204082 - 1.3501 -0.615833 -0.219141 - 1.42358 -0.442259 -0.245026 - 1.42892 -0.422626 -0.246894 - 1.43053 -0.408972 -0.247441 - 1.43359 -0.346903 -0.248401 - 1.425 -0.28336 -0.245199 - 1.41033 -0.174406 -0.239723 - 1.413 -0.0378196 -0.240388 - 1.41343 -0.011888 -0.240485 - 1.41052 0.0593388 -0.239295 - 1.41187 0.0723737 -0.239749 - 1.42636 0.138891 -0.244787 - 1.42578 0.145433 -0.244566 - 1.42014 0.164602 -0.242509 - 1.42548 0.185111 -0.244374 - 1.41859 0.22398 -0.241831 - 1.40812 0.308981 -0.237909 - 1.10305 0.321525 -0.128872 - 1.09268 0.334667 -0.125137 - 1.40649 0.53194 -0.236853 - 1.29862 0.622615 -0.198113 - 1.13351 0.567846 -0.139233 - 1.0975 0.56195 -0.126375 - 1.02585 0.566035 -0.100765 - 0.771274 0.517755 -0.00989971 - 0.326006 0.245307 0.14863 - 0.328033 0.275027 0.147969 - 0.292189 0.349011 0.160934 - 0.287921 0.359252 0.162481 - 0.28496 0.361773 0.163544 - 0.245572 0.439043 0.177783 - 0.155808 0.322754 0.209611 - 0.149988 0.348407 0.211746 - 0.0925742 0.418855 0.232411 - 0.0793874 0.437595 0.237163 - 0.0780919 0.674636 0.238129 - 0.0965272 0.908858 0.232039 - 0.045967 1.29158 0.250919 - 0.0141186 1.295 0.262306 - -0.0233816 1.30336 0.275724 - -0.0832606 1.31386 0.297143 - -0.210358 1.2554 0.342435 - -0.196916 0.93331 0.336947 - -0.187543 0.875022 0.333474 - -0.0991975 0.283427 0.300649 - -0.103707 0.291165 0.302277 - -0.106029 0.293366 0.303111 - -0.121491 0.312296 0.308677 - -0.119988 0.305322 0.308125 - -0.122492 0.304065 0.309017 - -0.117143 0.285715 0.307067 - -0.136334 0.279443 0.313911 - -0.1391 0.2789 0.314898 - -0.158081 0.298291 0.321722 - -0.171198 0.317888 0.32645 - -0.617326 1.05206 0.487425 - -0.755627 1.27021 0.537308 - -0.844006 1.38924 0.569141 - -0.873703 1.39707 0.579769 - -0.908423 1.3984 0.592179 - -0.962977 1.31543 0.611496 - -0.976211 1.19842 0.615977 - -1.30931 -1.59717 0.713326 - -1.3361 -1.67317 0.722418 - -0.226562 -0.366638 0.341919 - -0.225048 -0.367743 0.341394 - -0.196578 -0.370457 0.331554 - -0.192556 -0.370658 0.330164 - -0.178278 -0.366612 0.325241 - -0.175699 -0.369248 0.324345 - -0.167399 -0.368248 0.32148 - -0.162829 -0.370721 0.319896 - -0.148158 -0.380328 0.314808 - -0.143113 -0.377228 0.313072 - -0.0991121 -0.378712 0.29787 - -0.0819266 -0.37775 0.291935 - -0.0685594 -0.377144 0.287319 - -0.0576365 -0.379618 0.283541 - -0.036111 -0.387466 0.276089 - -0.0347594 -0.389674 0.275617 - -0.0329135 -0.387909 0.274983 - -0.0198309 -0.386397 0.270468 --0.00848956 -0.384298 0.266554 - 0.0496014 -0.394148 0.246468 - 0.0619171 -0.400732 0.242199 - 0.0836949 -0.409306 0.234659 - 0.0853824 -0.408978 0.234076 - 0.100923 -0.407625 0.228711 - 0.111446 -0.407001 0.225078 - 0.115281 -0.408014 0.223751 - 0.116963 -0.40754 0.223171 - 0.130588 -0.410707 0.218458 - 0.146665 -0.408361 0.212909 - 0.19168 -0.412985 0.19735 - 0.219293 -0.417623 0.187802 - 0.235975 -0.424019 0.182026 - 0.242938 -0.419845 0.17963 - 0.263908 -0.427534 0.17237 - 0.271718 -0.428244 0.169671 - 0.279875 -0.433387 0.166842 - 0.338496 -0.4356 0.146589 - 0.398218 -0.447535 0.125934 - 0.400061 -0.445755 0.125301 - 0.403822 -0.446167 0.124001 - 0.498648 -0.453521 0.0912298 - 0.524749 -0.461364 0.0821973 - 0.542773 -0.465104 0.0759636 - 0.575635 -0.468221 0.0646054 - 0.600263 -0.467158 0.0561008 - 0.642412 -0.47395 0.0415271 - 0.733576 -0.484627 0.0100139 - 0.780155 -0.496306 -0.00610012 - 1.35468 -0.615833 -0.204809 - 1.45772 -0.570077 -0.240306 - 1.46022 -0.548339 -0.241122 - 1.4628 -0.519295 -0.24195 - 1.46756 -0.491237 -0.243536 - 1.46512 -0.311293 -0.242312 - 1.46583 -0.269774 -0.242471 - 1.46283 -0.0926564 -0.241061 - 1.47452 0.0888831 -0.244715 - 1.46734 0.224104 -0.241948 - 1.46174 0.305843 -0.239838 - 1.29582 0.326641 -0.182484 - 1.438 0.505291 -0.231218 - 1.45085 0.539534 -0.235584 - 1.08861 0.561647 -0.110409 - 1.04409 0.56828 -0.0950173 - 1.00065 0.573615 -0.0800019 - 0.70335 0.434617 0.0224 - 0.420364 0.279712 0.119823 - 0.357145 0.243048 0.141582 - 0.325466 0.248789 0.152537 - 0.325462 0.274558 0.152593 - 0.324252 0.288372 0.15304 - 0.299756 0.345314 0.161622 - 0.297516 0.348697 0.162403 - 0.283713 0.365844 0.167208 - 0.254527 0.36746 0.177293 - 0.251488 0.369668 0.178347 - 0.244702 0.38752 0.180729 - 0.182768 0.336532 0.202014 - 0.173877 0.325655 0.205063 - 0.148134 0.335166 0.213975 - 0.160412 0.43844 0.209952 - 0.110882 0.412449 0.227007 - 0.0952944 0.424369 0.232416 - 0.0829636 0.437963 0.236704 - 0.0765673 0.445104 0.238929 - 0.0751296 0.462501 0.239462 - 0.0740263 0.484862 0.239891 - 0.112152 1.08207 0.227985 - 0.105184 1.23026 0.230705 - 0.0818316 1.27 0.238856 - 0.003021 1.29094 0.266123 - -0.0996292 1.30441 0.30161 - -0.122675 1.31702 0.309597 - -0.133534 1.3157 0.313345 - -0.160235 1.309 0.322554 - -0.202625 1.26531 0.337104 - -0.224507 1.18533 0.344493 - -0.0888028 0.404643 0.295966 - -0.0837905 0.291201 0.293995 - -0.0941737 0.28599 0.29757 - -0.139254 0.359116 0.313297 - -0.134673 0.332725 0.311659 - -0.122099 0.288064 0.307221 - -0.161619 0.302552 0.320903 - -0.637901 1.08157 0.487071 - -0.873238 1.39044 0.569016 - -0.911231 1.39676 0.582153 - -0.922987 1.40145 0.586223 - -0.935621 1.39436 0.590573 - -0.983129 1.15012 0.606466 - -0.988281 1.09694 0.608133 - -1.36225 -1.43865 0.715824 - -1.35027 -1.46392 0.711771 - -1.29666 -1.48199 0.693842 - -0.238531 -0.362286 0.34311 - -0.199763 -0.370339 0.330156 - -0.134515 -0.371759 0.30838 - -0.121785 -0.376027 0.304123 - -0.111779 -0.377731 0.300781 - -0.0871024 -0.375434 0.292551 - -0.0839058 -0.38258 0.291469 - -0.0761819 -0.378483 0.2889 - -0.0651127 -0.373004 0.285218 - -0.0549799 -0.379277 0.281824 - -0.0319995 -0.389112 0.274134 --0.00781766 -0.392383 0.266058 - 0.00050502 -0.386773 0.263293 - 0.0149478 -0.393994 0.258458 - 0.0262609 -0.390751 0.25469 - 0.0360753 -0.392249 0.251411 - 0.0563776 -0.398388 0.244624 - 0.090666 -0.400729 0.233177 - 0.123006 -0.409921 0.222366 - 0.128956 -0.404963 0.220391 - 0.136801 -0.406577 0.217769 - 0.139949 -0.410759 0.21671 - 0.154541 -0.420309 0.211821 - 0.156794 -0.409879 0.211091 - 0.174856 -0.411002 0.205061 - 0.216584 -0.420398 0.191117 - 0.25115 -0.425462 0.179571 - 0.291269 -0.434202 0.166165 - 0.293395 -0.425398 0.165475 - 0.329189 -0.433721 0.153513 - 0.351199 -0.439605 0.146156 - 0.370631 -0.440761 0.139669 - 0.399185 -0.447535 0.130126 - 0.42142 -0.453045 0.122695 - 0.427793 -0.452146 0.12057 - 0.445652 -0.447549 0.11462 - 0.455655 -0.453922 0.111269 - 0.467253 -0.449817 0.107407 - 0.575434 -0.462546 0.0712807 - 0.724155 -0.481463 0.0216131 - 0.827378 -0.504884 -0.0128816 - 0.865214 -0.517846 -0.0255344 - 1.06029 -0.555518 -0.0907118 - 1.2368 -0.614262 -0.149736 - 1.27452 -0.619014 -0.162331 - 1.34265 -0.622914 -0.185075 - 1.34522 -0.616792 -0.18592 - 1.49959 -0.616048 -0.23743 - 1.50124 -0.608842 -0.237967 - 1.51285 -0.558644 -0.241735 - 1.52025 -0.476962 -0.244031 - 1.52794 -0.434156 -0.246507 - 1.52204 -0.402781 -0.244473 - 1.52533 -0.388884 -0.245541 - 1.52019 -0.3729 -0.243792 - 1.51514 -0.200263 -0.241742 - 1.51374 -0.0609989 -0.240984 - 1.50803 -0.0263601 -0.239004 - 1.51192 -0.0195337 -0.240289 - 1.52448 0.112558 -0.244201 - 1.52592 0.154703 -0.244591 - 1.51982 0.203198 -0.242454 - 1.17736 0.323981 -0.127921 - 1.08006 0.344645 -0.0954103 - 1.47481 0.608044 -0.22658 - 1.18172 0.555775 -0.128887 - 1.13546 0.55881 -0.113445 - 0.69003 0.442011 0.0349475 - 0.3254 0.248186 0.156215 - 0.319589 0.268798 0.158197 - 0.312431 0.315598 0.160685 - 0.300921 0.334058 0.164565 - 0.289668 0.360029 0.168375 - 0.284252 0.365844 0.170194 - 0.25068 0.408596 0.181487 - 0.238661 0.433275 0.18555 - 0.166127 0.319803 0.209515 - 0.159944 0.442889 0.211838 - 0.112975 0.413937 0.22745 - 0.108049 0.416246 0.229099 - 0.0907383 0.420195 0.234884 - 0.0889986 0.420546 0.235465 - 0.0774762 0.594204 0.239676 - 0.105521 0.966183 0.231102 - 0.113924 1.21344 0.228819 - 0.0559941 1.29124 0.248314 - 0.0455022 1.29958 0.251833 - -0.0408988 1.30671 0.28068 - -0.145873 1.31825 0.315734 - -0.15742 1.32168 0.319594 - -0.224312 1.12939 0.34151 - -0.180081 0.882629 0.32623 - -0.151512 0.696545 0.316305 - -0.0690904 0.283959 0.287931 - -0.0785229 0.289168 0.291089 - -0.0935779 0.282276 0.296099 - -0.134276 0.286381 0.309688 - -0.153253 0.286359 0.316021 - -0.179246 0.324654 0.324775 - -0.937539 1.40443 0.580092 - -0.962807 1.26988 0.58824 - -0.974253 1.25092 0.59202 - -1.32167 -1.55865 0.687463 - -1.32406 -1.5752 0.6882 - -1.32566 -1.63357 0.688594 - -0.278731 -0.378692 0.353306 - -0.263458 -0.362077 0.348411 - -0.254826 -0.360325 0.345628 - -0.205407 -0.370919 0.329655 - -0.179319 -0.368371 0.32124 - -0.158379 -0.365157 0.314487 - -0.156862 -0.365938 0.313996 - -0.148085 -0.371386 0.311152 - -0.12728 -0.374134 0.304431 - -0.123828 -0.374469 0.303315 - -0.103409 -0.381999 0.296709 - -0.09042 -0.378815 0.292523 - -0.06835 -0.377519 0.285402 - -0.0573422 -0.379943 0.281844 - -0.0500831 -0.3854 0.279489 - -0.0481036 -0.393857 0.278833 - -0.0128919 -0.388071 0.267479 - -0.0112803 -0.388185 0.266959 --0.00805581 -0.388389 0.265918 - 0.0195258 -0.396934 0.256997 - 0.0341889 -0.393349 0.252272 - 0.059091 -0.394997 0.24423 - 0.0840565 -0.413242 0.236134 - 0.099855 -0.41193 0.231037 - 0.126777 -0.4171 0.222336 - 0.141977 -0.41112 0.217443 - 0.156874 -0.409879 0.212637 - 0.159242 -0.411086 0.21187 - 0.172287 -0.414329 0.207653 - 0.184075 -0.413462 0.20385 - 0.212084 -0.419571 0.194796 - 0.221217 -0.42479 0.191837 - 0.225152 -0.419237 0.190579 - 0.252329 -0.422644 0.1818 - 0.297173 -0.430325 0.167309 - 0.312197 -0.432595 0.162455 - 0.356761 -0.438019 0.148059 - 0.389395 -0.446838 0.137507 - 0.393094 -0.443366 0.13632 - 0.422921 -0.449719 0.126679 - 0.491015 -0.451966 0.104695 - 0.593087 -0.471576 0.0717077 - 0.696597 -0.47949 0.0382803 - 0.743734 -0.483963 0.0230563 - 0.780959 -0.489135 0.0110299 - 1.04005 -0.537329 -0.0727014 - 1.56995 -0.570164 -0.24381 - 1.57679 -0.393328 -0.245645 - 1.56672 -0.36826 -0.242341 - 1.56516 -0.338081 -0.241775 - 1.56311 -0.213271 -0.24085 - 1.56549 -0.155906 -0.2415 - 1.56921 -0.0916744 -0.242564 - 1.56548 -0.070045 -0.241314 - 1.57095 0.180493 -0.242553 - 1.58197 0.232921 -0.246 - 1.5666 0.259772 -0.240983 - 1.55332 0.315819 -0.23658 - 1.5069 0.334838 -0.221557 - 1.14128 0.324126 -0.103563 - 1.08327 0.360861 -0.0847643 - 1.54741 0.588077 -0.234099 - 1.43786 0.606076 -0.198702 - 1.17642 0.551661 -0.114429 - 1.17239 0.556158 -0.113118 - 1.03209 0.570246 -0.0678042 - 1.01966 0.569224 -0.063793 - 0.68292 0.436216 0.0446196 - 0.319887 0.250018 0.161407 - 0.318847 0.251423 0.161746 - 0.28978 0.36931 0.171376 - 0.280906 0.373965 0.17425 - 0.28049 0.376793 0.17439 - 0.258934 0.366042 0.181325 - 0.251328 0.382364 0.183814 - 0.254507 0.422767 0.182873 - 0.250306 0.432327 0.184249 - 0.241278 0.43766 0.187175 - 0.205659 0.377168 0.198544 - 0.173706 0.324768 0.208748 - 0.154128 0.362919 0.215147 - 0.222344 0.596848 0.193621 - 0.128976 0.418669 0.223383 - 0.12645 0.416312 0.224193 - 0.121005 0.41687 0.225952 - 0.118267 0.420745 0.226844 - 0.116519 0.421222 0.227409 - 0.106621 0.410411 0.230581 - 0.104922 0.419048 0.231148 - 0.0891753 0.432689 0.236259 - 0.0781386 0.473102 0.239907 - 0.0773299 0.514608 0.240255 - 0.0505242 1.29742 0.250552 - 0.028958 1.2969 0.257512 - -0.0033047 1.29287 0.267917 - -0.14669 1.31726 0.31425 - -0.213693 1.25343 0.335743 - -0.0651327 0.290601 0.285768 - -0.0827386 0.283661 0.291436 - -0.0892806 0.283267 0.293547 - -0.119048 0.274936 0.303137 - -0.129357 0.283972 0.306484 - -0.132883 0.281988 0.307618 - -0.142337 0.274032 0.310653 - -0.613824 1.04315 0.464454 - -0.968551 1.21737 0.579318 - -1.30443 -1.39225 0.666445 - -1.31128 -1.46191 0.668428 - -1.32528 -1.57072 0.67255 - -1.32758 -1.62978 0.673142 - -1.32734 -1.70322 0.672913 - -0.269502 -0.37481 0.34695 - -0.259708 -0.365055 0.343927 - -0.21172 -0.368732 0.329006 - -0.202051 -0.366798 0.326005 - -0.185807 -0.370961 0.320948 - -0.179596 -0.374524 0.31901 - -0.167207 -0.365522 0.315179 - -0.156056 -0.370187 0.311704 - -0.152215 -0.374279 0.310502 - -0.150654 -0.375027 0.310015 - -0.145569 -0.376312 0.308432 - -0.138988 -0.373839 0.306392 - -0.0925215 -0.383622 0.291931 - -0.0869648 -0.382131 0.290207 - -0.0681057 -0.380816 0.284349 - -0.0581957 -0.380924 0.281269 - -0.0341356 -0.383941 0.273786 - 0.00250574 -0.39987 0.262365 - 0.0109073 -0.382997 0.25979 - 0.0158719 -0.403981 0.258203 - 0.0875769 -0.404372 0.235918 - 0.0952989 -0.407824 0.233511 - 0.105309 -0.412641 0.23039 - 0.119258 -0.409952 0.226061 - 0.139987 -0.410759 0.219617 - 0.156284 -0.408003 0.214558 - 0.163084 -0.41066 0.212439 - 0.168602 -0.414847 0.210716 - 0.203348 -0.414175 0.199919 - 0.302961 -0.430148 0.168929 - 0.366075 -0.440972 0.149292 - 0.383368 -0.44255 0.143915 - 0.389639 -0.44609 0.141958 - 0.441436 -0.452771 0.125847 - 0.467611 -0.451902 0.117715 - 0.506724 -0.457493 0.105548 - 0.510781 -0.457206 0.104288 - 0.523719 -0.456821 0.100268 - 0.550421 -0.463927 0.0919548 - 0.66569 -0.478438 0.0561019 - 0.730529 -0.483084 0.0359422 - 0.859708 -0.51673 -0.00427356 - 1.42026 -0.67073 -0.178799 - 1.45325 -0.623824 -0.188955 - 1.61994 -0.636499 -0.240783 - 1.62519 -0.621782 -0.242384 - 1.63004 -0.549127 -0.243739 - 1.63593 -0.360115 -0.245174 - 1.63035 -0.251966 -0.243212 - 1.62842 -0.161708 -0.242424 - 1.62908 -0.117147 -0.242535 - 1.62888 0.0899391 -0.242038 - 1.63048 0.112285 -0.242492 - 1.63409 0.142339 -0.243551 - 1.62605 0.276418 -0.24077 - 1.62685 0.306935 -0.240955 - 1.24714 0.329307 -0.122903 - 1.09928 0.337952 -0.0769346 - 1.46155 0.598865 -0.188973 - 1.25536 0.553438 -0.124991 - 1.2078 0.545201 -0.110227 - 1.17739 0.550427 -0.100764 - 1.01025 0.5681 -0.0487847 - 0.98126 0.563115 -0.0397869 - 0.494322 0.324951 0.111041 - 0.3535 0.250338 0.154648 - 0.328187 0.242677 0.162499 - 0.318711 0.250807 0.16546 - 0.313004 0.255103 0.167243 - 0.316762 0.262931 0.166091 - 0.32011 0.295466 0.165119 - 0.320566 0.30377 0.164995 - 0.318119 0.309355 0.165767 - 0.307628 0.317546 0.169045 - 0.261265 0.362151 0.183546 - 0.247481 0.382851 0.187873 - 0.258992 0.434187 0.184403 - 0.249923 0.44886 0.187253 - 0.106297 0.42587 0.231839 - 0.0962379 0.422031 0.234957 - 0.0911506 0.434302 0.236564 - 0.12355 1.20949 0.228119 - 0.0285346 1.2959 0.257828 - -0.174974 1.31228 0.321107 - -0.212448 1.23968 0.332601 - -0.185526 0.915694 0.323555 - -0.174941 0.849506 0.320127 - -0.134528 0.616995 0.307081 - -0.0709539 0.29008 0.286639 - -0.0915723 0.291225 0.293049 - -0.410868 0.939405 0.393635 - -0.139418 0.286759 0.307909 - -0.140612 0.286062 0.308279 - -0.840069 1.38706 0.527956 - -0.897578 1.39872 0.545853 - -0.956156 1.36984 0.563996 - -0.958163 1.3118 0.564499 - -0.978568 1.17211 0.570547 - -0.99151 1.14644 0.574516 - -0.986769 1.09217 0.572929 - -1.33132 -1.61458 0.659581 - -1.34096 -1.7148 0.662261 - -0.269943 -0.370387 0.343997 - -0.266021 -0.368524 0.342825 - -0.256714 -0.365939 0.340041 - -0.229412 -0.370495 0.331846 - -0.211263 -0.369752 0.326407 - -0.180318 -0.370127 0.31713 - -0.177409 -0.368355 0.316262 - -0.139101 -0.371998 0.30477 - -0.132713 -0.379063 0.30284 - -0.109166 -0.378472 0.295782 - -0.101798 -0.383049 0.293564 - -0.0730776 -0.377735 0.284965 - -0.0605867 -0.38158 0.281213 - -0.0581089 -0.386155 0.28046 - 0.0072556 -0.38697 0.260864 - 0.0420207 -0.39675 0.250421 - 0.0637777 -0.396306 0.2439 - 0.0798079 -0.400765 0.239085 - 0.116979 -0.415749 0.22791 - 0.148854 -0.408686 0.21837 - 0.153885 -0.412127 0.216854 - 0.158984 -0.415506 0.215319 - 0.167282 -0.411126 0.21284 - 0.179038 -0.410418 0.209318 - 0.191905 -0.416538 0.205447 - 0.203456 -0.418654 0.20198 - 0.240264 -0.416561 0.19095 - 0.255033 -0.42608 0.186503 - 0.294603 -0.432918 0.174626 - 0.312875 -0.427993 0.169159 - 0.316371 -0.429028 0.168109 - 0.34302 -0.437955 0.160102 - 0.373519 -0.437597 0.150959 - 0.404843 -0.443232 0.141557 - 0.442729 -0.445314 0.130195 - 0.505931 -0.459749 0.111218 - 0.524433 -0.460459 0.10567 - 0.744859 -0.486774 0.0395356 - 0.827102 -0.505561 0.0148416 - 0.996875 -0.534419 -0.0361132 - 1.26663 -0.623719 -0.117167 - 1.47913 -0.664797 -0.180957 - 1.68187 -0.650468 -0.241705 - 1.6926 -0.628601 -0.244876 - 1.68255 -0.540217 -0.241677 - 1.68468 -0.482966 -0.242197 - 1.68391 -0.474554 -0.24195 - 1.68783 -0.459303 -0.24309 - 1.69161 -0.444016 -0.244193 - 1.70085 -0.341411 -0.24675 - 1.69945 -0.333157 -0.246311 - 1.70083 -0.325467 -0.246709 - 1.68668 -0.275618 -0.242362 - 1.6902 -0.167415 -0.243191 - 1.69088 -0.159769 -0.243382 - 1.69577 -0.0294042 -0.244574 - 1.68834 0.00890723 -0.242267 - 1.71579 0.125668 -0.250253 - 1.70514 0.140392 -0.247028 - 1.70487 0.187031 -0.246852 - 1.69963 0.233225 -0.245183 - 1.66222 0.336121 -0.233754 - 1.54534 0.334117 -0.19872 - 1.61838 0.570486 -0.220121 - 1.60929 0.591715 -0.217353 - 1.17476 0.554081 -0.0871665 - 1.0669 0.561931 -0.0548149 - 0.97336 0.574354 -0.0267489 - 0.363699 0.240967 0.15532 - 0.343458 0.24705 0.1614 - 0.323122 0.247195 0.167497 - 0.313192 0.257106 0.170495 - 0.319085 0.271604 0.168758 - 0.322884 0.282341 0.167642 - 0.321877 0.294059 0.167968 - 0.319136 0.304485 0.168811 - 0.314514 0.305184 0.170198 - 0.318149 0.328298 0.169157 - 0.311873 0.335918 0.171054 - 0.313718 0.340954 0.170512 - 0.311983 0.348018 0.171047 - 0.244165 0.376961 0.191438 - 0.265936 0.437052 0.185037 - 0.0883685 0.440907 0.238276 - 0.111139 1.24678 0.233132 - 0.0968331 1.26797 0.237465 - 0.055428 1.30124 0.249947 - 0.02272 1.29396 0.259737 - -0.212228 1.26233 0.330104 - -0.219481 1.24256 0.332237 - -0.165374 0.80177 0.315097 - -0.0635902 0.294549 0.283525 - -0.0648208 0.294201 0.283893 - -0.070679 0.291418 0.285643 - -0.0767236 0.276843 0.287425 - -0.0945563 0.286045 0.29279 - -0.109119 0.309038 0.297204 - -0.134325 0.359806 0.304866 - -0.4213 1.02756 0.39229 - -0.495741 1.18996 0.414945 - -0.132181 0.274305 0.304045 - -0.13472 0.276268 0.30481 - -0.139318 0.273549 0.306183 - -0.146165 0.277468 0.308244 - -0.157686 0.294736 0.311733 - -0.869923 1.40345 0.527563 - -0.902966 1.40203 0.537466 - -0.977259 1.19771 0.559311 - -1.3084 -1.36185 0.634097 - -1.3053 -1.39468 0.633146 - -1.31442 -1.53262 0.63546 - -1.32661 -1.63056 0.638733 - -0.253266 -0.36238 0.335173 - -0.235527 -0.367166 0.330102 - -0.233436 -0.36746 0.329505 - -0.16493 -0.372335 0.309952 - -0.163366 -0.373131 0.309504 - -0.128184 -0.37384 0.299466 - -0.128336 -0.379138 0.299498 - -0.121625 -0.380675 0.29758 - -0.117463 -0.379039 0.296397 - -0.0973372 -0.376407 0.290661 - -0.0764204 -0.381235 0.284684 - -0.0395121 -0.390439 0.274135 - -0.0213572 -0.391529 0.268954 - 0.0230928 -0.391808 0.256273 - 0.0453587 -0.40144 0.249901 - 0.0472192 -0.403273 0.249366 - 0.0670529 -0.397797 0.24372 - 0.0728087 -0.401942 0.242069 - 0.0761797 -0.401369 0.241109 - 0.099871 -0.405675 0.234341 - 0.108129 -0.402599 0.231992 - 0.123174 -0.404606 0.227695 - 0.129368 -0.406878 0.225924 - 0.139406 -0.415147 0.223043 - 0.140255 -0.411709 0.222808 - 0.16081 -0.409476 0.216949 - 0.180505 -0.408734 0.211332 - 0.215901 -0.416836 0.201217 - 0.240415 -0.424732 0.194208 - 0.252203 -0.4246 0.190845 - 0.259026 -0.423848 0.1889 - 0.322185 -0.436259 0.170857 - 0.326891 -0.438848 0.169509 - 0.375664 -0.439112 0.155594 - 0.40464 -0.445755 0.147314 - 0.468671 -0.454669 0.12903 - 0.530036 -0.460066 0.111512 - 0.575277 -0.465837 0.098594 - 0.735828 -0.488538 0.0527455 - 0.737873 -0.485245 0.052169 - 0.981781 -0.547044 -0.0175405 - 1.27308 -0.66024 -0.100877 - 1.36707 -0.701736 -0.127777 - 1.64771 -0.765164 -0.207969 - 1.64134 -0.735655 -0.20609 - 1.73768 -0.590574 -0.233271 - 1.74001 -0.539637 -0.233829 - 1.75261 -0.424996 -0.237186 - 1.74485 -0.373594 -0.234865 - 1.76641 -0.320444 -0.240905 - 1.76869 -0.312646 -0.241539 - 1.77408 -0.264416 -0.242977 - 1.77509 -0.191418 -0.243114 - 1.77664 -0.175406 -0.243522 - 1.77542 -0.0787523 -0.242972 - 1.77914 0.0574957 -0.243749 - 1.77521 0.121543 -0.242495 - 1.77627 0.218542 -0.242598 - 1.77534 0.226547 -0.242316 - 1.77724 0.234928 -0.24284 - 1.77521 0.250941 -0.242228 - 1.75684 0.321352 -0.236841 - 1.75359 0.32891 -0.235897 - 1.42023 0.332551 -0.140791 - 1.148 0.323071 -0.0631482 - 1.0981 0.330179 -0.0488992 - 1.08912 0.370347 -0.0462534 - 1.59686 0.585025 -0.190654 - 1.36213 0.533164 -0.123798 - 1.32804 0.533415 -0.114072 - 1.17613 0.552835 -0.0706967 - 1.15402 0.554915 -0.0643857 - 1.08054 0.561179 -0.0434106 - 1.03712 0.567895 -0.031008 - 0.355093 0.241271 0.162878 - 0.354078 0.242827 0.163171 - 0.330219 0.243269 0.169978 - 0.326626 0.244952 0.171007 - 0.322622 0.255301 0.17217 - 0.331043 0.291672 0.169844 - 0.331633 0.300012 0.169693 - 0.317199 0.338194 0.17389 - 0.314218 0.343799 0.174752 - 0.292718 0.348762 0.180896 - 0.276712 0.369578 0.185505 - 0.257577 0.369105 0.190963 - 0.257389 0.413456 0.191109 - 0.254027 0.428412 0.192099 - 0.168591 0.324269 0.216255 - 0.149839 0.347482 0.221653 - 0.201346 0.565652 0.207413 - 0.142212 0.424866 0.22399 - 0.113955 0.419753 0.23204 - 0.130131 1.22688 0.229104 - 0.0969258 1.27295 0.238672 - 0.0814395 1.28398 0.243113 - 0.0167779 1.29899 0.261591 --0.00498545 1.29587 0.267793 - -0.0104905 1.29978 0.269372 - -0.0381314 1.30895 0.277276 - -0.0436233 1.30871 0.278842 - -0.104823 1.31437 0.296313 - -0.131934 1.30743 0.304032 - -0.143605 1.31203 0.307371 - -0.214308 1.23575 0.327383 - -0.0656925 0.31591 0.283073 - -0.0634414 0.295859 0.282389 - -0.068305 0.289279 0.283763 - -0.0743555 0.287396 0.285485 - -0.0779664 0.2862 0.286513 - -0.0932846 0.283729 0.290878 - -0.0944744 0.28325 0.291216 - -0.118212 0.333687 0.298093 - -0.133157 0.362975 0.302417 - -0.351519 0.809057 0.365638 - -0.154255 0.365274 0.30844 - -0.136419 0.318735 0.303256 - -0.182089 0.331559 0.316311 - -0.849651 1.39127 0.508954 - -0.877183 1.39525 0.516816 - -0.975407 1.14893 0.544325 - -0.985893 1.13096 0.547279 - -0.986871 1.10273 0.547499 - -1.32535 -1.68237 0.623235 - -0.281404 -0.385025 0.339861 - -0.260192 -0.360325 0.3341 - -0.250026 -0.359582 0.331316 - -0.251396 -0.364767 0.33168 - -0.214221 -0.374158 0.321474 - -0.211065 -0.376181 0.320605 - -0.194745 -0.369947 0.316146 - -0.180563 -0.370118 0.312259 - -0.169668 -0.368121 0.309278 - -0.170288 -0.373401 0.309437 - -0.123027 -0.377253 0.296478 - -0.108344 -0.381463 0.292446 - -0.0918263 -0.39178 0.287898 - -0.0536468 -0.381169 0.277458 - -0.0442872 -0.384768 0.274886 - -0.0407244 -0.395394 0.273888 - -0.0216991 -0.389536 0.268687 - -0.0153391 -0.393059 0.266936 - 0.00314971 -0.380915 0.261895 - 0.00953412 -0.387997 0.260131 - 0.0127997 -0.387994 0.259236 - 0.0210387 -0.390858 0.256973 - 0.02295 -0.399804 0.25643 - 0.0263145 -0.399679 0.255509 - 0.0294456 -0.39453 0.254661 - 0.0327655 -0.394348 0.253752 - 0.0522003 -0.404739 0.248405 - 0.0540084 -0.405542 0.247908 - 0.0593601 -0.406907 0.246438 - 0.133005 -0.406746 0.226258 - 0.17441 -0.413593 0.214898 - 0.183252 -0.415163 0.212472 - 0.209882 -0.422283 0.20516 - 0.261839 -0.428121 0.190911 - 0.321628 -0.43084 0.174521 - 0.456075 -0.449041 0.137642 - 0.698007 -0.479828 0.0712835 - 0.753824 -0.489994 0.0559673 - 0.79075 -0.49474 0.0458388 - 0.976525 -0.525882 -0.00513238 - 1.6541 -0.730616 -0.191228 - 1.6193 -0.638832 -0.181502 - 1.77436 -0.288231 -0.223265 - 1.79539 -0.20944 -0.228864 - 1.80436 -0.0473381 -0.230987 - 1.80881 -0.00677891 -0.232121 - 1.80883 0.00135429 -0.232109 - 1.82911 0.174582 -0.237307 - 1.83454 0.208438 -0.238725 - 1.83426 0.267054 -0.238528 - 1.64464 0.338151 -0.186418 - 1.11936 0.324934 -0.0425076 - 1.37239 0.528787 -0.111421 - 1.1946 0.553718 -0.0626521 - 1.17471 0.550759 -0.0572081 - 1.06712 0.558749 -0.0277076 - 0.98304 0.570957 -0.00464308 - 0.692901 0.429538 0.0745683 - 0.66399 0.435975 0.0825039 - 0.436862 0.295328 0.144451 - 0.357601 0.247214 0.16607 - 0.323724 0.237942 0.175334 - 0.313966 0.26377 0.178061 - 0.412748 0.365579 0.151204 - 0.352289 0.321648 0.16768 - 0.305716 0.327868 0.180455 - 0.29862 0.337246 0.182419 - 0.291744 0.362857 0.184356 - 0.28536 0.364267 0.186108 - 0.278609 0.368372 0.187967 - 0.272059 0.365951 0.189757 - 0.256857 0.371041 0.193933 - 0.252154 0.374342 0.195229 - 0.251085 0.383452 0.195541 - 0.249991 0.385375 0.195844 - 0.251885 0.395981 0.195347 - 0.25769 0.421656 0.19381 - 0.251173 0.431461 0.195616 - 0.249834 0.43341 0.195987 - 0.249005 0.440789 0.196229 - 0.149712 0.32687 0.223202 - 0.150175 0.352735 0.223128 - 0.16623 0.413927 0.218856 - 0.124907 0.418753 0.230189 - 0.110315 0.428889 0.234209 - 0.108068 0.427386 0.234821 - 0.0871321 0.459325 0.240625 - 0.0853576 0.46065 0.241114 - 0.134083 1.2154 0.229327 - 0.101582 1.26558 0.238337 - 0.0272255 1.2949 0.258773 - -0.0886311 1.31087 0.290554 - -0.0994919 1.30792 0.293524 - -0.1224 1.31465 0.299815 - -0.162753 1.32267 0.310889 - -0.18586 1.28779 0.317149 - -0.122295 0.586846 0.298277 - -0.0772198 0.373899 0.285484 - -0.0674865 0.288677 0.28264 - -0.0719469 0.290459 0.283866 - -0.469427 1.0925 0.394448 - -0.87488 1.40011 0.506189 - -0.926982 1.40102 0.520468 - -0.948876 1.36894 0.526401 - -0.970942 1.24526 0.532191 - -0.981241 1.13178 0.534778 - -1.30841 -1.3534 0.604907 - -1.29912 -1.41609 0.602333 - -1.30312 -1.43287 0.603351 - -1.33743 -1.64807 0.611934 - -1.32384 -1.67542 0.608302 - -0.22818 -0.363052 0.322719 - -0.226647 -0.364125 0.322313 - -0.204499 -0.363386 0.316487 - -0.151262 -0.367745 0.30247 - -0.146574 -0.374278 0.301223 - -0.130293 -0.380072 0.296927 - -0.094502 -0.386023 0.287497 - -0.0696165 -0.374957 0.280972 - -0.0664494 -0.375666 0.280137 - -0.0485409 -0.387218 0.275401 - -0.0404886 -0.389448 0.273278 - -0.0120854 -0.386294 0.265811 --0.00577224 -0.391638 0.264139 - 0.0157517 -0.393962 0.25847 - 0.0189698 -0.3889 0.257634 - 0.0309089 -0.397439 0.254475 - 0.0492297 -0.394973 0.249659 - 0.0525617 -0.394608 0.248783 - 0.0780778 -0.405012 0.242048 - 0.148824 -0.408686 0.223425 - 0.157376 -0.410817 0.22117 - 0.17372 -0.411742 0.216868 - 0.185648 -0.410843 0.213731 - 0.212716 -0.418677 0.206593 - 0.214481 -0.41776 0.20613 - 0.235818 -0.419647 0.200512 - 0.250295 -0.420294 0.196701 - 0.268475 -0.434652 0.191888 - 0.306031 -0.431781 0.182012 - 0.33167 -0.428312 0.175273 - 0.347303 -0.437224 0.171141 - 0.357096 -0.438045 0.168563 - 0.362637 -0.437206 0.167106 - 0.384364 -0.43636 0.161391 - 0.488707 -0.456473 0.133894 - 0.544915 -0.463048 0.119091 - 0.604294 -0.466235 0.10346 - 0.619833 -0.469825 0.0993637 - 0.708302 -0.485973 0.0760518 - 0.711956 -0.483929 0.0750945 - 0.800349 -0.494834 0.0518135 - 0.975135 -0.535072 0.00573954 - 1.63331 -0.719582 -0.167826 - 1.41517 -0.593043 -0.110166 - 1.72928 -0.645468 -0.192923 - 1.73563 -0.586824 -0.194473 - 1.74295 -0.503848 -0.196229 - 1.73905 -0.469205 -0.195131 - 1.74215 -0.362944 -0.195725 - 1.75789 -0.358043 -0.199859 - 1.83024 -0.321921 -0.218821 - 1.83481 -0.305808 -0.219989 - 1.81983 -0.0312942 -0.21548 - 1.82489 0.107888 -0.216524 - 1.83195 0.182708 -0.218226 - 1.52225 0.333378 -0.136425 - 1.20101 0.412755 -0.0517346 - 1.42906 0.520468 -0.111516 - 1.35583 0.534978 -0.0922181 - 1.1223 0.561511 -0.0307145 - 0.691518 0.436216 0.0823753 - 0.360363 0.263002 0.169153 - 0.324985 0.245174 0.178425 - 0.312037 0.334454 0.182016 - 0.309857 0.337897 0.182597 - 0.30283 0.341743 0.184454 - 0.293301 0.364418 0.187008 - 0.260109 0.365225 0.195744 - 0.253428 0.372419 0.197516 - 0.253885 0.391265 0.197435 - 0.252739 0.429507 0.197816 - 0.251504 0.436016 0.198154 - 0.192226 0.353315 0.213581 - 0.197877 0.518119 0.212434 - 0.19359 0.527195 0.213581 - 0.128693 0.425927 0.230448 - 0.116646 1.25528 0.235333 - -0.0614984 1.30983 0.28232 - -0.168574 1.31692 0.310509 - -0.211258 1.23677 0.321575 - -0.149583 0.746744 0.304333 - -0.0669006 0.28903 0.281631 - -0.0777737 0.289863 0.284493 - -0.0775212 0.284699 0.284416 - -0.0784057 0.279144 0.284637 - -0.0823137 0.283062 0.285674 - -0.500332 1.22896 0.397621 - -0.505514 1.22664 0.39898 - -0.124861 0.280907 0.296865 - -0.127796 0.274869 0.297624 - -0.890604 1.39369 0.500653 - -0.905675 1.4037 0.504639 - -0.941442 1.40495 0.514053 - -0.949335 1.3906 0.5161 - -1.31925 -1.36045 0.592925 - -1.31239 -1.43868 0.591037 - -1.30619 -1.48291 0.589384 - -1.30643 -1.49622 0.589416 - -1.32523 -1.73291 0.593666 - -0.254602 -0.362778 0.326718 - -0.218898 -0.367705 0.317712 - -0.208052 -0.364114 0.314986 - -0.206975 -0.369484 0.314704 - -0.184453 -0.370127 0.309027 - -0.178161 -0.373572 0.307435 - -0.153346 -0.374856 0.301179 - -0.137627 -0.373103 0.297222 - -0.125584 -0.380068 0.294173 - -0.113653 -0.382266 0.291162 - -0.0900437 -0.386445 0.285205 - -0.0714081 -0.372641 0.280537 - -0.0678802 -0.379579 0.279634 - -0.0474787 -0.38748 0.274477 - -0.0450315 -0.393922 0.273847 - -0.0264569 -0.394204 0.269166 --0.00784399 -0.390562 0.264484 - 0.0103465 -0.388999 0.259903 - 0.0349534 -0.38715 0.253707 - 0.0458398 -0.398295 0.250941 - 0.0665628 -0.399776 0.245716 - 0.0754875 -0.401369 0.243464 - 0.0819169 -0.398164 0.24185 - 0.0989491 -0.403724 0.237547 - 0.104293 -0.403462 0.236201 - 0.121263 -0.41235 0.231907 - 0.133693 -0.403329 0.228794 - 0.162491 -0.419514 0.221504 - 0.165693 -0.41183 0.220713 - 0.177417 -0.420995 0.21774 - 0.23283 -0.418031 0.203783 - 0.270367 -0.428917 0.194302 - 0.405952 -0.44103 0.160113 - 0.551024 -0.455142 0.123529 - 0.605038 -0.470126 0.109888 - 0.650176 -0.474515 0.0985053 - 0.662882 -0.475078 0.0953025 - 0.903615 -0.525815 0.0345389 - 0.915118 -0.527199 0.0316375 - 1.01014 -0.541691 0.00766426 - 1.628 -0.741487 -0.148433 - 1.66084 -0.721224 -0.156668 - 1.57082 -0.600486 -0.133735 - 1.73127 -0.575335 -0.174112 - 1.73808 -0.393707 -0.175455 - 1.73974 -0.385928 -0.175855 - 1.74136 -0.378141 -0.176248 - 1.9035 -0.351621 -0.217049 - 1.91357 -0.344654 -0.219572 - 1.91501 -0.336086 -0.219918 - 1.90796 -0.264908 -0.217995 - 1.90533 -0.247192 -0.217295 - 1.90519 -0.195349 -0.217154 - 1.91373 -0.153059 -0.219217 - 1.91555 -0.0242935 -0.219409 - 1.91563 -0.01572 -0.219414 - 1.90668 0.0355578 -0.217052 - 1.91383 0.321143 -0.218264 - 1.89811 0.327218 -0.21429 - 1.45676 0.331803 -0.103071 - 1.25801 0.547176 -0.0525461 - 1.04612 0.568836 0.0008876 - 0.977464 0.570876 0.0181926 - 0.888505 0.53956 0.0405434 - 0.745543 0.526657 0.0765401 - 0.315487 0.259748 0.184353 - 0.32591 0.306513 0.181823 - 0.272625 0.365951 0.195373 - 0.256242 0.369392 0.199508 - 0.250436 0.385375 0.201004 - 0.260422 0.413186 0.198545 - 0.257169 0.419946 0.199378 - 0.252957 0.429507 0.20046 - 0.247074 0.436425 0.201956 - 0.152143 0.321322 0.225639 - 0.150813 0.354587 0.226043 - 0.14634 0.445487 0.227358 - 0.136206 0.431958 0.229883 - 0.12704 0.434684 0.232198 - 0.112487 0.439587 0.235875 - 0.104823 0.440379 0.237808 - 0.102959 0.4408 0.238279 - 0.0893365 0.501452 0.241836 - 0.101778 0.694664 0.2391 - 0.132196 0.956834 0.231976 - 0.107523 1.27812 0.238856 - 0.0755021 1.28928 0.246947 - 0.0209331 1.29396 0.260707 - 0.00448158 1.29998 0.264865 - -0.0397001 1.30395 0.276006 - -0.0901432 1.31187 0.288732 - -0.106787 1.31039 0.292923 - -0.113075 1.31781 0.294523 - -0.163937 1.31772 0.307339 - -0.0604119 0.292005 0.279137 - -0.0772163 0.29026 0.283368 - -0.0848246 0.284529 0.285273 - -0.0886306 0.279954 0.286223 - -0.250204 0.656012 0.327711 - -0.120298 0.275831 0.294194 - -0.125972 0.278507 0.295629 - -0.822997 1.37406 0.473522 - -0.896185 1.39785 0.492013 - -0.920449 1.39537 0.498122 - -0.948723 1.39819 0.505252 - -0.981184 1.20669 0.513037 - -0.984557 1.10881 0.513685 - -0.990583 1.09617 0.515177 - -1.35826 -1.39638 0.587587 - -1.29683 -1.46816 0.57264 - -0.279761 -0.381613 0.329822 - -0.238638 -0.361957 0.319955 - -0.234451 -0.362528 0.318945 - -0.210052 -0.365815 0.313059 - -0.205428 -0.365207 0.311946 - -0.201826 -0.366265 0.311076 - -0.139527 -0.37588 0.296046 - -0.136333 -0.377205 0.295274 - -0.124071 -0.378795 0.292316 - -0.120853 -0.379981 0.291538 - -0.111548 -0.37902 0.289298 - -0.109217 -0.382951 0.288729 - -0.107591 -0.383481 0.288336 - -0.0689007 -0.381536 0.279018 - -0.049686 -0.387218 0.274377 - -0.0229455 -0.386547 0.267935 - -0.019665 -0.386825 0.267144 - -0.0180239 -0.386953 0.266748 --0.00495441 -0.38971 0.263594 - 3.121e-05 -0.388873 0.262394 - 0.00829669 -0.384997 0.260411 - 0.0314813 -0.390354 0.254814 - 0.0401376 -0.394756 0.252719 - 0.0434856 -0.394467 0.251913 - 0.0636856 -0.406214 0.247022 - 0.0654084 -0.405968 0.246607 - 0.0718314 -0.401942 0.245068 - 0.0903709 -0.406608 0.240592 - 0.1129 -0.409449 0.235158 - 0.12156 -0.407034 0.233076 - 0.134478 -0.412475 0.229952 - 0.142373 -0.413019 0.228049 - 0.155241 -0.410536 0.224954 - 0.165325 -0.410898 0.222523 - 0.180874 -0.414099 0.21877 - 0.196756 -0.416697 0.214938 - 0.237587 -0.42227 0.205089 - 0.256288 -0.421541 0.200585 - 0.259588 -0.422994 0.199787 - 0.309716 -0.43207 0.18769 - 0.328883 -0.431194 0.183074 - 0.558314 -0.464562 0.127726 - 0.607367 -0.466839 0.115903 - 0.630456 -0.471825 0.11033 - 0.852449 -0.520073 0.0567434 - 0.857992 -0.518328 0.0554117 - 1.57479 -0.775182 -0.117822 - 1.58421 -0.771159 -0.120084 - 1.42192 -0.600522 -0.0806288 - 1.42696 -0.587821 -0.0818187 - 1.72964 -0.599162 -0.154768 - 1.7341 -0.549388 -0.155742 - 1.73964 -0.534175 -0.157044 - 1.74468 -0.443597 -0.158072 - 1.76778 -0.350156 -0.163445 - 2.0038 -0.141929 -0.219885 - 2.00351 -0.114957 -0.219759 - 1.99859 -0.0967727 -0.218537 - 2.00759 0.019426 -0.220465 - 2.02373 0.137282 -0.224112 - 2.02667 0.16478 -0.224763 - 1.85421 0.344453 -0.18284 - 1.49753 0.333381 -0.0969258 - 1.25167 0.325357 -0.0377049 - 1.44185 0.508304 -0.0831515 - 1.36066 0.527485 -0.0635505 - 1.20336 0.547545 -0.0256073 - 1.00779 0.563983 0.021546 - 0.965297 0.568213 0.031793 - 0.824706 0.504315 0.0655353 - 0.718685 0.443042 0.0909538 - 0.810888 0.561714 0.0689827 - 0.321378 0.246172 0.186276 - 0.331594 0.30358 0.183932 - 0.325083 0.310724 0.185516 - 0.323063 0.31144 0.186004 - 0.32174 0.312843 0.186326 - 0.253574 0.361706 0.20285 - 0.251747 0.376263 0.20332 - 0.261907 0.427643 0.200978 - 0.256445 0.430998 0.202301 - 0.226471 0.415061 0.20949 - 0.148758 0.325039 0.228029 - 0.14638 0.327191 0.228606 - 0.142471 0.446693 0.229794 - 0.125317 0.436169 0.233905 - 0.104784 0.432147 0.238844 - 0.0989282 0.614244 0.24063 - 0.140679 1.23173 0.231841 - 0.136061 1.23827 0.232967 - 0.102544 1.28752 0.241144 - 0.0371205 1.30071 0.256934 - -0.113378 1.31283 0.29322 - -0.176011 1.31609 0.308317 - -0.209497 1.18663 0.316119 - -0.0917428 0.452031 0.286236 - -0.07151 0.296375 0.281041 - -0.0858547 0.289689 0.284484 - -0.513161 1.22155 0.389356 - -0.122769 0.279425 0.293357 - -0.130099 0.273356 0.29511 - -0.140811 0.276468 0.297698 - -0.863002 1.39463 0.474002 - -0.960247 1.31108 0.49726 - -0.970276 1.26631 0.499584 - -0.973499 1.19372 0.500212 - -0.974706 1.17425 0.500462 - -0.981428 1.1616 0.502056 - -0.98153 1.11181 0.501978 - -0.99155 1.08441 0.504336 - -1.30008 -1.45493 0.558943 - -1.31872 -1.59708 0.562936 - -1.31762 -1.62423 0.562627 - -0.273309 -0.374997 0.325148 - -0.258665 -0.358795 0.321815 - -0.24445 -0.362151 0.318541 - -0.240079 -0.35921 0.317542 - -0.216199 -0.367213 0.312037 - -0.206333 -0.368742 0.309766 - -0.185159 -0.37188 0.304892 - -0.166087 -0.369534 0.300513 - -0.164091 -0.369415 0.300055 - -0.160527 -0.370048 0.299234 - -0.154985 -0.370476 0.29796 - -0.143405 -0.378904 0.29528 - -0.139083 -0.377474 0.29429 - -0.134256 -0.379434 0.293176 - -0.13145 -0.38695 0.292516 - -0.123491 -0.375036 0.290711 - -0.0680154 -0.391047 0.277927 - -0.0613444 -0.374052 0.276428 - -0.0559858 -0.381169 0.275182 - -0.0477191 -0.381549 0.273281 - -0.0170034 -0.389069 0.266205 --0.00719564 -0.392638 0.263943 - 0.0283105 -0.401522 0.255764 - 0.0344972 -0.391141 0.254363 - 0.0378229 -0.3909 0.253599 - 0.0464082 -0.393153 0.251621 - 0.055562 -0.399178 0.249505 - 0.0867062 -0.39814 0.242348 - 0.0916795 -0.405263 0.24119 - 0.0942137 -0.408802 0.240601 - 0.100068 -0.410551 0.239251 - 0.142179 -0.406731 0.22958 - 0.184393 -0.412546 0.219864 - 0.213467 -0.419571 0.213167 - 0.230512 -0.426298 0.209235 - 0.23584 -0.418773 0.208026 - 0.284716 -0.430481 0.196768 - 0.292701 -0.434647 0.194924 - 0.318985 -0.432829 0.188886 - 0.34073 -0.434734 0.183884 - 0.364114 -0.441104 0.178496 - 0.401381 -0.442357 0.169927 - 0.432086 -0.452606 0.162848 - 0.515589 -0.463075 0.143633 - 0.525134 -0.459512 0.141446 - 0.558204 -0.459567 0.133845 - 0.794805 -0.493175 0.0793911 - 0.950589 -0.534527 0.0434981 - 0.962255 -0.535591 0.0408144 - 0.991388 -0.534934 0.0341193 - 1.613 -0.774731 -0.109256 - 1.63307 -0.77556 -0.11387 - 1.64404 -0.763059 -0.116367 - 1.56874 -0.59699 -0.0987173 - 1.70914 -0.616274 -0.131028 - 1.75121 -0.469205 -0.140398 - 1.75609 -0.453834 -0.141487 - 2.10822 -0.368463 -0.222251 - 2.11032 -0.349495 -0.222695 - 2.10725 -0.101829 -0.221481 - 2.1046 -0.0265806 -0.220717 - 2.10793 0.0579495 -0.22131 - 2.11534 0.200128 -0.22272 - 2.10825 0.275542 -0.220936 - 2.10577 0.323048 -0.220268 - 2.05236 0.324176 -0.207991 - 1.94662 0.325179 -0.183682 - 1.74811 0.340023 -0.138023 - 1.09137 0.340249 0.0129328 - 1.44311 0.507652 -0.0675739 - 1.3877 0.52984 -0.0547913 - 1.35404 0.530669 -0.0470513 - 1.18698 0.551589 -0.00861001 - 1.1637 0.553221 -0.00325611 - 1.07474 0.557839 0.0172017 - 1.04187 0.564134 0.0247706 - 0.998037 0.563115 0.0348443 - 0.813979 0.578764 0.0771835 - 0.320941 0.245563 0.189828 - 0.315003 0.245261 0.191193 - 0.311338 0.262551 0.192071 - 0.309095 0.265243 0.192592 - 0.331846 0.322619 0.18748 - 0.331167 0.32476 0.18764 - 0.306251 0.369829 0.19346 - 0.261304 0.366042 0.203784 - 0.2523 0.36636 0.205854 - 0.25074 0.367443 0.206215 - 0.261223 0.447922 0.20397 - 0.252111 0.454324 0.206078 - 0.168996 0.325163 0.224917 - 0.155542 0.321848 0.228003 - 0.148059 0.327493 0.229735 - 0.151699 0.361707 0.228968 - 0.156675 0.487169 0.228082 - 0.119646 0.445928 0.236509 - 0.114461 0.441067 0.237691 - 0.107589 0.445804 0.23928 - 0.106324 0.449167 0.239578 - 0.106066 0.457415 0.239654 - 0.0930478 0.475353 0.242683 - 0.102461 1.28951 0.24219 - 0.0802391 1.28598 0.247291 - 0.042312 1.30258 0.256043 --0.00198523 1.29994 0.266219 - -0.0408621 1.30395 0.275164 - -0.187966 1.31338 0.308996 - -0.0607146 0.282963 0.277632 - -0.086527 0.289689 0.283579 - -0.0938858 0.287009 0.285265 - -0.128091 0.362448 0.293282 - -0.860205 1.39938 0.463692 - -0.867204 1.39715 0.465296 - -0.874732 1.39572 0.467023 - -0.963547 1.27664 0.487194 - -1.30065 -1.46447 0.544627 - -1.31744 -1.54977 0.548125 - -1.31717 -1.59099 0.547984 - -1.32767 -1.69128 0.550076 - -0.267821 -0.366294 0.320853 - -0.238579 -0.362249 0.314462 - -0.201055 -0.369013 0.306237 - -0.164606 -0.372896 0.298253 - -0.149065 -0.372443 0.294852 - -0.128864 -0.382884 0.29041 - -0.116831 -0.379812 0.287783 - -0.0861747 -0.370449 0.281094 - -0.0485721 -0.383526 0.272838 - -0.0424194 -0.387466 0.271484 - -0.0224599 -0.388683 0.267113 - -0.0162104 -0.39517 0.265732 - 0.0432333 -0.399448 0.252715 - 0.0571892 -0.400952 0.249658 - 0.094904 -0.404509 0.241397 - 0.108352 -0.407449 0.238448 - 0.113056 -0.404147 0.237426 - 0.123083 -0.400255 0.235239 - 0.140108 -0.41266 0.231488 - 0.149638 -0.406173 0.229416 - 0.191252 -0.413804 0.220294 - 0.203471 -0.412374 0.217622 - 0.223331 -0.416669 0.213268 - 0.306069 -0.433929 0.195126 - 0.334318 -0.437558 0.188937 - 0.336181 -0.4361 0.188532 - 0.339234 -0.436214 0.187864 - 0.38659 -0.444242 0.177484 - 0.396725 -0.440396 0.175274 - 0.414265 -0.448369 0.171419 - 0.422091 -0.449097 0.169705 - 0.435824 -0.448087 0.166702 - 0.449811 -0.450805 0.163635 - 0.481565 -0.454609 0.156679 - 0.552883 -0.462548 0.141056 - 0.557112 -0.46202 0.140131 - 0.604321 -0.467085 0.12979 - 0.672492 -0.475 0.114855 - 0.715771 -0.482819 0.105368 - 1.05101 -0.542651 0.0318824 - 1.51027 -0.765004 -0.0690768 - 1.55391 -0.597956 -0.0782828 - 1.73011 -0.579638 -0.116805 - 1.73725 -0.522722 -0.118252 - 1.76545 -0.430333 -0.124233 - 1.74401 -0.368115 -0.119415 - 2.19389 -0.392729 -0.217914 - 2.2086 -0.225089 -0.220792 - 2.20239 -0.184935 -0.21935 - 2.19902 -0.164967 -0.218571 - 2.20693 -0.0671073 -0.220103 - 2.20157 -0.0473436 -0.218889 - 2.20304 -0.00816815 -0.21913 - 2.23022 0.10093 -0.224855 - 2.22875 0.130683 -0.224472 - 2.22304 0.219887 -0.22304 - 2.22638 0.280364 -0.223647 - 1.93435 0.322434 -0.159655 - 1.53487 0.333169 -0.0722119 - 1.46618 0.331803 -0.0571816 - 1.3753 0.330376 -0.0372959 - 1.1451 0.323401 0.013065 - 1.08692 0.364697 0.0258829 - 1.26376 0.539621 -0.0124582 - 1.15302 0.553256 0.0118037 - 1.11161 0.551413 0.0208607 - 1.02682 0.560693 0.0394344 - 1.01773 0.567354 0.0414386 - 0.974837 0.565908 0.0508217 - 0.742771 0.531518 0.101536 - 0.381929 0.277711 0.179982 - 0.320963 0.247567 0.193262 - 0.321594 0.25484 0.193139 - 0.335648 0.323258 0.190203 - 0.334268 0.324714 0.190508 - 0.254434 0.362528 0.208056 - 0.262121 0.399395 0.20645 - 0.264585 0.440205 0.205994 - 0.205619 0.37893 0.218773 - 0.159868 0.32414 0.228672 - 0.109808 0.652936 0.240301 - 0.118297 0.728502 0.238598 - 0.143279 0.950163 0.233584 - -0.0472536 1.30971 0.276016 - -0.132093 1.31503 0.294593 - -0.15474 1.31428 0.299548 - -0.073041 0.297337 0.279587 - -0.076214 0.284915 0.280256 - -0.0774278 0.284531 0.280521 - -0.0862465 0.286848 0.282455 - -0.137697 0.273429 0.293687 - -0.203948 0.362423 0.308367 - -0.852567 1.3965 0.452427 - -0.928818 1.40864 0.469138 - -0.957215 1.34765 0.475227 - -0.966805 1.25458 0.477136 - -0.973947 1.20865 0.478604 - -0.983598 1.12735 0.48055 - -0.988648 1.08453 0.481568 - -0.994291 1.06244 0.482757 - -1.2951 -1.41692 0.529384 - -1.30355 -1.45126 0.531071 - -1.30383 -1.49023 0.531051 - -0.256112 -0.362362 0.31543 - -0.240668 -0.363888 0.312214 - -0.12427 -0.373156 0.287985 - -0.0709205 -0.382514 0.276869 - -0.0692858 -0.382864 0.276528 - -0.0534911 -0.389909 0.273228 - -0.0438729 -0.394403 0.271219 - -0.0282059 -0.391217 0.267967 - 0.00040542 -0.386913 0.262024 - 0.0086706 -0.385999 0.260307 - 0.0119508 -0.383982 0.259629 - 0.0136173 -0.385962 0.259278 - 0.0205436 -0.396805 0.257815 - 0.0408595 -0.395612 0.253592 - 0.0446878 -0.400286 0.252786 - 0.0531177 -0.398388 0.251037 - 0.074604 -0.402355 0.246559 - 0.103851 -0.397207 0.240487 - 0.118897 -0.412846 0.237325 - 0.133483 -0.416855 0.234283 - 0.137559 -0.405054 0.233459 - 0.141015 -0.403887 0.232743 - 0.181705 -0.421316 0.224244 - 0.214 -0.420466 0.217528 - 0.23974 -0.421243 0.212173 - 0.279859 -0.43041 0.203809 - 0.309858 -0.435045 0.19756 - 0.323742 -0.434652 0.194673 - 0.388259 -0.441799 0.181239 - 0.581819 -0.465215 0.140931 - 0.58534 -0.463892 0.140201 - 0.61345 -0.469258 0.134343 - 0.644283 -0.475532 0.127917 - 0.696142 -0.482067 0.117117 - 0.710791 -0.48318 0.114068 - 0.736581 -0.486891 0.108696 - 0.785844 -0.495427 0.098432 - 0.899518 -0.519373 0.074739 - 0.935536 -0.529465 0.0672266 - 0.970075 -0.537993 0.0600251 - 1.00773 -0.536111 0.0521977 - 1.58196 -0.773881 -0.0677291 - 1.64031 -0.767028 -0.0798511 - 1.49699 -0.590031 -0.049678 - 1.74971 -0.475193 -0.102009 - 2.32385 -0.351693 -0.221177 - 2.32533 -0.341371 -0.221465 - 2.33015 -0.289422 -0.222361 - 2.329 -0.226486 -0.221993 - 2.31887 -0.183998 -0.219799 - 2.32577 -0.0292634 -0.220918 - 2.34076 0.136999 -0.223697 - 1.82208 0.344677 -0.115389 - 1.61735 0.335533 -0.0728231 - 1.43317 0.330337 -0.0345246 - 1.09832 0.33055 0.0351253 - 1.34152 0.53051 -0.0150529 - 1.28878 0.53598 -0.00407034 - 1.24382 0.549594 0.0053083 - 1.10862 0.555003 0.0334411 - 1.04226 0.562254 0.0472583 - 1.00559 0.553766 0.0548681 - 0.993976 0.558746 0.0572941 - 0.680002 0.458843 0.122396 - 0.318497 0.273083 0.19721 - 0.339778 0.310341 0.192859 - 0.323394 0.330448 0.196308 - 0.310758 0.349237 0.198975 - 0.305859 0.382133 0.200061 - 0.264327 0.356638 0.208648 - 0.263377 0.358583 0.208849 - 0.269823 0.435892 0.207666 - 0.262715 0.436766 0.209147 - 0.257496 0.436421 0.210232 - 0.25813 0.455627 0.210139 - 0.229468 0.420348 0.216028 - 0.200109 0.368331 0.222029 - 0.167536 0.322483 0.22871 - 0.215314 0.641199 0.219424 - 0.131908 0.454924 0.236391 - 0.117321 0.454668 0.239425 - 0.103513 0.467074 0.242322 - 0.149757 0.939046 0.233668 - 0.148041 1.25399 0.234668 - 0.106948 1.28211 0.243273 - 0.0857399 1.29563 0.247712 - 0.0468784 1.29442 0.255792 - 0.0413991 1.29658 0.256937 - 0.0303204 1.29682 0.259241 - 0.00260912 1.29898 0.26501 --0.00296647 1.30194 0.266176 - -0.0421199 1.30695 0.27433 - -0.0929342 1.31187 0.284909 - -0.104139 1.31091 0.287238 - -0.144667 1.31868 0.295683 - -0.0644882 0.298796 0.276923 - -0.0717924 0.290601 0.278425 - -0.0794133 0.29352 0.280016 - -0.0806665 0.293124 0.280276 - -0.0925203 0.291201 0.282738 - -0.0960102 0.293106 0.283468 - -0.109835 0.323063 0.286404 - -0.138454 0.273429 0.292256 - -0.138671 0.271022 0.292296 - -0.152097 0.283937 0.295115 - -0.871601 1.39631 0.447044 - -0.94112 1.39691 0.461505 - -0.94708 1.39267 0.462736 - -0.978166 1.14808 0.468702 - -0.985332 1.13625 0.470168 - -0.989227 1.11107 0.470927 - -1.3007 -1.32381 0.516447 - -1.30385 -1.37412 0.516965 - -1.33123 -1.65767 0.521782 - -0.25788 -0.366755 0.312882 - -0.256307 -0.367934 0.31257 - -0.247005 -0.364912 0.310743 - -0.235903 -0.369102 0.308546 - -0.221581 -0.364339 0.305734 - -0.209604 -0.366063 0.30337 - -0.157706 -0.367012 0.29314 - -0.144569 -0.376131 0.290532 - -0.125365 -0.379392 0.286741 - -0.11885 -0.381706 0.285452 - -0.115971 -0.378472 0.284891 - -0.0974964 -0.375931 0.281256 - -0.0792316 -0.378708 0.277651 - -0.0154688 -0.395278 0.265051 - 0.00824886 -0.390999 0.260385 - 0.0479646 -0.401937 0.252536 - 0.125288 -0.402617 0.237296 - 0.135414 -0.410957 0.235283 - 0.157673 -0.412693 0.230893 - 0.159095 -0.411086 0.230616 - 0.192003 -0.425483 0.224101 - 0.263041 -0.423573 0.210105 - 0.293555 -0.430887 0.204077 - 0.336082 -0.439149 0.195679 - 0.364586 -0.444237 0.190051 - 0.387393 -0.444242 0.185556 - 0.414522 -0.447635 0.180203 - 0.441867 -0.44162 0.174826 - 0.476033 -0.456051 0.168063 - 0.493646 -0.452961 0.164598 - 0.549416 -0.462405 0.153588 - 0.887184 -0.521762 0.0869012 - 1.56569 -0.773009 -0.0473285 - 1.55428 -0.595834 -0.0447193 - 1.7156 -0.614942 -0.07655 - 1.73844 -0.537851 -0.080895 - 1.74299 -0.522439 -0.0817593 - 1.74912 -0.375862 -0.0826685 - 2.43339 -0.422932 -0.217618 - 2.44636 -0.358504 -0.220042 - 2.4468 -0.23752 -0.219883 - 2.44915 -0.172165 -0.220213 - 2.44431 -0.139191 -0.219192 - 2.44426 0.00180403 -0.218895 - 2.44416 0.0234719 -0.218831 - 2.43701 0.0450107 -0.217378 - 2.52808 0.170213 -0.235071 - 2.49426 0.268179 -0.228204 - 1.8453 0.339986 -0.100164 - 1.09926 0.330265 0.0468437 - 1.07303 0.358734 0.052071 - 1.36266 0.531028 -0.00465724 - 1.11843 0.558989 0.0435305 - 1.08931 0.562386 0.0492762 - 0.707959 0.442011 0.124187 - 0.646227 0.443399 0.136356 - 0.320434 0.242348 0.200152 - 0.314296 0.259838 0.201397 - 0.344874 0.309387 0.195472 - 0.345725 0.3129 0.195311 - 0.310311 0.348487 0.202363 - 0.303495 0.362343 0.203735 - 0.273466 0.356009 0.20964 - 0.253074 0.36362 0.213674 - 0.255931 0.371322 0.213127 - 0.254339 0.372419 0.213443 - 0.256012 0.378502 0.213125 - 0.26594 0.408935 0.211231 - 0.254334 0.413959 0.213528 - 0.163282 0.335667 0.231313 - 0.199136 0.528342 0.22464 - 0.195599 0.532843 0.225346 - 0.302516 0.924643 0.205074 - 0.298555 0.925942 0.205857 - 0.225604 0.73749 0.21985 - 0.157031 0.521416 0.232924 - 0.146975 0.502504 0.234867 - 0.118741 0.461468 0.240347 - 0.111039 0.464338 0.241871 - 0.10635 0.492974 0.242854 - 0.138671 1.2701 0.238068 - -0.0538758 1.30645 0.276089 - -0.0595199 1.30715 0.277202 - -0.121271 1.3053 0.289368 - -0.161734 1.31155 0.297355 - -0.0893971 0.28831 0.281014 - -0.095083 0.292629 0.282143 - -0.444752 1.03562 0.352569 - -0.138032 0.274082 0.290569 - -0.140455 0.26469 0.291028 - -0.152876 0.283937 0.293515 - -0.864783 1.39516 0.43608 - -0.886857 1.40327 0.440447 - -1.32327 -1.34354 0.506467 - -1.30139 -1.36839 0.502342 - -1.30324 -1.43149 0.502558 - -1.30686 -1.53982 0.503011 - -1.32186 -1.59919 0.505684 - -0.237288 -0.36636 0.306175 - -0.200105 -0.366482 0.299249 - -0.184888 -0.372721 0.296402 - -0.165373 -0.373667 0.292765 - -0.131694 -0.3698 0.2865 - -0.125391 -0.377509 0.28531 - -0.10686 -0.38165 0.28185 - -0.103303 -0.381692 0.281188 - -0.093542 -0.378271 0.279376 - -0.0514549 -0.403561 0.271486 - -0.0414256 -0.393862 0.269637 - -0.0180167 -0.401157 0.265262 --0.00226031 -0.391872 0.262346 - 0.00618552 -0.381997 0.260793 - 0.0111638 -0.388982 0.259852 - 0.0249398 -0.398607 0.257266 - 0.0441728 -0.402277 0.253676 - 0.0541653 -0.398185 0.251823 - 0.0588995 -0.394556 0.250949 - 0.137909 -0.413243 0.236194 - 0.192765 -0.417449 0.225968 - 0.219849 -0.418569 0.220921 - 0.221643 -0.417623 0.220589 - 0.237565 -0.421396 0.217615 - 0.244761 -0.417248 0.216283 - 0.258979 -0.424968 0.213619 - 0.271709 -0.425205 0.211248 - 0.292605 -0.42923 0.207347 - 0.297212 -0.432092 0.206483 - 0.306983 -0.426374 0.204675 - 0.340675 -0.437004 0.198378 - 0.345575 -0.439459 0.19746 - 0.35428 -0.438818 0.19584 - 0.546312 -0.459194 0.16003 - 0.741215 -0.488535 0.123666 - 0.743305 -0.485273 0.123284 - 0.776102 -0.492491 0.11716 - 0.786547 -0.494368 0.115211 - 0.799984 -0.493175 0.11271 - 0.937669 -0.528977 0.0869917 - 0.955968 -0.528386 0.0835845 - 1.56947 -0.782137 -0.0312051 - 1.67402 -0.735655 -0.0505846 - 1.6495 -0.606555 -0.0457553 - 1.68078 -0.609716 -0.0515872 - 1.7401 -0.545838 -0.062507 - 2.5881 -0.308744 -0.219977 - 2.58257 -0.158288 -0.21864 - 2.58222 -0.078108 -0.218412 - 2.58253 -0.0666805 -0.218447 - 2.57944 -0.00951375 -0.217755 - 2.59259 0.0592834 -0.220064 - 2.65488 0.084227 -0.231615 - 2.72577 0.11064 -0.244767 - 2.72571 0.134812 -0.244706 - 2.72326 0.255832 -0.244004 - 2.72659 0.292702 -0.244549 - 2.69611 0.374175 -0.238706 - 1.91965 0.326886 -0.0941747 - 1.7596 0.339649 -0.0643385 - 1.50724 0.332317 -0.017347 - 1.41377 0.331267 6.187e-05 - 1.29437 0.327303 0.0222922 - 1.23537 0.323897 0.0332754 - 1.09906 0.319167 0.0586549 - 1.3379 0.527242 0.0145914 - 1.22408 0.545411 0.0358296 - 1.16667 0.550682 0.0465336 - 1.09256 0.557122 0.0603511 - 1.04217 0.560374 0.0697423 - 0.92938 0.564132 0.0907595 - 0.31997 0.252971 0.203638 - 0.313733 0.263844 0.204822 - 0.30997 0.265243 0.205526 - 0.313595 0.273195 0.204867 - 0.336051 0.309096 0.200757 - 0.331532 0.326901 0.201635 - 0.322021 0.343237 0.20344 - 0.3023 0.354357 0.207135 - 0.297716 0.358247 0.207997 - 0.296488 0.36314 0.208236 - 0.259164 0.369105 0.2152 - 0.266163 0.405268 0.21397 - 0.239241 0.429766 0.219035 - 0.216016 0.394792 0.223289 - 0.157827 0.320528 0.233977 - 0.147097 0.33855 0.236012 - 0.197933 0.562723 0.226999 - 0.112984 0.504801 0.242704 - 0.158693 1.25469 0.235716 - 0.0405412 1.29358 0.257803 - 0.00164379 1.30398 0.265069 - -0.026294 1.30253 0.27027 - -0.208079 1.30864 0.304142 - -0.167642 0.915727 0.295811 - -0.06076 0.307182 0.274665 - -0.0689973 0.290686 0.276165 - -0.0725739 0.299024 0.276849 - -0.0863096 0.289588 0.279388 - -0.104704 0.318034 0.282872 - -0.136379 0.396748 0.288932 - -0.179433 0.508474 0.297179 - -0.406503 0.934248 0.34034 - -0.126327 0.276137 0.286814 - -0.142538 0.275394 0.289832 - -0.211091 0.373679 0.302801 - -0.914743 1.40284 0.43596 - -0.958876 1.36435 0.444102 - -0.983146 1.12805 0.448142 - -1.31182 -1.50204 0.489587 - -1.30861 -1.51161 0.489006 - -1.33859 -1.70426 0.493872 - -1.33432 -1.71412 0.493103 - -0.256261 -0.361929 0.306835 - -0.23976 -0.365269 0.303935 - -0.21601 -0.363129 0.299776 - -0.179539 -0.364699 0.293378 - -0.174379 -0.366255 0.29247 - -0.139334 -0.373489 0.286311 - -0.122177 -0.376786 0.283297 - -0.104734 -0.378323 0.280235 - -0.103107 -0.378814 0.279949 - -0.0783551 -0.377144 0.275613 - -0.0196038 -0.392062 0.265282 --0.00918791 -0.385644 0.263468 - 0.0158652 -0.393899 0.259059 - 0.0226352 -0.393684 0.257873 - 0.0260185 -0.393532 0.25728 - 0.0484806 -0.396783 0.253335 - 0.0693423 -0.397004 0.249677 - 0.0732413 -0.399396 0.248989 - 0.0837055 -0.398483 0.247156 - 0.134172 -0.414384 0.238275 - 0.147542 -0.413087 0.235934 - 0.175896 -0.412849 0.230963 - 0.181789 -0.407045 0.229942 - 0.193501 -0.419272 0.227863 - 0.195301 -0.418443 0.227549 - 0.201808 -0.423101 0.226399 - 0.211379 -0.433992 0.224699 - 0.268855 -0.432947 0.214624 - 0.275468 -0.431122 0.213468 - 0.326834 -0.434043 0.204457 - 0.500513 -0.458361 0.173957 - 0.611786 -0.474634 0.154414 - 0.633277 -0.474009 0.150648 - 0.637685 -0.473013 0.149877 - 0.659725 -0.476265 0.146006 - 0.901937 -0.518381 0.103454 - 0.955078 -0.53259 0.0941085 - 0.974341 -0.532272 0.0907319 - 1.06526 -0.55233 0.0747513 - 1.6605 -0.745954 -0.030004 - 1.66685 -0.731276 -0.0310882 - 1.42027 -0.578473 0.0124546 - 1.53761 -0.595194 -0.00815237 - 1.75603 -0.40857 -0.0460688 - 2.7362 -0.474028 -0.218052 - 2.73489 -0.362547 -0.217595 - 2.73886 -0.265011 -0.218093 - 2.73214 -0.203567 -0.21679 - 2.73454 -0.167337 -0.217137 - 2.84419 0.127847 -0.235762 - 2.84201 0.152923 -0.235329 - 2.85676 0.22979 -0.237759 - 2.8489 0.305333 -0.236228 - 2.83835 0.355021 -0.234277 - 1.86761 0.334429 -0.0641227 - 1.77123 0.341334 -0.0472095 - 1.66294 0.335605 -0.0282355 - 1.26443 0.325111 0.041612 - 1.09982 0.329411 0.0704819 - 1.33681 0.532773 0.0293441 - 1.24364 0.546798 0.0457069 - 1.19788 0.54549 0.0537272 - 1.14589 0.552324 0.062857 - 1.04959 0.557643 0.0797518 - 1.04545 0.561314 0.0804858 - 1.00722 0.5636 0.0871921 - 0.64974 0.440558 0.149618 - 0.311242 0.2639 0.208607 - 0.306734 0.326404 0.209525 - 0.300261 0.354894 0.210717 - 0.298777 0.36263 0.210993 - 0.289705 0.367421 0.212594 - 0.266748 0.406107 0.216697 - 0.256551 0.430136 0.218534 - 0.234101 0.424635 0.222459 - 0.14994 0.321957 0.237006 - 0.150711 0.356438 0.236941 - 0.303507 0.98521 0.211428 - 0.195396 0.739802 0.229885 - 0.148799 0.723922 0.238022 - 0.13534 0.872405 0.240683 - 0.139081 1.27806 0.240851 - 0.111995 1.28564 0.245615 - 0.0568519 1.29404 0.255301 - -0.0155399 1.29778 0.268 - -0.0608648 1.31015 0.275972 - -0.0725472 1.31648 0.278033 - -0.10098 1.31638 0.283018 - -0.177016 0.983295 0.295673 - -0.0604359 0.297132 0.27384 - -0.100675 0.313357 0.280928 - -0.229963 0.643318 0.304265 - -0.48773 1.18248 0.350554 - -0.492809 1.18028 0.35144 - -0.141321 0.326821 0.288082 - -0.127891 0.268984 0.28561 - -0.136116 0.279302 0.287072 - -0.137586 0.276255 0.287324 - -0.138772 0.275611 0.287531 - -0.845881 1.3982 0.413785 - -0.877077 1.40781 0.419274 - -0.88632 1.40892 0.420897 - -0.954862 1.35543 0.432806 - -1.23752 -1.28476 0.463882 - -1.30335 -1.43803 0.474419 - -1.33705 -1.71412 0.479414 - -0.225182 -0.362476 0.298938 - -0.22362 -0.363498 0.298678 - -0.207863 -0.369796 0.296069 - -0.187308 -0.366593 0.292688 - -0.180064 -0.36819 0.291491 - -0.165914 -0.367479 0.289161 - -0.162327 -0.368085 0.288569 - -0.138759 -0.375065 0.284671 - -0.133903 -0.376962 0.283867 - -0.131334 -0.380068 0.283437 - -0.103156 -0.376896 0.278801 - -0.0457076 -0.392421 0.269303 - 0.00031643 -0.386945 0.26173 - 0.0171598 -0.393857 0.25894 - 0.0592752 -0.402487 0.251983 - 0.0696534 -0.400954 0.250276 - 0.138404 -0.409808 0.238929 - 0.156914 -0.411755 0.235875 - 0.166846 -0.416489 0.234229 - 0.169 -0.416707 0.233874 - 0.199645 -0.418571 0.22882 - 0.203242 -0.416849 0.228231 - 0.205035 -0.415976 0.227937 - 0.218392 -0.424901 0.225718 - 0.232525 -0.438903 0.223361 - 0.29854 -0.433744 0.212493 - 0.339239 -0.434634 0.205785 - 0.349764 -0.432583 0.204055 - 0.358473 -0.435723 0.202613 - 0.436864 -0.454772 0.189657 - 0.445157 -0.443739 0.188313 - 0.529021 -0.459512 0.174462 - 0.588162 -0.463892 0.164708 - 0.727337 -0.487259 0.141727 - 0.84635 -0.51556 0.122058 - 0.880152 -0.520598 0.116478 - 0.885796 -0.518743 0.115552 - 0.949951 -0.523582 0.104971 - 1.05265 -0.545015 0.0880041 - 1.50411 -0.763613 0.0131685 - 1.55377 -0.763379 0.00498658 - 1.61438 -0.767065 -0.00500846 - 1.65409 -0.768282 -0.0115541 - 1.42415 -0.579221 0.0267179 - 1.73945 -0.535518 -0.0251489 - 1.74773 -0.496267 -0.0264334 - 1.7508 -0.48883 -0.0269247 - 1.75323 -0.456408 -0.0272594 - 1.75963 -0.408794 -0.0282171 - 1.75954 -0.352017 -0.0280863 - 2.89634 -0.487898 -0.215686 - 2.90334 -0.31935 -0.216499 - 2.90279 -0.228851 -0.216224 - 2.89679 -0.202677 -0.215182 - 2.8981 -0.125806 -0.215242 - 2.90047 -0.0874691 -0.215556 - 2.89984 -0.0746466 -0.215425 - 2.9066 0.0277825 -0.216332 - 2.9463 0.132237 -0.222662 - 2.9611 0.172197 -0.225019 - 2.9679 0.291155 -0.225899 - 1.98267 0.327601 -0.0634772 - 1.44363 0.516789 0.0257303 - 1.43079 0.52639 0.0278661 - 1.35109 0.530873 0.0410083 - 1.31576 0.537025 0.0468411 - 1.22043 0.542184 0.0625615 - 1.20582 0.54837 0.0649807 - 1.07918 0.554657 0.0858623 - 0.962934 0.565937 0.10504 - 0.683182 0.416553 0.150835 - 0.665199 0.41753 0.1538 - 0.315093 0.26715 0.211186 - 0.311293 0.268552 0.211815 - 0.332456 0.300115 0.208392 - 0.323397 0.315642 0.209916 - 0.315842 0.321846 0.211174 - 0.315139 0.323929 0.211294 - 0.312782 0.33581 0.211706 - 0.303777 0.355884 0.213231 - 0.258226 0.357581 0.22074 - 0.165874 0.330873 0.235904 - 0.15084 0.361707 0.238444 - 0.254877 0.741627 0.222071 - 0.319458 1.0064 0.211965 - 0.268916 0.927809 0.220135 - 0.202015 0.794814 0.230889 - 0.188099 0.96981 0.233537 - 0.189628 1.20692 0.233766 - 0.133849 1.2836 0.243112 - 0.106807 1.29407 0.24759 - 0.0788184 1.29397 0.252201 - 0.0453432 1.29442 0.257718 - -0.165238 0.855346 0.291528 - -0.0616515 0.300055 0.273334 - -0.0642327 0.299437 0.273758 - -0.0803003 0.292952 0.276392 - -0.0850311 0.290413 0.277167 - -0.130024 0.385781 0.284774 - -0.272155 0.690246 0.308812 - -0.459121 1.12474 0.340501 - -0.128565 0.27793 0.284315 - -0.829928 1.38236 0.402125 - -0.95098 1.37207 0.422052 - -0.962539 1.27896 0.423768 - -0.987409 1.10811 0.427519 - -0.986054 1.06852 0.427216 - -1.31639 -1.46152 0.458687 - -0.229388 -0.363957 0.296447 - -0.217273 -0.358752 0.294625 - -0.198541 -0.36657 0.291775 - -0.186665 -0.367447 0.289977 - -0.179848 -0.369904 0.28894 - -0.175259 -0.381128 0.288223 - -0.161683 -0.377592 0.286176 - -0.137788 -0.370411 0.282576 - -0.131132 -0.377253 0.281555 - -0.12849 -0.375036 0.28116 - -0.122974 -0.374898 0.280325 - -0.0833465 -0.378317 0.274323 - -0.077637 -0.368373 0.273479 - -0.0734906 -0.372383 0.272844 - -0.0594887 -0.378214 0.270713 - -0.0583576 -0.381457 0.270536 - -0.0256485 -0.390676 0.265568 - 0.00147442 -0.38397 0.261478 - 0.0130882 -0.384936 0.259719 - 0.0218996 -0.397681 0.25836 - 0.0270452 -0.397439 0.257582 - 0.0305345 -0.398237 0.257053 - 0.035613 -0.396883 0.256287 - 0.0445475 -0.40012 0.254929 - 0.0527025 -0.395206 0.253705 - 0.0627736 -0.392849 0.252186 - 0.0644679 -0.392596 0.25193 - 0.0820665 -0.402748 0.249247 - 0.0865054 -0.406966 0.248567 - 0.0919719 -0.406846 0.24774 - 0.123374 -0.412294 0.242978 - 0.128896 -0.417954 0.242131 - 0.157034 -0.412693 0.237884 - 0.160239 -0.41041 0.237404 - 0.176432 -0.42007 0.234935 - 0.177371 -0.412097 0.234809 - 0.254237 -0.438257 0.223126 - 0.255871 -0.428045 0.2229 - 0.290243 -0.433411 0.217688 - 0.377004 -0.442402 0.204544 - 0.410603 -0.445755 0.199453 - 0.458521 -0.44895 0.192197 - 0.463996 -0.450435 0.191366 - 0.494386 -0.455795 0.186757 - 0.606115 -0.469129 0.169826 - 0.609703 -0.467693 0.169286 - 0.750678 -0.492916 0.147906 - 0.893074 -0.522265 0.126302 - 0.901315 -0.521841 0.125056 - 0.917837 -0.520806 0.122559 - 0.958318 -0.527425 0.11642 - 1.46078 -0.740242 0.0399689 - 1.6736 -0.723128 0.00780502 - 1.47845 -0.585319 0.0376096 - 1.73302 -0.591464 -0.00091949 - 1.73972 -0.551422 -0.00185212 - 1.75407 -0.406776 -0.00373077 - 1.75581 -0.399059 -0.00397849 - 3.12723 -0.38525 -0.211441 - 3.12886 -0.371474 -0.211661 - 3.14096 -0.219382 -0.213184 - 3.13265 -0.0805002 -0.211646 - 2.96609 0.145965 -0.185987 - 2.97603 0.251766 -0.187277 - 2.99221 0.29299 -0.189642 - 2.99158 0.453455 -0.189222 - 1.86109 0.332162 -0.0184279 - 1.5584 0.334838 0.0273733 - 1.29459 0.325847 0.0672693 - 1.14369 0.391384 0.0902323 - 1.43876 0.528447 0.0458663 - 1.21824 0.54673 0.0792683 - 1.04755 0.560844 0.105121 - 1.04007 0.568578 0.106269 - 0.661922 0.410928 0.163162 - 0.65871 0.42911 0.163685 - 0.635022 0.425472 0.167262 - 0.339883 0.256889 0.211574 - 0.324262 0.324788 0.214075 - 0.320489 0.338194 0.214673 - 0.318145 0.363244 0.215078 - 0.317865 0.366132 0.215127 - 0.263925 0.438486 0.223434 - 0.256811 0.443833 0.224521 - 0.16954 0.324446 0.237483 - 0.166735 0.325873 0.237911 - 0.150619 0.317047 0.240331 - 0.144175 0.333015 0.241338 - 0.206595 0.549926 0.232333 - 0.38832 1.191 0.206135 - 0.305347 1.00663 0.218316 - 0.286057 1.00501 0.221231 - 0.277762 0.991773 0.22246 - 0.263829 0.973841 0.224531 - 0.232207 0.935567 0.229238 - 0.223674 0.935575 0.230529 - 0.217956 0.967663 0.231459 - 0.175488 1.26149 0.238479 - 0.133632 1.2846 0.244858 - 0.08361 1.28765 0.252433 - 0.0504612 1.29524 0.257463 - 0.016906 1.29396 0.262538 --0.00548749 1.30094 0.26594 - -0.0449993 1.30595 0.271928 - -0.0675838 1.30584 0.275345 - -0.0846866 1.30774 0.277936 - -0.131522 1.32062 0.285048 - -0.170131 1.30682 0.290862 - -0.419607 0.966216 0.327918 - -0.127211 0.273448 0.282278 - -0.925403 1.40865 0.405338 - -0.954378 1.34813 0.4096 - -0.954372 1.33579 0.409573 - -0.973647 1.25578 0.412328 - -0.97282 1.19993 0.41209 - -0.979961 1.17694 0.413124 - -0.982072 1.09924 0.413286 - -0.994884 1.04734 0.415119 - -1.29457 -1.30338 0.442099 - -1.29733 -1.31759 0.442458 - -1.31047 -1.60015 0.443739 - -0.238176 -0.365784 0.295218 - -0.235552 -0.368754 0.294843 - -0.199951 -0.360417 0.289846 - -0.197317 -0.363087 0.28947 - -0.187837 -0.368331 0.288124 - -0.163887 -0.368085 0.284751 - -0.150978 -0.378217 0.282913 - -0.131652 -0.371959 0.280204 - -0.124564 -0.377731 0.279194 - -0.0944414 -0.378716 0.27495 - -0.0827165 -0.380656 0.273295 - -0.0715588 -0.385166 0.271714 - -0.0395955 -0.389315 0.267204 - -0.0104742 -0.381648 0.263119 - 0.00271658 -0.382987 0.261258 - 0.0128401 -0.393934 0.259811 - 0.0263974 -0.392446 0.257904 - 0.0540615 -0.394997 0.254003 - 0.0653118 -0.400507 0.252408 - 0.0727161 -0.402355 0.251361 - 0.0767078 -0.404703 0.250794 - 0.0802024 -0.404062 0.250303 - 0.0813922 -0.400784 0.250142 - 0.0859873 -0.39681 0.249503 - 0.106171 -0.405509 0.246643 - 0.133482 -0.408096 0.242792 - 0.138761 -0.406373 0.242052 - 0.146923 -0.413087 0.240889 - 0.168224 -0.410414 0.237894 - 0.17214 -0.409892 0.237344 - 0.181939 -0.413326 0.235957 - 0.19212 -0.421921 0.234506 - 0.273666 -0.432307 0.223001 - 0.285329 -0.42591 0.221371 - 0.300822 -0.424923 0.219191 - 0.375222 -0.440113 0.208682 - 0.473151 -0.451214 0.194869 - 0.495206 -0.452286 0.19176 - 0.518765 -0.461745 0.188423 - 0.525716 -0.459841 0.187448 - 0.612548 -0.469518 0.1752 - 0.75267 -0.489082 0.155427 - 0.853686 -0.508625 0.141161 - 0.92827 -0.526215 0.130622 - 0.939715 -0.521939 0.129019 - 1.11092 -0.57382 0.104802 - 1.74474 -0.552322 0.0155848 - 1.75653 -0.358375 0.0143163 - 3.3523 -0.608602 -0.210925 - 3.35876 -0.458325 -0.211531 - 3.34841 -0.32256 -0.209798 - 3.34043 -0.100437 -0.208226 - 3.35553 -0.0418243 -0.210235 - 3.35767 -0.02708 -0.210506 - 2.98597 0.252267 -0.157594 - 2.0171 0.332283 -0.0209861 - 1.84932 0.338021 0.00265431 - 1.60341 0.336773 0.0372838 - 1.22282 0.324491 0.0908582 - 1.17699 0.323335 0.0973106 - 1.09993 0.322885 0.108161 - 1.08998 0.33556 0.109589 - 1.08852 0.340334 0.109804 - 1.07931 0.353066 0.111126 - 1.45058 0.517792 0.0591728 - 1.35352 0.537179 0.0728809 - 1.27404 0.538071 0.084076 - 1.09236 0.553967 0.109694 - 1.0372 0.608307 0.117573 - 0.453534 0.3289 0.199207 - 0.382958 0.287342 0.209062 - 0.317093 0.245877 0.218254 - 0.317126 0.261758 0.218282 - 0.334511 0.309868 0.215931 - 0.339076 0.325344 0.215319 - 0.329208 0.324083 0.216706 - 0.326396 0.32692 0.217108 - 0.358557 0.392574 0.212711 - 0.364588 0.409941 0.211897 - 0.353293 0.422348 0.213513 - 0.271512 0.343767 0.224871 - 0.262962 0.357773 0.226104 - 0.276736 0.434056 0.224318 - 0.167504 0.324269 0.23948 - 0.156788 0.327287 0.240995 - 0.148876 0.321045 0.242096 - 0.24091 0.671332 0.229843 - 0.408759 1.21794 0.207308 - 0.261037 0.998346 0.227669 - 0.155935 0.861815 0.242194 - 0.100613 1.2955 0.250862 - 0.0722978 1.29127 0.254841 - 0.066718 1.29155 0.255627 - 0.0387022 1.28858 0.259567 - -0.0172347 1.30278 0.267473 - -0.0228634 1.30267 0.268265 - -0.0284389 1.30053 0.269046 - -0.0854148 1.30973 0.277089 - -0.10847 1.3129 0.280342 - -0.114141 1.31238 0.28114 - -0.171487 0.987845 0.28856 - -0.0602505 0.306801 0.271519 - -0.0630416 0.294883 0.271888 - -0.0643151 0.294576 0.272067 - -0.0686419 0.285223 0.272657 - -0.0938201 0.30478 0.276243 - -0.194374 0.57015 0.29094 - -0.247597 0.683583 0.298665 - -0.12521 0.280284 0.280614 - -0.128398 0.277628 0.281058 - -0.665806 1.12754 0.358458 - -0.874234 1.39348 0.388349 - -0.947119 1.39866 0.398624 - -0.957926 1.32589 0.399999 - -1.30602 -1.49662 0.429634 - -1.30084 -1.50388 0.428944 - -0.244335 -0.366918 0.293475 - -0.242745 -0.368014 0.293266 - -0.235147 -0.363528 0.292284 - -0.23145 -0.364794 0.291799 - -0.192948 -0.361363 0.286786 - -0.169304 -0.365811 0.283694 - -0.163777 -0.370646 0.282963 - -0.117677 -0.37712 0.276939 - -0.109202 -0.37878 0.275831 - -0.107562 -0.37928 0.275616 - -0.091092 -0.370449 0.273486 - -0.0760279 -0.379225 0.271504 - -0.0476071 -0.394403 0.267768 - -0.035433 -0.39386 0.266181 - -0.0337286 -0.394035 0.265959 - -0.0270669 -0.396656 0.265085 - 0.00725053 -0.379994 0.260644 - 0.0106059 -0.384962 0.260196 - 0.0463516 -0.407906 0.255489 - 0.0751796 -0.39781 0.25175 - 0.0769002 -0.397499 0.251527 - 0.111907 -0.407048 0.246943 - 0.113153 -0.404643 0.246785 - 0.154847 -0.413354 0.241331 - 0.220381 -0.420347 0.232771 - 0.256386 -0.420684 0.228076 - 0.260263 -0.422994 0.227566 - 0.29286 -0.42923 0.223303 - 0.327681 -0.438669 0.218743 - 0.482528 -0.456029 0.198517 - 0.499858 -0.456336 0.196257 - 0.606231 -0.468517 0.182362 - 0.658664 -0.477978 0.175506 - 0.68634 -0.480157 0.171893 - 0.717114 -0.487992 0.167864 - 0.723785 -0.483374 0.167004 - 0.786882 -0.491722 0.15876 - 0.967197 -0.531268 0.135168 - 1.5075 -0.58786 0.0646015 - 1.73973 -0.583838 0.0343286 - 1.73623 -0.565777 0.0348212 - 1.74429 -0.501487 0.0339006 - 1.74761 -0.372132 0.0337282 - 1.81663 -0.34542 0.0247816 - 3.6059 -0.459249 -0.208757 - 3.60521 -0.203497 -0.20815 - 3.60486 -0.171715 -0.20804 - 3.08426 0.0835613 -0.139644 - 3.00096 0.293086 -0.128359 - 3.0077 0.400826 -0.129021 - 3.01111 0.455237 -0.129355 - 3.00911 0.468458 -0.129068 - 1.73693 0.340717 0.0365585 - 1.48841 0.332671 0.0689479 - 1.09338 0.341523 0.120475 - 1.10105 0.375922 0.119544 - 1.44897 0.523814 0.0744763 - 1.3545 0.530147 0.0868075 - 1.23501 0.546622 0.10242 - 1.16023 0.568974 0.112217 - 1.15776 0.574049 0.11255 - 1.14071 0.603336 0.114831 - 1.13976 0.622091 0.114993 - 1.14488 0.63141 0.114344 - 1.09642 0.642606 0.120685 - 0.694347 0.443239 0.172711 - 0.513849 0.366215 0.196092 - 0.326776 0.251244 0.220253 - 0.316365 0.261118 0.22163 - 0.268138 0.34256 0.228083 - 0.159669 0.330238 0.242202 - 0.150605 0.353952 0.243432 - 0.181683 0.457744 0.239589 - 0.219081 0.577146 0.234953 - 0.360132 1.01171 0.217437 - 0.368377 1.21829 0.216779 - 0.261739 1.01982 0.230283 - 0.170213 0.85708 0.24189 - 0.205851 1.24475 0.238025 - 0.190847 1.25519 0.240002 - 0.180116 1.25777 0.241406 - 0.155074 1.28017 0.244717 - 0.143776 1.27945 0.246189 - 0.0944793 1.29291 0.252644 - 0.0776904 1.29397 0.254835 --0.00076067 1.29298 0.265063 - -0.0402628 1.30217 0.270232 - -0.109082 1.3129 0.279227 - -0.198064 1.29174 0.290787 - -0.0588777 0.298008 0.270634 - -0.0637978 0.295856 0.271271 - -0.0722111 0.291652 0.27236 - -0.0909239 0.298561 0.274814 - -0.234532 0.682295 0.294313 - -0.258681 0.683899 0.297465 - -0.479807 1.1653 0.32727 - -0.121255 0.273612 0.278718 - -0.124796 0.271915 0.279177 - -0.835259 1.39545 0.374082 - -0.867227 1.39312 0.378246 - -0.875914 1.39348 0.379379 - -0.949795 1.36146 0.388949 - -0.972552 1.26089 0.391713 - -0.98091 1.15305 0.392585 - -0.985044 1.10804 0.393034 - -0.992585 1.09707 0.393995 - -1.29752 -1.31334 0.414582 - -1.30696 -1.34615 0.415643 - -1.28566 -1.38339 0.413024 - -1.30586 -1.46792 0.415266 - -1.31033 -1.58054 0.415574 - -1.32422 -1.64036 0.417111 - -1.3261 -1.67226 0.417272 - -0.25671 -0.359865 0.292226 - -0.252011 -0.363283 0.291658 - -0.178974 -0.368041 0.282927 - -0.101032 -0.373046 0.273611 - -0.0994153 -0.373508 0.273417 - -0.0857006 -0.381235 0.271763 - -0.0840481 -0.381629 0.271565 - -0.0692239 -0.376675 0.269805 - -0.0628783 -0.369753 0.269062 - -0.0290132 -0.393521 0.26497 --0.00820942 -0.385774 0.262502 - 0.0120697 -0.397933 0.260056 - 0.0137937 -0.397898 0.25985 - 0.027066 -0.388357 0.258284 - 0.0308229 -0.394135 0.257824 - 0.0398763 -0.399448 0.256732 - 0.043145 -0.397134 0.256347 - 0.0529104 -0.406129 0.255163 - 0.0746588 -0.396826 0.252585 - 0.0791833 -0.402096 0.252034 - 0.152479 -0.413068 0.24326 - 0.195833 -0.421172 0.238067 - 0.237696 -0.42227 0.233066 - 0.24098 -0.42386 0.232671 - 0.441706 -0.45095 0.208649 - 0.468935 -0.454619 0.20539 - 0.491752 -0.456582 0.202661 - 0.550583 -0.460479 0.195629 - 0.617297 -0.472559 0.187639 - 0.922167 -0.521789 0.151137 - 1.00587 -0.540744 0.141104 - 1.0181 -0.530269 0.139664 - 1.61676 -0.772878 0.0676942 - 1.6477 -0.770075 0.0640053 - 1.66696 -0.761403 0.0617223 - 1.67991 -0.732073 0.0602353 - 1.667 -0.709132 0.0618236 - 1.55243 -0.596983 0.07573 - 1.7496 -0.552622 0.0522754 - 1.74623 -0.387451 0.0530111 - 3.85905 -0.664077 -0.199825 - 3.8627 -0.629859 -0.200193 - 3.8902 -0.425656 -0.203064 - 3.87829 -0.218664 -0.201226 - 3.8792 -0.201641 -0.201301 - 3.50952 0.0641712 -0.156623 - 2.98759 0.159609 -0.0941111 - 2.98439 0.212007 -0.0936226 - 2.98435 0.251515 -0.093539 - 2.98818 0.265044 -0.0939692 - 2.99751 0.358915 -0.0948939 - 3.01174 0.441287 -0.096427 - 1.3281 0.327073 0.104376 - 1.24877 0.324901 0.113845 - 1.13347 0.321396 0.127605 - 1.43177 0.517042 0.0923807 - 1.42112 0.520222 0.0936586 - 1.2825 0.547176 0.110264 - 1.24098 0.574886 0.115278 - 0.546462 0.385928 0.197826 - 0.502765 0.358077 0.202987 - 0.42036 0.315654 0.212741 - 0.392126 0.296877 0.216075 - 0.414062 0.398338 0.21366 - 0.414014 0.454052 0.213778 - 0.385851 0.453638 0.21714 - 0.378141 0.448408 0.21805 - 0.273181 0.346132 0.230377 - 0.258245 0.364707 0.232197 - 0.256662 0.365816 0.232389 - 0.292767 0.442605 0.228232 - 0.290307 0.443026 0.228527 - 0.280404 0.462214 0.229748 - 0.282457 0.470297 0.229519 - 0.278372 0.472717 0.230012 - 0.264221 0.471609 0.231699 - 0.171265 0.318717 0.242491 - 0.167134 0.31412 0.242975 - 0.164406 0.315532 0.243303 - 0.152957 0.320034 0.244679 - 0.148122 0.316771 0.24525 - 0.157857 0.386496 0.244228 - 0.413969 1.23312 0.215352 - 0.409244 1.2368 0.215924 - 0.378012 1.23103 0.219642 - 0.206929 0.849025 0.2393 - 0.181113 1.26668 0.243224 - 0.11059 1.28764 0.251687 - 0.0549901 1.29803 0.258347 - 0.0327004 1.30871 0.26103 - -0.0294659 1.30053 0.268436 - -0.0691133 1.30284 0.273175 - -0.155752 1.31302 0.28354 - -0.066985 0.290065 0.270881 - -0.0750319 0.289994 0.271842 - -0.115235 0.361223 0.276786 - -0.128626 0.395718 0.278454 - -0.243946 0.687672 0.292812 - -0.266509 0.675717 0.295482 - -0.150151 0.275789 0.280782 - -0.167618 0.303743 0.282924 - -0.924679 1.39951 0.375528 - -0.961486 1.27847 0.379679 - -0.980875 1.10136 0.381637 - -1.31817 -1.65978 0.402166 - -1.33198 -1.69219 0.403602 - -1.32662 -1.74714 0.402908 - -0.270246 -0.373994 0.290865 - -0.249457 -0.361957 0.28863 - -0.218133 -0.362412 0.285225 - -0.212887 -0.364454 0.284651 - -0.202961 -0.365663 0.283569 - -0.195456 -0.371006 0.282743 - -0.186238 -0.369135 0.281745 - -0.168008 -0.381399 0.279739 - -0.118299 -0.369935 0.27436 - -0.113172 -0.370567 0.273801 - -0.109953 -0.371586 0.273449 - -0.105108 -0.37306 0.27292 - -0.0991497 -0.376855 0.272265 - -0.0649649 -0.387762 0.268528 - -0.0615984 -0.388357 0.26816 - -0.0587681 -0.381738 0.267866 - -0.0432406 -0.393082 0.266156 - -0.0277804 -0.393666 0.264474 - -0.0189344 -0.389289 0.263522 --0.00515856 -0.379876 0.262044 - 0.0197199 -0.383692 0.259332 - 0.0230481 -0.383544 0.258971 - 0.0253946 -0.39644 0.25869 - 0.036254 -0.402731 0.257497 - 0.04438 -0.395968 0.256628 - 0.104793 -0.403569 0.250047 - 0.106543 -0.403125 0.249857 - 0.113069 -0.406575 0.249141 - 0.121754 -0.410372 0.24819 - 0.13507 -0.409434 0.246744 - 0.163285 -0.409967 0.243677 - 0.175948 -0.41562 0.242289 - 0.206449 -0.420478 0.238965 - 0.294391 -0.431716 0.229385 - 0.309428 -0.433413 0.227747 - 0.323961 -0.437665 0.226159 - 0.391499 -0.443302 0.218808 - 0.409759 -0.444281 0.216821 - 0.413709 -0.4447 0.216391 - 0.534974 -0.459154 0.203183 - 0.66234 -0.475682 0.189308 - 0.718527 -0.483738 0.183185 - 0.789699 -0.49278 0.175432 - 0.847057 -0.513488 0.169157 - 0.855244 -0.513385 0.168267 - 0.925751 -0.528789 0.160573 - 0.960073 -0.526464 0.156848 - 1.02479 -0.544779 0.149777 - 1.57865 -0.779488 0.0891128 - 1.68102 -0.723128 0.0781007 - 1.44554 -0.584456 0.103971 - 1.73441 -0.59778 0.0725501 - 1.74946 -0.477178 0.0711577 - 1.74834 -0.403637 0.0714266 - 4.18955 -0.513788 -0.194103 - 4.19891 -0.181139 -0.194452 - 4.18929 -0.0704162 -0.193184 - 4.18787 -0.0153035 -0.192919 - 2.97468 0.119557 -0.0607988 - 2.9838 0.159237 -0.06171 - 2.98263 0.224798 -0.0614505 - 2.99421 0.318278 -0.0625208 - 2.9707 0.461427 -0.0596783 - 2.80078 0.447568 -0.0412394 - 1.42637 0.331267 0.107896 - 1.10813 0.319167 0.142458 - 1.09259 0.372379 0.144254 - 1.38854 0.52855 0.112405 - 1.31408 0.533272 0.120506 - 1.31946 0.596913 0.12005 - 1.23007 0.635966 0.129844 - 1.11226 0.644308 0.142664 - 0.682995 0.443831 0.188913 - 0.471865 0.348312 0.211666 - 0.305954 0.268581 0.229537 - 0.431401 0.39741 0.216162 - 0.449615 0.440495 0.21427 - 0.384527 0.456073 0.221375 - 0.26514 0.354691 0.234146 - 0.262053 0.356964 0.234486 - 0.313566 0.488549 0.229152 - 0.163545 0.324784 0.245127 - 0.155768 0.323 0.245968 - 0.153946 0.322754 0.246166 - 0.146512 0.325039 0.246978 - 0.143046 0.328721 0.247362 - 0.149683 0.348697 0.246681 - 0.148929 0.351179 0.246768 - 0.286285 0.749248 0.232641 - 0.365781 0.973465 0.224453 - 0.393314 1.07623 0.221667 - 0.315317 1.21138 0.230416 - 0.149291 1.2838 0.248605 - 0.127848 1.2951 0.250958 - 0.0824187 1.29164 0.255889 - 0.0600825 1.2948 0.258322 - 0.0547352 1.30203 0.258918 - 0.0490868 1.30224 0.259532 - 0.0038811 1.298 0.264437 - -0.0187108 1.30178 0.2669 - -0.104712 1.31439 0.276272 - -0.139315 1.31503 0.280034 - -0.168973 1.32048 0.283268 - -0.17548 1.10826 0.283548 - -0.165501 0.992329 0.28223 - -0.141522 0.790429 0.279218 - -0.0625311 0.29743 0.269641 - -0.072303 0.292958 0.270694 - -0.265097 0.678761 0.292423 - -0.361136 0.886655 0.303279 - -0.126712 0.285969 0.276594 - -0.843372 1.39003 0.356701 - -0.961393 1.26469 0.369275 - -0.981506 1.11972 0.371169 - -1.28719 -1.28788 0.386229 - -1.28581 -1.29777 0.386073 - -1.28407 -1.33039 0.385836 - -1.30211 -1.48538 0.387299 - -0.265213 -0.369548 0.287548 - -0.250559 -0.35921 0.286127 - -0.239343 -0.359744 0.285023 - -0.222974 -0.369218 0.283393 - -0.207395 -0.376147 0.281847 - -0.156014 -0.370608 0.276804 - -0.12173 -0.373182 0.273427 - -0.117166 -0.375755 0.272972 - -0.110198 -0.370631 0.272297 - -0.0753512 -0.376644 0.268858 - -0.0737149 -0.376989 0.268696 - -0.0421185 -0.394281 0.265553 - -0.0310166 -0.386397 0.264477 - -0.0266006 -0.394801 0.264026 - -0.0158412 -0.386483 0.262984 - 0.00261248 -0.392997 0.261156 - 0.00431903 -0.392999 0.260988 - 0.0197135 -0.393684 0.259472 - 0.0337489 -0.39788 0.258083 - 0.0410214 -0.401282 0.257361 - 0.0514629 -0.400171 0.256336 - 0.0566719 -0.399513 0.255825 - 0.0615852 -0.396807 0.255347 - 0.0874156 -0.401347 0.252798 - 0.148041 -0.413405 0.24681 - 0.1779 -0.415785 0.243868 - 0.191696 -0.412985 0.242517 - 0.303286 -0.432789 0.2315 - 0.308899 -0.428816 0.230956 - 0.380476 -0.438355 0.223896 - 0.4385 -0.451427 0.218163 - 0.539379 -0.458768 0.208225 - 0.666659 -0.4786 0.195665 - 0.693687 -0.480003 0.193004 - 1.53017 -0.763221 0.110154 - 1.64114 -0.783195 0.0991992 - 1.62455 -0.607476 0.101184 - 1.72601 -0.619833 0.0911788 - 1.75928 -0.34949 0.0884498 - 4.4996 -0.813477 -0.182032 - 4.52955 -0.798428 -0.184949 - 6.71524 -1.06308 -0.400474 - 2.99025 0.0938565 -0.0317432 - 2.99519 0.251933 -0.0319109 - 2.99802 0.344964 -0.0320024 - 1.84505 0.335877 0.0813907 - 1.18493 0.32439 0.1463 - 1.1051 0.328557 0.15416 - 1.44067 0.519412 0.121536 - 1.41277 0.523318 0.124288 - 1.36001 0.59353 0.129619 - 1.35742 0.599468 0.129886 - 1.36489 0.624276 0.129201 - 1.27033 0.628531 0.13851 - 1.18864 0.654046 0.146597 - 1.17883 0.655349 0.147565 - 1.08997 0.650134 0.156295 - 0.684111 0.444376 0.195803 - 0.361629 0.276029 0.227186 - 0.318314 0.253728 0.231402 - 0.465748 0.429338 0.217252 - 0.26653 0.340978 0.236671 - 0.260787 0.368805 0.237292 - 0.348927 0.539357 0.228965 - 0.343169 0.540667 0.229534 - 0.336823 0.55166 0.23018 - 0.334424 0.553113 0.230419 - 0.333036 0.556275 0.230562 - 0.323774 0.557087 0.231474 - 0.431003 1.18056 0.22218 - 0.343353 1.23177 0.230904 - 0.337478 1.23131 0.231481 - 0.13285 1.29156 0.251731 - 0.0651686 1.29155 0.258388 - 0.0259383 1.29582 0.262255 - -0.0480785 1.31694 0.269578 - -0.110289 1.30593 0.275676 - -0.0657687 0.360206 0.269396 - -0.0689935 0.293946 0.26958 - -0.0768108 0.287715 0.270336 - -0.0804225 0.290833 0.270698 - -0.259917 0.681104 0.289138 - -0.181663 0.322891 0.280721 - -0.891945 1.39799 0.352748 - -0.920527 1.40192 0.355567 - -0.954375 1.29994 0.358692 - -0.96795 1.22642 0.359879 - -0.974608 1.18099 0.360443 - -0.990189 1.08897 0.361791 - -1.2959 -1.40076 0.37309 - -1.30891 -1.47815 0.374076 - -1.31026 -1.60208 0.373945 - -1.32003 -1.71834 0.374569 - -0.239088 -0.365192 0.282413 - -0.228422 -0.3662 0.281475 - -0.223627 -0.369218 0.281048 - -0.187017 -0.368248 0.277836 - -0.152208 -0.369235 0.274779 - -0.123258 -0.370735 0.272235 - -0.116384 -0.377236 0.271619 - -0.096159 -0.374851 0.269849 - -0.0910698 -0.382365 0.269387 - -0.0820804 -0.381421 0.2686 - -0.0535407 -0.385757 0.266086 - -0.035336 -0.39105 0.264478 - -0.0109035 -0.377718 0.26236 - 0.027604 -0.389254 0.258957 - 0.0292957 -0.389146 0.258809 - 0.0418905 -0.396139 0.257689 - 0.0438127 -0.397957 0.257517 - 0.0475977 -0.400572 0.25718 - 0.0741232 -0.39978 0.254853 - 0.118817 -0.408959 0.250912 - 0.128261 -0.408251 0.250084 - 0.130331 -0.408655 0.249902 - 0.134487 -0.409434 0.249536 - 0.140448 -0.409575 0.249012 - 0.157051 -0.411086 0.247552 - 0.160619 -0.409727 0.247242 - 0.174304 -0.412849 0.246034 - 0.184398 -0.421593 0.245131 - 0.343003 -0.439375 0.231174 - 0.371461 -0.43944 0.228676 - 0.377857 -0.439241 0.228115 - 0.467735 -0.453224 0.220199 - 0.511769 -0.458652 0.216323 - 0.643755 -0.474796 0.204706 - 0.691022 -0.482449 0.200542 - 0.697207 -0.482281 0.2 - 0.711259 -0.482932 0.198765 - 0.754552 -0.493464 0.194944 - 0.763005 -0.489568 0.19421 - 0.804451 -0.496687 0.190558 - 0.954185 -0.522622 0.177364 - 0.989726 -0.536561 0.174217 - 1.5285 -0.59401 0.126814 - 1.73709 -0.59778 0.108498 - 1.7359 -0.588898 0.108621 - 1.89232 -0.349972 0.0953714 - 6.4984 -1.05697 -0.31032 - 6.71745 -1.06245 -0.329556 - 6.61006 -0.517091 -0.319036 - 6.85085 -0.445502 -0.340026 - 6.85876 -0.145152 -0.340118 - 6.79427 0.0644414 -0.334037 - 2.98234 0.106592 0.00061792 - 1.95574 0.329373 0.0911694 - 1.36638 0.329451 0.142897 - 1.13197 0.320308 0.163453 - 1.44387 0.513109 0.136465 - 1.33805 0.528734 0.145783 - 1.2291 0.627854 0.155545 - 1.21728 0.642035 0.156611 - 1.13691 0.657825 0.163696 - 1.09769 0.647908 0.167119 - 1.08433 0.652825 0.168301 - 0.676613 0.464943 0.203709 - 0.578444 0.412137 0.212219 - 0.52432 0.488008 0.217122 - 0.433119 0.487883 0.225127 - 0.271181 0.332036 0.239027 - 0.271383 0.338281 0.239022 - 0.16909 0.319444 0.247962 - 0.14629 0.318308 0.249961 - 0.15215 0.360421 0.249531 - 0.438275 1.23423 0.226172 - 0.310263 1.23735 0.237414 - 0.303937 1.23479 0.237964 - 0.0761548 1.29397 0.258075 - 0.0255771 1.30082 0.262528 - -0.031047 1.30353 0.267503 - -0.0482794 1.30895 0.269027 - -0.0653958 1.30915 0.27053 - -0.0939036 1.30832 0.27303 - -0.166636 1.04609 0.278887 - -0.0717075 0.407012 0.269272 - -0.0580616 0.303731 0.267867 - -0.0613812 0.299962 0.268151 - -0.0678846 0.298465 0.268719 - -0.117203 0.372725 0.273197 - -0.254753 0.785211 0.286097 - -0.270669 0.787169 0.287498 - -0.251565 0.702703 0.285652 - -0.261241 0.691589 0.286479 - -0.273225 0.68684 0.287521 - -0.440856 1.03699 0.302937 - -0.143391 0.327215 0.275404 - -0.14406 0.275611 0.275359 - -0.829626 1.37665 0.337741 - -0.963087 1.32186 0.349345 - -0.961045 1.2835 0.349088 - -0.963671 1.2639 0.34928 - -0.984149 1.12929 0.350807 - -1.29538 -1.39856 0.359572 - -1.31695 -1.65197 0.360733 - -1.33489 -1.7673 0.361891 - -0.2106 -0.364624 0.277693 - -0.203242 -0.36657 0.27712 - -0.182333 -0.369828 0.275495 - -0.179109 -0.371438 0.275242 - -0.164767 -0.366103 0.274143 - -0.161167 -0.366647 0.273863 - -0.154762 -0.369469 0.273362 - -0.148784 -0.368738 0.272901 - -0.143221 -0.368843 0.27247 - -0.133326 -0.382216 0.271677 - -0.0771453 -0.372383 0.267349 - -0.0723992 -0.382561 0.266961 - -0.061716 -0.380471 0.266139 - -0.0380115 -0.395849 0.264273 - -0.0222914 -0.394172 0.26306 - 0.0068381 -0.387982 0.260818 - 0.015555 -0.396805 0.260126 - 0.0290915 -0.392139 0.259088 - 0.043926 -0.402932 0.257918 - 0.0517036 -0.394005 0.257334 - 0.0660101 -0.396017 0.256223 - 0.0744548 -0.403719 0.255554 - 0.111335 -0.403678 0.252699 - 0.117137 -0.404147 0.252249 - 0.167143 -0.411342 0.248365 - 0.266856 -0.426684 0.240617 - 0.313239 -0.435325 0.23701 - 0.321707 -0.439063 0.236347 - 0.323615 -0.437665 0.236202 - 0.344702 -0.441746 0.234562 - 0.434138 -0.443076 0.227638 - 0.630618 -0.469227 0.212379 - 0.780958 -0.491425 0.2007 - 0.912747 -0.525836 0.190431 - 1.04268 -0.541796 0.180343 - 1.69334 -0.735655 0.129599 - 1.74274 -0.507181 0.126234 - 1.74359 -0.37768 0.126428 - 5.57887 -0.981909 -0.171605 - 6.64429 -0.960864 -0.254018 - 6.83845 -0.715532 -0.268553 - 5.53876 -0.481684 -0.167498 - 6.86411 -0.415868 -0.269937 - 2.97598 0.119317 0.0320469 - 2.98043 0.171737 0.0318079 - 2.99748 0.27815 0.0307021 - 3.00577 0.385327 0.0302753 - 2.8164 0.448982 0.0450589 - 1.28056 0.326345 0.163675 - 1.1982 0.322065 0.17004 - 1.12917 0.324694 0.175388 - 1.44371 0.512775 0.151422 - 1.43639 0.524334 0.152012 - 1.27587 0.54287 0.164472 - 1.27899 0.550807 0.164247 - 1.13096 0.640971 0.175883 - 0.681694 0.446804 0.210264 - 0.679744 0.449769 0.210421 - 0.578692 0.423796 0.218189 - 0.549236 0.413242 0.220448 - 0.333071 0.258818 0.236868 - 0.316233 0.26377 0.238181 - 0.539504 0.515567 0.221406 - 0.517529 0.534843 0.223146 - 0.328445 0.565751 0.237841 - 0.324993 0.565431 0.238108 - 0.171552 0.324768 0.2495 - 0.1472 0.321045 0.251377 - 0.188345 0.478254 0.248509 - 0.421384 1.25588 0.232033 - 0.379798 1.25756 0.235255 - 0.343186 1.2535 0.23808 - 0.3061 1.24451 0.240932 - 0.197715 1.27216 0.249376 - -0.0717218 1.31083 0.270306 - -0.0758608 0.290343 0.268579 - -0.280639 0.703524 0.285256 - -0.139431 0.271587 0.273461 - -0.819659 1.37172 0.328312 - -0.953888 1.35656 0.33867 - -0.966777 1.25491 0.339464 - -0.983738 1.11747 0.340501 - -0.988084 1.10285 0.340808 - -0.994675 1.03512 0.341182 - -1.30056 -1.51759 0.342379 - -1.3043 -1.53545 0.342583 - -1.32086 -1.63996 0.343434 - -1.33098 -1.74397 0.343874 - -0.2475 -0.365269 0.277213 - -0.204332 -0.370961 0.274435 - -0.165528 -0.370476 0.27195 - -0.150305 -0.366225 0.270983 - -0.137584 -0.376644 0.270147 - -0.134981 -0.379735 0.269974 - -0.119825 -0.378609 0.269005 - -0.0930411 -0.371838 0.267303 - -0.0906859 -0.369344 0.267157 - -0.0842392 -0.37092 0.26674 - -0.0791712 -0.371051 0.266415 - -0.0394537 -0.387712 0.263837 - -0.0345756 -0.390222 0.26352 - -0.0299674 -0.396656 0.263211 - -0.0264384 -0.395929 0.262987 - 0.00633389 -0.391982 0.260895 - 0.0253837 -0.396344 0.259665 - 0.036146 -0.400594 0.258967 - 0.0677312 -0.398698 0.256947 - 0.0759126 -0.404387 0.256412 - 0.0844995 -0.401709 0.255867 - 0.099375 -0.40249 0.254912 - 0.11141 -0.405609 0.254135 - 0.113175 -0.405129 0.254022 - 0.114938 -0.404642 0.25391 - 0.141829 -0.409919 0.252177 - 0.149174 -0.413712 0.251699 - 0.152772 -0.412415 0.251471 - 0.154566 -0.411755 0.251357 - 0.207237 -0.419587 0.247966 - 0.252302 -0.42828 0.245061 - 0.27265 -0.432307 0.24375 - 0.290695 -0.431322 0.242595 - 0.30101 -0.430325 0.241936 - 0.323586 -0.430039 0.24049 - 0.397675 -0.44287 0.235717 - 0.416175 -0.447635 0.234522 - 0.43818 -0.447371 0.233113 - 0.475858 -0.453287 0.230687 - 0.594666 -0.466984 0.223047 - 0.602658 -0.464848 0.222539 - 0.636263 -0.473411 0.220369 - 0.657741 -0.476216 0.218987 - 0.681843 -0.480267 0.217434 - 0.747419 -0.488535 0.213216 - 0.790051 -0.492251 0.210477 - 0.928031 -0.523757 0.201572 - 1.00781 -0.540272 0.196428 - 1.65106 -0.768809 0.154753 - 1.72188 -0.617135 0.150519 - 1.73705 -0.529976 0.149722 - 1.74434 -0.490853 0.149333 - 1.74289 -0.465901 0.149476 - 1.74106 -0.384862 0.149755 - 1.74848 -0.3546 0.149341 - 6.79046 -0.292018 -0.173601 - 2.9921 0.0937002 0.0705536 - 2.99196 0.264253 0.0709048 - 2.96735 0.45944 0.0728728 - 1.94051 0.326389 0.138401 - 1.42119 0.329236 0.171683 - 1.31552 0.329001 0.178453 - 1.2928 0.329307 0.179909 - 1.09184 0.339739 0.192807 - 1.08291 0.357793 0.193415 - 1.08826 0.370124 0.193097 - 1.37808 0.62926 0.175046 - 1.33546 0.616818 0.177752 - 1.27147 0.628088 0.181875 - 1.22211 0.637176 0.185056 - 1.20154 0.639822 0.186379 - 1.19171 0.641266 0.187012 - 1.11287 0.643307 0.192068 - 0.848237 0.540601 0.208818 - 0.679812 0.449769 0.219428 - 0.633368 0.464045 0.222433 - 0.314988 0.284638 0.242474 - 0.553253 0.524238 0.227687 - 0.361492 0.421525 0.239768 - 0.269618 0.336715 0.245485 - 0.266676 0.339036 0.245678 - 0.265535 0.343713 0.245761 - 0.265066 0.359058 0.245821 - 0.298481 0.419968 0.243802 - 0.317794 0.57048 0.242867 - 0.173023 0.324914 0.251651 - 0.148409 0.324693 0.253227 - 0.145174 0.325039 0.253435 - 0.142338 0.326272 0.25362 - 0.181031 0.448744 0.251386 - 0.457692 1.22175 0.235208 - 0.320298 1.25635 0.244081 - 0.237165 1.15844 0.249211 - 0.198216 1.27809 0.251947 - 0.159295 1.28447 0.254453 - 0.114897 1.29414 0.257318 - 0.0468786 1.29024 0.261668 - -0.170168 1.30957 0.275614 - -0.400185 1.20408 0.290141 - -0.249964 0.694248 0.279494 - -0.264657 0.687626 0.280422 - -0.143906 0.272969 0.271854 - -0.151818 0.278891 0.272373 - -0.872844 1.40203 0.320824 - -0.946217 1.39459 0.32551 - -0.962617 1.2819 0.326335 - -0.98075 1.17286 0.327279 - -0.980064 1.13135 0.327152 - -0.993674 1.06924 0.327899 - -1.29661 -1.32545 0.329494 - -1.28466 -1.38392 0.328731 - -1.29697 -1.47264 0.329219 - -1.32049 -1.65275 0.330129 - -1.33058 -1.72625 0.330527 - -0.260036 -0.365398 0.275386 - -0.253521 -0.366346 0.275032 - -0.241047 -0.365192 0.27436 - -0.175051 -0.360671 0.270801 - -0.173478 -0.361442 0.270715 - -0.159964 -0.365536 0.269976 - -0.146754 -0.370054 0.269253 - -0.128166 -0.36961 0.268249 - -0.12 -0.377658 0.267791 - -0.114463 -0.377317 0.267493 - -0.0940077 -0.373774 0.266394 - -0.0923783 -0.374191 0.266305 - -0.0644284 -0.380184 0.264782 - -0.0595045 -0.392157 0.264492 - -0.0533749 -0.386004 0.264173 - -0.0368077 -0.39105 0.263268 - -0.0320388 -0.395514 0.263001 - -0.028047 -0.388819 0.262799 - 0.014214 -0.383812 0.260524 - 0.040603 -0.396139 0.259073 - 0.0660916 -0.401942 0.257684 - 0.111513 -0.400307 0.255232 - 0.124186 -0.411244 0.254525 - 0.136984 -0.408272 0.253839 - 0.181698 -0.412546 0.251413 - 0.183091 -0.410843 0.251342 - 0.213314 -0.418653 0.249692 - 0.221077 -0.420283 0.249269 - 0.228486 -0.425415 0.248859 - 0.233138 -0.425179 0.248608 - 0.278027 -0.428728 0.246174 - 0.293231 -0.435478 0.245339 - 0.295125 -0.434202 0.245239 - 0.308697 -0.429629 0.244514 - 0.323151 -0.437665 0.243717 - 0.325055 -0.436259 0.243617 - 0.421263 -0.445457 0.238398 - 0.436768 -0.44999 0.237551 - 0.481843 -0.451186 0.235112 - 0.496028 -0.456473 0.234335 - 0.543173 -0.462013 0.231775 - 0.552536 -0.461763 0.231269 - 0.556847 -0.461271 0.231037 - 0.575252 -0.464021 0.230037 - 0.611292 -0.471576 0.228074 - 0.645512 -0.475984 0.226215 - 0.765961 -0.491189 0.219674 - 0.784177 -0.488546 0.218695 - 0.835757 -0.505715 0.215872 - 0.85902 -0.509646 0.214607 - 1.53572 -0.781109 0.177485 - 1.5507 -0.780243 0.176676 - 1.60027 -0.779136 0.173999 - 1.68694 -0.612699 0.169648 - 1.744 -0.490582 0.166808 - 1.74516 -0.4827 0.166761 - 1.74628 -0.474817 0.166716 - 1.74833 -0.467191 0.16662 - 1.75413 -0.41986 0.166402 - 6.64136 -1.04813 -0.0990327 - 6.79804 -0.29219 -0.105988 - 6.81709 -0.173751 -0.106781 - 2.97855 0.119277 0.101296 - 2.9814 0.197723 0.1013 - 1.56872 0.33463 0.177935 - 1.35418 0.527605 0.189919 - 1.32403 0.535899 0.191565 - 1.28438 0.627364 0.193891 - 1.14037 0.645902 0.201713 - 1.00366 0.627622 0.209066 - 0.897133 0.5718 0.214713 - 0.70269 0.519789 0.225119 - 0.332925 0.256759 0.24458 - 0.331017 0.257585 0.244684 - 0.309965 0.256638 0.24582 - 0.334106 0.304932 0.244612 - 0.56386 0.553425 0.232691 - 0.507914 0.568117 0.235744 - 0.293032 0.344429 0.246911 - 0.280625 0.332665 0.247559 - 0.263138 0.350337 0.248539 - 0.25795 0.352917 0.248825 - 0.439566 0.632164 0.239567 - 0.434041 0.635961 0.239873 - 0.431266 0.637841 0.240027 - 0.411376 0.619874 0.241066 - 0.395093 0.606643 0.24192 - 0.15935 0.316026 0.254081 - 0.155207 0.318057 0.254309 - 0.175566 0.430339 0.253433 - 0.182556 0.453389 0.253101 - 0.350261 1.25972 0.245651 - 0.337466 1.25595 0.246335 - 0.333259 1.26223 0.246575 - 0.321267 1.2612 0.247221 - 0.316733 1.26646 0.247477 - 0.235869 1.15354 0.251622 - 0.215232 1.27937 0.25299 - 0.0635569 1.29455 0.261219 - 0.00146452 1.3 0.264586 - -0.0325424 1.30053 0.266425 - -0.0780893 1.30251 0.268891 - -0.159419 1.31203 0.273306 - -0.165134 1.31131 0.273614 - -0.173985 1.29097 0.274052 - -0.0564117 0.301316 0.265714 - -0.0691144 0.29135 0.266381 - -0.076969 0.290343 0.266803 - -0.268635 0.678761 0.277942 - -0.443617 1.06297 0.28817 - -0.143144 0.279302 0.270358 - -0.906819 1.39992 0.313883 - -0.953004 1.33934 0.316258 - -0.958831 1.33515 0.316565 - -0.965031 1.26073 0.316751 - -0.988851 1.04454 0.317605 - -1.29982 -1.3626 0.3124 - -1.29127 -1.4266 0.311923 - -1.30396 -1.54573 0.312203 - -0.246041 -0.364706 0.271355 - -0.187655 -0.372578 0.268954 - -0.177417 -0.376508 0.268528 - -0.175773 -0.377286 0.268459 - -0.146515 -0.37256 0.267274 - -0.143793 -0.370411 0.267167 - -0.129784 -0.38303 0.26657 - -0.0826226 -0.389976 0.264629 - -0.0389754 -0.389881 0.262847 - -0.0220652 -0.393282 0.262149 - -0.0185836 -0.392475 0.262008 - 0.00716246 -0.396961 0.260948 - 0.040663 -0.402111 0.259569 - 0.0424157 -0.401937 0.259498 - 0.113147 -0.408023 0.256597 - 0.160964 -0.414393 0.254631 - 0.177098 -0.407815 0.253985 - 0.195244 -0.419421 0.253221 - 0.236036 -0.426795 0.25154 - 0.283579 -0.429645 0.249592 - 0.307766 -0.428816 0.248606 - 0.435915 -0.453328 0.243322 - 0.437887 -0.451427 0.243245 - 0.444038 -0.453813 0.242989 - 0.447978 -0.449932 0.242836 - 0.580985 -0.464639 0.237374 - 0.603556 -0.469927 0.236441 - 0.633681 -0.471618 0.235208 - 0.702309 -0.485697 0.232376 - 0.71606 -0.481504 0.231823 - 1.55989 -0.776142 0.196766 - 1.59105 -0.783021 0.195479 - 1.73384 -0.570263 0.190073 - 1.73732 -0.504948 0.190061 - 1.74912 -0.500113 0.189589 - 1.75483 -0.436119 0.189484 - 1.83661 -0.347279 0.186322 - 6.73842 -0.703699 -0.0146117 - 2.97555 0.184209 0.140864 - 2.97472 0.197194 0.140924 - 2.9975 0.317331 0.140234 - 2.9966 0.343711 0.140323 - 3.0044 0.424573 0.140167 - 1.62731 0.339634 0.196245 - 1.10464 0.322605 0.21756 - 1.34238 0.536429 0.208278 - 1.28677 0.540395 0.210557 - 0.971406 0.613293 0.223584 - 0.317649 0.261021 0.249583 - 0.572083 0.533055 0.239735 - 0.631601 0.676959 0.237592 - 0.61151 0.666941 0.238392 - 0.600327 0.666292 0.238848 - 0.28233 0.33221 0.251168 - 0.271194 0.342594 0.251644 - 0.269121 0.349269 0.251742 - 0.46278 0.792471 0.244719 - 0.192075 0.355137 0.2549 - 0.164306 0.323376 0.255971 - 0.150233 0.35082 0.256601 - 0.198771 0.501637 0.25492 - 0.397204 1.25824 0.248329 - 0.355922 1.26011 0.250019 - 0.256158 1.15221 0.253878 - 0.241067 1.15545 0.254501 - 0.153671 1.29209 0.258345 - 0.0743494 1.29496 0.26159 - 0.0687031 1.29527 0.261821 - 0.0460377 1.29424 0.262745 - -0.0445963 1.30317 0.266465 - -0.113293 1.30593 0.269277 - -0.175088 1.29394 0.271777 - -0.155345 1.01691 0.270416 - -0.0655028 0.380086 0.265471 - -0.0680951 0.295856 0.265409 - -0.0739834 0.297498 0.265652 - -0.151829 0.348621 0.268934 - -0.126049 0.27689 0.267738 - -0.136978 0.274936 0.26818 - -0.141059 0.268312 0.268334 - -0.170686 0.304499 0.269616 - -0.96425 1.23568 0.303894 - -0.991248 1.09258 0.304711 - -1.28891 -1.38612 0.298353 - -1.30455 -1.41525 0.298769 - -1.29686 -1.43178 0.298503 - -1.29328 -1.44041 0.298377 - -1.29474 -1.48056 0.298341 - -0.271537 -0.372775 0.269512 - -0.223053 -0.366798 0.268053 - -0.206798 -0.364794 0.267564 - -0.189782 -0.371747 0.267034 - -0.152322 -0.367147 0.265906 - -0.125069 -0.367898 0.265078 - -0.0994368 -0.370551 0.264295 - -0.0832765 -0.382769 0.26378 - -0.0799149 -0.375315 0.263693 - -0.0693283 -0.382537 0.263357 - -0.0444035 -0.388322 0.26259 - -0.0253832 -0.385078 0.262019 --0.00694916 -0.388913 0.261452 - 0.0480592 -0.39322 0.259774 - 0.0564016 -0.403242 0.259501 - 0.0887063 -0.401578 0.258524 - 0.155919 -0.412959 0.256462 - 0.163774 -0.4067 0.256236 - 0.170348 -0.412667 0.256025 - 0.1825 -0.416213 0.255649 - 0.228644 -0.422662 0.254236 - 0.241749 -0.424558 0.253835 - 0.40606 -0.441334 0.248816 - 0.455459 -0.457739 0.247284 - 0.456744 -0.455045 0.247251 - 0.511358 -0.462889 0.245578 - 0.526123 -0.459841 0.245136 - 0.661908 -0.475098 0.240986 - 0.751863 -0.486905 0.238233 - 1.62411 -0.781689 0.211178 - 1.52035 -0.597391 0.214695 - 1.59348 -0.602199 0.212466 - 1.61576 -0.602583 0.21179 - 1.73946 -0.546922 0.208148 - 1.74107 -0.514222 0.208164 - 1.75113 -0.459557 0.207968 - 1.75208 -0.427274 0.208004 - 1.74681 -0.401843 0.208215 - 1.74378 -0.369231 0.208372 - 1.74635 -0.361824 0.208309 - 6.7465 -0.674571 0.0559727 - 6.7444 -0.644644 0.0560962 - 5.70131 -0.469684 0.0880948 - 6.79705 -0.351363 0.0550855 - 6.80918 -0.113937 0.0551926 - 3.04677 0.0820009 0.169741 - 2.99244 0.0936064 0.171412 - 2.98552 0.119477 0.171674 - 2.97921 0.184394 0.171995 - 3.00938 0.385074 0.171482 - 1.9023 0.328226 0.204958 - 1.18334 0.323335 0.226762 - 1.08666 0.369479 0.229788 - 1.2785 0.536909 0.224302 - 1.26397 0.624102 0.224918 - 1.18422 0.637 0.227363 - 0.653132 0.492156 0.243187 - 0.310384 0.269208 0.253141 - 0.706408 0.700302 0.241987 - 0.645513 0.680143 0.243795 - 0.281342 0.331446 0.254146 - 0.271535 0.334369 0.25445 - 0.270074 0.335545 0.254496 - 0.268374 0.33945 0.254556 - 0.668679 0.972952 0.243678 - 0.686996 1.08895 0.243354 - 0.170441 0.325655 0.2575 - 0.16347 0.322483 0.257705 - 0.158885 0.320298 0.257839 - 0.159555 0.328869 0.257836 - 0.155559 0.373359 0.258047 - 0.184679 0.460822 0.257338 - 0.451366 1.23978 0.250805 - 0.440535 1.24366 0.251141 - 0.359431 1.25278 0.25362 - 0.34849 1.25586 0.253959 - 0.333298 1.26514 0.254438 - 0.208809 1.28028 0.258246 - 0.169373 1.28404 0.25945 - 0.147061 1.28777 0.260134 - 0.0910526 1.2969 0.261852 - 0.0794956 1.29364 0.262196 - 0.0402105 1.30342 0.263407 - -0.0223411 1.30378 0.265306 - -0.0338199 1.30752 0.265662 - -0.0394285 1.30436 0.265826 - -0.0802732 1.31947 0.267095 - -0.0967076 1.30732 0.267569 - -0.108107 1.30642 0.267913 - -0.113979 1.30792 0.268095 - -0.160269 1.30905 0.269501 - -0.175621 1.29394 0.269937 - -0.0628403 0.362362 0.264651 - -0.0629705 0.295077 0.26452 - -0.394896 1.21706 0.276436 - -0.259113 0.686199 0.271254 - -0.448956 1.05917 0.277761 - -0.33897 0.790831 0.273887 - -0.126164 0.279265 0.266406 - -0.126124 0.275982 0.266398 - -0.144115 0.27601 0.266944 - -0.570622 0.98945 0.281312 - -0.799426 1.34439 0.288965 - -0.863827 1.3965 0.291023 - -0.87097 1.3944 0.291236 - -0.956664 1.31719 0.293681 - -0.961247 1.28771 0.293761 - -0.963229 1.23332 0.293713 - -0.98049 1.12833 0.294026 - -0.990065 1.09036 0.294241 - -1.2998 -1.2914 0.285161 - -1.28817 -1.37246 0.284769 - -1.3216 -1.65041 0.284875 - -0.209376 -0.364749 0.265424 - -0.205694 -0.365699 0.26535 - -0.132739 -0.378096 0.26388 - -0.127811 -0.374518 0.26379 - -0.0330583 -0.390532 0.261882 - -0.017372 -0.384569 0.261583 - -0.0140932 -0.386712 0.261514 - 0.00614848 -0.385962 0.261114 - 0.0132258 -0.396805 0.260953 - 0.0458078 -0.392428 0.260316 - 0.0527797 -0.392574 0.260178 - 0.079516 -0.403391 0.259627 - 0.0913533 -0.398849 0.259402 - 0.144831 -0.411517 0.258317 - 0.201699 -0.420458 0.257173 - 0.216271 -0.42218 0.256881 - 0.308111 -0.434229 0.255039 - 0.330402 -0.428964 0.254608 - 0.333495 -0.429102 0.254547 - 0.35663 -0.438828 0.254069 - 0.382926 -0.442897 0.25354 - 0.391394 -0.444805 0.253369 - 0.439267 -0.449518 0.252411 - 0.516572 -0.459749 0.25086 - 0.7897 -0.492251 0.245387 - 0.812322 -0.491725 0.24494 - 1.63312 -0.786027 0.2281 - 1.42443 -0.581326 0.232641 - 1.65965 -0.610728 0.227925 - 1.74832 -0.442544 0.226506 - 2.97057 0.183838 0.203557 - 3.00443 0.424433 0.203368 - 1.7505 0.341483 0.228031 - 1.17646 0.321489 0.239357 - 1.10157 0.321763 0.24084 - 1.43604 0.523649 0.234622 - 1.34233 0.536429 0.236503 - 1.22975 0.627399 0.238914 - 1.21625 0.63394 0.239194 - 1.13772 0.644423 0.24077 - 1.08344 0.632518 0.241821 - 0.317669 0.256993 0.256232 - 0.316198 0.265057 0.256278 - 0.315039 0.266431 0.256303 - 0.711255 0.717802 0.249361 - 0.765297 1.16801 0.249192 - 0.744268 1.18033 0.249633 - 0.728686 1.17826 0.249937 - 0.444764 0.802347 0.254807 - 0.183184 0.343599 0.259068 - 0.168192 0.322106 0.259322 - 0.153942 0.318057 0.259596 - 0.384653 1.25877 0.25691 - 0.344467 1.26412 0.257716 - 0.308422 1.26102 0.258424 - 0.255173 1.15124 0.259259 - 0.246915 1.24185 0.259603 - 0.0674988 1.28928 0.263251 - -0.0458479 1.31116 0.265539 - -0.0629546 1.30944 0.265874 - -0.156015 1.31769 0.267733 - -0.148121 0.963543 0.266869 - -0.0642756 0.37742 0.264036 - -0.0553109 0.301818 0.263707 - -0.057103 0.29027 0.26372 - -0.0604505 0.293669 0.263793 - -0.0729006 0.294916 0.264042 - -0.391682 1.22354 0.272211 - -0.431747 1.02978 0.272617 - -0.140496 0.316897 0.265424 - -0.131629 0.290181 0.265195 - -0.171692 0.304499 0.266017 - -0.846079 1.39374 0.281549 - -0.961572 1.33515 0.283719 - -1.29124 -1.29353 0.271194 - -1.32421 -1.38573 0.271311 - -1.30401 -1.51608 0.270866 - -0.262259 -0.365398 0.263663 - -0.215052 -0.366348 0.263231 - -0.210848 -0.366482 0.263192 - -0.202 -0.365737 0.263113 - -0.144322 -0.372908 0.262572 - -0.133533 -0.379039 0.262462 - -0.128239 -0.379812 0.262412 - -0.119324 -0.380619 0.262329 - -0.0967435 -0.376679 0.262131 - -0.0936941 -0.378483 0.2621 - -0.0887321 -0.379682 0.262052 - -0.06371 -0.384697 0.261814 - -0.0519325 -0.386475 0.261703 - 0.0605275 -0.400507 0.260649 - 0.0995429 -0.404006 0.260286 - 0.102275 -0.407449 0.260254 - 0.146543 -0.411827 0.259841 - 0.148 -0.410245 0.259831 - 0.156202 -0.41041 0.259756 - 0.16413 -0.414847 0.259675 - 0.18655 -0.417354 0.259465 - 0.251907 -0.426323 0.258851 - 0.258711 -0.429252 0.258783 - 0.267995 -0.431784 0.258693 - 0.271753 -0.429432 0.258664 - 0.284371 -0.42841 0.258551 - 0.325053 -0.430228 0.258176 - 0.326927 -0.428807 0.258162 - 0.414073 -0.446901 0.25733 - 0.478706 -0.453277 0.256728 - 0.504035 -0.456843 0.25649 - 0.518215 -0.457493 0.256359 - 0.760997 -0.488487 0.254082 - 1.55179 -0.772132 0.246301 - 1.57103 -0.601633 0.246466 - 1.73157 -0.62017 0.244965 - 1.75006 -0.434913 0.245166 - 6.65718 -0.960293 0.199349 - 6.73353 -0.673079 0.199227 - 6.78245 -0.380186 0.199367 - 6.80404 -0.262376 0.199405 - 6.53861 -0.0808422 0.20219 - 2.9798 0.0931999 0.235004 - 2.96989 0.118838 0.235146 - 2.98748 0.276675 0.235301 - 2.99255 0.3167 0.235335 - 1.48503 0.330283 0.249115 - 1.34022 0.535687 0.250847 - 1.37029 0.625522 0.250752 - 1.31948 0.61629 0.251197 - 1.28241 0.633403 0.251569 - 1.16081 0.631169 0.252674 - 1.15176 0.63933 0.252773 - 0.326094 0.25716 0.259541 - 0.32072 0.257487 0.259591 - 0.312297 0.269163 0.259691 - 0.654244 0.678092 0.257389 - 0.620745 0.678007 0.257695 - 0.472398 0.525002 0.258742 - 0.265107 0.336307 0.260256 - 0.745853 1.05646 0.25731 - 0.780277 1.19144 0.257266 - 0.153511 0.318057 0.261237 - 0.158919 0.383525 0.261319 - 0.465607 1.24705 0.260248 - 0.412855 1.2539 0.260743 - 0.157772 1.28943 0.263141 - 0.12911 1.28758 0.263399 - 0.0791863 1.30362 0.263887 - -0.0347538 1.30652 0.264932 - -0.103714 1.31087 0.26557 - -0.126865 1.31184 0.265783 - -0.133395 1.31923 0.265857 - -0.139149 1.31863 0.265909 - -0.0572778 0.302552 0.263129 - -0.0797824 0.293237 0.263316 - -0.0863768 0.301773 0.263393 - -0.251465 0.709625 0.265715 - -0.247788 0.6897 0.265642 - -0.250795 0.688611 0.265667 - -0.279176 0.690548 0.26593 - -0.30684 0.749463 0.2663 - -0.419553 0.987395 0.267804 - -0.147253 0.334896 0.264015 - -0.130681 0.27429 0.263743 - -0.131876 0.273716 0.263752 - -0.145078 0.27601 0.263877 - -0.623516 1.06811 0.269826 - -0.883169 1.39819 0.272855 - -0.953584 1.3731 0.273447 - -0.958106 1.34178 0.273426 - -0.953425 1.32298 0.273346 - -0.96396 1.23253 0.273261 - -0.974616 1.20231 0.273298 - -0.974787 1.19185 0.273278 - -0.981941 1.16903 0.273298 - -0.993421 1.07359 0.273212 - -0.989479 1.04164 0.273112 - -0.99575 1.03009 0.273146 - -1.28971 -1.36101 0.258104 - -1.29688 -1.40496 0.25801 - -0.273542 -0.373582 0.261004 - -0.251003 -0.35897 0.261054 - -0.234514 -0.361637 0.261063 - -0.231349 -0.363669 0.261062 - -0.22976 -0.364675 0.261062 - -0.19758 -0.356988 0.261106 - -0.194395 -0.370065 0.261083 - -0.192318 -0.370023 0.261085 - -0.14325 -0.378833 0.261112 - -0.116601 -0.376362 0.261141 - -0.110437 -0.367787 0.261164 - -0.110294 -0.379299 0.261141 - -0.10698 -0.380247 0.261142 - -0.0798095 -0.376644 0.261174 - -0.064961 -0.379486 0.261182 - -0.0598324 -0.379315 0.261187 - -0.050921 -0.388683 0.261176 - -0.0398232 -0.398016 0.261168 - -0.0165512 -0.384645 0.261216 - -0.0150654 -0.38971 0.261207 - 0.0224133 -0.390354 0.26124 - 0.0313194 -0.394756 0.261239 - 0.0326239 -0.389633 0.26125 - 0.0441272 -0.400572 0.261239 - 0.0800462 -0.401082 0.261271 - 0.105124 -0.412815 0.26127 - 0.125395 -0.409207 0.261296 - 0.176876 -0.415939 0.261329 - 0.201849 -0.417777 0.261348 - 0.21637 -0.423961 0.261349 - 0.285627 -0.430911 0.261398 - 0.312977 -0.430169 0.261425 - 0.330163 -0.43358 0.261433 - 0.371156 -0.437825 0.261462 - 0.423625 -0.445797 0.261494 - 0.434451 -0.449271 0.261497 - 0.501107 -0.462577 0.261531 - 0.524329 -0.459182 0.261559 - 0.594305 -0.472056 0.261597 - 0.617536 -0.473167 0.261616 - 0.651917 -0.477304 0.261639 - 1.67643 -0.73621 0.262054 - 1.41597 -0.592571 0.262104 - 1.61616 -0.602932 0.262265 - 1.7523 -0.534351 0.262526 - 1.75103 -0.492477 0.262609 - 1.75346 -0.468482 0.262659 - 1.83641 -0.347279 0.262977 - 6.73622 -0.732786 0.266666 - 6.83689 -0.683424 0.266856 - 6.82551 -0.41249 0.267388 - 6.47975 -0.05184 0.267794 - 2.98649 0.250346 0.265219 - 3.00314 0.370958 0.265475 - 3.00818 0.438402 0.265615 - 1.38582 0.327388 0.263916 - 1.32906 0.620946 0.264452 - 1.29741 0.626977 0.264435 - 1.17813 0.634157 0.264341 - 0.668447 0.473167 0.263555 - 0.662196 0.481876 0.263567 - 0.324112 0.255921 0.262807 - 0.322992 0.257333 0.262809 - 0.310386 0.258558 0.2628 - 0.325621 0.298847 0.262894 - 0.714603 0.685116 0.264021 - 0.663761 0.682401 0.263969 - 0.63168 0.678423 0.263932 - 0.276498 0.321408 0.262895 - 0.269637 0.342594 0.262931 - 0.26814 0.343767 0.262932 - 0.333923 0.452009 0.263208 - 0.168746 0.321373 0.262796 - 0.154426 0.364632 0.26287 - 0.154378 0.368992 0.262879 - 0.469202 1.24126 0.26491 - 0.462384 1.23955 0.2649 - 0.451549 1.24354 0.264898 - 0.349125 1.26261 0.264843 - 0.207353 1.2793 0.264747 - 0.0499766 1.29703 0.26464 - 0.0329183 1.29458 0.264619 - -0.0812109 1.31149 0.264549 - -0.142923 0.951328 0.263773 - -0.0612055 0.363894 0.262672 - -0.060922 0.352784 0.26265 - -0.0576866 0.295427 0.262538 - -0.25542 0.729594 0.263227 - -0.257364 0.69595 0.263158 - -0.261297 0.688069 0.263138 - -0.272523 0.681547 0.263115 - -0.281499 0.695182 0.263134 - -0.411762 0.991946 0.263609 - -0.154213 0.353873 0.262567 - -0.130682 0.273388 0.262428 - -0.601796 1.04052 0.263533 - -0.884189 1.39903 0.263993 - -0.908969 1.3974 0.263967 - -0.951632 1.39542 0.263925 - -0.957711 1.39125 0.263911 - -0.982619 1.11877 0.263343 - -0.988473 1.09616 0.263293 - -0.991367 1.02506 0.263148 - -1.29721 -1.40496 0.244147 - -1.30201 -1.47339 0.243955 - -1.29622 -1.47981 0.244009 - -1.29565 -1.49224 0.243991 - -1.31572 -1.62674 0.243489 - -0.32075 -0.433511 0.257416 - -0.203955 -0.363978 0.258909 - -0.202509 -0.372765 0.258908 - -0.18679 -0.366338 0.259104 - -0.114033 -0.378323 0.259924 - -0.109621 -0.3817 0.259968 - -0.0971783 -0.381947 0.260112 - -0.0824501 -0.371051 0.260304 - -0.029389 -0.392937 0.260876 - -0.0102757 -0.384874 0.261114 - 0.0592267 -0.39754 0.261895 - 0.0671498 -0.402355 0.261977 - 0.0774084 -0.408642 0.262083 - 0.101176 -0.406479 0.262363 - 0.104971 -0.406545 0.262407 - 0.110283 -0.405129 0.262472 - 0.190158 -0.417533 0.263373 - 0.202266 -0.419577 0.26351 - 0.20585 -0.422283 0.263546 - 0.221913 -0.421977 0.263733 - 0.223282 -0.42012 0.263752 - 0.238264 -0.425604 0.263915 - 0.254953 -0.428658 0.264103 - 0.276529 -0.434145 0.264342 - 0.295641 -0.426219 0.264579 - 0.30817 -0.43207 0.264713 - 0.315458 -0.434212 0.264793 - 0.322911 -0.432441 0.264883 - 0.345893 -0.43874 0.265137 - 0.384269 -0.44198 0.265576 - 0.39862 -0.442624 0.265741 - 0.436763 -0.452146 0.266164 - 0.440692 -0.448313 0.266217 - 0.47243 -0.456046 0.26657 - 0.560311 -0.465743 0.26757 - 0.683358 -0.482573 0.268964 - 0.832999 -0.500011 0.270664 - 1.62395 -0.782123 0.279274 - 1.4748 -0.587372 0.277933 - 1.66797 -0.614183 0.28012 - 1.74771 -0.516489 0.28124 - 6.64039 -1.07665 0.336867 - 6.82702 -0.203647 0.340778 - 2.97078 0.144894 0.296749 - 2.98951 0.276951 0.29723 - 2.99855 0.317436 0.297416 - 2.99515 0.330301 0.297402 - 2.8218 0.44914 0.29563 - 2.01458 0.3297 0.286028 - 1.86389 0.338557 0.284298 - 1.44316 0.51244 0.279766 - 1.41152 0.529138 0.279433 - 1.37046 0.527438 0.278953 - 1.26695 0.545667 0.277789 - 1.34029 0.619334 0.278787 - 1.22944 0.627854 0.277518 - 1.21158 0.62542 0.277306 - 1.15637 0.629258 0.276673 - 1.15361 0.6343 0.276652 - 1.07272 0.62697 0.275699 - 1.06271 0.639934 0.275609 - 1.00815 0.631336 0.274959 - 0.669127 0.478404 0.270721 - 0.670586 0.488349 0.270757 - 0.429234 0.33026 0.267642 - 0.321035 0.260772 0.266248 - 0.696047 0.667815 0.271412 - 0.712381 0.695516 0.271656 - 0.292123 0.33125 0.266054 - 0.272124 0.331224 0.265822 - 0.268168 0.338281 0.26579 - 0.270737 0.354032 0.265851 - 0.594287 0.805092 0.270506 - 0.731676 1.00937 0.272508 - 0.784155 1.17627 0.27345 - 0.770652 1.21251 0.273366 - 0.746307 1.20889 0.273077 - 0.192959 0.35694 0.264955 - 0.14688 0.343734 0.264394 - 0.457846 1.24531 0.269804 - 0.439176 1.2446 0.269586 - 0.402181 1.26126 0.26919 - 0.377522 1.25948 0.268901 - 0.254462 1.15417 0.267263 - 0.24116 1.16622 0.267132 - 0.235082 1.27643 0.267282 - 0.172903 1.28131 0.266571 - 0.150983 1.28812 0.26633 - 0.0667785 1.30226 0.265382 - 0.0553267 1.3008 0.265246 - 0.00986646 1.29796 0.264713 - -0.0413147 1.30436 0.264133 - -0.155307 1.29981 0.262801 - -0.162962 1.26965 0.262652 - -0.0551919 0.293953 0.261951 - -0.0638966 0.285032 0.261832 - -0.073034 0.290065 0.261736 - -0.297366 0.939194 0.260432 - -0.410067 1.23906 0.259725 - -0.306596 0.746688 0.25994 - -0.384604 0.925447 0.259393 - -0.127044 0.270894 0.261071 - -0.150034 0.274961 0.260813 - -0.152195 0.276058 0.26079 - -0.894469 1.40106 0.254431 - -0.987596 1.08518 0.252719 - -1.30417 -1.47564 0.230211 - -1.30093 -1.5248 0.230185 - -0.322908 -0.435924 0.253996 - -0.263058 -0.36817 0.255455 - -0.22844 -0.368367 0.256221 - -0.21509 -0.37168 0.256509 - -0.214952 -0.375217 0.256505 - -0.181056 -0.366054 0.257273 - -0.179457 -0.366837 0.257307 - -0.106475 -0.375434 0.258904 - -0.103196 -0.376341 0.258975 - -0.0918902 -0.380262 0.259217 - -0.0646398 -0.372586 0.259835 - -0.0622486 -0.389193 0.259855 - -0.0123863 -0.384828 0.260966 - 0.00274613 -0.386982 0.261297 - 0.00443421 -0.386962 0.261334 - 0.019937 -0.392446 0.261666 - 0.0216487 -0.392351 0.261704 - 0.120632 -0.409327 0.26386 - 0.148715 -0.41589 0.264468 - 0.153031 -0.416444 0.264562 - 0.200492 -0.416876 0.265611 - 0.203186 -0.41779 0.265669 - 0.20545 -0.417792 0.265719 - 0.245178 -0.421372 0.26659 - 0.264824 -0.424678 0.267018 - 0.293861 -0.428331 0.267653 - 0.320532 -0.433848 0.268232 - 0.383144 -0.445168 0.269594 - 0.410667 -0.4447 0.270204 - 0.424027 -0.447246 0.270495 - 0.439618 -0.451666 0.270831 - 0.500652 -0.459036 0.272166 - 0.598962 -0.468082 0.274322 - 0.659437 -0.479152 0.275638 - 0.717216 -0.483738 0.276907 - 0.725972 -0.485039 0.277098 - 0.890018 -0.50847 0.280679 - 1.67059 -0.734199 0.297493 - 1.73168 -0.578455 0.299156 - 1.75133 -0.435637 0.299876 - 1.73841 -0.376412 0.299709 - 6.6457 -1.07777 0.40685 - 6.457 -0.759769 0.403312 - 5.83196 -0.454903 0.390097 - 5.83089 -0.429222 0.390124 - 6.37968 -0.190351 0.402741 - 2.96981 0.144894 0.327989 - 2.97664 0.184332 0.328219 - 2.9758 0.197326 0.328226 - 2.99912 0.357378 0.329062 - 3.00728 0.411728 0.329352 - 1.09543 0.336147 0.286912 - 1.41593 0.524012 0.294377 - 1.39491 0.523173 0.293911 - 1.33501 0.610154 0.29276 - 1.20374 0.628391 0.289893 - 1.19568 0.630845 0.289719 - 1.17076 0.630839 0.289168 - 1.1493 0.638844 0.288709 - 0.678044 0.47188 0.277952 - 0.67516 0.474265 0.277893 - 0.682383 0.501926 0.278108 - 0.318993 0.268917 0.269604 - 0.303753 0.277236 0.269284 - 0.659892 0.679533 0.277966 - 0.655533 0.680971 0.277872 - 0.273533 0.333541 0.268728 - 0.270613 0.335924 0.268668 - 0.588266 0.790463 0.276603 - 0.764004 1.07437 0.281058 - 0.781418 1.15118 0.281597 - 0.166334 0.40478 0.266499 - 0.188588 0.470219 0.267122 - 0.471767 1.23453 0.274915 - 0.394036 1.25633 0.273239 - 0.351976 1.2553 0.272307 - 0.318758 1.26314 0.271588 - 0.240138 1.27539 0.269873 - 0.139568 1.29237 0.267683 - 0.128287 1.29355 0.267436 - 0.100122 1.29706 0.26682 - 0.014996 1.2929 0.264928 - 0.00372636 1.29599 0.264685 - -0.0996672 1.3153 0.262437 - -0.111139 1.31439 0.262181 - -0.121771 1.30441 0.261926 - -0.133652 1.30828 0.261671 - -0.140094 1.31465 0.261541 - -0.0614561 0.391347 0.261434 - -0.0597758 0.350088 0.261388 - -0.252784 0.69049 0.2578 - -0.260903 0.693884 0.257627 - -0.131728 0.289845 0.259676 - -0.156731 0.280639 0.259105 - -0.620733 1.0612 0.250403 - -0.688358 1.16528 0.249116 - -0.853463 1.38918 0.245912 - -0.894782 1.40106 0.245022 - -0.951713 1.3435 0.243647 - -0.969925 1.20578 0.242969 - -0.977378 1.17254 0.242737 - -0.989255 1.12554 0.242381 - -1.26832 -1.2919 0.218095 - -1.30366 -1.55525 0.216416 - -1.31319 -1.63793 0.21594 - -0.244202 -0.360807 0.25334 - -0.237272 -0.36061 0.253567 - -0.230945 -0.364675 0.253765 - -0.218263 -0.365405 0.254177 - -0.213056 -0.363828 0.254349 - -0.184367 -0.36795 0.255276 - -0.179971 -0.371217 0.255413 - -0.150464 -0.370054 0.256377 - -0.145058 -0.375403 0.256543 - -0.125708 -0.372781 0.257179 - -0.11548 -0.36872 0.25752 - -0.113871 -0.369215 0.257572 - -0.11226 -0.369703 0.257623 - -0.100408 -0.370987 0.258007 - -0.0960366 -0.374191 0.258143 - -0.0401135 -0.388065 0.259938 - 0.0140835 -0.385691 0.26171 - 0.017983 -0.396528 0.261815 - 0.0248968 -0.39613 0.262041 - 0.0281262 -0.392894 0.262153 - 0.0298393 -0.392762 0.262209 - 0.0356207 -0.39929 0.262384 - 0.078699 -0.401082 0.263785 - 0.0819898 -0.399389 0.263896 - 0.0833136 -0.397066 0.263943 - 0.115073 -0.411846 0.264949 - 0.11838 -0.409854 0.265061 - 0.129698 -0.414771 0.26542 - 0.135005 -0.406731 0.265609 - 0.164883 -0.415985 0.266564 - 0.182114 -0.416333 0.267125 - 0.196891 -0.415044 0.26761 - 0.244173 -0.420509 0.26914 - 0.24956 -0.425462 0.269306 - 0.254483 -0.429516 0.269458 - 0.261649 -0.428686 0.269693 - 0.273098 -0.426207 0.270071 - 0.353727 -0.438051 0.272676 - 0.480694 -0.449086 0.276792 - 0.564301 -0.465833 0.279484 - 0.652691 -0.479076 0.282339 - 0.779214 -0.491958 0.286437 - 1.02156 -0.537506 0.294245 - 1.43361 -0.578847 0.307594 - 1.65133 -0.608656 0.314631 - 1.74515 -0.483233 0.31794 - 1.8302 -0.346535 0.320986 - 6.79344 -0.321599 0.482816 - 2.96612 0.131794 0.358969 - 2.98747 0.449148 0.3603 - 1.35636 0.529421 0.307293 - 1.23693 0.625636 0.303593 - 1.18154 0.63042 0.301797 - 1.08234 0.639777 0.298582 - 1.01694 0.637702 0.296446 - 0.67571 0.461991 0.284972 - 0.665916 0.472589 0.284674 - 0.653 0.498632 0.284305 - 0.324947 0.25778 0.27313 - 0.309512 0.273195 0.272658 - 0.308608 0.277232 0.272636 - 0.304427 0.275904 0.272497 - 0.309874 0.283292 0.27269 - 0.71072 0.707347 0.286604 - 0.283606 0.328505 0.271924 - 0.578079 1.02657 0.282919 - 0.168129 0.410325 0.268324 - 0.17578 0.434207 0.268621 - 0.272155 0.687517 0.272269 - 0.463524 1.24705 0.279627 - 0.435565 1.25501 0.278731 - 0.426192 1.24556 0.278407 - 0.38365 1.26356 0.277056 - 0.325203 1.26754 0.275159 - 0.1832 1.28074 0.270557 - 0.149511 1.28414 0.269465 - 0.0881722 1.2959 0.267489 - 0.0482688 1.29004 0.266177 - 0.0314888 1.29458 0.265639 - -0.0998066 1.31131 0.261393 - -0.161471 1.29615 0.259353 - -0.165472 1.28254 0.259195 - -0.146915 1.0994 0.259433 - -0.0562067 0.30206 0.260795 - -0.0564259 0.295919 0.260775 - -0.0639405 0.293398 0.260525 - -0.0647938 0.291168 0.260493 - -0.346357 1.09175 0.252917 - -0.31577 0.91125 0.253553 - -0.251506 0.695346 0.255216 - -0.272246 0.68645 0.254522 - -0.135326 0.277317 0.258166 - -0.136411 0.273448 0.258123 - -0.142993 0.274603 0.257911 - -0.145603 0.265297 0.257807 - -0.549328 0.947898 0.246013 - -0.888876 1.40495 0.23586 - -0.953108 1.39624 0.233749 - -0.948336 1.35091 0.233814 - -0.960082 1.33028 0.23339 - -0.979481 1.17485 0.232446 - -0.983873 1.1594 0.232272 - -0.991437 1.07939 0.231866 - -0.991907 1.0337 0.231759 - -1.31058 -1.53621 0.202579 - -1.30869 -1.56138 0.20261 - -1.31404 -1.61014 0.202282 - -1.33816 -1.79417 0.200876 - -0.2649 -0.369799 0.249902 - -0.230727 -0.360294 0.251391 - -0.153674 -0.367814 0.254691 - -0.147602 -0.371342 0.254945 - -0.135531 -0.373744 0.25546 - -0.127071 -0.37034 0.255831 - -0.125772 -0.371832 0.255883 - -0.124149 -0.37237 0.255952 - -0.113297 -0.377855 0.256408 - -0.0945555 -0.373631 0.257223 - -0.0836748 -0.371051 0.257696 - -0.0791763 -0.382226 0.257867 - -0.0219324 -0.390478 0.260314 - 0.00372299 -0.397961 0.261402 - 0.00723761 -0.399898 0.26155 - 0.0105358 -0.393807 0.261704 - 0.0172542 -0.390535 0.261999 - 0.0261843 -0.396012 0.262373 - 0.0557163 -0.394828 0.263646 - 0.0778297 -0.408298 0.26457 - 0.0997967 -0.406479 0.265519 - 0.130663 -0.406955 0.266846 - 0.137261 -0.408972 0.267125 - 0.16384 -0.40434 0.268278 - 0.165601 -0.403613 0.268355 - 0.195 -0.41681 0.269594 - 0.208502 -0.42136 0.270166 - 0.238128 -0.423688 0.271436 - 0.245664 -0.423963 0.271759 - 0.443085 -0.448513 0.280204 - 0.466419 -0.451881 0.281201 - 0.591726 -0.467603 0.28656 - 0.664725 -0.47511 0.289686 - 0.73173 -0.48517 0.292549 - 1.14622 -0.590737 0.31017 - 1.4213 -0.724441 0.321737 - 1.41663 -0.594116 0.321797 - 1.45023 -0.585952 0.323258 - 1.74427 -0.418231 0.336245 - 1.75034 -0.363448 0.336616 - 1.81281 -0.351676 0.339327 - 6.56168 -1.09444 0.542149 - 6.33409 -0.578074 0.533391 - 6.86153 0.0649424 0.55737 - 6.86118 0.0949163 0.557415 - 2.97904 0.119397 0.390444 - 2.97289 0.145186 0.390231 - 3.00214 0.358087 0.391916 - 2.96214 0.458829 0.390397 - 1.89928 0.328396 0.344408 - 1.83687 0.342481 0.341751 - 1.79512 0.342832 0.339956 - 1.48248 0.3305 0.326481 - 1.37741 0.332495 0.321964 - 1.15611 0.322329 0.312423 - 1.12489 0.318947 0.311073 - 1.28822 0.445664 0.318354 - 1.44716 0.514782 0.32533 - 1.44262 0.527419 0.32516 - 1.4225 0.527133 0.324294 - 1.36606 0.52672 0.321865 - 1.30433 0.617767 0.319391 - 1.1975 0.63271 0.314825 - 1.14688 0.631892 0.312646 - 1.05445 0.636324 0.308678 - 1.00544 0.643342 0.306583 - 0.38083 0.302396 0.279029 - 0.318289 0.266878 0.276267 - 0.713983 0.699008 0.294156 - 0.283999 0.321012 0.2749 - 0.272925 0.325336 0.274432 - 0.768988 1.07346 0.297272 - 0.171432 0.419567 0.270254 - 0.434273 1.25312 0.283231 - 0.421729 1.25215 0.282689 - 0.264026 1.15677 0.275714 - 0.194881 1.286 0.272997 - 0.161055 1.28972 0.27155 - 0.115714 1.29164 0.269603 - 0.00278545 1.29399 0.264749 --0.00853255 1.30098 0.264276 - -0.0142515 1.30594 0.26404 - -0.0542104 1.30795 0.262325 - -0.0828279 1.30849 0.261095 - -0.12838 0.86882 0.258255 - -0.0636829 0.400241 0.2601 - -0.0608714 0.371327 0.260163 - -0.066063 0.295077 0.259787 - -0.0947224 0.334312 0.258633 - -0.260529 0.831633 0.252495 - -0.407976 1.22956 0.246948 - -0.28044 0.688694 0.251352 - -0.3471 0.822351 0.248752 - -0.13192 0.272486 0.256909 - -0.131368 0.268313 0.256924 - -0.154844 0.278687 0.255935 - -0.161879 0.288508 0.255652 - -0.185496 0.321099 0.254701 - -0.540564 0.932316 0.240649 - -0.602584 1.02925 0.238174 - -0.695925 1.17734 0.234455 - -0.938213 1.40034 0.224478 - -0.954739 1.35992 0.223686 - -0.967418 1.21312 0.222846 - -0.994742 1.03659 0.221317 - -0.996472 1.02937 0.221229 - -1.29046 -1.28083 0.190801 - -1.30048 -1.40864 0.190011 - -1.30452 -1.47639 0.189661 - -1.30839 -1.53393 0.189339 - -1.31345 -1.63871 0.18886 - -1.32262 -1.69518 0.188259 - -0.197134 -0.363949 0.250837 - -0.169639 -0.368656 0.252291 - -0.164806 -0.370819 0.252544 - -0.1544 -0.368738 0.253102 - -0.142731 -0.372285 0.253716 - -0.112014 -0.378339 0.255339 - -0.0849157 -0.374957 0.256788 - -0.0808178 -0.371753 0.257013 - -0.0638742 -0.381025 0.257896 - -0.062835 -0.385242 0.257943 - -0.0136232 -0.383829 0.260566 --0.00691989 -0.38297 0.260924 --0.00525118 -0.382987 0.261013 - 0.0238934 -0.394135 0.262542 - 0.0277759 -0.399875 0.262737 - 0.0695472 -0.405688 0.264949 - 0.0878002 -0.405097 0.265922 - 0.120065 -0.412203 0.267625 - 0.124821 -0.402375 0.267898 - 0.147703 -0.411476 0.269098 - 0.153069 -0.409476 0.269387 - 0.175256 -0.417779 0.270552 - 0.186531 -0.413894 0.27116 - 0.197898 -0.424043 0.271745 - 0.239164 -0.430837 0.273928 - 0.274408 -0.425843 0.275814 - 0.332388 -0.439945 0.278872 - 0.382646 -0.438794 0.28155 - 0.432945 -0.446655 0.284211 - 0.484538 -0.453856 0.286943 - 0.559101 -0.462656 0.290895 - 0.922608 -0.517753 0.310134 - 1.58543 -0.782579 0.344887 - 1.66855 -0.760989 0.349355 - 1.67367 -0.754502 0.34964 - 1.44817 -0.585578 0.337975 - 1.49411 -0.588977 0.340414 - 1.74099 -0.591144 0.353551 - 1.749 -0.444016 0.354272 - 1.75046 -0.403861 0.354431 - 1.83068 -0.347093 0.358814 - 6.71593 -0.940513 0.617676 - 6.73259 -0.852999 0.618738 - 6.73624 -0.823564 0.618991 - 6.73026 -0.763184 0.618793 - 6.23454 -0.541841 0.592849 - 6.51368 -0.394333 0.608003 - 6.35208 -0.217581 0.599755 - 2.96962 0.171163 0.42048 - 2.9821 0.237391 0.421277 - 2.98191 0.263638 0.421319 - 3.00864 0.452861 0.423121 - 1.38843 0.328997 0.336627 - 1.2894 0.53029 0.331759 - 0.89088 0.581779 0.310648 - 0.67823 0.456062 0.299076 - 0.664667 0.485995 0.298414 - 0.693638 0.530743 0.300046 - 0.614522 0.474673 0.295722 - 0.316932 0.266238 0.279463 - 0.323828 0.302303 0.279903 - 0.277985 0.320487 0.277499 - 0.269801 0.333961 0.27709 - 0.27876 0.357523 0.277614 - 0.719328 0.960483 0.302274 - 0.752415 1.21156 0.304538 - 0.746604 1.214 0.304234 - 0.174272 0.326169 0.271989 - 0.166744 0.322258 0.271581 - 0.164417 0.321219 0.271455 - 0.148913 0.314453 0.270616 - 0.146331 0.323407 0.270497 - 0.163488 0.396666 0.271557 - 0.206819 0.519374 0.274109 - 0.408269 1.2501 0.286296 - 0.380647 1.25782 0.284841 - 0.243244 1.16124 0.277333 - 0.237916 1.27245 0.277273 - 0.222126 1.28041 0.276448 - 0.204572 1.27831 0.275509 - 0.115113 1.29065 0.270772 - 0.0817215 1.29927 0.269012 - 0.0644741 1.29527 0.268086 - 0.0475377 1.29603 0.267186 - 0.0362715 1.29742 0.266589 - 0.00236479 1.30399 0.264797 - -0.0431137 1.30436 0.262377 - -0.0601595 1.30371 0.261468 - -0.124029 1.31537 0.258092 - -0.139844 1.30073 0.25722 - -0.0548472 0.297373 0.259735 - -0.0603344 0.29125 0.259431 - -0.0762157 0.290715 0.258585 - -0.0782341 0.293293 0.258482 - -0.403796 1.23418 0.243037 - -0.274404 0.681547 0.248818 - -0.292457 0.708752 0.247911 - -0.177985 0.408734 0.253404 - -0.13123 0.279614 0.255634 - -0.138194 0.26958 0.255243 - -0.150392 0.269924 0.254594 - -0.826424 1.38476 0.220841 - -0.833479 1.38286 0.220462 - -0.867794 1.3982 0.218666 - -0.964648 1.28851 0.21329 - -0.982603 1.09823 0.211953 - -0.984718 1.07202 0.211788 - -0.985309 1.06332 0.21174 - -0.987887 1.05682 0.211589 - -1.28231 -1.30689 0.177307 - -1.30823 -1.57554 0.175108 - -0.251085 -0.362796 0.245272 - -0.243555 -0.361864 0.245756 - -0.223954 -0.366063 0.247003 - -0.204058 -0.376286 0.248258 - -0.191087 -0.367301 0.249107 - -0.117487 -0.371586 0.253814 - -0.10828 -0.376396 0.254394 - -0.0513469 -0.385925 0.258023 - -0.0401314 -0.393208 0.258727 - -0.0241951 -0.385394 0.259764 --0.00738598 -0.38497 0.260841 - 0.0482831 -0.398748 0.264381 - 0.0522954 -0.402251 0.264631 - 0.0552201 -0.397797 0.264827 - 0.0619783 -0.395738 0.265264 - 0.082816 -0.410157 0.26657 - 0.103358 -0.409449 0.267888 - 0.132124 -0.414562 0.269721 - 0.144695 -0.410245 0.270535 - 0.149647 -0.412693 0.270847 - 0.224334 -0.418151 0.275622 - 0.236504 -0.422818 0.276392 - 0.242006 -0.419645 0.276751 - 0.260482 -0.429538 0.277915 - 0.284656 -0.434245 0.279454 - 0.385288 -0.446505 0.285877 - 0.432226 -0.446655 0.288884 - 0.480351 -0.454609 0.291952 - 0.527183 -0.460823 0.29494 - 0.563086 -0.458362 0.297245 - 0.635014 -0.4764 0.301818 - 0.637082 -0.473607 0.301956 - 0.709238 -0.480387 0.306565 - 1.00051 -0.533527 0.325121 - 1.66998 -0.727296 0.367626 - 1.66579 -0.716823 0.367379 - 1.46347 -0.592308 0.354666 - 1.73726 -0.581938 0.372229 - 1.75212 -0.420791 0.373504 - 1.75394 -0.413115 0.373636 - 1.75474 -0.405206 0.373703 - 1.76823 -0.351629 0.374674 - 1.82075 -0.337266 0.378069 - 6.72313 -0.882288 0.691079 - 6.73748 -0.824291 0.692115 - 5.97393 -0.44067 0.643962 - 6.04744 -0.339833 0.648873 - 6.85294 0.0649424 0.701295 - 3.1211 0.0705765 0.462202 - 3.05493 0.0824583 0.457985 - 2.97764 0.145624 0.45316 - 2.99447 0.264956 0.454477 - 3.00039 0.345078 0.455017 - 2.98653 0.44989 0.454339 - 2.02707 0.332768 0.39263 - 1.84717 0.336592 0.381112 - 1.21978 0.32347 0.340887 - 1.14194 0.32439 0.335902 - 1.08029 0.358734 0.332021 - 1.32722 0.62973 0.348385 - 1.29018 0.633071 0.346019 - 1.21047 0.627254 0.3409 - 1.15006 0.628302 0.337031 - 1.12622 0.628165 0.335504 - 0.626327 0.484423 0.303187 - 0.316637 0.268917 0.282912 - 0.313643 0.293472 0.28277 - 0.688069 0.65788 0.30749 - 0.275693 0.338945 0.280429 - 0.269369 0.340227 0.280027 - 0.331184 0.42892 0.284165 - 0.776547 1.11707 0.314079 - 0.775847 1.21503 0.314231 - 0.719462 1.20656 0.310601 - 0.686067 1.18568 0.30842 - 0.143275 0.317956 0.271903 - 0.148832 0.341776 0.272307 - 0.149821 0.352262 0.272391 - 0.153003 0.363954 0.272619 - 0.41968 1.25025 0.291481 - 0.392061 1.25824 0.289728 - 0.369803 1.26399 0.288313 - 0.211163 1.28726 0.278195 - 0.109195 1.29414 0.271676 - 0.0921336 1.2935 0.270582 - 0.0863627 1.29191 0.270209 - 0.0638995 1.29427 0.268774 - 0.0583572 1.29655 0.268424 - 0.0414152 1.29724 0.267339 - 0.00189124 1.30699 0.264827 - -0.0208868 1.30787 0.263369 - -0.0956279 1.31572 0.258596 - -0.113057 1.31738 0.257482 - -0.129484 1.30786 0.256411 - -0.0532985 0.293658 0.25926 - -0.0666708 0.294099 0.258404 - -0.0690085 0.292554 0.258251 - -0.0726654 0.285523 0.258003 - -0.0937924 0.33375 0.256746 - -0.406923 1.18999 0.238399 - -0.251136 0.691582 0.247381 - -0.260148 0.688266 0.246797 - -0.297285 0.719855 0.244481 - -0.129988 0.282553 0.254324 - -0.134037 0.278476 0.254056 - -0.551196 0.959827 0.228694 - -0.867983 1.38508 0.209249 - -0.890213 1.39348 0.207841 - -0.906002 1.40472 0.206852 - -0.982094 1.13715 0.201441 - -0.985785 1.10196 0.201134 - -0.990277 1.05032 0.200742 - -1.29874 -1.28999 0.162552 - -1.30622 -1.47939 0.161614 - -0.227325 -0.371194 0.244398 - -0.188179 -0.368935 0.247326 - -0.179135 -0.366712 0.248005 - -0.14936 -0.373203 0.250216 - -0.145037 -0.371668 0.250542 - -0.103972 -0.378716 0.253594 - -0.0694648 -0.379199 0.256169 - -0.066981 -0.384697 0.256344 - -0.0440615 -0.39386 0.258037 - -0.0365981 -0.387543 0.258607 - -0.0333016 -0.388819 0.25885 --0.00779201 -0.38297 0.260767 --0.00445561 -0.381997 0.261018 - 0.00219286 -0.381963 0.261515 - 0.00734012 -0.387859 0.261887 - 0.0264833 -0.394889 0.263303 - 0.0689097 -0.397499 0.266465 - 0.0708212 -0.398164 0.266607 - 0.0980697 -0.405509 0.268627 - 0.124973 -0.406189 0.270634 - 0.131203 -0.407322 0.271097 - 0.132339 -0.404835 0.271187 - 0.135706 -0.408972 0.27143 - 0.155174 -0.407171 0.272887 - 0.208198 -0.419545 0.276822 - 0.210022 -0.418617 0.27696 - 0.236742 -0.420033 0.278952 - 0.307791 -0.432342 0.284233 - 0.331815 -0.433053 0.286025 - 0.425368 -0.444239 0.292988 - 0.439011 -0.450451 0.293995 - 0.53668 -0.465676 0.301257 - 0.541472 -0.461581 0.301623 - 0.610427 -0.471342 0.306753 - 0.721591 -0.480208 0.315035 - 0.732017 -0.48251 0.315809 - 0.756327 -0.489028 0.317612 - 0.761814 -0.487847 0.318024 - 0.829874 -0.501039 0.323079 - 0.839763 -0.501986 0.323816 - 0.925697 -0.520681 0.330195 - 1.01256 -0.54056 0.336641 - 1.68064 -0.723917 0.386159 - 1.50748 -0.633878 0.37341 - 1.46824 -0.587372 0.370573 - 1.73907 -0.499563 0.390973 - 1.74958 -0.436843 0.391883 - 1.7753 -0.353378 0.393971 - 6.21828 -0.322409 0.725792 - 6.21785 -0.267827 0.72587 - 2.96206 0.144991 0.483587 - 2.98306 0.211584 0.485288 - 1.89441 0.328396 0.404232 - 1.8331 0.342664 0.399683 - 1.74587 0.342249 0.393169 - 1.55142 0.332543 0.378629 - 1.10333 0.324288 0.345153 - 1.07776 0.353066 0.343302 - 1.42547 0.522621 0.369606 - 1.35987 0.532689 0.364727 - 1.29964 0.5356 0.360236 - 1.28574 0.543107 0.359213 - 1.28255 0.616136 0.359121 - 1.19312 0.625616 0.352463 - 1.02685 0.634018 0.340064 - 0.65731 0.473173 0.312148 - 0.654436 0.475473 0.311938 - 0.314809 0.260906 0.286147 - 0.302855 0.271897 0.285277 - 0.314546 0.287288 0.28618 - 0.703512 0.709742 0.316072 - 0.640044 0.657371 0.311228 - 0.346177 0.366492 0.288701 - 0.318518 0.340434 0.286584 - 0.29041 0.313413 0.284431 - 0.283521 0.319761 0.283929 - 0.278565 0.325485 0.28357 - 0.277974 0.345583 0.283567 - 0.624855 0.807379 0.310394 - 0.76542 1.09241 0.321462 - 0.773482 1.12458 0.322129 - 0.203468 0.374487 0.278061 - 0.166068 0.323143 0.275165 - 0.15151 0.349086 0.27413 - 0.171971 0.419728 0.2758 - 0.449745 1.25106 0.298209 - 0.444297 1.25303 0.297806 - 0.337553 1.25736 0.289844 - 0.255567 1.15109 0.283509 - 0.226793 1.28139 0.281622 - 0.215297 1.28138 0.280763 - 0.203818 1.28127 0.279906 - 0.159225 1.28873 0.276591 - 0.131357 1.29397 0.274521 - 0.0748822 1.29763 0.270311 - -0.0212735 1.30287 0.263141 - -0.0959593 1.31472 0.257588 - -0.139922 1.03497 0.253745 - -0.0743893 0.29652 0.257157 - -0.0838796 0.306494 0.256468 - -0.202157 0.705334 0.248436 - -0.339033 0.975529 0.238758 - -0.256469 0.696127 0.244362 - -0.160501 0.284136 0.250702 - -0.196906 0.339324 0.248094 - -0.885562 1.39988 0.198799 - -0.936223 1.39785 0.195012 - -0.960711 1.30735 0.193002 - -0.970392 1.22831 0.192121 - -0.972671 1.18798 0.19187 - -0.982318 1.16827 0.19111 - -1.28934 -1.32681 0.14984 - -1.28151 -1.35375 0.150452 - -1.29413 -1.39124 0.149303 - -0.244592 -0.362696 0.240623 - -0.238247 -0.366864 0.241154 - -0.226058 -0.365092 0.242194 - -0.21456 -0.363828 0.243175 - -0.20244 -0.368369 0.244196 - -0.193019 -0.369969 0.244994 - -0.154765 -0.376546 0.248234 - -0.144543 -0.379454 0.249098 - -0.141238 -0.380675 0.249376 - -0.0865119 -0.385089 0.254021 - -0.0696954 -0.388357 0.255445 - -0.0511736 -0.39209 0.257013 - -0.0100087 -0.390945 0.260516 - 0.0627408 -0.395452 0.266693 - 0.105376 -0.406575 0.270297 - 0.125904 -0.404673 0.272047 - 0.127662 -0.404103 0.272197 - 0.172788 -0.415939 0.276011 - 0.184657 -0.418361 0.277016 - 0.185646 -0.415714 0.277105 - 0.210783 -0.421289 0.279231 - 0.225507 -0.422543 0.280481 - 0.227342 -0.421537 0.280639 - 0.24044 -0.423308 0.28175 - 0.247471 -0.422644 0.282349 - 0.319955 -0.434043 0.28849 - 0.358705 -0.444237 0.291765 - 0.374015 -0.435191 0.293085 - 0.480718 -0.452493 0.302125 - 0.496173 -0.454827 0.303434 - 0.543647 -0.464163 0.307453 - 0.57656 -0.466515 0.310247 - 0.640503 -0.473169 0.315672 - 1.01242 -0.529808 0.347187 - 1.62404 -0.777607 0.398703 - 1.65817 -0.758505 0.401644 - 1.73528 -0.574013 0.408571 - 1.76168 -0.351045 0.411264 - 1.77003 -0.328553 0.412019 - 6.72169 -0.943559 0.831885 - 6.73605 -0.765659 0.833463 - 6.19184 -0.321326 0.788074 - 2.97919 0.0936377 0.515697 - 2.98973 0.278243 0.516964 - 3.00095 0.385835 0.518133 - 2.99479 0.45197 0.517742 - 2.00871 0.321375 0.433622 - 1.83066 0.334269 0.418506 - 1.64821 0.338534 0.402999 - 1.59893 0.335751 0.398802 - 1.39859 0.332446 0.381758 - 1.32984 0.328503 0.375904 - 1.17377 0.323071 0.36262 - 1.37433 0.47731 0.379986 - 1.34716 0.528331 0.377778 - 1.28734 0.619154 0.372873 - 0.30634 0.273195 0.288752 - 0.285573 0.319985 0.28708 - 0.28278 0.322505 0.286847 - 0.775329 1.21755 0.330531 - 0.73401 1.2222 0.327027 - 0.147151 0.33655 0.275341 - 0.480144 1.21988 0.305433 - 0.389625 1.25538 0.297806 - 0.384164 1.25709 0.297345 - 0.377823 1.2559 0.296803 - 0.1701 1.28924 0.279205 - 0.0683838 1.29197 0.27056 - 0.0291125 1.29658 0.26723 - -0.0444333 1.30436 0.260991 - -0.113481 1.31339 0.255137 - -0.258001 0.690322 0.241596 - -0.136701 0.276417 0.251081 - -0.890838 1.39516 0.189193 - -0.943657 1.39624 0.184703 - -0.948335 1.35173 0.184216 - -0.958208 1.31638 0.183306 - -0.975605 1.171 0.181534 - -1.28693 -1.33675 0.136867 - -1.31989 -1.72571 0.132944 - -1.33228 -1.80643 0.131601 - -0.246918 -0.362466 0.237932 - -0.234686 -0.360974 0.239101 - -0.230445 -0.357763 0.239511 - -0.227328 -0.359735 0.239804 - -0.145423 -0.376027 0.247577 - -0.121286 -0.374896 0.249879 - -0.117009 -0.384569 0.250267 - -0.0940317 -0.371118 0.252484 - -0.0914184 -0.382016 0.252711 - -0.0675477 -0.383711 0.254982 - -0.0658803 -0.383986 0.255141 - -0.0625421 -0.384515 0.255458 - -0.0558525 -0.385484 0.256093 - -0.0481393 -0.392493 0.256814 - -0.0414078 -0.394204 0.257452 - -0.0293419 -0.394172 0.258602 - -0.0216932 -0.377577 0.259364 - 0.0222916 -0.397128 0.263517 - 0.0558265 -0.399518 0.266708 - 0.0683 -0.399467 0.267896 - 0.0807207 -0.40722 0.269064 - 0.0886443 -0.401372 0.269831 - 0.0985039 -0.41133 0.270751 - 0.113662 -0.404094 0.27221 - 0.118031 -0.405921 0.272623 - 0.166299 -0.411925 0.27721 - 0.169871 -0.410418 0.277554 - 0.173621 -0.414245 0.277903 - 0.181032 -0.416441 0.278605 - 0.196543 -0.42136 0.280073 - 0.224931 -0.427064 0.282767 - 0.230366 -0.419499 0.2833 - 0.234496 -0.418297 0.283696 - 0.294463 -0.427379 0.289393 - 0.317947 -0.436259 0.291613 - 0.319838 -0.434844 0.291796 - 0.385602 -0.441599 0.298049 - 0.437404 -0.450451 0.302968 - 0.468164 -0.453287 0.305893 - 0.475711 -0.452555 0.306614 - 0.548556 -0.464974 0.313531 - 0.552101 -0.463826 0.313871 - 0.859717 -0.515263 0.343082 - 0.985667 -0.533181 0.355048 - 1.54065 -0.772132 0.407455 - 1.61337 -0.782123 0.414365 - 1.6846 -0.718493 0.421281 - 1.42671 -0.594028 0.396956 - 1.72962 -0.606683 0.425796 - 1.75725 -0.43154 0.42878 - 1.74289 -0.363651 0.427548 - 1.77828 -0.338545 0.430971 - 1.77386 -0.329642 0.430568 - 6.73596 -0.796332 0.902495 - 6.06215 -0.448375 0.838982 - 6.15392 -0.319674 0.847987 - 2.978 0.211655 0.546404 - 2.981 0.238183 0.546744 - 2.99937 0.426252 0.548872 - 1.46087 0.334101 0.402075 - 1.41576 0.330364 0.397769 - 1.09672 0.33367 0.367373 - 1.0769 0.353686 0.365524 - 1.08008 0.35999 0.36584 - 1.29465 0.534841 0.386639 - 1.06676 0.634696 0.365122 - 0.962464 0.62553 0.355165 - 0.675275 0.465372 0.327476 - 0.637959 0.486734 0.323963 - 0.538471 0.426433 0.314361 - 0.714862 0.704594 0.331729 - 0.35293 0.365444 0.296557 - 0.286986 0.311226 0.290164 - 0.281561 0.308108 0.289641 - 0.752025 0.991448 0.335846 - 0.754933 1.00431 0.336149 - 0.762835 1.03337 0.336961 - 0.160227 0.324446 0.278111 - 0.148293 0.321431 0.276968 - 0.151069 0.346582 0.277283 - 0.151297 0.363954 0.277339 - 0.168733 0.40975 0.279093 - 0.413401 1.25683 0.30411 - 0.371563 1.25756 0.300125 - 0.349925 1.26492 0.298078 - 0.320631 1.2656 0.295288 - 0.243993 1.15233 0.287757 - 0.238413 1.17601 0.287273 - 0.231228 1.28135 0.286799 - 0.202231 1.2793 0.284032 - 0.157035 1.28079 0.279728 - 0.141449 1.29274 0.278267 - 0.135832 1.29337 0.277733 - 0.0902288 1.28951 0.273379 - -0.0562575 1.30595 0.259453 - -0.0848524 1.30849 0.256733 - -0.108205 1.31486 0.25452 - -0.151096 1.28657 0.250376 - -0.0610523 0.392849 0.257162 - -0.0559318 0.336993 0.257537 - -0.0540407 0.298808 0.257641 - -0.0721063 0.295184 0.255912 - -0.161882 0.579721 0.247928 - -0.388566 1.22143 0.227616 - -0.397216 1.23021 0.226809 - -0.413211 1.22493 0.225274 - -0.263134 0.685264 0.238492 - -0.140264 0.268093 0.249362 - -0.145811 0.273095 0.248844 - -0.146995 0.272471 0.24873 - -0.148177 0.271842 0.248616 - -0.149582 0.268811 0.248476 - -0.608209 1.04918 0.206339 - -0.899226 1.39547 0.179302 - -0.909079 1.3974 0.178367 - -0.963112 1.27632 0.172975 - -1.29444 -1.39344 0.122534 - -1.32496 -1.73365 0.118621 - -0.262349 -0.367677 0.233749 - -0.214899 -0.367348 0.238768 - -0.200999 -0.364852 0.240243 - -0.176301 -0.367334 0.24285 - -0.153454 -0.371909 0.245257 - -0.150736 -0.369773 0.245549 - -0.0803026 -0.385503 0.252966 - -0.0492931 -0.38435 0.256248 - -0.0298043 -0.39517 0.258287 - -0.0159266 -0.390825 0.259764 --0.00905723 -0.38397 0.260504 --0.00739109 -0.383987 0.26068 --0.00068784 -0.387982 0.261381 - 0.0776437 -0.403668 0.269634 - 0.107845 -0.405606 0.272824 - 0.140366 -0.409943 0.276255 - 0.153831 -0.408103 0.277682 - 0.165796 -0.417294 0.278929 - 0.227007 -0.423289 0.285391 - 0.241458 -0.423099 0.28692 - 0.255665 -0.434393 0.288399 - 0.296584 -0.431473 0.292733 - 0.322758 -0.435815 0.295492 - 0.470655 -0.452589 0.3111 - 0.717883 -0.484484 0.337182 - 0.792634 -0.49511 0.345066 - 0.896909 -0.522341 0.35604 - 1.03255 -0.541796 0.370345 - 1.24376 -0.638306 0.392489 - 1.57246 -0.789063 0.426948 - 1.43675 -0.598994 0.412978 - 1.74332 -0.578075 0.445443 - 1.74254 -0.502312 0.445512 - 1.74746 -0.365071 0.446309 - 6.10967 -0.398481 0.907583 - 6.81833 -0.054888 0.983221 - 6.84471 0.095165 0.986313 - 2.98239 0.212219 0.578075 - 2.99432 0.30586 0.579525 - 3.00081 0.440421 0.580481 - 1.99758 0.329377 0.474158 - 1.84968 0.338557 0.458535 - 1.68944 0.340109 0.441591 - 1.63631 0.336934 0.435966 - 1.21854 0.324747 0.391759 - 1.12181 0.320308 0.38152 - 1.08385 0.356473 0.377577 - 1.08418 0.361873 0.377623 - 1.40648 0.489708 0.411966 - 1.43647 0.521444 0.415202 - 1.2993 0.537497 0.400727 - 1.37948 0.613588 0.40936 - 1.31178 0.625457 0.402224 - 1.24098 0.611998 0.39471 - 1.15195 0.639116 0.385348 - 1.10185 0.636957 0.380045 - 1.01037 0.638763 0.370375 - 0.938284 0.616675 0.362706 - 0.547644 0.434444 0.321026 - 0.351764 0.285371 0.30001 - 0.319523 0.261872 0.296553 - 0.314163 0.266878 0.295996 - 0.308411 0.28123 0.295417 - 0.312237 0.29483 0.295849 - 0.284804 0.320725 0.293 - 0.284074 0.322735 0.292927 - 0.751389 0.992242 0.343696 - 0.723417 1.20852 0.341172 - 0.441435 0.786044 0.310501 - 0.155569 0.31305 0.279317 - 0.469477 1.24481 0.314389 - 0.463016 1.24407 0.313704 - 0.393692 1.25459 0.306394 - 0.387648 1.25442 0.305754 - 0.382201 1.25613 0.305182 - 0.370713 1.25756 0.30397 - 0.358398 1.25601 0.302664 - 0.0958823 1.29706 0.274983 - 0.0112926 1.2999 0.266043 - -0.0508535 1.30217 0.259475 - -0.0683348 1.31244 0.257647 - -0.146037 1.28919 0.249382 - -0.0974145 0.35387 0.252643 - -0.235901 0.783185 0.238861 - -0.252379 0.702086 0.236955 - -0.259425 0.693136 0.236192 - -0.138177 0.301372 0.248227 - -0.138499 0.266902 0.248124 - -0.847661 1.3946 0.175392 - -0.884488 1.39988 0.171507 - -0.948222 1.39129 0.16475 - -0.957067 1.30413 0.163639 - -0.972532 1.22172 0.161838 - -0.982249 1.18022 0.160726 - -0.976586 1.13261 0.16123 - -0.986103 1.05682 0.160071 - -0.989068 1.04164 0.159727 - -1.30401 -1.31051 0.103571 - -1.32948 -1.74158 0.0996546 - -0.235643 -0.365357 0.233358 - -0.232468 -0.367371 0.233734 - -0.173409 -0.368829 0.2408 - -0.171398 -0.368656 0.241041 - -0.163799 -0.368774 0.24195 - -0.150376 -0.377569 0.243539 - -0.132929 -0.380759 0.245621 - -0.10838 -0.376855 0.248568 - -0.102213 -0.37335 0.249313 - -0.0989742 -0.374191 0.249699 - -0.0782428 -0.372751 0.252183 - -0.0352315 -0.39181 0.257293 - 0.0107849 -0.394683 0.262796 - 0.0158602 -0.393444 0.263406 - 0.0457635 -0.398748 0.266974 - 0.0581429 -0.398979 0.268456 - 0.0598707 -0.398698 0.268663 - 0.0643533 -0.393872 0.26921 - 0.0709554 -0.400784 0.269986 - 0.0843671 -0.404121 0.271584 - 0.114402 -0.404534 0.275179 - 0.126413 -0.406004 0.276614 - 0.166654 -0.411175 0.28142 - 0.195563 -0.417777 0.284867 - 0.20908 -0.42218 0.286476 - 0.230587 -0.418468 0.289058 - 0.273382 -0.430872 0.294156 - 0.294414 -0.429835 0.296675 - 0.299716 -0.433413 0.297303 - 0.344589 -0.445804 0.302649 - 0.469864 -0.449132 0.317637 - 0.500156 -0.457315 0.321247 - 0.560599 -0.464624 0.328467 - 0.573126 -0.466515 0.329963 - 0.584168 -0.466984 0.331284 - 0.636846 -0.473169 0.337577 - 0.751658 -0.484627 0.351296 - 0.81633 -0.501052 0.359004 - 0.854441 -0.508939 0.36355 - 0.940015 -0.521181 0.373769 - 1.56284 -0.768631 0.447822 - 1.46999 -0.583856 0.43708 - 1.48732 -0.583157 0.439156 - 1.64815 -0.612801 0.458348 - 1.72432 -0.615275 0.46746 - 1.74005 -0.578075 0.469418 - 1.73415 -0.550822 0.468767 - 1.74812 -0.496538 0.470548 - 1.73972 -0.485898 0.469564 - 1.74386 -0.470547 0.470091 - 1.76729 -0.345593 0.473147 - 6.83518 0.00500521 1.08047 - 2.99027 0.332602 0.620902 - 3.00334 0.42807 0.622659 - 1.98508 0.327924 0.500572 - 1.22803 0.322139 0.409943 - 1.10285 0.331404 0.394977 - 1.44467 0.511091 0.436255 - 1.40486 0.525052 0.431518 - 1.33589 0.53314 0.423278 - 1.2921 0.5356 0.418041 - 1.27917 0.543494 0.416509 - 1.01603 0.637465 0.385202 - 0.951805 0.632881 0.377505 - 0.661885 0.475478 0.342485 - 0.644408 0.475993 0.340394 - 0.314988 0.261402 0.30053 - 0.313348 0.296868 0.300405 - 0.457728 0.458733 0.318013 - 0.29536 0.308343 0.298275 - 0.287853 0.305933 0.297372 - 0.286569 0.312684 0.297232 - 0.287241 0.316158 0.297319 - 0.278169 0.325753 0.296253 - 0.275684 0.334501 0.295973 - 0.328717 0.408433 0.30247 - 0.752694 0.987334 0.354385 - 0.757313 1.01148 0.354987 - 0.773593 1.12199 0.357158 - 0.760892 1.20156 0.355798 - 0.679244 1.17231 0.345966 - 0.150603 0.318503 0.280968 - 0.149221 0.319184 0.280804 - 0.480358 1.21311 0.322242 - 0.448485 1.24156 0.318484 - 0.441069 1.2379 0.317589 - 0.363789 1.25824 0.308379 - 0.23989 1.27531 0.293583 - 0.212039 1.27941 0.290258 - 0.206494 1.28035 0.289596 - 0.0838738 1.29789 0.274954 - 0.066776 1.29496 0.272901 - 0.0219411 1.30071 0.267546 - 0.0162074 1.29482 0.266848 - -0.107736 0.780191 0.250975 - -0.0558888 0.296615 0.256207 - -0.0879157 0.327539 0.252436 - -0.117391 0.428318 0.249111 - -0.231628 0.780353 0.236146 - -0.250927 0.697374 0.233669 - -0.286123 0.690246 0.229441 - -0.823157 1.38218 0.166553 - -0.887121 1.39179 0.158916 - -0.948884 1.38054 0.1515 - -0.964202 1.24542 0.149394 - -0.972258 1.22251 0.148384 - -0.977397 1.15482 0.147632 - -0.985893 1.10494 0.146515 - -0.991964 1.06413 0.145706 - -0.994709 1.03948 0.145328 - -1.29588 -1.32688 0.0876848 - -1.29476 -1.40937 0.0876673 - -1.30192 -1.53393 0.0864655 - -1.30786 -1.58246 0.0855794 - -1.3173 -1.62254 0.0842459 - -1.32273 -1.68861 0.0833913 - -0.273772 -0.373153 0.225277 - -0.233684 -0.365521 0.230613 - -0.22219 -0.360931 0.232148 - -0.217487 -0.363762 0.232767 - -0.217906 -0.368149 0.232702 - -0.172474 -0.370476 0.238728 - -0.153561 -0.375347 0.241229 - -0.100718 -0.372806 0.248248 - -0.0954051 -0.37929 0.24894 - -0.0840954 -0.374688 0.25045 - -0.074345 -0.376636 0.25174 - -0.0734169 -0.380873 0.251855 - -0.0476614 -0.391688 0.255252 - 0.0374887 -0.39262 0.266552 - 0.0782444 -0.404284 0.271938 - 0.0966249 -0.404094 0.274378 - 0.104385 -0.405129 0.275406 - 0.128749 -0.415513 0.278619 - 0.132033 -0.401744 0.279083 - 0.140592 -0.409304 0.280204 - 0.156556 -0.413916 0.282313 - 0.169958 -0.415939 0.284088 - 0.174341 -0.416213 0.28467 - 0.180542 -0.415626 0.285494 - 0.189822 -0.41681 0.286723 - 0.249664 -0.427539 0.294644 - 0.287804 -0.433744 0.299694 - 0.351162 -0.435706 0.3081 - 0.412521 -0.443622 0.316229 - 0.579115 -0.468324 0.338291 - 0.836193 -0.50927 0.372331 - 0.967772 -0.526564 0.389761 - 1.60421 -0.605729 0.474078 - 1.73106 -0.5762 0.490975 - 1.7412 -0.537268 0.492399 - 1.7419 -0.495726 0.492575 - 1.73954 -0.380852 0.492495 - 1.75016 -0.358971 0.493948 - 1.76044 -0.352989 0.495325 - 6.71093 -0.947159 1.15122 - 6.73639 -0.860151 1.15478 - 6.10431 -0.480555 1.07164 - 6.79929 -0.0848725 1.16469 - 2.98359 0.199839 0.658793 - 2.98954 0.253269 0.65969 - 3.00015 0.347699 0.661289 - 2.99989 0.42835 0.661417 - 1.78515 0.34433 0.500012 - 1.36916 0.327618 0.444762 - 1.22837 0.322893 0.426065 - 1.09667 0.31972 0.408578 - 1.4317 0.521782 0.453456 - 1.36498 0.624064 0.444805 - 1.31633 0.630157 0.43836 - 1.27869 0.626107 0.433357 - 1.157 0.631313 0.417214 - 1.11935 0.623704 0.412202 - 1.02899 0.646948 0.400255 - 0.948611 0.638186 0.389568 - 0.637878 0.494391 0.348033 - 0.623945 0.488079 0.346171 - 0.308597 0.266344 0.303867 - 0.392441 0.391752 0.315249 - 0.299089 0.307814 0.302688 - 0.290921 0.30751 0.301604 - 0.280802 0.335811 0.300318 - 0.289401 0.352066 0.301492 - 0.75769 1.02361 0.365004 - 0.770903 1.11038 0.366933 - 0.740168 1.12802 0.362889 - 0.59522 1.04136 0.343475 - 0.147899 0.332727 0.282671 - 0.148633 0.354338 0.282812 - 0.151437 0.365104 0.283206 - 0.445191 1.25294 0.323988 - 0.387311 1.2611 0.316322 - 0.362906 1.2592 0.313078 - 0.238183 1.16222 0.296328 - 0.251523 1.28095 0.298338 - 0.178127 1.28668 0.288608 - 0.1335 1.29237 0.282696 - 0.0830937 1.2969 0.276014 - 0.0439044 1.30203 0.270823 - -0.0348942 1.29867 0.260357 - -0.109328 1.31386 0.250508 - -0.130185 1.05355 0.247214 - -0.0552227 0.343372 0.255731 - -0.0536207 0.296063 0.255848 - -0.0730628 0.28807 0.253252 - -0.255064 0.68955 0.229904 - -0.2577 0.687508 0.22955 - -0.264462 0.678522 0.228634 - -0.139081 0.272551 0.244458 - -0.860499 1.40452 0.150985 - -0.943624 1.38715 0.139917 - -0.952191 1.37392 0.138753 - -0.95437 1.33934 0.138394 - -0.966255 1.24937 0.136635 - -0.994841 1.05905 0.132457 - -1.30811 -1.51641 0.0686497 - -1.30459 -1.56675 0.0690615 - -1.31045 -1.61634 0.0681079 - -1.31954 -1.67183 0.06667 - -0.280206 -0.382057 0.220816 - -0.24333 -0.366467 0.226225 - -0.191456 -0.364633 0.233792 - -0.165831 -0.376821 0.237503 - -0.0906963 -0.387651 0.248437 - -0.0840694 -0.372731 0.249433 - -0.0680683 -0.376806 0.251758 - -0.0610471 -0.386004 0.252763 - -0.050222 -0.380377 0.254353 - -0.0413385 -0.392372 0.255624 - -0.0355634 -0.383834 0.256483 - -0.0139824 -0.384914 0.259627 --0.00895032 -0.378987 0.260373 - 0.0129942 -0.392533 0.263545 - 0.0365508 -0.405733 0.266953 - 0.0579626 -0.394751 0.270097 - 0.0717592 -0.402409 0.272094 - 0.0786965 -0.400978 0.273108 - 0.0916052 -0.409295 0.274973 - 0.101576 -0.397413 0.276451 - 0.114258 -0.415613 0.278263 - 0.116051 -0.415079 0.278526 - 0.117888 -0.408251 0.278808 - 0.125284 -0.413243 0.279876 - 0.140479 -0.411186 0.282096 - 0.169742 -0.412408 0.28636 - 0.178295 -0.417354 0.287597 - 0.240631 -0.426553 0.296667 - 0.274006 -0.426743 0.301533 - 0.304839 -0.435586 0.306011 - 0.308464 -0.436638 0.306537 - 0.310931 -0.436053 0.306898 - 0.325755 -0.432263 0.309067 - 0.355045 -0.441875 0.313318 - 0.373514 -0.440471 0.316014 - 0.423874 -0.445223 0.323347 - 0.477832 -0.455219 0.331194 - 0.626 -0.471825 0.352764 - 0.636815 -0.475532 0.354334 - 0.712707 -0.484484 0.365381 - 0.726351 -0.48903 0.367361 - 0.896187 -0.514904 0.392072 - 0.954858 -0.531748 0.400592 - 1.66667 -0.742241 0.503953 - 1.67712 -0.738044 0.505485 - 1.47376 -0.618094 0.476076 - 1.45681 -0.588482 0.473664 - 1.51442 -0.596181 0.482049 - 1.73294 -0.603628 0.513895 - 1.73381 -0.552922 0.514124 - 1.73567 -0.536684 0.514429 - 1.73867 -0.512484 0.514914 - 1.75145 -0.449662 0.516905 - 1.75045 -0.432962 0.516793 - 1.77189 -0.331638 0.520123 - 6.73382 -0.891634 1.24247 - 6.15063 -0.321532 1.15859 - 6.82171 -0.0250936 1.25703 - 6.83146 0.125634 1.25876 - 2.97201 0.120437 0.696021 - 3.00182 0.429469 0.700993 - 1.83787 0.338378 0.531099 - 1.09226 0.319167 0.422346 - 1.08946 0.328842 0.421957 - 1.44239 0.512413 0.473787 - 1.42952 0.522121 0.471931 - 1.3588 0.530669 0.461636 - 1.34635 0.532689 0.459826 - 1.38719 0.613501 0.465943 - 1.36289 0.624475 0.462422 - 1.27051 0.616567 0.448937 - 1.25447 0.622535 0.44661 - 1.08696 0.632485 0.422206 - 0.862928 0.593382 0.389463 - 0.662906 0.483055 0.360075 - 0.657603 0.483661 0.359303 - 0.337919 0.274511 0.312269 - 0.305832 0.274461 0.307591 - 0.302249 0.278565 0.307076 - 0.280398 0.305592 0.303945 - 0.746454 1.1297 0.373564 - 0.378255 1.25518 0.320132 - 0.305308 1.26743 0.309521 - 0.199269 1.28226 0.29409 - 0.126591 1.288 0.283505 - 0.120538 1.2836 0.282613 - -0.0695714 1.30844 0.254945 - -0.0600755 0.411409 0.254516 - -0.0548869 0.348538 0.255146 - -0.0580792 0.296389 0.254575 - -0.212241 0.77452 0.233064 - -0.215583 0.773604 0.232575 - -0.223333 0.775578 0.231449 - -0.240699 0.785035 0.228936 - -0.27861 0.786225 0.22341 - -0.163067 0.368319 0.239413 - -0.141075 0.309276 0.2425 - -0.130263 0.274717 0.244006 - -0.961368 1.27871 0.124856 - -0.980875 1.11148 0.121674 - -0.994192 1.03224 0.119572 - -1.30831 -1.45326 0.0547198 - -1.30505 -1.5282 0.0550783 - -1.31447 -1.60903 0.053439 - -1.31908 -1.6734 0.0525879 - -1.32629 -1.80884 0.0511842 - -0.243327 -0.362914 0.223678 - -0.210935 -0.36657 0.228742 - -0.205228 -0.367494 0.229634 - -0.199069 -0.367447 0.230598 - -0.15894 -0.368992 0.236879 - -0.148272 -0.370111 0.238547 - -0.141609 -0.376916 0.239576 - -0.137696 -0.37621 0.24019 - -0.115825 -0.374978 0.243617 - -0.0997937 -0.387634 0.246102 - -0.0822482 -0.396633 0.248831 - -0.0549718 -0.388901 0.253117 - -0.0476193 -0.383735 0.254279 - -0.0329067 -0.388071 0.256574 - -0.0273909 -0.379404 0.257455 --0.00609815 -0.387999 0.260771 --0.00281092 -0.381982 0.261298 - 0.0698419 -0.404713 0.272628 - 0.085617 -0.39415 0.275119 - 0.108565 -0.404606 0.278691 - 0.114302 -0.411244 0.279576 - 0.124282 -0.406004 0.281149 - 0.126031 -0.405423 0.281424 - 0.153969 -0.411126 0.285787 - 0.163174 -0.40841 0.287234 - 0.177337 -0.411981 0.289444 - 0.186523 -0.413193 0.29088 - 0.196189 -0.419587 0.292381 - 0.216054 -0.418259 0.295494 - 0.222031 -0.42066 0.296425 - 0.361642 -0.439351 0.318247 - 0.376376 -0.444996 0.320542 - 0.409601 -0.446913 0.325741 - 0.449002 -0.448344 0.331907 - 0.464085 -0.451214 0.334263 - 0.600651 -0.470734 0.355606 - 0.637757 -0.477304 0.361403 - 0.667324 -0.476719 0.366034 - 0.722725 -0.483058 0.374695 - 0.761875 -0.489826 0.380812 - 0.922937 -0.520486 0.405968 - 0.952579 -0.526077 0.410598 - 1.01817 -0.533127 0.420853 - 1.60673 -0.786027 0.512496 - 1.6676 -0.752857 0.522094 - 1.66701 -0.70877 0.522091 - 1.43959 -0.590065 0.486723 - 1.72802 -0.57745 0.531909 - 1.73292 -0.562109 0.532708 - 1.73703 -0.521305 0.533434 - 1.75014 -0.441908 0.535648 - 1.73877 -0.390255 0.533971 - 6.71974 -0.891245 1.31286 - 6.73306 -0.772183 1.31519 - 6.14759 -0.513025 1.22404 - 6.14758 -0.40372 1.22426 - 6.81535 -0.0251118 1.32958 - 2.98634 0.253938 0.730615 - 1.97558 0.328247 0.572504 - 1.39285 0.328107 0.481263 - 1.22131 0.32239 0.454392 - 1.07632 0.341226 0.431728 - 1.4402 0.519799 0.489065 - 1.4333 0.524491 0.487994 - 1.39721 0.525399 0.482346 - 1.33823 0.53051 0.473121 - 1.39722 0.633914 0.482566 - 1.3243 0.615138 0.471111 - 1.27694 0.620879 0.463708 - 1.24843 0.627645 0.459257 - 1.06818 0.635545 0.43105 - 0.661052 0.478366 0.366985 - 0.656134 0.497164 0.366253 - 0.643936 0.496975 0.364343 - 0.342356 0.278848 0.316681 - 0.321836 0.26481 0.31344 - 0.305403 0.267724 0.310873 - 0.28317 0.332 0.307521 - 0.622777 0.753772 0.36155 - 0.754625 1.16633 0.383029 - 0.147829 0.332048 0.28633 - 0.440957 1.24824 0.334082 - 0.424125 1.25218 0.331454 - 0.388888 1.25459 0.325942 - 0.338601 1.26454 0.318088 - 0.332628 1.26412 0.317152 - 0.326666 1.26367 0.316218 - 0.239466 1.15233 0.302339 - 0.238993 1.17493 0.302311 - 0.245902 1.26233 0.303569 - 0.198162 1.28028 0.296131 - 0.192641 1.28118 0.295268 - 0.142216 1.28315 0.287377 - 0.0815594 1.2939 0.277901 - -0.0755752 1.30815 0.253327 - -0.0513302 0.310717 0.255104 - -0.0530109 0.295284 0.254809 - -0.0553907 0.293877 0.254434 - -0.06904 0.296332 0.252302 - -0.11638 0.436072 0.245172 - -0.251917 0.6897 0.224464 - -0.142113 0.274645 0.240816 - -0.911474 1.39426 0.122619 - -0.935552 1.4045 0.11887 - -0.943586 1.32713 0.117455 - -0.949297 1.32298 0.116553 - -0.953245 1.31638 0.115921 - -0.969265 1.23381 0.113246 - -0.981474 1.1432 0.111151 - -0.990074 1.07506 0.109666 - -0.992996 1.05034 0.109159 - -1.31012 -1.60594 0.0398909 - -1.33046 -1.78433 0.0361227 - -0.279003 -0.380438 0.215082 - -0.222883 -0.368844 0.224506 - -0.196454 -0.370023 0.22893 - -0.175362 -0.367178 0.232468 - -0.172544 -0.365195 0.232944 - -0.167 -0.374278 0.233855 - -0.154193 -0.375347 0.235997 - -0.138446 -0.367516 0.238651 - -0.136863 -0.368095 0.238915 - -0.134013 -0.370176 0.239388 - -0.112296 -0.374008 0.243018 - -0.0960978 -0.371118 0.245737 - -0.0940413 -0.369564 0.246084 - -0.0901291 -0.374592 0.246729 - -0.0852857 -0.375666 0.247538 - -0.0714554 -0.373289 0.24986 - -0.0547038 -0.383941 0.252644 - 0.018692 -0.390143 0.264925 - 0.0203706 -0.390027 0.265206 - 0.0224936 -0.395886 0.26555 - 0.0640269 -0.395532 0.272507 - 0.0870694 -0.402909 0.276352 - 0.0952086 -0.406032 0.277709 - 0.118064 -0.413031 0.281522 - 0.143009 -0.410817 0.285705 - 0.152207 -0.413694 0.28724 - 0.167518 -0.410571 0.289811 - 0.223107 -0.424166 0.299094 - 0.261647 -0.426558 0.305544 - 0.298333 -0.429097 0.311684 - 0.304821 -0.434212 0.31276 - 0.44374 -0.448249 0.336 - 0.515326 -0.459512 0.347967 - 0.629849 -0.472578 0.367123 - 0.795827 -0.497872 0.394872 - 0.852738 -0.512487 0.404374 - 0.920381 -0.525561 0.415678 - 0.947029 -0.524171 0.420144 - 0.97067 -0.526026 0.4241 - 1.60353 -0.786027 0.529572 - 1.59742 -0.606777 0.528913 - 1.75048 -0.434621 0.554899 - 1.76071 -0.355127 0.556773 - 1.7792 -0.342448 0.559896 - 6.70678 -0.921344 1.38406 - 6.71067 -0.891634 1.38477 - 3.04244 0.0832116 0.772343 - 2.99847 0.403451 0.765629 - 2.99292 0.429749 0.764753 - 2.04226 0.330647 0.605322 - 1.57339 0.334525 0.526797 - 1.53625 0.333795 0.520574 - 1.39342 0.525052 0.497039 - 1.25382 0.62473 0.473859 - 1.11637 0.632533 0.450853 - 1.05274 0.640407 0.440211 - 0.997744 0.637702 0.430994 - 0.974758 0.635273 0.427139 - 0.652596 0.504806 0.372915 - 0.650416 0.50772 0.372555 - 0.372014 0.300722 0.325505 - 0.307833 0.268274 0.314689 - 0.297199 0.280601 0.312933 - 0.287365 0.312278 0.31135 - 0.286018 0.313577 0.311127 - 0.31102 0.371551 0.315432 - 0.325492 0.391905 0.317898 - 0.692698 0.846993 0.380325 - 0.748018 1.10567 0.390116 - 0.16125 0.318125 0.290239 - 0.144837 0.319859 0.287493 - 0.149457 0.352967 0.288334 - 0.1853 0.454943 0.294544 - 0.261076 1.15949 0.308665 - 0.130973 1.28939 0.287137 - 0.114315 1.29112 0.28435 - 0.0364147 1.29824 0.271317 - -0.0532568 1.30517 0.256312 - -0.0559911 0.374729 0.253967 - -0.0554463 0.300011 0.253907 - -0.0567368 0.299794 0.25369 - -0.0664318 0.294913 0.252056 - -0.192903 0.725973 0.231747 - -0.401526 1.24544 0.197857 - -0.406881 1.24369 0.196957 - -0.256607 0.693308 0.221011 - -0.304416 0.717252 0.213052 - -0.143787 0.271656 0.239052 - -0.143597 0.268382 0.239078 - -0.147282 0.269817 0.238463 - -0.958087 1.30074 0.104749 - -0.976214 1.16903 0.101446 - -0.99144 1.06851 0.0986917 - -1.29429 -1.49335 0.0290641 - -1.31621 -1.63029 0.0248816 - -1.32538 -1.81286 0.022876 - -0.271557 -0.373518 0.213528 - -0.253449 -0.364445 0.216772 - -0.223488 -0.366169 0.222105 - -0.216274 -0.364692 0.223393 - -0.202015 -0.372747 0.225917 - -0.125819 -0.377236 0.239482 - -0.120166 -0.382154 0.240479 - -0.116016 -0.374019 0.241234 - -0.109504 -0.382131 0.242378 - -0.0989248 -0.361186 0.244305 - -0.0989008 -0.374601 0.244282 - -0.0758569 -0.37762 0.248381 - -0.0338018 -0.390066 0.255847 - -0.02828 -0.3814 0.256849 - -0.0119874 -0.390969 0.259732 - 0.0340139 -0.395789 0.267916 - 0.0604157 -0.398114 0.272615 - 0.078916 -0.401578 0.275903 - 0.0906451 -0.404977 0.277986 - 0.095855 -0.403641 0.278917 - 0.134708 -0.406173 0.285833 - 0.143689 -0.414569 0.287416 - 0.145468 -0.413896 0.287734 - 0.152491 -0.405771 0.289001 - 0.170684 -0.419756 0.292214 - 0.176247 -0.412892 0.293219 - 0.190303 -0.410602 0.295727 - 0.199105 -0.419571 0.297277 - 0.205397 -0.418569 0.2984 - 0.269466 -0.427974 0.309794 - 0.382564 -0.446838 0.329903 - 0.517695 -0.46279 0.353943 - 0.564822 -0.461483 0.36234 - 0.615529 -0.471618 0.371353 - 0.619132 -0.470042 0.371998 - 0.664921 -0.477292 0.38014 - 0.735871 -0.484705 0.392764 - 0.851277 -0.507674 0.413275 - 1.63544 -0.785379 0.552401 - 1.57878 -0.699032 0.542483 - 1.45377 -0.598291 0.520419 - 1.65019 -0.611334 0.555383 - 1.74792 -0.443114 0.573133 - 1.74691 -0.361156 0.57312 - 2.99763 0.363527 0.797393 - 2.99597 0.444604 0.797263 - 1.84993 0.33408 0.592884 - 1.27615 0.32609 0.490656 - 1.09326 0.348062 0.45812 - 1.07616 0.353222 0.455085 - 1.07589 0.363756 0.455058 - 1.345 0.528515 0.503332 - 1.27867 0.5356 0.49153 - 1.27636 0.541296 0.49113 - 1.35009 0.622418 0.504429 - 1.3036 0.622215 0.496146 - 1.05061 0.634188 0.451103 - 0.900939 0.605985 0.424385 - 0.651567 0.500685 0.379748 - 0.341025 0.279468 0.323979 - 0.317897 0.265631 0.319831 - 0.294657 0.271897 0.315703 - 0.284961 0.30536 0.314044 - 0.285737 0.314303 0.314201 - 0.713717 0.890214 0.39161 - 0.715103 0.916116 0.39191 - 0.726333 0.964391 0.394008 - 0.737144 0.98748 0.395981 - 0.743655 1.04248 0.397253 - 0.747307 1.21756 0.398259 - 0.739985 1.2175 0.396955 - 0.145986 0.331143 0.28934 - 0.460905 1.24294 0.347291 - 0.444845 1.24906 0.344443 - 0.336993 1.26646 0.325266 - 0.318145 1.26127 0.321897 - 0.312233 1.26076 0.320843 - 0.21849 1.27647 0.304176 - 0.180004 1.28289 0.297333 - 0.13006 1.2874 0.288445 - 0.0915165 1.29407 0.281593 - 0.0693842 1.29763 0.277657 - 0.0580309 1.29427 0.275628 - 0.0191483 1.29871 0.268711 - 0.0134886 1.29382 0.267692 - -0.0199876 1.30694 0.261756 - -0.0703478 1.30245 0.252775 - -0.0988628 1.30873 0.247709 - -0.109789 1.30389 0.245752 - -0.115389 1.30343 0.244754 - -0.229363 0.783263 0.223394 - -0.237487 0.786061 0.221952 - -0.389981 1.2281 0.195685 - -0.262108 0.671989 0.217335 - -0.302393 0.703967 0.210223 - -0.143701 0.313851 0.2377 - -0.134561 0.27633 0.239252 - -0.134063 0.272147 0.239332 - -0.928294 1.39702 0.100134 - -0.951285 1.36647 0.0959764 - -1.28691 -1.38631 0.0171472 - -1.30056 -1.52972 0.01428 - -1.32305 -1.70118 0.00968954 - -1.32782 -1.72278 0.00874501 - -0.241157 -0.359577 0.216515 - -0.23598 -0.361815 0.217487 - -0.224331 -0.374968 0.219658 - -0.221239 -0.373334 0.220245 - -0.20307 -0.363109 0.223693 - -0.192762 -0.366411 0.225631 - -0.187595 -0.36795 0.226603 - -0.171206 -0.365925 0.229699 - -0.143662 -0.371022 0.234884 - -0.135997 -0.374898 0.236322 - -0.128232 -0.378609 0.23778 - -0.0989058 -0.373631 0.243322 - -0.0886871 -0.381179 0.245234 - -0.0834245 -0.372093 0.246246 - -0.0772133 -0.374364 0.247413 - -0.0664093 -0.390446 0.249418 - -0.0572618 -0.385708 0.251154 - -0.0427867 -0.392372 0.253871 - -0.0373564 -0.387822 0.254904 - -0.0139707 -0.384945 0.259322 - 0.0519131 -0.403474 0.271713 - 0.0672477 -0.399801 0.274613 - 0.0700924 -0.405354 0.275139 - 0.0718296 -0.405005 0.275467 - 0.092025 -0.405509 0.279276 - 0.0954982 -0.404609 0.279933 - 0.119674 -0.403721 0.284495 - 0.122514 -0.400676 0.285037 - 0.132615 -0.407742 0.286928 - 0.200993 -0.420438 0.299802 - 0.205942 -0.421236 0.300734 - 0.217738 -0.421665 0.302958 - 0.250941 -0.428686 0.309208 - 0.305981 -0.430635 0.319587 - 0.318044 -0.435172 0.321853 - 0.333418 -0.43566 0.324752 - 0.348329 -0.442689 0.327551 - 0.375477 -0.43616 0.332686 - 0.437946 -0.448831 0.344445 - 0.499304 -0.459749 0.355997 - 0.562896 -0.465264 0.367983 - 0.596138 -0.470734 0.374242 - 0.641901 -0.475098 0.382867 - 0.658798 -0.478537 0.386047 - 0.709741 -0.482414 0.39565 - 0.775719 -0.492482 0.408075 - 0.829674 -0.506072 0.418226 - 0.855214 -0.511196 0.423034 - 0.910679 -0.517097 0.433485 - 1.28656 -0.655399 0.504112 - 1.52346 -0.716868 0.548679 - 1.72803 -0.589537 0.587528 - 1.74339 -0.501141 0.590605 - 1.74666 -0.48531 0.591256 - 1.74989 -0.461152 0.591914 - 1.74372 -0.401919 0.590869 - 6.71071 -0.895009 1.52688 - 2.96905 0.147718 0.823144 - 2.97682 0.254606 0.824828 - 3.00224 0.405551 0.82993 - 2.97246 0.455534 0.824413 - 1.89632 0.325726 0.621139 - 1.80832 0.343945 0.604575 - 1.38691 0.328784 0.525046 - 1.35966 0.328767 0.519907 - 1.09227 0.34318 0.469492 - 1.39113 0.526439 0.526245 - 1.28442 0.545896 0.506155 - 1.38294 0.616696 0.524884 - 1.19369 0.624216 0.489197 - 1.03534 0.632729 0.459343 - 0.99176 0.630616 0.451117 - 0.982383 0.630805 0.449348 - 0.718328 0.557817 0.399387 - 0.293946 0.28937 0.318782 - 0.284361 0.285119 0.316965 - 0.291869 0.30021 0.318412 - 0.281935 0.303209 0.316544 - 0.287413 0.322745 0.317617 - 0.588789 0.71218 0.375264 - 0.588266 0.717878 0.375176 - 0.768917 1.20817 0.410254 - 0.734509 1.21156 0.40377 - 0.153845 0.320165 0.292415 - 0.148409 0.341793 0.291433 - 0.493654 1.2356 0.358382 - 0.483038 1.24001 0.356388 - 0.392895 1.25949 0.339423 - 0.379428 1.25442 0.336872 - 0.251809 1.14995 0.312584 - 0.246875 1.15109 0.311656 - 0.249785 1.26707 0.312441 - 0.200539 1.27542 0.303168 - 0.195695 1.28028 0.302264 - 0.101641 1.28916 0.284539 - 0.085049 1.29051 0.281412 - 0.0132119 1.30681 0.267893 --0.00920213 1.306 0.263663 - -0.0820709 1.30584 0.249916 - -0.121656 1.30792 0.242453 - -0.122272 1.09687 0.241907 - -0.0514792 0.313882 0.253668 - -0.0598126 0.298358 0.252065 - -0.0621888 0.296902 0.251613 - -0.217217 0.778427 0.223348 - -0.228298 0.779419 0.221259 - -0.411034 1.24001 0.187724 - -0.316536 0.896655 0.204852 - -0.266085 0.739782 0.21405 - -0.272514 0.67319 0.212702 - -0.18184 0.312329 0.229073 - -0.946029 1.38631 0.0870969 - -0.952435 1.32042 0.0857543 - -0.970404 1.18605 0.0820909 - -0.990086 1.06997 0.0781417 - -1.27822 -1.33183 0.00530955 - -0.265786 -0.368985 0.209092 - -0.230709 -0.356919 0.216109 - -0.21931 -0.381372 0.218331 - -0.214139 -0.379737 0.219365 - -0.196636 -0.370023 0.222874 - -0.177317 -0.370805 0.226724 - -0.157922 -0.369662 0.230592 - -0.155338 -0.377205 0.231092 - -0.136783 -0.371495 0.234802 - -0.134225 -0.369232 0.235317 - -0.100739 -0.373222 0.241984 - -0.0967971 -0.385523 0.242745 - -0.0760667 -0.375653 0.246897 - -0.0307778 -0.3833 0.255909 - -0.0260391 -0.387566 0.256845 - -0.0243804 -0.387642 0.257176 --0.00778225 -0.387999 0.260484 - 0.049917 -0.393585 0.271974 - 0.0902176 -0.400659 0.279993 - 0.100578 -0.405129 0.282049 - 0.139215 -0.406127 0.289749 - 0.162762 -0.409497 0.294436 - 0.201064 -0.417726 0.302055 - 0.214601 -0.421781 0.304745 - 0.217341 -0.422543 0.305289 - 0.219619 -0.422413 0.305744 - 0.251584 -0.422983 0.312115 - 0.287018 -0.429016 0.319166 - 0.28885 -0.427699 0.319534 - 0.342232 -0.436497 0.330157 - 0.347844 -0.439562 0.331269 - 0.349721 -0.437974 0.331647 - 0.434549 -0.446721 0.348538 - 0.437856 -0.446148 0.349199 - 0.520276 -0.459417 0.365601 - 0.546234 -0.465198 0.370764 - 0.618593 -0.4764 0.385165 - 0.682173 -0.478435 0.397835 - 0.879567 -0.516399 0.437106 - 1.00407 -0.536263 0.461884 - 1.51412 -0.594479 0.563439 - 1.72758 -0.582137 0.606016 - 1.73005 -0.57441 0.606525 - 1.7399 -0.484523 0.608671 - 1.74858 -0.412158 0.610549 - 6.73056 -0.838586 1.60279 - 6.82632 0.00506333 1.6236 - 6.84462 0.0660578 1.62737 - 2.97422 0.188224 0.856091 - 3.00035 0.3518 0.861635 - 2.99608 0.432827 0.860949 - 1.95347 0.327278 0.652899 - 1.4329 0.333658 0.549142 - 1.08046 0.356278 0.478933 - 1.28373 0.540152 0.519828 - 1.39771 0.632145 0.542736 - 1.27726 0.619476 0.518699 - 1.03974 0.630631 0.471375 - 0.65952 0.486542 0.395287 - 0.65743 0.489509 0.394877 - 0.663255 0.498351 0.396056 - 0.30661 0.272251 0.324501 - 0.293939 0.28532 0.322002 - 0.290249 0.28933 0.321275 - 0.292694 0.296842 0.321777 - 0.278875 0.301059 0.319031 - 0.709583 0.973269 0.40626 - 0.762353 1.18969 0.41722 - 0.736726 1.21835 0.41217 - 0.731505 1.22165 0.411136 - 0.158559 0.324029 0.295094 - 0.412825 1.25123 0.347671 - 0.391644 1.25949 0.343465 - 0.333985 1.26357 0.33198 - 0.234763 1.28218 0.312239 - 0.216894 1.27745 0.308667 - 0.205787 1.27842 0.306455 - 0.172892 1.28371 0.299909 - 0.155889 1.28206 0.296516 - 0.150401 1.28278 0.295423 - 0.0623089 1.29197 0.277882 - 0.00705501 1.3009 0.266886 - -0.0319498 1.30278 0.259114 - -0.0375243 1.30267 0.258003 - -0.115954 1.30442 0.242372 - -0.126296 1.29446 0.24029 - -0.0573582 0.289717 0.251983 - -0.232734 0.782273 0.218028 - -0.409019 1.25319 0.183848 - -0.414377 1.2514 0.182776 - -0.26701 0.676445 0.21098 - -0.164631 0.370156 0.230764 - -0.132753 0.268531 0.236911 - -0.141677 0.275241 0.235146 - -0.154045 0.273204 0.232676 - -0.175634 0.301019 0.228429 - -0.648037 1.10499 0.1359 - -0.945304 1.40037 0.077245 - -0.944039 1.35992 0.0774146 - -0.954083 1.30074 0.0752918 - -0.950235 1.28371 0.076024 - -0.95821 1.27131 0.0744091 - -0.973169 1.20192 0.0712856 - -0.98198 1.13004 0.0693827 - -0.985228 1.10433 0.0686828 - -0.984688 1.08455 0.0687501 - -0.988639 1.04237 0.0678765 - -1.29643 -1.42627 -0.0124358 - -1.29931 -1.45474 -0.0130993 - -1.3159 -1.59511 -0.0168723 - -1.33614 -1.75552 -0.0214541 - -1.33611 -1.83699 -0.0216148 - -0.156813 -0.371251 0.229205 - -0.141432 -0.374096 0.232432 - -0.131531 -0.371287 0.234518 - -0.126359 -0.377236 0.235593 - -0.112873 -0.379284 0.238422 - -0.0973074 -0.372089 0.241708 - -0.091449 -0.383745 0.242916 - -0.0777636 -0.374364 0.245811 - -0.0554246 -0.393082 0.250467 - -0.0520658 -0.393486 0.251172 - -0.01153 -0.389987 0.259697 --0.00986474 -0.389997 0.260047 - 0.0148563 -0.385262 0.265252 - 0.0290438 -0.395144 0.268213 - 0.0307306 -0.394973 0.268568 - 0.0723195 -0.395474 0.277307 - 0.0843292 -0.39374 0.279834 - 0.100188 -0.406094 0.283141 - 0.1274 -0.408025 0.288856 - 0.183857 -0.415906 0.300704 - 0.214639 -0.423542 0.307157 - 0.291333 -0.428816 0.323263 - 0.294306 -0.429097 0.323888 - 0.354819 -0.441737 0.336578 - 0.489322 -0.457315 0.364812 - 0.549352 -0.460877 0.377419 - 0.606985 -0.473171 0.389506 - 0.715798 -0.479833 0.412359 - 0.738036 -0.485164 0.417021 - 0.775369 -0.499661 0.424837 - 0.789233 -0.493798 0.427762 - 0.838519 -0.508939 0.438088 - 0.864032 -0.513851 0.44344 - 0.910691 -0.525073 0.453222 - 1.05201 -0.545181 0.482878 - 1.6317 -0.608603 0.604569 - 1.71422 -0.613263 0.621899 - 1.73455 -0.543101 0.626316 - 1.74949 -0.446492 0.629653 - 6.72988 -0.749008 1.67564 - 2.96731 0.134987 0.886761 - 2.98964 0.283776 0.891757 - 2.98709 0.310502 0.891276 - 2.99256 0.351686 0.89251 - 2.99224 0.446911 0.892636 - 1.74274 0.341147 0.629844 - 1.08977 0.333397 0.492609 - 1.34521 0.539225 0.546709 - 1.28491 0.555503 0.534071 - 1.37886 0.603146 0.553912 - 1.24849 0.620886 0.526551 - 1.24319 0.625169 0.525445 - 1.23875 0.62986 0.524522 - 1.23604 0.635417 0.523965 - 1.1686 0.627466 0.509777 - 0.822549 0.536899 0.43687 - 0.699832 0.462066 0.410928 - 0.731799 0.550716 0.417827 - 0.727642 0.573154 0.416999 - 0.302732 0.277088 0.327101 - 0.304485 0.281113 0.327478 - 0.291919 0.281944 0.324839 - 0.28336 0.317786 0.323114 - 0.508107 0.61401 0.370949 - 0.553843 0.757414 0.380853 - 0.684386 1.00417 0.40879 - 0.764819 1.20817 0.42611 - 0.167926 0.322954 0.298866 - 0.166545 0.323739 0.298578 - 0.154132 0.320331 0.295962 - 0.151389 0.321772 0.295389 - 0.15811 0.383812 0.296928 - 0.479383 1.23815 0.366188 - 0.458508 1.24761 0.361821 - 0.446468 1.24798 0.359291 - 0.429121 1.25021 0.35565 - 0.411796 1.25218 0.352014 - 0.344122 1.2624 0.337813 - 0.337669 1.26011 0.336452 - 0.222302 1.28135 0.312252 - 0.217347 1.28532 0.311219 - 0.150957 1.29369 0.297284 - 0.0894223 1.29208 0.28435 - 0.067456 1.29563 0.279741 - 0.0065801 1.3019 0.266961 - -0.0268881 1.30987 0.259944 - -0.120625 1.29098 0.240207 - -0.0503792 0.30101 0.252946 - -0.0512395 0.297853 0.252758 - -0.0653624 0.296409 0.249788 - -0.0660514 0.293212 0.249636 - -0.198107 0.758766 0.222837 - -0.223879 0.77654 0.217457 - -0.398178 1.23878 0.181774 - -0.408433 1.23431 0.179609 - -0.417815 1.20996 0.177588 - -0.27377 0.762399 0.206944 - -0.278414 0.671741 0.205783 - -0.595997 1.03706 0.139791 - -0.824197 1.38372 0.0925438 - -0.851135 1.388 0.0868918 - -0.942842 1.3731 0.0675894 - -0.94757 1.36728 0.066584 - -0.991317 1.05614 0.0567547 - -1.29185 -1.42407 -0.0259857 - -1.29895 -1.44455 -0.0275986 - -1.31497 -1.66992 -0.0316078 - -1.32689 -1.74682 -0.0344051 - -0.272068 -0.371534 0.202006 - -0.237324 -0.360798 0.209722 - -0.233193 -0.361138 0.210636 - -0.221321 -0.366265 0.213255 - -0.215737 -0.363828 0.214496 - -0.214185 -0.364749 0.214838 - -0.202148 -0.361355 0.217511 - -0.168304 -0.371734 0.224985 - -0.163538 -0.373839 0.226036 - -0.155538 -0.377205 0.2278 - -0.147913 -0.371668 0.2295 - -0.118953 -0.375449 0.235906 - -0.094958 -0.382991 0.241204 - -0.0696921 -0.383986 0.246797 - -0.0610943 -0.382282 0.248705 - -0.0580877 -0.384717 0.249366 - -0.0556328 -0.39209 0.249894 - -0.0450407 -0.387235 0.25225 - -0.0417399 -0.387543 0.25298 - -0.0286142 -0.390478 0.255881 - -0.0166599 -0.375916 0.258558 - -0.0102532 -0.375997 0.259977 --0.00538989 -0.381982 0.261041 - 0.00320936 -0.396805 0.262915 - 0.00900913 -0.376552 0.264241 - 0.0954847 -0.397883 0.283348 - 0.133813 -0.411827 0.291807 - 0.17586 -0.419272 0.301104 - 0.182557 -0.415002 0.302595 - 0.20859 -0.413856 0.308363 - 0.238681 -0.429768 0.314994 - 0.258663 -0.425366 0.319428 - 0.323824 -0.435522 0.333838 - 0.340441 -0.437271 0.337514 - 0.390492 -0.445755 0.348581 - 0.395607 -0.44363 0.349717 - 0.520792 -0.462662 0.377401 - 0.624941 -0.470931 0.400449 - 0.673795 -0.479804 0.411249 - 0.689196 -0.481504 0.414656 - 1.27436 -0.563528 0.544074 - 1.38566 -0.575855 0.568699 - 1.64362 -0.597953 0.625779 - 1.64707 -0.590891 0.626557 - 1.73872 -0.5203 0.646998 - 1.7405 -0.495493 0.647443 - 1.74259 -0.487671 0.647922 - 1.74873 -0.455798 0.649347 - 1.73711 -0.378763 0.646932 - 1.75807 -0.358626 0.651616 - 6.82989 0.0662185 1.77566 - 3.14299 0.0586994 0.959166 - 2.96091 0.135031 0.918999 - 2.97061 0.175527 0.92123 - 1.4761 0.331465 0.590585 - 1.22737 0.322642 0.535485 - 1.09375 0.319491 0.505887 - 1.41831 0.526184 0.578186 - 1.4078 0.529475 0.575865 - 1.19679 0.630581 0.529344 - 1.16358 0.633176 0.521994 - 1.15656 0.636062 0.520446 - 0.772236 0.582488 0.435225 - 0.686648 0.547794 0.416201 - 0.452677 0.380279 0.364044 - 0.308887 0.271358 0.331978 - 0.294953 0.293484 0.328937 - 0.277782 0.29437 0.325136 - 0.48667 0.585268 0.371991 - 0.485813 0.632854 0.371899 - 0.487048 0.663612 0.372236 - 0.519418 0.753533 0.379588 - 0.611327 0.935333 0.400314 - 0.732492 1.21835 0.427727 - 0.222368 0.403414 0.313088 - 0.159202 0.318257 0.298925 - 0.158305 0.319887 0.29873 - 0.306476 0.754561 0.332434 - 0.487936 1.23282 0.373598 - 0.485259 1.24152 0.373023 - 0.479964 1.24372 0.371855 - 0.432287 1.24636 0.361302 - 0.398733 1.25304 0.353885 - 0.35302 1.25728 0.343771 - 0.347932 1.25985 0.342649 - 0.331799 1.26454 0.339086 - 0.29904 1.2486 0.331799 - 0.193321 1.28226 0.308456 - 0.176629 1.28289 0.304761 - 0.138516 1.2901 0.296335 - 0.105315 1.29164 0.288986 - 0.0778429 1.2949 0.282909 - 0.0723255 1.29528 0.281688 - 0.0227093 1.30158 0.270713 - -0.0608286 1.30995 0.25223 - -0.109202 0.926385 0.240732 - -0.0723962 0.297031 0.247594 - -0.231817 0.779394 0.213277 - -0.829672 1.38178 0.0821138 - -0.853765 1.3948 0.0768051 - -0.950611 1.32447 0.055214 - -0.997774 1.04662 0.0442004 - -1.29136 -1.38932 -0.0390598 - -1.2936 -1.49288 -0.0397929 - -1.30179 -1.57017 -0.0418482 - -1.31523 -1.65862 -0.0451468 - -0.278167 -0.380438 0.197857 - -0.252396 -0.36362 0.203865 - -0.250847 -0.364706 0.204221 - -0.249294 -0.365784 0.204579 - -0.247197 -0.366023 0.205065 - -0.234135 -0.362825 0.208099 - -0.220081 -0.371606 0.211339 - -0.193938 -0.364699 0.217412 - -0.171109 -0.37376 0.222685 - -0.161623 -0.373604 0.224884 - -0.144154 -0.371022 0.228939 - -0.143583 -0.374438 0.229064 - -0.116993 -0.380259 0.235215 - -0.108753 -0.362919 0.237161 - -0.105873 -0.370987 0.237812 - -0.100488 -0.376542 0.239048 - -0.0895955 -0.373004 0.241581 - -0.0868239 -0.375666 0.242217 - -0.0752664 -0.375952 0.244896 --0.00733016 -0.397994 0.260597 - 0.00099399 -0.392857 0.262537 - 0.0127892 -0.394348 0.265268 - 0.0450706 -0.395076 0.272749 - 0.0653005 -0.401766 0.277425 - 0.0761429 -0.402555 0.279936 - 0.0827489 -0.39999 0.281473 - 0.117838 -0.412864 0.289579 - 0.189075 -0.421378 0.306074 - 0.262425 -0.432932 0.323052 - 0.264794 -0.432549 0.323601 - 0.268459 -0.430077 0.324456 - 0.308104 -0.435645 0.333634 - 0.309952 -0.434219 0.334065 - 0.325745 -0.4356 0.337723 - 0.394978 -0.444361 0.353752 - 0.416572 -0.448087 0.35875 - 0.51403 -0.458119 0.381319 - 0.518204 -0.457708 0.382287 - 0.592029 -0.468654 0.399377 - 0.682779 -0.482932 0.420382 - 0.764803 -0.490906 0.439378 - 0.809888 -0.499433 0.449811 - 0.891308 -0.50629 0.468669 - 1.1938 -0.555215 0.538683 - 1.74535 -0.506556 0.666625 - 3.0288 0.083938 0.965325 - 2.96496 0.148887 0.950662 - 2.97954 0.230261 0.954208 - 2.98409 0.271108 0.955347 - 1.7387 0.342083 0.666826 - 1.26904 0.328273 0.557936 - 1.3046 0.539399 0.566611 - 1.3612 0.627803 0.579913 - 1.15871 0.638882 0.533001 - 1.14655 0.638896 0.530182 - 1.11461 0.6343 0.522769 - 1.07592 0.631603 0.513794 - 0.586188 0.364484 0.399733 - 0.640074 0.421506 0.41234 - 0.663897 0.462736 0.417947 - 0.592417 0.496806 0.401449 - 0.362332 0.4137 0.347947 - 0.463681 0.550086 0.371719 - 0.536475 0.856763 0.389221 - 0.167156 0.321293 0.302518 - 0.156618 0.321516 0.300076 - 0.140956 0.314017 0.29643 - 0.14907 0.342198 0.298369 - 0.152314 0.357205 0.299151 - 0.442478 1.24517 0.368231 - 0.431874 1.24918 0.365781 - 0.340816 1.25951 0.344696 - 0.251743 1.26885 0.324069 - 0.220881 1.2843 0.316948 - 0.104896 1.29463 0.290085 - 0.0552911 1.29826 0.278595 - 0.0442516 1.2988 0.276037 --0.00545853 1.30199 0.264521 - -0.0330743 1.29878 0.258114 - -0.0556442 1.31216 0.25291 - -0.0609155 0.297373 0.249605 - -0.0681414 0.287795 0.24791 - -0.0699751 0.290464 0.24749 - -0.0720404 0.294099 0.247019 - -0.407513 1.23431 0.171191 - -0.262808 0.721692 0.203679 - -0.257094 0.68657 0.204932 - -0.268373 0.681104 0.202306 - -0.13338 0.275075 0.232762 - -0.140783 0.272551 0.231041 - -0.179176 0.307109 0.222213 - -0.948121 1.37302 0.0461693 - -0.961662 1.30613 0.0428933 - -0.971984 1.16474 0.0402105 - -1.28086 -1.29915 -0.0510709 - -1.28803 -1.34115 -0.0529009 - -1.29008 -1.36698 -0.0534544 - -0.249112 -0.365784 0.201866 - -0.236461 -0.356427 0.204963 - -0.218159 -0.361106 0.209406 - -0.191861 -0.372508 0.21578 - -0.171915 -0.371208 0.220636 - -0.16759 -0.369903 0.221691 - -0.16602 -0.370608 0.222071 - -0.157115 -0.36689 0.224245 - -0.125313 -0.372473 0.231971 - -0.107062 -0.374851 0.236406 - -0.0765634 -0.381857 0.243812 - -0.0556539 -0.387127 0.248888 - -0.0523694 -0.387524 0.249686 - -0.0359702 -0.390066 0.253671 --0.00946384 -0.393999 0.260112 - 0.0263747 -0.401282 0.268816 - 0.0347604 -0.399382 0.27086 - 0.0399597 -0.39974 0.272124 - 0.0612622 -0.402419 0.277301 - 0.0718705 -0.402326 0.279882 - 0.0803782 -0.400398 0.281956 - 0.109282 -0.405921 0.288977 - 0.124364 -0.411471 0.292635 - 0.12642 -0.411812 0.293134 - 0.131645 -0.409943 0.294409 - 0.209073 -0.422768 0.313221 - 0.225378 -0.422636 0.317188 - 0.292456 -0.435325 0.333481 - 0.329951 -0.434921 0.342604 - 0.411782 -0.448552 0.362485 - 0.461037 -0.45113 0.374463 - 0.463659 -0.44969 0.375103 - 0.508545 -0.454875 0.386013 - 0.514921 -0.456417 0.387561 - 0.534187 -0.460749 0.39224 - 0.617054 -0.476578 0.412368 - 0.668086 -0.478672 0.424779 - 0.670911 -0.476186 0.425472 - 0.746263 -0.48537 0.443785 - 0.942979 -0.5204 0.491572 - 1.0745 -0.543207 0.523524 - 1.73342 -0.555601 0.683807 - 1.73635 -0.51386 0.684607 - 1.75742 -0.327518 0.690116 - 6.71047 -0.905394 1.89396 - 2.96557 0.149326 0.985028 - 3.00115 0.424065 0.994251 - 2.00312 0.329704 0.751245 - 1.2761 0.324927 0.574358 - 1.08857 0.33046 0.528744 - 1.35737 0.527383 0.594546 - 1.30165 0.53977 0.581015 - 1.35766 0.591529 0.59475 - 1.38917 0.620004 0.602474 - 0.646427 0.543166 0.421613 - 0.511379 0.4431 0.388551 - 0.423576 0.375069 0.367049 - 0.294929 0.280564 0.335556 - 0.289273 0.292774 0.334205 - 0.286011 0.316011 0.333459 - 0.397744 0.450818 0.360921 - 0.442211 0.513309 0.371867 - 0.527925 0.896672 0.39351 - 0.161212 0.321886 0.303109 - 0.155607 0.370646 0.301846 - 0.453117 1.24574 0.376028 - 0.44783 1.24781 0.374746 - 0.406485 1.24934 0.364691 - 0.239825 1.27115 0.324189 - 0.223634 1.27441 0.320257 - 0.21299 1.27745 0.317673 - 0.142021 1.28645 0.300426 - 0.00508521 1.3009 0.26714 - -0.0059399 1.30299 0.264462 - -0.0169884 1.30298 0.261774 - -0.0445256 1.29953 0.255067 - -0.0555782 1.30017 0.25238 - -0.0780872 1.30815 0.24692 - -0.0607245 0.294419 0.249057 - -0.0655589 0.299605 0.247892 - -0.0680002 0.291974 0.247282 - -0.0708798 0.293398 0.246585 - -0.200501 0.768457 0.216027 - -0.205223 0.773403 0.214888 - -0.210488 0.780255 0.213621 - -0.230263 0.774594 0.208799 - -0.29633 0.829309 0.192838 - -0.256577 0.685632 0.202214 - -0.951237 1.30637 0.0344867 - -0.95893 1.28165 0.0325643 - -0.969393 1.18484 0.0298193 - -0.974896 1.16042 0.0284305 - -0.983671 1.05396 0.0260764 - -1.31185 -1.54888 -0.0768345 - -1.3162 -1.65353 -0.0781668 - -0.310044 -0.422801 0.182844 - -0.188977 -0.362773 0.214068 - -0.153688 -0.367272 0.223125 - -0.152134 -0.367914 0.223522 - -0.148286 -0.376962 0.224492 - -0.131393 -0.374678 0.228837 - -0.110944 -0.375891 0.234087 - -0.107762 -0.376784 0.234903 - -0.100922 -0.383748 0.236646 - -0.0949651 -0.380067 0.238183 - -0.0648253 -0.378833 0.245929 - -0.0609234 -0.386475 0.246915 - -0.0492677 -0.385903 0.249911 - -0.0460044 -0.38624 0.250748 - -0.0230012 -0.384774 0.25666 - -0.0067235 -0.385982 0.260839 - 0.0236237 -0.396459 0.268614 - 0.0339958 -0.398388 0.271274 - 0.0535545 -0.402646 0.27629 - 0.0622857 -0.392925 0.278553 - 0.0639454 -0.392595 0.27898 - 0.081493 -0.400963 0.28347 - 0.117238 -0.404103 0.292646 - 0.124849 -0.409919 0.29459 - 0.130551 -0.415293 0.296043 - 0.171591 -0.411165 0.306594 - 0.184452 -0.415976 0.309888 - 0.186207 -0.415095 0.310341 - 0.189708 -0.413309 0.311244 - 0.210501 -0.419029 0.316574 - 0.227189 -0.419645 0.320859 - 0.281725 -0.429835 0.334848 - 0.295786 -0.434212 0.338451 - 0.433597 -0.44965 0.373821 - 0.458008 -0.458092 0.380075 - 0.465588 -0.461456 0.382015 - 0.488693 -0.459083 0.387955 - 0.649842 -0.472031 0.429326 - 0.828499 -0.504151 0.475155 - 1.00644 -0.528102 0.520816 - 1.18471 -0.548197 0.566571 - 1.18701 -0.542809 0.567173 - 1.18396 -0.535022 0.566405 - 1.56207 -0.589488 0.663425 - 1.73708 -0.550101 0.708465 - 1.74051 -0.516884 0.709414 - 1.74036 -0.491343 0.709428 - 1.75122 -0.435221 0.712335 - 1.73938 -0.3991 0.709366 - 1.74428 -0.37542 0.710674 - 1.76652 -0.346907 0.716446 - 6.6863 -1.08986 1.97875 - 6.75434 -0.728923 1.99697 - 6.75734 -0.698443 1.99781 - 2.96454 0.163217 1.02526 - 2.97252 0.177135 1.02734 - 2.9756 0.190819 1.02816 - 2.97623 0.285621 1.02851 - 2.99929 0.397639 1.03467 - 1.4936 0.331292 0.647738 - 1.09194 0.321941 0.544536 - 1.43834 0.501793 0.633894 - 1.43404 0.514829 0.632815 - 1.40824 0.5272 0.626215 - 1.3136 0.539749 0.601928 - 1.36168 0.595403 0.614394 - 1.37171 0.614468 0.61701 - 1.33196 0.618432 0.606806 - 1.30906 0.622199 0.600931 - 1.17265 0.637176 0.565919 - 0.652048 0.424099 0.431743 - 0.795675 0.611427 0.469026 - 0.288177 0.280601 0.337973 - 0.286988 0.281944 0.33767 - 0.289592 0.302368 0.338381 - 0.283192 0.314571 0.336762 - 0.411349 0.515498 0.370099 - 0.417577 0.571989 0.371816 - 0.249906 0.448493 0.328488 - 0.160871 0.313456 0.305337 - 0.153317 0.318866 0.303407 - 0.150615 0.320331 0.302716 - 0.145234 0.319803 0.301333 - 0.148885 0.357927 0.30235 - 0.168862 0.41225 0.307594 - 0.476415 1.24835 0.388327 - 0.340159 1.26817 0.353365 - 0.256324 1.15343 0.331592 - 0.234223 1.27814 0.326172 - 0.184075 1.27821 0.31329 - 0.0535414 1.29127 0.279784 - -0.105975 1.30533 0.238835 - -0.120204 1.27704 0.235122 - -0.0499064 0.340592 0.251247 - -0.0511789 0.327331 0.250892 - -0.0531771 0.292716 0.250308 - -0.0553048 0.298451 0.249773 - -0.0633762 0.300092 0.247703 - -0.0751402 0.305824 0.244693 - -0.172495 0.693177 0.220483 - -0.223018 0.774616 0.207672 - -0.2342 0.776475 0.204804 - -0.265056 0.665057 0.196647 - -0.132425 0.272351 0.229908 - -0.14165 0.280018 0.227554 - -0.142831 0.279425 0.227249 - -0.148972 0.273982 0.22566 - -0.150128 0.273356 0.225362 - -0.166021 0.286062 0.221305 - -0.182882 0.310685 0.217025 - -0.957198 1.30613 0.0201674 - -0.964811 1.28134 0.0181605 - -0.968036 1.19684 0.0171575 - -0.99494 1.05969 0.00996289 - -1.29726 -1.33528 -0.0905768 - -1.287 -1.35978 -0.087848 - -1.30282 -1.54284 -0.0925112 - -1.3244 -1.66903 -0.0986173 - -1.32827 -1.68895 -0.0997071 - -1.32174 -1.69567 -0.0979538 - -1.318 -1.73697 -0.0970247 - -0.259662 -0.368805 0.192427 - -0.235539 -0.35912 0.19898 - -0.229953 -0.360444 0.20049 - -0.187539 -0.36795 0.211961 - -0.167578 -0.369903 0.217363 - -0.161321 -0.372682 0.219052 - -0.1188 -0.378814 0.230555 - -0.085021 -0.371113 0.239719 - -0.0761293 -0.375952 0.242117 - -0.074878 -0.378214 0.242451 - -0.0655819 -0.381801 0.244961 - -0.0252438 -0.38871 0.255871 --0.00889672 -0.382994 0.26031 --0.00727408 -0.383982 0.260747 - 0.0275049 -0.390993 0.270152 - 0.0476467 -0.391347 0.275606 - 0.071994 -0.401956 0.282177 - 0.086421 -0.402599 0.286083 - 0.0914986 -0.401246 0.287461 - 0.101399 -0.410883 0.290123 - 0.111741 -0.407701 0.29293 - 0.126675 -0.406798 0.296976 - 0.174204 -0.414881 0.309831 - 0.177177 -0.416759 0.310632 - 0.200348 -0.419396 0.316902 - 0.205688 -0.421002 0.318345 - 0.248101 -0.42436 0.329824 - 0.274932 -0.429978 0.337079 - 0.286306 -0.438841 0.340141 - 0.288151 -0.437494 0.340643 - 0.292388 -0.435586 0.341795 - 0.296616 -0.433635 0.342944 - 0.300834 -0.431641 0.34409 - 0.32123 -0.431749 0.349614 - 0.405405 -0.449719 0.372373 - 0.568856 -0.464236 0.416608 - 0.727161 -0.486237 0.459435 - 0.783067 -0.493323 0.47456 - 0.985574 -0.52497 0.529338 - 1.15145 -0.528736 0.574253 - 1.30267 -0.569409 0.615121 - 1.75087 -0.539154 0.736566 - 1.75127 -0.530628 0.736691 - 1.75014 -0.419782 0.736613 - 1.75188 -0.411818 0.737103 - 1.7404 -0.400826 0.734016 - 1.74651 -0.360764 0.735753 - 6.48759 -1.18199 2.01803 - 6.5676 -0.322402 2.04148 - 2.96761 0.136982 1.06748 - 2.98844 0.328909 1.07352 - 1.47706 0.335936 0.664226 - 1.32934 0.328077 0.624202 - 1.15541 0.31913 0.577081 - 1.13312 0.324126 0.571055 - 1.09135 0.333826 0.559763 - 1.08993 0.338807 0.559389 - 1.07701 0.361778 0.555937 - 1.38045 0.605862 0.638621 - 1.16306 0.621034 0.579778 - 1.10202 0.627346 0.563261 - 0.577827 0.374552 0.420776 - 0.825127 0.596488 0.488209 - 0.286384 0.2955 0.341684 - 0.284097 0.303652 0.341081 - 0.362672 0.401672 0.362564 - 0.37964 0.423599 0.367204 - 0.39529 0.47256 0.371544 - 0.392386 0.508032 0.370831 - 0.391376 0.539552 0.370623 - 0.393551 0.588909 0.371314 - 0.164889 0.319629 0.30883 - 0.154844 0.313993 0.306098 - 0.146851 0.318387 0.303943 - 0.144328 0.330873 0.303285 - 0.393598 1.25778 0.372713 - 0.365303 1.26091 0.365057 - 0.331744 1.26492 0.355977 - 0.306712 1.25643 0.34918 - 0.299012 1.24817 0.347077 - 0.243061 1.1942 0.331813 - 0.253706 1.2706 0.334854 - 0.237246 1.27213 0.3304 - 0.21125 1.28237 0.323381 - 0.177605 1.28007 0.314264 - 0.163145 1.2954 0.31038 - 0.152226 1.29693 0.307426 - 0.114109 1.3035 0.297117 - 0.0368412 1.30303 0.27619 - 0.00390068 1.3039 0.267271 - -0.0015838 1.30496 0.265788 - -0.0785492 1.30416 0.244943 - -0.0552437 0.295486 0.249164 - -0.132802 0.543606 0.228674 - -0.176111 0.708732 0.217287 - -0.214434 0.719883 0.206932 - -0.25613 0.814446 0.195835 - -0.257118 0.698005 0.195327 - -0.257679 0.672176 0.195121 - -0.267214 0.671568 0.192538 - -0.268963 0.667619 0.192056 - -0.276424 0.65364 0.190007 - -0.143207 0.268093 0.225285 - -0.148834 0.270702 0.223767 - -0.15178 0.267933 0.222963 - -0.61386 1.05763 0.0994594 - -0.863568 1.3965 0.0325357 - -0.953021 1.29228 0.00809422 - -0.977158 1.16954 0.00130314 - -0.975553 1.14719 0.00169158 - -0.980493 1.11324 0.00028339 - -1.29147 -1.39224 -0.103705 - -1.29766 -1.50054 -0.105676 - -1.30574 -1.55039 -0.108062 - -1.31267 -1.64377 -0.110212 - -1.33018 -1.74204 -0.115357 - -1.32463 -1.75037 -0.113806 - -0.235352 -0.362656 0.19647 - -0.220575 -0.366265 0.200633 - -0.177627 -0.367334 0.212751 - -0.162534 -0.366711 0.217011 - -0.158166 -0.374029 0.218229 - -0.141293 -0.372216 0.222994 - -0.122248 -0.372541 0.228368 - -0.0595448 -0.383725 0.246039 - -0.0319353 -0.384396 0.253829 - 0.00703815 -0.388538 0.264819 - 0.0223851 -0.395463 0.269136 - 0.0371778 -0.392797 0.273316 - 0.0446035 -0.397797 0.275401 - 0.0736358 -0.404509 0.28358 - 0.108686 -0.406338 0.293467 - 0.118397 -0.407322 0.296205 - 0.123516 -0.405525 0.297654 - 0.148817 -0.410621 0.304783 - 0.171501 -0.415714 0.311174 - 0.181778 -0.419556 0.314066 - 0.260886 -0.430481 0.336368 - 0.285451 -0.427475 0.343306 - 0.305375 -0.435815 0.348911 - 0.414802 -0.449739 0.379763 - 0.448512 -0.452589 0.38927 - 0.452293 -0.448404 0.390345 - 0.519702 -0.458076 0.409348 - 0.554506 -0.462654 0.41916 - 0.604226 -0.472419 0.433171 - 0.634804 -0.478011 0.441788 - 0.659806 -0.473937 0.448852 - 0.70149 -0.484701 0.460593 - 0.79523 -0.492718 0.48703 - 0.810176 -0.491879 0.49125 - 1.24106 -0.551157 0.612722 - 1.25453 -0.543602 0.61654 - 1.26571 -0.541639 0.619699 - 1.3473 -0.547705 0.642709 - 1.56794 -0.620233 0.704823 - 1.73214 -0.639926 0.75112 - 1.73208 -0.63103 0.751121 - 1.73838 -0.562997 0.753042 - 1.74254 -0.538304 0.754267 - 1.74759 -0.505355 0.75576 - 1.74169 -0.478091 0.754151 - 1.75621 -0.347279 0.75852 - 6.57656 -1.10961 2.11724 - 6.65398 -0.479217 2.1404 - 6.66141 -0.327978 2.14281 - 6.70813 -0.0253918 2.15662 - 6.71227 0.0965328 2.15804 - 2.98085 0.233329 1.10532 - 2.98124 0.288018 1.10554 - 2.69701 0.42271 1.02561 - 1.86004 0.326886 0.789221 - 1.41731 0.330283 0.664292 - 1.25165 0.328273 0.617538 - 1.08997 0.339945 0.571936 - 1.41135 0.524816 0.663015 - 1.35365 0.531594 0.646745 - 0.571505 0.336413 0.425618 - 0.75976 0.616039 0.479325 - 0.292596 0.300352 0.346835 - 0.371648 0.42028 0.369393 - 0.373713 0.44146 0.370019 - 0.372047 0.539677 0.369753 - 0.38057 0.556742 0.372194 - 0.372089 0.570419 0.369829 - 0.166135 0.317161 0.311183 - 0.153094 0.325799 0.307521 - 0.151724 0.326543 0.307135 - 0.15305 0.359353 0.307578 - 0.305573 1.2574 0.352486 - 0.24725 1.21959 0.335949 - 0.144402 1.28575 0.307063 - 0.106265 1.28713 0.296303 - 0.090745 1.2976 0.291945 - -0.0952315 1.30314 0.239474 - -0.109279 1.09133 0.23507 - -0.0519369 0.395789 0.249806 - -0.0501001 0.362801 0.250256 - -0.0494621 0.297404 0.2503 - -0.0540208 0.293705 0.249006 - -0.190988 0.669587 0.211135 - -0.201382 0.663359 0.208189 - -0.269771 0.78765 0.189148 - -0.253209 0.687672 0.193614 - -0.253754 0.680005 0.193444 - -0.183259 0.414245 0.212786 - -0.155359 0.342871 0.220511 - -0.134691 0.283465 0.22622 - -0.144873 0.277329 0.223333 - -0.82095 1.38263 0.0348419 - -0.96955 1.23773 -0.00739428 - -0.97231 1.23027 -0.00818852 - -0.974415 1.22204 -0.00879976 - -1.28738 -1.39151 -0.116885 - -1.29734 -1.42712 -0.119882 - -1.3013 -1.46963 -0.121134 - -1.30997 -1.6158 -0.12398 - -1.3249 -1.69362 -0.128524 - -1.3348 -1.83387 -0.131722 - -1.32711 -1.83987 -0.129477 - -0.268547 -0.369106 0.184202 - -0.234577 -0.361815 0.194185 - -0.23306 -0.362825 0.194628 - -0.215957 -0.358527 0.199655 - -0.214875 -0.363828 0.199962 - -0.195166 -0.360381 0.205752 - -0.192746 -0.375188 0.206431 - -0.17486 -0.369737 0.211691 - -0.166698 -0.372443 0.21408 - -0.162826 -0.371998 0.215218 - -0.156213 -0.373764 0.217154 - -0.108551 -0.365289 0.231157 - -0.0663714 -0.383779 0.243496 - -0.0610334 -0.380529 0.245069 - -0.0564807 -0.383156 0.246399 - -0.0439511 -0.38854 0.250064 - -0.0383695 -0.378975 0.251722 - -0.0272921 -0.380649 0.254969 - 0.0147014 -0.388032 0.267276 - 0.018026 -0.388775 0.26825 - 0.0236187 -0.396303 0.269875 - 0.0311362 -0.388454 0.272097 - 0.0613426 -0.398819 0.280939 - 0.0833319 -0.403034 0.287383 - 0.0850182 -0.402599 0.287878 - 0.0956113 -0.401752 0.290989 - 0.111026 -0.404282 0.295506 - 0.141364 -0.409035 0.304399 - 0.202229 -0.418355 0.322239 - 0.222497 -0.426108 0.32817 - 0.291134 -0.429605 0.348303 - 0.352044 -0.443041 0.366147 - 0.372044 -0.443366 0.372015 - 0.412295 -0.444965 0.383823 - 0.446035 -0.451902 0.393709 - 0.466047 -0.451468 0.399582 - 0.521403 -0.461271 0.415804 - 0.551221 -0.465837 0.424545 - 0.892798 -0.510829 0.524679 - 1.04854 -0.549805 0.570297 - 1.05828 -0.542769 0.573169 - 1.08791 -0.545485 0.581858 - 1.1719 -0.541603 0.606513 - 1.75497 -0.449076 0.777794 - 1.74629 -0.413138 0.775322 - 6.58195 -1.08316 2.19285 - 6.60418 -0.810934 2.19994 - 6.64096 -0.540566 2.2113 - 6.64314 -0.510311 2.212 - 6.66699 -0.329254 2.21938 - 2.97337 0.206187 1.13668 - 2.9772 0.247448 1.13788 - 2.99234 0.345205 1.14253 - 1.95904 0.326876 0.839293 - 1.47822 0.331292 0.698214 - 1.13098 0.314535 0.596289 - 1.12687 0.31895 0.595093 - 1.43801 0.506881 0.686782 - 1.3207 0.626944 0.652609 - 1.25447 0.623748 0.63317 - 0.529926 0.313597 0.419921 - 0.513925 0.310625 0.415219 - 0.457446 0.294442 0.398613 - 0.839255 0.605096 0.511294 - 0.800675 0.622081 0.500009 - 0.750946 0.611164 0.485394 - 0.397081 0.342689 0.381001 - 0.294132 0.292762 0.350688 - 0.361406 0.436726 0.370728 - 0.360862 0.54079 0.370786 - 0.359643 0.615125 0.370583 - 0.164417 0.322235 0.312687 - 0.144464 0.327664 0.306844 - 0.151781 0.350653 0.309039 - 0.440784 1.24968 0.395715 - 0.388798 1.25304 0.380467 - 0.359918 1.25327 0.371994 - 0.332011 1.25567 0.36381 - 0.251273 1.14857 0.339896 - 0.247773 1.1556 0.338883 - 0.245328 1.26885 0.338402 - 0.128294 1.29672 0.304119 - 0.11743 1.29795 0.300934 - 0.111805 1.29654 0.29928 - 0.0679398 1.29428 0.286404 - 0.00838444 1.30481 0.268951 - -0.0517095 1.30436 0.251316 - -0.0958124 1.30913 0.238385 - -0.0502816 0.347721 0.249741 - -0.130252 0.5422 0.226681 - -0.180032 0.650906 0.212301 - -0.200158 0.619773 0.20633 - -0.251018 0.691582 0.191556 - -0.25642 0.670306 0.189927 - -0.193433 0.439044 0.207927 - -0.605344 1.04729 0.0883279 - -0.830793 1.38918 0.0228868 - -0.850543 1.39525 0.0171043 - -0.951336 1.36944 -0.012525 - -0.960988 1.27466 -0.0155547 - -0.964538 1.26797 -0.0166104 - -0.971116 1.16802 -0.0187489 - -0.975181 1.15247 -0.019974 - -0.986308 1.09634 -0.0233561 - -0.984113 1.06556 -0.0227762 - -1.29813 -1.5095 -0.135304 - -1.31655 -1.64323 -0.141201 - -1.32927 -1.78242 -0.145373 - -0.217678 -0.361966 0.196741 - -0.21599 -0.369947 0.197239 - -0.207931 -0.370112 0.199698 - -0.19846 -0.359577 0.20261 - -0.182252 -0.373799 0.207525 - -0.179125 -0.375338 0.208476 - -0.109798 -0.38258 0.229612 - -0.1082 -0.383023 0.230099 - -0.0963242 -0.382991 0.233722 - -0.0758807 -0.380184 0.239965 - -0.0739718 -0.3785 0.240551 - -0.0722348 -0.377792 0.241083 - -0.0567602 -0.383156 0.245793 - -0.0312319 -0.388481 0.25357 - -0.0294766 -0.385568 0.254112 - -0.0278672 -0.385644 0.254603 - -0.026185 -0.383714 0.25512 --0.00868511 -0.370983 0.260486 - 0.0267779 -0.399947 0.271245 - 0.0284465 -0.399766 0.271754 - 0.0553529 -0.39781 0.279968 - 0.0777686 -0.405269 0.286791 - 0.10627 -0.40347 0.295491 - 0.11336 -0.408482 0.297643 - 0.118767 -0.407679 0.299295 - 0.125872 -0.406173 0.301465 - 0.132293 -0.402659 0.303432 - 0.152865 -0.410253 0.309692 - 0.166229 -0.412892 0.313764 - 0.209569 -0.421537 0.326969 - 0.214483 -0.422115 0.328467 - 0.257849 -0.429645 0.341682 - 0.267964 -0.421292 0.344786 - 0.297232 -0.436259 0.353684 - 0.333871 -0.438019 0.364859 - 0.397068 -0.446109 0.384123 - 0.405452 -0.447371 0.386679 - 0.536163 -0.463392 0.426525 - 0.560835 -0.463013 0.434053 - 0.567318 -0.464044 0.436029 - 0.613584 -0.474454 0.450123 - 0.800971 -0.499814 0.507241 - 0.812139 -0.49162 0.510666 - 1.11118 -0.5341 0.601815 - 1.7109 -0.69892 0.784444 - 1.72865 -0.660828 0.789938 - 1.73932 -0.584618 0.793353 - 1.73864 -0.566843 0.793183 - 1.74558 -0.542837 0.795349 - 1.75066 -0.50962 0.79697 - 1.75168 -0.441272 0.797423 - 6.64214 -0.542432 2.28928 - 6.65584 -0.421297 2.29372 - 2.99274 0.34641 1.17772 - 2.67092 0.421373 1.07969 - 1.45199 0.333594 0.707608 - 1.31774 0.328537 0.666639 - 1.2866 0.327109 0.657135 - 1.22537 0.323664 0.638445 - 1.09292 0.326839 0.598044 - 1.42103 0.524637 0.698563 - 1.33898 0.529489 0.67354 - 1.35578 0.593815 0.678801 - 0.521067 0.309713 0.423536 - 0.493076 0.302579 0.414981 - 0.442837 0.295025 0.399637 - 0.614929 0.513322 0.452599 - 0.296546 0.301677 0.355018 - 0.282527 0.298232 0.350734 - 0.342054 0.384396 0.369075 - 0.350853 0.465685 0.37193 - 0.347493 0.538455 0.371057 - 0.334196 0.581175 0.367089 - 0.163805 0.319697 0.314556 - 0.160189 0.319551 0.313453 - 0.152575 0.32165 0.311134 - 0.15123 0.3224 0.310726 - 0.146305 0.322833 0.309224 - 0.144956 0.323554 0.308814 - 0.152402 0.362061 0.311166 - 0.183902 0.451489 0.320964 - 0.343626 1.26208 0.37139 - 0.250196 1.14954 0.34265 - 0.201859 1.27943 0.328173 - 0.164792 1.28866 0.316884 - 0.0185837 1.29758 0.272294 - -0.0302628 1.30487 0.257407 - -0.101534 1.30973 0.235672 - -0.108799 1.26103 0.233354 - -0.0532624 0.40275 0.248503 - -0.0512538 0.367771 0.249043 - -0.0567681 0.291334 0.247201 - -0.172335 0.643696 0.212678 - -0.172541 0.611553 0.212548 - -0.176856 0.607183 0.211222 - -0.195964 0.588564 0.205354 - -0.141319 0.266902 0.221353 - -0.630809 1.0841 0.0737193 - -0.861295 1.40326 0.00406566 - -1.31093 -1.61217 -0.154413 - -1.31094 -1.62653 -0.154445 - -1.30895 -1.69801 -0.153966 - -1.34573 -1.82652 -0.165881 - -0.245885 -0.353485 0.185458 - -0.201896 -0.36661 0.199359 - -0.185501 -0.368746 0.204546 - -0.180773 -0.366712 0.206047 - -0.156232 -0.3694 0.213812 - -0.1376 -0.376786 0.219696 - -0.111805 -0.376855 0.227863 - -0.0972125 -0.371509 0.232495 - -0.0859696 -0.372093 0.236054 - -0.0741839 -0.3785 0.239772 - -0.0696646 -0.370167 0.24122 - -0.0121776 -0.385999 0.25939 --0.00890859 -0.391982 0.260412 - 0.0026179 -0.394683 0.264056 - 0.0273958 -0.394794 0.271901 - 0.0421405 -0.392849 0.276574 - 0.0823384 -0.404977 0.289277 - 0.0859394 -0.405063 0.290417 - 0.0993542 -0.401215 0.294672 - 0.102382 -0.405493 0.295622 - 0.184712 -0.423181 0.321654 - 0.231907 -0.425825 0.336592 - 0.239682 -0.418442 0.339069 - 0.272081 -0.429504 0.349304 - 0.273864 -0.428198 0.349872 - 0.287215 -0.427993 0.3541 - 0.318452 -0.43566 0.363974 - 0.334151 -0.440333 0.368935 - 0.389633 -0.447641 0.386487 - 0.427684 -0.449041 0.398533 - 0.522421 -0.45767 0.428512 - 0.545688 -0.460799 0.435872 - 0.902059 -0.519882 0.548588 - 1.19688 -0.530805 0.641917 - 1.71775 -0.686005 0.806514 - 1.74349 -0.535373 0.814983 - 1.75381 -0.460482 0.818406 - 1.7566 -0.435507 0.819343 - 1.73945 -0.372479 0.814045 - 1.75184 -0.35833 0.817996 - 1.76736 -0.353039 0.822922 - 6.50247 -0.442915 2.32203 - 6.50156 0.00496452 2.32269 - 2.97417 0.207642 1.20622 - 2.99003 0.319483 1.21147 - 2.99429 0.361711 1.21291 - 2.99817 0.418151 1.21426 - 2.99456 0.445697 1.21317 - 1.53955 0.332532 0.752229 - 1.38442 0.615934 0.703704 - 0.558463 0.319206 0.441554 - 0.415813 0.278693 0.396301 - 0.333137 0.414527 0.370407 - 0.329258 0.424617 0.369201 - 0.33117 0.44244 0.369843 - 0.329772 0.486594 0.369493 - 0.330624 0.520364 0.369834 - 0.332342 0.569551 0.370481 - 0.328954 0.569434 0.369408 - 0.16107 0.323034 0.315733 - 0.154278 0.320132 0.313577 - 0.156009 0.376381 0.314243 - 0.445615 1.24085 0.407755 - 0.363534 1.25728 0.3818 - 0.359425 1.26282 0.380511 - 0.265318 1.15456 0.350486 - 0.249335 1.15148 0.345419 - 0.239599 1.28078 0.342608 - 0.178796 1.2792 0.323352 - 0.0993047 1.29762 0.298221 - 0.0932511 1.29015 0.296288 - 0.0614714 1.30062 0.286248 - -0.0252266 1.30494 0.258805 - -0.0360286 1.30178 0.255378 - -0.105342 1.28439 0.233395 - -0.112012 1.23367 0.231176 - -0.0510311 0.362801 0.248658 - -0.0496404 0.291456 0.248949 - -0.0538263 0.294884 0.24763 - -0.183897 0.575746 0.207035 - -0.272828 0.672936 0.17908 - -0.174365 0.38871 0.209661 - -0.134808 0.280175 0.221958 - -0.133971 0.275075 0.222212 - -0.146604 0.271937 0.218206 - -0.15177 0.267933 0.216562 - -0.946185 1.36944 -0.0326674 - -0.953586 1.34282 -0.0350665 - -0.954615 1.33208 -0.0354149 - -0.958122 1.2664 -0.0366631 - -0.979708 1.13401 -0.0437757 - -1.29948 -1.4807 -0.165281 - -0.241267 -0.363748 0.184276 - -0.189662 -0.369828 0.201196 - -0.183235 -0.36426 0.203316 - -0.177057 -0.362964 0.205346 - -0.170659 -0.369384 0.207431 - -0.161049 -0.372682 0.210578 - -0.110815 -0.379236 0.227046 - -0.0909583 -0.372028 0.233576 - -0.0804773 -0.37633 0.237006 - -0.0640274 -0.385253 0.242384 - -0.055698 -0.383357 0.245121 - -0.0219986 -0.377877 0.25619 --0.00611378 -0.389935 0.261376 - 0.00722048 -0.397439 0.265735 - 0.0221183 -0.397299 0.270624 - 0.0295825 -0.389447 0.273089 - 0.0511025 -0.400382 0.280127 - 0.0524372 -0.398114 0.28057 - 0.054087 -0.39781 0.281112 - 0.0643387 -0.39779 0.284476 - 0.0844977 -0.402156 0.291081 - 0.122142 -0.405854 0.303424 - 0.137612 -0.411593 0.308488 - 0.139316 -0.410898 0.309048 - 0.146912 -0.415256 0.311532 - 0.169643 -0.415789 0.318989 - 0.180304 -0.415993 0.322486 - 0.204537 -0.416278 0.330436 - 0.244981 -0.421163 0.343696 - 0.266244 -0.426683 0.350661 - 0.306251 -0.433053 0.363774 - 0.315167 -0.429465 0.366707 - 0.324735 -0.434175 0.369836 - 0.396716 -0.445677 0.39343 - 0.589733 -0.472813 0.456702 - 0.648432 -0.47754 0.475952 - 0.686795 -0.481962 0.48853 - 0.723627 -0.488227 0.500601 - 0.733707 -0.490134 0.503904 - 0.740171 -0.484825 0.506036 - 0.849748 -0.507506 0.541941 - 1.74372 -0.608073 0.835045 - 1.75752 -0.420178 0.839971 - 6.25264 -0.951156 2.31372 - 6.24478 -0.774604 2.31152 - 6.24532 -0.687401 2.31188 - 6.24217 -0.513282 2.31121 - 6.24491 -0.398012 2.31235 - 6.23706 -0.167465 2.31026 - 6.24373 0.00478434 2.31281 - 6.24436 0.0622577 2.31314 - 2.98286 0.361597 1.24366 - 2.98845 0.404238 1.24558 - 2.98497 0.431792 1.2445 - 1.83968 0.336559 0.868519 - 1.34741 0.331718 0.706994 - 1.08009 0.347247 0.619317 - 1.44235 0.513877 0.738527 - 1.31146 0.536414 0.695629 - 1.35063 0.625483 0.708668 - 0.413009 0.272681 0.400287 - 0.80647 0.605176 0.530084 - 0.319735 0.274224 0.369687 - 0.290331 0.301027 0.360096 - 0.31184 0.354883 0.367266 - 0.316055 0.382204 0.368707 - 0.319253 0.403269 0.3698 - 0.317577 0.404792 0.369254 - 0.317004 0.457953 0.369177 - 0.314963 0.47202 0.368538 - 0.32338 0.497681 0.371353 - 0.31446 0.542551 0.368521 - 0.468814 1.24429 0.420642 - 0.435008 1.24968 0.409562 - 0.379812 1.2596 0.391473 - 0.373708 1.25854 0.389468 - 0.36762 1.25745 0.387468 - 0.340117 1.26112 0.378452 - 0.334619 1.26177 0.376649 - 0.251362 1.26353 0.349336 - 0.211358 1.2843 0.336254 - 0.141451 1.2927 0.313335 - 0.049847 1.29826 0.283291 - 0.0284354 1.30324 0.276276 - 0.001345 1.2979 0.267376 - -0.0643802 0.289037 0.243688 - -0.0705834 0.302038 0.24168 - -0.164012 0.610785 0.211675 - -0.166845 0.600688 0.210725 - -0.258413 0.652965 0.180791 - -0.213273 0.488643 0.195255 - -0.158967 0.347706 0.212777 - -0.133112 0.269988 0.221097 - -0.144747 0.274044 0.217287 - -0.151516 0.270327 0.215059 - -0.153293 0.268171 0.214471 - -0.195418 0.328118 0.200776 - -0.604745 1.05418 0.0680017 - -0.654662 1.12068 0.0517638 - -0.850494 1.39312 -0.0119163 - -0.862399 1.39938 -0.0158092 - -0.920274 1.39872 -0.0347996 - -0.949364 1.39084 -0.0443608 - -0.950844 1.36759 -0.0448952 - -0.947549 1.35034 -0.0438505 - -0.961874 1.23027 -0.0488033 - -0.971845 1.12805 -0.0522901 - -0.991011 1.08223 -0.0586749 - -1.31447 -1.71596 -0.185869 - -1.33739 -1.81011 -0.193858 - -0.250905 -0.35897 0.178352 - -0.243877 -0.361637 0.180734 - -0.237864 -0.365832 0.182769 - -0.23077 -0.361138 0.185189 - -0.225273 -0.358886 0.187061 - -0.20595 -0.363978 0.193616 - -0.194222 -0.363868 0.197601 - -0.189029 -0.368935 0.199354 - -0.150431 -0.378205 0.212449 - -0.114269 -0.379284 0.224733 - -0.0945011 -0.380445 0.231447 - -0.0913541 -0.381179 0.232514 - -0.0785819 -0.373686 0.23687 - -0.0671629 -0.38279 0.24073 - -0.0555185 -0.379384 0.244694 - -0.0382989 -0.382086 0.250538 - -0.0113915 -0.387994 0.259668 --0.00972142 -0.394982 0.260221 --0.00642227 -0.396934 0.261338 --0.00034547 -0.382756 0.263432 - 0.00138969 -0.38669 0.264013 - 0.00332811 -0.394611 0.264655 - 0.00984617 -0.394245 0.266871 - 0.0362022 -0.394556 0.275825 - 0.0601465 -0.406677 0.283934 - 0.0614617 -0.404372 0.284386 - 0.162847 -0.421823 0.318796 - 0.162034 -0.410158 0.318544 - 0.173239 -0.41681 0.322337 - 0.177087 -0.415976 0.323646 - 0.206176 -0.426057 0.333508 - 0.20839 -0.425918 0.334261 - 0.2119 -0.42386 0.335458 - 0.226979 -0.421541 0.340586 - 0.244988 -0.427401 0.346692 - 0.292417 -0.431641 0.362798 - 0.33886 -0.442503 0.378554 - 0.34558 -0.443041 0.380836 - 0.374087 -0.445755 0.390516 - 0.377855 -0.446167 0.391795 - 0.439499 -0.449132 0.412733 - 0.445279 -0.446977 0.414701 - 0.47593 -0.460414 0.425087 - 0.52236 -0.461463 0.44086 - 0.599508 -0.473759 0.467046 - 0.621525 -0.477431 0.474519 - 0.637506 -0.476017 0.479951 - 0.657487 -0.477035 0.486738 - 0.92236 -0.507979 0.576665 - 0.920935 -0.490992 0.576217 - 1.02468 -0.521843 0.611399 - 1.66891 -0.707214 0.829893 - 1.73577 -0.634492 0.852762 - 1.73555 -0.616449 0.852724 - 6.02529 -1.0624 2.30926 - 6.02586 -1.03392 2.30952 - 6.01542 -0.975199 2.30609 - 6.01272 -0.861387 2.30542 - 6.00693 -0.24519 2.30475 - 6.01034 -0.161968 2.30609 - 3.0629 0.0732589 1.30516 - 1.57125 0.334235 0.79891 - 1.3556 0.328344 0.725628 - 0.543747 0.307028 0.44975 - 0.817649 0.598899 0.543427 - 0.793293 0.614665 0.535185 - 0.314792 0.269015 0.37188 - 0.311069 0.270793 0.370619 - 0.306541 0.276737 0.369093 - 0.300472 0.281305 0.36704 - 0.302666 0.290876 0.367806 - 0.324596 0.342558 0.375366 - 0.303906 0.357145 0.368367 - 0.304647 0.412221 0.368735 - 0.304219 0.42667 0.368621 - 0.160515 0.312905 0.319555 - 0.153654 0.322763 0.317245 - 0.146535 0.318866 0.314818 - 0.148955 0.337816 0.31568 - 0.432328 1.24781 0.413881 - 0.308087 1.25254 0.371679 - 0.28046 1.18582 0.362152 - 0.209614 1.28135 0.338283 - 0.19228 1.27547 0.332381 - 0.170884 1.2771 0.325115 - 0.0223763 1.30042 0.274707 - 0.00619502 1.29682 0.269202 --0.00450022 1.29996 0.265575 - -0.0475666 1.30353 0.25095 - -0.0695278 1.3127 0.243508 - -0.0803717 1.31215 0.239823 - -0.0516181 0.362801 0.247587 - -0.0535721 0.29804 0.246786 - -0.0553726 0.284616 0.246146 - -0.0634306 0.289269 0.243418 - -0.119868 0.513941 0.224717 - -0.145294 0.623751 0.21631 - -0.178002 0.574416 0.205094 - -0.196537 0.528906 0.1987 - -0.154596 0.2708 0.212404 - -0.626391 1.08496 0.0538273 - -0.925028 1.41029 -0.0469499 - -0.956643 1.27191 -0.057984 - -0.975883 1.13625 -0.0648074 - -0.980308 1.08307 -0.0664233 - -0.981507 1.07499 -0.0668477 - -1.3043 -1.5237 -0.200785 - -0.259844 -0.366541 0.171718 - -0.20153 -0.36749 0.192377 - -0.18663 -0.364468 0.197662 - -0.157 -0.372177 0.208144 - -0.142192 -0.380333 0.213373 - -0.134126 -0.371681 0.216249 - -0.124481 -0.379228 0.21965 - -0.0277527 -0.384713 0.253909 - -0.0213065 -0.378915 0.256205 --0.00724293 -0.380936 0.261184 - 0.00399858 -0.38654 0.265155 - 0.0650907 -0.392176 0.286788 - 0.0667027 -0.391807 0.287359 - 0.103914 -0.401017 0.300524 - 0.108073 -0.402769 0.301994 - 0.119097 -0.408361 0.305888 - 0.141614 -0.412271 0.313857 - 0.15285 -0.410571 0.317841 - 0.213392 -0.420901 0.339269 - 0.236796 -0.424678 0.347553 - 0.240052 -0.42605 0.348704 - 0.248055 -0.422958 0.351546 - 0.264341 -0.436688 0.357287 - 0.268228 -0.42656 0.358686 - 0.279951 -0.436139 0.362819 - 0.289975 -0.43084 0.366381 - 0.30216 -0.4361 0.370688 - 0.327117 -0.438019 0.379525 - 0.337945 -0.436201 0.383366 - 0.353254 -0.443302 0.388775 - 0.393708 -0.443076 0.403108 - 0.415507 -0.446849 0.410823 - 0.433253 -0.453287 0.417097 - 0.616273 -0.471618 0.481902 - 0.629026 -0.476719 0.486409 - 0.658277 -0.475605 0.496775 - 0.724445 -0.488546 0.520191 - 0.768749 -0.497953 0.535868 - 0.853945 -0.498916 0.56605 - 0.876715 -0.496124 0.574123 - 0.883764 -0.494764 0.576624 - 0.986667 -0.499593 0.613072 - 1.56883 -0.72849 0.818845 - 1.73435 -0.583224 0.877795 - 1.75353 -0.422818 0.884933 - 5.75214 -0.800771 2.30083 - 5.75866 -0.720285 2.30331 - 5.75439 -0.477135 2.30231 - 5.75338 0.0578431 2.30309 - 2.97392 0.223989 1.31869 - 2.9947 0.451013 1.32653 - 1.8142 0.343496 0.908053 - 1.57192 0.335997 0.822199 - 1.3843 0.330066 0.755713 - 1.14541 0.319126 0.671052 - 1.44621 0.512208 0.778033 - 1.44193 0.525711 0.776546 - 1.41659 0.523965 0.767564 - 1.28495 0.544155 0.720969 - 1.39669 0.61374 0.760706 - 1.39158 0.626781 0.758922 - 1.38292 0.630544 0.75586 - 1.24261 0.615979 0.70612 - 0.501959 0.366518 0.443179 - 0.75322 0.587177 0.532668 - 0.292571 0.296077 0.368844 - 0.324688 0.335804 0.380307 - 0.323302 0.33737 0.379819 - 0.300781 0.334704 0.371834 - 0.298014 0.337608 0.37086 - 0.290212 0.385554 0.368198 - 0.289961 0.406407 0.368153 - 0.294107 0.427061 0.369666 - 0.288809 0.431307 0.367798 - 0.282086 0.494455 0.36555 - 0.170721 0.320735 0.325725 - 0.166265 0.322416 0.32415 - 0.158132 0.320498 0.321264 - 0.145568 0.333359 0.31684 - 0.401499 1.25026 0.409461 - 0.271909 1.15874 0.363353 - 0.254487 1.26718 0.357411 - 0.217523 1.27335 0.344328 - 0.0270443 1.30124 0.276901 - 0.016479 1.30757 0.273171 - 0.00572218 1.30781 0.26936 - -0.0157885 1.303 0.261729 - -0.0319881 1.31187 0.256008 - -0.0993113 1.26784 0.232063 - -0.0577699 0.290346 0.244706 - -0.0610977 0.295849 0.243539 - -0.0743958 0.312549 0.238863 - -0.173959 0.4906 0.203966 - -0.178398 0.483637 0.202379 - -0.254694 0.606622 0.175608 - -0.240633 0.557531 0.180485 - -0.136537 0.271583 0.21676 - -0.137242 0.270114 0.216507 - -0.138352 0.269542 0.216112 - -0.189311 0.32116 0.198167 - -0.66788 1.13995 0.0303486 - -0.771785 1.30822 -0.00610754 - -0.9388 1.39758 -0.0650911 - -0.96324 1.25176 -0.0740596 - -1.30244 -1.38657 -0.214746 - -1.31122 -1.60628 -0.218425 - -1.31132 -1.62067 -0.218492 - -1.31046 -1.66324 -0.218266 - -1.31997 -1.72083 -0.221871 - -0.285297 -0.387215 0.159518 - -0.259194 -0.362962 0.16912 - -0.226879 -0.356075 0.180958 - -0.213648 -0.361176 0.185788 - -0.187658 -0.359297 0.195301 - -0.179983 -0.366712 0.198093 - -0.120064 -0.381692 0.219983 - -0.111972 -0.383096 0.222941 - -0.0996299 -0.380262 0.227462 - -0.0562947 -0.38137 0.243314 - -0.0426341 -0.388819 0.248296 - -0.0393181 -0.387074 0.249513 - -0.0377317 -0.387187 0.250094 - -0.0154753 -0.382997 0.258245 - -0.0106619 -0.393982 0.259983 --0.00908855 -0.390962 0.260565 --0.00750434 -0.389935 0.261147 - 0.0106847 -0.399124 0.267782 - 0.0236546 -0.396962 0.272532 - 0.048735 -0.39841 0.281705 - 0.052655 -0.401749 0.283132 - 0.0579402 -0.402748 0.285063 - 0.0621299 -0.39779 0.286607 - 0.0655831 -0.398044 0.287869 - 0.132525 -0.405993 0.312344 - 0.145801 -0.415443 0.317181 - 0.147502 -0.414696 0.317805 - 0.151261 -0.414099 0.319182 - 0.163335 -0.413894 0.323599 - 0.185654 -0.412349 0.331768 - 0.223834 -0.425221 0.34571 - 0.333811 -0.433161 0.385929 - 0.352073 -0.440102 0.392596 - 0.363773 -0.442357 0.396872 - 0.386868 -0.445388 0.405315 - 0.544193 -0.463776 0.462835 - 0.723326 -0.485124 0.528328 - 0.785718 -0.49088 0.551142 - 0.852836 -0.500345 0.575678 - 0.939734 -0.522153 0.607424 - 0.939705 -0.499932 0.607461 - 0.970691 -0.49363 0.618811 - 0.999104 -0.502131 0.629189 - 1.02163 -0.507451 0.637419 - 1.19539 -0.578998 0.70084 - 1.51711 -0.724432 0.818233 - 1.64075 -0.737337 0.863442 - 1.74039 -0.38719 0.900644 - 1.7682 -0.350335 0.910896 - 5.56595 -0.963191 2.29905 - 5.56054 -0.88269 2.29724 - 5.56663 -0.777925 2.29969 - 5.55221 -0.644757 2.2947 - 5.56334 -0.5675 2.29893 - 5.56277 -0.229006 2.29945 - 5.56787 -0.151329 2.30148 - 5.56084 0.0561227 2.29935 - 3.04969 0.087812 1.38068 - 2.96481 0.099234 1.34965 - 2.96387 0.126915 1.34936 - 2.96692 0.182589 1.3506 - 2.99551 0.381739 1.36148 - 1.09545 0.317653 0.666184 - 1.09189 0.327688 0.664904 - 1.07052 0.348692 0.657128 - 1.0712 0.359951 0.6574 - 1.39545 0.525628 0.776386 - 1.369 0.530247 0.766717 - 1.29685 0.544308 0.740351 - 1.35406 0.627517 0.76146 - 0.52524 0.290281 0.457507 - 0.506275 0.292343 0.450573 - 0.421945 0.268837 0.419669 - 0.306376 0.272287 0.377394 - 0.300814 0.2873 0.375391 - 0.445288 0.461483 0.42862 - 0.334451 0.356399 0.387845 - 0.290486 0.334032 0.371712 - 0.276957 0.339373 0.366774 - 0.277454 0.342946 0.366963 - 0.281498 0.35386 0.368466 - 0.28204 0.363999 0.368686 - 0.278357 0.389388 0.367393 - 0.284 0.415154 0.369512 - 0.281713 0.419512 0.368684 - 0.152543 0.315198 0.321204 - 0.14693 0.320769 0.319162 - 0.145602 0.324914 0.318685 - 0.150186 0.352731 0.320421 - 0.379937 1.03043 0.405922 - 0.370306 1.2482 0.402862 - 0.328629 1.25985 0.387639 - 0.252316 1.14612 0.359477 - 0.132474 1.28943 0.315936 - 0.126862 1.28712 0.313878 - 0.0845102 1.29063 0.29839 - 0.0264604 1.30124 0.277175 - -0.0215377 1.29998 0.259611 - -0.0376061 1.30478 0.253743 - -0.0430399 1.30866 0.251763 - -0.0986264 1.06028 0.230897 - -0.0493643 0.34905 0.247406 - -0.0608664 0.292891 0.243078 - -0.0622264 0.293658 0.242582 - -0.149425 0.61862 0.211371 - -0.152526 0.597268 0.210191 - -0.16429 0.55357 0.205794 - -0.170197 0.472868 0.203461 - -0.171503 0.470256 0.202978 - -0.198217 0.494839 0.193256 - -0.135545 0.281994 0.215732 - -0.146978 0.276109 0.211537 - -0.747296 1.26987 -0.00598079 - -0.792588 1.32235 -0.0224395 - -0.810051 1.33902 -0.0287933 - -0.910107 1.39707 -0.0652765 - -0.943028 1.37003 -0.0773786 - -0.95973 1.2624 -0.0837182 - -0.966904 1.19525 -0.0864862 - -0.305848 -0.406422 0.148463 - -0.224034 -0.358886 0.179478 - -0.194658 -0.366524 0.190562 - -0.174752 -0.363715 0.198089 - -0.174448 -0.367178 0.198197 - -0.172947 -0.36792 0.198762 - -0.153104 -0.367272 0.206261 - -0.145904 -0.37135 0.208973 - -0.143734 -0.370085 0.209796 - -0.139752 -0.368456 0.211304 - -0.136738 -0.36961 0.21244 - -0.130623 -0.37712 0.214735 - -0.118735 -0.376896 0.219227 - -0.099703 -0.380262 0.226412 - -0.0678242 -0.38279 0.238452 - -0.0649547 -0.385253 0.239531 - -0.0503965 -0.38309 0.245037 - -0.0442885 -0.385693 0.247339 - -0.0411387 -0.385956 0.248529 - -0.0394992 -0.385078 0.24915 - -0.0221301 -0.382914 0.255718 - 0.0132255 -0.395886 0.269049 - 0.0297968 -0.398185 0.275306 - 0.0443847 -0.396017 0.280823 - 0.107492 -0.406577 0.304646 - 0.119882 -0.410574 0.309319 - 0.135582 -0.41183 0.315249 - 0.148374 -0.409497 0.320087 - 0.184472 -0.421331 0.333701 - 0.214766 -0.419645 0.345152 - 0.237047 -0.4215 0.353567 - 0.255141 -0.426744 0.360393 - 0.318367 -0.431079 0.384274 - 0.393088 -0.446655 0.412475 - 0.48913 -0.455125 0.448747 - 0.59999 -0.47218 0.4906 - 0.673466 -0.481415 0.518343 - 0.68209 -0.478221 0.521609 - 0.684822 -0.475503 0.522647 - 0.71567 -0.486958 0.534279 - 0.719241 -0.484599 0.535633 - 0.725999 -0.484303 0.538187 - 0.905545 -0.494843 0.606007 - 1.66445 -0.723559 0.892275 - 1.73007 -0.622465 0.917288 - 1.73905 -0.589524 0.920752 - 1.73931 -0.571685 0.920888 - 1.7557 -0.35787 0.927539 - 5.38581 -0.884205 2.29808 - 5.37744 -0.75456 2.29519 - 5.38518 -0.576996 2.2985 - 5.38241 -0.500526 2.29761 - 5.37593 -0.197043 2.29581 - 5.38267 -0.0209841 2.29873 - 2.96396 0.0996092 1.38507 - 2.99138 0.31182 1.39588 - 2.99007 0.325841 1.39541 - 2.98588 0.453251 1.39411 - 1.82948 0.3403 0.956908 - 1.26546 0.298255 0.743701 - 1.12634 0.322194 0.691183 - 1.28781 0.542856 0.752668 - 1.31314 0.633506 0.762432 - 1.25513 0.63449 0.740516 - 0.29586 0.286803 0.377304 - 0.287504 0.335447 0.374251 - 0.270238 0.33628 0.367729 - 0.266093 0.340244 0.366171 - 0.270473 0.398484 0.367951 - 0.268288 0.467359 0.367272 - 0.219831 0.394889 0.348808 - 0.177034 0.329191 0.332496 - 0.162978 0.31729 0.327159 - 0.152915 0.321208 0.323365 - 0.149836 0.321886 0.322203 - 0.147871 0.350045 0.321521 - 0.158589 0.390051 0.325656 - 0.222893 0.553243 0.350303 - 0.265484 0.659939 0.366625 - 0.42554 1.24781 0.42836 - 0.392675 1.25312 0.415953 - 0.315787 1.26011 0.386915 - 0.252148 1.24448 0.362835 - 0.215956 1.27924 0.349234 - 0.190106 1.28631 0.339481 - 0.0732753 1.2935 0.295351 - 0.0309907 1.29603 0.279379 - -0.006022 1.30196 0.265406 - -0.100607 1.2838 0.229628 - -0.0491127 0.294759 0.246971 - -0.0669113 0.297885 0.240252 - -0.141622 0.607157 0.212683 - -0.15485 0.596622 0.207663 - -0.156394 0.571414 0.207025 - -0.222498 0.53384 0.181967 - -0.853137 1.35024 -0.054579 - -0.952627 1.35136 -0.0921698 - -0.972249 1.15414 -0.100006 - -0.982877 1.08803 -0.104163 - -0.984557 1.07106 -0.104834 - -1.30686 -1.37735 -0.247526 - -1.3019 -1.3841 -0.245607 - -1.31472 -1.4476 -0.250744 - -1.30345 -1.51242 -0.246488 - -0.240339 -0.359148 0.170582 - -0.206149 -0.359583 0.183914 - -0.204685 -0.360475 0.184483 - -0.183526 -0.363474 0.192729 - -0.168952 -0.36756 0.198404 - -0.142434 -0.371623 0.208736 - -0.101531 -0.380833 0.224668 - -0.0984304 -0.381629 0.225875 - -0.0855037 -0.373406 0.230934 - -0.0775678 -0.373 0.23403 - -0.0680154 -0.38279 0.237734 - -0.0287313 -0.382715 0.253055 - -0.0100514 -0.382963 0.260339 --0.00849464 -0.382936 0.260946 - -0.0018284 -0.395748 0.263518 - 0.0124247 -0.391897 0.269085 - 0.0206547 -0.394148 0.27229 - 0.0238576 -0.3938 0.27354 - 0.0506583 -0.39781 0.283983 - 0.0607105 -0.39779 0.287903 - 0.0702247 -0.402749 0.291603 - 0.0842197 -0.40318 0.29706 - 0.127569 -0.408277 0.313954 - 0.174868 -0.412413 0.332391 - 0.359407 -0.445594 0.404287 - 0.36924 -0.445433 0.408122 - 0.374123 -0.443274 0.41003 - 0.401058 -0.445859 0.420529 - 0.450878 -0.453484 0.439942 - 0.571399 -0.469227 0.486909 - 0.59634 -0.471596 0.496631 - 0.609287 -0.472771 0.501677 - 0.87747 -0.492433 0.606221 - 0.87946 -0.488249 0.607007 - 1.28598 -0.649817 0.765197 - 1.64505 -0.773075 0.904961 - 1.683 -0.716284 0.919885 - 1.72895 -0.642938 0.93796 - 1.73638 -0.555303 0.941045 - 1.73593 -0.546259 0.940889 - 1.75464 -0.454538 0.948383 - 1.75102 -0.444875 0.946992 - 1.75964 -0.351606 0.950555 - 1.83033 -0.347767 0.978132 - 5.2122 -0.684728 2.29628 - 5.21125 -0.388164 2.29654 - 5.20822 -0.167217 2.29584 - 5.21566 -0.0694187 2.29895 - 5.21973 0.00408249 2.30069 - 5.21918 0.0776324 2.30064 - 2.99111 0.384341 1.43239 - 1.82526 0.340981 0.977632 - 1.79083 0.343321 0.964209 - 1.58381 0.334972 0.883456 - 1.1208 0.316364 0.702851 - 1.07867 0.326616 0.686445 - 1.06706 0.361735 0.681993 - 1.35174 0.631866 0.793593 - 1.33293 0.630675 0.786256 - 1.29117 0.625766 0.769959 - 0.448875 0.268261 0.44071 - 0.348735 0.271602 0.401664 - 0.309708 0.25629 0.386412 - 0.312894 0.268401 0.38768 - 0.302258 0.271664 0.383539 - 0.309132 0.28004 0.386238 - 0.298368 0.283071 0.382047 - 0.301438 0.296129 0.383272 - 0.451866 0.489515 0.442351 - 0.308373 0.348149 0.386088 - 0.267291 0.337608 0.370044 - 0.259559 0.346199 0.367047 - 0.258749 0.348247 0.366736 - 0.25733 0.349528 0.366185 - 0.258284 0.35388 0.366567 - 0.235649 0.419874 0.357881 - 0.150506 0.321989 0.324467 - 0.154813 0.371438 0.326253 - 0.262769 0.688928 0.369035 - 0.278571 0.77398 0.37538 - 0.297337 0.855297 0.382873 - 0.309981 1.24471 0.38864 - 0.274869 1.169 0.374784 - 0.265632 1.15197 0.371145 - 0.245286 1.19551 0.363304 - 0.203494 1.27742 0.347182 - 0.17125 1.27624 0.334605 - 0.0781628 1.29905 0.298352 - 0.0304318 1.29803 0.279735 - -0.0170912 1.305 0.261217 - -0.0595214 1.30417 0.244668 - -0.0699544 1.29972 0.24059 - -0.0853656 1.29086 0.234561 - -0.093179 0.988531 0.230865 - -0.0494507 0.375237 0.246601 - -0.0479747 0.292929 0.247 - -0.138272 0.603832 0.212453 - -0.152804 0.52058 0.206608 - -0.149955 0.49336 0.20766 - -0.152135 0.443402 0.206703 - -0.155391 0.267747 0.205056 - -0.186543 0.314302 0.193007 - -0.913254 1.39866 -0.0880697 - -1.30412 -1.7039 -0.262797 - -1.31352 -1.73172 -0.266638 - -0.233902 -0.359774 0.17044 - -0.195288 -0.36918 0.185946 - -0.183035 -0.359108 0.190895 - -0.160515 -0.369235 0.199928 - -0.146811 -0.3698 0.205438 - -0.137166 -0.371495 0.209313 - -0.130861 -0.367499 0.211856 - -0.12658 -0.37533 0.213561 - -0.125059 -0.37585 0.214171 - -0.105731 -0.377648 0.221939 - -0.100246 -0.382207 0.224135 - -0.0967332 -0.381042 0.22555 - -0.0949862 -0.380445 0.226254 - -0.0907295 -0.375315 0.227976 - -0.0824115 -0.37307 0.231326 - -0.0593282 -0.388119 0.240575 - -0.0386632 -0.387187 0.248887 --0.00871189 -0.394934 0.260914 --0.00106083 -0.385691 0.26401 - 0.034434 -0.392343 0.278269 - 0.0519277 -0.399467 0.285288 - 0.0845555 -0.40078 0.298405 - 0.121037 -0.403021 0.313069 - 0.167055 -0.411435 0.331555 - 0.21785 -0.421785 0.351958 - 0.279554 -0.432829 0.376745 - 0.284714 -0.432441 0.378821 - 0.344599 -0.437856 0.40289 - 0.375179 -0.442897 0.415175 - 0.392548 -0.442836 0.422159 - 0.424223 -0.445024 0.434891 - 0.433947 -0.446977 0.438797 - 0.439608 -0.44475 0.441078 - 0.524059 -0.46589 0.474991 - 0.528119 -0.465215 0.476625 - 0.579085 -0.469034 0.49711 - 0.597578 -0.470469 0.504543 - 0.682218 -0.478187 0.538561 - 0.71086 -0.483547 0.550066 - 0.740543 -0.488693 0.561991 - 0.831797 -0.510434 0.598638 - 0.833852 -0.506445 0.599473 - 0.846075 -0.503204 0.604394 - 0.856212 -0.493334 0.608492 - 0.899521 -0.485358 0.625924 - 1.63889 -0.782851 0.922586 - 1.65946 -0.746068 0.930936 - 1.72824 -0.673115 0.958753 - 1.73091 -0.564937 0.960059 - 1.75128 -0.473267 0.968446 - 1.73504 -0.382412 0.962111 - 5.04904 -0.738792 2.29392 - 5.05936 -0.187031 2.29926 - 2.97166 0.227513 1.46068 - 2.97645 0.298716 1.46276 - 2.99506 0.40087 1.47046 - 1.85563 0.330023 1.01214 - 1.63552 0.339274 0.923651 - 1.07856 0.344766 0.699704 - 1.13144 0.390913 0.721069 - 1.12984 0.396306 0.720438 - 1.28283 0.538568 0.782263 - 0.454438 0.267165 0.448576 - 0.43404 0.263743 0.440366 - 0.383195 0.258861 0.419911 - 0.373178 0.257374 0.41588 - 0.365819 0.262501 0.412932 - 0.421809 0.414411 0.435773 - 0.478147 0.515128 0.458644 - 0.251134 0.368998 0.367046 - 0.254474 0.383884 0.368421 - 0.180271 0.332449 0.338473 - 0.147582 0.335538 0.325335 - 0.156301 0.385633 0.328949 - 0.25688 0.639546 0.36994 - 0.2754 0.810142 0.377754 - 0.352534 1.24602 0.40971 - 0.336017 1.24634 0.403069 - 0.268934 1.15161 0.37589 - 0.247562 1.14515 0.367283 - 0.252404 1.26007 0.369477 - 0.228707 1.27589 0.359983 - 0.196976 1.27843 0.347229 - 0.103061 1.29057 0.309491 - 0.0510209 1.30096 0.288588 - 0.0402693 1.29655 0.284256 - 0.0349807 1.2958 0.282127 - -0.0227997 1.30398 0.258911 - -0.0915512 1.3045 0.231267 - -0.144512 0.609487 0.208473 - -0.147942 0.601444 0.207076 - -0.14955 0.517364 0.206249 - -0.144131 0.457618 0.208299 - -0.171664 0.419699 0.197146 - -0.140393 0.271654 0.209401 - -0.176661 0.293689 0.194865 - -0.844603 1.34607 -0.0714492 - -0.957024 1.30706 -0.116738 - -0.970021 1.20145 -0.122192 - -0.967362 1.16686 -0.121197 - -1.29924 -1.49297 -0.276128 - -1.30321 -1.56475 -0.277929 - -1.31698 -1.71248 -0.283954 - -1.31461 -1.75576 -0.283068 - -1.31727 -1.77519 -0.284213 - -1.31257 -1.83366 -0.28239 - -0.233368 -0.359774 0.167984 - -0.218762 -0.362642 0.17403 - -0.212204 -0.372611 0.176726 - -0.192153 -0.367361 0.185046 - -0.14581 -0.372285 0.204238 - -0.120965 -0.37928 0.214518 - -0.112067 -0.376855 0.21821 - -0.084387 -0.374713 0.229685 - -0.0618346 -0.38075 0.239016 - -0.0604144 -0.381956 0.239602 - -0.0546453 -0.386718 0.241983 - -0.0108687 -0.384962 0.260126 --0.00616275 -0.386859 0.262072 - 0.00841716 -0.395132 0.268095 - 0.0100096 -0.395014 0.268755 - 0.0180497 -0.395307 0.272086 - 0.0278171 -0.396199 0.276132 - 0.0676866 -0.406073 0.292631 - 0.0886913 -0.406569 0.301333 - 0.119054 -0.40554 0.313917 - 0.120687 -0.4049 0.314595 - 0.128854 -0.406927 0.317975 - 0.176612 -0.416887 0.337742 - 0.183301 -0.41319 0.340522 - 0.273575 -0.4226 0.377908 - 0.301421 -0.430967 0.389428 - 0.336733 -0.44214 0.404036 - 0.339671 -0.438042 0.405263 - 0.363326 -0.443232 0.415053 - 0.422829 -0.449838 0.439695 - 0.56493 -0.468629 0.498536 - 0.582107 -0.473759 0.505643 - 0.619942 -0.476587 0.521314 - 0.646744 -0.47838 0.532416 - 0.788308 -0.496576 0.591036 - 0.799957 -0.498675 0.595858 - 0.820922 -0.501119 0.60454 - 1.65199 -0.859279 0.948133 - 1.7352 -0.58696 0.9832 - 1.73681 -0.560403 0.983926 - 4.90323 -0.532237 2.29604 - 4.90912 -0.228879 2.29914 - 4.90231 0.0270983 2.29687 - 4.90187 0.0735567 2.29679 - 2.99101 0.33018 1.50555 - 2.99315 0.37356 1.50653 - 2.99436 0.388125 1.50706 - 2.98485 0.444536 1.50325 - 1.71615 0.340522 0.977315 - 1.57951 0.337078 0.920686 - 1.34887 0.315228 0.825072 - 1.12637 0.309349 0.732863 - 1.12511 0.314743 0.732352 - 1.0775 0.340445 0.71268 - 1.28877 0.557741 0.800694 - 1.31652 0.628678 0.812347 - 1.27344 0.622914 0.794483 - 0.454971 0.26319 0.454557 - 0.443025 0.262036 0.449605 - 0.384738 0.256114 0.42544 - 0.381321 0.25647 0.424024 - 0.376079 0.258138 0.421856 - 0.372672 0.25842 0.420445 - 0.346408 0.25292 0.40955 - 0.325665 0.252405 0.400954 - 0.312244 0.270824 0.395433 - 0.469997 0.474795 0.461241 - 0.433286 0.491801 0.446066 - 0.263182 0.342492 0.375258 - 0.247147 0.411852 0.368764 - 0.25004 0.424249 0.36999 - 0.240306 0.42048 0.365948 - 0.171444 0.325798 0.337209 - 0.160465 0.319005 0.332645 - 0.151378 0.3247 0.328892 - 0.148753 0.326272 0.327807 - 0.147664 0.341628 0.327389 - 0.357964 1.23395 0.416462 - 0.282203 1.17104 0.384933 - 0.237113 1.27158 0.366467 - 0.112515 1.28939 0.314877 - 0.102297 1.29256 0.310649 - 0.0605474 1.29628 0.293358 - -0.14668 0.533706 0.205839 - -0.134098 0.422196 0.210811 - -0.144126 0.274044 0.206335 - -0.150486 0.272725 0.203697 - -0.154138 0.266002 0.202169 - -0.668644 1.13811 -0.00913632 - -0.828515 1.38974 -0.0748369 - -0.918019 1.40348 -0.111895 - -0.947739 1.34697 -0.124332 - -0.961367 1.31813 -0.130041 - -0.957624 1.28953 -0.128552 - -0.961241 1.2271 -0.130186 - -0.975317 1.18114 -0.136118 - -0.981078 1.09818 -0.138685 - -1.29786 -1.63512 -0.291478 - -1.30791 -1.81802 -0.296161 - -0.259784 -0.365058 0.15406 - -0.254178 -0.363283 0.156455 - -0.226493 -0.35945 0.168272 - -0.225048 -0.360444 0.168887 - -0.207194 -0.363926 0.176495 - -0.199996 -0.364863 0.179562 - -0.194294 -0.364797 0.181995 - -0.140831 -0.373156 0.20478 - -0.129141 -0.37332 0.209766 - -0.0979379 -0.378708 0.223064 - -0.0863501 -0.376346 0.228011 - -0.0728708 -0.369901 0.233775 - -0.0583057 -0.375215 0.239976 - -0.0378122 -0.389289 0.248686 - -0.0361988 -0.388389 0.249377 - -0.0143568 -0.387994 0.258694 - -0.0114449 -0.372964 0.259968 - 0.00093476 -0.381546 0.26523 - 0.0471895 -0.399099 0.284921 - 0.0516505 -0.396197 0.28683 - 0.0689377 -0.399424 0.294197 - 0.083142 -0.401746 0.30025 - 0.0940245 -0.409854 0.304875 - 0.0954053 -0.408368 0.305467 - 0.112736 -0.411812 0.312851 - 0.120018 -0.405839 0.31597 - 0.122285 -0.407065 0.316934 - 0.127509 -0.411345 0.319154 - 0.140622 -0.405644 0.324759 - 0.182471 -0.414076 0.342591 - 0.18413 -0.41313 0.343301 - 0.187518 -0.415707 0.34474 - 0.221071 -0.420163 0.359042 - 0.22324 -0.419884 0.359967 - 0.235926 -0.425366 0.365367 - 0.286955 -0.436613 0.387108 - 0.289942 -0.425283 0.388406 - 0.322916 -0.434774 0.40245 - 0.365461 -0.440362 0.420585 - 0.379817 -0.43361 0.426723 - 0.417862 -0.447087 0.442921 - 0.450823 -0.45243 0.456969 - 0.474489 -0.454875 0.467058 - 0.504888 -0.462095 0.480008 - 0.552045 -0.464753 0.500117 - 0.574311 -0.465647 0.509612 - 0.589267 -0.468729 0.515985 - 0.694852 -0.482194 0.560991 - 0.814241 -0.479143 0.611921 - 0.908681 -0.500349 0.652157 - 1.71114 -0.766534 0.993854 - 1.73998 -0.60956 1.0065 - 1.73363 -0.598224 1.00381 - 1.75132 -0.415745 1.01176 - 1.74847 -0.40632 1.01056 - 4.75218 -0.701638 2.29111 - 4.75767 -0.381889 2.29414 - 4.75685 -0.336326 2.29389 - 4.75364 0.0263959 2.29331 - 2.9585 0.129434 1.52785 - 2.96768 0.172396 1.53185 - 2.9847 0.302221 1.53939 - 2.98344 0.316456 1.53889 - 1.24816 0.324859 0.798751 - 1.12688 0.316717 0.747004 - 1.35425 0.626394 0.844657 - 1.33396 0.632261 0.836015 - 1.19058 0.613327 0.774817 - 1.13015 0.616129 0.749049 - 0.410561 0.255261 0.441334 - 0.34495 0.255721 0.41335 - 0.312356 0.257914 0.399452 - 0.304895 0.278518 0.396315 - 0.299376 0.28117 0.393967 - 0.462016 0.469438 0.463748 - 0.457667 0.477571 0.46191 - 0.282386 0.346212 0.386861 - 0.277235 0.343237 0.384658 - 0.233288 0.333186 0.365891 - 0.236148 0.368776 0.367188 - 0.236 0.378819 0.367147 - 0.23883 0.393822 0.368386 - 0.16295 0.322443 0.335866 - 0.157744 0.325803 0.333653 - 0.156434 0.326628 0.333096 - 0.155121 0.327446 0.332537 - 0.148195 0.356428 0.329646 - 0.236392 0.642434 0.367887 - 0.239152 0.673709 0.369132 - 0.249099 0.755476 0.373553 - 0.284051 1.0417 0.389084 - 0.271264 1.07932 0.383711 - 0.269449 1.0903 0.382961 - 0.147691 1.28451 0.331449 - -0.0287446 1.29394 0.256214 - -0.0392529 1.30078 0.251747 - -0.05506 1.30536 0.245014 - -0.0812432 1.30416 0.233844 - -0.091363 1.29751 0.229513 - -0.137245 0.462845 0.208128 - -0.128496 0.362171 0.211641 - -0.135417 0.348913 0.20866 - -0.156755 0.366669 0.199597 - -0.142143 0.267202 0.205613 - -0.154468 0.272553 0.200368 - -0.18078 0.302302 0.18921 - -0.897538 1.40285 -0.114119 - -0.949318 1.33018 -0.136364 - -0.954542 1.27882 -0.138703 - -0.968372 1.16687 -0.144846 - -0.973379 1.1526 -0.147013 - -1.29648 -1.39004 -0.310291 - -1.29059 -1.42038 -0.307755 - -1.29315 -1.44832 -0.308947 - -1.27904 -1.72377 -0.30331 - -0.207059 -0.364794 0.173583 - -0.174839 -0.367334 0.187822 - -0.155394 -0.36689 0.19642 - -0.13494 -0.37112 0.205453 - -0.116963 -0.371142 0.2134 - -0.103377 -0.381394 0.219384 - -0.0835289 -0.368828 0.228187 - -0.0830945 -0.375034 0.228365 - -0.0673373 -0.384024 0.235312 - -0.0656783 -0.383272 0.236047 - -0.0571988 -0.391499 0.239778 - -0.0460213 -0.38968 0.244723 - -0.0132005 -0.399981 0.259211 --0.00871229 -0.385901 0.261226 - 0.0432965 -0.400672 0.284187 - 0.0806552 -0.395952 0.300713 - 0.116428 -0.409943 0.316498 - 0.151909 -0.408335 0.332187 - 0.176291 -0.41776 0.342946 - 0.177539 -0.415945 0.343502 - 0.23053 -0.419481 0.366922 - 0.246158 -0.421351 0.373827 - 0.290501 -0.433053 0.393405 - 0.341837 -0.442347 0.41608 - 0.406242 -0.449738 0.444537 - 0.408031 -0.447717 0.445333 - 0.436344 -0.44528 0.457855 - 0.446998 -0.451765 0.462551 - 0.45977 -0.460142 0.46818 - 0.490694 -0.460632 0.48185 - 0.497893 -0.458935 0.485037 - 0.502247 -0.454633 0.486971 - 0.550177 -0.462054 0.508144 - 0.595429 -0.472195 0.528128 - 0.652221 -0.478676 0.553222 - 0.69847 -0.483022 0.573659 - 1.69186 -0.869235 1.01199 - 1.70588 -0.797676 1.01835 - 1.71971 -0.70814 1.02466 - 1.72983 -0.628071 1.02931 - 1.73554 -0.538774 1.03203 - 1.74362 -0.469457 1.03575 - 4.58413 -0.703204 2.29103 - 4.58072 -0.106033 2.29083 - 4.58665 0.06955 2.29383 - 2.95884 0.144432 1.57434 - 2.97746 0.288859 1.58289 - 2.98565 0.463883 1.58689 - 2.98105 0.477772 1.58489 - 1.64261 0.337725 0.992858 - 1.42867 0.330029 0.898258 - 1.17171 0.325119 0.784644 - 1.08156 0.334119 0.74481 - 1.33767 0.504128 0.858409 - 1.37375 0.623602 0.874621 - 1.3552 0.62295 0.866419 - 1.34764 0.627168 0.863085 - 0.425392 0.255042 0.454545 - 0.367797 0.250839 0.429073 - 0.364441 0.251126 0.42759 - 0.348515 0.25269 0.420552 - 0.316559 0.251183 0.406422 - 0.30399 0.279764 0.400927 - 0.423117 0.404663 0.453866 - 0.426376 0.411287 0.455322 - 0.256581 0.335943 0.380091 - 0.22194 0.347596 0.364801 - 0.165266 0.319859 0.339685 - 0.151001 0.35405 0.333453 - 0.175087 0.436991 0.344283 - 0.226801 0.567286 0.367431 - 0.226841 0.580497 0.367477 - 0.22781 0.610707 0.367972 - 0.241025 0.757972 0.374136 - 0.246386 0.805855 0.376611 - 0.249433 1.27079 0.378974 - 0.156867 1.28586 0.338084 - 0.151733 1.28668 0.335816 - 0.141578 1.28924 0.331332 - 0.110163 1.2884 0.317442 - 0.105019 1.289 0.315169 - 0.0895759 1.29065 0.308345 - 0.0327367 1.29281 0.283221 - 0.0122947 1.30258 0.274205 - -0.0345682 1.30787 0.253499 - -0.0397524 1.30578 0.251202 - -0.0765755 1.31244 0.234937 - -0.0947568 1.26622 0.226798 - -0.0462073 0.358606 0.246277 - -0.0474638 0.340401 0.245682 - -0.0469761 0.307283 0.245825 - -0.0483772 0.297053 0.245183 - -0.0495623 0.296901 0.244659 - -0.0527511 0.293439 0.243242 - -0.0591853 0.288371 0.240386 - -0.0801523 0.352354 0.231257 - -0.125842 0.419544 0.211204 - -0.136084 0.342164 0.206507 - -0.137448 0.341594 0.205903 - -0.137381 0.271915 0.20578 - -0.138465 0.271339 0.205299 - -0.139806 0.268382 0.2047 - -0.150045 0.267054 0.20017 - -0.162059 0.271129 0.194868 - -0.950673 1.33893 -0.151443 - -0.951377 1.3042 -0.15183 - -0.978884 1.14496 -0.16434 - -1.28847 -1.39967 -0.322947 - -0.294886 -0.394775 0.131155 - -0.293314 -0.396103 0.131866 - -0.261043 -0.362734 0.146617 - -0.222335 -0.364964 0.164217 - -0.213718 -0.363685 0.168139 - -0.207619 -0.359507 0.170922 - -0.196748 -0.371864 0.175839 - -0.190433 -0.366473 0.178723 - -0.174102 -0.366429 0.186151 - -0.16236 -0.372226 0.191478 - -0.125699 -0.368145 0.208161 - -0.119832 -0.370171 0.210825 - -0.0954184 -0.389604 0.221886 - -0.0843153 -0.372751 0.226973 - -0.0568971 -0.386531 0.239413 - -0.0555566 -0.388706 0.240018 - -0.0382104 -0.384298 0.247917 - -0.0259215 -0.381876 0.253511 - -0.0198341 -0.378987 0.256286 --0.00309336 -0.383692 0.26389 - 0.0303677 -0.393565 0.279087 - 0.0554839 -0.399121 0.290498 - 0.0739361 -0.399689 0.298889 - 0.0755224 -0.399249 0.299611 - 0.0939181 -0.397734 0.307981 - 0.137189 -0.408231 0.327639 - 0.161068 -0.414098 0.338486 - 0.183226 -0.413059 0.348566 - 0.184864 -0.412095 0.349313 - 0.195838 -0.416882 0.354294 - 0.28193 -0.427378 0.393427 - 0.285311 -0.424496 0.394971 - 0.325577 -0.443927 0.413241 - 0.332029 -0.440471 0.416184 - 0.334977 -0.440296 0.417525 - 0.337929 -0.440102 0.418868 - 0.346291 -0.442624 0.422665 - 0.432939 -0.452286 0.462053 - 0.490421 -0.458843 0.488182 - 0.505791 -0.460262 0.495169 - 0.542346 -0.462348 0.511791 - 0.741354 -0.485032 0.602252 - 1.58417 -0.894444 0.984676 - 1.66092 -0.927212 1.01951 - 1.68569 -0.880357 1.03088 - 1.72218 -0.712684 1.04785 - 1.73637 -0.578162 1.05459 - 1.75185 -0.44714 1.06192 - 4.45101 -0.664349 2.28906 - 4.43983 -0.274464 2.28483 - 2.98191 0.290705 1.62299 - 2.9992 0.380053 1.63105 - 1.79519 0.343702 1.08337 - 1.54583 0.335163 0.969939 - 1.49539 0.331885 0.946992 - 1.26465 0.326302 0.842036 - 1.07622 0.351218 0.756393 - 1.44264 0.514861 0.923405 - 1.36217 0.508471 0.88679 - 1.30382 0.536843 0.860316 - 1.37343 0.618836 0.892156 - 1.31229 0.621542 0.864354 - 1.3098 0.627912 0.863237 - 1.26231 0.627395 0.841633 - 1.2142 0.632374 0.819766 - 1.15248 0.621321 0.791669 - 1.13438 0.632289 0.783461 - 0.408021 0.251672 0.452266 - 0.312072 0.251631 0.408627 - 0.314963 0.261001 0.409963 - 0.310868 0.290064 0.408164 - 0.40979 0.387712 0.45337 - 0.431571 0.469127 0.463455 - 0.428593 0.48683 0.46214 - 0.42323 0.50245 0.459735 - 0.250524 0.333499 0.380815 - 0.232246 0.333541 0.372501 - 0.228247 0.337106 0.370691 - 0.222184 0.334736 0.367928 - 0.217066 0.336569 0.365604 - 0.218208 0.3444 0.366141 - 0.219989 0.356638 0.366978 - 0.156697 0.313058 0.338096 - 0.147615 0.328114 0.333998 - 0.224128 0.577771 0.369346 - 0.218899 0.62935 0.367081 - 0.222483 0.671952 0.368804 - 0.221681 0.687305 0.368474 - 0.236456 1.26743 0.376468 - -0.0556661 1.30636 0.243692 - -0.0815974 1.30516 0.231896 - -0.0856123 1.28288 0.230021 - -0.0744718 0.78054 0.233984 - -0.0605425 0.288168 0.239238 - -0.113064 0.376703 0.215545 - -0.121093 0.343708 0.21182 - -0.131723 0.330011 0.206956 - -0.153766 0.335162 0.196941 - -0.136344 0.285633 0.204757 - -0.138895 0.278802 0.203581 - -0.141934 0.270473 0.202181 - -0.143006 0.269874 0.201692 - -0.159944 0.267675 0.193983 - -0.912285 1.40003 -0.145704 - -0.945757 1.34975 -0.161038 - -0.952555 1.29974 -0.16424 - -0.95373 1.28977 -0.164796 - -0.958398 1.25082 -0.167005 - -0.968942 1.16831 -0.171981 - -1.23511 -1.5773 -0.314285 - -1.22479 -1.63493 -0.309589 - -0.288974 -0.387655 0.130467 - -0.213213 -0.360167 0.165931 - -0.200504 -0.36136 0.171867 - -0.168295 -0.370296 0.186899 - -0.166095 -0.369191 0.187929 - -0.147908 -0.371043 0.196424 - -0.14028 -0.378451 0.199972 - -0.083251 -0.375034 0.226629 - -0.0687628 -0.380812 0.233386 - -0.0672568 -0.381055 0.234089 - -0.0584117 -0.38435 0.238215 - -0.0310315 -0.38871 0.251 --0.00373034 -0.378696 0.26378 --0.00223354 -0.378626 0.26448 - 0.0517682 -0.400784 0.289666 - 0.0843807 -0.397412 0.304913 - 0.105288 -0.403887 0.314669 - 0.112565 -0.404288 0.318068 - 0.135726 -0.407307 0.328884 - 0.149398 -0.412788 0.335261 - 0.156665 -0.411323 0.33866 - 0.17205 -0.41419 0.345843 - 0.197997 -0.42386 0.357947 - 0.200564 -0.424558 0.359145 - 0.204474 -0.415127 0.360993 - 0.206112 -0.414054 0.36176 - 0.228395 -0.421163 0.372158 - 0.245449 -0.425482 0.380117 - 0.267931 -0.425011 0.390624 - 0.278989 -0.429603 0.395781 - 0.282371 -0.426731 0.397368 - 0.438026 -0.451966 0.470049 - 0.441837 -0.451765 0.47183 - 0.464444 -0.453577 0.482391 - 0.483435 -0.45503 0.491262 - 0.522635 -0.465006 0.509558 - 0.527006 -0.460395 0.511611 - 0.589607 -0.472771 0.540836 - 0.756556 -0.467862 0.618862 - 0.833284 -0.498365 0.654649 - 1.70116 -0.793698 1.05955 - 1.71682 -0.742693 1.06698 - 1.71635 -0.732904 1.06678 - 1.71977 -0.705723 1.06844 - 1.71913 -0.695985 1.06816 - 1.72881 -0.624667 1.07285 - 1.73779 -0.535741 1.07724 - 1.74684 -0.502098 1.08154 - 1.75353 -0.422934 1.08484 - 4.32216 -0.605808 2.28475 - 4.3229 -0.521148 2.28528 - 4.32575 -0.352756 2.28698 - 4.33357 -0.143248 2.2911 - 4.3345 -0.10133 2.29163 - 2.95496 0.102642 1.64743 - 2.96121 0.174731 1.65051 - 2.97724 0.291672 1.65825 - 2.98698 0.43915 1.66313 - 1.85099 0.32829 1.13204 - 1.076 0.341535 0.769925 - 1.33454 0.522655 0.891136 - 1.28016 0.544168 0.865773 - 1.39579 0.62404 0.919983 - 1.05487 0.59814 0.760617 - 0.392489 0.249 0.450318 - 0.389916 0.250004 0.449117 - 0.386553 0.250498 0.447547 - 0.372953 0.244555 0.441179 - 0.371981 0.246436 0.440729 - 0.361796 0.249815 0.435977 - 0.344699 0.248137 0.427984 - 0.339876 0.247229 0.425728 - 0.321486 0.243725 0.417126 - 0.417838 0.397262 0.46249 - 0.252304 0.3408 0.385012 - 0.229342 0.334735 0.374269 - 0.222888 0.337879 0.37126 - 0.200535 0.358319 0.36086 - 0.160514 0.319025 0.342071 - 0.14861 0.335919 0.336546 - 0.150919 0.362854 0.337684 - 0.200303 0.500963 0.361066 - 0.215236 0.647566 0.368368 - 0.216466 0.744129 0.369156 - 0.219803 0.811441 0.370864 - 0.241515 1.15583 0.38177 - 0.190028 1.2804 0.357985 - 0.123701 1.28943 0.327011 - 0.108299 1.29038 0.319816 - 0.10245 1.28303 0.317066 - 0.00601086 1.30271 0.272044 - -0.071272 1.30271 0.23593 - -0.0764209 1.30245 0.233524 - -0.0870075 1.06734 0.228057 - -0.0463824 0.308417 0.245366 - -0.0482681 0.291092 0.244447 - -0.128905 0.335381 0.206863 - -0.144136 0.335267 0.199745 - -0.153844 0.348112 0.195237 - -0.142013 0.277034 0.200609 - -0.143459 0.268382 0.199914 - -0.152413 0.275611 0.195746 - -0.592105 1.03123 -0.00805187 - -0.761713 1.27274 -0.0867761 - -0.821042 1.34828 -0.114333 - -0.945136 1.367 -0.172281 - -0.943249 1.31575 -0.171512 - -0.949112 1.30052 -0.174285 - -0.963437 1.19772 -0.181206 - -0.97356 1.11874 -0.186111 - -1.21274 -1.31677 -0.318602 - -1.20942 -1.45845 -0.317321 - -1.19945 -1.459 -0.312537 - -1.19277 -1.51608 -0.309456 - -0.288571 -0.388446 0.127178 - -0.248492 -0.35921 0.146485 - -0.189535 -0.366473 0.174776 - -0.159916 -0.371998 0.188985 - -0.131492 -0.372235 0.202631 - -0.125343 -0.373425 0.205581 - -0.119354 -0.369215 0.208466 - -0.0983876 -0.380656 0.218507 - -0.0891933 -0.381885 0.222919 - -0.0805254 -0.376636 0.227092 - -0.0621831 -0.388901 0.235872 - -0.0372701 -0.384396 0.247843 - -0.032808 -0.386643 0.24998 - -0.019088 -0.376997 0.256589 - -0.0129967 -0.388962 0.259487 --0.00363529 -0.393684 0.263971 - 0.00874115 -0.392894 0.269915 - 0.0162849 -0.390167 0.273543 - 0.0432888 -0.403341 0.286479 - 0.046459 -0.402734 0.288003 - 0.0481322 -0.393248 0.288827 - 0.0702773 -0.398179 0.299449 - 0.0882972 -0.409411 0.308076 - 0.108642 -0.40647 0.31785 - 0.110239 -0.405854 0.318618 - 0.125242 -0.412527 0.325807 - 0.14025 -0.412258 0.333014 - 0.153794 -0.412158 0.339516 - 0.155795 -0.412229 0.340477 - 0.180602 -0.422057 0.352366 - 0.221322 -0.423831 0.371912 - 0.228744 -0.424525 0.375475 - 0.259928 -0.431257 0.390432 - 0.266715 -0.422031 0.393711 - 0.296771 -0.430285 0.408123 - 0.313322 -0.433248 0.416063 - 0.313801 -0.411556 0.416342 - 0.347677 -0.434129 0.432556 - 0.422266 -0.454537 0.468323 - 0.538331 -0.464152 0.524028 - 0.557953 -0.463298 0.533451 - 0.572945 -0.462394 0.540651 - 0.658091 -0.481463 0.58149 - 0.6997 -0.486912 0.601455 - 0.705375 -0.476453 0.604203 - 0.707239 -0.472948 0.605106 - 1.68588 -0.909657 1.07401 - 1.69236 -0.882738 1.07718 - 1.73807 -0.520363 1.09993 - 1.75832 -0.354811 1.11002 - 4.20628 -0.696768 2.2846 - 4.20876 -0.262822 2.28675 - 4.20973 -0.242362 2.28726 - 4.20153 -0.200956 2.28342 - 4.20136 -0.180492 2.28338 - 4.20704 -0.0170455 2.28647 - 2.96642 0.118027 1.69111 - 2.96063 0.190054 1.68849 - 2.98289 0.279081 1.69938 - 2.98325 0.3084 1.69962 - 2.98379 0.323119 1.69991 - 2.98338 0.337748 1.69974 - 2.99832 0.413374 1.70708 - 1.56575 0.334968 1.0191 - 1.28437 0.328123 0.88398 - 1.18925 0.322661 0.838296 - 1.13681 0.320509 0.813117 - 1.09022 0.324747 0.790756 - 1.24501 0.625358 0.86574 - 1.18513 0.631011 0.837003 - 1.10626 0.630143 0.799132 - 0.391031 0.247021 0.454883 - 0.363213 0.244807 0.441522 - 0.325482 0.23874 0.423393 - 0.310949 0.261001 0.416465 - 0.307545 0.272884 0.414857 - 0.307526 0.277857 0.414858 - 0.405303 0.405705 0.462088 - 0.405869 0.432043 0.462418 - 0.411816 0.465772 0.465348 - 0.394116 0.495999 0.456917 - 0.233958 0.334198 0.379661 - 0.225826 0.335146 0.375759 - 0.197636 0.359368 0.362278 - 0.166196 0.328343 0.347114 - 0.160536 0.33101 0.344403 - 0.162617 0.403761 0.345563 - 0.233569 0.996343 0.380943 - 0.244572 1.15553 0.386579 - 0.208339 1.27422 0.369446 - 0.173737 1.28528 0.352857 - 0.168678 1.28621 0.350431 - 0.0361572 1.30054 0.286836 - 0.0156865 1.30142 0.277009 - -0.0854336 1.27589 0.228402 - -0.0833118 1.07464 0.228974 - -0.060793 0.295284 0.238057 - -0.132009 0.532346 0.20439 - -0.114938 0.343729 0.212168 - -0.119479 0.338961 0.209977 - -0.132386 0.332816 0.203766 - -0.155462 0.340641 0.192704 - -0.136269 0.276668 0.201777 - -0.137356 0.276095 0.201254 - -0.13635 0.267745 0.201719 - -0.140312 0.267795 0.199817 - -0.151075 0.270568 0.194655 - -0.203418 0.337541 0.169672 - -0.838884 1.34569 -0.133195 - -0.945369 1.31287 -0.184395 - -0.952658 1.26538 -0.188 - -0.964712 1.13303 -0.194081 - -0.360044 -0.388284 0.0887069 - -0.356689 -0.394684 0.0903442 - -1.1775 -1.4768 -0.316134 - -1.1717 -1.48243 -0.313292 - -0.290267 -0.388709 0.123056 - -0.246474 -0.363888 0.144669 - -0.232905 -0.36208 0.151353 - -0.221952 -0.363977 0.15674 - -0.20222 -0.363087 0.166456 - -0.189858 -0.376143 0.172513 - -0.161443 -0.367856 0.186519 - -0.158556 -0.369235 0.187937 - -0.143113 -0.378192 0.195519 - -0.121209 -0.370631 0.206319 - -0.10366 -0.37613 0.214946 - -0.0977558 -0.377735 0.217848 - -0.0935046 -0.379839 0.219937 - -0.0893989 -0.382864 0.221951 - -0.0721393 -0.381291 0.230451 - -0.070376 -0.379572 0.231323 - -0.0688894 -0.379822 0.232054 - -0.0283002 -0.376832 0.252042 - -0.011827 -0.390935 0.26012 - -0.0012084 -0.388538 0.265352 - 0.00505302 -0.391141 0.268429 - 0.00664801 -0.392022 0.269212 - 0.0140633 -0.388337 0.272871 - 0.0406889 -0.390521 0.285973 - 0.0772637 -0.395952 0.303966 - 0.0872611 -0.402175 0.308873 - 0.0947426 -0.392295 0.312578 - 0.129281 -0.405986 0.32955 - 0.193396 -0.420371 0.36108 - 0.195039 -0.419338 0.361891 - 0.241641 -0.424656 0.38482 - 0.261076 -0.427743 0.394381 - 0.328113 -0.435611 0.427364 - 0.372012 -0.441899 0.44896 - 0.419599 -0.450368 0.472368 - 0.505961 -0.463971 0.514851 - 0.51633 -0.460566 0.519963 - 0.575636 -0.467006 0.549143 - 0.677614 -0.483782 0.599307 - 0.692481 -0.489329 0.606614 - 0.709684 -0.462876 0.615141 - 1.671 -0.988527 1.0872 - 1.67866 -0.972065 1.09101 - 1.68837 -0.925772 1.09589 - 1.69197 -0.917466 1.09768 - 1.69494 -0.838338 1.09932 - 1.71092 -0.767135 1.10734 - 1.73545 -0.605303 1.11978 - 1.72835 -0.593561 1.11631 - 1.7525 -0.364312 1.12871 - 1.86324 -0.349367 1.18326 - 4.09465 -0.47844 2.28144 - 4.09302 0.0433233 2.2818 - 2.95552 0.161648 1.7221 - 2.96576 0.191317 1.72721 - 2.96497 0.20583 1.72685 - 2.99319 0.399832 1.74117 - 2.99603 0.41509 1.74261 - 1.9171 0.324087 1.21128 - 1.08716 0.325513 0.802722 - 1.07977 0.340549 0.799118 - 1.0767 0.345345 0.797615 - 1.07361 0.350117 0.796104 - 1.07222 0.355426 0.795434 - 1.09601 0.374981 0.807186 - 1.40065 0.53073 0.957503 - 1.37551 0.637258 0.945362 - 1.19041 0.629834 0.854227 - 0.367777 0.241691 0.448399 - 0.362572 0.245808 0.445846 - 0.327269 0.241393 0.428457 - 0.320424 0.245906 0.425098 - 0.317958 0.246456 0.423885 - 0.319408 0.261902 0.424634 - 0.311488 0.260559 0.420732 - 0.389513 0.365869 0.459376 - 0.392522 0.399216 0.460932 - 0.39919 0.423929 0.464269 - 0.399411 0.435453 0.464404 - 0.398595 0.499852 0.464146 - 0.220535 0.335932 0.376126 - 0.200806 0.353485 0.366453 - 0.151488 0.357731 0.342184 - 0.202733 0.543426 0.367825 - 0.202739 0.569673 0.367887 - 0.201913 0.707301 0.367787 - 0.202905 0.763877 0.368401 - 0.14192 1.28847 0.339549 - 0.116972 1.29507 0.327283 - 0.0659607 1.29749 0.302176 - 0.0451369 1.28897 0.291906 - 0.0249433 1.29004 0.281968 - -0.0052781 1.2999 0.267113 - -0.0154584 1.29899 0.262099 - -0.0460092 1.30067 0.247063 - -0.066591 1.30595 0.236943 - -0.0766798 1.30245 0.231969 - -0.0887604 1.24462 0.225893 - -0.0472867 0.377675 0.244377 - -0.0623798 0.288946 0.236749 - -0.122 0.574656 0.208037 - -0.127739 0.328278 0.204662 - -0.135667 0.321638 0.200745 - -0.137553 0.276997 0.199717 - -0.146794 0.270702 0.195154 - -0.635922 1.09772 -0.0437882 - -0.938574 1.38189 -0.192143 - -0.950487 1.29073 -0.19821 - -0.947605 1.27532 -0.196826 - -0.95031 1.2677 -0.198175 - -0.955593 1.25245 -0.200809 - -0.95548 1.23033 -0.200803 - -0.969924 1.13429 -0.208127 - -0.973164 1.0991 -0.209801 - -0.34939 -0.384396 0.0895349 - -1.14066 -1.31634 -0.312658 - -1.13066 -1.47547 -0.307956 - -0.253215 -0.359058 0.138222 - -0.244501 -0.358689 0.142629 - -0.238776 -0.359498 0.145522 - -0.226462 -0.362656 0.151742 - -0.209524 -0.363762 0.160304 - -0.191235 -0.368295 0.169541 - -0.162493 -0.371526 0.184068 - -0.156682 -0.374283 0.187 - -0.146462 -0.369179 0.192179 - -0.140383 -0.370684 0.195249 - -0.106151 -0.367122 0.212566 - -0.102991 -0.380424 0.214134 - -0.0932667 -0.3635 0.219089 - -0.0918502 -0.363862 0.219805 - -0.0882756 -0.385166 0.221565 - -0.0829449 -0.381243 0.224269 - -0.0607664 -0.387127 0.23547 - -0.0563358 -0.388706 0.237707 - -0.0274795 -0.390873 0.252293 - -0.0259574 -0.390912 0.253063 - -0.0198421 -0.379997 0.256179 - 0.0410221 -0.397424 0.286916 - 0.0770578 -0.398849 0.305134 - 0.0799194 -0.396935 0.306585 - 0.0814636 -0.396449 0.307367 - 0.0873096 -0.406014 0.310302 - 0.0936151 -0.403881 0.313495 - 0.102587 -0.404835 0.318029 - 0.113467 -0.411186 0.323516 - 0.147102 -0.406617 0.340534 - 0.151683 -0.413066 0.342836 - 0.161978 -0.418677 0.348029 - 0.196915 -0.421768 0.365688 - 0.20482 -0.420067 0.369689 - 0.25066 -0.422306 0.392862 - 0.329948 -0.436905 0.432921 - 0.344583 -0.439563 0.440315 - 0.628468 -0.479106 0.583772 - 0.666273 -0.474087 0.602899 - 0.665824 -0.469168 0.602683 - 1.6805 -0.989066 1.11459 - 1.7119 -0.713668 1.13108 - 1.72704 -0.671853 1.13883 - 1.72786 -0.634225 1.13933 - 1.73891 -0.516938 1.14518 - 1.7409 -0.50834 1.1462 - 1.74037 -0.372734 1.14624 - 3.98854 -0.607746 2.28249 - 3.98638 -0.54771 2.28153 - 3.99245 -0.449283 2.28482 - 3.99078 -0.330594 2.28424 - 3.99228 -0.29131 2.28509 - 3.99334 -0.19302 2.28584 - 2.97033 0.0901526 1.7692 - 1.90462 0.32379 1.23085 - 1.80774 0.344126 1.18191 - 1.59067 0.335712 1.07213 - 1.38545 0.328599 0.968348 - 1.34751 0.326702 0.949156 - 1.08558 0.321135 0.816701 - 1.39081 0.631836 0.971736 - 1.31247 0.627168 0.932115 - 1.30591 0.631718 0.928805 - 1.25351 0.628917 0.902303 - 1.14469 0.637462 0.847299 - 1.0869 0.632854 0.818067 - 0.36625 0.239809 0.452794 - 0.31821 0.245906 0.428516 - 0.316786 0.251946 0.42781 - 0.316282 0.256349 0.427565 - 0.318783 0.26807 0.428856 - 0.307277 0.263762 0.423028 - 0.321358 0.282818 0.430191 - 0.375369 0.333726 0.457615 - 0.381927 0.37116 0.461015 - 0.384341 0.397254 0.462294 - 0.390586 0.464084 0.465602 - 0.375588 0.492283 0.458081 - 0.230282 0.339717 0.384266 - 0.216224 0.338248 0.377155 - 0.213579 0.340538 0.375822 - 0.202398 0.342394 0.370173 - 0.159131 0.317293 0.348239 - 0.149543 0.31218 0.343379 - 0.147408 0.311287 0.342298 - 0.143307 0.31284 0.340228 - 0.149251 0.341238 0.343297 - 0.151564 0.356899 0.344501 - 0.196559 0.50833 0.367592 - 0.198343 0.549217 0.368586 - 0.200327 0.574422 0.369645 - 0.197076 0.601918 0.368063 - 0.199361 0.632078 0.369286 - 0.195105 0.731442 0.367357 - 0.211044 0.834874 0.375648 - 0.225794 1.27353 0.38409 - 0.180516 1.28041 0.361211 - 0.130591 1.28999 0.335988 - 0.0955364 1.29654 0.318277 - 0.0550258 1.29927 0.297799 - -0.0514353 1.30353 0.243977 - -0.0565105 1.30336 0.241411 - -0.0775568 1.044 0.230187 - -0.052971 0.295589 0.240942 - -0.125924 0.525622 0.204569 - -0.108671 0.40789 0.213029 - -0.109487 0.335076 0.212453 - -0.113689 0.33991 0.21034 - -0.118999 0.328503 0.207629 - -0.124755 0.324108 0.204708 - -0.130712 0.320519 0.201688 - -0.142193 0.323917 0.195891 - -0.152514 0.330861 0.190687 - -0.133192 0.270339 0.200322 - -0.158586 0.270086 0.187481 - -0.838731 1.38358 -0.153935 - -0.843113 1.3779 -0.156164 - -0.89978 1.39247 -0.184785 - -0.944577 1.32389 -0.20759 - -0.973496 1.11455 -0.222682 - -1.12907 -1.29788 -0.321352 - -1.1236 -1.32581 -0.318574 - -1.11845 -1.33123 -0.315914 - -1.08526 -1.52753 -0.299142 - -0.239751 -0.355692 0.142136 - -0.219629 -0.36228 0.15256 - -0.218223 -0.363263 0.153287 - -0.193548 -0.366593 0.16608 - -0.161052 -0.368774 0.182933 - -0.152536 -0.368474 0.187352 - -0.147125 -0.371975 0.190151 - -0.109809 -0.376341 0.2095 - -0.0784645 -0.372015 0.225771 - -0.07558 -0.372586 0.227266 - -0.0580224 -0.388518 0.236339 - -0.0549197 -0.387892 0.23795 - -0.0489803 -0.389536 0.241028 - -0.0427596 -0.387074 0.24426 - -0.021714 -0.383987 0.255185 --0.00403303 -0.379625 0.264368 --0.00212138 -0.389536 0.265337 - 0.00611551 -0.400002 0.269587 - 0.0118344 -0.393471 0.272568 - 0.0226968 -0.394213 0.278202 - 0.101561 -0.404835 0.319092 - 0.11995 -0.401581 0.328639 - 0.127835 -0.403415 0.332725 - 0.147558 -0.415626 0.342929 - 0.221702 -0.424872 0.381373 - 0.243921 -0.426219 0.392897 - 0.260041 -0.427993 0.401256 - 0.26707 -0.43084 0.404896 - 0.307107 -0.433248 0.425661 - 0.323146 -0.438794 0.43397 - 0.348096 -0.438906 0.446913 - 0.363044 -0.444958 0.454654 - 0.416572 -0.44891 0.482414 - 0.502493 -0.45824 0.526968 - 0.659314 -0.458343 0.608323 - 0.705813 -0.46585 0.632429 - 1.65159 -1.03035 1.12181 - 1.67977 -0.994138 1.13651 - 1.67819 -0.951242 1.13579 - 1.70061 -0.790724 1.14778 - 1.72199 -0.702455 1.15907 - 1.72754 -0.647132 1.16208 - 1.7315 -0.620125 1.16419 - 1.7491 -0.42186 1.17377 - 3.89349 -0.635769 2.28576 - 3.8959 -0.616533 2.28705 - 3.89095 -0.518077 2.2847 - 3.8873 -0.28523 2.28334 - 3.88835 -0.266025 2.28392 - 3.87017 0.0414232 2.27518 - 3.45254 0.0711155 2.05859 - 2.96735 0.0905561 1.80693 - 2.95536 0.134112 1.80081 - 2.9841 0.298526 1.81608 - 2.98782 0.32872 1.81809 - 1.63627 0.338736 1.11695 - 1.15191 0.323973 0.865636 - 1.27769 0.547735 0.931392 - 1.28467 0.558012 0.935038 - 1.34757 0.631568 0.967837 - 1.20337 0.614766 0.892988 - 0.326634 0.23241 0.437291 - 0.316548 0.248652 0.432095 - 0.314838 0.256912 0.431227 - 0.319899 0.2783 0.433901 - 0.374547 0.369918 0.462457 - 0.37358 0.378949 0.461976 - 0.374121 0.382839 0.462265 - 0.375396 0.397854 0.462961 - 0.377143 0.403141 0.463879 - 0.373432 0.471577 0.462108 - 0.285465 0.417698 0.416351 - 0.18909 0.33951 0.366177 - 0.145169 0.31889 0.343345 - 0.146673 0.338613 0.34417 - 0.186429 0.471923 0.365095 - 0.191175 0.604943 0.367857 - 0.196326 0.787112 0.37094 - 0.248142 1.05761 0.39843 - 0.23925 1.27176 0.3943 - 0.234321 1.27303 0.391745 - 0.209428 1.27801 0.378842 - 0.179494 1.28337 0.363326 - 0.154591 1.28798 0.350417 - 0.124268 1.28972 0.334689 - -0.0566156 1.29936 0.240872 - -0.0715482 1.29472 0.233115 - -0.0464396 0.359738 0.244034 - -0.0454185 0.299593 0.244428 - -0.0501573 0.300033 0.241971 - -0.0674466 0.304266 0.233011 - -0.127757 0.55791 0.202294 - -0.125656 0.535899 0.203335 - -0.106046 0.411668 0.213228 - -0.101473 0.349036 0.215459 - -0.1112 0.331316 0.210374 - -0.119438 0.330396 0.206098 - -0.128314 0.318261 0.201465 - -0.14657 0.328203 0.192017 - -0.138301 0.282997 0.196205 - -0.138244 0.279704 0.196227 - -0.151278 0.275611 0.189456 - -0.159574 0.272683 0.185146 - -0.952026 1.30554 -0.223637 - -0.958193 1.22421 -0.22702 - -0.9688 1.12428 -0.232748 - -1.09399 -1.31973 -0.317279 - -1.08889 -1.32503 -0.314579 - -1.09029 -1.33845 -0.315353 - -1.07545 -1.45461 -0.307726 - -0.243719 -0.356767 0.137136 - -0.182468 -0.367148 0.16969 - -0.181051 -0.36795 0.170442 - -0.174108 -0.364009 0.174144 - -0.163469 -0.376113 0.179775 - -0.150976 -0.374418 0.186423 - -0.133529 -0.37641 0.195698 - -0.122675 -0.372034 0.201481 - -0.103484 -0.383335 0.211662 - -0.0736195 -0.379051 0.227556 - -0.0724316 -0.381291 0.228183 - -0.0666687 -0.383272 0.231244 - -0.037658 -0.369419 0.246705 - -0.0323597 -0.381716 0.249495 - -0.0293167 -0.377831 0.251123 - -0.027861 -0.377877 0.251897 - -0.0130116 -0.394934 0.259756 - 0.0143246 -0.393153 0.274299 - 0.0397779 -0.39841 0.287825 - 0.0493037 -0.398483 0.292892 - 0.0580938 -0.402555 0.297558 - 0.0846793 -0.403135 0.311696 - 0.094499 -0.401817 0.316922 - 0.117931 -0.409476 0.329368 - 0.12108 -0.408103 0.331045 - 0.152452 -0.421236 0.347702 - 0.152343 -0.406924 0.347676 - 0.166474 -0.407905 0.35519 - 0.229631 -0.421349 0.388751 - 0.380542 -0.452219 0.468946 - 0.384638 -0.44895 0.471132 - 0.429973 -0.449549 0.495243 - 0.433693 -0.4493 0.497222 - 0.473948 -0.455774 0.518618 - 0.634363 -0.466374 0.603914 - 0.633416 -0.456742 0.603432 - 0.639688 -0.456643 0.606768 - 0.641437 -0.453382 0.607706 - 1.63041 -1.04429 1.13237 - 1.63441 -1.03613 1.13452 - 1.71312 -0.771158 1.17699 - 1.71937 -0.676401 1.18052 - 1.72198 -0.648694 1.18198 - 1.73715 -0.550134 1.19027 - 1.75007 -0.498112 1.19726 - 1.75391 -0.425383 1.19946 - 1.7571 -0.40784 1.2012 - 1.76761 -0.355376 1.20691 - 1.77331 -0.347384 1.20996 - 1.88224 -0.349175 1.26789 - 3.78591 -0.660126 2.2797 - 3.78559 -0.44979 2.28 - 2.97828 0.0913901 1.85184 - 2.96332 0.12045 1.84395 - 2.97617 0.21003 1.85099 - 2.99397 0.406573 1.8609 - 2.98894 0.436095 1.85829 - 1.89031 0.324979 1.27371 - 1.8367 0.34407 1.24524 - 1.08282 0.341532 0.844265 - 1.09287 0.374395 0.849688 - 1.44827 0.517783 1.03904 - 1.38893 0.527587 1.0075 - 1.3758 0.640227 1.00077 - 1.2634 0.625935 0.940957 - 1.25612 0.629877 0.937092 - 1.16031 0.631866 0.886138 - 1.14665 0.638725 0.878886 - 0.353647 0.234955 0.456198 - 0.32934 0.228787 0.443256 - 0.330874 0.241518 0.444101 - 0.329939 0.243249 0.443607 - 0.319437 0.245287 0.438026 - 0.365305 0.326403 0.462606 - 0.362772 0.3302 0.461267 - 0.361773 0.341434 0.460761 - 0.362585 0.351475 0.461216 - 0.36152 0.389747 0.460736 - 0.367981 0.40692 0.464212 - 0.359409 0.415717 0.459672 - 0.359696 0.419684 0.459834 - 0.367271 0.439431 0.463908 - 0.347622 0.488482 0.453568 - 0.277431 0.416794 0.416073 - 0.202132 0.343728 0.375858 - 0.17253 0.326925 0.360076 - 0.156724 0.389534 0.351811 - 0.184868 0.510656 0.367054 - 0.186972 0.57493 0.368319 - 0.18673 0.682834 0.368435 - 0.185656 0.74216 0.367997 - 0.247003 1.17652 0.40161 - 0.0928771 1.28957 0.319891 - 0.0585313 1.30089 0.301649 - 0.0133001 1.30042 0.277591 - -0.0519938 1.30652 0.242877 - -0.0459368 0.349773 0.243931 - -0.0500607 0.285978 0.241593 - -0.0529405 0.291622 0.240074 - -0.117821 0.566318 0.206189 - -0.0982921 0.347889 0.21608 - -0.107469 0.338825 0.211179 - -0.117292 0.32377 0.20592 - -0.118904 0.319964 0.205054 - -0.124413 0.324108 0.202134 - -0.128435 0.319195 0.199983 - -0.146535 0.274869 0.190256 - -0.832041 1.35978 -0.171887 - -0.830792 1.34502 -0.171256 - -0.952108 1.26628 -0.235959 - -0.957818 1.25169 -0.239029 - -0.957022 1.22876 -0.238658 - -0.96485 1.17543 -0.242942 - -0.965779 1.16633 -0.243457 - -1.07479 -1.23649 -0.321381 - -1.06026 -1.28519 -0.313563 - -1.05779 -1.38784 -0.312449 - -1.05273 -1.40578 -0.309734 - -1.04528 -1.45923 -0.305788 - -0.247609 -0.357773 0.131933 - -0.242089 -0.362249 0.134935 - -0.178952 -0.364369 0.169377 - -0.176537 -0.366837 0.17069 - -0.163752 -0.364823 0.17767 - -0.157681 -0.375449 0.180958 - -0.146469 -0.371975 0.187083 - -0.142685 -0.370415 0.189151 - -0.0571444 -0.391688 0.235774 - -0.053883 -0.38906 0.23756 - -0.0473478 -0.381707 0.241142 - -0.0296714 -0.378831 0.250793 - -0.0209716 -0.382997 0.25553 - -0.018043 -0.381994 0.25713 - 0.0134887 -0.390167 0.274315 - 0.0407292 -0.399099 0.289157 - 0.0473416 -0.391613 0.292782 - 0.0589974 -0.403144 0.299115 - 0.0785867 -0.402715 0.309804 - 0.130921 -0.40841 0.338345 - 0.14545 -0.412075 0.346264 - 0.174243 -0.414824 0.361967 - 0.202094 -0.419828 0.377151 - 0.232712 -0.42966 0.393834 - 0.252554 -0.422351 0.404677 - 0.343278 -0.438906 0.454138 - 0.34677 -0.439273 0.456043 - 0.353173 -0.439207 0.459536 - 0.366382 -0.446888 0.466726 - 0.411408 -0.445422 0.491296 - 0.449307 -0.447634 0.511968 - 0.569186 -0.464629 0.577336 - 0.620737 -0.468494 0.605453 - 0.647514 -0.45143 0.620102 - 1.71073 -0.794606 1.19942 - 1.70722 -0.78304 1.19753 - 1.71873 -0.699555 1.20399 - 1.73222 -0.561245 1.21167 - 1.73869 -0.369758 1.21564 - 1.76181 -0.347216 1.2283 - 3.6862 -0.347708 2.27826 - 3.68929 -0.218363 2.28023 - 2.96776 0.0916054 1.88727 - 2.96819 0.195796 1.88775 - 2.9674 0.210648 1.88735 - 2.97981 0.301514 1.89433 - 2.99444 0.393838 1.90252 - 2.99464 0.409057 1.90266 - 1.88593 0.326167 1.29756 - 1.81963 0.34294 1.26142 - 1.65994 0.338962 1.17429 - 1.505 0.331223 1.08973 - 1.26748 0.326374 0.960132 - 1.40751 0.529909 1.037 - 1.30467 0.535855 0.980896 - 1.19062 0.637364 0.918903 - 1.14601 0.628021 0.894545 - 1.13805 0.630796 0.890206 - 0.327705 0.229288 0.447164 - 0.326387 0.237719 0.446464 - 0.390283 0.334244 0.481546 - 0.35566 0.335231 0.462658 - 0.34972 0.33893 0.459425 - 0.350385 0.364546 0.459846 - 0.355739 0.464402 0.462995 - 0.296205 0.450255 0.430481 - 0.197307 0.345099 0.376282 - 0.195473 0.345363 0.375282 - 0.158605 0.320636 0.35511 - 0.146086 0.325803 0.348292 - 0.161651 0.399305 0.356952 - 0.180162 0.64776 0.367617 - 0.18302 0.738344 0.369383 - 0.224974 0.964092 0.392788 - 0.170953 1.28039 0.364034 - 0.115742 1.2795 0.333909 - 0.0977395 1.29994 0.324133 - 0.087528 1.29808 0.318558 - 0.0574801 1.29789 0.302163 - 0.0421252 1.28997 0.293767 - 0.0225487 1.29703 0.283102 - 0.0126359 1.29842 0.277697 - -0.0478395 0.29535 0.242416 - -0.10872 0.52652 0.209726 - -0.111976 0.32991 0.207502 - -0.115335 0.322351 0.205652 - -0.118661 0.324231 0.203841 - -0.124845 0.321713 0.200462 - -0.130332 0.317181 0.197458 - -0.136718 0.315296 0.193969 - -0.145788 0.323916 0.18904 - -0.154983 0.270569 0.183902 - -0.932567 1.37529 -0.237834 - -0.945355 1.34516 -0.24488 - -0.9474 1.32419 -0.246043 - -0.962575 1.16854 -0.254677 - -1.04495 -1.33025 -0.319158 - -1.04104 -1.39735 -0.317129 - -1.0393 -1.4327 -0.316236 - -0.247354 -0.362151 0.128994 - -0.228566 -0.364794 0.139492 - -0.226226 -0.364154 0.140802 - -0.215117 -0.361561 0.147019 - -0.189373 -0.36918 0.161394 - -0.187965 -0.370023 0.16218 - -0.185359 -0.36819 0.163641 - -0.174241 -0.366712 0.169861 - -0.166136 -0.367745 0.17439 - -0.15734 -0.371077 0.1793 - -0.141034 -0.376315 0.188404 - -0.125359 -0.37195 0.197179 - -0.0849854 -0.393034 0.219703 - -0.0386409 -0.378405 0.245648 - -0.0312579 -0.372781 0.249788 - -0.0257 -0.381946 0.252875 - -0.0125041 -0.386901 0.260241 --0.00811653 -0.385754 0.262697 - 0.00876177 -0.394615 0.272113 - 0.0255986 -0.395548 0.281525 - 0.0581568 -0.394948 0.299729 - 0.0608473 -0.400398 0.301221 - 0.130559 -0.405817 0.340184 - 0.143286 -0.414715 0.347279 - 0.158138 -0.413309 0.355586 - 0.171221 -0.42479 0.362875 - 0.200458 -0.419828 0.379233 - 0.209599 -0.42044 0.384342 - 0.224263 -0.426302 0.392527 - 0.226849 -0.426743 0.393972 - 0.27468 -0.431584 0.420703 - 0.281772 -0.430244 0.424671 - 0.323126 -0.439887 0.44777 - 0.342505 -0.437098 0.458611 - 0.362586 -0.445462 0.469819 - 0.418068 -0.451298 0.500826 - 0.45296 -0.454056 0.520328 - 0.461118 -0.453759 0.524889 - 0.487479 -0.457706 0.539619 - 0.59787 -0.472275 0.601305 - 0.60549 -0.473592 0.605562 - 0.592464 -0.450662 0.598332 - 0.6178 -0.451486 0.612496 - 1.54286 -1.0317 1.12837 - 1.5415 -0.98965 1.1277 - 1.54371 -0.980876 1.12896 - 1.55311 -0.926342 1.13434 - 1.54207 -0.871057 1.12829 - 1.6569 -0.863577 1.19251 - 1.72685 -0.6198 1.23218 - 1.73448 -0.565306 1.23657 - 1.7402 -0.501248 1.23991 - 1.74996 -0.420268 1.24555 - 3.59321 -0.615574 2.27567 - 3.59591 -0.542328 2.27734 - 3.59554 -0.50555 2.27722 - 3.59637 -0.323065 2.2781 - 3.59457 -0.250281 2.27727 - 3.60084 -0.033192 2.28127 - 2.96607 0.0920896 1.92665 - 2.98465 0.349252 1.93763 - 2.98508 0.455949 1.93812 - 1.12779 0.32302 0.899405 - 1.08218 0.333682 0.873927 - 1.0648 0.345908 0.864241 - 1.22914 0.425359 0.956306 - 1.38535 0.532609 1.04389 - 1.33573 0.582473 1.01626 - 1.07592 0.634651 0.871117 - 1.06028 0.6324 0.862367 - 0.324028 0.237719 0.449827 - 0.316462 0.244142 0.445612 - 0.406148 0.355965 0.496011 - 0.352773 0.325959 0.4661 - 0.343316 0.344421 0.460856 - 0.346766 0.414543 0.462945 - 0.345884 0.428255 0.462483 - 0.343032 0.476217 0.460998 - 0.209026 0.343713 0.385773 - 0.197783 0.335907 0.379469 - 0.179966 0.332112 0.369499 - 0.148296 0.34306 0.351817 - 0.172676 0.426813 0.36564 - 0.174082 0.497072 0.366587 - 0.172186 0.498042 0.365529 - 0.177911 0.627879 0.369027 - 0.176625 0.69919 0.368471 - 0.225476 0.989342 0.396449 - 0.17463 1.2814 0.36869 - 0.130677 1.29023 0.344136 - 0.0421262 1.30595 0.294664 - 0.0370634 1.30426 0.291829 - 0.0217644 1.29304 0.28325 - 0.0121138 1.30142 0.277874 - -0.052389 1.30353 0.241815 - -0.0460841 0.384917 0.243235 - -0.0531265 0.289638 0.239079 - -0.11206 0.547148 0.20672 - -0.114502 0.324719 0.204845 - -0.117535 0.325663 0.203151 - -0.12585 0.325464 0.198502 - -0.151881 0.332684 0.183964 - -0.138392 0.266902 0.191355 - -0.155282 0.274724 0.18193 - -0.156327 0.274049 0.181345 - -0.157812 0.266129 0.180496 - -0.8114 1.33907 -0.182466 - -0.826023 1.33853 -0.190643 - -0.970439 1.14385 -0.271831 - -0.907835 -1.05227 -0.254519 - -0.959378 -1.15307 -0.284303 - -1.01689 -1.31279 -0.317649 - -0.242641 -0.352917 0.128482 - -0.200241 -0.363057 0.152769 - -0.186133 -0.367361 0.160848 - -0.161444 -0.369903 0.174997 - -0.139861 -0.363867 0.187386 - -0.138481 -0.364464 0.188175 - -0.0897201 -0.376644 0.216104 - -0.0854945 -0.369485 0.218544 - -0.0404504 -0.380305 0.244345 - -0.0129787 -0.384901 0.260085 - 0.0162849 -0.384668 0.276864 - 0.075738 -0.398862 0.310918 - 0.0799563 -0.402684 0.313328 - 0.0834959 -0.403575 0.315356 - 0.117175 -0.407171 0.334657 - 0.145765 -0.414881 0.351032 - 0.174751 -0.413759 0.367653 - 0.22048 -0.422958 0.393851 - 0.245899 -0.425853 0.408418 - 0.257504 -0.428437 0.415066 - 0.352259 -0.444239 0.469357 - 0.363037 -0.437575 0.475552 - 0.415806 -0.444252 0.505791 - 0.460857 -0.452613 0.531603 - 0.493258 -0.461931 0.550158 - 0.539238 -0.467995 0.576507 - 1.50512 -0.884515 1.12933 - 1.5569 -0.846027 1.15911 - 1.68859 -0.854682 1.2346 - 1.71575 -0.697159 1.25053 - 1.72432 -0.642106 1.25557 - 1.74223 -0.542819 1.26607 - 1.74738 -0.431599 1.26928 - 3.50656 -0.568351 2.27759 - 2.95749 0.107394 1.96434 - 2.98443 0.44333 1.98055 - 1.18735 0.322692 0.949924 - 1.08887 0.320024 0.893452 - 1.43785 0.507582 1.09398 - 1.36237 0.629708 1.05098 - 1.26057 0.636216 0.992626 - 1.20809 0.624883 0.96251 - 0.341822 0.222833 0.464911 - 0.337409 0.347405 0.462668 - 0.334234 0.410419 0.460992 - 0.320945 0.492393 0.453562 - 0.141503 0.318939 0.35028 - 0.150634 0.354377 0.355596 - 0.153216 0.37893 0.357134 - 0.168022 0.497172 0.365895 - 0.174351 0.574231 0.369702 - 0.172682 0.633617 0.368881 - 0.170849 0.636476 0.367837 - 0.13897 1.28767 0.351061 - 0.0903391 1.29753 0.323201 - 0.0607691 1.29948 0.306251 - -0.0458048 0.376939 0.24302 - -0.0491319 0.292229 0.240918 - -0.0503375 0.293079 0.240228 - -0.0641811 0.294863 0.232295 - -0.117765 0.543777 0.202147 - -0.113048 0.506089 0.204764 - -0.101074 0.336643 0.211239 - -0.108166 0.326983 0.20715 - -0.116874 0.319505 0.202141 - -0.119288 0.31853 0.200754 - -0.137945 0.324183 0.190071 - -0.144092 0.263283 0.186405 - -0.160384 0.264051 0.177066 - -0.728671 1.2763 -0.146427 - -0.796794 1.32166 -0.185381 - -0.890368 1.38787 -0.238879 - -0.937818 1.37332 -0.266118 - -0.941833 1.29556 -0.268599 - -0.821091 -0.938118 -0.215604 - -0.292511 -0.389578 0.0960431 - -0.265812 -0.370702 0.111764 - -0.258686 -0.363177 0.115966 - -0.24251 -0.360839 0.12547 - -0.238503 -0.367743 0.127807 - -0.189239 -0.363949 0.156743 - -0.175381 -0.372118 0.164861 - -0.160602 -0.373361 0.173536 - -0.154767 -0.366473 0.176978 - -0.145187 -0.366689 0.182603 - -0.130692 -0.365454 0.191117 - -0.129591 -0.372235 0.191748 - -0.124318 -0.370047 0.194849 - -0.11596 -0.379299 0.199735 - -0.103221 -0.363678 0.207252 - -0.0814584 -0.38057 0.219991 - -0.0805173 -0.393973 0.220513 - -0.0790341 -0.394271 0.221383 - -0.0599608 -0.385343 0.232603 - -0.036485 -0.382571 0.246394 - -0.0206336 -0.385999 0.255694 - -0.019192 -0.383994 0.256545 - 0.00177342 -0.39613 0.268828 - 0.016364 -0.391626 0.277406 - 0.0359478 -0.402646 0.28888 - 0.040447 -0.391596 0.291547 - 0.0483179 -0.392891 0.296166 - 0.0653388 -0.399689 0.306144 - 0.07352 -0.400307 0.310947 - 0.117552 -0.41183 0.336775 - 0.150265 -0.40611 0.355997 - 0.15447 -0.411516 0.358454 - 0.189834 -0.422442 0.379194 - 0.193003 -0.420294 0.38106 - 0.224506 -0.41722 0.399565 - 0.234646 -0.422466 0.405506 - 0.278997 -0.428731 0.431534 - 0.298104 -0.432402 0.442745 - 0.361599 -0.438982 0.480014 - 0.39486 -0.444942 0.49953 - 0.431537 -0.451328 0.521051 - 0.47042 -0.45651 0.543871 - 0.531665 -0.460507 0.579824 - 0.558734 -0.469844 0.595697 - 0.575394 -0.448279 0.605529 - 0.593752 -0.444614 0.616317 - 1.43811 -1.00448 1.11081 - 1.44186 -0.997094 1.11304 - 1.47062 -0.956726 1.13002 - 1.4732 -0.938743 1.13157 - 1.57064 -0.848956 1.189 - 1.70103 -0.845653 1.26557 - 1.72188 -0.713879 1.27811 - 1.7239 -0.694919 1.27935 - 1.73315 -0.591199 1.28502 - 1.73548 -0.54411 1.28649 - 1.74092 -0.395588 1.29003 - 3.41728 -0.628472 2.27383 - 3.42471 -0.611979 2.27823 - 3.42718 -0.452624 2.28005 - 3.42353 -0.188962 2.27852 - 1.88983 0.323033 1.37914 - 1.446 0.332099 1.11855 - 1.37247 0.330131 1.07537 - 1.09856 0.324877 0.91452 - 1.08645 0.339299 0.907439 - 1.42762 0.51521 1.10818 - 1.28743 0.622464 1.02611 - 0.434392 0.264087 0.524387 - 0.348651 0.221465 0.473942 - 0.331332 0.227188 0.463786 - 0.329605 0.23075 0.46278 - 0.321143 0.241518 0.457836 - 0.316509 0.250129 0.455136 - 0.684023 0.584781 0.671711 - 0.326969 0.319127 0.461438 - 0.32665 0.367405 0.461362 - 0.33076 0.435134 0.463932 - 0.324149 0.466193 0.460123 - 0.323276 0.477536 0.459637 - 0.199751 0.347452 0.386802 - 0.166029 0.320048 0.366938 - 0.163612 0.321934 0.365523 - 0.162123 0.32547 0.364657 - 0.157618 0.320523 0.362 - 0.156409 0.321426 0.361292 - 0.167383 0.450454 0.368035 - 0.165211 0.460524 0.366783 - 0.163893 0.467849 0.366026 - 0.159746 0.522157 0.363717 - 0.162314 0.572461 0.365341 - 0.163699 0.717376 0.366491 - 0.165864 0.737489 0.367809 - 0.123388 1.29296 0.344156 - 0.0937935 1.29297 0.326778 - 0.0301515 1.29255 0.289408 - -0.0719798 1.29073 0.229433 - -0.0493458 0.292229 0.240408 - -0.0504449 0.292085 0.239762 - -0.0922739 0.360817 0.21536 - -0.107297 0.329332 0.206466 - -0.119082 0.31853 0.199521 - -0.132997 0.323131 0.191361 - -0.138301 0.283313 0.188154 - -0.137391 0.274933 0.188669 - -0.140483 0.273151 0.186849 - -0.146545 0.263789 0.183268 - -0.156502 0.265268 0.177425 - -0.772675 1.35007 -0.181868 - -0.901596 1.38795 -0.257481 - -0.917687 1.38782 -0.26693 - -0.922896 1.38327 -0.269999 - -0.922967 1.16831 -0.270539 - -0.926723 1.14275 -0.272804 - -0.922361 1.10782 -0.270324 - -0.923971 1.08113 -0.271331 - -0.813444 -0.934564 -0.222414 - -0.949472 -1.24908 -0.304961 - -0.92708 -1.2517 -0.2915 - -0.292939 -0.395631 0.0919009 - -0.268658 -0.373415 0.106556 - -0.252461 -0.365146 0.116317 - -0.23413 -0.361971 0.12735 - -0.174048 -0.370316 0.163466 - -0.171926 -0.369284 0.164745 - -0.153843 -0.374283 0.175609 - -0.130107 -0.375076 0.189883 - -0.100433 -0.37169 0.207738 - -0.0869684 -0.378306 0.215821 - -0.0855529 -0.378637 0.216672 - -0.0841362 -0.378961 0.217523 - -0.0588396 -0.387524 0.232718 - -0.0281906 -0.383914 0.25116 - -0.0123741 -0.38486 0.260671 --0.00492527 -0.390535 0.265138 - 0.035294 -0.392493 0.289323 - 0.04803 -0.39583 0.296975 - 0.0631739 -0.393868 0.306088 - 0.0661331 -0.400218 0.307853 - 0.0787028 -0.405567 0.3154 - 0.0948558 -0.403887 0.325119 - 0.104756 -0.403021 0.331076 - 0.146522 -0.409631 0.356181 - 0.15072 -0.406137 0.358713 - 0.197544 -0.415902 0.386853 - 0.22104 -0.418458 0.400979 - 0.250237 -0.427421 0.418518 - 0.287463 -0.424858 0.440913 - 0.332179 -0.445433 0.46776 - 0.342638 -0.435202 0.474074 - 0.34787 -0.437622 0.477216 - 0.379603 -0.447068 0.496279 - 0.403461 -0.449453 0.510623 - 0.446891 -0.453604 0.536734 - 0.453583 -0.451981 0.540763 - 0.4948 -0.457164 0.56554 - 0.52612 -0.463298 0.584363 - 0.534448 -0.461768 0.589376 - 0.563375 -0.455071 0.60679 - 0.616001 -0.45937 0.638432 - 1.42055 -0.988984 1.12109 - 1.43392 -0.88209 1.12938 - 1.4555 -0.829406 1.14248 - 1.62298 -0.852345 1.24316 - 1.70241 -0.820962 1.291 - 1.70846 -0.803383 1.29469 - 1.71522 -0.686086 1.29902 - 1.71776 -0.677239 1.30057 - 1.72274 -0.659508 1.30361 - 1.72595 -0.641126 1.30558 - 1.72968 -0.613237 1.30789 - 1.74718 -0.503345 1.31867 - 1.74604 -0.465055 1.31807 - 1.74691 -0.446407 1.31865 - 1.74856 -0.4374 1.31966 - 1.73916 -0.379197 1.31414 - 1.76774 -0.357165 1.33138 - 3.27183 -0.605737 2.23543 - 3.32912 -0.598807 2.2699 - 3.333 -0.582037 2.27228 - 3.33789 -0.495763 2.27542 - 3.34249 -0.288839 2.27867 - 3.34014 -0.014267 2.2779 - 1.61501 0.338265 1.24115 - 1.19894 0.323474 0.990868 - 1.4362 0.521657 1.13403 - 1.38942 0.528611 1.10591 - 1.2978 0.539173 1.05083 - 1.21583 0.621981 1.00172 - 0.326027 0.234795 0.465647 - 0.325883 0.237068 0.465566 - 0.326467 0.239853 0.465924 - 0.322431 0.258877 0.463541 - 0.358884 0.332393 0.485637 - 0.335946 0.318082 0.471807 - 0.32425 0.316127 0.464769 - 0.317253 0.35387 0.460648 - 0.318806 0.381312 0.461646 - 0.316325 0.38859 0.460171 - 0.321725 0.427116 0.463509 - 0.305947 0.486389 0.454157 - 0.191566 0.346723 0.385037 - 0.154652 0.36132 0.362869 - 0.152776 0.364851 0.361749 - 0.159079 0.43427 0.365702 - 0.161209 0.459653 0.367043 - 0.161655 0.471515 0.367339 - 0.161243 0.481593 0.367115 - 0.166633 0.78456 0.371063 - 0.255577 1.23805 0.425617 - 0.209106 1.27863 0.397762 - 0.165038 1.28237 0.371266 - 0.150635 1.28513 0.36261 - 0.13115 1.28649 0.350893 - 0.0535708 1.29091 0.304244 - -0.0432716 1.30178 0.246024 - -0.0628002 1.30317 0.234282 - -0.0450672 0.338932 0.242697 - -0.046362 0.293621 0.241812 - -0.0474595 0.293494 0.241152 - -0.0818209 0.393872 0.22072 - -0.10436 0.480514 0.207365 - -0.0951864 0.335291 0.212544 - -0.09791 0.3355 0.210907 - -0.101509 0.328129 0.208725 - -0.103959 0.327307 0.207249 - -0.114774 0.327567 0.200745 - -0.115914 0.317614 0.200036 - -0.125115 0.321191 0.194511 - -0.165394 0.362227 0.170381 - -0.152907 0.269699 0.177675 - -0.16187 0.274032 0.172295 - -0.879082 1.38544 -0.256477 - -0.900168 1.3686 -0.269198 - -0.907735 1.29603 -0.273919 - -0.904641 1.19242 -0.2723 - -0.902756 1.16911 -0.271221 - -0.885449 -1.18026 -0.278768 - -0.884056 -1.22089 -0.278005 - -0.290511 -0.39407 0.0894837 - -0.249663 -0.359156 0.114723 - -0.244472 -0.357444 0.117924 - -0.218599 -0.363669 0.133843 - -0.184757 -0.364753 0.154683 - -0.178545 -0.366255 0.158505 - -0.153447 -0.369914 0.173954 - -0.129239 -0.373182 0.188855 - -0.122643 -0.37152 0.192922 - -0.115271 -0.378339 0.197446 - -0.114097 -0.379777 0.198165 - -0.0681873 -0.379076 0.226441 - -0.059524 -0.378391 0.231778 - -0.0561762 -0.388887 0.233816 - -0.0326552 -0.378778 0.248325 - -0.0284832 -0.381914 0.250887 - -0.0242489 -0.385987 0.253485 - -0.018549 -0.381982 0.257005 - 5.646e-05 -0.384157 0.268459 - 0.0107839 -0.392158 0.275047 - 0.0136962 -0.391811 0.276841 - 0.0271362 -0.392849 0.285116 - 0.0337966 -0.397712 0.289206 - 0.0508698 -0.399022 0.299718 - 0.0669053 -0.400737 0.30959 - 0.106262 -0.406127 0.333816 - 0.125187 -0.410253 0.345461 - 0.136383 -0.411069 0.352355 - 0.138972 -0.412985 0.353945 - 0.145081 -0.409631 0.357715 - 0.214593 -0.418408 0.400505 - 0.232523 -0.429504 0.411521 - 0.236195 -0.427699 0.413787 - 0.236866 -0.420986 0.414216 - 0.297104 -0.429912 0.451294 - 0.49487 -0.456336 0.57303 - 0.557136 -0.440663 0.611415 - 1.29797 -0.94773 1.06648 - 1.38679 -0.99179 1.12108 - 1.39558 -0.988142 1.1265 - 1.3977 -0.970064 1.12785 - 1.39308 -0.872285 1.12523 - 1.66683 -0.860255 1.29386 - 1.70039 -0.815172 1.31463 - 1.71206 -0.719209 1.32205 - 1.7415 -0.4955 1.3407 - 1.75183 -0.431632 1.34721 - 1.73928 -0.381738 1.3396 - 1.74067 -0.372711 1.34048 - 3.24203 -0.60418 2.26458 - 3.24962 -0.384034 2.26977 - 3.25356 -0.333713 2.27231 - 3.25352 -0.131533 2.27276 - 3.25891 -0.0812749 2.2762 - 3.2587 -0.0140124 2.27623 - 3.25779 0.0196061 2.27575 - 2.97006 0.232903 2.09904 - 2.98236 0.35793 2.10691 - 2.99563 0.390794 2.11516 - 2.99667 0.406598 2.11584 - 1.85535 0.331217 1.41276 - 1.69144 0.338324 1.31183 - 1.17296 0.325174 0.992481 - 1.39983 0.528049 1.13268 - 1.30708 0.538972 1.07558 - 1.01881 0.571422 0.898126 - 0.334194 0.213679 0.475648 - 0.339304 0.223803 0.478819 - 0.32812 0.233215 0.471953 - 0.314975 0.245503 0.463886 - 0.331294 0.267543 0.473989 - 0.716703 0.592138 0.712113 - 0.706545 0.600582 0.705877 - 0.306328 0.313052 0.45872 - 0.309995 0.325118 0.461007 - 0.306984 0.33085 0.459166 - 0.312166 0.351205 0.462405 - 0.310106 0.374392 0.461191 - 0.30762 0.391593 0.4597 - 0.307071 0.483029 0.459577 - 0.289745 0.487433 0.448916 - 0.17327 0.328646 0.37681 - 0.14837 0.330996 0.36148 - 0.15776 0.407291 0.367443 - 0.152812 0.413609 0.36441 - 0.153447 0.539759 0.365098 - 0.155248 0.626044 0.36641 - 0.156422 0.724029 0.367362 - 0.197039 1.27703 0.393676 - 0.130583 1.29342 0.352786 - 0.101697 1.29771 0.335006 - 0.0968734 1.29834 0.332037 - 0.0627273 1.29706 0.311005 - 0.0477761 1.28929 0.301778 - -0.0468008 0.431054 0.241516 - -0.0438921 0.30194 0.243004 - -0.0581905 0.29804 0.234188 - -0.0729225 0.343915 0.225223 - -0.100133 0.501794 0.208836 - -0.114029 0.325668 0.199864 - -0.139674 0.323917 0.184066 - -0.143821 0.292004 0.181437 - -0.13912 0.274645 0.184292 - -0.14419 0.271587 0.181162 - -0.15445 0.268355 0.174835 - -0.157305 0.268713 0.173078 - -0.769579 1.23821 -0.201726 - -0.870623 1.36732 -0.263652 - -0.880741 1.35859 -0.269904 - -0.885511 1.20502 -0.273203 - -0.879913 1.16592 -0.269847 - -0.850722 -1.09016 -0.268425 - -0.273755 -0.377953 0.096423 - -0.235709 -0.357872 0.120418 - -0.226214 -0.358319 0.126393 - -0.217719 -0.360132 0.131736 - -0.2119 -0.366798 0.135383 - -0.197085 -0.370088 0.1447 - -0.19191 -0.366617 0.147966 - -0.1864 -0.362187 0.151444 - -0.182371 -0.364699 0.153974 - -0.154025 -0.368315 0.171808 - -0.152663 -0.368992 0.172663 - -0.138328 -0.373499 0.181676 - -0.11711 -0.374491 0.195029 - -0.0373205 -0.38357 0.24523 - -0.0231397 -0.380997 0.254162 - -0.0146586 -0.382902 0.259496 - 0.00094023 -0.383044 0.269314 - 0.00335955 -0.376812 0.270852 - 0.0272369 -0.398787 0.285829 - 0.0313814 -0.396017 0.288444 - 0.056353 -0.399424 0.304154 - 0.0638898 -0.405509 0.308884 - 0.0704565 -0.399342 0.313032 - 0.148235 -0.411501 0.361959 - 0.160817 -0.414076 0.369873 - 0.165063 -0.414824 0.372544 - 0.25917 -0.428312 0.431746 - 0.274477 -0.431838 0.441373 - 0.298724 -0.435191 0.456627 - 0.350755 -0.443545 0.489357 - 0.359063 -0.437885 0.4946 - 0.370241 -0.442922 0.501624 - 0.449604 -0.45451 0.551551 - 0.471229 -0.45455 0.565162 - 0.52753 -0.462348 0.600582 - 0.529229 -0.459511 0.601658 - 0.532596 -0.453811 0.60379 - 1.35469 -0.985005 1.11999 - 1.36292 -0.895854 1.12539 - 1.62749 -0.855628 1.29201 - 1.70951 -0.793702 1.34378 - 1.70619 -0.741383 1.34182 - 1.72306 -0.599294 1.35277 - 1.73325 -0.563746 1.35926 - 1.74072 -0.51765 1.36408 - 3.17506 -0.59546 2.26672 - 3.18437 -0.278785 2.27333 - 3.18508 -0.129585 2.27413 - 3.18196 -0.079862 2.27228 - 2.96406 0.187519 2.13576 - 2.98829 0.45526 2.15165 - 1.91889 0.32413 1.47821 - 1.11354 0.323363 0.971295 - 1.42301 0.523709 1.16656 - 1.3471 0.53512 1.11881 - 1.24768 0.570081 1.05631 - 1.01787 0.561558 0.911638 - 0.327902 0.261772 0.47664 - 0.708143 0.600263 0.716777 - 0.375805 0.355412 0.507013 - 0.324892 0.315636 0.474873 - 0.300856 0.312834 0.459737 - 0.299621 0.331586 0.459004 - 0.298228 0.389943 0.458265 - 0.303349 0.45196 0.461635 - 0.288001 0.488232 0.45206 - 0.148372 0.354371 0.363856 - 0.151629 0.364828 0.36593 - 0.152874 0.403764 0.366806 - 0.152146 0.406448 0.366354 - 0.150454 0.425278 0.365334 - 0.149268 0.576101 0.364944 - 0.153267 0.652541 0.367641 - 0.21799 1.08717 0.409408 - 0.240398 1.27948 0.423967 - 0.191103 1.28109 0.392942 - 0.186369 1.28218 0.389965 - 0.129162 1.29243 0.353981 - 0.113568 1.28278 0.344143 - 0.0571047 1.29849 0.30864 - 0.0428121 1.30162 0.299651 - 0.0331108 1.30026 0.293541 - 0.0283863 1.30254 0.290573 - 0.0235052 1.3008 0.287497 - -0.0341853 1.30294 0.251189 - -0.0629211 1.29817 0.23309 - -0.0471264 0.297602 0.240668 - -0.0526142 0.296901 0.237212 - -0.0548909 0.287491 0.235756 - -0.0593034 0.296863 0.233001 - -0.0603991 0.296672 0.232311 - -0.0891007 0.442121 0.214589 - -0.0877961 0.376235 0.215254 - -0.115485 0.317614 0.197688 - -0.12511 0.314528 0.191622 - -0.14075 0.33189 0.181818 - -0.199225 0.451195 0.145294 - -0.141883 0.285103 0.180995 - -0.142176 0.282696 0.180805 - -0.15301 0.269029 0.173953 - -0.15499 0.267675 0.172703 - -0.158132 0.271296 0.170735 - -0.161123 0.269178 0.168847 - -0.161764 0.26519 0.168434 - -0.171168 0.272369 0.162532 - -0.186819 0.292553 0.152728 - -0.18884 0.293366 0.151458 - -0.813911 1.36898 -0.239443 - -0.863897 1.26876 -0.271143 - -0.862346 1.1485 -0.270451 - -0.85875 1.05682 -0.268404 - -0.697311 -0.85569 -0.181806 - -0.303516 -0.388873 0.0732925 - -0.288491 -0.3882 0.0829848 - -0.287064 -0.389578 0.0839022 - -0.198739 -0.356866 0.140947 - -0.194795 -0.359583 0.143485 - -0.19231 -0.369248 0.145064 - -0.177374 -0.370636 0.154694 - -0.138972 -0.371959 0.179459 - -0.111091 -0.375434 0.197434 - -0.0982395 -0.370146 0.205735 - -0.0968811 -0.370537 0.20661 - -0.0927975 -0.371666 0.209242 - -0.0916139 -0.373004 0.210002 - -0.083946 -0.369809 0.214955 - -0.0788072 -0.373 0.218262 - -0.0632609 -0.384933 0.22826 - 0.00087772 -0.391024 0.269614 - 0.00683335 -0.393471 0.273449 - 0.016414 -0.387263 0.279643 - 0.0264587 -0.386662 0.286123 - 0.0390052 -0.392265 0.294202 - 0.0446387 -0.399121 0.297819 - 0.0604094 -0.401092 0.307986 - 0.0639648 -0.395897 0.310292 - 0.101801 -0.4049 0.334674 - 0.124709 -0.411338 0.349433 - 0.127718 -0.409795 0.351378 - 0.13221 -0.407423 0.354281 - 0.149656 -0.414206 0.365517 - 0.151549 -0.414204 0.366737 - 0.187627 -0.419208 0.389995 - 0.254216 -0.428171 0.432922 - 0.330721 -0.438169 0.482242 - 0.40927 -0.445746 0.532886 - 0.438743 -0.447556 0.551891 - 0.448227 -0.452703 0.557996 - 0.46838 -0.451391 0.570997 - 0.483055 -0.456559 0.58045 - 0.494804 -0.46295 0.588012 - 0.509983 -0.455254 0.597821 - 1.32998 -0.945896 1.12553 - 1.58473 -0.849503 1.29007 - 1.68363 -0.859695 1.35383 - 1.71029 -0.748551 1.37129 - 1.72935 -0.6256 1.38388 - 3.10998 -0.487939 2.27468 - 3.10545 -0.257557 2.2723 - 3.10886 -0.11114 2.27485 - 3.1067 -0.029792 2.27365 - 3.10166 0.018924 2.27052 - 2.97935 0.283793 2.19226 - 2.98993 0.411155 2.19939 - 2.98843 0.45856 2.19853 - 1.35807 0.328165 1.14668 - 1.0897 0.331185 0.973597 - 1.0799 0.340468 0.967297 - 1.22522 0.534649 1.06148 - 1.20075 0.538577 1.04571 - 0.673629 0.396241 0.705395 - 0.370369 0.228731 0.509401 - 0.321801 0.237298 0.478097 - 0.327614 0.251126 0.481878 - 0.333863 0.258138 0.485926 - 0.706057 0.603116 0.726802 - 0.329378 0.322339 0.483186 - 0.319567 0.3162 0.476843 - 0.296 0.319098 0.46165 - 0.298803 0.397353 0.463644 - 0.297341 0.399021 0.462705 - 0.295748 0.449056 0.461797 - 0.297708 0.464023 0.463096 - 0.297593 0.46801 0.463032 - 0.293977 0.475317 0.460717 - 0.165389 0.329972 0.377435 - 0.161563 0.329421 0.374966 - 0.146276 0.313853 0.365069 - 0.146917 0.365737 0.365606 - 0.146557 0.424361 0.365513 - 0.146619 0.434268 0.365577 - 0.147232 0.591096 0.366346 - 0.155369 0.770094 0.37202 - 0.2311 1.26916 0.422052 - 0.132056 1.28866 0.358218 - 0.0465421 1.29827 0.303086 - 0.0276047 1.30254 0.290882 - 0.00379356 1.30757 0.275537 - -0.0527007 0.295908 0.236692 - -0.0631046 0.299234 0.229989 - -0.0753192 0.359682 0.222255 - -0.0842787 0.348487 0.21645 - -0.0859315 0.342953 0.215371 - -0.091841 0.33311 0.211536 - -0.0954981 0.332011 0.209174 - -0.102075 0.32676 0.20492 - -0.103272 0.326347 0.204147 - -0.143184 0.33588 0.178427 - -0.145414 0.338009 0.176994 - -0.15736 0.357993 0.169337 - -0.83476 1.30155 -0.265323 - -0.838542 1.22753 -0.267939 - -0.835526 1.19066 -0.266081 - -0.835644 1.16985 -0.266207 - -0.840929 1.12655 -0.269718 - -0.838561 1.04717 -0.26838 - -0.83639 1.0263 -0.26703 - -0.651997 -0.775586 -0.161739 - -0.296935 -0.399168 0.0734392 - -0.265216 -0.375788 0.094424 - -0.236754 -0.360025 0.113242 - -0.214918 -0.365521 0.127636 - -0.185126 -0.366564 0.147291 - -0.157975 -0.368988 0.1652 - -0.122243 -0.373425 0.188766 - -0.119518 -0.374451 0.190562 - -0.109501 -0.369658 0.197183 - -0.102437 -0.384306 0.201808 - -0.0648158 -0.372602 0.226659 - -0.0634582 -0.372818 0.227555 - -0.0591337 -0.385537 0.230378 - -0.0464101 -0.385956 0.238772 - -0.0364215 -0.382647 0.24537 - -0.0336336 -0.382776 0.24721 --0.00860902 -0.380624 0.263726 - 0.0104018 -0.390993 0.276245 - 0.0131555 -0.389638 0.278065 - 0.0256965 -0.397797 0.286321 - 0.0280769 -0.393323 0.287902 - 0.0399729 -0.393907 0.29575 - 0.050711 -0.395335 0.302831 - 0.0521496 -0.394948 0.303782 - 0.082259 -0.403881 0.323627 - 0.0977082 -0.400835 0.333828 - 0.122864 -0.40506 0.350416 - 0.139574 -0.411385 0.361426 - 0.174458 -0.416728 0.38443 - 0.189325 -0.417867 0.394237 - 0.223088 -0.423755 0.4165 - 0.320187 -0.435995 0.480539 - 0.349105 -0.437043 0.499617 - 0.374019 -0.446393 0.516034 - 0.380322 -0.445621 0.520194 - 0.391363 -0.445949 0.527478 - 0.429061 -0.453414 0.552334 - 0.53793 -0.443821 0.624191 - 0.569874 -0.460248 0.645228 - 1.29575 -0.855828 1.12323 - 1.59264 -0.849597 1.31913 - 1.73872 -0.51472 1.41632 - 1.7375 -0.494915 1.41557 - 1.7485 -0.449418 1.42293 - 1.73687 -0.379623 1.41542 - 3.01485 -0.541146 2.25827 - 3.02845 -0.013296 2.26851 - 3.02621 0.0664254 2.26722 - 1.79574 0.346834 1.45601 - 1.65898 0.338821 1.36575 - 1.43022 0.331972 1.2148 - 1.25975 0.327954 1.10231 - 1.19051 0.323551 1.05661 - 1.43443 0.510557 1.218 - 0.332675 0.220089 0.490351 - 0.750959 0.586582 0.76722 - 0.70925 0.598899 0.739729 - 0.7029 0.621984 0.735594 - 0.68998 0.628 0.727084 - 0.282257 0.3133 0.457308 - 0.286415 0.365443 0.460176 - 0.28646 0.391971 0.460269 - 0.287249 0.4818 0.461005 - 0.198185 0.359516 0.401946 - 0.162585 0.324867 0.378374 - 0.141597 0.372747 0.36464 - 0.144318 0.422555 0.366555 - 0.143122 0.607952 0.36621 - 0.20133 1.27766 0.406221 - 0.177236 1.27834 0.390325 - 0.0638363 1.28564 0.31552 - 0.0459918 1.30426 0.30379 --0.00642611 1.29882 0.269191 - -0.0301068 1.30398 0.253578 - -0.0490611 1.30167 0.241066 - -0.0440941 0.31102 0.24197 - -0.0934115 0.449286 0.209761 - -0.0842881 0.372965 0.215598 - -0.085155 0.34621 0.214962 - -0.109945 0.322786 0.198548 - -0.113463 0.321403 0.196224 - -0.127988 0.317181 0.18663 - -0.267951 0.626045 0.0950203 - -0.771975 1.26514 -0.236012 - -0.814525 1.28882 -0.264031 - -0.822479 1.14795 -0.269616 - -0.82107 1.12584 -0.26874 - -0.626975 -0.803665 -0.154003 - -0.310462 -0.388947 0.0603968 - -0.281976 -0.382776 0.0796172 - -0.252308 -0.357592 0.099681 - -0.182294 -0.365639 0.146866 - -0.124141 -0.365193 0.186075 - -0.113553 -0.375458 0.193189 - -0.107589 -0.381614 0.197195 - -0.1002 -0.367405 0.202211 - -0.0651281 -0.387691 0.225809 - -0.0507822 -0.385551 0.235486 - -0.043381 -0.378206 0.240494 - -0.026922 -0.37697 0.251594 --0.00997602 -0.393684 0.262979 - 0.0130359 -0.394608 0.278492 - 0.0146541 -0.396401 0.279578 - 0.0175205 -0.39599 0.281512 - 0.0555079 -0.400963 0.307112 - 0.0598515 -0.399689 0.310043 - 0.074663 -0.403135 0.320021 - 0.127972 -0.408222 0.355951 - 0.135063 -0.417533 0.360709 - 0.154491 -0.41053 0.373825 - 0.158234 -0.410411 0.376349 - 0.173489 -0.413958 0.386626 - 0.187147 -0.417012 0.395827 - 0.206057 -0.416741 0.408577 - 0.215345 -0.417622 0.414837 - 0.225209 -0.419051 0.421484 - 0.29065 -0.438355 0.465559 - 0.307869 -0.438659 0.477167 - 0.364999 -0.439547 0.515684 - 0.392365 -0.446442 0.534118 - 0.402182 -0.445091 0.54074 - 0.465726 -0.455673 0.583557 - 0.472304 -0.453536 0.587997 - 0.490165 -0.453084 0.60004 - 0.493677 -0.443784 0.602431 - 0.508429 -0.435707 0.612397 - 1.26431 -0.921755 1.12085 - 1.26771 -0.896868 1.1232 - 1.27021 -0.889574 1.12491 - 1.26563 -0.833332 1.12196 - 1.39838 -0.825068 1.21148 - 1.48619 -0.837252 1.27066 - 1.71763 -0.710784 1.427 - 1.71648 -0.679857 1.4263 - 1.72985 -0.564759 1.43559 - 1.74064 -0.508999 1.443 - 2.96126 -0.42334 2.26617 - 2.96643 0.00261994 2.27068 - 2.95787 0.396493 2.26586 - 1.64911 0.339153 1.38334 - 1.55026 0.336172 1.31668 - 1.50253 0.334269 1.28449 - 1.2262 0.328485 1.09818 - 1.08254 0.339922 1.00135 - 1.42759 0.511679 1.2344 - 1.33982 0.535794 1.17528 - 1.19627 0.566215 1.07857 - 1.02615 0.565063 0.96387 - 0.560192 0.344194 0.649177 - 0.691322 0.519269 0.73801 - 0.783984 0.615965 0.800718 - 0.708763 0.625689 0.750026 - 0.315074 0.319825 0.483855 - 0.295429 0.309485 0.470585 - 0.282189 0.332826 0.461714 - 0.27605 0.343751 0.457602 - 0.280465 0.470708 0.460885 - 0.155352 0.32704 0.376185 - 0.140928 0.344822 0.366503 - 0.138566 0.389481 0.365018 - 0.139206 0.418001 0.365518 - 0.139727 0.455004 0.365959 - 0.138442 0.485986 0.365167 - 0.140125 0.523819 0.366393 - 0.139553 0.657994 0.366331 - 0.226551 1.26722 0.426456 - 0.218293 1.27469 0.420907 - 0.208169 1.27232 0.414075 - 0.194337 1.27589 0.404758 - 0.147313 1.28127 0.373067 - 0.0632827 1.29162 0.316436 - 0.0351703 1.29297 0.297486 - -0.0116062 1.2999 0.265965 - -0.0584154 1.29137 0.234384 - -0.0587172 0.288947 0.231763 - -0.0843999 0.373946 0.214652 - -0.0856227 0.349144 0.213768 - -0.0924101 0.324632 0.209133 - -0.0957101 0.322556 0.206903 - -0.101746 0.32676 0.202843 - -0.107805 0.320375 0.198743 - -0.111273 0.319022 0.196401 - -0.119877 0.317531 0.190597 - -0.202747 0.477606 0.13511 - -0.247648 0.590368 0.105109 - -0.281386 0.656408 0.0825214 - -0.164377 0.346811 0.160665 - -0.149057 0.305723 0.170894 - -0.147504 0.266002 0.171846 - -0.153972 0.266129 0.167486 - -0.159973 0.267609 0.163443 - -0.16058 0.263623 0.163024 - -0.162864 0.265436 0.161489 - -0.176809 0.278383 0.152118 - -0.801662 1.18672 -0.26698 - -0.557013 -0.649594 -0.114876 - -0.5981 -0.718241 -0.143392 - -0.61348 -0.757085 -0.154098 - -0.627559 -0.795804 -0.163907 - -0.330454 -0.414945 0.0420141 - -0.300239 -0.397888 0.0629027 - -0.297368 -0.400808 0.064877 - -0.276295 -0.376577 0.0794755 - -0.250999 -0.357592 0.0969751 - -0.206857 -0.364239 0.127416 - -0.138771 -0.356451 0.174413 - -0.0745564 -0.37286 0.218679 - -0.0564807 -0.384908 0.231122 - -0.0481122 -0.384831 0.236896 - -0.0467298 -0.384959 0.237849 - -0.0453469 -0.385078 0.238803 - -0.0340822 -0.378778 0.246591 - -0.0259172 -0.378987 0.252224 - -0.0232001 -0.375999 0.254106 - -0.0164096 -0.377903 0.258787 - -0.0136149 -0.380813 0.260708 --0.00806395 -0.382545 0.264534 --0.00686955 -0.378465 0.265368 --0.00415198 -0.378275 0.267243 - 0.00073694 -0.3909 0.270586 - 0.0210075 -0.394325 0.284564 - 0.0341395 -0.405012 0.293599 - 0.0447196 -0.396453 0.300919 - 0.0714953 -0.394496 0.319399 - 0.0866559 -0.404474 0.329835 - 0.0924466 -0.402079 0.333836 - 0.10546 -0.406927 0.342803 - 0.10868 -0.406475 0.345026 - 0.14542 -0.415102 0.370355 - 0.163425 -0.417273 0.382773 - 0.18396 -0.414449 0.396948 - 0.21406 -0.423004 0.417695 - 0.229354 -0.425853 0.428241 - 0.232888 -0.423963 0.430684 - 0.251036 -0.426071 0.4432 - 0.348936 -0.439976 0.510716 - 0.365784 -0.440227 0.522339 - 0.436207 -0.451446 0.570903 - 0.478159 -0.454283 0.599841 - 1.23653 -0.899767 1.12202 - 1.28663 -0.809216 1.15681 - 1.71801 -0.706051 1.4547 - 1.71839 -0.645188 1.4551 - 1.74602 -0.367789 1.47484 - 2.89032 -0.182958 2.26483 - 2.88997 -0.121042 2.26474 - 2.87819 -0.0435922 2.2568 - 2.89284 0.0953718 2.26724 - 2.88654 0.218864 2.2632 - 1.37013 0.330567 1.21718 - 1.09564 0.32141 1.02777 - 1.08684 0.343872 1.02175 - 1.41206 0.526649 1.2466 - 1.25737 0.54512 1.13991 - 1.02891 0.557583 0.982307 - 1.01509 0.563433 0.972784 - 0.928341 0.553186 0.912904 - 0.33204 0.225647 0.500675 - 0.329042 0.226134 0.498607 - 0.708763 0.596218 0.761505 - 0.272907 0.30875 0.460076 - 0.270961 0.320549 0.458763 - 0.274117 0.329723 0.460962 - 0.273781 0.443989 0.461008 - 0.271794 0.461247 0.459679 - 0.167248 0.326629 0.387218 - 0.161593 0.32899 0.383322 - 0.160408 0.329972 0.382507 - 0.157573 0.331085 0.380553 - 0.155928 0.331211 0.379419 - 0.141401 0.342212 0.369422 - 0.134033 0.340448 0.364334 - 0.134592 0.356061 0.364758 - 0.13706 0.393913 0.366552 - 0.136003 0.404554 0.365849 - 0.135091 0.416135 0.365248 - 0.134573 0.450347 0.364974 - 0.137622 0.689367 0.367658 - 0.221842 1.25457 0.427141 - 0.164767 1.28237 0.387828 - 0.14592 1.28324 0.374827 - 0.136818 1.286 0.368553 - 0.0159044 1.29903 0.285157 - 0.00190452 1.29958 0.275499 - -0.0214371 1.29999 0.259395 - -0.026106 1.3 0.256174 - -0.0446615 0.42929 0.241255 - -0.0434228 0.311125 0.241823 - -0.0550019 0.292614 0.233788 - -0.0560523 0.292448 0.233063 - -0.0743361 0.361922 0.220617 - -0.0801503 0.393187 0.216681 - -0.09525 0.326798 0.206101 - -0.0985813 0.319469 0.203785 - -0.121552 0.319837 0.187936 - -0.160003 0.383015 0.16156 - -0.22713 0.509615 0.115551 - -0.149227 0.273645 0.16873 - -0.156041 0.268877 0.164016 - -0.15668 0.264905 0.163565 - -0.161344 0.263746 0.160345 - -0.195268 0.296382 0.137017 - -0.782729 1.06674 -0.266444 - -0.245889 -0.36118 0.0971403 - -0.227713 -0.36362 0.10995 - -0.217994 -0.359577 0.116812 - -0.206759 -0.365945 0.124718 - -0.196134 -0.35859 0.132227 - -0.182945 -0.363068 0.141515 - -0.157524 -0.368277 0.159426 - -0.145104 -0.368199 0.168182 - -0.141742 -0.371975 0.170543 - -0.122864 -0.368571 0.183862 - -0.119736 -0.367709 0.18607 - -0.0729972 -0.393411 0.21896 - -0.0719507 -0.396638 0.21969 - -0.0452589 -0.38009 0.238549 - -0.0262804 -0.385987 0.251916 - -0.0235256 -0.386999 0.253856 - -0.0113117 -0.380695 0.262483 --0.00995429 -0.380624 0.26344 --0.00432116 -0.384264 0.267403 --0.00015007 -0.384917 0.270342 - 0.0305805 -0.395452 0.291983 - 0.0388624 -0.392595 0.297829 - 0.0402614 -0.392257 0.298816 - 0.0454809 -0.397066 0.302484 - 0.0634303 -0.396917 0.31514 - 0.086456 -0.401991 0.331362 - 0.119429 -0.406897 0.354598 - 0.127667 -0.405707 0.360409 - 0.135547 -0.407826 0.36596 - 0.136999 -0.406972 0.366986 - 0.140983 -0.40793 0.369792 - 0.152322 -0.408707 0.377785 - 0.188554 -0.419034 0.403305 - 0.190045 -0.417897 0.404359 - 0.218895 -0.423285 0.424687 - 0.255865 -0.429403 0.450737 - 0.287552 -0.437454 0.473059 - 1.20735 -0.921115 1.12038 - 1.48549 -0.839655 1.31668 - 1.55272 -0.846782 1.36407 - 1.71016 -0.759784 1.47528 - 1.72062 -0.671127 1.48288 - 1.73611 -0.565179 1.49406 - 1.73414 -0.554531 1.4927 - 1.7462 -0.409525 1.50155 - 2.81995 -0.0126559 2.25958 - 2.82209 0.0937307 2.26134 - 2.82007 0.108864 2.25996 - 2.81917 0.215343 2.25958 - 1.83714 0.331975 1.56749 - 1.81735 0.338495 1.55354 - 1.22074 0.325033 1.13287 - 1.11798 0.32382 1.06042 - 1.07908 0.337736 1.03303 - 1.44009 0.515365 1.28799 - 1.39499 0.532501 1.25624 - 1.15203 0.605088 1.08511 - 1.04487 0.56346 1.00946 - 1.02809 0.568002 0.99764 - 0.9156 0.556056 0.918298 - 0.751458 0.61199 0.802706 - 0.294582 0.313871 0.479854 - 0.275293 0.311052 0.466248 - 0.263338 0.331884 0.45787 - 0.264017 0.356769 0.458409 - 0.266772 0.372998 0.460391 - 0.26603 0.420799 0.459985 - 0.266683 0.43314 0.460475 - 0.151488 0.332269 0.37901 - 0.136615 0.342223 0.368548 - 0.135785 0.385948 0.36807 - 0.133674 0.385014 0.366579 - 0.133334 0.462162 0.366529 - 0.131995 0.463926 0.365588 - 0.133736 0.573033 0.367083 - 0.134267 0.58336 0.367483 - 0.197436 1.11821 0.413329 - 0.199356 1.27255 0.415061 - 0.149717 1.28824 0.380101 - 0.124969 1.27777 0.362626 - -0.012582 1.2979 0.265695 - -0.0584628 1.28237 0.233308 - -0.043829 0.297064 0.241215 - -0.0517237 0.290098 0.235631 - -0.0803283 0.349409 0.215609 - -0.0812511 0.347147 0.214953 - -0.0828993 0.334474 0.21376 - -0.0937322 0.326204 0.206102 - -0.12179 0.321713 0.186308 - -0.12408 0.320662 0.184691 - -0.238639 0.586305 0.104571 - -0.262986 0.645315 0.0875491 - -0.143695 0.282601 0.170768 - -0.155197 0.273719 0.162637 - -0.185797 0.286652 0.141094 - -0.756005 1.20594 -0.258684 - -0.766959 1.14904 -0.266546 - -0.765371 1.12627 -0.265482 - -0.766652 1.01472 -0.266658 - -0.762822 0.957879 -0.264098 - -0.761687 0.939862 -0.263341 - -0.762751 0.933046 -0.264108 - -0.244622 -0.36118 0.0946361 - -0.220374 -0.359148 0.112111 - -0.209631 -0.35945 0.11985 - -0.193006 -0.364794 0.131814 - -0.156569 -0.367363 0.158059 - -0.147481 -0.367814 0.164606 - -0.139044 -0.3698 0.170679 - -0.129531 -0.367724 0.177538 - -0.126397 -0.366952 0.179798 - -0.101704 -0.370869 0.197578 - -0.096439 -0.372482 0.201367 - -0.0858444 -0.375366 0.208993 - -0.0679101 -0.386243 0.221887 - -0.0630989 -0.379972 0.225369 - -0.0453911 -0.379093 0.238128 - -0.0427059 -0.379307 0.240062 - -0.0238754 -0.383999 0.253617 - 0.0194668 -0.392343 0.284823 - 0.0363695 -0.39096 0.297004 - 0.0864734 -0.400452 0.333078 - 0.0946066 -0.406481 0.338922 - 0.103195 -0.402513 0.345119 - 0.111033 -0.406191 0.350758 - 0.125008 -0.411875 0.360812 - 0.146721 -0.412382 0.376454 - 0.148178 -0.41146 0.377506 - 0.151082 -0.409592 0.379603 - 0.170907 -0.415517 0.393871 - 0.181165 -0.416158 0.40126 - 0.280217 -0.434569 0.472577 - 0.353257 -0.436808 0.525193 - 0.358719 -0.435447 0.529131 - 0.377199 -0.444612 0.542422 - 0.387104 -0.439847 0.549571 - 0.395429 -0.444806 0.555556 - 0.404761 -0.446733 0.562274 - 0.434057 -0.448422 0.583377 - 0.449377 -0.455165 0.594397 - 1.18078 -0.94403 1.12014 - 1.19063 -0.897653 1.12734 - 1.18179 -0.864907 1.12105 - 1.2198 -0.804864 1.14859 - 1.24638 -0.804719 1.16774 - 1.32602 -0.818793 1.22508 - 1.34058 -0.818531 1.23557 - 1.37343 -0.819732 1.25923 - 1.44837 -0.834744 1.31319 - 1.61931 -0.857745 1.43628 - 1.70998 -0.818392 1.50171 - 1.69842 -0.802343 1.49342 - 1.69761 -0.770397 1.49291 - 1.71293 -0.756185 1.50398 - 1.71606 -0.633499 1.50654 - 1.73176 -0.598377 1.51794 - 1.73385 -0.58893 1.51947 - 1.80561 -0.355501 1.57174 - 2.75377 -0.493853 2.25451 - 2.75926 -0.207331 2.25917 - 2.76086 0.0774065 2.26102 - 2.75492 0.167054 2.25696 - 2.7625 0.197575 2.2625 - 2.61792 0.416803 2.15888 - 1.66296 0.340356 1.47069 - 1.60573 0.337827 1.42945 - 1.5154 0.336172 1.36436 - 1.23073 0.541816 1.15978 - 0.927403 0.567369 0.941313 - 0.816281 0.535091 0.861175 - 0.591545 0.400514 0.698932 - 0.78 0.534151 0.835034 - 0.767651 0.537011 0.826144 - 0.711962 0.596654 0.78617 - 0.709838 0.600613 0.784649 - 0.703003 0.623658 0.779782 - 0.703905 0.648001 0.780492 - 0.708016 0.669831 0.783508 - 0.481773 0.493252 0.620075 - 0.269355 0.302078 0.466567 - 0.262934 0.314339 0.461971 - 0.25674 0.324201 0.457533 - 0.258875 0.372451 0.45919 - 0.259264 0.382901 0.459496 - 0.260019 0.394173 0.460068 - 0.258619 0.395702 0.459063 - 0.261643 0.407044 0.46127 - 0.166118 0.324586 0.392245 - 0.149527 0.325371 0.380294 - 0.138746 0.346544 0.372579 - 0.128676 0.338665 0.365304 - 0.130738 0.35778 0.366837 - 0.129325 0.362097 0.36583 - 0.128997 0.422283 0.365742 - 0.129646 0.455705 0.366292 - 0.128753 0.594432 0.365991 - 0.129039 0.66533 0.366371 - 0.192011 1.26885 0.413227 - 0.174924 1.27924 0.400942 - 0.148339 1.29022 0.381816 - 0.143768 1.29114 0.378526 - 0.0836781 1.29596 0.335245 - 0.0605799 1.29661 0.318606 - -0.0314814 1.30798 0.252308 - -0.0626716 0.935886 0.22892 - -0.0422674 0.370387 0.242226 - -0.0452326 0.298951 0.239914 - -0.0815153 0.349108 0.213898 - -0.0939951 0.32814 0.204855 - -0.104104 0.318378 0.197547 - -0.134281 0.337059 0.175852 - -0.269482 0.644165 0.0792037 - -0.271759 0.642846 0.0775602 - -0.15981 0.332794 0.15745 - -0.162703 0.268818 0.155208 - -0.164599 0.267325 0.153838 - -0.746623 0.959847 -0.263775 - -0.746138 0.942594 -0.263468 - -0.515935 -0.627923 -0.109481 - -0.276198 -0.379866 0.0677485 - -0.249314 -0.357959 0.0876085 - -0.227461 -0.360609 0.103701 - -0.212856 -0.364339 0.114451 - -0.210711 -0.363669 0.116033 - -0.188079 -0.356109 0.132725 - -0.185087 -0.360488 0.134918 - -0.181122 -0.366564 0.137824 - -0.173337 -0.371531 0.143547 - -0.114511 -0.372576 0.186881 - -0.0958634 -0.370537 0.200624 - -0.078689 -0.373984 0.213268 - -0.0403717 -0.382489 0.241475 - -0.0336496 -0.382829 0.246426 - -0.0323432 -0.384874 0.247383 - -0.0309911 -0.384914 0.248379 - -0.0135013 -0.381757 0.261272 --0.00783189 -0.388451 0.265432 - 0.0141407 -0.38805 0.28162 - 0.0350674 -0.397181 0.297014 - 0.0397233 -0.399121 0.300439 - 0.047572 -0.393973 0.306234 - 0.0732539 -0.402091 0.325134 - 0.0767953 -0.403881 0.327738 - 0.0833471 -0.399146 0.332577 - 0.0950423 -0.406778 0.341174 - 0.10446 -0.405545 0.348115 - 0.121577 -0.416213 0.360699 - 0.135691 -0.407009 0.371119 - 0.139264 -0.407047 0.373751 - 0.160316 -0.409033 0.389255 - 0.161977 -0.404412 0.39049 - 0.218016 -0.421492 0.431732 - 0.223865 -0.419933 0.436045 - 0.227738 -0.4226 0.438891 - 0.23118 -0.42065 0.441432 - 0.252509 -0.427906 0.457127 - 0.277521 -0.434569 0.475537 - 0.279043 -0.432929 0.476662 - 0.402668 -0.444423 0.567707 - 0.407323 -0.445299 0.571135 - 0.446014 -0.45578 0.599612 - 0.464361 -0.428377 0.613196 - 1.15772 -0.845932 1.12296 - 1.15648 -0.836547 1.12206 - 1.19068 -0.80076 1.14735 - 1.47113 -0.834873 1.35387 - 1.51897 -0.841555 1.3891 - 1.64277 -0.855705 1.48027 - 1.70817 -0.813305 1.52855 - 1.72401 -0.662105 1.54059 - 1.73531 -0.543219 1.54921 - 1.73903 -0.524127 1.55201 - 1.73416 -0.492554 1.54849 - 1.784 -0.354099 1.58556 - 2.69313 -0.278018 2.2555 - 2.69334 -0.248404 2.25573 - 1.07507 0.354529 1.06505 - 1.08496 0.370595 1.07237 - 1.24821 0.43252 1.1928 - 1.39578 0.532716 1.30176 - 1.33093 0.53257 1.25399 - 1.32215 0.537167 1.24752 - 1.29462 0.542024 1.22725 - 1.2378 0.541582 1.1854 - 0.953483 0.574618 0.976023 - 0.919856 0.573803 0.951248 - 0.787045 0.583732 0.853431 - 0.767492 0.610597 0.839093 - 0.703433 0.658976 0.792021 - 0.708936 0.694934 0.796165 - 0.25436 0.354024 0.460433 - 0.18209 0.339283 0.407155 - 0.164945 0.322749 0.394483 - 0.151189 0.328589 0.384364 - 0.151071 0.334673 0.384292 - 0.147708 0.33143 0.381806 - 0.126866 0.363811 0.366532 - 0.124367 0.439215 0.364879 - 0.137172 0.799761 0.375208 - 0.127164 1.28289 0.369035 - 0.12311 1.28767 0.36606 - 0.0865732 1.29038 0.33915 - 0.0590107 1.28863 0.318841 - 0.0544825 1.28908 0.315506 - 0.0501843 1.2935 0.312351 - 0.0409908 1.29229 0.305575 - -0.0409503 1.30287 0.245235 - -0.0501033 1.30267 0.238492 - -0.0643072 1.06695 0.227442 - -0.0439707 0.401336 0.240771 - -0.102543 0.323052 0.197426 - -0.113018 0.315723 0.189691 - -0.260865 0.654799 0.0816142 - -0.264112 0.648586 0.079207 - -0.266606 0.640541 0.0773501 - -0.266782 0.633804 0.0772036 - -0.161302 0.338162 0.154176 - -0.14238 0.285016 0.167984 - -0.174417 0.274276 0.144355 - -0.177197 0.27677 0.142314 - -0.609971 1.00582 -0.174699 - -0.724009 1.15878 -0.258331 - -0.728283 1.13465 -0.26154 - -0.731565 1.02439 -0.264231 - -0.736965 1.00532 -0.268256 - -0.729663 0.969167 -0.262967 - -0.48801 -0.586324 -0.0967974 - -0.334606 -0.451032 0.0191981 - -0.246581 -0.359174 0.0857938 - -0.240887 -0.359582 0.0900856 - -0.234902 -0.36263 0.0945905 - -0.222368 -0.363879 0.104037 - -0.217612 -0.361864 0.107628 - -0.213376 -0.364154 0.110816 - -0.203214 -0.361561 0.118484 - -0.18664 -0.358733 0.130986 - -0.180474 -0.359577 0.135633 - -0.151671 -0.366022 0.157332 - -0.127035 -0.367343 0.175903 - -0.0937688 -0.375195 0.200964 - -0.0873781 -0.369796 0.205796 - -0.081067 -0.372399 0.210547 - -0.0799124 -0.373686 0.211415 - -0.0658562 -0.392649 0.221965 - -0.0446039 -0.382197 0.238014 - -0.043272 -0.382302 0.239018 - -0.0390551 -0.376578 0.242211 - -0.03385 -0.378831 0.24613 - -0.0153403 -0.379813 0.260082 - 0.0114894 -0.396401 0.280269 - 0.0265005 -0.392777 0.291595 - 0.0345064 -0.399147 0.297615 - 0.0478036 -0.392604 0.307657 - 0.0540414 -0.394838 0.312354 - 0.0573985 -0.404094 0.314862 - 0.0872251 -0.40647 0.337343 - 0.0979328 -0.404801 0.34542 - 0.129441 -0.404217 0.369177 - 0.149385 -0.409528 0.3842 - 0.157782 -0.411779 0.390525 - 0.176775 -0.415303 0.404836 - 0.181345 -0.416484 0.408279 - 0.19085 -0.411256 0.415458 - 0.199491 -0.419687 0.421952 - 0.207583 -0.418828 0.428054 - 0.226728 -0.425011 0.442473 - 0.313851 -0.438488 0.508125 - 0.363827 -0.441391 0.545796 - 0.391745 -0.440923 0.566846 - 0.421693 -0.452074 0.589396 - 0.428883 -0.447191 0.594829 - 1.1196 -0.937636 1.11436 - 1.12541 -0.92456 1.11877 - 1.12841 -0.909296 1.12107 - 1.25177 -0.804064 1.21434 - 1.72475 -0.60584 1.57143 - 1.72627 -0.575588 1.57265 - 1.73896 -0.377907 1.58271 - 2.59136 -0.385375 2.22535 - 1.91467 -0.051245 1.71601 - 1.90923 0.0334763 1.71212 - 1.91738 0.118642 1.71848 - 1.91299 0.160889 1.71528 - 1.91086 0.310318 1.71404 - 1.83588 0.339762 1.65759 - 1.67761 0.339448 1.53826 - 1.2906 0.329144 1.24645 - 1.17581 0.327846 1.1599 - 1.37979 0.48131 1.31407 - 1.19377 0.557234 1.17402 - 0.915281 0.575998 0.964105 - 0.870959 0.579568 0.930697 - 0.706065 0.607796 0.806449 - 0.711052 0.653421 0.810323 - 0.662648 0.68101 0.773899 - 0.291964 0.325499 0.493537 - 0.25606 0.304442 0.466414 - 0.24752 0.325151 0.460028 - 0.248462 0.406289 0.460941 - 0.245617 0.40927 0.458804 - 0.135002 0.34568 0.375248 - 0.128602 0.345648 0.370423 - 0.122629 0.346324 0.365921 - 0.121609 0.362773 0.365193 - 0.117974 0.400394 0.362547 - 0.123503 0.488398 0.366936 - 0.121183 0.521414 0.365269 - 0.122191 0.540025 0.366076 - 0.121501 0.569816 0.36563 - 0.123274 0.712848 0.367325 - 0.200982 1.2396 0.427232 - 0.180811 1.28291 0.412132 - 0.131171 1.29193 0.37473 - 0.112715 1.29122 0.360814 - 0.0630794 1.29812 0.323409 - -0.0139725 1.3049 0.265333 - -0.0230708 1.30199 0.258467 - -0.0366881 1.30294 0.248202 - -0.0457036 1.29878 0.241395 - -0.0588053 1.28037 0.231471 - -0.0636169 1.04597 0.227256 - -0.0524725 0.293079 0.233773 - -0.0591526 0.297049 0.228746 - -0.0748716 0.356726 0.217045 - -0.0865835 0.329281 0.208146 - -0.121209 0.323589 0.182026 - -0.149619 0.378433 0.160744 - -0.260425 0.635486 0.0778477 - -0.140056 0.263541 0.167666 - -0.142515 0.266418 0.16582 - -0.15396 0.269736 0.157199 - -0.165207 0.273975 0.14873 - -0.717053 1.12514 -0.265194 - -0.719001 1.11819 -0.26668 - -0.711201 0.902466 -0.26134 - -0.470638 -0.59449 -0.0922607 - -0.301327 -0.388175 0.0391536 - -0.296769 -0.402503 0.0426408 - -0.255302 -0.362857 0.0747986 - -0.234458 -0.357908 0.0909257 - -0.204874 -0.367517 0.113772 - -0.20151 -0.367773 0.116373 - -0.171167 -0.370636 0.139823 - -0.16365 -0.367479 0.145642 - -0.156947 -0.370296 0.150817 - -0.142286 -0.371631 0.162148 - -0.113317 -0.376896 0.184531 - -0.0750016 -0.367657 0.214175 - -0.0730878 -0.373128 0.215641 - -0.0488356 -0.382837 0.234365 - -0.0342308 -0.381829 0.245659 - -0.0197425 -0.380936 0.256862 - -0.0154089 -0.395806 0.260175 - 0.00759916 -0.391811 0.277972 - 0.0215613 -0.393585 0.288761 - 0.02902 -0.397129 0.294519 - 0.0430082 -0.395715 0.305336 - 0.0440271 -0.393383 0.30613 - 0.047638 -0.397475 0.308911 - 0.052126 -0.398179 0.312379 - 0.0717161 -0.405921 0.327504 - 0.082737 -0.406731 0.336022 - 0.0905743 -0.401142 0.342096 - 0.0966899 -0.405736 0.346812 - 0.105447 -0.40784 0.353577 - 0.134608 -0.408827 0.376118 - 0.136372 -0.408836 0.377482 - 0.150964 -0.409366 0.388762 - 0.179647 -0.413659 0.410925 - 0.213574 -0.418552 0.437141 - 0.231292 -0.421828 0.450831 - 0.252804 -0.421838 0.467461 - 0.280197 -0.435611 0.488604 - 0.291805 -0.429013 0.497595 - 0.293281 -0.427261 0.49874 - 0.315019 -0.436909 0.515521 - 0.321197 -0.433354 0.520306 - 0.326646 -0.436343 0.524512 - 0.399965 -0.450203 0.581158 - 0.412225 -0.45503 0.590624 - 0.455769 -0.428954 0.624354 - 1.10021 -0.852899 1.12149 - 1.41418 -0.827234 1.36429 - 1.70852 -0.763289 1.592 - 1.71145 -0.743179 1.59432 - 1.73509 -0.542683 1.6131 - 1.73548 -0.491648 1.61353 - 1.73715 -0.481934 1.61484 - 1.86468 -0.249341 1.71403 - 1.86598 -0.0713109 1.71548 - 1.86303 -0.060776 1.71323 - 1.86267 0.0225644 1.71315 - 1.86859 0.0853587 1.71789 - 1.86672 0.116645 1.71652 - 1.08017 0.356215 1.10906 - 1.43968 0.506628 1.38737 - 1.29722 0.536861 1.27731 - 1.0232 0.55744 1.06552 - 1.01835 0.561658 1.06178 - 0.995057 0.569213 1.0438 - 0.877565 0.576955 0.952983 - 0.86089 0.578651 0.940096 - 0.754834 0.618072 0.858205 - 0.709993 0.652832 0.823626 - 0.712295 0.704801 0.825537 - 0.698074 0.716679 0.814574 - 0.61975 0.65656 0.75387 - 0.260428 0.304301 0.475191 - 0.236057 0.317645 0.456384 - 0.243691 0.396454 0.462485 - 0.155449 0.33129 0.394101 - 0.154749 0.333112 0.393565 - 0.144896 0.32704 0.385932 - 0.134307 0.344798 0.37779 - 0.128312 0.34914 0.373167 - 0.117128 0.352182 0.364528 - 0.119179 0.479993 0.366437 - 0.116959 0.485327 0.364734 - 0.119558 0.544618 0.366894 - 0.119215 0.714626 0.367058 - 0.132739 0.842217 0.377836 - 0.190416 1.27158 0.423511 - 0.164145 1.27932 0.40322 - 0.106341 1.28999 0.358559 - 0.0168714 1.2998 0.289417 - -0.0625651 1.2532 0.227887 - -0.0526353 0.293079 0.233137 - -0.056257 0.288482 0.230325 - -0.0926303 0.324268 0.202296 - -0.0961911 0.324104 0.199542 - -0.0973088 0.323714 0.198677 - -0.106437 0.311872 0.19159 - -0.115789 0.319473 0.18438 - -0.160338 0.413593 0.150177 - -0.310673 0.843841 0.0350422 - -0.251545 0.623116 0.0801955 - -0.2487 0.608251 0.0823577 - -0.151123 0.323451 0.157073 - -0.147083 0.267294 0.160055 - -0.155044 0.268323 0.153903 - -0.698345 1.08447 -0.264054 - -0.373433 -0.468914 -0.0242718 - -0.307045 -0.396277 0.0286632 - -0.296804 -0.3852 0.0368291 - -0.302383 -0.410856 0.0323301 - -0.213017 -0.36208 0.103462 - -0.208442 -0.363498 0.107094 - -0.200147 -0.364239 0.113683 - -0.181376 -0.363109 0.128601 - -0.177838 -0.370065 0.131394 - -0.149349 -0.372919 0.154024 - -0.144113 -0.365966 0.158202 - -0.142566 -0.365696 0.159431 - -0.136405 -0.374156 0.164305 - -0.105557 -0.375376 0.188813 - -0.0995645 -0.366028 0.193598 - -0.0828909 -0.368828 0.206839 - -0.0771126 -0.374274 0.211417 - -0.0332646 -0.381876 0.246238 - -0.0189299 -0.380902 0.25763 --0.00722767 -0.380272 0.26693 - 0.0567215 -0.398346 0.317696 - 0.123842 -0.408605 0.371001 - 0.133536 -0.415993 0.378685 - 0.135668 -0.412414 0.380388 - 0.151112 -0.406533 0.392675 - 0.181016 -0.417597 0.416407 - 0.186685 -0.412928 0.420923 - 0.191995 -0.419242 0.425126 - 0.217693 -0.423157 0.445535 - 0.251044 -0.427994 0.472022 - 0.267346 -0.426021 0.48498 - 0.287016 -0.427551 0.500606 - 0.294243 -0.429849 0.506342 - 0.309019 -0.438066 0.518062 - 0.359851 -0.442606 0.55844 - 0.420676 -0.424994 0.606815 - 1.07168 -0.815598 1.12309 - 1.07037 -0.790307 1.12211 - 1.19402 -0.791989 1.22035 - 1.33355 -0.816897 1.33116 - 1.53572 -0.844483 1.49172 - 1.71312 -0.719631 1.633 - 1.71589 -0.678147 1.63531 - 1.7382 -0.497689 1.65349 - 1.73929 -0.385664 1.65464 - 1.76669 -0.350654 1.67651 - 1.81498 -0.255762 1.71512 - 1.81421 -0.111185 1.71487 - 1.81124 -0.0802389 1.71259 - 1.81217 0.011951 1.71357 - 1.81761 0.135449 1.71821 - 1.82127 0.156393 1.72117 - 1.82356 0.20845 1.72312 - 1.83135 0.240672 1.72939 - 1.8335 0.261917 1.73115 - 1.83905 0.326047 1.73573 - 1.31823 0.335163 1.32193 - 1.21735 0.331664 1.24176 - 1.13855 0.324227 1.17913 - 1.08745 0.336124 1.13855 - 1.07431 0.358189 1.12817 - 1.41592 0.495165 1.39996 - 1.42779 0.507947 1.40942 - 0.954583 0.572357 1.03359 - 0.854709 0.580943 0.954253 - 0.769939 0.618597 0.886994 - 0.749147 0.608385 0.870447 - 0.723656 0.605814 0.850186 - 0.714582 0.676625 0.843157 - 0.720671 0.694867 0.848041 - 0.718915 0.699619 0.846658 - 0.231198 0.315569 0.458153 - 0.229029 0.318429 0.456437 - 0.232942 0.329015 0.459573 - 0.229543 0.333325 0.456883 - 0.232342 0.352043 0.459155 - 0.235535 0.392612 0.461796 - 0.169331 0.323573 0.409016 - 0.147843 0.337051 0.391976 - 0.147116 0.338856 0.391404 - 0.144631 0.357415 0.389476 - 0.116265 0.35485 0.366931 - 0.115527 0.368746 0.36638 - 0.113744 0.394143 0.365028 - 0.115991 0.440822 0.366933 - 0.115207 0.455248 0.366347 - 0.117601 0.586669 0.368584 - 0.114707 0.602443 0.366326 - 0.131611 1.29105 0.381516 - 0.109309 1.2932 0.363801 - 0.0867507 1.29175 0.345873 - 0.0513796 1.29606 0.317779 - -0.028483 1.299 0.254331 - -0.0768294 0.336933 0.213458 - -0.0853039 0.330586 0.206709 - -0.0921888 0.3233 0.20122 - -0.0932922 0.322931 0.200342 - -0.102981 0.323588 0.192645 - -0.144765 0.305723 0.159399 - -0.141677 0.276255 0.161777 - -0.142907 0.26513 0.160772 - -0.158459 0.27199 0.148432 - -0.159386 0.271252 0.147694 - -0.606349 0.997851 -0.205593 - -0.676132 0.89527 -0.261302 - -0.297981 -0.389662 0.0312009 - -0.281599 -0.389487 0.0445001 - -0.222641 -0.362249 0.0924305 - -0.216232 -0.357024 0.0976465 - -0.203127 -0.365674 0.108262 - -0.168524 -0.368846 0.136344 - -0.160261 -0.367334 0.143055 - -0.152432 -0.366449 0.149413 - -0.112004 -0.374978 0.182209 - -0.0972003 -0.375975 0.194224 - -0.0828155 -0.377979 0.205896 - -0.0486903 -0.374861 0.233605 - -0.0126945 -0.38562 0.262798 --0.00697963 -0.395243 0.267412 --0.00564101 -0.395132 0.268499 - 0.0269749 -0.395158 0.294976 - 0.0444537 -0.39163 0.309174 - 0.0758856 -0.396878 0.334675 - 0.0816894 -0.401744 0.339374 - 0.100489 -0.402279 0.354634 - 0.108052 -0.405817 0.360764 - 0.149421 -0.41102 0.394333 - 0.215323 -0.423157 0.447799 - 0.233859 -0.423827 0.462844 - 0.264138 -0.429158 0.48741 - 0.313053 -0.435967 0.5271 - 0.316735 -0.436872 0.530087 - 0.31932 -0.436343 0.532186 - 0.330095 -0.442163 0.540918 - 0.387371 -0.449961 0.587392 - 0.424483 -0.424729 0.617584 - 1.03605 -0.929322 1.11274 - 1.04462 -0.851464 1.11989 - 1.04338 -0.80151 1.11901 - 1.05213 -0.791944 1.12614 - 1.16914 -0.799553 1.22111 - 1.22776 -0.80332 1.26868 - 1.69971 -0.80692 1.65178 - 1.70435 -0.787165 1.65561 - 1.70955 -0.745945 1.65993 - 1.70909 -0.691986 1.6597 - 1.71289 -0.682814 1.66281 - 1.73358 -0.56324 1.67991 - 1.73383 -0.531931 1.68019 - 1.74165 -0.523831 1.68657 - 1.73768 -0.49145 1.68342 - 1.73856 -0.481327 1.68416 - 1.73773 -0.378453 1.68375 - 1.77938 -0.29412 1.71778 - 1.77833 -0.201645 1.71717 - 1.78251 -0.171424 1.72064 - 1.789 -0.0595289 1.72619 - 1.79395 0.0323986 1.73045 - 1.79958 0.0941264 1.73518 - 1.44173 0.5084 1.44576 - 1.00163 0.563615 1.08864 - 0.865535 0.586936 0.978222 - 0.779756 0.619419 0.908673 - 0.719078 0.601626 0.859371 - 0.709585 0.63515 0.851751 - 0.716873 0.736688 0.857929 - 0.39592 0.453757 0.59666 - 0.227577 0.314184 0.459645 - 0.219973 0.315629 0.453477 - 0.22471 0.339024 0.457382 - 0.14949 0.321921 0.396277 - 0.148397 0.322909 0.395392 - 0.146859 0.323069 0.394144 - 0.116404 0.351474 0.369495 - 0.112505 0.599569 0.366969 - 0.113316 0.612816 0.367661 - 0.11236 0.67338 0.367041 - 0.151614 1.28532 0.400483 - 0.129556 1.28809 0.382584 - 0.0857743 1.29572 0.347063 - 0.0632442 1.29065 0.328761 - 0.0461855 1.30048 0.314938 - 0.00643416 1.30124 0.282671 --0.00679345 1.30171 0.271935 - -0.0111801 1.30381 0.268379 - -0.042568 0.41151 0.240601 - -0.0511122 0.29535 0.233366 - -0.053112 0.295066 0.231742 - -0.0609999 0.301811 0.225356 - -0.124097 0.338596 0.174231 - -0.133406 0.356527 0.16672 - -0.354083 0.988315 -0.0107908 - -0.159156 0.37296 0.145859 - -0.140352 0.299192 0.160934 - -0.142721 0.298799 0.15901 - -0.143732 0.298145 0.158188 - -0.161848 0.267409 0.143402 - -0.173447 0.271827 0.133998 - -0.548393 0.92179 -0.168697 - -0.663982 1.01047 -0.2623 - -0.661842 0.89803 -0.260852 - -0.662262 0.845348 -0.261329 - -0.309251 -0.419793 0.0170342 - -0.286873 -0.393421 0.0356584 - -0.251651 -0.358756 0.0649558 - -0.215539 -0.364954 0.0948845 - -0.154805 -0.371208 0.145229 - -0.138524 -0.366056 0.158744 - -0.136614 -0.369179 0.160319 - -0.125614 -0.370176 0.169438 - -0.101054 -0.363258 0.189822 - -0.0875461 -0.367496 0.201012 - -0.0813934 -0.378295 0.206085 - -0.07154 -0.383526 0.214243 - -0.0570057 -0.381925 0.226299 - -0.0452441 -0.379204 0.236059 - -0.0208688 -0.388935 0.256246 - -0.0168492 -0.392807 0.259569 --0.00630305 -0.392139 0.268316 --0.00498628 -0.392022 0.269408 - 0.00528394 -0.387833 0.277935 - 0.031636 -0.39489 0.299768 - 0.0410568 -0.401578 0.307563 - 0.05546 -0.402213 0.319505 - 0.0600058 -0.396449 0.323289 - 0.0718461 -0.403329 0.333089 - 0.0844265 -0.405231 0.343516 - 0.0987894 -0.401352 0.355436 - 0.144738 -0.408488 0.39352 - 0.158314 -0.414651 0.404761 - 0.181342 -0.418641 0.423845 - 0.211892 -0.429097 0.449152 - 0.244744 -0.426452 0.4764 - 0.253933 -0.425562 0.484022 - 0.317506 -0.434398 0.536715 - 0.3234 -0.437999 0.541592 - 0.335991 -0.438182 0.552033 - 0.396901 -0.436605 0.602545 - 0.393513 -0.417822 0.599784 - 1.15385 -0.796325 1.22929 - 1.29062 -0.814144 1.34265 - 1.54147 -0.841571 1.55059 - 1.66648 -0.864077 1.65419 - 1.68299 -0.861351 1.66789 - 1.71385 -0.699974 1.6939 - 1.74127 -0.4863 1.71719 - 1.74287 -0.476277 1.71855 - 1.74068 -0.444443 1.71681 - 1.75587 -0.231455 1.72996 - 1.77581 -0.0391721 1.74699 - 1.78059 0.011951 1.75109 - 1.79679 0.115525 1.76479 - 1.80847 0.189406 1.77467 - 1.66082 0.339155 1.65263 - 1.61102 0.338662 1.61132 - 1.35758 0.534403 1.40168 - 1.32008 0.536604 1.37059 - 1.2878 0.540105 1.34383 - 1.22113 0.559853 1.2886 - 1.10017 0.556237 1.18829 - 1.00243 0.569094 1.10727 - 0.798863 0.596125 0.938542 - 0.724259 0.599492 0.876688 - 0.716723 0.703693 0.87071 - 0.713247 0.719884 0.867869 - 0.723052 0.742798 0.876059 - 0.725313 0.758635 0.877975 - 0.721987 0.769002 0.875244 - 0.262345 0.32175 0.492939 - 0.239877 0.302039 0.474257 - 0.231321 0.305498 0.46717 - 0.223334 0.309307 0.460558 - 0.222421 0.327631 0.459848 - 0.220694 0.334007 0.458432 - 0.218965 0.337531 0.457008 - 0.218256 0.342505 0.456433 - 0.229757 0.398585 0.466116 - 0.163163 0.325744 0.410705 - 0.151629 0.329275 0.40115 - 0.149137 0.360294 0.399165 - 0.147414 0.374616 0.397773 - 0.141019 0.364454 0.392444 - 0.119226 0.343863 0.374319 - 0.119372 0.355137 0.37447 - 0.107994 0.338078 0.364991 - 0.107188 0.350941 0.364355 - 0.111059 0.38181 0.367646 - 0.105618 0.423097 0.363241 - 0.10829 0.552517 0.365793 - 0.109866 0.594781 0.36721 - 0.110233 0.721059 0.367842 - 0.0753414 1.29198 0.340393 - 0.0667291 1.2941 0.333257 - 0.0539891 1.30059 0.322709 - 0.0496193 1.30105 0.319087 - 0.0143935 1.2968 0.289866 - -0.0444133 0.298161 0.238508 - -0.0566793 0.289474 0.228314 - -0.0706251 0.34442 0.216893 - -0.0762547 0.342126 0.212218 - -0.0797666 0.326951 0.209267 - -0.0888843 0.326312 0.201705 - -0.112356 0.32045 0.182226 - -0.1514 0.357293 0.149946 - -0.140697 0.295221 0.15866 - -0.146866 0.271633 0.153483 - -0.530958 0.889839 -0.163407 - -0.651064 0.989084 -0.262744 - -0.255573 -0.364424 0.0576303 - -0.253393 -0.36418 0.0594773 - -0.244766 -0.356614 0.0668042 - -0.174979 -0.370065 0.125874 - -0.156828 -0.375027 0.141233 - -0.154324 -0.376502 0.14335 - -0.139565 -0.371631 0.155863 - -0.13638 -0.365758 0.158575 - -0.135161 -0.366382 0.159607 - -0.113688 -0.373997 0.177773 - -0.106822 -0.373508 0.183589 - -0.0916223 -0.377519 0.196452 - -0.0674125 -0.370168 0.216975 - -0.0655684 -0.389674 0.218486 - -0.0545233 -0.382258 0.22786 - -0.0479335 -0.378975 0.233449 - -0.0392799 -0.385644 0.240761 - -0.0340329 -0.379876 0.24522 - -0.0238946 -0.381982 0.253801 - -0.0211387 -0.395934 0.256098 - -0.019765 -0.398898 0.257254 - -0.0141455 -0.369635 0.26209 --0.00014652 -0.393471 0.273884 - 0.0215295 -0.385869 0.292262 - 0.0532451 -0.396412 0.319095 - 0.0613068 -0.400762 0.325912 - 0.0821107 -0.401461 0.343529 - 0.102557 -0.402878 0.360843 - 0.112761 -0.404689 0.369479 - 0.138834 -0.411361 0.391544 - 0.158356 -0.41082 0.40808 - 0.171768 -0.415354 0.419427 - 0.173965 -0.415906 0.421286 - 0.300076 -0.438781 0.528034 - 0.302981 -0.435029 0.530504 - 0.325153 -0.436769 0.549278 - 0.349086 -0.442606 0.569532 - 0.3964 -0.420881 0.609661 - 0.987243 -0.936895 1.10871 - 0.991598 -0.932238 1.11241 - 1.00164 -0.873166 1.12108 - 0.998104 -0.861878 1.11811 - 0.9987 -0.797663 1.11878 - 1.11232 -0.791852 1.21502 - 1.29876 -0.808051 1.37288 - 1.70143 -0.799824 1.71394 - 1.70046 -0.788293 1.71315 - 1.71167 -0.694481 1.72289 - 1.71694 -0.674864 1.7274 - 1.72134 -0.654903 1.73118 - 1.73676 -0.531679 1.74457 - 1.75435 -0.20251 1.76033 - 1.75576 -0.192405 1.76155 - 1.81853 0.170917 1.81566 - 1.81793 0.18147 1.81518 - 1.63904 0.337779 1.66408 - 1.07366 0.354249 1.18529 - 0.977919 0.567414 1.10476 - 0.905042 0.58423 1.04308 - 0.879865 0.581267 1.02175 - 0.786002 0.604485 0.942316 - 0.779954 0.612268 0.937214 - 0.703206 0.623217 0.872242 - 0.706404 0.644048 0.875005 - 0.707405 0.65104 0.875871 - 0.715346 0.70239 0.882731 - 0.437253 0.516695 0.646718 - 0.23006 0.299086 0.470669 - 0.217187 0.329731 0.459847 - 0.218583 0.340434 0.461057 - 0.216303 0.343237 0.459133 - 0.210801 0.344428 0.454477 - 0.217925 0.364226 0.460562 - 0.233266 0.390453 0.473623 - 0.231645 0.394938 0.472263 - 0.148419 0.326824 0.401597 - 0.151008 0.347536 0.403844 - 0.150436 0.356427 0.403382 - 0.150569 0.389323 0.403582 - 0.118776 0.336132 0.376516 - 0.116217 0.355081 0.374398 - 0.103308 0.344674 0.363438 - 0.106967 0.383364 0.366638 - 0.105284 0.392037 0.365235 - 0.104296 0.413271 0.364454 - 0.104416 0.429411 0.364598 - 0.106633 0.465824 0.366572 - 0.106767 0.578692 0.36698 - 0.104996 0.599197 0.365534 - 0.106132 0.62476 0.366564 - 0.105727 0.679766 0.366365 - 0.0657608 1.29709 0.334134 - 0.026575 1.29496 0.30094 - 0.00957204 1.30503 0.286566 - -0.0421799 0.427578 0.240436 - -0.0513796 0.29535 0.232298 - -0.0543271 0.294915 0.229801 - -0.0622172 0.302605 0.223138 - -0.0771185 0.332724 0.210597 - -0.0835785 0.329934 0.205118 - -0.117582 0.336954 0.176338 - -0.120498 0.343032 0.173885 - -0.133118 0.368948 0.163264 - -0.179096 0.502281 0.124673 - -0.139407 0.296758 0.157748 - -0.14142 0.298799 0.156049 - -0.142067 0.297252 0.155497 - -0.143055 0.296595 0.154658 - -0.146005 0.294588 0.152154 - -0.143271 0.276058 0.154422 - -0.154725 0.274305 0.144716 - -0.152514 0.26434 0.146563 - -0.156426 0.262281 0.143244 - -0.176096 0.272587 0.126612 - -0.526425 0.872891 -0.168521 - -0.633932 0.827973 -0.259689 - -0.312863 -0.378576 0.00384766 - -0.305927 -0.379191 0.0098476 - -0.296322 -0.403196 0.018094 - -0.283551 -0.387443 0.0291853 - -0.254568 -0.362343 0.0543281 - -0.2298 -0.356386 0.0757731 - -0.208789 -0.363748 0.093932 - -0.185297 -0.359507 0.114268 - -0.177485 -0.370999 0.120997 - -0.170639 -0.373469 0.126913 - -0.136276 -0.367619 0.15666 - -0.132983 -0.375707 0.159488 - -0.110125 -0.372101 0.179274 - -0.0735745 -0.380038 0.210876 - -0.0685503 -0.381055 0.215221 - -0.0355079 -0.377831 0.243817 - -0.0113624 -0.388451 0.26468 - 0.00974627 -0.393012 0.282931 - 0.0107506 -0.389821 0.283809 - 0.0162197 -0.39186 0.288535 - 0.0364062 -0.401347 0.305975 - 0.0403722 -0.400216 0.30941 - 0.0630437 -0.400699 0.329024 - 0.0652375 -0.397734 0.33093 - 0.0779042 -0.401744 0.341878 - 0.0972531 -0.400639 0.358622 - 0.118061 -0.410417 0.376599 - 0.131801 -0.40255 0.388508 - 0.14534 -0.414526 0.40019 - 0.149425 -0.411508 0.403732 - 0.162195 -0.415544 0.41477 - 0.163169 -0.413594 0.415618 - 0.194 -0.42047 0.442275 - 0.206725 -0.420739 0.453284 - 0.229881 -0.426274 0.473304 - 0.266813 -0.430741 0.505245 - 0.33975 -0.43592 0.568337 - 0.356304 -0.439847 0.582649 - 0.978097 -0.796827 1.11968 - 1.10778 -0.796072 1.23189 - 1.2593 -0.809416 1.36294 - 1.30843 -0.812172 1.40544 - 1.67843 -0.863461 1.72543 - 1.701 -0.840788 1.74502 - 1.77042 -0.206226 1.80676 - 1.77758 -0.144233 1.81312 - 1.78698 -0.0610814 1.82147 - 1.79117 -0.0297332 1.82518 - 1.79124 -0.01924 1.82527 - 1.79847 0.0439018 1.83169 - 1.80436 0.0863563 1.8369 - 1.80631 0.0970453 1.83862 - 1.81848 0.19392 1.8494 - 1.83548 0.337164 1.86449 - 1.26358 0.333248 1.36967 - 1.22687 0.331298 1.3379 - 1.19909 0.331332 1.31387 - 1.0908 0.322311 1.22015 - 1.41443 0.530517 1.5007 - 1.17958 0.543428 1.29755 - 1.08247 0.557657 1.21357 - 1.03631 0.562787 1.17365 - 0.976174 0.571764 1.12164 - 0.782238 0.613605 0.953953 - 0.714172 0.695018 0.895277 - 0.722114 0.804991 0.90244 - 0.588214 0.68516 0.786273 - 0.225979 0.30269 0.471855 - 0.210976 0.321905 0.458926 - 0.154426 0.320427 0.409995 - 0.153646 0.324932 0.409332 - 0.154593 0.332681 0.410172 - 0.149644 0.342182 0.405915 - 0.148512 0.343204 0.404938 - 0.102687 0.457406 0.365592 - 0.102111 0.508626 0.36523 - 0.104783 0.658888 0.367938 - 0.105301 0.711354 0.368526 - 0.117301 0.855514 0.37929 - 0.154912 1.28718 0.412972 - 0.0642009 1.29211 0.334502 - 0.0602051 1.29662 0.331057 --0.00419593 1.29758 0.275339 - -0.0170269 1.2999 0.264244 - -0.05498 1.26954 0.231327 - -0.0422187 0.422583 0.240128 - -0.0416091 0.340519 0.240438 - -0.0419828 0.301423 0.240012 - -0.0923885 0.322931 0.196458 - -0.0932554 0.32159 0.195704 - -0.105629 0.325142 0.185007 - -0.137578 0.38674 0.157529 - -0.150448 0.426303 0.146498 - -0.133191 0.294751 0.16108 - -0.137735 0.294068 0.157148 - -0.141944 0.292377 0.153502 - -0.141271 0.270148 0.154025 - -0.145666 0.274919 0.150235 - -0.151334 0.274032 0.145329 - -0.164144 0.266819 0.134226 - -0.193039 0.297419 0.109307 - -0.536518 0.866106 -0.186366 - -0.62642 0.924078 -0.263997 - -0.615895 0.876461 -0.255016 - -0.225249 -0.361479 0.0750755 - -0.172696 -0.370065 0.121748 - -0.140426 -0.370325 0.15042 - -0.13938 -0.376276 0.151333 - -0.124539 -0.378301 0.164515 - -0.123303 -0.378865 0.165611 - -0.0602577 -0.388518 0.221604 - -0.0533806 -0.381418 0.227733 - -0.0483998 -0.381967 0.232157 - -0.0396385 -0.381648 0.239943 - 0.0047343 -0.389638 0.279348 - 0.0233204 -0.403341 0.295826 - 0.0301819 -0.394558 0.301946 - 0.065511 -0.399107 0.333325 - 0.0806639 -0.407115 0.346768 - 0.118655 -0.408729 0.38052 - 0.120312 -0.408773 0.381992 - 0.149072 -0.412222 0.407537 - 0.152508 -0.411874 0.410591 - 0.154229 -0.411682 0.412121 - 0.172654 -0.415278 0.428483 - 0.17564 -0.41746 0.43113 - 0.213616 -0.423238 0.464857 - 0.218654 -0.420558 0.469341 - 0.239581 -0.424895 0.487924 - 0.249582 -0.429269 0.496799 - 0.253929 -0.432175 0.500653 - 0.329511 -0.436759 0.567798 - 0.363184 -0.441569 0.597705 - 0.948794 -0.798473 1.11709 - 0.973763 -0.771526 1.13934 - 1.09294 -0.78673 1.2452 - 1.10678 -0.788025 1.25749 - 1.19114 -0.802011 1.33241 - 1.6843 -0.865286 1.77043 - 1.70077 -0.782632 1.78528 - 1.71377 -0.73233 1.79697 - 1.71612 -0.722163 1.79909 - 1.71773 -0.71169 1.80055 - 1.71584 -0.644755 1.79905 - 1.73194 -0.519909 1.81369 - 1.73361 -0.509636 1.8152 - 1.74437 -0.448173 1.82492 - 1.75603 -0.354782 1.83553 - 1.7642 -0.260736 1.84304 - 1.77651 -0.177589 1.8542 - 1.79451 -0.0301412 1.87059 - 1.80155 0.0872469 1.87716 - 1.8165 0.131115 1.89056 - 1.71331 0.349931 1.79946 - 1.56406 0.338976 1.66682 - 1.34927 0.334627 1.47596 - 1.07412 0.355208 1.23153 - 1.30079 0.452982 1.43319 - 1.24154 0.553447 1.38082 - 0.957519 0.574757 1.12851 - 0.864617 0.583901 1.04599 - 0.849402 0.58671 1.03248 - 0.830955 0.593323 1.0161 - 0.802672 0.60489 0.991005 - 0.712354 0.596618 0.910733 - 0.720612 0.72286 0.918408 - 0.727208 0.784372 0.924433 - 0.721964 0.82198 0.919874 - 0.220099 0.304932 0.472566 - 0.162028 0.326421 0.421026 - 0.149459 0.33396 0.409877 - 0.148994 0.348993 0.409504 - 0.113678 0.354255 0.378139 - 0.0979161 0.354838 0.364136 - 0.0981084 0.363552 0.36433 - 0.0969955 0.456082 0.363588 - 0.101346 0.478429 0.367514 - 0.100285 0.481065 0.366578 - 0.0991801 0.640532 0.366023 - 0.109642 0.822347 0.375806 - 0.14817 1.0976 0.410775 - 0.170851 1.26592 0.431378 - 0.0882995 1.29241 0.358099 - 0.0499715 1.29262 0.324044 - -0.0525905 0.790366 0.23157 - -0.0417522 0.337523 0.239989 - -0.0702338 0.342446 0.214695 - -0.088906 0.324019 0.198055 - -0.170259 0.499224 0.126238 - -0.128217 0.310454 0.163089 - -0.134253 0.306849 0.157716 - -0.136249 0.3056 0.155939 - -0.139527 0.297905 0.153007 - -0.155468 0.27454 0.13878 - -0.158947 0.273975 0.135687 - -0.179586 0.275657 0.117353 - -0.579866 0.916607 -0.236596 - -0.270401 -0.37172 0.0291463 - -0.265818 -0.374471 0.0333198 - -0.25294 -0.366958 0.045089 - -0.243098 -0.363637 0.0540779 - -0.230351 -0.364376 0.0657054 - -0.226678 -0.364342 0.0690571 - -0.208612 -0.366855 0.0855326 - -0.207426 -0.36792 0.0866114 - -0.205045 -0.370027 0.0887785 - -0.193592 -0.366798 0.0992363 - -0.182311 -0.366531 0.109529 - -0.150796 -0.370296 0.138272 - -0.146616 -0.370608 0.142085 - -0.140411 -0.368738 0.147751 - -0.136561 -0.369773 0.15126 - -0.134026 -0.375403 0.153559 - -0.128915 -0.376916 0.158217 - -0.126955 -0.374685 0.160011 - -0.0990868 -0.367547 0.185456 - -0.0980013 -0.382365 0.186407 - -0.0947987 -0.386497 0.189317 - -0.0910866 -0.372271 0.192743 - -0.0820863 -0.37079 0.200958 - -0.0711878 -0.383526 0.210867 - -0.0497306 -0.380843 0.230451 - -0.0399278 -0.382647 0.239389 - -0.0239052 -0.380963 0.254012 --0.00610989 -0.3909 0.270221 - 0.0180749 -0.401229 0.292258 - 0.0289586 -0.393576 0.302209 - 0.0579755 -0.403645 0.328655 - 0.0646278 -0.395701 0.334746 - 0.0808449 -0.403021 0.349522 - 0.0834372 -0.401722 0.35189 - 0.0849936 -0.401997 0.35331 - 0.092276 -0.401352 0.359955 - 0.112883 -0.412158 0.378727 - 0.114209 -0.411323 0.379939 - 0.317966 -0.439547 0.565761 - 0.923821 -0.850702 1.1174 - 0.926787 -0.797853 1.12025 - 0.929342 -0.792211 1.1226 - 0.968553 -0.769147 1.15843 - 1.37086 -0.821243 1.52534 - 1.5028 -0.845531 1.64565 - 1.66238 -0.864578 1.79119 - 1.70442 -0.828139 1.82965 - 1.70838 -0.694129 1.83362 - 1.71552 -0.641396 1.84028 - 1.7201 -0.609959 1.84454 - 1.73487 -0.516191 1.85827 - 1.73981 -0.452447 1.86295 - 1.75297 -0.390781 1.87513 - 1.76634 -0.242794 1.88772 - 1.78121 -0.115863 1.90164 - 1.78186 -0.0944847 1.90229 - 1.80045 0.0450107 1.91962 - 1.80375 0.0667468 1.92269 - 1.80498 0.0776301 1.92384 - 1.8198 0.25379 1.93784 - 1.83017 0.366729 1.94761 - 1.12974 0.327373 1.30846 - 1.26986 0.538948 1.43687 - 1.17245 0.553414 1.34804 - 1.13496 0.559269 1.31386 - 0.911039 0.581079 1.10962 - 0.724833 0.602173 0.939788 - 0.716694 0.721385 0.932685 - 0.694648 0.83098 0.912868 - 0.236738 0.321216 0.493712 - 0.196651 0.33347 0.457171 - 0.19543 0.34965 0.456101 - 0.194299 0.350971 0.455073 - 0.165137 0.330451 0.428412 - 0.151908 0.334045 0.416352 - 0.152768 0.364954 0.41722 - 0.150833 0.371487 0.415472 - 0.103523 0.359893 0.372278 - 0.0953524 0.457021 0.365086 - 0.0971742 0.490105 0.366838 - 0.0979679 0.633024 0.367949 - 0.0975101 0.665241 0.367618 - 0.102909 0.794057 0.372893 - 0.124113 1.28719 0.393573 - 0.0867399 1.29539 0.359498 - 0.0742011 1.29734 0.348064 - 0.0278324 1.29663 0.305757 --0.00967871 1.30871 0.271566 - -0.0265845 1.28699 0.256083 - -0.0417428 0.434651 0.239946 - -0.047286 0.299947 0.234524 - -0.0642897 0.320406 0.219066 - -0.0685844 0.338737 0.215197 - -0.0713476 0.334061 0.212664 - -0.0732323 0.331577 0.210938 - -0.0835408 0.326685 0.201519 - -0.088068 0.321109 0.197374 - -0.092197 0.319658 0.193603 - -0.141175 0.371031 0.149056 - -0.130423 0.331572 0.15876 - -0.133154 0.302604 0.156189 - -0.148252 0.294462 0.142393 - -0.143433 0.265948 0.146712 - -0.150689 0.271742 0.140107 - -0.163937 0.268508 0.128012 - -0.167374 0.265272 0.124867 - -0.175591 0.27082 0.117386 - -0.176461 0.26995 0.11659 - -0.403382 0.665089 -0.089373 - -0.460421 0.745821 -0.141194 - -0.588065 0.809789 -0.257477 - -0.588128 0.802842 -0.257554 - -0.277579 -0.385959 0.0177403 - -0.252969 -0.363521 0.0407301 - -0.242504 -0.355931 0.0505009 - -0.239071 -0.359736 0.0536882 - -0.220402 -0.368985 0.0710564 - -0.193876 -0.366666 0.0957758 - -0.188095 -0.364454 0.101168 - -0.171854 -0.370097 0.116283 - -0.142002 -0.367394 0.144103 - -0.11745 -0.376706 0.16695 - -0.108378 -0.377379 0.175401 - -0.101829 -0.370551 0.181521 - -0.0933264 -0.365289 0.189457 - -0.0911228 -0.37422 0.191485 - -0.0808362 -0.372088 0.201075 - -0.0608453 -0.395473 0.219635 - -0.0525157 -0.384555 0.227426 - -0.0488301 -0.384959 0.230858 - -0.0475024 -0.383083 0.2321 - -0.0437523 -0.3814 0.235599 - -0.0228079 -0.396934 0.255069 --0.00157709 -0.391324 0.274864 - 0.00742571 -0.393012 0.283247 - 0.0131635 -0.399036 0.288576 - 0.0214289 -0.392201 0.296295 - 0.0226802 -0.391902 0.297462 - 0.0364164 -0.396311 0.310247 - 0.0454196 -0.394403 0.31864 - 0.0504422 -0.39259 0.323325 - 0.0598446 -0.398262 0.332069 - 0.0728901 -0.399853 0.344218 - 0.0892567 -0.401129 0.359463 - 0.0997989 -0.405978 0.369271 - 0.108379 -0.408436 0.377258 - 0.119701 -0.404363 0.387817 - 0.121982 -0.406156 0.389938 - 0.135539 -0.411123 0.402554 - 0.138867 -0.410905 0.405656 - 0.143879 -0.410487 0.410326 - 0.145186 -0.409457 0.411547 - 0.165574 -0.414756 0.430527 - 0.166895 -0.413597 0.43176 - 0.175906 -0.412657 0.440158 - 0.1958 -0.420466 0.458672 - 0.202404 -0.425011 0.464811 - 0.240499 -0.421615 0.500313 - 0.252814 -0.429449 0.511764 - 0.26334 -0.433966 0.521559 - 0.279027 -0.430192 0.536183 - 0.280909 -0.429069 0.53794 - 0.30815 -0.435394 0.563302 - 0.918542 -0.768044 1.13107 - 0.922871 -0.763915 1.13511 - 1.02921 -0.77472 1.23415 - 1.05107 -0.782476 1.2545 - 1.13841 -0.793073 1.33584 - 1.20717 -0.803398 1.39987 - 1.22031 -0.802842 1.41212 - 1.24675 -0.810583 1.43673 - 1.60074 -0.852372 1.76641 - 1.70035 -0.811226 1.85932 - 1.71976 -0.671707 1.87779 - 1.7232 -0.59484 1.8812 - 1.73013 -0.56392 1.88774 - 1.73765 -0.467254 1.89502 - 1.73983 -0.456906 1.89708 - 1.74984 -0.383063 1.9066 - 1.75358 -0.318802 1.91026 - 1.77066 -0.213314 1.92646 - 1.82011 0.211837 1.97369 - 1.82531 0.290622 1.97875 - 1.82581 0.369469 1.97943 - 1.39635 0.336219 1.57923 - 1.21902 0.332865 1.41401 - 1.14875 0.328731 1.34853 - 1.0747 0.342514 1.27959 - 1.21628 0.546333 1.41205 - 1.02615 0.569491 1.23497 - 0.918752 0.5781 1.13494 - 0.86519 0.590864 1.08507 - 0.839741 0.586895 1.06135 - 0.792461 0.579568 1.01729 - 0.794563 0.606193 1.01932 - 0.703942 0.609248 0.934898 - 0.706079 0.629214 0.936944 - 0.711263 0.646031 0.941819 - 0.726025 0.779498 0.955937 - 0.207944 0.305141 0.471969 - 0.192405 0.339675 0.457586 - 0.166687 0.325048 0.433586 - 0.16506 0.328148 0.432079 - 0.151855 0.316959 0.419746 - 0.152203 0.361147 0.42019 - 0.153526 0.437753 0.421633 - 0.0919916 0.359744 0.364091 - 0.0953649 0.378504 0.367285 - 0.0941543 0.379243 0.366159 - 0.0958242 0.403305 0.36778 - 0.0941232 0.434437 0.366281 - 0.093255 0.437037 0.365479 - 0.092179 0.48328 0.364603 - 0.0915675 0.487788 0.364046 - 0.0936459 0.629905 0.36637 - 0.100191 0.787229 0.372898 - 0.147174 1.28325 0.418026 - 0.101108 1.2855 0.375115 - 0.060152 1.2951 0.336984 - 0.0312596 1.30027 0.31008 - 0.0187271 1.29926 0.298402 - 0.0103988 1.2988 0.290641 - -0.0488672 0.292746 0.232676 - -0.0524386 0.290241 0.229342 - -0.0792875 0.32176 0.204414 - -0.0821402 0.32603 0.201768 - -0.112387 0.339417 0.173626 - -0.117086 0.34356 0.169259 - -0.231609 0.699472 0.0635356 - -0.134714 0.295598 0.152705 - -0.137908 0.297905 0.149735 - -0.141812 0.266623 0.146013 - -0.152572 0.264702 0.135982 - -0.153813 0.264803 0.134827 - -0.162556 0.267682 0.126689 - -0.178414 0.270589 0.111923 - -0.211864 0.325093 0.0809077 - -0.401942 0.650526 -0.0952894 - -0.270625 -0.385144 0.0194383 - -0.204594 -0.36792 0.0823071 - -0.197963 -0.364339 0.0886258 - -0.181122 -0.365615 0.104645 - -0.148176 -0.371932 0.135972 - -0.144067 -0.372226 0.13988 - -0.125136 -0.367516 0.157904 - -0.126648 -0.383753 0.15642 - -0.124217 -0.384921 0.158731 - -0.115039 -0.374378 0.167491 - -0.107504 -0.375458 0.174657 - -0.0452457 -0.384298 0.233864 - -0.0107739 -0.393247 0.266636 --0.00704657 -0.392894 0.270183 --0.00141372 -0.384195 0.275566 - 0.0181489 -0.392777 0.294154 - 0.022507 -0.396826 0.298289 - 0.0582402 -0.402617 0.332269 - 0.0633149 -0.400468 0.337103 - 0.0979442 -0.40506 0.370036 - 0.0992224 -0.404295 0.371254 - 0.131632 -0.410334 0.402072 - 0.16467 -0.413597 0.433495 - 0.186354 -0.418721 0.45411 - 0.18899 -0.416119 0.456625 - 0.190301 -0.414806 0.457876 - 0.219916 -0.426347 0.48602 - 0.222598 -0.42334 0.48858 - 0.234882 -0.424802 0.500263 - 0.259189 -0.432493 0.523367 - 0.31365 -0.439545 0.575161 - 0.353613 -0.415028 0.613249 - 0.362531 -0.417139 0.621727 - 0.469738 -0.521868 0.723434 - 0.887201 -0.811084 1.1198 - 1.17784 -0.80121 1.39635 - 1.21621 -0.79919 1.43285 - 1.32476 -0.819843 1.53607 - 1.34462 -0.822039 1.55496 - 1.6956 -0.828761 1.88886 - 1.72878 -0.546891 1.9212 - 1.73002 -0.525073 1.92244 - 1.74425 -0.440589 1.93621 - 1.74734 -0.397342 1.93927 - 1.7463 -0.353364 1.9384 - 1.76899 -0.182579 1.96046 - 1.79138 -0.0529953 1.98212 - 1.78944 -0.0310313 1.98034 - 1.80221 0.045956 1.9927 - 1.81964 0.247602 2.00984 - 1.82696 0.293812 2.01693 - 1.83213 0.36302 2.02204 - 1.09399 0.323695 1.31967 - 1.39276 0.527605 1.60448 - 1.19511 0.55066 1.41651 - 1.17097 0.555852 1.39355 - 1.06661 0.567034 1.2943 - 0.86439 0.583162 1.10195 - 0.661884 0.513771 0.909098 - 0.714064 0.680731 0.959203 - 0.717091 0.703129 0.962144 - 0.717239 0.709889 0.962303 - 0.718041 0.724029 0.963106 - 0.717544 0.73708 0.962669 - 0.736389 0.873466 0.980975 - 0.743619 0.889595 0.987897 - 0.231063 0.327031 0.498704 - 0.208283 0.303662 0.476967 - 0.151101 0.328133 0.422633 - 0.155075 0.381829 0.426562 - 0.103079 0.363575 0.377043 - 0.0983526 0.362342 0.372543 - 0.0923398 0.373944 0.366854 - 0.0916917 0.50916 0.366611 - 0.0918351 0.541617 0.366837 - 0.0917839 0.567742 0.366861 - 0.0893773 0.594678 0.364645 - 0.0914062 0.673506 0.366793 - 0.157253 1.27997 0.431113 - 0.10436 1.29262 0.380826 - 0.0920868 1.29495 0.369156 - -0.0231802 1.30596 0.259523 - -0.0314392 1.307 0.251668 - -0.0415614 0.343591 0.239379 - -0.0463372 0.29507 0.234701 - -0.0559146 0.296744 0.225594 - -0.0587258 0.296239 0.222918 - -0.0629257 0.317644 0.218981 - -0.0902422 0.318097 0.192994 - -0.0938384 0.31986 0.189578 - -0.0990863 0.318801 0.184582 - -0.20295 0.637699 0.086647 - -0.144521 0.277708 0.141243 - -0.175086 0.266598 0.112133 - -0.563994 0.803096 -0.256389 - -0.562973 0.767337 -0.255517 - -0.238075 -0.360807 0.0463982 - -0.227554 -0.358383 0.0566193 - -0.221168 -0.36632 0.0627974 - -0.218337 -0.364249 0.0655516 - -0.203946 -0.366023 0.0795179 - -0.186769 -0.359974 0.0962109 - -0.172194 -0.372761 0.110326 - -0.161404 -0.371531 0.120805 - -0.158757 -0.372232 0.123372 - -0.149361 -0.373944 0.132489 - -0.145267 -0.374278 0.136463 - -0.138104 -0.368738 0.143433 - -0.131391 -0.373535 0.149937 - -0.130219 -0.374156 0.151072 - -0.123622 -0.374324 0.157477 - -0.120096 -0.376023 0.160895 - -0.104652 -0.363935 0.175922 - -0.103913 -0.372546 0.176616 - -0.0636508 -0.384933 0.21567 - -0.0501939 -0.383834 0.228737 - -0.0481264 -0.391064 0.230724 - -0.035598 -0.375877 0.24293 --0.00744351 -0.394889 0.27021 - 0.0083907 -0.390591 0.285595 - 0.0141382 -0.39754 0.291155 - 0.0262496 -0.401766 0.302902 - 0.0513495 -0.394525 0.32729 - 0.0604445 -0.399107 0.336107 - 0.0671251 -0.398198 0.342595 - 0.06837 -0.397612 0.343805 - 0.069613 -0.397018 0.345014 - 0.0823355 -0.40226 0.357351 - 0.102064 -0.403777 0.376499 - 0.119763 -0.414204 0.393654 - 0.124526 -0.405168 0.398303 - 0.164452 -0.4178 0.437029 - 0.165756 -0.416622 0.438299 - 0.21628 -0.420964 0.487338 - 0.232504 -0.425562 0.503075 - 0.248196 -0.431686 0.518293 - 0.280205 -0.43361 0.549363 - 0.293821 -0.437187 0.562573 - 0.296219 -0.43661 0.564902 - 0.303427 -0.434754 0.571905 - 0.311941 -0.43816 0.580161 - 0.317018 -0.44081 0.585083 - 0.324339 -0.438458 0.592197 - 0.329353 -0.418092 0.597122 - 0.863791 -0.821482 1.11485 - 1.08654 -0.790175 1.33119 - 1.38962 -0.826898 1.62534 - 1.70277 -0.816952 1.92938 - 1.73574 -0.498427 1.96228 - 1.7442 -0.411648 1.97073 - 1.74668 -0.39007 1.9732 - 1.75473 -0.325423 1.98119 - 1.75571 -0.314573 1.98218 - 1.75847 -0.28199 1.98495 - 1.77645 -0.0860484 2.00295 - 1.78853 -0.0534381 2.01477 - 1.78867 -0.0423835 2.01493 - 1.79305 0.0240107 2.01938 - 1.79478 0.0573223 2.02114 - 1.81582 0.226904 2.04204 - 1.82008 0.23877 2.04621 - 1.45086 0.337611 1.68803 - 1.40168 0.33534 1.64028 - 1.07211 0.362793 1.3204 - 1.33425 0.537747 1.57538 - 1.17508 0.555206 1.4209 - 0.834396 0.58873 1.09024 - 0.677159 0.508497 0.937369 - 0.673936 0.517078 0.934264 - 0.714035 0.655497 0.973579 - 0.718701 0.698553 0.978229 - 0.722787 0.75678 0.982358 - 0.734308 0.841502 0.99378 - 0.737373 0.860169 0.996807 - 0.197365 0.311433 0.471016 - 0.182992 0.318354 0.457081 - 0.186713 0.332577 0.460733 - 0.147154 0.327619 0.422313 - 0.150329 0.349159 0.425456 - 0.169372 0.440825 0.4442 - 0.171488 0.454291 0.446291 - 0.167554 0.472717 0.442524 - 0.101926 0.353163 0.378475 - 0.0892294 0.356299 0.366158 - 0.0905416 0.368656 0.367467 - 0.0902641 0.37212 0.367207 - 0.0885113 0.425115 0.365653 - 0.086635 0.472876 0.363964 - 0.0888623 0.496093 0.366192 - 0.0886478 0.542344 0.366112 - 0.0886407 0.630633 0.366351 - 0.0932687 0.763817 0.371216 - 0.0973511 0.822957 0.375344 - 0.0657666 1.29297 0.345991 - 0.0131069 1.30154 0.29489 - -0.0398838 1.29994 0.24344 - -0.0475295 0.296958 0.233222 - -0.0530198 0.295211 0.227887 - -0.0711192 0.325929 0.2104 - -0.0798024 0.320481 0.201955 - -0.0851365 0.326999 0.196795 - -0.0885069 0.321725 0.193508 - -0.0888574 0.312295 0.193142 - -0.100355 0.321246 0.182004 - -0.185838 0.587149 0.0997551 - -0.120587 0.309038 0.162328 - -0.121959 0.306077 0.160988 - -0.122351 0.303672 0.1606 - -0.131722 0.304416 0.151505 - -0.158575 0.263551 0.125321 - -0.170566 0.262668 0.113677 - -0.173119 0.265001 0.111205 - -0.423668 0.670224 -0.130909 - -0.466505 0.729957 -0.17233 - -0.555705 0.826314 -0.258661 - -0.28465 -0.397018 -0.00437498 - -0.275774 -0.393454 0.00444151 - -0.25962 -0.370892 0.0205333 - -0.231727 -0.359424 0.0482399 - -0.206264 -0.367187 0.073482 - -0.19932 -0.362914 0.0803832 - -0.180566 -0.3629 0.0989906 - -0.17126 -0.36574 0.108216 - -0.170124 -0.36661 0.10934 - -0.156978 -0.366054 0.122385 - -0.153866 -0.369284 0.125464 - -0.15272 -0.370048 0.126599 - -0.135393 -0.376276 0.143772 - -0.128714 -0.37135 0.150413 - -0.11922 -0.375076 0.159821 - -0.102468 -0.373963 0.176446 - -0.0913406 -0.373841 0.187486 - -0.0832036 -0.376346 0.195552 - -0.0593642 -0.409773 0.219111 - -0.0512473 -0.379714 0.227249 - -0.0425813 -0.368507 0.235879 - 0.0004086 -0.391811 0.278466 - 0.0110015 -0.399036 0.288956 - 0.0207348 -0.395841 0.298622 - 0.0295826 -0.395474 0.307402 - 0.0363365 -0.397475 0.314097 - 0.0375665 -0.39707 0.315318 - 0.0400225 -0.396236 0.317758 - 0.0591224 -0.392841 0.336718 - 0.0968826 -0.407045 0.374142 - 0.102198 -0.404798 0.379422 - 0.148175 -0.414687 0.425011 - 0.16221 -0.414107 0.438938 - 0.174742 -0.413079 0.451375 - 0.186899 -0.421797 0.463412 - 0.220891 -0.422607 0.497136 - 0.247702 -0.432226 0.52371 - 0.249993 -0.432001 0.525984 - 0.310935 -0.438109 0.586431 - 0.319215 -0.437127 0.594649 - 0.347899 -0.421678 0.623152 - 0.833352 -0.913274 1.10342 - 0.997447 -0.775193 1.26662 - 1.41747 -0.831546 1.68319 - 1.54073 -0.84665 1.80545 - 1.68915 -0.8786 1.95261 - 1.70367 -0.790854 1.96726 - 1.70862 -0.734562 1.97234 - 1.71799 -0.634427 1.98192 - 1.71579 -0.622212 1.97977 - 1.71955 -0.600743 1.98356 - 1.73304 -0.458158 1.99734 - 1.73718 -0.436827 2.00151 - 1.74048 -0.415264 2.00485 - 1.75207 -0.339619 2.01656 - 1.78913 -0.00931737 2.05426 - 1.79104 0.0354382 2.05628 - 1.82271 0.299281 2.08845 - 1.82719 0.381295 2.09312 - 1.27607 0.334091 1.54618 - 1.07864 0.347438 1.35033 - 1.02968 0.574473 1.3024 - 0.956642 0.591404 1.22998 - 0.78091 0.615198 1.05569 - 0.705633 0.642733 0.981084 - 0.708204 0.657634 0.983676 - 0.715716 0.670775 0.991166 - 0.735632 0.822167 1.01135 - 0.734417 0.835846 1.01019 - 0.578639 0.787685 0.855493 - 0.191647 0.309993 0.470184 - 0.191223 0.317622 0.469785 - 0.181291 0.325355 0.459953 - 0.172376 0.328505 0.451117 - 0.164729 0.324573 0.443519 - 0.159648 0.330481 0.438494 - 0.157591 0.3328 0.436459 - 0.15247 0.329575 0.431369 - 0.148353 0.334012 0.427297 - 0.100634 0.350588 0.379999 - 0.0851887 0.374278 0.364741 - 0.0871802 0.620244 0.36741 - 0.0876277 0.669624 0.367993 - 0.121514 1.03696 0.402649 - 0.137281 1.28725 0.418998 - 0.09248 1.28924 0.374553 - 0.072951 1.2987 0.355204 - 0.0648278 1.29894 0.347145 - 0.00826037 1.3018 0.291028 - -0.0280552 1.30099 0.254995 - -0.0424842 0.305495 0.237874 - -0.0433397 0.303419 0.237019 - -0.0473669 0.291975 0.232992 - -0.0755119 0.335951 0.205191 - -0.085044 0.327972 0.195711 - -0.10899 0.341348 0.17199 - -0.128532 0.300494 0.152486 - -0.135661 0.304583 0.145424 - -0.136873 0.298145 0.144203 - -0.144642 0.296922 0.136492 - -0.147737 0.295655 0.133418 - -0.14865 0.294929 0.132509 - -0.16158 0.269354 0.119609 - -0.166892 0.260309 0.114313 - -0.539364 0.794643 -0.253737 - -0.541553 0.750734 -0.256033 - -0.296625 -0.377628 -0.0216764 - -0.239462 -0.360035 0.0362596 - -0.214622 -0.36344 0.0614035 - -0.210351 -0.361654 0.0657337 - -0.191154 -0.365521 0.0851627 - -0.163967 -0.372637 0.112673 - -0.161989 -0.375188 0.114669 - -0.150566 -0.366429 0.126261 - -0.146313 -0.365925 0.130569 - -0.135327 -0.3694 0.141684 - -0.130777 -0.371975 0.146284 - -0.123424 -0.373744 0.153725 - -0.120657 -0.378301 0.156514 - -0.112078 -0.380183 0.165196 - -0.109341 -0.37928 0.16797 - -0.106037 -0.375458 0.171327 - -0.0985703 -0.375285 0.178889 - -0.0871439 -0.380202 0.190446 - -0.046482 -0.37621 0.231633 - -0.0431245 -0.379493 0.235024 - -0.0419608 -0.379575 0.236202 - -0.0360898 -0.376877 0.242155 - -0.0244755 -0.380936 0.253904 - -0.021957 -0.389858 0.256429 --0.00405881 -0.388337 0.274558 - 0.0110057 -0.393839 0.289798 - 0.0118951 -0.390618 0.290707 - 0.0159426 -0.393764 0.294797 - 0.0438955 -0.408939 0.32306 - 0.0466563 -0.395484 0.325894 - 0.0508718 -0.396917 0.330159 - 0.0559438 -0.402091 0.33528 - 0.0625209 -0.40125 0.341943 - 0.0772017 -0.404532 0.3568 - 0.107961 -0.404271 0.387949 - 0.17937 -0.419537 0.460218 - 0.19848 -0.425625 0.479552 - 0.204966 -0.422258 0.486129 - 0.207573 -0.423145 0.488767 - 0.227402 -0.427082 0.508835 - 0.228707 -0.425484 0.510161 - 0.288885 -0.43661 0.571068 - 0.323877 -0.413721 0.606568 - 0.338253 -0.415459 0.62112 - 0.829892 -0.910957 1.11757 - 0.829839 -0.902647 1.11754 - 0.829583 -0.799619 1.11757 - 0.841486 -0.757767 1.12974 - 0.846802 -0.754946 1.13513 - 0.867109 -0.75732 1.15569 - 0.87851 -0.759353 1.16723 - 0.886293 -0.75824 1.17511 - 1.01071 -0.776966 1.30105 - 1.07396 -0.781043 1.36509 - 1.24457 -0.805241 1.53779 - 1.47015 -0.83847 1.76613 - 1.637 -0.872568 1.93498 - 1.70922 -0.719041 2.00856 - 1.71899 -0.595345 2.0188 - 1.7287 -0.5527 2.02876 - 1.74035 -0.442188 2.04087 - 1.74168 -0.431195 2.04224 - 1.74283 -0.408864 2.04348 - 1.74779 -0.37611 2.04859 - 1.75166 -0.320596 2.05266 - 1.75875 -0.27685 2.05997 - 1.77582 -0.132793 2.07766 - 1.77964 -0.0993014 2.08164 - 1.77754 -0.0654844 2.07961 - 1.78857 0.00188031 2.09097 - 1.79997 0.0587199 2.10267 - 1.81473 0.197035 2.11801 - 1.81271 0.231386 2.11606 - 1.82575 0.267918 2.12937 - 1.824 0.290958 2.12767 - 1.83208 0.374492 2.13609 - 1.31718 0.533464 1.61513 - 1.17057 0.556854 1.46673 - 1.09675 0.561639 1.39199 - 1.0326 0.567034 1.32704 - 0.898975 0.583332 1.19178 - 0.710148 0.603668 1.00062 - 0.730004 0.773701 1.02121 - 0.63557 0.878377 0.92588 - 0.225887 0.340582 0.509486 - 0.189032 0.307225 0.472071 - 0.171553 0.325255 0.454422 - 0.146038 0.336708 0.428617 - 0.153327 0.363775 0.436075 - 0.163318 0.425406 0.446367 - 0.165961 0.439609 0.449084 - 0.171505 0.474684 0.454798 - 0.15372 0.478883 0.4368 - 0.106961 0.368331 0.389136 - 0.0836358 0.392766 0.365585 - 0.0835739 0.402515 0.36555 - 0.0843845 0.462955 0.366543 - 0.0841462 0.482105 0.366356 - 0.0821698 0.510354 0.364435 - 0.083664 0.559826 0.366089 - 0.106693 1.286 0.391476 - 0.0591995 1.29455 0.343406 - 0.0513814 1.29762 0.335498 - 0.0474609 1.29912 0.331532 - 0.0234122 1.29863 0.307178 - 0.00753457 1.3018 0.291109 - -0.0440649 1.27388 0.238778 - -0.0455444 0.289186 0.234477 - -0.0515805 0.298468 0.228391 - -0.0541603 0.296059 0.225771 - -0.0628865 0.327745 0.217025 - -0.0655289 0.333261 0.214365 - -0.0752982 0.327816 0.204457 - -0.0919839 0.326419 0.187556 - -0.0949791 0.325242 0.184519 - -0.10514 0.341819 0.174277 - -0.1064 0.342305 0.173003 - -0.117338 0.30588 0.161823 - -0.120141 0.304233 0.15898 - -0.131196 0.297126 0.147765 - -0.138318 0.304394 0.140573 - -0.148792 0.297539 0.129947 - -0.15143 0.27549 0.127213 - -0.165875 0.267679 0.112564 - -0.403137 0.636215 -0.126649 - -0.528869 0.778934 -0.253565 - -0.52979 0.76685 -0.254532 - -0.529511 0.746619 -0.254307 - -0.291313 -0.387076 -0.0220902 - -0.223326 -0.357171 0.0483395 - -0.2023 -0.361971 0.0700811 - -0.173299 -0.362188 0.100087 - -0.143398 -0.368277 0.131006 - -0.114511 -0.376706 0.160871 - -0.0788602 -0.374364 0.197764 - -0.0777241 -0.37467 0.198939 - -0.0755679 -0.376244 0.201165 - -0.0640265 -0.377776 0.213102 - -0.0554876 -0.389226 0.221904 - -0.0508146 -0.390813 0.226734 - -0.0455848 -0.379307 0.232179 - -0.0421326 -0.379575 0.23575 - 0.00834344 -0.399279 0.287919 - 0.0234702 -0.391613 0.303592 - 0.0349152 -0.393177 0.315429 - 0.0626405 -0.401626 0.344091 - 0.07353 -0.401437 0.355359 - 0.0895187 -0.403056 0.371897 - 0.12401 -0.402256 0.407587 - 0.151061 -0.415354 0.435537 - 0.160856 -0.413408 0.445678 - 0.170737 -0.407294 0.455918 - 0.189769 -0.418255 0.475579 - 0.199953 -0.422133 0.486105 - 0.201229 -0.420688 0.487429 - 0.232649 -0.425881 0.519923 - 0.247423 -0.42682 0.535206 - 0.294915 -0.434775 0.584323 - 0.303391 -0.442229 0.59307 - 0.309211 -0.434466 0.599115 - 0.309445 -0.423459 0.599388 - 0.807444 -0.913723 1.11324 - 0.871762 -0.754718 1.18025 - 0.920327 -0.771619 1.23045 - 0.957643 -0.769579 1.26906 - 0.97406 -0.774248 1.28603 - 1.27151 -0.812087 1.59368 - 1.52531 -0.845483 1.85618 - 1.68258 -0.882199 2.01881 - 1.69679 -0.828898 2.03366 - 1.73285 -0.491016 2.07194 - 1.80319 0.0940514 2.14641 - 1.81975 0.258321 2.16402 - 1.16877 0.328976 1.49067 - 1.15974 0.558093 1.48198 - 0.747312 0.60919 1.05541 - 0.704842 0.637355 1.01155 - 0.717572 0.707532 1.02492 - 0.731761 0.799009 1.03986 - 0.172695 0.33125 0.46007 - 0.159465 0.326533 0.446367 - 0.150186 0.362151 0.436869 - 0.160593 0.408915 0.447772 - 0.159734 0.410944 0.446889 - 0.170343 0.464092 0.458019 - 0.167438 0.485304 0.455074 - 0.167303 0.505013 0.454991 - 0.107236 0.378033 0.392476 - 0.0923574 0.359774 0.37703 - 0.0834503 0.357019 0.367806 - 0.0810167 0.475475 0.365629 - 0.0821256 0.525378 0.36692 - 0.133453 1.2902 0.422228 - 0.0697168 1.29373 0.356292 - 0.0422068 1.2976 0.327839 - -0.0209141 1.2979 0.262531 - -0.0425189 0.297508 0.237299 - -0.0527216 0.300322 0.22675 - -0.0652552 0.331284 0.213871 - -0.098739 0.329762 0.179222 - -0.100735 0.328895 0.177155 - -0.118489 0.371104 0.158907 - -0.134371 0.302137 0.142275 - -0.137108 0.300157 0.139438 - -0.140152 0.299011 0.136285 - -0.153418 0.269155 0.122473 - -0.164292 0.271801 0.111231 - -0.392252 0.623921 -0.123619 - -0.477575 0.744219 -0.211553 - -0.511585 0.773158 -0.246659 - -0.520062 0.740095 -0.255525 - -0.286171 -0.386556 -0.0223814 - -0.280083 -0.390807 -0.0159615 - -0.249796 -0.361977 0.0161221 - -0.227722 -0.358955 0.0394532 - -0.19732 -0.35809 0.0715775 - -0.193394 -0.366671 0.0757007 - -0.185338 -0.36228 0.084225 - -0.126947 -0.373221 0.145887 - -0.115711 -0.373729 0.157756 - -0.115656 -0.37902 0.1578 - -0.112833 -0.37195 0.160803 - -0.0631564 -0.381956 0.21326 - -0.0546414 -0.394364 0.222221 - -0.0436717 -0.386483 0.233834 - -0.0320129 -0.372987 0.246191 - -0.0308941 -0.372997 0.247373 - -0.0297754 -0.372999 0.248555 - -0.0274743 -0.380982 0.250963 - -0.0218768 -0.375815 0.256892 - -0.0179534 -0.392613 0.260989 --0.00502061 -0.391324 0.274657 - 0.017067 -0.396143 0.297979 - 0.0475217 -0.398374 0.33015 - 0.0669734 -0.408361 0.350673 - 0.0786887 -0.41066 0.363044 - 0.0949891 -0.407309 0.380276 - 0.171393 -0.417554 0.460971 - 0.179609 -0.418849 0.469648 - 0.212123 -0.426452 0.503979 - 0.216884 -0.427191 0.509008 - 0.224129 -0.420761 0.516681 - 0.241081 -0.429546 0.534566 - 0.253301 -0.433474 0.547467 - 0.273645 -0.429517 0.568972 - 0.302339 -0.419526 0.599319 - 0.303789 -0.413994 0.600867 - 0.79553 -0.878404 1.11907 - 0.800193 -0.867317 1.12403 - 0.901918 -0.765225 1.2318 - 1.02509 -0.780202 1.3619 - 1.03295 -0.777546 1.37021 - 1.69916 -0.790832 2.07407 - 1.72793 -0.518292 2.10525 - 1.74992 -0.293126 2.12914 - 1.76202 -0.226192 2.14212 - 1.7649 -0.169262 2.14533 - 1.79468 0.0598695 2.17746 - 1.81886 0.284809 2.20366 - 1.3082 0.336219 1.66427 - 1.07355 0.342766 1.41636 - 1.16058 0.556417 1.50894 - 1.02367 0.575104 1.36435 - 0.852193 0.586894 1.1832 - 0.715509 0.680145 1.03906 - 0.714616 0.685948 1.03813 - 0.736343 0.866486 1.06161 - 0.736488 0.8824 1.06181 - 0.183154 0.306523 0.475505 - 0.175183 0.316481 0.467112 - 0.17181 0.322404 0.463566 - 0.165829 0.332778 0.457277 - 0.160281 0.329155 0.451404 - 0.137054 0.461076 0.427247 - 0.0897893 0.349282 0.376984 - 0.0898125 0.369284 0.377066 - 0.0801108 0.451881 0.367056 - 0.0782772 0.477122 0.365192 - 0.0786597 0.568926 0.365864 - 0.0789181 0.727456 0.366598 - 0.0713793 1.28315 0.36025 - 0.0256249 1.30226 0.311963 - -0.0135071 1.30271 0.270619 - -0.0174147 1.30282 0.266491 - -0.0252225 1.30496 0.258247 - -0.0403869 0.380757 0.239536 - -0.0526417 0.298333 0.226349 - -0.0551581 0.295908 0.223683 - -0.078038 0.32793 0.199602 - -0.0839199 0.326026 0.193382 - -0.0884457 0.322332 0.188589 - -0.0942052 0.325242 0.182513 - -0.103324 0.338 0.172916 - -0.118512 0.373944 0.156973 - -0.117934 0.356226 0.157532 - -0.115255 0.340616 0.160317 - -0.113217 0.319318 0.162409 - -0.11516 0.306418 0.160318 - -0.122731 0.302871 0.152308 - -0.129338 0.299554 0.145318 - -0.130235 0.298926 0.144369 - -0.147644 0.302632 0.125986 - -0.190123 0.388283 0.0813536 - -0.150525 0.286269 0.122894 - -0.148134 0.277836 0.125396 - -0.155956 0.269305 0.117107 - -0.162747 0.270985 0.109937 - -0.166773 0.266736 0.105671 - -0.284655 -0.37809 -0.0264622 - -0.287329 -0.385429 -0.0293692 - -0.239792 -0.361416 0.0219938 - -0.2372 -0.363326 0.0247841 - -0.218124 -0.363973 0.0453653 - -0.215144 -0.364767 0.0485784 - -0.197717 -0.365784 0.0673783 - -0.174308 -0.360314 0.092652 - -0.174442 -0.371743 0.0924741 - -0.169807 -0.370987 0.0974779 - -0.16457 -0.368355 0.103136 - -0.162377 -0.370065 0.105497 - -0.160793 -0.373526 0.107195 - -0.149001 -0.375338 0.119914 - -0.140659 -0.374278 0.128917 - -0.121953 -0.381867 0.149079 - -0.103142 -0.374969 0.169396 - -0.0921149 -0.373061 0.181299 - -0.0671319 -0.376106 0.208247 - -0.0620297 -0.383156 0.213731 - -0.0564713 -0.386075 0.21972 - -0.0390744 -0.379777 0.238509 - -0.0323133 -0.379987 0.245804 - -0.0266998 -0.377963 0.251866 - -0.0129347 -0.384157 0.266701 - 0.0141612 -0.388548 0.295923 - 0.0273538 -0.397066 0.310133 - 0.0380699 -0.394403 0.321703 - 0.0451836 -0.398862 0.329366 - 0.0461788 -0.397412 0.330444 - 0.0690211 -0.400202 0.355082 - 0.0787979 -0.401129 0.365628 - 0.0871216 -0.405817 0.374595 - 0.096565 -0.408436 0.384777 - 0.103774 -0.407872 0.392556 - 0.10648 -0.411501 0.395465 - 0.166064 -0.415543 0.459744 - 0.19058 -0.418829 0.486187 - 0.251465 -0.428425 0.551852 - 0.256061 -0.431623 0.556801 - 0.258769 -0.43192 0.559722 - 0.271733 -0.428281 0.573721 - 0.294764 -0.404126 0.598641 - 0.308466 -0.406467 0.613419 - 0.776238 -0.776069 1.11705 - 0.775011 -0.75297 1.11579 - 0.853234 -0.756227 1.20018 - 0.893522 -0.759307 1.24364 - 0.944334 -0.768575 1.29844 - 1.2891 -0.811842 1.6703 - 1.72427 -0.546595 2.14063 - 1.728 -0.45412 2.14493 - 1.74565 -0.36524 2.16423 - 1.7487 -0.331011 2.16762 - 1.78337 -0.032997 2.20591 - 1.79916 0.11951 2.22339 - 1.81451 0.26344 2.24038 - 1.82222 0.348901 2.24895 - 1.3106 0.539859 1.69748 - 1.23058 0.551486 1.61118 - 1.21786 0.554671 1.59747 - 1.19151 0.55155 1.56903 - 1.05162 0.565624 1.41813 - 0.959757 0.575733 1.31904 - 0.938659 0.57793 1.29628 - 0.874748 0.567137 1.22729 - 0.864627 0.581315 1.21641 - 0.846381 0.589802 1.19675 - 0.713219 0.685981 1.05335 - 0.73203 0.795544 1.07397 - 0.731865 0.802766 1.07382 - 0.748805 0.982799 1.09262 - 0.167631 0.33125 0.463632 - 0.150907 0.328537 0.445579 - 0.148959 0.362286 0.443576 - 0.155479 0.404401 0.450735 - 0.165164 0.454797 0.461333 - 0.0890501 0.359774 0.378929 - 0.0862001 0.367334 0.375876 - 0.0771507 0.396023 0.366196 - 0.0770781 0.52417 0.366495 - 0.0759094 0.526778 0.365241 - 0.132268 1.28325 0.428277 - 0.128581 1.28528 0.424304 - -0.0256377 1.30096 0.257952 - -0.0444037 0.292358 0.234737 - -0.0482772 0.298951 0.230577 - -0.0565966 0.291622 0.221579 - -0.0833211 0.324079 0.192839 - -0.0870793 0.316524 0.188762 - -0.0943665 0.328129 0.180933 - -0.103638 0.341819 0.170969 - -0.110971 0.300953 0.162937 - -0.113767 0.303632 0.159928 - -0.134194 0.29993 0.137877 - -0.13996 0.303434 0.131666 - -0.140858 0.302733 0.130695 - -0.148865 0.27389 0.121971 - -0.157587 0.272639 0.112557 - -0.218456 0.327666 0.0470418 - -0.498035 0.715363 -0.253477 - -0.28113 -0.376669 -0.0283688 - -0.283377 -0.397052 -0.0309044 - -0.275322 -0.387757 -0.0220019 - -0.246991 -0.361325 0.00929028 - -0.245927 -0.362727 0.0104581 - -0.212672 -0.366755 0.0470855 - -0.194701 -0.369588 0.066877 - -0.173312 -0.361176 0.0904676 - -0.167225 -0.367487 0.0971553 - -0.165824 -0.367494 0.0986998 - -0.158386 -0.369969 0.106887 - -0.156209 -0.371614 0.10928 - -0.139994 -0.370819 0.127148 - -0.133575 -0.380256 0.134192 - -0.119647 -0.380564 0.149537 - -0.0756909 -0.373 0.197989 - -0.0704158 -0.376352 0.203791 - -0.0631675 -0.383941 0.211754 - -0.0426964 -0.382571 0.234313 - -0.0381511 -0.37983 0.239328 - -0.0212864 -0.385754 0.257892 - -0.0143317 -0.389254 0.265544 --0.00019669 -0.393421 0.281105 - 0.00671245 -0.392105 0.288721 - 0.053807 -0.409207 0.340558 - 0.0594664 -0.399146 0.346823 - 0.123392 -0.408161 0.417227 - 0.141592 -0.413084 0.437264 - 0.1428 -0.411963 0.438599 - 0.174782 -0.415903 0.473824 - 0.182478 -0.419851 0.482291 - 0.187799 -0.418829 0.488157 - 0.202713 -0.420283 0.504585 - 0.219662 -0.423767 0.523248 - 0.291897 -0.43124 0.602812 - 0.30957 -0.412788 0.622338 - 0.761643 -0.823372 1.1192 - 0.757106 -0.79608 1.11428 - 0.767266 -0.747264 1.12562 - 0.792118 -0.748373 1.153 - 1.01291 -0.780692 1.39616 - 1.2002 -0.803759 1.60244 - 1.2912 -0.812538 1.70268 - 1.33332 -0.817789 1.74907 - 1.61968 -0.879164 2.06439 - 1.69143 -0.85486 2.14351 - 1.75765 -0.242559 2.21829 - 1.77735 0.0254381 2.2408 - 1.77982 0.0842895 2.24369 - 1.77855 0.107762 2.24236 - 1.77995 0.178612 2.24412 - 1.78485 0.238417 2.24969 - 1.1264 0.328414 1.5245 - 1.29385 0.539331 1.70962 - 1.22989 0.548709 1.63918 - 1.12153 0.559022 1.51982 - 1.05279 0.564943 1.4441 - 0.922097 0.589215 1.30018 - 0.740332 0.605667 1.09997 - 0.722346 0.744274 1.08056 - 0.752795 0.990709 1.11485 - 0.754151 1.07436 1.11659 - 0.739727 1.08274 1.10072 - 0.165812 0.318175 0.466126 - 0.161646 0.319761 0.46154 - 0.163227 0.33102 0.463316 - 0.162253 0.332281 0.462246 - 0.150245 0.331636 0.449015 - 0.150473 0.366755 0.44937 - 0.150185 0.369548 0.449062 - 0.159767 0.448047 0.459852 - 0.088122 0.350294 0.380625 - 0.0761666 0.360966 0.367485 - 0.0759443 0.40229 0.367363 - 0.074538 0.626237 0.36648 - 0.126206 1.28332 0.425361 - 0.0428379 1.30111 0.333562 - -0.0457049 0.298256 0.233024 - -0.0565934 0.301706 0.221037 - -0.0770411 0.331165 0.198597 - -0.0792955 0.319197 0.196077 - -0.0973952 0.334986 0.176182 - -0.101116 0.342735 0.172106 - -0.139847 0.299385 0.129305 - -0.290585 0.639166 -0.0357622 - -0.168748 0.270589 0.097377 - -0.172675 0.266069 0.093036 - -0.246147 0.373127 0.0124057 - -0.248238 -0.358555 0.0015602 - -0.246153 -0.361404 0.00390992 - -0.237337 -0.355846 0.0138983 - -0.186261 -0.368732 0.0716273 - -0.177769 -0.3696 0.0812299 - -0.169771 -0.3674 0.0902829 - -0.16903 -0.369182 0.0911146 - -0.166569 -0.370112 0.0938956 - -0.154632 -0.36723 0.107406 - -0.150363 -0.370434 0.112224 - -0.149576 -0.372118 0.113109 - -0.140112 -0.371019 0.123816 - -0.139038 -0.371734 0.125029 - -0.131371 -0.36689 0.133716 - -0.130308 -0.367548 0.134915 - -0.129396 -0.373489 0.135929 - -0.0910271 -0.372089 0.17933 - -0.0658405 -0.37733 0.207801 - -0.0596492 -0.38355 0.214785 - -0.0362162 -0.380915 0.241296 - -0.0350769 -0.376947 0.242597 - -0.0318073 -0.375997 0.246298 - -0.0307107 -0.380999 0.247523 - -0.0218033 -0.384755 0.257586 - -0.0149662 -0.388256 0.265308 --0.00859904 -0.381517 0.27253 --0.00567506 -0.392158 0.275805 - 0.00704619 -0.392849 0.290191 - 0.0154401 -0.394856 0.299679 - 0.0316262 -0.391796 0.317995 - 0.0341916 -0.400121 0.320872 - 0.046994 -0.402175 0.335345 - 0.0557069 -0.40125 0.345203 - 0.0867112 -0.402607 0.380265 - 0.113635 -0.409528 0.410696 - 0.114816 -0.408573 0.412034 - 0.117583 -0.412002 0.415153 - 0.166298 -0.41661 0.470238 - 0.175393 -0.423963 0.480503 - 0.184697 -0.419619 0.491038 - 0.201526 -0.42491 0.510057 - 0.21098 -0.419353 0.520767 - 0.271609 -0.432643 0.589299 - 0.279227 -0.432055 0.597917 - 0.281899 -0.417107 0.600985 - 0.290679 -0.403133 0.610957 - 0.462014 -0.595964 0.804161 - 0.77141 -0.740545 1.15366 - 0.792823 -0.752873 1.17784 - 0.838517 -0.756046 1.22951 - 0.954188 -0.772348 1.36029 - 1.00508 -0.777924 1.41783 - 1.02277 -0.782579 1.43783 - 1.19168 -0.800543 1.62882 - 1.28822 -0.812647 1.73797 - 1.41473 -0.835561 1.88099 - 1.49588 -0.859485 1.9727 - 1.57555 -0.868373 2.06278 - 1.71985 -0.595948 2.22681 - 1.72168 -0.524236 2.2291 - 1.73446 -0.184452 2.24458 - 1.73439 0.0135695 2.2451 - 1.73501 0.0717777 2.24598 - 1.74033 0.18903 2.25235 - 1.7365 0.212053 2.24808 - 1.73784 0.294575 2.24985 - 1.73696 0.30623 2.24888 - 1.7344 0.38865 2.24624 - 1.72625 0.422424 2.23713 - 1.4437 0.536675 1.91789 - 1.34842 0.530989 1.81012 - 1.11557 0.556111 1.54684 - 1.09533 0.562739 1.52395 - 0.728796 0.59926 1.10951 - 0.720033 0.605034 1.09961 - 0.712424 0.611579 1.09103 - 0.748757 0.948504 1.13314 - 0.76414 1.06637 1.15089 - 0.742624 1.10331 1.12667 - 0.158966 0.317762 0.464163 - 0.151749 0.355594 0.456115 - 0.15499 0.385685 0.459871 - 0.148604 0.393766 0.452672 - 0.150824 0.402373 0.455209 - 0.152354 0.498397 0.45723 - 0.145099 0.504357 0.449042 - 0.0727772 0.424427 0.367003 - 0.0725776 0.466951 0.366905 - 0.0716993 0.548993 0.36616 - 0.0701106 0.549673 0.364365 - 0.0720732 0.600649 0.366738 - 0.0816066 0.851679 0.378279 - 0.100799 1.28513 0.401295 - 0.0970823 1.286 0.397094 - 0.0895483 1.28668 0.388575 - 0.085737 1.28649 0.384264 - 0.060142 1.29834 0.35535 - 0.0451154 1.30061 0.338362 - -0.0434025 0.301501 0.235229 - -0.045054 0.299343 0.233354 - -0.0492561 0.296847 0.228594 - -0.0790519 0.326343 0.194983 - -0.0843304 0.316258 0.188983 - -0.11866 0.311608 0.150141 - -0.127018 0.300456 0.140653 - -0.140953 0.312281 0.124929 - -0.291638 0.663169 -0.0444413 - -0.154698 0.2669 0.109245 - -0.472558 0.692986 -0.248977 - -0.20355 -0.369799 0.0478555 - -0.19496 -0.37159 0.0577752 - -0.186758 -0.36312 0.0672782 - -0.178762 -0.364964 0.0765119 - -0.177717 -0.365945 0.0777164 - -0.143311 -0.368085 0.117464 - -0.127192 -0.373203 0.136074 - -0.126125 -0.37384 0.137305 - -0.114062 -0.379421 0.151226 - -0.108349 -0.374896 0.157842 - -0.103316 -0.37306 0.163662 - -0.101525 -0.369697 0.165742 - -0.100468 -0.370162 0.166962 - -0.0994095 -0.37062 0.168183 - -0.0472681 -0.379204 0.228405 - -0.0363906 -0.376915 0.24098 - -0.0145161 -0.384157 0.266233 - -0.0112808 -0.382794 0.269976 - 0.0393286 -0.40078 0.328398 - 0.0803976 -0.405644 0.375837 - 0.0892636 -0.402978 0.38609 - 0.0915579 -0.401357 0.388746 - 0.105122 -0.407929 0.404399 - 0.110991 -0.407763 0.41118 - 0.149303 -0.415908 0.455424 - 0.26911 -0.434706 0.593799 - 0.412294 -0.547645 0.758898 - 0.721194 -0.766406 1.11515 - 0.808631 -0.746668 1.21624 - 0.926511 -0.768131 1.35238 - 0.977823 -0.775299 1.41165 - 1.10719 -0.790799 1.56108 - 1.27146 -0.812269 1.75083 - 1.614 -0.87548 2.14642 - 1.65425 -0.884325 2.1929 - 1.69593 -0.704917 2.24161 - 1.69156 -0.569481 2.23698 - 1.69432 -0.534383 2.24027 - 1.69417 -0.415607 2.24047 - 1.69923 0.117426 2.24794 - 1.69886 0.128967 2.24755 - 1.69928 0.221778 2.24832 - 1.69177 0.407474 2.24021 - 1.62414 0.414143 2.16209 - 1.19657 0.332511 1.6678 - 1.46053 0.528492 1.97339 - 1.08741 0.557473 1.54235 - 0.85475 0.597855 1.27364 - 0.842391 0.61057 1.2594 - 0.822233 0.603399 1.23609 - 0.702395 0.630159 1.0977 - 0.719182 0.712275 1.11735 - 0.718241 0.718343 1.11628 - 0.723909 0.730824 1.12286 - 0.162219 0.313577 0.472577 - 0.147787 0.343348 0.455993 - 0.148368 0.417977 0.456892 - 0.150052 0.434178 0.458887 - 0.15335 0.473362 0.462817 - 0.151994 0.474596 0.461255 - 0.0776975 0.373944 0.3751 - 0.0680978 0.37588 0.364014 - 0.0699422 0.387676 0.366181 - 0.0713902 0.584776 0.368456 - 0.071058 0.593193 0.368098 - 0.0723183 0.671051 0.369792 - 0.120534 1.21641 0.427171 - 0.10621 1.28331 0.410824 - 0.0586357 1.29734 0.355897 - -0.0009405 1.29903 0.287064 - -0.0232125 1.2989 0.261329 - -0.0343259 1.292 0.248466 - -0.0534306 0.294217 0.223342 - -0.0559483 0.293767 0.220432 - -0.0608978 0.320017 0.214793 - -0.0753093 0.329495 0.19817 - -0.0818708 0.327333 0.190582 - -0.0881211 0.329108 0.183365 - -0.104026 0.357578 0.165075 - -0.105344 0.314761 0.163421 - -0.117256 0.305513 0.149628 - -0.295658 0.654535 -0.0554421 - -0.161154 0.270877 0.0988003 - -0.1662 0.271387 0.0929715 - -0.169274 0.267771 0.089409 - -0.177983 0.269906 0.0793521 - -0.182744 0.269016 0.0738487 - -0.186856 0.271523 0.0691046 - -0.262366 0.39669 -0.0177624 - -0.426621 0.650171 -0.206779 - -0.462694 0.679298 -0.248371 - -0.283102 -0.393014 -0.0499996 - -0.229849 -0.362758 0.0128663 - -0.193987 -0.366094 0.0551283 - -0.164775 -0.364828 0.0895656 - -0.160657 -0.37628 0.0943845 - -0.148476 -0.375722 0.108745 - -0.135759 -0.371526 0.123748 - -0.131856 -0.370837 0.128351 - -0.131053 -0.372435 0.129292 - -0.0995872 -0.368239 0.166396 - -0.0907629 -0.368778 0.176796 - -0.0854007 -0.369715 0.183114 - -0.0756168 -0.369753 0.194646 - -0.0711001 -0.378063 0.199945 - -0.047389 -0.380202 0.227888 - -0.0420452 -0.381648 0.234182 - -0.0397048 -0.372781 0.236968 - -0.0386524 -0.372833 0.238209 - -0.0190462 -0.392533 0.261259 --0.00238032 -0.377333 0.280951 - 0.0115774 -0.395452 0.297348 - 0.0673297 -0.401997 0.363046 - 0.0806262 -0.402304 0.378718 - 0.0923664 -0.409511 0.392535 - 0.116831 -0.412653 0.421362 - 0.131503 -0.406285 0.438677 - 0.134369 -0.40942 0.442046 - 0.153844 -0.415975 0.464982 - 0.156182 -0.41346 0.467745 - 0.186657 -0.419332 0.50365 - 0.233658 -0.427341 0.559028 - 0.239975 -0.426218 0.566477 - 0.253813 -0.42882 0.582781 - 0.268523 -0.435439 0.6001 - 0.705355 -0.887571 1.11362 - 0.710522 -0.793742 1.12 - 0.705231 -0.744851 1.11392 - 1.45851 -0.858786 2.00149 - 1.6635 -0.773742 2.24339 - 1.65881 -0.759236 2.23791 - 1.65959 -0.637475 2.2392 - 1.65774 -0.2956 2.23808 - 1.66162 -0.0780782 2.24332 - 1.65679 -0.055062 2.2377 - 1.66816 0.116672 2.25164 - 1.66244 0.219606 2.24522 - 1.66809 0.371414 2.25234 - 1.08496 0.337078 1.56487 - 1.42879 0.544168 1.9708 - 1.36165 0.539116 1.89165 - 1.04071 0.564688 1.51341 - 1.01855 0.568907 1.4873 - 0.995204 0.571895 1.45979 - 0.724778 0.604328 1.14113 - 0.729205 0.781294 1.14689 - 0.736265 0.873636 1.1555 - 0.744019 0.940371 1.16485 - 0.763277 1.03514 1.18784 - 0.775934 1.13855 1.20308 - 0.772704 1.144 1.19929 - 0.723245 1.12179 1.14092 - 0.159259 0.318354 0.473634 - 0.158794 0.320379 0.473093 - 0.156107 0.321466 0.469929 - 0.154764 0.321992 0.468348 - 0.148978 0.323219 0.461531 - 0.148904 0.325956 0.461452 - 0.145417 0.36238 0.457454 - 0.145768 0.433703 0.458089 - 0.14614 0.447485 0.45857 - 0.147785 0.49927 0.460669 - 0.0658371 0.359107 0.363639 - 0.0682569 0.386748 0.366577 - 0.0670892 0.40783 0.365266 - 0.0937297 1.28896 0.399392 - 0.0464167 1.30107 0.343659 - 0.0388495 1.29812 0.33473 - 0.0351322 1.2976 0.330347 - 0.0204285 1.29827 0.313017 - 0.00237983 1.31079 0.291781 - -0.0389694 0.43089 0.24032 - -0.046857 0.296167 0.230606 - -0.052 0.297473 0.224548 - -0.0666926 0.331824 0.207335 - -0.0706609 0.332822 0.20266 - -0.0883501 0.326798 0.18179 - -0.0897796 0.329316 0.180113 - -0.107301 0.35466 0.159538 - -0.102669 0.323299 0.1649 - -0.104128 0.311933 0.163146 - -0.118189 0.307698 0.146558 - -0.119195 0.300459 0.14535 - -0.130168 0.299038 0.132411 - -0.294126 0.690774 -0.0596442 - -0.297641 0.653547 -0.0639028 - -0.156836 0.259506 0.100854 - -0.157566 0.258664 0.0999909 - -0.166721 0.26293 0.0892133 - -0.241265 -0.358555 -0.00611779 - -0.220462 -0.365473 0.0189317 - -0.200589 -0.367834 0.0428758 - -0.198529 -0.370128 0.0453508 - -0.192176 -0.366094 0.0530206 - -0.179453 -0.370764 0.0683392 - -0.164905 -0.369182 0.0858767 - -0.137543 -0.372846 0.118842 - -0.119976 -0.375376 0.140005 - -0.115134 -0.380193 0.145826 - -0.0908961 -0.37266 0.17506 - -0.0818965 -0.370774 0.185912 - -0.0792008 -0.366545 0.189174 - -0.0777548 -0.372088 0.190899 - -0.0641212 -0.374584 0.207323 - -0.0505425 -0.400915 0.223605 - -0.0179965 -0.374381 0.262912 --0.00827339 -0.396303 0.274561 - 0.00429192 -0.399036 0.289696 - 0.00540299 -0.398787 0.291036 - 0.0156233 -0.388996 0.303384 - 0.0248305 -0.390072 0.314477 - 0.0298964 -0.400546 0.320549 - 0.0431894 -0.394948 0.336587 - 0.0534748 -0.403525 0.348956 - 0.065308 -0.400127 0.363228 - 0.0961464 -0.40524 0.400378 - 0.161399 -0.419363 0.478974 - 0.199103 -0.422522 0.524405 - 0.200275 -0.420941 0.525823 - 0.206201 -0.416775 0.532978 - 0.25259 -0.433004 0.588834 - 0.260626 -0.429962 0.598528 - 0.260146 -0.414518 0.597998 - 0.260699 -0.404527 0.598696 - 0.268735 -0.408382 0.608369 - 0.331755 -0.468375 0.684131 - 0.666183 -0.882771 1.08588 - 0.697492 -0.739879 1.12406 - 0.717761 -0.745993 1.14847 - 0.736422 -0.742666 1.17097 - 0.855842 -0.7529 1.31486 - 0.884269 -0.760909 1.34909 - 0.947145 -0.770804 1.42484 - 1.07385 -0.787073 1.57749 - 1.12303 -0.793707 1.63674 - 1.13343 -0.791387 1.64928 - 1.56759 -0.87219 2.17227 - 1.62424 -0.490352 2.24174 - 1.62374 -0.190798 2.24208 - 1.62042 -0.179068 2.23811 - 1.62881 -0.123045 2.2484 - 1.62262 -0.0886114 2.24105 - 0.977001 0.57711 1.46504 - 0.923334 0.576268 1.40036 - 0.870893 0.587681 1.3372 - 0.854878 0.620469 1.318 - 0.726537 0.594307 1.16324 - 0.714538 0.67735 1.14904 - 0.727546 0.790134 1.16507 - 0.728753 0.814119 1.1666 - 0.736703 0.853896 1.17631 - 0.741484 0.899658 1.18221 - 0.695967 1.12509 1.12806 - 0.188158 0.349662 0.513633 - 0.152278 0.396174 0.470537 - 0.144883 0.398309 0.461631 - 0.14271 0.458784 0.459202 - 0.143446 0.499608 0.460217 - 0.104146 0.431514 0.41264 - 0.0781988 0.361306 0.381149 - 0.0713471 0.371734 0.372924 - 0.0640622 0.483644 0.364495 - 0.0655192 0.731766 0.367028 - 0.106435 1.28828 0.418082 - 0.0592038 1.29373 0.361177 - -0.0276925 1.29696 0.256461 - -0.0431185 1.0419 0.237071 - -0.0488096 0.284893 0.227841 - -0.054085 0.291092 0.221503 - -0.061395 0.316853 0.212774 - -0.0815598 0.323106 0.188491 - -0.0960227 0.344059 0.171126 - -0.104851 0.356608 0.160526 - -0.124453 0.303792 0.136737 - -0.15214 0.276762 0.103284 - -0.164279 0.270491 0.0886352 - -0.229284 -0.364616 0.00194609 - -0.183906 -0.368977 0.0580823 - -0.166818 -0.368149 0.0792301 - -0.158902 -0.368371 0.0890239 - -0.148392 -0.375923 0.102005 - -0.145717 -0.371333 0.10533 - -0.143404 -0.371993 0.108189 - -0.132679 -0.368774 0.121471 - -0.128302 -0.374954 0.126867 - -0.12001 -0.380068 0.137111 - -0.114181 -0.374898 0.14434 - -0.110692 -0.374678 0.148659 - -0.100679 -0.3817 0.161026 - -0.0938448 -0.374318 0.169506 - -0.0876809 -0.369564 0.177149 - -0.0806832 -0.373072 0.185796 - -0.0710282 -0.371874 0.197747 - -0.0391786 -0.378831 0.237135 - -0.035003 -0.375971 0.242311 - -0.0308877 -0.373994 0.24741 - -0.0205391 -0.376552 0.260207 - -0.013571 -0.391897 0.26878 - -0.0124966 -0.391765 0.27011 --0.00981132 -0.382363 0.273463 --0.00626188 -0.387833 0.277838 --0.00526918 -0.386656 0.27907 --0.00420929 -0.386467 0.280382 - 0.00142863 -0.389371 0.287349 - 0.01038 -0.391216 0.298419 - 0.0135937 -0.390299 0.302399 - 0.0232273 -0.395335 0.314303 - 0.0335824 -0.395445 0.327116 - 0.037168 -0.395971 0.331551 - 0.0456974 -0.40347 0.342082 - 0.0586225 -0.400835 0.358084 - 0.0627977 -0.402659 0.363244 - 0.0688218 -0.406475 0.370686 - 0.108128 -0.405762 0.419326 - 0.119689 -0.409098 0.433621 - 0.132631 -0.410541 0.44963 - 0.186821 -0.417996 0.51666 - 0.197869 -0.420107 0.530324 - 0.203085 -0.422139 0.536772 - 0.206338 -0.42423 0.540791 - 0.207497 -0.422572 0.54223 - 0.233254 -0.425094 0.574093 - 0.668612 -0.884405 1.11134 - 0.674311 -0.867919 1.11844 - 0.673061 -0.798232 1.11712 - 0.671824 -0.760661 1.11571 - 0.735632 -0.739401 1.19473 - 0.930927 -0.770355 1.43629 - 0.939781 -0.769013 1.44725 - 1.06638 -0.785256 1.60386 - 1.10577 -0.794512 1.65256 - 1.18669 -0.801078 1.75267 - 1.57427 -0.852644 2.2321 - 1.5764 -0.743605 2.23508 - 1.5837 -0.68659 2.24429 - 1.58141 -0.358871 2.2425 - 1.58578 -0.336975 2.24797 - 1.5848 -0.325364 2.2468 - 1.58079 -0.233935 2.24213 - 1.57824 -0.0316866 2.23962 - 1.58359 0.147909 2.24681 - 1.58345 0.260854 2.24699 - 1.58282 0.351806 2.24651 - 1.07187 0.564361 1.61494 - 0.984686 0.57499 1.50709 - 0.929539 0.581795 1.43887 - 0.71601 0.608759 1.17474 - 0.717088 0.704822 1.17638 - 0.715679 0.71054 1.17465 - 0.7295 0.797551 1.19203 - 0.763707 1.20692 1.23566 - 0.139069 0.315667 0.459907 - 0.13634 0.365146 0.456688 - 0.136133 0.436426 0.456658 - 0.13833 0.46926 0.459482 - 0.0724267 0.373944 0.37763 - 0.0627338 0.374029 0.365636 - 0.0640374 0.613635 0.368012 - 0.0638997 0.648682 0.367953 - 0.114525 1.25476 0.432525 - 0.111259 1.28926 0.428594 - 0.0432805 1.29808 0.344505 - 0.0254145 1.29948 0.322403 --0.00317723 1.30003 0.287025 - -0.0419325 1.23594 0.238866 - -0.0400458 0.347829 0.238375 - -0.0455149 0.297347 0.231447 - -0.0511533 0.295611 0.224464 - -0.0529091 0.297339 0.222297 - -0.0796861 0.319539 0.189234 - -0.0918796 0.341466 0.174216 - -0.100533 0.328987 0.163468 - -0.109304 0.306949 0.152545 - -0.123636 0.304696 0.134804 - -0.342497 0.94076 -0.133989 - -0.423099 1.17304 -0.232985 - -0.443167 1.15907 -0.257862 - -0.442291 1.14491 -0.256824 - -0.154574 0.283379 0.096454 - -0.154633 0.280886 0.0963726 - -0.155836 0.275882 0.0948676 - -0.154381 0.265217 0.0966347 - -0.157706 0.26754 0.0925278 - -0.163713 0.272877 0.0851117 - -0.16388 0.261239 0.0848672 - -0.178124 0.269776 0.067269 - -0.219262 -0.365968 0.00935926 - -0.201109 -0.364767 0.03231 - -0.19369 -0.368494 0.0416756 - -0.192335 -0.368805 0.0433875 - -0.169282 -0.367884 0.0725295 - -0.162733 -0.368268 0.0808075 - -0.161733 -0.369182 0.0820682 - -0.160429 -0.369215 0.0837157 - -0.159128 -0.369237 0.0853604 - -0.156115 -0.37188 0.0891613 - -0.143031 -0.374702 0.105691 - -0.134135 -0.373566 0.116939 - -0.11706 -0.375976 0.138514 - -0.116041 -0.376568 0.139801 - -0.109506 -0.37807 0.148056 - -0.107267 -0.378188 0.150886 - -0.0738112 -0.371031 0.193198 - -0.0693946 -0.368192 0.19879 - -0.0673989 -0.368699 0.201311 - -0.0544846 -0.373299 0.21762 - -0.0112331 -0.385502 0.272252 --0.00797656 -0.387014 0.276364 - 0.0041681 -0.391607 0.2917 - 0.00590214 -0.398264 0.293871 - 0.0246665 -0.396501 0.317595 - 0.0447735 -0.399107 0.343003 - 0.0539245 -0.402689 0.354558 - 0.0677109 -0.408336 0.371967 - 0.0688143 -0.407628 0.373364 - 0.0921907 -0.406137 0.402917 - 0.099669 -0.40787 0.412364 - 0.103464 -0.402339 0.417179 - 0.109764 -0.408161 0.425124 - 0.111037 -0.403544 0.426747 - 0.113527 -0.402376 0.429899 - 0.125582 -0.410535 0.445111 - 0.134149 -0.41243 0.455933 - 0.171865 -0.416764 0.503594 - 0.579098 -0.810283 1.01708 - 0.656809 -0.873353 1.11511 - 0.661005 -0.863026 1.12044 - 0.661353 -0.855714 1.12091 - 0.659984 -0.838721 1.11923 - 0.768225 -0.750693 1.25634 - 1.39897 -0.848733 2.0533 - 1.53914 -0.845045 2.2305 - 1.54303 -0.725837 2.2358 - 1.54865 -0.447376 2.2438 - 1.54498 -0.299048 2.23963 - 1.5466 -0.265639 2.2418 - 1.5507 -0.12073 2.24744 - 1.54666 0.0129587 2.24276 - 1.54996 0.258836 2.24773 - 1.53879 0.414627 2.23412 - 1.07575 0.340772 1.64858 - 1.37013 0.555451 2.02138 - 1.34033 0.553916 1.9837 - 1.07363 0.564217 1.64661 - 0.869476 0.582091 1.38862 - 0.854338 0.594198 1.36952 - 0.849854 0.598502 1.36387 - 0.709242 0.631311 1.18623 - 0.708063 0.664087 1.18485 - 0.715976 0.678106 1.1949 - 0.769688 1.1089 1.26418 - 0.769482 1.11846 1.26395 - 0.755356 1.21036 1.24639 - 0.149639 0.308663 0.477838 - 0.151202 0.328132 0.479876 - 0.133768 0.40429 0.458085 - 0.13267 0.405462 0.456701 - 0.134848 0.435245 0.459549 - 0.136028 0.446981 0.461079 - 0.135226 0.462892 0.460117 - 0.133145 0.501421 0.45761 - 0.127683 0.506039 0.450721 - 0.0768296 0.369415 0.386 - 0.0702648 0.367745 0.377697 - 0.0687541 0.375397 0.375812 - 0.060581 0.36689 0.365453 - 0.0600519 0.3694 0.364792 - 0.0618591 0.401551 0.36718 - 0.0601012 0.439775 0.365082 - 0.0606388 0.455305 0.365811 - 0.061068 0.562581 0.3667 - 0.0611282 0.679924 0.367154 - 0.0617203 0.71349 0.368011 - 0.0612095 0.741248 0.367454 - 0.105699 1.29125 0.425463 - 0.090834 1.28612 0.406657 - 0.084491 1.29476 0.398667 - 0.00677438 1.30226 0.300455 --0.00385113 1.30103 0.28702 - -0.0384756 0.430928 0.240449 - -0.0439097 0.294513 0.23314 - -0.0472405 0.297164 0.228938 - -0.0695533 0.337017 0.200863 - -0.0720559 0.334261 0.19769 - -0.10117 0.367148 0.160995 - -0.112624 0.307559 0.146325 - -0.114529 0.307353 0.143916 - -0.153697 0.379427 0.0946384 - -0.42738 1.20047 -0.248659 - -0.435798 1.1761 -0.259379 - -0.433677 1.10092 -0.256939 - -0.432216 1.08605 -0.255141 - -0.312846 0.739171 -0.105371 - -0.167851 0.269682 0.0763939 - -0.263659 -0.377869 -0.0530482 - -0.230791 -0.359917 -0.0105538 - -0.229825 -0.361325 -0.00931148 - -0.199013 -0.371161 0.0304362 - -0.181508 -0.36792 0.0530477 - -0.179533 -0.370027 0.0555907 - -0.146721 -0.366338 0.0979652 - -0.125119 -0.374691 0.125827 - -0.105628 -0.373425 0.150996 - -0.0863418 -0.373841 0.175894 - -0.0838082 -0.37069 0.179175 - -0.0739599 -0.374968 0.191876 - -0.0590503 -0.381562 0.211104 - -0.0197804 -0.393444 0.261765 - -0.0119908 -0.381517 0.271861 --0.00995331 -0.381209 0.274493 --0.00397995 -0.392227 0.282169 - 0.00726901 -0.397712 0.296674 - 0.0203498 -0.396692 0.313565 - 0.0349387 -0.4032 0.332379 - 0.0353522 -0.398862 0.332927 - 0.0355756 -0.393563 0.333233 - 0.0366258 -0.393073 0.334591 - 0.0433464 -0.404426 0.34323 - 0.0534484 -0.395807 0.356301 - 0.0570383 -0.39581 0.360936 - 0.0615282 -0.39946 0.366721 - 0.0703787 -0.400112 0.378145 - 0.0745575 -0.401545 0.383535 - 0.103275 -0.412095 0.420577 - 0.130173 -0.416442 0.45529 - 0.208199 -0.420973 0.556012 - 0.21128 -0.418976 0.559996 - 0.23832 -0.408316 0.594942 - 0.316295 -0.477177 0.695388 - 0.642644 -0.859277 1.11548 - 0.64365 -0.800348 1.11697 - 0.644888 -0.787209 1.11861 - 0.649544 -0.742543 1.12477 - 0.720582 -0.744583 1.21648 - 0.757936 -0.743561 1.26471 - 0.875293 -0.76174 1.41616 - 1.13228 -0.795629 1.74783 - 1.20946 -0.807082 1.84745 - 1.40074 -0.849587 2.09427 - 1.42952 -0.854883 2.13141 - 1.50962 -0.533334 2.23587 - 1.51268 -0.47716 2.24001 - 1.51319 -0.0642882 2.24201 - 1.51664 -0.020248 2.2466 - 1.5148 0.31236 2.24532 - 1.19604 0.346593 1.83389 - 1.07054 0.360081 1.67191 - 1.40841 0.545642 2.10872 - 1.18301 0.552756 1.81774 - 1.00569 0.569525 1.58886 - 0.94539 0.57562 1.51103 - 0.807842 0.591929 1.3335 - 0.777474 0.619253 1.29438 - 0.722341 0.603657 1.22315 - 0.714849 0.651575 1.21363 - 0.713619 0.678165 1.21213 - 0.736152 0.866382 1.24184 - 0.749089 0.939928 1.25878 - 0.756877 1.02995 1.26913 - 0.758445 1.05065 1.27122 - 0.766919 1.08101 1.28226 - 0.653399 1.13569 1.13588 - 0.144063 0.3145 0.47561 - 0.144833 0.321466 0.476627 - 0.140486 0.32775 0.471036 - 0.129649 0.335932 0.45707 - 0.132494 0.357602 0.460815 - 0.127501 0.507561 0.454859 - 0.0569037 0.391929 0.363335 - 0.060185 0.422973 0.367672 - 0.0598799 0.681875 0.368124 - 0.0928308 1.29015 0.412653 - 0.0267656 1.29905 0.327387 - -0.0657475 0.337981 0.204808 - -0.0985761 0.386802 0.162583 - -0.0983547 0.338955 0.162713 - -0.109164 0.308275 0.148658 - -0.113259 0.305513 0.143361 - -0.118635 0.303826 0.136414 - -0.124812 0.30793 0.128454 - -0.421683 1.19781 -0.251921 - -0.425436 1.18433 -0.25681 - -0.422945 1.053 -0.254023 - -0.238219 0.489098 -0.0173709 - -0.236628 -0.365203 -0.0236093 - -0.216491 -0.362559 0.00294152 - -0.213606 -0.360035 0.00675201 - -0.210357 -0.36314 0.011024 - -0.206492 -0.368209 0.0161025 - -0.197374 -0.368364 0.0281201 - -0.196399 -0.369548 0.0294012 - -0.184999 -0.36335 0.0444471 - -0.0880097 -0.374032 0.172249 - -0.0761866 -0.370125 0.187845 - -0.0752096 -0.370434 0.189132 - -0.0720965 -0.379486 0.193205 - -0.0455808 -0.37541 0.228168 - -0.0357408 -0.38797 0.241096 - -0.0275705 -0.386901 0.251868 - -0.0215444 -0.383544 0.259822 - -0.0203312 -0.38945 0.261401 --0.00182455 -0.387617 0.2858 - 0.0145046 -0.392257 0.307307 - 0.0256308 -0.401518 0.321942 - 0.0341109 -0.391638 0.333152 - 0.0403425 -0.401134 0.341334 - 0.0477064 -0.39725 0.351053 - 0.0662223 -0.399714 0.375449 - 0.0813129 -0.399631 0.39534 - 0.0823644 -0.398804 0.396729 - 0.0903273 -0.403478 0.407209 - 0.103139 -0.409267 0.424076 - 0.104216 -0.408282 0.425498 - 0.160198 -0.41926 0.499249 - 0.162397 -0.416458 0.502158 - 0.164582 -0.413624 0.505047 - 0.185653 -0.422522 0.532789 - 0.219338 -0.4313 0.577159 - 0.221598 -0.427644 0.58015 - 0.233732 -0.421502 0.596164 - 0.233289 -0.41353 0.595606 - 0.237235 -0.412386 0.600811 - 0.247581 -0.399151 0.614491 - 0.627598 -0.821285 1.11398 - 0.627035 -0.741546 1.1135 - 0.778614 -0.750035 1.31326 - 0.830872 -0.749997 1.38214 - 0.849481 -0.758054 1.40664 - 0.911885 -0.768888 1.48886 - 1.12087 -0.798331 1.76421 - 1.48467 -0.658867 2.24418 - 1.4782 -0.461426 2.2363 - 1.48006 -0.338814 2.23916 - 1.48556 -0.306625 2.24652 - 1.48012 -0.217203 2.23964 - 1.48056 -0.0309695 2.24084 - 1.4824 0.0127653 2.24341 - 1.48257 0.0565559 2.24377 - 1.48681 0.111661 2.24954 - 1.4819 0.133237 2.24315 - 1.48712 0.288572 2.25054 - 1.48633 0.299549 2.24953 - 1.17773 0.355004 1.84297 - 1.10689 0.351263 1.74959 - 1.39241 0.546771 2.12657 - 1.34716 0.55049 2.06694 - 1.15156 0.554892 1.80914 - 1.01965 0.568003 1.63531 - 0.895138 0.583925 1.47126 - 0.844631 0.588813 1.4047 - 0.823627 0.589215 1.37702 - 0.78025 0.594224 1.31986 - 0.778666 0.600099 1.3178 - 0.749267 0.96158 1.28024 - 0.767899 1.09693 1.30525 - 0.776236 1.20023 1.31658 - 0.592057 1.07617 1.07341 - 0.143153 0.309222 0.479194 - 0.140685 0.313031 0.475954 - 0.129543 0.331636 0.46133 - 0.129668 0.337886 0.461514 - 0.128773 0.339064 0.460339 - 0.12865 0.348098 0.460207 - 0.127729 0.349269 0.458996 - 0.137669 0.406505 0.472288 - 0.128384 0.422734 0.460104 - 0.0694482 0.363715 0.382227 - 0.0665739 0.374674 0.378475 - 0.0574836 0.468029 0.366803 - 0.0571384 0.488124 0.366414 - 0.0570967 0.528803 0.366494 - 0.0574777 0.675046 0.36748 - 0.0576993 0.705671 0.367873 - 0.0579678 0.739289 0.368338 - 0.0843593 1.2949 0.404962 - 0.0667124 1.29197 0.381693 - 0.0598916 1.2934 0.372708 - 0.0188763 1.30089 0.318672 - 0.0153694 1.29927 0.314044 - -0.0415142 0.809921 0.23745 - -0.0404666 0.302807 0.237153 - -0.0411362 0.297761 0.236253 - -0.0419214 0.297706 0.235218 - -0.0432891 0.291588 0.233395 - -0.0460936 0.303334 0.229738 - -0.0502572 0.291751 0.224211 - -0.0727633 0.328798 0.19467 - -0.095869 0.3805 0.164386 - -0.0943479 0.31136 0.166162 - -0.098038 0.307216 0.161285 - -0.104692 0.304262 0.152505 - -0.106292 0.303229 0.150392 - -0.115141 0.304701 0.138734 - -0.402204 1.18905 -0.236704 - -0.414914 1.2041 -0.253406 - -0.419639 1.08883 -0.260015 - -0.417278 1.06091 -0.256996 - -0.412289 1.01674 -0.250566 - -0.395775 0.963014 -0.228978 - -0.171865 0.269255 0.0638515 - -0.189063 -0.367356 0.0345058 - -0.178668 -0.366023 0.0485158 - -0.169728 -0.367371 0.0605566 - -0.158437 -0.364749 0.075779 - -0.129881 -0.378659 0.114206 - -0.126916 -0.380752 0.118195 - -0.122716 -0.372837 0.12388 - -0.0774913 -0.375694 0.184803 - -0.0723908 -0.375259 0.191677 - -0.0428062 -0.37865 0.231526 - -0.0408363 -0.378778 0.23418 - -0.0359038 -0.37797 0.240828 - -0.0192416 -0.376279 0.263284 --0.00716246 -0.394608 0.279497 - 0.00714118 -0.391216 0.29878 - 0.00874111 -0.386676 0.300951 - 0.011984 -0.387687 0.305317 - 0.0215122 -0.395527 0.318129 - 0.038692 -0.392953 0.341284 - 0.0562138 -0.405189 0.364851 - 0.0625895 -0.41183 0.373419 - 0.0979979 -0.408573 0.421137 - 0.101928 -0.4038 0.426449 - 0.107611 -0.404103 0.434105 - 0.115829 -0.41103 0.445153 - 0.174443 -0.417996 0.524103 - 0.175525 -0.416473 0.525567 - 0.206164 -0.418679 0.566841 - 0.226697 -0.423939 0.594488 - 0.241014 -0.399205 0.61386 - 0.612113 -0.806353 1.11249 - 0.611159 -0.776266 1.11131 - 0.818196 -0.757628 1.39032 - 0.904182 -0.76513 1.50615 - 0.912066 -0.763036 1.51678 - 0.96806 -0.772462 1.59219 - 1.14491 -0.796475 1.83038 - 1.44547 -0.839725 2.2352 - 1.44447 -0.803187 2.23397 - 1.44561 -0.582199 2.23624 - 1.44922 -0.459066 2.24152 - 1.44851 -0.380783 2.24083 - 1.44923 -0.21582 2.24235 - 1.44616 -0.0740536 2.2387 - 1.44904 0.0126635 2.24287 - 1.44943 0.077849 2.24361 - 1.44868 0.17578 2.24293 - 1.44819 0.186633 2.24231 - 1.44827 0.197562 2.24245 - 1.4505 0.329822 2.2459 - 1.43913 0.426694 2.23091 - 1.44451 0.540733 2.23853 - 1.42737 0.545694 2.21546 - 1.4114 0.550857 2.19396 - 1.27812 0.561106 2.01442 - 1.18298 0.558583 1.88623 - 0.850639 0.586381 1.43854 - 0.826678 0.592498 1.40628 - 0.80004 0.595709 1.3704 - 0.750332 0.601432 1.30344 - 0.708827 0.671599 1.24776 - 0.767266 1.07295 1.32784 - 0.766494 1.11093 1.32693 - 0.77364 1.13087 1.33662 - 0.778447 1.19968 1.34333 - 0.734877 1.20739 1.28465 - 0.718499 1.21314 1.26261 - 0.614372 1.13087 1.12204 - 0.122568 0.36621 0.456841 - 0.125233 0.409138 0.460576 - 0.124134 0.466415 0.459288 - 0.12321 0.468443 0.45805 - 0.123239 0.49349 0.458173 - 0.122141 0.511375 0.456754 - 0.113126 0.503325 0.44458 - 0.097131 0.458615 0.422879 - 0.0811608 0.407206 0.40119 - 0.0547557 0.390345 0.365556 - 0.053113 0.482084 0.363651 - 0.0546623 0.551001 0.36597 - 0.0541308 0.611081 0.365455 - 0.0924026 1.2912 0.419303 - 0.0655329 1.29891 0.383126 - 0.062153 1.29964 0.378574 - 0.0583476 1.29439 0.37343 - 0.0211329 1.29849 0.323302 - 0.0143762 1.29927 0.314201 --0.00262634 1.2968 0.291285 - -0.019463 1.30071 0.268613 - -0.0363335 1.279 0.24581 - -0.0393904 1.22098 0.241497 - -0.0380454 0.438957 0.240684 - -0.0489868 0.295961 0.225463 - -0.0527658 0.294355 0.220366 - -0.0596648 0.322188 0.211164 - -0.0606669 0.32398 0.20982 - -0.0641823 0.33425 0.205118 - -0.10183 0.310955 0.154315 - -0.105913 0.312662 0.14882 - -0.121201 0.315927 0.128233 - -0.409286 1.14104 -0.257148 - -0.164572 0.303369 0.0697541 - -0.156588 0.272185 0.0804073 - -0.168185 0.262937 0.0647512 - -0.175254 0.267205 0.0552412 - -0.176517 0.262603 0.0535242 - -0.184957 0.261655 0.0421488 - -0.243369 -0.361033 -0.0449411 - -0.233719 -0.362976 -0.0316563 - -0.201288 -0.363023 0.0130117 - -0.197532 -0.367955 0.018168 - -0.177832 -0.368519 0.0452991 - -0.177207 -0.370423 0.0461538 - -0.164552 -0.372172 0.0635779 - -0.133841 -0.375938 0.105863 - -0.128572 -0.373361 0.11313 - -0.127383 -0.373145 0.114768 - -0.106623 -0.37902 0.143341 - -0.0953894 -0.362975 0.158869 - -0.0900431 -0.380977 0.166171 - -0.0778505 -0.373406 0.18299 - -0.0727439 -0.372015 0.190028 - -0.0693837 -0.378063 0.194636 - -0.0684137 -0.378327 0.195971 - -0.0556947 -0.380105 0.213483 - -0.0461804 -0.389388 0.226556 - -0.0427834 -0.372656 0.231291 --0.00987122 -0.393978 0.27655 - -0.0028944 -0.391582 0.286167 --0.00189122 -0.391352 0.28755 - 0.01019 -0.398164 0.304166 - 0.0220401 -0.399016 0.320485 - 0.0696826 -0.402461 0.386093 - 0.0717395 -0.400916 0.388931 - 0.0778304 -0.404981 0.397306 - 0.0861002 -0.402585 0.408705 - 0.0973985 -0.404885 0.424258 - 0.11014 -0.409759 0.441791 - 0.132575 -0.410209 0.472689 - 0.150013 -0.417226 0.496684 - 0.162173 -0.41767 0.513431 - 0.175341 -0.422598 0.531551 - 0.183502 -0.423878 0.542787 - 0.222133 -0.412008 0.596035 - 0.226569 -0.408316 0.602157 - 0.594746 -0.871091 1.10768 - 0.607819 -0.720588 1.1262 - 0.839684 -0.755268 1.44544 - 0.948789 -0.7687 1.59567 - 1.07021 -0.785592 1.76284 - 1.22056 -0.827707 1.96978 - 1.33029 -0.842419 2.12087 - 1.40436 -0.85212 2.22285 - 1.40961 -0.725294 2.23052 - 1.41585 -0.522353 2.23981 - 1.41576 -0.466383 2.23987 - 1.41693 -0.455617 2.24151 - 1.41541 -0.344749 2.2398 - 1.41342 -0.170439 2.23765 - 1.41722 -0.127632 2.24303 - 1.41617 0.109577 2.24239 - 1.41636 0.38195 2.24358 - 1.41096 0.46903 2.23645 - 1.38601 0.549086 2.20235 - 1.2823 0.560709 2.05954 - 1.26205 0.56234 2.03167 - 1.17731 0.564122 1.91496 - 0.815806 0.593636 1.41714 - 0.791156 0.598058 1.38321 - 0.788039 0.610305 1.37895 - 0.77894 0.610764 1.36642 - 0.71665 0.667232 1.28082 - 0.728467 0.736624 1.29733 - 0.736111 0.845955 1.30823 - 0.757787 1.20756 1.33932 - 0.74461 1.20853 1.32117 - 0.695374 1.21436 1.25338 - 0.121501 0.334366 0.459971 - 0.121245 0.346094 0.45966 - 0.127284 0.397877 0.468153 - 0.120157 0.430774 0.458448 - 0.108701 0.501704 0.442912 - 0.0530894 0.447717 0.366133 - 0.0531234 0.46137 0.366226 - 0.0532323 0.581965 0.366786 - 0.0612467 0.849226 0.378735 - 0.10059 1.25972 0.434321 - 0.0993058 1.27942 0.432619 - 0.0574987 1.30531 0.375125 - 0.0401732 1.29853 0.351239 - -0.0520731 0.295483 0.220771 - -0.055668 0.302859 0.215845 - -0.0566648 0.305676 0.214481 - -0.0631657 0.334466 0.205625 - -0.0667823 0.335538 0.200648 - -0.0761634 0.325366 0.187692 - -0.0794654 0.330255 0.183161 - -0.0923928 0.32646 0.165343 - -0.104735 0.310795 0.14829 - -0.128409 0.33815 0.115776 - -0.4015 1.20594 -0.257406 - -0.34668 0.814801 -0.183232 - -0.293879 0.652131 -0.111062 - -0.156523 0.272877 0.0768316 - -0.156502 0.270382 0.076853 - -0.163899 0.269328 0.0666613 - -0.166712 0.267952 0.062781 - -0.167397 0.266966 0.0618355 - -0.168461 0.266736 0.0603683 - -0.232723 -0.362936 -0.036554 - -0.223669 -0.365122 -0.0238063 - -0.220119 -0.367883 -0.0188149 - -0.206728 -0.360035 7.761e-05 - -0.202696 -0.364418 0.00574347 - -0.203207 -0.368821 0.00500861 - -0.178676 -0.361706 0.0395925 - -0.177759 -0.362796 0.0408802 - -0.173112 -0.364583 0.0474209 - -0.162942 -0.365092 0.0617458 - -0.144795 -0.373526 0.0872828 - -0.142022 -0.368121 0.0912074 - -0.137591 -0.373019 0.0974328 - -0.122805 -0.368069 0.118281 - -0.108106 -0.374518 0.138967 - -0.106573 -0.377524 0.141116 - -0.0969631 -0.382661 0.154637 - -0.0904242 -0.380553 0.163856 - -0.0817267 -0.384112 0.176097 - -0.066156 -0.377844 0.198054 - -0.0195568 -0.392249 0.263654 --0.00474148 -0.389821 0.284534 - 0.00535936 -0.400382 0.298728 - 0.0185579 -0.396898 0.317334 - 0.0568174 -0.405993 0.371202 - 0.0606816 -0.402279 0.376659 - 0.105248 -0.406514 0.439429 - 0.120116 -0.408239 0.46037 - 0.125292 -0.417943 0.467628 - 0.133548 -0.415543 0.479267 - 0.152645 -0.414878 0.506174 - 0.208015 -0.42408 0.584148 - 0.215797 -0.411828 0.595154 - 0.219055 -0.40289 0.599773 - 0.507223 -0.788884 1.00441 - 0.584921 -0.847711 1.11367 - 0.585072 -0.818007 1.11398 - 0.584919 -0.781526 1.1139 - 0.684082 -0.735872 1.25375 - 0.936276 -0.779358 1.6089 - 1.10406 -0.791988 1.84523 - 1.30497 -0.839347 2.1281 - 1.33706 -0.847802 2.17328 - 1.37824 -0.743483 2.23165 - 1.38218 -0.653293 2.23752 - 1.38303 -0.619512 2.23883 - 1.38325 -0.451805 2.23973 - 1.38037 -0.43988 2.23571 - 1.3856 -0.321009 2.24349 - 1.38527 -0.255881 2.24324 - 1.38294 -0.0623285 2.24063 - 1.38415 0.0445562 2.2427 - 1.38495 0.216359 2.24443 - 1.38396 0.281053 2.24326 - 1.38482 0.445395 2.24504 - 0.994356 0.570778 1.69538 - 0.961395 0.577475 1.64897 - 0.917215 0.584021 1.58675 - 0.888675 0.582251 1.54654 - 0.811415 0.592191 1.43773 - 0.78345 0.60158 1.39836 - 0.710523 0.622626 1.2957 - 0.718166 0.708094 1.30676 - 0.721781 0.733881 1.31194 - 0.732507 0.814493 1.32733 - 0.736798 0.868033 1.33356 - 0.735555 0.874946 1.33183 - 0.742478 0.89125 1.34164 - 0.13361 0.320725 0.481898 - 0.129719 0.333264 0.476461 - 0.11659 0.367356 0.458083 - 0.116208 0.431065 0.457764 - 0.115412 0.433057 0.45665 - 0.117792 0.472211 0.460138 - 0.106537 0.508171 0.444406 - 0.0653048 0.376096 0.385862 - 0.0546938 0.374283 0.370907 - 0.0525828 0.374691 0.367934 - 0.0496814 0.39696 0.363924 - 0.0519316 0.418932 0.36717 - 0.0509338 0.479527 0.365973 - 0.0522299 0.494518 0.367851 - 0.0509218 0.59878 0.366368 - 0.0715723 1.29262 0.397858 - 0.058493 1.29568 0.379443 --0.00735097 1.30003 0.286697 - -0.0423561 0.296707 0.233915 - -0.0616681 0.328735 0.206818 - -0.0629232 0.333477 0.205067 - -0.0637648 0.333261 0.20388 - -0.0921804 0.388589 0.164039 - -0.0949794 0.361358 0.160002 - -0.116593 0.316897 0.129399 - -0.120124 0.322929 0.124446 - -0.194344 0.569041 0.0207346 - -0.387501 1.18905 -0.249244 - -0.39422 1.04901 -0.259193 - -0.392099 1.03256 -0.256261 - -0.390204 0.987663 -0.253747 - -0.164389 0.299506 0.0620039 - -0.155686 0.274468 0.0741783 - -0.160777 0.266232 0.0669779 - -0.17466 0.261243 0.0474023 - -0.231803 -0.359921 -0.0415861 - -0.209304 -0.367158 -0.0091942 - -0.182747 -0.366541 0.0290717 - -0.180354 -0.374339 0.0324915 - -0.172844 -0.368754 0.0433323 - -0.156326 -0.372546 0.0671183 - -0.153906 -0.372665 0.0706037 - -0.134909 -0.376381 0.0979622 - -0.128127 -0.371932 0.10775 - -0.110798 -0.376568 0.132701 - -0.106129 -0.374129 0.139437 - -0.0950082 -0.38121 0.155435 - -0.0940584 -0.381674 0.156802 - -0.0777467 -0.371113 0.180341 - -0.0713577 -0.374274 0.189535 - -0.0640384 -0.37832 0.200067 - -0.0586919 -0.384543 0.207748 - -0.0553782 -0.37712 0.212549 - -0.0450069 -0.377495 0.22749 - -0.0421882 -0.377718 0.231551 - -0.0308859 -0.379963 0.247828 - -0.0258534 -0.393749 0.25503 --0.00646428 -0.389042 0.282983 - 0.00647591 -0.389628 0.301625 - 0.0103448 -0.388334 0.307204 - 0.0131011 -0.394495 0.311154 - 0.0192684 -0.386935 0.320066 - 0.0248009 -0.389644 0.328028 - 0.0330279 -0.394948 0.339863 - 0.0383317 -0.400468 0.347485 - 0.041624 -0.389091 0.352269 - 0.0466336 -0.397691 0.359456 - 0.0560163 -0.404376 0.372952 - 0.0578094 -0.402057 0.375543 - 0.0900046 -0.407763 0.421911 - 0.105941 -0.40334 0.444887 - 0.10784 -0.404823 0.447618 - 0.110051 -0.407135 0.450796 - 0.128188 -0.408973 0.476921 - 0.146853 -0.419851 0.503776 - 0.16978 -0.424895 0.536792 - 0.170833 -0.423333 0.538314 - 0.174626 -0.416253 0.543805 - 0.210999 -0.417664 0.596207 - 0.214478 -0.395035 0.601299 - 0.243922 -0.422803 0.643624 - 0.562193 -0.874717 1.10061 - 0.570479 -0.871293 1.11256 - 0.59127 -0.723896 1.14303 - 0.665416 -0.735098 1.24982 - 0.927447 -0.766372 1.62725 - 0.944954 -0.771314 1.65246 - 1.21487 -0.827449 2.04116 - 1.34528 -0.84225 2.229 - 1.35015 -0.751451 2.23634 - 1.34811 -0.692845 2.23361 - 1.35206 -0.604006 2.2396 - 1.35328 -0.493063 2.24176 - 1.35397 -0.471246 2.24283 - 1.35051 -0.285614 2.23849 - 1.35119 -0.275016 2.23951 - 1.35591 -0.232955 2.24646 - 1.35043 -0.178689 2.23875 - 1.3518 -0.157556 2.2408 - 1.353 -0.0938296 2.24276 - 1.35502 0.0017706 2.246 - 1.35264 0.0229992 2.24265 - 1.34945 0.0547301 2.23816 - 1.35546 0.118886 2.24704 - 1.35171 0.129204 2.24168 - 1.35213 0.4528 2.24341 - 0.715923 0.694722 1.32761 - 0.726686 0.757825 1.34334 - 0.723893 0.786129 1.33941 - 0.73338 0.828094 1.35323 - 0.746125 0.900744 1.37185 - 0.744816 0.907826 1.36999 - 0.775787 1.15521 1.41548 - 0.773708 1.19404 1.41262 - 0.722706 1.21123 1.33919 - 0.693116 1.20548 1.29654 - 0.112751 0.364097 0.457391 - 0.113874 0.427362 0.459231 - 0.113042 0.442204 0.458085 - 0.112533 0.449655 0.457377 - 0.0704624 0.398003 0.39658 - 0.0579644 0.371734 0.378481 - 0.0484146 0.377569 0.364742 - 0.0498017 0.416107 0.366876 - 0.0478644 0.478258 0.364302 - 0.0487872 0.583583 0.366001 - 0.0511077 0.635067 0.369525 - 0.0871455 1.17416 0.42334 - 0.060029 1.29495 0.384694 - 0.0568052 1.29568 0.380052 - 0.0474362 1.30268 0.366577 - 0.0409493 1.30391 0.357235 - 0.0375934 1.30251 0.352395 - 0.00807786 1.29763 0.309851 - -0.0112009 1.30523 0.282101 - -0.030736 1.29096 0.253905 - -0.0339573 1.26899 0.249186 - -0.0382489 0.823988 0.241442 - -0.037563 0.43498 0.241066 - -0.039664 0.355909 0.237761 - -0.0440404 0.298578 0.231255 - -0.0660361 0.323462 0.19965 - -0.084424 0.352534 0.173259 - -0.100228 0.305272 0.150323 - -0.382596 1.11653 -0.253672 - -0.162963 0.267186 0.0597988 - -0.171404 0.260822 0.0476154 - -0.176729 0.261679 0.0399453 - -0.177377 0.260591 0.039008 - -0.205633 -0.36123 -0.00947747 - -0.193732 -0.364267 0.00804667 - -0.192836 -0.365503 0.00936265 - -0.174067 -0.37351 0.036989 - -0.116719 -0.374134 0.121483 - -0.107827 -0.382084 0.134556 - -0.093577 -0.376396 0.155572 - -0.0876104 -0.37613 0.164365 - -0.0865537 -0.375572 0.165924 - -0.0816931 -0.375568 0.173085 - -0.0725687 -0.370736 0.186546 - -0.0597147 -0.37323 0.205477 - -0.0568499 -0.371806 0.209703 - -0.0485158 -0.396168 0.221895 - -0.0475447 -0.396276 0.223326 - -0.0422664 -0.37572 0.231176 - -0.0367242 -0.372971 0.239352 - -0.032969 -0.394994 0.244806 --0.00698023 -0.391027 0.283112 - 0.00806445 -0.393907 0.305269 - 0.0231643 -0.400218 0.327495 - 0.0309668 -0.396416 0.339005 - 0.0446075 -0.394864 0.359108 - 0.0467315 -0.394566 0.362239 - 0.055973 -0.401129 0.375832 - 0.0628019 -0.396044 0.385912 - 0.0781009 -0.404344 0.408424 - 0.123493 -0.411437 0.47528 - 0.141842 -0.418827 0.502289 - 0.143884 -0.416078 0.505307 - 0.156128 -0.410257 0.523368 - 0.186072 -0.423419 0.567442 - 0.203627 -0.415331 0.593336 - 0.500274 -0.810469 1.02901 - 0.55211 -0.873432 1.10516 - 0.555609 -0.796409 1.11059 - 0.55767 -0.784834 1.11367 - 0.557923 -0.743174 1.11419 - 0.594083 -0.724646 1.16753 - 0.707271 -0.745062 1.33423 - 0.790566 -0.754425 1.45693 - 0.925337 -0.767624 1.65545 - 1.13315 -0.81652 1.96147 - 1.15452 -0.820834 1.99294 - 1.32403 -0.52317 2.24376 - 1.3161 -0.422128 2.23243 - 1.31697 -0.400802 2.23379 - 1.32062 -0.358754 2.23933 - 1.32092 -0.348081 2.23979 - 1.32158 -0.188273 2.24134 - 1.32136 -0.0825627 2.24139 - 1.32525 0.118107 2.24785 - 1.32228 0.170776 2.24365 - 1.32135 0.191861 2.24236 - 1.2779 0.563368 2.17966 - 0.912905 0.583017 1.64195 - 0.791383 0.596319 1.46294 - 0.740108 0.601918 1.38741 - 0.71974 0.607197 1.35742 - 0.715476 0.69775 1.35146 - 0.717718 0.707311 1.3548 - 0.722424 0.742184 1.36186 - 0.728528 0.811387 1.3711 - 0.751684 0.984128 1.40583 - 0.764058 1.08572 1.42442 - 0.768044 1.10107 1.43035 - 0.706765 1.215 1.34047 - 0.694624 1.21627 1.32258 - 0.124671 0.316786 0.479609 - 0.123579 0.331742 0.478053 - 0.119691 0.33234 0.472326 - 0.109621 0.422244 0.45781 - 0.110751 0.470734 0.459648 - 0.109026 0.511863 0.457252 - 0.107769 0.512982 0.455403 - 0.082979 0.453306 0.418666 - 0.0479677 0.387543 0.366846 - 0.0481047 0.600721 0.367807 - 0.0481674 0.650012 0.368075 - 0.0471442 0.71383 0.366794 - 0.0506305 0.778854 0.372163 - 0.0711512 1.29377 0.404232 - 0.0106316 1.30626 0.315106 - -0.0389513 0.353941 0.238659 - -0.0413581 0.304806 0.234938 - -0.0421048 0.304755 0.233838 - -0.0464266 0.300341 0.227454 - -0.050249 0.288763 0.221781 - -0.0565319 0.306669 0.212588 - -0.0649537 0.331824 0.200268 - -0.0699233 0.331312 0.192944 - -0.074374 0.319503 0.186345 - -0.0828017 0.350964 0.174039 - -0.0888385 0.331565 0.165075 - -0.0980118 0.314761 0.1515 - -0.377875 1.09458 -0.258075 - -0.375302 1.07535 -0.254352 - -0.301903 0.669301 -0.147651 - -0.290215 0.611405 -0.130637 - -0.167492 0.268235 0.0489614 - -0.231717 -0.357348 -0.0544786 - -0.225703 -0.365114 -0.0454451 - -0.218792 -0.364457 -0.0350292 - -0.205025 -0.365049 -0.0142876 - -0.183243 -0.364342 0.0185344 - -0.169719 -0.366855 0.0389033 - -0.16106 -0.374475 0.051922 - -0.159245 -0.37646 0.0546499 - -0.15194 -0.372611 0.0656707 - -0.137025 -0.368935 0.0881573 - -0.130705 -0.370048 0.0976752 - -0.124621 -0.376113 0.10682 - -0.104607 -0.375076 0.13698 - -0.0959022 -0.37066 0.150112 - -0.0934533 -0.386493 0.153744 - -0.0749384 -0.378961 0.181669 - -0.070803 -0.375259 0.187913 - -0.0586601 -0.373425 0.206216 - -0.05373 -0.384405 0.213605 - -0.0405811 -0.376832 0.233444 - -0.0369432 -0.37697 0.238925 - -0.0333002 -0.377994 0.24441 - -0.0314297 -0.382963 0.247211 - -0.0303886 -0.392934 0.248743 - -0.0258639 -0.383692 0.255594 - -0.0195114 -0.380052 0.265179 - -0.0185947 -0.379931 0.266561 - -0.0150367 -0.377384 0.271931 - -0.0113499 -0.392805 0.27743 - -0.0041021 -0.387154 0.288371 - 0.0182329 -0.394712 0.321997 - 0.0351031 -0.391343 0.347428 - 0.0376013 -0.399349 0.351164 - 0.0404829 -0.397612 0.355512 - 0.0446823 -0.397072 0.361841 - 0.0458297 -0.397384 0.363569 - 0.0686579 -0.398639 0.39796 - 0.0724988 -0.399769 0.403744 - 0.0768705 -0.402574 0.41032 - 0.0800255 -0.400796 0.415081 - 0.0887244 -0.404885 0.428173 - 0.142238 -0.411717 0.50878 - 0.19625 -0.427329 0.590105 - 0.204853 -0.402746 0.603156 - 0.211708 -0.396542 0.613508 - 0.540367 -0.869579 1.107 - 0.540992 -0.825321 1.1081 - 0.543685 -0.743701 1.11246 - 0.543891 -0.716876 1.11286 - 0.673857 -0.737569 1.30861 - 0.812657 -0.753431 1.51769 - 0.849004 -0.759983 1.57243 - 1.20924 -0.827316 2.11498 - 1.23983 -0.836275 2.16103 - 1.29139 -0.776671 2.23893 - 1.29209 -0.742576 2.24011 - 1.29479 -0.687071 2.24438 - 1.28406 -0.548497 2.22871 - 1.29111 -0.518517 2.23945 - 1.29253 -0.335472 2.24224 - 1.28823 -0.0295848 2.23688 - 1.29433 0.0647022 2.24641 - 1.28621 0.126976 2.23439 - 1.29318 0.190832 2.24513 - 1.29066 0.544658 2.24262 - 1.28932 0.55512 2.24063 - 1.19869 0.568758 2.10413 - 1.12899 0.57599 1.99914 - 1.1148 0.578746 1.97776 - 1.1054 0.583738 1.96362 - 0.95235 0.573528 1.73297 - 0.870929 0.590179 1.61035 - 0.833441 0.58914 1.55386 - 0.797781 0.595193 1.50016 - 0.723986 0.605923 1.389 - 0.708933 0.60802 1.36633 - 0.705951 0.619753 1.36188 - 0.710839 0.645455 1.36934 - 0.716312 0.679654 1.37771 - 0.718105 0.68874 1.38044 - 0.718885 0.696958 1.38165 - 0.762393 1.06127 1.44852 - 0.775308 1.14927 1.4683 - 0.739173 1.21123 1.41408 - 0.682769 1.21558 1.32911 - 0.120901 0.331742 0.479319 - 0.116813 0.328833 0.473149 - 0.116016 0.330032 0.471952 - 0.107086 0.327664 0.458489 - 0.106293 0.328786 0.457297 - 0.108891 0.344062 0.461268 - 0.103817 0.360609 0.453683 - 0.108437 0.401912 0.460792 - 0.106859 0.413186 0.458456 - 0.107522 0.463483 0.459637 - 0.104328 0.514988 0.45501 - 0.0573441 0.369566 0.383692 - 0.0548515 0.37703 0.379963 - 0.0597898 1.29519 0.390725 - 0.0564522 1.29296 0.385688 - 0.0380319 1.30292 0.357969 - 0.00331072 1.30595 0.305664 - 0.00015881 1.30625 0.300916 - -0.0188018 1.30457 0.272341 - -0.0413396 0.296811 0.234738 - -0.0464248 0.298345 0.227081 - -0.0471444 0.298256 0.225997 - -0.0485829 0.298061 0.223828 - -0.0493018 0.297954 0.222745 - -0.0528319 0.296344 0.21742 - -0.0659721 0.327406 0.197734 - -0.0685389 0.328626 0.19387 - -0.0920333 0.313774 0.158417 - -0.0941398 0.307216 0.155219 - -0.101427 0.309862 0.144248 - -0.103877 0.301636 0.140527 - -0.166158 0.510204 0.0474408 - -0.294872 0.905568 -0.145069 - -0.368151 1.1016 -0.254772 - -0.366382 1.02062 -0.252399 - -0.369579 0.934796 -0.257527 - -0.313569 0.702216 -0.173976 - -0.301199 0.652871 -0.155516 - -0.158361 0.27165 0.0583255 - -0.157888 0.265858 0.0590173 - -0.168381 0.266614 0.0432102 - -0.225536 -0.361988 -0.0535442 - -0.220343 -0.361485 -0.0454901 - -0.216885 -0.367408 -0.0401509 - -0.199678 -0.363326 -0.0134563 - -0.186426 -0.368752 0.00707184 - -0.179942 -0.362734 0.0171475 - -0.179555 -0.371894 0.0177136 - -0.160054 -0.367213 0.0479675 - -0.12534 -0.376502 0.101759 - -0.12176 -0.379364 0.107299 - -0.117289 -0.368738 0.114271 - -0.110112 -0.378192 0.125364 - -0.100019 -0.383481 0.140994 - -0.0991104 -0.384004 0.142401 - -0.0954664 -0.379773 0.148067 - -0.0819373 -0.379093 0.169046 - -0.0749105 -0.374713 0.179958 - -0.069308 -0.373572 0.188649 - -0.0596133 -0.3772 0.203667 - -0.0500914 -0.413012 0.218299 - -0.0299452 -0.384901 0.24964 - -0.0290188 -0.38586 0.251073 - -0.0271942 -0.385754 0.253902 - -0.023273 -0.394443 0.25995 - -0.0179047 -0.388775 0.268295 - 0.00103012 -0.391507 0.297644 - 0.00646396 -0.388669 0.30608 - 0.00951054 -0.398769 0.310766 - 0.0115148 -0.39083 0.313903 - 0.0155808 -0.392204 0.320203 - 0.02304 -0.395952 0.331754 - 0.0269248 -0.394995 0.337781 - 0.038926 -0.393236 0.356396 - 0.0437543 -0.396444 0.363871 - 0.0516913 -0.398343 0.37617 - 0.0580841 -0.402136 0.386068 - 0.0602647 -0.397117 0.389468 - 0.0703186 -0.400669 0.405044 - 0.0712637 -0.399821 0.406512 - 0.0926446 -0.405995 0.439641 - 0.0936018 -0.404966 0.441129 - 0.0969033 -0.407182 0.44624 - 0.112663 -0.413764 0.470652 - 0.120366 -0.407729 0.482618 - 0.158733 -0.413371 0.542086 - 0.166953 -0.416029 0.554821 - 0.180973 -0.422165 0.576537 - 0.195681 -0.427932 0.599321 - 0.211395 -0.404526 0.623772 - 0.529095 -0.817686 1.11485 - 0.528356 -0.794896 1.11379 - 0.528172 -0.780401 1.11356 - 0.52529 -0.735 1.10926 - 0.569854 -0.72247 1.1784 - 0.611346 -0.728542 1.24271 - 0.723316 -0.741688 1.41628 - 1.0297 -0.79124 1.89115 - 1.12666 -0.82018 2.04138 - 1.17816 -0.823171 2.12122 - 1.25138 -0.689453 2.23525 - 1.2509 -0.677998 2.23454 - 1.25547 -0.5476 2.24212 - 1.2553 -0.471559 2.24213 - 1.25168 -0.39538 2.2368 - 1.25098 -0.38454 2.23576 - 1.25433 -0.36428 2.24102 - 1.25518 -0.301022 2.24258 - 1.25513 -0.23792 2.24273 - 1.25232 -0.133146 2.23875 - 1.2538 -0.0605469 2.24132 - 1.25483 0.105674 2.24354 - 1.25425 0.126445 2.24271 - 1.25363 0.209856 2.24206 - 1.254 0.346828 2.24313 - 1.25314 0.529191 2.24248 - 0.913701 0.579373 1.71635 - 0.892959 0.583372 1.6842 - 0.819414 0.591596 1.5702 - 0.707627 0.612321 1.39695 - 0.706655 0.618716 1.39546 - 0.737177 0.867906 1.44371 - 0.751698 0.982998 1.46665 - 0.756353 1.00757 1.47396 - 0.776536 1.1643 1.50583 - 0.629234 1.22095 1.27764 - 0.613677 1.2241 1.25353 - 0.498506 1.08958 1.07446 - 0.113562 0.3261 0.474775 - 0.103925 0.342801 0.459895 - 0.104456 0.356964 0.460771 - 0.10353 0.465484 0.459734 - 0.104144 0.477385 0.46073 - 0.103011 0.478509 0.458979 - 0.101877 0.479625 0.457224 - 0.0968692 0.515554 0.449592 - 0.0769929 0.453314 0.418544 - 0.0514623 0.371526 0.378656 - 0.0426692 0.388824 0.365086 - 0.0438849 0.462018 0.367241 - 0.0440396 0.484953 0.367565 - 0.0438162 0.49134 0.367243 - 0.04249 0.515981 0.365277 - 0.0425745 0.534597 0.365477 - 0.0442218 0.73505 0.368771 - 0.0850681 1.25481 0.434022 - 0.0764065 1.29608 0.420744 - 0.0421426 1.29771 0.367623 - 0.0359997 1.29894 0.358103 - 0.0268228 1.3016 0.343884 --0.00404093 1.30454 0.29604 - -0.0257102 1.29782 0.262416 - -0.0415084 0.295812 0.234223 - -0.0492397 0.295961 0.222236 - -0.0627385 0.330295 0.201432 - -0.0659487 0.330365 0.196455 - -0.0708338 0.330761 0.188882 - -0.0858929 0.337608 0.165558 - -0.0904753 0.314217 0.158366 - -0.0907088 0.310921 0.157992 - -0.0914428 0.310477 0.156852 - -0.0929077 0.309569 0.154578 - -0.0941875 0.307694 0.152586 - -0.0949138 0.307221 0.151458 - -0.0991498 0.311826 0.144907 - -0.101803 0.304561 0.140766 - -0.188964 0.616748 0.00677288 - -0.248528 0.782782 -0.0849694 - -0.259804 0.798037 -0.102398 - -0.338479 1.04412 -0.223476 - -0.358197 1.05616 -0.254006 - -0.356652 0.857485 -0.252343 - -0.163702 0.266456 0.0446505 - -0.164329 0.265424 0.0436742 - -0.170333 0.27296 0.034392 - -0.172142 0.267129 0.0315665 - -0.225294 -0.367005 -0.0599927 - -0.19117 -0.362362 -0.00584635 - -0.189327 -0.361296 -0.00291833 - -0.185607 -0.365503 0.00296593 - -0.183575 -0.367159 0.00618297 - -0.178153 -0.363538 0.0147967 - -0.157412 -0.368219 0.0476802 - -0.153727 -0.367773 0.0535279 - -0.152868 -0.368742 0.0548861 - -0.142779 -0.377168 0.0708582 - -0.140031 -0.375377 0.0752243 - -0.134215 -0.374217 0.0844538 - -0.128252 -0.371858 0.0939216 - -0.1089 -0.371959 0.124618 - -0.0976792 -0.380183 0.142387 - -0.0829256 -0.376372 0.165804 - -0.0803453 -0.370322 0.16992 - -0.0688923 -0.372586 0.188078 - -0.0459916 -0.404459 0.224285 - -0.0436638 -0.383646 0.228056 - -0.0267144 -0.382693 0.254945 --0.00982473 -0.394213 0.281694 --0.00503966 -0.383943 0.289322 - 0.008031 -0.393871 0.310019 - 0.0293908 -0.399219 0.34388 - 0.0404334 -0.392367 0.361423 - 0.0422545 -0.39112 0.364316 - 0.0844979 -0.403036 0.43128 - 0.1064 -0.411075 0.465993 - 0.114438 -0.414315 0.478731 - 0.133166 -0.409934 0.508453 - 0.140012 -0.418983 0.519279 - 0.146527 -0.415601 0.529627 - 0.1885 -0.396876 0.596277 - 0.194909 -0.394231 0.606454 - 0.513582 -0.78699 1.11048 - 0.513512 -0.75199 1.1105 - 0.515521 -0.720809 1.1138 - 0.530538 -0.713319 1.13765 - 0.607004 -0.72852 1.25889 - 0.717059 -0.747782 1.43339 - 0.805189 -0.757831 1.57315 - 0.874348 -0.765984 1.68282 - 0.908483 -0.767104 1.73696 - 1.12066 -0.818609 2.07334 - 1.22333 -0.685545 2.2367 - 1.22545 -0.468255 2.24088 - 1.22599 -0.45775 2.24177 - 1.22473 -0.414692 2.23994 - 1.22523 -0.298888 2.24117 - 1.22294 0.115087 2.23909 - 1.22212 0.125331 2.23781 - 1.22469 0.239764 2.24233 - 1.22522 0.292132 2.24336 - 1.22569 0.440359 2.24466 - 1.2276 0.483992 2.24785 - 0.953862 0.578122 1.81399 - 0.938271 0.57778 1.78926 - 0.848001 0.588704 1.64611 - 0.787209 0.59422 1.5497 - 0.720092 0.732255 1.44375 - 0.732966 0.843358 1.46459 - 0.752896 1.00091 1.49679 - 0.779006 1.17663 1.53887 - 0.612418 1.22064 1.27478 - 0.587735 1.2267 1.23565 - 0.10863 0.32968 0.472307 - 0.107859 0.330861 0.47109 - 0.10631 0.333204 0.468641 - 0.105532 0.334366 0.46741 - 0.0990319 0.346148 0.457144 - 0.0986115 0.41738 0.456745 - 0.0413259 0.384445 0.365752 - 0.0425311 0.449314 0.367907 - 0.0413832 0.485594 0.366222 - 0.0407764 0.541989 0.365471 - 0.041895 0.580675 0.36739 - 0.0442431 0.785411 0.371883 - 0.0474799 0.837161 0.377211 - 0.0526193 1.29396 0.387077 - -0.0109744 1.30103 0.286227 - -0.0599407 0.326953 0.204902 - -0.0616178 0.328529 0.202247 - -0.0851839 0.336643 0.164896 - -0.0845477 0.316188 0.165828 - -0.0862816 0.312099 0.163062 - -0.0941975 0.31147 0.150503 - -0.0987466 0.313699 0.143296 - -0.0990933 0.311314 0.142737 - -0.0998162 0.310795 0.141588 - -0.102377 0.31106 0.137528 - -0.351184 1.04918 -0.254376 - -0.351738 0.89016 -0.25585 - -0.303417 0.650979 -0.180099 - -0.160641 0.268506 0.0449462 - -0.172532 0.267088 0.0260789 - -0.210517 -0.363733 -0.0447802 - -0.118023 -0.379139 0.106223 - -0.113784 -0.378134 0.11315 - -0.107824 -0.372896 0.122903 - -0.104065 -0.378675 0.129021 - -0.0914331 -0.383135 0.149635 - -0.0888071 -0.384512 0.153918 - -0.0864895 -0.374318 0.157742 - -0.0713847 -0.366504 0.182442 - -0.0631435 -0.371158 0.195884 - -0.0623677 -0.372378 0.197146 - -0.0557198 -0.376952 0.207986 - -0.0500269 -0.386953 0.217245 - -0.0220141 -0.380165 0.263022 - -0.0189008 -0.391765 0.268062 --0.00924372 -0.387837 0.283849 --0.00807977 -0.391582 0.285736 --0.00532978 -0.39186 0.290226 - 0.0125773 -0.394553 0.319462 - 0.021936 -0.393081 0.334752 - 0.0951733 -0.406527 0.454313 - 0.109283 -0.409343 0.477346 - 0.133501 -0.412682 0.516887 - 0.136351 -0.412195 0.521542 - 0.165434 -0.418494 0.569017 - 0.18266 -0.398699 0.597227 - 0.49754 -0.80915 1.10992 - 0.497315 -0.801605 1.10958 - 0.60879 -0.731787 1.29191 - 0.651394 -0.734419 1.36148 - 0.663578 -0.739816 1.38136 - 0.696972 -0.743563 1.43589 - 0.896061 -0.764112 1.76096 - 1.14404 -0.819549 2.16575 - 1.19185 -0.660607 2.24444 - 1.18734 -0.348163 2.23827 - 1.18562 -0.244047 2.23586 - 1.18765 -0.018744 2.24004 - 1.18766 -0.00852092 2.2401 - 1.1894 0.155533 2.24357 - 1.18861 0.176007 2.24236 - 1.18571 0.216729 2.23778 - 1.19185 0.46973 2.24877 - 1.03412 0.589699 1.99163 - 0.91037 0.582083 1.78949 - 0.875115 0.585743 1.73192 - 0.836041 0.585096 1.6681 - 0.716664 0.697463 1.47357 - 0.72302 0.711218 1.484 - 0.723926 0.727914 1.48554 - 0.748186 0.93249 1.52595 - 0.746484 0.939576 1.5232 - 0.760706 1.05236 1.54686 - 0.772558 1.1188 1.56647 - 0.778045 1.16846 1.57562 - 0.775779 1.17587 1.57195 - 0.675343 1.22089 1.40808 - 0.667131 1.21746 1.39466 - 0.597973 1.23021 1.28176 - 0.590417 1.22624 1.2694 - 0.500178 1.12583 1.12164 - 0.4976 1.13032 1.11745 - 0.103008 0.324276 0.469907 - 0.0946627 0.330523 0.456302 - 0.0953621 0.371322 0.4576 - 0.089188 0.512096 0.448056 - 0.0457175 0.380752 0.376556 - 0.0382557 0.373535 0.364342 - 0.0403564 0.416754 0.367938 - 0.0393566 0.565503 0.366875 - 0.0402519 0.642216 0.368631 - 0.0390704 0.687742 0.366876 - 0.075584 1.20659 0.428498 - 0.0654652 1.29391 0.412306 - 0.0206453 1.29513 0.33911 - 0.0118221 1.29749 0.324709 - 0.00309633 1.30362 0.310482 - -0.0382896 0.371983 0.239321 - -0.047178 0.294266 0.224507 - -0.0489917 0.305039 0.221586 - -0.0523059 0.289383 0.216114 - -0.0590635 0.328136 0.205225 - -0.0615344 0.330508 0.201199 - -0.0781561 0.35204 0.174135 - -0.0826739 0.318897 0.166629 - -0.0833994 0.318507 0.165443 - -0.0909815 0.311922 0.153034 - -0.0918608 0.312409 0.1516 - -0.245115 0.780231 -0.0969051 - -0.290581 0.88251 -0.170768 - -0.340369 0.945155 -0.251842 - -0.340502 0.867631 -0.252356 - -0.342957 0.8584 -0.256402 - -0.341038 0.845129 -0.253319 - -0.312376 0.644685 -0.207275 - -0.274699 0.547083 -0.146114 - -0.170951 0.266687 0.0222543 - -0.216851 -0.3664 -0.061975 - -0.20981 -0.361518 -0.0501915 - -0.160268 -0.36792 0.0325634 - -0.1394 -0.373644 0.0674087 - -0.129131 -0.374929 0.0845624 - -0.112134 -0.375347 0.11296 - -0.108083 -0.379454 0.119713 - -0.106352 -0.375376 0.122621 - -0.101464 -0.374518 0.130792 - -0.0989382 -0.37617 0.135006 - -0.075411 -0.376009 0.174318 - -0.0607879 -0.377776 0.198744 - -0.0514879 -0.38071 0.214272 - -0.0489267 -0.381088 0.21855 - -0.0446759 -0.382571 0.225647 - -0.0412317 -0.381829 0.231405 - -0.0284548 -0.378759 0.252766 - -0.0215203 -0.382047 0.264339 - -0.0156725 -0.395144 0.27406 - -0.0127374 -0.38448 0.279005 - 0.0105138 -0.385785 0.31785 - 0.0145559 -0.403462 0.324535 - 0.0163606 -0.402599 0.327554 - 0.0167478 -0.39828 0.328218 - 0.0277088 -0.400602 0.346524 - 0.0332316 -0.398198 0.355761 - 0.0351807 -0.397963 0.359018 - 0.0471268 -0.396717 0.378984 - 0.054491 -0.401545 0.39127 - 0.0679155 -0.402574 0.413697 - 0.1061 -0.407686 0.477478 - 0.126159 -0.416659 0.51096 - 0.147058 -0.422598 0.545856 - 0.148334 -0.421807 0.547991 - 0.15642 -0.42139 0.561505 - 0.1754 -0.416953 0.593235 - 0.488649 -0.831266 1.11503 - 0.486503 -0.743129 1.11178 - 0.562854 -0.719014 1.23945 - 0.679816 -0.74636 1.43477 - 0.769901 -0.754361 1.58527 - 1.1056 -0.817298 2.14594 - 1.12625 -0.820915 2.18043 - 1.16207 -0.212602 2.24264 - 1.15908 -0.140613 2.23793 - 1.15896 -0.018616 2.23821 - 1.15762 0.154078 2.23665 - 1.15706 0.205022 2.2359 - 1.15961 0.236232 2.24029 - 1.15828 0.308035 2.23835 - 1.1622 0.413415 2.2453 - 1.16166 0.476589 2.24464 - 0.896909 0.583611 1.80269 - 0.842078 0.590847 1.7111 - 0.716114 0.608766 1.5007 - 0.718671 0.695522 1.50531 - 0.723812 0.716172 1.51398 - 0.730621 0.763335 1.52554 - 0.738099 0.855943 1.5384 - 0.742424 0.88724 1.54575 - 0.755295 0.99489 1.56767 - 0.760036 1.02994 1.57573 - 0.721005 1.20954 1.51121 - 0.621495 1.2207 1.34499 - 0.455099 1.08668 1.06644 - 0.0929047 0.344535 0.45836 - 0.0942307 0.351298 0.460602 - 0.0939151 0.360323 0.46011 - 0.0932633 0.375737 0.459081 - 0.0930977 0.41738 0.458967 - 0.092422 0.419337 0.457845 - 0.0941306 0.496256 0.461 - 0.0628254 0.431404 0.40844 - 0.0417519 0.383709 0.373042 - 0.0372529 0.480805 0.365903 - 0.0369748 0.569042 0.365782 - 0.0459728 0.881113 0.382032 - 0.0686728 1.28423 0.421531 - 0.0629866 1.28699 0.412041 - 0.0138622 1.30205 0.330018 - 0.00799006 1.30188 0.320206 - 0.002182 1.30362 0.310508 --0.00654091 1.30654 0.295945 - -0.0385157 0.376982 0.238898 - -0.0391577 0.353966 0.237736 - -0.0492423 0.294965 0.220656 - -0.0807815 0.325831 0.168078 - -0.0800452 0.309635 0.169245 - -0.0864047 0.307026 0.158609 - -0.0918332 0.316196 0.149574 - -0.0960331 0.309017 0.142528 - -0.229976 0.776128 -0.0794566 - -0.246101 0.779386 -0.106386 - -0.327157 0.994405 -0.240984 - -0.336063 0.937515 -0.256086 - -0.335504 0.883531 -0.255363 - -0.331439 0.839398 -0.248743 - -0.334003 0.831086 -0.25306 - -0.334081 0.823646 -0.253218 - -0.334666 0.788281 -0.254333 - -0.319121 0.689078 -0.228747 - -0.312771 0.661737 -0.218243 - -0.162286 0.269261 0.0316731 - -0.169061 0.269254 0.0203528 - -0.208452 -0.359987 -0.0568836 - -0.208004 -0.362211 -0.0561194 - -0.193835 -0.372686 -0.0317513 - -0.184675 -0.367028 -0.0159489 - -0.174917 -0.371983 0.0008418 - -0.170621 -0.367127 0.00826126 - -0.170694 -0.370725 0.00812173 - -0.164634 -0.374339 0.0185481 - -0.16381 -0.375457 0.0199618 - -0.149938 -0.368367 0.0438888 - -0.145868 -0.373244 0.0508806 - -0.139844 -0.378896 0.0612368 - -0.133365 -0.366564 0.0724469 - -0.122953 -0.373524 0.0903572 - -0.12131 -0.375027 0.0931805 - -0.0983247 -0.368446 0.132805 - -0.0801772 -0.377735 0.164032 - -0.0700375 -0.370736 0.181528 - -0.067265 -0.367657 0.186316 - -0.0622209 -0.37832 0.194964 - -0.0491993 -0.390066 0.21735 - -0.0388307 -0.375947 0.235269 - -0.0214712 -0.376939 0.265171 - -0.0146509 -0.379698 0.276909 --0.00995855 -0.386626 0.284966 --0.00080733 -0.391902 0.30071 - 0.0283289 -0.397056 0.350884 - 0.0650937 -0.401679 0.414202 - 0.080358 -0.403544 0.440491 - 0.0850473 -0.407375 0.448554 - 0.115632 -0.410261 0.501233 - 0.139445 -0.414942 0.542237 - 0.156855 -0.417757 0.57222 - 0.160161 -0.421217 0.577902 - 0.177085 -0.394569 0.607163 - 0.177944 -0.392716 0.608651 - 0.214421 -0.443781 0.671288 - 0.577407 -0.724637 1.2955 - 0.594016 -0.729561 1.3241 - 0.655535 -0.737851 1.43005 - 1.12489 -0.585149 2.23924 - 1.1262 -0.521812 2.24174 - 1.12388 -0.510201 2.23779 - 1.12319 -0.45737 2.23682 - 1.12177 -0.394433 2.23462 - 1.12526 -0.282275 2.24107 - 1.12149 -0.23046 2.23479 - 1.12335 -0.200349 2.23812 - 1.12251 -0.119271 2.23698 - 1.12274 -0.1092 2.23742 - 1.1233 -0.0789745 2.23852 - 1.12434 0.00167979 2.24063 - 1.12468 0.0319565 2.24134 - 1.12476 0.0925669 2.24172 - 1.12673 0.44188 2.24649 - 1.12792 0.526945 2.24889 - 1.06983 0.582348 2.14903 - 1.01044 0.59027 2.04675 - 0.999482 0.593844 2.02789 - 0.791179 0.593904 1.66903 - 0.763224 0.597561 1.62089 - 0.754865 0.599189 1.60649 - 0.708202 0.631718 1.52623 - 0.719447 0.672617 1.54577 - 0.742739 0.935922 1.58694 - 0.769233 1.08656 1.63319 - 0.776737 1.18145 1.64649 - 0.679919 1.20241 1.47978 - 0.665079 1.21997 1.45429 - 0.643538 1.21422 1.41715 - 0.636321 1.22266 1.40476 - 0.626879 1.22687 1.38851 - 0.588078 1.2282 1.32167 - 0.556389 1.22877 1.26708 - 0.485629 1.14059 1.14482 - 0.0954872 0.332017 0.469485 - 0.0969208 0.338665 0.471981 - 0.0883863 0.337801 0.457275 - 0.0904764 0.363068 0.460977 - 0.0907674 0.455627 0.461847 - 0.086004 0.515554 0.453879 - 0.0848717 0.51662 0.451933 - 0.0694928 0.472446 0.425263 - 0.0549028 0.412141 0.399888 - 0.0386775 0.383441 0.371821 - 0.0378357 0.384095 0.370374 - 0.0354731 0.397594 0.366357 - 0.0367072 0.415811 0.368556 - 0.0370305 0.455663 0.369272 - 0.0355415 0.49837 0.366876 - 0.0730905 1.30011 0.434758 - 0.0497728 1.30014 0.394588 - 0.0440711 1.30163 0.384771 - 0.0121662 1.29606 0.329785 --0.00196395 1.30096 0.305461 - -0.0162532 1.30024 0.280842 - -0.030638 1.2699 0.255939 - -0.0386613 0.360983 0.238496 - -0.0409095 0.30089 0.234384 - -0.0427772 0.295763 0.231146 - -0.0478758 0.293175 0.222352 - -0.0498008 0.292862 0.219034 - -0.0701215 0.331457 0.184181 - -0.0723013 0.337719 0.18045 - -0.080285 0.339167 0.166702 - -0.209608 0.776849 -0.0543449 - -0.226759 0.77089 -0.083917 - -0.238387 0.774931 -0.103931 - -0.244878 0.774927 -0.115114 - -0.328107 0.855974 -0.258174 - -0.323124 0.707721 -0.25018 - -0.164005 0.273718 0.0222127 - -0.209371 -0.36496 -0.0658659 - -0.207114 -0.366566 -0.0618877 - -0.201469 -0.370353 -0.051939 - -0.196925 -0.366551 -0.0439019 - -0.158664 -0.36636 0.0236392 - -0.144577 -0.374968 0.0484714 - -0.141245 -0.370814 0.0543714 - -0.119362 -0.372297 0.0929946 - -0.115333 -0.375902 0.100093 - -0.105315 -0.377581 0.117769 - -0.0771411 -0.378863 0.167499 - -0.0727723 -0.377656 0.175216 - -0.0695158 -0.378905 0.180959 - -0.0509491 -0.370744 0.213768 - -0.0485103 -0.396168 0.21797 - -0.0398756 -0.384914 0.233258 - -0.0324027 -0.386935 0.246442 - -0.0213273 -0.392894 0.265968 - -0.0201533 -0.380664 0.268091 --0.00244536 -0.38304 0.29934 - 0.00319833 -0.379811 0.309316 - 0.0146366 -0.394929 0.329446 - 0.018867 -0.3926 0.336923 - 0.0229527 -0.39539 0.344125 - 0.031687 -0.397018 0.359536 - 0.0428864 -0.404615 0.379276 - 0.052047 -0.404437 0.395447 - 0.0529145 -0.403656 0.396982 - 0.0584996 -0.405056 0.406835 - 0.0615239 -0.399861 0.412195 - 0.0678577 -0.403436 0.423361 - 0.0687227 -0.402515 0.424892 - 0.0698836 -0.394432 0.426974 - 0.074944 -0.404785 0.435865 - 0.0897606 -0.403226 0.462027 - 0.101028 -0.411 0.481884 - 0.116189 -0.408677 0.508658 - 0.136295 -0.411891 0.544137 - 0.147034 -0.411432 0.563097 - 0.452528 -0.851131 1.10059 - 0.460762 -0.828078 1.11522 - 0.457484 -0.731905 1.10982 - 0.515474 -0.717601 1.21225 - 0.605322 -0.726611 1.37082 - 0.620964 -0.729172 1.39842 - 0.82749 -0.75954 1.76287 - 0.843167 -0.764112 1.79053 - 1.09751 -0.711808 2.23972 - 1.09104 -0.685975 2.22841 - 1.09579 -0.656278 2.23692 - 1.09548 -0.559746 2.23676 - 1.09638 -0.413651 2.23894 - 1.09355 -0.38174 2.23407 - 1.09569 -0.270078 2.23831 - 1.09384 -0.249381 2.23512 - 1.09434 -0.239376 2.23605 - 1.09549 -0.148824 2.23844 - 1.09653 0.0217325 2.24097 - 1.09723 0.0518673 2.24232 - 1.09778 0.233507 2.24404 - 1.09809 0.439072 2.24541 - 0.884044 0.591042 1.86819 - 0.85978 0.584222 1.82533 - 0.849138 0.585966 1.80655 - 0.81366 0.596067 1.74396 - 0.76858 0.596644 1.66438 - 0.717954 0.605107 1.57505 - 0.716552 0.690708 1.57292 - 0.721763 0.736431 1.58231 - 0.728169 0.801949 1.59388 - 0.743774 0.936037 1.62197 - 0.772277 1.12174 1.67304 - 0.759076 1.21039 1.6501 - 0.64798 1.21275 1.45399 - 0.640877 1.22155 1.44149 - 0.609503 1.21736 1.38609 - 0.600647 1.22194 1.37047 - 0.545683 1.22949 1.27348 - 0.534275 1.22673 1.25333 - 0.526285 1.24184 1.23928 - 0.0997095 0.328391 0.482558 - 0.0857325 0.334303 0.457909 - 0.0855934 0.336996 0.457674 - 0.0911323 0.362151 0.467554 - 0.08625 0.358151 0.458919 - 0.0863997 0.386809 0.4593 - 0.0883778 0.420801 0.462929 - 0.0874697 0.42191 0.461331 - 0.0856463 0.424102 0.458121 - 0.0845901 0.520068 0.456646 - 0.0461681 0.389873 0.388292 - 0.0411891 0.380062 0.379463 - 0.0390921 0.383966 0.375777 - 0.0361223 0.388477 0.370553 - 0.0329655 0.54455 0.365614 - 0.0336742 0.616253 0.367156 - 0.0367942 0.801788 0.373416 - 0.0391926 0.848661 0.37784 - 0.0591097 1.29687 0.414818 - 0.0563182 1.29773 0.409894 --0.00839648 1.30454 0.295682 - -0.0197023 1.29942 0.275704 - -0.0365224 0.403997 0.242378 - -0.051244 0.296607 0.215955 - -0.0571788 0.318403 0.205567 - -0.0659961 0.330852 0.190053 - -0.0854386 0.315085 0.155667 - -0.089666 0.309107 0.148181 - -0.0913163 0.305802 0.145254 - -0.228061 0.780895 -0.0942098 - -0.255405 0.778646 -0.142488 - -0.284161 0.854833 -0.192941 - -0.32108 0.917169 -0.25786 - -0.319014 0.851841 -0.254478 - -0.279754 0.535643 -0.186457 - -0.194243 0.34131 -0.0362953 - -0.164085 -0.371428 0.00844687 - -0.146094 -0.379033 0.0409607 - -0.104637 -0.3698 0.115996 - -0.102903 -0.370085 0.119131 - -0.100551 -0.371861 0.123379 - -0.086135 -0.373963 0.149449 - -0.0725781 -0.380599 0.173946 - -0.0588118 -0.371043 0.198889 - -0.05618 -0.381747 0.203606 - -0.0383865 -0.38497 0.235781 - -0.0351567 -0.379994 0.241645 - -0.0326767 -0.386935 0.246102 - -0.0278479 -0.383622 0.254851 - -0.0270383 -0.383544 0.256316 - -0.0109261 -0.392574 0.285426 --0.00066557 -0.393248 0.303985 - 0.00016364 -0.392925 0.305486 - 0.00501736 -0.398044 0.314246 - 0.0168178 -0.393081 0.335613 - 0.0192999 -0.391617 0.34011 - 0.0317376 -0.394864 0.362596 - 0.037585 -0.395727 0.373171 - 0.0616363 -0.399907 0.416663 - 0.0696587 -0.405931 0.43115 - 0.0865532 -0.408835 0.461701 - 0.103406 -0.411004 0.49218 - 0.103709 -0.40811 0.492738 - 0.117848 -0.413899 0.518293 - 0.121382 -0.415833 0.524677 - 0.131166 -0.414923 0.542381 - 0.135902 -0.411856 0.550962 - 0.138043 -0.413319 0.554829 - 0.141155 -0.417004 0.560444 - 0.158246 -0.387327 0.591483 - 0.159058 -0.385571 0.59296 - 0.449383 -0.802956 1.11644 - 0.445381 -0.761446 1.10937 - 0.473012 -0.71456 1.15955 - 0.527537 -0.719014 1.25817 - 0.565724 -0.723523 1.32723 - 0.571017 -0.722588 1.33681 - 0.672429 -0.736197 1.52021 - 0.834128 -0.7614 1.81262 - 0.914961 -0.791988 1.95872 - 0.963661 -0.801298 2.04678 - 0.979804 -0.803727 2.07598 - 1.04511 -0.811016 2.19408 - 1.06905 -0.696231 2.23787 - 1.06881 -0.45251 2.23845 - 1.065 -0.308098 2.23215 - 1.06921 -0.278883 2.23988 - 1.06948 -0.0881652 2.24117 - 1.07248 -0.0383525 2.2468 - 1.0716 -0.018328 2.24529 - 1.0705 0.161754 2.24403 - 1.0661 0.312083 2.2367 - 1.06541 0.322032 2.23549 - 1.0693 0.436076 2.243 - 1.06738 0.456024 2.23961 - 0.958713 0.602009 2.04363 - 0.838514 0.589992 1.82614 - 0.823942 0.588788 1.79977 - 0.799545 0.597372 1.75568 - 0.738229 0.60107 1.64477 - 0.741812 0.904631 1.65251 - 0.746603 0.919547 1.66124 - 0.658177 1.22157 1.50252 - 0.545589 1.23123 1.29889 - 0.430778 1.10816 1.09068 - 0.0828714 0.379854 0.458301 - 0.081708 0.402624 0.45629 - 0.0845447 0.424729 0.461513 - 0.0835697 0.443192 0.459826 - 0.0385976 0.375449 0.37819 - 0.0363892 0.378401 0.374208 - 0.0503698 1.02058 0.402154 - 0.0427466 1.29098 0.389481 - 0.0265564 1.29894 0.360225 - -0.0146951 1.30503 0.285626 - -0.0411724 0.298891 0.233569 - -0.0544394 0.308975 0.20961 - -0.0641192 0.329379 0.192183 - -0.0649818 0.331105 0.19063 - -0.0732978 0.348166 0.175657 - -0.0788888 0.34962 0.165549 - -0.0783663 0.315796 0.166354 - -0.0940035 0.312763 0.138054 - -0.0954953 0.312662 0.135354 - -0.127678 0.448869 0.0776979 - -0.21588 0.786407 -0.080466 - -0.217717 0.776855 -0.0838276 - -0.232887 0.780263 -0.111258 - -0.259213 0.782302 -0.158872 - -0.308994 0.920332 -0.248357 - -0.309173 0.777079 -0.249273 - -0.309609 0.711088 -0.250335 - -0.285519 0.54372 -0.207447 - -0.202101 0.355155 -0.057322 - -0.199712 -0.36662 -0.0635772 - -0.1405 -0.369704 0.0462744 - -0.138963 -0.371606 0.04912 - -0.13695 -0.371743 0.0528543 - -0.130282 -0.377148 0.0652022 - -0.119968 -0.374572 0.0843514 - -0.118992 -0.374431 0.0861632 - -0.104968 -0.372908 0.11219 - -0.0787947 -0.381629 0.160717 - -0.0667146 -0.374557 0.183161 - -0.0554569 -0.370812 0.204065 - -0.0539658 -0.372145 0.206826 - -0.0533251 -0.37529 0.208002 - -0.0416533 -0.377831 0.229648 - -0.0345989 -0.379982 0.242728 - -0.0297688 -0.385754 0.251666 - -0.0272499 -0.390535 0.256319 - -0.0241177 -0.38715 0.262145 - -0.0205838 -0.394615 0.268671 - -0.0197673 -0.394467 0.270187 - -0.0190876 -0.391324 0.271461 - -0.0175184 -0.389998 0.274378 - 6.473e-05 -0.392595 0.306992 - 0.0162658 -0.391638 0.337057 - 0.0328166 -0.404599 0.367711 - 0.0347911 -0.394518 0.371418 - 0.0447678 -0.396793 0.389919 - 0.0532694 -0.408527 0.405644 - 0.0570485 -0.406972 0.412663 - 0.0593496 -0.403468 0.416948 - 0.0706061 -0.405659 0.437824 - 0.103577 -0.412542 0.498971 - 0.110372 -0.413222 0.511576 - 0.128883 -0.414176 0.545918 - 0.132134 -0.414923 0.551949 - 0.133611 -0.414885 0.55469 - 0.142955 -0.418859 0.57201 - 0.155865 -0.393957 0.596068 - 0.280714 -0.594812 0.826876 - 0.436651 -0.722251 1.11567 - 0.574446 -0.726374 1.37133 - 0.679012 -0.741507 1.56529 - 0.781449 -0.756314 1.75529 - 0.983694 -0.801463 2.13036 - 1.03759 -0.799158 2.23037 - 1.0432 -0.586489 2.24169 - 1.04371 -0.565652 2.24272 - 1.04067 -0.480705 2.23743 - 1.03745 -0.448428 2.2316 - 1.04184 -0.127437 2.24109 - 1.04038 0.0214678 2.239 - 1.03974 0.0412659 2.2379 - 1.04044 0.061124 2.23928 - 1.04318 0.160908 2.24479 - 1.04165 0.22066 2.2422 - 1.0409 0.270694 2.24103 - 1.0383 0.290138 2.23628 - 1.04292 0.342059 2.24508 - 1.04065 0.371841 2.24099 - 1.04196 0.579867 2.24429 - 1.00434 0.590409 2.17454 - 0.977165 0.59509 2.12413 - 0.709936 0.630351 1.62845 - 0.712533 0.648638 1.63334 - 0.711105 0.663582 1.63076 - 0.717441 0.685642 1.64261 - 0.741442 0.903528 1.68806 - 0.771395 1.2092 1.74492 - 0.719161 1.21719 1.64804 - 0.704349 1.21516 1.62055 - 0.578312 1.22605 1.38673 - 0.567732 1.22629 1.36711 - 0.0807158 0.360062 0.45981 - 0.0794099 0.419792 0.457639 - 0.0816213 0.4321 0.461794 - 0.0805475 0.446026 0.459861 - 0.0791182 0.469222 0.457306 - 0.0787508 0.483103 0.456683 - 0.0793775 0.519165 0.457998 - 0.0393375 0.383047 0.383131 - 0.0303404 0.384139 0.366442 - 0.0298661 0.433166 0.365769 - 0.0290244 0.509862 0.36453 - 0.0291759 0.603597 0.365206 - 0.0290888 0.669155 0.365321 - 0.0298144 0.741232 0.366971 - 0.0332853 1.30004 0.375767 - 0.0249174 1.29596 0.360224 - 0.00077951 1.30226 0.315463 - -0.0021322 1.29464 0.310028 - -0.0208232 1.30342 0.275385 - -0.0401395 0.304949 0.235335 - -0.0407209 0.300923 0.234239 - -0.0761452 0.365075 0.168781 - -0.0773719 0.329477 0.166355 - -0.0807758 0.311949 0.159965 - -0.0866614 0.313325 0.14905 - -0.0915008 0.311895 0.140065 - -0.226933 0.770488 -0.109291 - -0.229185 0.771406 -0.113467 - -0.240789 0.776469 -0.134975 - -0.25097 0.782788 -0.153839 - -0.262048 0.791169 -0.17436 - -0.306447 0.893523 -0.256309 - -0.30252 0.711956 -0.249787 - -0.204893 -0.362301 -0.0810045 - -0.19988 -0.367215 -0.0714909 - -0.195839 -0.364434 -0.0637921 - -0.190404 -0.37103 -0.053484 - -0.171431 -0.374997 -0.0174147 - -0.165978 -0.366362 -0.00700699 - -0.164889 -0.376809 -0.00497986 - -0.157474 -0.364912 0.00917362 - -0.146666 -0.368546 0.0297145 - -0.138364 -0.375927 0.0454719 - -0.125121 -0.37436 0.0706678 - -0.104523 -0.376637 0.109834 - -0.0910259 -0.378272 0.135497 - -0.0629879 -0.38279 0.188805 - -0.0589802 -0.381956 0.196431 - -0.0574275 -0.382363 0.199383 - -0.0558246 -0.381747 0.202434 - -0.0458094 -0.426522 0.22129 - -0.0363799 -0.376999 0.239437 - -0.0269607 -0.385455 0.257316 - -0.022941 -0.387909 0.264951 - -0.0221537 -0.387778 0.266449 - -0.0163876 -0.391626 0.277399 --0.00468305 -0.385994 0.299685 --0.00305125 -0.395532 0.302747 - 0.0165088 -0.395956 0.339948 - 0.0203714 -0.392424 0.34731 - 0.0239206 -0.398398 0.354034 - 0.025319 -0.401626 0.35668 - 0.0285673 -0.399247 0.362869 - 0.0324478 -0.400499 0.370244 - 0.0371815 -0.400894 0.379245 - 0.038168 -0.401129 0.381121 - 0.0419552 -0.401034 0.388324 - 0.0562987 -0.403447 0.415594 - 0.0618278 -0.400745 0.426122 - 0.105972 -0.409218 0.510047 - 0.120337 -0.411731 0.537357 - 0.126065 -0.411891 0.548251 - 0.152298 -0.42301 0.598097 - 0.421294 -0.808377 1.10806 - 0.423376 -0.749241 1.11227 - 0.703515 -0.747899 1.64509 - 0.767784 -0.758324 1.76728 - 0.915667 -0.79334 2.0484 - 1.00949 -0.771591 2.22695 - 1.01512 -0.509493 2.23878 - 1.01123 -0.435889 2.2317 - 1.01561 -0.0674651 2.24161 - 1.01628 -0.0477443 2.24296 - 1.01498 0.110265 2.24117 - 1.01538 0.350006 2.24297 - 1.0134 0.410199 2.23946 - 0.920791 0.602289 2.06414 - 0.720575 0.685275 1.6837 - 0.723285 0.704622 1.68894 - 0.735719 0.831135 1.71313 - 0.752678 0.993669 1.74608 - 0.762033 1.03596 1.76406 - 0.751716 1.21432 1.7452 - 0.710276 1.21563 1.66639 - 0.690669 1.21639 1.6291 - 0.686719 1.22076 1.62161 - 0.677302 1.21578 1.60368 - 0.585818 1.22199 1.4297 - 0.47156 1.22104 1.21238 - 0.0822349 0.336569 0.468104 - 0.0771388 0.337273 0.458415 - 0.077217 0.346992 0.458605 - 0.0778437 0.352152 0.459819 - 0.0774687 0.393443 0.459284 - 0.0770172 0.507997 0.458917 - 0.0362763 0.385373 0.380903 - 0.0286903 0.388514 0.366488 - 0.027646 0.422106 0.364646 - 0.0280804 0.562256 0.366075 - 0.0316271 0.797858 0.373833 - 0.0326527 0.829977 0.375921 --0.00563738 1.29696 0.305102 - -0.024209 1.28658 0.269735 - -0.0599053 0.336656 0.19776 - -0.0657807 0.331577 0.186564 - -0.0776129 0.376419 0.164252 - -0.07903 0.374686 0.161549 - -0.0800231 0.31099 0.159387 - -0.0820998 0.315929 0.155458 - -0.0831544 0.318378 0.153463 - -0.0833796 0.315085 0.15302 - -0.0845637 0.30902 0.150742 - -0.090017 0.320908 0.140421 - -0.0903526 0.31853 0.139773 - -0.0911589 0.314713 0.138223 - -0.226972 0.856224 -0.11776 - -0.219007 0.802239 -0.102844 - -0.221679 0.779283 -0.108024 - -0.232868 0.77576 -0.12932 - -0.25052 0.779711 -0.162876 - -0.298826 0.804806 -0.254646 - -0.296079 0.774635 -0.249549 - -0.297013 0.673223 -0.251762 - -0.296199 0.636571 -0.250372 - -0.297526 0.628717 -0.25293 - -0.197427 -0.368661 -0.0748111 - -0.194585 -0.371779 -0.0692795 - -0.190642 -0.368883 -0.0615715 - -0.189599 -0.369612 -0.059539 - -0.180217 -0.37559 -0.0412561 - -0.178306 -0.373882 -0.037519 - -0.161974 -0.375196 -0.00565109 - -0.153309 -0.369105 0.011287 - -0.1247 -0.375305 0.0670915 - -0.120181 -0.380227 0.0758892 - -0.117673 -0.372896 0.080817 - -0.11561 -0.371711 0.0848467 - -0.113566 -0.374856 0.0888223 - -0.111887 -0.375397 0.0920966 - -0.102605 -0.377271 0.110203 - -0.0977405 -0.368456 0.119736 - -0.0911542 -0.379665 0.13254 - -0.0743916 -0.373981 0.165279 - -0.0700806 -0.377979 0.173675 - -0.0560001 -0.373613 0.201173 - -0.0552562 -0.373794 0.202624 - -0.0514188 -0.371603 0.210123 - -0.0447225 -0.412619 0.223011 - -0.0197877 -0.382205 0.271807 --0.00705825 -0.386576 0.29663 - 0.00510521 -0.395527 0.320329 - 0.00602512 -0.388879 0.322154 - 0.0208692 -0.393247 0.351104 - 0.021793 -0.393644 0.352905 - 0.0288036 -0.393626 0.366587 - 0.0394669 -0.397347 0.387381 - 0.0450816 -0.401829 0.398319 - 0.0462575 -0.402866 0.400609 - 0.0488561 -0.396919 0.405707 - 0.0689247 -0.404412 0.444839 - 0.0722573 -0.404791 0.451342 - 0.0956087 -0.409743 0.496892 - 0.132924 -0.405232 0.569735 - 0.408725 -0.846262 1.10605 - 0.409106 -0.761478 1.10717 - 0.418444 -0.703392 1.12564 - 0.449186 -0.71667 1.18558 - 0.45837 -0.709799 1.20354 - 0.552607 -0.721732 1.3874 - 0.590677 -0.729498 1.46166 - 0.628344 -0.733051 1.53515 - 0.683507 -0.742788 1.64277 - 0.775211 -0.753599 1.82169 - 0.970912 -0.8018 2.2034 - 0.985655 -0.791496 2.23222 - 0.988703 -0.621566 2.23891 - 0.988148 -0.384483 2.23887 - 0.985681 -0.135546 2.23515 - 0.987693 0.0899679 2.24006 - 0.988287 0.139238 2.24144 - 0.988316 0.178717 2.24167 - 0.98666 0.227856 2.23865 - 0.987038 0.24778 2.23948 - 0.99085 0.308694 2.24718 - 0.988956 0.36845 2.24375 - 0.988991 0.419137 2.24404 - 0.989486 0.439734 2.24509 - 0.713517 0.651004 1.70744 - 0.716006 0.661534 1.71235 - 0.728682 0.768404 1.73755 - 0.777845 1.16574 1.83524 - 0.776645 1.17519 1.83294 - 0.771026 1.20076 1.82209 - 0.72969 1.20502 1.74144 - 0.701433 1.21518 1.68634 - 0.623775 1.22235 1.53481 - 0.617859 1.22222 1.52327 - 0.58223 1.22951 1.45376 - 0.0811204 0.337814 0.471896 - 0.0755627 0.384291 0.461253 - 0.0734364 0.411833 0.457224 - 0.0749103 0.421516 0.460143 - 0.0746517 0.44711 0.459751 - 0.0717521 0.530682 0.454458 - 0.0265251 0.390075 0.365577 - 0.0266919 0.4259 0.36606 - 0.0271523 0.5784 0.367627 - 0.0584912 1.29219 0.431918 - 0.0430845 1.29837 0.401878 - 0.0223606 1.30391 0.361458 - 0.00132629 1.29989 0.32039 - -0.0274173 1.27071 0.264166 - -0.0398106 0.300971 0.235727 - -0.0427139 0.295812 0.230038 - -0.0463326 0.298428 0.222987 - -0.0503081 0.293742 0.215208 - -0.0508922 0.293621 0.214068 - -0.0544617 0.315929 0.207199 - -0.0699232 0.342922 0.177143 - -0.0718388 0.355339 0.173459 - -0.0753833 0.316524 0.166372 - -0.0788895 0.312344 0.159511 - -0.0871537 0.317143 0.143404 - -0.294237 1.31223 -0.256373 - -0.279414 1.15254 -0.228145 - -0.255016 0.780189 -0.182164 - -0.291193 0.789259 -0.252725 - -0.291167 0.781939 -0.252707 - -0.288279 0.61286 -0.247812 - -0.201115 -0.364946 -0.0904731 - -0.178628 -0.365509 -0.0454303 - -0.149659 -0.371322 0.0125754 - -0.147711 -0.371846 0.0164758 - -0.121816 -0.377868 0.0683214 - -0.115851 -0.375477 0.0802804 - -0.111988 -0.378329 0.0880074 - -0.109068 -0.376821 0.0938627 - -0.103885 -0.371909 0.104267 - -0.101603 -0.378205 0.108809 - -0.0912383 -0.381046 0.12956 - -0.0849195 -0.375931 0.142241 - -0.0843048 -0.377359 0.143466 - -0.0749745 -0.370322 0.162188 - -0.0701565 -0.375694 0.171815 - -0.0511649 -0.367618 0.209895 - -0.0291561 -0.389616 0.253885 - -0.0272086 -0.377376 0.257841 - -0.0239523 -0.385914 0.264326 - -0.0178455 -0.386656 0.276556 - -0.0171452 -0.385473 0.277964 --0.00040202 -0.399749 0.31144 - 0.00988363 -0.396412 0.332059 - 0.0106549 -0.395952 0.333606 - 0.0232181 -0.401042 0.35875 - 0.041331 -0.397117 0.395051 - 0.0455425 -0.399448 0.403477 - 0.0714723 -0.399067 0.455422 - 0.0987694 -0.406014 0.510072 - 0.113916 -0.412505 0.540385 - 0.143376 -0.420844 0.599362 - 0.143751 -0.414444 0.600141 - 0.142981 -0.409113 0.598623 - 0.150092 -0.389798 0.612954 - 0.396214 -0.715462 1.10453 - 0.395427 -0.707685 1.10299 - 0.43555 -0.704805 1.18338 - 0.582561 -0.727679 1.47777 - 0.600876 -0.733392 1.51443 - 0.64505 -0.734406 1.60291 - 0.772157 -0.757411 1.85743 - 0.785188 -0.760203 1.88352 - 0.869063 -0.786466 2.05142 - 0.962525 -0.556004 2.23968 - 0.962134 -0.47366 2.23926 - 0.959503 -0.442014 2.23414 - 0.961153 -0.422532 2.23753 - 0.96444 -0.313458 2.2446 - 0.963695 -0.30327 2.24315 - 0.962144 -0.282953 2.24014 - 0.959623 -0.262485 2.23518 - 0.963746 -0.174747 2.24383 - 0.963463 -0.155045 2.24335 - 0.963042 -0.0961671 2.24277 - 0.961736 0.0993331 2.24103 - 0.960572 0.128559 2.23883 - 0.962242 0.336415 2.24311 - 0.960625 0.466946 2.24045 - 0.960679 0.507904 2.24075 - 0.86527 0.610716 2.05008 - 0.714769 0.674528 1.74888 - 0.716211 0.693018 1.75185 - 0.749265 0.950287 1.81922 - 0.780986 1.19518 1.88386 - 0.755985 1.20356 1.83382 - 0.740792 1.21422 1.80343 - 0.458598 1.24112 1.23826 - 0.385574 1.09653 1.09133 - 0.0824066 0.346132 0.480662 - 0.0709415 0.391975 0.457901 - 0.0707117 0.410973 0.457525 - 0.0705824 0.41462 0.457283 - 0.0716883 0.436226 0.459595 - 0.0471545 0.441244 0.410471 - 0.0320968 0.376372 0.380017 - 0.0305093 0.391817 0.376906 - 0.0247754 0.46391 0.365743 - 0.0255166 0.476974 0.367286 - 0.0249599 0.480471 0.366186 - 0.0246087 0.700748 0.366469 - 0.0310315 1.30134 0.382025 - 0.015867 1.30704 0.351673 --0.00728779 1.30295 0.305271 - -0.0123685 1.30354 0.295096 - -0.0279335 1.26372 0.263737 - -0.0405504 0.29995 0.234148 - -0.0480345 0.296167 0.219138 - -0.0497646 0.29585 0.215671 - -0.0561761 0.326518 0.202965 - -0.0569289 0.328323 0.201465 - -0.0580825 0.325962 0.199144 - -0.0597811 0.322383 0.195725 - -0.0630472 0.331351 0.189223 - -0.0683547 0.338321 0.178622 - -0.072227 0.356968 0.170948 - -0.0841141 0.311426 0.146932 - -0.0859284 0.310052 0.143291 - -0.0973388 0.348709 0.120607 - -0.10066 0.358721 0.113999 - -0.219449 1.00839 -0.121051 - -0.278966 1.30555 -0.238945 - -0.283389 1.28187 -0.247911 - -0.273251 1.11981 -0.228327 - -0.231234 0.870549 -0.145275 - -0.228691 0.772963 -0.140619 - -0.239088 0.774766 -0.161437 - -0.26065 0.785319 -0.204584 - -0.265642 0.787683 -0.214573 - -0.282794 0.679661 -0.249415 - -0.28097 0.581031 -0.246203 - -0.18083 -0.368791 -0.0575465 - -0.172892 -0.36734 -0.0412144 - -0.170368 -0.366958 -0.0360223 - -0.168958 -0.369604 -0.0331343 - -0.16254 -0.371041 -0.0199409 - -0.148685 -0.371866 0.0085503 - -0.145559 -0.368272 0.0149971 - -0.140837 -0.369388 0.0247041 - -0.138938 -0.37331 0.0285913 - -0.135887 -0.372905 0.0348682 - -0.13143 -0.374279 0.0440276 - -0.11964 -0.375188 0.0682722 - -0.114357 -0.37109 0.0791561 - -0.102279 -0.374418 0.103982 - -0.0975161 -0.375376 0.113773 - -0.0957877 -0.374685 0.117331 - -0.0934946 -0.375464 0.122044 - -0.0927767 -0.376023 0.123518 - -0.0873689 -0.383111 0.134608 - -0.074848 -0.375195 0.160395 - -0.0701962 -0.373406 0.169971 - -0.0645739 -0.387935 0.181468 - -0.055451 -0.370632 0.20031 - -0.0355116 -0.380982 0.241272 - -0.029678 -0.381623 0.253266 --0.00095989 -0.395474 0.312267 - 0.0132142 -0.399801 0.341399 - 0.0263313 -0.397384 0.368388 - 0.0276878 -0.395167 0.371188 - 0.0339313 -0.396013 0.384025 - 0.0462788 -0.398804 0.409407 - 0.056203 -0.396245 0.42983 - 0.0589811 -0.399627 0.435528 - 0.0634229 -0.397338 0.444674 - 0.0726113 -0.404585 0.463538 - 0.0813522 -0.408407 0.481498 - 0.0900517 -0.406846 0.499398 - 0.103085 -0.409532 0.52619 - 0.110285 -0.411731 0.540988 - 0.120311 -0.413319 0.561602 - 0.121095 -0.411745 0.563222 - 0.122459 -0.41166 0.566027 - 0.136092 -0.405855 0.594093 - 0.14022 -0.397821 0.60262 - 0.16591 -0.424608 0.655334 - 0.374724 -0.837661 1.08291 - 0.384763 -0.835774 1.10357 - 0.387254 -0.826042 1.10873 - 0.393032 -0.699613 1.12119 - 0.400701 -0.699036 1.13697 - 0.523213 -0.722931 1.38883 - 0.740666 -0.752819 1.83593 - 0.861586 -0.786558 2.08447 - 0.933559 -0.751198 2.23265 - 0.930033 -0.674064 2.22575 - 0.935407 -0.440653 2.23787 - 0.935581 -0.350674 2.23864 - 0.936847 -0.331248 2.24134 - 0.935972 -0.242135 2.23994 - 0.933832 -0.173193 2.23586 - 0.935162 -0.0760698 2.23904 - 0.93415 -0.0468796 2.23709 - 0.935067 0.127985 2.23978 - 0.936436 0.275338 2.24327 - 0.938791 0.49727 2.24912 - 0.937815 0.507019 2.24716 - 0.933989 0.587454 2.23966 - 0.857327 0.608713 2.08209 - 0.831201 0.619437 2.0284 - 0.812923 0.615756 1.9908 - 0.722184 0.609213 1.80414 - 0.726531 0.762882 1.81379 - 0.732846 0.806201 1.82697 - 0.738383 0.840351 1.83852 - 0.741577 0.882335 1.84528 - 0.742437 0.902845 1.84714 - 0.744968 0.915639 1.8524 - 0.798869 1.2006 1.96456 - 0.720803 1.22011 1.8041 - 0.670297 1.22587 1.70025 - 0.65347 1.21867 1.66561 - 0.64156 1.21952 1.64112 - 0.631743 1.22373 1.62094 - 0.606456 1.23135 1.56897 - 0.561195 1.22888 1.47587 - 0.531957 1.23222 1.41576 - 0.447064 1.23889 1.24119 - 0.37747 1.10901 1.09746 - 0.355135 1.07771 1.05138 - 0.0742629 0.339283 0.470338 - 0.0676482 0.340476 0.456739 - 0.0689611 0.357849 0.459518 - 0.0688416 0.371257 0.459334 - 0.0690469 0.489531 0.460297 - 0.0683032 0.491496 0.458777 - 0.0642081 0.523522 0.450501 - 0.0587195 0.507244 0.439138 - 0.0236067 0.419593 0.366521 - 0.0227711 0.535845 0.365334 - 0.0235728 0.620776 0.367371 - 0.0232369 0.719018 0.36713 - 0.0517736 1.29608 0.42846 - 0.0421657 1.3045 0.408738 - 0.0266061 1.29706 0.376703 --0.00086315 1.2969 0.320207 - -0.0329402 0.875876 0.252309 - -0.0734621 0.309748 0.166378 - -0.0779505 0.31003 0.157148 - -0.21986 0.775809 -0.132585 - -0.233176 0.774978 -0.159975 - -0.251581 0.783671 -0.197788 - -0.264319 0.784061 -0.223986 - -0.27852 0.745562 -0.253368 - -0.275868 0.717579 -0.248042 - -0.275485 0.579569 -0.247886 - -0.18098 -0.368883 -0.0678773 - -0.172095 -0.371308 -0.0489969 - -0.157584 -0.375563 -0.01816 - -0.150848 -0.371082 -0.00381516 - -0.150401 -0.373057 -0.00287431 - -0.140358 -0.373384 0.0184797 - -0.135303 -0.372621 0.0292328 - -0.123197 -0.368371 0.0549937 - -0.122222 -0.37188 0.0570511 - -0.107992 -0.378144 0.0872804 - -0.0994523 -0.371342 0.105471 - -0.0880086 -0.378712 0.12977 - -0.0822342 -0.381674 0.142035 - -0.0793894 -0.383458 0.148076 - -0.0773568 -0.378483 0.152421 - -0.0759593 -0.372089 0.155423 - -0.0733707 -0.375568 0.160911 - -0.0681521 -0.374052 0.172015 - -0.0463112 -0.41145 0.218282 - -0.0455469 -0.411539 0.219907 - -0.0400452 -0.383945 0.231735 --0.00680422 -0.394548 0.302369 - 0.00189405 -0.397475 0.320851 - 0.00532647 -0.386217 0.328203 - 0.0198729 -0.394772 0.359094 - 0.0214769 -0.394528 0.362506 - 0.042134 -0.403987 0.406387 - 0.049004 -0.384822 0.421086 - 0.0517328 -0.392759 0.426851 - 0.0692199 -0.403735 0.463984 - 0.0730669 -0.406326 0.472152 - 0.0779935 -0.404728 0.482635 - 0.0799404 -0.407686 0.486761 - 0.0839336 -0.402397 0.495277 - 0.0856692 -0.400707 0.498976 - 0.10454 -0.410867 0.539054 - 0.10976 -0.411114 0.550154 - 0.112388 -0.411123 0.555742 - 0.126185 -0.418494 0.585046 - 0.375282 -0.789544 1.11298 - 0.373725 -0.719083 1.11 - 0.408735 -0.70494 1.18451 - 0.427476 -0.707237 1.22435 - 0.470556 -0.715036 1.31592 - 0.640844 -0.74096 1.6779 - 0.719248 -0.752429 1.84457 - 0.901836 -0.693628 2.2331 - 0.901927 -0.417329 2.23459 - 0.903335 -0.23076 2.23846 - 0.904175 0.0595906 2.24161 - 0.904066 0.214865 2.24211 - 0.903031 0.322457 2.24041 - 0.905178 0.372803 2.24522 - 0.902549 0.401623 2.23976 - 0.905105 0.575482 2.24601 - 0.877773 0.60932 2.18805 - 0.716368 0.612706 1.84486 - 0.725134 0.745623 1.86412 - 0.764479 0.95423 1.94877 - 0.756879 1.20665 1.93379 - 0.750347 1.20827 1.91991 - 0.729751 1.21079 1.87613 - 0.708217 1.21055 1.83034 - 0.625074 1.22322 1.6536 - 0.615837 1.22809 1.63398 - 0.511331 1.23172 1.41178 - 0.422692 1.23132 1.22329 - 0.0658872 0.348067 0.46043 - 0.0652198 0.362466 0.459079 - 0.0659904 0.427129 0.461021 - 0.0653663 0.456479 0.459832 - 0.0656858 0.483103 0.460637 - 0.0649754 0.485064 0.459135 - 0.0416936 0.441156 0.409422 - 0.0222887 0.394774 0.367942 - 0.0215849 0.431266 0.366617 - 0.020372 0.463565 0.364189 - 0.0195736 0.533548 0.362821 - 0.0444955 1.30181 0.419425 - 0.0292846 1.29369 0.387043 - 0.0124698 1.29908 0.351313 - -0.0442314 0.300703 0.226051 - -0.0462668 0.293438 0.221689 - -0.0507046 0.294616 0.212258 - -0.0559237 0.329495 0.201324 - -0.0580603 0.323784 0.196754 - -0.0746933 0.315796 0.161348 - -0.0753927 0.316387 0.159864 - -0.0780718 0.312507 0.154148 - -0.0787757 0.313057 0.152654 - -0.0983453 0.369276 0.111306 - -0.266204 1.31065 -0.241206 - -0.27374 1.13628 -0.25805 - -0.273205 1.1213 -0.256983 - -0.269746 1.06939 -0.249872 - -0.23455 0.784892 -0.176368 - -0.243789 0.782373 -0.196026 - -0.266875 0.762241 -0.245209 - -0.268284 0.759901 -0.248216 - -0.266542 0.597949 -0.245275 - -0.267855 0.560885 -0.24824 - -0.186596 -0.361744 -0.0883945 - -0.176796 -0.368871 -0.0670244 - -0.173121 -0.368722 -0.0589963 - -0.164254 -0.363326 -0.0396035 - -0.156424 -0.369459 -0.022533 - -0.152652 -0.367573 -0.0142854 - -0.140328 -0.377344 0.0125849 - -0.132693 -0.370069 0.0292953 - -0.131342 -0.37205 0.0322378 - -0.129772 -0.373143 0.0356611 - -0.127726 -0.376012 0.0401169 - -0.10525 -0.379578 0.0891882 - -0.101756 -0.373359 0.0968496 - -0.0909092 -0.378865 0.120514 - -0.0902195 -0.379421 0.122018 - -0.0787746 -0.370987 0.147056 - -0.0739303 -0.388249 0.157553 - -0.0685314 -0.367525 0.169445 - -0.056121 -0.380377 0.196489 - -0.0555196 -0.382556 0.197792 - -0.0422341 -0.381829 0.226812 - -0.0232519 -0.387494 0.268244 - -0.0202118 -0.391811 0.274863 - -0.0196429 -0.388644 0.276121 - -0.0131175 -0.389629 0.290368 --0.00605552 -0.395872 0.305763 --0.00461981 -0.395198 0.308902 - 0.00150992 -0.388879 0.32232 - 0.0175452 -0.399727 0.357291 - 0.0297983 -0.394162 0.38408 - 0.0348667 -0.398794 0.395127 - 0.039144 -0.402978 0.404449 - 0.0585157 -0.402676 0.446761 - 0.0700342 -0.40464 0.471909 - 0.0748017 -0.40674 0.482312 - 0.0758016 -0.402714 0.484515 - 0.0899594 -0.409218 0.515406 - 0.0937017 -0.409934 0.523576 - 0.106379 -0.411114 0.551259 - 0.12738 -0.423897 0.597066 - 0.363673 -0.820202 1.11125 - 0.362357 -0.775254 1.1086 - 0.363946 -0.751022 1.11218 - 0.366687 -0.696889 1.11843 - 0.473251 -0.71346 1.3511 - 0.483053 -0.712651 1.37251 - 0.497987 -0.718316 1.4051 - 0.521469 -0.719417 1.45638 - 0.580154 -0.729583 1.58451 - 0.60777 -0.7372 1.64479 - 0.633861 -0.732835 1.70179 - 0.688975 -0.747561 1.8221 - 0.866736 -0.788146 2.21015 - 0.87582 -0.774507 2.23006 - 0.875216 -0.424483 2.23042 - 0.879323 -0.386677 2.23957 - 0.878275 -0.288039 2.23776 - 0.879203 -0.046479 2.24094 - 0.877994 0.0208061 2.23863 - 0.877514 0.0303953 2.23763 - 0.878169 0.400016 2.24083 - 0.880312 0.461019 2.24581 - 0.87978 0.541863 2.24503 - 0.773612 0.617263 2.01351 - 0.76178 0.617528 1.98767 - 0.733472 0.62263 1.92587 - 0.720546 0.647909 1.89776 - 0.745986 0.792967 1.95402 - 0.767617 0.947851 2.00201 - 0.784645 1.06641 2.03977 - 0.788352 1.09377 2.04799 - 0.770963 1.20802 2.01056 - 0.755282 1.20789 1.97631 - 0.74211 1.21098 1.94756 - 0.628254 1.22325 1.69895 - 0.617202 1.22497 1.67481 - 0.557805 1.22915 1.5451 - 0.537565 1.23017 1.5009 - 0.494772 1.23252 1.40745 - 0.457442 1.24029 1.32595 - 0.418721 1.24856 1.24142 - 0.398674 1.21509 1.19748 - 0.347733 1.09262 1.08563 - 0.0671955 0.341519 0.469294 - 0.0639273 0.366613 0.462276 - 0.0628208 0.37316 0.459891 - 0.0634898 0.379257 0.461381 - 0.0621842 0.393039 0.458596 - 0.062676 0.40284 0.459717 - 0.0617602 0.42839 0.45784 - 0.061996 0.43836 0.458403 - 0.0632641 0.472955 0.461339 - 0.0621562 0.483277 0.458968 - 0.0614109 0.513001 0.457483 - 0.0523685 0.506376 0.437702 - 0.0217605 0.385381 0.370269 - 0.0196103 0.397896 0.365633 - 0.0208688 0.430643 0.368539 - 0.0197437 0.49419 0.366387 - 0.0185992 0.501188 0.363921 - 0.0196213 0.519157 0.36624 - 0.0192504 0.554501 0.365599 - 0.0253791 0.86902 0.380496 - 0.00657433 1.30509 0.34152 - 0.00426713 1.30757 0.336492 --0.00531801 1.30626 0.315551 - -0.0368096 0.413968 0.242483 - -0.0399136 0.299986 0.235156 - -0.0484465 0.294073 0.216491 - -0.0644639 0.339449 0.181725 - -0.0684235 0.355973 0.173156 - -0.0721315 0.374572 0.165147 - -0.0714342 0.325686 0.166435 - -0.0753317 0.32121 0.157901 - -0.0856911 0.317588 0.135257 - -0.255323 1.30686 -0.230485 - -0.264775 1.22246 -0.251535 - -0.26507 1.14284 -0.252561 - -0.265803 1.08516 -0.254439 - -0.260326 1.02554 -0.242764 - -0.261989 1.02233 -0.246411 - -0.229562 0.77341 -0.176782 - -0.23755 0.774703 -0.194222 - -0.239614 0.775171 -0.198728 - -0.252109 0.777374 -0.22601 - -0.262797 0.743822 -0.249514 - -0.263327 0.663291 -0.251058 - -0.186129 -0.368851 -0.0968091 - -0.179806 -0.375438 -0.0826318 - -0.171046 -0.368044 -0.0629094 - -0.171193 -0.37172 -0.063257 - -0.154225 -0.367421 -0.0251016 - -0.145186 -0.367834 -0.00478859 - -0.141431 -0.371866 0.00363079 - -0.131491 -0.373472 0.025961 - -0.102892 -0.374064 0.0902328 - -0.0857826 -0.382093 0.128645 - -0.0820481 -0.3817 0.13704 - -0.077567 -0.380553 0.147116 - -0.0735582 -0.368592 0.156185 - -0.050298 -0.376724 0.20842 - -0.0431268 -0.393769 0.224453 - -0.0307094 -0.38562 0.2524 - -0.0286585 -0.385362 0.257011 - -0.0236923 -0.389486 0.268151 - -0.0217503 -0.386019 0.272533 - -0.017383 -0.389821 0.282329 - -0.0129245 -0.393323 0.292332 - -0.0081329 -0.390299 0.303116 --0.00503817 -0.392891 0.310058 - 0.00689749 -0.394045 0.336877 - 0.0197446 -0.392367 0.365758 - 0.0323323 -0.395127 0.394034 - 0.0337287 -0.39361 0.39718 - 0.0375471 -0.395921 0.40575 - 0.0423604 -0.385662 0.416618 - 0.0526496 -0.395951 0.439692 - 0.0762396 -0.406914 0.492654 - 0.0802583 -0.41346 0.501654 - 0.0838865 -0.410763 0.509821 - 0.0865446 -0.408417 0.515806 - 0.091418 -0.409346 0.526754 - 0.11741 -0.415547 0.585139 - 0.120341 -0.401828 0.591793 - 0.349174 -0.838848 1.10393 - 0.3528 -0.839309 1.11207 - 0.349087 -0.761058 1.10411 - 0.364244 -0.703094 1.13846 - 0.369939 -0.693527 1.15131 - 0.435236 -0.710798 1.29797 - 0.466948 -0.714598 1.36922 - 0.47174 -0.714137 1.38 - 0.60501 -0.735052 1.67941 - 0.726684 -0.766912 1.9527 - 0.817389 -0.783987 2.15647 - 0.854219 -0.753073 2.23939 - 0.853696 -0.678673 2.23859 - 0.855111 -0.627684 2.24202 - 0.85243 -0.594964 2.23615 - 0.854078 -0.575588 2.23995 - 0.854285 -0.565516 2.24047 - 0.851564 -0.5032 2.23466 - 0.851978 -0.247796 2.23685 - 0.852085 -0.180338 2.23742 - 0.852901 -0.0941082 2.23968 - 0.853395 0.0686259 2.24159 - 0.852254 0.126033 2.2393 - 0.853482 0.155058 2.24221 - 0.854252 0.213127 2.24422 - 0.852285 0.378395 2.24061 - 0.813104 0.612949 2.15371 - 0.779444 0.61749 2.07809 - 0.732094 0.701919 1.97209 - 0.7517 0.8282 2.01677 - 0.775507 0.991298 2.07108 - 0.780952 1.03112 2.08351 - 0.716493 1.22295 1.93959 - 0.664165 1.22711 1.82201 - 0.607294 1.22477 1.69418 - 0.40454 1.23957 1.23858 - 0.397458 1.24152 1.22267 - 0.0602245 0.380326 0.460535 - 0.0602171 0.407331 0.460651 - 0.0588394 0.431187 0.457672 - 0.0610301 0.464609 0.46276 - 0.0602016 0.475801 0.460953 - 0.0203064 0.391634 0.370877 - 0.0187553 0.397279 0.367419 - 0.0181974 0.656801 0.367442 - 0.0175578 0.67858 0.366112 - 0.0444231 1.29213 0.429508 - 0.026027 1.29865 0.388196 - 0.0237215 1.29936 0.383018 - -0.0527465 0.308132 0.206286 - -0.0541109 0.32487 0.203302 - -0.0577956 0.327745 0.195035 - -0.066729 0.349409 0.175065 - -0.0685715 0.320834 0.170784 - -0.0692312 0.31532 0.169274 - -0.0755674 0.313305 0.155024 - -0.081438 0.316173 0.141844 - -0.0970213 0.385492 0.107163 - -0.181174 0.914308 -0.0793617 - -0.258503 1.25978 -0.251453 - -0.260054 1.09379 -0.255754 - -0.258688 1.07532 -0.252777 - -0.250771 0.94298 -0.235633 - -0.22939 0.782579 -0.188371 - -0.231726 0.776771 -0.193649 - -0.234682 0.773471 -0.20031 - -0.250969 0.776214 -0.236899 - -0.254651 0.707122 -0.245514 - -0.256793 0.641594 -0.25065 - -0.256227 0.601772 -0.249573 - -0.167986 -0.370971 -0.0644084 - -0.161918 -0.3631 -0.050342 - -0.160887 -0.373113 -0.0480084 - -0.138104 -0.374908 0.00464833 - -0.129028 -0.375328 0.0256254 - -0.122332 -0.369081 0.0411365 - -0.114467 -0.375305 0.0592873 - -0.0991789 -0.368992 0.0946589 - -0.0986878 -0.370586 0.095786 - -0.0901047 -0.377731 0.115591 - -0.0781697 -0.373446 0.143202 - -0.0781259 -0.379682 0.143272 - -0.0737082 -0.377345 0.153496 - -0.072398 -0.378118 0.156521 - -0.0676817 -0.370465 0.167462 - -0.0643259 -0.370047 0.175221 - -0.0631069 -0.3716 0.178031 - -0.0564109 -0.383156 0.193452 - -0.0514121 -0.374447 0.205051 - -0.0461932 -0.374411 0.217116 - -0.0456063 -0.416533 0.21826 - -0.0448845 -0.416615 0.219929 - -0.0424683 -0.391825 0.225639 - -0.0390544 -0.377987 0.2336 - -0.0317116 -0.385691 0.250535 - -0.0158905 -0.391115 0.287081 --0.00621529 -0.389952 0.309452 --0.00226874 -0.386759 0.318592 --0.00132059 -0.389284 0.320771 - 0.00500322 -0.394519 0.335363 - 0.0162085 -0.388865 0.361294 - 0.0233053 -0.395059 0.377668 - 0.0267061 -0.391606 0.385547 - 0.0325436 -0.397263 0.399013 - 0.0388869 -0.399769 0.413664 - 0.04418 -0.391899 0.425939 - 0.0493831 -0.399627 0.437928 - 0.094957 -0.408636 0.543233 - 0.0961068 -0.404934 0.54591 - 0.0987901 -0.405789 0.552108 - 0.104204 -0.407237 0.564615 - 0.12031 -0.418976 0.601788 - 0.118007 -0.402276 0.596549 - 0.117073 -0.38622 0.594471 - 0.341345 -0.805669 1.11079 - 0.341812 -0.799576 1.11191 - 0.343236 -0.774625 1.11532 - 0.34063 -0.74903 1.10943 - 0.34019 -0.702389 1.10865 - 0.353305 -0.694167 1.13901 - 0.430901 -0.707319 1.31831 - 0.467683 -0.710996 1.40332 - 0.481977 -0.716203 1.43634 - 0.529719 -0.726254 1.54665 - 0.536648 -0.727208 1.56266 - 0.587322 -0.732099 1.67978 - 0.742542 -0.77189 2.03839 - 0.825867 -0.652625 2.23161 - 0.826915 -0.63279 2.23413 - 0.827468 -0.541531 2.23587 - 0.827988 -0.491674 2.23732 - 0.82807 -0.471783 2.23761 - 0.828583 -0.373354 2.2393 - 0.826789 -0.294819 2.23554 - 0.829048 -0.227957 2.2411 - 0.827978 0.183019 2.2407 - 0.827635 0.192544 2.23996 - 0.826842 0.288742 2.23861 - 0.828171 0.328098 2.24188 - 0.827329 0.425944 2.24042 - 0.829749 0.527309 2.24653 - 0.827469 0.546152 2.24135 - 0.737889 0.734056 2.03522 - 0.743931 0.769439 2.04937 - 0.76052 0.889117 2.08832 - 0.765682 0.916144 2.10039 - 0.792361 1.11746 2.16307 - 0.793539 1.13087 2.16586 - 0.800004 1.17575 2.18104 - 0.716311 1.21676 1.98777 - 0.470606 1.24576 1.41994 - 0.433478 1.23885 1.33407 - 0.324433 1.10703 1.08134 - 0.0571029 0.340476 0.459501 - 0.0561417 0.343399 0.457294 - 0.0578903 0.359744 0.461418 - 0.0572642 0.360807 0.459976 - 0.0566363 0.361864 0.45853 - 0.0575162 0.406474 0.460789 - 0.0568266 0.521302 0.459773 - 0.0553925 0.53173 0.456511 - 0.0178868 0.401986 0.369157 - 0.0164836 0.476635 0.36629 - 0.0166536 0.49419 0.366771 - 0.015029 0.513971 0.363115 - 0.0187886 0.802442 0.373259 - 0.0462698 1.28335 0.439208 --0.00749795 1.29927 0.314997 - -0.02107 1.29703 0.283611 - -0.0301621 1.01367 0.261166 - -0.0392125 0.312999 0.236716 - -0.0417076 0.292925 0.230847 - -0.0428505 0.301852 0.22825 - -0.0489409 0.295961 0.214141 - -0.0511569 0.299463 0.209036 - -0.051719 0.300322 0.207741 - -0.0568835 0.337058 0.195987 - -0.0681367 0.364799 0.170114 - -0.243946 1.31189 -0.231524 - -0.253302 1.22847 -0.253572 - -0.253102 1.17164 -0.253397 - -0.254095 1.10063 -0.256049 - -0.231155 0.776871 -0.204652 - -0.249074 0.685867 -0.246533 - -0.250492 0.626227 -0.25011 - -0.249939 0.587442 -0.249027 - -0.165532 -0.362945 -0.0675284 - -0.163014 -0.362072 -0.0615289 - -0.156302 -0.367728 -0.0455785 - -0.145144 -0.367573 -0.0190099 - -0.142408 -0.371534 -0.0125182 - -0.135357 -0.369668 0.00428006 - -0.133257 -0.375671 0.00924903 - -0.130307 -0.374638 0.0162771 - -0.124394 -0.379278 0.0303313 - -0.117644 -0.375388 0.0464237 - -0.114375 -0.375377 0.0542076 - -0.0995085 -0.37476 0.0896052 - -0.0836185 -0.380183 0.127409 - -0.0816848 -0.381692 0.132006 - -0.0672263 -0.380599 0.166435 - -0.0665106 -0.379943 0.168143 - -0.0645805 -0.380873 0.172733 - -0.0503131 -0.385693 0.206678 - -0.0473324 -0.370222 0.213854 - -0.0391982 -0.378987 0.233175 - -0.0327647 -0.380757 0.248484 - -0.0241913 -0.38535 0.268872 - -0.0151058 -0.393585 0.290462 - -0.0084849 -0.390632 0.30624 --0.00602365 -0.395474 0.312075 - 0.0104761 -0.401972 0.351326 - 0.0319833 -0.391278 0.402588 - 0.0386636 -0.396311 0.418467 - 0.0399967 -0.394569 0.42165 - 0.066012 -0.405073 0.483535 - 0.069368 -0.40648 0.491518 - 0.0859072 -0.412507 0.530865 - 0.0872913 -0.4097 0.534175 - 0.0917572 -0.40941 0.544809 - 0.0977672 -0.413417 0.559097 - 0.113575 -0.397709 0.596816 - 0.114094 -0.382103 0.598132 - 0.143618 -0.432734 0.668164 - 0.32971 -0.81526 1.10925 - 0.328848 -0.764565 1.10746 - 0.329839 -0.707128 1.11012 - 0.334847 -0.691052 1.12212 - 0.562267 -0.7372 1.66335 - 0.576492 -0.729408 1.69726 - 0.799205 -0.6486 2.22793 - 0.803196 -0.570003 2.23784 - 0.800379 -0.558026 2.23119 - 0.807181 -0.383218 2.24829 - 0.802073 -0.371161 2.23619 - 0.801916 -0.341953 2.23597 - 0.802621 -0.322864 2.23775 - 0.803261 -0.303767 2.23937 - 0.80526 -0.179436 2.24477 - 0.805799 -0.160417 2.24615 - 0.802581 -0.0553041 2.23903 - 0.802701 -0.0363454 2.23942 - 0.801962 -0.0268402 2.23771 - 0.801688 0.0773787 2.23759 - 0.802127 0.115409 2.23883 - 0.80501 0.154001 2.2459 - 0.801815 0.24904 2.23878 - 0.801974 0.453663 2.24022 - 0.80313 0.504121 2.24323 - 0.726671 0.654384 2.06196 - 0.741327 0.756162 2.09738 - 0.742917 0.767799 2.10123 - 0.754794 0.841712 2.12989 - 0.756874 0.86502 2.13496 - 0.690504 1.21694 1.97876 - 0.48778 1.24218 1.49623 - 0.457251 1.24437 1.42355 - 0.438921 1.24116 1.37989 - 0.412608 1.24709 1.31727 - 0.386364 1.24931 1.2548 - 0.298689 1.08398 1.0452 - 0.0643608 0.340236 0.483453 - 0.0630707 0.351591 0.48044 - 0.0555653 0.364125 0.462635 - 0.0553825 0.377579 0.462269 - 0.053455 0.412223 0.457859 - 0.0533712 0.466908 0.457942 - 0.052977 0.514049 0.457247 - 0.0277824 0.415116 0.396751 - 0.0194128 0.396881 0.376729 - 0.0187405 0.397541 0.375132 - 0.0145653 0.53391 0.365895 - 0.0147299 0.625296 0.366759 - 0.0175669 0.808343 0.374459 - 0.00925732 1.30151 0.357222 - 0.00249476 1.29812 0.341104 - -0.0150992 1.30026 0.299225 - -0.0429777 0.30485 0.227709 - -0.0463484 0.295434 0.219635 - -0.0503745 0.295611 0.21005 - -0.0617319 0.335046 0.183213 - -0.0622974 0.334791 0.181865 - -0.0730883 0.324487 0.15612 - -0.0750557 0.320994 0.151418 - -0.0777838 0.305216 0.144841 - -0.0873514 0.353943 0.122314 - -0.233162 1.30602 -0.219927 - -0.246334 1.3088 -0.251274 - -0.249599 1.28147 -0.259191 - -0.247721 1.23998 -0.254932 - -0.24762 1.2248 -0.254772 - -0.247886 1.17073 -0.255683 - -0.246632 1.05333 -0.253303 - -0.245911 0.9176 -0.252288 - -0.23305 0.780617 -0.222375 - -0.241964 0.771454 -0.243645 - -0.242162 0.765042 -0.244152 - -0.245157 0.741273 -0.251404 - -0.242846 0.5815 -0.246726 - -0.24155 0.553182 -0.243788 - -0.172436 -0.365572 -0.0937286 - -0.171221 -0.368661 -0.0907641 - -0.149009 -0.369604 -0.0362719 - -0.135559 -0.372393 -0.00328822 - -0.132667 -0.375174 0.00379236 - -0.131013 -0.375671 0.00784697 - -0.12043 -0.374198 0.033822 - -0.113315 -0.370999 0.0512933 - -0.108943 -0.372508 0.0620135 - -0.107255 -0.375828 0.0661358 - -0.0935706 -0.373203 0.0997254 - -0.0851329 -0.37807 0.120401 - -0.079288 -0.374498 0.134761 - -0.0711397 -0.387274 0.154685 - -0.0701825 -0.383745 0.157052 - -0.0533537 -0.368823 0.19842 - -0.0462757 -0.382399 0.215714 - -0.0419099 -0.388873 0.226391 - -0.0322349 -0.392685 0.250108 - -0.031607 -0.391614 0.251655 - -0.0266127 -0.385784 0.263939 - -0.0259777 -0.385647 0.265497 - -0.0109695 -0.387349 0.302311 --0.00875706 -0.390295 0.307724 - 0.00374166 -0.3926 0.338377 - 0.00375044 -0.386346 0.338431 - 0.0100509 -0.398008 0.353828 - 0.0212452 -0.3937 0.381316 - 0.0429909 -0.395311 0.43466 - 0.0925074 -0.41188 0.55606 - 0.11343 -0.387327 0.607524 - 0.317858 -0.824156 1.10677 - 0.319204 -0.820042 1.11009 - 0.335549 -0.697626 1.15084 - 0.339996 -0.692958 1.16178 - 0.414974 -0.705114 1.34567 - 0.424802 -0.706109 1.36978 - 0.471178 -0.715433 1.48351 - 0.49297 -0.714921 1.53698 - 0.52867 -0.72226 1.62453 - 0.568855 -0.730765 1.72308 - 0.77896 -0.680428 2.23884 - 0.782199 -0.65205 2.24694 - 0.777934 -0.31196 2.23828 - 0.776798 -0.273165 2.23569 - 0.778778 -0.235538 2.24075 - 0.774749 -0.130238 2.23142 - 0.774994 -0.064305 2.23237 - 0.77514 -0.0454878 2.23283 - 0.777332 0.143365 2.23921 - 0.778932 0.210327 2.24349 - 0.77852 0.238904 2.24263 - 0.775855 0.314813 2.23649 - 0.780525 0.58418 2.24938 - 0.782446 0.59577 2.25415 - 0.742256 0.62545 2.15571 - 0.731058 0.675412 2.1285 - 0.734835 0.698693 2.13789 - 0.754387 0.852635 2.18667 - 0.762904 0.894461 2.20779 - 0.768032 0.933432 2.22058 - 0.777464 1.11879 2.2447 - 0.589784 1.22759 1.78481 - 0.508124 1.23386 1.58449 - 0.445154 1.23528 1.43 - 0.390153 1.24904 1.29513 - 0.380671 1.25419 1.27189 - 0.303415 1.09857 1.08152 - 0.29945 1.09559 1.07178 - 0.0596376 0.342919 0.479414 - 0.0519877 0.412896 0.461016 - 0.0513678 0.418465 0.459525 - 0.0516689 0.437485 0.460364 - 0.0510963 0.463194 0.459096 - 0.0512202 0.49541 0.45957 - 0.049993 0.5234 0.456708 - 0.0383769 0.488938 0.428025 - 0.0207273 0.391619 0.384206 - 0.0133314 0.39163 0.366061 - 0.0129111 0.429978 0.365233 - 0.0126403 0.530041 0.365098 - 0.0133431 0.557409 0.366968 - 0.0127805 0.561902 0.365611 --0.00098776 1.29661 0.335724 - -0.015939 1.30026 0.299061 - -0.037852 0.369971 0.240368 - -0.0433602 0.291814 0.22644 - -0.0464678 0.300425 0.218861 - -0.0468283 0.295352 0.217949 - -0.0496328 0.291751 0.21105 - -0.0543228 0.32967 0.199744 - -0.0580229 0.336445 0.190701 - -0.0662854 0.319197 0.170338 - -0.0914878 0.382017 0.108837 - -0.239169 1.29489 -0.248659 - -0.239368 1.20555 -0.24962 - -0.241193 1.20233 -0.254115 - -0.239878 1.0444 -0.251726 - -0.241661 1.02056 -0.256226 - -0.241961 1.00087 -0.257069 - -0.240535 0.983569 -0.25366 - -0.236214 0.805337 -0.244003 - -0.238923 0.743577 -0.250977 - -0.237872 0.719643 -0.248524 - -0.237683 0.58602 -0.248771 - -0.238134 0.582243 -0.249896 - -0.166761 -0.368018 -0.0890388 - -0.157941 -0.370892 -0.0667822 - -0.140037 -0.370379 -0.0215668 - -0.129093 -0.372925 0.00605616 - -0.103093 -0.369284 0.0717312 - -0.0986084 -0.37265 0.0830379 - -0.0930796 -0.383163 0.0969425 - -0.0888483 -0.372561 0.107685 - -0.0773937 -0.383601 0.136551 - -0.0688576 -0.383134 0.15811 - -0.0624247 -0.372304 0.174413 - -0.0493279 -0.382837 0.207429 - -0.0332991 -0.383755 0.247901 - -0.0281223 -0.392022 0.260929 - -0.0259137 -0.382514 0.266557 - -0.0182975 -0.385174 0.285776 - -0.0157081 -0.386141 0.29231 - -0.0144693 -0.38559 0.295441 - -0.0132062 -0.395158 0.298579 - 0.00139847 -0.394519 0.335463 - 0.00765948 -0.401017 0.351238 - 0.00999047 -0.396878 0.357147 - 0.0332973 -0.398024 0.415997 - 0.0356685 -0.393678 0.422008 - 0.0555228 -0.403226 0.472094 - 0.056238 -0.394827 0.473945 - 0.0614275 -0.404728 0.486996 - 0.0674229 -0.405662 0.502131 - 0.0680712 -0.404405 0.503775 - 0.103826 -0.378911 0.594204 - 0.307277 -0.784805 1.10577 - 0.308527 -0.78071 1.10894 - 0.307953 -0.706449 1.1079 - 0.344169 -0.692041 1.19943 - 0.384495 -0.708502 1.30117 - 0.443113 -0.715242 1.44916 - 0.508171 -0.721796 1.61342 - 0.53108 -0.719018 1.67128 - 0.636067 -0.756382 1.9362 - 0.68868 -0.765484 2.06901 - 0.753753 -0.494903 2.23481 - 0.755274 -0.225051 2.24012 - 0.757338 -0.197079 2.24548 - 0.754449 -0.13964 2.2385 - 0.756827 0.0298703 2.24542 - 0.752201 0.275161 2.23507 - 0.754429 0.343219 2.24107 - 0.755149 0.570349 2.24412 - 0.73933 0.720598 2.20499 - 0.756618 0.854787 2.24938 - 0.752924 0.928028 2.24045 - 0.630923 1.22191 1.93396 - 0.532862 1.24243 1.68644 - 0.483209 1.24033 1.56104 - 0.471499 1.23415 1.53144 - 0.410415 1.2505 1.37727 - 0.400018 1.25417 1.35104 - 0.362962 1.25411 1.25746 - 0.297218 1.11643 1.09069 - 0.278974 1.08467 1.04445 - 0.0578231 0.34256 0.481953 - 0.0487316 0.396853 0.45929 - 0.0506659 0.449062 0.464458 - 0.0487761 0.458598 0.459738 - 0.0116956 0.41926 0.365886 - 0.010837 0.437855 0.363819 - 0.0118635 0.492267 0.366707 - 0.0112668 0.494802 0.365214 - 0.011534 0.575136 0.366325 - 0.0108859 0.702342 0.365379 - 0.0317297 1.29786 0.42125 - 0.025464 1.30035 0.405441 - 0.0168788 1.29836 0.38375 - -0.010285 1.30725 0.315203 - -0.0335135 0.73676 0.253446 - -0.0538458 0.323712 0.199858 - -0.0555541 0.326153 0.195557 - -0.0634725 0.347041 0.175675 - -0.0698674 0.316524 0.15936 - -0.0714871 0.316387 0.155269 - -0.0719943 0.316006 0.153986 - -0.0983386 0.441295 0.0881406 - -0.235536 1.22528 -0.254059 - -0.232824 0.920456 -0.248867 - -0.234421 0.900597 -0.253008 - -0.232988 0.86793 -0.249567 - -0.23031 0.625411 -0.244121 - -0.232794 0.590545 -0.250582 - -0.156739 -0.365908 -0.075436 - -0.152227 -0.374351 -0.0636428 - -0.151641 -0.375741 -0.0621146 - -0.137889 -0.370769 -0.0259968 - -0.136729 -0.373189 -0.0229651 - -0.125137 -0.375062 0.00744589 - -0.0978115 -0.379059 0.0791341 - -0.0918125 -0.380649 0.0948686 - -0.0794631 -0.376867 0.127299 - -0.0721686 -0.366028 0.146503 - -0.0597226 -0.37734 0.179102 - -0.0473322 -0.381199 0.211596 - -0.0390279 -0.381997 0.233385 - -0.0372997 -0.371983 0.237977 - -0.0298934 -0.391251 0.257305 - -0.0250749 -0.389172 0.269962 - -0.0237095 -0.392805 0.273525 - -0.0189953 -0.388145 0.285923 - -0.0177909 -0.387651 0.289086 - -0.0171893 -0.387394 0.290667 - -0.0139321 -0.389933 0.2992 --0.00588518 -0.395527 0.320286 --0.00527173 -0.395123 0.321899 --0.00430688 -0.39138 0.324452 - 0.00031605 -0.392118 0.33658 - 0.00284939 -0.397376 0.343198 - 0.00741371 -0.390232 0.355217 - 0.0112746 -0.393922 0.365328 - 0.0121297 -0.39519 0.367565 - 0.0151814 -0.391994 0.375592 - 0.0155266 -0.389468 0.376512 - 0.0209462 -0.397347 0.390691 - 0.0241276 -0.398947 0.399031 - 0.0245987 -0.397263 0.400276 - 0.0299749 -0.397968 0.414381 - 0.0325512 -0.391006 0.421182 - 0.0399708 -0.396917 0.44062 - 0.046444 -0.400309 0.457588 - 0.0496116 -0.403118 0.465886 - 0.0524359 -0.404072 0.473292 - 0.0666734 -0.402201 0.510666 - 0.0747359 -0.406382 0.531802 - 0.0876038 -0.410342 0.565549 - 0.0983835 -0.397515 0.59391 - 0.0981908 -0.37681 0.593521 - 0.100311 -0.379314 0.599071 - 0.286441 -0.825676 1.08503 - 0.296405 -0.828917 1.11116 - 0.295587 -0.711144 1.10968 - 0.294396 -0.702241 1.1066 - 0.29655 -0.694069 1.1123 - 0.321514 -0.699221 1.17778 - 0.349627 -0.692324 1.2516 - 0.397672 -0.70511 1.37761 - 0.449928 -0.711943 1.51471 - 0.454511 -0.710988 1.52675 - 0.514776 -0.722394 1.68483 - 0.638697 -0.756408 2.00985 - 0.724743 -0.714917 2.2359 - 0.721467 -0.599961 2.22795 - 0.723068 -0.443199 2.23303 - 0.725142 -0.328549 2.23912 - 0.724688 -0.309247 2.23803 - 0.724335 -0.214247 2.23764 - 0.726711 -0.195989 2.24398 - 0.724451 -0.129574 2.23842 - 0.725426 -0.092178 2.24119 - 0.725383 0.0953421 2.24213 - 0.726795 0.498931 2.2481 - 0.725233 0.53766 2.24422 - 0.726191 0.659984 2.24742 - 0.725857 0.711505 2.24684 - 0.726889 0.829395 2.25021 - 0.722745 1.16726 2.24123 - 0.719354 1.19867 2.23251 - 0.636449 1.22669 2.01509 - 0.56759 1.23342 1.83442 - 0.49416 1.24208 1.64177 - 0.463808 1.24653 1.56214 - 0.453815 1.24354 1.5359 - 0.427029 1.23976 1.46558 - 0.374558 1.25512 1.32796 - 0.370913 1.25506 1.3184 - 0.332659 1.2433 1.21794 - 0.0521479 0.359715 0.476826 - 0.0479564 0.363052 0.465845 - 0.0449121 0.371071 0.457901 - 0.0447119 0.373794 0.457391 - 0.0464216 0.396653 0.462006 - 0.0466182 0.449252 0.462817 - 0.0213212 0.416794 0.396248 - 0.0156479 0.40274 0.38128 - 0.00985005 0.40762 0.366092 - 0.00881173 0.465127 0.36369 - 0.00906347 0.475324 0.364408 - 0.00961256 0.543232 0.36623 - 0.0103071 0.606518 0.368409 - -0.0450098 0.299643 0.221515 - -0.0544006 0.330488 0.197044 - -0.0588425 0.334787 0.185411 - -0.0598812 0.334309 0.182683 - -0.0678582 0.320485 0.161671 - -0.0739015 0.307446 0.145738 - -0.0761136 0.312823 0.139963 - -0.210564 1.30019 -0.207332 - -0.228436 1.17718 -0.254926 - -0.226059 1.05076 -0.249397 - -0.227362 1.03547 -0.252904 - -0.226184 1.01804 -0.249911 - -0.22805 0.996113 -0.254931 - -0.22476 0.920107 -0.246723 - -0.225414 0.852824 -0.248818 - -0.226733 0.850554 -0.252293 - -0.225391 0.753697 -0.249313 - -0.224268 0.653793 -0.246927 - -0.225707 0.641544 -0.250772 - -0.159648 -0.36577 -0.0937888 - -0.143562 -0.368285 -0.050162 - -0.142568 -0.368054 -0.0474651 - -0.140599 -0.377671 -0.0421797 - -0.135343 -0.367955 -0.0278651 - -0.131164 -0.371894 -0.0165498 - -0.127724 -0.371571 -0.00721593 - -0.125453 -0.372419 -0.00105993 - -0.124698 -0.372678 0.00098753 - -0.12112 -0.374638 0.0106842 - -0.119619 -0.375007 0.0147533 - -0.113317 -0.374279 0.0318529 - -0.0921018 -0.383038 0.089358 - -0.0908164 -0.383441 0.0928428 - -0.0882286 -0.378833 0.09989 - -0.0848991 -0.378096 0.108927 - -0.0829619 -0.377917 0.114183 - -0.0813923 -0.37522 0.118457 - -0.079946 -0.373425 0.122391 - -0.0696172 -0.373454 0.150412 - -0.0597891 -0.376089 0.177059 - -0.0538212 -0.371439 0.193277 - -0.0481768 -0.371994 0.208586 - -0.046069 -0.380402 0.214256 - -0.0429338 -0.417813 0.222545 - -0.0408619 -0.371947 0.228431 - -0.0403005 -0.371971 0.229954 - -0.0363057 -0.379936 0.240745 - -0.0335501 -0.372701 0.248263 - -0.0222787 -0.38408 0.278775 - -0.0142712 -0.388644 0.300473 --0.00435482 -0.389558 0.327369 - -0.0033248 -0.393961 0.330138 - -7.738e-05 -0.394525 0.338945 - 0.016231 -0.392083 0.383202 - 0.0284614 -0.40157 0.416327 - 0.0483209 -0.401791 0.470203 - 0.0554581 -0.399044 0.489581 - 0.0633048 -0.408818 0.510812 - 0.0740253 -0.405303 0.539916 - 0.0960833 -0.424388 0.599647 - 0.0961701 -0.379314 0.600143 - 0.284247 -0.815592 1.10785 - 0.286138 -0.751052 1.11336 - 0.286201 -0.731339 1.11364 - 0.293273 -0.688717 1.13308 - 0.330567 -0.69775 1.2342 - 0.335102 -0.699621 1.24649 - 0.459829 -0.716439 1.58476 - 0.60017 -0.753305 1.96528 - 0.699824 -0.374917 2.23782 - 0.698318 -0.364585 2.2338 - 0.700979 -0.176234 2.24211 - 0.700318 -0.129212 2.24059 - 0.702125 -0.017152 2.24614 - 0.702114 0.00155772 2.24621 - 0.701256 0.179594 2.24492 - 0.69895 0.226079 2.23893 - 0.69884 0.254374 2.23879 - 0.70012 0.340548 2.24276 - 0.701074 0.360205 2.24546 - 0.699581 0.495546 2.2422 - 0.700576 0.525891 2.24507 - 0.699758 0.535234 2.24291 - 0.701757 0.556651 2.24845 - 0.700672 0.616227 2.24586 - 0.700522 0.69808 2.24592 - 0.700674 0.760967 2.2467 - 0.701969 0.794167 2.2504 - 0.700799 0.8143 2.24735 - 0.699244 0.844873 2.2433 - 0.69938 0.888614 2.24392 - 0.700763 0.912351 2.24781 - 0.699707 1.09386 2.246 - 0.700741 1.13114 2.24902 - 0.69823 1.16343 2.2424 - 0.671721 1.21705 2.17079 - 0.639139 1.22014 2.08241 - 0.602701 1.2235 1.98358 - 0.532369 1.23011 1.79281 - 0.438664 1.24154 1.53867 - 0.413917 1.24114 1.47153 - 0.348338 1.2545 1.2937 - 0.0434912 0.352077 0.46146 - 0.0428362 0.359368 0.459725 - 0.0429877 0.443977 0.460625 - 0.0438296 0.463024 0.463019 - 0.0427694 0.488073 0.460288 - 0.0139935 0.414378 0.381796 - 0.00989959 0.398534 0.370597 - 0.00873071 0.417698 0.367537 - 0.00808265 0.524599 0.366397 - 0.00793233 0.542263 0.366092 - 0.00883575 0.584851 0.368789 - 0.00845223 0.615904 0.367928 - 0.0131215 1.30233 0.384565 - 0.00105663 1.29808 0.351809 - -0.0106937 1.30188 0.319954 - -0.0364711 0.423862 0.244945 - -0.0409414 0.297986 0.232089 - -0.0534774 0.326691 0.198246 - -0.0547368 0.33229 0.194862 - -0.0587355 0.330604 0.184004 - -0.0639581 0.370636 0.170067 - -0.0660881 0.319213 0.163991 - -0.0710642 0.317544 0.150482 - -0.0752464 0.322282 0.139164 - -0.0790168 0.34086 0.129042 - -0.0863991 0.387565 0.109285 - -0.212508 1.3166 -0.227465 - -0.222625 1.08406 -0.256254 - -0.221235 1.05255 -0.252665 - -0.221291 0.891962 -0.253747 - -0.218008 0.737465 -0.245735 - -0.216762 0.693171 -0.24261 - -0.218897 0.664594 -0.248567 - -0.218433 0.628432 -0.247518 - -0.219585 0.579309 -0.250928 - -0.220148 0.57107 -0.252501 - -0.157 -0.354637 -0.0966844 - -0.153508 -0.365924 -0.0869808 - -0.142342 -0.373689 -0.0557755 - -0.137836 -0.370387 -0.0431451 - -0.136535 -0.372151 -0.0395128 - -0.13186 -0.377616 -0.0264615 - -0.121031 -0.37674 0.00385158 - -0.11287 -0.374106 0.0267077 - -0.110655 -0.377889 0.0328851 - -0.0989864 -0.371217 0.065581 - -0.0962359 -0.370646 0.0732824 - -0.085009 -0.377856 0.104661 - -0.0785512 -0.381138 0.122715 - -0.0599096 -0.37582 0.17492 - -0.0595651 -0.380038 0.175859 - -0.0471264 -0.380202 0.210671 - -0.0393036 -0.374997 0.232595 - -0.0341559 -0.388752 0.246921 - -0.0267505 -0.387341 0.267655 - -0.023345 -0.38627 0.277193 - -0.0210333 -0.386399 0.283662 --0.00384767 -0.393512 0.331718 --0.00260475 -0.393554 0.335196 --0.00030851 -0.397879 0.341597 - 0.00754469 -0.393584 0.363602 - 0.0189408 -0.39863 0.395467 - 0.0251763 -0.397901 0.412922 - 0.03021 -0.389245 0.427062 - 0.0358468 -0.399539 0.442777 - 0.0515661 -0.405073 0.486738 - 0.0516081 -0.397742 0.486899 - 0.0554607 -0.406914 0.497627 - 0.0585994 -0.397825 0.506465 - 0.0631783 -0.405214 0.519237 - 0.0679951 -0.405594 0.532716 - 0.27206 -0.835753 1.10128 - 0.275496 -0.830342 1.11093 - 0.273583 -0.81098 1.10569 - 0.274852 -0.772405 1.10947 - 0.27166 -0.737919 1.10075 - 0.275381 -0.720514 1.11126 - 0.275624 -0.714616 1.11198 - 0.377054 -0.704226 1.39592 - 0.378368 -0.699326 1.39962 - 0.434149 -0.714014 1.55565 - 0.485582 -0.724503 1.69954 - 0.518197 -0.726158 1.79081 - 0.638869 -0.760617 2.12834 - 0.68002 -0.651021 2.24416 - 0.677401 -0.638537 2.2369 - 0.675887 -0.607064 2.23285 - 0.677455 -0.499485 2.23788 - 0.676135 -0.421021 2.23465 - 0.674846 -0.362898 2.23139 - 0.676664 -0.335258 2.23664 - 0.675693 -0.306391 2.2341 - 0.677039 -0.250336 2.2382 - 0.679584 -0.138476 2.24598 - 0.678134 -0.0263704 2.24259 - 0.677139 -0.01704 2.23987 - 0.679938 0.113658 2.24848 - 0.678647 0.179009 2.24525 - 0.677724 0.197546 2.24278 - 0.676385 0.234739 2.23925 - 0.677907 0.263569 2.24368 - 0.677158 0.358381 2.24215 - 0.678179 0.397366 2.24524 - 0.677612 0.504186 2.24429 - 0.677559 0.533778 2.24431 - 0.677221 0.66432 2.24414 - 0.676221 0.673625 2.2414 - 0.676279 0.756619 2.24206 - 0.674999 1.01755 2.24003 - 0.675518 1.05287 2.24169 - 0.674802 1.19476 2.24053 - 0.641383 1.22211 2.14716 - 0.630877 1.22723 2.11778 - 0.547387 1.22815 1.88412 - 0.37843 1.25107 1.41139 - 0.330337 1.25231 1.2768 - 0.0407021 0.340714 0.460765 - 0.0395696 0.365832 0.457745 - 0.0402511 0.395143 0.459827 - 0.0403541 0.399613 0.460142 - 0.0407575 0.435735 0.461485 - 0.0395063 0.53551 0.458577 - 0.00979709 0.39913 0.374617 - 0.00725642 0.417698 0.367617 - 0.00664595 0.424616 0.36595 - 0.00622488 0.427124 0.364786 - 0.00635481 0.441671 0.365236 - 0.005869 0.626882 0.364977 - 0.00679106 0.698788 0.367985 - 0.0131476 1.29568 0.389324 - 0.00381629 1.30491 0.363263 - -0.0330731 0.794645 0.256986 - -0.0387816 0.337974 0.238295 - -0.0392915 0.320989 0.236766 - -0.0401766 0.293999 0.234129 - -0.0445581 0.297706 0.221888 - -0.049016 0.299835 0.209424 - -0.0570203 0.333261 0.187221 - -0.0646609 0.389316 0.16617 - -0.0742287 0.320375 0.138982 - -0.0754844 0.322331 0.13548 - -0.0799299 0.357 0.123244 - -0.21839 1.29489 -0.258695 - -0.215539 0.981959 -0.252577 - -0.212784 0.917979 -0.245248 - -0.212819 0.665251 -0.246847 - -0.214042 0.652223 -0.250346 - -0.155061 -0.355932 -0.102461 - -0.149196 -0.368883 -0.0855608 - -0.148667 -0.370353 -0.0840373 - -0.144927 -0.373816 -0.0732296 - -0.14439 -0.375229 -0.0716859 - -0.137559 -0.36674 -0.0518568 - -0.13384 -0.375788 -0.0411436 - -0.125548 -0.372243 -0.0171147 - -0.110885 -0.367027 0.0253673 - -0.0992588 -0.375026 0.0589787 - -0.0922433 -0.380497 0.0792561 - -0.0916994 -0.381206 0.0808264 - -0.0827022 -0.379039 0.106888 - -0.0794858 -0.37712 0.116212 - -0.0765193 -0.383111 0.124764 - -0.0726401 -0.379236 0.136018 - -0.0703116 -0.386247 0.142716 - -0.068656 -0.38747 0.147502 - -0.0600709 -0.377514 0.172418 - -0.0581605 -0.372401 0.177981 - -0.0570978 -0.372899 0.181054 - -0.0566555 -0.375117 0.182321 - -0.0543965 -0.373027 0.188874 - -0.0383523 -0.378994 0.235288 - -0.035138 -0.376815 0.244607 - -0.0225248 -0.380678 0.281101 --0.00075036 -0.393989 0.34406 - 0.016385 -0.398455 0.393642 - 0.0208761 -0.396725 0.406655 - 0.0220011 -0.395111 0.409922 - 0.0317174 -0.397946 0.438035 - 0.0531015 -0.401998 0.49992 - 0.0550039 -0.402777 0.505423 - 0.0590471 -0.408649 0.517093 - 0.0718122 -0.407239 0.554059 - 0.0853807 -0.377075 0.593526 - 0.263466 -0.760713 1.10676 - 0.264435 -0.691586 1.10999 - 0.279302 -0.686672 1.15306 - 0.309507 -0.690916 1.24048 - 0.311582 -0.688421 1.24651 - 0.340695 -0.696517 1.33075 - 0.426662 -0.708865 1.57956 - 0.453344 -0.716997 1.65675 - 0.542062 -0.743899 1.91344 - 0.57686 -0.75012 2.01415 - 0.652017 -0.675261 2.2322 - 0.654217 -0.606789 2.23899 - 0.652912 -0.575814 2.2354 - 0.65412 -0.420632 2.23985 - 0.652862 -0.362561 2.23656 - 0.651732 -0.230239 2.2341 - 0.651567 -0.192903 2.23385 - 0.652606 -0.165264 2.23703 - 0.654924 -0.0541589 2.24442 - 0.652079 0.0107854 2.23658 - 0.653129 0.482443 2.24251 - 0.650956 0.510216 2.23639 - 0.650689 0.609043 2.23622 - 0.652427 0.959339 2.2434 - 0.651629 0.969435 2.24115 - 0.653862 1.01798 2.24791 - 0.651089 1.05992 2.24014 - 0.651379 1.17914 2.24171 - 0.618339 1.2294 2.14637 - 0.597537 1.22606 2.08612 - 0.582078 1.23156 2.0414 - 0.53603 1.2302 1.90807 - 0.525389 1.24164 1.87734 - 0.481428 1.24335 1.75007 - 0.455204 1.24627 1.67417 - 0.389586 1.25652 1.48425 - 0.355174 1.25083 1.38459 - 0.315834 1.25186 1.2707 - 0.311813 1.25986 1.25911 - 0.307564 1.26698 1.24685 - 0.0460814 0.355147 0.484234 - 0.0363904 0.479101 0.456937 - 0.0386666 0.540851 0.463905 - 0.0134629 0.404581 0.390101 - 0.0108774 0.394858 0.382556 - 0.00469114 0.427124 0.364844 - 0.00514207 0.459127 0.366345 - 0.00469106 0.477245 0.365151 - 0.00363687 0.498893 0.362231 - 0.00476481 0.540327 0.365751 - 0.00563786 0.561287 0.368407 --0.00885086 1.30902 0.33104 - -0.0144501 1.31025 0.314837 - -0.0283442 1.06121 0.273086 - -0.0425102 0.303922 0.227434 - -0.0438086 0.303806 0.223674 - -0.0441964 0.300759 0.222533 - -0.0521625 0.316922 0.199569 - -0.0550149 0.328934 0.191384 - -0.0582561 0.344663 0.182097 - -0.0657491 0.317572 0.160237 - -0.210674 0.97263 -0.25533 - -0.209331 0.945232 -0.251609 - -0.207652 0.926329 -0.246866 - -0.20912 0.897343 -0.251291 - -0.208964 0.828719 -0.251261 - -0.208915 0.820536 -0.25117 - -0.206146 0.748252 -0.243595 - -0.206003 0.67589 -0.243626 - -0.20666 0.660493 -0.245622 - -0.207829 0.608633 -0.249323 - -0.206764 0.530567 -0.246717 - -0.206829 0.526186 -0.246933 - -0.14796 -0.343903 -0.0926349 - -0.14521 -0.356416 -0.0844776 - -0.145923 -0.365203 -0.0866677 - -0.141598 -0.369388 -0.0737439 - -0.139747 -0.369164 -0.0682001 - -0.135361 -0.369057 -0.0550645 - -0.121728 -0.376503 -0.0142908 - -0.121205 -0.377637 -0.012731 - -0.117193 -0.372925 -0.00068685 - -0.103577 -0.375402 0.0400697 - -0.0981197 -0.374217 0.0564182 - -0.0965585 -0.376623 0.061078 - -0.0936777 -0.374279 0.069719 - -0.0850786 -0.37384 0.0954711 - -0.0828927 -0.375376 0.102007 - -0.0811136 -0.380564 0.107302 - -0.0805862 -0.381138 0.108877 - -0.0785133 -0.37807 0.115104 - -0.0764132 -0.380183 0.121379 - -0.0726291 -0.382638 0.132695 - -0.0682285 -0.384152 0.145863 - -0.0672733 -0.378708 0.148757 - -0.0593215 -0.372586 0.172607 - -0.0588561 -0.373847 0.173993 - -0.0490472 -0.38071 0.203321 - -0.0479727 -0.379972 0.206544 - -0.0435783 -0.418754 0.219457 - -0.0405944 -0.374971 0.228669 - -0.0385282 -0.372994 0.234869 - -0.0305376 -0.383044 0.258733 - -0.0278941 -0.382363 0.266653 - -0.0113324 -0.386171 0.316221 --0.00734419 -0.393434 0.328118 --0.00374594 -0.394525 0.338886 - 4.712e-05 -0.390933 0.350267 - 0.0316594 -0.394108 0.444907 - 0.0427816 -0.397341 0.478192 - 0.0440296 -0.399553 0.481915 - 0.0550548 -0.408337 0.514874 - 0.0663958 -0.403317 0.548865 - 0.0696349 -0.401244 0.558578 - 0.0768299 -0.409319 0.580072 - 0.0773915 -0.407719 0.581763 - 0.082444 -0.410741 0.596874 - 0.0818117 -0.401579 0.595038 - 0.0821418 -0.399189 0.596042 - 0.082826 -0.384386 0.598184 - 0.253964 -0.713786 1.10856 - 0.268148 -0.683212 1.15123 - 0.30397 -0.694365 1.25843 - 0.317998 -0.695362 1.30043 - 0.361142 -0.698178 1.4296 - 0.557819 -0.74938 2.01822 - 0.628236 -0.764253 2.22898 - 0.632494 -0.737956 2.2419 - 0.630153 -0.515194 2.23629 - 0.631334 -0.400234 2.24056 - 0.629311 -0.361043 2.23475 - 0.628172 -0.257197 2.23199 - 0.630226 -0.192721 2.23855 - 0.629223 -0.155353 2.23578 - 0.630735 -0.0261726 2.24112 - 0.630747 -0.00769901 2.24128 - 0.62849 0.0107396 2.23463 - 0.633057 0.112915 2.24895 - 0.629084 0.195701 2.23758 - 0.628483 0.214133 2.2359 - 0.630585 0.252246 2.24243 - 0.627873 0.326316 2.23478 - 0.631528 0.41407 2.24628 - 0.631877 0.73342 2.24934 - 0.628732 1.01152 2.24168 - 0.628381 1.17526 2.24166 - 0.57583 1.233 2.08466 - 0.508089 1.24106 1.88187 - 0.392914 1.24958 1.53704 - 0.338184 1.25634 1.3732 - 0.03624 0.356436 0.463363 - 0.0354532 0.366467 0.46107 - 0.0352404 0.395143 0.460614 - 0.0344117 0.41517 0.458259 - 0.0346501 0.438702 0.459121 - 0.0288655 0.525814 0.44235 - 0.0103619 0.404148 0.386174 - 0.00800452 0.405959 0.379126 - 0.00831321 0.414121 0.380102 - 0.00347666 0.514332 0.366252 - 0.00295681 0.656437 0.365593 --0.00822885 1.30657 0.336203 - -0.0381821 0.345922 0.240444 - -0.0391991 0.315975 0.23721 - -0.0458616 0.299504 0.217155 - -0.0519879 0.317916 0.198927 - -0.0527023 0.324705 0.19683 - -0.0543073 0.330119 0.192059 - -0.0716967 0.316994 0.139904 - -0.139402 0.89518 -0.0591828 - -0.205318 1.06785 -0.255476 - -0.204421 1.0391 -0.25297 - -0.202823 0.838297 -0.249453 - -0.202634 0.782947 -0.249238 - -0.138212 -0.364975 -0.0742145 - -0.137719 -0.366378 -0.0726968 - -0.119407 -0.370128 -0.0159194 - -0.119794 -0.378969 -0.0171767 - -0.116892 -0.372149 -0.00812946 - -0.115545 -0.379854 -0.00400096 - -0.0855007 -0.373764 0.089232 - -0.0838112 -0.379138 0.0944377 - -0.0810488 -0.375036 0.103033 - -0.069943 -0.381088 0.137443 - -0.0672081 -0.388444 0.145878 - -0.0666871 -0.388838 0.147492 - -0.0595784 -0.377229 0.169618 - -0.0522397 -0.373613 0.192405 - -0.0471084 -0.369117 0.208351 - -0.0466139 -0.369225 0.209884 - -0.0438135 -0.386712 0.218457 - -0.0429805 -0.414815 0.220857 - -0.0417736 -0.393912 0.224738 - -0.0361242 -0.378862 0.242359 - -0.0269299 -0.394973 0.270774 - -0.0240089 -0.387837 0.279881 --0.00930434 -0.389987 0.325479 --0.00279326 -0.393475 0.345653 - 0.00064278 -0.39308 0.356314 - 0.00294356 -0.392641 0.363454 - 0.00685056 -0.395452 0.375554 - 0.00779194 -0.393195 0.378489 - 0.0176668 -0.396827 0.409096 - 0.0326617 -0.39704 0.455607 - 0.045867 -0.402796 0.496531 - 0.0533895 -0.399896 0.519884 - 0.0650765 -0.408007 0.556083 - 0.0646246 -0.402693 0.554716 - 0.0720357 -0.405591 0.577685 - 0.0771163 -0.409476 0.593419 - 0.0778904 -0.401579 0.595872 - 0.0798819 -0.391029 0.602118 - 0.242135 -0.694817 1.10343 - 0.24397 -0.686805 1.10917 - 0.338195 -0.700757 1.40136 - 0.363979 -0.703818 1.48132 - 0.372095 -0.703035 1.5065 - 0.425549 -0.712123 1.67225 - 0.538723 -0.749011 2.02306 - 0.574516 -0.755313 2.13405 - 0.605812 -0.670698 2.23167 - 0.604379 -0.609343 2.22763 - 0.607462 -0.552992 2.23756 - 0.606096 -0.542047 2.23339 - 0.607487 -0.523681 2.23783 - 0.603711 -0.41519 2.22682 - 0.606721 -0.3602 2.23652 - 0.607543 -0.294767 2.23949 - 0.606214 0.00153012 2.2373 - 0.608911 0.0846498 2.24621 - 0.607494 0.355066 2.24358 - 0.606452 0.677417 2.24245 - 0.60511 0.864092 2.2395 - 0.604778 0.87443 2.23854 - 0.60666 0.92065 2.24468 - 0.605058 1.04179 2.2405 - 0.604352 1.09864 2.23868 - 0.605622 1.19664 2.24325 - 0.603611 1.22973 2.23724 - 0.563426 1.23561 2.11262 - 0.499539 1.23849 1.91447 - 0.464136 1.24575 1.8047 - 0.385576 1.25764 1.5611 - 0.372395 1.25133 1.52017 - 0.342466 1.25602 1.42736 - 0.30909 1.2629 1.32388 - 0.296415 1.26088 1.28455 - 0.282959 1.26551 1.24284 - 0.269738 1.24673 1.20171 - 0.0464679 0.370702 0.503437 - 0.0332164 0.357489 0.462246 - 0.0317135 0.475381 0.458353 - 0.0307532 0.519873 0.455664 - 0.0268918 0.528581 0.443743 - 0.0026614 0.40606 0.367784 - 0.00188144 0.416414 0.365432 - 0.00164368 0.618467 0.366012 - 0.0133299 1.30035 0.406706 - 0.00942565 1.29098 0.394534 - 0.00443591 1.29904 0.379109 --0.00256091 1.30052 0.357416 --0.00769216 1.30609 0.341535 --0.00930228 1.31255 0.336583 - -0.0219005 1.29527 0.297392 - -0.0258772 1.25085 0.284767 - -0.040614 0.300999 0.232864 - -0.0554283 0.331498 0.18711 - -0.0564609 0.334028 0.183924 - -0.0605322 0.318428 0.171193 - -0.0637198 0.319213 0.161311 - -0.0700985 0.318801 0.141522 - -0.0758117 0.357065 0.12405 - -0.0784189 0.377479 0.116096 - -0.193856 1.3166 -0.235856 - -0.199677 1.26616 -0.254241 - -0.197504 1.14835 -0.248268 - -0.198731 1.11797 -0.252274 - -0.199211 1.08407 -0.253982 - -0.198393 0.999337 -0.251997 - -0.197377 0.860397 -0.249753 - -0.196789 0.840512 -0.248059 - -0.196509 0.784321 -0.247557 - -0.196219 0.657322 -0.247484 - -0.196342 0.64045 -0.247975 - -0.196357 0.62368 -0.248129 - -0.197051 0.589015 -0.250509 - -0.194644 0.526982 -0.243448 - -0.141363 -0.343903 -0.0956729 - -0.140626 -0.350519 -0.0933475 - -0.140373 -0.352723 -0.0925481 - -0.137781 -0.362243 -0.0842698 - -0.127554 -0.37066 -0.0514176 - -0.118386 -0.37027 -0.0219138 - -0.109152 -0.373136 0.0077796 - -0.108355 -0.372461 0.0103478 - -0.10787 -0.373472 0.0119013 - -0.0771522 -0.381318 0.110693 - -0.0725138 -0.377855 0.125642 - -0.0696365 -0.381614 0.134875 - -0.065033 -0.383372 0.149676 - -0.0621419 -0.378306 0.159013 - -0.0607751 -0.381243 0.163392 - -0.0572554 -0.371154 0.174786 - -0.0564217 -0.37463 0.177445 - -0.0544769 -0.375574 0.183696 - -0.0540267 -0.376784 0.185137 - -0.0378 -0.383963 0.237303 - -0.0328322 -0.383366 0.253292 - -0.0295863 -0.374545 0.263796 - -0.0247583 -0.384861 0.279263 - -0.0178638 -0.389316 0.301418 --0.00462827 -0.393989 0.343976 - 0.00376606 -0.392996 0.370994 - 0.00655679 -0.396922 0.379947 - 0.0182179 -0.392689 0.417499 - 0.0214328 -0.392796 0.427843 - 0.0371622 -0.400147 0.478408 - 0.0498842 -0.40201 0.519332 - 0.0624347 -0.408052 0.559677 - 0.0719109 -0.412028 0.590142 - 0.0737018 -0.393921 0.596027 - 0.0747855 -0.37751 0.599625 - 0.0770421 -0.378303 0.606881 - 0.23367 -0.810379 1.10797 - 0.232182 -0.705834 1.10388 - 0.263974 -0.687065 1.20631 - 0.311305 -0.700636 1.35852 - 0.320419 -0.697619 1.38787 - 0.325822 -0.693916 1.40528 - 0.424807 -0.710477 1.72368 - 0.499274 -0.740076 1.96311 - 0.581656 -0.697819 2.22848 - 0.583666 -0.64968 2.23527 - 0.580669 -0.548167 2.22631 - 0.583344 -0.511639 2.23517 - 0.58407 -0.368865 2.23846 - 0.581955 -0.22786 2.23261 - 0.583246 -0.117699 2.2375 - 0.584309 -0.016832 2.2416 - 0.583847 0.176336 2.24142 - 0.583567 0.468172 2.24248 - 0.583122 0.736738 2.24286 - 0.583105 0.757448 2.24295 - 0.581039 0.817734 2.23671 - 0.5831 0.884776 2.24379 - 0.582685 0.927845 2.24275 - 0.583053 1.06376 2.24485 - 0.569645 1.22911 2.20282 - 0.503935 1.24386 1.99147 - 0.488335 1.24275 1.94127 - 0.335695 1.25415 1.45018 - 0.330328 1.25815 1.43293 - 0.315117 1.26068 1.38401 - 0.269368 1.26551 1.23683 - 0.256254 1.24494 1.19449 - 0.208995 1.08492 1.04134 - 0.0311218 0.356436 0.46407 - 0.0313448 0.375062 0.464913 - 0.0294817 0.437823 0.459341 - 0.0291063 0.496593 0.458529 - 0.0281441 0.518961 0.455583 - 0.0263543 0.536819 0.449945 - 0.00014089 0.64605 0.366331 - 0.00282177 1.30103 0.379372 - -0.0391365 0.317955 0.237733 - -0.0450325 0.300642 0.218644 - -0.0454217 0.300575 0.217391 - -0.0488306 0.296729 0.206396 - -0.0517482 0.323877 0.19719 - -0.0527773 0.328503 0.19391 - -0.0550781 0.331498 0.186527 - -0.0556907 0.335239 0.184581 - -0.0653075 0.319428 0.15353 - -0.0660306 0.322931 0.151226 - -0.178498 1.30817 -0.204032 - -0.192429 1.31225 -0.248833 - -0.194263 1.29477 -0.254851 - -0.190982 1.01579 -0.246175 - -0.1934 0.999337 -0.254065 - -0.190896 0.827188 -0.247168 - -0.191563 0.784321 -0.249605 - -0.189978 0.700589 -0.245066 - -0.190279 0.635741 -0.246474 - -0.191216 0.622903 -0.249575 - -0.190911 0.610759 -0.248675 - -0.189625 0.554765 -0.244913 - -0.191047 0.550378 -0.249521 - -0.13689 -0.339657 -0.093051 - -0.133069 -0.346941 -0.0803436 - -0.131173 -0.358339 -0.0740926 - -0.130344 -0.35823 -0.0713233 - -0.125391 -0.370138 -0.054868 - -0.118491 -0.376003 -0.0318702 - -0.111164 -0.377931 -0.00742018 - -0.0972856 -0.375405 0.0389384 - -0.0957353 -0.377121 0.0441029 - -0.0939581 -0.381379 0.0500073 - -0.0917801 -0.378425 0.0573002 - -0.0874931 -0.38089 0.0715974 - -0.0801203 -0.379454 0.0962251 - -0.0736799 -0.378712 0.117735 - -0.0732045 -0.379228 0.119319 - -0.0707413 -0.380738 0.127533 - -0.0676566 -0.380553 0.137834 - -0.0541726 -0.377556 0.182878 - -0.0488175 -0.373596 0.200786 - -0.0479424 -0.376855 0.203685 - -0.0464925 -0.375212 0.208538 - -0.0446236 -0.376578 0.214769 - -0.0419874 -0.423905 0.223241 - -0.0307772 -0.382794 0.260959 - -0.0261466 -0.377133 0.27646 - -0.0227429 -0.38864 0.287745 - -0.0196151 -0.381757 0.298236 - -0.0161535 -0.3896 0.30974 --0.00278468 -0.392693 0.354357 - 0.00023837 -0.395472 0.364432 - 0.00121598 -0.388929 0.367741 - 0.00741204 -0.389049 0.388429 - 0.00789725 -0.388332 0.390054 - 0.0130981 -0.396725 0.407362 - 0.0166941 -0.396275 0.419372 - 0.0169282 -0.393628 0.420172 - 0.0184808 -0.387476 0.425399 - 0.0244614 -0.401288 0.445272 - 0.0323757 -0.400096 0.471706 - 0.0371044 -0.402572 0.487478 - 0.0385723 -0.40639 0.492353 - 0.0395822 -0.404002 0.495741 - 0.0493691 -0.406531 0.528402 - 0.0495219 -0.403591 0.528933 - 0.0702078 -0.40928 0.597964 - 0.0721604 -0.378617 0.604697 - 0.223447 -0.793166 1.10696 - 0.222431 -0.723322 1.10405 - 0.260042 -0.688611 1.22987 - 0.26258 -0.687892 1.23835 - 0.281559 -0.690106 1.30171 - 0.322836 -0.697693 1.43948 - 0.435668 -0.717742 1.81609 - 0.449341 -0.720834 1.86172 - 0.462698 -0.731546 1.90624 - 0.473698 -0.738428 1.94292 - 0.560118 -0.656727 2.23205 - 0.561275 -0.472095 2.2372 - 0.561562 -0.46274 2.23823 - 0.56062 -0.423931 2.23535 - 0.559777 -0.181334 2.23423 - 0.558963 -0.135306 2.23183 - 0.559109 -0.126196 2.23238 - 0.559561 0.0288894 2.23497 - 0.559034 0.0836101 2.23359 - 0.560385 0.138803 2.23849 - 0.560764 0.203374 2.2402 - 0.561337 0.222079 2.24225 - 0.563697 0.269577 2.25046 - 0.559348 0.304863 2.23618 - 0.56162 0.343585 2.24404 - 0.560226 0.371045 2.23958 - 0.561777 0.477129 2.24549 - 0.562894 0.69644 2.25075 - 0.560152 0.765254 2.24208 - 0.559383 0.85916 2.24017 - 0.561698 1.10969 2.24964 - 0.556439 1.21964 2.23285 - 0.493991 1.2399 2.02447 - 0.475171 1.24231 1.96165 - 0.464529 1.23963 1.9261 - 0.429818 1.24274 1.81022 - 0.310027 1.26373 1.41038 - 0.271793 1.26267 1.28271 - 0.0319222 0.366638 0.475537 - 0.0298793 0.363052 0.46869 - 0.0274811 0.465129 0.461394 - 0.0265299 0.49015 0.458393 - 0.0277977 0.535378 0.462941 - 0.00411402 0.416249 0.383031 --0.00060907 0.404172 0.367176 --0.00120143 0.44896 0.365511 --0.00074923 0.476635 0.367213 --0.00135347 0.58255 0.365934 - 0.0177842 1.30101 0.434843 - 0.0108634 1.2946 0.41169 - 0.0092407 1.2954 0.406277 - 0.00765367 1.29717 0.400991 - 0.00270805 1.29737 0.384479 --0.00876059 1.29861 0.346193 - -0.0103875 1.29912 0.340765 - -0.0168649 1.30288 0.319163 - -0.0393549 0.304957 0.237112 - -0.0430955 0.296892 0.224566 - -0.0625487 0.320186 0.159774 - -0.130212 0.916804 -0.0619965 - -0.1889 1.30723 -0.255233 - -0.189888 1.29942 -0.258587 - -0.187689 1.20402 -0.25191 - -0.186153 1.12329 -0.247342 - -0.187428 1.01359 -0.252363 - -0.18677 0.947035 -0.250632 - -0.18696 0.90092 -0.251587 - -0.186577 0.776241 -0.251179 - -0.186105 0.759303 -0.249719 - -0.185246 0.713936 -0.247169 - -0.185019 0.6395 -0.246929 - -0.182224 0.564165 -0.238121 - -0.185501 0.543033 -0.249212 - -0.126214 -0.366742 -0.0691302 - -0.121787 -0.367028 -0.0537601 - -0.10735 -0.384764 -0.00375921 - -0.102557 -0.379033 0.0129236 - -0.0956237 -0.377168 0.0370103 - -0.09382 -0.385056 0.0432162 - -0.0908178 -0.371531 0.0537383 - -0.0811952 -0.377205 0.0871085 - -0.0806386 -0.376926 0.0890431 - -0.0785222 -0.376644 0.0963939 - -0.0748044 -0.369789 0.109352 - -0.0659271 -0.382365 0.140085 - -0.05948 -0.379277 0.162493 - -0.0544881 -0.384262 0.17979 - -0.0510066 -0.377771 0.191925 - -0.0414451 -0.400943 0.224957 - -0.0391005 -0.377994 0.233264 - -0.0208016 -0.384025 0.296757 - -0.0171016 -0.3896 0.309564 - -0.0163453 -0.385945 0.312216 - -0.0158182 -0.38655 0.314042 - -0.0124094 -0.392898 0.325832 --0.00588005 -0.391469 0.348514 --0.00166239 -0.386383 0.363195 - 0.00300907 -0.395059 0.379353 - 0.0123065 -0.401357 0.411589 - 0.0163812 -0.383937 0.425863 - 0.0495296 -0.400626 0.54084 - 0.0578187 -0.404268 0.569595 - 0.0641619 -0.412028 0.591564 - 0.0657865 -0.41481 0.597185 - 0.0671374 -0.372056 0.602184 - 0.215684 -0.770676 1.11508 - 0.214105 -0.707057 1.11006 - 0.229139 -0.683789 1.16243 - 0.239266 -0.683639 1.1976 - 0.282194 -0.689401 1.34661 - 0.293541 -0.692626 1.38598 - 0.440232 -0.724597 1.89509 - 0.490761 -0.742693 2.07041 - 0.514936 -0.746588 2.15432 - 0.536348 -0.744609 2.22868 - 0.537224 -0.735532 2.23179 - 0.537294 -0.585883 2.23311 - 0.537654 -0.537553 2.23471 - 0.53643 -0.272592 2.23238 - 0.536367 -0.198996 2.23269 - 0.537089 -0.0622181 2.23618 - 0.538566 -0.0441171 2.24144 - 0.539307 0.0655307 2.24481 - 0.538084 0.129416 2.24102 - 0.536899 0.211711 2.2375 - 0.536881 0.230137 2.23757 - 0.536768 0.257807 2.23738 - 0.537555 0.295313 2.24039 - 0.537063 0.332376 2.23894 - 0.538749 0.399377 2.24528 - 0.539376 0.544348 2.24851 - 0.537091 0.783882 2.2423 - 0.536379 0.793357 2.2399 - 0.537254 0.826147 2.24318 - 0.538245 0.85954 2.24686 - 0.536722 0.90035 2.24187 - 0.535612 0.909467 2.23808 - 0.53739 0.934167 2.24443 - 0.538089 0.95739 2.24702 - 0.536788 1.10316 2.24356 - 0.531883 1.2373 2.2275 - 0.473134 1.2475 2.02359 - 0.443597 1.24387 1.921 - 0.419559 1.24932 1.83758 - 0.389314 1.24367 1.73252 - 0.371231 1.25709 1.66983 - 0.326267 1.25622 1.5137 - 0.237909 1.25427 1.20689 - 0.0297893 0.362774 0.477815 - 0.0255127 0.389636 0.46316 - 0.0237096 0.542153 0.458002 --0.00341872 0.522304 0.363663 --0.00336253 0.542868 0.364007 --0.00323199 0.669767 0.365377 - -0.0010052 0.800476 0.374054 - -0.0195987 1.29628 0.313077 - -0.0399035 0.303976 0.235404 - -0.0587516 0.32165 0.170087 - -0.0652072 0.320245 0.147662 - -0.067131 0.318259 0.140968 - -0.166443 1.31212 -0.19668 - -0.182432 1.29419 -0.252326 - -0.183886 1.29105 -0.257397 - -0.181773 1.12786 -0.251239 - -0.180545 0.735299 -0.249814 - -0.177987 0.652925 -0.241527 - -0.180146 0.634171 -0.249157 - -0.180205 0.596383 -0.249636 - -0.180198 0.59114 -0.249649 - -0.179014 0.537162 -0.245928 - -0.179256 0.519739 -0.246894 - -0.128825 -0.346244 -0.090782 - -0.124702 -0.351094 -0.0759109 - -0.123461 -0.355232 -0.0714574 - -0.118195 -0.370387 -0.0525329 - -0.112209 -0.371161 -0.0308983 - -0.11103 -0.371894 -0.0266419 - -0.110158 -0.374213 -0.0235054 - -0.106336 -0.377931 -0.00971748 - -0.0979292 -0.378611 0.020669 - -0.0955702 -0.374452 0.0292284 - -0.0886494 -0.376727 0.0542309 - -0.0875496 -0.380905 0.0581755 - -0.0749049 -0.383976 0.103865 - -0.074122 -0.380759 0.106719 - -0.070251 -0.381196 0.120711 - -0.0653987 -0.380008 0.138261 - -0.0570141 -0.3785 0.168584 - -0.0480257 -0.376724 0.201092 - -0.0457608 -0.37232 0.209313 - -0.0415077 -0.405942 0.224436 - -0.0318658 -0.372825 0.259542 - -0.028049 -0.382493 0.273267 - -0.023504 -0.393323 0.289617 - -0.0230471 -0.393054 0.291271 - -0.0164215 -0.385196 0.315282 - -0.0139162 -0.394294 0.324271 --0.00226287 -0.395807 0.366388 --0.00026521 -0.389843 0.373655 - 0.00108805 -0.387872 0.378562 - 0.00194062 -0.390915 0.381621 - 0.0124793 -0.396275 0.41968 - 0.024632 -0.400978 0.463579 - 0.028121 -0.398739 0.476209 - 0.0332938 -0.401523 0.494888 - 0.0339106 -0.401148 0.497121 - 0.0345279 -0.400761 0.499356 - 0.035919 -0.404454 0.504357 - 0.0455107 -0.401245 0.539056 - 0.045974 -0.399847 0.540742 - 0.0602726 -0.391248 0.592498 - 0.0607236 -0.389608 0.594141 - 0.069413 -0.387934 0.625567 - 0.203628 -0.803758 1.10766 - 0.203442 -0.748638 1.1074 - 0.20454 -0.719341 1.11159 - 0.203432 -0.703388 1.1077 - 0.208557 -0.674101 1.12645 - 0.241351 -0.682212 1.24494 - 0.264906 -0.684171 1.33008 - 0.306927 -0.696256 1.4819 - 0.511355 -0.73955 2.22062 - 0.515472 -0.674307 2.23599 - 0.514362 -0.478085 2.23345 - 0.514897 -0.459504 2.23552 - 0.514682 -0.309331 2.23587 - 0.514408 -0.263002 2.23523 - 0.514699 -0.244729 2.23642 - 0.516199 -0.144414 2.24259 - 0.514083 -0.125653 2.23508 - 0.514053 -0.107453 2.23511 - 0.514725 -0.0620989 2.23788 - 0.514049 0.00151123 2.23592 - 0.51478 0.0833702 2.23917 - 0.513139 0.284427 2.23475 - 0.514684 0.331747 2.24069 - 0.514276 0.340841 2.23928 - 0.51587 0.369999 2.24526 - 0.514031 0.444365 2.23917 - 0.515051 0.454727 2.24294 - 0.515102 0.741567 2.24527 - 0.515629 0.847006 2.24797 - 0.511671 1.22721 2.23652 - 0.510221 1.23628 2.23134 - 0.440681 1.24854 1.98003 - 0.41052 1.2489 1.871 - 0.406705 1.24976 1.85722 - 0.380203 1.25296 1.76143 - 0.339966 1.25018 1.61595 - 0.31806 1.25337 1.53678 - 0.0227307 0.380751 0.46257 - 0.0215039 0.448859 0.458645 - 0.0239386 0.47669 0.467656 - 0.0211469 0.487447 0.457644 - 0.0110912 0.482349 0.421253 - 0.00040861 0.40274 0.382037 --0.00463926 0.411672 0.363855 --0.00473684 0.443228 0.363739 --0.00425671 0.48746 0.365806 --0.00428822 0.596782 0.366513 - 0.00584769 1.03221 0.406422 - -0.0113795 1.30061 0.346156 - -0.0337374 0.708346 0.260886 - -0.0377354 0.381776 0.243983 - -0.0514154 0.324705 0.1941 - -0.0546327 0.337217 0.182563 - -0.0623009 0.44409 0.155643 - -0.0616784 0.314658 0.156922 - -0.0627727 0.31362 0.152958 - -0.0628569 0.309395 0.152622 - -0.0654808 0.323318 0.143241 - -0.172357 1.31217 -0.235714 - -0.173713 0.945194 -0.243369 - -0.175835 0.930736 -0.251149 - -0.175204 0.880436 -0.249246 - -0.173685 0.804532 -0.244324 - -0.175829 0.779277 -0.252266 - -0.174078 0.754805 -0.246118 - -0.17649 0.740256 -0.254948 - -0.175818 0.72981 -0.252597 - -0.174664 0.716935 -0.248519 - -0.172744 0.668991 -0.241938 - -0.173481 0.660674 -0.244665 - -0.174841 0.655542 -0.249622 - -0.123294 -0.346212 -0.0837539 - -0.115709 -0.3691 -0.0553318 - -0.115293 -0.370387 -0.0537731 - -0.114232 -0.37864 -0.0498373 - -0.0988378 -0.379747 0.00820039 - -0.0906443 -0.377148 0.0391147 - -0.0908028 -0.382445 0.0384759 - -0.0805365 -0.379139 0.0772116 - -0.0782161 -0.380649 0.0859491 - -0.077425 -0.377569 0.0889561 - -0.0542699 -0.377844 0.176262 - -0.0507698 -0.3756 0.189477 - -0.0499038 -0.374963 0.192748 - -0.0342199 -0.382367 0.251827 - -0.0314706 -0.389633 0.262137 - -0.0309322 -0.376388 0.26427 - -0.0171982 -0.389097 0.315957 --0.00677467 -0.390232 0.35525 --0.00607398 -0.387198 0.357916 --0.00503831 -0.387921 0.361816 --0.00294993 -0.389244 0.36968 --0.00251612 -0.388612 0.37132 - 0.00945823 -0.393531 0.416432 - 0.0132317 -0.392783 0.430666 - 0.0346945 -0.40314 0.511513 - 0.0362949 -0.393511 0.517622 - 0.043726 -0.394834 0.545631 - 0.0486032 -0.399743 0.563983 - 0.0592526 -0.382702 0.604271 - 0.0596765 -0.381012 0.605882 - 0.192588 -0.812336 1.10367 - 0.194313 -0.762969 1.11056 - 0.191228 -0.682722 1.09955 - 0.192731 -0.67485 1.10528 - 0.212758 -0.681001 1.18075 - 0.269015 -0.693125 1.39278 - 0.32199 -0.70129 1.59246 - 0.325067 -0.699552 1.60407 - 0.464872 -0.74329 2.13088 - 0.493051 -0.545375 2.23867 - 0.490913 -0.438436 2.23145 - 0.493228 -0.402622 2.24046 - 0.492479 0.0650617 2.24128 - 0.492383 0.0741367 2.24099 - 0.492404 0.165255 2.24178 - 0.491952 0.247634 2.24072 - 0.490099 0.292794 2.23408 - 0.491415 0.312057 2.2392 - 0.492101 0.540079 2.24356 - 0.49302 0.792647 2.249 - 0.492111 0.801749 2.24564 - 0.490851 0.994269 2.24239 - 0.489489 1.01414 2.23741 - 0.489624 1.21359 2.23948 - 0.48099 1.24239 2.20715 - 0.477187 1.24554 2.19283 - 0.331153 1.25958 1.64231 - 0.263415 1.26157 1.38691 - 0.186795 1.13779 1.09704 - 0.0297834 0.371983 0.499042 - 0.0215617 0.364125 0.467981 - 0.0194924 0.372951 0.460247 - 0.0200931 0.387934 0.462629 - 0.0196125 0.392577 0.460853 - 0.0189254 0.399966 0.45832 - 0.0193949 0.456982 0.460535 - 0.0188902 0.506797 0.45902 - 0.00323749 0.432194 0.399418 --0.00432595 0.409211 0.370721 - -0.0053936 0.493229 0.36735 --0.00632438 0.514938 0.36401 --0.00563822 0.588385 0.36717 --0.00609068 0.630787 0.365795 --0.00570738 0.681517 0.367636 --0.00547374 0.754624 0.369088 - 0.0122515 1.29613 0.440147 - 0.0107994 1.29706 0.434679 - 0.00232704 1.31005 0.402835 --0.00677147 1.30331 0.368475 --0.00820608 1.30491 0.363078 - -0.0408987 0.301997 0.231983 - -0.0425546 0.29695 0.225701 - -0.0441414 0.290767 0.219669 - -0.0540105 0.341393 0.182852 - -0.0544318 0.342162 0.181269 - -0.0648043 0.320033 0.141986 - -0.0736629 0.398561 0.109197 - -0.171225 1.12329 -0.253015 - -0.169289 1.06943 -0.246137 - -0.170647 1.02246 -0.251623 - -0.170336 0.97707 -0.250804 - -0.170026 0.934678 -0.249967 - -0.170738 0.920635 -0.25276 - -0.169829 0.81135 -0.250184 - -0.167331 0.631404 -0.242169 - -0.169211 0.586563 -0.24961 - -0.167738 0.540741 -0.244412 - -0.124721 -0.350455 -0.103128 - -0.120706 -0.342638 -0.0872645 - -0.116176 -0.349986 -0.069494 - -0.115052 -0.360467 -0.0651565 - -0.113481 -0.365729 -0.0590169 - -0.112534 -0.367539 -0.0553074 - -0.110983 -0.366166 -0.04919 - -0.0925857 -0.374348 0.0231415 - -0.0807735 -0.377228 0.0696033 - -0.0772591 -0.385302 0.0833677 - -0.0681386 -0.374954 0.119344 - -0.061668 -0.382991 0.144742 - -0.0612555 -0.383372 0.146363 - -0.058623 -0.373406 0.156804 - -0.0573719 -0.373382 0.161727 - -0.0518055 -0.379972 0.183579 - -0.0492143 -0.37513 0.193816 - -0.0488537 -0.377281 0.195217 - -0.048042 -0.377581 0.198409 - -0.0456036 -0.378309 0.207999 - -0.0451968 -0.378405 0.209599 - -0.0415962 -0.407942 0.223529 - -0.0382428 -0.383936 0.236921 - -0.0378528 -0.380902 0.23848 - -0.0365396 -0.388752 0.243584 - -0.0353428 -0.384542 0.248328 - -0.0328461 -0.384917 0.25815 - -0.0290127 -0.38746 0.273216 - -0.0182517 -0.388122 0.315558 - -0.0134428 -0.393554 0.334439 - 0.00085366 -0.398995 0.390656 - 0.00424655 -0.392972 0.404057 - 0.00508637 -0.391391 0.407375 - 0.00838962 -0.397171 0.420327 - 0.00792002 -0.389155 0.418544 - 0.00867432 -0.390981 0.421498 - 0.00875125 -0.387443 0.421829 - 0.0147054 -0.399539 0.445162 - 0.0161071 -0.397469 0.450695 - 0.0199342 -0.399921 0.465737 - 0.0249599 -0.401225 0.485503 - 0.0270778 -0.402714 0.493826 - 0.0313695 -0.401518 0.510725 - 0.0347141 -0.405214 0.523857 - 0.0355769 -0.402554 0.527274 - 0.0370674 -0.406762 0.533106 - 0.044757 -0.402004 0.563405 - 0.0528394 -0.410389 0.595144 - 0.0534636 -0.402513 0.597665 - 0.183256 -0.783989 1.10534 - 0.183584 -0.706121 1.10727 - 0.213955 -0.67979 1.227 - 0.248071 -0.686358 1.3612 - 0.261491 -0.689981 1.41399 - 0.276982 -0.696195 1.4749 - 0.288001 -0.690732 1.51831 - 0.292316 -0.685 1.53533 - 0.352723 -0.707377 1.77287 - 0.400083 -0.728358 1.95908 - 0.407492 -0.731411 1.98821 - 0.415603 -0.735325 2.0201 - 0.456021 -0.740266 2.17912 - 0.469949 -0.495267 2.23592 - 0.469039 -0.456484 2.23265 - 0.470854 -0.420355 2.24009 - 0.468777 -0.372002 2.2323 - 0.468767 -0.334933 2.23257 - 0.471383 -0.318102 2.243 - 0.472602 -0.281809 2.24809 - 0.470436 -0.216435 2.2401 - 0.468862 -0.00752445 2.2356 - 0.469401 0.0919718 2.23853 - 0.468944 0.137216 2.2371 - 0.469931 0.247161 2.24188 - 0.469038 0.274305 2.23858 - 0.46977 0.339549 2.24199 - 0.47018 0.471815 2.24468 - 0.47013 0.48133 2.24456 - 0.469155 0.596608 2.24166 - 0.469282 0.74729 2.24338 - 0.46961 0.758057 2.24476 - 0.469595 0.789098 2.24495 - 0.469362 1.00464 2.24579 - 0.467961 1.04708 2.24062 - 0.46705 1.12617 2.23768 - 0.468248 1.17643 2.2428 - 0.445602 1.24198 2.15421 - 0.356609 1.25867 1.80413 - 0.348098 1.2542 1.7706 - 0.325279 1.25709 1.68082 - 0.314051 1.26265 1.63668 - 0.308736 1.26598 1.61579 - 0.299803 1.25563 1.58056 - 0.287757 1.26582 1.53323 - 0.275049 1.26045 1.48318 - 0.255665 1.26935 1.40697 - 0.223398 1.26914 1.27999 - 0.219546 1.27317 1.26486 - 0.210304 1.26146 1.22839 - 0.021991 0.358091 0.479986 - 0.0212655 0.36746 0.477207 - 0.0164061 0.420713 0.458516 - 0.0172718 0.455057 0.462202 - 0.0171129 0.468842 0.461689 - 0.0158147 0.49581 0.456799 - 0.0153815 0.49773 0.45511 - 0.0020033 0.438686 0.401983 --0.00718556 0.458171 0.36598 --0.00698658 0.603597 0.367944 --0.00416883 1.29936 0.384683 - -0.0139474 1.30459 0.346243 - -0.0167908 1.30358 0.335045 - -0.0225551 1.29428 0.312285 - -0.0378058 0.383714 0.244874 - -0.0413309 0.294999 0.230282 - -0.0426116 0.29695 0.225258 - -0.0451173 0.293585 0.215369 - -0.0478256 0.300831 0.20477 - -0.0589315 0.390612 0.161794 - -0.0633701 0.321787 0.143768 - -0.0647467 0.320176 0.138337 - -0.165546 1.30789 -0.250319 - -0.165491 1.1696 -0.251226 - -0.164476 0.824233 -0.250036 - -0.162706 0.738466 -0.243766 - -0.163138 0.694604 -0.245825 - -0.163371 0.587197 -0.247613 - -0.163514 0.58275 -0.248213 - -0.162734 0.549487 -0.245411 - -0.113272 -0.353589 -0.0711163 - -0.109058 -0.370881 -0.0539325 - -0.106135 -0.371568 -0.041914 - -0.0948148 -0.37874 0.00458777 - -0.0894323 -0.381527 0.0267035 - -0.0874457 -0.385995 0.0348371 - -0.0813496 -0.37973 0.0599645 - -0.0714029 -0.375267 0.100915 - -0.06871 -0.373853 0.112003 - -0.0682289 -0.384959 0.113889 - -0.0516741 -0.374801 0.182067 - -0.0481859 -0.376439 0.196402 - -0.045867 -0.378206 0.205924 - -0.0427696 -0.383829 0.218617 - -0.0407908 -0.380987 0.226781 - -0.0400159 -0.375999 0.23001 - -0.0352524 -0.383458 0.24954 - -0.0190229 -0.392022 0.316223 - -0.018217 -0.391231 0.319544 - -0.0120669 -0.392518 0.34483 - -0.0112608 -0.391469 0.348154 --0.00980745 -0.387384 0.354167 --0.00628971 -0.391747 0.368599 --0.00548585 -0.390485 0.371917 --0.00410992 -0.3904 0.377577 --0.00277205 -0.394629 0.383044 - 0.00652873 -0.398964 0.421263 - 0.0129559 -0.395848 0.447726 - 0.0162384 -0.395838 0.461227 - 0.0176744 -0.398005 0.467116 - 0.0252025 -0.397476 0.498085 - 0.0269746 -0.397082 0.505377 - 0.0387831 -0.393585 0.553977 - 0.0494169 -0.384879 0.59779 - 0.0502972 -0.375409 0.601491 - 0.051404 -0.373444 0.60606 - 0.0665959 -0.4238 0.668121 - 0.173323 -0.767642 1.1042 - 0.177414 -0.672242 1.12184 - 0.215764 -0.68064 1.27951 - 0.226211 -0.681369 1.32247 - 0.260016 -0.687141 1.46147 - 0.356028 -0.709132 1.8562 - 0.40549 -0.730755 2.05946 - 0.442922 -0.741383 2.21334 - 0.446563 -0.686738 2.22878 - 0.446405 -0.61755 2.22871 - 0.446874 -0.569591 2.23105 - 0.447788 -0.381193 2.2364 - 0.44978 -0.23486 2.24584 - 0.448133 -0.179432 2.23953 - 0.448632 -0.0889181 2.24235 - 0.447201 -0.0525809 2.23677 - 0.446328 -0.016496 2.23349 - 0.448142 0.0195678 2.24125 - 0.448099 0.0285992 2.24115 - 0.446334 0.0465025 2.23404 - 0.449407 0.164939 2.24769 - 0.447528 0.595779 2.2436 - 0.446539 0.724184 2.24062 - 0.445421 0.846643 2.23706 - 0.447485 1.03669 2.24716 - 0.446308 1.09151 2.24278 - 0.446764 1.1276 2.24496 - 0.444797 1.14662 2.23703 - 0.400191 1.24432 2.05439 - 0.398498 1.25139 2.04748 - 0.392376 1.25752 2.02236 - 0.374986 1.25311 1.95079 - 0.370809 1.25211 1.9336 - 0.369309 1.25916 1.92749 - 0.348219 1.25057 1.84067 - 0.34001 1.25806 1.80697 - 0.333322 1.25854 1.77946 - 0.311401 1.2616 1.68932 - 0.294274 1.26598 1.61891 - 0.28797 1.26434 1.59297 - 0.258332 1.26745 1.47109 - 0.248117 1.26803 1.42908 - 0.196498 1.26649 1.21675 - 0.194455 1.26699 1.20835 - 0.155185 1.10466 1.04544 - 0.149401 1.08194 1.02146 - 0.017976 0.374078 0.474893 - 0.0134521 0.514297 0.457472 - 0.00081211 0.446105 0.404904 --0.00752914 0.408268 0.370274 --0.00776839 0.449634 0.36964 --0.00888807 0.694868 0.367111 - -0.0063295 0.849337 0.378943 - 0.00091715 1.29856 0.412553 - -0.0426886 0.30095 0.224748 - -0.0472688 0.296958 0.205875 - -0.0515469 0.323179 0.1885 - -0.0578254 0.318526 0.162636 - -0.0635687 0.320588 0.13903 - -0.15931 1.21425 -0.247206 - -0.15986 1.19052 -0.249673 - -0.160068 0.9837 -0.252277 - -0.158962 0.852675 -0.248837 - -0.158078 0.760783 -0.24598 - -0.158003 0.718776 -0.246027 - -0.112771 -0.34111 -0.0827497 - -0.111746 -0.345275 -0.0783757 - -0.109953 -0.354937 -0.0707479 - -0.107002 -0.368319 -0.0581678 - -0.103899 -0.377594 -0.044894 - -0.0911454 -0.379161 0.00997509 - -0.0832416 -0.369969 0.044069 - -0.0828742 -0.370795 0.0456428 - -0.0824343 -0.375113 0.0474977 - -0.0809399 -0.378313 0.0539006 - -0.0807536 -0.380905 0.0546793 - -0.0782248 -0.378329 0.0655845 - -0.0762551 -0.380984 0.0740373 - -0.0755385 -0.37798 0.0771478 - -0.0746574 -0.38278 0.080897 - -0.0711558 -0.382216 0.0959707 - -0.0689998 -0.376023 0.105303 - -0.0657515 -0.382651 0.119223 - -0.060716 -0.37929 0.140923 - -0.0592585 -0.381792 0.147173 - -0.0587886 -0.380202 0.149209 - -0.0580356 -0.380905 0.152443 - -0.0569447 -0.382888 0.15712 - -0.0499666 -0.382556 0.187152 - -0.0492099 -0.382919 0.190405 - -0.0445513 -0.373501 0.210536 - -0.0300152 -0.390441 0.272941 - -0.0237984 -0.397499 0.299632 - -0.022127 -0.381769 0.306963 - -0.019773 -0.388708 0.317032 - -0.0188977 -0.389851 0.320788 - -0.017747 -0.388589 0.325752 - -0.0173643 -0.388153 0.327403 - -0.0150132 -0.3926 0.33748 - -0.0130174 -0.391041 0.346083 - 0.00425655 -0.392733 0.420404 - 0.0047133 -0.388334 0.422409 - 0.0140539 -0.39394 0.462555 - 0.0210583 -0.403897 0.49261 - 0.0271016 -0.397205 0.518675 - 0.028572 -0.398576 0.524991 - 0.0330441 -0.402185 0.544204 - 0.0371995 -0.395958 0.562141 - 0.0400244 -0.399684 0.574265 - 0.0439601 -0.40833 0.591125 - 0.16592 -0.733756 1.11309 - 0.164134 -0.714614 1.10557 - 0.175851 -0.671681 1.15637 - 0.205558 -0.682239 1.28412 - 0.206992 -0.679624 1.29031 - 0.216935 -0.68655 1.33304 - 0.231055 -0.68913 1.39378 - 0.254528 -0.689647 1.49479 - 0.259825 -0.694666 1.51754 - 0.366213 -0.73176 1.97504 - 0.420923 -0.738653 2.21042 - 0.424653 -0.567459 2.22798 - 0.425583 -0.539789 2.23223 - 0.426693 -0.502871 2.23733 - 0.426083 -0.445561 2.23521 - 0.426605 -0.20629 2.23957 - 0.427583 -0.134077 2.24442 - 0.423813 -0.0791483 2.22868 - 0.426394 0.0285302 2.24074 - 0.426748 0.31072 2.24475 - 0.42618 0.338096 2.24255 - 0.425976 0.440818 2.24258 - 0.425953 0.497806 2.24299 - 0.425774 0.693543 2.24395 - 0.424992 0.71254 2.24075 - 0.425851 0.75463 2.24482 - 0.425931 0.848539 2.24599 - 0.42423 0.898682 2.23911 - 0.371055 1.2485 2.01337 - 0.321902 1.25132 1.80187 - 0.313695 1.26801 1.7667 - 0.268153 1.263 1.57068 - 0.233767 1.2698 1.42276 - 0.232189 1.27369 1.41601 - 0.207586 1.26615 1.31006 - 0.196079 1.27397 1.26061 - 0.0178273 0.365398 0.485503 - 0.0169447 0.363283 0.481686 - 0.0114973 0.44341 0.458952 - 0.0115852 0.468985 0.459556 - 0.011922 0.499301 0.461274 - 0.0107995 0.518049 0.456609 - 0.0109007 0.551551 0.45734 - 0.00042292 0.4628 0.411466 - -0.0100605 0.412962 0.365912 --0.00999932 0.446441 0.366471 - -0.0103169 0.463565 0.365256 - -0.010392 0.648982 0.366571 - -0.0095642 0.697184 0.370559 - -0.0105672 0.724541 0.366485 - 0.00171988 1.3028 0.42447 - 0.00046248 1.30465 0.419075 --0.00352512 1.30311 0.401901 - -0.0259102 1.27866 0.305354 - -0.0378903 0.388641 0.245935 - -0.043608 0.298853 0.220537 - -0.0446841 0.290654 0.215833 - -0.0518689 0.332897 0.185288 - -0.0573671 0.327628 0.161581 - -0.154492 1.30911 -0.247711 - -0.155696 1.19698 -0.253885 - -0.154278 1.16807 -0.248038 - -0.154776 1.0573 -0.251159 - -0.152953 0.751093 -0.246016 - -0.153563 0.748118 -0.248671 - -0.153654 0.701655 -0.24947 - -0.153662 0.646791 -0.249991 - -0.152064 0.631949 -0.243245 - -0.15178 0.542776 -0.242813 - -0.152584 0.518972 -0.246482 - -0.110035 -0.34767 -0.0902459 - -0.108151 -0.350353 -0.081645 - -0.104526 -0.355884 -0.0650977 - -0.102765 -0.365198 -0.0571215 - -0.102422 -0.366471 -0.0555625 - -0.101294 -0.373083 -0.0504618 - -0.0930034 -0.37376 -0.0125062 - -0.0900871 -0.377725 0.00080989 - -0.0892691 -0.378892 0.00454462 - -0.0889139 -0.37989 0.0061615 - -0.0869976 -0.375927 0.0149728 - -0.0789709 -0.372232 0.0517607 - -0.0768598 -0.38124 0.0613426 - -0.0735932 -0.382361 0.0762893 - -0.0651683 -0.376362 0.114921 - -0.0641121 -0.377855 0.119744 - -0.0624513 -0.382131 0.127308 - -0.0611226 -0.378616 0.133425 - -0.0589042 -0.379093 0.143578 - -0.0564601 -0.382561 0.154737 - -0.0559485 -0.378961 0.157113 - -0.0488939 -0.369818 0.189501 - -0.0466098 -0.379846 0.199865 - -0.0377039 -0.385811 0.240587 - -0.0233246 -0.388972 0.306398 - -0.0148224 -0.389129 0.345327 --0.00889641 -0.392358 0.372431 --0.00876539 -0.388908 0.373063 --0.00533555 -0.394377 0.388716 --0.00352994 -0.395127 0.396977 - 0.0206462 -0.399523 0.507634 - 0.032081 -0.392929 0.560054 - 0.039164 -0.40907 0.592334 - 0.154269 -0.795169 1.11576 - 0.152477 -0.747488 1.108 - 0.151496 -0.711505 1.10385 - 0.164783 -0.676294 1.16501 - 0.222158 -0.686109 1.42764 - 0.32153 -0.708384 1.88243 - 0.397547 -0.723872 2.23036 - 0.39804 -0.645326 2.23335 - 0.397552 -0.625062 2.23131 - 0.397496 -0.50969 2.23213 - 0.396965 -0.471358 2.23006 - 0.397382 -0.462415 2.23205 - 0.397791 -0.453464 2.23401 - 0.400223 -0.427776 2.24539 - 0.399094 -0.278858 2.24161 - 0.398078 -0.25999 2.23714 - 0.398973 -0.0794951 2.24292 - 0.397449 -0.00747353 2.23662 - 0.396344 0.0104342 2.23173 - 0.398248 0.535309 2.24537 - 0.39673 0.620827 2.23922 - 0.397927 0.662139 2.24509 - 0.39725 1.12282 2.24631 - 0.396369 1.1323 2.24236 - 0.301315 1.26451 1.80837 - 0.243186 1.26582 1.54221 - 0.229483 1.25906 1.47941 - 0.222637 1.2712 1.44818 - 0.202892 1.27327 1.35778 - 0.192568 1.27475 1.31053 - 0.179152 1.27928 1.24914 - 0.0138746 0.376503 0.483902 - 0.0112875 0.372678 0.47202 - 0.00941689 0.37717 0.463497 - 0.00820837 0.415329 0.458321 - 0.00824557 0.433427 0.458661 - 0.0086019 0.460682 0.460548 - 0.00889133 0.478962 0.462045 - 0.00813466 0.517028 0.458937 - -0.0103925 0.4114 0.373114 - -0.0118257 0.521087 0.36758 --0.00236266 1.29872 0.418199 - -0.0257339 1.28829 0.311088 - -0.0402511 0.306931 0.235418 - -0.0435854 0.295855 0.220047 - -0.0465914 0.294073 0.206266 - -0.050473 0.333465 0.188862 - -0.0571582 0.415852 0.159024 - -0.0588493 0.322079 0.150402 - -0.05893 0.317848 0.149993 - -0.0598579 0.322931 0.145792 - -0.0694971 0.422592 0.10259 - -0.148616 1.29667 -0.251491 - -0.150463 1.2858 -0.260049 - -0.148631 1.2331 -0.252156 - -0.147874 1.18036 -0.24918 - -0.148694 1.16132 -0.253115 - -0.147336 1.0819 -0.247641 - -0.146823 0.985308 -0.246199 - -0.146875 0.944669 -0.246818 - -0.146901 0.925341 -0.247118 - -0.147686 0.913125 -0.250826 - -0.148116 0.907458 -0.25285 - -0.147147 0.813952 -0.249288 - -0.146213 0.733465 -0.245766 - -0.145794 0.672441 -0.244418 - -0.145692 0.592831 -0.244698 - -0.145277 0.585311 -0.24287 - -0.145388 0.536941 -0.243831 - -0.145083 0.503858 -0.242742 - -0.103948 -0.350874 -0.0778043 - -0.0984131 -0.369459 -0.0513038 - -0.0965586 -0.384886 -0.0425149 - -0.0918825 -0.369392 -0.0198184 - -0.0913292 -0.3796 -0.0172512 - -0.082911 -0.382404 0.0233066 - -0.0748635 -0.377592 0.0621518 - -0.0604981 -0.363796 0.131545 - -0.0598509 -0.364645 0.134657 - -0.0591071 -0.377918 0.138113 - -0.0575905 -0.375568 0.145447 - -0.0558806 -0.376346 0.153684 - -0.0529848 -0.382999 0.167579 - -0.0468357 -0.38669 0.197188 - -0.0457461 -0.382086 0.202487 - -0.0433549 -0.379717 0.214038 - -0.0423481 -0.380876 0.218881 - -0.0383563 -0.372864 0.238205 - -0.0342897 -0.377809 0.257762 - -0.0307907 -0.382095 0.274589 - -0.0293938 -0.394325 0.281203 - -0.0278211 -0.388116 0.288846 - -0.0271348 -0.387562 0.292161 - -0.0229742 -0.392784 0.312168 - -0.0203981 -0.392898 0.324587 - -0.0191429 -0.395445 0.330613 - -0.0181525 -0.393081 0.335411 - -0.014017 -0.386821 0.355411 - -0.0123048 -0.394528 0.363589 --0.00908199 -0.395059 0.379122 --0.00846288 -0.392772 0.382129 --0.00766454 -0.387912 0.386026 --0.00673717 -0.389253 0.390484 --0.00391848 -0.397397 0.403993 --0.00305291 -0.388782 0.408251 - 0.00691647 -0.394456 0.456259 - 0.0111089 -0.397053 0.476445 - 0.0171333 -0.392595 0.505534 - 0.0258003 -0.401547 0.547231 - 0.0268058 -0.393506 0.552158 - 0.0314998 -0.402728 0.574697 - 0.039329 -0.375206 0.612714 - 0.141832 -0.697509 1.10372 - 0.151925 -0.672348 1.15263 - 0.176367 -0.670513 1.27049 - 0.199335 -0.678643 1.38114 - 0.210954 -0.683168 1.43711 - 0.235072 -0.680915 1.55341 - 0.238949 -0.683023 1.57208 - 0.256018 -0.693355 1.65427 - 0.313522 -0.718945 1.93125 - 0.350126 -0.725609 2.10766 - 0.375175 -0.681989 2.22886 - 0.375242 -0.623312 2.22975 - 0.37571 -0.604601 2.23219 - 0.374772 -0.583969 2.22788 - 0.376119 -0.547465 2.23473 - 0.376802 -0.444293 2.23904 - 0.377447 -0.342794 2.24315 - 0.37646 -0.314468 2.23867 - 0.377842 -0.151684 2.24693 - 0.376738 -0.142274 2.2417 - 0.376045 -0.0343551 2.23943 - 0.376054 -0.0253938 2.23956 - 0.375018 0.0014887 2.23483 - 0.375807 0.0104495 2.23872 - 0.376995 0.0554206 2.24489 - 0.375853 0.0911736 2.23974 - 0.375641 0.109094 2.23889 - 0.37506 0.135893 2.23635 - 0.374304 0.198642 2.23333 - 0.375482 0.235483 2.23937 - 0.376021 0.254007 2.24215 - 0.375187 0.289997 2.23848 - 0.375224 0.679806 2.2425 - 0.37479 0.739502 2.24099 - 0.376277 0.845884 2.24921 - 0.373266 0.968519 2.2359 - 0.373684 1.21197 2.24032 - 0.373907 1.23707 2.24164 - 0.317792 1.25947 1.97132 - 0.209447 1.26978 1.44907 - 0.192747 1.27191 1.36859 - 0.0108485 0.367677 0.482721 - 0.00864049 0.372678 0.472125 - 0.00660606 0.432235 0.462903 - 0.00521878 0.47282 0.456614 - 0.00575643 0.489249 0.459368 - 0.00600469 0.497496 0.460646 - -0.0134036 0.427466 0.366387 - -0.0131302 0.466779 0.368092 - 0.00137444 1.29617 0.446188 --0.00349325 1.29094 0.422669 - -0.0256071 1.28293 0.315976 - -0.0404154 0.304932 0.234952 - -0.0486814 0.3222 0.195271 - -0.0544927 0.352515 0.167552 - -0.0549231 0.324592 0.165202 - -0.13763 1.30333 -0.223901 - -0.144051 1.23774 -0.255506 - -0.143236 1.19822 -0.251966 - -0.142986 1.15303 -0.251204 - -0.142935 1.13894 -0.251098 - -0.142074 1.01957 -0.24812 - -0.142655 0.841881 -0.252669 - -0.141466 0.807954 -0.247275 - -0.140728 0.786635 -0.243925 - -0.14142 0.78452 -0.247282 - -0.141713 0.75742 -0.24896 - -0.141582 0.702152 -0.248874 - -0.140961 0.65479 -0.246347 - -0.140368 0.627984 -0.243752 - -0.141125 0.616119 -0.247518 - -0.0894705 -0.253328 -0.0202196 - -0.101602 -0.35248 -0.0830103 - -0.100271 -0.357202 -0.0762853 - -0.091273 -0.377001 -0.0306794 - -0.0874389 -0.379485 -0.0111853 - -0.0870979 -0.384136 -0.00949754 - -0.0833903 -0.374862 0.00947408 - -0.0792859 -0.375405 0.0303647 - -0.0760763 -0.383831 0.0466174 - -0.073907 -0.372618 0.057778 - -0.0703363 -0.379584 0.0758845 - -0.0700857 -0.381184 0.0771436 - -0.0697635 -0.381851 0.0787769 - -0.0662053 -0.383397 0.0968762 - -0.0627748 -0.373496 0.114444 - -0.0606089 -0.377818 0.125426 - -0.0580196 -0.373061 0.138657 - -0.0553822 -0.373072 0.152085 - -0.0521678 -0.374115 0.168439 - -0.0506885 -0.379311 0.175916 - -0.0438854 -0.373582 0.21061 - -0.0364962 -0.386454 0.248096 - -0.0357913 -0.390252 0.251646 - -0.0355515 -0.384157 0.252929 - -0.0270679 -0.391902 0.29604 - -0.0229142 -0.392604 0.317179 - -0.0212964 -0.383314 0.325512 - -0.0196387 -0.388264 0.3339 - -0.0153351 -0.39403 0.355751 --0.00362195 -0.395267 0.41537 --0.00136558 -0.384822 0.426966 - 0.00389155 -0.393741 0.453638 - 0.0126851 -0.400324 0.498339 - 0.0133517 -0.397904 0.501757 - 0.0136834 -0.396683 0.503459 - 0.0141277 -0.396268 0.505725 - 0.0222501 -0.404523 0.546991 - 0.0225869 -0.403101 0.548721 - 0.0338521 -0.37513 0.606363 - 0.0583203 -0.476344 0.729882 - 0.253134 -0.691432 1.71946 - 0.295959 -0.720091 1.93719 - 0.300847 -0.721555 1.96206 - 0.341863 -0.728867 2.1708 - 0.354331 -0.732468 2.23424 - 0.353614 -0.622729 2.23173 - 0.35279 -0.563727 2.22814 - 0.354313 -0.53725 2.23617 - 0.355626 -0.115349 2.24724 - 0.353458 -0.09682 2.23639 - 0.354114 -0.016408 2.24057 - 0.353133 0.0461419 2.23622 - 0.353198 0.06403 2.23674 - 0.353597 0.144839 2.23961 - 0.353363 0.180768 2.23879 - 0.353935 0.400855 2.24399 - 0.35452 0.410794 2.24707 - 0.354532 0.429549 2.24732 - 0.354149 0.438523 2.24547 - 0.353144 0.465616 2.24063 - 0.35493 0.486713 2.24994 - 0.354376 0.533802 2.24761 - 0.353903 0.610706 2.246 - 0.352963 0.728521 2.24244 - 0.35198 0.829368 2.23848 - 0.351554 1.18549 2.24 - 0.343525 1.25737 2.19987 - 0.323702 1.26366 2.09902 - 0.3041 1.26547 1.99924 - 0.265957 1.26845 1.80508 - 0.235353 1.27161 1.64931 - 0.233268 1.27327 1.63871 - 0.214476 1.27305 1.54304 - 0.181936 1.26829 1.37732 - 0.153214 1.28657 1.23129 - 0.00728059 0.358396 0.478697 - 0.00392138 0.385382 0.461875 - 0.00347379 0.40531 0.459803 - 0.00321601 0.433427 0.458782 - 0.00353251 0.460682 0.460676 --0.00334702 0.499898 0.426059 --0.00793756 0.445028 0.402119 - -0.0115679 0.41812 0.383357 - -0.0135526 0.412342 0.373193 - -0.0152181 0.436298 0.364962 - -0.0147137 0.4741 0.367922 - -0.0149447 0.49419 0.366955 - -0.0151267 0.517227 0.366267 - -0.0149185 0.692288 0.369144 - -0.0150742 0.739268 0.368839 - -0.0054712 1.29687 0.423514 - -0.02093 1.29961 0.344841 - -0.0329175 0.856436 0.279212 - -0.0390178 0.347679 0.242876 - -0.0413378 0.29799 0.23055 - -0.0415884 0.297997 0.229274 - -0.041839 0.297999 0.227998 - -0.0527059 0.371829 0.173439 - -0.0536156 0.343653 0.168516 - -0.0535295 0.318269 0.16869 - -0.0582925 0.317727 0.144436 - -0.0639149 0.383445 0.116494 - -0.118864 1.23478 -0.154422 - -0.138045 1.00719 -0.254435 - -0.136715 0.894281 -0.248838 - -0.136663 0.833246 -0.249204 - -0.135855 0.779421 -0.245651 - -0.136495 0.720908 -0.249517 - -0.135814 0.613765 -0.24716 - -0.135061 0.552851 -0.24396 - -0.134932 0.533228 -0.243507 - -0.135302 0.503858 -0.245696 - -0.0950421 -0.358496 -0.0651442 - -0.0951473 -0.365729 -0.0657889 - -0.0886567 -0.376181 -0.0310165 - -0.0840304 -0.377367 -0.00616308 - -0.0788469 -0.382404 0.0216426 - -0.0734913 -0.378313 0.0504733 - -0.0691599 -0.383287 0.0737002 - -0.0688524 -0.383966 0.0753456 - -0.0651586 -0.380924 0.0952324 - -0.0613193 -0.378323 0.115897 - -0.0542632 -0.387797 0.15372 - -0.0533759 -0.370434 0.158678 - -0.052783 -0.371031 0.161859 - -0.0492296 -0.375012 0.180915 - -0.0484229 -0.380569 0.18519 - -0.0456239 -0.37698 0.200273 - -0.03806 -0.380757 0.240888 - -0.0353293 -0.379931 0.255574 - -0.0316147 -0.394005 0.275386 - -0.0314542 -0.375721 0.276448 - -0.0286136 -0.387562 0.291587 - -0.027929 -0.388948 0.295252 - -0.0265808 -0.390632 0.30248 - -0.019437 -0.388238 0.340904 - -0.014885 -0.389544 0.365356 - -0.0136281 -0.392358 0.372081 --0.00747175 -0.386861 0.405231 - 0.00064946 -0.39313 0.448813 - 0.00395605 -0.399921 0.466512 - 0.00529825 -0.400096 0.473724 - 0.0088469 -0.399399 0.492806 - 0.0124245 -0.39414 0.512092 - 0.0172117 -0.403232 0.537724 - 0.020485 -0.400324 0.55535 - 0.0268809 -0.408461 0.589638 - 0.0287324 -0.374964 0.599956 - 0.104628 -0.729136 1.00402 - 0.124414 -0.799736 1.10959 - 0.124172 -0.675185 1.10966 - 0.127982 -0.672242 1.13017 - 0.129106 -0.670578 1.13623 - 0.135116 -0.669241 1.16854 - 0.142541 -0.671983 1.20842 - 0.143374 -0.668733 1.21293 - 0.151955 -0.673832 1.259 - 0.167303 -0.67306 1.34151 - 0.176521 -0.682139 1.39095 - 0.205581 -0.682733 1.54714 - 0.218587 -0.688091 1.61699 - 0.295139 -0.719942 2.02811 - 0.322496 -0.729213 2.17505 - 0.331359 -0.619229 2.22388 - 0.332519 -0.48782 2.23156 - 0.334855 -0.462635 2.24439 - 0.335006 -0.444081 2.2454 - 0.33387 -0.424124 2.23952 - 0.323751 -0.376637 2.18565 - 0.319975 -0.354988 2.16559 - 0.318828 -0.27483 2.1603 - 0.324473 -0.270273 2.19069 - 0.334616 -0.214255 2.24582 - 0.333086 -0.195381 2.2378 - 0.333234 -0.123663 2.23938 - 0.334492 0.0822506 2.24839 - 0.333438 0.126883 2.24322 - 0.332755 0.171575 2.24004 - 0.332164 0.252536 2.23775 - 0.333068 0.381633 2.24402 - 0.332428 0.408836 2.24087 - 0.33223 0.647704 2.24242 - 0.330744 0.837539 2.23651 - 0.330838 0.922726 2.23794 - 0.331405 0.934961 2.24112 - 0.332043 0.969373 2.24493 - 0.331921 0.991155 2.24451 - 0.331179 1.07938 2.24149 - 0.330608 1.24395 2.24022 - 0.317965 1.26194 2.17246 - 0.255133 1.26725 1.8348 - 0.245192 1.26989 1.7814 - 0.189995 1.26886 1.48471 - 0.185004 1.27477 1.45794 - 0.181683 1.27844 1.44014 - 0.179151 1.27513 1.42649 - 0.154445 1.28225 1.29378 - 0.00384619 0.3796 0.474445 - 0.00098959 0.396357 0.459274 - 0.00092731 0.408068 0.459067 - 0.00122283 0.488217 0.461532 - 0.0005915 0.547769 0.45879 - -0.0139098 0.413184 0.379375 - -0.0164876 0.446441 0.365883 --0.00540798 1.29608 0.434725 - -0.0147186 1.30531 0.384782 - -0.0157038 1.30897 0.379527 - -0.0252577 1.30404 0.328121 - -0.0444987 0.294649 0.213665 - -0.0452566 0.298428 0.209633 - -0.0533777 0.320946 0.166229 - -0.0538884 0.320387 0.163477 - -0.0552459 0.320834 0.156186 - -0.0576206 0.324865 0.143466 - -0.118018 1.28341 -0.170686 - -0.124988 1.3036 -0.207927 - -0.133556 1.15672 -0.255584 - -0.132143 0.923572 -0.25054 - -0.131062 0.715107 -0.247009 - -0.130055 0.541146 -0.243498 - -0.130518 0.49887 -0.246451 - -0.0894485 -0.28959 -0.0503103 - -0.0944443 -0.34011 -0.0793874 - -0.0941476 -0.353589 -0.0778513 - -0.0928725 -0.34814 -0.070516 - -0.092607 -0.349455 -0.0690173 - -0.0923406 -0.350764 -0.0675131 - -0.0922859 -0.366504 -0.0673832 - -0.087398 -0.376766 -0.0396251 - -0.0858598 -0.38176 -0.0309104 - -0.0801773 -0.378037 0.0015415 - -0.0739741 -0.379708 0.0369006 - -0.0671312 -0.37588 0.0759717 - -0.0671602 -0.381184 0.0757452 - -0.0668714 -0.381851 0.0773846 - -0.0599236 -0.391314 0.1169 - -0.0557857 -0.373841 0.140702 - -0.0501643 -0.37092 0.172796 - -0.045374 -0.372991 0.200092 - -0.0353635 -0.382794 0.257071 - -0.0342489 -0.380214 0.263458 - -0.0276944 -0.391943 0.300704 - -0.0192848 -0.396243 0.348616 - -0.0155169 -0.387676 0.370205 - -0.0132114 -0.396486 0.383251 - -0.0112966 -0.394037 0.3942 --0.00341631 -0.39174 0.43917 - 0.00125486 -0.390985 0.46582 - 0.00422711 -0.402669 0.482636 - 0.00482779 -0.400389 0.486088 - 0.00542494 -0.39808 0.489521 - 0.0100017 -0.395284 0.515656 - 0.0157734 -0.391872 0.548613 - 0.0189211 -0.402764 0.566438 - 0.0244932 -0.403433 0.59821 - 0.0236451 -0.371667 0.593741 - 0.0927719 -0.709466 0.984076 - 0.114364 -0.768301 1.10654 - 0.114039 -0.702022 1.10546 - 0.114559 -0.698124 1.10847 - 0.113326 -0.674256 1.10171 - 0.116147 -0.6622 1.11794 - 0.195409 -0.685859 1.56972 - 0.199839 -0.683653 1.595 - 0.205217 -0.683653 1.62568 - 0.240954 -0.697513 1.82934 - 0.290741 -0.723841 2.11298 - 0.311687 -0.669942 2.23306 - 0.310301 -0.467322 2.2275 - 0.296179 -0.386422 2.1479 - 0.29628 -0.377719 2.14858 - 0.299627 -0.301901 2.16855 - 0.301285 -0.259352 2.17849 - 0.311294 -0.168026 2.23663 - 0.313395 -0.151024 2.24881 - 0.311686 0.11765 2.24218 - 0.310631 0.206968 2.23719 - 0.310568 0.243022 2.23726 - 0.310735 0.389454 2.2399 - 0.310258 0.491718 2.23837 - 0.31103 0.727183 2.24549 - 0.311385 0.915834 2.24971 - 0.31105 0.936622 2.24804 - 0.240967 1.26742 1.85216 - 0.229284 1.25987 1.78544 - 0.184907 1.28122 1.5326 - 0.164599 1.27391 1.41669 - 0.160282 1.28078 1.39215 - 0.136249 1.2785 1.25506 - 0.133658 1.28287 1.24034 - 0.130332 1.28158 1.22135 - 0.0032892 0.368985 0.486223 - 0.00140069 0.37767 0.475553 - 7.525e-05 0.37674 0.467983 - -0.0010972 0.384531 0.461386 --0.00180176 0.389323 0.457424 --0.00166897 0.402717 0.458336 --0.00164973 0.42436 0.458696 - -0.0015775 0.484621 0.459806 --0.00196479 0.496715 0.457737 --0.00166572 0.537458 0.459915 --0.00173841 0.54307 0.459565 --0.00175257 0.549607 0.45956 --0.00197248 0.553393 0.45835 --0.00281203 0.555417 0.453585 - -0.0148177 0.413691 0.383472 - -0.0152694 0.417868 0.380945 - -0.0162203 0.419873 0.375545 - -0.0182717 0.470881 0.364436 - -0.0180485 0.644458 0.367719 - -0.0104322 1.30465 0.418802 - -0.0223447 1.30903 0.350913 - -0.0254554 1.2986 0.333051 - -0.0265152 1.29208 0.326931 - -0.0442472 0.298705 0.214297 - -0.0476698 0.32334 0.195062 - -0.0491626 0.334457 0.186677 - -0.0521392 0.375535 0.170177 - -0.0538945 0.322738 0.159554 - -0.054137 0.322435 0.158168 - -0.0571611 0.326419 0.140967 - -0.127239 1.12517 -0.249458 - -0.127246 1.06248 -0.250223 - -0.127408 0.975123 -0.252155 - -0.126088 0.748173 -0.247256 - -0.124953 0.573208 -0.242812 - -0.12532 0.56083 -0.245045 - -0.125061 0.535321 -0.243863 - -0.0888434 -0.301206 -0.0649193 - -0.0881871 -0.302334 -0.0609452 - -0.0900047 -0.358939 -0.0726865 - -0.0825037 -0.382373 -0.027396 - -0.0812528 -0.377931 -0.0197403 - -0.0773093 -0.37205 0.00429516 - -0.0755902 -0.380501 0.0146367 - -0.0653332 -0.386233 0.0768927 - -0.0641728 -0.382575 0.0839887 - -0.0634646 -0.381007 0.0883115 - -0.0590472 -0.376407 0.11521 - -0.0587794 -0.376896 0.116832 - -0.0582683 -0.38506 0.119836 - -0.0532085 -0.380266 0.150642 - -0.0454916 -0.378849 0.19755 - -0.042544 -0.383829 0.2154 - -0.0406436 -0.381999 0.22697 - -0.0387144 -0.38681 0.238634 - -0.0310292 -0.384429 0.285362 - -0.0304858 -0.383895 0.28867 - -0.0301856 -0.384604 0.290486 - -0.0212877 -0.39539 0.344421 - -0.0202621 -0.386037 0.350768 - -0.018239 -0.394528 0.362957 - -0.0176831 -0.393308 0.366349 - -0.0162091 -0.386673 0.375388 - -0.0132418 -0.387793 0.393405 --0.00250872 -0.394296 0.458544 - 0.00048243 -0.397053 0.476686 - 0.0126872 -0.397919 0.550837 - 0.0168517 -0.399684 0.57612 - 0.0185118 -0.404005 0.586155 - 0.0195695 -0.40759 0.592537 - 0.10524 -0.762451 1.10874 - 0.104036 -0.66797 1.10259 - 0.114651 -0.666376 1.16711 - 0.122789 -0.669288 1.21653 - 0.124619 -0.670417 1.22763 - 0.13727 -0.674864 1.30445 - 0.156484 -0.676837 1.42118 - 0.200477 -0.689481 1.68834 - 0.206947 -0.683973 1.72772 - 0.259565 -0.715923 2.04706 - 0.282953 -0.722268 2.1891 - 0.289795 -0.610075 2.23206 - 0.29031 -0.515687 2.23635 - 0.289431 -0.467546 2.2316 - 0.28016 -0.427375 2.17576 - 0.27785 -0.406469 2.16198 - 0.276408 -0.3605 2.15379 - 0.278636 -0.345346 2.16752 - 0.275963 -0.30754 2.15174 - 0.29099 -0.114677 2.24542 - 0.290169 -0.0341543 2.24143 - 0.290494 -0.016352 2.24362 - 0.289695 0.0370848 2.23942 - 0.288037 0.269055 2.2322 - 0.288904 0.50086 2.24033 - 0.288364 0.734084 2.23992 - 0.288277 0.921492 2.2417 - 0.288488 0.976591 2.24366 - 0.289104 1.05689 2.24839 - 0.288442 1.24395 2.24667 - 0.255937 1.27122 2.04949 - 0.244759 1.27013 1.98156 - 0.227212 1.27172 1.87495 - 0.173222 1.27098 1.54688 - 0.156109 1.27772 1.44297 - 0.147896 1.28005 1.3931 --0.00127412 0.37767 0.475554 --0.00252026 0.37674 0.46797 --0.00392668 0.389156 0.459577 --0.00430174 0.422611 0.45771 --0.00528759 0.547953 0.453263 - -0.0168982 0.418805 0.381121 - -0.0193565 0.410457 0.366081 - -0.0196441 0.417363 0.364418 - -0.0195822 0.467396 0.36541 - -0.0197596 0.576107 0.365672 --0.00888689 1.29811 0.440631 - -0.0125343 1.30366 0.418536 - -0.0209451 1.30629 0.367461 - -0.0410013 0.303932 0.233245 - -0.0412234 0.294958 0.231785 - -0.0428905 0.293951 0.221642 - -0.0433259 0.296892 0.219033 - -0.051526 0.353302 0.1699 - -0.0531156 0.318826 0.159816 - -0.0548628 0.326659 0.149296 - -0.0550528 0.325341 0.148125 - -0.0578507 0.342563 0.131336 - -0.0802881 0.762058 0.00016218 - -0.12155 0.974549 -0.247949 - -0.121921 0.938449 -0.250645 - -0.121621 0.879004 -0.249553 - -0.120789 0.861152 -0.244717 - -0.120047 0.751506 -0.241561 - -0.120312 0.639052 -0.244556 - -0.120343 0.590282 -0.245347 - -0.0851983 -0.310497 -0.0619934 - -0.0863644 -0.342304 -0.0700004 - -0.0860507 -0.368583 -0.0683048 - -0.0858968 -0.37066 -0.0673312 - -0.083421 -0.373166 -0.0512528 - -0.0830086 -0.376406 -0.0486119 - -0.0728217 -0.381487 0.017613 - -0.0688833 -0.380324 0.0432574 - -0.0655725 -0.371734 0.0649155 - -0.0625158 -0.378833 0.0847133 - -0.0595376 -0.381463 0.104059 - -0.0593722 -0.383904 0.105104 - -0.0580552 -0.37928 0.113735 - -0.0551573 -0.381394 0.132565 - -0.0549717 -0.383748 0.133742 - -0.0543337 -0.388838 0.137827 - -0.0522705 -0.382561 0.151336 - -0.0507182 -0.383428 0.161426 - -0.0500297 -0.376089 0.166003 - -0.0497798 -0.376352 0.167625 - -0.0482243 -0.374801 0.177768 - -0.0455121 -0.379714 0.195353 - -0.0447646 -0.381088 0.2002 - -0.0424723 -0.375832 0.215186 - -0.0389708 -0.377814 0.237946 - -0.0387132 -0.378759 0.23961 - -0.0384301 -0.382693 0.2414 - -0.0351581 -0.380214 0.262725 - -0.0261851 -0.390409 0.320983 - -0.0243872 -0.387301 0.332723 - -0.0237448 -0.389229 0.336879 - -0.0209418 -0.388717 0.355126 - -0.019238 -0.393308 0.366153 - -0.0164873 -0.389536 0.384103 - -0.0139376 -0.395436 0.400617 - -0.0104022 -0.395444 0.423624 --0.00326338 -0.394162 0.470097 - -0.0005241 -0.399238 0.487856 - 0.0052854 -0.39778 0.52568 - 0.00958992 -0.394271 0.553738 - 0.0127581 -0.397439 0.574313 - 0.0160825 -0.407442 0.595815 - 0.0950236 -0.719295 1.10542 - 0.105564 -0.658598 1.17481 - 0.148733 -0.681137 1.45544 - 0.247458 -0.715708 2.09743 - 0.267087 -0.714545 2.22518 - 0.26843 -0.678189 2.2344 - 0.268247 -0.648494 2.2336 - 0.256433 -0.361226 2.16051 - 0.269268 -0.016368 2.24857 - 0.269259 -0.0074408 2.24863 - 0.267921 0.445147 2.24588 - 0.267946 0.530287 2.24717 - 0.266301 0.712621 2.23886 - 0.26659 0.733407 2.24101 - 0.266651 0.743664 2.24155 - 0.266722 0.82599 2.24309 - 0.266733 0.943048 2.24471 - 0.266224 0.952371 2.24152 - 0.265846 0.962111 2.23918 - 0.266547 1.0197 2.2445 - 0.225406 1.26722 1.98004 - 0.217594 1.27655 1.92932 - 0.195668 1.27992 1.78669 - 0.129068 1.27882 1.35327 - 0.109178 1.28158 1.22388 - 0.0878917 1.15226 1.08365 - 0.0829753 1.12922 1.05135 --0.00433416 0.381527 0.473342 --0.00622453 0.4124 0.461447 --0.00695973 0.480125 0.457555 --0.00616204 0.508477 0.463119 - -0.0079078 0.552645 0.45234 - -0.020684 0.447729 0.367818 - -0.0205839 0.479847 0.368892 - -0.0155693 1.30153 0.412344 - -0.0234201 1.30391 0.361286 - -0.0391042 0.368421 0.246904 - -0.0423349 0.298996 0.224966 - -0.0459538 0.30194 0.201455 - -0.0461536 0.301827 0.200153 - -0.0463534 0.301708 0.198851 - -0.0476167 0.326024 0.19095 - -0.0507074 0.326178 0.17084 - -0.0626082 0.454966 0.0950909 - -0.101292 1.21355 -0.146655 - -0.106906 1.3082 -0.181944 - -0.111563 1.30549 -0.212284 - -0.11636 1.03766 -0.247027 - -0.116885 0.989219 -0.251077 - -0.115938 0.936099 -0.245617 - -0.115323 0.798042 -0.243432 - -0.11596 0.72513 -0.248535 - -0.115623 0.652871 -0.247295 - -0.115552 0.640654 -0.246992 - -0.115646 0.557218 -0.248709 - -0.115697 0.520284 -0.249522 - -0.114791 0.505143 -0.24383 - -0.0948115 -0.385197 -0.151614 - -0.0837821 -0.32494 -0.0736657 - -0.0755739 -0.378418 -0.0170435 - -0.0669843 -0.379425 0.0429854 - -0.0601636 -0.381275 0.0906374 - -0.0599266 -0.381867 0.0922854 - -0.0577346 -0.379665 0.107639 - -0.0552597 -0.381614 0.124911 - -0.0466484 -0.377771 0.18516 - -0.0457996 -0.386397 0.190972 - -0.0443137 -0.380202 0.201446 - -0.0419865 -0.406909 0.217336 - -0.0369855 -0.383044 0.252632 - -0.0355372 -0.384195 0.262739 - -0.034117 -0.383088 0.272683 - -0.0257948 -0.387767 0.33079 - -0.0241114 -0.390603 0.342518 - -0.0145362 -0.396827 0.409362 - -0.0036293 -0.399553 0.485565 --0.00070212 -0.396268 0.506073 - 0.0007153 -0.402677 0.515891 - 0.00154991 -0.403318 0.521716 - 0.0031036 -0.396144 0.532678 - 0.00524477 -0.40077 0.54758 - 0.00603643 -0.403992 0.553068 - 0.0115436 -0.406111 0.591535 - 0.012969 -0.406356 0.601495 - 0.0125255 -0.369806 0.59891 - 0.0864759 -0.775467 1.11011 - 0.0862753 -0.728227 1.10938 - 0.0856007 -0.686873 1.10524 - 0.0862158 -0.665884 1.10984 - 0.0986428 -0.666773 1.19669 - 0.0999936 -0.666956 1.20613 - 0.10191 -0.657221 1.21966 - 0.12011 -0.672549 1.34667 - 0.124777 -0.671652 1.37931 - 0.15158 -0.674112 1.56663 - 0.170249 -0.683846 1.697 - 0.245892 -0.559196 2.22751 - 0.246361 -0.512987 2.23145 - 0.246686 -0.476179 2.23423 - 0.244744 -0.463734 2.22084 - 0.243902 -0.453176 2.2151 - 0.243191 -0.442893 2.21028 - 0.238585 -0.426741 2.17831 - 0.235773 -0.413572 2.15883 - 0.2369 -0.370876 2.16732 - 0.240611 -0.24278 2.19507 - 0.247855 -0.0698502 2.24815 - 0.245782 -0.0427885 2.23404 - 0.245788 -0.0339369 2.23421 - 0.246418 0.0192275 2.23936 - 0.246274 0.215448 2.24112 - 0.245797 0.242075 2.23817 - 0.245732 0.260058 2.23797 - 0.245718 0.341805 2.23902 - 0.245904 0.351185 2.24046 - 0.245667 0.36006 2.23892 - 0.246163 0.453406 2.24371 - 0.245557 0.471175 2.23972 - 0.245703 0.499668 2.24114 - 0.245361 0.575302 2.23982 - 0.24638 0.606435 2.24739 - 0.245985 0.615339 2.24475 - 0.245661 0.723504 2.24402 - 0.245326 0.73273 2.24181 - 0.245432 0.753245 2.24283 - 0.245432 0.835642 2.244 - 0.243984 1.10514 2.23768 - 0.245167 1.14485 2.24651 - 0.245047 1.16809 2.246 - 0.245035 1.17998 2.24608 - 0.244338 1.21324 2.24169 - 0.199702 1.28765 1.93072 - 0.19003 1.27047 1.86287 - 0.171961 1.28218 1.73673 - 0.145311 1.28234 1.55044 - 0.140992 1.28642 1.52031 - 0.107865 1.28084 1.28866 - 0.102627 1.28149 1.25206 - 0.101215 1.28053 1.24218 --0.00594371 0.381543 0.480418 --0.00681249 0.383201 0.474369 --0.00720254 0.382613 0.471634 - -0.008364 0.380751 0.463489 --0.00863356 0.397041 0.461834 --0.00845757 0.403235 0.463152 --0.00883711 0.437823 0.460988 - -0.0113145 0.549053 0.445241 - -0.0201371 0.421616 0.381769 - -0.0210066 0.428068 0.375783 - -0.0223502 0.482389 0.367158 - -0.0227668 0.524599 0.364842 - -0.0228881 0.531009 0.364084 - -0.0228497 0.542263 0.364511 - -0.0227593 0.555471 0.36533 - -0.0248221 1.30889 0.361551 - -0.0300756 1.26915 0.324267 - -0.0387103 0.398164 0.251607 - -0.0405087 0.306771 0.237746 - -0.0423815 0.297996 0.224531 - -0.0438842 0.301758 0.21408 - -0.0487689 0.346972 0.180573 - -0.0502924 0.355526 0.170044 - -0.0501942 0.326178 0.170316 - -0.050596 0.325674 0.1675 - -0.0543679 0.324865 0.141122 - -0.10308 1.29686 -0.185658 - -0.113138 1.28358 -0.256151 - -0.111648 1.11322 -0.248145 - -0.111157 1.00993 -0.246167 - -0.111696 0.995821 -0.25014 - -0.111205 0.83833 -0.248932 - -0.110783 0.763743 -0.24703 - -0.110728 0.714715 -0.247339 - -0.110742 0.676647 -0.247978 - -0.110329 0.609573 -0.246037 - -0.11088 0.609056 -0.249893 - -0.111072 0.605387 -0.251286 - -0.110686 0.537557 -0.249548 - -0.109881 0.500162 -0.244448 - -0.0785122 -0.353809 -0.0581809 - -0.0791683 -0.370095 -0.0633804 - -0.0773293 -0.371983 -0.04953 - -0.071338 -0.375173 -0.00436103 - -0.0704404 -0.382726 0.00229758 - -0.0680192 -0.377142 0.0206564 - -0.0628515 -0.38089 0.0596003 - -0.0621615 -0.37774 0.0648558 - -0.0592115 -0.384435 0.0870187 - -0.0576381 -0.382266 0.0989261 - -0.0560931 -0.379736 0.110625 - -0.0549629 -0.38121 0.119132 - -0.0478817 -0.381291 0.172574 - -0.0449911 -0.379714 0.194414 - -0.0439723 -0.392284 0.201912 - -0.0437472 -0.392383 0.203609 - -0.0429841 -0.36866 0.20973 - -0.032625 -0.383895 0.28768 - -0.0272348 -0.386294 0.328325 - -0.0245879 -0.391887 0.348216 - -0.0203828 -0.389986 0.379981 - -0.0144604 -0.393678 0.424623 - -0.0115832 -0.393238 0.446344 - -0.01136 -0.392262 0.448043 --0.00912439 -0.397358 0.464839 --0.00367698 -0.392595 0.506024 --0.00149636 -0.404122 0.522306 --0.00089391 -0.399371 0.526925 --0.00021864 -0.395356 0.532082 - 0.00100029 -0.403421 0.541159 - 0.00182286 -0.397027 0.547464 - 0.00887888 -0.401785 0.600645 - 0.00848458 -0.37215 0.598121 - 0.0767136 -0.707151 1.10796 - 0.0764511 -0.674861 1.10647 - 0.0955862 -0.670787 1.25095 - 0.134008 -0.682183 1.54075 - 0.195331 -0.704944 2.00322 - 0.225482 -0.6269 2.23196 - 0.225725 -0.598651 2.23422 - 0.223591 -0.509306 2.21948 - 0.223863 -0.500524 2.22167 - 0.225018 -0.456256 2.23106 - 0.216995 -0.424626 2.17099 - 0.216902 -0.380001 2.17096 - 0.217552 -0.363223 2.17613 - 0.216478 -0.239388 2.16991 - 0.226082 -0.0963475 2.24457 - 0.226216 -0.0429994 2.24639 - 0.226614 -0.0341543 2.24953 - 0.225483 0.0192275 2.24181 - 0.225375 0.0458488 2.24139 - 0.224287 0.196711 2.23548 - 0.225525 0.242667 2.24553 - 0.224419 0.286779 2.23785 - 0.225045 0.342137 2.24342 - 0.224149 0.377608 2.2372 - 0.223928 0.395684 2.23581 - 0.225745 0.617072 2.25289 - 0.223699 0.994388 2.24319 - 0.223097 1.01434 2.23895 - 0.224158 1.14485 2.24895 - 0.21447 1.28079 2.1779 - 0.207539 1.27029 2.12543 - 0.188949 1.27963 1.98527 - 0.17171 1.28608 1.85526 - 0.16624 1.27607 1.81383 - 0.149305 1.28235 1.68611 - 0.130026 1.28261 1.54061 - 0.124925 1.27802 1.50205 - 0.122795 1.28423 1.48606 - 0.0892086 1.29023 1.23267 - 0.0850732 1.28436 1.20137 - 0.0587504 1.06588 0.999382 --0.00871328 0.369927 0.479624 - -0.0114502 0.422459 0.459768 - -0.0113021 0.447826 0.461272 - -0.0110562 0.461419 0.463335 - -0.0199652 0.43649 0.395717 - -0.0240111 0.408565 0.364757 - -0.0238491 0.603946 0.368954 - -0.0243468 0.719018 0.36695 - -0.0234864 0.815226 0.374908 - -0.0219716 0.907403 0.387744 - -0.042086 0.298997 0.226674 - -0.0427562 0.294971 0.221554 - -0.043806 0.29976 0.213704 - -0.0477257 0.334457 0.18465 - -0.0502739 0.387394 0.166224 - -0.0515929 0.325366 0.155325 - -0.0521099 0.317267 0.1513 - -0.052291 0.316937 0.149928 - -0.0536971 0.323521 0.139416 - -0.0999938 1.30359 -0.195071 - -0.106743 1.12543 -0.248722 - -0.106549 1.02468 -0.248792 - -0.106597 0.893753 -0.251149 - -0.106151 0.861152 -0.248277 - -0.105716 0.846847 -0.245211 - -0.106142 0.724297 -0.250292 - -0.105805 0.713884 -0.24791 - -0.105271 0.682443 -0.244359 - -0.106271 0.67455 -0.252023 - -0.105427 0.58277 -0.247049 - -0.105529 0.499527 -0.249093 - -0.10544 0.494557 -0.248493 - -0.0903626 -0.406513 -0.181505 - -0.0837381 -0.36712 -0.126429 - -0.0763758 -0.362362 -0.0658658 - -0.0746182 -0.377211 -0.0516719 - -0.0732536 -0.371894 -0.0403724 - -0.0682108 -0.380021 0.00092159 - -0.0659792 -0.382435 0.0192152 - -0.0657756 -0.383336 0.0208734 - -0.0625521 -0.38 0.0474111 - -0.06235 -0.380777 0.0490586 - -0.060604 -0.379578 0.0634224 - -0.0547614 -0.381196 0.111396 - -0.0542483 -0.385545 0.115539 - -0.0534857 -0.382131 0.121861 - -0.0520114 -0.38318 0.133955 - -0.0500925 -0.382561 0.149731 - -0.0499111 -0.38387 0.1512 - -0.049708 -0.38419 0.152863 - -0.0484218 -0.370888 0.16365 - -0.0384438 -0.386454 0.245366 - -0.0358743 -0.3938 0.266354 - -0.0336896 -0.377253 0.284576 - -0.0296142 -0.381669 0.317984 - -0.024841 -0.390985 0.357045 - -0.0218451 -0.394629 0.381598 - -0.0177312 -0.392633 0.415428 - -0.016189 -0.38836 0.428169 --0.00774572 -0.395012 0.497424 --0.00662097 -0.400764 0.50657 --0.00641248 -0.399523 0.508303 - -0.0041674 -0.395662 0.526811 --0.00314872 -0.399294 0.53512 --0.00174783 -0.38585 0.546852 - 0.00062653 -0.391458 0.566265 - 0.00193376 -0.396644 0.576919 - 0.00396184 -0.404495 0.593451 - 0.00441944 -0.398146 0.597315 - 0.0146009 -0.427279 0.680479 - 0.035192 -0.578561 0.847141 - 0.0675886 -0.794414 1.10972 - 0.0669615 -0.769568 1.10498 - 0.0669075 -0.704663 1.10561 - 0.0671958 -0.669774 1.10856 - 0.0697484 -0.661183 1.12967 - 0.0718595 -0.655538 1.14711 - 0.0778403 -0.665086 1.19609 - 0.130694 -0.681484 1.63003 - 0.152899 -0.685691 1.81239 - 0.168562 -0.70568 1.94074 - 0.195578 -0.423357 2.16736 - 0.195863 -0.406063 2.16999 - 0.195555 -0.265176 2.16979 - 0.202107 -0.219101 2.22438 - 0.204852 -0.212594 2.24704 - 0.204112 -0.122818 2.24245 - 0.20419 -0.0695427 2.24397 - 0.20324 -0.0604294 2.23632 - 0.203326 0.0103222 2.23819 - 0.203051 0.0899763 2.23725 - 0.203992 0.134901 2.24573 - 0.203119 0.170071 2.23914 - 0.203009 0.178922 2.23838 - 0.203013 0.205757 2.23885 - 0.202853 0.232521 2.23799 - 0.20307 0.241721 2.23992 - 0.203042 0.250697 2.23984 - 0.20293 0.277648 2.23937 - 0.203214 0.341639 2.24275 - 0.203333 0.378523 2.24434 - 0.203113 0.387394 2.24269 - 0.202889 0.396259 2.24099 - 0.202427 0.413964 2.23749 - 0.203444 0.452972 2.24649 - 0.202522 0.507574 2.23982 - 0.202495 0.574213 2.2407 - 0.202404 0.58362 2.24011 - 0.202065 0.750471 2.24009 - 0.202064 0.874648 2.24213 - 0.201689 1.15227 2.24364 - 0.201955 1.22572 2.24705 - 0.178926 1.28326 2.05881 - 0.170505 1.28138 1.98959 - 0.13575 1.274 1.70394 - 0.132429 1.28415 1.67682 - 0.107671 1.2812 1.47338 - 0.0988533 1.28299 1.40096 - 0.0852789 1.29089 1.28957 - -0.0116681 0.36746 0.477821 - -0.0138877 0.402552 0.460166 - -0.013581 0.483439 0.464025 - -0.0231899 0.412063 0.383901 - -0.0255061 0.422106 0.365039 - -0.0256328 0.572577 0.366489 - -0.024411 1.29964 0.388561 - -0.0250978 1.30035 0.382931 - -0.0271599 1.30231 0.366021 - -0.0292627 1.30008 0.348709 - -0.0418377 0.295977 0.228779 - -0.0478602 0.343006 0.180079 - -0.0487115 0.368341 0.173505 - -0.0489052 0.368111 0.17191 - -0.0494606 0.32469 0.166628 - -0.0504819 0.323035 0.158211 - -0.0539888 0.351112 0.129865 - -0.0552015 0.379593 0.120373 - -0.0622354 0.559337 0.0655613 - -0.102526 1.30373 -0.253128 - -0.102369 1.22129 -0.253201 - -0.102281 1.17601 -0.253225 - -0.101765 1.12543 -0.249828 - -0.101189 1.08912 -0.24569 - -0.101582 0.970963 -0.25088 - -0.101203 0.925118 -0.248523 - -0.10118 0.905879 -0.248655 - -0.101068 0.894961 -0.24791 - -0.101011 0.72263 -0.250295 - -0.100244 0.596001 -0.246091 - -0.099469 0.558105 -0.240352 - -0.0849311 -0.407589 -0.180162 - -0.0804621 -0.378637 -0.138519 - -0.0757059 -0.34111 -0.0940751 - -0.0708344 -0.363177 -0.0496739 - -0.0666265 -0.380097 -0.0112813 - -0.0585893 -0.379578 0.0626575 - -0.056043 -0.383495 0.0860069 - -0.055512 -0.391542 0.0907421 - -0.0539957 -0.382527 0.104856 - -0.0507439 -0.38455 0.13473 - -0.0478209 -0.378779 0.161724 - -0.0441483 -0.371871 0.195634 - -0.0420431 -0.378876 0.214868 - -0.0343262 -0.387128 0.285699 - -0.0334817 -0.382741 0.293548 - -0.0312515 -0.395923 0.313818 - -0.0306756 -0.388467 0.319254 - -0.0301004 -0.388153 0.32455 - -0.0256366 -0.394249 0.365497 - -0.0254521 -0.393626 0.367206 - -0.0251238 -0.391422 0.370267 - -0.0245753 -0.389468 0.375348 - -0.0243931 -0.388802 0.377037 - -0.0230502 -0.394581 0.389282 - -0.0218133 -0.388424 0.400773 - -0.0137616 -0.394524 0.474723 --0.00924166 -0.396087 0.51627 - -0.0055992 -0.396377 0.549769 --0.00647823 -0.376804 0.542046 - -0.0039275 -0.393709 0.565196 --0.00330828 -0.396718 0.570836 --0.00045917 -0.408179 0.596831 --0.00057206 -0.376836 0.596372 - 0.0554926 -0.735989 1.10543 - 0.0552144 -0.671838 1.10406 - 0.0574967 -0.663381 1.12521 - 0.0610272 -0.662457 1.1577 - 0.0647625 -0.661713 1.19207 - 0.0653373 -0.659135 1.19741 - 0.0762513 -0.66698 1.29765 - 0.0844831 -0.666159 1.37339 - 0.0876538 -0.669326 1.40249 - 0.118154 -0.675068 1.68294 - 0.125131 -0.680577 1.74702 - 0.126734 -0.679114 1.76179 - 0.155822 -0.704347 2.02889 - 0.159898 -0.709655 2.06627 - 0.178368 -0.685444 2.23662 - 0.178042 -0.664943 2.234 - 0.177798 -0.558929 2.23372 - 0.178042 -0.550105 2.23613 - 0.177922 -0.456476 2.23675 - 0.177928 -0.202809 2.2415 - 0.179653 -0.177444 2.25784 - 0.177739 0.0813309 2.24503 - 0.176868 0.125339 2.23783 - 0.176321 0.258789 2.23526 - 0.176743 0.304482 2.23999 - 0.175819 0.458974 2.23435 - 0.177228 0.480736 2.24771 - 0.176277 0.602449 2.24121 - 0.175989 0.780565 2.24186 - 0.175196 1.18534 2.24206 - 0.158837 1.28174 2.09337 - 0.138679 1.27768 1.90788 - 0.0778615 1.29098 1.3487 - 0.0726357 1.29157 1.30064 - 0.0674033 1.2899 1.25248 - -0.0143174 0.376503 0.483878 - -0.0173397 0.409091 0.456682 - -0.0169692 0.419683 0.460285 - -0.0169692 0.433275 0.460537 - -0.0169741 0.452401 0.460846 - -0.0167723 0.471516 0.463055 - -0.0169439 0.478962 0.461615 - -0.0269008 0.416448 0.368871 - -0.0273684 0.480471 0.365755 - -0.0275187 0.492267 0.36459 - -0.0274451 0.552915 0.366389 - -0.0272645 0.606863 0.369049 - -0.0273928 0.614306 0.368007 - -0.0197849 1.29322 0.45055 - -0.0412506 0.294827 0.234625 - -0.0425129 0.298996 0.223091 - -0.0437538 0.294709 0.211598 - -0.0445389 0.304332 0.204554 - -0.0454098 0.304695 0.19655 - -0.0503625 0.318565 0.15125 - -0.0671812 0.757317 0.00466444 - -0.0686799 0.789896 -0.00851804 - -0.0928593 1.30071 -0.221477 - -0.0954617 1.13304 -0.248518 - -0.0951048 0.933427 -0.248928 - -0.0943958 0.770442 -0.245422 - -0.094373 0.734723 -0.245875 - -0.0934224 0.547151 -0.240601 - -0.0936701 0.535719 -0.243091 - -0.0931861 0.508382 -0.239145 - -0.093505 0.502829 -0.242181 - -0.080098 -0.40827 -0.174689 - -0.0713748 -0.338635 -0.0843353 - -0.066346 -0.370444 -0.033722 - -0.0655399 -0.376006 -0.0256191 - -0.0617399 -0.383237 0.0129706 - -0.0576856 -0.383812 0.0542898 - -0.0575579 -0.385468 0.0555576 - -0.0573921 -0.386203 0.057233 - -0.0553544 -0.382874 0.0780737 - -0.0524299 -0.376362 0.10802 - -0.0453629 -0.375411 0.180082 - -0.04329 -0.381304 0.201093 - -0.0419874 -0.379876 0.214401 - -0.0416596 -0.390945 0.217516 - -0.0408019 -0.400994 0.226054 - -0.0377224 -0.384506 0.257785 - -0.0375589 -0.384354 0.259454 - -0.0361658 -0.377704 0.273793 - -0.0349108 -0.393054 0.286272 - -0.0334976 -0.394558 0.300648 - -0.0327308 -0.389853 0.308561 - -0.0309524 -0.390611 0.326675 - -0.0261689 -0.3904 0.375443 - -0.0247087 -0.397347 0.390187 - -0.0247376 -0.387608 0.390091 - -0.0227515 -0.391585 0.410257 - -0.0214995 -0.375989 0.423339 - -0.0209091 -0.383037 0.429213 - -0.0198372 -0.390797 0.439982 - -0.016058 -0.400425 0.47831 - -0.0155552 -0.397046 0.483505 - -0.0151662 -0.399238 0.487426 - -0.0146652 -0.39574 0.492605 - -0.0110687 -0.402554 0.529129 --0.00938239 -0.392521 0.546525 --0.00947387 -0.381381 0.545821 --0.00794805 -0.389183 0.561215 --0.00421506 -0.403433 0.598978 --0.00404684 -0.401785 0.600727 - -0.0040879 -0.378026 0.600795 - 0.0461645 -0.78191 1.10481 - 0.0460678 -0.685038 1.1058 - 0.0458829 -0.665565 1.10432 - 0.0461579 -0.661699 1.1072 - 0.0689797 -0.66591 1.33977 - 0.07106 -0.665158 1.36099 - 0.0728892 -0.662597 1.37969 - 0.0788789 -0.67639 1.44046 - 0.0952507 -0.676711 1.60736 - 0.10565 -0.680667 1.71329 - 0.126529 -0.69812 1.92578 - 0.156707 -0.69362 2.23351 - 0.156424 -0.682878 2.23085 - 0.156064 -0.464182 2.23166 - 0.151187 -0.31941 2.1849 - 0.154525 -0.235968 2.22064 - 0.154606 -0.227212 2.22165 - 0.157314 -0.14985 2.25084 - 0.155449 0.169654 2.23837 - 0.155835 0.205757 2.24304 - 0.155302 0.322318 2.24 - 0.155561 0.423827 2.24472 - 0.153856 0.494423 2.22878 - 0.154811 0.650528 2.24172 - 0.154648 0.739551 2.24188 - 0.154563 0.790137 2.24205 - 0.154265 0.947291 2.24223 - 0.154029 0.978972 2.24047 - 0.154452 1.00326 2.24528 - 0.1544 1.0822 2.24637 - 0.139701 1.28569 2.10069 - 0.0986046 1.28613 1.68176 - 0.094847 1.28576 1.64344 - 0.0790559 1.28833 1.48252 - 0.072858 1.28952 1.41936 - 0.0666193 1.28678 1.35571 - 0.0618355 1.28683 1.30694 - 0.0555181 1.28813 1.24257 - 0.0516548 1.28356 1.20309 - 0.0489025 1.2811 1.17498 - -0.0181363 0.38597 0.473234 - -0.0194127 0.399796 0.460505 - -0.0195747 0.493754 0.460779 - -0.0197471 0.49569 0.459061 - -0.0198311 0.517938 0.458661 - -0.0197149 0.540205 0.460301 - -0.0198334 0.557997 0.459458 - -0.026988 0.41836 0.383662 - -0.0276721 0.428346 0.376892 - -0.0282519 0.423058 0.370873 - -0.0287188 0.478889 0.367258 - -0.0287373 0.503805 0.367579 - -0.0222511 1.29026 0.449812 - -0.040875 0.302596 0.239723 - -0.041779 0.295934 0.230371 - -0.0445586 0.296167 0.202039 - -0.0465959 0.341405 0.182198 - -0.0483589 0.325413 0.163897 - -0.0494826 0.324077 0.152415 - -0.0504069 0.32596 0.143031 - -0.0543491 0.430655 0.104988 - -0.064827 0.754438 0.00480741 - -0.0850412 1.29781 -0.19013 - -0.0896247 1.30522 -0.236702 - -0.0912957 1.25158 -0.254836 - -0.0901984 0.973945 -0.249338 - -0.0897277 0.915343 -0.24574 - -0.0900247 0.90234 -0.249034 - -0.0897154 0.844231 -0.247071 - -0.0894797 0.800109 -0.245573 - -0.0895047 0.756114 -0.246729 - -0.0886571 0.635944 -0.24055 - -0.0889235 0.633901 -0.243307 - -0.089212 0.626584 -0.246398 - -0.0882065 0.557072 -0.237572 - -0.0880279 0.483646 -0.237255 - -0.0697271 -0.351287 -0.102243 - -0.0633409 -0.381829 -0.0301505 - -0.0621998 -0.376119 -0.0170129 - -0.0578854 -0.377926 0.032123 - -0.0544709 -0.374954 0.0711109 - -0.0532239 -0.377253 0.0852714 - -0.0524543 -0.384548 0.093877 - -0.0523064 -0.385112 0.0955496 - -0.0492556 -0.383748 0.130355 - -0.0469157 -0.380184 0.157108 - -0.0425091 -0.380649 0.207325 - -0.0419279 -0.380876 0.213945 - -0.0388255 -0.38715 0.249163 - -0.0375015 -0.385844 0.264285 - -0.0361404 -0.386912 0.279774 - -0.0360831 -0.380729 0.280569 - -0.0338033 -0.382036 0.306525 - -0.0331525 -0.390656 0.313746 - -0.0326176 -0.393323 0.319781 - -0.0311618 -0.387777 0.336502 - -0.0304865 -0.383306 0.344303 - -0.0303415 -0.382773 0.345968 - -0.0271499 -0.39301 0.382112 - -0.0253802 -0.388554 0.402385 - -0.0209435 -0.39015 0.45292 - -0.0200811 -0.394794 0.462644 - -0.0184105 -0.394538 0.481692 - -0.0181127 -0.395904 0.485055 - -0.0162491 -0.400764 0.506185 - -0.0160124 -0.393782 0.509043 - -0.0154498 -0.395284 0.515421 - -0.0135525 -0.394988 0.537055 - -0.0123601 -0.394177 0.550664 --0.00976512 -0.400372 0.580101 --0.00864497 -0.373997 0.593473 --0.00821314 -0.363032 0.598646 --0.00238683 -0.411605 0.663944 - 0.00392964 -0.473429 0.734527 - 0.0376297 -0.780676 1.11162 - 0.0378148 -0.762451 1.11415 - 0.0373534 -0.732115 1.10958 - 0.0373968 -0.664688 1.11162 - 0.0499367 -0.664645 1.25456 - 0.0554034 -0.65845 1.31701 - 0.0619706 -0.669039 1.39162 - 0.0629083 -0.668343 1.40233 - 0.081469 -0.679337 1.61364 - 0.091434 -0.678642 1.72724 - 0.132353 -0.708187 2.19297 - 0.135431 -0.701108 2.22821 - 0.136007 -0.683841 2.23518 - 0.135316 -0.604325 2.22912 - 0.136003 -0.502936 2.23927 - 0.13514 -0.426833 2.23118 - 0.129461 -0.299176 2.16937 - 0.133298 -0.270407 2.21376 - 0.134947 -0.264025 2.2327 - 0.136605 -0.212594 2.25278 - 0.135617 -0.0605188 2.24499 - 0.135443 -0.0339202 2.24362 - 0.135153 0.0279913 2.24173 - 0.134966 0.054479 2.2402 - 0.134862 0.151986 2.24125 - 0.134704 0.169654 2.23986 - 0.13462 0.178483 2.2391 - 0.134739 0.232293 2.24169 - 0.134645 0.28622 2.24185 - 0.134038 0.477977 2.23932 - 0.134343 0.554628 2.24455 - 0.134257 0.690962 2.24669 - 0.134466 0.701773 2.24931 - 0.133908 0.895572 2.2474 - 0.133714 1.0037 2.24766 - 0.133161 1.10275 2.24362 - 0.132223 1.19113 2.23495 - 0.133119 1.2216 2.24586 - 0.091103 1.29151 1.76855 - 0.0721906 1.29025 1.55295 - 0.0632089 1.28814 1.45053 - 0.0517717 1.29045 1.32021 - 0.0459337 1.2899 1.25366 - -0.0197496 0.377325 0.484091 - -0.0217922 0.393432 0.461178 - -0.0219287 0.411534 0.460036 - -0.0289536 0.426991 0.380317 - -0.0296379 0.422411 0.372412 - -0.0301487 0.417077 0.366468 - -0.0304859 0.484927 0.364178 - -0.030252 0.503805 0.367276 - -0.0304254 0.514681 0.365548 - -0.0285321 1.30134 0.40513 - -0.0295377 1.30189 0.393681 - -0.0336039 1.2951 0.347178 - -0.0363538 0.981312 0.308652 - -0.0409396 0.309514 0.241009 - -0.0422285 0.30099 0.226122 - -0.0453713 0.32533 0.190856 - -0.0467738 0.353703 0.175519 - -0.0469581 0.321949 0.172692 - -0.0477569 0.317287 0.16348 - -0.0486601 0.318221 0.153207 - -0.0858181 1.29831 -0.247905 - -0.0861478 1.2754 -0.252187 - -0.0858424 1.14988 -0.251578 - -0.0846457 0.799248 -0.245961 - -0.084497 0.781394 -0.244676 - -0.0848022 0.764971 -0.248529 - -0.0843784 0.716354 -0.244812 - -0.084021 0.672588 -0.241739 - -0.0840224 0.648918 -0.242297 - -0.0827636 0.506492 -0.231208 - -0.0710598 -0.397563 -0.165798 - -0.0670645 -0.355678 -0.112866 - -0.0655465 -0.340309 -0.0927698 - -0.0601473 -0.290206 -0.021408 - -0.0596992 -0.368977 -0.0176443 - -0.0593203 -0.372107 -0.0128086 - -0.0580719 -0.374968 0.00331514 - -0.0575229 -0.377889 0.0103633 - -0.0552492 -0.377626 0.0398716 - -0.0551209 -0.378425 0.0415161 - -0.0530325 -0.384893 0.0684452 - -0.0526926 -0.383441 0.0728944 - -0.0518186 -0.378192 0.0843707 - -0.0508956 -0.381318 0.0962659 - -0.0487851 -0.380121 0.123682 - -0.0478533 -0.381042 0.135749 - -0.0477247 -0.381421 0.137408 - -0.047596 -0.381792 0.139068 - -0.0446831 -0.380178 0.176907 - -0.0427442 -0.37541 0.202188 - -0.0403409 -0.377862 0.233309 - -0.039336 -0.376279 0.24639 - -0.0391888 -0.379167 0.248224 - -0.036993 -0.390362 0.276425 - -0.0368107 -0.383943 0.278957 - -0.0347194 -0.389242 0.305954 - -0.0345897 -0.388876 0.307647 - -0.0320034 -0.397824 0.340973 - -0.0317062 -0.392424 0.34497 - -0.0296834 -0.386394 0.371374 - -0.0280233 -0.394956 0.392691 - -0.0201699 -0.399044 0.494487 - -0.0200387 -0.397853 0.49622 - -0.015476 -0.389845 0.555632 - -0.0126741 -0.389257 0.592003 - -0.0125852 -0.383857 0.593298 --0.00754952 -0.406153 0.658058 - 0.0277701 -0.776064 1.10672 - 0.0276626 -0.691974 1.10751 - 0.0319246 -0.6595 1.16366 - 0.0352292 -0.664163 1.20642 - 0.0412671 -0.664274 1.28476 - 0.0443166 -0.662565 1.32437 - 0.0445954 -0.65825 1.3281 - 0.057495 -0.663066 1.49536 - 0.113873 -0.556531 2.22966 - 0.113831 -0.426833 2.2325 - 0.114911 -0.37484 2.24786 - 0.114182 -0.364027 2.23868 - 0.114684 -0.212075 2.24915 - 0.113708 -0.113334 2.23906 - 0.113589 -0.0955914 2.23798 - 0.113816 -0.00736807 2.24322 - 0.113268 0.0985764 2.23886 - 0.11307 0.160504 2.23791 - 0.112513 0.248981 2.23299 - 0.112763 0.303442 2.23764 - 0.112732 0.348804 2.23843 - 0.113089 0.451235 2.24572 - 0.112416 0.62042 2.24139 - 0.111807 0.71648 2.23599 - 0.112448 0.749777 2.24517 - 0.112391 0.759671 2.24469 - 0.111986 0.798609 2.24045 - 0.111522 0.869112 2.23626 - 0.111198 1.11063 2.23835 - 0.110873 1.11992 2.23437 - 0.093294 1.29249 2.01077 - 0.0812931 1.292 1.85504 - 0.074523 1.28959 1.76713 - 0.0588363 1.28857 1.56356 - 0.0461734 1.28888 1.39926 - 0.0380687 1.2932 1.29421 - 0.0179019 1.11217 1.02782 - -0.0241789 0.385188 0.46288 - -0.0245703 0.417942 0.458654 - -0.0321789 0.5442 0.363215 - -0.0319986 0.691656 0.369392 - -0.0323129 0.742213 0.366629 - -0.0297654 1.02255 0.406981 - -0.0408358 0.348269 0.245787 - -0.04219 0.300976 0.226984 - -0.042291 0.30099 0.225675 - -0.04399 0.298345 0.20356 - -0.0440825 0.297258 0.202332 - -0.0441819 0.297164 0.201039 - -0.0464564 0.356459 0.17307 - -0.0465949 0.331824 0.170632 - -0.047917 0.322435 0.153232 - -0.0487694 0.324989 0.142238 - -0.0605108 0.762117 0.00126527 - -0.0752302 1.28707 -0.176063 - -0.0808575 1.29831 -0.248788 - -0.0808975 1.23665 -0.250912 - -0.0805996 0.979336 -0.253743 - -0.0798799 0.912677 -0.24614 - -0.0789683 0.70716 -0.239661 - -0.0782229 0.600648 -0.232761 - -0.0784217 0.593473 -0.235527 - -0.077542 0.508961 -0.226312 - -0.0778741 0.505007 -0.230724 - -0.0773098 0.464366 -0.22446 - -0.065649 -0.370085 -0.146003 - -0.0638069 -0.357095 -0.117863 - -0.058567 -0.358251 -0.0389701 - -0.0579595 -0.372976 -0.0302641 - -0.0563244 -0.378037 -0.0057877 - -0.0541114 -0.380641 0.0274684 - -0.0536365 -0.378694 0.0346797 - -0.0533051 -0.376727 0.0397316 - -0.0528535 -0.384272 0.0463061 - -0.0494855 -0.38282 0.0970815 - -0.0492617 -0.383904 0.100419 - -0.0472877 -0.379861 0.130277 - -0.0467087 -0.379839 0.138997 - -0.0464875 -0.380557 0.142308 - -0.0458399 -0.373382 0.15228 - -0.0455139 -0.374274 0.157163 - -0.0449855 -0.377595 0.165023 - -0.0441925 -0.375215 0.177039 - -0.0401574 -0.376698 0.237774 - -0.0400388 -0.378626 0.239502 - -0.0394928 -0.37817 0.24774 - -0.0392261 -0.384917 0.251554 - -0.0378464 -0.387837 0.272248 - -0.0374235 -0.384933 0.278707 - -0.0363598 -0.387349 0.294655 - -0.0361081 -0.388669 0.298407 - -0.0359458 -0.384073 0.300991 - -0.0354122 -0.381295 0.309112 - -0.0351592 -0.382472 0.312887 - -0.0343336 -0.394929 0.324947 - -0.0342412 -0.38726 0.32657 - -0.033829 -0.389714 0.332705 - -0.0328299 -0.390391 0.347734 - -0.0323118 -0.396302 0.355359 - -0.0322029 -0.390401 0.357178 - -0.0311538 -0.386673 0.373093 - -0.0306097 -0.392083 0.381125 - -0.0284153 -0.392633 0.414163 - -0.0256627 -0.391719 0.455652 - -0.025441 -0.389667 0.459054 - -0.0232076 -0.392911 0.492598 - -0.0223242 -0.397082 0.505778 - -0.0217548 -0.394481 0.514433 - -0.0211862 -0.391697 0.523082 - -0.0199239 -0.394557 0.542009 - -0.0197023 -0.39175 0.545433 - -0.0190475 -0.383149 0.555556 - -0.0163607 -0.386732 0.595917 - 0.0185721 -0.765692 1.11066 - 0.0178752 -0.658113 1.10342 - 0.0394748 -0.661923 1.42865 - 0.0734423 -0.693644 1.93934 - 0.0754952 -0.697227 1.97016 - 0.0786748 -0.698197 2.01802 - 0.0799861 -0.696778 2.03782 - 0.0924164 -0.699134 2.22498 - 0.0930319 -0.644236 2.23591 - 0.0925857 -0.585058 2.23097 - 0.0920928 -0.52684 2.22531 - 0.0926153 -0.501006 2.23396 - 0.0925758 -0.184551 2.24292 - 0.0915128 0.0454431 2.23385 - 0.0913289 0.28538 2.23832 - 0.0911889 0.303145 2.23675 - 0.0916578 0.340645 2.24495 - 0.0907389 0.523508 2.23663 - 0.0908229 0.53333 2.23819 - 0.0905959 0.638361 2.23794 - 0.0910992 0.67039 2.24649 - 0.0900318 0.724604 2.23205 - 0.0901414 0.806686 2.23618 - 0.0898612 0.836095 2.23284 - 0.0896007 0.844876 2.22919 - 0.0901689 1.04496 2.24378 - 0.089323 1.26373 2.23765 - 0.085858 1.29211 2.18631 - 0.0803631 1.28512 2.10333 - 0.0793329 1.28653 2.08786 - 0.077384 1.29016 2.05861 - 0.064507 1.28731 1.86456 - 0.0589643 1.28919 1.78113 - 0.0481132 1.29413 1.61783 - 0.0412296 1.28436 1.51385 - 0.0315923 1.28853 1.36881 - 0.0253199 1.29168 1.27442 - -0.0259899 0.396577 0.474524 - -0.0267456 0.381597 0.462688 - -0.0269659 0.404276 0.460056 - -0.0269829 0.42595 0.460454 - -0.0269869 0.430485 0.46053 - -0.0271191 0.494656 0.460476 - -0.0291569 0.52307 0.430638 - -0.0323695 0.432372 0.37951 - -0.0325777 0.429287 0.37628 - -0.0332764 0.450587 0.3664 - -0.0334349 0.499959 0.365503 - -0.0333963 0.521428 0.366732 - -0.033564 0.531361 0.364506 - -0.0333248 0.838827 0.377391 - -0.0312909 1.06881 0.414972 - -0.0404973 0.407619 0.256335 - -0.0414771 0.301597 0.238375 - -0.0423371 0.29299 0.22516 - -0.0425045 0.291999 0.22261 - -0.0435325 0.294584 0.207203 - -0.0436349 0.297508 0.205749 - -0.0437268 0.298428 0.204392 - -0.0443285 0.297725 0.195307 - -0.0451763 0.340766 0.183837 - -0.045294 0.342578 0.182118 - -0.0464336 0.322722 0.164354 - -0.0466822 0.319965 0.160526 - -0.0473465 0.325053 0.150674 - -0.0739156 1.30454 -0.219961 - -0.0760606 1.27353 -0.253208 - -0.075463 1.15103 -0.247904 - -0.0753672 1.0724 -0.248835 - -0.0755863 1.06759 -0.252281 - -0.0752487 0.960204 -0.250437 - -0.0748222 0.919176 -0.245251 - -0.0748584 0.9109 -0.246047 - -0.0742635 0.765662 -0.241471 - -0.0742006 0.73629 -0.241411 - -0.0739785 0.71791 -0.23862 - -0.0738635 0.689783 -0.237737 - -0.0737486 0.681133 -0.236268 - -0.0734174 0.656164 -0.232033 - -0.0736679 0.649711 -0.236001 - -0.0727013 0.547943 -0.224514 - -0.0723675 0.528247 -0.22008 - -0.0719083 0.465838 -0.215047 - -0.0582104 -0.328462 -0.080403 - -0.0540882 -0.268822 -0.00456989 - -0.0554504 -0.334505 -0.0312756 - -0.0539793 -0.362983 -0.00599477 - -0.0530118 -0.370874 0.0110197 - -0.0521507 -0.38242 0.026002 - -0.0513087 -0.376623 0.0412623 - -0.0500381 -0.379139 0.0638884 - -0.0460281 -0.386298 0.135323 - -0.0438847 -0.384933 0.173693 - -0.0415296 -0.380946 0.215941 - -0.0400209 -0.385455 0.242753 - -0.0369481 -0.386706 0.297645 - -0.0363039 -0.390455 0.309026 - -0.0357706 -0.386107 0.318718 - -0.0353457 -0.393512 0.326049 - -0.0341067 -0.382636 0.348589 - -0.0336643 -0.393825 0.356098 - -0.0332683 -0.382679 0.363576 - -0.029621 -0.380377 0.428867 - -0.0264252 -0.393924 0.485517 - -0.0251115 -0.394591 0.50898 - -0.0247506 -0.396087 0.515379 - -0.0241059 -0.393541 0.526996 - 0.00851679 -0.786929 1.09615 - 0.00900311 -0.698311 1.10801 - 0.0087812 -0.683204 1.10459 - 0.0174405 -0.661197 1.26019 - 0.034699 -0.663779 1.56865 - 0.0363809 -0.67102 1.59846 - 0.0375042 -0.673242 1.61846 - 0.0592044 -0.693132 2.00571 - 0.0718545 -0.662443 2.23297 - 0.0717823 -0.652416 2.23204 - 0.0713645 -0.50906 2.22971 - 0.0717953 -0.428076 2.24031 - 0.071494 -0.39964 2.23594 - 0.0712261 -0.371573 2.23216 - 0.071778 -0.337206 2.24325 - 0.071446 -0.264544 2.23992 - 0.0713316 -0.139996 2.24233 - 0.0708298 -0.0513593 2.23654 - 0.0703699 0.00146109 2.23021 - 0.0710625 0.0368121 2.24386 - 0.0708468 0.0809311 2.24158 - 0.0705451 0.0983815 2.23681 - 0.0703062 0.133512 2.2338 - 0.0705882 0.169403 2.24012 - 0.0703908 0.204748 2.23786 - 0.0699907 0.430804 2.2388 - 0.0698821 0.572036 2.24192 - 0.0697313 0.639265 2.24163 - 0.0695568 0.648083 2.23883 - 0.0691535 0.859121 2.23917 - 0.069303 0.924577 2.24419 - 0.0690611 0.955275 2.24097 - 0.0685851 1.06306 2.23632 - 0.0683722 1.11895 2.23451 - 0.0686149 1.16897 2.24064 - 0.0684963 1.20403 2.23978 - 0.0689334 1.22108 2.2482 - 0.0679243 1.28453 2.23243 - 0.0594986 1.2941 2.08214 - 0.056414 1.29105 2.02688 - 0.0441959 1.28811 1.80834 - 0.0384206 1.29286 1.70526 - 0.033512 1.29345 1.61752 - 0.0279211 1.29919 1.51777 - 0.0227309 1.29317 1.42476 - 0.0221862 1.29401 1.41505 - 0.0153234 1.29012 1.29222 - -0.0281324 0.383727 0.482844 - -0.0287809 0.392358 0.47156 - -0.0295071 0.394468 0.458652 - -0.0296242 0.399104 0.456725 - -0.0294893 0.460532 0.461337 - -0.0297494 0.570093 0.46061 - -0.0314057 0.520283 0.429215 - -0.0347797 0.436965 0.365908 - -0.0348911 0.476974 0.365351 - -0.034858 0.526247 0.367707 - -0.0333593 1.30775 0.422489 - -0.0340004 1.30944 0.411087 - -0.0410507 0.374861 0.25157 - -0.0416017 0.293539 0.238807 - -0.0432893 0.302701 0.208964 - -0.0435049 0.301501 0.205066 - -0.0453532 0.354694 0.173927 - -0.0472482 0.327539 0.139075 - -0.0511611 0.534385 0.076526 - -0.0677277 1.29495 -0.192417 - -0.0699344 0.98642 -0.24292 - -0.0699623 0.967009 -0.244114 - -0.0688997 0.716549 -0.234086 - -0.0688892 0.67251 -0.235475 - -0.0686688 0.616225 -0.23355 - -0.0686745 0.611024 -0.233838 - -0.0673101 0.509915 -0.213067 - -0.0560403 -0.321967 -0.0992674 - -0.0545074 -0.323252 -0.0658948 - -0.0505026 -0.239346 0.0250988 - -0.0526861 -0.357331 -0.0276659 - -0.0522225 -0.355831 -0.017492 - -0.0515919 -0.37021 -0.00436725 - -0.050045 -0.375305 0.0291423 - -0.0482966 -0.379584 0.0670821 - -0.0479426 -0.379434 0.0748075 - -0.0475143 -0.379735 0.084134 - -0.0474372 -0.380333 0.0857905 - -0.0471275 -0.382653 0.0924418 - -0.0465017 -0.379736 0.106215 - -0.0455548 -0.383335 0.126709 - -0.0452028 -0.380067 0.134527 - -0.0449491 -0.378247 0.140138 - -0.0429345 -0.37911 0.184033 - -0.0423222 -0.377208 0.197467 - -0.04102 -0.384982 0.225525 - -0.0406528 -0.379813 0.233758 - -0.0400422 -0.380165 0.247058 - -0.0387522 -0.378243 0.275273 - -0.037173 -0.392407 0.309091 - -0.0362824 -0.390661 0.328588 - -0.0360338 -0.384898 0.334262 - -0.0350203 -0.389455 0.356165 - -0.0331728 -0.387371 0.396542 - -0.0319941 -0.384816 0.422357 - -0.0316004 -0.384769 0.430945 - -0.0299957 -0.393535 0.465555 - -0.0286496 -0.39337 0.494916 - -0.0252855 -0.391451 0.568359 - -0.024533 -0.395653 0.584586 - -0.0239679 -0.395056 0.596934 - 0.00026426 -0.701404 1.11198 - 0.00028425 -0.695664 1.11267 - 0.00392279 -0.655225 1.19378 - 0.00435856 -0.655414 1.20327 - 0.00606572 -0.660995 1.24026 - 0.00622812 -0.65708 1.24397 - 0.0123604 -0.666659 1.37728 - 0.0225206 -0.663698 1.59897 - 0.0277805 -0.671261 1.71334 - 0.0368582 -0.681678 1.91084 - 0.042508 -0.694632 2.03348 - 0.04723 -0.695985 2.13639 - 0.0516902 -0.653341 2.23551 - 0.0506825 -0.370302 2.22589 - 0.0508374 -0.352955 2.23003 - 0.0514455 -0.319219 2.24476 - 0.050976 -0.219641 2.23887 - 0.0504187 0.0455107 2.2383 - 0.050583 0.0898433 2.24381 - 0.0501095 0.133579 2.2354 - 0.0500481 0.177868 2.23599 - 0.0498216 0.213028 2.23259 - 0.0499419 0.222246 2.23561 - 0.049505 0.439186 2.23556 - 0.0495316 0.448629 2.23655 - 0.0490738 0.706344 2.23782 - 0.0491445 0.757565 2.2416 - 0.0490167 0.766734 2.23921 - 0.0488986 0.859512 2.24069 - 0.0357912 1.29977 1.97408 - 0.0353734 1.30501 1.9652 - 0.0338236 1.29093 1.93079 - 0.0316052 1.30087 1.88284 - 0.0266647 1.29471 1.77484 - 0.0241297 1.29355 1.71951 - 0.020189 1.29681 1.63372 - 0.0185058 1.29668 1.59701 - 0.013144 1.29455 1.47999 - 0.00827901 1.29375 1.37387 - 0.00593673 1.29197 1.32271 - 7.614e-05 1.29449 1.19502 - -0.0309731 0.392404 0.478555 - -0.0319356 0.419683 0.458757 - -0.0319559 0.453286 0.459781 - -0.0319188 0.482543 0.461867 - -0.0321083 0.536423 0.460088 - -0.0324073 0.563735 0.454759 - -0.0325221 0.564746 0.452299 - -0.0334161 0.525857 0.431106 - -0.0367614 0.733732 0.367233 - -0.0359146 1.31043 0.410878 - -0.0370187 1.30064 0.386373 - -0.0413894 0.359907 0.24999 - -0.0436837 0.295961 0.197168 - -0.0448181 0.322383 0.173585 - -0.0453054 0.32469 0.163059 - -0.045287 0.316565 0.163105 - -0.0454982 0.323891 0.158818 - -0.063754 1.28837 -0.197171 - -0.0648633 1.30265 -0.220738 - -0.0656069 1.0772 -0.246797 - -0.0652205 0.954179 -0.243742 - -0.064481 0.727836 -0.237497 - -0.0641308 0.685123 -0.231726 - -0.0630193 0.529016 -0.214303 - -0.0627315 0.508762 -0.208911 - -0.0621391 0.481954 -0.197163 - -0.0621005 0.473035 -0.196712 - -0.0616824 0.447965 -0.188688 - -0.0511187 -0.278802 -0.056784 - -0.049755 -0.321227 -0.0201079 - -0.049943 -0.338886 -0.0265129 - -0.0478613 -0.37436 0.0311495 - -0.0470274 -0.374674 0.0550491 - -0.0466161 -0.379584 0.0665614 - -0.0459224 -0.38281 0.0862719 - -0.045301 -0.378272 0.104353 - -0.0452 -0.381196 0.107082 - -0.0444833 -0.376542 0.127902 - -0.0435949 -0.378905 0.153246 - -0.0434427 -0.385684 0.157223 - -0.0432187 -0.372653 0.164393 - -0.0429454 -0.378767 0.171882 - -0.0428293 -0.379186 0.175187 - -0.0424131 -0.372455 0.187508 - -0.0420707 -0.370222 0.197457 - -0.0418405 -0.382571 0.203351 - -0.0410627 -0.418994 0.223566 - -0.0409875 -0.374937 0.228251 - -0.0409306 -0.374904 0.229886 - -0.0401688 -0.378806 0.251509 - -0.0401115 -0.378671 0.253161 - -0.0399022 -0.385191 0.258787 - -0.0397172 -0.376532 0.264589 - -0.039502 -0.382878 0.270398 - -0.0375271 -0.385838 0.326866 - -0.0344461 -0.391792 0.414884 - -0.0340425 -0.382156 0.427011 - -0.033422 -0.386084 0.444582 - -0.033346 -0.38597 0.446768 - -0.0326276 -0.396085 0.466791 - -0.0316065 -0.392173 0.496298 - -0.0304846 -0.395912 0.528258 - -0.0302563 -0.390493 0.535118 - -0.0298601 -0.397027 0.546105 - -0.0297552 -0.397148 0.549106 - -0.0303004 -0.367047 0.535198 - -0.0302474 -0.365674 0.536795 - -0.0296277 -0.378685 0.553821 - -0.0102008 -0.779575 1.08796 --0.00948514 -0.777382 1.10861 --0.00660923 -0.652084 1.19828 --0.00494483 -0.658161 1.24566 - 0.00124516 -0.658561 1.42316 - 0.00870061 -0.66655 1.63651 - 0.0155552 -0.66661 1.83309 - 0.0172928 -0.678466 1.88225 - 0.0237551 -0.688916 2.06698 - 0.0291079 -0.481536 2.23239 - 0.0286816 -0.281199 2.23166 - 0.0289304 -0.166795 2.24537 - 0.0281098 0.0542099 2.23452 - 0.0276057 0.284401 2.23327 - 0.0276596 0.339153 2.23796 - 0.0276205 0.35727 2.23788 - 0.0273232 0.438761 2.23403 - 0.0270941 0.49347 2.2306 - 0.0273108 0.542657 2.23963 - 0.0270375 0.569315 2.23332 - 0.0268863 0.777333 2.24093 - 0.0264651 0.909973 2.23646 - 0.0260253 1.22888 2.24215 - 0.0178337 1.30324 2.01149 - 0.015745 1.29423 1.95107 - 0.0127828 1.29943 1.86642 - 0.0122583 1.29913 1.85136 - 0.00954728 1.30534 1.77397 --0.00081936 1.3022 1.47648 --0.00393353 1.29689 1.38687 --0.00565812 1.29776 1.33746 --0.00806069 1.29548 1.26842 - -0.0195765 1.00151 0.921291 - -0.0335972 0.386208 0.483881 - -0.0345337 0.416039 0.458734 - -0.0356528 0.532361 0.433315 - -0.0379255 0.460422 0.364008 - -0.0378087 1.30861 0.416038 - -0.0396674 1.2874 0.361516 - -0.0418432 0.318238 0.243494 - -0.0420777 0.29467 0.235415 - -0.0423497 0.296933 0.227744 - -0.0426752 0.300986 0.218641 - -0.0442676 0.355104 0.176079 - -0.0450002 0.320782 0.1531 - -0.045654 0.343422 0.13565 - -0.061253 1.29529 -0.257084 - -0.060976 1.21965 -0.25348 - -0.0598958 0.888447 -0.24151 - -0.0598099 0.851236 -0.241181 - -0.0598053 0.843073 -0.24152 - -0.056448 0.405422 -0.170352 - -0.0473054 -0.306081 -0.0518251 - -0.047204 -0.306193 -0.0471684 - -0.0456819 -0.232398 0.0296573 - -0.0462395 -0.29309 -0.00158253 - -0.046439 -0.31004 -0.0123245 - -0.046412 -0.335203 -0.0133956 - -0.0455637 -0.370118 0.0224183 - -0.0452937 -0.369828 0.0348687 - -0.045257 -0.370636 0.0364837 - -0.0451541 -0.37392 0.0409161 - -0.0450128 -0.377913 0.0470497 - -0.0427819 -0.375347 0.149934 - -0.0423777 -0.373368 0.168712 - -0.04177 -0.372218 0.196778 - -0.0410394 -0.381902 0.229505 - -0.039457 -0.376174 0.302839 - -0.0386397 -0.39156 0.339025 - -0.0384774 -0.386988 0.346918 - -0.0384069 -0.390232 0.349859 - -0.0380964 -0.38393 0.364726 - -0.0379269 -0.384152 0.372505 - -0.0372261 -0.395817 0.403676 - -0.0372081 -0.386172 0.405392 - -0.0368948 -0.389225 0.419526 - -0.0362431 -0.391151 0.449336 - -0.036208 -0.39015 0.45104 - -0.0358283 -0.39501 0.468067 - -0.0353556 -0.391264 0.49016 - -0.0346366 -0.393283 0.523056 - -0.0341083 -0.385957 0.548038 - -0.0339783 -0.386115 0.554006 - -0.0328774 -0.374433 0.605732 - -0.0328283 -0.373444 0.608082 - -0.0213229 -0.770794 1.10088 - -0.0213646 -0.673652 1.10791 - -0.0212726 -0.659604 1.11343 - -0.0177594 -0.657922 1.27524 --0.00172082 -0.68569 2.01063 - 0.0004757 -0.686769 2.1116 - 0.00094651 -0.685256 2.1334 - 0.00307535 -0.633926 2.23607 - 0.00274162 -0.582825 2.22542 - 0.00277252 -0.564765 2.22851 - 0.00260846 -0.526078 2.22452 - 0.00271357 -0.382397 2.24258 - 0.00238902 -0.255348 2.23934 - 0.00197848 -0.121612 2.23276 - 0.00187638 -0.0337195 2.23615 - 0.00183387 0.00146545 2.23744 - 0.00166903 0.10729 2.23959 - 0.0012239 0.284681 2.23544 - 0.00117892 0.29347 2.23418 - 0.00104718 0.338158 2.23223 - 0.00100015 0.411764 2.23684 - 7.752e-05 0.878712 2.23737 --0.00031378 1.12235 2.24179 --0.00033544 1.17097 2.24527 --0.00346513 1.30297 2.11342 - -0.011245 1.30111 1.75529 - -0.0158493 1.30185 1.5435 - -0.0163572 1.30131 1.52009 - -0.0211784 1.29705 1.29787 - -0.0227393 1.28755 1.22517 - -0.0233688 1.29769 1.19714 - -0.0242925 1.27244 1.15232 - -0.0371218 0.398261 0.481567 - -0.0379212 0.547657 0.458536 - -0.0393741 0.420926 0.380019 - -0.0402908 0.769703 0.369946 - -0.040131 1.3039 0.426467 - -0.0405119 1.30252 0.408815 - -0.0422483 0.294606 0.236147 - -0.0426471 0.297986 0.21811 - -0.0435384 0.34474 0.181405 - -0.0437128 0.327328 0.171776 - -0.0441416 0.319503 0.151329 - -0.0444257 0.332139 0.139417 - -0.0486347 0.786061 -0.0124615 - -0.0546204 1.30051 -0.24052 - -0.0545824 1.17832 -0.250018 - -0.054233 1.07832 -0.243143 - -0.0536333 0.835186 -0.237932 - -0.0532433 0.740026 -0.228744 - -0.0526657 0.604305 -0.214663 - -0.0522231 0.542897 -0.199952 - -0.0510546 0.416467 -0.157825 - -0.0426705 -0.0965205 0.123151 - -0.0437642 -0.301273 -0.0457752 - -0.0431875 -0.350668 0.00793396 - -0.0431392 -0.358643 0.0115703 - -0.0427709 -0.368829 0.0506663 - -0.0426842 -0.37774 0.0584084 - -0.0426328 -0.37798 0.0641306 - -0.0422707 -0.38165 0.103993 - -0.0420473 -0.377345 0.130068 - -0.0419404 -0.372093 0.143257 - -0.0418746 -0.390086 0.146603 - -0.0418454 -0.38481 0.151074 - -0.0418299 -0.385108 0.152753 - -0.0417981 -0.359308 0.162121 - -0.0416837 -0.376784 0.171043 - -0.0416367 -0.379384 0.175745 - -0.0412481 -0.388987 0.217255 - -0.041019 -0.37817 0.245429 - -0.0409848 -0.379931 0.248878 - -0.0409676 -0.3808 0.250614 - -0.0409097 -0.380214 0.257255 - -0.0404562 -0.387526 0.306572 - -0.0403992 -0.385963 0.313322 - -0.0403791 -0.383197 0.316201 - -0.0402047 -0.38632 0.335102 - -0.0399342 -0.390182 0.36463 - -0.039657 -0.395287 0.394634 - -0.0390276 -0.392467 0.465995 - -0.0389691 -0.394524 0.4721 - -0.0389235 -0.392031 0.477791 - -0.0388064 -0.390085 0.491388 - -0.0380947 -0.392171 0.570892 - -0.0378713 -0.405968 0.592897 - -0.0378615 -0.363172 0.603614 - -0.0327023 -0.704041 1.10675 - -0.0325135 -0.654364 1.13912 - -0.0322337 -0.647096 1.1722 - -0.0290572 -0.650944 1.52828 - -0.0287066 -0.662012 1.5652 - -0.0268324 -0.659204 1.77643 - -0.0247961 -0.681755 2.00019 - -0.0229381 -0.602312 2.22683 - -0.0229324 -0.593551 2.22944 - -0.0230134 -0.555465 2.22889 - -0.0232754 -0.381653 2.23852 - -0.0234871 -0.264544 2.24105 - -0.0235465 -0.220182 2.24435 - -0.0237904 -0.156791 2.23119 - -0.0238294 -0.104304 2.2386 - -0.0238841 -0.0865589 2.23644 - -0.0241071 0.027867 2.2371 - -0.0242981 0.124844 2.23744 - -0.0244704 0.204445 2.23596 - -0.0247073 0.311337 2.23337 - -0.0246863 0.321061 2.23791 - -0.0248223 0.374864 2.23472 - -0.0248035 0.40394 2.24337 - -0.0250806 0.513709 2.2369 - -0.0252436 0.619834 2.24244 - -0.0253012 0.628057 2.23781 - -0.0255752 0.744228 2.23313 - -0.0257495 0.858729 2.23927 - -0.0261587 1.05148 2.23661 - -0.0264534 1.20198 2.23733 - -0.0264519 1.21593 2.24063 - -0.0268951 1.30748 2.2114 - -0.027426 1.30432 2.15103 - -0.0282006 1.30511 2.06417 - -0.028919 1.30692 1.98384 - -0.0296302 1.30524 1.90355 - -0.0301073 1.29663 1.848 - -0.0307418 1.31049 1.77982 - -0.0309767 1.29723 1.75044 - -0.031266 1.30533 1.71975 - -0.0314793 1.30776 1.69633 - -0.033253 1.29904 1.49506 - -0.034133 1.29549 1.39538 - -0.0344897 1.29624 1.35546 - -0.0348119 1.30135 1.3204 - -0.0352233 1.30404 1.27478 - -0.0355922 1.29622 1.23156 - -0.0405261 0.396314 0.474882 - -0.0405614 0.39852 0.471414 - -0.0407079 0.4124 0.458072 - -0.0408006 0.465129 0.459503 - -0.0409125 0.542675 0.464358 - -0.0410655 0.571227 0.453586 - -0.0414139 0.428409 0.382329 - -0.0414862 0.43117 0.374828 - -0.0415954 0.455663 0.368064 - -0.0416991 0.509893 0.368596 - -0.0423054 0.859479 0.379033 - -0.042508 1.28237 0.451317 - -0.0427278 1.30891 0.432583 - -0.0424668 0.421897 0.262553 - -0.0424154 0.301279 0.241226 - -0.0424736 0.293729 0.23299 - -0.042661 0.295892 0.212416 - -0.0430902 0.352322 0.176862 - -0.0430707 0.321395 0.17211 - -0.0430913 0.319973 0.169465 - -0.0431067 0.320735 0.167907 - -0.0432378 0.331742 0.155648 - -0.0432837 0.326343 0.149278 - -0.0443534 0.541441 0.0774189 - -0.0483697 1.28938 -0.205799 - -0.0485734 1.28552 -0.229558 - -0.047586 0.776257 -0.233051 - -0.0472768 0.682603 -0.219364 - -0.0468618 0.569851 -0.198069 - -0.0468055 0.551554 -0.195855 - -0.0433667 0.129935 0.0958145 - -0.0416301 -0.105679 0.113487 - -0.0416299 -0.106143 0.113949 - -0.0416826 -0.0940562 0.13312 - -0.0415081 -0.148388 0.0888474 - -0.041348 -0.200089 0.0507994 - -0.0411648 -0.268565 0.0196952 - -0.0411025 -0.289543 0.00601304 - -0.0410451 -0.309032 -0.00630812 - -0.0409809 -0.358733 0.0173212 - -0.040979 -0.36483 0.0242498 - -0.0409804 -0.366524 0.027441 - -0.0409981 -0.364468 0.0365637 - -0.0409989 -0.365265 0.0381557 - -0.0410117 -0.375681 0.0607937 - -0.0410412 -0.371975 0.0755965 - -0.0410966 -0.373508 0.114891 - -0.0411103 -0.383134 0.137044 - -0.0411166 -0.381536 0.139131 - -0.0411365 -0.379587 0.149872 - -0.0412154 -0.374214 0.195685 - -0.0412477 -0.366785 0.207397 - -0.041276 -0.382047 0.246933 - -0.0413829 -0.382346 0.319117 - -0.0414028 -0.388605 0.340914 - -0.0414267 -0.385674 0.353051 - -0.0414522 -0.385741 0.370268 - -0.0415136 -0.38462 0.40996 - -0.0416 -0.384174 0.467443 - -0.0416093 -0.382 0.470786 - -0.0416548 -0.38484 0.505138 - -0.0416874 -0.388935 0.532557 - -0.0416955 -0.389287 0.538472 - -0.0417264 -0.38233 0.54986 - -0.0417967 -0.37989 0.593799 - -0.0418039 -0.375417 0.592635 - -0.041828 -0.366066 0.596263 - -0.0418429 -0.365923 0.606104 - -0.0418731 -0.722537 1.10559 - -0.0419613 -0.674476 1.10026 - -0.0420839 -0.650332 1.15015 - -0.0422201 -0.647243 1.23754 - -0.0423276 -0.647526 1.31014 - -0.0429625 -0.654165 1.74561 - -0.0437681 -0.613687 2.23245 - -0.043806 -0.594401 2.23197 - -0.0440064 -0.489126 2.22514 - -0.0447717 -0.112886 2.23377 - -0.045184 0.0978945 2.22755 - -0.0453103 0.151611 2.24025 - -0.0453485 0.169487 2.24184 - -0.0455598 0.276428 2.24011 - -0.0456779 0.338821 2.23566 - -0.045765 0.383837 2.23368 - -0.0462806 0.63806 2.23849 - -0.0464073 0.698184 2.24284 - -0.0465034 0.754056 2.23229 - -0.0468884 0.942635 2.2376 - -0.0473611 1.17878 2.23786 - -0.0472073 1.30501 1.96492 - -0.0469766 1.29756 1.81991 - -0.0468889 1.30715 1.74816 - -0.0465628 1.29904 1.53993 - -0.0464585 1.3026 1.46509 - -0.0464139 1.29423 1.44633 - -0.0463573 1.30068 1.39966 - -0.0462834 1.30118 1.34938 - -0.0462624 1.29928 1.33782 - -0.0462637 1.30414 1.33214 - -0.0460635 1.2982 1.20562 - -0.0460561 1.30009 1.19814 - -0.0431466 0.395143 0.459323 - -0.0431971 0.421424 0.457963 - -0.0433337 0.488073 0.460187 - -0.0434968 0.574004 0.454281 - -0.0434854 0.571312 0.450278 - -0.0449225 1.30785 0.426103 - -0.0448936 1.30267 0.413652 - -0.0442129 1.02048 0.335453 - -0.0427656 0.358513 0.252617 - -0.0425837 0.292996 0.218446 - -0.0425681 0.288926 0.213423 - -0.0425674 0.29743 0.201528 - -0.0425708 0.301248 0.198652 - -0.042567 0.305565 0.19029 - -0.0425413 0.331168 0.138645 - -0.0426109 0.37696 0.123909 - -0.0431326 0.707884 0.0297072 - -0.0431984 0.776345 -0.0180342 - -0.0439069 1.2958 -0.239992 - -0.043882 1.29173 -0.251282 - -0.0434804 1.0831 -0.240742 - -0.0432107 0.9454 -0.236919 - -0.043196 0.939803 -0.239284 - -0.0430049 0.838279 -0.231274 - -0.042983 0.82576 -0.229193 - -0.0428629 0.763305 -0.225955 - -0.042853 0.760491 -0.228773 - -0.0427343 0.693177 -0.218131 - -0.0426718 0.657006 -0.2115 - -0.0425646 0.596657 -0.20239 - -0.0425464 0.583417 -0.196851 - -0.0422679 0.363074 -0.0878818 - -0.0422236 0.317531 -0.0564945 - -0.0420556 0.089527 0.137059 - -0.0420519 0.0927295 0.130259 - -0.0404017 -0.113927 0.105745 - -0.0406356 -0.103191 0.123418 - -0.0408012 -0.094064 0.135671 - -0.0408233 -0.0943981 0.137565 - -0.0407941 -0.0996463 0.136014 - -0.0393474 -0.238136 0.0387044 - -0.038639 -0.313254 -0.00772591 - -0.038597 -0.324372 -0.00937121 - -0.038885 -0.335272 0.0164027 - -0.038927 -0.346554 0.0217795 - -0.0392154 -0.366272 0.0490449 - -0.0399448 -0.373538 0.11093 - -0.0404537 -0.365819 0.151983 - -0.0405779 -0.380065 0.164684 - -0.0411634 -0.38797 0.214708 - -0.0411587 -0.420999 0.219811 - -0.0414992 -0.380371 0.241379 - -0.0415407 -0.379167 0.244631 - -0.0416203 -0.379668 0.251328 - -0.0418626 -0.378473 0.271289 - -0.0420254 -0.381362 0.285315 - -0.0422973 -0.382862 0.308182 - -0.0424025 -0.381806 0.316759 - -0.0428877 -0.392979 0.358978 - -0.0430159 -0.38826 0.368857 - -0.0431727 -0.385362 0.381418 - -0.0433647 -0.392063 0.39851 - -0.0435737 -0.38741 0.415115 - -0.0435699 -0.380318 0.413621 - -0.0438074 -0.3873 0.434541 - -0.0438461 -0.389846 0.438186 - -0.0439173 -0.387816 0.44377 - -0.0440152 -0.385556 0.451535 - -0.0449131 -0.393781 0.5276 - -0.0450068 -0.392832 0.535233 - -0.045006 -0.388343 0.534424 - -0.0453767 -0.390703 0.565651 - -0.0456006 -0.394799 0.58496 - -0.0457471 -0.397955 0.597674 - -0.0510839 -0.766946 1.10302 - -0.0628476 -0.680161 2.06717 - -0.0651003 -0.537399 2.23081 - -0.0652683 -0.453616 2.23085 - -0.0655607 -0.31735 2.2325 - -0.0659405 -0.18437 2.24197 - -0.0659169 -0.0948826 2.22511 - -0.0659609 -0.0773757 2.22586 - -0.0661107 -0.0601313 2.23545 - -0.0663319 0.0629983 2.23336 - -0.0665955 0.186663 2.23472 - -0.066784 0.275886 2.23556 - -0.0671145 0.421579 2.2388 - -0.0674887 0.591068 2.24173 - -0.0677218 0.726635 2.23857 - -0.0677793 0.766025 2.2368 - -0.0678162 0.776615 2.2381 - -0.0678166 0.795671 2.23497 - -0.0680106 0.898723 2.23396 - -0.0682494 0.997056 2.23746 - -0.0663918 1.30653 2.03144 - -0.0647325 1.30949 1.89292 - -0.0641859 1.30873 1.84757 - -0.0630016 1.30845 1.7491 - -0.0621643 1.30552 1.67994 - -0.0612462 1.30422 1.60378 - -0.0610825 1.31279 1.58874 - -0.0605213 1.30325 1.54364 - -0.0598404 1.30316 1.48701 - -0.0593948 1.29931 1.45059 - -0.0572926 1.29555 1.27633 - -0.0570928 1.2977 1.25936 - -0.045924 0.389008 0.481446 - -0.0458628 0.400795 0.474394 - -0.0458415 0.481648 0.459171 - -0.0458871 0.512236 0.457873 - -0.0460284 0.578521 0.458604 - -0.045104 0.651962 0.369488 - -0.0473455 1.28434 0.450731 - -0.0468492 1.29955 0.406912 - -0.043079 0.34955 0.251348 - -0.0429237 0.30995 0.245014 - -0.0428988 0.307067 0.243429 - -0.0428829 0.307169 0.242089 - -0.042715 0.297825 0.229671 - -0.0426462 0.294958 0.224422 - -0.0426264 0.292977 0.223111 - -0.0424602 0.294812 0.20898 - -0.0422583 0.313527 0.189071 - -0.042025 0.321949 0.16826 - -0.041973 0.32125 0.16405 - -0.041741 0.326359 0.143897 - -0.0408666 0.719917 0.005675 - -0.0399188 1.1188 -0.139534 - -0.0386913 1.15308 -0.247347 - -0.0384339 0.935495 -0.232563 - -0.0383318 0.886221 -0.232858 - -0.0383187 0.875352 -0.232135 - -0.0382063 0.71439 -0.214704 - -0.0382258 0.691874 -0.209331 - -0.0411204 0.0950114 0.130771 - -0.0410953 0.0956832 0.128567 - -0.0390059 -0.130797 0.0983585 - -0.0393349 -0.117305 0.111752 - -0.0392072 -0.12493 0.106764 - -0.0394915 -0.116738 0.118644 - -0.0395502 -0.117704 0.121335 - -0.0361658 -0.32519 -0.0103411 - -0.036226 -0.32718 -0.00749525 - -0.0365436 -0.333293 0.00713111 - -0.0367812 -0.34135 0.0183826 - -0.0371494 -0.349703 0.0354522 - -0.0378052 -0.369662 0.0663041 - -0.0378299 -0.371251 0.0675403 - -0.0386604 -0.370631 0.10431 - -0.0387566 -0.368745 0.108411 - -0.0392708 -0.372867 0.13158 - -0.0393208 -0.371296 0.133655 - -0.0393566 -0.371666 0.135276 - -0.0397184 -0.381169 0.152163 - -0.0401337 -0.374801 0.170016 - -0.0404066 -0.372145 0.18188 - -0.0405313 -0.368615 0.187098 - -0.041188 -0.384997 0.217671 - -0.0412279 -0.403994 0.221127 - -0.0415016 -0.376815 0.230854 - -0.0415388 -0.37676 0.232498 - -0.0416486 -0.37855 0.237525 - -0.0432767 -0.375268 0.30943 - -0.0439192 -0.392953 0.339491 - -0.0439589 -0.392424 0.341204 - -0.0442445 -0.397612 0.35433 - -0.0465198 -0.387103 0.454297 - -0.0468134 -0.389466 0.467523 - -0.0482022 -0.393218 0.529444 - -0.0493006 -0.395015 0.578311 - -0.0604817 -0.742417 1.10495 - -0.0605605 -0.651284 1.10036 - -0.0610683 -0.643342 1.12217 - -0.0675941 -0.653757 1.41248 - -0.0720711 -0.655477 1.61116 - -0.0742464 -0.653783 1.70748 - -0.0797374 -0.672874 1.95267 - -0.0839748 -0.679234 2.14114 - -0.0853394 -0.681274 2.20183 - -0.0861762 -0.61427 2.23299 - -0.0860436 -0.6026 2.22608 - -0.0861012 -0.574071 2.2261 - -0.0864233 -0.520075 2.23559 - -0.0865591 -0.502454 2.24005 - -0.0865411 -0.389315 2.22922 - -0.0871959 -0.130714 2.23532 - -0.0873655 -0.0690301 2.23736 - -0.087488 0.00146618 2.23654 - -0.0878613 0.107608 2.24368 - -0.0878381 0.213238 2.23328 - -0.0879911 0.258154 2.23608 - -0.0882014 0.339484 2.23819 - -0.088361 0.421579 2.23799 - -0.0884014 0.440038 2.23814 - -0.088655 0.589665 2.23611 - -0.0890699 0.680187 2.24648 - -0.0890642 0.689673 2.24538 - -0.0889535 0.716814 2.23807 - -0.0891095 0.79714 2.23786 - -0.0895693 1.00943 2.23942 - -0.0896133 1.02094 2.24035 - -0.0896136 1.04221 2.23847 - -0.0897269 1.15368 2.23361 - -0.0900058 1.23979 2.23834 - -0.0897318 1.31407 2.2196 - -0.0860166 1.31198 2.05503 - -0.0845346 1.31227 1.98929 - -0.0838833 1.31442 1.96022 - -0.0787207 1.30596 1.73203 - -0.0775208 1.3159 1.67795 - -0.0740031 1.29563 1.52375 - -0.0722106 1.30394 1.44353 - -0.0679424 1.30379 1.25427 - -0.0657602 1.29511 1.15827 - -0.0591056 0.971674 0.891869 - -0.0485285 0.393521 0.474121 - -0.0463842 0.431432 0.375668 - -0.0461595 0.432853 0.36558 - -0.0461752 0.444565 0.365234 - -0.0463922 0.563567 0.364303 - -0.0432385 0.315813 0.246431 - -0.0427986 0.302865 0.228071 - -0.0427391 0.302932 0.225428 - -0.0426302 0.29399 0.221392 - -0.0426013 0.293997 0.220109 - -0.0424291 0.294924 0.212392 - -0.0423697 0.293856 0.209851 - -0.0422573 0.297646 0.20453 - -0.041682 0.347169 0.174627 - -0.0406514 0.367675 0.127105 - -0.0386942 0.717964 0.00924061 - -0.0386218 0.717041 0.00611074 - -0.0376176 0.835055 -0.0488888 - -0.0336045 0.905343 -0.233083 - -0.0337331 0.74793 -0.213414 - -0.0337184 0.706699 -0.210408 - -0.0400793 0.118473 0.123846 - -0.0401244 0.101744 0.127327 - -0.0362719 -0.164881 0.0555047 - -0.0368995 -0.160624 0.0742904 - -0.0369214 -0.161253 0.0749923 - -0.0388548 -0.112749 0.130714 - -0.0386432 -0.123448 0.124945 - -0.0349894 -0.274498 0.0232436 - -0.0341678 -0.317446 0.00092028 - -0.0351533 -0.343752 0.0324214 - -0.0353655 -0.34262 0.0387933 - -0.0360942 -0.353656 0.0615754 - -0.0374206 -0.373496 0.103028 - -0.0375194 -0.370171 0.105824 - -0.0382775 -0.374427 0.129086 - -0.0386676 -0.37503 0.140962 - -0.0388729 -0.377312 0.147329 - -0.0394724 -0.379311 0.165643 - -0.040247 -0.378849 0.189119 - -0.0405452 -0.372415 0.197777 - -0.0410135 -0.377946 0.212323 - -0.0416064 -0.382812 0.23061 - -0.0421013 -0.378057 0.24534 - -0.0427127 -0.382298 0.264147 - -0.043707 -0.390632 0.294827 - -0.0440264 -0.384598 0.304153 - -0.0445419 -0.382876 0.319688 - -0.0454344 -0.382081 0.346724 - -0.0457402 -0.388268 0.356378 - -0.0458157 -0.389544 0.358747 - -0.0459395 -0.389244 0.362486 - -0.0464265 -0.38676 0.377113 - -0.0464942 -0.386988 0.379181 - -0.0465512 -0.386284 0.380867 - -0.04762 -0.385625 0.413259 - -0.0478178 -0.384816 0.419212 - -0.0479155 -0.386591 0.422286 - -0.0480715 -0.38744 0.427072 - -0.0490995 -0.386735 0.458221 - -0.0519836 -0.393408 0.546144 - -0.0523997 -0.394443 0.558833 - -0.0535385 -0.383665 0.592734 - -0.0689576 -0.771792 1.08419 - -0.0696835 -0.656918 1.09924 - -0.0743554 -0.643863 1.24021 - -0.0762974 -0.648676 1.29943 - -0.0798199 -0.650875 1.40645 - -0.10693 -0.622462 2.22738 - -0.107051 -0.565306 2.22758 - -0.107405 -0.444835 2.231 - -0.10753 -0.408436 2.23257 - -0.107615 -0.344517 2.23129 - -0.107788 -0.272688 2.23217 - -0.107855 -0.24593 2.23259 - -0.107836 -0.183281 2.2282 - -0.108073 -0.139444 2.23271 - -0.108802 0.0633422 2.24252 - -0.108426 0.0893111 2.22954 - -0.10875 0.222027 2.23131 - -0.10919 0.40257 2.2337 - -0.109303 0.421375 2.23598 - -0.109994 0.640471 2.24366 - -0.110021 0.766734 2.23681 - -0.11023 0.81886 2.23999 - -0.110437 1.00764 2.2348 - -0.110793 1.19012 2.23452 - -0.111142 1.25438 2.24121 - -0.111028 1.2998 2.23499 - -0.107123 1.31864 2.11537 - -0.104046 1.31325 2.02232 - -0.100163 1.30831 1.90479 - -0.0978869 1.31205 1.83549 - -0.0803417 1.30705 1.3034 - -0.0790463 1.3055 1.26418 - -0.0779399 1.29859 1.23103 - -0.0753952 1.30163 1.15363 - -0.051276 0.39128 0.477025 - -0.0512927 0.409519 0.476422 - -0.0506307 0.4124 0.456161 - -0.0507645 0.438537 0.458634 - -0.0508099 0.457713 0.458847 - -0.0509747 0.570093 0.457023 - -0.0478013 0.427126 0.369411 - -0.0477412 0.42778 0.367547 - -0.047681 0.428426 0.36568 - -0.0478722 0.516304 0.366145 - -0.0479724 0.539741 0.367762 - -0.048134 0.632803 0.367015 - -0.0481384 0.653585 0.365886 - -0.0509753 1.30465 0.412439 - -0.0468184 0.824316 0.315467 - -0.043719 0.338458 0.250919 - -0.0435511 0.314695 0.247267 - -0.0429049 0.296826 0.228741 - -0.0421381 0.299704 0.205301 - -0.0415084 0.315239 0.18525 - -0.036545 0.712205 0.0105324 - -0.0360781 0.728541 -0.00462647 - -0.0294827 1.2892 -0.238804 - -0.0290075 0.875533 -0.228107 - -0.0293192 0.786109 -0.213219 - -0.0294835 0.708702 -0.203532 - -0.0387903 0.142206 0.113278 - -0.0390022 0.120386 0.12103 - -0.0375713 0.157562 0.0753557 - -0.0367676 0.176134 0.0498398 - -0.0352432 -0.170558 0.0715817 - -0.0380032 -0.113094 0.132397 - -0.0329364 -0.286141 0.0238613 - -0.0337759 -0.346464 0.0459415 - -0.0343141 -0.351361 0.0585405 - -0.0349553 -0.358925 0.0736312 - -0.0350891 -0.360174 0.0767661 - -0.0353598 -0.358255 0.0829012 - -0.035846 -0.361278 0.0942194 - -0.0372034 -0.37169 0.125909 - -0.0377964 -0.371753 0.139546 - -0.0382855 -0.366803 0.150564 - -0.0384221 -0.360205 0.153402 - -0.03865 -0.382538 0.15967 - -0.0406616 -0.372781 0.205473 - -0.0411302 -0.384997 0.21681 - -0.0415612 -0.3919 0.227037 - -0.0434544 -0.378473 0.269947 - -0.0450214 -0.389097 0.306467 - -0.0453359 -0.389438 0.313714 - -0.0468993 -0.386251 0.349513 - -0.0474261 -0.394566 0.362009 - -0.0489717 -0.392972 0.397473 - -0.0508552 -0.388791 0.440587 - -0.0509307 -0.387816 0.442279 - -0.0538506 -0.393677 0.509683 - -0.0556995 -0.394348 0.552227 - -0.0558573 -0.395165 0.555891 - -0.0582865 -0.362194 0.610228 - -0.0646036 -0.488739 0.761299 - -0.0794356 -0.758542 1.11474 - -0.0793648 -0.709639 1.11086 - -0.079891 -0.642762 1.11989 - -0.0824374 -0.647405 1.17865 - -0.0880369 -0.647526 1.3074 - -0.103961 -0.647279 1.67352 - -0.120834 -0.670385 2.06253 - -0.122223 -0.672778 2.0946 - -0.127712 -0.669007 2.22063 - -0.127998 -0.651491 2.22639 - -0.128251 -0.556264 2.22783 - -0.128249 -0.546695 2.22734 - -0.128239 -0.527602 2.22623 - -0.128412 -0.472066 2.22766 - -0.128477 -0.463061 2.22873 - -0.129197 -0.246415 2.23531 - -0.12926 -0.237603 2.23636 - -0.128981 -0.201118 2.22827 - -0.129304 -0.184007 2.23492 - -0.129627 -0.0425987 2.23582 - -0.129617 0.0366485 2.23194 - -0.129692 0.0806512 2.23165 - -0.129949 0.116157 2.23592 - -0.129862 0.221917 2.22906 - -0.130766 0.496092 2.23723 - -0.130985 0.657509 2.23483 - -0.13081 0.675417 2.22996 - -0.132048 1.16797 2.23576 - -0.131944 1.18961 2.23238 - -0.118204 1.31382 1.91075 - -0.11557 1.31312 1.8502 - -0.110809 1.31511 1.74064 - -0.103855 1.30795 1.58109 - -0.103315 1.31841 1.5682 - -0.0942639 1.30602 1.36066 - -0.0901721 1.30941 1.26642 - -0.0887714 1.30411 1.23446 - -0.0865024 1.30616 1.18219 - -0.0760216 1.06128 0.952484 - -0.0534098 0.465856 0.459986 - -0.0535402 0.573782 0.458016 - -0.053201 0.575949 0.450118 - -0.0497804 0.439891 0.377732 - -0.0493719 0.432502 0.36868 - -0.0495448 0.565829 0.366517 - -0.0497167 0.657487 0.366251 - -0.0499008 0.721664 0.367531 - -0.05025 0.79621 0.372128 - -0.0544578 1.29814 0.445772 - -0.0428696 0.292905 0.2256 - -0.0424881 0.296996 0.216639 - -0.0422648 0.298923 0.211416 - -0.0407238 0.347169 0.173765 - -0.0399603 0.318269 0.15754 - -0.0347891 0.711014 0.0205618 - -0.0320986 0.797554 -0.0452821 - -0.0240259 1.23684 -0.251114 - -0.0244327 0.945734 -0.228363 - -0.024403 0.912849 -0.227531 - -0.0248553 0.790622 -0.211505 - -0.0252385 0.649952 -0.19622 - -0.0373454 0.142845 0.105491 - -0.0350424 0.193083 0.0502259 - -0.0335798 -0.153458 0.067402 - -0.0338033 -0.151887 0.0715173 - -0.033259 -0.169007 0.061994 - -0.0330542 -0.18351 0.0587126 - -0.0341262 -0.171242 0.0782688 - -0.0305248 -0.331851 0.0170343 - -0.0312652 -0.328315 0.030726 - -0.0321801 -0.33425 0.0480295 - -0.0329567 -0.352507 0.0632119 - -0.0344541 -0.358295 0.0913872 - -0.0373192 -0.366866 0.1452 - -0.0381801 -0.360547 0.161037 - -0.0392071 -0.372145 0.180647 - -0.0410281 -0.375987 0.214791 - -0.0414279 -0.40696 0.223413 - -0.041994 -0.377697 0.232887 - -0.042712 -0.382923 0.24649 - -0.0447339 -0.386289 0.284366 - -0.0452117 -0.387687 0.293339 - -0.0453113 -0.388334 0.295223 - -0.046368 -0.380837 0.314671 - -0.048121 -0.381518 0.347426 - -0.0486764 -0.378927 0.357701 - -0.0503652 -0.385391 0.389472 - -0.0506089 -0.386605 0.394068 - -0.0522274 -0.392783 0.424518 - -0.0528334 -0.388974 0.435691 - -0.0550074 -0.382827 0.47605 - -0.0550988 -0.381695 0.477716 - -0.0563888 -0.391357 0.502161 - -0.0567298 -0.389197 0.508448 - -0.0582955 -0.391609 0.537771 - -0.0595795 -0.392209 0.561767 - -0.0596739 -0.390703 0.563472 - -0.0604892 -0.390396 0.578684 - -0.0617628 -0.360812 0.601357 - -0.0882015 -0.721181 1.10847 - -0.0877425 -0.65069 1.09726 - -0.0879016 -0.646841 1.10009 - -0.0890097 -0.643922 1.12067 - -0.0914559 -0.639585 1.16618 - -0.0929006 -0.645607 1.19337 - -0.0981647 -0.645075 1.29164 - -0.110829 -0.653171 1.52839 - -0.114035 -0.653379 1.58826 - -0.117929 -0.642 1.66054 - -0.121215 -0.64589 1.72204 - -0.148724 -0.472751 2.22919 - -0.148943 -0.445698 2.23227 - -0.149064 -0.436891 2.23419 - -0.148854 -0.389886 2.22852 - -0.149319 -0.345698 2.23554 - -0.149167 -0.281752 2.2303 - -0.149329 -0.264154 2.23268 - -0.150253 0.0456234 2.23834 - -0.150315 0.0897989 2.23786 - -0.150194 0.222246 2.23063 - -0.150265 0.231267 2.23163 - -0.150495 0.493708 2.22611 - -0.151233 0.543695 2.23802 - -0.151024 0.589665 2.2324 - -0.151275 0.638662 2.23526 - -0.151296 0.785416 2.23015 - -0.151934 0.933823 2.23652 - -0.151901 0.975926 2.23432 - -0.152697 1.00459 2.24811 - -0.152131 1.06493 2.23529 - -0.152113 1.15467 2.2316 - -0.152549 1.18231 2.2387 - -0.15292 1.20966 2.24462 - -0.152963 1.26957 2.24317 - -0.151819 1.31681 2.22004 - -0.150369 1.32369 2.19272 - -0.127417 1.3134 1.76457 - -0.12499 1.30927 1.7194 - -0.118615 1.31576 1.60014 - -0.118199 1.31971 1.59223 - -0.114781 1.31476 1.52858 - -0.107932 1.3066 1.40102 - -0.104022 1.31509 1.32769 - -0.0991623 1.30884 1.2372 - -0.0976231 1.30696 1.20853 - -0.0968605 1.31156 1.19412 - -0.0933026 1.28126 1.12883 - -0.0873599 1.15313 1.02266 - -0.0555825 0.427696 0.45648 - -0.05554 0.430485 0.455581 - -0.0556812 0.452243 0.457403 - -0.0516607 0.432367 0.383081 - -0.0512614 0.435192 0.37552 - -0.0508237 0.430613 0.367519 - -0.0512178 0.637671 0.367135 - -0.0510733 0.649683 0.363987 - -0.0561739 1.30501 0.434713 - -0.0558922 1.30792 0.429344 - -0.0440478 0.306728 0.245641 - -0.0429338 0.295904 0.225245 - -0.0427958 0.295958 0.222666 - -0.0425019 0.286999 0.217515 - -0.0421038 0.293893 0.209824 - -0.0415533 0.294436 0.199525 - -0.0407668 0.320211 0.183877 - -0.0399702 0.326339 0.168775 - -0.0397056 0.319517 0.164089 - -0.0332036 0.705953 0.0282404 - -0.0319212 0.708446 0.00420423 - -0.0317541 0.707507 0.00111961 - -0.0312215 0.718936 -0.00925216 - -0.0294409 0.784071 -0.0449341 - -0.0202628 0.866763 -0.219388 - -0.0202147 0.85861 -0.219981 - -0.0203077 0.80746 -0.216331 - -0.0228912 0.580923 -0.159624 - -0.0333254 0.173239 0.0504367 - -0.0315574 -0.168325 0.0609199 - -0.0316499 -0.184729 0.0628777 - -0.0317002 -0.185402 0.0636837 - -0.0319615 -0.182212 0.0676631 - -0.0338149 -0.154796 0.0957351 - -0.0361188 -0.119797 0.130603 - -0.0365637 -0.113571 0.137353 - -0.0372057 -0.10451 0.14709 - -0.0359005 -0.139677 0.127816 - -0.0303301 -0.276589 0.0451507 - -0.0292595 -0.325761 0.0299776 - -0.0300383 -0.34062 0.0425987 - -0.0308224 -0.345619 0.054994 - -0.0316016 -0.346757 0.0671921 - -0.0319323 -0.351179 0.0724924 - -0.0336459 -0.359071 0.0994876 - -0.0339229 -0.361541 0.103889 - -0.0344663 -0.367278 0.11255 - -0.0356945 -0.372271 0.131877 - -0.0365935 -0.370125 0.145843 - -0.0397266 -0.373318 0.194848 - -0.0405738 -0.369879 0.207965 - -0.0418062 -0.391857 0.22789 - -0.0446527 -0.374048 0.271763 - -0.0448856 -0.376523 0.275477 - -0.0460224 -0.381469 0.293375 - -0.0463319 -0.379462 0.298144 - -0.0468073 -0.381888 0.305641 - -0.0504401 -0.393934 0.362723 - -0.0541151 -0.38925 0.41994 - -0.0550659 -0.392545 0.434884 - -0.0554792 -0.387816 0.441188 - -0.0559802 -0.385556 0.448937 - -0.0563101 -0.390522 0.454243 - -0.061619 -0.391609 0.537143 - -0.0630209 -0.386212 0.558857 - -0.0647608 -0.392323 0.586208 - -0.0966851 -0.764324 1.09616 - -0.097592 -0.67728 1.10759 - -0.0982808 -0.642182 1.11725 - -0.112138 -0.644686 1.33362 - -0.114619 -0.64707 1.37243 - -0.115689 -0.64976 1.38921 - -0.123506 -0.645151 1.51108 - -0.124261 -0.643905 1.52283 - -0.145686 -0.654321 1.85758 - -0.170145 -0.464855 2.23345 - -0.170551 -0.273493 2.23379 - -0.17061 -0.228674 2.23331 - -0.171117 -0.175802 2.23958 - -0.170988 -0.148896 2.23672 - -0.170464 0.0277703 2.22301 - -0.172463 0.377791 2.24326 - -0.171777 0.39396 2.23206 - -0.172207 0.590226 2.23262 - -0.172345 0.657818 2.23267 - -0.173125 0.740237 2.24227 - -0.172791 0.798242 2.23522 - -0.172584 0.807057 2.23173 - -0.171284 1.32647 2.19518 - -0.134417 1.32411 1.61979 - -0.132131 1.31349 1.58444 - -0.125894 1.31947 1.48689 - -0.0928952 1.11147 0.978321 - -0.0591888 0.408673 0.474175 - -0.0584792 0.456479 0.461604 - -0.058503 0.475801 0.461371 - -0.0583024 0.583263 0.454878 - -0.0523306 0.458516 0.365566 - -0.0525577 0.566796 0.365723 - -0.0526139 0.58843 0.365923 - -0.0531999 0.754652 0.369871 - -0.058986 1.29125 0.443401 - -0.0572025 1.29687 0.415387 - -0.0462051 0.425608 0.270981 - -0.0440925 0.299984 0.241934 - -0.0428838 0.289935 0.223381 - -0.0424085 0.295996 0.215774 - -0.0419958 0.296892 0.209303 - -0.04183 0.296811 0.206718 - -0.0411696 0.295263 0.196458 - -0.0405118 0.312397 0.185654 - -0.0401331 0.333812 0.179072 - -0.0400396 0.333642 0.177619 - -0.0393715 0.322169 0.16755 - -0.0386107 0.324163 0.155612 - -0.0306911 0.711014 0.0198902 - -0.0236441 0.910305 -0.0963421 - -0.0157393 1.2647 -0.230816 - -0.0147664 1.27294 -0.24626 - -0.0146926 1.08034 -0.241386 - -0.0153759 0.929339 -0.225997 - -0.015757 0.780719 -0.2154 - -0.0174637 0.691638 -0.185972 - -0.0167447 0.682772 -0.196919 - -0.03774 0.103352 0.148927 - -0.0313745 0.2236 0.0458048 - -0.0312789 0.194603 0.0452203 - -0.0316776 0.171082 0.0521787 - -0.0287493 -0.188079 0.0525726 - -0.0310944 -0.171297 0.0823421 - -0.0326387 -0.156032 0.101837 - -0.0335426 -0.143271 0.113149 - -0.0370446 -0.0933987 0.156963 - -0.0370757 -0.0936596 0.15737 - -0.0280473 -0.33425 0.0473073 - -0.0283523 -0.340763 0.0514045 - -0.0289309 -0.333169 0.05866 - -0.0291066 -0.343168 0.0611805 - -0.0298302 -0.346216 0.0705794 - -0.0308245 -0.34494 0.0833526 - -0.0320264 -0.35381 0.0990606 - -0.0340867 -0.36062 0.125772 - -0.0346825 -0.369715 0.133681 - -0.0365335 -0.367205 0.157455 - -0.0379913 -0.3728 0.176374 - -0.0400231 -0.371723 0.202515 - -0.0403798 -0.376877 0.207241 - -0.0458021 -0.368105 0.27685 - -0.0461116 -0.384604 0.281263 - -0.0465738 -0.389628 0.287346 - -0.0498004 -0.391151 0.328941 - -0.050663 -0.384678 0.339883 - -0.0542669 -0.390543 0.38645 - -0.0554895 -0.384463 0.402039 - -0.0577372 -0.382869 0.430947 - -0.0621683 -0.38808 0.48815 - -0.0634061 -0.385193 0.504018 - -0.0638971 -0.386642 0.510379 - -0.0643036 -0.390111 0.515704 - -0.0666877 -0.393506 0.546497 - -0.069277 -0.393332 0.57984 - -0.0697029 -0.392323 0.585299 - -0.0708795 -0.387481 0.600328 - -0.109515 -0.676675 1.1054 - -0.122627 -0.641989 1.27337 - -0.15792 -0.642041 1.72792 - -0.160711 -0.641397 1.76385 - -0.177253 -0.667617 1.97757 - -0.197103 -0.587291 2.23115 - -0.197378 -0.345192 2.22843 - -0.197853 -0.264674 2.23247 - -0.19749 -0.228224 2.22686 - -0.198388 -0.166877 2.23683 - -0.198412 -0.122396 2.236 - -0.197473 -0.0512066 2.22207 - -0.198001 -0.0337529 2.22842 - -0.198014 0.133446 2.22427 - -0.198646 0.187124 2.23101 - -0.198598 0.195938 2.23018 - -0.198362 0.222246 2.22645 - -0.199117 0.28594 2.23453 - -0.198953 0.30359 2.23196 - -0.199096 0.376144 2.23192 - -0.199806 0.423623 2.23985 - -0.199673 0.46937 2.23694 - -0.19988 0.544733 2.23766 - -0.199712 0.553573 2.23527 - -0.199817 0.572853 2.23613 - -0.20038 0.710308 2.23983 - -0.20038 0.769929 2.23829 - -0.200326 0.789774 2.23709 - -0.19974 0.827297 2.22857 - -0.200021 0.859512 2.23136 - -0.200694 0.904834 2.23885 - -0.20082 1.01256 2.2377 - -0.2006 1.11111 2.23231 - -0.201368 1.22108 2.23936 - -0.200838 1.2528 2.23172 - -0.17065 1.3215 1.84115 - -0.169605 1.32226 1.82767 - -0.151298 1.32248 1.59188 - -0.149005 1.31701 1.56248 - -0.119898 1.31823 1.18758 - -0.119271 1.31924 1.17948 - -0.11699 1.30325 1.15051 - -0.0666112 0.457023 0.523538 - -0.0612184 0.403235 0.455471 - -0.0614576 0.441168 0.457573 - -0.0614315 0.449429 0.457023 - -0.0617763 0.461959 0.46114 - -0.0559098 0.438166 0.386199 - -0.0549192 0.433312 0.373566 - -0.0545243 0.460713 0.367773 - -0.055097 0.719048 0.368473 - -0.0592137 1.28388 0.406901 - -0.0562546 1.09269 0.373729 - -0.0421494 0.297971 0.212598 - -0.0402103 0.301583 0.18753 - -0.0400965 0.303443 0.186017 - -0.0391981 0.324171 0.17391 - -0.038679 0.320193 0.167327 - -0.0375834 0.318708 0.153255 - -0.0373116 0.322057 0.149669 - -0.0343254 0.443823 0.108062 - -0.0295063 0.697716 0.039437 - -0.0288897 0.703873 0.0313362 - -0.0249887 0.704432 -0.0189202 --0.00805704 1.21705 -0.250231 - -0.0088239 1.11124 -0.23762 - -0.0181203 0.703574 -0.107357 - -0.0108669 0.773052 -0.20257 - -0.0357696 0.138304 0.134556 - -0.0367539 0.11481 0.14784 - -0.035623 0.125491 0.132999 - -0.0310733 0.202609 0.0724097 - -0.0288519 0.218221 0.0433967 - -0.0287964 0.215142 0.0427612 - -0.0287223 0.214379 0.0418271 - -0.0282471 -0.154886 0.0649534 - -0.0271776 -0.185111 0.053455 - -0.0341127 -0.129314 0.131223 - -0.0361917 -0.0989953 0.154224 - -0.0357723 -0.11148 0.149731 - -0.027306 -0.282981 0.0571585 - -0.0262587 -0.315619 0.0459686 - -0.0267749 -0.334653 0.0522878 - -0.0279064 -0.337462 0.0652483 - -0.0290978 -0.34223 0.0789361 - -0.0294245 -0.34156 0.0826451 - -0.0300517 -0.353974 0.0900771 - -0.0313403 -0.346265 0.104589 - -0.0315401 -0.354392 0.107052 - -0.0319436 -0.355798 0.111683 - -0.0348114 -0.363923 0.144555 - -0.0364348 -0.370168 0.163201 - -0.0416728 -0.412931 0.223881 - -0.0422704 -0.383755 0.230024 - -0.0434333 -0.381049 0.243217 - -0.0436947 -0.374819 0.246054 - -0.0441667 -0.381367 0.251583 - -0.0480534 -0.391911 0.296124 - -0.0502274 -0.382944 0.320697 - -0.0530832 -0.387325 0.353347 - -0.0545061 -0.384415 0.369499 - -0.0571209 -0.388782 0.399402 - -0.0606271 -0.38695 0.439322 - -0.0637098 -0.390904 0.474549 - -0.0650883 -0.395833 0.490372 - -0.0672669 -0.393802 0.515157 - -0.0696835 -0.389678 0.542607 - -0.0717907 -0.389895 0.566629 - -0.073478 -0.393778 0.585949 - -0.0743459 -0.373308 0.595373 - -0.125905 -0.639148 1.18912 - -0.128073 -0.643031 1.21391 - -0.128617 -0.640803 1.22006 - -0.166262 -0.646658 1.64926 - -0.179982 -0.643163 1.80556 - -0.214614 -0.664891 2.20079 - -0.217102 -0.548531 2.22647 - -0.218234 -0.429527 2.23666 - -0.218069 -0.309926 2.23204 - -0.218076 -0.291829 2.2317 - -0.218809 -0.229799 2.23864 - -0.218338 -0.184461 2.23223 - -0.218366 -0.0602803 2.22971 - -0.21844 -0.0426409 2.23015 - -0.219226 0.214291 2.23324 - -0.219074 0.223013 2.23129 - -0.219024 0.303442 2.22888 - -0.219772 0.534351 2.23213 - -0.220067 0.582515 2.23439 - -0.219736 0.600456 2.2302 - -0.220229 0.650222 2.23469 - -0.220598 0.671018 2.23841 - -0.220201 0.698837 2.23325 - -0.219829 0.776615 2.22724 - -0.220481 0.850687 2.23297 - -0.221632 1.10514 2.24026 - -0.22201 1.18837 2.24267 - -0.220129 1.33218 2.21794 - -0.200433 1.3224 1.99368 - -0.182183 1.324 1.78563 - -0.172961 1.31418 1.68074 - -0.167582 1.32685 1.61914 - -0.158083 1.31336 1.51119 - -0.157217 1.31474 1.50128 - -0.141389 1.31204 1.32094 - -0.140117 1.31782 1.30631 - -0.137217 1.31259 1.27338 - -0.0679236 0.432573 0.503732 - -0.0657447 0.41514 0.479296 - -0.0641396 0.421729 0.460852 - -0.0639807 0.422797 0.459016 - -0.0640195 0.453835 0.458749 - -0.0639766 0.457543 0.458174 - -0.0638464 0.459483 0.456646 - -0.0644998 0.561264 0.461764 - -0.0591253 0.475578 0.402468 - -0.0574402 0.439838 0.38408 - -0.0568119 0.438252 0.376954 - -0.0558283 0.436938 0.365774 - -0.0560612 0.462613 0.367841 - -0.0560863 0.54456 0.366252 - -0.0563208 0.632149 0.36692 - -0.045725 0.326911 0.253137 - -0.0450741 0.301497 0.246299 - -0.0425324 0.299997 0.217364 - -0.042418 0.299999 0.21606 - -0.0406042 0.295263 0.195495 - -0.0396235 0.305294 0.184088 - -0.0366972 0.324306 0.1503 - -0.0281747 0.687814 0.0448451 - -0.0248229 0.697915 0.00641122 - -0.022217 0.707181 -0.0235024 --0.00392022 1.16641 -0.242552 --0.00747344 0.874307 -0.19537 --0.00629093 0.843554 -0.208144 --0.00667045 0.806873 -0.202979 --0.00663901 0.789931 -0.20295 - -0.0367131 0.10448 0.155512 - -0.0364593 0.108519 0.152527 - -0.0344761 0.132906 0.129365 - -0.0284119 0.222138 0.0582046 - -0.0271992 0.226735 0.0442771 - -0.0255942 -0.164171 0.0541982 - -0.0250309 -0.186651 0.0489199 - -0.025955 -0.192249 0.0584476 - -0.0266367 -0.188842 0.0653214 - -0.0272193 -0.189717 0.0712731 - -0.0304489 -0.161455 0.103591 - -0.0308232 -0.160437 0.107382 - -0.0322534 -0.144746 0.121629 - -0.0323143 -0.145158 0.122258 - -0.0344753 -0.118569 0.143726 - -0.0349284 -0.118992 0.14835 - -0.0248038 -0.322106 0.0493797 - -0.0258475 -0.321882 0.0600063 - -0.0289586 -0.351695 0.0923055 - -0.0300802 -0.348168 0.103657 - -0.0368446 -0.367466 0.172953 - -0.0415263 -0.425958 0.221837 - -0.0427017 -0.384621 0.232963 - -0.044963 -0.378883 0.255879 - -0.0451249 -0.378705 0.257524 - -0.0497623 -0.385785 0.304905 - -0.0503214 -0.387496 0.310636 - -0.0524854 -0.388688 0.332702 - -0.0527322 -0.391041 0.335264 - -0.0537932 -0.389665 0.346043 - -0.0563896 -0.388375 0.372463 - -0.0602262 -0.389195 0.411558 - -0.0624197 -0.386278 0.433841 - -0.0638274 -0.391719 0.448291 - -0.0645001 -0.387585 0.455058 - -0.0677857 -0.386888 0.48851 - -0.0691818 -0.388857 0.502771 - -0.0693962 -0.381073 0.504795 - -0.0734793 -0.388325 0.546534 - -0.0776539 -0.36095 0.588495 - -0.0789946 -0.358124 0.602093 - -0.127413 -0.746913 1.10323 - -0.127369 -0.739822 1.10264 - -0.140666 -0.639397 1.23602 - -0.143566 -0.63888 1.26555 - -0.14768 -0.638491 1.30745 - -0.153459 -0.639593 1.36633 - -0.162436 -0.641489 1.45781 - -0.166482 -0.641587 1.49903 - -0.186805 -0.641949 1.70604 - -0.1991 -0.646183 1.83136 - -0.237934 -0.520325 2.22434 - -0.239019 -0.466649 2.23429 - -0.239233 -0.457796 2.23629 - -0.239603 -0.283829 2.23649 - -0.23916 -0.274163 2.23179 - -0.239422 -0.256477 2.23409 - -0.239524 -0.21166 2.23422 - -0.239508 -0.113558 2.23205 - -0.239475 -0.104666 2.23152 - -0.23995 -0.0339369 2.23491 - -0.240047 0.116559 2.23283 - -0.240023 0.178659 2.23131 - -0.241237 0.593032 2.23519 - -0.241068 0.650222 2.2323 - -0.242211 0.854561 2.23975 - -0.243333 1.17898 2.24455 - -0.234461 1.32625 2.15116 - -0.222594 1.32678 2.03028 - -0.2153 1.31985 1.95612 - -0.209644 1.32305 1.89845 - -0.207141 1.32654 1.87288 - -0.188663 1.31952 1.68481 - -0.15667 1.31204 1.35909 - -0.153649 1.31099 1.32834 - -0.152417 1.31916 1.31563 - -0.147229 1.3017 1.26314 - -0.141783 1.31253 1.20744 - -0.135257 1.3057 1.14111 - -0.132255 1.28672 1.11092 - -0.12024 1.13621 0.991627 - -0.0686086 0.410302 0.480574 - -0.0679376 0.407546 0.473796 - -0.0671557 0.40665 0.46585 - -0.0669197 0.457164 0.462412 - -0.0668287 0.499736 0.460614 - -0.0670049 0.536891 0.461648 - -0.0666761 0.541763 0.458199 - -0.0667076 0.587763 0.457579 - -0.0585464 0.43567 0.377564 - -0.0583619 0.436375 0.37567 - -0.0579125 0.472113 0.370361 - -0.0574185 0.484303 0.365079 - -0.0575118 0.509242 0.36552 - -0.0581546 0.721004 0.367732 - -0.0671267 1.2932 0.447408 - -0.0655668 1.30107 0.431358 - -0.046767 0.346241 0.259411 - -0.0428791 0.297958 0.220799 - -0.0425005 0.298997 0.21692 - -0.0421202 0.300986 0.213006 - -0.0409707 0.298645 0.201346 - -0.0401957 0.300155 0.193421 - -0.0400791 0.298061 0.192276 - -0.0394274 0.299463 0.185609 - -0.0388973 0.314935 0.179894 - -0.0347888 0.347164 0.137385 - -0.0244375 0.702224 0.0246811 - -0.0235359 0.699651 0.0155501 - -0.0226327 0.685517 0.0066395 - -0.0223388 0.684593 0.00366485 - -0.0208792 0.690264 -0.0113181 - -0.0192718 0.699391 -0.0278776 --0.00494695 1.07957 -0.18157 --0.00252839 1.03167 -0.205224 - -0.0022852 0.905093 -0.20511 - -0.0371548 0.0869996 0.16681 - -0.0269286 0.223514 0.0598542 - -0.0259928 0.220302 0.0503881 - -0.0251917 0.194594 0.0427543 - -0.025188 0.181187 0.0429909 - -0.0223965 -0.179153 0.0407313 - -0.0224796 -0.179919 0.0415102 - -0.02336 -0.180764 0.0496236 - -0.0231579 -0.185917 0.0478598 - -0.0250403 -0.190283 0.0652544 - -0.0286324 -0.166165 0.0978473 - -0.0294132 -0.157692 0.104872 - -0.0314578 -0.149729 0.12353 - -0.027445 -0.342531 0.0901895 - -0.0340267 -0.360205 0.151053 - -0.0417445 -0.412931 0.223014 - -0.0429965 -0.37855 0.233893 - -0.0446033 -0.377533 0.248654 - -0.0460167 -0.375148 0.26161 - -0.0472622 -0.386662 0.273279 - -0.0507639 -0.367101 0.305124 - -0.0525719 -0.385374 0.322092 - -0.0531758 -0.385857 0.327655 - -0.0579775 -0.388375 0.371866 - -0.0602925 -0.386739 0.393128 - -0.0609771 -0.387074 0.399431 - -0.0613447 -0.385445 0.402782 - -0.0644124 -0.386358 0.431014 - -0.0653806 -0.382399 0.439846 - -0.0720049 -0.390916 0.500933 - -0.0721915 -0.38966 0.502625 - -0.0725629 -0.387125 0.505994 - -0.0756624 -0.388665 0.534531 - -0.0767452 -0.386806 0.544456 - -0.0825124 -0.366914 0.597133 - -0.0833061 -0.357778 0.604264 - -0.140838 -0.637098 1.13859 - -0.164633 -0.64219 1.35754 - -0.170327 -0.637607 1.40983 - -0.187172 -0.638866 1.5648 - -0.254513 -0.661092 2.18458 - -0.257799 -0.661506 2.21482 - -0.25958 -0.419253 2.22671 - -0.259863 -0.373751 2.22847 - -0.260905 -0.31144 2.2369 - -0.260852 -0.211971 2.23458 - -0.260843 -0.060489 2.23169 - -0.260887 -0.0516392 2.23193 - -0.26109 0.0545866 2.23183 - -0.260318 0.107343 2.22375 - -0.261452 0.214712 2.2322 - -0.261457 0.313477 2.23042 - -0.262841 0.37018 2.2421 - -0.262037 0.423827 2.23371 - -0.261592 0.459859 2.22895 - -0.262347 0.480046 2.23552 - -0.263372 0.742978 2.24008 - -0.262928 0.832608 2.23434 - -0.262986 0.905649 2.23353 - -0.2625 0.946021 2.2283 - -0.263667 1.10562 2.23609 - -0.263424 1.1503 2.23303 - -0.264012 1.26018 2.2364 - -0.26436 1.27434 2.23934 - -0.23358 1.33292 1.95516 - -0.219472 1.32543 1.82553 - -0.18711 1.31113 1.52814 - -0.185272 1.31692 1.51112 - -0.178169 1.31779 1.44578 - -0.162991 1.30997 1.30632 - -0.159358 1.3157 1.2728 - -0.158538 1.31799 1.26522 - -0.139302 1.26926 1.08919 - -0.120516 1.04367 0.92058 - -0.0715659 0.413659 0.482007 - -0.0701855 0.413456 0.469315 - -0.0689889 0.415482 0.458271 - -0.0692436 0.423458 0.460467 - -0.0692129 0.427129 0.460116 - -0.0690877 0.433614 0.458844 - -0.0692859 0.454527 0.46028 - -0.0690521 0.469405 0.457854 - -0.069786 0.573342 0.462681 - -0.069458 0.586697 0.459417 - -0.0692694 0.589611 0.457629 - -0.0668498 0.557446 0.43597 - -0.0592341 0.4929 0.367117 - -0.0592831 0.607514 0.365447 - -0.0598557 0.742227 0.36822 - -0.0695594 1.29615 0.447223 - -0.0677293 1.29909 0.430336 - -0.0478142 0.364674 0.264453 - -0.0434298 0.294827 0.225419 - -0.0411949 0.299809 0.204771 - -0.0410604 0.296762 0.20359 - -0.0361139 0.31977 0.157668 - -0.0353194 0.320387 0.150349 - -0.022936 0.708707 0.0292657 - -0.0228878 0.697261 0.0290337 --0.00462477 0.950769 -0.143635 - -0.0321557 0.149145 0.124419 - -0.0255778 0.225547 0.0625034 - -0.0244595 0.225596 0.0522176 - -0.0241541 0.207328 0.0497459 - -0.0243212 0.203492 0.0513537 - -0.0238503 0.184196 0.0473798 - -0.0246601 -0.185571 0.075165 - -0.029432 -0.148859 0.114579 - -0.029901 -0.158661 0.11868 - -0.0342634 -0.111388 0.15448 - -0.0343204 -0.111654 0.154963 - -0.0232683 -0.312651 0.065636 - -0.0257584 -0.33282 0.0868673 - -0.0259694 -0.336741 0.0887037 - -0.0266629 -0.338911 0.0945591 - -0.0289121 -0.346208 0.113552 - -0.0290901 -0.346651 0.115053 - -0.0383297 -0.369325 0.192954 - -0.038719 -0.368507 0.196206 - -0.0398507 -0.370879 0.205741 - -0.0487916 -0.384318 0.28098 - -0.0518889 -0.384018 0.30696 - -0.05308 -0.381466 0.31691 - -0.0532485 -0.38005 0.318299 - -0.0556814 -0.382234 0.338747 - -0.0588899 -0.384152 0.365699 - -0.0619352 -0.384015 0.391246 - -0.0639379 -0.389155 0.408134 - -0.0669348 -0.383584 0.433183 - -0.0696487 -0.383784 0.455955 - -0.0712686 -0.390359 0.469657 - -0.0735499 -0.38569 0.488718 - -0.0766163 -0.3888 0.514496 - -0.0777288 -0.390295 0.523855 - -0.0802212 -0.384601 0.544669 - -0.082337 -0.391425 0.562535 - -0.0863839 -0.357088 0.595907 - -0.0919248 -0.3839 0.642847 - -0.146243 -0.737199 1.10453 - -0.157221 -0.639777 1.19499 - -0.172197 -0.64169 1.32067 - -0.178397 -0.638386 1.37262 - -0.181759 -0.640479 1.40086 - -0.187797 -0.640118 1.45152 - -0.201275 -0.639718 1.56459 - -0.280816 -0.6095 2.2314 - -0.280454 -0.550892 2.22737 - -0.280998 -0.140065 2.225 - -0.282491 -0.0251589 2.23558 - -0.282234 0.0458038 2.23222 - -0.282394 0.116846 2.23236 - -0.282718 0.143711 2.23463 - -0.282283 0.286499 2.22857 - -0.282415 0.404724 2.22768 - -0.283121 0.442805 2.23296 - -0.284273 0.557792 2.24068 - -0.283184 0.670704 2.22963 - -0.28432 0.693539 2.23878 - -0.284202 0.703078 2.23763 - -0.28509 0.715594 2.24487 - -0.284238 0.742978 2.23725 - -0.283719 0.761425 2.23259 - -0.284503 1.17497 2.23218 - -0.280225 1.3337 2.1936 - -0.251217 1.3311 1.95028 - -0.242177 1.33153 1.87443 - -0.23127 1.32722 1.783 - -0.209577 1.32678 1.60101 - -0.197094 1.31546 1.49647 - -0.167683 1.31241 1.24977 - -0.1653 1.31041 1.22981 - -0.155695 1.32118 1.14904 - -0.15481 1.32282 1.14159 - -0.150106 1.27934 1.10286 - -0.0720828 0.412248 0.462926 - -0.0724146 0.520785 0.463875 - -0.0718995 0.572584 0.458678 - -0.0613011 0.441526 0.371975 - -0.0606181 0.536196 0.364645 - -0.0611871 0.599395 0.368351 - -0.0635864 0.878678 0.383761 - -0.0724542 1.2902 0.451206 - -0.071147 1.29322 0.440188 - -0.0479098 0.35497 0.261089 - -0.0443958 0.294462 0.23263 - -0.043902 0.289676 0.228568 - -0.0437525 0.289733 0.227312 - -0.0416562 0.292951 0.209671 - -0.040309 0.289521 0.198427 - -0.0396556 0.297164 0.192816 - -0.0230152 0.6905 0.0465609 - -0.0192032 0.690128 0.0145852 - -0.0190042 0.684448 0.0130119 - -0.0187138 0.68164 0.0106228 - -0.0116278 0.700222 -0.0491404 - 0.00349316 1.02398 -0.181472 - 0.00402499 1.02223 -0.185904 - 0.00645084 1.00858 -0.206025 - 0.00712558 0.926902 -0.210306 - -0.0289044 0.179343 0.104607 - -0.0263931 0.208221 0.0830497 - -0.025372 0.215659 0.0743574 - -0.0229262 0.217021 0.0538151 - -0.0228493 0.189983 0.0536265 - -0.0228206 0.18192 0.0535219 - -0.0160463 -0.19601 0.0205448 - -0.0177742 -0.199197 0.033895 - -0.0178849 -0.19999 0.0347589 - -0.0199715 -0.195507 0.0507514 - -0.0216392 -0.191849 0.063532 - -0.0226838 -0.186707 0.0714929 - -0.0244779 -0.178319 0.0851735 - -0.0275772 -0.157129 0.108701 - -0.0278856 -0.155106 0.111044 - -0.028735 -0.151032 0.117519 - -0.0285841 -0.158657 0.116476 - -0.0312903 -0.137232 0.136975 - -0.0224439 -0.310062 0.0715618 - -0.0222544 -0.323781 0.070316 - -0.0230065 -0.329642 0.0761959 - -0.0248669 -0.331128 0.0905395 - -0.0265021 -0.336736 0.103214 - -0.0290245 -0.346834 0.122787 - -0.0299008 -0.351688 0.129608 - -0.0305543 -0.350831 0.134625 - -0.0378348 -0.369225 0.190953 - -0.0380422 -0.369325 0.192551 - -0.0388949 -0.366662 0.199073 - -0.0391147 -0.364728 0.200736 - -0.0444197 -0.389029 0.241948 - -0.0466777 -0.37634 0.259133 - -0.0561307 -0.392518 0.332149 - -0.0603787 -0.383221 0.364705 - -0.0615058 -0.380752 0.373343 - -0.0632368 -0.389044 0.386796 - -0.0634568 -0.388283 0.388478 - -0.0642197 -0.387767 0.394342 - -0.0684994 -0.381997 0.427196 - -0.0819308 -0.393004 0.530757 - -0.0905691 -0.385092 0.597128 - -0.0903147 -0.373039 0.594983 - -0.154491 -0.763735 1.09505 - -0.155916 -0.675185 1.10464 - -0.155969 -0.663169 1.10487 - -0.170214 -0.634802 1.21408 - -0.172785 -0.634919 1.23388 - -0.194998 -0.643788 1.405 - -0.213717 -0.633329 1.54893 - -0.22014 -0.642046 1.5985 - -0.220627 -0.636366 1.60217 - -0.225219 -0.637533 1.63753 - -0.252842 -0.639954 1.8502 - -0.264747 -0.649769 1.94199 - -0.288789 -0.653049 2.12711 - -0.302152 -0.629267 2.22961 - -0.302517 -0.61065 2.23212 - -0.302767 -0.256853 2.22855 - -0.302926 -0.24799 2.22964 - -0.302964 -0.158345 2.22854 - -0.302551 -0.0338867 2.22343 - -0.303613 0.250697 2.22719 - -0.304031 0.314241 2.22942 - -0.304879 0.499668 2.23307 - -0.305206 0.557001 2.2347 - -0.305726 0.577207 2.23838 - -0.305403 0.605296 2.23546 - -0.306334 0.705362 2.24108 - -0.305785 0.835263 2.23483 - -0.307062 1.05459 2.24126 - -0.306551 1.09769 2.23666 - -0.306776 1.20333 2.23675 - -0.306761 1.2513 2.23589 - -0.306047 1.32168 2.22929 - -0.272169 1.33491 1.96831 - -0.270395 1.33655 1.95463 - -0.257971 1.33317 1.85905 - -0.227319 1.32683 1.6232 - -0.191368 1.31553 1.34663 - -0.164071 1.31792 1.13648 - -0.0765785 0.412301 0.477055 - -0.0763487 0.413452 0.475268 - -0.0761666 0.419125 0.473778 - -0.073975 0.428199 0.456767 - -0.0746237 0.488451 0.460825 - -0.074345 0.522048 0.458158 - -0.0742563 0.569827 0.456734 - -0.0736187 0.571938 0.451793 - -0.0632856 0.443651 0.374244 - -0.062167 0.545523 0.364052 - -0.0621535 0.563243 0.363673 - -0.06304 0.716422 0.368119 - -0.0644538 0.828882 0.377256 - -0.059438 0.777843 0.339438 - -0.0489172 0.353342 0.265044 - -0.0446816 0.293384 0.233371 - -0.0432443 0.302901 0.222159 - -0.0410426 0.296854 0.205305 - -0.0390409 0.295961 0.189911 - -0.038531 0.296607 0.185975 - -0.0378603 0.31012 0.180603 - -0.0372953 0.312623 0.176215 - -0.0370905 0.314436 0.17461 - -0.0368537 0.318223 0.172729 - -0.036659 0.319027 0.171217 - -0.0359409 0.318216 0.165703 - -0.0353647 0.319517 0.161247 - -0.0165386 0.680683 0.0107237 - -0.0126721 0.653004 -0.0186092 - -0.0372785 0.0817467 0.17967 - -0.037115 0.0779159 0.178471 - -0.0357361 0.0948285 0.167594 - -0.0356824 0.0946209 0.167184 - -0.0356289 0.0944115 0.166775 - -0.0361804 0.0820822 0.171212 - -0.036134 0.0818907 0.170858 - -0.0290631 0.164925 0.115139 - -0.0259643 0.201442 0.090719 - -0.0242836 0.214364 0.0775809 - -0.0227494 0.224387 0.0656161 - -0.0215953 0.214514 0.0568855 - -0.0218551 0.184588 0.0593499 - -0.0217908 0.180261 0.0589217 - -0.0134668 -0.206148 0.020734 - -0.0159497 -0.203126 0.0380238 - -0.0170725 -0.19935 0.0458085 - -0.0211782 -0.182752 0.0742347 - -0.0242973 -0.167794 0.0957968 - -0.0263906 -0.157224 0.11026 - -0.0265877 -0.164146 0.111734 - -0.0305243 -0.13737 0.138836 - -0.0315945 -0.126599 0.146155 - -0.0326515 -0.119173 0.153429 - -0.0342981 -0.101383 0.164673 - -0.0212069 -0.324434 0.0764334 - -0.0222299 -0.323109 0.0835556 - -0.0226282 -0.324248 0.086352 - -0.0234811 -0.325516 0.0923236 - -0.0256859 -0.326774 0.107732 - -0.0257288 -0.335321 0.108153 - -0.0285749 -0.34317 0.128131 - -0.0303321 -0.351208 0.140511 - -0.0337369 -0.359503 0.164396 - -0.0380897 -0.374499 0.194992 - -0.041818 -0.404932 0.221447 - -0.0425158 -0.382812 0.226006 - -0.0434191 -0.373555 0.232182 - -0.0436504 -0.373472 0.233795 - -0.0438816 -0.373382 0.235408 - -0.0449011 -0.38392 0.242673 - -0.0453074 -0.376678 0.245407 - -0.0477648 -0.382878 0.262649 - -0.049147 -0.379488 0.27225 - -0.049917 -0.381645 0.277655 - -0.0502534 -0.375163 0.279912 - -0.0547774 -0.386651 0.311655 - -0.0551521 -0.390089 0.314319 - -0.0559564 -0.377204 0.319752 - -0.0565003 -0.378179 0.323562 - -0.0598377 -0.383202 0.346931 - -0.0600758 -0.382613 0.348584 - -0.0629823 -0.381208 0.368854 - -0.0646566 -0.385959 0.380608 - -0.0648413 -0.384307 0.381874 - -0.0674599 -0.384547 0.400157 - -0.0698454 -0.392796 0.416926 - -0.079964 -0.390153 0.487523 - -0.0874195 -0.391209 0.539582 - -0.0911267 -0.393608 0.565495 - -0.0930184 -0.390867 0.578662 - -0.0966046 -0.362872 0.603301 - -0.168121 -0.756546 1.10808 - -0.167354 -0.650026 1.10123 - -0.166965 -0.642025 1.0984 - -0.167369 -0.638121 1.10116 - -0.183739 -0.630928 1.21534 - -0.19635 -0.6342 1.30342 - -0.219814 -0.636869 1.46725 - -0.220217 -0.63134 1.46999 - -0.238455 -0.635538 1.59736 - -0.251982 -0.63229 1.69174 - -0.26127 -0.636132 1.75663 - -0.263113 -0.633441 1.76946 - -0.303145 -0.654916 2.04921 - -0.313075 -0.651445 2.11848 - -0.317911 -0.653493 2.15226 - -0.326397 -0.653958 2.21151 - -0.329022 -0.543594 2.22827 - -0.329099 -0.534203 2.22868 - -0.328963 -0.514951 2.22746 - -0.329404 -0.440486 2.22949 - -0.329272 -0.403138 2.22804 - -0.329981 -0.35797 2.23236 - -0.330036 -0.284937 2.23171 - -0.329751 -0.257481 2.22933 - -0.330285 -0.212802 2.23243 - -0.330854 -0.195191 2.23615 - -0.330314 -0.141031 2.23161 - -0.329805 -0.122939 2.22781 - -0.329982 -0.105182 2.22879 - -0.331018 0.0460066 2.23389 - -0.330328 0.0903311 2.22845 - -0.330949 0.108351 2.23253 - -0.330999 0.242667 2.23099 - -0.331792 0.481885 2.23315 - -0.332486 0.539713 2.23718 - -0.332884 0.5691 2.23954 - -0.332547 0.578023 2.23706 - -0.331552 0.614472 2.2296 - -0.3322 0.723839 2.23258 - -0.33217 0.763881 2.23181 - -0.33377 1.24187 2.23624 - -0.333657 1.32768 2.23424 - -0.314271 1.33552 2.0988 - -0.26714 1.3328 1.76983 - -0.241449 1.32196 1.59065 - -0.232176 1.32749 1.52584 - -0.209712 1.32125 1.36911 - -0.184862 1.31847 1.19568 - -0.168387 1.27721 1.08126 - -0.153557 1.14878 0.979548 - -0.142086 1.04067 0.900996 - -0.0803303 0.416508 0.478703 - -0.0800745 0.417671 0.476901 - -0.0779579 0.413959 0.462178 - -0.0779676 0.452359 0.461705 - -0.0777716 0.488451 0.459827 - -0.0772714 0.519334 0.4559 - -0.077526 0.566004 0.457019 - -0.0782569 0.591145 0.461766 - -0.0657767 0.446698 0.376683 - -0.0643745 0.496721 0.36619 - -0.0644643 0.521709 0.366464 - -0.0643039 0.542935 0.365045 - -0.0649338 0.595813 0.368697 - -0.0647156 0.600363 0.367109 - -0.076049 1.25285 0.437021 - -0.0623359 0.810824 0.34753 - -0.0502905 0.367711 0.269694 - -0.0472999 0.296797 0.249818 - -0.0456051 0.295001 0.238012 - -0.0448195 0.29039 0.232593 - -0.0423093 0.293997 0.21502 - -0.0408638 0.289858 0.204987 - -0.0404975 0.291766 0.202404 - -0.0399558 0.291588 0.198624 - -0.0389585 0.30215 0.191514 - -0.0378613 0.299463 0.183892 - -0.0366261 0.318578 0.175 - -0.0363966 0.320387 0.173373 - -0.0332085 0.317728 0.151155 - -0.0310563 0.348139 0.135703 - -0.0212128 0.632901 0.0629726 - -0.0185112 0.688784 0.043325 - -0.017093 0.690337 0.0334034 - -0.0109887 0.651298 -0.0086583 - -0.0307684 0.192455 0.135888 - -0.0373503 0.0673147 0.1836 - -0.0352422 0.0899581 0.168565 - -0.0257902 0.189351 0.101181 - -0.0209302 0.226525 0.0667314 - -0.0214884 0.210047 0.0708598 - -0.0207558 0.207654 0.0657798 - -0.0202399 0.205009 0.0622156 - -0.0218356 0.181139 0.0736916 - -0.0214974 0.179268 0.0713571 - -0.0185457 0.193023 0.0505581 - -0.0159579 0.198133 0.0324216 - -0.0244604 -0.158657 0.10504 - -0.0251352 -0.168838 0.109553 - -0.0290583 -0.14437 0.134691 - -0.0298612 -0.139235 0.139834 - -0.0299532 -0.139559 0.140435 - -0.028775 -0.34401 0.135474 - -0.0292313 -0.344687 0.138445 - -0.0310932 -0.3543 0.150654 - -0.0313281 -0.354575 0.152182 - -0.0332945 -0.363683 0.165063 - -0.033601 -0.36092 0.167016 - -0.0368782 -0.370114 0.188405 - -0.0415597 -0.387962 0.21902 - -0.0421132 -0.413894 0.222953 - -0.0430613 -0.376698 0.228618 - -0.0483185 -0.388829 0.262895 - -0.0490726 -0.374048 0.267594 - -0.0500168 -0.382191 0.273829 - -0.0589921 -0.384785 0.33211 - -0.0628124 -0.381429 0.356859 - -0.0648367 -0.385835 0.370053 - -0.0678877 -0.385831 0.389854 - -0.0734633 -0.382869 0.425998 - -0.0751982 -0.391278 0.437368 - -0.0755236 -0.383129 0.439373 - -0.0816742 -0.3868 0.479337 - -0.082105 -0.383624 0.482091 - -0.086713 -0.382229 0.511977 - -0.0903206 -0.387381 0.535457 - -0.0922041 -0.384696 0.547645 - -0.100598 -0.395997 0.602267 - -0.100595 -0.389034 0.602153 - -0.0994879 -0.365236 0.594659 - -0.125203 -0.482455 0.763085 - -0.178269 -0.753877 1.11103 - -0.178797 -0.636008 1.11291 - -0.180773 -0.633137 1.12569 - -0.209437 -0.633853 1.31173 - -0.219661 -0.638536 1.37814 - -0.228005 -0.626972 1.43213 - -0.240979 -0.641693 1.51652 - -0.24613 -0.629141 1.54979 - -0.258749 -0.637533 1.63179 - -0.274449 -0.635667 1.73366 - -0.285181 -0.632145 1.80326 - -0.334048 -0.653369 2.12067 - -0.350339 -0.582044 2.22545 - -0.351425 -0.230699 2.22789 - -0.351593 -0.221804 2.22886 - -0.351131 -0.17658 2.22527 - -0.351965 -0.150143 2.23033 - -0.352562 -0.0788015 2.23327 - -0.352419 -0.0252454 2.23164 - -0.35245 -0.016336 2.23173 - -0.351866 -0.00741171 2.22782 - -0.353032 0.225205 2.23233 - -0.352912 0.252168 2.2312 - -0.353392 0.361804 2.23287 - -0.352167 0.433934 2.22398 - -0.354925 0.737132 2.23789 - -0.355345 0.768443 2.2402 - -0.354882 0.902027 2.23545 - -0.355794 1.19644 2.2375 - -0.354187 1.25025 2.22637 - -0.355198 1.2665 2.23271 - -0.3571 1.31143 2.24447 - -0.353125 1.34489 2.21823 - -0.348927 1.33926 2.19106 - -0.345139 1.34766 2.16637 - -0.294673 1.33409 1.83904 - -0.29007 1.33312 1.80918 - -0.282266 1.32569 1.75862 - -0.213238 1.3253 1.31066 - -0.205455 1.32189 1.2602 - -0.200834 1.31909 1.23024 - -0.185923 1.31955 1.13347 - -0.143439 0.984104 0.862171 - -0.0799513 0.432542 0.457395 - -0.0808263 0.460464 0.462707 - -0.0804527 0.517181 0.459538 - -0.0660748 0.478493 0.366737 - -0.0663445 0.497953 0.368232 - -0.0656721 0.530726 0.363438 - -0.0668362 0.684121 0.368978 - -0.0412717 0.30095 0.208104 - -0.0410717 0.300923 0.206807 - -0.0350081 0.321602 0.167184 - -0.0344762 0.316023 0.163806 - -0.0283717 0.394553 0.123158 - -0.0103528 0.654171 0.00281122 - -0.0346829 0.0921447 0.168087 - -0.0318831 0.122966 0.149513 - -0.021165 0.209568 0.0788182 - -0.0189708 0.203266 0.0646614 - -0.0202317 0.188374 0.0730397 - -0.0179731 0.1868 0.0584023 - -0.017072 0.192216 0.0524834 - -0.0158347 0.198357 0.044373 - -0.0149394 0.199842 0.0385438 - -0.0128908 0.19696 0.0252864 --0.00926533 -0.197573 0.0202661 - -0.0113973 -0.197665 0.0332105 - -0.0136303 -0.197828 0.0467689 - -0.0184327 -0.174015 0.0756303 - -0.0200357 -0.16772 0.0852845 - -0.0207881 -0.166207 0.0898341 - -0.0290171 -0.14375 0.139515 - -0.0320849 -0.12611 0.157922 - -0.0223446 -0.321523 0.101194 - -0.0235572 -0.32724 0.108627 - -0.0264751 -0.347048 0.126585 - -0.0287008 -0.343061 0.140047 - -0.0295887 -0.354417 0.145577 - -0.0305264 -0.34938 0.151208 - -0.0336696 -0.356355 0.170376 - -0.0349512 -0.356224 0.178155 - -0.0410152 -0.371994 0.215163 - -0.0439233 -0.372474 0.232824 - -0.0477816 -0.39759 0.256556 - -0.050073 -0.384685 0.270308 - -0.0501402 -0.375535 0.270604 - -0.050407 -0.375278 0.27222 - -0.0518417 -0.387964 0.281086 - -0.0521715 -0.389628 0.283109 - -0.0524483 -0.389316 0.284785 - -0.0545882 -0.384598 0.297718 - -0.0589652 -0.384898 0.324295 - -0.0664485 -0.38676 0.369748 - -0.0677058 -0.391093 0.377434 - -0.0704678 -0.383465 0.394108 - -0.0748172 -0.394524 0.420649 - -0.0754391 -0.381125 0.42426 - -0.0760246 -0.383668 0.427845 - -0.0823336 -0.390359 0.466229 - -0.0834353 -0.389456 0.472906 - -0.0874064 -0.384392 0.496952 - -0.0922862 -0.39517 0.52671 - -0.0965086 -0.387709 0.552252 - -0.0974918 -0.387667 0.55822 - -0.100018 -0.391008 0.573599 - -0.104227 -0.376915 0.598975 - -0.112453 -0.386714 0.649039 - -0.121232 -0.43067 0.702874 - -0.187005 -0.724787 1.1058 - -0.186665 -0.66614 1.10301 - -0.202697 -0.635972 1.19997 - -0.204295 -0.629869 1.20959 - -0.219164 -0.634699 1.29992 - -0.239526 -0.630516 1.42349 - -0.260781 -0.631672 1.55254 - -0.268775 -0.632306 1.60108 - -0.273684 -0.630865 1.63086 - -0.346515 -0.647487 2.07321 - -0.350667 -0.646954 2.09841 - -0.359602 -0.646507 2.15265 - -0.373092 -0.508725 2.23285 - -0.372144 -0.284937 2.22435 - -0.373215 -0.213321 2.22996 - -0.374351 -0.0342714 2.23466 - -0.373694 0.180153 2.22803 - -0.37472 0.362327 2.23202 - -0.374963 0.427301 2.23269 - -0.375199 0.483725 2.23343 - -0.376374 0.523337 2.24008 - -0.376157 0.628919 2.23746 - -0.375977 0.73747 2.23503 - -0.375961 0.767741 2.23456 - -0.377219 0.916649 2.24037 - -0.376216 1.00053 2.23325 - -0.376547 1.01256 2.23511 - -0.376023 1.11231 2.2307 - -0.376185 1.13594 2.23139 - -0.378491 1.25122 2.24397 - -0.373411 1.34323 2.212 - -0.345856 1.33869 2.04477 - -0.326824 1.33688 1.92925 - -0.322751 1.34154 1.90447 - -0.31753 1.34025 1.87279 - -0.28994 1.34025 1.70529 - -0.240663 1.32208 1.40636 - -0.233215 1.31751 1.3612 - -0.199996 1.32263 1.15947 - -0.193506 1.31541 1.12015 - -0.0853258 0.420518 0.474416 - -0.0834176 0.461341 0.46233 - -0.0829618 0.475419 0.459389 - -0.0826264 0.476504 0.45734 - -0.0832645 0.583613 0.459895 - -0.0823072 0.598076 0.453906 - -0.0693626 0.445976 0.377192 - -0.0681323 0.443409 0.369755 - -0.0674498 0.443833 0.365606 - -0.067524 0.457479 0.365888 - -0.0675737 0.49223 0.365762 - -0.0678225 0.82506 0.363177 - -0.0530948 0.391314 0.279104 - -0.0503387 0.331137 0.263113 - -0.0487109 0.303234 0.253574 - -0.0472836 0.297246 0.244983 - -0.0458367 0.300089 0.236164 - -0.0432072 0.288906 0.220338 - -0.0373085 0.299593 0.184396 - -0.0365598 0.306144 0.17977 - -0.0332681 0.322475 0.159585 - -0.0319669 0.310863 0.151829 - -0.0166508 0.666928 0.054465 - -0.0126222 0.524779 0.0317566 - -0.0213748 0.318489 0.087431 - -0.0356911 0.0768522 0.177318 - -0.0304844 0.130928 0.145043 - -0.0263927 0.170482 0.119716 - -0.0206411 0.208525 0.0843299 - -0.0189379 0.214823 0.0739124 - -0.0187328 0.179734 0.0730993 - -0.0153695 0.193691 0.0525093 - -0.0134898 0.202143 0.0409939 - -0.0130295 0.203642 0.0381812 --0.00927862 -0.200673 0.0319611 - -0.0124562 -0.195507 0.0500329 - -0.0164942 -0.175738 0.0728453 - -0.0257691 -0.145013 0.125413 - -0.0284554 -0.150151 0.140801 - -0.0205103 -0.298749 0.0971864 - -0.0201658 -0.319491 0.0954612 - -0.0220162 -0.315881 0.105978 - -0.0230425 -0.321031 0.111894 - -0.0232836 -0.321476 0.113275 - -0.0235251 -0.321914 0.114657 - -0.0286188 -0.337821 0.143907 - -0.0291729 -0.344599 0.147147 - -0.0308137 -0.352399 0.1566 - -0.037664 -0.36559 0.195842 - -0.0392883 -0.370917 0.205172 - -0.0398634 -0.366971 0.208408 - -0.042144 -0.402897 0.221837 - -0.0446658 -0.378275 0.235942 - -0.0458174 -0.378806 0.242519 - -0.0466737 -0.37838 0.2474 - -0.0472905 -0.381044 0.250951 - -0.0514781 -0.373756 0.274761 - -0.055961 -0.383837 0.300458 - -0.0578608 -0.385249 0.311314 - -0.0625016 -0.383586 0.337776 - -0.0658466 -0.37986 0.35682 - -0.0661337 -0.379219 0.358451 - -0.0695429 -0.389445 0.378022 - -0.0723914 -0.385269 0.394228 - -0.0726829 -0.384463 0.395882 - -0.081338 -0.384369 0.445268 - -0.0880737 -0.384876 0.483708 - -0.0905418 -0.386795 0.497813 - -0.093257 -0.389843 0.513342 - -0.0939535 -0.387948 0.517294 - -0.0965048 -0.388798 0.531862 - -0.0996781 -0.386212 0.549939 - -0.10305 -0.387354 0.569194 - -0.108028 -0.390038 0.597628 - -0.108424 -0.372114 0.599682 - -0.108707 -0.370397 0.601277 - -0.196717 -0.754516 1.10792 - -0.196936 -0.742134 1.10903 - -0.1969 -0.709196 1.10844 - -0.196468 -0.688165 1.10573 - -0.198686 -0.630308 1.11771 - -0.222346 -0.633244 1.25276 - -0.226604 -0.628932 1.277 - -0.229759 -0.633201 1.29506 - -0.240757 -0.629958 1.35777 - -0.258494 -0.629557 1.45898 - -0.360898 -0.64748 2.04351 - -0.382809 -0.643475 2.16849 - -0.392914 -0.555352 2.22513 - -0.394676 -0.510173 2.23466 - -0.393501 -0.368103 2.22631 - -0.394427 -0.177617 2.22939 - -0.394575 -0.168683 2.23013 - -0.394897 0.0461644 2.22948 - -0.395677 0.126945 2.23299 - -0.394906 0.135628 2.22849 - -0.394952 0.243613 2.2275 - -0.39615 0.262596 2.23412 - -0.396088 0.503005 2.23098 - -0.39732 0.5333 2.23766 - -0.398111 0.631264 2.24104 - -0.397485 0.639947 2.23736 - -0.397214 0.688773 2.23525 - -0.396625 0.798488 2.23062 - -0.396361 0.93413 2.22754 - -0.396932 0.946402 2.23066 - -0.398719 1.119 2.23886 - -0.399529 1.204 2.2425 - -0.392203 1.34983 2.199 - -0.384873 1.34654 2.15722 - -0.363519 1.34678 2.03536 - -0.252792 1.32208 1.40383 - -0.23611 1.32836 1.30857 - -0.160145 1.01405 0.878748 - -0.0856135 0.42755 0.460257 - -0.085702 0.483603 0.460113 - -0.0853701 0.517181 0.45783 - -0.0689924 0.546785 0.364034 - -0.0698854 0.624298 0.368231 - -0.0696061 0.704021 0.365714 - -0.0558427 0.427773 0.290379 - -0.0500635 0.31454 0.258714 - -0.0480928 0.291834 0.247732 - -0.0465181 0.290794 0.238759 - -0.0447766 0.29254 0.228802 - -0.0430132 0.292934 0.218735 - -0.0406099 0.283897 0.205126 - -0.0397488 0.284719 0.200203 - -0.0385442 0.298345 0.193172 - -0.0345698 0.314073 0.170311 - -0.0322742 0.318051 0.157166 - -0.0305651 0.317162 0.147424 - -0.0302235 0.319804 0.145444 - -0.0294598 0.33416 0.14092 - -0.0126292 0.647043 0.0412582 - -0.0165858 0.389843 0.0668151 - -0.0348697 0.0932835 0.17458 - -0.0173275 0.217951 0.0730386 - -0.0167625 0.208593 0.0699231 - -0.018398 0.182377 0.0795589 - -0.0079623 -0.184936 0.0355224 - -0.0101088 -0.182234 0.047009 - -0.01242 -0.190613 0.0595001 - -0.0190176 -0.155062 0.0945091 - -0.0212946 -0.145576 0.106622 - -0.0243496 -0.137657 0.122926 - -0.0252973 -0.136224 0.127994 - -0.0258178 -0.13563 0.13078 - -0.0279003 -0.13634 0.141961 - -0.0277177 -0.142614 0.14105 - -0.0276815 -0.149252 0.140928 - -0.0321286 -0.115098 0.164414 - -0.0236285 -0.319764 0.121045 - -0.0238835 -0.320166 0.122417 - -0.0253495 -0.329599 0.130386 - -0.0287324 -0.342922 0.14868 - -0.0292801 -0.343475 0.151625 - -0.0343485 -0.356376 0.178958 - -0.0376345 -0.371657 0.196754 - -0.0385927 -0.362838 0.201799 - -0.0462806 -0.372692 0.243153 - -0.0486433 -0.370382 0.255804 - -0.0513861 -0.371327 0.270529 - -0.0552128 -0.383727 0.291195 - -0.0562476 -0.385574 0.296767 - -0.0598139 -0.384873 0.315893 - -0.0610949 -0.383938 0.322756 - -0.0686473 -0.388802 0.363328 - -0.0706506 -0.386492 0.374051 - -0.0769116 -0.3848 0.407623 - -0.0813996 -0.389659 0.431755 - -0.0839514 -0.386073 0.445406 - -0.0948827 -0.382478 0.504014 - -0.0968413 -0.389293 0.514597 - -0.100488 -0.385957 0.534125 - -0.101463 -0.385358 0.53935 - -0.101774 -0.383904 0.541 - -0.106378 -0.381405 0.565674 - -0.11228 -0.387627 0.59741 - -0.111818 -0.371751 0.594758 - -0.123541 -0.393306 0.657889 - -0.133217 -0.435675 0.710261 - -0.206392 -0.677241 1.10549 - -0.206701 -0.660008 1.10696 - -0.221255 -0.628996 1.1847 - -0.254136 -0.633294 1.36116 - -0.270024 -0.631475 1.44638 - -0.280428 -0.631598 1.5022 - -0.371046 -0.647148 1.98854 - -0.383321 -0.643588 2.05436 - -0.401719 -0.639775 2.15303 - -0.415471 -0.614962 2.22654 - -0.415753 -0.557188 2.22742 - -0.417694 -0.241925 2.23439 - -0.416421 0.108723 2.22374 - -0.419226 0.581561 2.23362 - -0.420494 0.661833 2.23955 - -0.420109 0.82302 2.23572 - -0.420522 0.962106 2.23643 - -0.420188 1.04976 2.23367 - -0.419526 1.05918 2.23002 - -0.421749 1.32851 2.23901 - -0.376937 1.34681 1.99839 - -0.332387 1.33474 1.7595 - -0.302914 1.33165 1.60141 - -0.29694 1.33544 1.56932 - -0.284824 1.32829 1.5044 - -0.245123 1.32243 1.29146 - -0.240211 1.32503 1.26508 - -0.238346 1.32423 1.25508 - -0.207236 1.29947 1.08844 - -0.0986129 0.470216 0.51472 - -0.0882945 0.428412 0.459817 - -0.0882879 0.468816 0.459341 - -0.0879095 0.500448 0.456965 - -0.0883699 0.55818 0.458806 - -0.0710742 0.440584 0.367296 - -0.0711649 0.516518 0.366954 - -0.064339 0.615566 0.329251 - -0.0495386 0.299091 0.2533 - -0.0479228 0.292134 0.244707 - -0.0469408 0.302744 0.239323 - -0.0443588 0.288677 0.225623 - -0.0441281 0.288733 0.224385 - -0.0432312 0.292905 0.219528 - -0.0408931 0.289952 0.207016 - -0.0392774 0.288656 0.198362 - -0.0376246 0.291083 0.189468 - -0.0373917 0.290979 0.188219 - -0.0368515 0.295734 0.185269 - -0.0355557 0.301027 0.178259 - -0.0335291 0.313686 0.167248 - -0.017 0.587819 0.075576 - -0.0140471 0.586883 0.0597433 - -0.0131534 0.584544 0.0549745 - -0.0121742 0.564389 0.0499408 - -0.0107674 0.537025 0.0426917 - -0.0147204 0.421251 0.0651638 - -0.0155864 0.401776 0.0700227 - -0.0345948 0.092691 0.175378 - -0.0345204 0.0925263 0.174981 - -0.034083 0.0936872 0.172621 - -0.033275 0.100457 0.168212 - -0.0314379 0.11778 0.158167 - -0.0280317 0.146395 0.13958 - -0.0273032 0.151076 0.135621 - -0.026518 0.157828 0.131334 - -0.0155376 0.201606 0.0719453 - -0.0143814 0.192029 0.0658469 - -0.0110308 0.19905 0.0477941 - -0.0125619 -0.165625 0.0683835 - -0.0136881 -0.170631 0.0741439 - -0.0211548 -0.140843 0.111686 - -0.0246879 -0.138556 0.129572 - -0.0261575 -0.165337 0.137298 - -0.0260509 -0.168398 0.136789 - -0.0319095 -0.114801 0.165933 - -0.0321029 -0.115206 0.166918 - -0.0195157 -0.312572 0.105151 - -0.0259819 -0.321269 0.138019 - -0.0280201 -0.341939 0.148565 - -0.0340408 -0.365484 0.179327 - -0.0411553 -0.381982 0.215562 - -0.043419 -0.382693 0.227045 - -0.0452387 -0.371185 0.23615 - -0.0483342 -0.38485 0.251982 - -0.0486595 -0.384668 0.253629 - -0.049482 -0.377133 0.257721 - -0.0500022 -0.371755 0.260302 - -0.0511003 -0.377017 0.265923 - -0.058223 -0.381102 0.302071 - -0.0635278 -0.389129 0.329045 - -0.0830053 -0.388018 0.427767 - -0.0934482 -0.386888 0.480691 - -0.0993363 -0.385369 0.510523 - -0.100828 -0.388155 0.518115 - -0.101487 -0.385418 0.521425 - -0.108358 -0.389152 0.556294 - -0.112238 -0.386917 0.57594 - -0.113766 -0.391764 0.583733 - -0.11678 -0.390441 0.599001 - -0.117113 -0.388716 0.600668 - -0.116118 -0.376915 0.595502 - -0.120578 -0.362339 0.617963 - -0.215126 -0.752599 1.10127 - -0.215576 -0.727914 1.10329 - -0.217111 -0.628045 1.11005 - -0.231856 -0.630606 1.18481 - -0.272318 -0.6305 1.38992 - -0.279442 -0.622486 1.42595 - -0.2817 -0.621537 1.43738 - -0.2965 -0.631026 1.51251 - -0.298785 -0.629496 1.52407 - -0.341721 -0.620662 1.74163 - -0.436154 -0.624187 2.22036 - -0.436879 -0.615537 2.22394 - -0.437413 -0.606584 2.22656 - -0.437858 -0.529813 2.22802 - -0.437718 -0.500975 2.22701 - -0.439549 -0.251503 2.23371 - -0.438488 -0.205395 2.22786 - -0.439462 -0.097387 2.23168 - -0.438558 0.0373211 2.22571 - -0.438708 0.0552591 2.22628 - -0.440315 0.190813 2.23303 - -0.439974 0.199704 2.23121 - -0.442221 0.692589 2.23751 - -0.441135 0.80212 2.23087 - -0.442653 1.01965 2.23631 - -0.442903 1.16953 2.23603 - -0.442267 1.17951 2.23271 - -0.339185 1.34024 1.70851 - -0.326718 1.32966 1.64542 - -0.325029 1.33332 1.63683 - -0.294696 1.33254 1.48307 - -0.286219 1.32181 1.44021 - -0.280758 1.32634 1.41248 - -0.245274 1.32244 1.23265 - -0.170026 0.991965 0.854625 - -0.102885 0.479419 0.519576 - -0.0932135 0.427919 0.471082 - -0.0923913 0.429354 0.466899 - -0.0910655 0.426449 0.460209 - -0.0907071 0.42755 0.45838 - -0.0909226 0.455859 0.45918 - -0.0911074 0.462218 0.460051 - -0.0911734 0.588209 0.459084 - -0.0769394 0.457895 0.388277 - -0.0741123 0.449513 0.374032 - -0.0731381 0.515826 0.368409 - -0.0725145 0.537741 0.365021 - -0.0734521 0.655771 0.368555 - -0.0727787 0.705974 0.364622 - -0.0609476 0.479253 0.306992 - -0.0562673 0.381906 0.284273 - -0.0469068 0.290794 0.237765 - -0.0400648 0.278863 0.203206 - -0.0343455 0.312623 0.173865 - -0.0338171 0.312275 0.17119 - -0.0335774 0.3111 0.169987 - -0.0150998 0.596578 0.0733721 - -0.0124958 0.573647 0.0604089 - -0.0237951 0.253649 0.120993 - -0.0262568 0.214788 0.133873 - -0.0339744 0.0934516 0.174248 - -0.0328499 0.103985 0.168439 - -0.0307261 0.124202 0.157465 - -0.0232051 0.176109 0.118804 - -0.0230898 0.173522 0.118246 - -0.0154246 0.198283 0.0791342 - -0.0156887 0.194396 0.0805133 - -0.0146719 0.180783 0.0754995 --0.00829823 0.197609 0.0430168 --0.00986601 0.184873 0.0510956 --0.00926794 0.173968 0.0481766 - -0.0136552 -0.13374 0.0807535 - -0.0101318 -0.156206 0.0640394 - -0.0131723 -0.153634 0.0786278 - -0.0133122 -0.156914 0.0793323 - -0.0177842 -0.14636 0.100723 - -0.0187975 -0.145105 0.105581 - -0.0184449 -0.150078 0.103935 - -0.025595 -0.14707 0.138272 - -0.0251016 -0.169308 0.136119 - -0.0287317 -0.142062 0.153299 - -0.024211 -0.3274 0.133391 - -0.0267938 -0.331263 0.145842 - -0.033863 -0.353534 0.180039 - -0.034177 -0.353671 0.181549 - -0.0388058 -0.369917 0.203957 - -0.0404552 -0.366999 0.211856 - -0.0467986 -0.375682 0.24243 - -0.0501338 -0.37395 0.258443 - -0.0589098 -0.385391 0.300737 - -0.0669783 -0.389665 0.339559 - -0.0680989 -0.383556 0.344885 - -0.0864921 -0.387697 0.433331 - -0.0923633 -0.385069 0.461525 - -0.0941743 -0.391113 0.470288 - -0.0974232 -0.392199 0.485915 - -0.10125 -0.381967 0.504208 - -0.108363 -0.386872 0.538445 - -0.109531 -0.383218 0.544023 - -0.114183 -0.388085 0.566428 - -0.121553 -0.377616 0.601749 - -0.120513 -0.359803 0.596578 - -0.124713 -0.359219 0.616757 - -0.226173 -0.639446 1.10717 - -0.229559 -0.633041 1.12338 - -0.24206 -0.625208 1.18339 - -0.258003 -0.623397 1.26 - -0.283343 -0.62771 1.38183 - -0.286246 -0.628484 1.3958 - -0.441359 -0.63885 2.14144 - -0.458942 -0.42595 2.22385 - -0.460205 -0.324825 2.22893 - -0.460676 -0.206091 2.23003 - -0.461214 -0.133754 2.2319 - -0.460325 0.037412 2.22595 - -0.461886 0.154904 2.2323 - -0.460817 0.172577 2.22699 - -0.462644 0.209693 2.23541 - -0.461296 0.254497 2.22849 - -0.462076 0.273255 2.23205 - -0.461888 0.430367 2.22961 - -0.463148 0.45992 2.23537 - -0.46338 0.526793 2.23583 - -0.463321 0.536313 2.23545 - -0.462499 0.564122 2.23123 - -0.46533 0.59716 2.24451 - -0.464353 0.755315 2.23826 - -0.463987 0.77511 2.23631 - -0.463188 0.825247 2.23198 - -0.463649 0.878691 2.23367 - -0.463258 0.888487 2.23169 - -0.463382 0.910095 2.23208 - -0.465367 1.05794 2.24017 - -0.464323 1.101 2.23472 - -0.464902 1.20854 2.23645 - -0.463992 1.27914 2.23138 - -0.452236 1.3547 2.17414 - -0.436345 1.3516 2.09779 - -0.425603 1.35156 2.04616 - -0.406157 1.34274 1.95278 - -0.384461 1.34444 1.84849 - -0.369673 1.34459 1.77741 - -0.358391 1.34473 1.72318 - -0.3146 1.33174 1.51283 - -0.293791 1.33001 1.41283 - -0.287364 1.33035 1.38193 - -0.244977 1.32519 1.17826 - -0.23798 1.3268 1.14461 - -0.0940428 0.439013 0.461506 - -0.0935857 0.481616 0.45889 - -0.0940226 0.528894 0.460526 - -0.0747257 0.460831 0.368446 - -0.0743112 0.467898 0.366384 - -0.0744839 0.56315 0.366279 - -0.04683 0.290907 0.236036 - -0.0421599 0.28999 0.213598 - -0.0419157 0.294997 0.212375 - -0.041129 0.292986 0.208614 - -0.0398226 0.293856 0.202326 - -0.0360687 0.298721 0.184236 - -0.0330063 0.313082 0.169375 - -0.0130558 0.562049 0.0710407 - -0.0113681 0.553677 0.0630112 - -0.0108644 0.543675 0.0606884 - -0.0332555 0.130028 0.172371 - -0.0344105 0.086652 0.178348 - -0.033034 0.0979015 0.171622 - -0.0285718 0.139454 0.149767 - -0.0252846 0.166018 0.133706 - -0.0244379 0.16174 0.129678 - -0.0218233 0.171811 0.117013 --0.00925026 0.193483 0.0563686 --0.00740858 0.17906 0.0476583 --0.00724832 0.178329 0.0468953 - -0.0105039 -0.159491 0.0746269 - -0.0132247 -0.153092 0.0868563 - -0.0162583 -0.145076 0.100484 - -0.016668 -0.146545 0.102348 - -0.0187174 -0.149686 0.111633 - -0.0226799 -0.153853 0.129568 - -0.0233397 -0.172256 0.132719 - -0.0321323 -0.108859 0.171845 - -0.0253924 -0.202086 0.142266 - -0.0201677 -0.307041 0.119639 - -0.022324 -0.30264 0.129338 - -0.0234443 -0.315403 0.134516 - -0.02792 -0.336116 0.154922 - -0.0368993 -0.365662 0.195751 - -0.04452 -0.368479 0.230197 - -0.0498901 -0.373361 0.254497 - -0.054231 -0.384604 0.274207 - -0.0545942 -0.384318 0.275845 - -0.0577434 -0.387643 0.290099 - -0.062693 -0.386294 0.312442 - -0.0673262 -0.390391 0.333406 - -0.072444 -0.382014 0.356443 - -0.0735582 -0.385343 0.361506 - -0.0755858 -0.389049 0.370699 - -0.0761538 -0.385771 0.373234 - -0.0795016 -0.388673 0.388381 - -0.0819646 -0.382054 0.399445 - -0.0853472 -0.37947 0.414698 - -0.089941 -0.385706 0.435504 - -0.101889 -0.381189 0.489425 - -0.102507 -0.381538 0.492223 - -0.102998 -0.381073 0.494437 - -0.108657 -0.383267 0.520015 - -0.110938 -0.382246 0.530306 - -0.11676 -0.389097 0.556668 - -0.127291 -0.358617 0.603948 - -0.128309 -0.353319 0.608495 - -0.237076 -0.738786 1.10332 - -0.236818 -0.711656 1.1019 - -0.236915 -0.66177 1.10188 - -0.292572 -0.627244 1.35294 - -0.321256 -0.612885 1.48236 - -0.480845 -0.631929 2.20333 - -0.48618 -0.570924 2.22687 - -0.486732 -0.56191 2.22927 - -0.487152 -0.466375 2.23029 - -0.486018 -0.242392 2.22309 - -0.488577 -0.170653 2.23399 - -0.48789 -0.161299 2.2308 - -0.486765 0.0284887 2.22396 - -0.487788 0.0917058 2.228 - -0.489271 0.1192 2.23444 - -0.489171 0.128242 2.23391 - -0.48894 0.366337 2.23066 - -0.490427 0.423768 2.23684 - -0.489068 0.526793 2.22975 - -0.488585 0.535811 2.22749 - -0.490614 0.675472 2.23536 - -0.490915 0.860629 2.23501 - -0.491003 0.946591 2.23461 - -0.491451 1.0137 2.23601 - -0.492082 1.03758 2.23864 - -0.491636 1.082 2.23621 - -0.43632 1.34621 1.98393 - -0.427328 1.3517 1.94327 - -0.378531 1.34867 1.7229 - -0.356926 1.34168 1.62539 - -0.32567 1.32973 1.48432 - -0.308545 1.32781 1.407 - -0.304291 1.32957 1.38777 - -0.287694 1.33571 1.31275 - -0.261645 1.32846 1.19516 - -0.0992777 0.434186 0.470089 - -0.0968935 0.527092 0.458461 - -0.0973089 0.542858 0.460191 - -0.0783076 0.451598 0.375214 - -0.0765671 0.508446 0.366827 - -0.0741052 0.640267 0.354489 - -0.0516485 0.295352 0.256252 - -0.0467635 0.30607 0.234089 - -0.046475 0.306172 0.232785 - -0.0439474 0.285787 0.221558 - -0.0434336 0.288871 0.219208 - -0.0409806 0.290986 0.20811 - -0.0395986 0.292856 0.201851 - -0.0390728 0.288768 0.199514 - -0.0382556 0.288592 0.195824 - -0.0290543 0.304517 0.154118 - -0.0314099 0.112156 0.166537 - -0.0313038 0.111957 0.16606 - -0.0311979 0.111756 0.165584 - -0.0241646 0.157106 0.133397 - -0.0190488 0.174835 0.110127 --0.00936513 0.182521 0.0663192 --0.00919202 0.181874 0.0655433 - -0.0103319 0.149425 0.0709918 --0.00973062 -0.137875 0.0776182 - -0.0105706 -0.140093 0.0812504 --0.00834939 -0.154311 0.0718231 --0.00854811 -0.165871 0.0727798 --0.00990338 -0.161734 0.0785719 - -0.0176836 -0.147592 0.111907 - -0.0209086 -0.15875 0.125876 - -0.0220713 -0.155817 0.13085 - -0.0218522 -0.160972 0.129953 - -0.0233046 -0.169643 0.136276 - -0.0276229 -0.140724 0.154592 - -0.0254151 -0.19701 0.145595 - -0.0211155 -0.306496 0.12807 - -0.026667 -0.3255 0.152113 - -0.0295582 -0.337715 0.164655 - -0.0331631 -0.358652 0.180344 - -0.0342633 -0.357034 0.185061 - -0.037751 -0.362838 0.200112 - -0.0381095 -0.362882 0.201654 - -0.0564793 -0.387349 0.280873 - -0.0593472 -0.380693 0.293148 - -0.0625169 -0.38762 0.306841 - -0.0801166 -0.391017 0.382562 - -0.0839839 -0.391792 0.399201 - -0.0881519 -0.385605 0.417072 - -0.0885343 -0.384677 0.418708 - -0.0915582 -0.38856 0.431747 - -0.0933587 -0.382664 0.439438 - -0.13099 -0.393619 0.601376 - -0.129001 -0.368343 0.592597 - -0.254898 -0.627965 1.13633 - -0.298516 -0.625897 1.32391 - -0.323294 -0.636946 1.43056 - -0.426248 -0.602949 1.87304 - -0.472328 -0.628383 2.07144 - -0.508954 -0.582634 2.22855 - -0.509402 -0.534556 2.23005 - -0.509951 -0.458426 2.23174 - -0.508438 -0.419163 2.22489 - -0.508982 -0.382101 2.2269 - -0.509373 -0.373065 2.2285 - -0.510358 -0.225697 2.23144 - -0.509617 0.0647178 2.22569 - -0.509566 0.0737448 2.22539 - -0.509506 0.0827704 2.22505 - -0.509743 0.146178 2.22551 - -0.510289 0.155428 2.22778 - -0.511254 0.192197 2.2316 - -0.511754 0.201539 2.23367 - -0.511181 0.237875 2.23089 - -0.510959 0.246924 2.22985 - -0.512 0.321272 2.23367 - -0.511731 0.348933 2.23227 - -0.513577 0.453876 2.23928 - -0.513585 0.463395 2.23923 - -0.514025 0.473365 2.24104 - -0.513571 0.482458 2.239 - -0.513107 0.491541 2.23693 - -0.513548 0.638004 2.23753 - -0.515438 0.986035 2.24259 - -0.51413 1.08477 2.23609 - -0.51572 1.28007 2.2412 - -0.456588 1.35157 1.98626 - -0.406431 1.34652 1.7706 - -0.349382 1.34072 1.5253 - -0.339143 1.34186 1.48125 - -0.327736 1.33601 1.43224 - -0.323775 1.32904 1.41527 - -0.319924 1.33388 1.39867 - -0.275378 1.32436 1.20717 - -0.259219 1.32518 1.13767 - -0.244631 1.30666 1.0751 - -0.101676 0.43248 0.46801 - -0.0999081 0.445323 0.460294 - -0.0993726 0.459359 0.457867 - -0.0995832 0.465726 0.458716 - -0.100038 0.484041 0.460512 - -0.0997813 0.53632 0.458945 - -0.0997819 0.573891 0.458616 - -0.0829024 0.461618 0.387014 - -0.0776818 0.488006 0.364328 - -0.0786978 0.575665 0.367924 - -0.0657233 0.459004 0.313154 - -0.0503077 0.297461 0.248283 - -0.0489674 0.292134 0.242566 - -0.047342 0.29788 0.235525 - -0.0466752 0.294107 0.232691 - -0.0458034 0.294382 0.228939 - -0.0437759 0.295827 0.220207 - -0.0313507 0.307748 0.166664 - -0.0277115 0.304979 0.151038 - -0.0128117 0.544998 0.0848385 - -0.0332211 0.0980093 0.176561 - -0.0186509 0.177916 0.113193 - -0.0184745 0.177479 0.112438 - -0.0180602 0.175284 0.110676 - -0.0155489 0.181399 0.0998216 - -0.0150693 0.181245 0.0977601 - -0.0139213 0.187464 0.0927679 - -0.011931 0.190021 0.084186 - -0.0107886 0.193811 0.0792393 - -0.0108636 0.14986 0.0799498 --0.00875632 0.149425 0.070891 --0.00953307 -0.140515 0.0829999 --0.00789034 -0.159946 0.0764274 - -0.0128157 -0.145923 0.0965066 - -0.0131146 -0.145649 0.0977304 - -0.0135621 -0.145864 0.0995672 - -0.0170446 -0.141785 0.113813 - -0.0174937 -0.152724 0.115748 - -0.0203166 -0.153995 0.127334 - -0.0299283 -0.121997 0.16648 - -0.0317416 -0.108762 0.173804 - -0.0190424 -0.297869 0.123324 - -0.0194878 -0.296338 0.125137 - -0.0214545 -0.296596 0.133204 - -0.0227565 -0.30214 0.138591 - -0.0257392 -0.322287 0.150992 - -0.0263612 -0.323791 0.153555 - -0.0276863 -0.333876 0.159074 - -0.0323377 -0.34443 0.178238 - -0.0379424 -0.358883 0.201343 - -0.0393995 -0.365988 0.207379 - -0.0527299 -0.378243 0.262147 - -0.0600169 -0.370568 0.291965 - -0.0739844 -0.387368 0.349384 - -0.0760912 -0.3904 0.358049 - -0.078148 -0.382596 0.366417 - -0.0803128 -0.380824 0.37528 - -0.0809946 -0.382814 0.378092 - -0.0842671 -0.381851 0.391504 - -0.091174 -0.384613 0.419851 - -0.091573 -0.383668 0.421479 - -0.0953092 -0.383685 0.4368 - -0.102922 -0.381872 0.468003 - -0.113966 -0.388155 0.513344 - -0.124792 -0.382969 0.557695 - -0.137619 -0.357253 0.610078 - -0.259318 -0.679331 1.11186 - -0.259009 -0.665955 1.11048 - -0.2823 -0.626775 1.20566 - -0.286785 -0.632144 1.2241 - -0.300095 -0.62741 1.27864 - -0.337138 -0.631925 1.43058 - -0.34052 -0.577573 1.44399 - -0.343245 -0.5164 1.45465 - -0.344192 -0.498505 1.45838 - -0.342755 -0.464218 1.4522 - -0.518232 -0.625717 2.17315 - -0.529263 -0.571457 2.21793 - -0.530477 -0.534057 2.22259 - -0.532313 -0.30889 2.22822 - -0.532968 -0.290752 2.23075 - -0.530702 -0.280199 2.22137 - -0.533789 -0.226562 2.23358 - -0.533243 -0.171309 2.23087 - -0.533078 0.0468406 2.22836 - -0.534978 0.322189 2.23382 - -0.533626 0.339872 2.22813 - -0.533034 0.423568 2.22499 - -0.535673 0.454301 2.23556 - -0.534842 0.568869 2.23118 - -0.53561 0.708679 2.23315 - -0.537589 0.793712 2.24055 - -0.537293 0.814102 2.23916 - -0.537435 0.931723 2.23875 - -0.53595 1.19094 2.23047 - -0.537842 1.31901 2.23715 - -0.497095 1.35537 2.06975 - -0.43924 1.35488 1.8325 - -0.424966 1.34143 1.77408 - -0.388351 1.3478 1.62388 - -0.37864 1.34469 1.58408 - -0.374673 1.34047 1.56785 - -0.359118 1.33457 1.50411 - -0.327724 1.33481 1.37537 - -0.303266 1.33262 1.27509 - -0.295397 1.32735 1.24287 - -0.28488 1.3304 1.19972 - -0.274964 1.32305 1.15912 - -0.272895 1.32327 1.15063 - -0.108161 0.441297 0.482537 - -0.107706 0.442517 0.480663 - -0.106541 0.443232 0.475879 - -0.10312 0.581202 0.460684 - -0.0846893 0.461618 0.386115 - -0.0798192 0.598023 0.364992 - -0.0553353 0.29722 0.267129 - -0.0532388 0.292746 0.258569 - -0.0508142 0.294316 0.248613 - -0.0495675 0.293973 0.243504 - -0.0468494 0.296101 0.23234 - -0.0434429 0.292869 0.218397 - -0.0428166 0.289935 0.215854 - -0.0425169 0.289959 0.214625 - -0.0395325 0.286896 0.202413 - -0.0367546 0.294354 0.190958 - -0.0313451 0.30002 0.168727 - -0.0109429 0.531228 0.0831105 - -0.0332806 0.108182 0.178283 - -0.0336415 0.101346 0.179821 - -0.0330795 0.10269 0.177505 - -0.0328085 0.0959747 0.17645 - -0.0267667 0.143819 0.151271 - -0.0235979 0.156417 0.13817 - -0.023274 0.155766 0.136847 - -0.0140254 0.186645 0.0986602 --0.00975418 0.196385 0.0810625 --0.00791289 0.18598 0.0735997 --0.00810099 0.168884 0.0745153 --0.00954958 0.142517 0.0806782 --0.00591546 -0.163588 0.0745171 - -0.0173954 -0.155215 0.119478 - -0.0186046 -0.162645 0.124281 - -0.0211636 -0.168971 0.13437 - -0.020721 -0.17477 0.132681 - -0.0279334 -0.130518 0.160612 - -0.0253533 -0.192695 0.150996 - -0.0194137 -0.293245 0.128512 - -0.0197293 -0.293608 0.129753 - -0.0215805 -0.301816 0.13708 - -0.0233209 -0.30143 0.143904 - -0.0261592 -0.305833 0.155072 - -0.0280767 -0.317299 0.162687 - -0.0285246 -0.333754 0.164577 - -0.0313789 -0.336173 0.175792 - -0.0473624 -0.376812 0.238814 - -0.051334 -0.372171 0.254355 - -0.0540807 -0.392849 0.265296 - -0.0545045 -0.392596 0.266956 - -0.0572945 -0.386676 0.277852 - -0.0700331 -0.385213 0.327806 - -0.0728354 -0.385674 0.338801 - -0.0749957 -0.383617 0.347258 - -0.0825228 -0.386304 0.376804 - -0.0939117 -0.385408 0.421468 - -0.0943284 -0.384452 0.423095 - -0.100849 -0.378899 0.448625 - -0.10731 -0.381621 0.47399 - -0.11599 -0.386384 0.508078 - -0.130229 -0.381142 0.563883 - -0.281088 -0.622019 1.15756 - -0.290058 -0.620513 1.19273 - -0.314491 -0.64169 1.28874 - -0.344037 -0.675373 1.4049 - -0.344772 -0.669986 1.40775 - -0.350704 -0.606438 1.4305 - -0.34981 -0.597927 1.42692 - -0.349513 -0.577257 1.42559 - -0.467617 -0.603722 1.88905 - -0.509537 -0.625884 2.05366 - -0.5529 -0.525996 2.22294 - -0.5541 -0.153005 2.22463 - -0.555545 0.0287927 2.22882 - -0.556029 0.0834502 2.23028 - -0.557746 0.212114 2.23597 - -0.557776 0.221342 2.23601 - -0.557304 0.258052 2.23387 - -0.557816 0.426769 2.23451 - -0.557396 0.483586 2.2324 - -0.559016 0.504362 2.23859 - -0.558485 0.513494 2.23643 - -0.557394 0.53173 2.232 - -0.557626 0.610144 2.23228 - -0.558729 0.86753 2.23452 - -0.559839 0.934167 2.23834 - -0.559186 1.02161 2.23507 - -0.558429 1.21863 2.2305 - -0.560816 1.29864 2.23922 - -0.559765 1.33402 2.23481 - -0.558966 1.34475 2.23159 - -0.527206 1.36086 2.10688 - -0.507426 1.35448 2.02935 - -0.499113 1.35485 1.99674 - -0.32605 1.33036 1.31812 - -0.31919 1.33296 1.29119 - -0.296004 1.33516 1.20022 - -0.274726 1.32772 1.11683 - -0.272299 1.32606 1.10732 - -0.105222 0.447056 0.459092 - -0.104876 0.453641 0.457682 - -0.104949 0.472989 0.457812 - -0.104874 0.492476 0.457362 - -0.105146 0.551221 0.457952 - -0.0843026 0.457406 0.376955 - -0.0813491 0.502981 0.365001 - -0.0820221 0.54306 0.367316 - -0.0676845 0.426036 0.312026 - -0.0415322 0.293997 0.210515 - -0.0412153 0.293999 0.209272 - -0.0387076 0.289815 0.19947 - -0.0355856 0.289089 0.18723 - -0.03253 0.285827 0.175272 - -0.0258214 0.30667 0.148789 - -0.0122603 0.51438 0.0939155 - -0.0117051 0.513855 0.091742 - -0.0301427 0.12138 0.167239 - -0.0241592 0.149184 0.143544 - -0.0225103 0.154865 0.13703 - -0.0179451 0.170017 0.119001 - -0.0133958 0.182383 0.101057 --0.00734632 0.202186 0.0771683 --0.00803171 0.187149 0.0799784 - -0.0115065 0.132193 0.0940526 --0.00577019 -0.135743 0.0794201 --0.00643242 -0.146495 0.0819922 --0.00958779 -0.150347 0.0938793 - -0.0120041 -0.144952 0.102917 - -0.0120181 -0.14751 0.10299 - -0.0138941 -0.142911 0.110004 - -0.0145062 -0.140915 0.112288 - -0.0149706 -0.140966 0.114034 - -0.0138623 -0.164596 0.110053 - -0.0152787 -0.170237 0.115419 - -0.0169873 -0.163619 0.121788 - -0.018679 -0.170466 0.128198 - -0.0195558 -0.171 0.131497 - -0.0219722 -0.162062 0.140508 - -0.0247833 -0.146017 0.150947 - -0.0285752 -0.122737 0.165014 - -0.0314602 -0.108598 0.175746 - -0.0201136 -0.289834 0.134518 - -0.0228041 -0.3027 0.144728 - -0.0304389 -0.326911 0.173606 - -0.0328506 -0.351931 0.182863 - -0.0344304 -0.352356 0.188803 - -0.0387268 -0.363971 0.205038 - -0.0395321 -0.367997 0.208095 - -0.0497182 -0.37806 0.24645 - -0.0526852 -0.376712 0.257589 - -0.0583948 -0.37819 0.279056 - -0.0654989 -0.370842 0.305694 - -0.0686854 -0.39019 0.317819 - -0.0725669 -0.390791 0.332409 - -0.0749405 -0.384498 0.34128 - -0.0842614 -0.387217 0.376327 - -0.0871893 -0.385269 0.387314 - -0.0899183 -0.385625 0.397571 - -0.102807 -0.379971 0.445958 - -0.105501 -0.381458 0.456094 - -0.112673 -0.375152 0.482996 - -0.119976 -0.380774 0.510484 - -0.135054 -0.386195 0.567186 - -0.142514 -0.388379 0.595233 - -0.276712 -0.74696 1.10231 - -0.277221 -0.728619 1.10408 - -0.279758 -0.684647 1.11327 - -0.293532 -0.622543 1.16454 - -0.360912 -0.642861 1.4179 - -0.363101 -0.619615 1.42595 - -0.362262 -0.544576 1.42221 - -0.373371 -0.516725 1.46373 - -0.373958 -0.511057 1.4659 - -0.367115 -0.475006 1.4399 - -0.513142 -0.62386 1.98979 - -0.525764 -0.622134 2.03721 - -0.57573 -0.479655 2.22386 - -0.577687 -0.37661 2.23042 - -0.578737 -0.172458 2.23277 - -0.579622 0.0198136 2.2346 - -0.57711 0.101693 2.22453 - -0.578062 0.175083 2.22754 - -0.58014 0.240381 2.23483 - -0.580027 0.286732 2.23405 - -0.58108 0.662774 2.23508 - -0.581821 0.67375 2.23778 - -0.580928 1.02292 2.23171 - -0.582726 1.14193 2.23754 - -0.580959 1.1858 2.23056 - -0.476765 1.3551 1.83771 - -0.43011 1.34484 1.66247 - -0.410066 1.34399 1.58716 - -0.397907 1.34564 1.54145 - -0.392139 1.34706 1.51977 - -0.378715 1.32973 1.46946 - -0.344061 1.33612 1.33919 - -0.275065 1.31431 1.08009 - -0.115662 0.449324 0.487817 - -0.11488 0.448891 0.484883 - -0.109571 0.441633 0.464986 - -0.107357 0.458246 0.45654 - -0.108997 0.489084 0.462462 - -0.108523 0.546252 0.460234 - -0.109162 0.611185 0.462132 - -0.107011 0.621221 0.453972 - -0.0888134 0.468133 0.38678 - -0.0595843 0.310876 0.278167 - -0.0569195 0.295716 0.268271 - -0.0554925 0.294775 0.262916 - -0.0546889 0.292298 0.259916 - -0.0522309 0.289812 0.250698 - -0.0520218 0.292967 0.249888 - -0.0487832 0.296522 0.237691 - -0.0394552 0.292925 0.202666 - -0.0385703 0.278822 0.199451 - -0.0375257 0.288656 0.195449 - -0.0320012 0.287812 0.174696 - -0.0287427 0.295076 0.162395 - -0.0279547 0.2976 0.159414 - -0.0257592 0.300076 0.151144 - -0.0107773 0.496793 0.0933165 --0.00916617 0.494215 0.0872822 - -0.0333796 0.0968197 0.181361 - -0.0320695 0.105691 0.176369 - -0.0232251 0.157684 0.142729 - -0.0208702 0.161168 0.133853 - -0.0206889 0.160827 0.133174 - -0.0131856 0.184782 0.104793 --0.00705782 0.189704 0.0817277 --0.00671461 0.186335 0.0804642 --0.00650472 0.185753 0.07968 - -0.0036316 -0.143127 0.077013 --0.00514617 -0.149711 0.0825232 - -0.0145066 -0.141416 0.116211 - -0.0150011 -0.142663 0.118004 - -0.0129181 -0.180237 0.110774 - -0.015179 -0.172316 0.118867 - -0.0200957 -0.166907 0.136554 - -0.0206794 -0.167875 0.138666 - -0.0216244 -0.161757 0.142027 - -0.0295288 -0.118395 0.170203 - -0.0210286 -0.252214 0.140556 - -0.0219916 -0.291385 0.144321 - -0.022331 -0.291675 0.145547 - -0.0234832 -0.302841 0.149786 - -0.029465 -0.318635 0.171472 - -0.0361327 -0.354736 0.195783 - -0.0445984 -0.371558 0.226433 - -0.0513433 -0.378519 0.250804 - -0.0534464 -0.374509 0.258357 - -0.0569664 -0.383618 0.271117 - -0.0613743 -0.379462 0.286979 - -0.0663067 -0.383314 0.304793 - -0.0737845 -0.385485 0.331771 - -0.0767431 -0.379535 0.342394 - -0.0820435 -0.391156 0.361592 - -0.0833856 -0.379341 0.366343 - -0.0851199 -0.385222 0.37264 - -0.0856772 -0.385391 0.374651 - -0.0929978 -0.382156 0.401022 - -0.0934447 -0.381283 0.402627 - -0.0971941 -0.379318 0.416131 - -0.0986088 -0.38089 0.421243 - -0.105259 -0.38801 0.445275 - -0.107954 -0.385069 0.454971 - -0.121447 -0.380361 0.503585 - -0.14325 -0.383406 0.582221 - -0.144646 -0.385214 0.58727 - -0.147464 -0.378613 0.597381 - -0.147908 -0.37685 0.598968 - -0.146701 -0.359701 0.594489 - -0.150819 -0.354296 0.609293 - -0.288786 -0.722349 1.10951 - -0.287304 -0.673514 1.1038 - -0.287242 -0.630792 1.10325 - -0.364678 -0.723616 1.38315 - -0.372105 -0.599498 1.409 - -0.600203 -0.560629 2.23115 - -0.599306 -0.472315 2.22725 - -0.596791 -0.432038 2.21788 - -0.598614 -0.423931 2.22439 - -0.599628 -0.339573 2.22742 - -0.600018 -0.17254 2.22757 - -0.598575 -0.0714222 2.22161 - -0.598947 -0.0258388 2.22261 - -0.600164 0.0746355 2.22625 - -0.600621 0.175584 2.22714 - -0.601965 0.231452 2.23157 - -0.600364 0.258543 2.22559 - -0.603175 0.287816 2.23551 - -0.604443 0.411197 2.23916 - -0.604022 0.497289 2.237 - -0.601768 0.524315 2.22867 - -0.601765 0.573089 2.22829 - -0.602743 0.623518 2.23144 - -0.605425 0.885551 2.23915 - -0.604605 0.905885 2.23604 - -0.605132 0.961543 2.23752 - -0.60508 1.04002 2.23675 - -0.605269 1.07476 2.23717 - -0.607006 1.17235 2.2427 - -0.604836 1.31572 2.23381 - -0.583461 1.3659 2.15636 - -0.581658 1.37414 2.1498 - -0.567878 1.36429 2.10019 - -0.533084 1.35872 1.97477 - -0.518286 1.35412 1.92146 - -0.468721 1.35026 1.74277 - -0.46035 1.35917 1.71252 - -0.446574 1.34951 1.66292 - -0.422195 1.34814 1.57503 - -0.365586 1.34225 1.37097 - -0.3561 1.33762 1.3368 - -0.110882 0.465229 0.459163 - -0.0891214 0.460541 0.380739 - -0.0877595 0.459277 0.375838 - -0.0803988 0.517906 0.348859 - -0.0758487 0.46649 0.332838 - -0.0613022 0.304727 0.2816 - -0.0608169 0.303112 0.279862 - -0.0481694 0.292786 0.234337 - -0.0403016 0.284987 0.206027 - -0.0376533 0.28372 0.196488 - -0.0353563 0.282206 0.188217 - -0.0263254 0.295919 0.155553 - -0.014003 0.450533 0.109966 --0.00970112 0.465144 0.0943455 - -0.0149567 0.346412 0.114184 - -0.0320142 0.104073 0.1775 - -0.0238866 0.150273 0.147849 - -0.0228358 0.154017 0.144032 - -0.0229046 0.149773 0.144312 - -0.0137092 0.182721 0.11091 --0.00673819 0.202036 0.0856312 --0.00741111 0.194189 0.0881162 --0.00494945 0.198871 0.0792054 --0.00411641 0.181989 0.0763281 --0.00530426 0.172854 0.0806794 --0.00367383 0.17442 0.074789 --0.00443487 0.153437 0.07769 --0.00121071 -0.145296 0.0749891 --0.00152319 -0.157234 0.0761475 --0.00136693 -0.162067 0.0756455 - -0.013203 -0.143914 0.116157 - -0.0113984 -0.162454 0.110093 - -0.0116455 -0.164191 0.110955 - -0.0106282 -0.187663 0.107629 - -0.0138507 -0.17795 0.118625 - -0.0170733 -0.170291 0.129636 - -0.0208179 -0.162058 0.142435 - -0.0259699 -0.131671 0.159908 - -0.0311153 -0.107271 0.177401 - -0.0223891 -0.287351 0.148726 - -0.0239784 -0.291584 0.154213 - -0.0314835 -0.337731 0.180314 - -0.0331108 -0.339188 0.185912 - -0.034159 -0.350449 0.189592 - -0.0405873 -0.362983 0.211754 - -0.041473 -0.362939 0.214795 - -0.05081 -0.378883 0.24697 - -0.0671904 -0.38762 0.303278 - -0.078215 -0.378595 0.341069 - -0.0859114 -0.384852 0.367541 - -0.0887197 -0.375989 0.37712 - -0.0918844 -0.38275 0.388035 - -0.110973 -0.381458 0.453571 - -0.119023 -0.386886 0.48125 - -0.126122 -0.385037 0.505613 - -0.129595 -0.386493 0.517551 - -0.13072 -0.384432 0.521397 - -0.145576 -0.381804 0.572389 - -0.153186 -0.361944 0.598378 - -0.153684 -0.350888 0.600011 - -0.177067 -0.404824 0.680685 - -0.337892 -0.693092 1.23498 - -0.372938 -0.752594 1.35574 - -0.380068 -0.703112 1.37987 - -0.377426 -0.683588 1.37066 - -0.384352 -0.607691 1.39389 - -0.391566 -0.586523 1.41851 - -0.393199 -0.529647 1.42371 - -0.399543 -0.461334 1.44501 - -0.627298 -0.454866 2.22701 - -0.62575 -0.255743 2.22027 - -0.627028 -0.154473 2.22393 - -0.627084 -0.0351077 2.22327 - -0.62907 0.0934352 2.22917 - -0.63077 0.449789 2.23246 - -0.631602 0.460049 2.23524 - -0.631059 0.737729 2.23139 - -0.632838 0.77108 2.23726 - -0.630172 0.819912 2.22776 - -0.633095 0.834592 2.23769 - -0.632119 0.865229 2.23412 - -0.631238 0.939871 2.23056 - -0.632615 1.00893 2.23479 - -0.633903 1.11482 2.23846 - -0.634536 1.1278 2.24054 - -0.619969 1.38098 2.18871 - -0.605239 1.37133 2.1382 - -0.576875 1.37671 2.04077 - -0.556936 1.36229 1.97241 - -0.49949 1.35999 1.77517 - -0.465492 1.35084 1.6585 - -0.430202 1.35123 1.53732 - -0.317419 1.34102 1.15013 - -0.121476 0.451422 0.483679 - -0.114774 0.470466 0.460527 - -0.114553 0.493757 0.459603 - -0.115229 0.525263 0.461698 - -0.114716 0.527306 0.459922 - -0.115116 0.599719 0.46078 - -0.114838 0.604532 0.459791 - -0.113515 0.622881 0.455114 - -0.0500656 0.301222 0.239549 - -0.0479143 0.28991 0.232243 - -0.0462851 0.297375 0.226596 - -0.0450332 0.287616 0.222367 - -0.0443593 0.289733 0.220037 - -0.0220332 0.31687 0.143182 - -0.0100793 0.420584 0.101394 - -0.0318332 0.101346 0.178374 - -0.0317094 0.101209 0.17795 - -0.0315857 0.101071 0.177526 - -0.0293044 0.123608 0.169531 - -0.0207337 0.152208 0.139897 - -0.0201765 0.151264 0.137991 - -0.0201125 0.150045 0.13778 --0.00980074 0.189099 0.102093 --0.00265662 0.190404 0.0775528 - -0.0004154 0.185707 0.0698907 --0.00243662 0.146171 0.0771138 --0.00085568 -0.146078 0.079986 --0.00102283 -0.15598 0.0806012 --0.00811189 -0.144632 0.10374 --0.00934321 -0.181075 0.108022 - -0.0119063 -0.185874 0.116448 - -0.0162077 -0.171905 0.13044 - -0.0165215 -0.173513 0.131478 - -0.0247257 -0.137502 0.1581 - -0.0250063 -0.299867 0.160131 - -0.0298561 -0.306193 0.176057 - -0.031133 -0.316686 0.180311 - -0.0325998 -0.342181 0.185289 - -0.0334717 -0.342375 0.188146 - -0.04244 -0.381861 0.217787 - -0.0487823 -0.381661 0.238556 - -0.0632597 -0.382396 0.285973 - -0.0637474 -0.382036 0.287568 - -0.0677005 -0.387077 0.300549 - -0.0701639 -0.384873 0.308601 - -0.0701965 -0.37863 0.308665 - -0.0830206 -0.382946 0.350693 - -0.0849708 -0.380283 0.357062 - -0.0853461 -0.378676 0.358279 - -0.0864246 -0.37821 0.361808 - -0.0965579 -0.38741 0.395057 - -0.114636 -0.384783 0.454242 - -0.116927 -0.385498 0.46175 - -0.142603 -0.38159 0.545812 - -0.14507 -0.387354 0.553932 - -0.146953 -0.384029 0.560074 - -0.157367 -0.379297 0.594147 - -0.158946 -0.364605 0.599218 - -0.159479 -0.353497 0.600888 - -0.313035 -0.719481 1.10628 - -0.311315 -0.689315 1.10044 - -0.387505 -0.79693 1.35069 - -0.397933 -0.625159 1.38367 - -0.402415 -0.605801 1.39821 - -0.405543 -0.597498 1.4084 - -0.405489 -0.583991 1.40813 - -0.59267 -0.614492 2.02135 - -0.618683 -0.61477 2.10654 - -0.654637 -0.582918 2.22407 - -0.656159 -0.525128 2.22866 - -0.654418 -0.417328 2.22222 - -0.657832 -0.230239 2.23212 - -0.655751 -0.182976 2.22498 - -0.657228 -0.00768446 2.22861 - -0.659063 0.196162 2.23323 - -0.658825 0.205402 2.23238 - -0.657655 0.279686 2.22804 - -0.658029 0.355232 2.22875 - -0.659548 0.384651 2.23352 - -0.65795 0.528197 2.22731 - -0.660395 0.599523 2.23483 - -0.660953 0.742354 2.23568 - -0.662436 0.981206 2.2389 - -0.662491 1.26495 2.23714 - -0.637375 1.37541 2.15412 - -0.55269 1.36619 1.87685 - -0.489766 1.35617 1.67085 - -0.369824 1.33679 1.27818 - -0.366622 1.33551 1.2677 - -0.333195 1.33401 1.15824 - -0.322256 1.33167 1.12243 - -0.304379 1.29392 1.06414 - -0.128952 0.45552 0.495373 - -0.119749 0.449351 0.465275 - -0.117253 0.476251 0.456917 - -0.118586 0.602466 0.460419 - -0.100997 0.514709 0.403416 - -0.0894794 0.482334 0.365919 - -0.0625238 0.2947 0.278926 - -0.0590085 0.295446 0.267409 - -0.0571002 0.28962 0.261199 - -0.0560879 0.285182 0.257914 - -0.0406607 0.288999 0.207365 - -0.0395559 0.288972 0.203747 - -0.0356202 0.281461 0.19091 - -0.0290678 0.273114 0.169508 - -0.0282005 0.27671 0.166643 - -0.0274951 0.276326 0.164335 - -0.0257351 0.282382 0.15853 - -0.0245474 0.28365 0.154632 - -0.0174955 0.36738 0.130964 - -0.0210919 0.24916 0.143552 - -0.0281879 0.132536 0.167589 - -0.0238689 0.14958 0.153328 - -0.0230253 0.147379 0.15058 - -0.0181087 0.158467 0.134403 - -0.0152662 0.169228 0.12502 --0.00058957 0.220992 0.0766007 --0.00104891 0.194632 0.0782855 - 0.00034068 0.178777 0.0738433 - 0.00598184 0.186183 0.0553181 - 0.00621998 0.185487 0.054543 - 0.00044779 -0.158668 0.0806778 --0.00871121 -0.153896 0.109532 - -0.0101841 -0.152299 0.114167 - -0.0110133 -0.188487 0.117021 - -0.0149754 -0.168134 0.129383 - -0.0311672 -0.102041 0.180011 - -0.0219139 -0.274901 0.151972 - -0.028392 -0.310856 0.172641 - -0.0324318 -0.333203 0.185529 - -0.0328711 -0.3333 0.186915 - -0.0348911 -0.345681 0.193368 - -0.0376131 -0.347951 0.201968 - -0.0394167 -0.366999 0.207782 - -0.0448675 -0.376552 0.225036 - -0.0565933 -0.380729 0.262045 - -0.0694111 -0.377075 0.302446 - -0.081866 -0.380803 0.341751 - -0.0907538 -0.386137 0.369817 - -0.113802 -0.378899 0.442461 - -0.120856 -0.381175 0.464722 - -0.134557 -0.381725 0.507934 - -0.145968 -0.377853 0.543899 - -0.148621 -0.380558 0.552284 - -0.154801 -0.381559 0.57178 - -0.162452 -0.382721 0.595919 - -0.161446 -0.356858 0.592576 - -0.366698 -0.817076 1.24295 - -0.379275 -0.817964 1.28262 - -0.393293 -0.813101 1.3268 - -0.404896 -0.801082 1.36331 - -0.408105 -0.762724 1.37318 - -0.423103 -0.525266 1.41891 - -0.429101 -0.513766 1.43775 - -0.433862 -0.487239 1.45259 - -0.678866 -0.487055 2.22529 - -0.678751 -0.448175 2.22467 - -0.679215 -0.390814 2.22575 - -0.679807 -0.334012 2.22724 - -0.682119 0.16866 2.23121 - -0.681149 0.196347 2.22797 - -0.680901 0.205595 2.22712 - -0.681562 0.261975 2.22884 - -0.682082 0.280998 2.23035 - -0.681836 0.337562 2.2292 - -0.684247 0.652071 2.23472 - -0.684595 0.797216 2.23486 - -0.684338 0.85012 2.2337 - -0.68462 0.993428 2.23364 - -0.685159 1.09769 2.23465 - -0.686045 1.21926 2.23664 - -0.521054 1.35395 1.7154 - -0.496034 1.35273 1.6365 - -0.483988 1.35187 1.59851 - -0.455348 1.34393 1.50824 - -0.44682 1.35103 1.48129 - -0.427825 1.34504 1.42143 - -0.364793 1.34216 1.22265 - -0.354077 1.33306 1.18892 - -0.346053 1.33445 1.1636 - -0.120819 0.502864 0.458754 - -0.121979 0.623134 0.461617 - -0.0932796 0.458341 0.372195 - -0.0920715 0.459836 0.368375 - -0.0692798 0.310867 0.29748 - -0.0585538 0.286903 0.26381 - -0.0523828 0.28837 0.244338 - -0.0501681 0.291281 0.237334 - -0.0499838 0.297384 0.236713 - -0.0495918 0.297517 0.235475 - -0.0473083 0.301185 0.228249 - -0.033155 0.27792 0.183766 - -0.0278058 0.272757 0.16693 - -0.0229816 0.285115 0.151634 - -0.012951 0.382074 0.119357 - -0.0243689 0.201107 0.156565 - -0.0317527 0.0991123 0.180527 - -0.0287496 0.128454 0.170861 - -0.0263646 0.143778 0.163238 - -0.0253391 0.139475 0.160032 - -0.0198447 0.153723 0.14261 - -0.0174854 0.160033 0.135127 - -0.0168881 0.162409 0.133228 --0.00928665 0.19329 0.10905 --0.00501472 0.202564 0.0955153 --0.00189671 0.216176 0.0855916 --0.00094797 0.210792 0.0826351 --0.00156288 0.201477 0.084636 - 0.0018332 0.201202 0.0739272 - 0.00240055 0.182546 0.0722613 - 0.00493052 0.178379 0.0643098 - 0.0080336 0.176055 0.0545386 - 0.0146675 -0.17261 0.0418128 - 0.0113077 -0.169163 0.0520225 - 0.00318043 -0.169517 0.0767755 - 0.00037331 -0.16131 0.0852716 --0.00143962 -0.158227 0.0907729 --0.00280184 -0.153996 0.0948943 - -0.0068503 -0.146159 0.107173 - -0.0152683 -0.173291 0.132983 - -0.0167572 -0.16664 0.137475 - -0.0169836 -0.166957 0.138166 - -0.0200372 -0.153685 0.147381 - -0.0249977 -0.132946 0.162354 - -0.0228538 -0.21859 0.156374 - -0.0202279 -0.267022 0.148688 - -0.0214832 -0.270988 0.152536 - -0.028895 -0.307187 0.17534 - -0.0312682 -0.31294 0.182605 - -0.0315895 -0.317037 0.183609 - -0.0388326 -0.352997 0.205898 - -0.0526925 -0.377525 0.248264 - -0.0753907 -0.378612 0.317396 - -0.0909816 -0.385771 0.364922 - -0.0951617 -0.37974 0.377613 - -0.114441 -0.389285 0.436386 - -0.115502 -0.387165 0.439604 - -0.114534 -0.378507 0.436602 - -0.115397 -0.375546 0.439211 - -0.148962 -0.386878 0.541503 - -0.150639 -0.379221 0.546559 - -0.162308 -0.387315 0.582148 - -0.1684 -0.385709 0.60069 - -0.414556 -0.88313 1.35352 - -0.420018 -0.855459 1.36998 - -0.419222 -0.799071 1.36719 - -0.419311 -0.784066 1.36737 - -0.420652 -0.684645 1.37081 - -0.421047 -0.678326 1.37197 - -0.420165 -0.662838 1.36919 - -0.428082 -0.614316 1.39299 - -0.42948 -0.602968 1.39717 - -0.43335 -0.588633 1.40887 - -0.447695 -0.501837 1.452 - -0.700986 -0.596983 2.22398 - -0.700675 -0.507602 2.22246 - -0.702893 -0.344854 2.22817 - -0.702084 -0.296982 2.2254 - -0.700576 -0.258651 2.22056 - -0.702509 -0.184359 2.22597 - -0.70246 -0.175003 2.22576 - -0.701403 -0.128187 2.22224 - -0.703245 -0.0448552 2.22732 - -0.703753 0.0386845 2.22833 - -0.702888 0.0757399 2.22546 - -0.704458 0.281786 2.22892 - -0.705014 0.291477 2.23055 - -0.704669 0.348268 2.22914 - -0.708984 0.398647 2.24195 - -0.707909 0.417326 2.23856 - -0.706921 0.674529 2.2339 - -0.705516 0.724463 2.2293 - -0.709269 0.738966 2.24064 - -0.708151 0.758626 2.23711 - -0.708253 0.941964 2.23624 - -0.705932 1.13344 2.22795 - -0.708259 1.14935 2.23493 - -0.7069 1.21976 2.23034 - -0.711105 1.31564 2.24253 - -0.678723 1.37765 2.14352 - -0.609276 1.37105 1.93207 - -0.574062 1.3695 1.82484 - -0.544122 1.3632 1.7337 - -0.484801 1.34745 1.55314 - -0.471852 1.35445 1.51366 - -0.418319 1.34002 1.35073 - -0.375661 1.33282 1.22087 - -0.373462 1.3359 1.21415 - -0.362156 1.33754 1.17971 - -0.324439 1.29328 1.06513 - -0.142013 0.477177 0.514801 - -0.138728 0.466146 0.504866 - -0.134409 0.458502 0.491763 - -0.123183 0.467572 0.457517 - -0.12545 0.544316 0.46393 - -0.123924 0.591014 0.458983 - -0.06809 0.294996 0.290844 - -0.0672378 0.290584 0.288277 - -0.0550914 0.297328 0.251243 - -0.0525756 0.29647 0.243587 - -0.0439269 0.288785 0.217298 - -0.0353873 0.281534 0.191338 - -0.0336998 0.271145 0.186265 - -0.0232908 0.281687 0.154498 - -0.0259028 0.14704 0.163316 - -0.0253024 0.146428 0.161491 - -0.0245071 0.147684 0.159061 - -0.0229966 0.147017 0.154466 - -0.018169 0.154642 0.139715 --0.00511933 0.207319 0.0996357 - 0.00360867 0.196913 0.0731223 - 0.0109761 0.180494 0.0507907 - 0.0100639 0.16962 0.0536386 - 0.0177526 -0.182786 0.038252 - 0.0174279 -0.186549 0.0392318 - 0.0122271 -0.175588 0.0544778 - 0.00977859 -0.187514 0.0617618 --0.00719794 -0.157787 0.111566 --0.00741881 -0.158223 0.112219 --0.00791568 -0.160367 0.113696 --0.00554054 -0.182808 0.106841 --0.00405059 -0.198618 0.102552 - -0.0043287 -0.199096 0.103374 - -0.0129753 -0.176789 0.128696 - -0.0178411 -0.162651 0.142936 - -0.0204266 -0.15077 0.150475 - -0.0243042 -0.286262 0.162736 - -0.0281331 -0.29298 0.174053 - -0.0325318 -0.318331 0.187163 - -0.0391817 -0.353999 0.206966 - -0.043413 -0.380757 0.219592 - -0.0595211 -0.378687 0.267011 - -0.0662813 -0.380693 0.286929 - -0.0758443 -0.385362 0.315118 - -0.0768337 -0.383392 0.318019 - -0.0779101 -0.382352 0.321182 - -0.0858595 -0.388612 0.344629 - -0.0920661 -0.383015 0.36287 - -0.0982316 -0.380861 0.381011 - -0.11181 -0.379693 0.420988 - -0.1142 -0.38454 0.428055 - -0.115818 -0.381447 0.4328 - -0.11865 -0.380576 0.441134 - -0.124903 -0.380711 0.459548 - -0.129612 -0.380019 0.473408 - -0.135829 -0.37778 0.491702 - -0.136561 -0.377243 0.493853 - -0.16147 -0.380146 0.567219 - -0.16659 -0.382468 0.582308 - -0.172241 -0.385709 0.598968 - -0.437309 -0.934317 1.3829 - -0.44098 -0.917392 1.3936 - -0.43936 -0.888729 1.38866 - -0.430122 -0.813024 1.36098 - -0.431121 -0.792105 1.3638 - -0.43237 -0.727701 1.36707 - -0.432653 -0.706608 1.36777 - -0.436372 -0.663641 1.37846 - -0.438698 -0.632866 1.38512 - -0.449342 -0.580886 1.41614 - -0.45423 -0.520887 1.43016 - -0.466544 -0.482991 1.46618 - -0.458914 -0.44866 1.4435 - -0.559117 -0.540145 1.73913 - -0.723299 -0.588782 2.22288 - -0.723582 -0.519459 2.22328 - -0.725001 -0.461633 2.2271 - -0.723504 -0.325975 2.22185 - -0.726336 -0.308247 2.23008 - -0.725706 -0.213352 2.22763 - -0.725569 -0.0263704 2.22607 - -0.726057 0.122702 2.22657 - -0.726498 0.178926 2.22752 - -0.729014 0.437174 2.23333 - -0.728111 0.456048 2.23055 - -0.728573 0.564732 2.23123 - -0.729401 0.6664 2.23304 - -0.728991 0.707111 2.23158 - -0.729658 1.03379 2.23151 - -0.729318 1.11483 2.23001 - -0.733187 1.133 2.24129 - -0.668634 1.37848 2.04968 - -0.608271 1.36468 1.87202 - -0.56649 1.36968 1.74896 - -0.468448 1.35043 1.46038 - -0.463853 1.3476 1.44687 - -0.416249 1.3397 1.30674 - -0.385357 1.33126 1.21583 - -0.280008 1.0695 0.90725 - -0.13898 0.471554 0.495697 - -0.12961 0.456723 0.468198 - -0.126313 0.481234 0.458337 - -0.127765 0.515259 0.462403 - -0.126738 0.622214 0.458714 - -0.083529 0.373744 0.333025 - -0.0791935 0.341323 0.32046 - -0.0727172 0.30164 0.301637 - -0.0717831 0.297326 0.298913 - -0.0695025 0.297476 0.292197 - -0.0497946 0.294532 0.234183 - -0.0436081 0.297825 0.215946 - -0.0431558 0.294868 0.214632 - -0.03785 0.283897 0.199077 - -0.0355213 0.279605 0.192247 - -0.0272882 0.260898 0.16812 - -0.0250144 0.254628 0.161463 - -0.0273749 0.185819 0.168842 - -0.0314952 0.113982 0.181421 - -0.0274096 0.13647 0.169251 - -0.0202661 0.152013 0.14812 --0.00298825 0.214853 0.0968525 --0.00271831 0.207569 0.096103 --0.00078089 0.207563 0.0903981 - 0.00188991 0.1953 0.0826099 - 0.00702656 0.20732 0.0674097 - 0.0143568 0.187892 0.0459458 - 0.0212155 -0.182566 0.0342128 - 0.017445 -0.185173 0.0449476 --0.00358574 -0.154079 0.104549 --0.00204136 -0.17152 0.100263 --0.00363469 -0.192027 0.104917 --0.00255183 -0.203966 0.10191 - -0.0177477 -0.15924 0.144841 - -0.0182295 -0.157667 0.146202 - -0.018809 -0.157285 0.147847 - -0.0245547 -0.133746 0.164039 - -0.0244317 -0.136789 0.163708 - -0.0287927 -0.10837 0.175935 - -0.0289495 -0.108508 0.176381 - -0.0306109 -0.0995095 0.18105 - -0.0296276 -0.116329 0.178356 - -0.0297229 -0.119496 0.178646 - -0.0226323 -0.221439 0.159103 - -0.0323716 -0.330397 0.187447 - -0.0445087 -0.380624 0.222255 - -0.049258 -0.371696 0.235703 - -0.0510835 -0.378223 0.240932 - -0.057782 -0.378751 0.259978 - -0.0621019 -0.375552 0.27224 - -0.0652797 -0.38079 0.281306 - -0.0658314 -0.38044 0.282872 - -0.067144 -0.382646 0.286617 - -0.0725284 -0.383843 0.301932 - -0.0789326 -0.38765 0.320161 - -0.0860601 -0.379248 0.340373 - -0.0976145 -0.383107 0.373245 - -0.101658 -0.382827 0.384737 - -0.102653 -0.384682 0.387577 - -0.104422 -0.37861 0.39257 - -0.125271 -0.381695 0.451863 - -0.128238 -0.380359 0.460288 - -0.14111 -0.3798 0.496878 - -0.143679 -0.382496 0.504199 - -0.149146 -0.381641 0.519736 - -0.161714 -0.37937 0.555451 - -0.174016 -0.38587 0.590463 - -0.179857 -0.355795 0.606887 - -0.180628 -0.354578 0.609073 - -0.436145 -0.919574 1.33889 - -0.446212 -0.730255 1.36637 - -0.45215 -0.641032 1.38271 - -0.454356 -0.616966 1.38884 - -0.457907 -0.594997 1.3988 - -0.483875 -0.500521 1.47206 - -0.472476 -0.448985 1.43934 - -0.746381 -0.569922 2.21876 - -0.74817 -0.491988 2.22337 - -0.747338 -0.471801 2.22089 - -0.749181 -0.385471 2.22561 - -0.747961 -0.336815 2.22185 - -0.749416 -0.308819 2.22581 - -0.749851 -0.270907 2.22682 - -0.748938 -0.261074 2.22417 - -0.749494 -0.157482 2.22512 - -0.749037 -0.0824622 2.22337 - -0.754422 0.449167 2.23548 - -0.753727 0.487978 2.23327 - -0.756595 0.671453 2.24032 - -0.755634 0.680858 2.23753 - -0.752718 0.990011 2.22737 - -0.755222 1.30627 2.23258 - -0.729168 1.38543 2.15804 - -0.675274 1.37554 2.00488 - -0.658315 1.37598 1.95667 - -0.636573 1.37649 1.89485 - -0.628794 1.37081 1.87277 - -0.608093 1.37076 1.81392 - -0.581259 1.36517 1.73767 - -0.48258 1.35257 1.45721 - -0.468065 1.35448 1.41593 - -0.40461 1.33894 1.23563 - -0.390841 1.33501 1.19651 - -0.372582 1.33561 1.14459 - -0.130792 0.564033 0.461857 - -0.130176 0.59258 0.459934 - -0.0872608 0.374156 0.339246 - -0.0823369 0.344408 0.325427 - -0.06706 0.293002 0.282306 - -0.0651924 0.292435 0.277 - -0.050299 0.292411 0.23466 - -0.0480937 0.290017 0.228404 - -0.0456138 0.29254 0.221339 - -0.0405052 0.285998 0.206855 - -0.0281947 0.262553 0.171999 - -0.0260688 0.251472 0.166022 - -0.0252606 0.239881 0.163794 - -0.0276235 0.135043 0.171144 - -0.023855 0.142004 0.160388 - -0.0229108 0.144187 0.15769 - -0.0217065 0.15243 0.154217 - -0.0198965 0.158929 0.149032 - -0.0179068 0.152184 0.143416 --0.00120606 0.222046 0.0955166 - 0.00283571 0.20232 0.0841451 - 0.00436869 0.201703 0.0797907 - 0.0103222 0.212374 0.0628011 - 0.0109377 0.211042 0.0610591 - 0.0179481 0.19534 0.0412239 - 0.0177902 0.193091 0.0416864 - 0.01835 0.191564 0.0401041 - 0.022422 -0.188668 0.0362748 - 0.0191096 -0.188139 0.0453953 - 0.0186008 -0.188138 0.0467969 - 0.0178 -0.195545 0.049046 - 0.0215346 -0.213867 0.0388668 - 0.0220907 -0.221616 0.0373807 - 0.0160189 -0.208859 0.0540298 --0.00137388 -0.155576 0.101624 --0.00437859 -0.160318 0.109928 --0.00535075 -0.157377 0.112588 --0.00533275 -0.170247 0.112614 --0.00163804 -0.208936 0.102664 --0.00916404 -0.190774 0.123287 - -0.0207948 -0.14851 0.155075 - -0.027857 -0.113165 0.17432 - -0.0281224 -0.112349 0.175046 - -0.0249911 -0.187479 0.166862 - -0.0217317 -0.261149 0.158316 - -0.0246428 -0.281899 0.166455 - -0.0263226 -0.282588 0.171086 - -0.0383989 -0.345997 0.204721 - -0.0389141 -0.345999 0.20614 - -0.0530868 -0.380692 0.24538 - -0.0623582 -0.380773 0.270917 - -0.0685725 -0.377017 0.288012 - -0.0754189 -0.386337 0.306924 - -0.0758126 -0.38394 0.307994 - -0.0821341 -0.384535 0.32541 - -0.0862436 -0.386722 0.336742 - -0.0948517 -0.386492 0.36045 - -0.100288 -0.381548 0.375394 - -0.109205 -0.379498 0.399943 - -0.114727 -0.377231 0.415139 - -0.118385 -0.380107 0.425231 - -0.121708 -0.384629 0.434412 - -0.138828 -0.385051 0.481568 - -0.139085 -0.375667 0.482221 - -0.146737 -0.383267 0.503344 - -0.149455 -0.379206 0.510805 - -0.154631 -0.383218 0.525085 - -0.18077 -0.364315 0.596973 - -0.181645 -0.34755 0.599283 - -0.458149 -0.775513 1.36339 - -0.462029 -0.680177 1.37351 - -0.48217 -0.57784 1.42839 - -0.478376 -0.546086 1.41776 - -0.477183 -0.51827 1.41431 - -0.487429 -0.510443 1.44248 - -0.494808 -0.498774 1.46274 - -0.487611 -0.445523 1.4426 - -0.715019 -0.604645 2.0699 - -0.740286 -0.597898 2.13946 - -0.753308 -0.599091 2.17533 - -0.770667 -0.513421 2.22264 - -0.771621 -0.484414 2.2251 - -0.770107 -0.453976 2.22075 - -0.7713 -0.357584 2.22347 - -0.771851 -0.309818 2.22471 - -0.769402 -0.289722 2.21785 - -0.773787 -0.177301 2.22927 - -0.774229 -0.149039 2.23032 - -0.772159 -0.120386 2.22445 - -0.773379 0.0578688 2.22677 - -0.774668 0.0673753 2.23026 - -0.775976 0.171353 2.23325 - -0.777086 0.600181 2.2338 - -0.776747 0.640601 2.23263 - -0.779507 0.725978 2.23973 - -0.778645 0.746144 2.23724 - -0.776153 0.828677 2.22989 - -0.777516 0.87365 2.23338 - -0.781878 1.11924 2.24396 - -0.78089 1.26504 2.24038 - -0.780211 1.34078 2.23806 - -0.689434 1.38032 1.9878 - -0.627249 1.37828 1.81653 - -0.608924 1.37132 1.7661 - -0.549446 1.36442 1.60231 - -0.482983 1.35176 1.41932 - -0.461592 1.35549 1.36038 - -0.450477 1.34302 1.32984 - -0.437751 1.34779 1.29476 - -0.154841 0.484193 0.52058 - -0.14422 0.452046 0.491515 - -0.143581 0.46652 0.489671 - -0.133279 0.517914 0.460993 - -0.133623 0.536583 0.46183 - -0.130205 0.597888 0.452056 - -0.127802 0.588937 0.445492 - -0.0909613 0.369127 0.345306 - -0.0747376 0.296021 0.301048 - -0.0701838 0.289824 0.288542 - -0.0684559 0.291322 0.283774 - -0.0663721 0.294038 0.278018 - -0.0609533 0.289576 0.263119 - -0.0587297 0.289862 0.256993 - -0.04552 0.287548 0.220622 - -0.0354981 0.269679 0.193123 - -0.035064 0.271616 0.191916 - -0.0346595 0.271551 0.190802 - -0.0295599 0.266255 0.176787 - -0.0275503 0.257443 0.171303 - -0.0258547 0.245555 0.166702 - -0.0253786 0.21789 0.165553 - -0.0270682 0.187303 0.170386 - -0.0289983 0.144607 0.175953 - -0.0300944 0.114598 0.179148 - -0.0270736 0.1381 0.170689 - -0.0268678 0.137937 0.170123 - -0.0264829 0.139698 0.169053 - -0.0252375 0.138633 0.165629 - -0.0252302 0.136537 0.165621 - -0.0232697 0.148329 0.160152 - -0.0220665 0.152418 0.156814 - -0.0172574 0.160996 0.143518 - -0.016934 0.157357 0.142648 - -0.0064627 0.204815 0.113528 - 0.0015664 0.197724 0.0914547 - 0.0114424 0.204727 0.0642114 - 0.0148138 0.204766 0.0549251 - 0.0194378 0.210527 0.042155 - 0.0200654 0.209002 0.0404353 - 0.0249113 -0.188599 0.0351052 - 0.025606 -0.219222 0.0334278 - 0.0224773 -0.220039 0.0417718 - 0.021266 -0.217657 0.044987 - 0.00514036 -0.173221 0.0877162 --0.00223424 -0.188994 0.107463 --0.00813424 -0.195181 0.123224 - -0.0211368 -0.146371 0.157604 - -0.0241057 -0.135459 0.165455 - -0.0241017 -0.137554 0.165457 - -0.0226125 -0.262977 0.162201 - -0.0259547 -0.270533 0.171153 - -0.0267839 -0.270842 0.173365 - -0.027614 -0.27113 0.175579 - -0.0298342 -0.26778 0.181478 - -0.0377083 -0.344988 0.202906 - -0.040367 -0.349966 0.210021 - -0.0473337 -0.374178 0.228728 - -0.0561813 -0.377704 0.252331 - -0.0687955 -0.394738 0.286051 - -0.0702082 -0.373324 0.289694 - -0.0819649 -0.384678 0.321096 - -0.0864258 -0.383556 0.33298 - -0.0870143 -0.382958 0.334545 - -0.106844 -0.384732 0.38741 - -0.108874 -0.379514 0.392792 - -0.109457 -0.378637 0.39434 - -0.112537 -0.382976 0.402575 - -0.116437 -0.387055 0.412992 - -0.119214 -0.381272 0.420362 - -0.126913 -0.382836 0.440893 - -0.144546 -0.378563 0.487868 - -0.147246 -0.381353 0.495081 - -0.161745 -0.378655 0.533712 - -0.167443 -0.382586 0.548924 - -0.222101 -0.411317 0.694773 - -0.465371 -0.91628 1.34608 - -0.473542 -0.751319 1.36692 - -0.480887 -0.634172 1.38583 - -0.484427 -0.604805 1.3951 - -0.493668 -0.569346 1.41953 - -0.492314 -0.514506 1.4156 - -0.50934 -0.500172 1.4609 - -0.638753 -0.554061 1.80616 - -0.795272 -0.545632 2.2233 - -0.795499 -0.505883 2.22368 - -0.797372 -0.282716 2.2274 - -0.797011 0.0768799 2.2244 - -0.802795 0.593396 2.23687 - -0.801998 0.613129 2.23463 - -0.803169 1.0598 2.23521 - -0.803798 1.30565 2.23549 - -0.705846 1.38799 1.97393 - -0.563368 1.36239 1.59431 - -0.553778 1.36096 1.56876 - -0.453551 1.35027 1.30166 - -0.377221 1.32843 1.09833 - -0.150981 0.455421 0.500273 - -0.145291 0.461485 0.485072 - -0.147839 0.477091 0.491774 - -0.147299 0.479267 0.490323 - -0.13884 0.463565 0.467864 - -0.136349 0.470125 0.461187 - -0.134488 0.494968 0.456085 - -0.0801593 0.295529 0.31241 - -0.0766731 0.288561 0.303158 - -0.0620048 0.29126 0.264044 - -0.0567779 0.289016 0.250125 - -0.056219 0.287249 0.248645 - -0.0547691 0.293957 0.244742 - -0.0521487 0.296952 0.237741 - -0.050217 0.294532 0.232606 - -0.0455456 0.288546 0.220188 - -0.032235 0.257098 0.184889 - -0.0296318 0.252346 0.177977 - -0.0267325 0.255303 0.170232 - -0.0254512 0.208075 0.167086 - -0.0290378 0.137768 0.177046 - -0.0287072 0.12833 0.176219 - -0.0277777 0.131791 0.173721 - -0.0226702 0.152559 0.159989 - -0.0209463 0.156205 0.155373 - -0.0146152 0.16748 0.138434 - 0.00134879 0.224328 0.0955589 - 0.00101932 0.206697 0.0965376 - 0.00179485 0.204296 0.0944841 - 0.0238895 0.21745 0.0355167 - 0.0257774 0.214202 0.0305032 - 0.0267788 0.200893 0.0279096 - 0.0273283 0.20079 0.0264457 - 0.0288456 0.203564 0.0223855 - 0.0274131 -0.188599 0.0354595 - 0.0265518 -0.203097 0.0377437 - 0.027677 -0.208392 0.0348928 - 0.0289257 -0.216041 0.0317388 - 0.0293062 -0.223054 0.0308035 - 0.00396141 -0.172842 0.0953978 --0.00294453 -0.165937 0.113036 --0.00126359 -0.192109 0.108877 - 0.00020289 -0.212606 0.105236 --0.00356933 -0.207614 0.114864 --0.00759049 -0.195023 0.125087 - -0.0143295 -0.164795 0.142169 - -0.0226252 -0.133746 0.163232 - -0.0230683 -0.13204 0.164356 - -0.0289124 -0.114759 0.179219 - -0.0286177 -0.133048 0.178566 - -0.0270884 -0.155691 0.174776 - -0.0235872 -0.248574 0.166325 - -0.0283017 -0.271525 0.178518 - -0.0291639 -0.271762 0.180726 - -0.0304269 -0.273075 0.183966 - -0.0305288 -0.284137 0.184287 - -0.0318339 -0.305442 0.187745 - -0.0396724 -0.349984 0.208053 - -0.0502966 -0.369564 0.235353 - -0.0557921 -0.372959 0.249437 - -0.0691262 -0.371543 0.283558 - -0.0911142 -0.381429 0.339891 - -0.109993 -0.381245 0.388211 - -0.127085 -0.381879 0.43196 - -0.13517 -0.382694 0.45266 - -0.136401 -0.383986 0.455818 - -0.149738 -0.384038 0.489953 - -0.155002 -0.381257 0.503411 - -0.163061 -0.383224 0.52405 - -0.163172 -0.37355 0.524279 - -0.18615 -0.381351 0.583137 - -0.188693 -0.381185 0.589644 - -0.192164 -0.347627 0.598343 - -0.194396 -0.346444 0.60405 - -0.502357 -0.860228 1.3951 - -0.488923 -0.804074 1.36041 - -0.491889 -0.690431 1.36738 - -0.493361 -0.664331 1.371 - -0.497605 -0.63552 1.3817 - -0.512986 -0.5394 1.42055 - -0.514692 -0.514715 1.42478 - -0.52746 -0.50157 1.45738 - -0.523148 -0.464225 1.44614 - -0.518737 -0.453533 1.43479 - -0.758459 -0.594262 2.04914 - -0.822183 -0.585782 2.21219 - -0.823825 -0.576891 2.21635 - -0.826845 -0.41954 2.22321 - -0.827808 -0.361363 2.22536 - -0.829417 -0.294149 2.22911 - -0.827677 -0.188076 2.22407 - -0.828344 -0.14061 2.22552 - -0.828065 -0.0836182 2.22449 - -0.82906 -0.0268402 2.22672 - -0.829537 0.00157807 2.22779 - -0.828059 0.0299532 2.22385 - -0.828347 0.162687 2.22386 - -0.830261 0.306924 2.22796 - -0.832707 0.376014 2.23384 - -0.832912 0.5752 2.23327 - -0.834337 0.658383 2.23646 - -0.835036 0.679776 2.23813 - -0.835312 0.700944 2.23872 - -0.835329 0.78589 2.2383 - -0.835115 0.839807 2.23746 - -0.833949 1.07634 2.23317 - -0.834844 1.12521 2.2352 - -0.835408 1.24907 2.23596 - -0.780328 1.3971 2.09417 - -0.684258 1.38159 1.84836 - -0.564495 1.36536 1.54191 - -0.149422 0.450874 0.484555 - -0.140157 0.472717 0.460722 - -0.139348 0.483245 0.458594 - -0.138198 0.497606 0.455571 - -0.104262 0.371993 0.369403 - -0.0758372 0.2894 0.297103 - -0.0724263 0.299785 0.288315 - -0.0660867 0.292111 0.272131 - -0.0615195 0.289841 0.260454 - -0.0578918 0.292746 0.251153 - -0.0519128 0.297102 0.235826 - -0.0499886 0.296648 0.230903 - -0.0338002 0.257507 0.189684 - -0.0295751 0.249488 0.178914 - -0.0259637 0.249204 0.169672 - -0.0292759 0.121897 0.178849 - -0.0288069 0.122625 0.177645 - -0.0270986 0.134846 0.173205 - -0.0261503 0.135203 0.170776 - -0.015523 0.162209 0.143427 - -0.013219 0.171477 0.137479 - 0.00493874 0.239591 0.0906296 - 0.00569991 0.238515 0.0886873 - 0.00256152 0.212589 0.0968625 - 0.00465167 0.203591 0.0915622 - 0.00806581 0.204849 0.0828168 - 0.0191139 0.227726 0.0544134 - 0.022114 0.220429 0.0467746 - 0.0242371 0.22601 0.04131 - 0.0288262 0.223548 0.0295775 - 0.0320408 -0.227714 0.0290517 - 0.0315369 -0.230131 0.0303173 - 0.00669589 -0.173748 0.0917601 - 0.00339711 -0.16887 0.0999335 - 0.00332993 -0.170194 0.100108 --0.00222158 -0.167655 0.113893 --0.00249418 -0.168079 0.114573 --0.00174525 -0.175013 0.112748 --0.00083596 -0.205457 0.110651 --0.00430262 -0.204301 0.119262 - -0.0106917 -0.183311 0.13503 - -0.0174363 -0.150598 0.151619 - -0.01856 -0.14851 0.154401 - -0.0284042 -0.111604 0.178672 - -0.0294722 -0.106116 0.181297 - -0.0222431 -0.242105 0.164057 - -0.0259689 -0.264889 0.17344 - -0.0303236 -0.265102 0.184266 - -0.0315312 -0.285401 0.187376 - -0.0353089 -0.321895 0.196962 - -0.037879 -0.337997 0.203436 - -0.0395505 -0.349984 0.207655 - -0.0486148 -0.368962 0.230287 - -0.0556085 -0.376141 0.247709 - -0.0594409 -0.377762 0.257244 - -0.0707782 -0.376043 0.285415 - -0.0797104 -0.386346 0.307672 - -0.0854083 -0.387939 0.321843 - -0.0911941 -0.383617 0.336201 - -0.0935558 -0.380151 0.342053 - -0.10164 -0.385222 0.362175 - -0.103047 -0.384637 0.365669 - -0.1043 -0.383107 0.368775 - -0.111261 -0.38741 0.386101 - -0.113153 -0.384816 0.390788 - -0.145844 -0.375046 0.471993 - -0.152757 -0.378247 0.489193 - -0.159322 -0.379206 0.505518 - -0.159942 -0.377787 0.507049 - -0.172735 -0.379108 0.538856 - -0.177898 -0.376836 0.551676 - -0.186921 -0.380734 0.574124 - -0.194737 -0.380254 0.593551 - -0.196313 -0.374072 0.597436 - -0.204319 -0.353265 0.617224 - -0.514598 -0.919262 1.39149 - -0.506184 -0.783367 1.36985 - -0.507073 -0.674512 1.37147 - -0.510645 -0.62359 1.38008 - -0.523595 -0.578247 1.41202 - -0.522529 -0.549987 1.40922 - -0.52608 -0.527244 1.41793 - -0.530874 -0.505772 1.42973 - -0.533767 -0.449693 1.43662 - -0.762958 -0.592394 2.00706 - -0.818637 -0.588319 2.14544 - -0.852869 -0.295356 2.22895 - -0.852769 -0.131806 2.22783 - -0.852994 -0.122289 2.22834 - -0.851774 -0.0269268 2.22479 - -0.855129 0.0492976 2.23273 - -0.852756 0.154001 2.22627 - -0.85492 0.298933 2.23087 - -0.851443 0.336403 2.22202 - -0.853748 0.386215 2.22749 - -0.855305 0.466061 2.23093 - -0.852905 0.564936 2.22444 - -0.857292 0.820023 2.23397 - -0.856633 0.941077 2.23169 - -0.858882 0.955 2.2372 - -0.857469 1.08077 2.23301 - -0.859512 1.1435 2.23776 - -0.856545 1.17589 2.23021 - -0.86316 1.36449 2.24564 - -0.85872 1.38365 2.2345 - -0.837132 1.39969 2.18076 - -0.812279 1.39501 2.11901 - -0.586249 1.36301 1.55736 - -0.56709 1.36186 1.50974 - -0.552973 1.36045 1.47466 - -0.54353 1.35885 1.45119 - -0.439804 1.34373 1.19345 - -0.432195 1.34195 1.17455 - -0.402185 1.33234 1.10001 - -0.168409 0.49256 0.523432 - -0.156442 0.486347 0.49372 - -0.146791 0.472974 0.469802 - -0.13948 0.477448 0.451607 - -0.111245 0.369135 0.382006 - -0.0823812 0.292234 0.310674 - -0.077202 0.289908 0.297813 - -0.0763844 0.295948 0.295749 - -0.0733167 0.288088 0.288165 - -0.0643085 0.294601 0.26574 - -0.0563517 0.294564 0.245962 - -0.0549514 0.287028 0.242522 - -0.0528475 0.292827 0.237262 - -0.0493624 0.289798 0.228615 - -0.0477371 0.299191 0.224525 - -0.0451731 0.293608 0.218182 - -0.0255482 0.240144 0.169688 - -0.0256928 0.191551 0.170308 - -0.025845 0.133272 0.170999 - -0.022103 0.15222 0.161596 - -0.0200689 0.157838 0.15651 - -0.0200021 0.149354 0.15639 - -0.0168673 0.157994 0.148551 --0.00107312 0.230138 0.108907 - 0.00332036 0.24231 0.097921 - 0.00473237 0.239379 0.094427 - 0.00425497 0.226614 0.095682 - 0.00589103 0.201346 0.0917508 - 0.0116337 0.214122 0.0774083 - 0.0123842 0.215205 0.075537 - 0.0201327 0.225277 0.0562234 - 0.0254299 0.232237 0.0430193 - 0.0274555 0.226826 0.0380134 - 0.0317946 0.228976 0.0272165 - 0.0379599 0.214212 0.0119713 - 0.0332809 -0.185996 0.0309852 - 0.032662 -0.208285 0.032595 - 0.0321822 -0.219988 0.0338136 - 0.0186884 -0.205598 0.0662943 - 0.0107663 -0.182204 0.0852854 - 0.00143272 -0.162396 0.107701 - -5.351e-05 -0.170675 0.11133 - 5.029e-05 -0.17284 0.111091 --0.00094836 -0.178923 0.113532 --0.00099822 -0.182415 0.11367 --0.00191335 -0.18368 0.115885 --0.00259144 -0.205719 0.117636 - -0.0169576 -0.152966 0.152021 - -0.0187772 -0.144037 0.156365 - -0.0213041 -0.14309 0.162456 - -0.0299738 -0.10869 0.183193 - -0.0234988 -0.245962 0.168288 - -0.0304151 -0.251149 0.185002 - -0.0494498 -0.372825 0.231562 - -0.050103 -0.373689 0.233142 - -0.0614968 -0.384166 0.260686 - -0.0647283 -0.373586 0.268428 - -0.0777847 -0.379085 0.299957 - -0.088652 -0.388145 0.326223 - -0.0980774 -0.382134 0.348932 - -0.10745 -0.383357 0.371551 - -0.117766 -0.378594 0.396415 - -0.124869 -0.384121 0.413582 - -0.127466 -0.376536 0.419808 - -0.131191 -0.381036 0.428818 - -0.145931 -0.380019 0.464375 - -0.14939 -0.378218 0.472712 - -0.151827 -0.379605 0.478599 - -0.151991 -0.376735 0.478979 - -0.186768 -0.381012 0.562905 - -0.320116 -0.565003 0.885589 - -0.504009 -0.909164 1.33106 - -0.530169 -0.908644 1.39417 - -0.531692 -0.903016 1.39782 - -0.530915 -0.860196 1.39572 - -0.520754 -0.764791 1.37071 - -0.522038 -0.759275 1.37377 - -0.529276 -0.611253 1.39046 - -0.530832 -0.578998 1.39405 - -0.556347 -0.478362 1.45508 - -0.557152 -0.47245 1.45699 - -0.87483 -0.502976 2.2236 - -0.871203 -0.490794 2.21479 - -0.875567 -0.443399 2.22507 - -0.873959 -0.402976 2.22098 - -0.877727 -0.365307 2.22987 - -0.878347 -0.355736 2.23132 - -0.874147 -0.29549 2.22087 - -0.87465 -0.285962 2.22203 - -0.87696 -0.209269 2.22721 - -0.879237 -0.0846586 2.23205 - -0.879259 -0.0558895 2.23195 - -0.878059 0.231868 2.22755 - -0.882279 0.330623 2.23722 - -0.878996 0.407977 2.22889 - -0.880691 0.438598 2.23282 - -0.880283 0.488367 2.23158 - -0.879851 0.498163 2.23048 - -0.881376 0.611166 2.23357 - -0.878294 0.63988 2.22599 - -0.879096 0.661272 2.22781 - -0.883355 0.891289 2.23689 - -0.878466 1.06902 2.22416 - -0.86074 1.40518 2.17964 - -0.702406 1.38767 1.79772 - -0.66548 1.38195 1.70866 - -0.645489 1.37362 1.66048 - -0.582995 1.36811 1.50973 - -0.572393 1.36497 1.48417 - -0.522548 1.36161 1.36392 - -0.508763 1.35787 1.33069 - -0.484557 1.3574 1.27229 - -0.461473 1.34514 1.21666 - -0.415147 1.33376 1.10495 - -0.357754 1.17248 0.967322 - -0.155554 0.449558 0.483258 - -0.0978517 0.30038 0.344823 - -0.0936127 0.287999 0.33466 - -0.076069 0.291627 0.292314 - -0.0755822 0.292043 0.291138 - -0.0711777 0.286155 0.280542 - -0.0705929 0.285554 0.279134 - -0.0635493 0.292238 0.262105 - -0.0579177 0.299095 0.248482 - -0.0564182 0.299704 0.244861 - -0.0554657 0.291977 0.242604 - -0.0503771 0.288561 0.230344 - -0.0498186 0.286694 0.229007 - -0.0488607 0.286922 0.226694 - -0.0467288 0.297375 0.221496 - -0.0459577 0.286477 0.219693 - -0.0440428 0.286735 0.215071 - -0.038773 0.260996 0.202492 - -0.0362379 0.252876 0.196418 - -0.0329068 0.25045 0.188394 - -0.0258791 0.23947 0.171496 - -0.0254758 0.232238 0.17056 - -0.0246997 0.231916 0.16869 - -0.027202 0.12833 0.175268 - -0.0230346 0.140916 0.165148 - -0.0109713 0.181674 0.13583 --0.00531421 0.207969 0.122044 - 0.00337203 0.243788 0.1009 - 0.00391839 0.233199 0.0996373 - 0.00469778 0.232206 0.0977621 - 0.00544358 0.216614 0.0960442 - 0.0209165 0.228168 0.0586529 - 0.0241491 0.229555 0.0508466 - 0.0287415 0.233099 0.0397482 - 0.0282044 0.229151 0.0410648 - 0.0293514 0.226826 0.0383096 - 0.0311539 0.230735 0.0339403 - 0.034072 0.217894 0.026967 - 0.0342928 0.214725 0.0264509 - 0.0391421 0.215287 0.0147481 - 0.0379565 -0.196152 0.0250881 - 0.033488 -0.206844 0.0356114 - 0.0334761 -0.227859 0.0357463 - 0.030702 -0.227055 0.0422414 - 0.0266835 -0.219745 0.0516186 - 0.0117245 -0.18057 0.0864651 - 0.00547004 -0.172008 0.101074 - 0.00407907 -0.17308 0.104339 --0.00163363 -0.168869 0.117701 - 0.00067701 -0.192988 0.112411 --0.00302665 -0.201958 0.121133 --0.00337221 -0.202348 0.121945 - -0.0110318 -0.178996 0.139771 - -0.0193868 -0.138816 0.15914 - -0.0189687 -0.145863 0.158197 - -0.0279393 -0.115969 0.179061 - -0.0307391 -0.0990734 0.185534 - -0.0292272 -0.120757 0.182102 - -0.025476 -0.177009 0.1736 - -0.0237618 -0.227036 0.169839 - -0.0241506 -0.227194 0.170751 - -0.0259364 -0.255107 0.175077 - -0.0295235 -0.241996 0.183414 - -0.0304161 -0.267277 0.185634 - -0.0306713 -0.274343 0.186268 - -0.0410609 -0.346911 0.210979 - -0.0428922 -0.350776 0.215288 - -0.0487643 -0.366967 0.229128 - -0.0549719 -0.378519 0.24373 - -0.0701942 -0.377151 0.279386 - -0.0704233 -0.371908 0.279896 - -0.0745014 -0.386935 0.289527 - -0.0826311 -0.383445 0.308556 - -0.0866067 -0.37504 0.317827 - -0.0913482 -0.388865 0.329006 - -0.108048 -0.382331 0.368096 - -0.11757 -0.376873 0.390378 - -0.12826 -0.378558 0.41543 - -0.182779 -0.374901 0.543138 - -0.195024 -0.375874 0.571833 - -0.205529 -0.36403 0.596383 - -0.213797 -0.34937 0.615678 - -0.517524 -0.904429 1.33008 - -0.555254 -0.923071 1.41857 - -0.530383 -0.799125 1.35967 - -0.53279 -0.787601 1.36525 - -0.531446 -0.703676 1.36167 - -0.538229 -0.641813 1.37725 - -0.551571 -0.574975 1.40817 - -0.553667 -0.550107 1.41295 - -0.808716 -0.589662 2.01068 - -0.896326 -0.564018 2.2158 - -0.899205 -0.464751 2.22204 - -0.902337 -0.446379 2.22929 - -0.9052 0.136581 2.23302 - -0.89925 0.154847 2.21899 - -0.901042 0.232394 2.22279 - -0.904117 0.262416 2.22985 - -0.906857 0.521889 2.23494 - -0.907206 0.698339 2.23486 - -0.908145 0.839503 2.23634 - -0.906969 0.905058 2.23325 - -0.90928 1.09317 2.23771 - -0.908003 1.3554 2.23338 - -0.905625 1.40502 2.22756 - -0.78382 1.38918 1.94227 - -0.764085 1.38972 1.89603 - -0.745094 1.39042 1.85154 - -0.618139 1.37256 1.5542 - -0.60715 1.37018 1.52847 - -0.586197 1.36638 1.4794 - -0.539965 1.35278 1.37116 - -0.532121 1.355 1.35277 - -0.165553 0.463641 0.498509 - -0.151232 0.435075 0.465104 - -0.123659 0.34795 0.40095 - -0.114804 0.324136 0.380324 - -0.084172 0.288014 0.308745 - -0.0769485 0.292577 0.291798 - -0.0693543 0.287901 0.27403 - -0.0682682 0.287593 0.271487 - -0.0648989 0.290699 0.263578 - -0.0634876 0.292511 0.260262 - -0.0611759 0.28962 0.254861 - -0.0557578 0.292967 0.242151 - -0.0495693 0.290794 0.227663 - -0.0475455 0.290215 0.222925 - -0.03388 0.249647 0.191116 - -0.0321699 0.249378 0.187111 - -0.0245906 0.225008 0.169478 - -0.023289 0.140489 0.166859 - -0.0219408 0.147816 0.163663 - -0.0189757 0.155936 0.156675 - -0.0187083 0.155713 0.15605 - -0.0167296 0.159265 0.151396 - -0.010854 0.181379 0.137518 - 0.00710092 0.211572 0.0952995 - 0.00913211 0.212087 0.0905382 - 0.010381 0.209057 0.0876277 - 0.0319835 0.235494 0.0368824 - 0.036235 0.22418 0.0269797 - 0.042576 0.214931 0.0121712 - 0.0394476 -0.201679 0.0267635 - 0.0368031 -0.198252 0.0327667 - 0.0341613 -0.201566 0.0387976 - 0.0389026 -0.232398 0.0281569 - 0.00273038 -0.178054 0.110236 - 0.00069847 -0.176292 0.114853 - 3.02e-06 -0.174953 0.116429 --0.00023245 -0.197734 0.117078 - -0.0145449 -0.159535 0.149472 - -0.0160662 -0.153451 0.152905 - -0.0190935 -0.142283 0.159741 - -0.0195928 -0.142692 0.16088 - -0.0205832 -0.139274 0.163118 - -0.0232759 -0.214878 0.169624 - -0.0304466 -0.241267 0.18608 - -0.0316154 -0.280559 0.188936 - -0.0368788 -0.311989 0.201075 - -0.0730075 -0.386171 0.283694 - -0.0851306 -0.384348 0.311284 - -0.088788 -0.378288 0.31958 - -0.0922363 -0.381671 0.327447 - -0.0930315 -0.376716 0.329233 - -0.101276 -0.380523 0.348022 - -0.109927 -0.384143 0.367734 - -0.120101 -0.380395 0.390878 - -0.126345 -0.38089 0.405094 - -0.144232 -0.381051 0.445817 - -0.157632 -0.37752 0.476305 - -0.168463 -0.379966 0.500974 - -0.183151 -0.373793 0.534382 - -0.184647 -0.37436 0.53779 - -0.208574 -0.3433 0.592108 - -0.547153 -0.768418 1.36502 - -0.548004 -0.739623 1.36682 - -0.550357 -0.713436 1.37204 - -0.550506 -0.656121 1.3721 - -0.551662 -0.650546 1.3747 - -0.556579 -0.607774 1.38568 - -0.848364 -0.586175 2.04985 - -0.897769 -0.581585 2.1623 - -0.924584 -0.548285 2.22318 - -0.923135 -0.396459 2.21913 - -0.926854 -0.0562458 2.2259 - -0.927243 0.0208912 2.2264 - -0.927171 0.0401752 2.22614 - -0.927215 0.127066 2.22581 - -0.929439 0.205108 2.23049 - -0.926735 0.233657 2.22419 - -0.928471 0.381626 2.2274 - -0.927529 0.401087 2.22516 - -0.930135 0.432265 2.23094 - -0.92823 0.461428 2.22646 - -0.929366 0.48219 2.22894 - -0.934778 0.639992 2.24048 - -0.932191 0.842343 2.23358 - -0.93299 0.865302 2.23529 - -0.937474 1.13841 2.24414 - -0.933435 1.20739 2.2346 - -0.936182 1.35302 2.24013 - -0.925207 1.40287 2.2149 - -0.79271 1.39785 1.91328 - -0.634122 1.37734 1.55234 - -0.569958 1.3641 1.40634 - -0.50073 1.35251 1.24879 - -0.471893 1.34921 1.18316 - -0.394195 1.22287 1.0069 - -0.390644 1.2218 0.998822 - -0.123291 0.317028 0.394671 - -0.102742 0.277938 0.348083 - -0.0956362 0.286204 0.331866 - -0.0925856 0.283191 0.324936 - -0.0904235 0.287859 0.31999 - -0.0792988 0.283807 0.294684 - -0.075035 0.289436 0.284949 - -0.0745274 0.289824 0.283792 - -0.0731976 0.283502 0.280796 - -0.0717466 0.280393 0.277508 - -0.0680647 0.296311 0.269047 - -0.0677358 0.298569 0.268287 - -0.0652607 0.289724 0.262696 - -0.0642439 0.290283 0.260379 - -0.0609695 0.295999 0.252896 - -0.0538242 0.291676 0.23665 - -0.0455602 0.291542 0.217837 - -0.0383986 0.255996 0.20171 - -0.0370784 0.250958 0.19873 - -0.0281584 0.232476 0.178515 - -0.0258017 0.187232 0.173374 - -0.0235358 0.148265 0.16841 - -0.0223431 0.146442 0.165704 - -0.018681 0.153084 0.157333 --0.00054434 0.226792 0.115677 - 0.00453124 0.23103 0.104101 - 0.0073741 0.2354 0.0976076 - 0.00633972 0.215462 0.100062 - 0.00709598 0.214473 0.0983448 - 0.0141689 0.214769 0.0822414 - 0.0264702 0.231702 0.0541521 - 0.0290906 0.234422 0.0481731 - 0.0354623 0.236269 0.0336584 - 0.0421262 0.215603 0.0185901 - 0.0453021 -0.202379 0.0187133 - 0.0417575 -0.202402 0.0265587 - 0.0383327 -0.200604 0.0341298 - 0.037436 -0.205298 0.0361372 - 0.00638052 -0.166135 0.104681 - 0.00241534 -0.160367 0.113429 - 0.00472649 -0.178025 0.108399 - 0.00437804 -0.181979 0.10919 - 0.00070067 -0.184506 0.117341 --0.00237304 -0.201278 0.124225 --0.00377682 -0.200542 0.127329 - -0.0054746 -0.197893 0.131073 - -0.0122212 -0.169858 0.145869 - -0.0133796 -0.164489 0.148407 - -0.0157759 -0.15487 0.153664 - -0.0298185 -0.106119 0.184507 - -0.0342007 -0.288871 0.195093 - -0.0402113 -0.341943 0.208654 - -0.0442746 -0.36464 0.217758 - -0.0511629 -0.373548 0.233046 - -0.0593096 -0.373292 0.251076 - -0.0615655 -0.376523 0.256084 - -0.0704764 -0.382748 0.275837 - -0.0928139 -0.377901 0.325252 - -0.0943112 -0.377656 0.328564 - -0.108391 -0.376598 0.359721 - -0.127998 -0.383584 0.40315 - -0.130538 -0.378834 0.40875 - -0.140621 -0.384767 0.431094 - -0.212025 -0.384285 0.589126 - -0.214773 -0.376833 0.595173 - -0.213951 -0.368497 0.593312 - -0.215626 -0.343313 0.596898 - -0.219448 -0.344449 0.605362 - -0.561479 -0.802696 1.36459 - -0.562838 -0.743649 1.36731 - -0.563151 -0.685384 1.36772 - -0.567658 -0.620319 1.37738 - -0.577161 -0.582713 1.39823 - -0.582552 -0.567863 1.41009 - -0.583929 -0.542017 1.41301 - -0.585877 -0.530411 1.41727 - -0.586956 -0.504603 1.41953 - -0.606916 -0.488689 1.46363 - -0.830402 -0.587436 1.95874 - -0.838948 -0.584487 1.97764 - -0.859608 -0.580592 2.02335 - -0.916499 -0.580536 2.14926 - -0.951776 -0.340056 2.22617 - -0.950767 -0.329777 2.22389 - -0.952376 -0.280945 2.22721 - -0.953936 -0.017792 2.22938 - -0.952326 0.0791243 2.22535 - -0.952309 0.12764 2.22508 - -0.954981 0.206123 2.23061 - -0.952192 0.225031 2.22434 - -0.953312 0.274357 2.22658 - -0.953407 0.333593 2.22651 - -0.957417 0.568018 2.23424 - -0.953535 0.638334 2.22531 - -0.955168 0.649978 2.22887 - -0.95921 0.949534 2.23636 - -0.958824 0.972175 2.23539 - -0.959729 0.984726 2.23734 - -0.960328 1.0087 2.23854 - -0.962847 1.21838 2.2431 - -0.963161 1.24419 2.24367 - -0.960918 1.31868 2.23835 - -0.919503 1.40134 2.14628 - -0.614505 1.37129 1.47139 - -0.593599 1.36827 1.42513 - -0.109915 0.282349 0.359894 - -0.108901 0.283846 0.357641 - -0.0996068 0.287259 0.337055 - -0.0826088 0.28904 0.299426 - -0.0761055 0.288088 0.285037 - -0.0706575 0.284668 0.272996 - -0.0626806 0.28618 0.255333 - -0.0585571 0.28803 0.246198 - -0.0564858 0.288823 0.24161 - -0.0508485 0.292542 0.229115 - -0.0468633 0.283322 0.22034 - -0.0382031 0.261996 0.201276 - -0.0364099 0.249936 0.197366 - -0.0296985 0.224943 0.182633 - -0.0288072 0.226733 0.180652 - -0.0283997 0.226626 0.17975 - -0.0279925 0.226515 0.17885 - -0.0269839 0.23025 0.176599 - -0.025395 0.214593 0.173159 - -0.0268444 0.16962 0.176585 - -0.0286389 0.114531 0.180824 - -0.0218811 0.145479 0.165717 - -0.0217299 0.144338 0.165388 - -0.0199907 0.149348 0.161514 - -0.0159791 0.156679 0.1526 --0.00281795 0.215043 0.123188 - 0.00483023 0.234246 0.106167 - 0.00926751 0.225725 0.0963876 - 0.00872966 0.220782 0.097602 - 0.0106908 0.213674 0.0932959 - 0.0174688 0.217849 0.0782742 - 0.0442908 -0.198425 0.0258854 - 0.0401943 -0.228615 0.0348483 - 0.0350788 -0.225437 0.0458465 - 0.0311497 -0.221179 0.0542855 - 0.00705058 -0.18454 0.105995 - 0.00776351 -0.189346 0.104483 - 0.0008272 -0.192317 0.119431 --0.00285725 -0.188614 0.127346 --0.00765867 -0.188949 0.137684 - -0.0216714 -0.13879 0.167615 - -0.024874 -0.188538 0.174746 - -0.0387834 -0.318985 0.205311 - -0.0449752 -0.367563 0.218872 - -0.0456509 -0.367481 0.220327 - -0.0491754 -0.371953 0.227936 - -0.0535595 -0.37806 0.237404 - -0.0843072 -0.374817 0.303586 - -0.0950008 -0.390753 0.326684 - -0.103234 -0.381208 0.344366 - -0.112115 -0.384015 0.363497 - -0.11545 -0.379156 0.370654 - -0.126649 -0.377636 0.394759 - -0.141462 -0.376149 0.426644 - -0.147259 -0.375303 0.439119 - -0.14795 -0.374161 0.440601 - -0.161122 -0.382182 0.468999 - -0.216034 -0.377912 0.587201 - -0.218594 -0.344571 0.592552 - -0.578549 -0.908067 1.37019 - -0.592391 -0.888716 1.3999 - -0.591583 -0.879064 1.39811 - -0.593204 -0.873307 1.40157 - -0.575819 -0.737569 1.3635 - -0.575331 -0.692859 1.36224 - -0.576609 -0.687275 1.36496 - -0.581131 -0.642924 1.37449 - -0.58163 -0.622488 1.37547 - -0.58842 -0.595377 1.38996 - -0.605135 -0.502968 1.4255 - -0.621292 -0.476275 1.46016 - -0.903244 -0.578302 2.06767 - -0.930949 -0.576863 2.12731 - -0.959524 -0.574827 2.18882 - -0.976046 -0.321383 2.22319 - -0.975703 -0.291543 2.22231 - -0.975352 -0.232317 2.22127 - -0.97748 -0.125031 2.22534 - -0.976117 -0.0664217 2.22213 - -0.979521 0.0406296 2.22895 - -0.975581 0.0598865 2.22038 - -0.97548 0.0695951 2.22011 - -0.977441 0.128214 2.22406 - -0.977576 0.196674 2.22402 - -0.976461 0.505248 2.22016 - -0.98191 0.559739 2.23163 - -0.982428 0.622688 2.23245 - -0.981293 0.632451 2.22995 - -0.984965 0.919851 2.2365 - -0.983433 1.03446 2.23266 - -0.985549 1.09668 2.23691 - -0.984538 1.1198 2.23463 - -0.983053 1.1425 2.23132 - -0.978181 1.30034 2.22008 - -0.973311 1.38576 2.20919 - -0.970772 1.3954 2.20368 - -0.769531 1.3908 1.77045 - -0.638337 1.37228 1.48808 - -0.618636 1.3742 1.44566 - -0.129455 0.294508 0.397609 - -0.123689 0.278448 0.385271 - -0.11967 0.277856 0.376621 - -0.11486 0.281879 0.366246 - -0.114342 0.282666 0.365128 - -0.110635 0.282245 0.357148 - -0.104683 0.277757 0.344356 - -0.102919 0.293711 0.340482 - -0.102186 0.293485 0.338904 - -0.0939044 0.288553 0.321099 - -0.0907625 0.285295 0.31435 - -0.0773115 0.283481 0.285399 - -0.0708138 0.291136 0.271374 - -0.0696374 0.285657 0.268867 - -0.0645321 0.296695 0.257823 - -0.063274 0.295258 0.255122 - -0.0607844 0.285182 0.24981 - -0.0541612 0.291676 0.235519 - -0.047235 0.295293 0.220591 - -0.0464889 0.288394 0.219017 - -0.0389315 0.250998 0.202924 - -0.0375496 0.249988 0.199954 - -0.0276814 0.150883 0.179179 - -0.0263807 0.133007 0.176463 - -0.0195159 0.155692 0.161576 - -0.0169779 0.155936 0.156111 - -0.0126612 0.174612 0.146728 - 0.00139111 0.217274 0.116272 - 0.0124334 0.217692 0.0924969 - 0.0451553 0.230155 0.0219895 - 0.0485206 0.227096 0.0147588 - 0.0382764 -0.19935 0.0431358 - 0.00477219 -0.162505 0.1132 - 0.0046903 -0.16379 0.113378 - 0.009164 -0.190214 0.104122 - 0.00039412 -0.177261 0.122447 --0.00068248 -0.195023 0.124786 - -0.0189799 -0.146731 0.162919 - -0.0222859 -0.138471 0.169812 - -0.02449 -0.130455 0.174395 - -0.0270828 -0.121528 0.179789 - -0.0244523 -0.223957 0.17475 - -0.0282253 -0.215923 0.182622 - -0.0313556 -0.252603 0.189355 - -0.0358908 -0.282978 0.199003 - -0.0364014 -0.28699 0.200092 - -0.0374499 -0.306999 0.202383 - -0.0398652 -0.324946 0.20753 - -0.0404835 -0.325917 0.20883 - -0.0424827 -0.337785 0.213076 - -0.0439766 -0.350654 0.216268 - -0.0469829 -0.3653 0.222638 - -0.0477226 -0.367194 0.224198 - -0.0492847 -0.372951 0.227499 - -0.0499855 -0.372825 0.228968 - -0.0544458 -0.377889 0.238341 - -0.0551558 -0.37771 0.239829 - -0.0558656 -0.377525 0.241316 - -0.057233 -0.376141 0.244176 - -0.0579927 -0.376926 0.245772 - -0.0598615 -0.384417 0.249725 - -0.0832428 -0.38441 0.29874 - -0.0839653 -0.38394 0.300252 - -0.101472 -0.382946 0.336947 - -0.101803 -0.375129 0.337606 - -0.105386 -0.381447 0.345145 - -0.108208 -0.383015 0.351068 - -0.108928 -0.382292 0.352575 - -0.11464 -0.376247 0.36452 - -0.127628 -0.3821 0.391776 - -0.128515 -0.374098 0.393597 - -0.130068 -0.376641 0.396864 - -0.131204 -0.377428 0.39925 - -0.131914 -0.376472 0.400733 - -0.133925 -0.380676 0.40497 - -0.136068 -0.377704 0.409447 - -0.153063 -0.373128 0.445053 - -0.154971 -0.372378 0.44905 - -0.159704 -0.380388 0.459008 - -0.162626 -0.379011 0.465129 - -0.174885 -0.380491 0.490834 - -0.177733 -0.374853 0.496779 - -0.178439 -0.373425 0.498251 - -0.203974 -0.373444 0.551782 - -0.219397 -0.380427 0.584145 - -0.223794 -0.379468 0.593359 - -0.225088 -0.355896 0.595962 - -0.224343 -0.338913 0.594321 - -0.261564 -0.388532 0.672578 - -0.587872 -0.904031 1.35902 - -0.609719 -0.888499 1.40475 - -0.605153 -0.864794 1.39507 - -0.587031 -0.774636 1.35666 - -0.594012 -0.694365 1.37092 - -0.59929 -0.608043 1.38158 - -0.600047 -0.601919 1.38314 - -0.604526 -0.578996 1.39242 - -0.622464 -0.500535 1.42966 - -0.957806 -0.57147 2.13298 - -1.00126 -0.535996 2.22391 - -0.998545 -0.392037 2.21755 - -1.00143 -0.313043 2.22324 - -1.00005 -0.292712 2.22024 - -1.001 -0.213835 2.22187 - -1.00332 -0.0473014 2.22597 - -1.0035 -0.0277304 2.22625 - -1.00685 0.469398 2.23096 - -1.00753 0.56265 2.23195 - -1.00594 0.624563 2.22834 - -1.00691 0.646348 2.23026 - -1.00713 0.775833 2.23011 - -1.00829 0.876921 2.23209 - -1.00866 0.888567 2.2328 - -1.00875 1.05142 2.23225 - -1.00427 1.09448 2.22264 - -1.00076 1.12687 2.21514 - -0.998974 1.16153 2.21123 - -0.991696 1.2272 2.19567 - -0.978361 1.31132 2.16733 - -0.975906 1.32082 2.16213 - -0.652274 1.31587 1.48372 - -0.638893 1.34448 1.45553 - -0.635769 1.38481 1.4488 - -0.634805 1.40682 1.44667 - -0.137709 0.277719 0.409843 - -0.13399 0.27702 0.40205 - -0.11164 0.286305 0.355155 - -0.102806 0.290817 0.336613 - -0.103047 0.295032 0.3371 - -0.0931346 0.28933 0.316347 - -0.0909562 0.291504 0.31177 - -0.0856635 0.279205 0.300732 - -0.0794311 0.281307 0.287657 - -0.07638 0.28466 0.281245 - -0.0738722 0.283274 0.275994 - -0.0517616 0.29639 0.229582 - -0.0512942 0.298512 0.228593 - -0.0423346 0.267843 0.209953 - -0.0382811 0.249999 0.201538 - -0.0373599 0.241989 0.199644 - -0.0257519 0.205954 0.175477 - -0.0233805 0.139848 0.170813 - -0.0217052 0.150203 0.167253 - -0.0166147 0.156156 0.156554 - -0.0149241 0.161175 0.152987 --0.00786213 0.193525 0.138032 - 0.00510096 0.228754 0.110694 - 0.0097422 0.22593 0.100977 - 0.0124766 0.223816 0.0952549 - 0.01621 0.21673 0.0874613 - 0.0166177 0.216176 0.0866093 - 0.0264936 0.233699 0.0658248 - 0.036268 0.233796 0.045334 - 0.0367078 0.233038 0.0444154 - 0.0373023 0.224455 0.043209 - 0.0417849 0.23149 0.0337794 - 0.0513172 0.222911 0.0138364 - 0.0427576 -0.193879 0.038148 - 0.0440239 -0.228615 0.0357213 - 0.0320635 -0.215435 0.0600737 - 0.029537 -0.213408 0.0652211 - 0.0106967 -0.168652 0.103472 - 0.0052404 -0.180653 0.114664 - 0.00276735 -0.175694 0.119689 - 0.00189163 -0.175593 0.121476 - 0.00087909 -0.176747 0.123548 - 0.00124803 -0.192975 0.122869 --0.00265179 -0.195693 0.130841 - -0.0035211 -0.200775 0.132638 --0.00954795 -0.179148 0.144841 - -0.0164374 -0.149561 0.158769 - -0.0282273 -0.117116 0.182685 - -0.0284391 -0.13039 0.183178 - -0.0277981 -0.20787 0.182222 - -0.0303385 -0.204379 0.187391 - -0.0337651 -0.264882 0.19466 - -0.0351992 -0.274961 0.197633 - -0.0469572 -0.363304 0.222034 - -0.0483228 -0.362097 0.224816 - -0.0551746 -0.373735 0.238854 - -0.0607281 -0.381213 0.250223 - -0.0614602 -0.380975 0.251716 - -0.0694796 -0.377872 0.26807 - -0.0900741 -0.381399 0.310121 - -0.0930872 -0.385485 0.31629 - -0.114699 -0.382199 0.360387 - -0.117628 -0.37906 0.36635 - -0.12005 -0.38193 0.371306 - -0.124914 -0.383043 0.38124 - -0.132997 -0.38098 0.397728 - -0.144991 -0.377223 0.422192 - -0.15541 -0.373128 0.443439 - -0.163921 -0.378687 0.460838 - -0.176865 -0.378194 0.487254 - -0.180183 -0.37703 0.494021 - -0.186277 -0.379496 0.50647 - -0.187006 -0.378012 0.507953 - -0.199677 -0.375614 0.533805 - -0.212456 -0.374505 0.559881 - -0.396256 -0.598402 0.936051 - -0.615793 -0.612684 1.38421 - -1.03052 -0.0968963 2.22835 - -1.02897 0.0114674 2.22471 - -1.02976 0.0409932 2.22617 - -1.03154 0.189284 2.22914 - -1.03282 0.289249 2.23129 - -1.03237 0.410199 2.22983 - -1.03122 0.430084 2.2274 - -1.03249 0.492195 2.2297 - -1.03284 0.502699 2.23037 - -1.03233 0.617396 2.2288 - -1.0325 0.63871 2.22905 - -1.03506 0.69398 2.23404 - -1.02765 0.932316 2.21782 - -0.998646 1.13656 2.15769 - -0.996082 1.14559 2.15242 - -0.986081 1.23118 2.13162 - -0.969984 1.36154 2.09817 - -0.956777 1.40732 2.07101 - -0.947522 1.40626 2.05212 - -0.874457 1.40516 1.90299 - -0.831896 1.39532 1.81617 - -0.807012 1.40083 1.76535 - -0.769517 1.35646 1.68902 - -0.742595 1.47755 1.63352 - -0.735343 1.50107 1.61861 - -0.726676 1.52162 1.60083 - -0.15564 0.281639 0.440933 - -0.148762 0.277024 0.426916 - -0.130524 0.273859 0.389705 - -0.12579 0.274401 0.380039 - -0.113601 0.277339 0.355147 - -0.0816861 0.287509 0.28996 - -0.0711829 0.285332 0.268532 - -0.0678888 0.287195 0.2618 - -0.0656811 0.288328 0.257289 - -0.0600124 0.296907 0.245679 - -0.0576642 0.296736 0.240887 - -0.051108 0.292542 0.227525 - -0.0493432 0.290907 0.22393 - -0.0354574 0.224918 0.195888 - -0.0336597 0.228774 0.192201 - -0.0320303 0.223572 0.188899 - -0.0184883 0.151655 0.161585 - -0.0157266 0.160187 0.15591 --0.00512318 0.202595 0.134075 - 0.00186352 0.218893 0.11974 - 0.00346552 0.224948 0.116443 - 0.0105522 0.226415 0.101972 - 0.0139964 0.211058 0.0950114 - 0.0292077 0.230875 0.0638736 - 0.0369927 0.236855 0.0479568 - 0.0382437 0.212057 0.0455159 - 0.0469245 0.216216 0.0277788 - 0.0476252 -0.197342 0.0327898 - 0.0442846 -0.206887 0.0394711 - 0.0440619 -0.209976 0.0399276 - 0.0383824 -0.225274 0.0512829 - 0.0140881 -0.172697 0.0993302 - 0.00189942 -0.188957 0.123626 --0.00204374 -0.193838 0.131484 --0.00799172 -0.183862 0.14326 - -0.0104857 -0.173073 0.148169 - -0.0197753 -0.140718 0.166487 - -0.0235735 -0.132536 0.173998 - -0.0250887 -0.128157 0.17699 - -0.0270018 -0.115749 0.180737 - -0.0271415 -0.11683 0.18102 - -0.0319234 -0.242728 0.191083 - -0.0376666 -0.295996 0.202734 - -0.0382545 -0.298986 0.203916 - -0.0415665 -0.329838 0.210635 - -0.0469761 -0.363304 0.221535 - -0.052317 -0.37141 0.232185 - -0.0638967 -0.37824 0.255228 - -0.0722086 -0.376875 0.271741 - -0.0784206 -0.376813 0.284086 - -0.0813732 -0.375141 0.289947 - -0.0846474 -0.382483 0.296486 - -0.0941554 -0.380185 0.315372 - -0.0956465 -0.379057 0.31833 - -0.111372 -0.376072 0.349569 - -0.116358 -0.387514 0.359529 - -0.125795 -0.379496 0.378248 - -0.127074 -0.376872 0.380778 - -0.147374 -0.378061 0.421127 - -0.153833 -0.385313 0.433995 - -0.175379 -0.383479 0.476807 - -0.185294 -0.379378 0.496492 - -0.20027 -0.37595 0.526241 - -0.20966 -0.380592 0.544921 - -0.221632 -0.372864 0.568681 - -0.227238 -0.370903 0.579812 - -0.233936 -0.367355 0.593109 - -0.234685 -0.362244 0.594574 - -0.234363 -0.355246 0.593903 - -0.235061 -0.353326 0.595282 - -0.241992 -0.343304 0.609011 - -0.2459 -0.34669 0.616794 - -0.63979 -0.896268 1.40204 - -0.623253 -0.715242 1.36837 - -0.636986 -0.593677 1.39512 - -0.636432 -0.579209 1.39395 - -0.674083 -0.473339 1.46831 - -0.672458 -0.465272 1.46504 - -0.880308 -0.5635 1.87855 - -0.967063 -0.572523 2.051 - -1.05382 -0.0575692 2.22114 - -1.05394 -0.0477021 2.22133 - -1.05568 0.10053 2.22412 - -1.05739 0.160274 2.22726 - -1.05506 0.319654 2.22193 - -1.05754 0.401559 2.22649 - -1.06045 0.433455 2.23212 - -1.05803 0.56726 2.22671 - -1.03079 0.859855 2.17127 - -1.02458 0.92119 2.15867 - -1.0139 1.02449 2.13697 - -1.00137 1.10411 2.11172 - -0.991 1.17526 2.0908 - -0.975612 1.30299 2.05965 - -0.950312 1.40708 2.00891 - -0.887582 1.39742 1.88428 - -0.860462 1.40269 1.83036 - -0.816161 1.42543 1.74222 - -0.18253 0.270204 0.488109 - -0.173053 0.268568 0.469283 - -0.171468 0.272478 0.466116 - -0.159532 0.268426 0.442413 - -0.153011 0.270025 0.429446 - -0.140774 0.272877 0.405113 - -0.139416 0.27409 0.402409 - -0.135874 0.276589 0.39536 - -0.135618 0.283384 0.394819 - -0.129627 0.275871 0.382947 - -0.118655 0.279355 0.361127 - -0.113708 0.277968 0.351301 - -0.11207 0.280149 0.348036 - -0.110195 0.281413 0.344304 - -0.110195 0.287167 0.344279 - -0.108062 0.296584 0.339999 - -0.0865765 0.282019 0.297363 - -0.0808402 0.281307 0.285966 - -0.0751079 0.288438 0.274542 - -0.0610474 0.29154 0.246585 - -0.0587584 0.292389 0.242033 - -0.0570373 0.292967 0.23861 - -0.051371 0.284454 0.227387 - -0.0506114 0.292666 0.22584 - -0.0402557 0.242945 0.205481 - -0.0397792 0.242966 0.204534 - -0.0392953 0.241981 0.203577 - -0.0374019 0.231997 0.199859 - -0.0334713 0.22278 0.192088 - -0.033155 0.216742 0.191486 - -0.032774 0.214697 0.190738 - -0.0295781 0.221224 0.184358 - -0.0291442 0.221141 0.183496 - -0.0287104 0.221053 0.182634 - -0.0272362 0.206645 0.179768 - -0.026985 0.203561 0.179283 - -0.0283283 0.115117 0.182346 - -0.0196447 0.147583 0.164944 - -0.0151785 0.159234 0.156016 - 0.00014843 0.211707 0.125323 - 0.0216248 0.217906 0.0826141 - 0.02295 0.218442 0.0799782 - 0.032127 0.237392 0.0616559 - 0.0481259 0.221827 0.0299295 - 0.0485617 0.22099 0.0290673 - 0.0517466 0.217352 0.022754 - 0.0486276 0.206102 0.0290026 - 0.0473324 -0.182473 0.0375789 - 0.0476186 -0.184689 0.0370343 - 0.0439022 -0.227846 0.0444201 - 0.0342927 -0.215991 0.0629794 - 0.0127714 -0.173928 0.104477 - 0.00251848 -0.18714 0.124392 - 0.00229776 -0.19723 0.124864 - -0.0201076 -0.136062 0.16799 - -0.0203439 -0.141376 0.168471 - -0.0210841 -0.137656 0.169888 - -0.027186 -0.120068 0.181629 - -0.0314046 -0.149494 0.189928 - -0.0298612 -0.222468 0.187257 - -0.0348715 -0.258963 0.19712 - -0.0436885 -0.342662 0.214561 - -0.052644 -0.376388 0.232052 - -0.0564088 -0.375538 0.23934 - -0.0635575 -0.368365 0.253154 - -0.0903085 -0.387731 0.305048 - -0.100631 -0.382353 0.325017 - -0.102872 -0.375194 0.329325 - -0.108756 -0.378676 0.340737 - -0.118011 -0.379613 0.358666 - -0.122043 -0.380953 0.366481 - -0.129716 -0.376873 0.381323 - -0.134732 -0.381125 0.391056 - -0.136258 -0.379244 0.394003 - -0.145165 -0.381636 0.411265 - -0.170473 -0.376156 0.460256 - -0.177561 -0.375357 0.47398 - -0.192724 -0.37727 0.503355 - -0.220653 -0.373443 0.557429 - -0.222484 -0.370604 0.560964 - -0.237377 -0.373114 0.589817 - -0.241019 -0.341191 0.596732 - -0.63948 -0.698086 1.37 - -0.646796 -0.605314 1.38377 - -0.650891 -0.595302 1.39166 - -0.665065 -0.545576 1.41889 - -0.679009 -0.440418 1.44544 - -0.859826 -0.538775 1.79606 - -0.952919 -0.571322 1.9765 - -1.07864 -0.543677 2.21988 - -1.0788 -0.429592 2.21967 - -1.07685 -0.286717 2.21528 - -1.07799 -0.266924 2.21741 - -1.08406 -0.187972 2.22881 - -1.08332 -0.157806 2.22725 - -1.08048 0.130741 2.2205 - -1.08618 0.231792 2.23109 - -1.07844 0.514768 2.21486 - -1.06754 0.550683 2.19359 - -1.06615 0.591539 2.19073 - -1.063 0.62108 2.1845 - -1.05617 0.679913 2.17102 - -1.04325 0.745079 2.14571 - -1.04286 0.766142 2.14487 - -1.02888 0.862742 2.11736 - -1.00092 1.09309 2.06221 - -0.987014 1.21858 2.03473 - -0.970808 1.33273 2.00285 - -0.894164 1.40539 1.85409 - -0.882572 1.39896 1.83167 - -0.878318 1.40452 1.8234 - -0.859644 1.39823 1.78727 - -0.844932 1.38557 1.75883 - -0.842164 1.39321 1.75343 - -0.174636 0.261977 0.465536 - -0.165629 0.267126 0.44807 - -0.145395 0.267825 0.408879 - -0.147276 0.274887 0.412492 - -0.146727 0.275926 0.411423 - -0.124533 0.272924 0.368452 - -0.123959 0.276217 0.367326 - -0.123407 0.277034 0.366253 - -0.121234 0.277779 0.362042 - -0.118625 0.274306 0.357005 - -0.114991 0.280415 0.34994 - -0.111944 0.28315 0.344026 - -0.111243 0.304551 0.342575 - -0.108573 0.303054 0.337411 - -0.105321 0.298765 0.331131 - -0.103525 0.300664 0.327644 - -0.0964681 0.294469 0.314004 - -0.095879 0.295023 0.31286 - -0.0952889 0.295573 0.311715 - -0.0850182 0.287133 0.29186 - -0.0842893 0.286636 0.290451 - -0.0609161 0.286615 0.245183 - -0.0604216 0.287818 0.24422 - -0.0376526 0.230999 0.20037 - -0.0358752 0.219963 0.196976 - -0.0281908 0.203953 0.182163 - -0.0283953 0.115295 0.182946 - -0.0267991 0.125839 0.179808 - -0.0256333 0.12432 0.177557 - -0.0229657 0.137363 0.172334 - -0.0186522 0.148369 0.163931 - 0.00891107 0.230584 0.11019 - 0.0153217 0.221668 0.0978134 - 0.0157863 0.214346 0.0969456 - 0.019077 0.222938 0.0905349 - 0.0328036 0.236393 0.0638914 - 0.0404921 0.22589 0.0490465 - 0.0407696 0.212784 0.0485663 - 0.0420589 0.214366 0.0460623 - 0.0433435 0.212072 0.0435844 - 0.0394794 -0.17347 0.0565125 - 0.0482639 -0.209186 0.0400847 - 0.042266 -0.222207 0.0514612 - 0.0410765 -0.222869 0.0537092 - 0.0138374 -0.162215 0.104863 - 0.0128411 -0.168377 0.10677 - 0.0149905 -0.177322 0.102751 - 0.0146342 -0.181321 0.103441 - 0.0131713 -0.179693 0.106195 - 0.0128665 -0.185871 0.106797 - 0.0149207 -0.199493 0.102978 - 0.00936724 -0.187689 0.113409 - 0.00178514 -0.192087 0.127739 - -0.0151705 -0.154202 0.15958 - -0.0203265 -0.144755 0.169272 - -0.0254189 -0.198527 0.179113 - -0.0307795 -0.165497 0.18909 - -0.0320884 -0.229788 0.191835 - -0.0384999 -0.294971 0.204215 - -0.0612078 -0.374282 0.247414 - -0.0619726 -0.374048 0.248857 - -0.0904022 -0.381987 0.302551 - -0.0979056 -0.391562 0.316754 - -0.0987059 -0.390985 0.318262 - -0.0985986 -0.384729 0.318033 - -0.105295 -0.377356 0.330641 - -0.110205 -0.379599 0.339918 - -0.117916 -0.381147 0.354478 - -0.118889 -0.381292 0.356316 - -0.129953 -0.383043 0.377207 - -0.142134 -0.378834 0.400179 - -0.146886 -0.384369 0.409172 - -0.16033 -0.373829 0.434503 - -0.194468 -0.380973 0.498968 - -0.196797 -0.376522 0.503345 - -0.200372 -0.374929 0.510085 - -0.214225 -0.372607 0.536223 - -0.244659 -0.343742 0.593542 - -0.250524 -0.347106 0.604626 - -0.499571 -0.705414 1.07623 - -0.638609 -0.892247 1.33945 - -0.669572 -0.878062 1.39783 - -0.653401 -0.722447 1.36665 - -0.652853 -0.699493 1.36551 - -0.654049 -0.686121 1.36772 - -0.662827 -0.594895 1.38389 - -0.665255 -0.58319 1.38843 - -0.680377 -0.533958 1.41676 - -0.703438 -0.461871 1.45998 - -1.10532 -0.473233 2.21856 - -1.11044 -0.198966 2.22706 - -1.1118 -0.0384027 2.22893 - -1.1129 0.162318 2.23015 - -1.11456 0.182755 2.23321 - -1.10183 0.331253 2.20854 - -1.09579 0.369742 2.19698 - -1.0921 0.398769 2.1899 - -1.06161 0.607951 2.13144 - -1.04715 0.73316 2.10362 - -1.03675 0.79897 2.08371 - -0.968502 0.927821 1.95434 - -0.99 1.19825 1.99376 - -0.973214 1.32223 1.96155 - -0.155542 0.268223 0.422722 - -0.148553 0.268298 0.40953 - -0.148005 0.26933 0.408492 - -0.134132 0.271586 0.382297 - -0.126834 0.280352 0.368486 - -0.110371 0.280865 0.33741 - -0.110237 0.304836 0.337055 - -0.0905117 0.276818 0.299943 - -0.0871964 0.283888 0.293655 - -0.0846006 0.28802 0.288738 - -0.0826645 0.284148 0.2851 - -0.0790308 0.285615 0.278236 - -0.0777275 0.285418 0.275776 - -0.0646551 0.291335 0.251077 - -0.0624352 0.287148 0.246905 - -0.056348 0.295307 0.235381 - -0.0519681 0.293406 0.227122 - -0.0467581 0.282324 0.217336 - -0.0428151 0.260759 0.209986 - -0.0422825 0.260806 0.20898 - -0.0289126 0.197156 0.184017 - -0.0306733 0.0939461 0.187781 - -0.0272848 0.118069 0.181282 - -0.0241611 0.132029 0.175327 - -0.0218988 0.13708 0.171035 - -0.0192742 0.149066 0.16603 - -0.0023402 0.205738 0.133826 --0.00091614 0.205673 0.131138 - 0.0110983 0.227414 0.108368 - 0.025764 0.231409 0.0806704 - 0.0259578 0.223033 0.0803404 - 0.0379428 0.238645 0.0576524 - 0.0403348 0.220302 0.0532159 - 0.0494449 0.191929 0.036142 - 0.0353209 -0.156862 0.0684302 - 0.0346641 -0.158164 0.0696377 - 0.0462677 -0.202393 0.0485875 - 0.0503692 -0.216156 0.0411392 - 0.0470351 -0.219256 0.0472535 - 0.0161368 -0.181321 0.103639 - 0.0138862 -0.180618 0.107755 - 0.00978069 -0.189854 0.115306 - 0.00577259 -0.193885 0.122658 --0.00261497 -0.187078 0.137979 --0.00300619 -0.187385 0.138696 - -0.0235145 -0.129135 0.175983 - -0.0274914 -0.10629 0.183166 - -0.0283818 -0.106608 0.184796 - -0.0263883 -0.186807 0.181483 - -0.0315102 -0.218755 0.190989 - -0.0326839 -0.229865 0.193183 - -0.0336459 -0.229925 0.194944 - -0.0349739 -0.244981 0.197437 - -0.0456993 -0.342433 0.217471 - -0.0475816 -0.357216 0.220977 - -0.0746921 -0.384706 0.270704 - -0.079986 -0.371957 0.280339 - -0.098743 -0.383411 0.314712 - -0.121217 -0.375219 0.355805 - -0.132902 -0.378637 0.377202 - -0.134906 -0.370689 0.380836 - -0.154903 -0.376985 0.417458 - -0.160735 -0.380868 0.428146 - -0.17715 -0.375667 0.458164 - -0.208428 -0.374645 0.515399 - -0.209995 -0.371497 0.518253 - -0.234308 -0.37803 0.562774 - -0.238529 -0.372748 0.570476 - -0.250639 -0.358329 0.592577 - -0.25288 -0.352445 0.596654 - -0.277632 -0.361868 0.641989 - -0.686861 -0.889439 1.39308 - -0.676038 -0.642877 1.37224 - -0.679612 -0.610696 1.37865 - -0.686051 -0.595482 1.39037 - -0.702647 -0.546542 1.42054 - -0.71309 -0.423775 1.43913 - -0.719034 -0.420727 1.45 - -0.947387 -0.543553 1.8684 - -1.0911 -0.557168 2.13145 - -1.14066 -0.498428 2.2219 - -1.14144 -0.425485 2.22302 - -1.14234 -0.415423 2.22462 - -1.14083 -0.363131 2.22164 - -1.14164 -0.332519 2.22301 - -1.14212 -0.129228 2.22302 - -1.14218 -0.0586891 2.22284 - -1.11399 0.217859 2.1701 - -1.11021 0.236814 2.16311 - -1.09016 0.398586 2.12575 - -1.08698 0.407246 2.11988 - -1.0783 0.472822 2.10372 - -1.07505 0.520987 2.09758 - -1.04101 0.701492 2.03453 - -1.03228 0.705458 2.01853 - -0.988785 0.71343 1.93891 - -0.974448 0.751123 1.91252 - -0.963265 0.860428 1.8916 - -0.962784 0.87007 1.89068 - -0.960969 0.878473 1.88732 - -0.9904 1.21782 1.93976 - -0.981501 1.24208 1.92338 - -0.976297 1.25918 1.91378 - -0.964991 1.35389 1.8927 - -0.188384 0.262398 0.47606 - -0.146134 0.275634 0.398689 - -0.138228 0.27215 0.384236 - -0.117596 0.276258 0.346461 - -0.11819 0.289507 0.347494 - -0.115213 0.308978 0.341965 - -0.105394 0.294631 0.324055 - -0.10293 0.293743 0.31955 - -0.0793198 0.286955 0.276372 - -0.0737674 0.289201 0.266201 - -0.06941 0.29041 0.258222 - -0.0301248 0.109048 0.187087 - -0.0270384 0.121208 0.181388 - -0.0260249 0.120824 0.179535 - -0.0239086 0.126043 0.17564 - -0.0146866 0.155092 0.158643 - 0.00529969 0.221921 0.121789 - 0.0164882 0.23459 0.101261 - 0.024219 0.226199 0.087149 - 0.0292219 0.225849 0.0779952 - 0.049604 0.221344 0.0407148 - 0.0549319 0.213143 0.0309989 - 0.0285949 -0.14534 0.0835921 - 0.0505201 -0.213867 0.0447268 - 0.0426262 -0.212649 0.0588157 - 0.0304662 -0.193643 0.0804487 - 0.0178011 -0.167691 0.102955 - 0.0151332 -0.164079 0.107704 - 0.0159026 -0.171383 0.10636 - 0.00835313 -0.185719 0.119898 - 0.00734729 -0.185608 0.121693 - 0.00655547 -0.186381 0.12311 - -0.0170878 -0.147815 0.165165 - -0.0243945 -0.121528 0.178103 - -0.0268014 -0.115324 0.182375 - -0.0275394 -0.109491 0.183669 - -0.0304548 -0.0911685 0.188799 - -0.0380008 -0.270974 0.203008 - -0.0494259 -0.36597 0.223795 - -0.0568705 -0.372558 0.237114 - -0.0720168 -0.377872 0.264178 - -0.074138 -0.373938 0.26795 - -0.0783354 -0.374094 0.275444 - -0.0798177 -0.372352 0.278084 - -0.0856962 -0.378568 0.288605 - -0.0901142 -0.3729 0.29647 - -0.100387 -0.381893 0.314848 - -0.135221 -0.381285 0.377038 - -0.150245 -0.38096 0.403862 - -0.187307 -0.378452 0.470023 - -0.192899 -0.375407 0.479994 - -0.202188 -0.370603 0.496559 - -0.210226 -0.378493 0.510944 - -0.211035 -0.376934 0.51238 - -0.219947 -0.375907 0.52829 - -0.231767 -0.366554 0.549354 - -0.244553 -0.367193 0.572186 - -0.313436 -0.400703 0.695308 - -0.656955 -0.881429 1.3106 - -0.690371 -0.894603 1.37032 - -0.696756 -0.894808 1.38172 - -0.710794 -0.896559 1.40679 - -0.685982 -0.806761 1.36212 - -0.685652 -0.782671 1.36144 - -0.688563 -0.770527 1.36658 - -0.691276 -0.704895 1.37116 - -0.690107 -0.681373 1.36897 - -0.700518 -0.604641 1.38725 - -0.717919 -0.520794 1.41797 - -0.728684 -0.480164 1.43703 - -1.10959 -0.556432 2.11741 - -1.16754 -0.417018 2.22031 - -1.16805 -0.323842 2.22085 - -1.15018 -0.0679719 2.1879 - -1.13808 0.0213071 2.16592 - -1.13584 0.0605322 2.16177 - -1.12406 0.118221 2.14049 - -1.11954 0.156539 2.13227 - -1.10552 0.270066 2.10677 - -1.10592 0.279857 2.10745 - -1.0965 0.364349 2.09028 - -1.08023 0.445489 2.06089 - -1.07083 0.509279 2.04385 - -0.999907 0.547665 1.91707 - -0.99061 0.952241 1.89881 - -1.00364 1.06309 1.92163 - -0.992758 1.15201 1.90183 - -0.986985 1.20275 1.89132 - -0.982633 1.25625 1.88333 - -0.975215 1.33119 1.86978 - -0.960525 1.39742 1.84328 - -0.177318 0.265619 0.449553 - -0.176542 0.268799 0.448153 - -0.15147 0.269601 0.403387 - -0.136435 0.275066 0.37652 - -0.132637 0.276983 0.369731 - -0.127781 0.272909 0.361077 - -0.123788 0.273535 0.353945 - -0.116398 0.302263 0.340634 - -0.115523 0.302084 0.339073 - -0.11294 0.304836 0.334449 - -0.11229 0.30551 0.333287 - -0.100426 0.294824 0.312147 - -0.0923164 0.280091 0.297729 - -0.0799301 0.282749 0.275603 - -0.0789605 0.289625 0.273844 - -0.0748617 0.288867 0.266529 - -0.0720111 0.292425 0.261425 - -0.0544973 0.290841 0.230162 - -0.0411441 0.243857 0.206513 - -0.0399057 0.229925 0.204359 - -0.0374294 0.222998 0.199966 - -0.0356276 0.20298 0.196831 - -0.0335736 0.195875 0.193193 - -0.0275759 0.173946 0.182574 - -0.024252 0.126391 0.176834 - -0.0231752 0.125922 0.174913 - -0.0215526 0.135414 0.171978 - -0.0192789 0.141481 0.167893 - 0.00644299 0.214275 0.121671 - 0.0141104 0.234705 0.107898 - 0.0182881 0.221778 0.100492 - 0.0225134 0.221723 0.0929479 - 0.0349761 0.230982 0.0706588 - 0.0352058 0.229496 0.0702547 - 0.0395896 0.23436 0.0624079 - 0.0412383 0.228427 0.0594885 - 0.0609868 0.228413 0.024229 - 0.0472045 0.18937 0.0489962 - 0.0250114 -0.135549 0.0925989 - 0.0484273 -0.221469 0.0521483 - 0.0410018 -0.207637 0.0650297 - 0.0170989 -0.161851 0.10649 - 0.018806 -0.185712 0.103612 - 0.0192587 -0.190988 0.102844 - 0.0185046 -0.194169 0.104171 - 0.0041248 -0.186222 0.129192 - 0.00451161 -0.190249 0.128534 --0.00213938 -0.18053 0.140082 --0.00611821 -0.188618 0.147047 - -0.0152642 -0.154396 0.162844 - -0.0257464 -0.114073 0.180944 - -0.0290989 -0.142291 0.186898 - -0.0297849 -0.183561 0.188259 - -0.032471 -0.210876 0.193049 - -0.0331855 -0.224927 0.19435 - -0.0366141 -0.234996 0.200364 - -0.0436528 -0.320618 0.212971 - -0.0455558 -0.339438 0.216362 - -0.0610898 -0.371537 0.243554 - -0.0667118 -0.379948 0.253383 - -0.0697484 -0.375853 0.258657 - -0.0796883 -0.380914 0.275995 - -0.0815725 -0.382074 0.279282 - -0.0821687 -0.379726 0.280311 - -0.0891533 -0.372891 0.292453 - -0.0964582 -0.379917 0.305208 - -0.151134 -0.377551 0.400455 - -0.155483 -0.373246 0.408016 - -0.173434 -0.366372 0.439262 - -0.205753 -0.372076 0.495593 - -0.235062 -0.372762 0.546658 - -0.72586 -0.882848 1.40379 - -0.718853 -0.581582 1.39037 - -0.73301 -0.543725 1.41488 - -0.734304 -0.502813 1.41697 - -0.740492 -0.479522 1.42766 - -0.754941 -0.468346 1.45279 - -0.753712 -0.439848 1.45053 - -1.19099 -0.428389 2.21232 - -1.1809 -0.331805 2.19435 - -1.17825 -0.29023 2.18956 - -1.15726 -0.175602 2.15254 - -1.15899 -0.12643 2.15535 - -1.15032 -0.0960813 2.14013 - -1.13758 0.0112587 2.1175 - -1.13119 0.0976037 2.10602 - -1.11609 0.124712 2.07961 - -1.11354 0.22892 2.07474 - -1.09942 0.282573 2.04993 - -1.03407 0.336666 1.93585 - -1.0235 0.359817 1.91735 - -1.01832 0.366814 1.90829 - -1.01466 0.409931 1.90175 - -1.00907 0.443254 1.89187 - -1.00836 0.496923 1.89042 - -1.00873 0.626083 1.89055 - -1.0084 0.663581 1.88981 - -1.01544 0.677957 1.90203 - -1.01306 0.724461 1.8977 - -1.01177 0.742952 1.89538 - -1.01061 0.801124 1.89312 - -1.01362 0.936492 1.89782 - -1.00916 0.995655 1.88982 - -0.980654 1.24271 1.83915 - -0.979337 1.30071 1.83663 - -0.972453 1.32764 1.82452 - -0.946031 1.41309 1.77815 - -0.925276 1.3933 1.74207 - -0.173721 0.268151 0.437213 - -0.166127 0.269221 0.423978 - -0.160899 0.272236 0.414859 - -0.15753 0.274293 0.40898 - -0.125267 0.26864 0.352793 - -0.12588 0.280979 0.353812 - -0.121079 0.276378 0.345466 - -0.120908 0.281273 0.345148 - -0.120298 0.282007 0.344082 - -0.112773 0.299488 0.330902 - -0.103717 0.294924 0.315142 - -0.100582 0.291161 0.309696 - -0.0920276 0.285274 0.294816 - -0.0887615 0.279204 0.28915 - -0.0856001 0.284672 0.28362 - -0.0804836 0.286955 0.274697 - -0.0511835 0.286571 0.223651 - -0.0494946 0.290907 0.220692 - -0.0486924 0.287028 0.21931 - -0.0445051 0.272572 0.212072 - -0.0429421 0.257711 0.209409 - -0.0402053 0.227898 0.204761 - -0.0381066 0.212983 0.201164 - -0.0325816 0.188814 0.191636 - -0.0318107 0.186736 0.190301 - -0.0302221 0.185537 0.187538 - -0.0297836 0.186475 0.18677 - -0.0227654 0.127997 0.174778 - -0.0224873 0.127874 0.174294 - -0.0175181 0.151172 0.165543 - -0.0183665 0.139228 0.167069 - 0.0163505 0.226036 0.106235 - 0.0226272 0.224182 0.0953075 - 0.0260103 0.227309 0.0894007 - 0.0267534 0.225329 0.0881141 - 0.0319707 0.22962 0.0790071 - 0.037055 0.21352 0.0702139 - 0.0464785 0.215736 0.0537871 - 0.047415 0.214268 0.0521613 - 0.0519163 0.202867 0.044365 - 0.053337 0.198987 0.0419053 - 0.0458291 0.177598 0.0550718 - 0.0523369 0.189974 0.0436839 - 0.029077 -0.141475 0.0882404 - 0.0264196 -0.13811 0.0927467 - 0.0388476 -0.20317 0.0718663 - 0.0205431 -0.187431 0.102936 - 0.0212526 -0.193581 0.101753 - 0.0126447 -0.190274 0.116381 - 0.00605348 -0.179872 0.12755 - 0.00225203 -0.182059 0.134024 --0.00327884 -0.187259 0.143451 - -0.0046958 -0.195556 0.145893 - -0.0102052 -0.171665 0.155169 - -0.0168412 -0.15447 0.166388 - -0.0189049 -0.14618 0.169865 - -0.0259548 -0.110227 0.181713 - -0.0283386 -0.0937755 0.185703 - -0.030589 -0.0853201 0.189497 - -0.0375042 -0.245976 0.201892 - -0.0401036 -0.275865 0.206431 - -0.0563386 -0.371747 0.234421 - -0.0608346 -0.376712 0.242087 - -0.0649201 -0.374546 0.249027 - -0.0683997 -0.375449 0.254949 - -0.0720907 -0.37819 0.261237 - -0.0779492 -0.38399 0.271224 - -0.0891415 -0.386802 0.29027 - -0.0918555 -0.380098 0.29486 - -0.100341 -0.381133 0.309296 - -0.118158 -0.374041 0.33957 - -0.141009 -0.378594 0.378453 - -0.143915 -0.381125 0.383406 - -0.173098 -0.376372 0.43302 - -0.17559 -0.372788 0.437243 - -0.182872 -0.378218 0.44965 - -0.187462 -0.376216 0.457448 - -0.238549 -0.369655 0.54431 - -0.250245 -0.370903 0.564208 - -0.253417 -0.369802 0.569597 - -0.265665 -0.373684 0.590443 - -0.266471 -0.342703 0.591692 - -0.276725 -0.338784 0.609117 - -0.732553 -0.892751 1.38656 - -0.740914 -0.89484 1.40079 - -0.718602 -0.78541 1.36241 - -0.751871 -0.492519 1.41783 - -0.768974 -0.434412 1.44669 - -1.05136 -0.554398 1.92744 - -1.19234 -0.42131 2.16668 - -1.18596 -0.378125 2.15567 - -1.17885 -0.305282 2.14328 - -1.14061 -0.00792449 2.07708 - -1.13196 0.0298703 2.06222 - -1.10232 0.111747 2.01148 - -1.03398 0.199601 1.89491 - -1.02866 0.320174 1.88537 - -1.03122 0.356244 1.88959 - -1.02723 0.407888 1.88261 - -1.02782 0.417035 1.88358 - -1.03434 0.428755 1.89462 - -1.03585 0.594538 1.89653 - -1.03253 0.649048 1.89066 - -1.03452 0.717618 1.89377 - -1.0191 0.966977 1.86657 - -0.986636 1.21699 1.81037 - -0.916531 1.3676 1.69054 - -0.192655 0.26325 0.463757 - -0.187444 0.265902 0.454884 - -0.175533 0.260397 0.434648 - -0.17438 0.262778 0.432678 - -0.175518 0.271948 0.434577 - -0.167071 0.264502 0.420239 - -0.150381 0.272546 0.391823 - -0.145334 0.265162 0.383269 - -0.14581 0.278479 0.384025 - -0.136372 0.273643 0.367992 - -0.127401 0.276052 0.352724 - -0.113464 0.297706 0.328937 - -0.0984307 0.280708 0.303435 - -0.0973083 0.289261 0.301493 - -0.0929287 0.278723 0.294085 - -0.0891177 0.284802 0.28758 - -0.0884882 0.28525 0.286507 - -0.0826956 0.297476 0.276607 - -0.0736337 0.293082 0.261212 - -0.072337 0.293706 0.259005 - -0.0603134 0.295352 0.238549 - -0.058168 0.284867 0.234941 - -0.0568347 0.293325 0.23264 - -0.0549509 0.294812 0.229431 - -0.0521462 0.280346 0.224718 - -0.0463005 0.274343 0.214799 - -0.041349 0.24182 0.206506 - -0.0408142 0.241858 0.205596 - -0.0388618 0.213952 0.202386 - -0.0340256 0.182933 0.194283 - -0.0301189 0.178555 0.187656 - -0.0286272 0.101857 0.185422 - -0.0248553 0.116797 0.178947 - -0.0177675 0.147458 0.166772 - 0.00182397 0.207617 0.133214 - 0.00993506 0.223914 0.119355 - 0.0110086 0.226282 0.117519 - 0.0236678 0.225585 0.0959918 - 0.0261429 0.225228 0.0917836 - 0.0256262 0.214356 0.0927054 - 0.0382961 0.227172 0.0711062 - 0.0385227 0.217285 0.0707599 - 0.0409684 0.210233 0.0666281 - 0.0488181 0.205866 0.0532949 - 0.0517367 0.203662 0.0483397 - 0.0491773 0.190861 0.0527433 - 0.0420579 0.164499 0.0649556 - 0.0326682 -0.138067 0.0854936 - 0.0370257 -0.149418 0.0783411 - 0.0296931 -0.137962 0.0904066 - 0.0342691 -0.156914 0.0829225 - 0.0467498 -0.217049 0.0625429 - 0.0266918 -0.176977 0.095514 - 0.0213919 -0.20085 0.104359 - 0.0217152 -0.206208 0.103846 - 0.0127582 -0.183615 0.118551 - 0.0123434 -0.184021 0.119238 - 0.0102229 -0.183806 0.122739 - 0.00771891 -0.18606 0.126883 - 0.00133214 -0.181483 0.137413 --0.00712176 -0.189169 0.151404 - -0.0169843 -0.150743 0.167544 - -0.018285 -0.143111 0.169663 - -0.0247301 -0.115056 0.180198 - -0.0306175 -0.0914603 0.18983 - -0.0310339 -0.0955645 0.190534 - -0.0296955 -0.176629 0.188636 - -0.0432648 -0.311629 0.211567 - -0.0442011 -0.320547 0.213148 - -0.0574753 -0.373551 0.235275 - -0.0609163 -0.373738 0.240959 - -0.0793623 -0.382646 0.271457 - -0.0811329 -0.374686 0.27435 - -0.0903688 -0.382483 0.289633 - -0.0971605 -0.383831 0.300855 - -0.111453 -0.377356 0.324435 - -0.136924 -0.380356 0.366511 - -0.15952 -0.379557 0.403825 - -0.17383 -0.37791 0.427453 - -0.210257 -0.371343 0.487585 - -0.215013 -0.368303 0.495428 - -0.220468 -0.376209 0.504469 - -0.223372 -0.372213 0.509248 - -0.230388 -0.372853 0.520838 - -0.236352 -0.37106 0.530682 - -0.247141 -0.367724 0.548486 - -0.2587 -0.371106 0.567588 - -0.262683 -0.374412 0.57418 - -0.275835 -0.365547 0.595865 - -0.336759 -0.399459 0.696612 - -0.698207 -0.86302 1.29534 - -0.728404 -0.885436 1.34529 - -0.750469 -0.887815 1.38174 - -0.735991 -0.780515 1.35742 - -0.742447 -0.725278 1.36787 - -0.745249 -0.697694 1.37239 - -0.737887 -0.668195 1.36011 - -0.781512 -0.474022 1.43141 - -0.973104 -0.500824 1.74793 - -1.20107 -0.476768 2.12432 - -1.18007 -0.358296 2.08919 - -1.18038 -0.348494 2.08965 - -1.16219 -0.227023 2.05915 - -1.16013 -0.217033 2.05571 - -1.08709 -0.113781 1.93468 - -1.05366 0.0271486 1.87893 - -1.05361 0.0357214 1.87881 - -1.05798 0.0617164 1.88593 - -1.06041 0.148394 1.88961 - -1.06438 0.414223 1.89514 - -1.06157 0.540914 1.89001 - -1.06341 0.598005 1.89282 - -1.06137 0.682524 1.88913 - -1.05974 0.700759 1.88637 - -1.04116 0.864502 1.85506 - -1.00748 1.06105 1.79867 - -1.00419 1.06822 1.7932 - -0.977177 1.30711 1.74767 - -0.971784 1.36021 1.73856 - -0.198561 0.263127 0.465819 - -0.185157 0.268234 0.443664 - -0.177779 0.268646 0.431477 - -0.131292 0.272057 0.35469 - -0.126051 0.277437 0.346014 - -0.124225 0.306239 0.342887 - -0.114894 0.301043 0.327498 - -0.087879 0.285187 0.282943 - -0.0811301 0.283128 0.271805 - -0.0722244 0.288844 0.257076 - -0.0689546 0.290283 0.25167 - -0.0629392 0.29154 0.241731 - -0.0591352 0.294758 0.235436 - -0.0428383 0.242676 0.208723 - -0.0361848 0.193 0.197926 - -0.0333347 0.178912 0.193274 - -0.0313861 0.161732 0.190122 - -0.0293563 0.135364 0.186871 - -0.0300354 0.0912558 0.188163 - -0.0273235 0.103622 0.183637 - -0.0270051 0.104533 0.183107 - -0.0120162 0.162419 0.15813 - 0.00489897 0.209412 0.130013 - 0.0102206 0.224706 0.121165 - 0.0206998 0.227796 0.103847 - 0.0222418 0.226336 0.101306 - 0.0454628 0.209127 0.0630228 - 0.0462483 0.209232 0.0617251 - 0.0478382 0.184834 0.0591935 - 0.0484011 0.168926 0.0583255 - 0.042829 -0.155416 0.0717625 - 0.031896 -0.151213 0.0893865 - 0.050349 -0.206656 0.0598239 - 0.0215869 -0.162215 0.106061 - 0.0175855 -0.155227 0.112491 - 0.0241503 -0.208361 0.102101 - 0.0202913 -0.205439 0.108316 - 0.0113125 -0.178156 0.122699 - 0.00277249 -0.184275 0.136501 - 0.00068567 -0.19642 0.139914 --0.00021769 -0.19701 0.141374 --0.00742974 -0.185562 0.152967 - -0.0194181 -0.140743 0.172139 - -0.0217715 -0.128389 0.17589 - -0.0254714 -0.111381 0.181795 - -0.0295058 -0.0822005 0.188193 - -0.0319697 -0.0827197 0.19217 - -0.0323055 -0.194913 0.193138 - -0.0331632 -0.197956 0.194534 - -0.0359144 -0.218997 0.199052 - -0.0418735 -0.284719 0.208917 - -0.0730325 -0.37819 0.259545 - -0.0776973 -0.379462 0.267076 - -0.0828875 -0.384418 0.275469 - -0.0832845 -0.380129 0.276094 - -0.106417 -0.381671 0.313423 - -0.123697 -0.377171 0.341287 - -0.125213 -0.374779 0.343723 - -0.131358 -0.382563 0.353667 - -0.135568 -0.381998 0.360457 - -0.138678 -0.381245 0.365472 - -0.155998 -0.377704 0.393405 - -0.156867 -0.376698 0.394803 - -0.15722 -0.366877 0.395334 - -0.194141 -0.375684 0.454938 - -0.217263 -0.38022 0.492261 - -0.218492 -0.379444 0.494242 - -0.223049 -0.375484 0.501578 - -0.241182 -0.370738 0.530817 - -0.242801 -0.370397 0.533428 - -0.277939 -0.376124 0.590144 - -0.289079 -0.340165 0.60798 - -0.757183 -0.881331 1.3653 - -0.783426 -0.844644 1.4075 - -0.757393 -0.720704 1.36503 - -0.756253 -0.711943 1.36315 - -0.757372 -0.667956 1.36479 - -0.816163 -0.538629 1.45916 - -0.813576 -0.507788 1.45487 - -0.813251 -0.500371 1.45431 - -0.814044 -0.486521 1.45554 - -1.09663 -0.299623 1.91077 - -1.07869 -0.137028 1.88121 - -1.08558 0.290297 1.8907 - -1.08229 0.324856 1.88526 - -1.0855 0.442983 1.89 - -1.08808 0.462374 1.89408 - -1.08752 0.620923 1.89258 - -1.08617 0.639222 1.89032 - -1.09415 0.751951 1.90278 - -1.08912 0.849336 1.89429 - -1.01873 0.940707 1.78037 - -1.01751 0.949736 1.77837 - -1.01674 0.959221 1.77709 - -1.01251 1.01719 1.77004 - -0.97671 1.28489 1.71127 - -0.975042 1.29442 1.70854 - -0.144493 0.27578 0.37236 - -0.143224 0.277564 0.370306 - -0.128483 0.267738 0.34656 - -0.127868 0.268501 0.345564 - -0.121523 0.270125 0.335321 - -0.104017 0.286386 0.307014 - -0.102066 0.281462 0.303885 - -0.10142 0.282005 0.30284 - -0.0935409 0.280613 0.290133 - -0.087527 0.283726 0.280418 - -0.0670639 0.28912 0.247382 - -0.060806 0.288236 0.237288 - -0.0553585 0.287707 0.228501 - -0.0548938 0.290841 0.227739 - -0.041263 0.228789 0.205982 - -0.0378227 0.201971 0.200533 - -0.0296564 0.150526 0.187553 - -0.0306463 0.0934777 0.189366 - -0.0304868 0.0853963 0.18914 - -0.0282704 0.0989545 0.185512 - -0.0228991 0.126612 0.176741 - -0.0116725 0.168804 0.158467 - -0.0102216 0.170107 0.156121 - 0.003899 0.210768 0.133184 - 0.0142301 0.224533 0.116463 - 0.0147464 0.224115 0.115631 - 0.0215243 0.231461 0.104668 - 0.0219691 0.225517 0.103973 - 0.0296432 0.224686 0.0915942 - 0.0329657 0.219912 0.0862516 - 0.0358093 0.220142 0.0816627 - 0.0435612 0.21156 0.0691879 - 0.0477312 0.206949 0.0624774 - 0.07557 0.228954 0.0174773 - 0.065674 0.201399 0.0335486 - 0.0309505 -0.135011 0.0933341 - 0.0517306 -0.20965 0.0608635 - 0.0208519 -0.159806 0.109342 - 0.017128 -0.153568 0.115188 - 0.0241516 -0.19591 0.104276 - 0.0126387 -0.181233 0.122366 - 0.00920891 -0.182052 0.127774 - 0.0010605 -0.186108 0.140631 --0.00093644 -0.196915 0.143819 - -0.0192559 -0.137811 0.172469 - -0.0229134 -0.12184 0.178174 - -0.0294678 -0.164654 0.188663 - -0.0302121 -0.178761 0.189889 - -0.0351958 -0.206 0.197845 - -0.0379464 -0.238939 0.202303 - -0.0523121 -0.351495 0.225363 - -0.0575453 -0.369577 0.233678 - -0.0584094 -0.369389 0.235039 - -0.0762027 -0.378194 0.263114 - -0.0843662 -0.369615 0.275948 - -0.100865 -0.37843 0.301983 - -0.105437 -0.381893 0.309201 - -0.106505 -0.382258 0.310886 - -0.110994 -0.384554 0.317968 - -0.122354 -0.374958 0.335836 - -0.13972 -0.379467 0.363221 - -0.144129 -0.38305 0.370184 - -0.150524 -0.381058 0.380254 - -0.156937 -0.378702 0.390353 - -0.157823 -0.377704 0.391746 - -0.159065 -0.366877 0.393662 - -0.180156 -0.372759 0.426923 - -0.193068 -0.380897 0.447303 - -0.208969 -0.373344 0.472334 - -0.224174 -0.37186 0.496292 - -0.242425 -0.370369 0.52505 - -0.830603 -0.445912 1.4523 - -0.826966 -0.415857 1.44645 - -1.13472 -0.539027 1.93192 - -1.16397 -0.543545 1.97805 - -1.16525 -0.534341 1.98002 - -1.11853 -0.474808 1.90618 - -1.11495 -0.463958 1.9005 - -1.10857 -0.173814 1.88935 - -1.10795 -0.138546 1.88825 - -1.11125 0.586299 1.89073 - -1.11145 0.653482 1.89081 - -1.11904 0.726974 1.90249 - -1.02476 0.900876 1.75327 - -1.00955 0.997445 1.72893 - -1.00767 1.06867 1.72569 - -1.00266 1.08443 1.71774 - -0.989434 1.1891 1.69651 - -0.199462 0.275234 0.454931 - -0.194336 0.288402 0.446803 - -0.168538 0.277713 0.406186 - -0.143209 0.27602 0.366273 - -0.141268 0.278617 0.363205 - -0.125171 0.291835 0.337786 - -0.126511 0.305365 0.339849 - -0.120672 0.30101 0.330661 - -0.112661 0.297334 0.318051 - -0.103825 0.281826 0.304183 - -0.0923066 0.282014 0.286029 - -0.0898902 0.288964 0.282195 - -0.0854927 0.281178 0.275294 - -0.0820031 0.286376 0.269775 - -0.0814873 0.287707 0.268957 - -0.0744738 0.284036 0.257918 - -0.0732381 0.290789 0.255945 - -0.0693732 0.288328 0.249863 - -0.0665151 0.294529 0.245336 - -0.0644453 0.288132 0.242097 - -0.0549059 0.289849 0.227057 - -0.0535505 0.290146 0.22492 - -0.05146 0.289556 0.221627 - -0.0505725 0.285698 0.220243 - -0.040265 0.21484 0.204263 - -0.0390839 0.204908 0.202439 - -0.0317555 0.167834 0.191028 - -0.0302424 0.114555 0.188842 - -0.0298952 0.0863436 0.1884 - -0.0237078 0.119941 0.178523 - -0.0134776 0.154518 0.162272 --0.00739229 0.178302 0.152592 - 0.0252979 0.233603 0.100867 - 0.0249621 0.22723 0.10142 - 0.0260959 0.221668 0.0996534 - 0.0306927 0.214684 0.092435 - 0.0346891 0.225365 0.0860969 - 0.0365896 0.213871 0.0831445 - 0.0382897 0.210643 0.0804772 - 0.0443179 0.162829 0.0711553 - 0.0356386 -0.144264 0.0884955 - 0.0342607 -0.146506 0.0906263 - 0.0310816 -0.142284 0.095508 - 0.0282989 -0.138738 0.0997816 - 0.0500348 -0.201739 0.0665302 - 0.051982 -0.217856 0.0635899 - 0.016615 -0.151869 0.117828 - 0.0158241 -0.158607 0.119071 - 0.0241077 -0.20628 0.106486 - 0.0233653 -0.205864 0.107628 - 0.0054254 -0.179286 0.135166 - 0.00276561 -0.185511 0.139286 - 0.00160533 -0.197957 0.141119 --0.00161722 -0.191476 0.146059 --0.00878558 -0.179697 0.157058 - -0.0252265 -0.105467 0.182112 - -0.0290643 -0.0792293 0.187927 - -0.0298392 -0.0763913 0.189111 - -0.0389422 -0.241881 0.203741 - -0.0455624 -0.300341 0.214154 - -0.0534547 -0.356326 0.226517 - -0.0593749 -0.368201 0.23568 - -0.0710511 -0.378117 0.253703 - -0.0728474 -0.377518 0.256468 - -0.0839652 -0.39163 0.273646 - -0.0848317 -0.375842 0.274923 - -0.0943224 -0.381541 0.289564 - -0.10817 -0.380728 0.310892 - -0.116955 -0.383221 0.324434 - -0.117866 -0.382558 0.325835 - -0.146839 -0.375089 0.370439 - -0.148257 -0.375934 0.372625 - -0.151644 -0.379318 0.377855 - -0.196095 -0.372305 0.446303 - -0.208689 -0.380491 0.465733 - -0.210847 -0.378446 0.469051 - -0.231564 -0.370781 0.500937 - -0.236503 -0.370254 0.508542 - -0.247729 -0.367658 0.525826 - -0.275369 -0.373784 0.568425 - -0.610972 -0.700189 1.0866 - -0.759491 -0.872461 1.31602 - -0.762023 -0.867181 1.3199 - -0.787686 -0.880701 1.35948 - -0.793836 -0.845622 1.36882 - -0.793269 -0.820182 1.36786 - -0.788649 -0.774922 1.36057 - -0.794549 -0.710387 1.36942 - -0.793403 -0.678899 1.36754 - -0.798208 -0.660587 1.37488 - -0.79978 -0.654458 1.37728 - -0.809415 -0.625236 1.39201 - -0.841617 -0.466219 1.44103 - -0.843881 -0.439143 1.44442 - -1.12752 -0.416006 1.88127 - -1.12852 -0.407244 1.88277 - -1.12814 -0.352609 1.88199 - -1.13075 -0.103995 1.8851 - -1.07867 -0.0739077 1.80476 - -1.07819 0.0515465 1.80356 - -1.13546 0.0808511 1.89167 - -1.13567 0.276428 1.89128 - -1.13538 0.375778 1.89046 - -1.13358 0.393386 1.88763 - -1.14045 0.460524 1.89796 - -1.134 0.476368 1.88797 - -1.13765 0.524763 1.89342 - -1.13515 0.542397 1.88949 - -1.14111 0.641375 1.89832 - -1.14116 0.660915 1.89832 - -1.14311 0.691606 1.90121 - -1.13961 0.749084 1.89561 - -1.13829 0.77841 1.89347 - -1.1385 0.860686 1.89349 - -1.09834 0.869798 1.83159 - -1.02689 0.888583 1.72147 - -1.02022 0.902184 1.71114 - -1.021 0.912761 1.7123 - -1.00747 1.03079 1.69102 - -1.00549 1.03907 1.68795 - -1.00017 1.09633 1.67953 - -0.968063 1.36143 1.6291 - -0.920141 1.41105 1.5551 - -0.209922 0.309355 0.465099 - -0.187078 0.29592 0.429959 - -0.173154 0.293361 0.40852 - -0.141692 0.294503 0.360051 - -0.12735 0.291972 0.337967 - -0.126928 0.293572 0.337311 - -0.121351 0.302584 0.328686 - -0.103801 0.281462 0.301729 - -0.0959819 0.285274 0.289671 - -0.0903497 0.28802 0.280985 - -0.0884163 0.281834 0.278029 - -0.0869025 0.28172 0.275698 - -0.0855633 0.28253 0.273632 - -0.0762248 0.288562 0.259224 - -0.0468879 0.264198 0.214122 - -0.0324991 0.153902 0.192362 - -0.030466 0.148715 0.189249 - -0.0295765 0.128549 0.187953 - -0.026837 0.0987573 0.183843 - -0.0246784 0.11431 0.18046 - -0.0164745 0.144858 0.16771 - -0.0114812 0.164175 0.159948 - 0.00109793 0.197859 0.140447 - 0.0185415 0.228275 0.113464 - 0.019084 0.227839 0.11263 - 0.0270236 0.225341 0.100409 - 0.0312745 0.221189 0.0938758 - 0.0355297 0.223638 0.0873119 - 0.0361299 0.212492 0.0864283 - 0.0513353 0.221443 0.0629725 - 0.042253 0.169958 0.0771523 - 0.0519114 0.167471 0.0622834 - 0.0355 -0.14129 0.0910923 - 0.0316679 -0.143337 0.0968724 - 0.0313222 -0.14386 0.097395 - 0.0480737 -0.213907 0.0724138 - 0.0477705 -0.219154 0.0728894 - 0.0159153 -0.157284 0.120653 - 0.0187376 -0.169369 0.116445 - 0.0220078 -0.201442 0.111635 - 0.0178121 -0.19069 0.117916 - 0.0171064 -0.190205 0.118978 - 0.0110445 -0.177696 0.128064 - 0.0113556 -0.18953 0.127638 - 0.0069327 -0.182059 0.134274 - 0.00586175 -0.179608 0.135878 - 0.0047883 -0.179312 0.137494 - 0.00561621 -0.19269 0.136296 - -0.0151532 -0.150899 0.167432 - -0.0182557 -0.140875 0.172069 - -0.026966 -0.0929162 0.185017 - -0.0313813 -0.0727267 0.191595 - -0.0312743 -0.0877626 0.191489 - -0.0309283 -0.101756 0.191018 - -0.0302386 -0.170809 0.190229 - -0.0305493 -0.174839 0.190711 - -0.0347455 -0.195 0.197105 - -0.0352161 -0.194997 0.197814 - -0.0736153 -0.381451 0.256334 - -0.0909622 -0.374262 0.282439 - -0.102791 -0.38563 0.3003 - -0.112039 -0.379865 0.314209 - -0.130376 -0.375845 0.341819 - -0.140309 -0.379376 0.356794 - -0.151797 -0.378508 0.374097 - -0.163732 -0.377386 0.392072 - -0.165811 -0.379752 0.395212 - -0.181666 -0.376278 0.419084 - -0.187075 -0.369177 0.427207 - -0.197576 -0.367111 0.443018 - -0.214662 -0.377787 0.468795 - -0.282847 -0.373105 0.571493 - -0.289868 -0.37021 0.582059 - -0.297757 -0.371513 0.593948 - -0.299547 -0.367343 0.596629 - -0.301668 -0.350556 0.599764 - -0.297963 -0.339364 0.594142 - -0.594725 -0.663793 1.04236 - -0.811723 -0.886377 1.37006 - -0.829384 -0.863187 1.39658 - -0.835597 -0.844278 1.40587 - -0.808382 -0.76712 1.36459 - -0.832444 -0.718667 1.40066 - -0.838092 -0.63096 1.40885 - -0.893642 -0.511206 1.4921 - -1.0408 -0.537738 1.71387 - -1.17458 -0.541312 1.91542 - -1.15461 -0.401389 1.88484 - -1.15475 -0.373933 1.88494 - -1.1556 -0.193669 1.88557 - -1.15939 -0.14963 1.89113 - -1.15601 -0.122516 1.88593 - -1.15134 -0.113166 1.87887 - -1.14845 -0.0776455 1.87439 - -1.15743 0.125586 1.88717 - -1.16388 0.206968 1.89659 - -1.15734 0.250574 1.88659 - -1.16053 0.305521 1.89119 - -1.16183 0.342302 1.89303 - -1.1631 0.509758 1.89433 - -1.16364 0.538436 1.89504 - -1.15294 0.879511 1.87768 - -1.01992 0.897887 1.67724 - -1.00908 0.996464 1.66055 - -0.999263 1.12108 1.64531 - -0.996561 1.12866 1.64121 - -0.982525 1.2213 1.61973 - -0.973787 1.31321 1.60624 - -0.934189 1.4117 1.54623 - -0.830243 1.3626 1.38982 - -0.827644 1.38202 1.38584 - -0.190739 0.298836 0.43031 - -0.174016 0.298939 0.405118 - -0.144844 0.293622 0.361193 - -0.137062 0.294406 0.349467 - -0.125186 0.293115 0.331581 - -0.124479 0.29382 0.330514 - -0.11152 0.285621 0.311022 - -0.0958842 0.281545 0.287482 - -0.0890421 0.286043 0.277159 - -0.0873121 0.284977 0.274557 - -0.0866246 0.285384 0.27352 - -0.0857127 0.293257 0.272117 - -0.0776022 0.290169 0.259911 - -0.0694998 0.284418 0.247726 - -0.0654993 0.294032 0.241665 - -0.0639826 0.29351 0.239382 - -0.0587725 0.291977 0.231539 - -0.0466913 0.261207 0.213451 - -0.0314035 0.141831 0.190853 - -0.0305516 0.0815813 0.189787 - -0.0273667 0.0909189 0.184956 - -0.0245648 0.108315 0.180672 - -0.0190669 0.136919 0.172287 --0.00308357 0.187141 0.148027 - 0.0002676 0.194641 0.142952 - 0.0164836 0.223104 0.118421 - 0.0173426 0.221359 0.117133 - 0.0227427 0.230143 0.108967 - 0.0309015 0.227354 0.0966865 - 0.0320225 0.217163 0.0950346 - 0.0402515 0.208136 0.0826709 - 0.0512306 0.221196 0.0660847 - 0.051653 0.218199 0.0654593 - 0.0400314 0.166395 0.0831534 - 0.0524327 0.177446 0.064432 - 0.0401707 0.142206 0.0830312 - 0.036185 -0.146301 0.0924268 - 0.0347385 -0.149784 0.0945703 - 0.0494632 -0.211618 0.0730972 - 0.0531576 -0.231414 0.0677249 - 0.0155014 -0.157599 0.122939 - 0.023105 -0.183298 0.111829 - 0.0246593 -0.20679 0.109623 - 0.0213599 -0.19742 0.11445 - 0.0113922 -0.183682 0.129086 - 0.0109423 -0.184036 0.12975 - 0.00932781 -0.188528 0.132145 - 0.00886597 -0.188866 0.132826 - 0.00710273 -0.185815 0.135413 - 0.00071449 -0.177262 0.144794 --0.00646041 -0.180235 0.155375 - -0.0123909 -0.161271 0.164045 - -0.0162269 -0.144374 0.169636 - -0.0182253 -0.14309 0.172576 - -0.0299899 -0.133756 0.189875 - -0.0304378 -0.152829 0.190602 - -0.0308608 -0.166876 0.191276 - -0.0312697 -0.166902 0.191878 - -0.0372271 -0.224942 0.200862 - -0.0763546 -0.376566 0.259046 - -0.0873972 -0.386525 0.27535 - -0.0974466 -0.385857 0.290153 - -0.108528 -0.378483 0.306452 - -0.115792 -0.377994 0.317152 - -0.120116 -0.378179 0.323524 - -0.121255 -0.378433 0.325202 - -0.133496 -0.383107 0.343253 - -0.135616 -0.386861 0.346391 - -0.136702 -0.373765 0.347944 - -0.152446 -0.379431 0.371158 - -0.155785 -0.378377 0.376073 - -0.172537 -0.371733 0.400729 - -0.181497 -0.374161 0.413939 - -0.198178 -0.373304 0.438511 - -0.20048 -0.375166 0.441909 - -0.248462 -0.377778 0.512609 - -0.249107 -0.372341 0.513539 - -0.266569 -0.378705 0.539289 - -0.301117 -0.374206 0.590169 - -0.844828 -0.884061 1.39301 - -0.846038 -0.767942 1.39438 - -0.853803 -0.734849 1.4057 - -0.856395 -0.605488 1.40906 - -0.871193 -0.563656 1.43071 - -0.917627 -0.555979 1.49909 - -0.92588 -0.553385 1.51124 - -1.06043 -0.540004 1.70943 - -1.10487 -0.536337 1.77488 - -1.19711 -0.534057 1.91077 - -1.17876 -0.257732 1.88275 - -1.18215 -0.150363 1.88735 - -0.299241 -0.00582301 0.586094 - -0.298705 -0.00170927 0.58529 - -1.18713 0.135959 1.89367 - -1.18388 0.207472 1.88863 - -1.1912 0.345949 1.89892 - -1.18915 0.373038 1.89581 - -1.18501 0.427301 1.88952 - -1.19065 0.562276 1.89734 - -1.1938 0.612414 1.9018 - -1.19015 0.821535 1.89568 - -1.11108 0.873904 1.77901 - -1.02599 0.880289 1.65362 - -1.00862 0.971169 1.62772 - -0.998641 1.07221 1.61265 - -0.995916 1.1005 1.60853 - -0.975581 1.27293 1.57796 - -0.822216 1.38792 1.35161 - -0.207921 0.310574 0.45043 - -0.205219 0.311094 0.446447 - -0.139375 0.312099 0.349439 - -0.130814 0.301266 0.336864 - -0.0859481 0.278725 0.270846 - -0.0699107 0.291532 0.247174 - -0.0619282 0.293172 0.235407 - -0.0588883 0.291977 0.230933 - -0.053353 0.285178 0.222802 - -0.0411849 0.20972 0.205144 - -0.0367065 0.176975 0.198663 - -0.033817 0.152985 0.194492 - -0.0323812 0.148927 0.192391 - -0.0308391 0.0816826 0.190358 - -0.0233881 0.116192 0.179258 - -0.0167002 0.14642 0.169298 - 0.0019623 0.202527 0.141603 - 0.0230454 0.224236 0.110465 - 0.0491708 0.215984 0.0720053 - 0.0533616 0.210615 0.0658502 - 0.0543928 0.209232 0.064336 - 0.0485602 0.192029 0.0729901 - 0.0457843 0.180678 0.0771201 - 0.0435536 0.159288 0.0804828 - 0.0539975 -0.156353 0.069084 - 0.0373548 -0.138512 0.093001 - 0.0472651 -0.191603 0.078908 - 0.0288178 -0.173819 0.105425 - 0.0235009 -0.160762 0.11304 - 0.0160326 -0.149987 0.123763 - 0.015083 -0.148642 0.125127 - 0.0259187 -0.196515 0.109682 - 0.0111699 -0.179112 0.130872 --0.00348344 -0.185328 0.152007 --0.00612142 -0.175202 0.155772 --0.00845316 -0.172167 0.159121 - -0.0119422 -0.163386 0.164118 - -0.054586 -0.342089 0.226188 - -0.066566 -0.381718 0.243588 - -0.0682009 -0.37824 0.245932 - -0.0707362 -0.374464 0.249571 - -0.110928 -0.380728 0.307504 - -0.117258 -0.385169 0.316639 - -0.118673 -0.37671 0.318649 - -0.134282 -0.376895 0.34114 - -0.139063 -0.381761 0.348046 - -0.155505 -0.380253 0.371731 - -0.159563 -0.377335 0.377567 - -0.175971 -0.375901 0.401204 - -0.178793 -0.376198 0.405271 - -0.198221 -0.375046 0.433259 - -0.23368 -0.371942 0.484339 - -0.252248 -0.369279 0.511084 - -0.279753 -0.374296 0.550732 - -0.302707 -0.371113 0.583793 - -0.310585 -0.339204 0.595032 - -0.316022 -0.339484 0.602868 - -0.859644 -0.878266 1.38803 - -0.866159 -0.859215 1.39735 - -0.864999 -0.840939 1.39562 - -0.872784 -0.814863 1.40674 - -0.87664 -0.680502 1.41183 - -0.870042 -0.667418 1.40228 - -0.869285 -0.636135 1.40108 - -0.850352 -0.59952 1.37367 - -0.907684 -0.55672 1.45612 - -0.924944 -0.552315 1.48098 - -0.996892 -0.547586 1.58463 - -1.19726 -0.469564 1.87306 - -1.20493 -0.178136 1.88309 - -1.20873 -0.11546 1.88834 - -0.299013 -0.00776083 0.577197 - -0.285379 0.00223953 0.557518 - -1.20807 0.172494 1.88638 - -1.21401 0.191551 1.89487 - -1.21187 0.264119 1.89152 - -1.20927 0.290976 1.88769 - -1.2116 0.411968 1.89062 - -1.21459 0.469601 1.89473 - -1.21502 0.488782 1.89528 - -1.21759 0.576602 1.89868 - -1.21477 0.653732 1.89434 - -1.21301 0.692589 1.89167 - -1.20901 0.710256 1.88585 - -1.16772 0.793693 1.82606 - -1.17176 0.826894 1.83176 - -1.18703 0.869112 1.85362 - -1.18165 0.88589 1.8458 - -1.17006 0.887316 1.82911 - -1.10784 0.878297 1.73948 - -1.05908 0.867152 1.66926 - -1.01708 0.955354 1.60845 - -1.00823 1.03619 1.59541 - -0.990282 1.14089 1.56918 - -0.989284 1.16116 1.56767 - -0.985511 1.20009 1.5621 - -0.983081 1.24153 1.55845 - -0.971075 1.35285 1.54076 - -0.857959 1.405 1.3776 - -0.186735 0.309279 0.41431 - -0.580766 1.29169 0.978602 - -0.545698 1.31327 0.927999 - -0.533205 1.33033 0.909938 - -0.129131 0.298365 0.33135 - -0.128389 0.299082 0.330278 - -0.115133 0.298572 0.311179 - -0.110886 0.303064 0.305044 - -0.105474 0.302741 0.297247 - -0.0963596 0.288573 0.284165 - -0.0889472 0.283617 0.273502 - -0.0871805 0.28253 0.270961 - -0.0849811 0.292122 0.267758 - -0.0815318 0.285554 0.262811 - -0.0792805 0.2908 0.259549 - -0.0726944 0.287487 0.250071 - -0.0650924 0.286165 0.239122 - -0.0634677 0.284645 0.236786 - -0.0573112 0.289361 0.227899 - -0.0508998 0.279606 0.218696 - -0.0377664 0.174922 0.20014 - -0.0335317 0.155985 0.194105 - -0.0303604 0.100717 0.189729 - -0.0303709 0.0947015 0.189765 - -0.028704 0.0813367 0.18741 - -0.0282237 0.0822335 0.186715 - -0.0269457 0.0899905 0.184847 - -0.0256183 0.0997448 0.1829 - -0.016662 0.142516 0.169845 - -0.0116823 0.158924 0.162613 --0.00874072 0.169969 0.158336 - 0.0103628 0.21163 0.130664 - 0.01857 0.217685 0.118818 - 0.0334445 0.227354 0.0973518 - 0.0353973 0.215223 0.0945807 - 0.0358949 0.212413 0.0938736 - 0.0362547 0.1992 0.0934015 - 0.0509881 0.195849 0.0721847 - 0.0473409 0.158302 0.0775715 - 0.0418554 0.14135 0.0855347 - 0.0405752 -0.139615 0.0907644 - 0.0325866 -0.142301 0.102027 - 0.0398152 -0.160527 0.0919072 - 0.03941 -0.161082 0.09248 - 0.0391095 -0.167805 0.0929265 - 0.044827 -0.192826 0.0849585 - 0.018709 -0.16792 0.121666 - 0.0154314 -0.189708 0.126358 - 0.00730336 -0.183657 0.137788 - 0.00537512 -0.187048 0.140516 - 0.00031604 -0.182646 0.147627 --0.00939568 -0.170803 0.161268 --0.00996576 -0.170015 0.162068 - -0.0124377 -0.161772 0.165522 - -0.0145325 -0.155404 0.168451 - -0.0219453 -0.122224 0.178779 - -0.0308133 -0.0938286 0.191174 - -0.0327548 -0.169987 0.194172 - -0.0349822 -0.190991 0.197382 - -0.0384458 -0.220859 0.202365 - -0.0598359 -0.366216 0.233 - -0.0679502 -0.383441 0.24449 - -0.0697948 -0.381922 0.247084 - -0.0908899 -0.381378 0.276799 - -0.0984021 -0.376734 0.287366 - -0.119923 -0.377641 0.317687 - -0.122562 -0.374732 0.321394 - -0.126523 -0.37729 0.326982 - -0.137263 -0.383237 0.342133 - -0.138232 -0.382453 0.343495 - -0.14696 -0.379467 0.355781 - -0.157214 -0.376708 0.370215 - -0.186187 -0.375799 0.411028 - -0.196723 -0.369936 0.425851 - -0.214421 -0.374967 0.450799 - -0.224243 -0.374928 0.464635 - -0.230165 -0.376527 0.472985 - -0.231441 -0.369115 0.474755 - -0.249622 -0.369336 0.500369 - -0.258339 -0.37106 0.512654 - -0.872964 -0.879302 1.38025 - -0.87986 -0.752138 1.38953 - -0.854308 -0.579058 1.35293 - -1.05767 -0.539601 1.63928 - -1.17981 -0.529139 1.8113 - -1.18825 -0.431604 1.82286 - -1.18804 -0.368124 1.82235 - -1.23287 -0.179692 1.88485 - -0.288333 -0.00542739 0.553645 - -0.281416 0.00217336 0.543874 - -1.23859 0.0469083 1.89213 - -1.23935 0.165335 1.89279 - -1.23756 0.201636 1.89013 - -1.24028 0.312799 1.89359 - -1.23889 0.415297 1.89127 - -1.24018 0.434658 1.89302 - -1.23623 0.471151 1.88733 - -1.24105 0.501786 1.89401 - -1.21959 0.530789 1.86369 - -1.21545 0.538436 1.85783 - -1.20253 0.589385 1.83945 - -1.00287 1.05563 1.55657 - -0.996133 1.09956 1.54693 - -0.992969 1.11679 1.54241 - -0.989585 1.16587 1.53748 - -0.963814 1.3824 1.50042 - -0.953294 1.40325 1.48553 - -0.185273 0.313107 0.40736 - -0.176895 0.311949 0.395562 - -0.174606 0.312497 0.392336 - -0.507292 1.27917 0.857662 - -0.131233 0.295171 0.331295 - -0.113463 0.317081 0.306186 - -0.100092 0.302627 0.287399 - -0.080382 0.285291 0.259693 - -0.077921 0.284365 0.256229 - -0.0623972 0.287043 0.234351 - -0.0586834 0.287028 0.229119 - -0.0435222 0.222468 0.207984 - -0.0325702 0.146962 0.192817 - -0.0294271 0.0775301 0.188629 - -0.0291669 0.0784855 0.188259 - -0.0275567 0.0892213 0.185953 - -0.0181451 0.135088 0.172536 - -0.01675 0.137635 0.170562 --0.00260712 0.182856 0.150483 - 0.00195633 0.190843 0.144026 - 0.0280263 0.22647 0.107178 - 0.0341176 0.230169 0.0985837 - 0.0346992 0.229648 0.0977663 - 0.0341489 0.207413 0.0986183 - 0.0511547 0.211233 0.0746484 - 0.0472825 0.171198 0.0802417 - 0.0495513 0.163916 0.0770706 - 0.0527307 0.165699 0.0725855 - 0.0423842 -0.141651 0.0906066 - 0.0311121 -0.175146 0.106248 - 0.0127188 -0.145941 0.131485 - 0.017826 -0.184191 0.12458 - 0.016881 -0.184949 0.125884 - 0.00867797 -0.18117 0.137171 - 0.00911777 -0.19269 0.136604 - 0.00567585 -0.182057 0.141309 --0.00203954 -0.185328 0.151948 --0.00565546 -0.175626 0.156896 --0.00671839 -0.171968 0.158348 - -0.0198231 -0.131878 0.176263 - -0.0289724 -0.0765483 0.188677 - -0.0296694 -0.0686271 0.189611 - -0.0307401 -0.0818281 0.19113 - -0.0308757 -0.0838469 0.191324 - -0.0321801 -0.157978 0.193373 - -0.0329016 -0.171994 0.194415 - -0.0514066 -0.314523 0.22039 - -0.0589849 -0.352322 0.230958 - -0.0639645 -0.368341 0.237872 - -0.0697989 -0.378961 0.245945 - -0.0938955 -0.383397 0.279153 - -0.103218 -0.381921 0.291989 - -0.108223 -0.385485 0.298896 - -0.10926 -0.379624 0.300304 - -0.112553 -0.38509 0.304859 - -0.114312 -0.377656 0.307256 - -0.124818 -0.374981 0.321719 - -0.130165 -0.387412 0.329127 - -0.134885 -0.378418 0.335597 - -0.139971 -0.375459 0.342593 - -0.145463 -0.381998 0.350181 - -0.180741 -0.37481 0.398752 - -0.212247 -0.378802 0.442164 - -0.299578 -0.3763 0.562452 - -0.302412 -0.373595 0.566347 - -0.307566 -0.370679 0.573437 - -0.314577 -0.370043 0.583093 - -0.319685 -0.353492 0.590072 - -0.867794 -0.676591 1.34618 - -1.19683 -0.492323 1.79879 - -1.1937 -0.463612 1.79438 - -1.19432 -0.454764 1.79521 - -1.18661 -0.397907 1.7844 - -1.25958 -0.310361 1.88462 - -1.26016 -0.0531408 1.88454 - -0.282464 -0.00522958 0.537615 - -1.26761 0.12075 1.89421 - -1.2658 0.138935 1.89166 - -1.26509 0.194041 1.89048 - -1.26433 0.286461 1.88913 - -1.22149 0.375961 1.82981 - -1.21991 0.421171 1.82748 - -1.20132 0.533574 1.80149 - -1.19731 0.587644 1.79578 - -1.18801 0.658245 1.78273 - -1.17094 0.80236 1.75872 - -1.17926 0.8282 1.7701 - -1.18902 0.845388 1.78349 - -1.18131 0.880354 1.77274 - -1.1056 0.870524 1.66849 - -1.06773 0.868161 1.61634 - -1.05341 0.865543 1.59661 - -1.00145 1.06923 1.52435 - -0.993005 1.1426 1.51247 - -0.980535 1.22447 1.49501 - -0.980292 1.24642 1.4946 - -0.969851 1.33558 1.47991 - -0.970598 1.36045 1.48086 - -0.966667 1.36672 1.47542 - -0.955983 1.41166 1.46055 - -0.921612 1.40737 1.41322 - -0.893117 1.41052 1.37396 - -0.873278 1.40215 1.34666 - -0.828693 1.3747 1.28534 - -0.177917 0.324423 0.392482 - -0.613999 1.35582 0.989666 - -0.59632 1.36376 0.965287 - -0.131408 0.28923 0.328535 - -0.130667 0.289947 0.327512 - -0.126735 0.295901 0.322076 - -0.117259 0.289514 0.309045 - -0.107853 0.32591 0.295964 - -0.103879 0.31242 0.290535 - -0.0969002 0.309261 0.280933 - -0.0961076 0.309722 0.27984 - -0.0871688 0.298827 0.267564 - -0.083484 0.287115 0.262528 - -0.0820114 0.287832 0.260497 - -0.0706111 0.290554 0.244784 - -0.068375 0.291335 0.241701 - -0.0553042 0.280763 0.223733 - -0.0454006 0.228227 0.21027 - -0.0401201 0.191744 0.20312 - -0.0318276 0.128937 0.191911 - -0.0315743 0.12492 0.191576 - -0.0306745 0.088805 0.190459 - -0.0287073 0.0744341 0.187798 - -0.0247343 0.100732 0.182236 - -0.0225838 0.11431 0.179228 - -0.022089 0.116192 0.17854 - -0.0219979 0.114133 0.178421 --0.00990832 0.159714 0.161613 - 0.0314796 0.226827 0.104373 - 0.0323672 0.202336 0.103234 - 0.034057 0.197228 0.100923 - 0.0345628 0.196719 0.100229 - 0.0604058 0.2529 0.064439 - 0.0532982 0.199404 0.0744117 - 0.0507396 0.180048 0.0780021 - 0.0370329 0.127578 0.0970615 - 0.0414459 -0.15552 0.0941689 - 0.045004 -0.174997 0.0894383 - 0.0462725 -0.189558 0.0877775 - 0.0570726 -0.223289 0.0733335 - 0.0567072 -0.230924 0.0738517 - 0.054154 -0.226547 0.0772784 - 0.0257163 -0.160788 0.115388 - 0.0165663 -0.144321 0.127666 - 0.0186142 -0.187669 0.125051 - 0.0137492 -0.18692 0.131606 - 0.00399863 -0.190935 0.144762 --0.00560902 -0.17797 0.157668 --0.00786504 -0.169646 0.160681 - -0.0281236 -0.0754401 0.187671 - -0.0305202 -0.0667971 0.190872 - -0.0307157 -0.110898 0.191284 - -0.0309303 -0.113915 0.191583 - -0.0616929 -0.361842 0.233879 - -0.0728474 -0.366998 0.248931 - -0.0858238 -0.381888 0.266472 - -0.0905816 -0.371698 0.272851 - -0.154555 -0.378634 0.359102 - -0.162196 -0.378377 0.3694 - -0.173824 -0.373639 0.385058 - -0.180951 -0.374234 0.394666 - -0.193191 -0.379542 0.411181 - -0.196492 -0.376802 0.415622 - -0.197472 -0.375602 0.416939 - -0.23593 -0.367648 0.468748 - -0.239319 -0.370544 0.473326 - -0.24288 -0.37041 0.478125 - -0.243844 -0.36887 0.479419 - -0.260352 -0.370947 0.501676 - -0.26958 -0.379352 0.514143 - -0.326662 -0.344361 0.590965 - -0.884692 -0.824459 1.34473 - -0.87647 -0.775766 1.33348 - -0.87444 -0.742093 1.33063 - -0.865685 -0.68065 1.31863 - -0.858198 -0.630155 1.30837 - -0.936764 -0.550917 1.414 - -0.975052 -0.5432 1.46558 - -1.13451 -0.528706 1.68046 - -1.1929 -0.48388 1.75901 - -1.18479 -0.400584 1.7478 - -1.28524 -0.303108 1.88287 - -1.28987 -0.136665 1.88855 - -1.28928 -0.0812676 1.88757 - -1.28805 0.0658434 1.88541 - -1.26046 0.136422 1.848 - -1.24582 0.224219 1.82797 - -1.24228 0.232521 1.82317 - -1.22943 0.337164 1.8055 - -1.22766 0.354655 1.80305 - -1.20869 0.718646 1.77625 - -1.18135 0.749831 1.7393 - -1.15798 0.880414 1.70737 - -1.01578 0.951694 1.51545 - -0.998588 1.08176 1.49185 - -0.997042 1.12121 1.48963 - -0.987218 1.15155 1.47629 - -0.980337 1.24048 1.46672 - -0.962662 1.37805 1.44243 - -0.960806 1.39961 1.43986 - -0.957169 1.40637 1.43493 - -0.892812 1.4029 1.3482 - -0.886186 1.40425 1.33926 - -0.216122 0.330666 0.439706 - -0.199733 0.325655 0.417632 - -0.179451 0.320965 0.39031 - -0.598085 1.36215 0.95108 - -0.534155 1.35352 0.86494 - -0.122933 0.286612 0.314246 - -0.18976 0.621751 0.403196 - -0.0973006 0.312563 0.27961 - -0.092081 0.299653 0.272618 - -0.0836029 0.299749 0.26119 - -0.0773159 0.291141 0.252745 - -0.0629832 0.290003 0.23343 - -0.0526002 0.273254 0.219492 - -0.0444165 0.222325 0.208632 - -0.0349779 0.138989 0.19619 - -0.0311088 0.117905 0.191045 - -0.03102 0.0768528 0.191064 - -0.0308958 0.0748357 0.190903 - -0.0291471 0.0745833 0.188547 - -0.0282213 0.0794385 0.187283 - -0.0275862 0.0823286 0.186417 - -0.0239773 0.107719 0.181467 - -0.0229433 0.109464 0.180068 - -0.0149393 0.146561 0.169155 - -0.0032298 0.179718 0.153261 - 0.00232171 0.187313 0.145752 - 0.00965074 0.195711 0.135846 - 0.014183 0.207779 0.129696 - 0.0269383 0.226954 0.112439 - 0.0752051 0.284978 0.0471871 - 0.0756227 0.283336 0.0466298 - 0.0735364 0.270096 0.0494864 - 0.0548044 0.199404 0.074972 - 0.0476102 0.164432 0.0847861 - 0.0415426 0.145567 0.0930278 - 0.0407453 0.142758 0.0941119 - 0.0421445 0.13796 0.0922421 - 0.0531763 -0.148288 0.0808668 - 0.0450933 -0.175335 0.0916146 - 0.0490623 -0.192826 0.0864389 - 0.0518434 -0.203049 0.0828056 - 0.0396282 -0.191222 0.0988733 - 0.0226087 -0.187513 0.121303 - 0.0221144 -0.187914 0.121956 - 0.0218826 -0.189212 0.122266 - 0.0112652 -0.187067 0.136259 - 0.00319183 -0.172812 0.146857 - 0.00336572 -0.181173 0.146656 - 0.00288811 -0.181436 0.147286 - 0.00042995 -0.179584 0.150522 --0.00634021 -0.175463 0.159435 - -0.0119473 -0.15608 0.166764 - -0.0287061 -0.0736001 0.188589 - -0.0301579 -0.0718057 0.190498 - -0.0308123 -0.0879015 0.191414 - -0.0317685 -0.144979 0.192864 - -0.0337185 -0.170997 0.195521 - -0.0341859 -0.174992 0.196151 - -0.0362365 -0.188931 0.198901 - -0.040047 -0.215695 0.204014 - -0.042936 -0.230425 0.207872 - -0.0511044 -0.295483 0.218858 - -0.0538257 -0.313102 0.222505 - -0.0600549 -0.351137 0.230845 - -0.0863542 -0.374686 0.265601 - -0.0897503 -0.376406 0.270085 - -0.114516 -0.380728 0.302754 - -0.118522 -0.378312 0.308029 - -0.136249 -0.383564 0.331421 - -0.13726 -0.382814 0.332752 - -0.144747 -0.374758 0.342598 - -0.148252 -0.374083 0.347217 - -0.158297 -0.377718 0.360474 - -0.164844 -0.373881 0.369095 - -0.215568 -0.37281 0.435975 - -0.247816 -0.371036 0.478491 - -0.282263 -0.371067 0.523914 - -0.334075 -0.351696 0.592168 - -0.353634 -0.337575 0.617913 - -0.884166 -0.837495 1.31913 - -0.870071 -0.728144 1.30018 - -0.856893 -0.642273 1.28252 - -0.855145 -0.562703 1.27995 - -0.874696 -0.554823 1.3057 - -0.922581 -0.549455 1.36883 - -1.01503 -0.542678 1.4907 - -1.02564 -0.540578 1.50469 - -1.17822 -0.52428 1.70583 - -1.19338 -0.459658 1.72561 - -1.31785 -0.297259 1.8892 - -1.31475 -0.268272 1.885 - -1.293 -0.0986156 1.85577 - -1.28263 -0.0797263 1.84204 - -1.28285 -0.0707046 1.84229 - -1.23502 -0.0419449 1.77912 - -0.284189 -0.00694126 0.525248 - -0.281804 0.0056784 0.522061 - -1.2515 0.151237 1.80022 - -1.24904 0.177428 1.79689 - -1.24227 0.247019 1.78773 - -1.23564 0.298689 1.77882 - -1.23656 0.406361 1.77967 - -1.23038 0.541177 1.77108 - -1.23115 0.588214 1.77193 - -1.23188 0.664605 1.77265 - -1.17485 0.821995 1.69693 - -1.07481 0.869039 1.56486 - -1.04763 0.864766 1.52903 - -1.01453 0.928109 1.48518 - -1.00206 1.08096 1.46824 - -0.965066 1.3628 1.41852 - -0.96096 1.39291 1.413 - -0.862368 1.40638 1.28296 - -0.207882 0.331526 0.42351 - -0.186467 0.320592 0.395308 - -0.613255 1.35468 0.954647 - -0.594473 1.36041 0.929862 - -0.122886 0.28637 0.311583 - -0.0851519 0.30131 0.261778 - -0.0783367 0.301169 0.252792 - -0.0729075 0.291959 0.245663 - -0.0657287 0.285182 0.23622 - -0.0635749 0.286832 0.233374 - -0.0426975 0.200458 0.206132 - -0.0308445 0.0858787 0.190881 - -0.0307505 0.0818646 0.190771 - -0.0289513 0.0756119 0.188419 - -0.0234819 0.102635 0.181118 - -0.0110746 0.155552 0.164582 --0.00981948 0.158129 0.162919 --0.00414107 0.173206 0.155381 - -0.0028922 0.174692 0.15373 - 0.00950248 0.196343 0.137314 - 0.0121009 0.205408 0.133858 - 0.0194754 0.212428 0.124111 - 0.0362271 0.227122 0.101973 - 0.0340953 0.2132 0.104831 - 0.0402071 0.207563 0.0967902 - 0.065994 0.269314 0.0625832 - 0.0753935 0.289052 0.0501238 - 0.0520966 0.197109 0.0811474 - 0.0531347 0.195861 0.0797827 - 0.049463 0.179197 0.0846793 - 0.0652498 -0.167705 0.0677589 - 0.0488682 -0.159434 0.0888748 - 0.0464189 -0.175335 0.0920879 - 0.0642707 -0.233213 0.0692365 - 0.0195535 -0.184042 0.12679 - 0.0143285 -0.173629 0.1335 - 0.0133997 -0.174296 0.134701 - 0.0155921 -0.18692 0.131912 - 0.0133921 -0.185163 0.134746 - 0.00983616 -0.189565 0.13935 - 0.00827689 -0.185168 0.141348 - 0.00267567 -0.176686 0.148549 --0.00042975 -0.182448 0.152576 - -0.0125634 -0.160587 0.168165 - -0.0247448 -0.0940266 0.18367 - -0.0255143 -0.0881427 0.184644 - -0.0344394 -0.179982 0.196463 - -0.0410685 -0.216585 0.205138 - -0.0463676 -0.251025 0.21209 - -0.0745143 -0.376837 0.248828 - -0.0835787 -0.382036 0.260544 - -0.0918683 -0.379868 0.271236 - -0.0957625 -0.377156 0.276253 - -0.0977774 -0.376242 0.278851 - -0.118999 -0.376439 0.306242 - -0.120006 -0.37582 0.307538 - -0.15353 -0.37861 0.350816 - -0.156271 -0.375112 0.354341 - -0.162463 -0.374098 0.362329 - -0.16446 -0.372234 0.364901 - -0.177576 -0.37092 0.381825 - -0.189927 -0.373142 0.397773 - -0.196436 -0.37791 0.40619 - -0.223527 -0.367651 0.441122 - -0.226098 -0.369327 0.444445 - -0.227484 -0.368702 0.446232 - -0.249631 -0.369592 0.474818 - -0.251893 -0.370199 0.47774 - -0.275348 -0.375553 0.508029 - -0.340989 -0.365236 0.592715 - -0.340206 -0.344576 0.591638 - -0.358634 -0.335256 0.615391 - -0.87271 -0.751749 1.28024 - -0.858428 -0.635033 1.26143 - -0.848998 -0.606556 1.24916 - -1.15476 -0.524032 1.64353 - -1.19117 -0.523213 1.69051 - -1.19924 -0.473508 1.70077 - -1.23181 -0.361408 1.74244 - -1.25326 -0.358887 1.77012 - -1.29737 -0.251988 1.82669 - -1.29263 -0.223751 1.82048 - -1.28324 -0.123361 1.80804 - -1.2554 0.123485 1.7713 - -1.26127 0.159237 1.77876 - -1.26127 0.194489 1.77864 - -1.24202 0.23498 1.75367 - -1.25589 0.362319 1.77115 - -1.25413 0.461472 1.76857 - -1.25284 0.479308 1.76684 - -1.32286 0.585176 1.85686 - -1.33077 0.772108 1.86646 - -1.3182 0.795842 1.85016 - -1.17147 0.877093 1.66052 - -1.01056 0.940102 1.45264 - -0.969402 1.30455 1.39832 - -0.199927 0.32968 0.408385 - -0.15431 0.325009 0.349524 - -0.133489 0.280001 0.322798 - -0.120829 0.279879 0.306459 - -0.138904 0.36462 0.329511 - -0.171349 0.549007 0.370784 - -0.129602 0.461268 0.31719 - -0.0675773 0.29281 0.237688 - -0.0603576 0.284679 0.228397 - -0.0552519 0.269698 0.221856 - -0.0495537 0.249643 0.214567 - -0.0374062 0.150861 0.199211 - -0.035776 0.149951 0.19711 - -0.0333462 0.128 0.194046 - -0.0222025 0.111517 0.179717 - 0.00103737 0.178304 0.149505 - 0.0120245 0.203859 0.135241 - 0.015504 0.202773 0.130753 - 0.0215057 0.213885 0.122971 - 0.0241903 0.216357 0.119498 - 0.0315992 0.212917 0.109947 - 0.0473671 0.223927 0.0895604 - 0.0659467 0.267469 0.0654384 - 0.0808137 0.279238 0.0462118 - 0.0757538 0.264333 0.0527911 - 0.054221 0.195055 0.0808086 - 0.0513267 0.172254 0.0846186 - 0.0437945 0.146118 0.0944254 - 0.0469379 0.144247 0.0903744 - 0.0462696 0.13571 0.0912649 - 0.0620743 -0.155599 0.0744067 - 0.0620661 -0.177381 0.0744873 - 0.0489983 -0.158477 0.0909358 - 0.0493193 -0.161944 0.0905414 - 0.0413064 -0.164317 0.100672 - 0.0327054 -0.168838 0.111553 - 0.0267015 -0.159502 0.119108 - 0.0152871 -0.182316 0.133602 - 0.0147935 -0.182651 0.134227 - 0.0069686 -0.183199 0.144114 - 0.00101767 -0.177912 0.151616 --0.00540823 -0.176625 0.15973 - -0.0090128 -0.16567 0.164248 - -0.0109939 -0.158185 0.166727 - -0.0206266 -0.120428 0.178775 - -0.0271336 -0.0724229 0.186841 - -0.0283119 -0.0726379 0.18833 - -0.0312833 -0.13798 0.192295 - -0.0341094 -0.167984 0.195962 - -0.03776 -0.185817 0.200631 - -0.0399167 -0.204661 0.203417 - -0.0738946 -0.378117 0.246902 - -0.106601 -0.378538 0.288224 - -0.114155 -0.376595 0.29776 - -0.118225 -0.374237 0.302895 - -0.119239 -0.37363 0.304174 - -0.139312 -0.381902 0.329561 - -0.150855 -0.374083 0.344119 - -0.15288 -0.372403 0.346671 - -0.164943 -0.37317 0.361914 - -0.177883 -0.374666 0.378266 - -0.186321 -0.374234 0.388925 - -0.235676 -0.369745 0.451264 - -0.253261 -0.368043 0.473475 - -0.298225 -0.365327 0.530273 - -0.325444 -0.371732 0.564681 - -0.348843 -0.366538 0.594226 - -0.848127 -0.789111 1.22637 - -0.859359 -0.656271 1.24013 - -0.854013 -0.630596 1.23329 - -0.851889 -0.573238 1.23042 - -0.909237 -0.548428 1.30279 - -0.978615 -0.546316 1.39044 - -1.03348 -0.538562 1.45973 - -1.05438 -0.541828 1.48615 - -1.10043 -0.533116 1.54429 - -1.33056 -0.320373 1.83435 - -1.29557 -0.212386 1.78979 - -1.29043 -0.184733 1.78321 - -1.2897 -0.175716 1.78225 - -1.28305 0.0893998 1.773 - -1.24182 0.240522 1.72043 - -1.23004 0.298193 1.70536 - -1.22924 0.306603 1.70432 - -1.24164 0.327218 1.71992 - -1.34766 0.384472 1.85368 - -1.3447 0.440993 1.84976 - -1.34775 0.461327 1.85355 - -1.35573 0.542592 1.86336 - -1.3581 0.583374 1.86622 - -1.36508 0.7193 1.8746 - -1.19994 0.751001 1.66587 - -1.175 0.878285 1.63395 - -1.07673 0.8666 1.50984 - -1.01513 0.886528 1.43195 - -0.990111 1.1408 1.39952 - -0.987391 1.1584 1.39603 - -0.984223 1.20772 1.39187 - -0.959189 1.37837 1.35969 - -0.863741 1.40892 1.23901 - -0.19622 0.333164 0.399152 - -0.61461 1.34818 0.92446 - -0.121802 0.283177 0.305296 - -0.166 0.535148 0.360323 - -0.163657 0.546296 0.357326 - -0.162225 0.554659 0.35549 - -0.144324 0.541457 0.332917 - -0.10357 0.370171 0.281982 - -0.087864 0.311899 0.262327 - -0.0860095 0.311687 0.259985 - -0.0728826 0.300337 0.243437 - -0.0677571 0.29281 0.236986 - -0.0555146 0.272673 0.221584 - -0.0374735 0.146836 0.199198 - -0.0361893 0.142916 0.197588 - -0.035742 0.139937 0.197032 - -0.0315409 0.111971 0.191815 - -0.0305962 0.0899113 0.190692 - -0.0303429 0.0758745 0.190418 - -0.0285337 0.0786632 0.188123 - -0.0280862 0.0755777 0.187568 - -0.0264483 0.0863436 0.185464 - -0.0199208 0.117085 0.177118 - -0.0175624 0.128575 0.174101 --0.00593923 0.1663 0.159295 --0.00069536 0.176384 0.152638 - 0.00152216 0.182613 0.149816 - 0.00445008 0.186363 0.146105 - 0.00635901 0.187446 0.14369 - 0.0622208 0.260961 0.0728793 - 0.0686178 0.234158 0.064884 - 0.0471105 0.151227 0.0923228 - 0.0467115 0.149147 0.0928335 - 0.0446357 0.141461 0.0954808 - 0.0594941 -0.145133 0.0800986 - 0.0658034 -0.160565 0.0723458 - 0.0666204 -0.167639 0.0713579 - 0.0523593 -0.162323 0.088976 - 0.0505093 -0.166008 0.0912754 - 0.0361579 -0.153133 0.108981 - 0.0592947 -0.222558 0.0805914 - 0.0287989 -0.165503 0.11812 - 0.0187182 -0.146995 0.130527 - 0.0182892 -0.173163 0.131141 - 0.0141964 -0.172786 0.136201 --0.00097286 -0.171885 0.154956 - -0.0119638 -0.153593 0.168489 - -0.0201945 -0.120428 0.178562 - -0.0223147 -0.108803 0.181146 - -0.0268288 -0.0744474 0.186619 - -0.0283193 -0.0736943 0.18846 - -0.0300123 -0.071887 0.190548 - -0.040744 -0.201557 0.204231 - -0.0428367 -0.210337 0.206846 - -0.05024 -0.259428 0.216157 - -0.0800805 -0.38245 0.253449 - -0.0883055 -0.378579 0.263608 - -0.0972417 -0.379085 0.274659 - -0.101045 -0.375299 0.27935 - -0.102075 -0.374817 0.280622 - -0.105593 -0.38148 0.284994 - -0.139909 -0.384477 0.327439 - -0.142281 -0.379476 0.330356 - -0.212415 -0.369834 0.417051 - -0.225252 -0.36882 0.432922 - -0.248653 -0.372051 0.461869 - -0.27012 -0.378026 0.488434 - -0.283342 -0.37208 0.504766 - -0.300774 -0.374197 0.526328 - -0.301801 -0.372329 0.527592 - -0.32906 -0.368437 0.561287 - -0.338075 -0.36948 0.572439 - -0.342599 -0.371562 0.578041 - -0.355635 -0.353063 0.594101 - -0.353401 -0.344091 0.591311 - -0.355691 -0.336826 0.594119 - -0.858789 -0.64038 1.21721 - -0.860574 -0.606516 1.21931 - -1.11001 -0.531045 1.52751 - -1.19327 -0.433451 1.63016 - -1.19139 -0.424267 1.62781 - -1.17885 -0.394598 1.61221 - -1.19292 -0.365818 1.62952 - -1.21961 -0.357126 1.6625 - -1.31134 -0.284383 1.77569 - -1.29916 -0.263765 1.76057 - -1.29739 -0.254469 1.75835 - -1.30005 -0.219317 1.76152 - -1.31003 -0.212075 1.77384 - -1.3042 -0.18437 1.76654 - -1.3047 -0.175543 1.76714 - -1.30519 -0.166713 1.76771 - -1.26212 -0.0497813 1.71408 - -1.31534 0.0727117 1.7795 - -1.32661 0.10033 1.79335 - -1.23275 0.278039 1.67672 - -1.39591 0.413046 1.87804 - -1.3969 0.512233 1.87895 - -1.39406 0.531135 1.87539 - -1.3862 0.628659 1.86536 - -1.39215 0.703655 1.87247 - -1.0154 0.920792 1.4059 - -1.01141 0.935407 1.40092 - -1.00831 0.94166 1.39707 - -0.985927 1.15237 1.36872 - -0.982767 1.15896 1.36479 - -0.965038 1.34581 1.34227 - -0.843888 1.39394 1.19231 - -0.191245 0.340214 0.388614 - -0.192709 0.349679 0.390395 - -0.60743 1.3651 0.900002 - -0.517504 1.23107 0.789227 - -0.128682 0.274741 0.311459 - -0.12761 0.280232 0.310116 - -0.119658 0.276634 0.300293 - -0.239875 0.746216 0.447458 - -0.238079 0.748556 0.44523 - -0.161328 0.575158 0.350872 - -0.0660977 0.291314 0.234015 - -0.057466 0.277303 0.223386 - -0.031542 0.112981 0.191851 - -0.0271908 0.077492 0.186584 - -0.0267657 0.0774115 0.186058 - -0.0246204 0.0920853 0.183359 - -0.0237438 0.0989545 0.182253 - -0.0229172 0.10179 0.181222 - -0.0193606 0.121116 0.176762 --0.00788485 0.159099 0.162451 - 0.0132632 0.198843 0.136173 - 0.0202106 0.206334 0.127558 - 0.0257783 0.214524 0.120647 - 0.0262872 0.178699 0.120132 - 0.0745502 0.284455 0.0601142 - 0.0517249 0.15596 0.0887482 - 0.050502 0.148369 0.0902846 - 0.0654847 -0.156313 0.0751669 - 0.0743758 -0.184436 0.0644826 - 0.0738637 -0.185164 0.0651054 - 0.0388094 -0.162434 0.107506 - 0.0415906 -0.170361 0.104162 - 0.0602443 -0.219417 0.0817145 - 0.0590239 -0.220674 0.0831971 - 0.0450625 -0.194291 0.10003 - 0.0160496 -0.155546 0.135061 - 0.0182935 -0.168286 0.132382 - 0.0157897 -0.175544 0.135439 --0.00889743 -0.161933 0.165307 - -0.0152623 -0.140509 0.172952 - -0.0178049 -0.132081 0.176006 - -0.0202146 -0.119524 0.178886 - -0.0271849 -0.0735659 0.187187 - -0.0273893 -0.0736001 0.187435 - -0.0387291 -0.180701 0.201511 - -0.045638 -0.219967 0.210005 - -0.0600313 -0.334084 0.227803 - -0.0612983 -0.337851 0.22935 - -0.0690383 -0.367377 0.238821 - -0.0917352 -0.376406 0.266349 - -0.110956 -0.387534 0.289672 - -0.112032 -0.386988 0.290974 - -0.120991 -0.378927 0.301804 - -0.132663 -0.377064 0.315941 - -0.140221 -0.377345 0.325098 - -0.161075 -0.373349 0.350353 - -0.17116 -0.374745 0.362576 - -0.189041 -0.376149 0.384246 - -0.219422 -0.369959 0.421036 - -0.223511 -0.364759 0.425975 - -0.228801 -0.368242 0.432395 - -0.262516 -0.371497 0.473255 - -0.280506 -0.366974 0.495037 - -0.290671 -0.368833 0.50736 - -0.295086 -0.368597 0.512709 - -0.303342 -0.373538 0.522727 - -0.341579 -0.36948 0.569043 - -0.360256 -0.347443 0.591603 - -0.361222 -0.345188 0.592766 - -0.363809 -0.331672 0.595858 - -0.868937 -0.758543 1.20922 - -0.862564 -0.685831 1.20127 - -0.8552 -0.658253 1.19226 - -0.850305 -0.640251 1.18628 - -0.851513 -0.634189 1.18772 - -0.851545 -0.565728 1.18754 - -0.856034 -0.562092 1.19297 - -0.857596 -0.556434 1.19485 - -1.06917 -0.536204 1.45113 - -1.18376 -0.424768 1.58962 - -1.32686 -0.348059 1.76276 - -1.29262 -0.224175 1.72089 - -1.33087 -0.177012 1.76709 - -0.276824 0.0019545 0.489417 - -0.276809 0.00530536 0.489388 - -1.2362 0.241908 1.65106 - -1.22806 0.290398 1.64104 - -1.41949 0.464601 1.87244 - -1.42018 0.544939 1.87303 - -1.42206 0.565941 1.87524 - -1.4253 0.776019 1.8785 - -1.22894 0.760316 1.64063 - -1.18291 0.749457 1.5849 - -1.17054 0.787458 1.56979 - -1.17586 0.876729 1.57596 - -1.15729 0.881629 1.55344 - -1.1108 0.87302 1.49714 - -1.05945 0.867344 1.43494 - -1.00694 0.929195 1.37113 - -0.961445 1.31322 1.3148 - -0.214003 0.348683 0.412213 - -0.211429 0.34681 0.4091 - -0.210466 0.348031 0.407929 - -0.199211 0.344062 0.394305 - -0.133768 0.277938 0.315221 - -0.246311 0.779376 0.450005 - -0.178699 0.566674 0.368753 - -0.170189 0.592162 0.358362 - -0.167111 0.594958 0.354624 - -0.152122 0.621598 0.336379 - -0.144367 0.600157 0.327051 - -0.0842611 0.307579 0.255144 - -0.0834069 0.307928 0.254108 - -0.0820056 0.31055 0.252402 - -0.0498709 0.237483 0.213697 - -0.0383033 0.14773 0.199963 - -0.0362865 0.134875 0.19756 - -0.0283366 0.0827392 0.188091 - -0.0281068 0.0827098 0.187813 - -0.0275331 0.0846376 0.187112 - -0.023728 0.0980263 0.18246 - -0.015032 0.13827 0.171797 - -0.0110597 0.149203 0.16695 --0.00878286 0.158633 0.164161 - -0.0071788 0.156986 0.162223 - 0.0107461 0.192249 0.140394 - 0.0110661 0.191008 0.14001 - 0.0119895 0.187283 0.138903 - 0.0264128 0.208221 0.121362 - 0.0289411 0.20971 0.118294 - 0.0259074 0.176448 0.122074 - 0.0768124 0.291967 0.0600335 - 0.0773113 0.258461 0.0595344 - 0.076254 0.253561 0.0608308 - 0.0720585 0.232623 0.06598 - 0.0595658 0.193798 0.0812384 - 0.0577489 0.154725 0.0835625 - 0.0577083 0.149324 0.0836286 - 0.0528504 0.140041 0.0895437 - 0.07102 -0.182061 0.0713146 - 0.0320608 -0.141785 0.117344 - 0.0556023 -0.208927 0.0896632 - 0.0412361 -0.185105 0.106609 - 0.0119724 -0.1337 0.141118 - 0.01479 -0.157161 0.137852 - 0.0172216 -0.183907 0.135055 - 0.0174397 -0.187014 0.134806 --0.00080258 -0.168255 0.156359 --0.00535257 -0.178339 0.161781 --0.00846656 -0.164044 0.165426 --0.00979579 -0.161419 0.166992 - -0.0218776 -0.104847 0.18113 - -0.0234669 -0.0940849 0.182979 - -0.0274973 -0.0696527 0.187678 - -0.0319507 -0.136 0.19316 - -0.0683434 -0.358489 0.236964 - -0.0764834 -0.374569 0.246657 - -0.0869846 -0.371172 0.259087 - -0.0976343 -0.381466 0.271736 - -0.140846 -0.375522 0.32291 - -0.141903 -0.374779 0.32416 - -0.153056 -0.373128 0.337367 - -0.162506 -0.373349 0.348563 - -0.179653 -0.374142 0.36888 - -0.22083 -0.368395 0.417643 - -0.235713 -0.370087 0.435281 - -0.24199 -0.368249 0.442711 - -0.24757 -0.361777 0.449301 - -0.280054 -0.368296 0.487805 - -0.366198 -0.36611 0.589852 - -0.367229 -0.363842 0.591066 - -0.372536 -0.329755 0.597248 - -0.853491 -0.627565 1.16795 - -0.851183 -0.605235 1.16515 - -0.851138 -0.598404 1.16507 - -0.874637 -0.553887 1.19278 - -1.07843 -0.534016 1.43415 - -1.12681 -0.526016 1.49144 - -1.19289 -0.51496 1.56968 - -1.19434 -0.507097 1.57138 - -1.19406 -0.490032 1.571 - -1.32892 -0.33507 1.73028 - -1.32769 -0.209687 1.72844 - -1.43872 -0.16049 1.85982 - -1.45296 0.0785187 1.87594 - -1.4455 0.164408 1.86684 - -1.23915 0.23937 1.62215 - -1.22399 0.310476 1.60398 - -1.44878 0.498384 1.8697 - -1.44952 0.528948 1.87047 - -1.71623 0.837222 2.18548 - -1.75363 1.02579 2.22921 - -1.01244 0.922442 1.35145 - -1.00187 0.995127 1.33871 - -0.971637 1.28786 1.30198 - -0.964725 1.33557 1.29364 - -0.918025 1.40853 1.23809 - -0.900698 1.40525 1.21757 - -0.852352 1.41066 1.16028 - -0.8247 1.38721 1.1276 - -0.23356 0.365221 0.43045 - -0.227573 0.363881 0.423361 - -0.197639 0.343122 0.387964 - -0.200675 0.355831 0.39152 - -0.202166 0.368985 0.393246 - -0.574104 1.22031 0.831237 - -0.617846 1.3437 0.882675 - -0.59673 1.35807 0.857615 - -0.174321 0.352099 0.36031 - -0.128254 0.276707 0.305969 - -0.12335 0.273919 0.300169 - -0.256604 0.788333 0.456438 - -0.158829 0.620057 0.341126 - -0.163621 0.65338 0.346701 - -0.152258 0.635686 0.333294 - -0.0784189 0.308926 0.246831 - -0.0779796 0.31216 0.2463 - -0.0703231 0.302383 0.23726 - -0.0559518 0.268551 0.220339 - -0.0440417 0.189138 0.206476 - -0.038322 0.143698 0.199841 - -0.0379176 0.143737 0.199362 - -0.0374002 0.140779 0.198758 - -0.032864 0.114996 0.193464 - -0.0267189 0.0805499 0.18629 - -0.0264922 0.080512 0.186022 - -0.0169679 0.13086 0.174583 - -0.0160171 0.135671 0.173441 --0.00527748 0.164738 0.160628 - -5.134e-05 0.180162 0.154389 - 0.0181891 0.201256 0.132714 - 0.0187555 0.200912 0.132044 - 0.0213294 0.205774 0.12898 - 0.023962 0.210581 0.125846 - 0.0247223 0.205745 0.124961 - 0.0281463 0.187868 0.12096 - 0.0269886 0.176448 0.122367 - 0.0279808 0.175638 0.121194 - 0.0860496 0.296639 0.052025 - 0.0719931 0.230883 0.0688815 - 0.0562192 0.181989 0.0877202 - 0.0820778 -0.191102 0.0617626 - 0.0804825 -0.198606 0.063626 - 0.0507412 -0.15951 0.0978201 - 0.0468049 -0.160337 0.102364 - 0.0349922 -0.141287 0.115935 - 0.0327631 -0.148503 0.118528 - 0.0543424 -0.205882 0.0938069 - 0.0537541 -0.206452 0.0944874 - 0.0355682 -0.17065 0.11536 - 0.0321283 -0.173697 0.119338 - 0.021546 -0.149458 0.131473 - 0.0164654 -0.145609 0.137323 - 0.0172389 -0.186744 0.136556 - 0.0147063 -0.191442 0.139492 - 0.0106468 -0.181976 0.144147 --0.00087785 -0.163448 0.157387 --0.00400499 -0.171958 0.16102 --0.00480421 -0.170194 0.161937 --0.00684707 -0.166811 0.164284 - -0.0162902 -0.136023 0.175085 - -0.0184499 -0.123389 0.177538 - -0.0205847 -0.11276 0.179968 - -0.0272713 -0.0696824 0.187551 - -0.0287546 -0.0678575 0.189257 - -0.0304506 -0.0839811 0.191263 - -0.034924 -0.145907 0.196613 - -0.0358956 -0.150851 0.197749 - -0.0638085 -0.341393 0.230535 - -0.0771805 -0.377518 0.246073 - -0.0812317 -0.374275 0.250737 - -0.0836403 -0.37555 0.25352 - -0.0990502 -0.379085 0.27131 - -0.101758 -0.374813 0.27442 - -0.124242 -0.379248 0.300374 - -0.142441 -0.37205 0.32135 - -0.157811 -0.382947 0.339115 - -0.161559 -0.369829 0.343399 - -0.18867 -0.373246 0.374689 - -0.189737 -0.372193 0.375916 - -0.191517 -0.372805 0.377972 - -0.19907 -0.375911 0.386696 - -0.200708 -0.365667 0.388555 - -0.208444 -0.371951 0.397498 - -0.212014 -0.369177 0.401609 - -0.222744 -0.370456 0.413993 - -0.251984 -0.370604 0.447728 - -0.28992 -0.371082 0.491497 - -0.299458 -0.371521 0.502503 - -0.304992 -0.372589 0.508892 - -0.364121 -0.368759 0.577098 - -0.377855 -0.35981 0.592916 - -0.850782 -0.576003 1.13921 - -0.848855 -0.568051 1.13696 - -0.868462 -0.554926 1.15954 - -0.898901 -0.547804 1.19464 - -1.09049 -0.532142 1.41563 - -1.12808 -0.526821 1.45899 - -1.13709 -0.523058 1.46937 - -1.17329 -0.523537 1.51113 - -1.18196 -0.404309 1.52077 - -1.23687 -0.356429 1.58398 - -1.3256 -0.32037 1.68624 - -1.29709 -0.252991 1.65314 - -1.48176 -0.172649 1.86595 - -1.47899 -0.133556 1.86264 - -0.283832 -0.00811906 0.483365 - -1.48431 0.0790531 1.86813 - -1.48292 0.185692 1.8662 - -1.23392 0.251077 1.57872 - -1.2831 0.346775 1.63517 - -1.76081 0.562862 2.18566 - -1.78896 0.658198 2.21785 - -1.60073 0.968971 1.99972 - -1.06452 0.86548 1.3814 - -1.01628 0.903436 1.32563 - -1.01095 0.943446 1.31935 - -1.0088 0.950489 1.31686 - -1.0039 0.963997 1.31116 - -0.997194 1.04166 1.30319 - -0.999022 1.0533 1.30526 - -0.986835 1.12876 1.29097 - -0.965778 1.34056 1.26603 - -0.953711 1.39426 1.25194 - -0.939867 1.40967 1.23592 - -0.89573 1.40088 1.18503 - -0.24095 0.380189 0.432705 - -0.237521 0.380638 0.428748 - -0.21021 0.388475 0.397214 - -0.236245 0.453495 0.427053 - -0.597204 1.33956 0.840797 - -0.15302 0.298607 0.331507 - -0.138398 0.275839 0.314707 - -0.120745 0.277825 0.294334 - -0.213729 0.67677 0.400393 - -0.171511 0.683947 0.351664 - -0.0391815 0.14157 0.200647 - -0.0382316 0.130647 0.199585 - -0.0378583 0.130687 0.199154 - -0.0351081 0.125906 0.195996 - -0.0337558 0.110964 0.194481 - -0.0321505 0.105999 0.192644 - -0.0304168 0.0819702 0.190717 - -0.0285074 0.0678092 0.188558 - -0.026478 0.0775666 0.186186 - -0.024804 0.0873361 0.184225 - -0.0235319 0.093132 0.18274 - -0.0208841 0.10567 0.179647 - -0.0162959 0.134901 0.174264 --0.00288882 0.17133 0.158684 - 4.052e-05 0.170107 0.155309 - 0.00262374 0.175197 0.152313 - 0.00388647 0.178789 0.150845 - 0.0102893 0.187165 0.143432 - 0.0108242 0.186882 0.142816 - 0.0267452 0.192072 0.124431 - 0.0524856 0.232555 0.0946103 - 0.0773354 0.283354 0.0657852 - 0.0895837 0.294178 0.0516209 - 0.066173 0.209932 0.0788878 - 0.0489293 -0.12224 0.101717 - 0.0916357 -0.215283 0.0537472 - 0.0573508 -0.169725 0.0923457 - 0.0397934 -0.153259 0.112133 - 0.0486136 -0.194818 0.102293 - 0.0173528 -0.193626 0.137609 --0.00056952 -0.172934 0.157795 - -0.0023998 -0.171585 0.159859 - -0.0136297 -0.140509 0.172453 - -0.0270113 -0.0717026 0.187364 - -0.0280016 -0.0728257 0.188487 - -0.0284229 -0.0728669 0.188963 - -0.0290881 -0.0719194 0.189711 - -0.0328328 -0.130978 0.194121 - -0.042953 -0.18314 0.205712 - -0.0492151 -0.238437 0.212954 - -0.0520296 -0.256053 0.216187 - -0.107994 -0.379568 0.27979 - -0.117767 -0.385305 0.290849 - -0.128444 -0.38266 0.302904 - -0.140477 -0.379542 0.31649 - -0.160217 -0.374176 0.338777 - -0.162838 -0.377744 0.341748 - -0.165333 -0.376873 0.344565 - -0.189538 -0.375135 0.371907 - -0.195299 -0.370655 0.378402 - -0.23003 -0.37048 0.417641 - -0.231101 -0.369165 0.418848 - -0.24689 -0.364585 0.436673 - -0.272022 -0.372928 0.465093 - -0.296902 -0.367229 0.493186 - -0.323061 -0.366078 0.522738 - -0.33188 -0.367193 0.532704 - -0.342353 -0.366592 0.544536 - -0.387015 -0.355056 0.594961 - -0.39452 -0.325806 0.603352 - -0.872091 -0.550945 1.1436 - -0.954996 -0.541193 1.23724 - -1.02086 -0.535187 1.31164 - -1.19938 -0.504237 1.51324 - -1.1801 -0.414973 1.49119 - -1.18265 -0.375989 1.49395 - -1.31794 -0.211206 1.64631 - -1.49543 -0.065885 1.84641 - -0.274663 -0.00453725 0.466965 - -0.276014 0.00187815 0.468472 - -1.73923 0.114366 2.12132 - -1.84499 0.658668 2.23916 - -1.86312 0.939644 2.25879 - -1.86454 0.96734 2.26031 - -1.84609 1.09365 2.23909 - -1.65805 1.0052 2.0269 - -1.17234 0.767133 1.47885 - -1.05008 0.861087 1.34044 - -1.02187 0.863083 1.30856 - -1.01828 0.903744 1.30438 - -1.00105 1.02432 1.28455 - -0.992602 1.07292 1.27486 - -0.978497 1.25247 1.25838 - -0.968324 1.28323 1.2468 - -0.969812 1.33096 1.24833 - -0.855438 1.40369 1.11889 - -0.234453 0.449059 0.420166 - -0.136338 0.268081 0.30986 - -0.127085 0.273565 0.299389 - -0.121217 0.267991 0.292775 - -0.371098 1.16098 0.572403 - -0.185405 0.61081 0.364263 - -0.186472 0.640099 0.365379 - -0.0746151 0.30425 0.240014 - -0.0556015 0.256505 0.218676 - -0.0502601 0.228305 0.212726 - -0.0331064 0.106976 0.193712 - -0.0327089 0.0999858 0.193284 - -0.0318336 0.0979992 0.192301 - -0.0295753 0.0749399 0.189819 - -0.0277795 0.0717738 0.187799 - -0.0269105 0.0796903 0.186794 - -0.0205912 0.110758 0.17956 - -0.0146382 0.131519 0.172772 - -0.0138729 0.134348 0.171899 - -0.0076054 0.153767 0.164759 - 0.0145881 0.196961 0.139554 - 0.0232329 0.210214 0.129747 - 0.0244477 0.209482 0.128376 - 0.0251529 0.206886 0.127587 - 0.0257994 0.190119 0.126907 - 0.042998 0.20957 0.107417 - 0.0672767 0.261219 0.0798308 - 0.0926677 0.291704 0.0510513 - 0.0793711 0.241442 0.0662259 - 0.0668693 0.197155 0.0804844 - 0.0785353 0.199778 0.0672959 - 0.078114 0.193783 0.06779 - 0.0789165 0.190094 0.0668944 - 0.0837722 0.19159 0.0614038 - 0.0691832 -0.156139 0.0813348 - 0.0950002 -0.210524 0.0529459 - 0.0923323 -0.215328 0.0559106 - 0.0535283 -0.164315 0.0986719 - 0.0335807 -0.1685 0.120744 - 0.0296602 -0.16489 0.125069 - 0.0136194 -0.141143 0.142738 - 0.0135311 -0.182348 0.142959 - 0.0102951 -0.178747 0.146527 --0.00108955 -0.172362 0.159098 --0.00879385 -0.162691 0.167589 - -0.0131233 -0.140509 0.172311 - -0.0226538 -0.0951876 0.182716 - -0.0263224 -0.0736643 0.186709 - -0.0278332 -0.0738449 0.18838 - -0.0287704 -0.0659119 0.189393 - -0.0299339 -0.0779825 0.190715 - -0.0303317 -0.0839934 0.191173 - -0.0324915 -0.124979 0.193684 - -0.0457023 -0.200783 0.20852 - -0.0519054 -0.255061 0.215542 - -0.0819923 -0.375255 0.249173 - -0.101394 -0.379593 0.270643 - -0.107127 -0.378157 0.276978 - -0.113571 -0.368807 0.284077 - -0.123014 -0.382958 0.294562 - -0.145645 -0.380079 0.319581 - -0.160185 -0.378537 0.335656 - -0.189328 -0.374485 0.367873 - -0.194064 -0.374708 0.373112 - -0.201355 -0.369847 0.38116 - -0.21231 -0.365557 0.393263 - -0.253193 -0.371295 0.438493 - -0.277705 -0.380982 0.465629 - -0.315261 -0.368396 0.507125 - -0.39295 -0.346913 0.592977 - -0.393966 -0.344552 0.594093 - -0.395407 -0.339283 0.595671 - -0.468597 -0.368843 0.6767 - -0.853021 -0.57091 1.10244 - -0.861042 -0.556855 1.11127 - -0.908376 -0.534457 1.16355 - -1.18718 -0.444673 1.47161 - -1.18718 -0.436653 1.47159 - -1.17637 -0.393097 1.45949 - -1.33466 -0.341368 1.6344 - -1.30079 -0.264723 1.59671 - -1.29908 -0.230787 1.59472 - -1.53641 -0.214501 1.85713 - -1.80259 -0.136509 2.15127 - -1.8671 0.28965 2.22134 - -1.88568 0.539325 2.24115 - -1.89027 0.718599 2.24569 - -1.89835 0.747678 2.25453 - -1.89911 0.906513 2.25491 - -1.90503 0.949952 2.26132 - -1.16545 0.780352 1.44392 - -1.16147 0.795493 1.43948 - -1.18135 0.864982 1.46125 - -1.13113 0.872528 1.4057 - -1.01799 0.884356 1.28054 - -0.999846 1.00196 1.26012 - -0.996181 1.03575 1.25597 - -0.996057 1.05476 1.25577 - -0.983389 1.12902 1.24154 - -0.964153 1.33079 1.21967 - -0.912167 1.40734 1.16195 - -0.868594 1.39752 1.11379 - -0.853311 1.3963 1.09689 - -0.137732 0.274645 0.308878 - -0.137779 0.280369 0.308912 - -0.126627 0.275698 0.296594 - -0.388065 1.22007 0.582902 - -0.236333 0.74528 0.416517 - -0.0602027 0.278749 0.223126 - -0.048939 0.213416 0.210864 - -0.0414663 0.157283 0.202768 - -0.0361017 0.117785 0.196953 - -0.0354122 0.117843 0.19619 - -0.033408 0.104953 0.194012 - -0.0331008 0.104966 0.193672 - -0.0314902 0.0859993 0.191947 - -0.0270618 0.0747377 0.187084 --0.00215128 0.162244 0.159274 - 0.0196059 0.197863 0.135107 - 0.0251123 0.191239 0.129037 - 0.0256019 0.179925 0.128529 - 0.0750713 0.218319 0.0737065 - 0.0729781 0.204459 0.0760627 - 0.0783883 0.201939 0.0700871 - 0.091612 0.203488 0.0554584 - 0.0838156 -0.184442 0.0677203 - 0.071829 -0.185189 0.0807186 - 0.0569434 -0.165576 0.0968002 - 0.037546 -0.161202 0.117818 - 0.0307515 -0.163619 0.125192 - 0.0257565 -0.155097 0.130583 - 0.0145795 -0.157455 0.142708 - 0.0131179 -0.185088 0.144374 - 0.012127 -0.183476 0.145444 - 0.00619601 -0.172662 0.151843 - 0.00568523 -0.172897 0.152397 --0.00234479 -0.170986 0.161098 --0.00731558 -0.162397 0.166462 --0.00779599 -0.162546 0.166983 --0.00942425 -0.157929 0.168735 - -0.0217266 -0.0981052 0.181897 - -0.0225668 -0.0952411 0.1828 - -0.0249659 -0.0785365 0.185352 - -0.0259271 -0.0746598 0.186382 - -0.0261479 -0.0746902 0.186622 - -0.0288268 -0.0669382 0.189503 - -0.0290248 -0.0669501 0.189718 - -0.0307798 -0.0959998 0.191707 - -0.038053 -0.154614 0.199765 - -0.0389676 -0.154513 0.200757 - -0.0416207 -0.17525 0.203694 - -0.0553806 -0.277577 0.218915 - -0.0939306 -0.368239 0.260979 - -0.125306 -0.378927 0.295029 - -0.131635 -0.378571 0.30189 - -0.150238 -0.374315 0.322048 - -0.152744 -0.373658 0.324763 - -0.168171 -0.377754 0.3415 - -0.170728 -0.376841 0.344271 - -0.197414 -0.375313 0.3732 - -0.225859 -0.368579 0.40402 - -0.246263 -0.372367 0.426154 - -0.31165 -0.373073 0.49705 - -0.317565 -0.367741 0.503448 - -0.337719 -0.363331 0.525287 - -0.401331 -0.358186 0.594241 - -0.403627 -0.320504 0.596619 - -0.87052 -0.665059 1.10385 - -1.17778 -0.428553 1.4363 - -1.22439 -0.356984 1.48662 - -1.32416 -0.343645 1.59475 - -1.30141 -0.270413 1.56987 - -1.29751 -0.261261 1.56562 - -1.863 -0.234489 2.17866 - -1.9145 -0.155757 2.23426 - -1.91781 -0.119501 2.23774 - -0.276914 -0.00765511 0.458311 - -1.92871 0.185489 2.24866 - -1.92696 0.222109 2.24665 - -1.92698 0.234391 2.24664 - -1.92587 0.557841 2.24448 - -1.9295 0.674122 2.24808 - -1.92548 0.698521 2.24364 - -1.93247 0.727136 2.25114 - -1.93506 0.79383 2.25375 - -1.86849 1.12399 2.1806 - -1.16716 0.782214 1.4212 - -1.17663 0.8432 1.43129 - -1.08584 0.871851 1.33277 - -1.01592 0.88193 1.25693 - -1.0134 0.914598 1.25411 - -0.998338 1.03671 1.23742 - -0.993277 1.0503 1.23189 - -0.990868 1.11601 1.22908 - -0.988629 1.12342 1.22663 - -0.985129 1.13946 1.22279 - -0.963409 1.36256 1.19858 - -0.861913 1.3963 1.08844 - -0.816829 1.4172 1.0395 - -0.240459 0.398731 0.417586 - -0.212494 0.385546 0.387305 - -0.212123 0.388356 0.386894 - -0.276588 0.567864 0.456259 - -0.159607 0.306264 0.330198 - -0.135304 0.263581 0.303973 - -0.127562 0.273302 0.295551 - -0.125131 0.275138 0.29291 - -0.371304 1.19369 0.557107 - -0.188348 0.653417 0.360335 - -0.160012 0.707194 0.329454 - -0.181785 0.904478 0.352479 - -0.190039 1.0311 0.361054 - -0.0749436 0.310404 0.238391 - -0.0548473 0.2415 0.216806 - -0.0401361 0.146393 0.201136 - -0.0390423 0.135491 0.199982 - -0.0386415 0.135541 0.199547 - -0.0366659 0.119714 0.197452 - -0.0344921 0.107879 0.19513 - -0.0309528 0.0809998 0.191372 - -0.0295153 0.0809705 0.189813 - -0.0238678 0.0883753 0.183669 - -0.0209745 0.104957 0.180483 - -0.020375 0.10786 0.179824 --0.00331489 0.16395 0.161162 - 0.00641363 0.180701 0.150564 - 0.0126088 0.192462 0.143813 - 0.0141862 0.193782 0.142098 - 0.0144303 0.189422 0.141847 - 0.0258139 0.207628 0.129451 - 0.0249242 0.185389 0.130481 - 0.0257174 0.181567 0.129632 - 0.0884991 0.2716 0.0612971 - 0.0746009 0.206733 0.0765572 - 0.084973 0.211259 0.0652981 - 0.097259 0.223489 0.0519413 - 0.0974004 0.214063 0.0518157 - 0.0490807 -0.120214 0.106985 - 0.069175 -0.155884 0.0857545 - 0.0903218 -0.200869 0.0634341 - 0.0837125 -0.203786 0.0704598 - 0.0683041 -0.179478 0.086748 - 0.0352113 -0.12949 0.121737 - 0.0352386 -0.154833 0.121782 - 0.0325613 -0.156021 0.124628 - 0.0183877 -0.144448 0.139642 - 0.0179556 -0.144757 0.140102 - -0.0013838 -0.169832 0.160708 --0.00626927 -0.162246 0.165873 - -0.0077268 -0.162691 0.167421 --0.00883244 -0.161991 0.168593 - -0.0119422 -0.145541 0.171847 - -0.0195876 -0.112902 0.179869 - -0.0246189 -0.0815568 0.185119 - -0.0272566 -0.0678377 0.187879 - -0.0284832 -0.0749442 0.189202 - -0.0297494 -0.0829935 0.19057 - -0.0379028 -0.146588 0.199412 - -0.0456002 -0.194724 0.207725 - -0.0607791 -0.306759 0.224167 - -0.0651978 -0.331063 0.22893 - -0.0767041 -0.365721 0.241247 - -0.0929578 -0.373899 0.258527 - -0.130113 -0.37456 0.297977 - -0.162696 -0.375024 0.332571 - -0.176945 -0.370503 0.347687 - -0.184181 -0.373561 0.355378 - -0.201983 -0.371226 0.374272 - -0.211776 -0.371043 0.384668 - -0.238445 -0.371487 0.412985 - -0.257776 -0.368358 0.4335 - -0.294993 -0.417548 0.473156 - -0.287653 -0.3752 0.46524 - -0.307236 -0.369929 0.486016 - -0.315551 -0.37441 0.494857 - -0.340297 -0.36917 0.521114 - -0.360961 -0.363145 0.543036 - -0.38244 -0.366049 0.565848 - -0.383535 -0.363803 0.567005 - -0.403906 -0.350155 0.588593 - -0.410714 -0.326451 0.595752 - -0.411691 -0.324026 0.596781 - -0.41266 -0.321594 0.597803 - -0.887326 -0.657003 1.10274 - -0.88904 -0.616966 1.10444 - -0.889654 -0.610615 1.10507 - -0.88835 -0.563006 1.10355 - -0.922467 -0.551547 1.13974 - -0.94449 -0.544662 1.1631 - -0.989567 -0.536176 1.21093 - -1.01779 -0.537571 1.2409 - -1.18186 -0.441022 1.41481 - -1.17624 -0.400077 1.40872 - -1.17241 -0.37574 1.40459 - -1.2349 -0.356189 1.47088 - -1.3243 -0.322932 1.56569 - -1.28922 -0.248544 1.52823 - -1.28724 -0.24001 1.52611 - -1.28865 -0.224003 1.52756 - -1.96269 -0.219756 2.24317 - -1.96852 0.125452 2.24836 - -1.97139 0.16278 2.25129 - -1.95964 0.211104 2.23868 - -1.98584 0.846447 2.26465 - -1.98914 0.916056 2.26795 - -1.98285 0.982026 2.26107 - -1.98828 1.04079 2.26666 - -1.16714 0.827114 1.39549 - -1.11883 0.871259 1.34407 - -1.01547 0.906585 1.23423 - -1.01407 0.92286 1.23269 - -1.0063 0.969055 1.2243 - -0.995321 1.06021 1.21238 - -0.975045 1.19699 1.19046 - -0.975254 1.25093 1.19052 - -0.932997 1.41027 1.14519 - -0.850349 1.39849 1.05748 - -0.21579 0.396131 0.386692 - -0.23966 0.464359 0.411836 - -0.253988 0.500921 0.426942 - -0.250987 0.503737 0.423747 - -0.129162 0.27268 0.295079 - -0.128346 0.273302 0.294211 - -0.192795 0.639078 0.36157 - -0.187447 0.745125 0.355582 - -0.169538 0.715249 0.336656 - -0.164531 0.713117 0.331346 - -0.177874 0.841446 0.345138 - -0.177719 0.888899 0.344835 - -0.0668433 0.29033 0.228864 - -0.0548168 0.234422 0.216258 - -0.0473694 0.190482 0.20848 - -0.0369248 0.115649 0.197609 - -0.03594 0.109737 0.196581 - -0.0329877 0.0969432 0.193484 - -0.0326977 0.0969567 0.193176 - -0.0292656 0.076972 0.18959 - -0.0290353 0.0769622 0.189346 - -0.0157171 0.127121 0.175059 - -0.0125197 0.136427 0.171637 --0.00667274 0.148901 0.165393 --0.00253376 0.16492 0.160952 - 0.0100085 0.185674 0.147575 - 0.0109859 0.187313 0.146533 - 0.0167376 0.19289 0.14041 - 0.0244568 0.199286 0.132196 - 0.0286104 0.173554 0.127861 - 0.0296476 0.172791 0.126762 - 0.0341535 0.181768 0.121952 - 0.0464763 0.211825 0.108781 - 0.0758497 0.211981 0.077595 - 0.0928083 0.224475 0.0595535 - 0.0990073 0.219556 0.0529864 - 0.0938398 0.198195 0.058535 - 0.0792315 0.168895 0.0741302 - 0.0921075 -0.20467 0.0642571 - 0.0789604 -0.189249 0.0778797 - 0.0783879 -0.189933 0.0784768 - 0.0338622 -0.134399 0.124603 - 0.0360628 -0.144331 0.122344 - 0.0292411 -0.146914 0.129443 - 0.0270125 -0.156702 0.131788 - 0.0176955 -0.139962 0.141425 - 0.0145043 -0.157388 0.144793 - 0.0174177 -0.171879 0.141806 - 0.018044 -0.183337 0.141188 - 0.0156635 -0.181408 0.143657 - 0.00138007 -0.16385 0.158455 --0.00445384 -0.166973 0.164529 - -0.0164875 -0.124463 0.176916 - -0.0211271 -0.0991537 0.181666 - -0.0297169 -0.0789973 0.190537 - -0.0338146 -0.120881 0.194918 - -0.0412096 -0.166219 0.202736 - -0.0424662 -0.177091 0.204074 - -0.0676219 -0.333565 0.230676 - -0.0812058 -0.363497 0.244883 - -0.0923566 -0.382472 0.25653 - -0.0980505 -0.373207 0.262422 - -0.109256 -0.38632 0.274109 - -0.115391 -0.379381 0.280466 - -0.116971 -0.380737 0.282113 - -0.123156 -0.374489 0.288524 - -0.131678 -0.377356 0.297391 - -0.145185 -0.382292 0.311447 - -0.154412 -0.380644 0.321034 - -0.161793 -0.373193 0.328686 - -0.171012 -0.378634 0.338285 - -0.174105 -0.37506 0.34149 - -0.180446 -0.372155 0.348074 - -0.219718 -0.373184 0.388902 - -0.220316 -0.367575 0.389507 - -0.227284 -0.367463 0.39675 - -0.23214 -0.363213 0.401786 - -0.283325 -0.391739 0.455078 - -0.291688 -0.37732 0.46373 - -0.298714 -0.374138 0.471024 - -0.308896 -0.37169 0.481602 - -0.339183 -0.360905 0.513056 - -0.368199 -0.37069 0.543248 - -0.37318 -0.359364 0.548393 - -0.374829 -0.357783 0.550103 - -0.37873 -0.358508 0.554161 - -0.390537 -0.363842 0.56645 - -0.975288 -0.550054 1.17487 - -1.18999 -0.510433 1.39795 - -1.1806 -0.397284 1.38786 - -1.26472 -0.352989 1.47517 - -1.29243 -0.262703 1.50372 - -1.29125 -0.246264 1.50244 - -1.32365 -0.211239 1.53603 - -1.99725 -0.283674 2.23647 - -1.9997 -0.246503 2.23892 - -0.274255 -0.00588753 0.444536 - -2.01228 0.114399 2.25095 - -2.0119 0.214471 2.25027 - -1.2237 0.289258 1.43068 - -1.23506 0.323272 1.44239 - -2.01983 0.770775 2.25691 - -2.01865 0.864941 2.25541 - -2.0215 1.10406 2.25768 - -2.02175 1.17665 2.25774 - -1.98733 1.19964 2.22189 - -1.17948 0.747478 1.38339 - -1.17368 0.761063 1.37732 - -1.172 0.821752 1.3754 - -1.12736 0.877683 1.32883 - -1.06473 0.870595 1.26375 - -1.02822 0.865277 1.22581 - -1.0088 0.95221 1.20537 - -0.991624 1.10285 1.18708 - -0.980072 1.15949 1.17491 - -0.974774 1.2588 1.16911 - -0.967324 1.28201 1.1613 - -0.924756 1.40692 1.11669 - -0.220717 0.418341 0.387657 - -0.140301 0.268943 0.304491 - -0.12726 0.276924 0.290912 - -0.148202 0.372297 0.312407 - -0.188295 0.624119 0.353359 - -0.201076 0.755315 0.366267 - -0.192973 0.752724 0.357851 - -0.0522841 0.223823 0.213123 - -0.0442776 0.162792 0.204976 - -0.03727 0.119595 0.197816 - -0.0344941 0.104835 0.194973 - -0.0336204 0.0978903 0.194085 - -0.0320057 0.0909703 0.192426 - -0.029906 0.0709967 0.190301 - -0.029443 0.0739876 0.189811 - -0.0255694 0.0786942 0.185771 - -0.0131274 0.137747 0.172666 - -0.0109102 0.138149 0.17036 --0.00924096 0.137635 0.168626 --0.00108738 0.163586 0.160076 - 0.0253146 0.191759 0.132548 - 0.0281584 0.1812 0.129622 - 0.031301 0.184578 0.126346 - 0.0325935 0.180315 0.125014 - 0.0460366 0.209661 0.110955 - 0.0620652 0.231131 0.0942304 - 0.0827709 0.249094 0.0726539 - 0.100978 0.225845 0.053794 - 0.0972601 0.202685 0.0577255 - 0.0504355 -0.12295 0.109064 - 0.0695196 -0.161748 0.0897453 - 0.0596572 -0.159189 0.099779 - 0.0355277 -0.140994 0.124294 - 0.0338507 -0.14136 0.126002 - 0.0279605 -0.135991 0.131984 - 0.0337139 -0.163619 0.126205 - 0.0332136 -0.164013 0.126715 - 0.0327121 -0.164403 0.127227 - 0.0289109 -0.159358 0.131083 - 0.0247186 -0.151189 0.135328 - 0.0228443 -0.149182 0.13723 - 0.0223881 -0.149508 0.137696 - 0.0216242 -0.152271 0.138481 - 0.0130606 -0.139172 0.147163 - 0.0175643 -0.180826 0.142696 - 0.00583672 -0.166434 0.154595 - 0.00532782 -0.166653 0.155114 - 0.00302101 -0.163448 0.157453 - 0.00194797 -0.160763 0.158538 --0.00583984 -0.164504 0.166478 - -0.0222197 -0.0923631 0.182948 - -0.0270785 -0.0708886 0.187834 - -0.0286678 -0.079982 0.189478 - -0.0304474 -0.0929957 0.191327 - -0.0354063 -0.129751 0.196481 - -0.038588 -0.150472 0.199779 - -0.081163 -0.369702 0.243751 - -0.105075 -0.388264 0.268149 - -0.106049 -0.368107 0.269084 - -0.107175 -0.367626 0.270228 - -0.121797 -0.376595 0.285141 - -0.130658 -0.380494 0.294173 - -0.158021 -0.375562 0.322018 - -0.169911 -0.380398 0.334138 - -0.174393 -0.380377 0.3387 - -0.174547 -0.376841 0.338847 - -0.214847 -0.373829 0.379869 - -0.252841 -0.369459 0.418538 - -0.254173 -0.365161 0.419882 - -0.31531 -0.421955 0.482289 - -0.306367 -0.367991 0.47303 - -0.309548 -0.368977 0.476271 - -0.369879 -0.362231 0.537676 - -0.374362 -0.363673 0.542245 - -0.396386 -0.362707 0.564665 - -0.512328 -0.369635 0.682727 - -0.92824 -0.550129 1.10669 - -0.989826 -0.538859 1.16936 - -1.09921 -0.531999 1.2807 - -1.11902 -0.526673 1.30086 - -1.18932 -0.481222 1.3723 - -1.18608 -0.472069 1.36898 - -1.18692 -0.456846 1.36978 - -1.18156 -0.431628 1.36425 - -1.29002 -0.21952 1.47408 - -2.01375 -0.295535 2.21113 - -2.05066 -0.19957 2.24844 - -2.05744 -0.174877 2.25527 - -0.275909 -0.002808 0.440978 - -0.278692 0.00645348 0.443785 - -0.310137 0.0125059 0.475783 - -2.02217 0.325939 2.21793 - -1.23415 0.235079 1.4159 - -2.07232 0.934695 2.26725 - -2.07152 1.10538 2.26595 - -2.03066 1.21334 2.22405 - -1.17677 0.861642 1.35569 - -1.16449 0.879623 1.34313 - -1.07393 0.86058 1.25099 - -1.01074 0.926612 1.18646 - -0.995469 1.0572 1.17055 - -0.99225 1.10199 1.16714 - -0.987499 1.12621 1.16224 - -0.973553 1.22266 1.14776 - -0.958776 1.35978 1.13233 - -0.961117 1.38718 1.13463 - -0.958807 1.39585 1.13226 - -0.94452 1.41084 1.11767 - -0.843155 1.39398 1.01451 - -0.818965 1.47899 0.989643 - -0.814443 1.48387 0.985024 - -0.251683 0.427077 0.415086 - -0.237499 0.41087 0.400691 - -0.220318 0.405953 0.383213 - -0.156677 0.400394 0.318435 - -0.248005 0.713697 0.410523 - -0.287627 0.896187 0.450342 - -0.227173 0.703311 0.389344 - -0.183992 0.750916 0.345244 - -0.18226 0.918052 0.343004 - -0.0511689 0.206858 0.211568 - -0.0418527 0.153097 0.202237 - -0.0321461 0.0859496 0.192546 - -0.0318387 0.0839625 0.192238 - -0.0304634 0.0709976 0.190875 - -0.0222758 0.0903134 0.182484 - -0.0203993 0.0980263 0.180552 --0.00264573 0.157159 0.162308 --0.00067326 0.159532 0.160293 - 0.00377034 0.174382 0.155726 - 0.0143309 0.189618 0.144931 - 0.0238077 0.181283 0.135306 - 0.0320511 0.19026 0.126888 - 0.040161 0.196839 0.118612 - 0.0664282 0.243599 0.0917358 - 0.0672493 0.229015 0.0909414 - 0.0692924 0.22486 0.0888732 - 0.071349 0.222981 0.0867847 - 0.0935325 0.229944 0.0641794 - 0.104536 0.22494 0.0529912 - 0.0592157 0.135384 0.0993878 - 0.0417725 -0.109927 0.119414 - 0.0439397 -0.115263 0.11727 - 0.0394343 -0.12579 0.121788 - 0.0368854 -0.122244 0.124317 - 0.0289793 -0.118018 0.132181 - 0.0294792 -0.122396 0.131695 - 0.0315458 -0.152375 0.129721 - 0.0317686 -0.154494 0.129505 - 0.0316352 -0.155745 0.129642 - 0.0162449 -0.179811 0.145041 - 0.0142449 -0.181855 0.147039 - 0.00592474 -0.163564 0.155276 - 0.00521406 -0.162822 0.155982 --0.00882447 -0.15021 0.169931 - -0.0115126 -0.147852 0.172602 - -0.0132656 -0.13711 0.174318 - -0.0177464 -0.114811 0.178719 - -0.0204315 -0.101194 0.181356 - -0.0245158 -0.0776778 0.185358 - -0.028687 -0.0719898 0.189497 - -0.0336794 -0.121855 0.194611 - -0.078997 -0.36935 0.240454 - -0.100248 -0.387185 0.261674 - -0.102641 -0.386294 0.264055 - -0.11187 -0.375237 0.273218 - -0.127435 -0.380474 0.288739 - -0.131116 -0.374261 0.292388 - -0.155023 -0.376124 0.316208 - -0.168661 -0.377723 0.329799 - -0.180997 -0.366974 0.342057 - -0.1876 -0.375397 0.348659 - -0.197177 -0.371763 0.358189 - -0.203315 -0.3709 0.364302 - -0.20564 -0.372317 0.366622 - -0.231149 -0.371082 0.39203 - -0.244914 -0.372261 0.405746 - -0.252464 -0.368567 0.413255 - -0.258667 -0.368917 0.419436 - -0.270122 -0.37727 0.430871 - -0.351838 -0.374955 0.512268 - -0.355249 -0.372223 0.515659 - -0.359256 -0.363517 0.519625 - -0.400654 -0.359853 0.560855 - -0.427405 -0.364499 0.587517 - -0.434847 -0.320119 0.594805 - -0.436455 -0.318102 0.596401 - -0.937415 -0.652359 1.09639 - -0.938295 -0.597494 1.09711 - -1.00999 -0.544347 1.16838 - -1.13235 -0.519882 1.29021 - -1.18111 -0.389139 1.33841 - -1.31061 -0.285117 1.46712 - -1.29447 -0.22586 1.45088 - -2.09366 -0.265616 2.24712 - -0.272612 0.00623533 0.432269 - -2.09414 0.26985 2.24609 - -2.08845 0.320328 2.24028 - -1.25048 0.205179 1.40584 - -1.22786 0.299382 1.38303 - -2.09692 0.64884 2.24779 - -2.10824 0.801744 2.25863 - -2.1131 0.900884 2.26319 - -2.11099 0.913997 2.26105 - -2.10529 0.939583 2.25531 - -2.11299 1.10108 2.26252 - -2.11628 1.19151 2.26554 - -1.16362 0.772735 1.3177 - -1.16975 0.829461 1.32366 - -1.17088 0.848121 1.32472 - -1.1344 0.873808 1.28832 - -1.02264 0.86769 1.177 - -0.999218 1.0313 1.1532 - -0.993105 1.09134 1.14694 - -0.98621 1.11284 1.14001 - -0.983315 1.11935 1.13711 - -0.981888 1.1681 1.13555 - -0.975709 1.18109 1.12936 - -0.970437 1.24868 1.12392 - -0.972945 1.27404 1.12635 - -0.948441 1.4143 1.10154 - -0.895414 1.40464 1.04874 - -0.846997 1.39825 1.00053 - -0.802917 1.39557 0.956624 - -0.278679 0.483237 0.436966 - -0.222786 0.411303 0.38149 - -0.140988 0.266357 0.300413 - -0.126694 0.268292 0.286169 - -0.195724 0.608863 0.353973 - -0.19569 0.624929 0.353894 - -0.17548 0.751716 0.333404 - -0.0598022 0.252519 0.219577 - -0.0530859 0.219585 0.21298 - -0.0432496 0.154851 0.203364 - -0.035798 0.10867 0.196071 - -0.0354087 0.107709 0.195686 - -0.0347235 0.100759 0.195023 - -0.0330955 0.0988892 0.193406 - -0.0282475 0.0789713 0.188633 - -0.0280034 0.0789612 0.18839 - -0.0240799 0.0826119 0.184471 - -0.010003 0.140232 0.170285 - 0.0232736 0.200393 0.136966 - 0.023893 0.200063 0.13635 - 0.0292608 0.185027 0.131045 - 0.0486787 0.212802 0.111623 - 0.0539435 0.2247 0.106345 - 0.0806811 0.231188 0.0796911 - 0.0817937 0.23133 0.0785824 - 0.0901155 0.226631 0.0703057 - 0.0962077 0.227605 0.0642341 - 0.102908 0.221201 0.0575772 - 0.102673 0.218861 0.0578181 - 0.0393725 -0.0951114 0.123167 - 0.0369596 -0.0983971 0.125531 - 0.0439608 -0.132119 0.118794 - 0.0309294 -0.11575 0.131463 - 0.0362236 -0.166644 0.12644 - 0.0279945 -0.156875 0.134442 - 0.0233478 -0.148934 0.138954 - 0.0210121 -0.150498 0.141237 - 0.0162054 -0.167435 0.145975 - 0.0163534 -0.174829 0.145851 - 0.00332794 -0.16385 0.15853 - 0.0002251 -0.171167 0.161578 - -0.0028408 -0.173158 0.164575 --0.00884998 -0.153408 0.170383 - -0.0225559 -0.0854955 0.183567 - -0.0228985 -0.0845406 0.183898 - -0.0263457 -0.0668779 0.187213 - -0.0270077 -0.0659261 0.187856 - -0.027522 -0.069959 0.188369 - -0.0386195 -0.150415 0.199422 - -0.0408781 -0.162168 0.201659 - -0.0544126 -0.251502 0.215114 - -0.110889 -0.380072 0.27058 - -0.116279 -0.380869 0.275841 - -0.132252 -0.370834 0.291399 - -0.164307 -0.374913 0.322688 - -0.173469 -0.371592 0.331618 - -0.202071 -0.368626 0.359519 - -0.234353 -0.367004 0.391013 - -0.244489 -0.374905 0.400925 - -0.256309 -0.371607 0.412449 - -0.327768 -0.420836 0.482313 - -0.311152 -0.36731 0.46595 - -0.336444 -0.369802 0.490635 - -0.353848 -0.367193 0.50761 - -0.374827 -0.360438 0.528061 - -0.391449 -0.360828 0.544281 - -0.406522 -0.362116 0.558992 - -0.412926 -0.361407 0.565239 - -0.44106 -0.355828 0.592675 - -0.442664 -0.336604 0.594186 - -0.437306 -0.325599 0.588927 - -0.966134 -0.609731 1.10572 - -0.964064 -0.594549 1.10366 - -0.964804 -0.547405 1.10425 - -1.02381 -0.532599 1.16178 - -1.07371 -0.537496 1.21048 - -1.10934 -0.526077 1.24522 - -1.18595 -0.477674 1.31983 - -1.18557 -0.446984 1.31938 - -1.18697 -0.439927 1.32072 - -1.2877 -0.261527 1.41851 - -1.29007 -0.238484 1.42077 - -2.14805 -0.269883 2.25802 - -2.13721 -0.165103 2.24715 - -2.13772 -0.15225 2.24761 - -0.274062 0.0077091 0.428711 - -2.14965 0.170359 2.25835 - -2.14654 0.313016 2.25492 - -1.26632 0.21343 1.39633 - -2.1454 0.616941 2.25295 - -2.14487 0.835467 2.25183 - -2.15065 0.879758 2.25734 - -2.15157 1.00826 2.25789 - -2.15102 1.18423 2.25685 - -2.15315 1.24581 2.25876 - -2.14135 1.28452 2.24714 - -1.16505 0.791813 1.2959 - -1.01733 0.888198 1.15149 - -1.00987 0.932997 1.14409 - -0.997076 1.07544 1.1312 - -0.988908 1.11487 1.12312 - -0.983565 1.12845 1.11787 - -0.985182 1.15048 1.11939 - -0.982669 1.1576 1.11692 - -0.958532 1.35537 1.09281 - -0.947324 1.41104 1.08172 - -0.867874 1.39505 1.00424 - -0.183716 0.351443 0.339596 - -0.123165 0.271205 0.280738 - -0.213695 0.725076 0.367804 - -0.20719 0.773524 0.361322 - -0.183672 0.748977 0.338443 - -0.178414 0.747926 0.333316 - -0.166486 0.9798 0.321029 - -0.0583667 0.240682 0.217597 - -0.0447014 0.161621 0.204484 - -0.0340051 0.0977946 0.194226 - -0.0336997 0.0978213 0.193928 - -0.023904 0.0836418 0.184409 - -0.0202617 0.0971521 0.180818 - -0.0179765 0.113869 0.178541 - -0.0161543 0.120566 0.176744 - -0.0126698 0.132932 0.17331 --0.00907103 0.143174 0.16977 - -0.0081772 0.142919 0.168898 --0.00529472 0.149203 0.166068 --0.00241821 0.154416 0.163247 - 0.00393903 0.165508 0.157013 - 0.00964306 0.178789 0.15141 - 0.0209053 0.198846 0.140365 - 0.022134 0.192902 0.139183 - 0.0287254 0.187021 0.132768 - 0.0315215 0.17865 0.130063 - 0.0651885 0.238674 0.0970449 - 0.0674188 0.236919 0.0948735 - 0.0572198 0.203591 0.104918 - 0.0534409 0.192778 0.108636 - 0.0696011 0.215205 0.0928048 - 0.0916202 0.243906 0.0712396 - 0.0945649 0.238533 0.0683814 - 0.0937994 0.230635 0.0691504 - 0.0976928 0.231529 0.0653489 - 0.101624 0.23232 0.0615108 - 0.105142 0.232229 0.0580785 - 0.0953962 0.200626 0.0676761 - 0.0460928 0.112092 0.116031 - 0.0371456 -0.0980676 0.126692 - 0.0368362 -0.0984651 0.126989 - 0.0386975 -0.109566 0.125241 - 0.0287816 -0.115088 0.13473 - 0.028194 -0.125225 0.13532 - 0.0190812 -0.142338 0.144074 - 0.0164268 -0.169858 0.146686 - 0.00665342 -0.165911 0.156013 - 0.00552052 -0.163243 0.157088 --0.00569587 -0.164936 0.16781 - -0.0229002 -0.0795676 0.184011 - -0.0235427 -0.0776462 0.18462 - -0.0314523 -0.0999363 0.192239 - -0.0502448 -0.225036 0.21054 - -0.0571068 -0.270146 0.217221 - -0.0777983 -0.357562 0.237232 - -0.0945172 -0.379157 0.253266 - -0.110086 -0.368095 0.26811 - -0.11598 -0.37706 0.273767 - -0.120915 -0.381133 0.278493 - -0.146611 -0.374958 0.303027 - -0.151628 -0.37296 0.307815 - -0.252711 -0.369007 0.404383 - -0.273497 -0.375784 0.424262 - -0.317329 -0.43544 0.466306 - -0.323228 -0.363275 0.471743 - -0.386718 -0.362704 0.532402 - -0.393103 -0.362452 0.538502 - -0.408318 -0.363846 0.553043 - -0.415332 -0.36029 0.559734 - -0.461202 -0.320949 0.603452 - -0.978704 -0.550107 1.09853 - -1.18565 -0.472858 1.29605 - -1.18654 -0.420456 1.29674 - -1.18576 -0.412714 1.29598 - -1.32688 -0.331457 1.43059 - -1.2919 -0.220967 1.39686 - -0.269767 0.00460075 0.419646 - -2.18891 0.664257 2.25145 - -2.18608 0.690741 2.24868 - -2.19509 0.762788 2.25709 - -2.18939 0.816513 2.2515 - -2.18994 0.872997 2.25187 - -2.19422 0.989265 2.25563 - -2.19917 1.19908 2.25978 - -2.18454 1.34439 2.2454 - -1.16713 0.751522 1.27497 - -1.16476 0.758377 1.27268 - -1.17395 0.869332 1.28115 - -1.14802 0.876158 1.25636 - -1.00282 0.996709 1.11729 - -1.00139 1.02271 1.11586 - -0.992992 1.08922 1.10765 - -0.991788 1.09756 1.10647 - -0.990733 1.12586 1.10539 - -0.970633 1.22468 1.08591 - -0.967137 1.27449 1.08243 - -0.903824 1.40313 1.02158 - -0.868421 1.39475 0.987781 - -0.851356 1.39086 0.971488 - -0.843777 1.39035 0.964248 - -0.696718 1.35462 0.82384 - -0.246512 0.44541 0.396208 - -0.224606 0.428133 0.375326 - -0.200102 0.385564 0.352031 - -0.134136 0.272936 0.289316 - -0.123397 0.282526 0.279029 - -0.224057 0.665912 0.374143 - -0.215571 0.679094 0.365999 - -0.211324 0.77339 0.361681 - -0.183476 0.767203 0.33509 - -0.179893 0.936417 0.331199 - -0.0611192 0.250173 0.219615 - -0.0521793 0.20659 0.211194 - -0.0411715 0.146067 0.200844 - -0.0407106 0.146138 0.200404 - -0.0359763 0.108592 0.195984 - -0.0349481 0.108706 0.195001 - -0.0325358 0.0908785 0.192746 - -0.0304982 0.0749756 0.190843 - -0.0251605 0.0828182 0.185722 - -0.0236594 0.0816504 0.184291 --0.00659115 0.146699 0.167803 --0.00504538 0.147252 0.166324 - 0.00479588 0.16647 0.156869 - 0.0179132 0.19749 0.14425 - 0.0185362 0.197203 0.143655 - 0.0256139 0.182873 0.136933 - 0.031999 0.187761 0.130819 - 0.033438 0.183541 0.129455 - 0.0332742 0.176999 0.12963 - 0.0645484 0.241269 0.0995713 - 0.0558429 0.197578 0.10801 - 0.0911797 0.242172 0.0741241 - 0.0940007 0.245548 0.0714195 - 0.102103 0.232331 0.0637143 - 0.102293 0.224463 0.0635545 - 0.036528 -0.0921399 0.12885 - 0.038704 -0.100336 0.126846 - 0.0325587 -0.0944289 0.132552 - 0.0281082 -0.0891118 0.136681 - 0.0371946 -0.106154 0.128267 - 0.0365152 -0.106933 0.128902 - 0.0427671 -0.127007 0.123135 - 0.0274313 -0.111312 0.137372 - 0.0250129 -0.10751 0.139614 - 0.0288887 -0.124379 0.136051 - 0.0328357 -0.162751 0.132481 - 0.0183875 -0.142281 0.145878 - 0.0178294 -0.173889 0.146484 - 0.00211365 -0.161711 0.161085 --0.00216243 -0.159007 0.165059 - -0.0231306 -0.0806654 0.18437 - -0.0252088 -0.0748633 0.186289 - -0.0268022 -0.0689596 0.187757 - -0.0301247 -0.0819702 0.190886 - -0.037349 -0.145489 0.197787 - -0.0865878 -0.374572 0.244262 - -0.107787 -0.378657 0.264012 - -0.117551 -0.380869 0.273111 - -0.14265 -0.372455 0.296459 - -0.154546 -0.374029 0.30754 - -0.170917 -0.374176 0.322785 - -0.186025 -0.3731 0.33685 - -0.241532 -0.366048 0.388516 - -0.257886 -0.367047 0.403747 - -0.278055 -0.378755 0.42256 - -0.321742 -0.370333 0.463216 - -0.369146 -0.357004 0.50732 - -0.437024 -0.3588 0.570531 - -0.476547 -0.32176 0.607231 - -1.07014 -0.53128 1.16054 - -1.18412 -0.429434 1.26638 - -2.24733 -0.289743 2.25602 - -2.24048 -0.19591 2.24939 - -0.26574 0.00164911 0.410053 - -0.303711 0.0101156 0.445387 - -2.24451 0.121157 2.25228 - -2.24532 0.227267 2.25274 - -2.24516 0.320489 2.25234 - -2.25381 1.15365 2.25811 - -2.24518 1.31847 2.24963 - -1.22117 0.760627 1.29763 - -1.17399 0.747211 1.25374 - -1.16919 0.760827 1.24923 - -1.12495 0.874126 1.20773 - -1.04996 0.864002 1.13793 - -1.00718 0.936472 1.09789 - -1.00754 0.97199 1.09814 - -0.986493 1.12761 1.07811 - -0.983444 1.13396 1.07526 - -0.964467 1.33513 1.05703 - -0.954837 1.40472 1.04788 - -0.906237 1.40306 1.00263 - -0.750973 1.38227 0.858109 - -0.734141 1.37523 0.842455 - -0.726406 1.37284 0.835259 - -0.242242 0.448899 0.386951 - -0.132593 0.272415 0.285332 - -0.129977 0.274244 0.282891 - -0.12621 0.278995 0.27937 - -0.123839 0.281618 0.277155 - -0.213198 0.700416 0.359218 - -0.221059 0.761331 0.366372 - -0.170062 0.944785 0.318384 - -0.0443451 0.156572 0.203476 - -0.0321046 0.0888812 0.192263 - -0.0314387 0.0859207 0.191651 - -0.0286859 0.0769998 0.189112 - -0.0265956 0.0819478 0.187152 - -0.0250701 0.0808451 0.185734 - -0.024812 0.0808225 0.185494 - -0.0204039 0.0922984 0.181358 - -0.0193245 0.0941227 0.180348 - -0.0136691 0.12632 0.174994 - -0.0045159 0.146277 0.166416 - 0.00415835 0.164946 0.158288 - 0.00604847 0.171491 0.15651 - 0.00989118 0.178302 0.152914 - 0.0184284 0.195591 0.144917 - 0.0275996 0.200663 0.136363 - 0.0325011 0.192521 0.131821 - 0.0367403 0.198699 0.127857 - 0.0373747 0.198305 0.127267 - 0.0619489 0.214684 0.10434 - 0.0526763 0.181531 0.113065 - 0.0959876 0.252732 0.0725406 - 0.0973967 0.212812 0.0713377 - 0.0624848 0.143304 0.104036 - 0.0575249 0.131966 0.108686 - 0.0388484 -0.0999952 0.128 - 0.0287695 -0.107184 0.137211 - 0.0288882 -0.1168 0.137129 - 0.0317338 -0.128609 0.134566 - 0.02999 -0.145062 0.136201 - 0.0143596 -0.130931 0.150417 - 0.0127754 -0.137263 0.151879 - 0.0123281 -0.142877 0.152302 - 0.0152968 -0.16167 0.149645 - 0.0165286 -0.168514 0.14854 - 0.0139525 -0.172886 0.150902 --0.00313123 -0.159462 0.166445 - -0.0162296 -0.111842 0.178261 - -0.0190841 -0.0972252 0.180825 - -0.0219017 -0.0815568 0.183352 - -0.0222395 -0.0805982 0.183657 - -0.0274939 -0.076994 0.188439 - -0.0277567 -0.0749974 0.188674 - -0.0368748 -0.141503 0.197169 - -0.0832446 -0.367417 0.240067 - -0.098488 -0.368794 0.253972 - -0.104618 -0.367582 0.25956 - -0.115851 -0.371347 0.269814 - -0.130293 -0.375175 0.282995 - -0.133652 -0.372394 0.28605 - -0.164821 -0.371262 0.314472 - -0.194742 -0.371722 0.341759 - -0.214241 -0.366552 0.359527 - -0.224423 -0.369072 0.36882 - -0.331839 -0.379829 0.466807 - -0.329797 -0.373979 0.46493 - -0.352951 -0.365439 0.486021 - -0.356443 -0.362849 0.489199 - -0.382069 -0.36074 0.512563 - -0.406903 -0.358685 0.535205 - -0.42789 -0.357813 0.554342 - -0.441175 -0.355823 0.566452 - -0.467385 -0.319058 0.590255 - -0.468413 -0.31646 0.591185 - -0.475968 -0.318505 0.598081 - -0.479982 -0.314572 0.60173 - -1.02614 -0.643492 1.10069 - -1.03949 -0.531425 1.11257 - -1.07086 -0.526736 1.14116 - -1.16345 -0.520579 1.22558 - -1.19817 -0.505837 1.2572 - -1.22982 -0.359406 1.28566 - -1.28803 -0.245998 1.33845 - -2.28035 -0.345092 2.24367 - -2.28146 -0.331787 2.24464 - -2.28208 -0.197721 2.24484 - -2.2878 0.162474 2.24909 - -2.28671 0.189151 2.24801 - -1.21244 0.283689 1.26807 - -1.21589 0.313521 1.27114 - -2.28673 0.665698 2.24675 - -2.28849 0.736406 2.24816 - -2.28391 1.23504 2.24264 - -2.29098 1.34901 2.24877 - -1.17226 0.7475 1.23018 - -1.16496 0.767683 1.22347 - -1.03044 0.864423 1.10053 - -0.999467 1.04553 1.07179 - -0.992145 1.07528 1.06504 - -0.989245 1.08159 1.06238 - -0.963592 1.27641 1.03845 - -0.965063 1.31227 1.0397 - -0.961673 1.33053 1.03656 - -0.84093 1.39395 0.926274 - -0.245836 0.461548 0.3861 - -0.222067 0.427362 0.364516 - -0.139718 0.268838 0.289846 - -0.128852 0.275438 0.27992 - -0.22841 0.668694 0.369647 - -0.215247 0.776244 0.357351 - -0.0509968 0.192621 0.209143 - -0.039533 0.132156 0.198852 - -0.0318878 0.0838682 0.192011 - -0.0260734 0.0789367 0.186722 - -0.0258818 0.0769241 0.186552 - -0.0229595 0.0836748 0.183869 - -0.019783 0.0983051 0.180933 - -0.0131493 0.13036 0.174796 - 0.0297594 0.199982 0.135477 - 0.0315946 0.191406 0.133827 - 0.0627418 0.232125 0.105312 - 0.097099 0.256713 0.0739131 - 0.102025 0.264278 0.0694006 - 0.111676 0.275944 0.0605675 - 0.108338 0.257134 0.063663 - 0.0641815 0.150602 0.10422 - 0.0406679 -0.0919905 0.127629 - 0.0400675 -0.0927885 0.128167 - 0.0356891 -0.0914809 0.132073 - 0.0333117 -0.099599 0.134218 - 0.027528 -0.109164 0.139408 - 0.02668 -0.118252 0.140189 - 0.029028 -0.124541 0.13811 - 0.0344955 -0.160609 0.133324 - 0.03173 -0.160251 0.135793 - 0.0312084 -0.160597 0.136259 - 0.0107924 -0.133314 0.154415 - 0.0138839 -0.172181 0.151759 - 0.0133235 -0.172423 0.15226 - 0.0127622 -0.172662 0.152762 - 0.00259408 -0.157837 0.161801 - -0.0126633 -0.132455 0.175356 - -0.021578 -0.0775424 0.183169 - -0.0241702 -0.0718281 0.185468 - -0.0266255 -0.0789823 0.187679 - -0.0279125 -0.0769998 0.188823 - -0.0284081 -0.0759964 0.189263 - -0.0288905 -0.0749875 0.189691 - -0.0350751 -0.122614 0.195341 - -0.0668074 -0.321722 0.224208 - -0.0742898 -0.345352 0.230952 - -0.0788889 -0.361491 0.235102 - -0.0940256 -0.370408 0.248641 - -0.0980038 -0.371146 0.252195 - -0.107454 -0.372891 0.260638 - -0.108667 -0.37242 0.26172 - -0.11382 -0.377656 0.266335 - -0.116276 -0.376631 0.268525 - -0.127495 -0.372608 0.278532 - -0.155734 -0.380991 0.303768 - -0.167466 -0.375735 0.314229 - -0.199165 -0.374994 0.342531 - -0.207637 -0.36779 0.350076 - -0.235661 -0.363152 0.375086 - -0.310861 -0.414073 0.442368 - -0.33688 -0.376223 0.465498 - -0.369191 -0.363838 0.494314 - -0.376843 -0.358828 0.501133 - -0.435662 -0.358186 0.55365 - -0.478596 -0.317575 0.591877 - -1.04626 -0.635892 1.09959 - -1.0451 -0.578071 1.0984 - -1.08467 -0.528833 1.1336 - -1.15955 -0.521433 1.20044 - -1.16548 -0.516729 1.20572 - -1.18343 -0.517349 1.22174 - -1.19002 -0.49022 1.22756 - -1.279 -0.355349 1.30665 - -1.31887 -0.311744 1.34213 - -1.32123 -0.211645 1.34397 - -2.33003 -0.200049 2.24468 - -0.271868 -0.00404273 0.406451 - -2.32549 0.298784 2.23928 - -1.2447 0.2159 1.27449 - -1.2403 0.222336 1.27054 - -1.22971 0.263502 1.26097 - -2.33463 0.874111 2.2459 - -2.32735 1.06326 2.2389 - -2.32952 1.07934 2.24079 - -2.32611 1.34123 2.23704 - -2.3446 1.38434 2.25344 - -1.17635 0.751608 1.21203 - -1.16428 0.768522 1.2012 - -1.17019 0.858152 1.20624 - -1.01185 0.92384 1.06468 - -1.01067 0.939951 1.06359 - -1.00312 0.967534 1.05677 - -0.958464 1.33709 1.01591 - -0.957659 1.34765 1.01516 - -0.957402 1.37104 1.01487 - -0.754468 1.37674 0.833656 - -0.734633 1.37697 0.815945 - -0.716463 1.36692 0.799748 - -0.143672 0.27099 0.29125 - -0.139051 0.271016 0.287124 - -0.139239 0.274298 0.287283 - -0.140382 0.28596 0.288272 - -0.233276 0.671215 0.370183 - -0.209035 0.683589 0.348506 - -0.188055 0.771058 0.329538 - -0.0476269 0.175074 0.20575 - -0.0432806 0.149635 0.201938 - -0.0378125 0.119296 0.197137 - -0.0373454 0.118357 0.196722 - -0.0323359 0.0878156 0.192331 - -0.0300119 0.0759555 0.190288 - -0.0291195 0.0829882 0.189472 - -0.0267812 0.0769803 0.1874 --0.00791157 0.142435 0.170376 --0.00419317 0.144468 0.167051 - 0.0115019 0.17926 0.152944 - 0.0216578 0.193782 0.143837 - 0.0320316 0.197081 0.134565 - 0.0370206 0.180976 0.130154 - 0.0687591 0.234303 0.101672 - 0.0581698 0.190561 0.111244 - 0.0798249 0.220674 0.0918282 - 0.106128 0.266819 0.0682192 - 0.108622 0.252279 0.0660308 - 0.0926139 0.214715 0.0804251 - 0.0592247 0.143177 0.11043 - 0.0307366 0.0837052 0.136026 - 0.032878 -0.0892355 0.135709 - 0.0282948 -0.0839368 0.139701 - 0.0254893 -0.0870914 0.142162 - 0.0252031 -0.0873978 0.142413 - 0.0350569 -0.111434 0.133863 - 0.0317191 -0.11461 0.136789 - 0.0326514 -0.11861 0.135985 - 0.0310855 -0.119986 0.137357 - 0.0298114 -0.128107 0.138493 - 0.0289684 -0.128766 0.139232 - 0.0364548 -0.159875 0.13277 - 0.0252902 -0.150498 0.142505 - 0.0149544 -0.176234 0.151609 - 0.0111932 -0.173583 0.15489 - 0.00773821 -0.171766 0.157905 - 0.00289835 -0.162068 0.162111 --0.00547712 -0.154266 0.169412 --0.00853285 -0.146866 0.172063 - -0.0189467 -0.0933074 0.181025 - -0.0225316 -0.0767117 0.184115 - -0.022973 -0.0737501 0.184493 - -0.0237 -0.0738233 0.185129 - -0.0251561 -0.0739318 0.186402 - -0.025308 -0.0769427 0.186543 - -0.0275862 -0.0739998 0.188526 - -0.0283337 -0.0759926 0.189185 - -0.0288329 -0.0759805 0.189621 - -0.0293765 -0.0779617 0.190102 - -0.0763537 -0.350974 0.231895 - -0.101245 -0.379442 0.253731 - -0.113058 -0.378157 0.264054 - -0.147012 -0.378908 0.293739 - -0.154434 -0.378998 0.300227 - -0.171708 -0.380269 0.315332 - -0.178093 -0.37247 0.320892 - -0.232324 -0.364372 0.36828 - -0.236078 -0.364367 0.371562 - -0.279027 -0.380939 0.409152 - -0.329802 -0.419401 0.453642 - -0.334443 -0.414814 0.457687 - -0.354989 -0.361605 0.475507 - -0.36847 -0.366564 0.487305 - -0.39293 -0.362231 0.508677 - -0.406768 -0.359088 0.520766 - -0.409735 -0.355248 0.523349 - -0.486066 -0.344253 0.590049 - -0.497024 -0.310546 0.599539 - -1.06918 -0.622464 1.10055 - -1.11321 -0.523952 1.13877 - -1.15667 -0.522787 1.17677 - -1.18233 -0.446051 1.19899 - -1.17864 -0.380157 1.19559 - -1.30936 -0.299 1.30965 - -1.28671 -0.218982 1.28964 - -2.3777 -0.353416 2.24374 - -2.38194 -0.202701 2.24705 - -0.274522 -0.00691701 0.40422 - -2.37402 0.151956 2.23919 - -2.37823 0.179546 2.24279 - -2.377 0.206782 2.24164 - -1.2326 0.240318 1.24112 - -2.37368 0.678684 2.23749 - -2.37058 0.763567 2.23455 - -2.3724 0.998861 2.23552 - -2.37474 1.19849 2.23704 - -1.17925 0.746778 1.19313 - -1.10641 0.869984 1.12913 - -0.987975 1.0894 1.02501 - -0.978364 1.17736 1.01637 - -0.972079 1.23241 1.01073 - -0.966374 1.2795 1.00562 - -0.957652 1.37125 0.997753 - -0.881084 1.39891 0.930744 - -0.803454 1.39142 0.862899 - -0.795761 1.39024 0.856177 - -0.673421 1.37106 0.749279 - -0.186895 0.351591 0.326664 - -0.1453 0.270313 0.290517 - -0.131758 0.270966 0.278677 - -0.128336 0.279898 0.275662 - -0.126508 0.290947 0.274035 - -0.230148 0.681259 0.3636 - -0.221609 0.669562 0.356166 - -0.0606149 0.235029 0.216579 - -0.042475 0.143689 0.200964 - -0.0367103 0.11841 0.195991 - -0.0287141 0.0769891 0.189111 - -0.0268981 0.081992 0.18751 - -0.0210728 0.0875506 0.182403 - -0.0193632 0.0903134 0.180901 --0.00983623 0.134901 0.172454 - -0.0093931 0.134796 0.172067 - 0.0227833 0.197859 0.143771 - 0.0246159 0.193831 0.14218 - 0.0338608 0.19765 0.134087 - 0.0380023 0.198559 0.130465 - 0.0386544 0.198175 0.129896 - 0.0415197 0.188679 0.127416 - 0.0793049 0.186957 0.0943886 - 0.075007 0.176224 0.0981743 - 0.0580337 -0.111316 0.115357 - 0.0526565 -0.107064 0.119947 - 0.0422177 -0.0939018 0.128845 - 0.0343575 -0.088532 0.135556 - 0.03368 -0.0906817 0.136142 - 0.0327743 -0.0917225 0.13692 - 0.0305778 -0.0915473 0.138799 - 0.0383763 -0.117803 0.132195 - 0.0354887 -0.116839 0.134663 - 0.0338452 -0.11591 0.136067 - 0.0259764 -0.114304 0.142796 - 0.0279053 -0.124445 0.141172 - 0.0248226 -0.146871 0.143869 - 0.0174851 -0.136942 0.150121 - 0.0125675 -0.123385 0.154294 - 0.0117484 -0.123837 0.154996 - 0.00891167 -0.168464 0.15754 --0.00227752 -0.15765 0.167086 --0.00573079 -0.152425 0.170028 --0.00936742 -0.144118 0.173117 - -0.0114 -0.131377 0.174823 - -0.0198786 -0.0884779 0.181965 - -0.0231988 -0.0718057 0.184762 - -0.0280148 -0.0769925 0.188897 - -0.0287997 -0.0779716 0.189571 - -0.030306 -0.0839002 0.190876 - -0.0347828 -0.126601 0.194819 - -0.0353891 -0.129545 0.195345 - -0.0402884 -0.164083 0.199629 - -0.0600373 -0.281651 0.216837 - -0.0660778 -0.306697 0.222072 - -0.0928591 -0.367874 0.245149 - -0.0952968 -0.367101 0.247233 - -0.102469 -0.377075 0.253396 - -0.120539 -0.373142 0.268848 - -0.127451 -0.383784 0.274791 - -0.153116 -0.372605 0.296723 - -0.161887 -0.380519 0.304248 - -0.168738 -0.373946 0.310094 - -0.172449 -0.371469 0.313262 - -0.197345 -0.365619 0.33455 - -0.233427 -0.363571 0.36542 - -0.282016 -0.382442 0.407046 - -0.33641 -0.414102 0.453674 - -1.32221 -1.60346 1.30034 - -0.3349 -0.358182 0.452234 - -0.397166 -0.360108 0.505519 - -0.458112 -0.354103 0.557654 - -1.08448 -0.597024 1.09427 - -1.09195 -0.544087 1.10052 - -1.19179 -0.49702 1.18583 - -1.2942 -0.353277 1.27308 - -1.31159 -0.304478 1.28783 - -1.30886 -0.296233 1.28547 - -1.28712 -0.261448 1.26678 - -1.28287 -0.238431 1.26308 - -2.42027 -0.287131 2.23647 - -2.41768 0.291339 2.23272 - -2.42134 0.729554 2.23471 - -2.42351 0.921247 2.23606 - -2.42552 0.982064 2.23761 - -2.42226 0.995819 2.23479 - -2.42427 1.02699 2.23643 - -2.42317 1.22805 2.23496 - -2.43121 1.26404 2.24174 - -1.16013 0.776819 1.15538 - -1.12313 0.875697 1.12346 - -1.01167 0.976481 1.02782 - -0.96874 1.2605 0.99034 - -0.953195 1.37671 0.976733 - -0.764855 1.38507 0.815551 - -0.748327 1.37945 0.801424 - -0.679058 1.35801 0.742207 - -0.150985 0.281576 0.293177 - -0.233064 0.677297 0.362369 - -0.216631 0.6738 0.348317 - -0.207171 0.676138 0.340216 - -0.208355 0.765142 0.340995 - -0.0374055 0.12029 0.196413 - -0.0331262 0.101725 0.1928 - -0.0303572 0.0819082 0.190483 - -0.0296 0.0749442 0.189854 - -0.0238731 0.0878759 0.184919 - -0.0224206 0.0827392 0.18369 - -0.0218722 0.0826787 0.183221 - 0.00783752 0.164546 0.157583 - 0.0185732 0.186363 0.148339 - 0.0249003 0.197264 0.142897 - 0.0370801 0.195272 0.13248 - 0.0346731 0.183563 0.13457 - 0.0595367 0.219895 0.113199 - 0.097874 0.224878 0.0803813 - 0.0342923 0.0869719 0.13515 - 0.0563671 -0.110633 0.118248 - 0.0320083 -0.109822 0.138661 - 0.022704 -0.10464 0.146445 - 0.0224418 -0.107192 0.146671 - 0.0291521 -0.133315 0.141116 - 0.0284033 -0.149568 0.141786 - 0.0135703 -0.175273 0.154284 - 0.0020673 -0.166811 0.163903 --0.00434729 -0.151192 0.169238 - -0.0225965 -0.071782 0.184325 - -0.0277041 -0.0779924 0.188622 - -0.029562 -0.0789221 0.190182 - -0.0311226 -0.0968398 0.191536 - -0.0437559 -0.19373 0.202377 - -0.0490442 -0.213015 0.20686 - -0.0590594 -0.281838 0.215433 - -0.0602335 -0.283627 0.216422 - -0.0633271 -0.30121 0.21906 - -0.0980912 -0.373495 0.248384 - -0.105326 -0.376192 0.254455 - -0.114769 -0.375743 0.262367 - -0.162382 -0.375219 0.302271 - -0.164295 -0.376247 0.303877 - -0.18648 -0.375934 0.322469 - -0.196777 -0.37282 0.331091 - -0.207882 -0.374485 0.340402 - -0.211627 -0.371355 0.343533 - -0.225409 -0.370068 0.35508 - -0.22788 -0.367789 0.357145 - -0.242733 -0.367117 0.369591 - -0.246126 -0.366216 0.372432 - -0.28055 -0.387565 0.401339 - -0.307905 -0.393201 0.424279 - -0.311506 -0.343202 0.427168 - -0.360722 -0.368619 0.468481 - -0.39336 -0.360139 0.495813 - -0.399454 -0.359514 0.500919 - -0.409205 -0.355608 0.509081 - -0.442844 -0.362392 0.537291 - -1.1176 -0.559711 1.10332 - -1.19652 -0.494862 1.16929 - -1.25685 -0.35466 1.21949 - -1.28793 -0.259424 1.24529 - -2.46704 -0.17848 2.23328 - -0.265336 0.00022596 0.387577 - -0.265335 0.00158294 0.387572 - -2.46122 0.140973 2.22757 - -2.47622 0.828573 2.23835 - -2.472 0.931907 2.23454 - -2.47276 0.977668 2.23506 - -2.47149 1.37207 2.23297 - -1.19677 0.75344 1.16624 - -1.16307 0.788848 1.13791 - -1.17323 0.864084 1.14622 - -1.13167 0.875178 1.11136 - -0.991434 1.09391 0.993262 - -0.981864 1.17188 0.985038 - -0.960223 1.31679 0.966522 - -0.9581 1.33697 0.96469 - -0.957821 1.3602 0.964396 - -0.939673 1.40597 0.949067 - -0.852427 1.40263 0.875955 - -0.841231 1.39616 0.866589 - -0.799681 1.38657 0.831791 - -0.765406 1.38764 0.803062 - -0.740279 1.37853 0.782027 - -0.689286 1.36817 0.739317 - -0.155374 0.286914 0.294669 - -0.153071 0.287492 0.292738 - -0.144548 0.270791 0.285639 - -0.138907 0.27142 0.280909 - -0.135044 0.276314 0.277658 - -0.243376 0.663887 0.36744 - -0.216604 0.669108 0.344989 - -0.212125 0.671232 0.341229 - -0.200009 0.725022 0.330935 - -0.217898 1.09646 0.344958 - -0.186903 0.998775 0.319236 - -0.0537122 0.191913 0.209715 - -0.0433819 0.134341 0.201208 - -0.0347723 0.109546 0.194057 - -0.0315844 0.0847971 0.191449 - -0.0285792 0.0769749 0.188951 - -0.0228781 0.0828182 0.184158 - -0.0215827 0.0856993 0.183065 - -0.0219119 0.0726887 0.183375 - -0.0106271 0.128201 0.173772 - 0.0277818 0.199477 0.141396 - 0.0302839 0.195063 0.13931 - 0.0335951 0.191185 0.136545 - 0.0348257 0.192681 0.13551 - 0.0376707 0.1812 0.133156 - 0.0728412 0.232861 0.103544 - 0.0724894 0.229679 0.103848 - 0.0731265 0.217625 0.103345 - 0.075045 0.219615 0.101732 - 0.0757792 0.21903 0.101118 - 0.112912 0.27342 0.0698559 - 0.0466175 0.100339 0.125868 - 0.0438701 -0.0969393 0.129918 - 0.0306873 -0.093184 0.140726 - 0.0310796 -0.113789 0.140458 - 0.0295791 -0.120913 0.141707 - 0.0240529 -0.116962 0.146232 - 0.0308438 -0.157429 0.140764 - 0.0117863 -0.121282 0.15631 - 0.00942073 -0.118197 0.158243 - 0.011645 -0.139547 0.156473 - 0.0140069 -0.16385 0.154598 - 0.00648105 -0.159408 0.160762 - 0.00469457 -0.168249 0.162251 --0.00590625 -0.147625 0.170897 - -0.0175325 -0.0952927 0.180303 - -0.0212147 -0.0756861 0.183273 - -0.0215312 -0.0787333 0.183541 - -0.0224915 -0.0808302 0.184335 - -0.0227163 -0.0818505 0.184522 - -0.0253086 -0.0759829 0.186634 - -0.0265859 -0.0819998 0.187698 - -0.0271391 -0.0819962 0.188152 - -0.0273874 -0.0789923 0.188348 - -0.0284302 -0.0779617 0.189201 - -0.0309207 -0.0918241 0.19128 - -0.0327549 -0.107697 0.192827 - -0.033238 -0.109654 0.193228 - -0.0401008 -0.167067 0.199008 - -0.0697451 -0.326178 0.223747 - -0.115487 -0.382944 0.261431 - -0.125791 -0.373386 0.269862 - -0.147748 -0.374299 0.287884 - -0.153722 -0.369865 0.292775 - -0.171124 -0.371342 0.307059 - -0.172376 -0.370521 0.308084 - -0.190652 -0.367906 0.323076 - -0.217099 -0.372567 0.344791 - -0.232216 -0.36629 0.357181 - -0.316263 -0.423635 0.4263 - -0.31498 -0.414403 0.425224 - -1.32016 -1.68831 1.2534 - -1.32585 -1.68098 1.25805 - -0.314217 -0.334963 0.424392 - -0.374246 -0.36083 0.473721 - -0.411545 -0.355027 0.504315 - -0.414634 -0.354579 0.506849 - -0.468787 -0.353725 0.551286 - -0.48161 -0.353402 0.561808 - -0.520533 -0.328746 0.593686 - -0.512433 -0.309587 0.58699 - -0.527038 -0.311895 0.59898 - -0.55047 -0.315625 0.61822 - -1.13494 -0.6226 1.09865 - -1.14021 -0.588508 1.10289 - -1.14219 -0.582212 1.1045 - -1.17864 -0.519497 1.13425 - -1.18895 -0.502151 1.14266 - -1.187 -0.4508 1.14093 - -1.18183 -0.427529 1.13663 - -1.27361 -0.349132 1.21174 - -0.266283 0.00022523 0.384188 - -0.266281 0.00157785 0.384184 - -2.5101 0.128554 2.22521 - -2.51809 0.185345 2.23162 - -2.51746 0.199405 2.23107 - -2.5177 0.820552 2.22966 - -2.52389 0.943689 2.23442 - -2.52467 1.1463 2.23453 - -2.52669 1.19507 2.23607 - -2.5269 1.29226 2.23599 - -2.52913 1.39264 2.23756 - -2.52696 1.45875 2.2356 - -2.53635 1.53288 2.24311 - -1.20233 0.750782 1.1504 - -1.04674 0.865615 1.02242 - -1.00504 0.989053 0.987876 - -0.99024 1.10284 0.97544 - -0.978833 1.13856 0.965986 - -0.971509 1.22206 0.95976 - -0.969341 1.25155 0.957905 - -0.960822 1.28426 0.950829 - -0.959509 1.32808 0.949638 - -0.839438 1.39438 0.850932 - -0.766103 1.37777 0.790794 - -0.627121 1.25398 0.677061 - -0.130311 0.268577 0.271911 - -0.123971 0.275809 0.26669 - -0.24398 0.661125 0.364176 - -0.229406 0.673098 0.352185 - -0.211879 0.675103 0.337797 - -0.206033 0.681956 0.332981 - -0.199121 0.684921 0.327302 - -0.19358 0.763382 0.322551 - -0.225144 1.10804 0.347562 - -0.171282 0.958201 0.303749 - -0.0536835 0.187827 0.209237 - -0.0413588 0.126607 0.199281 - -0.0350843 0.107464 0.194182 - -0.0281727 0.0729762 0.188599 - -0.0274775 0.076994 0.188018 - -0.0259098 0.0779924 0.186729 - -0.0250816 0.0799709 0.186044 - -0.0232651 0.0848801 0.184541 - -0.0229357 0.085858 0.184268 - -0.0205043 0.0795915 0.182289 - -0.0185297 0.0893683 0.180643 - -0.0176365 0.0922477 0.179903 - -0.0149935 0.107928 0.177693 --0.00594419 0.13839 0.170188 --0.00166632 0.143351 0.166665 - 0.0046589 0.16298 0.161423 - 0.0138958 0.180451 0.153798 - 0.0205901 0.191387 0.148276 - 0.0262281 0.19632 0.143637 - 0.0300978 0.189144 0.14048 - 0.0293718 0.181993 0.141094 - 0.0345048 0.188993 0.136863 - 0.0546087 0.211128 0.120308 - 0.0779354 0.234594 0.101105 - 0.075864 0.21876 0.102846 - 0.0318042 0.0917681 0.139331 - 0.030604 0.0852281 0.140333 - 0.0370852 0.0884337 0.135006 - 0.0557548 0.112355 0.119623 - 0.0555494 -0.108696 0.121786 - 0.0380941 -0.0885536 0.135755 - 0.0316135 -0.0839368 0.140949 - 0.0302438 -0.0841422 0.14205 - 0.0362947 -0.103638 0.137239 - 0.026919 -0.0938953 0.144746 - 0.0332463 -0.109002 0.139702 - 0.0273896 -0.108004 0.144404 - 0.028361 -0.114304 0.14364 - 0.0353785 -0.15846 0.138116 - 0.033551 -0.160716 0.13959 - 0.0114542 -0.119642 0.157234 - 0.0106617 -0.123267 0.15788 - 0.0126414 -0.14681 0.15635 - 0.0142811 -0.159815 0.155066 - 0.0143683 -0.16503 0.15501 - 0.0132445 -0.165477 0.155914 - 0.00791045 -0.163273 0.160193 - 0.0071558 -0.162494 0.160797 --0.00767599 -0.142042 0.172658 - -0.0183458 -0.0924544 0.181102 - -0.0227762 -0.0848866 0.184641 - -0.0277424 -0.0729734 0.1886 - -0.0279906 -0.0729642 0.188799 - -0.028487 -0.0729415 0.189198 - -0.0297838 -0.0798678 0.190257 - -0.0379941 -0.150229 0.197033 - -0.0414575 -0.178916 0.199888 - -0.0832543 -0.360558 0.233928 - -0.104998 -0.371369 0.251422 - -0.116673 -0.374283 0.260808 - -0.139073 -0.372697 0.278797 - -0.175261 -0.371469 0.307863 - -0.198711 -0.36842 0.326691 - -0.243704 -0.360351 0.362812 - -0.329113 -0.343617 0.431376 - -0.373226 -0.360276 0.466853 - -0.392218 -0.360045 0.482108 - -0.401977 -0.349969 0.489921 - -0.406161 -0.344201 0.493267 - -0.421297 -0.351319 0.505444 - -0.456086 -0.350992 0.533387 - -0.51446 -0.350374 0.580276 - -0.521215 -0.33015 0.585651 - -0.645903 -0.357568 0.685879 - -1.15478 -0.621063 1.09532 - -1.1667 -0.567963 1.10476 - -1.16658 -0.54596 1.10461 - -1.16548 -0.523722 1.10366 - -1.17578 -0.387196 1.11159 - -1.23161 -0.355873 1.15636 - -1.31679 -0.343155 1.22474 - -2.56686 -0.254114 2.22866 - -2.57078 -0.197257 2.23166 - -0.305963 -0.0138336 0.411933 - -0.288105 0.0119702 0.397523 - -2.56962 0.230473 2.22963 - -2.56674 0.30176 2.22713 - -1.23315 0.218652 1.15611 - -1.2324 0.225402 1.1555 - -1.21928 0.284669 1.14481 - -1.22701 0.30741 1.15095 - -1.23218 0.329831 1.15505 - -2.57464 0.817165 2.23216 - -2.57966 1.14574 2.23535 - -2.57778 1.39103 2.23321 - -2.58517 1.53226 2.23878 - -2.58419 1.54912 2.23795 - -1.16887 0.829811 1.10292 - -1.15664 0.880372 1.09296 - -1.03002 0.8688 0.991278 - -1.02344 0.879423 0.985967 - -0.999234 0.984025 0.966257 - -0.988143 1.13048 0.956972 - -0.973763 1.17346 0.945311 - -0.964696 1.25706 0.937813 - -0.970434 1.2983 0.942316 - -0.959074 1.34004 0.933084 - -0.950286 1.38708 0.925904 - -0.942559 1.41244 0.919632 - -0.824789 1.39589 0.825074 - -0.787676 1.38083 0.795301 - -0.625563 1.25308 0.665409 - -0.621299 1.25642 0.661975 - -0.125162 0.265451 0.265986 - -0.128929 0.29517 0.268935 - -0.244133 0.665108 0.360526 - -0.242169 0.66724 0.358943 - -0.234766 0.668935 0.352992 - -0.227927 0.672364 0.347489 - -0.217149 0.671116 0.338835 - -0.193864 0.701125 0.320054 - -0.193263 0.732671 0.31949 - -0.19443 0.762419 0.320352 - -0.180841 0.76401 0.309432 - -0.225288 1.12378 0.344212 - -0.0540972 0.182608 0.209114 - -0.0418087 0.128501 0.199382 - -0.0421746 0.148644 0.199624 - -0.0288699 0.0739318 0.189129 - -0.0230933 0.0798871 0.184473 - -0.0225968 0.078849 0.184077 - -0.0220067 0.0798009 0.1836 - -0.0181582 0.0923943 0.180477 - -0.0103028 0.12327 0.174088 --0.00792056 0.127806 0.172162 --0.00464897 0.140232 0.169503 - 0.034536 0.211974 0.137842 - 0.0325635 0.187236 0.13949 - 0.0419514 0.201689 0.131912 - 0.0792997 0.255073 0.101775 - 0.0873464 0.268811 0.0952758 - 0.0859653 0.235223 0.0964713 - 0.0958449 0.246156 0.0885072 - 0.0749839 0.182267 0.105428 - 0.049671 0.132992 0.125888 - 0.0375871 0.0902468 0.135704 - 0.0458784 -0.0942994 0.131051 - 0.0471898 -0.0968639 0.130032 - 0.03797 -0.0899791 0.137224 - 0.0365404 -0.103193 0.138375 - 0.0322807 -0.108337 0.141719 - 0.0247292 -0.0978919 0.147597 - 0.0324766 -0.164171 0.141708 - 0.00981726 -0.113347 0.159296 - 0.0121489 -0.159949 0.157592 - 0.00994302 -0.155561 0.159305 - 0.00887274 -0.155949 0.160143 - 0.00813276 -0.163462 0.160741 - 0.00330208 -0.156741 0.164501 - -0.0120848 -0.123796 0.176449 - -0.01865 -0.0865298 0.181487 - -0.0208633 -0.0757434 0.183191 - -0.0226841 -0.0909161 0.184653 - -0.0269836 -0.0849858 0.188 - -0.0275791 -0.0729642 0.188435 - -0.0278299 -0.0729535 0.188631 - -0.0290355 -0.07789 0.189586 - -0.0414455 -0.181897 0.199554 - -0.0460853 -0.210401 0.203254 - -0.0634122 -0.294089 0.217015 - -0.0713435 -0.328883 0.223305 - -0.0768903 -0.350974 0.227698 - -0.0783892 -0.35265 0.228874 - -0.0870491 -0.366748 0.235681 - -0.0912008 -0.360456 0.238911 - -0.107517 -0.374776 0.251706 - -0.11591 -0.374787 0.258268 - -0.128215 -0.37282 0.267885 - -0.136528 -0.376439 0.274394 - -0.141401 -0.37299 0.278196 - -0.161834 -0.374937 0.294178 - -0.198019 -0.367666 0.322453 - -0.208471 -0.371276 0.330635 - -0.285517 -0.386046 0.390916 - -0.319382 -0.406705 0.417448 - -0.32078 -0.405073 0.418536 - -1.31513 -1.55311 1.19895 - -0.337772 -0.347187 0.431676 - -0.377655 -0.361534 0.462897 - -0.396246 -0.360653 0.477432 - -0.400603 -0.358335 0.480832 - -0.403726 -0.358047 0.483274 - -0.451313 -0.357262 0.520481 - -0.479697 -0.352789 0.542663 - -0.486012 -0.347254 0.547587 - -0.53467 -0.321685 0.585569 - -1.18569 -0.624098 1.09538 - -1.18403 -0.534192 1.09385 - -1.17901 -0.488853 1.08981 - -1.18084 -0.475438 1.09121 - -1.17973 -0.43291 1.09023 - -1.19102 -0.36092 1.09888 - -1.25499 -0.351981 1.14888 - -1.28904 -0.267202 1.17529 - -1.28607 -0.259401 1.17294 - -1.29725 -0.211323 1.18156 - -2.63729 -0.331417 2.22967 - -2.63137 -0.316092 2.225 - -0.281885 -0.0026 0.387102 - -0.264564 0.00154222 0.373548 - -0.264558 0.00286427 0.37354 - -2.63592 0.394511 2.22675 - -1.23054 0.229624 1.12828 - -2.63797 0.752558 2.22745 - -2.63924 0.79869 2.22832 - -2.65558 1.10288 2.24032 - -2.65017 1.13292 2.23602 - -1.181 0.747878 1.08823 - -1.17462 0.842557 1.083 - -1.07825 0.868033 1.00758 - -1.00723 0.947582 0.951847 - -1.00078 1.01133 0.946641 - -0.992584 1.07628 0.94007 - -0.97752 1.16651 0.928062 - -0.972519 1.22267 0.92401 - -0.965723 1.29033 0.918524 - -0.963949 1.29921 0.917114 - -0.959119 1.36235 0.913177 - -0.844095 1.39012 0.823167 - -0.810421 1.3953 0.796824 - -0.764209 1.38849 0.760708 - -0.740329 1.3822 0.742051 - -0.61839 1.26301 0.647007 - -0.140494 0.276221 0.275838 - -0.249709 0.684799 0.360198 - -0.235926 0.675675 0.349444 - -0.229579 0.672364 0.344489 - -0.227267 0.673481 0.342679 - -0.219229 0.672996 0.336395 - -0.190309 0.681039 0.313762 - -0.187968 0.681938 0.311929 - -0.0453123 0.169248 0.201686 - -0.040181 0.14187 0.197743 - -0.0299933 0.0788344 0.189937 - -0.021934 0.0828413 0.183625 - -0.0114062 0.116534 0.175308 --0.00429244 0.13827 0.16969 - 0.00470916 0.156189 0.162606 - 0.0100725 0.167839 0.158383 - 0.0134746 0.171812 0.155713 - 0.0185455 0.179257 0.151729 - 0.0238361 0.191793 0.14756 - 0.0273456 0.196618 0.144804 - 0.0337191 0.180696 0.139861 - 0.0579561 0.216068 0.12082 - 0.0792323 0.253894 0.104087 - 0.104689 0.2629 0.0841592 - 0.0343768 0.0936457 0.139567 - 0.0323033 0.0880412 0.141203 - 0.0507265 -0.102041 0.128561 - 0.0469756 -0.0995985 0.131424 - 0.0334096 -0.0853359 0.141768 - 0.0263321 -0.0923277 0.147201 - 0.0277629 -0.116096 0.146166 - 0.0277403 -0.118417 0.146189 - 0.0368997 -0.160941 0.139288 - 0.0261735 -0.154977 0.14748 - 0.019546 -0.136775 0.152505 - 0.00885762 -0.123707 0.16065 - 0.0111103 -0.145952 0.158983 - 0.00120103 -0.154427 0.166586 --0.00016292 -0.149679 0.167618 --0.00120092 -0.14995 0.168413 --0.00224076 -0.15021 0.169209 --0.00422968 -0.147625 0.170724 --0.00756144 -0.138196 0.17325 - -0.0367694 -0.148303 0.195623 - -0.0621104 -0.292321 0.215375 - -0.0643936 -0.301984 0.217146 - -0.0732173 -0.333545 0.223977 - -0.0856148 -0.365128 0.233542 - -0.0870444 -0.36577 0.234638 - -0.142721 -0.380151 0.277274 - -0.162289 -0.378418 0.292242 - -0.163932 -0.378568 0.293499 - -0.208368 -0.365186 0.327465 - -0.21776 -0.376609 0.33468 - -0.236756 -0.36629 0.349188 - -0.24642 -0.365958 0.356582 - -0.257654 -0.367612 0.365182 - -0.268991 -0.375357 0.373875 - -0.272877 -0.371304 0.376838 - -0.324291 -0.389608 0.416224 - -1.31095 -1.53592 1.17403 - -0.405832 -0.357449 0.478532 - -0.485637 -0.351306 0.539578 - -0.538293 -0.350242 0.579864 - -1.19817 -0.595674 1.08538 - -1.19127 -0.540605 1.07996 - -1.17729 -0.456319 1.06905 - -1.17887 -0.449983 1.07024 - -1.29552 -0.280842 1.15907 - -1.29179 -0.272848 1.1562 - -1.29117 -0.265558 1.1557 - -1.28827 -0.250704 1.15345 - -1.29157 -0.215816 1.15588 - -2.68684 -0.290756 2.22364 - -0.270093 -0.00515159 0.373787 - -0.288284 0.0103486 0.387666 - -2.68311 0.163158 2.21964 - -2.68288 0.251064 2.21924 - -2.69063 0.325533 2.22499 - -2.69621 0.355853 2.22918 - -2.69391 0.400069 2.22731 - -1.23292 0.221509 1.10991 - -2.69067 0.761635 2.22392 - -2.69847 0.794789 2.2298 - -2.69858 0.935639 2.22953 - -2.70056 1.04805 2.23077 - -2.70233 1.09729 2.232 - -2.70079 1.11292 2.23078 - -2.69731 1.22653 2.22783 - -1.27553 0.785557 1.14108 - -1.17383 0.869402 1.06307 - -1.1283 0.876668 1.02821 - -1.11587 0.875181 1.0187 - -1.05027 0.862624 0.968543 - -1.01483 0.897142 0.941338 - -1.01307 0.912109 0.939956 - -0.999063 1.03792 0.928919 - -0.993563 1.09759 0.92456 - -0.953782 1.36806 0.893441 - -0.889905 1.39241 0.844506 - -0.826997 1.38819 0.796383 - -0.706927 1.37191 0.704554 - -0.63445 1.2624 0.649376 - -0.630073 1.26573 0.646019 - -0.143357 0.275826 0.276109 - -0.134221 0.268292 0.269138 - -0.132004 0.268577 0.26744 - -0.136521 0.313447 0.270783 - -0.282951 0.762411 0.381691 - -0.218644 0.675939 0.332706 - -0.216301 0.676989 0.330911 - -0.20618 0.668696 0.323188 - -0.0500209 0.158064 0.204991 - -0.0453333 0.140845 0.201448 - -0.0391612 0.138969 0.19673 - -0.0304006 0.0817787 0.190171 - -0.0274637 0.0779652 0.187933 - -0.0217492 0.0848596 0.183544 - -0.0206899 0.0827671 0.182738 - -0.0176663 0.0874269 0.180413 --0.00709129 0.128892 0.172217 - 0.0132624 0.167973 0.156546 - 0.0240992 0.189894 0.148199 - 0.0348416 0.183796 0.139995 - 0.0786799 0.255052 0.106273 - 0.0928961 0.269274 0.0953602 - 0.10353 0.2789 0.0871994 - 0.107929 0.26144 0.083878 - 0.0426681 0.11297 0.134185 - 0.030921 -0.0700543 0.144571 - 0.0314926 -0.0843161 0.144179 - 0.0288208 -0.0944861 0.146204 - 0.0268677 -0.100972 0.147682 - 0.0265411 -0.115216 0.147962 - 0.0308025 -0.125996 0.1448 - 0.00014753 -0.154851 0.167816 --0.00745294 -0.135234 0.173455 - -0.0207045 -0.0968478 0.183277 - -0.0248381 -0.0799993 0.186329 - -0.0267534 -0.0779716 0.187757 - -0.0271069 -0.0709548 0.188004 - -0.0296958 -0.0817959 0.189969 - -0.0331205 -0.114555 0.192614 - -0.0522047 -0.2416 0.207215 - -0.0563642 -0.26206 0.210379 - -0.0604376 -0.279483 0.213472 - -0.0637193 -0.29705 0.215972 - -0.0785735 -0.344502 0.227208 - -0.0817994 -0.356953 0.229653 - -0.0846167 -0.358276 0.231765 - -0.0902667 -0.368003 0.236018 - -0.0993109 -0.372525 0.242799 - -0.103413 -0.372241 0.245868 - -0.122468 -0.369344 0.260123 - -0.148315 -0.376582 0.279486 - -0.155822 -0.375875 0.285103 - -0.192488 -0.369748 0.31253 - -0.210776 -0.367722 0.326213 - -0.218522 -0.368626 0.332012 - -0.23683 -0.36745 0.345712 - -0.242702 -0.370766 0.350115 - -1.30939 -1.48269 1.15126 - -0.496788 -0.346727 0.540225 - -0.502837 -0.347673 0.544755 - -0.513591 -0.348396 0.552805 - -0.5209 -0.34647 0.558271 - -0.559898 -0.329019 0.587416 - -0.559361 -0.314322 0.586977 - -0.560458 -0.311406 0.58779 - -0.586298 -0.307994 0.607122 - -1.19419 -0.60396 1.06284 - -1.19629 -0.597579 1.0644 - -1.18684 -0.570686 1.05725 - -1.18057 -0.474959 1.05232 - -1.18013 -0.419534 1.05185 - -1.17982 -0.399007 1.05157 - -1.18706 -0.36086 1.05689 - -1.26417 -0.349121 1.11458 - -2.76099 -0.266474 2.23466 - -2.73436 -0.160091 2.21447 - -0.270095 0.00689761 0.369674 - -2.74677 0.180621 2.2229 - -2.74849 0.772041 2.22271 - -2.74848 0.803295 2.22263 - -2.75086 0.978503 2.22397 - -2.75091 1.07569 2.22377 - -2.74901 1.15708 2.22214 - -2.75029 1.20751 2.22297 - -1.18435 0.746469 1.0521 - -1.16634 0.750673 1.03861 - -1.16472 0.830748 1.03719 - -1.11179 0.873576 0.997475 - -1.0869 0.870006 0.978857 - -1.01679 0.933711 0.92622 - -1.00286 0.998028 0.915637 - -1.00061 1.00461 0.913935 - -0.973685 1.20554 0.89328 - -0.59966 1.21714 0.613313 - -0.141475 0.272936 0.272744 - -0.131675 0.27243 0.265411 - -0.351449 0.982377 0.428126 - -0.233919 0.669369 0.340943 - -0.191023 0.686727 0.308794 - -0.183515 0.736177 0.303051 - -0.0450786 0.14796 0.200908 - -0.0324375 0.0935736 0.191583 - -0.0313613 0.0876705 0.190792 - -0.0275063 0.0729456 0.187944 - -0.0261443 0.0669905 0.186939 - -0.0233769 0.087968 0.184816 - -0.020176 0.0847615 0.182428 - -0.0194526 0.0866958 0.181882 - -0.0154442 0.10327 0.17884 --0.00983715 0.121471 0.174598 --0.00530728 0.137747 0.171167 --0.00330434 0.1444 0.169651 - 0.0152754 0.173732 0.155672 - 0.035099 0.212982 0.140737 - 0.0505372 0.1985 0.129219 - 0.107955 0.288265 0.0860206 - 0.116695 0.29225 0.0794688 - 0.117716 0.291472 0.078707 - 0.100715 0.244627 0.091548 - 0.0624798 0.162411 0.120371 - 0.0445282 0.123249 0.133904 - 0.0365625 0.103305 0.139916 - 0.0344735 0.0888068 0.141516 - 0.0415589 -0.0874641 0.137707 - 0.0468659 -0.100424 0.133851 - 0.0317079 -0.0912863 0.144933 - 0.0318752 -0.092387 0.144813 - 0.02883 -0.119871 0.147112 - 0.0280194 -0.119282 0.147705 - 0.0248842 -0.11456 0.14999 - 0.0382337 -0.173291 0.140356 - 0.00735238 -0.107921 0.162817 - 0.0100933 -0.123707 0.160848 - 0.00992092 -0.124839 0.160977 - 0.0111839 -0.157875 0.160134 - 0.00957455 -0.161527 0.161322 --0.00437823 -0.146866 0.171507 - -0.0148888 -0.0962332 0.179081 - -0.0186661 -0.0786416 0.181805 - -0.0203926 -0.082826 0.18308 - -0.0208126 -0.101886 0.183435 - -0.0218025 -0.104938 0.184168 - -0.0232803 -0.104985 0.185251 - -0.0293867 -0.0817959 0.189667 - -0.0458733 -0.206317 0.202053 - -0.0833104 -0.357619 0.229854 - -0.0944919 -0.367874 0.238071 - -0.100058 -0.368239 0.24215 - -0.102901 -0.362151 0.244217 - -0.156182 -0.370582 0.283271 - -0.175055 -0.373946 0.297106 - -0.177318 -0.371411 0.298757 - -0.194616 -0.372358 0.311431 - -0.220099 -0.369462 0.330093 - -0.254252 -0.367463 0.355108 - -0.32296 -0.421512 0.405576 - -0.347423 -0.382807 0.423402 - -0.347273 -0.341318 0.423189 - -0.40539 -0.358596 0.465808 - -0.428442 -0.353426 0.482682 - -0.513473 -0.345918 0.544956 - -0.5189 -0.34622 0.548933 - -0.551692 -0.346933 0.572958 - -0.569142 -0.350899 0.585751 - -1.17929 -0.45717 1.033 - -1.1747 -0.38098 1.02945 - -1.28824 -0.25396 1.11231 - -2.80414 -0.344447 2.22306 - -2.79658 -0.283026 2.21737 - -2.80343 -0.223268 2.22224 - -2.80598 -0.148025 2.22392 - -0.273279 -0.00112012 0.368139 - -0.270861 0.0015524 0.366361 - -2.80984 0.183433 2.22593 - -2.80929 0.213613 2.22545 - -2.80388 0.394977 2.22104 - -2.8077 0.991491 2.22236 - -2.81 1.29302 2.2233 - -1.15917 0.788188 1.01517 - -1.17062 0.845686 1.02342 - -1.15105 0.881476 1.00899 - -1.13124 0.882782 0.994475 - -1.05488 0.869896 0.938572 - -1.00912 0.928194 0.904898 - -1.00465 0.983878 0.901491 - -0.990323 1.05907 0.890806 - -0.985147 1.12976 0.886839 - -0.981121 1.17515 0.883777 - -0.977411 1.21212 0.880968 - -0.966096 1.28438 0.8725 - -0.922618 1.41123 0.840333 - -0.777172 1.38185 0.733855 - -0.625924 1.23914 0.623407 - -0.154283 0.280544 0.280266 - -0.153295 0.28124 0.27954 - -0.133685 0.270367 0.265201 - -0.134163 0.274541 0.265541 - -0.399333 1.11915 0.457707 - -0.274587 0.77485 0.367173 - -0.228424 0.665063 0.333627 - -0.208547 0.669643 0.319054 - -0.0429275 0.169553 0.198963 - -0.0327182 0.0924974 0.191675 - -0.0299959 0.0807547 0.18971 - -0.0289723 0.0728257 0.18898 - -0.0242347 0.0909958 0.185464 - -0.0220929 0.098937 0.183875 - -0.0210865 0.0978835 0.183141 - -0.0201452 0.0787783 0.182498 --0.00943295 0.124519 0.174537 --0.00552154 0.132828 0.171651 --0.00243352 0.143297 0.169363 - 0.0205888 0.184525 0.152395 - 0.023181 0.18351 0.150499 - 0.0321014 0.208273 0.143902 - 0.0333585 0.209852 0.142977 - 0.0320207 0.183864 0.144022 - 0.068162 0.233999 0.117421 - 0.0810343 0.255052 0.107939 - 0.0893845 0.220249 0.101908 - 0.033071 0.0935633 0.143476 - 0.0518533 0.109364 0.129677 - 0.0314772 0.0729079 0.144695 - 0.183572 -0.26746 0.0372829 - 0.0249037 -0.0917713 0.150672 - 0.0246947 -0.0931361 0.150825 - 0.0275296 -0.10041 0.14881 - 0.037061 -0.15342 0.142103 - 0.010417 -0.113182 0.161117 - 0.00837546 -0.110913 0.162576 - 0.0112687 -0.137177 0.160565 - 0.00338682 -0.148129 0.166246 - 0.00233576 -0.148421 0.167001 - 0.00196067 -0.152614 0.16728 --0.00493586 -0.14708 0.172214 --0.00833864 -0.128501 0.174609 - -0.0153544 -0.0943494 0.179558 - -0.016786 -0.0895136 0.180573 - -0.0171854 -0.0885585 0.180857 - -0.0182054 -0.0796371 0.181567 - -0.0184878 -0.0796695 0.181769 - -0.0261165 -0.0789713 0.18724 - -0.0361237 -0.137233 0.194562 - -0.0536232 -0.256453 0.207409 - -0.119099 -0.387731 0.254702 - -0.135919 -0.372361 0.26673 - -0.183723 -0.376836 0.301033 - -0.194989 -0.37502 0.309111 - -0.196318 -0.374098 0.310062 - -0.210223 -0.373289 0.320035 - -0.232833 -0.359652 0.336221 - -0.239672 -0.364673 0.341139 - -0.270525 -0.370713 0.363286 - -0.315197 -0.43029 0.395479 - -0.318082 -0.419427 0.397522 - -1.32355 -1.71459 1.12199 - -1.32261 -1.66894 1.1212 - -1.3676 -1.47505 1.153 - -0.405884 -0.356781 0.460353 - -0.423243 -0.353114 0.472797 - -0.441546 -0.355874 0.485933 - -0.444059 -0.351377 0.487725 - -0.490543 -0.351224 0.52107 - -0.522865 -0.346712 0.544245 - -0.59767 -0.30265 0.597798 - -1.17584 -0.56444 1.0132 - -1.18977 -0.542439 1.02314 - -1.18143 -0.482409 1.017 - -1.17184 -0.417328 1.00997 - -1.22681 -0.354228 1.04924 - -1.28202 -0.230197 1.08855 - -1.31091 -0.207299 1.10921 - -2.85382 -0.271527 2.21619 - -0.273119 -0.00111285 0.364238 - -0.264166 0.00407574 0.357802 - -2.86001 0.246543 2.21935 - -1.22844 0.222494 1.04899 - -2.87039 0.908167 2.22517 - -2.86388 0.938685 2.22042 - -2.86168 1.25587 2.21806 - -2.86714 1.27554 2.22194 - -2.79115 1.66258 2.16647 - -2.76483 1.66501 2.14758 - -1.15292 0.810572 0.99337 - -1.08232 0.870411 0.942575 - -1.01067 0.931675 0.891031 - -1.0065 1.00543 0.887857 - -0.967764 1.23397 0.859506 - -0.968311 1.26748 0.859816 - -0.963814 1.27253 0.856577 - -0.742149 1.38549 0.697287 - -0.185971 0.343956 0.300872 - -0.139823 0.272415 0.267944 - -0.139041 0.323824 0.267256 - -0.211897 0.668647 0.318671 - -0.206634 0.668729 0.314895 - -0.20212 1.02525 0.310779 - -0.0438901 0.119673 0.199501 - -0.0485889 0.176566 0.202732 - -0.0427153 0.169553 0.198536 - -0.0317779 0.0885585 0.190889 - -0.0204543 0.0958646 0.182748 - -0.0166596 0.0884638 0.180044 - -0.0117674 0.111889 0.176477 --0.00412524 0.135671 0.170936 - -0.0034933 0.136541 0.170481 --0.00300927 0.136427 0.170134 - 0.0025156 0.150325 0.166136 - 0.00429985 0.157004 0.16484 - 0.0139023 0.17673 0.157903 - 0.0151545 0.176308 0.157006 - 0.0211955 0.181412 0.15266 - 0.0350708 0.207327 0.142642 - 0.0359847 0.204798 0.141993 - 0.033527 0.179208 0.143819 - 0.0506164 0.193988 0.131523 - 0.0527139 0.197183 0.130011 - 0.107393 0.287099 0.0905654 - 0.0566059 0.15086 0.127333 - 0.0494744 0.136295 0.132485 - 0.0390701 0.108694 0.140016 - 0.0311828 0.0885072 0.145724 - 0.0466399 0.105267 0.134594 - 0.053285 0.110118 0.129816 - 0.0536751 0.109698 0.129537 - 0.0277355 0.067133 0.148249 - 0.0461859 -0.0936964 0.136543 - 0.0462683 -0.0963036 0.136492 - 0.0522198 -0.107236 0.132345 - 0.0510654 -0.108445 0.133157 - 0.0281873 -0.1052 0.149193 - 0.026688 -0.116594 0.150272 - 0.0290232 -0.128636 0.148664 - 0.028828 -0.13099 0.148807 - 0.010366 -0.129374 0.161749 - -0.0156302 -0.0904223 0.179884 - -0.0164017 -0.0854955 0.180413 - -0.0284073 -0.0808225 0.18882 - -0.0320718 -0.106544 0.191453 - -0.0326082 -0.10849 0.191834 - -0.054869 -0.26025 0.207815 - -0.0565215 -0.266016 0.208988 - -0.0782918 -0.341557 0.224439 - -0.0911328 -0.362767 0.233496 - -0.104014 -0.365048 0.242534 - -0.122876 -0.383306 0.255806 - -0.125748 -0.371652 0.257791 - -0.141566 -0.374261 0.26889 - -0.146175 -0.374201 0.272122 - -0.160092 -0.377902 0.28189 - -0.179862 -0.369692 0.295734 - -0.181182 -0.368856 0.296658 - -0.238815 -0.367789 0.33707 - -0.240128 -0.366639 0.337988 - -0.276379 -0.380577 0.363444 - -0.30913 -0.414942 0.386494 - -1.32343 -1.74724 1.10103 - -1.32866 -1.72376 1.10464 - -0.334219 -0.378733 0.403999 - -0.367306 -0.370762 0.427182 - -0.36951 -0.350745 0.428679 - -0.368567 -0.331528 0.427971 - -0.437128 -0.356308 0.47611 - -0.593504 -0.338793 0.585726 - -0.600622 -0.313082 0.590656 - -0.602844 -0.306921 0.592199 - -1.1774 -0.504836 0.995595 - -1.17712 -0.490874 0.995359 - -1.18112 -0.437854 0.998034 - -1.30476 -0.310032 1.08442 - -1.28793 -0.243385 1.07246 - -2.93086 -0.308043 2.22473 - -2.91693 -0.24451 2.2148 - -2.91779 -0.229089 2.21537 - -2.90492 -0.151071 2.20616 - -0.270558 0.00021869 0.358432 - -0.280269 0.00978584 0.365218 - -2.92775 0.203949 2.2213 - -2.92701 0.21942 2.22074 - -2.92605 0.40637 2.21961 - -2.92551 0.437647 2.21915 - -1.22988 0.247485 1.03056 - -1.22119 0.278609 1.02438 - -1.21837 0.311055 1.02233 - -2.92421 0.869174 2.21719 - -2.93776 1.03963 2.22627 - -2.93104 1.07092 2.22149 - -2.93808 1.62403 2.22508 - -2.80595 1.65907 2.13233 - -1.25976 0.778106 1.05021 - -1.15905 0.801005 0.979534 - -1.01304 0.886066 0.876935 - -0.998527 1.03481 0.866395 - -0.976016 1.19348 0.850221 - -0.974559 1.23397 0.849101 - -0.971824 1.24121 0.847165 - -0.968009 1.29151 0.844367 - -0.963392 1.29652 0.841117 - -0.951358 1.37354 0.83249 - -0.829143 1.39063 0.746745 - -0.799021 1.38935 0.725625 - -0.722403 1.37734 0.671925 - -0.15349 0.28193 0.275649 - -0.141884 0.270286 0.267539 - -0.143997 0.332364 0.268869 - -0.235745 0.672364 0.332377 - -0.230073 0.671775 0.328401 - -0.201267 0.684924 0.308169 - -0.0374707 0.137055 0.194644 - -0.0290387 0.0757699 0.188881 - -0.027066 0.0679092 0.187516 - -0.026762 0.0729327 0.187291 - -0.0249937 0.0779939 0.186039 - -0.0230373 0.10599 0.184598 - -0.02228 0.105973 0.184067 - -0.0160988 0.0864334 0.17978 - -0.0109007 0.111819 0.176073 --0.00634914 0.130174 0.172837 - 0.00061429 0.148926 0.167908 - 0.0217446 0.183569 0.153005 - 0.0331282 0.187283 0.145014 - 0.0381687 0.179443 0.141498 - 0.0450468 0.18557 0.13666 - 0.0571931 0.208424 0.128086 - 0.0629812 0.218329 0.124003 - 0.114501 0.293459 0.0876912 - 0.102584 0.260287 0.0961294 - 0.0493862 0.138315 0.133732 - 0.0497768 0.109505 0.133529 - 0.0469012 0.0980499 0.135573 - 0.0484974 0.0976441 0.134455 - 0.0505042 0.099466 0.133043 - 0.054288 -0.106009 0.132107 - 0.0289483 -0.0920706 0.149449 - 0.0261573 -0.0931361 0.151365 - 0.0334921 -0.125121 0.146413 - 0.0254352 -0.114467 0.151912 - 0.0264263 -0.120596 0.151247 - 0.0392679 -0.167488 0.142556 - 0.0383967 -0.16906 0.143157 - 0.0223578 -0.143569 0.154093 - 0.0137873 -0.14194 0.159965 - 0.0115946 -0.154212 0.161499 - 0.00432999 -0.156381 0.166485 --0.00913073 -0.12174 0.175631 - -0.0125586 -0.106154 0.177944 - -0.0129407 -0.106212 0.178206 - -0.0184523 -0.07674 0.181913 - -0.0190673 -0.0858198 0.182357 - -0.0262683 -0.07093 0.187259 - -0.0830856 -0.354679 0.226906 - -0.109949 -0.377666 0.245381 - -0.113318 -0.385865 0.247711 - -0.116092 -0.384898 0.249611 - -0.117354 -0.371919 0.250445 - -0.144138 -0.380794 0.268832 - -0.16007 -0.376072 0.279745 - -0.170902 -0.374442 0.287168 - -0.181025 -0.370581 0.2941 - -0.183688 -0.368898 0.295922 - -0.282688 -0.391273 0.363859 - -0.31768 -0.421044 0.387925 - -1.31823 -1.68316 1.07705 - -1.30648 -1.63894 1.06888 - -0.351625 -0.383856 0.41111 - -0.371933 -0.37341 0.425009 - -0.442349 -0.351888 0.473241 - -0.476946 -0.346449 0.49695 - -0.47959 -0.345105 0.49876 - -0.502708 -0.345211 0.514612 - -0.56118 -0.349782 0.554716 - -0.606602 -0.329128 0.585811 - -0.609706 -0.323358 0.587926 - -1.18134 -0.428181 0.980141 - -1.17815 -0.361032 0.97779 - -1.27638 -0.349594 1.04512 - -1.28918 -0.262562 1.05369 - -0.279218 -0.0119455 0.360559 - -0.267787 -0.00753337 0.352711 - -0.312196 0.013995 0.383109 - -1.23842 0.221158 1.0177 - -1.22369 0.244502 1.00755 - -1.22028 0.309386 1.00505 - -1.21802 0.322031 1.00347 - -1.29685 0.357443 1.05744 - -2.99148 0.916333 2.21807 - -3.00814 1.17813 2.22886 - -2.99192 1.38376 2.21724 - -2.99338 1.62413 2.21765 - -2.99578 1.64438 2.21925 - -2.9144 1.67379 2.16338 - -1.16038 0.772532 0.96286 - -1.03112 0.863717 0.874004 - -0.995924 1.02496 0.849481 - -0.987695 1.11902 0.84361 - -0.973046 1.21293 0.833338 - -0.948873 1.38491 0.816345 - -0.814723 1.38188 0.724368 - -0.792827 1.38185 0.709354 - -0.555713 1.07278 0.547518 - -0.161991 0.296042 0.279432 - -0.137489 0.273351 0.262686 - -0.135399 0.271263 0.261258 - -0.133314 0.281381 0.259804 - -0.207747 0.675396 0.309886 - -0.199946 0.676339 0.304535 - -0.188898 0.685619 0.296937 - -0.177921 0.684168 0.289413 - -0.172938 0.710576 0.285933 - -0.177286 0.78857 0.288725 - -0.0416391 0.101743 0.197379 - -0.0575166 0.26491 0.207871 - -0.0389076 0.148895 0.195392 - -0.0274402 0.0778776 0.187701 - -0.0269599 0.0799105 0.187367 - -0.0200001 0.0878759 0.182576 - -0.0147857 0.0923472 0.178989 - 0.00014441 0.146116 0.168621 - 0.0156365 0.175556 0.157927 - 0.0197703 0.181411 0.155079 - 0.0267376 0.194513 0.15027 - 0.0309601 0.180084 0.147409 - 0.0377082 0.17793 0.142787 - 0.0596216 0.209789 0.127684 - 0.118769 0.299518 0.0869103 - 0.0622574 0.166989 0.125981 - 0.0424144 0.114623 0.139714 - 0.0285101 0.0848866 0.14932 - 0.0378078 0.0938585 0.142923 - 0.0482022 0.106803 0.135764 - 0.0546476 0.113305 0.131329 - 0.0549258 0.11171 0.131142 - 0.0456443 0.0976645 0.13754 - 0.137953 -0.210157 0.0774252 - 0.0542814 -0.102958 0.133277 - 0.0277703 -0.11456 0.151084 - 0.027713 -0.116863 0.151128 - 0.0320181 -0.136665 0.148288 - 0.0281303 -0.157285 0.150945 - 0.0257965 -0.154083 0.152502 - 0.0205997 -0.141476 0.155957 - 0.0138823 -0.123132 0.160418 - 0.0104674 -0.118219 0.162696 - 0.0116164 -0.131461 0.161957 - 0.0135438 -0.154795 0.160721 - 0.00273081 -0.150795 0.167962 - -0.0119127 -0.108138 0.17768 - -0.0169035 -0.0806326 0.18096 - -0.0183037 -0.0817787 0.181902 - -0.0198822 -0.105921 0.183019 - -0.0205982 -0.107952 0.183504 - -0.0225392 -0.109996 0.18481 - -0.0229502 -0.106999 0.185079 - -0.0251547 -0.0829698 0.186499 - -0.0257035 -0.0719423 0.186841 - -0.0259643 -0.071929 0.187015 - -0.0275847 -0.0728183 0.188104 - -0.0329034 -0.114413 0.191771 - -0.094971 -0.3669 0.234002 - -0.0964938 -0.367491 0.235024 - -0.116856 -0.386817 0.248726 - -0.124322 -0.374627 0.253703 - -0.191059 -0.375993 0.29846 - -0.232074 -0.365728 0.32594 - -0.243131 -0.371043 0.333367 - -0.251629 -0.364776 0.339051 - -0.26066 -0.369043 0.345118 - -0.31743 -0.429537 0.383333 - -1.32003 -1.65955 1.05864 - -1.30743 -1.58691 1.05001 - -1.32201 -1.5498 1.0597 - -0.355158 -0.389076 0.408536 - -0.371851 -0.391161 0.419736 - -0.374677 -0.38748 0.421622 - -0.381292 -0.367923 0.426011 - -0.3808 -0.357772 0.425656 - -0.383384 -0.353999 0.42738 - -0.384665 -0.352102 0.428235 - -0.379154 -0.33151 0.424489 - -0.399972 -0.341501 0.438474 - -0.421122 -0.354166 0.452688 - -0.426421 -0.355615 0.456245 - -0.462999 -0.350094 0.480761 - -0.471095 -0.34981 0.486189 - -0.474456 -0.349074 0.488441 - -1.18071 -0.520095 0.962465 - -1.18015 -0.405019 0.961817 - -1.18162 -0.398935 0.962784 - -1.31516 -0.308282 1.05212 - -1.29004 -0.274704 1.03519 - -1.2964 -0.2075 1.03929 - -2.81073 -0.379961 2.05522 - -3.03734 -0.187552 2.20672 - -3.03801 -0.171715 2.20713 - -0.271527 -0.0115216 0.351544 - -0.269209 -0.00365947 0.349971 - -0.260893 0.00519914 0.344373 - -3.03464 0.160929 2.20407 - -1.21886 0.300398 0.986072 - -1.29248 0.353833 1.03532 - -3.05383 0.929169 2.21509 - -3.0547 1.06628 2.21534 - -3.06371 1.24502 2.22095 - -3.06154 1.26195 2.21946 - -3.07283 1.48573 2.22649 - -3.08194 1.64182 2.23222 - -3.07071 1.67429 2.22462 - -2.81683 1.66058 2.05439 - -1.15941 0.774589 0.945064 - -1.01673 0.893567 0.849101 - -0.99924 1.02168 0.83706 - -0.997411 1.03785 0.835795 - -0.996946 1.07436 0.835395 - -0.993049 1.07946 0.83277 - -0.983053 1.14556 0.825907 - -0.959619 1.29665 0.809828 - -0.522584 1.01974 0.51742 - -0.144406 0.273819 0.26561 - -0.137401 0.269183 0.260924 - -0.149086 0.347675 0.26857 - -0.255398 0.708249 0.338995 - -0.17303 0.682863 0.28382 - -0.0449935 0.190265 0.199145 - -0.0378374 0.140954 0.194465 - -0.0322124 0.0964309 0.1908 - -0.0277175 0.0738233 0.18784 - -0.0252172 0.0819733 0.186144 - -0.0196555 0.0948871 0.182383 - -0.0188751 0.0898279 0.181872 - -0.0177947 0.0817133 0.181167 - -0.0119551 0.105083 0.177194 - -0.0114628 0.106012 0.176862 --0.00716667 0.120399 0.173946 --0.00023045 0.147347 0.16923 - 0.0173235 0.174168 0.157394 - 0.0186399 0.176835 0.156505 - 0.0444028 0.187938 0.139201 - 0.0515896 0.198305 0.134357 - 0.0540765 0.200226 0.132685 - 0.100715 0.287282 0.101199 - 0.10552 0.292142 0.0979652 - 0.10917 0.279443 0.0955483 - 0.110774 0.277173 0.0944782 - 0.0368852 0.0954672 0.144465 - 0.0626542 0.125699 0.127112 - 0.328999 -0.421033 -0.0449691 - 0.302971 -0.410844 -0.0279247 - 0.119426 -0.185917 0.0919024 - 0.0321821 -0.086812 0.148878 - 0.030893 -0.108332 0.149775 - 0.0297035 -0.109165 0.150557 - 0.0304181 -0.120127 0.150114 - 0.0299796 -0.120404 0.150402 - 0.0269573 -0.121121 0.152386 - 0.0316119 -0.138429 0.149375 - 0.0409333 -0.169643 0.143337 - 0.0468286 -0.201466 0.139547 - 0.0139563 -0.144434 0.160968 --0.00912535 -0.117854 0.176041 - -0.0148494 -0.0854541 0.179717 - -0.0259472 -0.0809202 0.186984 - -0.0333761 -0.118339 0.191945 - -0.037724 -0.154984 0.194884 - -0.053746 -0.254313 0.205628 - -0.0586424 -0.277698 0.208895 - -0.0653721 -0.295629 0.213351 - -0.075901 -0.333986 0.220348 - -0.0930071 -0.356195 0.231618 - -0.103969 -0.368373 0.238836 - -0.119809 -0.373328 0.249235 - -0.129292 -0.374891 0.255458 - -0.155833 -0.374529 0.272862 - -0.160893 -0.379542 0.276193 - -0.166739 -0.373121 0.280011 - -0.220096 -0.370077 0.314994 - -0.235914 -0.36709 0.32536 - -0.247478 -0.369525 0.332949 - -0.316849 -0.41877 0.378559 - -0.327496 -0.426322 0.385559 - -0.371803 -0.38208 0.414509 - -0.375643 -0.36643 0.41699 - -0.391893 -0.366717 0.427647 - -0.39323 -0.364786 0.428519 - -0.404114 -0.324862 0.435561 - -0.402567 -0.320562 0.434536 - -0.410391 -0.321141 0.439668 - -0.475788 -0.347993 0.482618 - -0.635112 -0.329275 0.587055 - -1.18312 -0.490354 0.94681 - -1.17332 -0.374082 0.940109 - -1.31239 -0.333695 1.03121 - -1.31234 -0.319615 1.03114 - -1.31218 -0.305561 1.031 - -1.2883 -0.225048 1.01515 - -1.28912 -0.218443 1.01567 - -1.28991 -0.211834 1.01618 - -1.30137 -0.20016 1.02366 - -3.11094 -0.27174 2.21051 - -0.268844 -0.00491742 0.346088 - -0.268881 -0.00106921 0.346103 - -3.09806 0.405369 2.20044 - -1.23636 0.211414 0.980048 - -1.2511 0.340067 0.989404 - -3.1238 0.927075 2.21608 - -3.12727 1.08451 2.21798 - -3.12542 1.15446 2.2166 - -3.12567 1.19014 2.21668 - -3.13721 1.2666 2.22406 - -3.10843 1.62575 2.20433 - -1.01497 0.878223 0.833269 - -1.01789 0.896964 0.835139 - -1.01594 0.903354 0.833848 - -1.01331 0.90913 0.832106 - -1.00848 0.980474 0.828768 - -0.997224 1.05848 0.821202 - -0.988354 1.08617 0.815318 - -0.98663 1.11298 0.814124 - -0.978541 1.13288 0.808772 - -0.976632 1.16057 0.807453 - -0.972461 1.207 0.804607 - -0.967098 1.23207 0.80103 - -0.962736 1.32731 0.797942 - -0.912034 1.39775 0.764524 - -0.4734 0.922965 0.478013 - -0.167998 0.303127 0.279219 - -0.156174 0.28124 0.271518 - -0.135707 0.276027 0.258108 - -0.145238 0.335749 0.264215 - -0.259811 0.708886 0.338457 - -0.241579 0.671234 0.326592 - -0.209032 0.673496 0.305243 - -0.167906 0.734052 0.278128 - -0.0380601 0.0861688 0.194527 - -0.0600584 0.27856 0.208493 - -0.0388287 0.147822 0.194884 - -0.0267946 0.0728669 0.187172 - -0.0252874 0.0759555 0.186176 - -0.0219552 0.10299 0.183926 --0.00602257 0.125333 0.173424 - 0.00492598 0.154378 0.166175 - 0.0116746 0.163769 0.161727 - 0.0135255 0.169394 0.1605 - 0.0211052 0.181411 0.1555 - 0.0240639 0.184525 0.153553 - 0.0289231 0.197374 0.150335 - 0.0351301 0.20229 0.146253 - 0.0567715 0.202528 0.132061 - 0.112885 0.299558 0.0950305 - 0.02969 0.0876039 0.150095 - 0.531258 0.70458 -0.180298 - 0.284981 -0.39533 -0.0116065 - 0.046098 -0.0999557 0.140804 - 0.0402632 -0.0965182 0.144536 - 0.0385325 -0.0955728 0.145643 - 0.0296849 -0.0896045 0.1513 - 0.0284072 -0.122915 0.152198 - 0.0158018 -0.127092 0.160287 - 0.0149842 -0.160958 0.160892 - 0.00695119 -0.152027 0.166019 - 0.00312139 -0.146879 0.168462 - 0.00392818 -0.154851 0.167963 - 0.00286511 -0.152043 0.168638 --0.00796018 -0.123796 0.175509 - -0.0133746 -0.0963842 0.178915 - -0.0214008 -0.109991 0.184091 - -0.0233524 -0.0999953 0.185319 - -0.0268138 -0.0758335 0.18748 - -0.0674052 -0.302297 0.214035 - -0.0969363 -0.361274 0.233103 - -0.105078 -0.366014 0.238333 - -0.116251 -0.382018 0.245532 - -0.133793 -0.378483 0.256767 - -0.137138 -0.379194 0.258913 - -0.139921 -0.377989 0.260694 - -0.146531 -0.37392 0.264921 - -0.147904 -0.373272 0.265799 - -0.161136 -0.378625 0.274293 - -0.195145 -0.369814 0.296071 - -0.217863 -0.374836 0.310643 - -0.237001 -0.36709 0.322892 - -0.245429 -0.371043 0.328303 - -0.315869 -0.418765 0.373565 - -0.317406 -0.417239 0.374546 - -1.32752 -1.73644 1.02511 - -1.30798 -1.58071 1.01222 - -1.31553 -1.49564 1.01686 - -0.362373 -0.376169 0.40327 - -0.403241 -0.36917 0.429448 - -0.397022 -0.334887 0.425381 - -0.483458 -0.351776 0.480822 - -0.513948 -0.350316 0.500362 - -0.519573 -0.350829 0.503968 - -0.67992 -0.295265 0.606611 - -1.17943 -0.419139 0.927065 - -1.31708 -0.339774 1.0151 - -1.31094 -0.296359 1.01107 - -1.28991 -0.277908 0.997545 - -1.27988 -0.222107 0.990981 - -2.86211 -0.366934 2.00546 - -3.16783 -0.193074 2.201 - -3.19318 0.431775 2.21577 - -1.23016 0.221772 0.958059 - -1.22461 0.272056 0.954386 - -1.30698 0.360264 1.00697 - -3.1778 1.13043 2.20425 - -3.15878 1.21281 2.19186 - -3.16114 1.26789 2.19324 - -3.15807 1.28479 2.19123 - -3.12297 1.58441 2.16802 - -3.10315 1.68902 2.15507 - -3.04725 1.69651 2.11922 - -1.18537 0.750618 0.928096 - -1.1588 0.764235 0.911032 - -1.13794 0.877436 0.897392 - -1.01127 0.942865 0.816052 - -1.00823 0.956866 0.81407 - -0.990481 1.07225 0.802417 - -0.983301 1.16128 0.797604 - -0.951301 1.37417 0.776587 - -0.812356 1.39014 0.687492 - -0.275167 0.732319 0.344743 - -0.243595 0.674031 0.324645 - -0.207175 0.673505 0.301303 - -0.191317 0.675153 0.291134 - -0.181375 0.678531 0.284754 - -0.178438 0.677413 0.282874 - -0.0598714 0.270468 0.207845 - -0.0346942 0.120171 0.192065 - -0.0269958 0.0778365 0.187231 - -0.0257289 0.0749161 0.186426 - -0.0243594 0.0899798 0.185513 - -0.0219077 0.109995 0.183894 - -0.0210996 0.109982 0.183376 - -0.0183634 0.0908497 0.181668 - -0.0179452 0.0807984 0.181423 - -0.0167586 0.0806865 0.180663 --0.00834338 0.117756 0.175181 - -0.0076629 0.119658 0.174741 - 0.00195812 0.140961 0.168523 - 0.0135148 0.16649 0.161055 - 0.017557 0.175556 0.158443 - 0.021805 0.184523 0.155699 - 0.038829 0.228521 0.144683 - 0.0368038 0.179519 0.146097 - 0.0417141 0.18254 0.142943 - 0.057114 0.210548 0.133006 - 0.0961921 0.280292 0.107793 - 0.108702 0.29058 0.0997503 - 0.100344 0.258389 0.105184 - 0.0357253 0.0928948 0.146994 - 0.0520281 0.102964 0.136521 - 0.356633 0.504752 -0.0596705 - 0.333055 -0.415672 -0.0370693 - 0.0531757 -0.10424 0.137406 - 0.0417406 -0.0984304 0.144551 - 0.0268536 -0.0827763 0.153833 - 0.0259252 -0.0918791 0.154436 - 0.031046 -0.119519 0.151296 - 0.027689 -0.118174 0.153394 - 0.0412848 -0.170302 0.145006 - 0.0517631 -0.210707 0.138541 - 0.0144717 -0.125785 0.161686 - 0.0158657 -0.156718 0.160886 - 0.0135424 -0.157476 0.162343 - 0.00025218 -0.146641 0.170637 --0.00029025 -0.146755 0.170977 - -0.0127798 -0.0943494 0.178672 - -0.0146036 -0.0895535 0.179802 - -0.0164619 -0.0867366 0.180959 - -0.0171037 -0.0867923 0.181361 - -0.0197288 -0.112963 0.183066 - -0.0222373 -0.11 0.184629 - -0.0249086 -0.0899427 0.186254 - -0.0279357 -0.0807168 0.188128 - -0.0542465 -0.25316 0.205006 - -0.0613989 -0.284221 0.209556 - -0.108199 -0.366105 0.239047 - -0.113675 -0.3705 0.242486 - -0.132503 -0.37282 0.254278 - -0.154667 -0.382134 0.268175 - -0.160017 -0.374041 0.271505 - -0.167639 -0.376598 0.276283 - -0.168677 -0.374937 0.276928 - -0.172462 -0.371735 0.27929 - -0.21202 -0.372704 0.304057 - -0.223861 -0.366325 0.311454 - -0.230304 -0.3709 0.315499 - -0.282246 -0.385602 0.34805 - -0.319654 -0.421838 0.371554 - -1.32827 -1.71108 1.00601 - -1.32279 -1.64516 1.00242 - -1.30919 -1.55828 0.993702 - -1.34414 -1.47951 1.01539 - -0.380794 -0.374072 0.409716 - -0.382176 -0.372221 0.410577 - -0.388929 -0.366037 0.414789 - -0.396771 -0.370567 0.41971 - -0.409386 -0.372963 0.427612 - -0.422223 -0.358596 0.435615 - -0.402635 -0.313993 0.423247 - -0.611514 -0.334886 0.554058 - -1.18041 -0.416805 0.910392 - -1.17627 -0.408825 0.907779 - -1.19724 -0.357536 0.920789 - -1.29978 -0.346903 0.984953 - -1.29957 -0.285032 0.98468 - -1.28467 -0.228167 0.975213 - -0.280603 -0.0117528 0.346139 - -0.270516 -0.00873498 0.339818 - -0.266395 -0.00104739 0.33722 - -3.25538 0.302955 2.20766 - -3.26199 0.404479 2.21156 - -1.23786 0.208962 0.944877 - -1.23042 0.233147 0.940167 - -3.23539 0.912722 2.19371 - -3.25882 1.00794 2.20816 - -3.18989 1.10952 2.16476 - -3.17998 1.14149 2.15848 - -3.14197 1.45218 2.13396 - -3.13113 1.50287 2.12705 - -3.12486 1.57492 2.12295 - -3.12554 1.61324 2.12329 - -3.09742 1.67476 2.10554 - -1.29117 0.79684 0.976866 - -1.15903 0.790702 0.894155 - -1.17133 0.847794 0.901723 - -1.16433 0.875667 0.897273 - -1.05154 0.866708 0.826688 - -1.00966 0.960686 0.800246 - -0.965416 1.28004 0.771797 - -0.807435 1.3859 0.672648 - -0.685811 1.25228 0.596825 - -0.51934 1.00506 0.493194 - -0.144129 0.275964 0.260025 - -0.142085 0.277205 0.258743 - -0.132048 0.290601 0.252427 - -0.249357 0.670793 0.324968 - -0.225307 0.704688 0.309833 - -0.217582 0.6877 0.305037 - -0.164278 0.670594 0.271708 - -0.153953 0.699139 0.265176 - -0.0297659 0.083546 0.188886 - -0.0241422 0.0819733 0.185369 - -0.0238254 0.100986 0.185126 - -0.0230941 0.102996 0.184663 - -0.0182318 0.110891 0.181601 - -0.0118979 0.100238 0.177661 - 0.010683 0.159271 0.163385 - 0.0227222 0.185484 0.155787 - 0.031645 0.208428 0.150147 - 0.0404033 0.231378 0.14461 - 0.0399929 0.223125 0.144886 - 0.0451923 0.187725 0.141715 - 0.0577629 0.207402 0.133799 - 0.0653776 0.22197 0.128998 - 0.0978551 0.284485 0.108518 - 0.105338 0.295704 0.103808 - 0.0994966 0.262036 0.107544 - 0.0754095 0.197734 0.122775 - 0.0463782 0.129692 0.141109 - 0.0395654 0.113487 0.145412 - 0.0451167 0.106509 0.141954 - 0.0572425 0.116914 0.134338 - 0.36614 0.517943 -0.059984 - 0.569481 0.761836 -0.187855 - 0.326179 -0.422548 -0.0276331 - 0.0459588 -0.0991029 0.142911 - 0.0498413 -0.105713 0.140553 - 0.032941 -0.086863 0.15084 - 0.0300045 -0.0868741 0.152635 - 0.0277134 -0.102744 0.154073 - 0.0282055 -0.107003 0.153782 - 0.0290116 -0.112177 0.153302 - 0.0263913 -0.115985 0.154912 - 0.0397427 -0.16604 0.146868 - 0.0486072 -0.201827 0.141533 - 0.0148687 -0.155175 0.162048 - 0.00641093 -0.149397 0.167205 - 0.00585463 -0.14954 0.167545 --0.00249255 -0.143231 0.172633 - -0.0107357 -0.106212 0.177586 - -0.0199267 -0.103977 0.183199 - -0.0233532 -0.0999833 0.185284 - -0.0271035 -0.0737412 0.187515 - -0.0276524 -0.0736845 0.187851 - -0.0443751 -0.19419 0.198356 - -0.0546381 -0.250027 0.204761 - -0.0603272 -0.277313 0.208303 - -0.0682971 -0.309189 0.213249 - -0.0695993 -0.309931 0.214047 - -0.101768 -0.369208 0.233851 - -0.103142 -0.368794 0.23469 - -0.14606 -0.37456 0.26094 - -0.150235 -0.372618 0.263488 - -0.151375 -0.366669 0.264171 - -0.160171 -0.377504 0.269573 - -0.166474 -0.376434 0.273424 - -0.192738 -0.368957 0.289462 - -0.208291 -0.374745 0.298983 - -0.242054 -0.372018 0.319616 - -0.317553 -0.424114 0.365892 - -1.33266 -1.76716 0.989588 - -1.32968 -1.74766 0.987718 - -0.395447 -0.373763 0.413392 - -0.433818 -0.380391 0.436864 - -0.433888 -0.377049 0.436899 - -0.402206 -0.314797 0.417385 - -0.410369 -0.309774 0.422363 - -0.498 -0.351779 0.476032 - -0.516145 -0.347744 0.487115 - -0.53031 -0.34717 0.495772 - -0.544545 -0.34622 0.504472 - -0.561283 -0.350057 0.514714 - -0.622715 -0.339224 0.552242 - -0.679869 -0.303268 0.587097 - -0.794672 -0.320129 0.657317 - -1.17314 -0.424517 0.888921 - -1.17849 -0.400612 0.892137 - -1.17966 -0.362654 0.892765 - -1.31955 -0.336107 0.978218 - -1.31319 -0.31373 0.974278 - -1.28413 -0.239878 0.95634 - -1.47791 -0.178131 1.07466 - -3.23631 -0.326885 2.14994 - -0.291257 -0.0135543 0.348855 - -0.278561 -0.0102862 0.341085 - -0.274372 0.00796334 0.338482 - -3.28903 1.11874 2.17878 - -3.17757 1.13329 2.1106 - -3.1583 1.30418 2.09842 - -3.15605 1.37583 2.09688 - -3.13226 1.47522 2.0821 - -3.101 1.68506 2.0625 - -3.04985 1.69491 2.03121 - -2.91743 1.67564 1.95031 - -1.16508 0.758811 0.881221 - -1.16813 0.848354 0.88288 - -1.10935 0.876588 0.846876 - -1.01461 0.893287 0.788924 - -1.01196 0.898963 0.787288 - -1.01331 0.908327 0.788095 - -1.00876 0.945467 0.785222 - -1.00467 0.966944 0.782672 - -0.999939 1.00567 0.779691 - -0.998635 1.04935 0.778792 - -0.971654 1.20436 0.761935 - -0.952595 1.33507 0.749977 - -0.944963 1.39714 0.745166 - -0.939758 1.40184 0.741973 - -0.896812 1.39831 0.715728 - -0.874689 1.401 0.702198 - -0.863064 1.39472 0.695106 - -0.844869 1.3901 0.683994 - -0.82825 1.3877 0.67384 - -0.165862 0.301133 0.271462 - -0.138527 0.310389 0.25473 - -0.255513 0.677041 0.325385 - -0.252675 0.677297 0.32365 - -0.232591 0.677696 0.311371 - -0.200818 0.674395 0.291955 - -0.195701 0.686661 0.288799 - -0.193144 0.68754 0.287233 - -0.176211 0.685765 0.276886 - -0.165646 0.674476 0.270454 - -0.162525 0.672287 0.268552 - -0.0763161 0.335061 0.216641 - -0.0317041 0.100359 0.18992 - -0.0302107 0.0884779 0.189035 - -0.0266167 0.0738003 0.186872 - -0.0248799 0.0789271 0.185798 - -0.0243826 0.0729456 0.185508 - -0.0219521 0.108 0.18394 - -0.0180431 0.104896 0.181558 - -0.0168243 0.085786 0.180858 - -0.016287 0.0757058 0.180553 - -0.0128189 0.0903613 0.178398 - 0.0215258 0.177796 0.157198 - 0.0359643 0.189127 0.148345 - 0.0360853 0.186949 0.148276 - 0.0380085 0.180758 0.147115 - 0.042951 0.185978 0.144081 - 0.0469703 0.192681 0.141609 - 0.0767984 0.242711 0.123257 - 0.0948518 0.274645 0.112146 - 0.101628 0.287433 0.107973 - 0.104155 0.287044 0.10643 - 0.105224 0.286396 0.105778 - 0.0775791 0.206189 0.122865 - 0.0381008 0.110433 0.147224 - 0.0355903 0.102814 0.148776 - 0.0387339 0.0978391 0.146866 - 0.480409 0.665392 -0.124466 - 0.308875 -0.41203 -0.0112811 - 0.0385213 -0.0838542 0.148478 - 0.0509965 -0.106864 0.141124 - 0.0310343 -0.0879603 0.152933 - 0.0302167 -0.0874008 0.153417 - 0.0279485 -0.0867656 0.154762 - 0.0284893 -0.0911282 0.154451 - 0.0298942 -0.098358 0.153634 - 0.0217955 -0.0853376 0.158412 - 0.0243905 -0.0951405 0.156894 - 0.0267925 -0.116231 0.155517 - 0.0404432 -0.169425 0.147536 - 0.0286182 -0.157658 0.154529 - 0.0265542 -0.15321 0.155744 - 0.0225555 -0.146371 0.158103 - 0.0154945 -0.152099 0.162308 - 0.00995408 -0.154793 0.165604 --0.00208898 -0.134151 0.172707 --0.00323103 -0.133353 0.173383 - -0.0102934 -0.105219 0.177511 - -0.0165699 -0.0757949 0.181169 - -0.0167939 -0.0768162 0.181305 - -0.0164592 -0.0878156 0.181131 - -0.0167251 -0.0958493 0.181308 - -0.0171529 -0.102885 0.181578 - -0.0201845 -0.107992 0.18339 - -0.0245455 -0.0929254 0.185945 - -0.0268243 -0.0757342 0.187258 - -0.0374446 -0.146803 0.193729 - -0.0544363 -0.242943 0.204041 - -0.0868006 -0.35077 0.223508 - -0.127658 -0.37504 0.247824 - -0.140691 -0.381413 0.255577 - -0.142122 -0.380803 0.256425 - -0.146575 -0.37456 0.259055 - -0.150337 -0.376058 0.261292 - -0.166738 -0.384307 0.271049 - -0.188824 -0.366281 0.28412 - -0.212611 -0.370134 0.298253 - -0.223191 -0.368391 0.304531 - -0.23059 -0.367566 0.308922 - -0.243623 -0.365667 0.316656 - -0.269238 -0.372204 0.33188 - -1.33616 -1.82207 0.968734 - -1.32668 -1.74605 0.962929 - -1.29884 -1.52464 0.945883 - -1.29371 -1.50531 0.942793 - -0.39715 -0.376324 0.407837 - -0.427186 -0.36515 0.425645 - -0.606855 -0.350236 0.532288 - -0.612762 -0.34998 0.535795 - -0.625141 -0.345801 0.543135 - -0.694192 -0.315599 0.584064 - -0.695373 -0.31218 0.584757 - -0.696544 -0.289129 0.585399 - -0.726494 -0.289815 0.603183 - -0.817253 -0.318058 0.657137 - -1.18087 -0.430707 0.873294 - -1.17515 -0.383814 0.86979 - -1.3271 -0.32862 0.959885 - -1.29417 -0.286664 0.940232 - -3.4007 -0.289205 2.19099 - -0.267244 -0.0085263 0.32985 - -3.40608 0.399203 2.19258 - -3.41153 0.434629 2.19574 - -3.4175 0.487786 2.19915 - -3.43559 1.08526 2.2085 - -3.14611 1.43382 2.03582 - -3.12093 1.51388 2.02068 - -3.11897 1.55001 2.01943 - -3.11937 1.60638 2.01954 - -1.16169 0.758684 0.85914 - -1.15896 0.803501 0.857418 - -1.01371 0.918423 0.770904 - -0.990884 1.10825 0.756913 - -0.985582 1.1413 0.753688 - -0.98237 1.15751 0.751743 - -0.982187 1.16743 0.751611 - -0.971228 1.21624 0.744991 - -0.85323 1.39421 0.674516 - -0.84361 1.39099 0.668811 - -0.736668 1.26841 0.6056 - -0.731438 1.27118 0.602488 - -0.659205 1.234 0.559686 - -0.605735 1.14178 0.528153 - -0.238305 0.665063 0.311101 - -0.236713 0.668964 0.310147 - -0.190464 0.684559 0.28265 - -0.173493 0.682671 0.272578 - -0.158428 0.649942 0.263709 - -0.148002 0.636369 0.25755 - -0.0560237 0.239696 0.203861 - -0.0345116 0.119051 0.191369 - -0.0301852 0.0924544 0.188862 - -0.0181067 0.0999198 0.181673 - -0.0154242 0.0847028 0.180116 - -0.0147993 0.0806213 0.179754 - -0.0144969 0.0805864 0.179575 --0.00535161 0.125591 0.17404 --0.00256355 0.128106 0.172379 - 0.00810063 0.152128 0.165991 - 0.0955814 0.276137 0.113761 - 0.10216 0.273356 0.109861 - 0.0511569 0.146297 0.14044 - 0.0488448 0.137445 0.141833 - 0.0348804 0.102846 0.150205 - 0.0320122 0.0966741 0.151923 - 0.029174 0.0856661 0.153633 - 0.0547429 0.113409 0.138387 - 0.0447278 -0.101814 0.145776 - 0.0434453 -0.101666 0.146519 - 0.0284432 -0.0951869 0.155197 - 0.024058 -0.0911985 0.157729 - 0.0221823 -0.0901219 0.158813 - 0.0261265 -0.105832 0.156564 - 0.0368458 -0.15199 0.15046 - 0.0497837 -0.199976 0.143074 - 0.0511498 -0.214422 0.142316 - 0.0329111 -0.168919 0.152779 - 0.0237648 -0.146147 0.158026 --0.00219195 -0.137304 0.173046 - -0.017211 -0.111917 0.18169 - -0.0260467 -0.0697552 0.186712 - -0.0265733 -0.0697015 0.187017 - -0.0268364 -0.0696727 0.18717 - -0.0288935 -0.0865166 0.188401 - -0.0589456 -0.262319 0.206221 - -0.083533 -0.340342 0.220648 - -0.0925495 -0.358507 0.225915 - -0.0980418 -0.364188 0.22911 - -0.126287 -0.386166 0.245528 - -0.141604 -0.377989 0.254384 - -0.150128 -0.374201 0.259314 - -0.154259 -0.376582 0.261714 - -0.158852 -0.375449 0.264373 - -0.223613 -0.367548 0.30188 - -0.248908 -0.365828 0.316533 - -0.277674 -0.379605 0.333233 - -0.311756 -0.422363 0.353081 - -1.31758 -1.81763 0.939125 - -1.33081 -1.78791 0.946723 - -1.31388 -1.67381 0.936652 - -1.30729 -1.63628 0.932748 - -1.32389 -1.46636 0.941972 - -1.33315 -1.46393 0.947334 - -1.3418 -1.46075 0.952336 - -0.406577 -0.377012 0.40792 - -0.449154 -0.305896 0.432427 - -0.641997 -0.334191 0.544234 - -0.656612 -0.338161 0.552712 - -0.66988 -0.333385 0.560389 - -0.714009 -0.306897 0.585898 - -0.715497 -0.299544 0.586743 - -1.0801 -0.402778 0.79825 - -1.17721 -0.38855 0.854486 - -1.19318 -0.355712 0.863664 - -1.31548 -0.337462 0.934489 - -1.48997 -0.132382 1.03512 - -0.269262 -0.00855611 0.327501 - -0.265918 0.00144043 0.325541 - -3.49024 0.265702 2.19326 - -3.49574 0.407276 2.19611 - -3.48147 0.547163 2.18752 - -1.23628 0.210909 0.88733 - -1.23635 0.236048 0.887311 - -3.16331 1.21759 2.00161 - -3.16525 1.236 2.0027 - -3.12219 1.63566 1.97682 - -2.83867 1.66124 1.81248 - -1.16969 0.85462 0.847255 - -1.16426 0.875226 0.844061 - -1.14067 0.881728 0.830379 - -1.04501 0.868309 0.774977 - -1.00837 0.932802 0.753598 - -1.00868 0.966782 0.753703 - -0.998151 1.02618 0.747462 - -0.974144 1.19187 0.733168 - -0.976772 1.23776 0.734585 - -0.959869 1.32809 0.724582 - -0.956526 1.39635 0.722487 - -0.945956 1.40572 0.716341 - -0.694462 1.25738 0.570956 - -0.551923 1.05173 0.488837 - -0.187349 0.339577 0.279233 - -0.154555 0.27824 0.260372 - -0.141109 0.275138 0.252587 - -0.163284 0.382336 0.265189 - -0.244562 0.672364 0.311615 - -0.182899 0.685133 0.275855 - -0.0676656 0.297219 0.20998 - -0.0641335 0.28169 0.207969 - -0.0256307 0.0667971 0.186156 - -0.0253785 0.0668192 0.18601 - -0.0233137 0.0979681 0.184741 - -0.0210959 0.103 0.183444 - -0.0182962 0.105948 0.181815 - -0.0135481 0.0865557 0.179109 - -0.0118367 0.0903613 0.178108 --0.00725194 0.113869 0.175397 - 0.00309565 0.147347 0.169324 - 0.0427613 0.180426 0.146264 - 0.0992913 0.279118 0.113279 - 0.041255 0.122299 0.147271 - 0.0408407 0.119094 0.147518 - 0.040393 0.117071 0.147782 - 0.0506827 0.115183 0.141824 - 0.0505367 0.107836 0.141926 - 0.051349 0.107108 0.141457 - 0.0602306 0.118105 0.136285 - 0.322343 0.477161 -0.0164253 - 0.692731 0.869122 -0.231952 - 0.292225 -0.410013 0.00736433 - 0.0574181 -0.108864 0.139511 - 0.0285813 -0.089688 0.155781 - 0.0314723 -0.129908 0.154238 - 0.0186359 -0.138887 0.161521 - 0.015191 -0.148429 0.163492 - 0.0129316 -0.149122 0.164771 - 0.0103081 -0.153976 0.166267 - -0.0161825 -0.0978692 0.181125 - -0.0176916 -0.11095 0.182008 - -0.0219286 -0.112989 0.18441 - -0.0239836 -0.10993 0.185566 - -0.0244535 -0.0768728 0.185755 - -0.0247454 -0.0768528 0.185921 - -0.103145 -0.366858 0.23094 - -0.106828 -0.369877 0.233031 - -0.124191 -0.377585 0.242872 - -0.128213 -0.37504 0.245141 - -0.129637 -0.374496 0.245946 - -0.133328 -0.376221 0.248037 - -0.246699 -0.370886 0.312163 - -0.255881 -0.371951 0.317361 - -0.270924 -0.381538 0.325893 - -1.32335 -1.70634 0.924333 - -1.31475 -1.65093 0.919343 - -1.3128 -1.60562 0.918134 - -1.30767 -1.57147 0.915155 - -1.41211 -1.4388 0.973934 - -0.432026 -0.37235 0.417013 - -0.416157 -0.345292 0.407974 - -0.423333 -0.335876 0.412011 - -0.418789 -0.326022 0.409418 - -0.415326 -0.314308 0.407432 - -0.558969 -0.345982 0.488769 - -0.570936 -0.350057 0.495548 - -0.572263 -0.347294 0.496293 - -0.575108 -0.345476 0.497899 - -0.603211 -0.344292 0.513794 - -0.636162 -0.333062 0.53241 - -0.72469 -0.322167 0.582469 - -0.736532 -0.294741 0.589105 - -3.57116 -0.246541 2.19265 - -3.57208 -0.228738 2.19313 - -0.260844 -0.00582041 0.319327 - -0.263511 -0.00101465 0.320825 - -3.57018 0.288127 2.19087 - -3.56809 0.485334 2.18923 - -3.56835 0.539553 2.18925 - -1.21571 0.317953 0.858787 - -3.58065 1.11796 2.19488 - -3.16627 1.19421 1.96028 - -3.16585 1.21155 1.96 - -3.15688 1.27842 1.95477 - -3.1531 1.36592 1.95243 - -3.1384 1.43147 1.94397 - -3.12881 1.53657 1.9383 - -1.22386 0.645496 0.862646 - -1.21956 0.665266 0.860166 - -1.16001 0.764167 0.82625 - -1.10612 0.873887 0.79551 - -1.0174 0.879273 0.745303 - -1.01271 0.9153 0.74257 - -0.999599 1.0043 0.734947 - -0.993534 1.05188 0.731406 - -0.98967 1.104 0.729101 - -0.984228 1.14671 0.725924 - -0.961398 1.25455 0.71276 - -0.962262 1.30089 0.713143 - -0.954368 1.33672 0.708594 - -0.958374 1.37901 0.710763 - -0.769188 1.28691 0.603946 - -0.735975 1.26531 0.585205 - -0.70034 1.26164 0.565054 - -0.601374 1.12115 0.509388 - -0.591367 1.11284 0.503746 - -0.168786 0.303751 0.266535 - -0.154541 0.277365 0.258537 - -0.159615 0.371307 0.261192 - -0.262197 0.686316 0.318502 - -0.214868 0.706865 0.291679 - -0.17626 0.678027 0.269903 - -0.161381 0.659657 0.261528 - -0.0886639 0.383206 0.221025 - -0.0573216 0.244448 0.203612 - -0.0465677 0.192752 0.197647 - -0.0394671 0.148463 0.193731 - -0.0263302 0.0777366 0.186462 - -0.0194004 0.115989 0.182454 - -0.0148671 0.0767019 0.179979 - -0.0114295 0.0974095 0.177987 --0.00262468 0.124257 0.172944 - 0.00264671 0.141453 0.169922 - 0.00285234 0.139371 0.169811 - 0.0184563 0.168038 0.160917 - 0.0792829 0.246432 0.126325 - 0.0950028 0.260968 0.117398 - 0.0365497 0.100306 0.150837 - 0.0361075 0.0958368 0.151097 - 0.0604645 0.12372 0.137253 - 0.466342 0.655062 -0.0935874 - 0.699973 0.911345 -0.22635 - 0.711933 0.894554 -0.233078 - 0.336013 -0.428991 -0.0124534 - 0.309809 -0.422541 0.00199527 - 0.0480308 -0.0990064 0.145743 - 0.0384891 -0.0958893 0.151002 - 0.0253605 -0.0818467 0.158217 - 0.0261265 -0.0848431 0.157801 - 0.0277656 -0.0895669 0.156907 - 0.0237959 -0.0899035 0.159099 - 0.0290267 -0.110525 0.156259 - 0.0463983 -0.186089 0.146843 - 0.03242 -0.167573 0.154516 - 0.0247585 -0.153665 0.158713 - 0.0063173 -0.1459 0.168874 - 0.00352509 -0.146524 0.170416 --0.00074445 -0.133164 0.172742 - -0.0102823 -0.0963357 0.177923 - -0.0157236 -0.107879 0.180952 - -0.0190578 -0.104992 0.182786 - -0.0202574 -0.116 0.183473 - -0.0259971 -0.0787238 0.186556 - -0.0269371 -0.0756119 0.187068 - -0.0932205 -0.354249 0.224289 - -0.108615 -0.364178 0.232808 - -0.115492 -0.379618 0.236639 - -0.164739 -0.375157 0.263811 - -0.170835 -0.381902 0.267191 - -0.172293 -0.381147 0.267994 - -0.207967 -0.371368 0.287662 - -0.21042 -0.365089 0.289001 - -0.217333 -0.367323 0.292822 - -0.240747 -0.362984 0.305735 - -1.3297 -1.798 0.910053 - -1.3235 -1.74252 0.906504 - -0.413617 -0.383496 0.401197 - -0.413076 -0.379594 0.400889 - -0.425065 -0.370836 0.407487 - -0.568996 -0.343451 0.486866 - -0.604189 -0.335738 0.506273 - -0.628164 -0.334452 0.519503 - -0.715801 -0.32853 0.56786 - -1.1697 -0.400471 0.818549 - -1.16893 -0.375291 0.818069 - -1.20464 -0.355204 0.83773 - -1.29557 -0.282102 0.887753 - -1.28546 -0.273326 0.882154 - -3.64943 -0.214234 2.1868 - -0.269664 0.0101533 0.320843 - -0.31599 0.0135152 0.346405 - -3.64342 0.256113 2.18241 - -3.65299 0.329561 2.18752 - -3.65637 0.421201 2.18918 - -3.65387 0.439212 2.18776 - -1.22926 0.225882 0.849996 - -1.224 0.243411 0.847052 - -1.2189 0.279511 0.844155 - -1.21904 0.298255 0.844186 - -1.24998 0.403726 0.861024 - -1.21446 0.510892 0.841175 - -1.23257 0.546358 0.851088 - -1.17523 0.665752 0.81917 - -1.1681 0.742541 0.815059 - -1.16566 0.771392 0.813644 - -1.17262 0.871911 0.817259 - -1.04809 0.869292 0.74853 - -0.99332 1.06435 0.717853 - -0.973241 1.20914 0.70644 - -0.966706 1.24379 0.702754 - -0.953249 1.33981 0.695107 - -0.922575 1.40557 0.678026 - -0.746997 1.2659 0.581436 - -0.691324 1.25052 0.550743 - -0.662349 1.22028 0.53482 - -0.145708 0.263749 0.251847 - -0.1447 0.26437 0.25129 - -0.135253 0.272106 0.246058 - -0.133987 0.291515 0.245315 - -0.141342 0.314052 0.249323 - -0.18925 0.683482 0.274921 - -0.166024 0.666712 0.26214 - -0.0300349 0.0903296 0.188398 - -0.0292769 0.0864042 0.187989 - -0.0228298 0.108964 0.184379 - -0.022044 0.111984 0.183938 - -0.0186364 0.110981 0.18206 --0.00916968 0.100183 0.176859 --0.00699179 0.111957 0.175631 --0.00275862 0.130449 0.173252 - 0.0156561 0.16492 0.163009 - 0.0318679 0.198173 0.153985 - 0.0345608 0.193018 0.152511 - 0.0399896 0.172708 0.149561 - 0.0927147 0.256191 0.120269 - 0.084955 0.236029 0.124598 - 0.0407833 0.125894 0.149229 - 0.0310631 0.0929872 0.15467 - 0.0522257 0.114011 0.142941 - 0.0505912 0.110424 0.143851 - 0.246632 0.383256 0.0350245 - 0.364335 0.532872 -0.0302828 - 0.420088 0.604712 -0.0612193 - 0.265202 -0.392219 0.0313358 - 0.0473521 -0.0966491 0.147244 - 0.0431785 -0.0914609 0.149466 - 0.0520663 -0.110187 0.144752 - 0.0422948 -0.0996812 0.149957 - 0.0306628 -0.0856828 0.15615 - 0.0300022 -0.0861783 0.156505 - 0.0267383 -0.0861548 0.158251 - 0.028447 -0.091996 0.15735 - 0.0242192 -0.105857 0.159644 - 0.0378869 -0.150445 0.152431 - 0.0513363 -0.20475 0.145357 - 0.0431065 -0.193319 0.149735 - 0.0205496 -0.140789 0.161687 - 0.00694702 -0.14897 0.168985 - -0.0114952 -0.0895136 0.178719 - -0.0190172 -0.0999966 0.182768 - -0.0246298 -0.0737924 0.185712 - -0.0251749 -0.069729 0.185994 - -0.0447087 -0.183814 0.196706 - -0.0664869 -0.286088 0.208593 - -0.0764821 -0.323612 0.214027 - -0.0814939 -0.329584 0.216722 - -0.0887905 -0.346189 0.220664 - -0.0992685 -0.361854 0.226307 - -0.142685 -0.377989 0.249578 - -0.166729 -0.370053 0.262426 - -0.168152 -0.369321 0.263186 - -0.169941 -0.36949 0.264143 - -0.185821 -0.36963 0.272642 - -0.21724 -0.372704 0.289462 - -0.24894 -0.360961 0.306399 - -1.33823 -1.86283 0.892721 - -1.34539 -1.85628 0.896537 - -1.33178 -1.78878 0.8891 - -1.3012 -1.58556 0.872279 - -1.3067 -1.57846 0.875204 - -1.29475 -1.48384 0.868597 - -1.40124 -1.46038 0.92553 - -0.412131 -0.390008 0.393794 - -0.427535 -0.364309 0.401979 - -0.413793 -0.31848 0.394521 - -0.415462 -0.305276 0.395385 - -0.438069 -0.313707 0.407501 - -0.573395 -0.347636 0.479996 - -0.623733 -0.326259 0.506885 - -0.739927 -0.329434 0.569072 - -0.753537 -0.323052 0.57634 - -0.771644 -0.314 0.586009 - -1.16773 -0.384746 0.79813 - -1.1735 -0.361958 0.801165 - -1.31215 -0.317201 0.875258 - -1.28372 -0.264657 0.859926 - -1.28421 -0.2261 0.860099 - -3.73892 -0.218002 2.17368 - -0.265749 -0.00588368 0.314589 - -0.264043 -0.00100738 0.313665 - -0.264044 0.00140989 0.31366 - -0.264846 0.00747909 0.314075 - -1.2667 0.1684 0.849834 - -1.25813 0.210909 0.845155 - -1.2295 0.224428 0.829803 - -1.22943 0.242888 0.829723 - -1.22014 0.296552 0.82463 - -1.20113 0.468803 0.814066 - -1.19729 0.48698 0.811971 - -1.18571 0.568996 0.805588 - -1.1728 0.681566 0.798421 - -1.16758 0.707616 0.795571 - -1.17366 0.866938 0.798462 - -1.01508 0.890456 0.713547 - -1.0137 0.905276 0.712776 - -1.01638 0.915851 0.714187 - -1.00933 0.96755 0.710296 - -1.00252 0.977958 0.706628 - -0.987863 1.10797 0.69849 - -0.980757 1.17938 0.694525 - -0.958496 1.31492 0.682305 - -0.951516 1.38979 0.6784 - -0.142385 0.272748 0.247941 - -0.134612 0.275953 0.243774 - -0.131377 0.27435 0.242046 - -0.29461 0.733867 0.328355 - -0.248427 0.731676 0.303646 - -0.19857 0.683784 0.277075 - -0.180675 0.680143 0.267507 - -0.157275 0.636341 0.255084 - -0.0610262 0.251747 0.20445 - -0.045527 0.183731 0.196311 - -0.0320477 0.105103 0.189276 - -0.027214 0.0795676 0.186747 - -0.0243384 0.0778365 0.185212 - -0.0206646 0.105996 0.183182 - -0.0180671 0.115981 0.18177 - -0.0169416 0.107947 0.181186 - -0.0165873 0.105932 0.181001 - -0.0158868 0.102898 0.180633 - -0.015533 0.101879 0.180445 - -0.0142886 0.0847615 0.179818 - -0.012985 0.0846376 0.179121 - 0.00163641 0.134796 0.171183 - 0.00215488 0.134687 0.170906 - 0.0101041 0.150178 0.166617 - 0.0311577 0.201822 0.155233 - 0.0332265 0.196955 0.154137 - 0.0392681 0.168065 0.150969 - 0.0842877 0.250448 0.126691 - 0.0445107 0.134406 0.14824 - 0.0348975 0.0955631 0.153473 - 0.0534763 0.118716 0.143478 - 0.451081 0.647775 -0.0704934 - 0.464549 0.654567 -0.0777161 - 0.507737 0.694251 -0.100918 - 0.54316 0.721528 -0.119935 - 0.35972 -0.424127 -0.0141248 - 0.284854 -0.405525 0.0248994 - 0.276037 -0.400808 0.0294898 - 0.0371492 -0.0847015 0.153432 - 0.0279286 -0.111959 0.158305 - 0.0357416 -0.173221 0.154366 - 0.0284376 -0.161254 0.15815 - 0.022234 -0.146703 0.161355 - 0.0216663 -0.146906 0.161651 - 0.0119068 -0.136534 0.166721 - 0.0125227 -0.155925 0.166443 - 0.0119194 -0.15608 0.166758 - 0.00724784 -0.151062 0.169184 - -0.0139032 -0.0747468 0.180049 - -0.0142622 -0.0737759 0.180234 - -0.021998 -0.111959 0.184357 - -0.024834 -0.0777549 0.18576 - -0.0258669 -0.0756446 0.186294 - -0.0258939 -0.0726272 0.186301 - -0.174668 -0.367224 0.264598 - -0.194552 -0.371576 0.274984 - -0.199535 -0.374228 0.27759 - -0.217495 -0.371847 0.286957 - -0.220366 -0.36988 0.28845 - -0.230353 -0.369883 0.293661 - -0.306978 -0.418829 0.333756 - -1.328 -1.46257 0.868895 - -1.34313 -1.46662 0.876801 - -0.426729 -0.333527 0.396052 - -0.434537 -0.306703 0.400065 - -0.627012 -0.330114 0.500554 - -0.644456 -0.328284 0.509653 - -0.677446 -0.326087 0.526863 - -0.777508 -0.319117 0.579061 - -0.807977 -0.284096 0.594881 - -1.17295 -0.366041 0.785514 - -1.24982 -0.351482 0.825593 - -1.28816 -0.232036 0.845328 - -1.2943 -0.105819 0.84825 - -0.289619 -0.0117528 0.323779 - -1.24151 0.0853093 0.82027 - -1.23313 0.217812 0.815601 - -1.23019 0.26026 0.813971 - -1.19506 0.483553 0.795134 - -1.19793 0.497909 0.796599 - -1.18711 0.513081 0.790918 - -1.17986 0.632198 0.786867 - -1.16797 0.689654 0.780533 - -1.16163 0.729721 0.777137 - -1.15903 0.742932 0.775747 - -1.11197 0.847671 0.750955 - -1.02125 0.867695 0.703571 - -1.01389 0.908922 0.699638 - -0.999502 1.0224 0.691874 - -0.996363 1.05536 0.690162 - -0.98976 1.12395 0.686562 - -0.979306 1.16144 0.681022 - -0.977229 1.20022 0.679851 - -0.956547 1.294 0.668847 - -0.954885 1.30326 0.667959 - -0.956501 1.31721 0.66877 - -0.959683 1.33355 0.670394 - -0.951881 1.37088 0.666239 - -0.940569 1.40429 0.66026 - -0.906871 1.40345 0.642678 - -0.872478 1.40006 0.624739 - -0.805824 1.35292 0.590064 - -0.733194 1.27594 0.552338 - -0.721435 1.2795 0.546194 - -0.71092 1.2727 0.540723 - -0.669988 1.22114 0.51948 - -0.597943 1.10766 0.482142 - -0.151916 0.275178 0.251277 - -0.151387 0.342171 0.25085 - -0.299882 0.744916 0.327428 - -0.358752 1.15986 0.357211 - -0.199909 0.686661 0.275392 - -0.174008 0.661584 0.261933 - -0.171004 0.660399 0.260368 - -0.0845238 0.352509 0.215936 - -0.0410533 0.158155 0.193691 - -0.0269804 0.0775424 0.18653 - -0.0243129 0.0738003 0.185146 - -0.0235747 0.0818713 0.184743 - -0.016483 0.109946 0.180979 - -0.0152893 0.0978835 0.180383 - -0.014746 0.0868337 0.180125 - -0.0144101 0.0868094 0.179949 - -0.0140743 0.0867835 0.179774 --0.00368344 0.115625 0.174287 - 0.048711 0.185643 0.146789 - 0.0494288 0.185306 0.146415 - 0.0326704 0.0987888 0.155355 - 0.0382565 0.103131 0.15243 - 0.0407277 0.102518 0.151142 - 0.139716 0.233908 0.0991922 - 0.255639 0.400653 0.0383255 - 0.314885 0.473985 0.00724494 - 0.538838 0.777464 -0.110302 - 0.76938 0.93726 -0.230962 - 0.350984 -0.436975 -0.00351088 - 0.294845 -0.415453 0.02482 - 0.0295351 -0.0979966 0.158228 - 0.0297043 -0.104707 0.158157 - 0.0306748 -0.121975 0.157705 - 0.0388651 -0.150728 0.153629 - 0.0393247 -0.153771 0.153404 - 0.0253716 -0.157399 0.160465 - 0.0129745 -0.118765 0.166646 - 0.01369 -0.146541 0.166346 --0.00355122 -0.11877 0.175 --0.00495905 -0.114952 0.175703 --0.00720924 -0.103178 0.176814 - -0.0151018 -0.108919 0.180817 - -0.0197622 -0.107995 0.183171 - -0.0231773 -0.0838612 0.184843 - -0.0236923 -0.071798 0.185076 - -0.0259922 -0.0785966 0.186254 - -0.0328797 -0.114929 0.189817 - -0.0931104 -0.353275 0.220799 - -0.113088 -0.374318 0.230945 - -0.132124 -0.379236 0.240579 - -0.150805 -0.370487 0.250003 - -0.164401 -0.374958 0.256887 - -0.169852 -0.37114 0.259633 - -0.172738 -0.369647 0.261089 - -0.184907 -0.373052 0.267248 - -0.194402 -0.377723 0.272059 - -0.194826 -0.370694 0.272257 - -0.228881 -0.369234 0.28947 - -0.236573 -0.368399 0.293356 - -0.244376 -0.370954 0.297306 - -0.281385 -0.386642 0.31605 - -1.29752 -1.48295 0.832183 - -1.38464 -1.4642 0.87618 - -0.415452 -0.399816 0.383853 - -0.415342 -0.313644 0.383604 - -0.457838 -0.306995 0.405072 - -0.620933 -0.324909 0.487559 - -0.680883 -0.32973 0.517876 - -0.702724 -0.328659 0.528914 - -1.27755 -0.209751 0.819232 - -1.27414 -0.134408 0.81734 - -1.27426 -0.122042 0.817373 - -1.26984 -0.109295 0.815108 - -1.22057 -0.0636961 0.7901 - -0.956179 -0.040499 0.656395 - -0.358761 -0.01302 0.354328 - -1.24413 0.151342 0.801531 - -1.23454 0.216712 0.796534 - -1.22587 0.27611 0.792021 - -1.21445 0.341156 0.7861 - -1.21189 0.396888 0.784682 - -1.20279 0.406482 0.78006 - -1.20044 0.418341 0.778846 - -1.2014 0.437825 0.779288 - -1.19683 0.468287 0.776908 - -1.18562 0.555787 0.771048 - -1.07343 0.62901 0.714169 - -1.03032 0.736629 0.692133 - -1.02157 0.809416 0.687546 - -1.01843 0.844556 0.685879 - -1.0123 0.910004 0.682634 - -1.00999 0.924154 0.681434 - -0.990575 1.09873 0.67123 - -0.978217 1.16321 0.664838 - -0.974285 1.22101 0.66272 - -0.953897 1.34116 0.652145 - -0.887644 1.40326 0.618514 - -0.854758 1.4017 0.601893 - -0.186871 0.329183 0.266668 - -0.175916 0.310844 0.26117 - -0.145285 0.274808 0.245767 - -0.133606 0.272334 0.239868 - -0.133364 0.287859 0.239711 - -0.248113 0.668629 0.296866 - -0.377206 1.16517 0.361012 - -0.227623 0.764255 0.286293 - -0.200182 0.696182 0.272574 - -0.159229 0.629835 0.25202 - -0.155714 0.625654 0.250253 - -0.1236 0.497481 0.234305 - -0.0268484 0.0775049 0.186337 - -0.0252112 0.0726688 0.18552 - -0.0239943 0.0757949 0.184898 - -0.0217544 0.101954 0.183707 - -0.0181349 0.107995 0.181864 - -0.0173551 0.103983 0.181479 - -0.0148142 0.0888745 0.180228 - -0.0132039 0.0777272 0.179439 - -0.0129013 0.0776981 0.179286 - -0.0100332 0.0914457 0.177806 - 0.0168585 0.164127 0.164048 - 0.0255383 0.189504 0.159604 - 0.0382032 0.171364 0.153242 - 0.0465632 0.179501 0.148998 - 0.0607127 0.205356 0.141787 - 0.0834923 0.2354 0.130204 - 0.0622397 0.1825 0.141066 - 0.0502747 0.112849 0.147271 - 0.580869 0.815117 -0.122528 - 0.732048 0.934263 -0.199218 - 0.357928 -0.434785 -0.00216159 - 0.303807 -0.424617 0.0244754 - 0.264103 -0.396228 0.04397 - 0.0586684 -0.114267 0.144536 - 0.0467084 -0.0992453 0.150394 - 0.0388781 -0.0931726 0.154238 - 0.0303437 -0.105832 0.15847 - 0.0305143 -0.114668 0.158406 - 0.0370697 -0.144295 0.155243 - 0.0399836 -0.163518 0.15385 - 0.0429622 -0.174038 0.152406 - 0.0480886 -0.198628 0.149936 - 0.012491 -0.114933 0.167284 - 0.0129171 -0.135566 0.16712 - 0.0117498 -0.137955 0.167701 - 0.0101805 -0.141448 0.168481 - 0.0096267 -0.141585 0.168755 - 0.00334072 -0.134831 0.171836 --0.00830961 -0.0963357 0.177489 - -0.0130892 -0.0817787 0.179811 - -0.0137296 -0.0818281 0.180126 - -0.0181408 -0.100999 0.182342 - -0.0252829 -0.074617 0.185801 - -0.0629636 -0.267409 0.204792 - -0.078222 -0.320099 0.212426 - -0.114116 -0.365701 0.230209 - -0.125229 -0.360798 0.235672 - -0.140586 -0.373898 0.243266 - -0.146423 -0.371461 0.246136 - -0.159317 -0.374299 0.252493 - -0.198834 -0.366325 0.271941 - -0.227183 -0.368567 0.285911 - -0.237815 -0.369233 0.291149 - -0.244209 -0.372883 0.294307 - -0.278564 -0.381073 0.311248 - -1.31647 -1.66383 0.825372 - -1.31143 -1.61416 0.822778 - -1.29569 -1.56674 0.814917 - -1.44649 -1.48355 0.889016 - -1.44881 -1.46014 0.890104 - -0.407983 -0.387227 0.375012 - -0.408305 -0.380785 0.375157 - -0.412066 -0.374412 0.376995 - -0.427564 -0.37559 0.384632 - -0.405157 -0.336453 0.373507 - -0.409308 -0.337014 0.375553 - -0.427803 -0.331179 0.384651 - -0.417746 -0.31422 0.379659 - -0.427981 -0.304676 0.384679 - -0.682753 -0.325283 0.510223 - -0.750053 -0.31654 0.543355 - -1.18169 -0.352571 0.756053 - -1.23212 -0.355204 0.780903 - -1.27798 -0.34904 0.80348 - -1.31604 -0.326243 0.822174 - -1.28585 -0.267195 0.807171 - -1.27435 -0.139947 0.801227 - -0.970524 0.0424648 0.651156 - -1.23842 0.0782034 0.783041 - -1.23885 0.125979 0.783143 - -1.23885 0.18007 0.783026 - -1.2369 0.216084 0.781981 - -1.23044 0.257451 0.778711 - -1.22169 0.304433 0.774293 - -1.21803 0.321958 0.77245 - -1.21547 0.333611 0.771165 - -1.09799 0.536545 0.712841 - -1.05966 0.54813 0.693937 - -1.05346 0.55103 0.690877 - -1.05527 0.583266 0.691697 - -1.0324 0.755839 0.680043 - -1.0301 0.775661 0.678869 - -1.024 0.785465 0.675841 - -1.01584 0.85368 0.67167 - -1.01693 0.918031 0.672062 - -1.00361 1.0156 0.665285 - -0.858118 1.38766 0.592787 - -0.141507 0.274844 0.242273 - -0.136991 0.270632 0.240058 - -0.315694 0.799395 0.326907 - -0.261048 0.677297 0.300261 - -0.223493 0.758561 0.28158 - -0.189898 0.676743 0.265214 - -0.181997 0.667764 0.261342 - -0.170592 0.643207 0.255779 - -0.158683 0.625953 0.249951 - -0.151323 0.604281 0.246374 - -0.0340339 0.11877 0.189681 - -0.0298224 0.0951876 0.187659 - -0.0257036 0.0755893 0.185674 - -0.0232129 0.0788344 0.18444 - -0.0229043 0.078856 0.184288 - -0.0185846 0.108 0.182095 --0.00808645 0.0952757 0.176952 - 0.00228362 0.131947 0.171762 - 0.00695863 0.143174 0.169434 - 0.0280248 0.175426 0.158985 - 0.0469562 0.178576 0.149653 - 0.0791987 0.233748 0.133647 - 0.0733059 0.21474 0.136592 - 0.0339833 0.10353 0.15621 - 0.0391225 0.105962 0.153673 - 0.0364672 0.0972139 0.155001 - 0.513165 0.772294 -0.0813204 - 0.587656 0.864743 -0.11822 - 0.665865 0.958921 -0.156955 - 0.531832 0.718136 -0.0903948 - 0.544189 0.708804 -0.0964611 - 0.793235 0.953208 -0.219684 - 0.338319 -0.431593 0.0121937 - 0.333799 -0.437472 0.0143735 - 0.305786 -0.420764 0.0277657 - 0.293189 -0.411616 0.0337843 - 0.0328514 -0.127024 0.157956 - 0.0374328 -0.148789 0.155808 - 0.0413667 -0.167523 0.153964 - 0.031088 -0.170518 0.158898 - 0.0127366 -0.139898 0.167628 - 0.00773426 -0.144196 0.170035 --0.00125819 -0.121582 0.174296 --0.00282021 -0.120825 0.175043 - -0.0122667 -0.0827487 0.179487 - -0.0140698 -0.0938948 0.180376 - -0.019942 -0.114981 0.183238 - -0.0260897 -0.0744736 0.186096 - -0.032314 -0.111889 0.189162 - -0.0370579 -0.136378 0.191491 - -0.0623053 -0.264459 0.203878 - -0.0921829 -0.342214 0.218374 - -0.150441 -0.377356 0.24638 - -0.158261 -0.370611 0.250114 - -0.192956 -0.372403 0.26675 - -0.196059 -0.367187 0.268226 - -0.203002 -0.369814 0.271561 - -0.214324 -0.373018 0.276995 - -0.221498 -0.375275 0.280439 - -0.247207 -0.362699 0.292736 - -1.30503 -1.62669 0.80265 - -1.29341 -1.48961 0.796777 - -0.424489 -0.367906 0.377735 - -0.411746 -0.340759 0.371566 - -0.427349 -0.329417 0.37902 - -0.465568 -0.303733 0.397285 - -0.499568 -0.304785 0.413587 - -0.547594 -0.30525 0.436611 - -0.650483 -0.333997 0.485999 - -0.785009 -0.325855 0.550471 - -0.845867 -0.306483 0.579603 - -0.858011 -0.29748 0.585405 - -0.869487 -0.283475 0.590875 - -1.30498 -0.302306 0.799687 - -1.30263 -0.295263 0.798546 - -1.28368 -0.233842 0.789326 - -1.27541 -0.194942 0.785272 - -1.27128 -0.108362 0.783103 - -0.267027 0.00260904 0.301427 - -0.284948 0.00925434 0.310004 - -1.23775 0.0837032 0.766602 - -1.23896 0.107531 0.767131 - -1.23853 0.113437 0.766912 - -1.23667 0.154938 0.765926 - -1.21128 0.264138 0.753514 - -1.21137 0.288249 0.753502 - -1.20579 0.311064 0.750779 - -1.20456 0.316807 0.750176 - -1.17539 0.326839 0.736169 - -1.09812 0.355604 0.699063 - -1.09012 0.364281 0.695206 - -1.07177 0.391767 0.68635 - -1.06877 0.407684 0.684877 - -1.06723 0.418509 0.684114 - -1.06727 0.424265 0.684122 - -1.0656 0.429336 0.683308 - -1.06887 0.448089 0.684836 - -1.05412 0.605201 0.677416 - -1.02979 0.715422 0.66551 - -1.02925 0.721932 0.665234 - -1.02677 0.769424 0.663938 - -1.02114 0.816222 0.661136 - -1.02372 0.825827 0.662353 - -1.01821 0.843978 0.65967 - -1.01541 0.872486 0.658267 - -1.01063 0.899872 0.655912 - -1.00663 0.978974 0.653819 - -0.970442 1.24789 0.635876 - -0.952334 1.36271 0.62694 - -0.78821 1.32778 0.548338 - -0.255171 0.684504 0.294232 - -0.246469 0.714704 0.289993 - -0.0740869 0.291532 0.208293 - -0.0300982 0.0940849 0.187643 - -0.0224112 0.0768596 0.183996 - -0.0173366 0.106995 0.181497 - 0.00311131 0.133916 0.171635 - 0.0100915 0.15075 0.168251 - 0.0108717 0.151589 0.167875 - 0.0252161 0.179627 0.160937 - 0.0384836 0.175013 0.154586 - 0.038336 0.167618 0.154674 - 0.0493643 0.185382 0.149347 - 0.0400339 0.125304 0.153953 - 0.0393609 0.105108 0.154321 - 0.046365 0.106065 0.150961 - 0.77688 1.09821 -0.201441 - 0.526541 0.719641 -0.0805915 - 0.538384 0.709732 -0.0862469 - 0.36896 -0.430681 0.00249249 - 0.36491 -0.433668 0.00438839 - 0.291872 -0.41461 0.0384169 - 0.0447402 -0.0958156 0.152996 - 0.0423189 -0.0964707 0.154127 - 0.0419371 -0.0967586 0.154306 - 0.032686 -0.0890853 0.158604 - 0.0236699 -0.083322 0.162797 - 0.0278341 -0.095615 0.160882 - 0.0237174 -0.140789 0.162902 - 0.0110857 -0.114695 0.168737 - 0.0103196 -0.139633 0.169149 - 0.00430164 -0.13789 0.171953 - -0.00323 -0.113892 0.175413 --0.00676522 -0.102295 0.177037 - -0.0103862 -0.0805982 0.178678 - -0.0156603 -0.104976 0.181192 - -0.0169138 -0.103996 0.181775 - -0.0186051 -0.109995 0.182577 - -0.0367551 -0.136378 0.191102 - -0.0979316 -0.355063 0.220122 - -0.100737 -0.354275 0.221429 - -0.16322 -0.37821 0.250629 - -0.200394 -0.383052 0.26798 - -0.205881 -0.370659 0.270513 - -0.210156 -0.371434 0.272509 - -0.215007 -0.36948 0.274767 - -0.234368 -0.368002 0.283795 - -0.279581 -0.386795 0.304928 - -0.323861 -0.440065 0.325701 - -1.30372 -1.60323 0.785356 - -1.30945 -1.59627 0.788013 - -1.29506 -1.48454 0.781053 - -1.40535 -1.49076 0.832516 - -0.413897 -0.400306 0.367614 - -0.409644 -0.389119 0.365605 - -0.407539 -0.37364 0.364589 - -0.408481 -0.342691 0.36496 - -0.409834 -0.340806 0.365587 - -0.427233 -0.337126 0.373695 - -0.41808 -0.311914 0.36937 - -0.423245 -0.307233 0.371769 - -0.576085 -0.303404 0.443058 - -0.683783 -0.322871 0.49334 - -0.712588 -0.324921 0.506781 - -0.873951 -0.288176 0.581973 - -0.913698 -0.273468 0.600482 - -1.28481 -0.258122 0.773566 - -1.27521 -0.169365 0.768893 - -1.25007 -0.0762274 0.756956 - -0.272409 -0.00102193 0.300731 - -0.264218 0.00494464 0.296897 - -0.31392 0.0116495 0.320067 - -1.23678 0.0891405 0.750393 - -1.1021 0.174352 0.687381 - -1.0977 0.21098 0.685244 - -1.08709 0.230209 0.680257 - -1.0905 0.247062 0.681806 - -1.07126 0.423923 0.672441 - -1.02379 0.778001 0.649518 - -1.00586 0.940111 0.640798 - -1.00218 1.01355 0.638919 - -0.998172 1.01828 0.637036 - -0.993845 1.04068 0.634969 - -0.986135 1.12655 0.631182 - -0.964298 1.25627 0.62071 - -0.961876 1.28693 0.619512 - -0.956749 1.30301 0.617085 - -0.885501 1.39347 0.58365 - -0.174449 0.30562 0.254358 - -0.146273 0.272415 0.241288 - -0.142216 0.272458 0.239395 - -0.132055 0.276719 0.234646 - -0.299503 0.750414 0.311711 - -0.243851 0.66709 0.285935 - -0.380968 1.21495 0.348688 - -0.117374 0.440593 0.227435 - -0.0730162 0.286641 0.207083 - -0.0252162 0.0815932 0.185238 - -0.0245707 0.0816613 0.184937 - -0.0206813 0.104953 0.183071 - -0.0164364 0.112989 0.181073 - -0.0070226 0.0932396 0.176725 - 0.00660015 0.13839 0.170271 - 0.0177557 0.163329 0.165012 - 0.0338758 0.178056 0.15746 - 0.0374189 0.165077 0.155835 - 0.066125 0.218092 0.142328 - 0.0362706 0.110949 0.156491 - 0.0459572 0.109284 0.151976 - 0.0531185 0.114839 0.148623 - 0.238923 0.389739 0.0613419 - 0.636923 0.941183 -0.125535 - 0.728279 1.06288 -0.168419 - 0.31796 -0.427533 0.0305151 - 0.0507588 -0.103936 0.151069 - 0.0504526 -0.111471 0.151225 - 0.0352284 -0.0889408 0.158085 - 0.0311878 -0.0870078 0.159914 - 0.023012 -0.078364 0.163606 - 0.0329586 -0.113288 0.159168 - 0.029273 -0.108572 0.16083 - 0.0272647 -0.106288 0.161737 - 0.0466551 -0.190503 0.153122 - 0.0397139 -0.179422 0.156248 - 0.0158761 -0.117494 0.16693 - 0.0100968 -0.106854 0.16953 - 0.0140459 -0.135717 0.167801 - 0.00242501 -0.13326 0.173069 --0.00113464 -0.122729 0.174662 --0.00624353 -0.0992633 0.176929 - -0.011557 -0.0807547 0.179299 - -0.02199 -0.0778291 0.184028 - -0.0243697 -0.0766068 0.185105 - -0.0255575 -0.0734417 0.185637 - -0.060408 -0.243409 0.201827 - -0.0643922 -0.25987 0.203671 - -0.12126 -0.367599 0.229716 - -0.124362 -0.372817 0.231136 - -0.138275 -0.375074 0.237455 - -0.15246 -0.37671 0.243896 - -0.170594 -0.382477 0.252138 - -0.178311 -0.366455 0.255605 - -0.228184 -0.366877 0.27824 - -0.270906 -0.379632 0.297657 - -1.31563 -1.75997 0.774821 - -1.43527 -1.5028 0.82855 - -0.410131 -0.381355 0.360846 - -0.429751 -0.373048 0.369732 - -0.42497 -0.301638 0.367405 - -0.459456 -0.300115 0.383053 - -0.544693 -0.294672 0.421724 - -0.545861 -0.292142 0.422249 - -0.551433 -0.28883 0.42477 - -0.558306 -0.289331 0.427891 - -0.737914 -0.315139 0.509459 - -0.884215 -0.308634 0.575841 - -0.887171 -0.305084 0.577175 - -1.32115 -0.336113 0.774198 - -1.27825 -0.236929 0.754508 - -1.27379 -0.229899 0.752472 - -1.26466 -0.106807 0.748057 - -1.26508 -0.100829 0.748234 - -0.264133 0.0001969 0.293749 - -0.266856 0.00259013 0.294979 - -0.281345 0.00780193 0.301544 - -1.11139 0.105982 0.678031 - -1.10309 0.16843 0.674127 - -1.09614 0.204418 0.670891 - -1.09184 0.230209 0.668885 - -1.09828 0.291314 0.671674 - -1.0862 0.337405 0.666089 - -1.07416 0.417494 0.660451 - -1.07056 0.4564 0.658732 - -1.06046 0.498869 0.654054 - -1.04339 0.612535 0.646058 - -1.044 0.658243 0.646234 - -1.04138 0.663153 0.645034 - -1.03838 0.701366 0.643587 - -1.02574 0.726743 0.637798 - -1.01365 0.943378 0.631834 - -1.00146 0.973699 0.626236 - -1.00048 0.998619 0.625737 - -0.994054 1.06384 0.622675 - -0.973845 1.23034 0.613138 - -0.963603 1.2723 0.608398 - -0.956627 1.32066 0.605126 - -0.178835 0.313456 0.25435 - -0.141838 0.268292 0.237659 - -0.140515 0.271263 0.237052 - -0.132201 0.276719 0.233266 - -0.261095 0.670793 0.290897 - -0.243017 0.699618 0.28263 - -0.210497 0.739363 0.267784 - -0.133262 0.49191 0.233275 - -0.0722752 0.277577 0.206068 - -0.0592709 0.236605 0.200257 - -0.0561204 0.224029 0.198854 - -0.0327201 0.11276 0.188479 - -0.0237407 0.0726688 0.184492 - -0.0206976 0.0929307 0.183066 - -0.0203506 0.106952 0.182878 - -0.0195006 0.106976 0.182492 - -0.0126746 0.0908497 0.17943 --0.00381454 0.105948 0.175376 - -0.0024353 0.109769 0.174741 - 0.00185938 0.126229 0.172756 - 0.0232555 0.160893 0.16297 - 0.0238945 0.160697 0.16268 - 0.0245328 0.160497 0.162391 - 0.0264436 0.165093 0.161514 - 0.0321333 0.177833 0.158903 - 0.0357539 0.167061 0.157284 - 0.0384017 0.166015 0.156085 - 0.0393978 0.162397 0.15564 - 0.0613636 0.208733 0.14557 - 0.0674389 0.216767 0.142795 - 0.0580421 0.177576 0.147146 - 0.0399118 0.12614 0.155487 - 0.0404566 0.114529 0.155265 - 0.0387695 0.100567 0.156061 - 0.144997 0.252212 0.107519 - 0.259757 0.422608 0.0550623 - 0.804236 1.11377 -0.193558 - 0.78409 0.960031 -0.184077 - 0.381603 -0.435893 0.0066388 - 0.312949 -0.426145 0.0369153 - 0.280961 -0.40954 0.0509958 - 0.267696 -0.405629 0.056841 - 0.221662 -0.355831 0.0770475 - 0.201415 -0.328634 0.0859233 - 0.046904 -0.102548 0.153617 - 0.0262018 -0.0916028 0.162729 - 0.0258359 -0.0918074 0.162891 - 0.0242849 -0.0904209 0.163572 - 0.029455 -0.108794 0.161331 - 0.0356097 -0.135356 0.158673 - 0.0357769 -0.13745 0.158604 - 0.0359004 -0.172636 0.158626 - 0.0308435 -0.160766 0.160832 - 0.0196498 -0.126873 0.165698 - 0.0169717 -0.119404 0.166863 - -0.0173694 -0.106998 0.181991 - -0.0286585 -0.0910952 0.186938 - -0.0300609 -0.0959239 0.187568 - -0.0466392 -0.184135 0.195077 - -0.0672603 -0.270419 0.204366 - -0.0957009 -0.345362 0.217081 - -0.101661 -0.358147 0.219739 - -0.133311 -0.380185 0.233755 - -0.136951 -0.375651 0.235351 - -0.144255 -0.382353 0.238589 - -0.150864 -0.376424 0.241493 - -0.169837 -0.370965 0.249854 - -0.179963 -0.37354 0.254329 - -0.189029 -0.373128 0.258329 - -0.212873 -0.378448 0.268863 - -0.224888 -0.363647 0.274133 - -0.252928 -0.36485 0.28651 - -1.31436 -1.84748 0.758175 - -1.32907 -1.83502 0.764639 - -1.30188 -1.62926 0.75219 - -1.3558 -1.47541 0.775647 - -1.41259 -1.48518 0.800731 - -1.43825 -1.49933 0.812087 - -0.43129 -0.373048 0.365241 - -0.430653 -0.328243 0.364862 - -0.424842 -0.314797 0.362268 - -0.425726 -0.30108 0.362628 - -0.44889 -0.306288 0.372862 - -0.464438 -0.311278 0.379735 - -0.468614 -0.296303 0.381545 - -0.474511 -0.297209 0.384149 - -0.683393 -0.327634 0.476398 - -0.858481 -0.307117 0.553622 - -0.93064 -0.299862 0.585451 - -0.964652 -0.267153 0.600389 - -1.16505 -0.265838 0.688825 - -1.14836 -0.200511 0.681315 - -1.13986 -0.160699 0.677476 - -1.13566 -0.149254 0.675598 - -0.849607 -0.0390759 0.54912 - -0.265801 0.00138444 0.29139 - -1.1021 0.146495 0.660143 - -1.09353 0.250972 0.656134 - -1.07715 0.327655 0.648737 - -1.07584 0.332707 0.648147 - -1.08062 0.367404 0.650181 - -1.06923 0.413769 0.645051 - -1.0659 0.435193 0.643535 - -1.05181 0.602214 0.636955 - -1.04846 0.625737 0.635423 - -1.04276 0.628691 0.632902 - -1.03865 0.632589 0.63108 - -1.04468 0.669075 0.633659 - -1.04148 0.707318 0.632164 - -1.03172 0.73488 0.627796 - -1.03036 0.769159 0.627122 - -1.01677 0.934049 0.620766 - -1.0062 0.948923 0.616068 - -1.00649 0.983111 0.616121 - -0.979186 1.15846 0.603686 - -0.968838 1.22956 0.598964 - -0.97128 1.25474 0.599987 - -0.963409 1.32461 0.596361 - -0.93759 1.39826 0.584805 - -0.909401 1.40654 0.572347 - -0.84529 1.39453 0.54408 - -0.726747 1.25398 0.492073 - -0.715765 1.25898 0.487216 - -0.142178 0.271564 0.236243 - -0.141093 0.272158 0.235763 - -0.139197 0.270952 0.234929 - -0.13273 0.280914 0.232053 - -0.156363 0.350427 0.242331 - -0.0870401 0.325164 0.211793 - -0.0391331 0.140952 0.191054 - -0.0384192 0.140069 0.190741 - -0.0357991 0.12635 0.189614 - -0.0298366 0.0969958 0.187047 - -0.0245771 0.0825882 0.184758 - -0.0117046 0.0878072 0.179065 - 0.00415288 0.130962 0.171973 - 0.0165087 0.14956 0.166479 - 0.0192771 0.156017 0.165244 - 0.0253737 0.156254 0.162553 - 0.0288959 0.166581 0.160976 - 0.0334097 0.155495 0.159008 - 0.0427025 0.165567 0.154885 - 0.0373809 0.11783 0.157338 - 0.0429507 0.114554 0.154887 - 0.0450271 0.107358 0.153986 - 0.0551111 0.115665 0.149518 - 0.37529 0.595382 0.00716995 - 0.801598 1.10445 -0.182078 - 0.542047 0.715096 -0.0666833 - 0.385543 -0.43399 0.00986615 - 0.375579 -0.430681 0.0141329 - 0.331211 -0.427928 0.0331583 - 0.313647 -0.424617 0.0406851 - 0.296964 -0.42146 0.0478346 - 0.228192 -0.366677 0.077215 - 0.0331534 -0.0900417 0.160274 - 0.0283845 -0.092959 0.162326 - 0.00883682 -0.101323 0.170729 - 0.00802345 -0.101559 0.171079 - 0.01071 -0.133774 0.169996 - 0.00818492 -0.138429 0.17109 - 0.00596125 -0.138875 0.172044 --0.00754179 -0.089472 0.177729 --0.00844401 -0.0875634 0.178112 - -0.0118342 -0.0838469 0.179558 - -0.0299935 -0.0979017 0.187378 - -0.0317838 -0.104683 0.188161 - -0.109811 -0.359884 0.222186 - -0.147729 -0.376755 0.238487 - -0.148547 -0.364618 0.238812 - -0.151468 -0.363349 0.240061 - -0.164097 -0.37821 0.245511 - -0.189662 -0.36963 0.256458 - -0.201129 -0.369835 0.261378 - -0.20736 -0.370659 0.264052 - -0.212816 -0.36611 0.266383 - -0.242235 -0.3709 0.279012 - -0.248231 -0.370128 0.281583 - -0.248673 -0.367376 0.281766 - -1.3391 -1.85786 0.752745 - -1.31597 -1.68427 0.742446 - -1.30067 -1.57853 0.735651 - -1.30638 -1.57167 0.738086 - -1.43105 -1.49843 0.791407 - -1.45027 -1.50558 0.799667 - -1.47497 -1.49186 0.810231 - -0.42171 -0.379585 0.356016 - -0.422629 -0.338758 0.356322 - -0.42551 -0.305535 0.357485 - -0.431447 -0.301346 0.360023 - -0.447373 -0.304112 0.36686 - -0.46552 -0.299036 0.374633 - -0.550633 -0.28618 0.411114 - -0.562844 -0.286301 0.416353 - -0.584052 -0.284239 0.425445 - -0.62101 -0.292372 0.441316 - -0.698341 -0.322048 0.474551 - -0.885118 -0.297312 0.554615 - -1.15351 -0.267717 0.669678 - -1.13887 -0.176182 0.663198 - -1.11852 -0.0672167 0.65423 - -0.313263 0.0100985 0.308651 - -1.10386 0.161871 0.647446 - -1.10537 0.209759 0.647987 - -1.09915 0.224498 0.645288 - -1.09441 0.250138 0.6432 - -1.08293 0.377843 0.637997 - -1.06483 0.455872 0.630061 - -1.06076 0.477252 0.628271 - -1.06198 0.567943 0.628595 - -1.0462 0.628202 0.621695 - -1.04367 0.633082 0.620602 - -1.04117 0.677289 0.619431 - -1.03405 0.699304 0.61633 - -1.02283 0.840884 0.611208 - -0.94348 1.40151 0.575952 - -0.880118 1.40669 0.548762 - -0.774387 1.30725 0.503625 - -0.209047 0.366531 0.263172 - -0.145594 0.269753 0.236164 - -0.134198 0.271429 0.231272 - -0.133211 0.27854 0.230833 - -0.132093 0.27909 0.230353 - -0.250745 0.672546 0.280392 - -0.240397 0.784247 0.27571 - -0.0926345 0.331901 0.213312 - -0.0422506 0.154514 0.192086 - -0.0382071 0.137009 0.19039 - -0.0298884 0.0999651 0.186902 - -0.0277242 0.092213 0.185991 - -0.0253063 0.0834668 0.184973 - -0.0192167 0.109964 0.182303 - -0.0151876 0.114989 0.180564 - -0.0107983 0.089776 0.178736 --0.00950355 0.0836418 0.178194 --0.00695412 0.0883753 0.17709 --0.00166906 0.111819 0.174772 - 0.00605454 0.129665 0.17142 - 0.022826 0.157229 0.164166 - 0.0279129 0.166053 0.161965 - 0.0680692 0.211773 0.14464 - 0.0313153 0.0911228 0.160668 - 0.0316804 0.0908943 0.160512 - 0.0476222 0.10959 0.153633 - 0.0503157 0.108869 0.152479 - 0.0795252 0.154954 0.13985 - 0.550529 0.703272 -0.0633792 - 0.782462 0.931842 -0.163364 - 0.3361 -0.431675 0.0351733 - 0.323104 -0.430656 0.0405941 - 0.301555 -0.425348 0.0495748 - 0.263231 -0.401933 0.0655167 - 0.0301873 -0.0888126 0.162085 - 0.0270718 -0.0940019 0.163397 - 0.026693 -0.0942052 0.163555 - 0.0408832 -0.15303 0.157761 - 0.0447619 -0.181408 0.156204 - 0.044343 -0.182635 0.156382 - 0.00879101 -0.104579 0.171048 - 0.00960496 -0.125962 0.170755 - 0.00579356 -0.134936 0.172365 --0.00957114 -0.081693 0.178661 - -0.0111457 -0.0778138 0.17931 - -0.0130354 -0.11095 0.18017 - -0.0200183 -0.0868966 0.183032 - -0.020079 -0.0808857 0.183044 - -0.0209956 -0.0798247 0.183424 - -0.0209313 -0.0738158 0.183384 - -0.0240038 -0.0775301 0.184675 - -0.0846511 -0.321487 0.210511 - -0.107391 -0.356471 0.220076 - -0.122426 -0.365189 0.226369 - -0.146597 -0.373015 0.236472 - -0.170413 -0.375345 0.246415 - -0.190598 -0.374913 0.254838 - -0.209849 -0.367095 0.262854 - -1.32586 -1.78331 0.731626 - -1.31692 -1.67891 0.727669 - -1.37533 -1.47183 0.751595 - -0.434859 -0.373684 0.356763 - -0.426539 -0.331746 0.3532 - -0.430098 -0.331584 0.354685 - -0.467026 -0.299036 0.370025 - -0.522645 -0.3007 0.393238 - -0.536432 -0.302514 0.398995 - -0.541685 -0.296028 0.401173 - -0.563408 -0.282414 0.410208 - -0.569011 -0.278915 0.412539 - -0.778629 -0.324852 0.50011 - -0.85421 -0.3076 0.531612 - -1.15224 -0.227264 0.655804 - -1.14537 -0.187439 0.652853 - -1.13452 -0.0998141 0.648134 - -1.13492 -0.0945253 0.648288 - -1.13321 -0.0784544 0.647542 - -0.265313 0.00490828 0.285192 - -0.271724 0.00745218 0.287862 - -1.10256 0.145392 0.634264 - -1.10396 0.251389 0.634619 - -1.07281 0.469219 0.62115 - -1.05936 0.564368 0.615328 - -1.02914 0.734149 0.60235 - -1.02341 0.830649 0.599749 - -1.00878 0.935663 0.593419 - -1.00219 0.979704 0.590574 - -0.990219 1.04693 0.585432 - -0.975301 1.15486 0.578973 - -0.980145 1.19167 0.580915 - -0.977157 1.19848 0.579653 - -0.904939 1.40171 0.549077 - -0.881786 1.4042 0.53941 - -0.707881 1.24772 0.46718 - -0.174484 0.30637 0.246637 - -0.159824 0.280865 0.240575 - -0.142732 0.269183 0.233468 - -0.14056 0.270367 0.232559 - -0.150386 0.330532 0.236528 - -0.392878 1.23775 0.335753 - -0.123006 0.417335 0.224915 - -0.0996255 0.349566 0.215305 - -0.0480384 0.181778 0.194142 - -0.0226175 0.0797005 0.183755 - -0.0130857 0.109946 0.179712 --0.00953482 0.0866958 0.178281 - 0.0351289 0.163778 0.159476 - 0.0364463 0.163286 0.158927 - 0.0584493 0.190485 0.149687 - 0.0592159 0.19013 0.149367 - 0.0534616 0.165558 0.151822 - 0.036737 0.11885 0.158902 - 0.0361103 0.113615 0.159175 - 0.0492674 0.111276 0.15369 - 0.812938 1.17033 -0.16728 - 0.560945 0.744905 -0.0612027 - 0.755606 0.91214 -0.142796 - 0.307415 -0.430791 0.0511144 - 0.296968 -0.420602 0.0553235 - 0.202761 -0.336842 0.0932962 - 0.0484231 -0.107703 0.155308 - 0.0455714 -0.104918 0.156457 - 0.0286251 -0.0900952 0.163288 - 0.0237085 -0.0827093 0.165263 - 0.0359791 -0.138191 0.160413 - 0.0443832 -0.180753 0.157101 - 0.014751 -0.106031 0.168941 - 0.00825517 -0.105895 0.171571 --0.00355852 -0.107204 0.176359 - -0.0140108 -0.107985 0.180594 - -0.0207387 -0.0768084 0.183251 - -0.0214325 -0.0777549 0.183534 - -0.024767 -0.0763772 0.184882 - -0.0264 -0.0791636 0.185549 - -0.0330441 -0.111436 0.188309 - -0.114608 -0.37193 0.221905 - -0.155664 -0.373545 0.238535 - -0.178632 -0.372507 0.247835 - -0.187368 -0.371262 0.251371 - -0.198678 -0.367187 0.255942 - -0.223459 -0.369158 0.265983 - -0.246381 -0.36874 0.275265 - -0.247782 -0.364081 0.275822 - -0.267005 -0.376372 0.283634 - -1.33144 -1.84906 0.717902 - -1.2897 -1.486 0.700216 - -1.32295 -1.48526 0.713678 - -1.36804 -1.52312 0.732022 - -1.39271 -1.45891 0.741874 - -0.407094 -0.390003 0.340399 - -0.421589 -0.376976 0.346241 - -0.430605 -0.365378 0.349867 - -0.403092 -0.332118 0.338653 - -0.427428 -0.337431 0.348521 - -0.43341 -0.327068 0.350921 - -0.425994 -0.31249 0.347886 - -0.541942 -0.307831 0.394834 - -0.541094 -0.294645 0.394462 - -0.561403 -0.286705 0.40267 - -0.774183 -0.325866 0.488929 - -0.820428 -0.306805 0.507617 - -0.836539 -0.308606 0.514146 - -0.846546 -0.307987 0.518197 - -0.899457 -0.290801 0.539589 - -1.00656 -0.290661 0.582963 - -1.14941 -0.236859 0.640703 - -1.14401 -0.175611 0.638382 - -1.14605 -0.159661 0.639176 - -1.12864 -0.0883541 0.631972 - -0.583499 -0.0236212 0.411051 - -0.266888 -0.00571497 0.282787 - -0.26691 -0.00453273 0.282793 - -0.266939 -0.002168 0.2828 - -1.11329 0.14625 0.625249 - -1.10573 0.176599 0.622118 - -1.09256 0.285116 0.616552 - -1.0914 0.290181 0.616071 - -1.0809 0.379762 0.611625 - -1.08006 0.413092 0.611215 - -1.06822 0.471142 0.606292 - -1.05094 0.626245 0.59896 - -1.03518 0.701436 0.592414 - -1.02438 0.79136 0.587848 - -1.02133 0.840748 0.586504 - -1.00275 0.985033 0.578668 - -0.978403 1.15411 0.568444 - -0.957506 1.28944 0.559689 - -0.955657 1.39629 0.55871 - -0.923902 1.39982 0.545841 - -0.899025 1.40011 0.535765 - -0.864056 1.39642 0.521611 - -0.847219 1.39509 0.514795 - -0.587375 1.05778 0.410288 - -0.579386 1.05353 0.407061 - -0.157111 0.278033 0.237716 - -0.178613 0.408989 0.246141 - -0.359538 0.895507 0.318365 - -0.262078 0.666148 0.279389 - -0.253978 0.669562 0.276101 - -0.350699 1.12885 0.314282 - -0.0787562 0.294308 0.205947 - -0.0396922 0.142704 0.190453 - -0.0341327 0.118368 0.188254 - -0.031724 0.108658 0.1873 - -0.0191059 0.10294 0.182202 - -0.0153417 0.106998 0.180669 - -0.014925 0.104995 0.180504 - -0.0125482 0.113944 0.179522 --0.00988199 0.0807455 0.178514 --0.00848789 0.0816166 0.177948 - 1.712e-05 0.110684 0.174441 - 0.0102708 0.135088 0.170235 - 0.010817 0.134963 0.170014 - 0.0146639 0.142234 0.168441 - 0.0310457 0.160187 0.161767 - 0.0319757 0.160917 0.161389 - 0.0362767 0.167812 0.159632 - 0.0342876 0.107118 0.160569 - 0.0407599 0.115889 0.157929 - 0.0462532 0.110235 0.155716 - 0.0594232 0.127293 0.150346 - 0.246069 0.414742 0.0741347 - 0.625837 0.988211 -0.0809068 - 0.659248 1.03007 -0.0945283 - 0.778295 1.16791 -0.143039 - 0.808668 1.1177 -0.155232 - 0.694191 0.920514 -0.108444 - 0.729327 0.876774 -0.122579 - 0.340558 -0.432424 0.0420966 - 0.313869 -0.429279 0.0525686 - 0.306271 -0.426903 0.0555466 - 0.299896 -0.425984 0.0580477 - 0.19134 -0.323218 0.100448 - 0.164878 -0.284487 0.110755 - 0.093967 -0.174183 0.138359 - 0.0439703 -0.0981705 0.157826 - 0.0443405 -0.10266 0.15769 - 0.0353583 -0.0898051 0.161189 - 0.0341512 -0.0894167 0.161662 - 0.0315017 -0.0899035 0.162704 - 0.0266841 -0.0926084 0.164601 - 0.0267439 -0.0959049 0.164585 - 0.0443175 -0.181033 0.157868 - 0.0149317 -0.113452 0.16926 - 0.0144707 -0.113593 0.169441 - 0.0113976 -0.107238 0.170634 - 0.0110494 -0.127915 0.170815 - 0.00896774 -0.128389 0.171634 - 0.00079877 -0.112686 0.174807 --0.00057543 -0.112902 0.175347 --0.00995602 -0.0828018 0.178966 - -0.0130898 -0.110975 0.180257 - -0.0166598 -0.107989 0.181652 - -0.0188369 -0.0859152 0.182459 - -0.0228993 -0.0805864 0.184043 - -0.0240912 -0.0824594 0.184515 - -0.0247608 -0.0823738 0.184777 - -0.0266984 -0.0841113 0.185542 - -0.104696 -0.352077 0.216741 - -0.122153 -0.369509 0.223633 - -0.146374 -0.376439 0.233158 - -0.185174 -0.37816 0.248395 - -0.188241 -0.376551 0.249596 - -0.194989 -0.370629 0.252233 - -0.196493 -0.369783 0.252821 - -0.231827 -0.375686 0.266707 - -1.33449 -1.82941 0.702764 - -1.3121 -1.7042 0.693702 - -1.32338 -1.42904 0.697541 - -1.32517 -1.38187 0.698143 - -0.421931 -0.382762 0.341362 - -0.441968 -0.377497 0.349217 - -0.416556 -0.336453 0.339152 - -0.541274 -0.293723 0.388027 - -0.545302 -0.289686 0.3896 - -0.805254 -0.325139 0.491739 - -1.04837 -0.255412 0.587044 - -1.1369 -0.120452 0.621513 - -1.13831 -0.115288 0.622055 - -1.14188 -0.0943698 0.623413 - -1.11353 -0.071302 0.612231 - -0.34187 -0.0119948 0.309131 - -0.310284 0.0099109 0.296683 - -1.11869 0.135912 0.613813 - -1.11721 0.140964 0.61322 - -1.10167 0.175263 0.607044 - -1.10371 0.180811 0.607834 - -1.10051 0.195933 0.606544 - -1.0871 0.309348 0.601037 - -1.08675 0.347247 0.600817 - -1.08082 0.383817 0.59841 - -1.07503 0.39281 0.596116 - -1.06769 0.417892 0.593182 - -1.0703 0.441547 0.594155 - -1.01956 0.843622 0.573369 - -1.00776 0.935725 0.56854 - -0.945684 1.40182 0.543165 - -0.939985 1.40616 0.540918 - -0.733765 1.25991 0.460266 - -0.204745 0.356109 0.254501 - -0.132711 0.276719 0.22639 - -0.143203 0.31222 0.230433 - -0.256564 0.675165 0.274161 - -0.389412 1.21875 0.325153 - -0.359065 1.15362 0.313378 - -0.113656 0.374471 0.218698 - -0.0919147 0.312415 0.210295 - -0.0800096 0.294984 0.205659 - -0.0352186 0.124195 0.18844 - -0.0267546 0.0871523 0.185196 - -0.018085 0.111964 0.181739 - -0.0162003 0.103996 0.181016 - -0.0153555 0.104 0.180684 - -0.0149211 0.106998 0.180507 --0.00039642 0.110829 0.174796 - 5.362e-05 0.110758 0.17462 - 0.00050336 0.110684 0.174443 - 0.0118411 0.131778 0.169947 - 0.0243051 0.156264 0.165 - 0.0349708 0.154791 0.160816 - 0.0423399 0.165746 0.157899 - 0.048868 0.113653 0.155448 - 0.23031 0.391113 0.0836131 - 0.81133 1.15685 -0.146155 - 0.776202 1.03104 -0.132092 - 0.556569 0.725386 -0.0452024 - 0.546039 0.69955 -0.0410126 - 0.745753 0.876297 -0.119805 - 0.749308 0.872718 -0.121193 - 0.0484506 -0.108599 0.156846 - 0.0299384 -0.0922838 0.163859 - 0.0313059 -0.0971554 0.163348 - 0.028844 -0.0940019 0.164279 - 0.0245552 -0.0906613 0.165905 - 0.0456106 -0.188205 0.158097 - 0.0397913 -0.177636 0.16029 - 0.0119492 -0.102041 0.170728 - 0.0115329 -0.102165 0.170887 - 0.0106989 -0.102408 0.171205 - 0.00879888 -0.101899 0.171927 - 0.00973696 -0.124244 0.171618 - 0.00923017 -0.124357 0.171811 - 0.00967406 -0.132425 0.171659 - 0.00651275 -0.126958 0.172851 - 0.00583259 -0.126071 0.173108 - 0.00142048 -0.12075 0.174777 - -0.0100917 -0.084845 0.179083 - -0.0113853 -0.108936 0.179627 - -0.0136316 -0.106992 0.180478 - -0.0185933 -0.111929 0.182377 - -0.0187931 -0.104916 0.182438 - -0.0198312 -0.0798247 0.18278 - -0.0206206 -0.0817699 0.183085 - -0.0231935 -0.077492 0.184055 - -0.0259968 -0.084164 0.185137 - -0.0339276 -0.115207 0.188222 - -0.0466798 -0.174705 0.193205 - -0.121907 -0.368554 0.22226 - -0.159777 -0.374058 0.236689 - -0.167747 -0.371497 0.239718 - -0.223831 -0.371847 0.261071 - -0.225831 -0.371722 0.261832 - -0.235873 -0.37092 0.265653 - -0.244425 -0.36733 0.268901 - -0.269817 -0.375185 0.278585 - -1.31917 -1.85102 0.681247 - -0.418963 -0.409944 0.335442 - -0.435771 -0.380885 0.341779 - -0.415657 -0.337713 0.334029 - -0.417032 -0.335838 0.334548 - -0.436519 -0.336528 0.341969 - -0.430879 -0.31422 0.339774 - -0.582955 -0.286212 0.397612 - -0.775328 -0.324016 0.470931 - -0.808431 -0.329563 0.483546 - -0.831191 -0.312951 0.492176 - -1.06929 -0.285702 0.582767 - -1.14979 -0.224178 0.613283 - -1.14978 -0.2187 0.613266 - -1.14839 -0.164176 0.612621 - -1.15062 -0.15371 0.613448 - -1.14685 -0.137114 0.611975 - -1.1396 -0.10441 0.609144 - -1.13308 -0.0775489 0.606606 - -0.350247 -0.0122682 0.30843 - -0.266303 0.0048901 0.276434 - -0.304482 0.0110439 0.290956 - -1.07072 0.0550839 0.58258 - -1.11064 0.134431 0.59761 - -1.11009 0.139545 0.597388 - -1.09651 0.236294 0.592012 - -1.09402 0.267405 0.590998 - -1.09293 0.27244 0.59057 - -1.08624 0.334948 0.587891 - -1.08838 0.3685 0.588635 - -1.06275 0.442448 0.578716 - -1.04813 0.558024 0.572903 - -1.0459 0.644119 0.571869 - -1.03304 0.735569 0.566778 - -1.02993 0.775445 0.56551 - -1.00941 0.877923 0.557479 - -1.00396 0.953609 0.555243 - -0.9984 0.973484 0.553082 - -0.98415 1.13247 0.547316 - -0.966981 1.24751 0.540534 - -0.966137 1.26883 0.540167 - -0.958834 1.3169 0.537283 - -0.955514 1.34844 0.535952 - -0.914341 1.40089 0.520165 - -0.877955 1.39576 0.506323 - -0.14061 0.272746 0.228008 - -0.133442 0.271984 0.22528 - -0.25127 0.676459 0.269274 - -0.245745 0.678636 0.267166 - -0.324716 0.962777 0.296623 - -0.401305 1.21805 0.325235 - -0.0996201 0.326736 0.212287 - -0.0740277 0.273843 0.202657 - -0.0615504 0.229685 0.198001 - -0.0386216 0.136691 0.18947 - -0.0212183 0.0767117 0.182973 --0.00864438 0.0907447 0.178156 - 0.00517536 0.1221 0.172827 - 0.00736247 0.128789 0.171981 - 0.0508489 0.176422 0.155323 - 0.0515679 0.176113 0.15505 - 0.0375943 0.112721 0.160505 - 0.0375671 0.100296 0.160542 - 0.0587862 0.128691 0.152403 - 0.0607858 0.130895 0.151637 - 0.096259 0.18851 0.138008 - 0.154656 0.276678 0.115587 - 0.778567 1.06686 -0.123636 - 0.546274 0.696522 -0.0344063 - 0.571301 0.690166 -0.0439208 - 0.747617 0.851795 -0.111393 - 0.359921 -0.432071 0.0433443 - 0.347681 -0.429074 0.0478543 - 0.32674 -0.429963 0.0555831 - 0.320241 -0.43314 0.0579882 - 0.304913 -0.424504 0.0636255 - 0.295633 -0.423401 0.0670476 - 0.280724 -0.421687 0.0725453 - 0.276764 -0.419838 0.0740026 - 0.241605 -0.390114 0.0869125 - 0.191866 -0.329421 0.105137 - 0.0847394 -0.16148 0.144308 - 0.0279836 -0.106811 0.165134 - 0.0335869 -0.157912 0.163175 - 0.030652 -0.150513 0.164242 - 0.0167309 -0.109043 0.169291 - 0.0128723 -0.101915 0.170699 - -0.0101776 -0.0818713 0.179162 - -0.0176902 -0.109946 0.181994 - -0.0201016 -0.0847884 0.18283 - -0.0202103 -0.0727447 0.182844 - -0.0202628 -0.069729 0.182857 - -0.0235371 -0.0753852 0.184078 - -0.0262418 -0.0810364 0.185088 - -0.0453279 -0.168816 0.192318 - -0.0498621 -0.189264 0.194034 - -0.0554224 -0.209484 0.196129 - -0.067738 -0.255748 0.200772 - -0.0879 -0.319514 0.208348 - -0.0955938 -0.340137 0.211231 - -0.106799 -0.354544 0.215396 - -0.151907 -0.376424 0.232087 - -0.158051 -0.373806 0.234349 - -0.172518 -0.373699 0.239687 - -0.179728 -0.369029 0.242337 - -0.203046 -0.377755 0.25096 - -0.257762 -0.370068 0.271134 - -1.32722 -1.85581 0.668927 - -1.29455 -1.47499 0.656059 - -1.31176 -1.36971 0.662184 - -1.31621 -1.35061 0.663786 - -0.404476 -0.394124 0.325321 - -0.410874 -0.386805 0.327667 - -0.431563 -0.308045 0.335133 - -0.502411 -0.302893 0.361265 - -0.54213 -0.292339 0.375898 - -0.576466 -0.28847 0.38856 - -0.616393 -0.291892 0.4033 - -0.762154 -0.325437 0.457156 - -0.805417 -0.314573 0.473097 - -0.822465 -0.308567 0.479375 - -0.828145 -0.306472 0.481466 - -0.866857 -0.303317 0.495744 - -1.14639 -0.222726 0.59872 - -0.340824 -0.0118923 0.301019 - -0.262179 0.00479921 0.271964 - -0.310863 0.00987963 0.289918 - -1.11577 0.0726458 0.58679 - -1.1163 0.0932778 0.58694 - -1.11458 0.124091 0.586242 - -1.11407 0.129205 0.586041 - -1.10528 0.14875 0.582759 - -1.10391 0.210817 0.582121 - -1.10371 0.25291 0.581956 - -1.08663 0.269911 0.575618 - -1.09871 0.288968 0.580034 - -1.08164 0.354007 0.573598 - -1.07696 0.424223 0.57172 - -1.07873 0.430578 0.572358 - -1.06616 0.499879 0.567573 - -1.0641 0.504764 0.566805 - -1.05783 0.519359 0.564457 - -1.05523 0.529903 0.563478 - -1.06267 0.545706 0.566188 - -1.05711 0.573148 0.564076 - -1.05419 0.59624 0.56295 - -1.04164 0.671682 0.558161 - -1.03842 0.696057 0.556918 - -1.03642 0.728587 0.556114 - -1.01343 0.902114 0.547258 - -1.00622 0.960906 0.544475 - -1.00643 0.969562 0.544534 - -1.00197 0.990852 0.542841 - -0.992426 1.00732 0.539284 - -0.989699 1.09607 0.538089 - -0.98508 1.11986 0.536334 - -0.98381 1.14816 0.535805 - -0.983476 1.15788 0.535661 - -0.963541 1.29543 0.528012 - -0.958617 1.31214 0.526159 - -0.954055 1.32965 0.524439 - -0.949168 1.33481 0.522624 - -0.824418 1.38209 0.476491 - -0.153979 0.271016 0.231471 - -0.134282 0.273797 0.224198 - -0.383265 0.949108 0.314631 - -0.266238 0.681259 0.27202 - -0.249966 0.680369 0.266018 - -0.0965269 0.31517 0.210178 - -0.0916948 0.312415 0.208401 - -0.031431 0.110556 0.186594 - -0.0231432 0.0804858 0.1836 - -0.0195143 0.0758186 0.182271 - -0.0176639 0.108951 0.181518 - -0.0132147 0.107989 0.179878 --0.00982727 0.0958646 0.178654 --0.00758734 0.0806546 0.17786 --0.00472676 0.0883753 0.176788 --0.00305646 0.0962154 0.176155 - 0.0163393 0.13708 0.168911 - 0.0260743 0.156076 0.165278 - 0.0337948 0.160917 0.162419 - 0.0337088 0.151471 0.162471 - 0.0452061 0.172581 0.158183 - 0.0442358 0.122913 0.158647 - 0.0364502 0.0990304 0.161571 - 0.0417887 0.105008 0.159588 - 0.140209 0.258801 0.122944 - 0.481703 0.762102 -0.00413845 - 0.724193 1.10337 -0.0943437 - 0.730213 0.850717 -0.0960261 - 0.739954 0.839523 -0.0995969 - 0.362545 -0.436758 0.0469159 - 0.322463 -0.426179 0.0612014 - 0.234458 -0.384234 0.0925271 - 0.0486258 -0.104629 0.158269 - 0.0337984 -0.0872842 0.163525 - 0.0285705 -0.0835204 0.165383 - 0.0299644 -0.0929036 0.164905 - 0.0249468 -0.0921179 0.166695 - 0.026085 -0.0970538 0.166299 - 0.0384457 -0.138191 0.161974 - 0.0419255 -0.163549 0.160786 - 0.0213471 -0.121315 0.168042 - 0.0161042 -0.10837 0.169886 - 0.0116018 -0.113787 0.171504 - 0.00921268 -0.124577 0.17238 - 0.0051044 -0.125363 0.173848 --0.00963619 -0.0838682 0.179022 - -0.012864 -0.101992 0.180213 - -0.0201064 -0.0807455 0.182753 - -0.0284219 -0.0907271 0.185743 - -0.0383639 -0.135559 0.189387 - -0.0888558 -0.318199 0.207798 - -0.133703 -0.373944 0.223926 - -0.151344 -0.37456 0.230224 - -0.176596 -0.378418 0.239247 - -0.17815 -0.37766 0.2398 - -0.231721 -0.36958 0.258906 - -1.32875 -1.80175 0.653548 - -1.32719 -1.76752 0.652919 - -0.408561 -0.393675 0.322082 - -0.443511 -0.378855 0.334527 - -0.445065 -0.376861 0.335077 - -0.438219 -0.33593 0.332546 - -0.444764 -0.33494 0.334881 - -0.430212 -0.311914 0.329637 - -0.485943 -0.303636 0.349514 - -0.615736 -0.29065 0.395818 - -0.677676 -0.294935 0.417937 - -0.72143 -0.302885 0.433573 - -0.745414 -0.309221 0.442147 - -0.793575 -0.321243 0.459365 - -0.848136 -0.308606 0.478814 - -1.08055 -0.2815 0.561721 - -1.1494 -0.233437 0.586195 - -1.15035 -0.228174 0.586524 - -1.15036 -0.222726 0.586514 - -1.14421 -0.119955 0.584103 - -0.273114 0.0001998 0.272896 - -1.10968 0.143676 0.571214 - -1.10566 0.153427 0.56976 - -1.09762 0.224464 0.56674 - -1.08534 0.354007 0.562081 - -1.08688 0.365444 0.562607 - -1.08384 0.375368 0.561502 - -1.07693 0.451046 0.558874 - -1.06027 0.610218 0.552588 - -1.05841 0.628152 0.551884 - -1.04631 0.646384 0.547529 - -1.03052 0.784888 0.541598 - -1.02729 0.789587 0.540434 - -1.02036 0.85829 0.537816 - -1.01903 0.86483 0.537324 - -1.01502 0.941028 0.535732 - -0.995979 1.03425 0.528737 - -0.989558 1.07329 0.526363 - -0.9897 1.08285 0.526393 - -0.990449 1.10278 0.526618 - -0.972352 1.14071 0.520078 - -0.978606 1.17884 0.522229 - -0.956819 1.2935 0.514208 - -0.939452 1.40392 0.507774 - -0.933677 1.40819 0.505704 - -0.852083 1.3973 0.476601 - -0.747806 1.27185 0.439644 - -0.181071 0.313456 0.239375 - -0.150077 0.268776 0.228406 - -0.145883 0.268865 0.226909 - -0.137375 0.27448 0.223859 - -0.134376 0.277076 0.222783 - -0.155976 0.342435 0.230355 - -0.309505 0.965548 0.283836 - -0.058759 0.213843 0.195925 - -0.0550421 0.204464 0.194618 - -0.0250414 0.0852227 0.184162 - -0.0218565 0.0815932 0.183033 - -0.0136669 0.109998 0.180049 --0.00415649 0.0893683 0.176698 --0.00091077 0.10304 0.175511 - 0.00599157 0.118069 0.173015 - 0.0111408 0.126161 0.17116 - 0.0134 0.131778 0.170341 - 0.0261653 0.162432 0.165719 - 0.0268325 0.162244 0.165482 - 0.0262603 0.157229 0.165696 - 0.0344049 0.160917 0.162781 - 0.0483211 0.172664 0.157789 - 0.0500543 0.175168 0.157165 - 0.0421837 0.140794 0.160047 - 0.0508888 0.117131 0.15699 - 0.128618 0.242431 0.128977 - 0.473726 0.725813 0.00475936 - 0.753929 1.10149 -0.096061 - 0.772718 1.06872 -0.102698 - 0.769473 1.01772 -0.101432 - 0.561448 0.715096 -0.0265316 - 0.377138 -0.435524 0.0474419 - 0.287538 -0.426497 0.0780912 - 0.285213 -0.427077 0.0788883 - 0.216672 -0.36792 0.102223 - 0.210483 -0.361447 0.104328 - 0.140926 -0.256509 0.127914 - 0.0311085 -0.0937969 0.165158 - 0.0324095 -0.097583 0.164721 - 0.0253817 -0.0845164 0.167099 - 0.0252374 -0.0901158 0.16716 - 0.0423889 -0.160473 0.161438 - 0.0153414 -0.106722 0.170582 - 0.0137356 -0.135983 0.171194 - 0.0125962 -0.13317 0.171578 - 0.0111033 -0.128389 0.172079 - 0.00513237 -0.118368 0.174101 - -0.0108815 -0.109964 0.179565 - -0.0154717 -0.112981 0.181142 - -0.0178266 -0.0928895 0.181906 - -0.0178956 -0.0798678 0.181902 - -0.0241016 -0.0842646 0.184035 - -0.0377972 -0.131519 0.188823 - -0.0886041 -0.312034 0.206595 - -0.144603 -0.375175 0.225895 - -0.146151 -0.374566 0.226424 - -0.162786 -0.380523 0.232131 - -0.16562 -0.37383 0.233086 - -0.183466 -0.376247 0.2392 - -1.32968 -1.79543 0.634524 - -1.29634 -1.51798 0.622527 - -1.31554 -1.37503 0.628795 - -0.414542 -0.377912 0.318296 - -0.44038 -0.381531 0.327147 - -0.435864 -0.332942 0.325499 - -0.44408 -0.336338 0.328318 - -0.431542 -0.303272 0.323957 - -0.435702 -0.294962 0.325363 - -0.48553 -0.305299 0.34244 - -0.494966 -0.302315 0.345664 - -0.500716 -0.299875 0.347627 - -0.527484 -0.300671 0.35679 - -0.547564 -0.284052 0.363628 - -0.616776 -0.293435 0.387338 - -0.617984 -0.29065 0.387745 - -0.747259 -0.300984 0.432015 - -0.925303 -0.29851 0.492951 - -0.969458 -0.28896 0.508044 - -1.14726 -0.167529 0.568647 - -1.14295 -0.140412 0.567114 - -1.14466 -0.114242 0.567642 - -0.343541 -0.0134483 0.293223 - -0.271802 0.00734457 0.268624 - -0.354885 0.0144348 0.297047 - -1.10432 0.0713485 0.553443 - -1.12294 0.103434 0.559747 - -1.1035 0.193612 0.552903 - -1.09694 0.25993 0.550518 - -1.0929 0.290551 0.549071 - -1.09122 0.316703 0.548441 - -1.08857 0.326628 0.547513 - -1.06789 0.456702 0.540158 - -1.05474 0.543487 0.535476 - -1.0536 0.554869 0.535061 - -1.04946 0.652181 0.533438 - -1.04337 0.687551 0.531279 - -1.03795 0.703914 0.52939 - -1.03493 0.735806 0.528286 - -1.02433 0.791294 0.524541 - -1.01874 0.900174 0.522397 - -0.990696 1.04259 0.512499 - -0.989702 1.05065 0.512141 - -0.971472 1.19672 0.505593 - -0.920799 1.39594 0.487827 - -0.874596 1.40208 0.472 - -0.199031 0.34308 0.243007 - -0.156938 0.276278 0.22874 - -0.136743 0.279237 0.221822 - -0.246641 0.686295 0.258577 - -0.160934 0.479445 0.229679 - -0.125531 0.381138 0.217769 - -0.098594 0.318637 0.208681 - -0.0602816 0.222631 0.19577 - -0.0390502 0.138429 0.188681 - -0.0267703 0.0879142 0.184585 - -0.0261839 0.0890209 0.184382 - -0.0230308 0.0783755 0.183325 - -0.0205808 0.0766507 0.18249 - -0.020414 0.0867062 0.182412 - -0.0116814 0.115981 0.179361 - -0.0107487 0.114958 0.179044 --0.00989882 0.111929 0.178759 --0.00951115 0.109912 0.178631 --0.00828732 0.0988365 0.178236 --0.00863071 0.0858356 0.178381 --0.00589014 0.0846026 0.177445 --0.00083902 0.0990766 0.175686 - 0.00529797 0.119326 0.173542 - 0.00644688 0.120131 0.173147 - 0.0110949 0.12018 0.171556 - 0.0142843 0.127621 0.170449 - 0.029956 0.160497 0.165015 - 0.0463317 0.171643 0.159387 - 0.0460458 0.168555 0.159491 - 0.0394369 0.130427 0.161834 - 0.0369196 0.11849 0.162721 - 0.0404835 0.121155 0.161495 - 0.0419798 0.120395 0.160985 - 0.0420579 0.119241 0.16096 - 0.033584 0.0957607 0.16391 - 0.257974 0.44177 0.0863748 - 0.400098 0.654047 0.0372802 - 0.450678 0.68757 0.0198966 - 0.453514 0.68542 0.0189307 - 0.577454 0.828528 -0.0237939 - 0.725886 0.837562 -0.0746184 - 0.384029 -0.437333 0.0497737 - 0.374537 -0.434405 0.0529042 - 0.308929 -0.426767 0.0745702 - 0.280991 -0.422801 0.0837948 - 0.255831 -0.404866 0.0920718 - 0.224721 -0.378765 0.102298 - 0.0507673 -0.108894 0.159218 - 0.049863 -0.109477 0.159518 - 0.0304896 -0.093308 0.165886 - 0.0297353 -0.0948041 0.166139 - 0.0254343 -0.0913839 0.167553 - 0.0142945 -0.100953 0.171255 - 0.0115899 -0.113046 0.172174 - 0.00753453 -0.114962 0.173518 - -0.0036752 -0.0914603 0.177173 --0.00843135 -0.0818505 0.178725 --0.00913055 -0.0889004 0.178971 - -0.0163468 -0.108946 0.181398 - -0.0175347 -0.104896 0.181782 - -0.0177055 -0.0778509 0.181781 - -0.0432876 -0.155785 0.1904 - -0.0620189 -0.227217 0.19674 - -0.0725991 -0.260549 0.200307 - -0.113901 -0.352308 0.21415 - -0.139938 -0.371667 0.222795 - -0.143671 -0.372361 0.22403 - -0.14488 -0.370821 0.224427 - -0.151888 -0.375492 0.226753 - -0.153443 -0.37485 0.227265 - -0.179762 -0.380384 0.235975 - -0.191231 -0.367849 0.239738 - -0.207459 -0.36894 0.245104 - -0.226486 -0.370013 0.251394 - -0.251068 -0.371226 0.259521 - -0.248627 -0.357235 0.258684 - -0.267829 -0.372317 0.265062 - -1.33042 -1.83984 0.619316 - -1.33348 -1.811 0.620267 - -1.31173 -1.68774 0.61282 - -1.31327 -1.63068 0.613208 - -1.29486 -1.52464 0.606901 - -1.29365 -1.42003 0.60628 - -1.2937 -1.37131 0.606196 - -1.326 -1.33413 0.616793 - -0.411556 -0.39436 0.312607 - -0.438799 -0.372466 0.321564 - -0.422607 -0.304419 0.31607 - -0.423866 -0.302533 0.316482 - -0.454355 -0.301392 0.326556 - -0.504102 -0.298124 0.342989 - -0.557027 -0.28515 0.360452 - -0.612129 -0.293683 0.37868 - -0.751047 -0.293851 0.42459 - -0.839313 -0.307471 0.453789 - -1.08466 -0.280535 0.534813 - -1.15819 -0.260951 0.559074 - -1.14472 -0.156026 0.554399 - -1.13878 -0.102854 0.552327 - -1.13447 -0.0972695 0.550889 - -0.265745 0.00019326 0.263588 - -0.262858 0.00478103 0.262625 - -0.311138 0.0111864 0.278567 - -0.360425 0.0146348 0.294848 - -1.08179 0.0598002 0.533148 - -1.11285 0.0818286 0.543367 - -1.1144 0.0870306 0.543868 - -1.10383 0.182767 0.540175 - -1.09807 0.22811 0.538175 - -1.08805 0.288329 0.534735 - -1.09332 0.321668 0.536409 - -1.08985 0.358362 0.535185 - -1.0741 0.413036 0.529865 - -1.06531 0.494176 0.526788 - -1.05028 0.587709 0.521623 - -1.05033 0.612546 0.521589 - -1.04581 0.673816 0.519964 - -1.03156 0.717463 0.515163 - -1.02847 0.784852 0.513999 - -1.02193 0.794149 0.51182 - -1.02109 0.860421 0.511402 - -1.01155 0.931081 0.508099 - -1.00648 0.95942 0.506364 - -0.965574 1.2395 0.492257 - -0.956419 1.29547 0.489114 - -0.902474 1.40254 0.47106 - -0.859452 1.39983 0.456848 - -0.733242 1.25043 0.415453 - -0.147321 0.271527 0.223881 - -0.142481 0.2674 0.22229 - -0.133609 0.275259 0.219341 - -0.251469 0.729176 0.257335 - -0.123081 0.367264 0.215668 - -0.101073 0.312642 0.20851 - -0.0943573 0.308423 0.206299 - -0.0913078 0.307223 0.205294 - -0.0378105 0.13352 0.18798 - -0.0346277 0.12194 0.186953 - -0.0297351 0.101525 0.185379 - -0.0217733 0.0794921 0.182794 - -0.0198644 0.0766819 0.182169 - -0.0171828 0.0879015 0.181259 - -0.017108 0.0949124 0.18122 - -0.014515 0.107992 0.180335 - -0.0094943 0.110929 0.17867 --0.00822137 0.091848 0.178289 --0.00789891 0.090826 0.178185 --0.00622287 0.0836748 0.177646 --0.00171758 0.0982531 0.176127 - 0.00914333 0.123771 0.172483 - 0.0235828 0.155219 0.167645 - 0.0257509 0.155664 0.166928 - 0.035461 0.159965 0.16371 - 0.0407601 0.169708 0.161938 - 0.0431782 0.169893 0.161139 - 0.0393 0.119834 0.162526 - 0.0395589 0.116393 0.162447 - 0.0392156 0.114348 0.162565 - 0.0388564 0.112309 0.162688 - 0.0780989 0.161498 0.149616 - 0.491428 0.704808 0.0118747 - 0.65435 0.829884 -0.0422311 - 0.577613 0.728015 -0.0166567 - 0.736807 0.817314 -0.0694548 - 0.399704 -0.437078 0.0493675 - 0.386593 -0.442057 0.0535591 - 0.311028 -0.42755 0.0776262 - 0.298673 -0.422465 0.0815557 - 0.290537 -0.418927 0.0841427 - 0.288794 -0.420311 0.0847016 - 0.0392446 -0.0908992 0.163592 - 0.0432719 -0.16167 0.162456 - 0.0245539 -0.128173 0.168355 - 0.0137936 -0.102287 0.171732 - 0.011201 -0.100929 0.172556 - 0.0121342 -0.131444 0.172322 --0.00057846 -0.104226 0.176319 - -0.0015713 -0.0993152 0.176626 - -0.017945 -0.0888299 0.181825 - -0.0249891 -0.0809809 0.184055 - -0.069274 -0.246938 0.198526 - -0.12142 -0.356112 0.215385 - -0.12587 -0.359849 0.216812 - -0.186823 -0.370275 0.236271 - -0.206248 -0.377754 0.242482 - -0.217025 -0.374905 0.245913 - -0.219175 -0.371291 0.246591 - -0.225319 -0.367449 0.248542 - -0.240586 -0.368002 0.253412 - -0.254993 -0.366269 0.258003 - -1.32353 -1.77568 0.60172 - -1.318 -1.75232 0.599907 - -1.32115 -1.74083 0.600886 - -1.28994 -1.50084 0.590431 - -1.28151 -1.47789 0.587694 - -1.28796 -1.45957 0.589713 - -0.426053 -0.418563 0.312664 - -0.409959 -0.388435 0.307468 - -0.426709 -0.327071 0.312681 - -0.440744 -0.329032 0.317161 - -0.428001 -0.313425 0.313064 - -0.442139 -0.300791 0.317546 - -0.445423 -0.297393 0.318586 - -0.476555 -0.303819 0.328528 - -0.493832 -0.29705 0.334023 - -0.546967 -0.304019 0.350983 - -0.606643 -0.283611 0.369971 - -0.774338 -0.29431 0.423471 - -0.986595 -0.287526 0.491146 - -1.02968 -0.285219 0.50488 - -1.12144 -0.283902 0.534142 - -1.15458 -0.242956 0.544622 - -1.15464 -0.237529 0.544632 - -1.14534 -0.219459 0.541627 - -1.14683 -0.19299 0.542046 - -1.14233 -0.171042 0.540566 - -1.1384 -0.102508 0.53917 - -1.11587 -0.0699749 0.531915 - -0.733148 -0.03577 0.409793 - -0.2719 0.00138444 0.262623 - -1.09072 0.0601186 0.523621 - -1.10228 0.223123 0.526965 - -1.10008 0.253847 0.5262 - -1.09683 0.268761 0.525132 - -1.08883 0.33539 0.522441 - -1.0813 0.370661 0.519967 - -1.07183 0.405417 0.516874 - -1.06227 0.52036 0.513582 - -1.04242 0.624784 0.507032 - -1.02056 0.783554 0.49973 - -1.02021 0.826984 0.499527 - -1.02131 0.873466 0.49978 - -1.00375 0.889199 0.494146 - -0.990489 1.08228 0.489512 - -0.991143 1.11177 0.489659 - -0.97784 1.12585 0.485387 - -0.969294 1.22969 0.482444 - -0.963457 1.26665 0.480505 - -0.960531 1.27415 0.479556 - -0.138868 0.271531 0.219631 - -0.244227 0.686418 0.252359 - -0.118446 0.352001 0.21295 - -0.102029 0.316478 0.207789 - -0.0872047 0.291766 0.203113 - -0.0738803 0.262308 0.198926 - -0.0262303 0.0868658 0.184099 - -0.0229513 0.0813061 0.183065 - -0.0204227 0.0765839 0.182268 - -0.0164111 0.0799105 0.180982 - -0.0163277 0.0859207 0.180943 - -0.0100584 0.107961 0.178897 --0.00662459 0.0817424 0.177857 --0.00525663 0.0856333 0.177413 --0.00312342 0.0853963 0.176733 - 0.00942737 0.119741 0.172658 - 0.0294055 0.156848 0.166209 - 0.0388691 0.164258 0.163176 - 0.043164 0.168005 0.161798 - 0.046169 0.17219 0.160831 - 0.0384765 0.131387 0.16337 - 0.034408 0.118006 0.164696 - 0.040827 0.101415 0.162683 - 0.480331 0.698978 0.0212706 - 0.486126 0.694431 0.019432 - 0.507581 0.704897 0.012568 - 0.516961 0.711168 0.00956364 - 0.550734 0.743046 -0.00127375 - 0.302385 -0.429442 0.0839295 - 0.208962 -0.367213 0.11254 - 0.0302457 -0.110367 0.166983 - 0.0348907 -0.152205 0.165642 - 0.0175938 -0.107548 0.17087 - 0.0121074 -0.100818 0.172544 - 0.0119549 -0.108063 0.172606 --0.00457591 -0.0886324 0.177651 --0.00820708 -0.0828892 0.178756 - -0.0106595 -0.101986 0.17955 - -0.0114608 -0.107996 0.179809 - -0.0174848 -0.0818203 0.181608 - -0.107757 -0.347903 0.209936 - -0.118155 -0.350887 0.213141 - -0.125215 -0.363217 0.215339 - -0.139643 -0.370726 0.219793 - -0.176482 -0.380991 0.231148 - -0.191353 -0.371342 0.235703 - -0.199958 -0.376836 0.238362 - -0.203095 -0.375107 0.239323 - -0.211947 -0.368878 0.242033 - -0.216929 -0.370503 0.243569 - -0.23425 -0.367722 0.248892 - -0.240395 -0.367164 0.250782 - -1.31418 -1.74209 0.583999 - -1.3167 -1.72984 0.584749 - -1.30209 -1.60694 0.579998 - -1.29838 -1.56036 0.57876 - -1.30587 -1.40029 0.58073 - -1.28038 -1.32557 0.572731 - -0.453303 -0.449041 0.316453 - -0.427024 -0.380127 0.308224 - -0.427033 -0.300642 0.30806 - -0.547424 -0.297238 0.34509 - -0.550733 -0.2928 0.346099 - -0.556565 -0.289686 0.347887 - -0.560329 -0.288546 0.349043 - -0.575713 -0.280695 0.353759 - -0.61486 -0.28019 0.365801 - -0.842685 -0.311265 0.435955 - -0.849226 -0.300839 0.437945 - -1.1514 -0.225387 0.53075 - -1.14692 -0.181837 0.529279 - -1.12919 -0.0757379 0.523605 - -0.91625 -0.0488749 0.458038 - -0.851529 -0.0415348 0.438111 - -0.722786 -0.0319127 0.398484 - -1.1216 0.102379 0.520895 - -1.09531 0.185355 0.512634 - -1.09669 0.278441 0.512865 - -1.09361 0.314559 0.51184 - -1.08701 0.393478 0.509645 - -1.08536 0.398379 0.509128 - -1.07223 0.409915 0.505062 - -1.07767 0.439877 0.506674 - -1.06125 0.553967 0.501383 - -1.05101 0.572563 0.498195 - -1.04545 0.587689 0.496452 - -1.04718 0.594806 0.49697 - -1.04802 0.607654 0.497202 - -1.04881 0.614346 0.49743 - -1.03326 0.707806 0.492451 - -1.0311 0.713014 0.491775 - -1.03234 0.73427 0.492112 - -1.0146 0.872955 0.486364 - -1.01534 0.88138 0.486576 - -1.01637 0.913995 0.486823 - -1.00047 0.9565 0.481843 - -0.959233 1.32759 0.468381 - -0.955963 1.33512 0.467359 - -0.803756 1.35203 0.420498 - -0.147811 0.272415 0.22096 - -0.136478 0.269403 0.21748 - -0.13754 0.28105 0.217783 - -0.135588 0.283091 0.217178 - -0.193484 0.542988 0.234445 - -0.100813 0.312642 0.206418 - -0.0974121 0.310552 0.205376 - -0.0958571 0.309973 0.204899 - -0.0501886 0.178691 0.191124 - -0.0213936 0.0864896 0.182458 - -0.0164677 0.0898993 0.180935 - -0.0118968 0.105998 0.179496 - -0.0081355 0.11191 0.178326 --0.00667392 0.0847884 0.177933 --0.00200499 0.0913542 0.176483 - 0.0107196 0.118553 0.172512 - 0.0300821 0.154731 0.166479 - 0.0423547 0.168512 0.162675 - 0.0459649 0.174612 0.161551 - 0.0483886 0.176895 0.160801 - 0.0390401 0.128147 0.163779 - 0.0407752 0.121894 0.163258 - 0.0349989 0.0993015 0.165082 - 0.039712 0.102382 0.163626 - 0.0488417 0.11425 0.160793 - 0.105067 0.208425 0.143298 - 0.450421 0.691011 0.0360426 - 0.46685 0.695965 0.0309782 - 0.490458 0.697624 0.0237118 - 0.515484 0.693771 0.0160207 - 0.5549 0.676223 0.00393145 - 0.404776 -0.431172 0.0572663 - 0.390503 -0.438779 0.0615078 - 0.361538 -0.436726 0.0700783 - 0.330183 -0.43314 0.0793533 - 0.27367 -0.417857 0.0960517 - 0.270714 -0.421257 0.0969339 - 0.0369529 -0.0929699 0.165452 - 0.0275523 -0.0766672 0.168201 - 0.0303612 -0.0875438 0.167393 - 0.0255377 -0.0909885 0.168828 - 0.0255313 -0.0920787 0.168832 - 0.0353249 -0.126789 0.166005 - 0.0387651 -0.141476 0.165017 - 0.0346092 -0.145128 0.166255 - 0.0342818 -0.1484 0.166359 - 0.0210146 -0.116042 0.170219 - 0.0135891 -0.108809 0.172402 - 0.0107487 -0.121739 0.17327 - 0.00323412 -0.102801 0.175455 - 0.00145545 -0.106095 0.175989 - 0.00064884 -0.103178 0.176221 - -0.0105686 -0.108991 0.179554 - -0.0115293 -0.0969992 0.179814 - -0.0163278 -0.104896 0.181251 - -0.0191011 -0.0776353 0.182015 - -0.0199069 -0.0825762 0.182264 - -0.0203526 -0.0835333 0.182398 - -0.022098 -0.0833205 0.182914 - -0.0235549 -0.0810903 0.183341 - -0.042459 -0.146561 0.189074 - -0.0972937 -0.320824 0.20567 - -0.146963 -0.376439 0.220491 - -0.175001 -0.37296 0.228784 - -0.191078 -0.37045 0.233538 - -0.21429 -0.365309 0.240399 - -0.231986 -0.367037 0.245642 - -0.235567 -0.369413 0.246707 - -0.240187 -0.366325 0.248068 - -0.413318 -0.386611 0.299365 - -0.43424 -0.372493 0.305529 - -0.406058 -0.329562 0.297096 - -0.424403 -0.309339 0.302485 - -0.428253 -0.303679 0.303613 - -0.480855 -0.296382 0.31917 - -0.531494 -0.303039 0.334175 - -0.553963 -0.284501 0.340789 - -0.607889 -0.273013 0.356729 - -1.01357 -0.288927 0.47686 - -1.04096 -0.286768 0.484965 - -1.15365 -0.235974 0.51822 - -1.15463 -0.230776 0.518499 - -1.15558 -0.225573 0.518772 - -1.14403 -0.170328 0.515236 - -1.12725 -0.0804908 0.510079 - -0.265984 -0.00443237 0.25495 - -1.09964 0.170361 0.501383 - -1.10514 0.191623 0.502969 - -1.08592 0.306192 0.49704 - -1.09074 0.339447 0.498397 - -1.07975 0.362667 0.495095 - -1.08731 0.392486 0.497271 - -1.07263 0.436573 0.492831 - -1.07121 0.464081 0.492356 - -1.05489 0.579178 0.487284 - -1.05254 0.590078 0.486565 - -1.04841 0.600009 0.48532 - -1.04586 0.610895 0.484542 - -1.0361 0.707806 0.481452 - -1.03524 0.7412 0.481128 - -1.0239 0.803385 0.477641 - -1.01223 0.884008 0.474018 - -0.99268 1.0882 0.467804 - -0.988748 1.10296 0.46661 - -0.977174 1.12877 0.46313 - -0.983245 1.14589 0.464891 - -0.970157 1.17099 0.460964 - -0.961245 1.32679 0.458001 - -0.903499 1.40577 0.440741 - -0.875413 1.40098 0.432436 - -0.860081 1.40286 0.427893 - -0.747961 1.26582 0.394987 - -0.172893 0.296913 0.226763 - -0.13883 0.271531 0.216731 - -0.136294 0.27833 0.215966 - -0.25847 0.679094 0.2513 - -0.0966721 0.303439 0.204184 - -0.0584862 0.210499 0.193074 - -0.0492565 0.175761 0.190414 - -0.0151878 0.11195 0.180461 - -0.0137659 0.110984 0.180042 - -0.011444 0.110998 0.179355 --0.00041478 0.0942316 0.176124 - 0.00116777 0.0970361 0.17565 - 0.0232609 0.155714 0.168987 - 0.0251533 0.152141 0.168434 - 0.0363842 0.0977551 0.165223 - 0.03635 0.0966474 0.165235 - 0.171831 0.318726 0.124664 - 0.487297 0.696711 0.0304841 - 0.528717 0.689573 0.0182368 - 0.410562 -0.435399 0.0603719 - 0.398307 -0.433965 0.0638572 - 0.395812 -0.435102 0.0645698 - 0.372975 -0.432805 0.0710657 - 0.369207 -0.432331 0.0721372 - 0.313548 -0.425201 0.0879654 - 0.299897 -0.426095 0.091853 - 0.288789 -0.422251 0.095007 - 0.212145 -0.376024 0.116727 - 0.210565 -0.377034 0.117179 - 0.0397783 -0.0962467 0.165209 - 0.0348396 -0.0887953 0.166599 - 0.0275709 -0.0780863 0.168646 - 0.028754 -0.0908445 0.168336 - 0.0276072 -0.0913839 0.168663 - 0.0255972 -0.0955278 0.169244 - 0.0394123 -0.143581 0.165412 - 0.031583 -0.140034 0.167633 - 0.033542 -0.150927 0.167098 - 0.00884983 -0.117116 0.174056 --0.00566637 -0.0817787 0.178115 --0.00657926 -0.0838469 0.178379 - -0.0106169 -0.106996 0.179576 - -0.0160426 -0.089873 0.181085 - -0.0235952 -0.084057 0.183223 - -0.0246867 -0.0818516 0.183529 - -0.0250301 -0.0817908 0.183626 - -0.0283761 -0.0923374 0.184601 - -0.146667 -0.365861 0.218841 - -0.162462 -0.378676 0.223363 - -0.169598 -0.373327 0.225383 - -0.18329 -0.370056 0.229274 - -0.217478 -0.366974 0.238999 - -0.219017 -0.366035 0.239435 - -0.271606 -0.371951 0.254417 - -1.32281 -1.80792 0.556623 - -1.30969 -1.68045 0.552624 - -1.2902 -1.46244 0.546625 - -1.31211 -1.37487 0.552677 - -0.428208 -0.376262 0.299002 - -0.423409 -0.305138 0.297488 - -0.424687 -0.303266 0.297848 - -0.562199 -0.278826 0.33694 - -0.588294 -0.272847 0.344355 - -0.597328 -0.273917 0.346929 - -1.05604 -0.285128 0.477524 - -1.12445 -0.276959 0.496979 - -1.15383 -0.208556 0.5052 - -1.14957 -0.186548 0.503941 - -1.13959 -0.15356 0.501032 - -1.13814 -0.0913382 0.500489 - -0.262505 0.00360599 0.251045 - -0.265373 0.00479921 0.251859 - -0.270132 0.00723696 0.253209 - -0.803099 0.0401319 0.404848 - -1.10156 0.195575 0.48948 - -1.09806 0.210209 0.488455 - -1.08865 0.238872 0.485716 - -1.07914 0.308664 0.482864 - -1.07702 0.376888 0.482119 - -1.08489 0.396037 0.484317 - -1.07342 0.452529 0.480935 - -1.04357 0.645606 0.472039 - -1.04727 0.673778 0.473033 - -1.01089 0.904146 0.462199 - -1.00109 1.02086 0.459165 - -0.987166 1.04224 0.455158 - -0.984158 1.13399 0.454111 - -0.976375 1.19652 0.451765 - -0.96997 1.20986 0.449915 - -0.955394 1.35177 0.44547 - -0.935756 1.39924 0.439782 - -0.85021 1.39652 0.415437 - -0.586478 1.0258 0.341137 - -0.152808 0.270782 0.219265 - -0.141202 0.273644 0.215955 - -0.1558 0.337207 0.219978 - -0.0926462 0.299384 0.202081 - -0.0911324 0.298785 0.201651 - -0.0481952 0.168762 0.189699 - -0.0318529 0.108976 0.185172 - -0.0249791 0.0838443 0.183268 - -0.023824 0.0809996 0.182945 - -0.0165818 0.0808302 0.180883 - -0.0152596 0.0999255 0.180467 - -0.0138317 0.111975 0.180036 --0.00751808 0.104916 0.178253 --0.00602409 0.0928222 0.177853 --0.00503532 0.0807168 0.177597 --0.00206152 0.0894578 0.176732 - 4.639e-05 0.0942316 0.176122 - 0.00356072 0.10786 0.175094 - 0.0145164 0.127139 0.171935 - 0.0209769 0.146131 0.170057 - 0.0305205 0.160123 0.167311 - 0.0338594 0.164341 0.166352 - 0.0442638 0.16826 0.163382 - 0.0427533 0.150763 0.163849 - 0.0377039 0.128138 0.165333 - 0.0410618 0.125597 0.164382 - 0.0428796 0.122558 0.163871 - 0.0344795 0.0990419 0.166311 - 0.474224 0.694577 0.0399011 - 0.50913 0.698575 0.0299567 - 0.535677 0.695764 0.022406 - 0.55515 0.689259 0.0168767 - 0.555803 0.666141 0.0167389 - 0.384582 -0.43984 0.073277 - 0.346267 -0.433699 0.0836377 - 0.326082 -0.431569 0.0890983 - 0.211429 -0.372621 0.120017 - 0.0282316 -0.0780863 0.169006 - 0.0290632 -0.0832589 0.168792 - 0.0286356 -0.0901158 0.168922 - 0.032092 -0.117859 0.168043 - 0.0151064 -0.104579 0.172615 - 0.0163247 -0.113545 0.172303 - 0.0109674 -0.119875 0.173767 - 0.00652865 -0.108504 0.174945 - 0.00270801 -0.101017 0.175964 --0.00434432 -0.0787042 0.177827 --0.00467584 -0.0787333 0.177917 - -0.0132697 -0.107972 0.180304 - -0.0152406 -0.11191 0.180846 - -0.0163096 -0.0788034 0.181067 - -0.0165698 -0.0777811 0.181135 - -0.0186698 -0.0826119 0.181714 - -0.0205551 -0.0904517 0.18224 - -0.0290709 -0.0941416 0.184554 - -0.0346779 -0.115403 0.186116 - -0.0356492 -0.115184 0.186378 - -0.0637842 -0.223368 0.19422 - -0.102293 -0.329643 0.204866 - -0.118144 -0.35184 0.209203 - -0.128012 -0.356904 0.211885 - -0.151252 -0.363987 0.218192 - -0.162861 -0.379599 0.221368 - -0.228366 -0.370867 0.239084 - -0.239755 -0.368202 0.242162 - -1.32596 -1.7267 0.539058 - -1.29807 -1.44124 0.530915 - -1.32074 -1.30914 0.536779 - -0.439169 -0.371851 0.296159 - -0.407752 -0.329562 0.287566 - -0.440849 -0.29441 0.296454 - -0.475058 -0.305911 0.305739 - -0.483463 -0.29373 0.30799 - -0.55861 -0.304405 0.328357 - -0.581111 -0.27812 0.334395 - -0.977733 -0.4141 0.442058 - -0.890142 -0.299662 0.418107 - -0.923319 -0.297312 0.427084 - -1.15035 -0.260817 0.488474 - -1.14578 -0.254395 0.487224 - -1.14796 -0.238784 0.487782 - -1.15028 -0.186081 0.488302 - -1.13752 -0.106392 0.484682 - -1.13434 -0.0856389 0.483778 - -0.263812 -0.00552518 0.247924 - -0.331242 0.0118277 0.266144 - -1.09223 0.064423 0.472067 - -1.10828 0.14545 0.476244 - -1.0956 0.249938 0.472593 - -1.09962 0.292512 0.473594 - -1.08168 0.339956 0.468639 - -1.07514 0.424033 0.466695 - -1.06066 0.507931 0.4626 - -1.04756 0.60843 0.458846 - -1.02997 0.733211 0.453824 - -1.02376 0.742392 0.452124 - -1.02766 0.75912 0.453144 - -1.0052 0.896267 0.446778 - -1.0099 0.916491 0.44801 - -1.00502 0.928161 0.446664 - -0.992468 1.03566 0.443044 - -0.977424 1.19422 0.438642 - -0.974239 1.20088 0.437766 - -0.957969 1.2796 0.433198 - -0.954777 1.33457 0.43222 - -0.942888 1.40583 0.428854 - -0.855219 1.40076 0.405129 - -0.188618 0.322235 0.226887 - -0.13939 0.282286 0.213642 - -0.307985 0.752686 0.258313 - -0.0949255 0.298638 0.201569 - -0.0254957 0.0978585 0.183188 - -0.0234531 0.0921041 0.182647 - -0.0209445 0.0873973 0.181977 - -0.0170375 0.0757434 0.180944 - -0.0156671 0.085865 0.180552 - -0.0113796 0.0999991 0.179362 --0.00577502 0.0878318 0.177869 --0.00424717 0.0837063 0.177464 - 0.00489704 0.103695 0.174947 - 0.012019 0.119638 0.172986 - 0.0215709 0.143062 0.170351 - 0.0305233 0.160312 0.167892 - 0.0314522 0.161087 0.167639 - 0.0400583 0.162592 0.165306 - 0.224264 0.393535 0.114955 - 0.479347 0.69862 0.0452615 - 0.507995 0.693833 0.0375152 - 0.534032 0.696688 0.03046 - 0.5603 0.668386 0.0234068 - 0.410272 -0.435186 0.0709833 - 0.395777 -0.442782 0.0747626 - 0.324986 -0.428458 0.0931131 - 0.281724 -0.419802 0.104328 - 0.26609 -0.420114 0.108388 - 0.21998 -0.388976 0.120295 - 0.177106 -0.332717 0.131311 - 0.0443834 -0.10462 0.1653 - 0.0254626 -0.0730894 0.170147 - 0.0251536 -0.0732509 0.170228 - 0.0309524 -0.0870276 0.168751 - 0.0253425 -0.0863931 0.170206 - 0.0249774 -0.086554 0.170301 - 0.025726 -0.0905673 0.170115 - 0.0387422 -0.140051 0.166838 - 0.040472 -0.151092 0.166411 - 0.0324926 -0.141182 0.168463 - 0.0168184 -0.113545 0.172475 - 0.0116303 -0.103504 0.173802 - 0.0135897 -0.125558 0.173338 - 0.0101839 -0.112997 0.174197 - 0.00728987 -0.107439 0.174937 --0.00330931 -0.0816613 0.177635 --0.00549081 -0.0858432 0.17821 --0.00621605 -0.0858852 0.178399 --0.00714975 -0.115948 0.178703 - -0.0122816 -0.100983 0.180005 - -0.0197802 -0.0904944 0.18193 - -0.066829 -0.228696 0.194431 - -0.108213 -0.340307 0.205407 - -0.11335 -0.347061 0.206755 - -0.124294 -0.356051 0.209615 - -0.134049 -0.359996 0.212156 - -0.150602 -0.371765 0.216478 - -0.169287 -0.372412 0.221331 - -0.172428 -0.370965 0.222143 - -0.174395 -0.37114 0.222654 - -0.25304 -0.36765 0.243066 - -1.33396 -1.84627 0.526773 - -1.29812 -1.58398 0.516925 - -1.291 -1.49395 0.51489 - -1.2912 -1.44262 0.514836 - -1.29146 -1.41786 0.514852 - -0.425283 -0.328419 0.287707 - -0.436706 -0.296611 0.290607 - -0.48327 -0.310741 0.302726 - -0.483054 -0.301692 0.302651 - -0.482276 -0.295346 0.302436 - -0.548165 -0.294893 0.319543 - -0.552355 -0.290956 0.320623 - -0.552541 -0.281804 0.320652 - -0.90226 -0.303099 0.411497 - -1.05025 -0.287026 0.449889 - -1.07138 -0.282633 0.455366 - -1.14882 -0.233058 0.47537 - -1.15549 -0.218369 0.477072 - -1.15425 -0.196868 0.476703 - -1.14831 -0.164344 0.475096 - -1.14358 -0.148064 0.473834 - -0.331707 -0.0113455 0.262756 - -1.10357 0.1898 0.462747 - -1.10276 0.194725 0.462527 - -1.0927 0.233371 0.459834 - -1.09928 0.239915 0.461529 - -1.09302 0.264163 0.459855 - -1.08229 0.365953 0.456859 - -1.07223 0.432901 0.454107 - -1.06853 0.442454 0.453128 - -1.07092 0.482883 0.453665 - -1.04456 0.630122 0.446516 - -1.04119 0.653373 0.445594 - -1.03592 0.715417 0.444096 - -1.02017 0.801278 0.43983 - -1.01723 0.889199 0.438884 - -1.00423 0.95827 0.435366 - -0.967134 1.2435 0.425145 - -0.866097 1.40201 0.398584 - -0.803641 1.35135 0.382473 - -0.14381 0.273351 0.213382 - -0.404836 0.984226 0.279686 - -0.181236 0.465824 0.222701 - -0.112852 0.311616 0.205265 - -0.0980844 0.300742 0.201453 - -0.0920227 0.289036 0.199903 - -0.0583668 0.202075 0.191344 - -0.0455759 0.15382 0.188123 - -0.0377639 0.126939 0.18615 - -0.0370225 0.126082 0.185959 - -0.0245959 0.0868035 0.182814 - -0.0175361 0.0786737 0.180998 - -0.0163116 0.0757699 0.180686 - -0.0149016 0.0938948 0.180282 --0.00917816 0.10699 0.178769 - 0.00083299 0.0892213 0.176207 - 0.0198497 0.14154 0.171161 - 0.029398 0.156631 0.168651 - 0.0382715 0.162316 0.166335 - 0.0426794 0.161885 0.165192 - 0.0433627 0.161643 0.165015 - 0.0405326 0.151016 0.165771 - 0.0306717 0.0882373 0.168461 - 0.0623154 0.140007 0.160138 - 0.119078 0.238966 0.145196 - 0.219496 0.391376 0.118809 - 0.352192 0.555182 0.0840169 - 0.48637 0.699619 0.0488803 - 0.497525 0.696027 0.0459913 - 0.524034 0.693771 0.0391133 - 0.563899 0.688194 0.0287743 - 0.40811 -0.438961 0.0762161 - 0.364588 -0.432993 0.0870188 - 0.354602 -0.432721 0.0894996 - 0.328722 -0.427718 0.0959203 - 0.320227 -0.432171 0.0980402 - 0.0417555 -0.0995793 0.166552 - 0.0369031 -0.0931711 0.167745 - 0.0317085 -0.0846768 0.169018 - 0.0268263 -0.0826685 0.170227 - 0.0201901 -0.112767 0.171938 - 0.0172581 -0.117677 0.172677 - 0.00794624 -0.111464 0.174978 - 0.00405292 -0.100955 0.175924 - 0.0028055 -0.0981052 0.176228 --0.00506883 -0.0798323 0.178147 - -0.0143445 -0.109912 0.180514 - -0.0166963 -0.0857298 0.181048 - -0.0195837 -0.0924833 0.18178 - -0.0232026 -0.0899905 0.182674 - -0.0255345 -0.0855315 0.183244 - -0.0264437 -0.0863708 0.183472 - -0.0864413 -0.28325 0.198786 - -0.101177 -0.321548 0.202527 - -0.105572 -0.331679 0.20364 - -0.113234 -0.341819 0.205565 - -0.160752 -0.365327 0.217421 - -0.162298 -0.364645 0.217804 - -0.170473 -0.370779 0.219848 - -0.180771 -0.372507 0.22241 - -0.24434 -0.36779 0.238197 - -1.32201 -1.7287 0.50879 - -1.31545 -1.68945 0.507081 - -1.28611 -1.47176 0.499342 - -0.429819 -0.33146 0.284211 - -0.485602 -0.2969 0.298002 - -0.5241 -0.308428 0.307592 - -0.544951 -0.298777 0.312753 - -0.546213 -0.296369 0.313062 - -0.591537 -0.269406 0.324269 - -0.602683 -0.268188 0.327036 - -0.839169 -0.310275 0.385887 - -0.843598 -0.303473 0.386974 - -0.876797 -0.302468 0.395221 - -1.023 -0.28866 0.431524 - -1.15605 -0.277162 0.464561 - -1.15722 -0.272006 0.46484 - -1.14872 -0.158811 0.462496 - -1.14792 -0.0914159 0.462158 - -0.797265 -0.0383689 0.374914 - -1.01535 0.0505058 0.428923 - -1.11472 0.105413 0.453501 - -1.10154 0.153873 0.450126 - -1.09759 0.193364 0.449064 - -1.10268 0.209477 0.450296 - -1.10088 0.229491 0.449807 - -1.0989 0.239289 0.449295 - -1.10051 0.255059 0.449661 - -1.09392 0.279263 0.447974 - -1.0824 0.343901 0.444979 - -1.08222 0.354444 0.444914 - -1.08341 0.40336 0.445109 - -1.07715 0.406447 0.443545 - -1.06886 0.498009 0.441297 - -1.05862 0.545403 0.438655 - -1.05656 0.556183 0.43812 - -1.04215 0.608637 0.434431 - -1.02296 0.787329 0.429296 - -1.02657 0.797326 0.430173 - -1.01655 0.871086 0.427529 - -1.01272 0.922995 0.42647 - -1.01096 0.929501 0.426021 - -1.01021 0.945222 0.425802 - -1.00329 0.980615 0.424009 - -0.994082 1.09781 0.42148 - -0.97861 1.16947 0.417487 - -0.96992 1.17966 0.415307 - -0.970501 1.19088 0.415428 - -0.965759 1.25015 0.414127 - -0.901635 1.40228 0.39788 - -0.639072 1.0902 0.333279 - -0.15873 0.340198 0.215464 - -0.480495 1.15679 0.293737 - -0.27755 0.682606 0.244284 - -0.124508 0.328555 0.206985 - -0.100716 0.300898 0.201129 - -0.0949581 0.295379 0.19971 - -0.0191961 0.0854955 0.181317 - -0.0154594 0.0788114 0.180402 - -0.0133351 0.108951 0.179812 - -0.0110112 0.106996 0.179238 - -0.0076258 0.11697 0.178377 --0.00265094 0.0836418 0.177209 --0.00194283 0.083571 0.177033 --0.00138568 0.0855222 0.176891 - 0.0160209 0.13227 0.172469 - 0.0318542 0.161278 0.168475 - 0.0350356 0.167638 0.167671 - 0.0436883 0.154312 0.165549 - 0.0380881 0.124424 0.167002 - 0.0376695 0.120284 0.167114 - 0.0317412 0.0935072 0.168643 - 0.0436693 0.106401 0.165652 - 0.566333 0.647634 0.0346602 - 0.363363 -0.430007 0.0914349 - 0.341077 -0.433888 0.0967346 - 0.284996 -0.428956 0.110041 - 0.269459 -0.421768 0.113716 - 0.192095 -0.35955 0.131958 - 0.185741 -0.351766 0.133451 - 0.0392761 -0.0978283 0.167707 - 0.0305328 -0.087762 0.169763 - 0.0309819 -0.0897547 0.16966 - 0.0336644 -0.124267 0.169094 - 0.032383 -0.135271 0.169421 - 0.0309204 -0.138878 0.169776 - 0.0176057 -0.135128 0.172929 --0.00104968 -0.0885585 0.177263 - -0.0049713 -0.0798542 0.178177 --0.00739572 -0.109975 0.178814 --0.00927146 -0.107999 0.179256 - -0.012712 -0.116957 0.180091 - -0.015425 -0.0837909 0.180667 - -0.0162895 -0.0857298 0.180876 - -0.0166533 -0.0856993 0.180963 - -0.0252612 -0.106802 0.18305 - -0.0227043 -0.0819108 0.182392 - -0.107364 -0.333161 0.203011 - -0.109063 -0.333676 0.203415 - -0.110478 -0.333226 0.20375 - -0.130794 -0.361097 0.208632 - -0.16414 -0.373609 0.216576 - -0.197345 -0.374135 0.224461 - -0.200969 -0.373321 0.22532 - -0.227336 -0.368304 0.231571 - -0.229944 -0.365486 0.232184 - -1.30726 -1.66018 0.490656 - -1.29189 -1.55527 0.486791 - -1.29196 -1.42436 0.486539 - -0.436785 -0.416135 0.281403 - -0.415506 -0.328435 0.27617 - -0.446822 -0.329032 0.283607 - -0.527507 -0.309937 0.302727 - -0.548436 -0.306482 0.307689 - -0.564082 -0.286748 0.311364 - -0.595509 -0.267601 0.318787 - -0.961939 -0.293825 0.40585 - -1.14735 -0.179112 0.44964 - -1.14058 -0.157335 0.44799 - -1.14029 -0.0957099 0.447792 - -0.633748 -0.0275376 0.327373 - -0.42678 -0.016531 0.278206 - -1.08987 0.0638489 0.435492 - -1.10863 0.0897146 0.439895 - -1.10781 0.204921 0.439463 - -1.09652 0.217952 0.436755 - -1.08914 0.355972 0.434719 - -1.05381 0.559494 0.425912 - -1.04387 0.566015 0.423539 - -1.04373 0.658538 0.423314 - -1.04715 0.673661 0.424095 - -1.02221 0.828699 0.417855 - -1.01913 0.902833 0.416972 - -1.0094 0.967538 0.414526 - -0.984812 1.10439 0.408407 - -0.976084 1.206 0.406126 - -0.958538 1.29529 0.401776 - -0.9564 1.35279 0.40115 - -0.908309 1.39659 0.389641 - -0.840537 1.39468 0.373552 - -0.116764 0.315405 0.20391 - -0.0959944 0.294996 0.19902 - -0.0254623 0.0875213 0.182698 - -0.0246346 0.102869 0.18247 - -0.0238959 0.103989 0.182293 - -0.014536 0.0878619 0.180103 --0.00775708 0.112981 0.178442 --0.00099797 0.081506 0.176902 - 0.00399719 0.100007 0.175677 - 0.0031172 0.0880127 0.175911 - 0.00627333 0.100661 0.175136 - 0.0163212 0.13129 0.172687 - 0.0184477 0.135941 0.172172 - 0.0190246 0.135813 0.172036 - 0.0290676 0.153906 0.169614 - 0.0375377 0.169146 0.167571 - 0.0368002 0.129435 0.167828 - 0.0379328 0.125785 0.167566 - 0.0411206 0.124459 0.166812 - 0.0405075 0.121469 0.166964 - 0.0326714 0.0933179 0.168882 - 0.15153 0.295655 0.140243 - 0.2278 0.398005 0.121923 - 0.238185 0.399582 0.119453 - 0.48125 0.713377 0.061092 - 0.479188 0.703843 0.0616012 - 0.531859 0.692912 0.049117 - 0.551637 0.693075 0.0444203 - 0.419036 -0.435399 0.0841662 - 0.418061 -0.442052 0.0843979 - 0.41344 -0.441103 0.0854291 - 0.369572 -0.435233 0.0952252 - 0.366423 -0.435422 0.0959296 - 0.354463 -0.432839 0.0985985 - 0.304345 -0.426704 0.109791 - 0.281233 -0.425355 0.114956 - 0.0727498 -0.154732 0.161015 - 0.0345224 -0.0860724 0.169421 - 0.0324595 -0.0837854 0.169877 - 0.0300346 -0.0872108 0.170427 - 0.0269724 -0.0842354 0.171105 - 0.0353204 -0.127092 0.169326 - 0.0397315 -0.147757 0.168383 - 0.039102 -0.147974 0.168524 - 0.0342244 -0.136984 0.169592 - 0.0178684 -0.117799 0.173209 - 0.0139192 -0.124788 0.174107 - 0.00714183 -0.105695 0.175583 - 0.00465739 -0.0949556 0.176116 - -0.0126533 -0.115943 0.18003 - -0.0253505 -0.110758 0.182858 - -0.0248784 -0.0986878 0.182728 - -0.0296904 -0.0967304 0.1838 - -0.0324546 -0.101214 0.184427 - -0.034482 -0.107914 0.184894 - -0.0361025 -0.112655 0.185266 - -0.0853646 -0.27198 0.196606 - -0.126623 -0.359326 0.20601 - -0.12878 -0.360691 0.206495 - -0.163621 -0.377064 0.214319 - -0.180778 -0.372507 0.218145 - -0.196273 -0.367969 0.2216 - -0.199401 -0.366281 0.222296 - -0.207032 -0.365443 0.224001 - -0.224892 -0.367563 0.227998 - -0.23941 -0.362972 0.231235 - -1.3223 -1.78397 0.476262 - -1.29986 -1.3802 0.470417 - -0.419905 -0.375251 0.271615 - -0.426756 -0.374856 0.273146 - -0.432996 -0.370519 0.274533 - -0.407527 -0.333138 0.268762 - -0.411751 -0.327765 0.269695 - -0.41391 -0.32658 0.270175 - -0.419913 -0.328457 0.271521 - -0.434828 -0.307878 0.274814 - -0.58503 -0.274695 0.308328 - -0.622289 -0.272686 0.316655 - -0.967611 -0.401032 0.394126 - -0.926952 -0.295812 0.38482 - -1.02177 -0.291858 0.406011 - -1.10388 -0.278846 0.424342 - -1.15106 -0.210724 0.434751 - -1.14983 -0.168615 0.43439 - -1.14173 -0.131378 0.432503 - -1.13005 -0.0744444 0.429774 - -0.266717 -0.00671896 0.23661 - -0.266782 -0.00326385 0.236618 - -1.11505 0.124931 0.426013 - -1.1124 0.13963 0.425389 - -1.09106 0.261864 0.420368 - -1.09258 0.272481 0.420687 - -1.09615 0.278535 0.421472 - -1.08466 0.322044 0.418814 - -1.07192 0.397192 0.415811 - -1.04354 0.594444 0.409063 - -1.03975 0.629145 0.408144 - -1.03586 0.717214 0.407094 - -1.03213 0.728076 0.406236 - -1.02784 0.801887 0.405127 - -1.01708 0.844778 0.402634 - -1.01143 0.885887 0.401285 - -1.0093 0.915664 0.400748 - -1.01191 0.942517 0.401276 - -0.993016 1.0634 0.396805 - -0.991245 1.08021 0.396374 - -0.988625 1.08679 0.395775 - -0.966021 1.22279 0.390442 - -0.949426 1.3901 0.386389 - -0.934867 1.40756 0.383098 - -0.606719 1.04043 0.310483 - -0.194009 0.328361 0.219667 - -0.501942 1.17642 0.286777 - -0.0866468 0.272711 0.195777 - -0.0253346 0.0965963 0.182429 - -0.0182013 0.0814795 0.180866 - -0.0157261 0.0857396 0.180303 - -0.0145888 0.079809 0.180061 - -0.0131589 0.104922 0.17969 --0.00995592 0.0959967 0.178992 - 0.00257941 0.091204 0.176199 - 0.0177222 0.135209 0.172724 - 0.0192928 0.139982 0.172363 - 0.0302179 0.155842 0.169887 - 0.0342611 0.163016 0.168969 - 0.0410977 0.132307 0.167503 - 0.0399293 0.119849 0.16779 - 0.0341554 0.0940309 0.169134 - 0.0396211 0.103544 0.167892 - 0.0409178 0.105121 0.167599 - 0.135028 0.27473 0.14621 - 0.1532 0.299873 0.142096 - 0.154476 0.299144 0.141812 - 0.159114 0.304499 0.140764 - 0.219638 0.38984 0.127057 - 0.222309 0.390522 0.126458 - 0.530415 0.811308 0.056709 - 0.668637 1.00026 0.0254178 - 0.515017 0.699346 0.0603811 - 0.566899 0.684409 0.0488118 - 0.569809 0.681825 0.0481665 - 0.607154 0.659058 0.0398633 - 0.40153 -0.434785 0.0925545 - 0.365642 -0.42926 0.100176 - 0.365103 -0.432424 0.100297 - 0.356346 -0.433598 0.102162 - 0.338925 -0.431596 0.105862 - 0.310911 -0.422465 0.111802 - 0.290472 -0.42926 0.116162 - 0.208947 -0.381976 0.133404 - 0.0301399 -0.0863023 0.170827 - 0.0271625 -0.086554 0.171461 - 0.0273947 -0.0950914 0.171429 - 0.0365557 -0.140589 0.169574 - 0.0263361 -0.136379 0.171739 - 0.0192502 -0.121693 0.173215 - 0.0173184 -0.128274 0.17364 - 0.00915001 -0.109491 0.175339 - 0.00197645 -0.0863122 0.176817 --0.00072559 -0.0815932 0.177382 --0.00351562 -0.0818281 0.177976 --0.00507902 -0.0959285 0.178337 --0.00531925 -0.100941 0.178398 --0.00644355 -0.108976 0.178654 - -0.0258316 -0.116691 0.182793 - -0.0417617 -0.13276 0.186214 - -0.149586 -0.369902 0.20963 - -0.152739 -0.36863 0.210298 - -0.154678 -0.36891 0.210711 - -0.172717 -0.367502 0.214545 - -0.176262 -0.366929 0.215297 - -0.179809 -0.366322 0.21605 - -0.265581 -0.367789 0.234295 - -1.29245 -1.38161 0.454756 - -1.28657 -1.2493 0.453236 - -0.42463 -0.382433 0.268151 - -0.441097 -0.323716 0.271533 - -0.441684 -0.321196 0.271652 - -0.449624 -0.300791 0.273299 - -0.577938 -0.270898 0.300527 - -0.590639 -0.273789 0.303234 - -0.841038 -0.304858 0.356551 - -1.1563 -0.269988 0.423527 - -1.15113 -0.19983 0.422286 - -1.14596 -0.111103 0.421004 - -1.13599 -0.0898612 0.41884 - -0.277631 -0.00699891 0.23612 - -0.265006 0.00019036 0.23342 - -0.27081 0.00604104 0.234643 - -0.275672 0.00734457 0.235674 - -0.378179 0.0151146 0.257459 - -1.11659 0.129874 0.414266 - -1.1086 0.194044 0.412435 - -1.07872 0.409836 0.405638 - -1.07855 0.453891 0.405512 - -1.0766 0.458658 0.405089 - -1.07244 0.473706 0.404172 - -1.06793 0.505815 0.403149 - -1.0602 0.542699 0.401429 - -1.05226 0.592242 0.399638 - -1.04137 0.673465 0.397156 - -1.03452 0.71496 0.395615 - -1.01623 0.8885 0.391369 - -0.999634 0.962365 0.38769 - -0.991216 1.05032 0.385719 - -0.981091 1.0955 0.383474 - -0.959263 1.35116 0.378309 - -0.926697 1.40586 0.371271 - -0.874224 1.4037 0.360116 - -0.144194 0.300695 0.207112 - -0.239675 0.577708 0.226852 - -0.126136 0.321365 0.203229 - -0.115386 0.312572 0.200961 - -0.10881 0.310625 0.199567 - -0.104162 0.300604 0.198599 - -0.102878 0.301026 0.198325 - -0.0632198 0.204575 0.190088 - -0.0278263 0.0919599 0.182791 - -0.0216676 0.10417 0.181456 - -0.0197459 0.0953425 0.181065 - -0.0193389 0.0953906 0.180979 - -0.018507 0.0914603 0.18081 - -0.0174029 0.0845406 0.180589 - -0.0101632 0.113991 0.178989 --0.00498433 0.108931 0.177898 --0.00206493 0.0776981 0.177341 - 0.00025533 0.0804725 0.176842 - 0.00394984 0.0920853 0.176032 - 0.00872933 0.106506 0.174986 - 0.0336467 0.164366 0.169569 - 0.0406432 0.167538 0.168074 - 0.0418975 0.154539 0.167834 - 0.0383338 0.117508 0.168668 - 0.098817 0.211028 0.155613 - 0.150036 0.298679 0.144541 - 0.1622 0.305478 0.14194 - 0.219428 0.391719 0.129593 - 0.29517 0.464565 0.113336 - 0.310283 0.483091 0.110084 - 0.571646 0.646897 0.0541635 - 0.574402 0.644301 0.0535826 - 0.418704 -0.43992 0.0934782 - 0.409456 -0.437969 0.0953421 - 0.40434 -0.440225 0.09638 - 0.387438 -0.437214 0.0997879 - 0.348793 -0.434611 0.107588 - 0.337609 -0.432367 0.109843 - 0.321054 -0.422852 0.113167 - 0.313123 -0.43167 0.114787 - 0.265303 -0.422148 0.124426 - 0.257586 -0.414158 0.125969 - 0.167908 -0.331444 0.143914 - 0.0363429 -0.0935075 0.170002 - 0.0337124 -0.11956 0.170586 - 0.0027646 -0.0923148 0.176782 --0.00461354 -0.0969278 0.178281 --0.00968296 -0.10399 0.17932 - -0.0137918 -0.0848138 0.180111 - -0.0140793 -0.0787783 0.180156 - -0.0148344 -0.0797203 0.180311 - -0.024365 -0.132989 0.182344 - -0.0269975 -0.139698 0.18289 - -0.0257393 -0.118669 0.182593 - -0.0240416 -0.0885518 0.182189 - -0.0240219 -0.0804126 0.182168 - -0.0249091 -0.0812483 0.182349 - -0.0274375 -0.0878523 0.182873 - -0.0360962 -0.113504 0.184674 - -0.0365814 -0.113379 0.184772 - -0.130585 -0.356774 0.204256 - -0.137942 -0.367903 0.205765 - -0.142652 -0.366139 0.206712 - -0.152995 -0.369558 0.208808 - -0.175913 -0.379168 0.213457 - -0.177533 -0.378418 0.213783 - -0.179446 -0.369795 0.214151 - -0.188784 -0.372965 0.216044 - -0.192664 -0.368739 0.216819 - -0.191994 -0.363471 0.216673 - -0.203936 -0.3672 0.219093 - -0.210874 -0.372437 0.220505 - -0.216815 -0.364383 0.221688 - -1.30977 -1.66755 0.445107 - -1.30814 -1.59284 0.444624 - -0.450962 -0.301346 0.268853 - -0.455164 -0.298488 0.269696 - -0.50115 -0.304673 0.278997 - -0.512533 -0.308648 0.281305 - -0.545086 -0.303092 0.287868 - -0.559641 -0.292339 0.290787 - -0.889574 -0.371697 0.357589 - -0.803636 -0.310832 0.340107 - -0.868484 -0.301489 0.353186 - -0.888332 -0.304072 0.357201 - -0.894274 -0.301734 0.358396 - -0.971744 -0.290401 0.37402 - -1.04015 -0.286202 0.38783 - -1.11357 -0.280293 0.402646 - -1.14643 -0.27789 0.409279 - -1.14761 -0.27282 0.409507 - -1.15821 -0.227164 0.411555 - -0.27003 0.00019399 0.231693 - -0.266099 0.00248615 0.230894 - -1.11374 0.119354 0.401866 - -1.11154 0.139017 0.401381 - -1.11517 0.149489 0.402093 - -1.10029 0.212327 0.39896 - -1.09153 0.245812 0.397121 - -1.0806 0.361559 0.394677 - -1.07373 0.391083 0.39323 - -1.07702 0.419365 0.393836 - -1.07483 0.457108 0.393316 - -1.06113 0.542248 0.390377 - -1.05757 0.558107 0.389624 - -1.04529 0.649188 0.386959 - -1.03817 0.670237 0.385477 - -1.03859 0.67698 0.385548 - -1.0398 0.684285 0.385777 - -1.01979 0.792747 0.381514 - -1.00713 0.926588 0.378684 - -1.00749 0.93508 0.37874 - -0.970052 1.18088 0.370677 - -0.967496 1.22045 0.37008 - -0.962879 1.22549 0.369137 - -0.909696 1.40395 0.358031 - -0.855329 1.39775 0.347062 - -0.744486 1.25115 0.324973 - -0.199745 0.331868 0.21682 - -0.186973 0.31284 0.214279 - -0.156971 0.273866 0.208299 - -0.0977495 0.294212 0.196295 - -0.0339096 0.108924 0.183779 - -0.0154654 0.0836855 0.180105 - -0.0151074 0.0837164 0.180032 - -0.0131967 0.0818505 0.17965 --0.00872366 0.102999 0.178704 - 0.00617848 0.0958601 0.175708 - 0.023922 0.142234 0.17203 - 0.0361523 0.133484 0.169577 - 0.191288 0.345365 0.13781 - 0.234574 0.403971 0.128948 - 0.243256 0.394827 0.127212 - 0.551889 0.838572 0.0639685 - 0.575435 0.690465 0.0595146 - 0.615604 0.658452 0.0514665 - 0.401727 -0.439879 0.101478 - 0.357517 -0.435982 0.109907 - 0.331982 -0.431527 0.11477 - 0.248085 -0.417428 0.130751 - 0.240907 -0.413714 0.132113 - 0.157112 -0.316217 0.147905 - 0.0438215 -0.103395 0.16909 - 0.0304832 -0.0909885 0.17161 - 0.0279396 -0.0963452 0.172107 - 0.032455 -0.12652 0.171307 - 0.0229258 -0.133375 0.173139 - 0.0265854 -0.165332 0.172506 - 0.0107206 -0.110396 0.175421 - 0.00132846 -0.0824731 0.177157 - 0.00097491 -0.082513 0.177224 --0.00700023 -0.105996 0.178794 - -0.0120744 -0.107913 0.179766 - -0.0129713 -0.0908497 0.179902 - -0.0193513 -0.106355 0.181151 - -0.0243721 -0.0904471 0.182077 - -0.0253317 -0.0872002 0.182254 - -0.140435 -0.36052 0.204775 - -0.158831 -0.361646 0.208287 - -0.165425 -0.372912 0.209569 - -0.202039 -0.363686 0.216537 - -0.228576 -0.373561 0.221621 - -0.232798 -0.373289 0.222426 - -0.240715 -0.364649 0.223919 - -0.250299 -0.368992 0.225757 - -1.33203 -1.80344 0.435099 - -1.30238 -1.59707 0.429022 - -1.30168 -1.58209 0.428856 - -1.28212 -1.28459 0.424519 - -0.411524 -0.386144 0.256557 - -0.414283 -0.378705 0.257069 - -0.420585 -0.374585 0.258263 - -0.417452 -0.325381 0.257565 - -0.443502 -0.336826 0.262559 - -0.454028 -0.297393 0.264488 - -0.520485 -0.3039 0.277183 - -0.524351 -0.297041 0.277906 - -0.544924 -0.302608 0.281844 - -0.562984 -0.293723 0.285272 - -0.564238 -0.291254 0.285506 - -0.601115 -0.268414 0.292496 - -0.603615 -0.26009 0.292957 - -0.638185 -0.271873 0.299578 - -0.948182 -0.395764 0.358985 - -0.946066 -0.295847 0.358378 - -0.952024 -0.293135 0.359509 - -1.03837 -0.280315 0.37596 - -1.15628 -0.236996 0.398373 - -1.14686 -0.131265 0.39636 - -1.13208 -0.0892393 0.393453 - -0.726082 -0.0345887 0.315867 - -0.547618 -0.0235914 0.28179 - -0.267191 0.00134372 0.228226 - -0.257331 0.00461742 0.226338 - -1.11707 0.0797846 0.390245 - -1.08266 0.351083 0.383126 - -1.08511 0.378455 0.383537 - -1.06274 0.513087 0.378995 - -1.06537 0.52595 0.37947 - -1.0617 0.53577 0.37875 - -1.0434 0.65327 0.375019 - -1.03574 0.667548 0.373529 - -1.03246 0.678287 0.37288 - -1.02798 0.734882 0.37191 - -1.03042 0.743474 0.372358 - -1.01365 0.883273 0.368873 - -1.01134 0.889044 0.36842 - -0.989967 1.05469 0.364005 - -0.972815 1.16159 0.360515 - -0.971542 1.19133 0.360211 - -0.365173 0.817886 0.245261 - -0.515414 1.20399 0.273145 - -0.124725 0.318554 0.200394 - -0.119977 0.31394 0.199497 - -0.0825226 0.252854 0.192475 - -0.0535464 0.170801 0.187112 - -0.0276143 0.0908099 0.182327 - -0.0234182 0.0835196 0.181541 - -0.0259131 0.119605 0.181943 - -0.02569 0.121662 0.181897 - -0.0247829 0.122805 0.181721 - -0.0144718 0.0857396 0.179829 --0.00109365 0.0827098 0.177282 - 0.00149587 0.0834529 0.176787 - 0.0215605 0.137768 0.172847 - 0.0376181 0.148949 0.16976 - 0.0352413 0.125532 0.170262 - 0.0371881 0.125885 0.169889 - 0.0354793 0.110496 0.170247 - 0.0391008 0.100152 0.169577 - 0.167705 0.312421 0.144604 - 0.775986 1.09725 0.0269304 - 0.594583 0.717376 0.0623202 - 0.586748 0.701822 0.0638469 - 0.585883 0.694647 0.0640265 - 0.586691 0.631627 0.0640008 - 0.376286 -0.433536 0.110293 - 0.368638 -0.432424 0.111671 - 0.251805 -0.41798 0.132727 - 0.154635 -0.313405 0.150051 - 0.0274353 -0.0816439 0.172536 - 0.0264043 -0.083174 0.172725 - 0.0282693 -0.0985363 0.17242 - 0.0298633 -0.152364 0.172242 - 0.0275739 -0.145727 0.172641 - 0.00966941 -0.101525 0.175783 --0.00082279 -0.0736943 0.17762 --0.00113928 -0.0737229 0.177677 --0.00138207 -0.0887875 0.177751 --0.00704273 -0.105999 0.178808 - -0.0114507 -0.114927 0.179622 - -0.0120745 -0.0968847 0.179698 - -0.0126818 -0.0928464 0.179799 - -0.0133253 -0.0847884 0.179899 - -0.0241922 -0.078166 0.181846 - -0.180448 -0.368126 0.210636 - -0.194345 -0.372302 0.213152 - -0.195942 -0.371469 0.213439 - -0.197536 -0.370629 0.213725 - -0.206693 -0.372471 0.215381 - -0.266588 -0.372196 0.22619 - -1.29469 -1.48995 0.414008 - -0.41173 -0.376005 0.252392 - -0.424619 -0.377912 0.254722 - -0.425501 -0.375396 0.254877 - -0.429454 -0.372329 0.255584 - -0.438049 -0.366713 0.257123 - -0.444206 -0.307475 0.258114 - -0.442419 -0.297728 0.257772 - -0.467282 -0.303024 0.26227 - -0.47531 -0.299545 0.263712 - -0.536041 -0.303434 0.27468 - -0.538628 -0.298735 0.275137 - -0.565355 -0.294645 0.279952 - -0.728645 -0.310489 0.309454 - -0.825592 -0.306055 0.326942 - -0.846719 -0.305532 0.330754 - -0.965933 -0.292387 0.352242 - -0.992977 -0.291133 0.35712 - -1.15794 -0.242298 0.386793 - -1.13545 -0.104485 0.382453 - -1.13631 -0.0944787 0.382587 - -0.725866 -0.0377271 0.308398 - -0.325135 -0.011038 0.236022 - -0.282883 -0.00834742 0.228392 - -0.270206 -0.002136 0.226091 - -0.265284 0.0024767 0.225193 - -0.263303 0.00359217 0.224834 - -1.05972 0.0614947 0.368448 - -1.11135 0.173475 0.37754 - -1.1173 0.214949 0.37853 - -1.098 0.236369 0.375002 - -1.09257 0.301445 0.37389 - -1.09032 0.305985 0.373475 - -1.0757 0.444943 0.370553 - -1.06748 0.474815 0.36901 - -1.07079 0.498989 0.369558 - -1.05497 0.560906 0.366577 - -1.04038 0.69565 0.36367 - -1.00947 0.925915 0.357624 - -1.0003 0.975337 0.355868 - -0.995246 1.03149 0.354842 - -0.989532 1.1095 0.353652 - -0.986467 1.14561 0.353025 - -0.976114 1.18473 0.351077 - -0.967603 1.22784 0.349454 - -0.955089 1.33898 0.346969 - -0.951505 1.35877 0.346282 - -0.144794 0.271251 0.202902 - -0.454956 1.03463 0.257327 - -0.114112 0.306437 0.197293 - -0.0362477 0.113294 0.183633 - -0.024761 0.0974326 0.181592 - -0.0108745 0.114949 0.17905 --0.00878705 0.105992 0.178692 --0.00694784 0.109998 0.178352 - 0.00075337 0.0825762 0.177018 - 0.0368629 0.164946 0.170333 - 0.0391379 0.162214 0.169928 - 0.0370356 0.152419 0.170328 - 0.0348769 0.124777 0.170774 - 0.0425336 0.107593 0.169427 - 0.0511574 0.123352 0.167838 - 0.119515 0.252952 0.155238 - 0.155952 0.30235 0.148562 - 0.243964 0.396784 0.132486 - 0.31395 0.479184 0.119688 - 0.7773 1.09645 0.0348103 - 0.758051 0.97691 0.0385272 - 0.697218 0.822866 0.0498192 - 0.423347 -0.444671 0.106585 - 0.385151 -0.434545 0.113035 - 0.376886 -0.436726 0.11444 - 0.340909 -0.432367 0.120526 - 0.233792 -0.410973 0.138629 - 0.043945 -0.106095 0.170172 - 0.0317036 -0.084315 0.172202 - 0.0299264 -0.104498 0.172544 - 0.027322 -0.115891 0.173008 - 0.00895328 -0.0996982 0.176087 - 0.0035516 -0.0943969 0.176991 --0.00286681 -0.0808919 0.178051 - -0.0126589 -0.0868094 0.179722 - -0.0282054 -0.152485 0.182489 - -0.0247064 -0.094302 0.181778 - -0.0328263 -0.0975393 0.183161 - -0.0581765 -0.180679 0.187624 - -0.100911 -0.297078 0.195099 - -0.118518 -0.33752 0.198164 - -0.152422 -0.37392 0.203982 - -0.169973 -0.370779 0.206949 - -0.174244 -0.363305 0.207657 - -0.185661 -0.37107 0.209607 - -0.194723 -0.365309 0.21113 - -0.236018 -0.367722 0.218131 - -1.3091 -1.68853 0.402599 - -1.31007 -1.65973 0.402706 - -1.28451 -1.40014 0.397849 - -1.29204 -1.35998 0.399044 - -0.434277 -0.376262 0.251735 - -0.439851 -0.371202 0.252669 - -0.40275 -0.330468 0.246301 - -0.504515 -0.299762 0.263479 - -0.541335 -0.296857 0.269711 - -0.571484 -0.288097 0.2748 - -0.611218 -0.275557 0.281506 - -0.80794 -0.311189 0.314905 - -0.896317 -0.301101 0.329856 - -0.959428 -0.294593 0.340535 - -1.16063 -0.242501 0.374515 - -1.15201 -0.214376 0.372997 - -1.15663 -0.199493 0.373749 - -1.14353 -0.110152 0.37135 - -0.719051 -0.0341634 0.299284 - -0.277077 -0.00697346 0.224355 - -0.381383 0.0151946 0.24198 - -1.11531 0.0942242 0.366154 - -1.10041 0.246681 0.363321 - -1.09321 0.301181 0.36199 - -1.0827 0.334388 0.360143 - -1.07908 0.445701 0.359303 - -1.07248 0.45401 0.358168 - -1.07415 0.460285 0.358438 - -1.04768 0.591997 0.353687 - -1.04037 0.668624 0.352293 - -1.03166 0.682282 0.350789 - -1.03858 0.69344 0.351939 - -1.03719 0.725794 0.351639 - -1.03015 0.741149 0.350414 - -1.02015 0.825712 0.348549 - -1.01316 0.903891 0.347206 - -0.999405 1.00765 0.344666 - -0.983504 1.11085 0.341762 - -0.977307 1.15349 0.340626 - -0.980651 1.17813 0.341143 - -0.967058 1.20373 0.338788 - -0.958276 1.28171 0.337142 - -0.951192 1.38188 0.335739 - -0.946479 1.40093 0.334902 - -0.880361 1.40539 0.323692 - -0.176773 0.295556 0.206749 - -0.151113 0.272301 0.202449 - -0.14645 0.287101 0.201629 - -0.388814 0.891662 0.241461 - -0.156579 0.371251 0.203174 - -0.132209 0.318673 0.199153 - -0.122557 0.322399 0.19751 - -0.106073 0.300691 0.194761 - -0.0899283 0.267101 0.192094 - -0.0242888 0.0903223 0.181333 - -0.0248047 0.128748 0.181343 - -0.0185142 0.0952927 0.180345 - -0.0144719 0.0826571 0.179686 - -0.0113324 0.0918971 0.179135 - -0.0104863 0.10194 0.178971 --0.00788704 0.105996 0.178523 --0.00400354 0.114958 0.177847 --0.00150195 0.0848138 0.177484 - 0.0248081 0.142376 0.17291 - 0.0374631 0.154535 0.170742 - 0.0343662 0.109198 0.171358 - 0.0355843 0.10548 0.171159 - 0.233838 0.406119 0.136964 - 0.249488 0.388938 0.134347 - 0.763315 1.10435 0.0458493 - 0.776955 1.08328 0.0435812 - 0.729204 0.850538 0.0521427 - 0.426907 -0.439431 0.110542 - 0.38823 -0.436758 0.116682 - 0.34931 -0.426145 0.122843 - 0.305177 -0.427077 0.129856 - 0.240195 -0.412248 0.140149 - 0.224348 -0.405469 0.142653 - 0.0279828 -0.0796574 0.173189 - 0.0300215 -0.0863931 0.172879 - 0.0241587 -0.0833863 0.173804 - 0.0269978 -0.0961739 0.173379 - 0.0260976 -0.110145 0.17355 - 0.0249429 -0.111529 0.173737 - 0.0334577 -0.159952 0.172482 - 0.0308488 -0.174952 0.172927 - 0.00570928 -0.0982174 0.176765 --0.00422223 -0.111975 0.178371 - -0.0122447 -0.0868094 0.179594 - -0.0162269 -0.0965047 0.180247 - -0.0178863 -0.108394 0.180534 - -0.0293364 -0.149226 0.182436 - -0.0250844 -0.10331 0.181668 - -0.0254107 -0.0807765 0.181674 - -0.0278371 -0.0894422 0.182077 - -0.0308617 -0.0948604 0.182568 - -0.0316784 -0.0946421 0.182698 - -0.0351363 -0.104051 0.183266 - -0.0898527 -0.266979 0.192288 - -0.126554 -0.347336 0.198282 - -0.13255 -0.35473 0.199249 - -0.139549 -0.359584 0.200371 - -0.147177 -0.360898 0.201585 - -0.210021 -0.363658 0.211575 - -0.229146 -0.367323 0.21462 - -0.240123 -0.360267 0.21635 - -0.251189 -0.359963 0.218107 - -1.31151 -1.68932 0.389248 - -1.31389 -1.67726 0.3896 - -1.30258 -1.59013 0.387628 - -1.30005 -1.54535 0.387135 - -1.29658 -1.50092 0.386495 - -0.413936 -0.374208 0.243991 - -0.415546 -0.372404 0.244243 - -0.417147 -0.370593 0.244494 - -0.427754 -0.373538 0.246185 - -0.440813 -0.375061 0.248263 - -0.442503 -0.31442 0.248408 - -0.490065 -0.299558 0.255934 - -0.501097 -0.300418 0.257689 - -0.509627 -0.299585 0.259042 - -0.539668 -0.298735 0.263813 - -0.59089 -0.278546 0.271909 - -0.610916 -0.275147 0.275084 - -1.15158 -0.235009 0.360895 - -1.15064 -0.22956 0.360735 - -1.15521 -0.152262 0.361305 - -1.14061 -0.114783 0.358909 - -0.703057 -0.0333601 0.289232 - -0.293855 -0.00867536 0.224174 - -0.265336 -0.002096 0.21963 - -0.268306 -0.00096374 0.2201 - -1.11654 0.0843367 0.354681 - -1.11332 0.15333 0.35403 - -1.10332 0.18665 0.352374 - -1.11548 0.208928 0.35426 - -1.11651 0.2142 0.354414 - -1.08379 0.37109 0.348899 - -1.08783 0.410187 0.349461 - -1.07025 0.508825 0.346468 - -1.034 0.650966 0.340421 - -1.04285 0.688869 0.341751 - -0.997252 0.9955 0.333886 - -0.992605 1.01711 0.333104 - -0.990618 1.11757 0.332585 - -0.978494 1.15349 0.330586 - -0.974865 1.18011 0.329955 - -0.970309 1.23915 0.329112 - -0.965035 1.25474 0.328243 - -0.956343 1.32506 0.326719 - -0.948902 1.3391 0.325509 - -0.941012 1.40425 0.324124 - -0.151841 0.268385 0.201052 - -0.149523 0.269657 0.200681 - -0.411934 0.922977 0.241046 - -0.153843 0.360421 0.201184 - -0.123025 0.320008 0.19637 - -0.107754 0.297912 0.193988 - -0.0270176 0.127337 0.181508 - -0.0111137 0.105902 0.179024 - -0.010734 0.10792 0.17896 --0.00949123 0.113963 0.17875 --0.00654642 0.108 0.178295 --0.00419766 0.108972 0.177919 - 0.00135789 0.0795915 0.177096 - 0.00858976 0.0967821 0.175913 - 0.00991354 0.0996025 0.175697 - 0.0110132 0.10347 0.175514 - 0.0181483 0.128575 0.17433 - 0.0309828 0.152308 0.172243 - 0.0342755 0.159714 0.171705 - 0.0336801 0.144338 0.17183 - 0.0324282 0.119633 0.172079 - 0.0312246 0.109486 0.172291 - 0.0321801 0.099526 0.172159 - 0.0330365 0.0991793 0.172024 - 0.0711365 0.162969 0.165842 - 0.143105 0.290829 0.15415 - 0.150711 0.299203 0.152925 - 0.19804 0.354885 0.145293 - 0.233936 0.4089 0.139481 - 0.245366 0.388687 0.137706 - 0.334282 0.501641 0.123352 - 0.7605 1.09782 0.0544333 - 0.765224 1.09442 0.0536896 - 0.753998 1.03963 0.0555841 - 0.723678 0.864803 0.0607549 - 0.435716 -0.447215 0.113872 - 0.41471 -0.437253 0.116965 - 0.402357 -0.439507 0.1188 - 0.380208 -0.43428 0.122072 - 0.378331 -0.435979 0.122354 - 0.372515 -0.433174 0.12321 - 0.349773 -0.433119 0.126581 - 0.346014 -0.432368 0.127136 - 0.301121 -0.431982 0.133788 - 0.243066 -0.415669 0.142359 - 0.213316 -0.400736 0.146738 - 0.0427722 -0.103833 0.171412 - 0.0241498 -0.0749909 0.174114 - 0.0250336 -0.103304 0.17404 - 0.0125578 -0.110396 0.175903 - 0.00645453 -0.0971707 0.176781 - 0.00450024 -0.0913699 0.177059 - 0.00410579 -0.091416 0.177118 - 0.00032894 -0.0717026 0.177638 - -0.0256909 -0.0990448 0.181549 - -0.0803253 -0.237421 0.189926 - -0.0907107 -0.266608 0.191524 - -0.141239 -0.359927 0.199201 - -0.160918 -0.368088 0.202134 - -0.16409 -0.366707 0.202601 - -0.170069 -0.371692 0.203497 - -0.176462 -0.368741 0.204438 - -0.193826 -0.367915 0.20701 - -0.207099 -0.36983 0.208981 - -1.31001 -1.71586 0.375155 - -1.29758 -1.55412 0.372985 - -1.27505 -1.37401 0.369281 - -1.28414 -1.35986 0.3706 - -0.414003 -0.377355 0.23966 - -0.416361 -0.376223 0.240007 - -0.422394 -0.378421 0.240905 - -0.439678 -0.370556 0.243451 - -0.408855 -0.323411 0.238788 - -0.46257 -0.299216 0.246699 - -0.470978 -0.298934 0.247945 - -0.485351 -0.296427 0.25007 - -0.523261 -0.304403 0.255704 - -0.525871 -0.299829 0.256082 - -0.558306 -0.30259 0.260894 - -0.581515 -0.283203 0.264295 - -0.58424 -0.275138 0.264682 - -0.965187 -0.41575 0.321423 - -0.869201 -0.304 0.306972 - -0.912844 -0.301537 0.313435 - -0.935545 -0.295512 0.316787 - -0.986347 -0.288063 0.324301 - -1.03385 -0.287328 0.331339 - -1.03604 -0.283054 0.331654 - -1.10118 -0.280302 0.341303 - -1.15206 -0.224313 0.34873 - -1.13888 -0.0943145 0.346514 - -0.265324 0.00133354 0.21686 - -0.265316 0.0024767 0.216856 - -0.266252 0.00592834 0.216988 - -1.12414 0.124603 0.343886 - -1.10723 0.222236 0.341183 - -1.10527 0.23194 0.340874 - -1.10226 0.241414 0.340409 - -1.09159 0.27441 0.33876 - -1.0904 0.279195 0.338574 - -1.09094 0.346608 0.338517 - -1.08485 0.387006 0.337533 - -1.08549 0.41425 0.337574 - -1.07314 0.45872 0.335653 - -1.06823 0.467714 0.334908 - -1.0699 0.490948 0.335108 - -1.06614 0.506262 0.33452 - -1.05022 0.591997 0.331987 - -1.05084 0.623008 0.332016 - -1.04136 0.648528 0.330559 - -1.03662 0.683929 0.329786 - -1.02132 0.832076 0.327219 - -1.00797 0.905001 0.325093 - -1.00553 0.91075 0.324719 - -1.00159 0.915148 0.324127 - -1.00918 0.946667 0.325188 - -0.998805 1.01345 0.323515 - -0.993844 1.03513 0.322736 - -0.989989 1.06777 0.322099 - -0.981009 1.11516 0.320672 - -0.975321 1.16893 0.319721 - -0.971366 1.19559 0.319081 - -0.964211 1.24103 0.317928 - -0.958565 1.32668 0.316918 - -0.945871 1.3968 0.314895 - -0.179514 0.38504 0.203367 - -0.376701 0.852425 0.231645 - -0.133747 0.315702 0.196724 - -0.114998 0.306903 0.193963 - -0.10619 0.298356 0.192675 - -0.0633411 0.18939 0.186546 - -0.0319743 0.0975773 0.182083 - -0.0250365 0.0828352 0.181084 - -0.026374 0.129402 0.181188 --0.00114317 0.0768313 0.177555 - 0.0139889 0.115207 0.175235 - 0.0191779 0.128464 0.174439 - 0.0243039 0.138611 0.173659 - 0.0294077 0.146646 0.172887 - 0.0304522 0.0950377 0.172836 - 0.0320508 0.0954717 0.172598 - 0.0332838 0.0949576 0.172417 - 0.0345186 0.0933317 0.172237 - 0.0448288 0.111664 0.170672 - 0.0983652 0.218792 0.162521 - 0.140896 0.294574 0.156065 - 0.240908 0.399248 0.141031 - 0.750004 1.04137 0.0642851 - 0.672486 0.781413 0.0762988 - 0.662738 0.763442 0.0777798 - 0.540671 0.597336 0.096206 - 0.431432 -0.442262 0.117116 - 0.422047 -0.440389 0.118447 - 0.37692 -0.433739 0.124851 - 0.371202 -0.434839 0.125667 - 0.336585 -0.431527 0.130583 - 0.33162 -0.432957 0.131292 - 0.306016 -0.426272 0.13492 - 0.266404 -0.420015 0.14054 - 0.247833 -0.410641 0.143162 - 0.243757 -0.420194 0.143761 - 0.183185 -0.367361 0.152269 - 0.124896 -0.26826 0.160358 - 0.0306359 -0.108924 0.173441 - 0.0265752 -0.122696 0.174046 - 0.0323815 -0.161441 0.173299 - 0.0258735 -0.154712 0.17421 - 0.0235721 -0.150082 0.174528 - 0.022735 -0.149228 0.174646 - 0.017987 -0.133847 0.17529 - 0.00968512 -0.0997678 0.176402 --0.00083284 -0.0788344 0.177855 --0.00196042 -0.083906 0.178026 --0.00736058 -0.107989 0.178842 --0.00784478 -0.108982 0.178913 - -0.0105636 -0.0968847 0.179275 - -0.0113895 -0.083816 0.179366 - -0.0251637 -0.102161 0.181362 - -0.0240975 -0.0881006 0.181182 - -0.0237646 -0.0779364 0.181114 - -0.0245559 -0.0798033 0.181231 - -0.0291427 -0.088951 0.181902 - -0.0542045 -0.161794 0.185613 - -0.133196 -0.347975 0.197222 - -0.164775 -0.368541 0.201755 - -0.177841 -0.363615 0.203603 - -0.217618 -0.36259 0.209258 - -0.223804 -0.36585 0.210144 - -0.225383 -0.364886 0.210367 - -0.257196 -0.365448 0.214892 - -1.30251 -1.67436 0.366191 - -1.31138 -1.65582 0.367415 - -1.29884 -1.58242 0.365483 - -1.27368 -1.35966 0.361456 - -1.27168 -1.334 0.36112 - -1.29387 -1.2881 0.364183 - -1.29166 -1.27471 0.363841 - -0.436094 -0.364144 0.24033 - -0.4395 -0.332593 0.240751 - -0.437495 -0.304825 0.24041 - -0.442877 -0.305767 0.241177 - -0.445503 -0.301903 0.241543 - -0.475668 -0.304764 0.245838 - -0.476981 -0.302691 0.246021 - -0.508045 -0.301294 0.250436 - -0.545068 -0.298298 0.255695 - -0.599566 -0.291957 0.263432 - -0.602606 -0.290205 0.263861 - -0.60183 -0.280181 0.26373 - -1.01497 -0.416151 0.322758 - -0.810586 -0.307288 0.293473 - -0.895162 -0.299834 0.305485 - -0.997399 -0.291133 0.320007 - -1.05702 -0.28367 0.32847 - -1.06877 -0.281828 0.330137 - -1.15335 -0.256071 0.342113 - -1.15065 -0.203022 0.341623 - -0.267242 0.00479921 0.215573 - -0.269199 0.00599596 0.215848 - -1.11038 0.0739311 0.335336 - -1.1074 0.167094 0.334725 - -1.09996 0.245812 0.333508 - -1.09669 0.260255 0.333013 - -1.04481 0.588573 0.324973 - -1.05167 0.610766 0.325903 - -1.03897 0.704781 0.323906 - -1.02583 0.722306 0.322002 - -1.02825 0.765096 0.32226 - -1.0158 0.880007 0.320258 - -1.01024 0.92255 0.319381 - -1.00989 0.930347 0.319316 - -0.983754 1.10786 0.31524 - -0.980272 1.11366 0.314733 - -0.968895 1.23522 0.31287 - -0.942513 1.39101 0.308803 - -0.157109 0.267516 0.19938 - -0.151062 0.273182 0.198508 - -0.141535 0.269183 0.197162 - -0.350672 0.78316 0.225865 - -0.13286 0.313851 0.195838 - -0.0975225 0.276977 0.190887 - -0.0308263 0.0957556 0.181768 - -0.0263494 0.0845216 0.181154 - -0.0244227 0.0900856 0.180869 - -0.0266637 0.119177 0.181129 - -0.0252192 0.123475 0.180914 - -0.0142091 0.0835833 0.179429 - -0.0105444 0.0718491 0.178932 - 0.00255446 0.084566 0.177043 - 0.0047422 0.0873361 0.176727 - 0.00601501 0.091204 0.176538 - 0.0103937 0.103695 0.17589 - 0.0121082 0.108478 0.175636 - 0.0237656 0.137768 0.173919 - 0.0307966 0.148428 0.172898 - 0.0327171 0.147929 0.172626 - 0.0325759 0.137603 0.172667 - 0.0329309 0.134378 0.172623 - 0.0315188 0.125414 0.172842 - 0.029138 0.104136 0.173223 - 0.0333181 0.100456 0.172636 - 0.143439 0.295704 0.156581 - 0.243305 0.3909 0.142187 - 0.667099 0.809214 0.0810737 -VERTICES 36670 73340 -1 0 -1 1 -1 2 -1 3 -1 4 -1 5 -1 6 -1 7 -1 8 -1 9 -1 10 -1 11 -1 12 -1 13 -1 14 -1 15 -1 16 -1 17 -1 18 -1 19 -1 20 -1 21 -1 22 -1 23 -1 24 -1 25 -1 26 -1 27 -1 28 -1 29 -1 30 -1 31 -1 32 -1 33 -1 34 -1 35 -1 36 -1 37 -1 38 -1 39 -1 40 -1 41 -1 42 -1 43 -1 44 -1 45 -1 46 -1 47 -1 48 -1 49 -1 50 -1 51 -1 52 -1 53 -1 54 -1 55 -1 56 -1 57 -1 58 -1 59 -1 60 -1 61 -1 62 -1 63 -1 64 -1 65 -1 66 -1 67 -1 68 -1 69 -1 70 -1 71 -1 72 -1 73 -1 74 -1 75 -1 76 -1 77 -1 78 -1 79 -1 80 -1 81 -1 82 -1 83 -1 84 -1 85 -1 86 -1 87 -1 88 -1 89 -1 90 -1 91 -1 92 -1 93 -1 94 -1 95 -1 96 -1 97 -1 98 -1 99 -1 100 -1 101 -1 102 -1 103 -1 104 -1 105 -1 106 -1 107 -1 108 -1 109 -1 110 -1 111 -1 112 -1 113 -1 114 -1 115 -1 116 -1 117 -1 118 -1 119 -1 120 -1 121 -1 122 -1 123 -1 124 -1 125 -1 126 -1 127 -1 128 -1 129 -1 130 -1 131 -1 132 -1 133 -1 134 -1 135 -1 136 -1 137 -1 138 -1 139 -1 140 -1 141 -1 142 -1 143 -1 144 -1 145 -1 146 -1 147 -1 148 -1 149 -1 150 -1 151 -1 152 -1 153 -1 154 -1 155 -1 156 -1 157 -1 158 -1 159 -1 160 -1 161 -1 162 -1 163 -1 164 -1 165 -1 166 -1 167 -1 168 -1 169 -1 170 -1 171 -1 172 -1 173 -1 174 -1 175 -1 176 -1 177 -1 178 -1 179 -1 180 -1 181 -1 182 -1 183 -1 184 -1 185 -1 186 -1 187 -1 188 -1 189 -1 190 -1 191 -1 192 -1 193 -1 194 -1 195 -1 196 -1 197 -1 198 -1 199 -1 200 -1 201 -1 202 -1 203 -1 204 -1 205 -1 206 -1 207 -1 208 -1 209 -1 210 -1 211 -1 212 -1 213 -1 214 -1 215 -1 216 -1 217 -1 218 -1 219 -1 220 -1 221 -1 222 -1 223 -1 224 -1 225 -1 226 -1 227 -1 228 -1 229 -1 230 -1 231 -1 232 -1 233 -1 234 -1 235 -1 236 -1 237 -1 238 -1 239 -1 240 -1 241 -1 242 -1 243 -1 244 -1 245 -1 246 -1 247 -1 248 -1 249 -1 250 -1 251 -1 252 -1 253 -1 254 -1 255 -1 256 -1 257 -1 258 -1 259 -1 260 -1 261 -1 262 -1 263 -1 264 -1 265 -1 266 -1 267 -1 268 -1 269 -1 270 -1 271 -1 272 -1 273 -1 274 -1 275 -1 276 -1 277 -1 278 -1 279 -1 280 -1 281 -1 282 -1 283 -1 284 -1 285 -1 286 -1 287 -1 288 -1 289 -1 290 -1 291 -1 292 -1 293 -1 294 -1 295 -1 296 -1 297 -1 298 -1 299 -1 300 -1 301 -1 302 -1 303 -1 304 -1 305 -1 306 -1 307 -1 308 -1 309 -1 310 -1 311 -1 312 -1 313 -1 314 -1 315 -1 316 -1 317 -1 318 -1 319 -1 320 -1 321 -1 322 -1 323 -1 324 -1 325 -1 326 -1 327 -1 328 -1 329 -1 330 -1 331 -1 332 -1 333 -1 334 -1 335 -1 336 -1 337 -1 338 -1 339 -1 340 -1 341 -1 342 -1 343 -1 344 -1 345 -1 346 -1 347 -1 348 -1 349 -1 350 -1 351 -1 352 -1 353 -1 354 -1 355 -1 356 -1 357 -1 358 -1 359 -1 360 -1 361 -1 362 -1 363 -1 364 -1 365 -1 366 -1 367 -1 368 -1 369 -1 370 -1 371 -1 372 -1 373 -1 374 -1 375 -1 376 -1 377 -1 378 -1 379 -1 380 -1 381 -1 382 -1 383 -1 384 -1 385 -1 386 -1 387 -1 388 -1 389 -1 390 -1 391 -1 392 -1 393 -1 394 -1 395 -1 396 -1 397 -1 398 -1 399 -1 400 -1 401 -1 402 -1 403 -1 404 -1 405 -1 406 -1 407 -1 408 -1 409 -1 410 -1 411 -1 412 -1 413 -1 414 -1 415 -1 416 -1 417 -1 418 -1 419 -1 420 -1 421 -1 422 -1 423 -1 424 -1 425 -1 426 -1 427 -1 428 -1 429 -1 430 -1 431 -1 432 -1 433 -1 434 -1 435 -1 436 -1 437 -1 438 -1 439 -1 440 -1 441 -1 442 -1 443 -1 444 -1 445 -1 446 -1 447 -1 448 -1 449 -1 450 -1 451 -1 452 -1 453 -1 454 -1 455 -1 456 -1 457 -1 458 -1 459 -1 460 -1 461 -1 462 -1 463 -1 464 -1 465 -1 466 -1 467 -1 468 -1 469 -1 470 -1 471 -1 472 -1 473 -1 474 -1 475 -1 476 -1 477 -1 478 -1 479 -1 480 -1 481 -1 482 -1 483 -1 484 -1 485 -1 486 -1 487 -1 488 -1 489 -1 490 -1 491 -1 492 -1 493 -1 494 -1 495 -1 496 -1 497 -1 498 -1 499 -1 500 -1 501 -1 502 -1 503 -1 504 -1 505 -1 506 -1 507 -1 508 -1 509 -1 510 -1 511 -1 512 -1 513 -1 514 -1 515 -1 516 -1 517 -1 518 -1 519 -1 520 -1 521 -1 522 -1 523 -1 524 -1 525 -1 526 -1 527 -1 528 -1 529 -1 530 -1 531 -1 532 -1 533 -1 534 -1 535 -1 536 -1 537 -1 538 -1 539 -1 540 -1 541 -1 542 -1 543 -1 544 -1 545 -1 546 -1 547 -1 548 -1 549 -1 550 -1 551 -1 552 -1 553 -1 554 -1 555 -1 556 -1 557 -1 558 -1 559 -1 560 -1 561 -1 562 -1 563 -1 564 -1 565 -1 566 -1 567 -1 568 -1 569 -1 570 -1 571 -1 572 -1 573 -1 574 -1 575 -1 576 -1 577 -1 578 -1 579 -1 580 -1 581 -1 582 -1 583 -1 584 -1 585 -1 586 -1 587 -1 588 -1 589 -1 590 -1 591 -1 592 -1 593 -1 594 -1 595 -1 596 -1 597 -1 598 -1 599 -1 600 -1 601 -1 602 -1 603 -1 604 -1 605 -1 606 -1 607 -1 608 -1 609 -1 610 -1 611 -1 612 -1 613 -1 614 -1 615 -1 616 -1 617 -1 618 -1 619 -1 620 -1 621 -1 622 -1 623 -1 624 -1 625 -1 626 -1 627 -1 628 -1 629 -1 630 -1 631 -1 632 -1 633 -1 634 -1 635 -1 636 -1 637 -1 638 -1 639 -1 640 -1 641 -1 642 -1 643 -1 644 -1 645 -1 646 -1 647 -1 648 -1 649 -1 650 -1 651 -1 652 -1 653 -1 654 -1 655 -1 656 -1 657 -1 658 -1 659 -1 660 -1 661 -1 662 -1 663 -1 664 -1 665 -1 666 -1 667 -1 668 -1 669 -1 670 -1 671 -1 672 -1 673 -1 674 -1 675 -1 676 -1 677 -1 678 -1 679 -1 680 -1 681 -1 682 -1 683 -1 684 -1 685 -1 686 -1 687 -1 688 -1 689 -1 690 -1 691 -1 692 -1 693 -1 694 -1 695 -1 696 -1 697 -1 698 -1 699 -1 700 -1 701 -1 702 -1 703 -1 704 -1 705 -1 706 -1 707 -1 708 -1 709 -1 710 -1 711 -1 712 -1 713 -1 714 -1 715 -1 716 -1 717 -1 718 -1 719 -1 720 -1 721 -1 722 -1 723 -1 724 -1 725 -1 726 -1 727 -1 728 -1 729 -1 730 -1 731 -1 732 -1 733 -1 734 -1 735 -1 736 -1 737 -1 738 -1 739 -1 740 -1 741 -1 742 -1 743 -1 744 -1 745 -1 746 -1 747 -1 748 -1 749 -1 750 -1 751 -1 752 -1 753 -1 754 -1 755 -1 756 -1 757 -1 758 -1 759 -1 760 -1 761 -1 762 -1 763 -1 764 -1 765 -1 766 -1 767 -1 768 -1 769 -1 770 -1 771 -1 772 -1 773 -1 774 -1 775 -1 776 -1 777 -1 778 -1 779 -1 780 -1 781 -1 782 -1 783 -1 784 -1 785 -1 786 -1 787 -1 788 -1 789 -1 790 -1 791 -1 792 -1 793 -1 794 -1 795 -1 796 -1 797 -1 798 -1 799 -1 800 -1 801 -1 802 -1 803 -1 804 -1 805 -1 806 -1 807 -1 808 -1 809 -1 810 -1 811 -1 812 -1 813 -1 814 -1 815 -1 816 -1 817 -1 818 -1 819 -1 820 -1 821 -1 822 -1 823 -1 824 -1 825 -1 826 -1 827 -1 828 -1 829 -1 830 -1 831 -1 832 -1 833 -1 834 -1 835 -1 836 -1 837 -1 838 -1 839 -1 840 -1 841 -1 842 -1 843 -1 844 -1 845 -1 846 -1 847 -1 848 -1 849 -1 850 -1 851 -1 852 -1 853 -1 854 -1 855 -1 856 -1 857 -1 858 -1 859 -1 860 -1 861 -1 862 -1 863 -1 864 -1 865 -1 866 -1 867 -1 868 -1 869 -1 870 -1 871 -1 872 -1 873 -1 874 -1 875 -1 876 -1 877 -1 878 -1 879 -1 880 -1 881 -1 882 -1 883 -1 884 -1 885 -1 886 -1 887 -1 888 -1 889 -1 890 -1 891 -1 892 -1 893 -1 894 -1 895 -1 896 -1 897 -1 898 -1 899 -1 900 -1 901 -1 902 -1 903 -1 904 -1 905 -1 906 -1 907 -1 908 -1 909 -1 910 -1 911 -1 912 -1 913 -1 914 -1 915 -1 916 -1 917 -1 918 -1 919 -1 920 -1 921 -1 922 -1 923 -1 924 -1 925 -1 926 -1 927 -1 928 -1 929 -1 930 -1 931 -1 932 -1 933 -1 934 -1 935 -1 936 -1 937 -1 938 -1 939 -1 940 -1 941 -1 942 -1 943 -1 944 -1 945 -1 946 -1 947 -1 948 -1 949 -1 950 -1 951 -1 952 -1 953 -1 954 -1 955 -1 956 -1 957 -1 958 -1 959 -1 960 -1 961 -1 962 -1 963 -1 964 -1 965 -1 966 -1 967 -1 968 -1 969 -1 970 -1 971 -1 972 -1 973 -1 974 -1 975 -1 976 -1 977 -1 978 -1 979 -1 980 -1 981 -1 982 -1 983 -1 984 -1 985 -1 986 -1 987 -1 988 -1 989 -1 990 -1 991 -1 992 -1 993 -1 994 -1 995 -1 996 -1 997 -1 998 -1 999 -1 1000 -1 1001 -1 1002 -1 1003 -1 1004 -1 1005 -1 1006 -1 1007 -1 1008 -1 1009 -1 1010 -1 1011 -1 1012 -1 1013 -1 1014 -1 1015 -1 1016 -1 1017 -1 1018 -1 1019 -1 1020 -1 1021 -1 1022 -1 1023 -1 1024 -1 1025 -1 1026 -1 1027 -1 1028 -1 1029 -1 1030 -1 1031 -1 1032 -1 1033 -1 1034 -1 1035 -1 1036 -1 1037 -1 1038 -1 1039 -1 1040 -1 1041 -1 1042 -1 1043 -1 1044 -1 1045 -1 1046 -1 1047 -1 1048 -1 1049 -1 1050 -1 1051 -1 1052 -1 1053 -1 1054 -1 1055 -1 1056 -1 1057 -1 1058 -1 1059 -1 1060 -1 1061 -1 1062 -1 1063 -1 1064 -1 1065 -1 1066 -1 1067 -1 1068 -1 1069 -1 1070 -1 1071 -1 1072 -1 1073 -1 1074 -1 1075 -1 1076 -1 1077 -1 1078 -1 1079 -1 1080 -1 1081 -1 1082 -1 1083 -1 1084 -1 1085 -1 1086 -1 1087 -1 1088 -1 1089 -1 1090 -1 1091 -1 1092 -1 1093 -1 1094 -1 1095 -1 1096 -1 1097 -1 1098 -1 1099 -1 1100 -1 1101 -1 1102 -1 1103 -1 1104 -1 1105 -1 1106 -1 1107 -1 1108 -1 1109 -1 1110 -1 1111 -1 1112 -1 1113 -1 1114 -1 1115 -1 1116 -1 1117 -1 1118 -1 1119 -1 1120 -1 1121 -1 1122 -1 1123 -1 1124 -1 1125 -1 1126 -1 1127 -1 1128 -1 1129 -1 1130 -1 1131 -1 1132 -1 1133 -1 1134 -1 1135 -1 1136 -1 1137 -1 1138 -1 1139 -1 1140 -1 1141 -1 1142 -1 1143 -1 1144 -1 1145 -1 1146 -1 1147 -1 1148 -1 1149 -1 1150 -1 1151 -1 1152 -1 1153 -1 1154 -1 1155 -1 1156 -1 1157 -1 1158 -1 1159 -1 1160 -1 1161 -1 1162 -1 1163 -1 1164 -1 1165 -1 1166 -1 1167 -1 1168 -1 1169 -1 1170 -1 1171 -1 1172 -1 1173 -1 1174 -1 1175 -1 1176 -1 1177 -1 1178 -1 1179 -1 1180 -1 1181 -1 1182 -1 1183 -1 1184 -1 1185 -1 1186 -1 1187 -1 1188 -1 1189 -1 1190 -1 1191 -1 1192 -1 1193 -1 1194 -1 1195 -1 1196 -1 1197 -1 1198 -1 1199 -1 1200 -1 1201 -1 1202 -1 1203 -1 1204 -1 1205 -1 1206 -1 1207 -1 1208 -1 1209 -1 1210 -1 1211 -1 1212 -1 1213 -1 1214 -1 1215 -1 1216 -1 1217 -1 1218 -1 1219 -1 1220 -1 1221 -1 1222 -1 1223 -1 1224 -1 1225 -1 1226 -1 1227 -1 1228 -1 1229 -1 1230 -1 1231 -1 1232 -1 1233 -1 1234 -1 1235 -1 1236 -1 1237 -1 1238 -1 1239 -1 1240 -1 1241 -1 1242 -1 1243 -1 1244 -1 1245 -1 1246 -1 1247 -1 1248 -1 1249 -1 1250 -1 1251 -1 1252 -1 1253 -1 1254 -1 1255 -1 1256 -1 1257 -1 1258 -1 1259 -1 1260 -1 1261 -1 1262 -1 1263 -1 1264 -1 1265 -1 1266 -1 1267 -1 1268 -1 1269 -1 1270 -1 1271 -1 1272 -1 1273 -1 1274 -1 1275 -1 1276 -1 1277 -1 1278 -1 1279 -1 1280 -1 1281 -1 1282 -1 1283 -1 1284 -1 1285 -1 1286 -1 1287 -1 1288 -1 1289 -1 1290 -1 1291 -1 1292 -1 1293 -1 1294 -1 1295 -1 1296 -1 1297 -1 1298 -1 1299 -1 1300 -1 1301 -1 1302 -1 1303 -1 1304 -1 1305 -1 1306 -1 1307 -1 1308 -1 1309 -1 1310 -1 1311 -1 1312 -1 1313 -1 1314 -1 1315 -1 1316 -1 1317 -1 1318 -1 1319 -1 1320 -1 1321 -1 1322 -1 1323 -1 1324 -1 1325 -1 1326 -1 1327 -1 1328 -1 1329 -1 1330 -1 1331 -1 1332 -1 1333 -1 1334 -1 1335 -1 1336 -1 1337 -1 1338 -1 1339 -1 1340 -1 1341 -1 1342 -1 1343 -1 1344 -1 1345 -1 1346 -1 1347 -1 1348 -1 1349 -1 1350 -1 1351 -1 1352 -1 1353 -1 1354 -1 1355 -1 1356 -1 1357 -1 1358 -1 1359 -1 1360 -1 1361 -1 1362 -1 1363 -1 1364 -1 1365 -1 1366 -1 1367 -1 1368 -1 1369 -1 1370 -1 1371 -1 1372 -1 1373 -1 1374 -1 1375 -1 1376 -1 1377 -1 1378 -1 1379 -1 1380 -1 1381 -1 1382 -1 1383 -1 1384 -1 1385 -1 1386 -1 1387 -1 1388 -1 1389 -1 1390 -1 1391 -1 1392 -1 1393 -1 1394 -1 1395 -1 1396 -1 1397 -1 1398 -1 1399 -1 1400 -1 1401 -1 1402 -1 1403 -1 1404 -1 1405 -1 1406 -1 1407 -1 1408 -1 1409 -1 1410 -1 1411 -1 1412 -1 1413 -1 1414 -1 1415 -1 1416 -1 1417 -1 1418 -1 1419 -1 1420 -1 1421 -1 1422 -1 1423 -1 1424 -1 1425 -1 1426 -1 1427 -1 1428 -1 1429 -1 1430 -1 1431 -1 1432 -1 1433 -1 1434 -1 1435 -1 1436 -1 1437 -1 1438 -1 1439 -1 1440 -1 1441 -1 1442 -1 1443 -1 1444 -1 1445 -1 1446 -1 1447 -1 1448 -1 1449 -1 1450 -1 1451 -1 1452 -1 1453 -1 1454 -1 1455 -1 1456 -1 1457 -1 1458 -1 1459 -1 1460 -1 1461 -1 1462 -1 1463 -1 1464 -1 1465 -1 1466 -1 1467 -1 1468 -1 1469 -1 1470 -1 1471 -1 1472 -1 1473 -1 1474 -1 1475 -1 1476 -1 1477 -1 1478 -1 1479 -1 1480 -1 1481 -1 1482 -1 1483 -1 1484 -1 1485 -1 1486 -1 1487 -1 1488 -1 1489 -1 1490 -1 1491 -1 1492 -1 1493 -1 1494 -1 1495 -1 1496 -1 1497 -1 1498 -1 1499 -1 1500 -1 1501 -1 1502 -1 1503 -1 1504 -1 1505 -1 1506 -1 1507 -1 1508 -1 1509 -1 1510 -1 1511 -1 1512 -1 1513 -1 1514 -1 1515 -1 1516 -1 1517 -1 1518 -1 1519 -1 1520 -1 1521 -1 1522 -1 1523 -1 1524 -1 1525 -1 1526 -1 1527 -1 1528 -1 1529 -1 1530 -1 1531 -1 1532 -1 1533 -1 1534 -1 1535 -1 1536 -1 1537 -1 1538 -1 1539 -1 1540 -1 1541 -1 1542 -1 1543 -1 1544 -1 1545 -1 1546 -1 1547 -1 1548 -1 1549 -1 1550 -1 1551 -1 1552 -1 1553 -1 1554 -1 1555 -1 1556 -1 1557 -1 1558 -1 1559 -1 1560 -1 1561 -1 1562 -1 1563 -1 1564 -1 1565 -1 1566 -1 1567 -1 1568 -1 1569 -1 1570 -1 1571 -1 1572 -1 1573 -1 1574 -1 1575 -1 1576 -1 1577 -1 1578 -1 1579 -1 1580 -1 1581 -1 1582 -1 1583 -1 1584 -1 1585 -1 1586 -1 1587 -1 1588 -1 1589 -1 1590 -1 1591 -1 1592 -1 1593 -1 1594 -1 1595 -1 1596 -1 1597 -1 1598 -1 1599 -1 1600 -1 1601 -1 1602 -1 1603 -1 1604 -1 1605 -1 1606 -1 1607 -1 1608 -1 1609 -1 1610 -1 1611 -1 1612 -1 1613 -1 1614 -1 1615 -1 1616 -1 1617 -1 1618 -1 1619 -1 1620 -1 1621 -1 1622 -1 1623 -1 1624 -1 1625 -1 1626 -1 1627 -1 1628 -1 1629 -1 1630 -1 1631 -1 1632 -1 1633 -1 1634 -1 1635 -1 1636 -1 1637 -1 1638 -1 1639 -1 1640 -1 1641 -1 1642 -1 1643 -1 1644 -1 1645 -1 1646 -1 1647 -1 1648 -1 1649 -1 1650 -1 1651 -1 1652 -1 1653 -1 1654 -1 1655 -1 1656 -1 1657 -1 1658 -1 1659 -1 1660 -1 1661 -1 1662 -1 1663 -1 1664 -1 1665 -1 1666 -1 1667 -1 1668 -1 1669 -1 1670 -1 1671 -1 1672 -1 1673 -1 1674 -1 1675 -1 1676 -1 1677 -1 1678 -1 1679 -1 1680 -1 1681 -1 1682 -1 1683 -1 1684 -1 1685 -1 1686 -1 1687 -1 1688 -1 1689 -1 1690 -1 1691 -1 1692 -1 1693 -1 1694 -1 1695 -1 1696 -1 1697 -1 1698 -1 1699 -1 1700 -1 1701 -1 1702 -1 1703 -1 1704 -1 1705 -1 1706 -1 1707 -1 1708 -1 1709 -1 1710 -1 1711 -1 1712 -1 1713 -1 1714 -1 1715 -1 1716 -1 1717 -1 1718 -1 1719 -1 1720 -1 1721 -1 1722 -1 1723 -1 1724 -1 1725 -1 1726 -1 1727 -1 1728 -1 1729 -1 1730 -1 1731 -1 1732 -1 1733 -1 1734 -1 1735 -1 1736 -1 1737 -1 1738 -1 1739 -1 1740 -1 1741 -1 1742 -1 1743 -1 1744 -1 1745 -1 1746 -1 1747 -1 1748 -1 1749 -1 1750 -1 1751 -1 1752 -1 1753 -1 1754 -1 1755 -1 1756 -1 1757 -1 1758 -1 1759 -1 1760 -1 1761 -1 1762 -1 1763 -1 1764 -1 1765 -1 1766 -1 1767 -1 1768 -1 1769 -1 1770 -1 1771 -1 1772 -1 1773 -1 1774 -1 1775 -1 1776 -1 1777 -1 1778 -1 1779 -1 1780 -1 1781 -1 1782 -1 1783 -1 1784 -1 1785 -1 1786 -1 1787 -1 1788 -1 1789 -1 1790 -1 1791 -1 1792 -1 1793 -1 1794 -1 1795 -1 1796 -1 1797 -1 1798 -1 1799 -1 1800 -1 1801 -1 1802 -1 1803 -1 1804 -1 1805 -1 1806 -1 1807 -1 1808 -1 1809 -1 1810 -1 1811 -1 1812 -1 1813 -1 1814 -1 1815 -1 1816 -1 1817 -1 1818 -1 1819 -1 1820 -1 1821 -1 1822 -1 1823 -1 1824 -1 1825 -1 1826 -1 1827 -1 1828 -1 1829 -1 1830 -1 1831 -1 1832 -1 1833 -1 1834 -1 1835 -1 1836 -1 1837 -1 1838 -1 1839 -1 1840 -1 1841 -1 1842 -1 1843 -1 1844 -1 1845 -1 1846 -1 1847 -1 1848 -1 1849 -1 1850 -1 1851 -1 1852 -1 1853 -1 1854 -1 1855 -1 1856 -1 1857 -1 1858 -1 1859 -1 1860 -1 1861 -1 1862 -1 1863 -1 1864 -1 1865 -1 1866 -1 1867 -1 1868 -1 1869 -1 1870 -1 1871 -1 1872 -1 1873 -1 1874 -1 1875 -1 1876 -1 1877 -1 1878 -1 1879 -1 1880 -1 1881 -1 1882 -1 1883 -1 1884 -1 1885 -1 1886 -1 1887 -1 1888 -1 1889 -1 1890 -1 1891 -1 1892 -1 1893 -1 1894 -1 1895 -1 1896 -1 1897 -1 1898 -1 1899 -1 1900 -1 1901 -1 1902 -1 1903 -1 1904 -1 1905 -1 1906 -1 1907 -1 1908 -1 1909 -1 1910 -1 1911 -1 1912 -1 1913 -1 1914 -1 1915 -1 1916 -1 1917 -1 1918 -1 1919 -1 1920 -1 1921 -1 1922 -1 1923 -1 1924 -1 1925 -1 1926 -1 1927 -1 1928 -1 1929 -1 1930 -1 1931 -1 1932 -1 1933 -1 1934 -1 1935 -1 1936 -1 1937 -1 1938 -1 1939 -1 1940 -1 1941 -1 1942 -1 1943 -1 1944 -1 1945 -1 1946 -1 1947 -1 1948 -1 1949 -1 1950 -1 1951 -1 1952 -1 1953 -1 1954 -1 1955 -1 1956 -1 1957 -1 1958 -1 1959 -1 1960 -1 1961 -1 1962 -1 1963 -1 1964 -1 1965 -1 1966 -1 1967 -1 1968 -1 1969 -1 1970 -1 1971 -1 1972 -1 1973 -1 1974 -1 1975 -1 1976 -1 1977 -1 1978 -1 1979 -1 1980 -1 1981 -1 1982 -1 1983 -1 1984 -1 1985 -1 1986 -1 1987 -1 1988 -1 1989 -1 1990 -1 1991 -1 1992 -1 1993 -1 1994 -1 1995 -1 1996 -1 1997 -1 1998 -1 1999 -1 2000 -1 2001 -1 2002 -1 2003 -1 2004 -1 2005 -1 2006 -1 2007 -1 2008 -1 2009 -1 2010 -1 2011 -1 2012 -1 2013 -1 2014 -1 2015 -1 2016 -1 2017 -1 2018 -1 2019 -1 2020 -1 2021 -1 2022 -1 2023 -1 2024 -1 2025 -1 2026 -1 2027 -1 2028 -1 2029 -1 2030 -1 2031 -1 2032 -1 2033 -1 2034 -1 2035 -1 2036 -1 2037 -1 2038 -1 2039 -1 2040 -1 2041 -1 2042 -1 2043 -1 2044 -1 2045 -1 2046 -1 2047 -1 2048 -1 2049 -1 2050 -1 2051 -1 2052 -1 2053 -1 2054 -1 2055 -1 2056 -1 2057 -1 2058 -1 2059 -1 2060 -1 2061 -1 2062 -1 2063 -1 2064 -1 2065 -1 2066 -1 2067 -1 2068 -1 2069 -1 2070 -1 2071 -1 2072 -1 2073 -1 2074 -1 2075 -1 2076 -1 2077 -1 2078 -1 2079 -1 2080 -1 2081 -1 2082 -1 2083 -1 2084 -1 2085 -1 2086 -1 2087 -1 2088 -1 2089 -1 2090 -1 2091 -1 2092 -1 2093 -1 2094 -1 2095 -1 2096 -1 2097 -1 2098 -1 2099 -1 2100 -1 2101 -1 2102 -1 2103 -1 2104 -1 2105 -1 2106 -1 2107 -1 2108 -1 2109 -1 2110 -1 2111 -1 2112 -1 2113 -1 2114 -1 2115 -1 2116 -1 2117 -1 2118 -1 2119 -1 2120 -1 2121 -1 2122 -1 2123 -1 2124 -1 2125 -1 2126 -1 2127 -1 2128 -1 2129 -1 2130 -1 2131 -1 2132 -1 2133 -1 2134 -1 2135 -1 2136 -1 2137 -1 2138 -1 2139 -1 2140 -1 2141 -1 2142 -1 2143 -1 2144 -1 2145 -1 2146 -1 2147 -1 2148 -1 2149 -1 2150 -1 2151 -1 2152 -1 2153 -1 2154 -1 2155 -1 2156 -1 2157 -1 2158 -1 2159 -1 2160 -1 2161 -1 2162 -1 2163 -1 2164 -1 2165 -1 2166 -1 2167 -1 2168 -1 2169 -1 2170 -1 2171 -1 2172 -1 2173 -1 2174 -1 2175 -1 2176 -1 2177 -1 2178 -1 2179 -1 2180 -1 2181 -1 2182 -1 2183 -1 2184 -1 2185 -1 2186 -1 2187 -1 2188 -1 2189 -1 2190 -1 2191 -1 2192 -1 2193 -1 2194 -1 2195 -1 2196 -1 2197 -1 2198 -1 2199 -1 2200 -1 2201 -1 2202 -1 2203 -1 2204 -1 2205 -1 2206 -1 2207 -1 2208 -1 2209 -1 2210 -1 2211 -1 2212 -1 2213 -1 2214 -1 2215 -1 2216 -1 2217 -1 2218 -1 2219 -1 2220 -1 2221 -1 2222 -1 2223 -1 2224 -1 2225 -1 2226 -1 2227 -1 2228 -1 2229 -1 2230 -1 2231 -1 2232 -1 2233 -1 2234 -1 2235 -1 2236 -1 2237 -1 2238 -1 2239 -1 2240 -1 2241 -1 2242 -1 2243 -1 2244 -1 2245 -1 2246 -1 2247 -1 2248 -1 2249 -1 2250 -1 2251 -1 2252 -1 2253 -1 2254 -1 2255 -1 2256 -1 2257 -1 2258 -1 2259 -1 2260 -1 2261 -1 2262 -1 2263 -1 2264 -1 2265 -1 2266 -1 2267 -1 2268 -1 2269 -1 2270 -1 2271 -1 2272 -1 2273 -1 2274 -1 2275 -1 2276 -1 2277 -1 2278 -1 2279 -1 2280 -1 2281 -1 2282 -1 2283 -1 2284 -1 2285 -1 2286 -1 2287 -1 2288 -1 2289 -1 2290 -1 2291 -1 2292 -1 2293 -1 2294 -1 2295 -1 2296 -1 2297 -1 2298 -1 2299 -1 2300 -1 2301 -1 2302 -1 2303 -1 2304 -1 2305 -1 2306 -1 2307 -1 2308 -1 2309 -1 2310 -1 2311 -1 2312 -1 2313 -1 2314 -1 2315 -1 2316 -1 2317 -1 2318 -1 2319 -1 2320 -1 2321 -1 2322 -1 2323 -1 2324 -1 2325 -1 2326 -1 2327 -1 2328 -1 2329 -1 2330 -1 2331 -1 2332 -1 2333 -1 2334 -1 2335 -1 2336 -1 2337 -1 2338 -1 2339 -1 2340 -1 2341 -1 2342 -1 2343 -1 2344 -1 2345 -1 2346 -1 2347 -1 2348 -1 2349 -1 2350 -1 2351 -1 2352 -1 2353 -1 2354 -1 2355 -1 2356 -1 2357 -1 2358 -1 2359 -1 2360 -1 2361 -1 2362 -1 2363 -1 2364 -1 2365 -1 2366 -1 2367 -1 2368 -1 2369 -1 2370 -1 2371 -1 2372 -1 2373 -1 2374 -1 2375 -1 2376 -1 2377 -1 2378 -1 2379 -1 2380 -1 2381 -1 2382 -1 2383 -1 2384 -1 2385 -1 2386 -1 2387 -1 2388 -1 2389 -1 2390 -1 2391 -1 2392 -1 2393 -1 2394 -1 2395 -1 2396 -1 2397 -1 2398 -1 2399 -1 2400 -1 2401 -1 2402 -1 2403 -1 2404 -1 2405 -1 2406 -1 2407 -1 2408 -1 2409 -1 2410 -1 2411 -1 2412 -1 2413 -1 2414 -1 2415 -1 2416 -1 2417 -1 2418 -1 2419 -1 2420 -1 2421 -1 2422 -1 2423 -1 2424 -1 2425 -1 2426 -1 2427 -1 2428 -1 2429 -1 2430 -1 2431 -1 2432 -1 2433 -1 2434 -1 2435 -1 2436 -1 2437 -1 2438 -1 2439 -1 2440 -1 2441 -1 2442 -1 2443 -1 2444 -1 2445 -1 2446 -1 2447 -1 2448 -1 2449 -1 2450 -1 2451 -1 2452 -1 2453 -1 2454 -1 2455 -1 2456 -1 2457 -1 2458 -1 2459 -1 2460 -1 2461 -1 2462 -1 2463 -1 2464 -1 2465 -1 2466 -1 2467 -1 2468 -1 2469 -1 2470 -1 2471 -1 2472 -1 2473 -1 2474 -1 2475 -1 2476 -1 2477 -1 2478 -1 2479 -1 2480 -1 2481 -1 2482 -1 2483 -1 2484 -1 2485 -1 2486 -1 2487 -1 2488 -1 2489 -1 2490 -1 2491 -1 2492 -1 2493 -1 2494 -1 2495 -1 2496 -1 2497 -1 2498 -1 2499 -1 2500 -1 2501 -1 2502 -1 2503 -1 2504 -1 2505 -1 2506 -1 2507 -1 2508 -1 2509 -1 2510 -1 2511 -1 2512 -1 2513 -1 2514 -1 2515 -1 2516 -1 2517 -1 2518 -1 2519 -1 2520 -1 2521 -1 2522 -1 2523 -1 2524 -1 2525 -1 2526 -1 2527 -1 2528 -1 2529 -1 2530 -1 2531 -1 2532 -1 2533 -1 2534 -1 2535 -1 2536 -1 2537 -1 2538 -1 2539 -1 2540 -1 2541 -1 2542 -1 2543 -1 2544 -1 2545 -1 2546 -1 2547 -1 2548 -1 2549 -1 2550 -1 2551 -1 2552 -1 2553 -1 2554 -1 2555 -1 2556 -1 2557 -1 2558 -1 2559 -1 2560 -1 2561 -1 2562 -1 2563 -1 2564 -1 2565 -1 2566 -1 2567 -1 2568 -1 2569 -1 2570 -1 2571 -1 2572 -1 2573 -1 2574 -1 2575 -1 2576 -1 2577 -1 2578 -1 2579 -1 2580 -1 2581 -1 2582 -1 2583 -1 2584 -1 2585 -1 2586 -1 2587 -1 2588 -1 2589 -1 2590 -1 2591 -1 2592 -1 2593 -1 2594 -1 2595 -1 2596 -1 2597 -1 2598 -1 2599 -1 2600 -1 2601 -1 2602 -1 2603 -1 2604 -1 2605 -1 2606 -1 2607 -1 2608 -1 2609 -1 2610 -1 2611 -1 2612 -1 2613 -1 2614 -1 2615 -1 2616 -1 2617 -1 2618 -1 2619 -1 2620 -1 2621 -1 2622 -1 2623 -1 2624 -1 2625 -1 2626 -1 2627 -1 2628 -1 2629 -1 2630 -1 2631 -1 2632 -1 2633 -1 2634 -1 2635 -1 2636 -1 2637 -1 2638 -1 2639 -1 2640 -1 2641 -1 2642 -1 2643 -1 2644 -1 2645 -1 2646 -1 2647 -1 2648 -1 2649 -1 2650 -1 2651 -1 2652 -1 2653 -1 2654 -1 2655 -1 2656 -1 2657 -1 2658 -1 2659 -1 2660 -1 2661 -1 2662 -1 2663 -1 2664 -1 2665 -1 2666 -1 2667 -1 2668 -1 2669 -1 2670 -1 2671 -1 2672 -1 2673 -1 2674 -1 2675 -1 2676 -1 2677 -1 2678 -1 2679 -1 2680 -1 2681 -1 2682 -1 2683 -1 2684 -1 2685 -1 2686 -1 2687 -1 2688 -1 2689 -1 2690 -1 2691 -1 2692 -1 2693 -1 2694 -1 2695 -1 2696 -1 2697 -1 2698 -1 2699 -1 2700 -1 2701 -1 2702 -1 2703 -1 2704 -1 2705 -1 2706 -1 2707 -1 2708 -1 2709 -1 2710 -1 2711 -1 2712 -1 2713 -1 2714 -1 2715 -1 2716 -1 2717 -1 2718 -1 2719 -1 2720 -1 2721 -1 2722 -1 2723 -1 2724 -1 2725 -1 2726 -1 2727 -1 2728 -1 2729 -1 2730 -1 2731 -1 2732 -1 2733 -1 2734 -1 2735 -1 2736 -1 2737 -1 2738 -1 2739 -1 2740 -1 2741 -1 2742 -1 2743 -1 2744 -1 2745 -1 2746 -1 2747 -1 2748 -1 2749 -1 2750 -1 2751 -1 2752 -1 2753 -1 2754 -1 2755 -1 2756 -1 2757 -1 2758 -1 2759 -1 2760 -1 2761 -1 2762 -1 2763 -1 2764 -1 2765 -1 2766 -1 2767 -1 2768 -1 2769 -1 2770 -1 2771 -1 2772 -1 2773 -1 2774 -1 2775 -1 2776 -1 2777 -1 2778 -1 2779 -1 2780 -1 2781 -1 2782 -1 2783 -1 2784 -1 2785 -1 2786 -1 2787 -1 2788 -1 2789 -1 2790 -1 2791 -1 2792 -1 2793 -1 2794 -1 2795 -1 2796 -1 2797 -1 2798 -1 2799 -1 2800 -1 2801 -1 2802 -1 2803 -1 2804 -1 2805 -1 2806 -1 2807 -1 2808 -1 2809 -1 2810 -1 2811 -1 2812 -1 2813 -1 2814 -1 2815 -1 2816 -1 2817 -1 2818 -1 2819 -1 2820 -1 2821 -1 2822 -1 2823 -1 2824 -1 2825 -1 2826 -1 2827 -1 2828 -1 2829 -1 2830 -1 2831 -1 2832 -1 2833 -1 2834 -1 2835 -1 2836 -1 2837 -1 2838 -1 2839 -1 2840 -1 2841 -1 2842 -1 2843 -1 2844 -1 2845 -1 2846 -1 2847 -1 2848 -1 2849 -1 2850 -1 2851 -1 2852 -1 2853 -1 2854 -1 2855 -1 2856 -1 2857 -1 2858 -1 2859 -1 2860 -1 2861 -1 2862 -1 2863 -1 2864 -1 2865 -1 2866 -1 2867 -1 2868 -1 2869 -1 2870 -1 2871 -1 2872 -1 2873 -1 2874 -1 2875 -1 2876 -1 2877 -1 2878 -1 2879 -1 2880 -1 2881 -1 2882 -1 2883 -1 2884 -1 2885 -1 2886 -1 2887 -1 2888 -1 2889 -1 2890 -1 2891 -1 2892 -1 2893 -1 2894 -1 2895 -1 2896 -1 2897 -1 2898 -1 2899 -1 2900 -1 2901 -1 2902 -1 2903 -1 2904 -1 2905 -1 2906 -1 2907 -1 2908 -1 2909 -1 2910 -1 2911 -1 2912 -1 2913 -1 2914 -1 2915 -1 2916 -1 2917 -1 2918 -1 2919 -1 2920 -1 2921 -1 2922 -1 2923 -1 2924 -1 2925 -1 2926 -1 2927 -1 2928 -1 2929 -1 2930 -1 2931 -1 2932 -1 2933 -1 2934 -1 2935 -1 2936 -1 2937 -1 2938 -1 2939 -1 2940 -1 2941 -1 2942 -1 2943 -1 2944 -1 2945 -1 2946 -1 2947 -1 2948 -1 2949 -1 2950 -1 2951 -1 2952 -1 2953 -1 2954 -1 2955 -1 2956 -1 2957 -1 2958 -1 2959 -1 2960 -1 2961 -1 2962 -1 2963 -1 2964 -1 2965 -1 2966 -1 2967 -1 2968 -1 2969 -1 2970 -1 2971 -1 2972 -1 2973 -1 2974 -1 2975 -1 2976 -1 2977 -1 2978 -1 2979 -1 2980 -1 2981 -1 2982 -1 2983 -1 2984 -1 2985 -1 2986 -1 2987 -1 2988 -1 2989 -1 2990 -1 2991 -1 2992 -1 2993 -1 2994 -1 2995 -1 2996 -1 2997 -1 2998 -1 2999 -1 3000 -1 3001 -1 3002 -1 3003 -1 3004 -1 3005 -1 3006 -1 3007 -1 3008 -1 3009 -1 3010 -1 3011 -1 3012 -1 3013 -1 3014 -1 3015 -1 3016 -1 3017 -1 3018 -1 3019 -1 3020 -1 3021 -1 3022 -1 3023 -1 3024 -1 3025 -1 3026 -1 3027 -1 3028 -1 3029 -1 3030 -1 3031 -1 3032 -1 3033 -1 3034 -1 3035 -1 3036 -1 3037 -1 3038 -1 3039 -1 3040 -1 3041 -1 3042 -1 3043 -1 3044 -1 3045 -1 3046 -1 3047 -1 3048 -1 3049 -1 3050 -1 3051 -1 3052 -1 3053 -1 3054 -1 3055 -1 3056 -1 3057 -1 3058 -1 3059 -1 3060 -1 3061 -1 3062 -1 3063 -1 3064 -1 3065 -1 3066 -1 3067 -1 3068 -1 3069 -1 3070 -1 3071 -1 3072 -1 3073 -1 3074 -1 3075 -1 3076 -1 3077 -1 3078 -1 3079 -1 3080 -1 3081 -1 3082 -1 3083 -1 3084 -1 3085 -1 3086 -1 3087 -1 3088 -1 3089 -1 3090 -1 3091 -1 3092 -1 3093 -1 3094 -1 3095 -1 3096 -1 3097 -1 3098 -1 3099 -1 3100 -1 3101 -1 3102 -1 3103 -1 3104 -1 3105 -1 3106 -1 3107 -1 3108 -1 3109 -1 3110 -1 3111 -1 3112 -1 3113 -1 3114 -1 3115 -1 3116 -1 3117 -1 3118 -1 3119 -1 3120 -1 3121 -1 3122 -1 3123 -1 3124 -1 3125 -1 3126 -1 3127 -1 3128 -1 3129 -1 3130 -1 3131 -1 3132 -1 3133 -1 3134 -1 3135 -1 3136 -1 3137 -1 3138 -1 3139 -1 3140 -1 3141 -1 3142 -1 3143 -1 3144 -1 3145 -1 3146 -1 3147 -1 3148 -1 3149 -1 3150 -1 3151 -1 3152 -1 3153 -1 3154 -1 3155 -1 3156 -1 3157 -1 3158 -1 3159 -1 3160 -1 3161 -1 3162 -1 3163 -1 3164 -1 3165 -1 3166 -1 3167 -1 3168 -1 3169 -1 3170 -1 3171 -1 3172 -1 3173 -1 3174 -1 3175 -1 3176 -1 3177 -1 3178 -1 3179 -1 3180 -1 3181 -1 3182 -1 3183 -1 3184 -1 3185 -1 3186 -1 3187 -1 3188 -1 3189 -1 3190 -1 3191 -1 3192 -1 3193 -1 3194 -1 3195 -1 3196 -1 3197 -1 3198 -1 3199 -1 3200 -1 3201 -1 3202 -1 3203 -1 3204 -1 3205 -1 3206 -1 3207 -1 3208 -1 3209 -1 3210 -1 3211 -1 3212 -1 3213 -1 3214 -1 3215 -1 3216 -1 3217 -1 3218 -1 3219 -1 3220 -1 3221 -1 3222 -1 3223 -1 3224 -1 3225 -1 3226 -1 3227 -1 3228 -1 3229 -1 3230 -1 3231 -1 3232 -1 3233 -1 3234 -1 3235 -1 3236 -1 3237 -1 3238 -1 3239 -1 3240 -1 3241 -1 3242 -1 3243 -1 3244 -1 3245 -1 3246 -1 3247 -1 3248 -1 3249 -1 3250 -1 3251 -1 3252 -1 3253 -1 3254 -1 3255 -1 3256 -1 3257 -1 3258 -1 3259 -1 3260 -1 3261 -1 3262 -1 3263 -1 3264 -1 3265 -1 3266 -1 3267 -1 3268 -1 3269 -1 3270 -1 3271 -1 3272 -1 3273 -1 3274 -1 3275 -1 3276 -1 3277 -1 3278 -1 3279 -1 3280 -1 3281 -1 3282 -1 3283 -1 3284 -1 3285 -1 3286 -1 3287 -1 3288 -1 3289 -1 3290 -1 3291 -1 3292 -1 3293 -1 3294 -1 3295 -1 3296 -1 3297 -1 3298 -1 3299 -1 3300 -1 3301 -1 3302 -1 3303 -1 3304 -1 3305 -1 3306 -1 3307 -1 3308 -1 3309 -1 3310 -1 3311 -1 3312 -1 3313 -1 3314 -1 3315 -1 3316 -1 3317 -1 3318 -1 3319 -1 3320 -1 3321 -1 3322 -1 3323 -1 3324 -1 3325 -1 3326 -1 3327 -1 3328 -1 3329 -1 3330 -1 3331 -1 3332 -1 3333 -1 3334 -1 3335 -1 3336 -1 3337 -1 3338 -1 3339 -1 3340 -1 3341 -1 3342 -1 3343 -1 3344 -1 3345 -1 3346 -1 3347 -1 3348 -1 3349 -1 3350 -1 3351 -1 3352 -1 3353 -1 3354 -1 3355 -1 3356 -1 3357 -1 3358 -1 3359 -1 3360 -1 3361 -1 3362 -1 3363 -1 3364 -1 3365 -1 3366 -1 3367 -1 3368 -1 3369 -1 3370 -1 3371 -1 3372 -1 3373 -1 3374 -1 3375 -1 3376 -1 3377 -1 3378 -1 3379 -1 3380 -1 3381 -1 3382 -1 3383 -1 3384 -1 3385 -1 3386 -1 3387 -1 3388 -1 3389 -1 3390 -1 3391 -1 3392 -1 3393 -1 3394 -1 3395 -1 3396 -1 3397 -1 3398 -1 3399 -1 3400 -1 3401 -1 3402 -1 3403 -1 3404 -1 3405 -1 3406 -1 3407 -1 3408 -1 3409 -1 3410 -1 3411 -1 3412 -1 3413 -1 3414 -1 3415 -1 3416 -1 3417 -1 3418 -1 3419 -1 3420 -1 3421 -1 3422 -1 3423 -1 3424 -1 3425 -1 3426 -1 3427 -1 3428 -1 3429 -1 3430 -1 3431 -1 3432 -1 3433 -1 3434 -1 3435 -1 3436 -1 3437 -1 3438 -1 3439 -1 3440 -1 3441 -1 3442 -1 3443 -1 3444 -1 3445 -1 3446 -1 3447 -1 3448 -1 3449 -1 3450 -1 3451 -1 3452 -1 3453 -1 3454 -1 3455 -1 3456 -1 3457 -1 3458 -1 3459 -1 3460 -1 3461 -1 3462 -1 3463 -1 3464 -1 3465 -1 3466 -1 3467 -1 3468 -1 3469 -1 3470 -1 3471 -1 3472 -1 3473 -1 3474 -1 3475 -1 3476 -1 3477 -1 3478 -1 3479 -1 3480 -1 3481 -1 3482 -1 3483 -1 3484 -1 3485 -1 3486 -1 3487 -1 3488 -1 3489 -1 3490 -1 3491 -1 3492 -1 3493 -1 3494 -1 3495 -1 3496 -1 3497 -1 3498 -1 3499 -1 3500 -1 3501 -1 3502 -1 3503 -1 3504 -1 3505 -1 3506 -1 3507 -1 3508 -1 3509 -1 3510 -1 3511 -1 3512 -1 3513 -1 3514 -1 3515 -1 3516 -1 3517 -1 3518 -1 3519 -1 3520 -1 3521 -1 3522 -1 3523 -1 3524 -1 3525 -1 3526 -1 3527 -1 3528 -1 3529 -1 3530 -1 3531 -1 3532 -1 3533 -1 3534 -1 3535 -1 3536 -1 3537 -1 3538 -1 3539 -1 3540 -1 3541 -1 3542 -1 3543 -1 3544 -1 3545 -1 3546 -1 3547 -1 3548 -1 3549 -1 3550 -1 3551 -1 3552 -1 3553 -1 3554 -1 3555 -1 3556 -1 3557 -1 3558 -1 3559 -1 3560 -1 3561 -1 3562 -1 3563 -1 3564 -1 3565 -1 3566 -1 3567 -1 3568 -1 3569 -1 3570 -1 3571 -1 3572 -1 3573 -1 3574 -1 3575 -1 3576 -1 3577 -1 3578 -1 3579 -1 3580 -1 3581 -1 3582 -1 3583 -1 3584 -1 3585 -1 3586 -1 3587 -1 3588 -1 3589 -1 3590 -1 3591 -1 3592 -1 3593 -1 3594 -1 3595 -1 3596 -1 3597 -1 3598 -1 3599 -1 3600 -1 3601 -1 3602 -1 3603 -1 3604 -1 3605 -1 3606 -1 3607 -1 3608 -1 3609 -1 3610 -1 3611 -1 3612 -1 3613 -1 3614 -1 3615 -1 3616 -1 3617 -1 3618 -1 3619 -1 3620 -1 3621 -1 3622 -1 3623 -1 3624 -1 3625 -1 3626 -1 3627 -1 3628 -1 3629 -1 3630 -1 3631 -1 3632 -1 3633 -1 3634 -1 3635 -1 3636 -1 3637 -1 3638 -1 3639 -1 3640 -1 3641 -1 3642 -1 3643 -1 3644 -1 3645 -1 3646 -1 3647 -1 3648 -1 3649 -1 3650 -1 3651 -1 3652 -1 3653 -1 3654 -1 3655 -1 3656 -1 3657 -1 3658 -1 3659 -1 3660 -1 3661 -1 3662 -1 3663 -1 3664 -1 3665 -1 3666 -1 3667 -1 3668 -1 3669 -1 3670 -1 3671 -1 3672 -1 3673 -1 3674 -1 3675 -1 3676 -1 3677 -1 3678 -1 3679 -1 3680 -1 3681 -1 3682 -1 3683 -1 3684 -1 3685 -1 3686 -1 3687 -1 3688 -1 3689 -1 3690 -1 3691 -1 3692 -1 3693 -1 3694 -1 3695 -1 3696 -1 3697 -1 3698 -1 3699 -1 3700 -1 3701 -1 3702 -1 3703 -1 3704 -1 3705 -1 3706 -1 3707 -1 3708 -1 3709 -1 3710 -1 3711 -1 3712 -1 3713 -1 3714 -1 3715 -1 3716 -1 3717 -1 3718 -1 3719 -1 3720 -1 3721 -1 3722 -1 3723 -1 3724 -1 3725 -1 3726 -1 3727 -1 3728 -1 3729 -1 3730 -1 3731 -1 3732 -1 3733 -1 3734 -1 3735 -1 3736 -1 3737 -1 3738 -1 3739 -1 3740 -1 3741 -1 3742 -1 3743 -1 3744 -1 3745 -1 3746 -1 3747 -1 3748 -1 3749 -1 3750 -1 3751 -1 3752 -1 3753 -1 3754 -1 3755 -1 3756 -1 3757 -1 3758 -1 3759 -1 3760 -1 3761 -1 3762 -1 3763 -1 3764 -1 3765 -1 3766 -1 3767 -1 3768 -1 3769 -1 3770 -1 3771 -1 3772 -1 3773 -1 3774 -1 3775 -1 3776 -1 3777 -1 3778 -1 3779 -1 3780 -1 3781 -1 3782 -1 3783 -1 3784 -1 3785 -1 3786 -1 3787 -1 3788 -1 3789 -1 3790 -1 3791 -1 3792 -1 3793 -1 3794 -1 3795 -1 3796 -1 3797 -1 3798 -1 3799 -1 3800 -1 3801 -1 3802 -1 3803 -1 3804 -1 3805 -1 3806 -1 3807 -1 3808 -1 3809 -1 3810 -1 3811 -1 3812 -1 3813 -1 3814 -1 3815 -1 3816 -1 3817 -1 3818 -1 3819 -1 3820 -1 3821 -1 3822 -1 3823 -1 3824 -1 3825 -1 3826 -1 3827 -1 3828 -1 3829 -1 3830 -1 3831 -1 3832 -1 3833 -1 3834 -1 3835 -1 3836 -1 3837 -1 3838 -1 3839 -1 3840 -1 3841 -1 3842 -1 3843 -1 3844 -1 3845 -1 3846 -1 3847 -1 3848 -1 3849 -1 3850 -1 3851 -1 3852 -1 3853 -1 3854 -1 3855 -1 3856 -1 3857 -1 3858 -1 3859 -1 3860 -1 3861 -1 3862 -1 3863 -1 3864 -1 3865 -1 3866 -1 3867 -1 3868 -1 3869 -1 3870 -1 3871 -1 3872 -1 3873 -1 3874 -1 3875 -1 3876 -1 3877 -1 3878 -1 3879 -1 3880 -1 3881 -1 3882 -1 3883 -1 3884 -1 3885 -1 3886 -1 3887 -1 3888 -1 3889 -1 3890 -1 3891 -1 3892 -1 3893 -1 3894 -1 3895 -1 3896 -1 3897 -1 3898 -1 3899 -1 3900 -1 3901 -1 3902 -1 3903 -1 3904 -1 3905 -1 3906 -1 3907 -1 3908 -1 3909 -1 3910 -1 3911 -1 3912 -1 3913 -1 3914 -1 3915 -1 3916 -1 3917 -1 3918 -1 3919 -1 3920 -1 3921 -1 3922 -1 3923 -1 3924 -1 3925 -1 3926 -1 3927 -1 3928 -1 3929 -1 3930 -1 3931 -1 3932 -1 3933 -1 3934 -1 3935 -1 3936 -1 3937 -1 3938 -1 3939 -1 3940 -1 3941 -1 3942 -1 3943 -1 3944 -1 3945 -1 3946 -1 3947 -1 3948 -1 3949 -1 3950 -1 3951 -1 3952 -1 3953 -1 3954 -1 3955 -1 3956 -1 3957 -1 3958 -1 3959 -1 3960 -1 3961 -1 3962 -1 3963 -1 3964 -1 3965 -1 3966 -1 3967 -1 3968 -1 3969 -1 3970 -1 3971 -1 3972 -1 3973 -1 3974 -1 3975 -1 3976 -1 3977 -1 3978 -1 3979 -1 3980 -1 3981 -1 3982 -1 3983 -1 3984 -1 3985 -1 3986 -1 3987 -1 3988 -1 3989 -1 3990 -1 3991 -1 3992 -1 3993 -1 3994 -1 3995 -1 3996 -1 3997 -1 3998 -1 3999 -1 4000 -1 4001 -1 4002 -1 4003 -1 4004 -1 4005 -1 4006 -1 4007 -1 4008 -1 4009 -1 4010 -1 4011 -1 4012 -1 4013 -1 4014 -1 4015 -1 4016 -1 4017 -1 4018 -1 4019 -1 4020 -1 4021 -1 4022 -1 4023 -1 4024 -1 4025 -1 4026 -1 4027 -1 4028 -1 4029 -1 4030 -1 4031 -1 4032 -1 4033 -1 4034 -1 4035 -1 4036 -1 4037 -1 4038 -1 4039 -1 4040 -1 4041 -1 4042 -1 4043 -1 4044 -1 4045 -1 4046 -1 4047 -1 4048 -1 4049 -1 4050 -1 4051 -1 4052 -1 4053 -1 4054 -1 4055 -1 4056 -1 4057 -1 4058 -1 4059 -1 4060 -1 4061 -1 4062 -1 4063 -1 4064 -1 4065 -1 4066 -1 4067 -1 4068 -1 4069 -1 4070 -1 4071 -1 4072 -1 4073 -1 4074 -1 4075 -1 4076 -1 4077 -1 4078 -1 4079 -1 4080 -1 4081 -1 4082 -1 4083 -1 4084 -1 4085 -1 4086 -1 4087 -1 4088 -1 4089 -1 4090 -1 4091 -1 4092 -1 4093 -1 4094 -1 4095 -1 4096 -1 4097 -1 4098 -1 4099 -1 4100 -1 4101 -1 4102 -1 4103 -1 4104 -1 4105 -1 4106 -1 4107 -1 4108 -1 4109 -1 4110 -1 4111 -1 4112 -1 4113 -1 4114 -1 4115 -1 4116 -1 4117 -1 4118 -1 4119 -1 4120 -1 4121 -1 4122 -1 4123 -1 4124 -1 4125 -1 4126 -1 4127 -1 4128 -1 4129 -1 4130 -1 4131 -1 4132 -1 4133 -1 4134 -1 4135 -1 4136 -1 4137 -1 4138 -1 4139 -1 4140 -1 4141 -1 4142 -1 4143 -1 4144 -1 4145 -1 4146 -1 4147 -1 4148 -1 4149 -1 4150 -1 4151 -1 4152 -1 4153 -1 4154 -1 4155 -1 4156 -1 4157 -1 4158 -1 4159 -1 4160 -1 4161 -1 4162 -1 4163 -1 4164 -1 4165 -1 4166 -1 4167 -1 4168 -1 4169 -1 4170 -1 4171 -1 4172 -1 4173 -1 4174 -1 4175 -1 4176 -1 4177 -1 4178 -1 4179 -1 4180 -1 4181 -1 4182 -1 4183 -1 4184 -1 4185 -1 4186 -1 4187 -1 4188 -1 4189 -1 4190 -1 4191 -1 4192 -1 4193 -1 4194 -1 4195 -1 4196 -1 4197 -1 4198 -1 4199 -1 4200 -1 4201 -1 4202 -1 4203 -1 4204 -1 4205 -1 4206 -1 4207 -1 4208 -1 4209 -1 4210 -1 4211 -1 4212 -1 4213 -1 4214 -1 4215 -1 4216 -1 4217 -1 4218 -1 4219 -1 4220 -1 4221 -1 4222 -1 4223 -1 4224 -1 4225 -1 4226 -1 4227 -1 4228 -1 4229 -1 4230 -1 4231 -1 4232 -1 4233 -1 4234 -1 4235 -1 4236 -1 4237 -1 4238 -1 4239 -1 4240 -1 4241 -1 4242 -1 4243 -1 4244 -1 4245 -1 4246 -1 4247 -1 4248 -1 4249 -1 4250 -1 4251 -1 4252 -1 4253 -1 4254 -1 4255 -1 4256 -1 4257 -1 4258 -1 4259 -1 4260 -1 4261 -1 4262 -1 4263 -1 4264 -1 4265 -1 4266 -1 4267 -1 4268 -1 4269 -1 4270 -1 4271 -1 4272 -1 4273 -1 4274 -1 4275 -1 4276 -1 4277 -1 4278 -1 4279 -1 4280 -1 4281 -1 4282 -1 4283 -1 4284 -1 4285 -1 4286 -1 4287 -1 4288 -1 4289 -1 4290 -1 4291 -1 4292 -1 4293 -1 4294 -1 4295 -1 4296 -1 4297 -1 4298 -1 4299 -1 4300 -1 4301 -1 4302 -1 4303 -1 4304 -1 4305 -1 4306 -1 4307 -1 4308 -1 4309 -1 4310 -1 4311 -1 4312 -1 4313 -1 4314 -1 4315 -1 4316 -1 4317 -1 4318 -1 4319 -1 4320 -1 4321 -1 4322 -1 4323 -1 4324 -1 4325 -1 4326 -1 4327 -1 4328 -1 4329 -1 4330 -1 4331 -1 4332 -1 4333 -1 4334 -1 4335 -1 4336 -1 4337 -1 4338 -1 4339 -1 4340 -1 4341 -1 4342 -1 4343 -1 4344 -1 4345 -1 4346 -1 4347 -1 4348 -1 4349 -1 4350 -1 4351 -1 4352 -1 4353 -1 4354 -1 4355 -1 4356 -1 4357 -1 4358 -1 4359 -1 4360 -1 4361 -1 4362 -1 4363 -1 4364 -1 4365 -1 4366 -1 4367 -1 4368 -1 4369 -1 4370 -1 4371 -1 4372 -1 4373 -1 4374 -1 4375 -1 4376 -1 4377 -1 4378 -1 4379 -1 4380 -1 4381 -1 4382 -1 4383 -1 4384 -1 4385 -1 4386 -1 4387 -1 4388 -1 4389 -1 4390 -1 4391 -1 4392 -1 4393 -1 4394 -1 4395 -1 4396 -1 4397 -1 4398 -1 4399 -1 4400 -1 4401 -1 4402 -1 4403 -1 4404 -1 4405 -1 4406 -1 4407 -1 4408 -1 4409 -1 4410 -1 4411 -1 4412 -1 4413 -1 4414 -1 4415 -1 4416 -1 4417 -1 4418 -1 4419 -1 4420 -1 4421 -1 4422 -1 4423 -1 4424 -1 4425 -1 4426 -1 4427 -1 4428 -1 4429 -1 4430 -1 4431 -1 4432 -1 4433 -1 4434 -1 4435 -1 4436 -1 4437 -1 4438 -1 4439 -1 4440 -1 4441 -1 4442 -1 4443 -1 4444 -1 4445 -1 4446 -1 4447 -1 4448 -1 4449 -1 4450 -1 4451 -1 4452 -1 4453 -1 4454 -1 4455 -1 4456 -1 4457 -1 4458 -1 4459 -1 4460 -1 4461 -1 4462 -1 4463 -1 4464 -1 4465 -1 4466 -1 4467 -1 4468 -1 4469 -1 4470 -1 4471 -1 4472 -1 4473 -1 4474 -1 4475 -1 4476 -1 4477 -1 4478 -1 4479 -1 4480 -1 4481 -1 4482 -1 4483 -1 4484 -1 4485 -1 4486 -1 4487 -1 4488 -1 4489 -1 4490 -1 4491 -1 4492 -1 4493 -1 4494 -1 4495 -1 4496 -1 4497 -1 4498 -1 4499 -1 4500 -1 4501 -1 4502 -1 4503 -1 4504 -1 4505 -1 4506 -1 4507 -1 4508 -1 4509 -1 4510 -1 4511 -1 4512 -1 4513 -1 4514 -1 4515 -1 4516 -1 4517 -1 4518 -1 4519 -1 4520 -1 4521 -1 4522 -1 4523 -1 4524 -1 4525 -1 4526 -1 4527 -1 4528 -1 4529 -1 4530 -1 4531 -1 4532 -1 4533 -1 4534 -1 4535 -1 4536 -1 4537 -1 4538 -1 4539 -1 4540 -1 4541 -1 4542 -1 4543 -1 4544 -1 4545 -1 4546 -1 4547 -1 4548 -1 4549 -1 4550 -1 4551 -1 4552 -1 4553 -1 4554 -1 4555 -1 4556 -1 4557 -1 4558 -1 4559 -1 4560 -1 4561 -1 4562 -1 4563 -1 4564 -1 4565 -1 4566 -1 4567 -1 4568 -1 4569 -1 4570 -1 4571 -1 4572 -1 4573 -1 4574 -1 4575 -1 4576 -1 4577 -1 4578 -1 4579 -1 4580 -1 4581 -1 4582 -1 4583 -1 4584 -1 4585 -1 4586 -1 4587 -1 4588 -1 4589 -1 4590 -1 4591 -1 4592 -1 4593 -1 4594 -1 4595 -1 4596 -1 4597 -1 4598 -1 4599 -1 4600 -1 4601 -1 4602 -1 4603 -1 4604 -1 4605 -1 4606 -1 4607 -1 4608 -1 4609 -1 4610 -1 4611 -1 4612 -1 4613 -1 4614 -1 4615 -1 4616 -1 4617 -1 4618 -1 4619 -1 4620 -1 4621 -1 4622 -1 4623 -1 4624 -1 4625 -1 4626 -1 4627 -1 4628 -1 4629 -1 4630 -1 4631 -1 4632 -1 4633 -1 4634 -1 4635 -1 4636 -1 4637 -1 4638 -1 4639 -1 4640 -1 4641 -1 4642 -1 4643 -1 4644 -1 4645 -1 4646 -1 4647 -1 4648 -1 4649 -1 4650 -1 4651 -1 4652 -1 4653 -1 4654 -1 4655 -1 4656 -1 4657 -1 4658 -1 4659 -1 4660 -1 4661 -1 4662 -1 4663 -1 4664 -1 4665 -1 4666 -1 4667 -1 4668 -1 4669 -1 4670 -1 4671 -1 4672 -1 4673 -1 4674 -1 4675 -1 4676 -1 4677 -1 4678 -1 4679 -1 4680 -1 4681 -1 4682 -1 4683 -1 4684 -1 4685 -1 4686 -1 4687 -1 4688 -1 4689 -1 4690 -1 4691 -1 4692 -1 4693 -1 4694 -1 4695 -1 4696 -1 4697 -1 4698 -1 4699 -1 4700 -1 4701 -1 4702 -1 4703 -1 4704 -1 4705 -1 4706 -1 4707 -1 4708 -1 4709 -1 4710 -1 4711 -1 4712 -1 4713 -1 4714 -1 4715 -1 4716 -1 4717 -1 4718 -1 4719 -1 4720 -1 4721 -1 4722 -1 4723 -1 4724 -1 4725 -1 4726 -1 4727 -1 4728 -1 4729 -1 4730 -1 4731 -1 4732 -1 4733 -1 4734 -1 4735 -1 4736 -1 4737 -1 4738 -1 4739 -1 4740 -1 4741 -1 4742 -1 4743 -1 4744 -1 4745 -1 4746 -1 4747 -1 4748 -1 4749 -1 4750 -1 4751 -1 4752 -1 4753 -1 4754 -1 4755 -1 4756 -1 4757 -1 4758 -1 4759 -1 4760 -1 4761 -1 4762 -1 4763 -1 4764 -1 4765 -1 4766 -1 4767 -1 4768 -1 4769 -1 4770 -1 4771 -1 4772 -1 4773 -1 4774 -1 4775 -1 4776 -1 4777 -1 4778 -1 4779 -1 4780 -1 4781 -1 4782 -1 4783 -1 4784 -1 4785 -1 4786 -1 4787 -1 4788 -1 4789 -1 4790 -1 4791 -1 4792 -1 4793 -1 4794 -1 4795 -1 4796 -1 4797 -1 4798 -1 4799 -1 4800 -1 4801 -1 4802 -1 4803 -1 4804 -1 4805 -1 4806 -1 4807 -1 4808 -1 4809 -1 4810 -1 4811 -1 4812 -1 4813 -1 4814 -1 4815 -1 4816 -1 4817 -1 4818 -1 4819 -1 4820 -1 4821 -1 4822 -1 4823 -1 4824 -1 4825 -1 4826 -1 4827 -1 4828 -1 4829 -1 4830 -1 4831 -1 4832 -1 4833 -1 4834 -1 4835 -1 4836 -1 4837 -1 4838 -1 4839 -1 4840 -1 4841 -1 4842 -1 4843 -1 4844 -1 4845 -1 4846 -1 4847 -1 4848 -1 4849 -1 4850 -1 4851 -1 4852 -1 4853 -1 4854 -1 4855 -1 4856 -1 4857 -1 4858 -1 4859 -1 4860 -1 4861 -1 4862 -1 4863 -1 4864 -1 4865 -1 4866 -1 4867 -1 4868 -1 4869 -1 4870 -1 4871 -1 4872 -1 4873 -1 4874 -1 4875 -1 4876 -1 4877 -1 4878 -1 4879 -1 4880 -1 4881 -1 4882 -1 4883 -1 4884 -1 4885 -1 4886 -1 4887 -1 4888 -1 4889 -1 4890 -1 4891 -1 4892 -1 4893 -1 4894 -1 4895 -1 4896 -1 4897 -1 4898 -1 4899 -1 4900 -1 4901 -1 4902 -1 4903 -1 4904 -1 4905 -1 4906 -1 4907 -1 4908 -1 4909 -1 4910 -1 4911 -1 4912 -1 4913 -1 4914 -1 4915 -1 4916 -1 4917 -1 4918 -1 4919 -1 4920 -1 4921 -1 4922 -1 4923 -1 4924 -1 4925 -1 4926 -1 4927 -1 4928 -1 4929 -1 4930 -1 4931 -1 4932 -1 4933 -1 4934 -1 4935 -1 4936 -1 4937 -1 4938 -1 4939 -1 4940 -1 4941 -1 4942 -1 4943 -1 4944 -1 4945 -1 4946 -1 4947 -1 4948 -1 4949 -1 4950 -1 4951 -1 4952 -1 4953 -1 4954 -1 4955 -1 4956 -1 4957 -1 4958 -1 4959 -1 4960 -1 4961 -1 4962 -1 4963 -1 4964 -1 4965 -1 4966 -1 4967 -1 4968 -1 4969 -1 4970 -1 4971 -1 4972 -1 4973 -1 4974 -1 4975 -1 4976 -1 4977 -1 4978 -1 4979 -1 4980 -1 4981 -1 4982 -1 4983 -1 4984 -1 4985 -1 4986 -1 4987 -1 4988 -1 4989 -1 4990 -1 4991 -1 4992 -1 4993 -1 4994 -1 4995 -1 4996 -1 4997 -1 4998 -1 4999 -1 5000 -1 5001 -1 5002 -1 5003 -1 5004 -1 5005 -1 5006 -1 5007 -1 5008 -1 5009 -1 5010 -1 5011 -1 5012 -1 5013 -1 5014 -1 5015 -1 5016 -1 5017 -1 5018 -1 5019 -1 5020 -1 5021 -1 5022 -1 5023 -1 5024 -1 5025 -1 5026 -1 5027 -1 5028 -1 5029 -1 5030 -1 5031 -1 5032 -1 5033 -1 5034 -1 5035 -1 5036 -1 5037 -1 5038 -1 5039 -1 5040 -1 5041 -1 5042 -1 5043 -1 5044 -1 5045 -1 5046 -1 5047 -1 5048 -1 5049 -1 5050 -1 5051 -1 5052 -1 5053 -1 5054 -1 5055 -1 5056 -1 5057 -1 5058 -1 5059 -1 5060 -1 5061 -1 5062 -1 5063 -1 5064 -1 5065 -1 5066 -1 5067 -1 5068 -1 5069 -1 5070 -1 5071 -1 5072 -1 5073 -1 5074 -1 5075 -1 5076 -1 5077 -1 5078 -1 5079 -1 5080 -1 5081 -1 5082 -1 5083 -1 5084 -1 5085 -1 5086 -1 5087 -1 5088 -1 5089 -1 5090 -1 5091 -1 5092 -1 5093 -1 5094 -1 5095 -1 5096 -1 5097 -1 5098 -1 5099 -1 5100 -1 5101 -1 5102 -1 5103 -1 5104 -1 5105 -1 5106 -1 5107 -1 5108 -1 5109 -1 5110 -1 5111 -1 5112 -1 5113 -1 5114 -1 5115 -1 5116 -1 5117 -1 5118 -1 5119 -1 5120 -1 5121 -1 5122 -1 5123 -1 5124 -1 5125 -1 5126 -1 5127 -1 5128 -1 5129 -1 5130 -1 5131 -1 5132 -1 5133 -1 5134 -1 5135 -1 5136 -1 5137 -1 5138 -1 5139 -1 5140 -1 5141 -1 5142 -1 5143 -1 5144 -1 5145 -1 5146 -1 5147 -1 5148 -1 5149 -1 5150 -1 5151 -1 5152 -1 5153 -1 5154 -1 5155 -1 5156 -1 5157 -1 5158 -1 5159 -1 5160 -1 5161 -1 5162 -1 5163 -1 5164 -1 5165 -1 5166 -1 5167 -1 5168 -1 5169 -1 5170 -1 5171 -1 5172 -1 5173 -1 5174 -1 5175 -1 5176 -1 5177 -1 5178 -1 5179 -1 5180 -1 5181 -1 5182 -1 5183 -1 5184 -1 5185 -1 5186 -1 5187 -1 5188 -1 5189 -1 5190 -1 5191 -1 5192 -1 5193 -1 5194 -1 5195 -1 5196 -1 5197 -1 5198 -1 5199 -1 5200 -1 5201 -1 5202 -1 5203 -1 5204 -1 5205 -1 5206 -1 5207 -1 5208 -1 5209 -1 5210 -1 5211 -1 5212 -1 5213 -1 5214 -1 5215 -1 5216 -1 5217 -1 5218 -1 5219 -1 5220 -1 5221 -1 5222 -1 5223 -1 5224 -1 5225 -1 5226 -1 5227 -1 5228 -1 5229 -1 5230 -1 5231 -1 5232 -1 5233 -1 5234 -1 5235 -1 5236 -1 5237 -1 5238 -1 5239 -1 5240 -1 5241 -1 5242 -1 5243 -1 5244 -1 5245 -1 5246 -1 5247 -1 5248 -1 5249 -1 5250 -1 5251 -1 5252 -1 5253 -1 5254 -1 5255 -1 5256 -1 5257 -1 5258 -1 5259 -1 5260 -1 5261 -1 5262 -1 5263 -1 5264 -1 5265 -1 5266 -1 5267 -1 5268 -1 5269 -1 5270 -1 5271 -1 5272 -1 5273 -1 5274 -1 5275 -1 5276 -1 5277 -1 5278 -1 5279 -1 5280 -1 5281 -1 5282 -1 5283 -1 5284 -1 5285 -1 5286 -1 5287 -1 5288 -1 5289 -1 5290 -1 5291 -1 5292 -1 5293 -1 5294 -1 5295 -1 5296 -1 5297 -1 5298 -1 5299 -1 5300 -1 5301 -1 5302 -1 5303 -1 5304 -1 5305 -1 5306 -1 5307 -1 5308 -1 5309 -1 5310 -1 5311 -1 5312 -1 5313 -1 5314 -1 5315 -1 5316 -1 5317 -1 5318 -1 5319 -1 5320 -1 5321 -1 5322 -1 5323 -1 5324 -1 5325 -1 5326 -1 5327 -1 5328 -1 5329 -1 5330 -1 5331 -1 5332 -1 5333 -1 5334 -1 5335 -1 5336 -1 5337 -1 5338 -1 5339 -1 5340 -1 5341 -1 5342 -1 5343 -1 5344 -1 5345 -1 5346 -1 5347 -1 5348 -1 5349 -1 5350 -1 5351 -1 5352 -1 5353 -1 5354 -1 5355 -1 5356 -1 5357 -1 5358 -1 5359 -1 5360 -1 5361 -1 5362 -1 5363 -1 5364 -1 5365 -1 5366 -1 5367 -1 5368 -1 5369 -1 5370 -1 5371 -1 5372 -1 5373 -1 5374 -1 5375 -1 5376 -1 5377 -1 5378 -1 5379 -1 5380 -1 5381 -1 5382 -1 5383 -1 5384 -1 5385 -1 5386 -1 5387 -1 5388 -1 5389 -1 5390 -1 5391 -1 5392 -1 5393 -1 5394 -1 5395 -1 5396 -1 5397 -1 5398 -1 5399 -1 5400 -1 5401 -1 5402 -1 5403 -1 5404 -1 5405 -1 5406 -1 5407 -1 5408 -1 5409 -1 5410 -1 5411 -1 5412 -1 5413 -1 5414 -1 5415 -1 5416 -1 5417 -1 5418 -1 5419 -1 5420 -1 5421 -1 5422 -1 5423 -1 5424 -1 5425 -1 5426 -1 5427 -1 5428 -1 5429 -1 5430 -1 5431 -1 5432 -1 5433 -1 5434 -1 5435 -1 5436 -1 5437 -1 5438 -1 5439 -1 5440 -1 5441 -1 5442 -1 5443 -1 5444 -1 5445 -1 5446 -1 5447 -1 5448 -1 5449 -1 5450 -1 5451 -1 5452 -1 5453 -1 5454 -1 5455 -1 5456 -1 5457 -1 5458 -1 5459 -1 5460 -1 5461 -1 5462 -1 5463 -1 5464 -1 5465 -1 5466 -1 5467 -1 5468 -1 5469 -1 5470 -1 5471 -1 5472 -1 5473 -1 5474 -1 5475 -1 5476 -1 5477 -1 5478 -1 5479 -1 5480 -1 5481 -1 5482 -1 5483 -1 5484 -1 5485 -1 5486 -1 5487 -1 5488 -1 5489 -1 5490 -1 5491 -1 5492 -1 5493 -1 5494 -1 5495 -1 5496 -1 5497 -1 5498 -1 5499 -1 5500 -1 5501 -1 5502 -1 5503 -1 5504 -1 5505 -1 5506 -1 5507 -1 5508 -1 5509 -1 5510 -1 5511 -1 5512 -1 5513 -1 5514 -1 5515 -1 5516 -1 5517 -1 5518 -1 5519 -1 5520 -1 5521 -1 5522 -1 5523 -1 5524 -1 5525 -1 5526 -1 5527 -1 5528 -1 5529 -1 5530 -1 5531 -1 5532 -1 5533 -1 5534 -1 5535 -1 5536 -1 5537 -1 5538 -1 5539 -1 5540 -1 5541 -1 5542 -1 5543 -1 5544 -1 5545 -1 5546 -1 5547 -1 5548 -1 5549 -1 5550 -1 5551 -1 5552 -1 5553 -1 5554 -1 5555 -1 5556 -1 5557 -1 5558 -1 5559 -1 5560 -1 5561 -1 5562 -1 5563 -1 5564 -1 5565 -1 5566 -1 5567 -1 5568 -1 5569 -1 5570 -1 5571 -1 5572 -1 5573 -1 5574 -1 5575 -1 5576 -1 5577 -1 5578 -1 5579 -1 5580 -1 5581 -1 5582 -1 5583 -1 5584 -1 5585 -1 5586 -1 5587 -1 5588 -1 5589 -1 5590 -1 5591 -1 5592 -1 5593 -1 5594 -1 5595 -1 5596 -1 5597 -1 5598 -1 5599 -1 5600 -1 5601 -1 5602 -1 5603 -1 5604 -1 5605 -1 5606 -1 5607 -1 5608 -1 5609 -1 5610 -1 5611 -1 5612 -1 5613 -1 5614 -1 5615 -1 5616 -1 5617 -1 5618 -1 5619 -1 5620 -1 5621 -1 5622 -1 5623 -1 5624 -1 5625 -1 5626 -1 5627 -1 5628 -1 5629 -1 5630 -1 5631 -1 5632 -1 5633 -1 5634 -1 5635 -1 5636 -1 5637 -1 5638 -1 5639 -1 5640 -1 5641 -1 5642 -1 5643 -1 5644 -1 5645 -1 5646 -1 5647 -1 5648 -1 5649 -1 5650 -1 5651 -1 5652 -1 5653 -1 5654 -1 5655 -1 5656 -1 5657 -1 5658 -1 5659 -1 5660 -1 5661 -1 5662 -1 5663 -1 5664 -1 5665 -1 5666 -1 5667 -1 5668 -1 5669 -1 5670 -1 5671 -1 5672 -1 5673 -1 5674 -1 5675 -1 5676 -1 5677 -1 5678 -1 5679 -1 5680 -1 5681 -1 5682 -1 5683 -1 5684 -1 5685 -1 5686 -1 5687 -1 5688 -1 5689 -1 5690 -1 5691 -1 5692 -1 5693 -1 5694 -1 5695 -1 5696 -1 5697 -1 5698 -1 5699 -1 5700 -1 5701 -1 5702 -1 5703 -1 5704 -1 5705 -1 5706 -1 5707 -1 5708 -1 5709 -1 5710 -1 5711 -1 5712 -1 5713 -1 5714 -1 5715 -1 5716 -1 5717 -1 5718 -1 5719 -1 5720 -1 5721 -1 5722 -1 5723 -1 5724 -1 5725 -1 5726 -1 5727 -1 5728 -1 5729 -1 5730 -1 5731 -1 5732 -1 5733 -1 5734 -1 5735 -1 5736 -1 5737 -1 5738 -1 5739 -1 5740 -1 5741 -1 5742 -1 5743 -1 5744 -1 5745 -1 5746 -1 5747 -1 5748 -1 5749 -1 5750 -1 5751 -1 5752 -1 5753 -1 5754 -1 5755 -1 5756 -1 5757 -1 5758 -1 5759 -1 5760 -1 5761 -1 5762 -1 5763 -1 5764 -1 5765 -1 5766 -1 5767 -1 5768 -1 5769 -1 5770 -1 5771 -1 5772 -1 5773 -1 5774 -1 5775 -1 5776 -1 5777 -1 5778 -1 5779 -1 5780 -1 5781 -1 5782 -1 5783 -1 5784 -1 5785 -1 5786 -1 5787 -1 5788 -1 5789 -1 5790 -1 5791 -1 5792 -1 5793 -1 5794 -1 5795 -1 5796 -1 5797 -1 5798 -1 5799 -1 5800 -1 5801 -1 5802 -1 5803 -1 5804 -1 5805 -1 5806 -1 5807 -1 5808 -1 5809 -1 5810 -1 5811 -1 5812 -1 5813 -1 5814 -1 5815 -1 5816 -1 5817 -1 5818 -1 5819 -1 5820 -1 5821 -1 5822 -1 5823 -1 5824 -1 5825 -1 5826 -1 5827 -1 5828 -1 5829 -1 5830 -1 5831 -1 5832 -1 5833 -1 5834 -1 5835 -1 5836 -1 5837 -1 5838 -1 5839 -1 5840 -1 5841 -1 5842 -1 5843 -1 5844 -1 5845 -1 5846 -1 5847 -1 5848 -1 5849 -1 5850 -1 5851 -1 5852 -1 5853 -1 5854 -1 5855 -1 5856 -1 5857 -1 5858 -1 5859 -1 5860 -1 5861 -1 5862 -1 5863 -1 5864 -1 5865 -1 5866 -1 5867 -1 5868 -1 5869 -1 5870 -1 5871 -1 5872 -1 5873 -1 5874 -1 5875 -1 5876 -1 5877 -1 5878 -1 5879 -1 5880 -1 5881 -1 5882 -1 5883 -1 5884 -1 5885 -1 5886 -1 5887 -1 5888 -1 5889 -1 5890 -1 5891 -1 5892 -1 5893 -1 5894 -1 5895 -1 5896 -1 5897 -1 5898 -1 5899 -1 5900 -1 5901 -1 5902 -1 5903 -1 5904 -1 5905 -1 5906 -1 5907 -1 5908 -1 5909 -1 5910 -1 5911 -1 5912 -1 5913 -1 5914 -1 5915 -1 5916 -1 5917 -1 5918 -1 5919 -1 5920 -1 5921 -1 5922 -1 5923 -1 5924 -1 5925 -1 5926 -1 5927 -1 5928 -1 5929 -1 5930 -1 5931 -1 5932 -1 5933 -1 5934 -1 5935 -1 5936 -1 5937 -1 5938 -1 5939 -1 5940 -1 5941 -1 5942 -1 5943 -1 5944 -1 5945 -1 5946 -1 5947 -1 5948 -1 5949 -1 5950 -1 5951 -1 5952 -1 5953 -1 5954 -1 5955 -1 5956 -1 5957 -1 5958 -1 5959 -1 5960 -1 5961 -1 5962 -1 5963 -1 5964 -1 5965 -1 5966 -1 5967 -1 5968 -1 5969 -1 5970 -1 5971 -1 5972 -1 5973 -1 5974 -1 5975 -1 5976 -1 5977 -1 5978 -1 5979 -1 5980 -1 5981 -1 5982 -1 5983 -1 5984 -1 5985 -1 5986 -1 5987 -1 5988 -1 5989 -1 5990 -1 5991 -1 5992 -1 5993 -1 5994 -1 5995 -1 5996 -1 5997 -1 5998 -1 5999 -1 6000 -1 6001 -1 6002 -1 6003 -1 6004 -1 6005 -1 6006 -1 6007 -1 6008 -1 6009 -1 6010 -1 6011 -1 6012 -1 6013 -1 6014 -1 6015 -1 6016 -1 6017 -1 6018 -1 6019 -1 6020 -1 6021 -1 6022 -1 6023 -1 6024 -1 6025 -1 6026 -1 6027 -1 6028 -1 6029 -1 6030 -1 6031 -1 6032 -1 6033 -1 6034 -1 6035 -1 6036 -1 6037 -1 6038 -1 6039 -1 6040 -1 6041 -1 6042 -1 6043 -1 6044 -1 6045 -1 6046 -1 6047 -1 6048 -1 6049 -1 6050 -1 6051 -1 6052 -1 6053 -1 6054 -1 6055 -1 6056 -1 6057 -1 6058 -1 6059 -1 6060 -1 6061 -1 6062 -1 6063 -1 6064 -1 6065 -1 6066 -1 6067 -1 6068 -1 6069 -1 6070 -1 6071 -1 6072 -1 6073 -1 6074 -1 6075 -1 6076 -1 6077 -1 6078 -1 6079 -1 6080 -1 6081 -1 6082 -1 6083 -1 6084 -1 6085 -1 6086 -1 6087 -1 6088 -1 6089 -1 6090 -1 6091 -1 6092 -1 6093 -1 6094 -1 6095 -1 6096 -1 6097 -1 6098 -1 6099 -1 6100 -1 6101 -1 6102 -1 6103 -1 6104 -1 6105 -1 6106 -1 6107 -1 6108 -1 6109 -1 6110 -1 6111 -1 6112 -1 6113 -1 6114 -1 6115 -1 6116 -1 6117 -1 6118 -1 6119 -1 6120 -1 6121 -1 6122 -1 6123 -1 6124 -1 6125 -1 6126 -1 6127 -1 6128 -1 6129 -1 6130 -1 6131 -1 6132 -1 6133 -1 6134 -1 6135 -1 6136 -1 6137 -1 6138 -1 6139 -1 6140 -1 6141 -1 6142 -1 6143 -1 6144 -1 6145 -1 6146 -1 6147 -1 6148 -1 6149 -1 6150 -1 6151 -1 6152 -1 6153 -1 6154 -1 6155 -1 6156 -1 6157 -1 6158 -1 6159 -1 6160 -1 6161 -1 6162 -1 6163 -1 6164 -1 6165 -1 6166 -1 6167 -1 6168 -1 6169 -1 6170 -1 6171 -1 6172 -1 6173 -1 6174 -1 6175 -1 6176 -1 6177 -1 6178 -1 6179 -1 6180 -1 6181 -1 6182 -1 6183 -1 6184 -1 6185 -1 6186 -1 6187 -1 6188 -1 6189 -1 6190 -1 6191 -1 6192 -1 6193 -1 6194 -1 6195 -1 6196 -1 6197 -1 6198 -1 6199 -1 6200 -1 6201 -1 6202 -1 6203 -1 6204 -1 6205 -1 6206 -1 6207 -1 6208 -1 6209 -1 6210 -1 6211 -1 6212 -1 6213 -1 6214 -1 6215 -1 6216 -1 6217 -1 6218 -1 6219 -1 6220 -1 6221 -1 6222 -1 6223 -1 6224 -1 6225 -1 6226 -1 6227 -1 6228 -1 6229 -1 6230 -1 6231 -1 6232 -1 6233 -1 6234 -1 6235 -1 6236 -1 6237 -1 6238 -1 6239 -1 6240 -1 6241 -1 6242 -1 6243 -1 6244 -1 6245 -1 6246 -1 6247 -1 6248 -1 6249 -1 6250 -1 6251 -1 6252 -1 6253 -1 6254 -1 6255 -1 6256 -1 6257 -1 6258 -1 6259 -1 6260 -1 6261 -1 6262 -1 6263 -1 6264 -1 6265 -1 6266 -1 6267 -1 6268 -1 6269 -1 6270 -1 6271 -1 6272 -1 6273 -1 6274 -1 6275 -1 6276 -1 6277 -1 6278 -1 6279 -1 6280 -1 6281 -1 6282 -1 6283 -1 6284 -1 6285 -1 6286 -1 6287 -1 6288 -1 6289 -1 6290 -1 6291 -1 6292 -1 6293 -1 6294 -1 6295 -1 6296 -1 6297 -1 6298 -1 6299 -1 6300 -1 6301 -1 6302 -1 6303 -1 6304 -1 6305 -1 6306 -1 6307 -1 6308 -1 6309 -1 6310 -1 6311 -1 6312 -1 6313 -1 6314 -1 6315 -1 6316 -1 6317 -1 6318 -1 6319 -1 6320 -1 6321 -1 6322 -1 6323 -1 6324 -1 6325 -1 6326 -1 6327 -1 6328 -1 6329 -1 6330 -1 6331 -1 6332 -1 6333 -1 6334 -1 6335 -1 6336 -1 6337 -1 6338 -1 6339 -1 6340 -1 6341 -1 6342 -1 6343 -1 6344 -1 6345 -1 6346 -1 6347 -1 6348 -1 6349 -1 6350 -1 6351 -1 6352 -1 6353 -1 6354 -1 6355 -1 6356 -1 6357 -1 6358 -1 6359 -1 6360 -1 6361 -1 6362 -1 6363 -1 6364 -1 6365 -1 6366 -1 6367 -1 6368 -1 6369 -1 6370 -1 6371 -1 6372 -1 6373 -1 6374 -1 6375 -1 6376 -1 6377 -1 6378 -1 6379 -1 6380 -1 6381 -1 6382 -1 6383 -1 6384 -1 6385 -1 6386 -1 6387 -1 6388 -1 6389 -1 6390 -1 6391 -1 6392 -1 6393 -1 6394 -1 6395 -1 6396 -1 6397 -1 6398 -1 6399 -1 6400 -1 6401 -1 6402 -1 6403 -1 6404 -1 6405 -1 6406 -1 6407 -1 6408 -1 6409 -1 6410 -1 6411 -1 6412 -1 6413 -1 6414 -1 6415 -1 6416 -1 6417 -1 6418 -1 6419 -1 6420 -1 6421 -1 6422 -1 6423 -1 6424 -1 6425 -1 6426 -1 6427 -1 6428 -1 6429 -1 6430 -1 6431 -1 6432 -1 6433 -1 6434 -1 6435 -1 6436 -1 6437 -1 6438 -1 6439 -1 6440 -1 6441 -1 6442 -1 6443 -1 6444 -1 6445 -1 6446 -1 6447 -1 6448 -1 6449 -1 6450 -1 6451 -1 6452 -1 6453 -1 6454 -1 6455 -1 6456 -1 6457 -1 6458 -1 6459 -1 6460 -1 6461 -1 6462 -1 6463 -1 6464 -1 6465 -1 6466 -1 6467 -1 6468 -1 6469 -1 6470 -1 6471 -1 6472 -1 6473 -1 6474 -1 6475 -1 6476 -1 6477 -1 6478 -1 6479 -1 6480 -1 6481 -1 6482 -1 6483 -1 6484 -1 6485 -1 6486 -1 6487 -1 6488 -1 6489 -1 6490 -1 6491 -1 6492 -1 6493 -1 6494 -1 6495 -1 6496 -1 6497 -1 6498 -1 6499 -1 6500 -1 6501 -1 6502 -1 6503 -1 6504 -1 6505 -1 6506 -1 6507 -1 6508 -1 6509 -1 6510 -1 6511 -1 6512 -1 6513 -1 6514 -1 6515 -1 6516 -1 6517 -1 6518 -1 6519 -1 6520 -1 6521 -1 6522 -1 6523 -1 6524 -1 6525 -1 6526 -1 6527 -1 6528 -1 6529 -1 6530 -1 6531 -1 6532 -1 6533 -1 6534 -1 6535 -1 6536 -1 6537 -1 6538 -1 6539 -1 6540 -1 6541 -1 6542 -1 6543 -1 6544 -1 6545 -1 6546 -1 6547 -1 6548 -1 6549 -1 6550 -1 6551 -1 6552 -1 6553 -1 6554 -1 6555 -1 6556 -1 6557 -1 6558 -1 6559 -1 6560 -1 6561 -1 6562 -1 6563 -1 6564 -1 6565 -1 6566 -1 6567 -1 6568 -1 6569 -1 6570 -1 6571 -1 6572 -1 6573 -1 6574 -1 6575 -1 6576 -1 6577 -1 6578 -1 6579 -1 6580 -1 6581 -1 6582 -1 6583 -1 6584 -1 6585 -1 6586 -1 6587 -1 6588 -1 6589 -1 6590 -1 6591 -1 6592 -1 6593 -1 6594 -1 6595 -1 6596 -1 6597 -1 6598 -1 6599 -1 6600 -1 6601 -1 6602 -1 6603 -1 6604 -1 6605 -1 6606 -1 6607 -1 6608 -1 6609 -1 6610 -1 6611 -1 6612 -1 6613 -1 6614 -1 6615 -1 6616 -1 6617 -1 6618 -1 6619 -1 6620 -1 6621 -1 6622 -1 6623 -1 6624 -1 6625 -1 6626 -1 6627 -1 6628 -1 6629 -1 6630 -1 6631 -1 6632 -1 6633 -1 6634 -1 6635 -1 6636 -1 6637 -1 6638 -1 6639 -1 6640 -1 6641 -1 6642 -1 6643 -1 6644 -1 6645 -1 6646 -1 6647 -1 6648 -1 6649 -1 6650 -1 6651 -1 6652 -1 6653 -1 6654 -1 6655 -1 6656 -1 6657 -1 6658 -1 6659 -1 6660 -1 6661 -1 6662 -1 6663 -1 6664 -1 6665 -1 6666 -1 6667 -1 6668 -1 6669 -1 6670 -1 6671 -1 6672 -1 6673 -1 6674 -1 6675 -1 6676 -1 6677 -1 6678 -1 6679 -1 6680 -1 6681 -1 6682 -1 6683 -1 6684 -1 6685 -1 6686 -1 6687 -1 6688 -1 6689 -1 6690 -1 6691 -1 6692 -1 6693 -1 6694 -1 6695 -1 6696 -1 6697 -1 6698 -1 6699 -1 6700 -1 6701 -1 6702 -1 6703 -1 6704 -1 6705 -1 6706 -1 6707 -1 6708 -1 6709 -1 6710 -1 6711 -1 6712 -1 6713 -1 6714 -1 6715 -1 6716 -1 6717 -1 6718 -1 6719 -1 6720 -1 6721 -1 6722 -1 6723 -1 6724 -1 6725 -1 6726 -1 6727 -1 6728 -1 6729 -1 6730 -1 6731 -1 6732 -1 6733 -1 6734 -1 6735 -1 6736 -1 6737 -1 6738 -1 6739 -1 6740 -1 6741 -1 6742 -1 6743 -1 6744 -1 6745 -1 6746 -1 6747 -1 6748 -1 6749 -1 6750 -1 6751 -1 6752 -1 6753 -1 6754 -1 6755 -1 6756 -1 6757 -1 6758 -1 6759 -1 6760 -1 6761 -1 6762 -1 6763 -1 6764 -1 6765 -1 6766 -1 6767 -1 6768 -1 6769 -1 6770 -1 6771 -1 6772 -1 6773 -1 6774 -1 6775 -1 6776 -1 6777 -1 6778 -1 6779 -1 6780 -1 6781 -1 6782 -1 6783 -1 6784 -1 6785 -1 6786 -1 6787 -1 6788 -1 6789 -1 6790 -1 6791 -1 6792 -1 6793 -1 6794 -1 6795 -1 6796 -1 6797 -1 6798 -1 6799 -1 6800 -1 6801 -1 6802 -1 6803 -1 6804 -1 6805 -1 6806 -1 6807 -1 6808 -1 6809 -1 6810 -1 6811 -1 6812 -1 6813 -1 6814 -1 6815 -1 6816 -1 6817 -1 6818 -1 6819 -1 6820 -1 6821 -1 6822 -1 6823 -1 6824 -1 6825 -1 6826 -1 6827 -1 6828 -1 6829 -1 6830 -1 6831 -1 6832 -1 6833 -1 6834 -1 6835 -1 6836 -1 6837 -1 6838 -1 6839 -1 6840 -1 6841 -1 6842 -1 6843 -1 6844 -1 6845 -1 6846 -1 6847 -1 6848 -1 6849 -1 6850 -1 6851 -1 6852 -1 6853 -1 6854 -1 6855 -1 6856 -1 6857 -1 6858 -1 6859 -1 6860 -1 6861 -1 6862 -1 6863 -1 6864 -1 6865 -1 6866 -1 6867 -1 6868 -1 6869 -1 6870 -1 6871 -1 6872 -1 6873 -1 6874 -1 6875 -1 6876 -1 6877 -1 6878 -1 6879 -1 6880 -1 6881 -1 6882 -1 6883 -1 6884 -1 6885 -1 6886 -1 6887 -1 6888 -1 6889 -1 6890 -1 6891 -1 6892 -1 6893 -1 6894 -1 6895 -1 6896 -1 6897 -1 6898 -1 6899 -1 6900 -1 6901 -1 6902 -1 6903 -1 6904 -1 6905 -1 6906 -1 6907 -1 6908 -1 6909 -1 6910 -1 6911 -1 6912 -1 6913 -1 6914 -1 6915 -1 6916 -1 6917 -1 6918 -1 6919 -1 6920 -1 6921 -1 6922 -1 6923 -1 6924 -1 6925 -1 6926 -1 6927 -1 6928 -1 6929 -1 6930 -1 6931 -1 6932 -1 6933 -1 6934 -1 6935 -1 6936 -1 6937 -1 6938 -1 6939 -1 6940 -1 6941 -1 6942 -1 6943 -1 6944 -1 6945 -1 6946 -1 6947 -1 6948 -1 6949 -1 6950 -1 6951 -1 6952 -1 6953 -1 6954 -1 6955 -1 6956 -1 6957 -1 6958 -1 6959 -1 6960 -1 6961 -1 6962 -1 6963 -1 6964 -1 6965 -1 6966 -1 6967 -1 6968 -1 6969 -1 6970 -1 6971 -1 6972 -1 6973 -1 6974 -1 6975 -1 6976 -1 6977 -1 6978 -1 6979 -1 6980 -1 6981 -1 6982 -1 6983 -1 6984 -1 6985 -1 6986 -1 6987 -1 6988 -1 6989 -1 6990 -1 6991 -1 6992 -1 6993 -1 6994 -1 6995 -1 6996 -1 6997 -1 6998 -1 6999 -1 7000 -1 7001 -1 7002 -1 7003 -1 7004 -1 7005 -1 7006 -1 7007 -1 7008 -1 7009 -1 7010 -1 7011 -1 7012 -1 7013 -1 7014 -1 7015 -1 7016 -1 7017 -1 7018 -1 7019 -1 7020 -1 7021 -1 7022 -1 7023 -1 7024 -1 7025 -1 7026 -1 7027 -1 7028 -1 7029 -1 7030 -1 7031 -1 7032 -1 7033 -1 7034 -1 7035 -1 7036 -1 7037 -1 7038 -1 7039 -1 7040 -1 7041 -1 7042 -1 7043 -1 7044 -1 7045 -1 7046 -1 7047 -1 7048 -1 7049 -1 7050 -1 7051 -1 7052 -1 7053 -1 7054 -1 7055 -1 7056 -1 7057 -1 7058 -1 7059 -1 7060 -1 7061 -1 7062 -1 7063 -1 7064 -1 7065 -1 7066 -1 7067 -1 7068 -1 7069 -1 7070 -1 7071 -1 7072 -1 7073 -1 7074 -1 7075 -1 7076 -1 7077 -1 7078 -1 7079 -1 7080 -1 7081 -1 7082 -1 7083 -1 7084 -1 7085 -1 7086 -1 7087 -1 7088 -1 7089 -1 7090 -1 7091 -1 7092 -1 7093 -1 7094 -1 7095 -1 7096 -1 7097 -1 7098 -1 7099 -1 7100 -1 7101 -1 7102 -1 7103 -1 7104 -1 7105 -1 7106 -1 7107 -1 7108 -1 7109 -1 7110 -1 7111 -1 7112 -1 7113 -1 7114 -1 7115 -1 7116 -1 7117 -1 7118 -1 7119 -1 7120 -1 7121 -1 7122 -1 7123 -1 7124 -1 7125 -1 7126 -1 7127 -1 7128 -1 7129 -1 7130 -1 7131 -1 7132 -1 7133 -1 7134 -1 7135 -1 7136 -1 7137 -1 7138 -1 7139 -1 7140 -1 7141 -1 7142 -1 7143 -1 7144 -1 7145 -1 7146 -1 7147 -1 7148 -1 7149 -1 7150 -1 7151 -1 7152 -1 7153 -1 7154 -1 7155 -1 7156 -1 7157 -1 7158 -1 7159 -1 7160 -1 7161 -1 7162 -1 7163 -1 7164 -1 7165 -1 7166 -1 7167 -1 7168 -1 7169 -1 7170 -1 7171 -1 7172 -1 7173 -1 7174 -1 7175 -1 7176 -1 7177 -1 7178 -1 7179 -1 7180 -1 7181 -1 7182 -1 7183 -1 7184 -1 7185 -1 7186 -1 7187 -1 7188 -1 7189 -1 7190 -1 7191 -1 7192 -1 7193 -1 7194 -1 7195 -1 7196 -1 7197 -1 7198 -1 7199 -1 7200 -1 7201 -1 7202 -1 7203 -1 7204 -1 7205 -1 7206 -1 7207 -1 7208 -1 7209 -1 7210 -1 7211 -1 7212 -1 7213 -1 7214 -1 7215 -1 7216 -1 7217 -1 7218 -1 7219 -1 7220 -1 7221 -1 7222 -1 7223 -1 7224 -1 7225 -1 7226 -1 7227 -1 7228 -1 7229 -1 7230 -1 7231 -1 7232 -1 7233 -1 7234 -1 7235 -1 7236 -1 7237 -1 7238 -1 7239 -1 7240 -1 7241 -1 7242 -1 7243 -1 7244 -1 7245 -1 7246 -1 7247 -1 7248 -1 7249 -1 7250 -1 7251 -1 7252 -1 7253 -1 7254 -1 7255 -1 7256 -1 7257 -1 7258 -1 7259 -1 7260 -1 7261 -1 7262 -1 7263 -1 7264 -1 7265 -1 7266 -1 7267 -1 7268 -1 7269 -1 7270 -1 7271 -1 7272 -1 7273 -1 7274 -1 7275 -1 7276 -1 7277 -1 7278 -1 7279 -1 7280 -1 7281 -1 7282 -1 7283 -1 7284 -1 7285 -1 7286 -1 7287 -1 7288 -1 7289 -1 7290 -1 7291 -1 7292 -1 7293 -1 7294 -1 7295 -1 7296 -1 7297 -1 7298 -1 7299 -1 7300 -1 7301 -1 7302 -1 7303 -1 7304 -1 7305 -1 7306 -1 7307 -1 7308 -1 7309 -1 7310 -1 7311 -1 7312 -1 7313 -1 7314 -1 7315 -1 7316 -1 7317 -1 7318 -1 7319 -1 7320 -1 7321 -1 7322 -1 7323 -1 7324 -1 7325 -1 7326 -1 7327 -1 7328 -1 7329 -1 7330 -1 7331 -1 7332 -1 7333 -1 7334 -1 7335 -1 7336 -1 7337 -1 7338 -1 7339 -1 7340 -1 7341 -1 7342 -1 7343 -1 7344 -1 7345 -1 7346 -1 7347 -1 7348 -1 7349 -1 7350 -1 7351 -1 7352 -1 7353 -1 7354 -1 7355 -1 7356 -1 7357 -1 7358 -1 7359 -1 7360 -1 7361 -1 7362 -1 7363 -1 7364 -1 7365 -1 7366 -1 7367 -1 7368 -1 7369 -1 7370 -1 7371 -1 7372 -1 7373 -1 7374 -1 7375 -1 7376 -1 7377 -1 7378 -1 7379 -1 7380 -1 7381 -1 7382 -1 7383 -1 7384 -1 7385 -1 7386 -1 7387 -1 7388 -1 7389 -1 7390 -1 7391 -1 7392 -1 7393 -1 7394 -1 7395 -1 7396 -1 7397 -1 7398 -1 7399 -1 7400 -1 7401 -1 7402 -1 7403 -1 7404 -1 7405 -1 7406 -1 7407 -1 7408 -1 7409 -1 7410 -1 7411 -1 7412 -1 7413 -1 7414 -1 7415 -1 7416 -1 7417 -1 7418 -1 7419 -1 7420 -1 7421 -1 7422 -1 7423 -1 7424 -1 7425 -1 7426 -1 7427 -1 7428 -1 7429 -1 7430 -1 7431 -1 7432 -1 7433 -1 7434 -1 7435 -1 7436 -1 7437 -1 7438 -1 7439 -1 7440 -1 7441 -1 7442 -1 7443 -1 7444 -1 7445 -1 7446 -1 7447 -1 7448 -1 7449 -1 7450 -1 7451 -1 7452 -1 7453 -1 7454 -1 7455 -1 7456 -1 7457 -1 7458 -1 7459 -1 7460 -1 7461 -1 7462 -1 7463 -1 7464 -1 7465 -1 7466 -1 7467 -1 7468 -1 7469 -1 7470 -1 7471 -1 7472 -1 7473 -1 7474 -1 7475 -1 7476 -1 7477 -1 7478 -1 7479 -1 7480 -1 7481 -1 7482 -1 7483 -1 7484 -1 7485 -1 7486 -1 7487 -1 7488 -1 7489 -1 7490 -1 7491 -1 7492 -1 7493 -1 7494 -1 7495 -1 7496 -1 7497 -1 7498 -1 7499 -1 7500 -1 7501 -1 7502 -1 7503 -1 7504 -1 7505 -1 7506 -1 7507 -1 7508 -1 7509 -1 7510 -1 7511 -1 7512 -1 7513 -1 7514 -1 7515 -1 7516 -1 7517 -1 7518 -1 7519 -1 7520 -1 7521 -1 7522 -1 7523 -1 7524 -1 7525 -1 7526 -1 7527 -1 7528 -1 7529 -1 7530 -1 7531 -1 7532 -1 7533 -1 7534 -1 7535 -1 7536 -1 7537 -1 7538 -1 7539 -1 7540 -1 7541 -1 7542 -1 7543 -1 7544 -1 7545 -1 7546 -1 7547 -1 7548 -1 7549 -1 7550 -1 7551 -1 7552 -1 7553 -1 7554 -1 7555 -1 7556 -1 7557 -1 7558 -1 7559 -1 7560 -1 7561 -1 7562 -1 7563 -1 7564 -1 7565 -1 7566 -1 7567 -1 7568 -1 7569 -1 7570 -1 7571 -1 7572 -1 7573 -1 7574 -1 7575 -1 7576 -1 7577 -1 7578 -1 7579 -1 7580 -1 7581 -1 7582 -1 7583 -1 7584 -1 7585 -1 7586 -1 7587 -1 7588 -1 7589 -1 7590 -1 7591 -1 7592 -1 7593 -1 7594 -1 7595 -1 7596 -1 7597 -1 7598 -1 7599 -1 7600 -1 7601 -1 7602 -1 7603 -1 7604 -1 7605 -1 7606 -1 7607 -1 7608 -1 7609 -1 7610 -1 7611 -1 7612 -1 7613 -1 7614 -1 7615 -1 7616 -1 7617 -1 7618 -1 7619 -1 7620 -1 7621 -1 7622 -1 7623 -1 7624 -1 7625 -1 7626 -1 7627 -1 7628 -1 7629 -1 7630 -1 7631 -1 7632 -1 7633 -1 7634 -1 7635 -1 7636 -1 7637 -1 7638 -1 7639 -1 7640 -1 7641 -1 7642 -1 7643 -1 7644 -1 7645 -1 7646 -1 7647 -1 7648 -1 7649 -1 7650 -1 7651 -1 7652 -1 7653 -1 7654 -1 7655 -1 7656 -1 7657 -1 7658 -1 7659 -1 7660 -1 7661 -1 7662 -1 7663 -1 7664 -1 7665 -1 7666 -1 7667 -1 7668 -1 7669 -1 7670 -1 7671 -1 7672 -1 7673 -1 7674 -1 7675 -1 7676 -1 7677 -1 7678 -1 7679 -1 7680 -1 7681 -1 7682 -1 7683 -1 7684 -1 7685 -1 7686 -1 7687 -1 7688 -1 7689 -1 7690 -1 7691 -1 7692 -1 7693 -1 7694 -1 7695 -1 7696 -1 7697 -1 7698 -1 7699 -1 7700 -1 7701 -1 7702 -1 7703 -1 7704 -1 7705 -1 7706 -1 7707 -1 7708 -1 7709 -1 7710 -1 7711 -1 7712 -1 7713 -1 7714 -1 7715 -1 7716 -1 7717 -1 7718 -1 7719 -1 7720 -1 7721 -1 7722 -1 7723 -1 7724 -1 7725 -1 7726 -1 7727 -1 7728 -1 7729 -1 7730 -1 7731 -1 7732 -1 7733 -1 7734 -1 7735 -1 7736 -1 7737 -1 7738 -1 7739 -1 7740 -1 7741 -1 7742 -1 7743 -1 7744 -1 7745 -1 7746 -1 7747 -1 7748 -1 7749 -1 7750 -1 7751 -1 7752 -1 7753 -1 7754 -1 7755 -1 7756 -1 7757 -1 7758 -1 7759 -1 7760 -1 7761 -1 7762 -1 7763 -1 7764 -1 7765 -1 7766 -1 7767 -1 7768 -1 7769 -1 7770 -1 7771 -1 7772 -1 7773 -1 7774 -1 7775 -1 7776 -1 7777 -1 7778 -1 7779 -1 7780 -1 7781 -1 7782 -1 7783 -1 7784 -1 7785 -1 7786 -1 7787 -1 7788 -1 7789 -1 7790 -1 7791 -1 7792 -1 7793 -1 7794 -1 7795 -1 7796 -1 7797 -1 7798 -1 7799 -1 7800 -1 7801 -1 7802 -1 7803 -1 7804 -1 7805 -1 7806 -1 7807 -1 7808 -1 7809 -1 7810 -1 7811 -1 7812 -1 7813 -1 7814 -1 7815 -1 7816 -1 7817 -1 7818 -1 7819 -1 7820 -1 7821 -1 7822 -1 7823 -1 7824 -1 7825 -1 7826 -1 7827 -1 7828 -1 7829 -1 7830 -1 7831 -1 7832 -1 7833 -1 7834 -1 7835 -1 7836 -1 7837 -1 7838 -1 7839 -1 7840 -1 7841 -1 7842 -1 7843 -1 7844 -1 7845 -1 7846 -1 7847 -1 7848 -1 7849 -1 7850 -1 7851 -1 7852 -1 7853 -1 7854 -1 7855 -1 7856 -1 7857 -1 7858 -1 7859 -1 7860 -1 7861 -1 7862 -1 7863 -1 7864 -1 7865 -1 7866 -1 7867 -1 7868 -1 7869 -1 7870 -1 7871 -1 7872 -1 7873 -1 7874 -1 7875 -1 7876 -1 7877 -1 7878 -1 7879 -1 7880 -1 7881 -1 7882 -1 7883 -1 7884 -1 7885 -1 7886 -1 7887 -1 7888 -1 7889 -1 7890 -1 7891 -1 7892 -1 7893 -1 7894 -1 7895 -1 7896 -1 7897 -1 7898 -1 7899 -1 7900 -1 7901 -1 7902 -1 7903 -1 7904 -1 7905 -1 7906 -1 7907 -1 7908 -1 7909 -1 7910 -1 7911 -1 7912 -1 7913 -1 7914 -1 7915 -1 7916 -1 7917 -1 7918 -1 7919 -1 7920 -1 7921 -1 7922 -1 7923 -1 7924 -1 7925 -1 7926 -1 7927 -1 7928 -1 7929 -1 7930 -1 7931 -1 7932 -1 7933 -1 7934 -1 7935 -1 7936 -1 7937 -1 7938 -1 7939 -1 7940 -1 7941 -1 7942 -1 7943 -1 7944 -1 7945 -1 7946 -1 7947 -1 7948 -1 7949 -1 7950 -1 7951 -1 7952 -1 7953 -1 7954 -1 7955 -1 7956 -1 7957 -1 7958 -1 7959 -1 7960 -1 7961 -1 7962 -1 7963 -1 7964 -1 7965 -1 7966 -1 7967 -1 7968 -1 7969 -1 7970 -1 7971 -1 7972 -1 7973 -1 7974 -1 7975 -1 7976 -1 7977 -1 7978 -1 7979 -1 7980 -1 7981 -1 7982 -1 7983 -1 7984 -1 7985 -1 7986 -1 7987 -1 7988 -1 7989 -1 7990 -1 7991 -1 7992 -1 7993 -1 7994 -1 7995 -1 7996 -1 7997 -1 7998 -1 7999 -1 8000 -1 8001 -1 8002 -1 8003 -1 8004 -1 8005 -1 8006 -1 8007 -1 8008 -1 8009 -1 8010 -1 8011 -1 8012 -1 8013 -1 8014 -1 8015 -1 8016 -1 8017 -1 8018 -1 8019 -1 8020 -1 8021 -1 8022 -1 8023 -1 8024 -1 8025 -1 8026 -1 8027 -1 8028 -1 8029 -1 8030 -1 8031 -1 8032 -1 8033 -1 8034 -1 8035 -1 8036 -1 8037 -1 8038 -1 8039 -1 8040 -1 8041 -1 8042 -1 8043 -1 8044 -1 8045 -1 8046 -1 8047 -1 8048 -1 8049 -1 8050 -1 8051 -1 8052 -1 8053 -1 8054 -1 8055 -1 8056 -1 8057 -1 8058 -1 8059 -1 8060 -1 8061 -1 8062 -1 8063 -1 8064 -1 8065 -1 8066 -1 8067 -1 8068 -1 8069 -1 8070 -1 8071 -1 8072 -1 8073 -1 8074 -1 8075 -1 8076 -1 8077 -1 8078 -1 8079 -1 8080 -1 8081 -1 8082 -1 8083 -1 8084 -1 8085 -1 8086 -1 8087 -1 8088 -1 8089 -1 8090 -1 8091 -1 8092 -1 8093 -1 8094 -1 8095 -1 8096 -1 8097 -1 8098 -1 8099 -1 8100 -1 8101 -1 8102 -1 8103 -1 8104 -1 8105 -1 8106 -1 8107 -1 8108 -1 8109 -1 8110 -1 8111 -1 8112 -1 8113 -1 8114 -1 8115 -1 8116 -1 8117 -1 8118 -1 8119 -1 8120 -1 8121 -1 8122 -1 8123 -1 8124 -1 8125 -1 8126 -1 8127 -1 8128 -1 8129 -1 8130 -1 8131 -1 8132 -1 8133 -1 8134 -1 8135 -1 8136 -1 8137 -1 8138 -1 8139 -1 8140 -1 8141 -1 8142 -1 8143 -1 8144 -1 8145 -1 8146 -1 8147 -1 8148 -1 8149 -1 8150 -1 8151 -1 8152 -1 8153 -1 8154 -1 8155 -1 8156 -1 8157 -1 8158 -1 8159 -1 8160 -1 8161 -1 8162 -1 8163 -1 8164 -1 8165 -1 8166 -1 8167 -1 8168 -1 8169 -1 8170 -1 8171 -1 8172 -1 8173 -1 8174 -1 8175 -1 8176 -1 8177 -1 8178 -1 8179 -1 8180 -1 8181 -1 8182 -1 8183 -1 8184 -1 8185 -1 8186 -1 8187 -1 8188 -1 8189 -1 8190 -1 8191 -1 8192 -1 8193 -1 8194 -1 8195 -1 8196 -1 8197 -1 8198 -1 8199 -1 8200 -1 8201 -1 8202 -1 8203 -1 8204 -1 8205 -1 8206 -1 8207 -1 8208 -1 8209 -1 8210 -1 8211 -1 8212 -1 8213 -1 8214 -1 8215 -1 8216 -1 8217 -1 8218 -1 8219 -1 8220 -1 8221 -1 8222 -1 8223 -1 8224 -1 8225 -1 8226 -1 8227 -1 8228 -1 8229 -1 8230 -1 8231 -1 8232 -1 8233 -1 8234 -1 8235 -1 8236 -1 8237 -1 8238 -1 8239 -1 8240 -1 8241 -1 8242 -1 8243 -1 8244 -1 8245 -1 8246 -1 8247 -1 8248 -1 8249 -1 8250 -1 8251 -1 8252 -1 8253 -1 8254 -1 8255 -1 8256 -1 8257 -1 8258 -1 8259 -1 8260 -1 8261 -1 8262 -1 8263 -1 8264 -1 8265 -1 8266 -1 8267 -1 8268 -1 8269 -1 8270 -1 8271 -1 8272 -1 8273 -1 8274 -1 8275 -1 8276 -1 8277 -1 8278 -1 8279 -1 8280 -1 8281 -1 8282 -1 8283 -1 8284 -1 8285 -1 8286 -1 8287 -1 8288 -1 8289 -1 8290 -1 8291 -1 8292 -1 8293 -1 8294 -1 8295 -1 8296 -1 8297 -1 8298 -1 8299 -1 8300 -1 8301 -1 8302 -1 8303 -1 8304 -1 8305 -1 8306 -1 8307 -1 8308 -1 8309 -1 8310 -1 8311 -1 8312 -1 8313 -1 8314 -1 8315 -1 8316 -1 8317 -1 8318 -1 8319 -1 8320 -1 8321 -1 8322 -1 8323 -1 8324 -1 8325 -1 8326 -1 8327 -1 8328 -1 8329 -1 8330 -1 8331 -1 8332 -1 8333 -1 8334 -1 8335 -1 8336 -1 8337 -1 8338 -1 8339 -1 8340 -1 8341 -1 8342 -1 8343 -1 8344 -1 8345 -1 8346 -1 8347 -1 8348 -1 8349 -1 8350 -1 8351 -1 8352 -1 8353 -1 8354 -1 8355 -1 8356 -1 8357 -1 8358 -1 8359 -1 8360 -1 8361 -1 8362 -1 8363 -1 8364 -1 8365 -1 8366 -1 8367 -1 8368 -1 8369 -1 8370 -1 8371 -1 8372 -1 8373 -1 8374 -1 8375 -1 8376 -1 8377 -1 8378 -1 8379 -1 8380 -1 8381 -1 8382 -1 8383 -1 8384 -1 8385 -1 8386 -1 8387 -1 8388 -1 8389 -1 8390 -1 8391 -1 8392 -1 8393 -1 8394 -1 8395 -1 8396 -1 8397 -1 8398 -1 8399 -1 8400 -1 8401 -1 8402 -1 8403 -1 8404 -1 8405 -1 8406 -1 8407 -1 8408 -1 8409 -1 8410 -1 8411 -1 8412 -1 8413 -1 8414 -1 8415 -1 8416 -1 8417 -1 8418 -1 8419 -1 8420 -1 8421 -1 8422 -1 8423 -1 8424 -1 8425 -1 8426 -1 8427 -1 8428 -1 8429 -1 8430 -1 8431 -1 8432 -1 8433 -1 8434 -1 8435 -1 8436 -1 8437 -1 8438 -1 8439 -1 8440 -1 8441 -1 8442 -1 8443 -1 8444 -1 8445 -1 8446 -1 8447 -1 8448 -1 8449 -1 8450 -1 8451 -1 8452 -1 8453 -1 8454 -1 8455 -1 8456 -1 8457 -1 8458 -1 8459 -1 8460 -1 8461 -1 8462 -1 8463 -1 8464 -1 8465 -1 8466 -1 8467 -1 8468 -1 8469 -1 8470 -1 8471 -1 8472 -1 8473 -1 8474 -1 8475 -1 8476 -1 8477 -1 8478 -1 8479 -1 8480 -1 8481 -1 8482 -1 8483 -1 8484 -1 8485 -1 8486 -1 8487 -1 8488 -1 8489 -1 8490 -1 8491 -1 8492 -1 8493 -1 8494 -1 8495 -1 8496 -1 8497 -1 8498 -1 8499 -1 8500 -1 8501 -1 8502 -1 8503 -1 8504 -1 8505 -1 8506 -1 8507 -1 8508 -1 8509 -1 8510 -1 8511 -1 8512 -1 8513 -1 8514 -1 8515 -1 8516 -1 8517 -1 8518 -1 8519 -1 8520 -1 8521 -1 8522 -1 8523 -1 8524 -1 8525 -1 8526 -1 8527 -1 8528 -1 8529 -1 8530 -1 8531 -1 8532 -1 8533 -1 8534 -1 8535 -1 8536 -1 8537 -1 8538 -1 8539 -1 8540 -1 8541 -1 8542 -1 8543 -1 8544 -1 8545 -1 8546 -1 8547 -1 8548 -1 8549 -1 8550 -1 8551 -1 8552 -1 8553 -1 8554 -1 8555 -1 8556 -1 8557 -1 8558 -1 8559 -1 8560 -1 8561 -1 8562 -1 8563 -1 8564 -1 8565 -1 8566 -1 8567 -1 8568 -1 8569 -1 8570 -1 8571 -1 8572 -1 8573 -1 8574 -1 8575 -1 8576 -1 8577 -1 8578 -1 8579 -1 8580 -1 8581 -1 8582 -1 8583 -1 8584 -1 8585 -1 8586 -1 8587 -1 8588 -1 8589 -1 8590 -1 8591 -1 8592 -1 8593 -1 8594 -1 8595 -1 8596 -1 8597 -1 8598 -1 8599 -1 8600 -1 8601 -1 8602 -1 8603 -1 8604 -1 8605 -1 8606 -1 8607 -1 8608 -1 8609 -1 8610 -1 8611 -1 8612 -1 8613 -1 8614 -1 8615 -1 8616 -1 8617 -1 8618 -1 8619 -1 8620 -1 8621 -1 8622 -1 8623 -1 8624 -1 8625 -1 8626 -1 8627 -1 8628 -1 8629 -1 8630 -1 8631 -1 8632 -1 8633 -1 8634 -1 8635 -1 8636 -1 8637 -1 8638 -1 8639 -1 8640 -1 8641 -1 8642 -1 8643 -1 8644 -1 8645 -1 8646 -1 8647 -1 8648 -1 8649 -1 8650 -1 8651 -1 8652 -1 8653 -1 8654 -1 8655 -1 8656 -1 8657 -1 8658 -1 8659 -1 8660 -1 8661 -1 8662 -1 8663 -1 8664 -1 8665 -1 8666 -1 8667 -1 8668 -1 8669 -1 8670 -1 8671 -1 8672 -1 8673 -1 8674 -1 8675 -1 8676 -1 8677 -1 8678 -1 8679 -1 8680 -1 8681 -1 8682 -1 8683 -1 8684 -1 8685 -1 8686 -1 8687 -1 8688 -1 8689 -1 8690 -1 8691 -1 8692 -1 8693 -1 8694 -1 8695 -1 8696 -1 8697 -1 8698 -1 8699 -1 8700 -1 8701 -1 8702 -1 8703 -1 8704 -1 8705 -1 8706 -1 8707 -1 8708 -1 8709 -1 8710 -1 8711 -1 8712 -1 8713 -1 8714 -1 8715 -1 8716 -1 8717 -1 8718 -1 8719 -1 8720 -1 8721 -1 8722 -1 8723 -1 8724 -1 8725 -1 8726 -1 8727 -1 8728 -1 8729 -1 8730 -1 8731 -1 8732 -1 8733 -1 8734 -1 8735 -1 8736 -1 8737 -1 8738 -1 8739 -1 8740 -1 8741 -1 8742 -1 8743 -1 8744 -1 8745 -1 8746 -1 8747 -1 8748 -1 8749 -1 8750 -1 8751 -1 8752 -1 8753 -1 8754 -1 8755 -1 8756 -1 8757 -1 8758 -1 8759 -1 8760 -1 8761 -1 8762 -1 8763 -1 8764 -1 8765 -1 8766 -1 8767 -1 8768 -1 8769 -1 8770 -1 8771 -1 8772 -1 8773 -1 8774 -1 8775 -1 8776 -1 8777 -1 8778 -1 8779 -1 8780 -1 8781 -1 8782 -1 8783 -1 8784 -1 8785 -1 8786 -1 8787 -1 8788 -1 8789 -1 8790 -1 8791 -1 8792 -1 8793 -1 8794 -1 8795 -1 8796 -1 8797 -1 8798 -1 8799 -1 8800 -1 8801 -1 8802 -1 8803 -1 8804 -1 8805 -1 8806 -1 8807 -1 8808 -1 8809 -1 8810 -1 8811 -1 8812 -1 8813 -1 8814 -1 8815 -1 8816 -1 8817 -1 8818 -1 8819 -1 8820 -1 8821 -1 8822 -1 8823 -1 8824 -1 8825 -1 8826 -1 8827 -1 8828 -1 8829 -1 8830 -1 8831 -1 8832 -1 8833 -1 8834 -1 8835 -1 8836 -1 8837 -1 8838 -1 8839 -1 8840 -1 8841 -1 8842 -1 8843 -1 8844 -1 8845 -1 8846 -1 8847 -1 8848 -1 8849 -1 8850 -1 8851 -1 8852 -1 8853 -1 8854 -1 8855 -1 8856 -1 8857 -1 8858 -1 8859 -1 8860 -1 8861 -1 8862 -1 8863 -1 8864 -1 8865 -1 8866 -1 8867 -1 8868 -1 8869 -1 8870 -1 8871 -1 8872 -1 8873 -1 8874 -1 8875 -1 8876 -1 8877 -1 8878 -1 8879 -1 8880 -1 8881 -1 8882 -1 8883 -1 8884 -1 8885 -1 8886 -1 8887 -1 8888 -1 8889 -1 8890 -1 8891 -1 8892 -1 8893 -1 8894 -1 8895 -1 8896 -1 8897 -1 8898 -1 8899 -1 8900 -1 8901 -1 8902 -1 8903 -1 8904 -1 8905 -1 8906 -1 8907 -1 8908 -1 8909 -1 8910 -1 8911 -1 8912 -1 8913 -1 8914 -1 8915 -1 8916 -1 8917 -1 8918 -1 8919 -1 8920 -1 8921 -1 8922 -1 8923 -1 8924 -1 8925 -1 8926 -1 8927 -1 8928 -1 8929 -1 8930 -1 8931 -1 8932 -1 8933 -1 8934 -1 8935 -1 8936 -1 8937 -1 8938 -1 8939 -1 8940 -1 8941 -1 8942 -1 8943 -1 8944 -1 8945 -1 8946 -1 8947 -1 8948 -1 8949 -1 8950 -1 8951 -1 8952 -1 8953 -1 8954 -1 8955 -1 8956 -1 8957 -1 8958 -1 8959 -1 8960 -1 8961 -1 8962 -1 8963 -1 8964 -1 8965 -1 8966 -1 8967 -1 8968 -1 8969 -1 8970 -1 8971 -1 8972 -1 8973 -1 8974 -1 8975 -1 8976 -1 8977 -1 8978 -1 8979 -1 8980 -1 8981 -1 8982 -1 8983 -1 8984 -1 8985 -1 8986 -1 8987 -1 8988 -1 8989 -1 8990 -1 8991 -1 8992 -1 8993 -1 8994 -1 8995 -1 8996 -1 8997 -1 8998 -1 8999 -1 9000 -1 9001 -1 9002 -1 9003 -1 9004 -1 9005 -1 9006 -1 9007 -1 9008 -1 9009 -1 9010 -1 9011 -1 9012 -1 9013 -1 9014 -1 9015 -1 9016 -1 9017 -1 9018 -1 9019 -1 9020 -1 9021 -1 9022 -1 9023 -1 9024 -1 9025 -1 9026 -1 9027 -1 9028 -1 9029 -1 9030 -1 9031 -1 9032 -1 9033 -1 9034 -1 9035 -1 9036 -1 9037 -1 9038 -1 9039 -1 9040 -1 9041 -1 9042 -1 9043 -1 9044 -1 9045 -1 9046 -1 9047 -1 9048 -1 9049 -1 9050 -1 9051 -1 9052 -1 9053 -1 9054 -1 9055 -1 9056 -1 9057 -1 9058 -1 9059 -1 9060 -1 9061 -1 9062 -1 9063 -1 9064 -1 9065 -1 9066 -1 9067 -1 9068 -1 9069 -1 9070 -1 9071 -1 9072 -1 9073 -1 9074 -1 9075 -1 9076 -1 9077 -1 9078 -1 9079 -1 9080 -1 9081 -1 9082 -1 9083 -1 9084 -1 9085 -1 9086 -1 9087 -1 9088 -1 9089 -1 9090 -1 9091 -1 9092 -1 9093 -1 9094 -1 9095 -1 9096 -1 9097 -1 9098 -1 9099 -1 9100 -1 9101 -1 9102 -1 9103 -1 9104 -1 9105 -1 9106 -1 9107 -1 9108 -1 9109 -1 9110 -1 9111 -1 9112 -1 9113 -1 9114 -1 9115 -1 9116 -1 9117 -1 9118 -1 9119 -1 9120 -1 9121 -1 9122 -1 9123 -1 9124 -1 9125 -1 9126 -1 9127 -1 9128 -1 9129 -1 9130 -1 9131 -1 9132 -1 9133 -1 9134 -1 9135 -1 9136 -1 9137 -1 9138 -1 9139 -1 9140 -1 9141 -1 9142 -1 9143 -1 9144 -1 9145 -1 9146 -1 9147 -1 9148 -1 9149 -1 9150 -1 9151 -1 9152 -1 9153 -1 9154 -1 9155 -1 9156 -1 9157 -1 9158 -1 9159 -1 9160 -1 9161 -1 9162 -1 9163 -1 9164 -1 9165 -1 9166 -1 9167 -1 9168 -1 9169 -1 9170 -1 9171 -1 9172 -1 9173 -1 9174 -1 9175 -1 9176 -1 9177 -1 9178 -1 9179 -1 9180 -1 9181 -1 9182 -1 9183 -1 9184 -1 9185 -1 9186 -1 9187 -1 9188 -1 9189 -1 9190 -1 9191 -1 9192 -1 9193 -1 9194 -1 9195 -1 9196 -1 9197 -1 9198 -1 9199 -1 9200 -1 9201 -1 9202 -1 9203 -1 9204 -1 9205 -1 9206 -1 9207 -1 9208 -1 9209 -1 9210 -1 9211 -1 9212 -1 9213 -1 9214 -1 9215 -1 9216 -1 9217 -1 9218 -1 9219 -1 9220 -1 9221 -1 9222 -1 9223 -1 9224 -1 9225 -1 9226 -1 9227 -1 9228 -1 9229 -1 9230 -1 9231 -1 9232 -1 9233 -1 9234 -1 9235 -1 9236 -1 9237 -1 9238 -1 9239 -1 9240 -1 9241 -1 9242 -1 9243 -1 9244 -1 9245 -1 9246 -1 9247 -1 9248 -1 9249 -1 9250 -1 9251 -1 9252 -1 9253 -1 9254 -1 9255 -1 9256 -1 9257 -1 9258 -1 9259 -1 9260 -1 9261 -1 9262 -1 9263 -1 9264 -1 9265 -1 9266 -1 9267 -1 9268 -1 9269 -1 9270 -1 9271 -1 9272 -1 9273 -1 9274 -1 9275 -1 9276 -1 9277 -1 9278 -1 9279 -1 9280 -1 9281 -1 9282 -1 9283 -1 9284 -1 9285 -1 9286 -1 9287 -1 9288 -1 9289 -1 9290 -1 9291 -1 9292 -1 9293 -1 9294 -1 9295 -1 9296 -1 9297 -1 9298 -1 9299 -1 9300 -1 9301 -1 9302 -1 9303 -1 9304 -1 9305 -1 9306 -1 9307 -1 9308 -1 9309 -1 9310 -1 9311 -1 9312 -1 9313 -1 9314 -1 9315 -1 9316 -1 9317 -1 9318 -1 9319 -1 9320 -1 9321 -1 9322 -1 9323 -1 9324 -1 9325 -1 9326 -1 9327 -1 9328 -1 9329 -1 9330 -1 9331 -1 9332 -1 9333 -1 9334 -1 9335 -1 9336 -1 9337 -1 9338 -1 9339 -1 9340 -1 9341 -1 9342 -1 9343 -1 9344 -1 9345 -1 9346 -1 9347 -1 9348 -1 9349 -1 9350 -1 9351 -1 9352 -1 9353 -1 9354 -1 9355 -1 9356 -1 9357 -1 9358 -1 9359 -1 9360 -1 9361 -1 9362 -1 9363 -1 9364 -1 9365 -1 9366 -1 9367 -1 9368 -1 9369 -1 9370 -1 9371 -1 9372 -1 9373 -1 9374 -1 9375 -1 9376 -1 9377 -1 9378 -1 9379 -1 9380 -1 9381 -1 9382 -1 9383 -1 9384 -1 9385 -1 9386 -1 9387 -1 9388 -1 9389 -1 9390 -1 9391 -1 9392 -1 9393 -1 9394 -1 9395 -1 9396 -1 9397 -1 9398 -1 9399 -1 9400 -1 9401 -1 9402 -1 9403 -1 9404 -1 9405 -1 9406 -1 9407 -1 9408 -1 9409 -1 9410 -1 9411 -1 9412 -1 9413 -1 9414 -1 9415 -1 9416 -1 9417 -1 9418 -1 9419 -1 9420 -1 9421 -1 9422 -1 9423 -1 9424 -1 9425 -1 9426 -1 9427 -1 9428 -1 9429 -1 9430 -1 9431 -1 9432 -1 9433 -1 9434 -1 9435 -1 9436 -1 9437 -1 9438 -1 9439 -1 9440 -1 9441 -1 9442 -1 9443 -1 9444 -1 9445 -1 9446 -1 9447 -1 9448 -1 9449 -1 9450 -1 9451 -1 9452 -1 9453 -1 9454 -1 9455 -1 9456 -1 9457 -1 9458 -1 9459 -1 9460 -1 9461 -1 9462 -1 9463 -1 9464 -1 9465 -1 9466 -1 9467 -1 9468 -1 9469 -1 9470 -1 9471 -1 9472 -1 9473 -1 9474 -1 9475 -1 9476 -1 9477 -1 9478 -1 9479 -1 9480 -1 9481 -1 9482 -1 9483 -1 9484 -1 9485 -1 9486 -1 9487 -1 9488 -1 9489 -1 9490 -1 9491 -1 9492 -1 9493 -1 9494 -1 9495 -1 9496 -1 9497 -1 9498 -1 9499 -1 9500 -1 9501 -1 9502 -1 9503 -1 9504 -1 9505 -1 9506 -1 9507 -1 9508 -1 9509 -1 9510 -1 9511 -1 9512 -1 9513 -1 9514 -1 9515 -1 9516 -1 9517 -1 9518 -1 9519 -1 9520 -1 9521 -1 9522 -1 9523 -1 9524 -1 9525 -1 9526 -1 9527 -1 9528 -1 9529 -1 9530 -1 9531 -1 9532 -1 9533 -1 9534 -1 9535 -1 9536 -1 9537 -1 9538 -1 9539 -1 9540 -1 9541 -1 9542 -1 9543 -1 9544 -1 9545 -1 9546 -1 9547 -1 9548 -1 9549 -1 9550 -1 9551 -1 9552 -1 9553 -1 9554 -1 9555 -1 9556 -1 9557 -1 9558 -1 9559 -1 9560 -1 9561 -1 9562 -1 9563 -1 9564 -1 9565 -1 9566 -1 9567 -1 9568 -1 9569 -1 9570 -1 9571 -1 9572 -1 9573 -1 9574 -1 9575 -1 9576 -1 9577 -1 9578 -1 9579 -1 9580 -1 9581 -1 9582 -1 9583 -1 9584 -1 9585 -1 9586 -1 9587 -1 9588 -1 9589 -1 9590 -1 9591 -1 9592 -1 9593 -1 9594 -1 9595 -1 9596 -1 9597 -1 9598 -1 9599 -1 9600 -1 9601 -1 9602 -1 9603 -1 9604 -1 9605 -1 9606 -1 9607 -1 9608 -1 9609 -1 9610 -1 9611 -1 9612 -1 9613 -1 9614 -1 9615 -1 9616 -1 9617 -1 9618 -1 9619 -1 9620 -1 9621 -1 9622 -1 9623 -1 9624 -1 9625 -1 9626 -1 9627 -1 9628 -1 9629 -1 9630 -1 9631 -1 9632 -1 9633 -1 9634 -1 9635 -1 9636 -1 9637 -1 9638 -1 9639 -1 9640 -1 9641 -1 9642 -1 9643 -1 9644 -1 9645 -1 9646 -1 9647 -1 9648 -1 9649 -1 9650 -1 9651 -1 9652 -1 9653 -1 9654 -1 9655 -1 9656 -1 9657 -1 9658 -1 9659 -1 9660 -1 9661 -1 9662 -1 9663 -1 9664 -1 9665 -1 9666 -1 9667 -1 9668 -1 9669 -1 9670 -1 9671 -1 9672 -1 9673 -1 9674 -1 9675 -1 9676 -1 9677 -1 9678 -1 9679 -1 9680 -1 9681 -1 9682 -1 9683 -1 9684 -1 9685 -1 9686 -1 9687 -1 9688 -1 9689 -1 9690 -1 9691 -1 9692 -1 9693 -1 9694 -1 9695 -1 9696 -1 9697 -1 9698 -1 9699 -1 9700 -1 9701 -1 9702 -1 9703 -1 9704 -1 9705 -1 9706 -1 9707 -1 9708 -1 9709 -1 9710 -1 9711 -1 9712 -1 9713 -1 9714 -1 9715 -1 9716 -1 9717 -1 9718 -1 9719 -1 9720 -1 9721 -1 9722 -1 9723 -1 9724 -1 9725 -1 9726 -1 9727 -1 9728 -1 9729 -1 9730 -1 9731 -1 9732 -1 9733 -1 9734 -1 9735 -1 9736 -1 9737 -1 9738 -1 9739 -1 9740 -1 9741 -1 9742 -1 9743 -1 9744 -1 9745 -1 9746 -1 9747 -1 9748 -1 9749 -1 9750 -1 9751 -1 9752 -1 9753 -1 9754 -1 9755 -1 9756 -1 9757 -1 9758 -1 9759 -1 9760 -1 9761 -1 9762 -1 9763 -1 9764 -1 9765 -1 9766 -1 9767 -1 9768 -1 9769 -1 9770 -1 9771 -1 9772 -1 9773 -1 9774 -1 9775 -1 9776 -1 9777 -1 9778 -1 9779 -1 9780 -1 9781 -1 9782 -1 9783 -1 9784 -1 9785 -1 9786 -1 9787 -1 9788 -1 9789 -1 9790 -1 9791 -1 9792 -1 9793 -1 9794 -1 9795 -1 9796 -1 9797 -1 9798 -1 9799 -1 9800 -1 9801 -1 9802 -1 9803 -1 9804 -1 9805 -1 9806 -1 9807 -1 9808 -1 9809 -1 9810 -1 9811 -1 9812 -1 9813 -1 9814 -1 9815 -1 9816 -1 9817 -1 9818 -1 9819 -1 9820 -1 9821 -1 9822 -1 9823 -1 9824 -1 9825 -1 9826 -1 9827 -1 9828 -1 9829 -1 9830 -1 9831 -1 9832 -1 9833 -1 9834 -1 9835 -1 9836 -1 9837 -1 9838 -1 9839 -1 9840 -1 9841 -1 9842 -1 9843 -1 9844 -1 9845 -1 9846 -1 9847 -1 9848 -1 9849 -1 9850 -1 9851 -1 9852 -1 9853 -1 9854 -1 9855 -1 9856 -1 9857 -1 9858 -1 9859 -1 9860 -1 9861 -1 9862 -1 9863 -1 9864 -1 9865 -1 9866 -1 9867 -1 9868 -1 9869 -1 9870 -1 9871 -1 9872 -1 9873 -1 9874 -1 9875 -1 9876 -1 9877 -1 9878 -1 9879 -1 9880 -1 9881 -1 9882 -1 9883 -1 9884 -1 9885 -1 9886 -1 9887 -1 9888 -1 9889 -1 9890 -1 9891 -1 9892 -1 9893 -1 9894 -1 9895 -1 9896 -1 9897 -1 9898 -1 9899 -1 9900 -1 9901 -1 9902 -1 9903 -1 9904 -1 9905 -1 9906 -1 9907 -1 9908 -1 9909 -1 9910 -1 9911 -1 9912 -1 9913 -1 9914 -1 9915 -1 9916 -1 9917 -1 9918 -1 9919 -1 9920 -1 9921 -1 9922 -1 9923 -1 9924 -1 9925 -1 9926 -1 9927 -1 9928 -1 9929 -1 9930 -1 9931 -1 9932 -1 9933 -1 9934 -1 9935 -1 9936 -1 9937 -1 9938 -1 9939 -1 9940 -1 9941 -1 9942 -1 9943 -1 9944 -1 9945 -1 9946 -1 9947 -1 9948 -1 9949 -1 9950 -1 9951 -1 9952 -1 9953 -1 9954 -1 9955 -1 9956 -1 9957 -1 9958 -1 9959 -1 9960 -1 9961 -1 9962 -1 9963 -1 9964 -1 9965 -1 9966 -1 9967 -1 9968 -1 9969 -1 9970 -1 9971 -1 9972 -1 9973 -1 9974 -1 9975 -1 9976 -1 9977 -1 9978 -1 9979 -1 9980 -1 9981 -1 9982 -1 9983 -1 9984 -1 9985 -1 9986 -1 9987 -1 9988 -1 9989 -1 9990 -1 9991 -1 9992 -1 9993 -1 9994 -1 9995 -1 9996 -1 9997 -1 9998 -1 9999 -1 10000 -1 10001 -1 10002 -1 10003 -1 10004 -1 10005 -1 10006 -1 10007 -1 10008 -1 10009 -1 10010 -1 10011 -1 10012 -1 10013 -1 10014 -1 10015 -1 10016 -1 10017 -1 10018 -1 10019 -1 10020 -1 10021 -1 10022 -1 10023 -1 10024 -1 10025 -1 10026 -1 10027 -1 10028 -1 10029 -1 10030 -1 10031 -1 10032 -1 10033 -1 10034 -1 10035 -1 10036 -1 10037 -1 10038 -1 10039 -1 10040 -1 10041 -1 10042 -1 10043 -1 10044 -1 10045 -1 10046 -1 10047 -1 10048 -1 10049 -1 10050 -1 10051 -1 10052 -1 10053 -1 10054 -1 10055 -1 10056 -1 10057 -1 10058 -1 10059 -1 10060 -1 10061 -1 10062 -1 10063 -1 10064 -1 10065 -1 10066 -1 10067 -1 10068 -1 10069 -1 10070 -1 10071 -1 10072 -1 10073 -1 10074 -1 10075 -1 10076 -1 10077 -1 10078 -1 10079 -1 10080 -1 10081 -1 10082 -1 10083 -1 10084 -1 10085 -1 10086 -1 10087 -1 10088 -1 10089 -1 10090 -1 10091 -1 10092 -1 10093 -1 10094 -1 10095 -1 10096 -1 10097 -1 10098 -1 10099 -1 10100 -1 10101 -1 10102 -1 10103 -1 10104 -1 10105 -1 10106 -1 10107 -1 10108 -1 10109 -1 10110 -1 10111 -1 10112 -1 10113 -1 10114 -1 10115 -1 10116 -1 10117 -1 10118 -1 10119 -1 10120 -1 10121 -1 10122 -1 10123 -1 10124 -1 10125 -1 10126 -1 10127 -1 10128 -1 10129 -1 10130 -1 10131 -1 10132 -1 10133 -1 10134 -1 10135 -1 10136 -1 10137 -1 10138 -1 10139 -1 10140 -1 10141 -1 10142 -1 10143 -1 10144 -1 10145 -1 10146 -1 10147 -1 10148 -1 10149 -1 10150 -1 10151 -1 10152 -1 10153 -1 10154 -1 10155 -1 10156 -1 10157 -1 10158 -1 10159 -1 10160 -1 10161 -1 10162 -1 10163 -1 10164 -1 10165 -1 10166 -1 10167 -1 10168 -1 10169 -1 10170 -1 10171 -1 10172 -1 10173 -1 10174 -1 10175 -1 10176 -1 10177 -1 10178 -1 10179 -1 10180 -1 10181 -1 10182 -1 10183 -1 10184 -1 10185 -1 10186 -1 10187 -1 10188 -1 10189 -1 10190 -1 10191 -1 10192 -1 10193 -1 10194 -1 10195 -1 10196 -1 10197 -1 10198 -1 10199 -1 10200 -1 10201 -1 10202 -1 10203 -1 10204 -1 10205 -1 10206 -1 10207 -1 10208 -1 10209 -1 10210 -1 10211 -1 10212 -1 10213 -1 10214 -1 10215 -1 10216 -1 10217 -1 10218 -1 10219 -1 10220 -1 10221 -1 10222 -1 10223 -1 10224 -1 10225 -1 10226 -1 10227 -1 10228 -1 10229 -1 10230 -1 10231 -1 10232 -1 10233 -1 10234 -1 10235 -1 10236 -1 10237 -1 10238 -1 10239 -1 10240 -1 10241 -1 10242 -1 10243 -1 10244 -1 10245 -1 10246 -1 10247 -1 10248 -1 10249 -1 10250 -1 10251 -1 10252 -1 10253 -1 10254 -1 10255 -1 10256 -1 10257 -1 10258 -1 10259 -1 10260 -1 10261 -1 10262 -1 10263 -1 10264 -1 10265 -1 10266 -1 10267 -1 10268 -1 10269 -1 10270 -1 10271 -1 10272 -1 10273 -1 10274 -1 10275 -1 10276 -1 10277 -1 10278 -1 10279 -1 10280 -1 10281 -1 10282 -1 10283 -1 10284 -1 10285 -1 10286 -1 10287 -1 10288 -1 10289 -1 10290 -1 10291 -1 10292 -1 10293 -1 10294 -1 10295 -1 10296 -1 10297 -1 10298 -1 10299 -1 10300 -1 10301 -1 10302 -1 10303 -1 10304 -1 10305 -1 10306 -1 10307 -1 10308 -1 10309 -1 10310 -1 10311 -1 10312 -1 10313 -1 10314 -1 10315 -1 10316 -1 10317 -1 10318 -1 10319 -1 10320 -1 10321 -1 10322 -1 10323 -1 10324 -1 10325 -1 10326 -1 10327 -1 10328 -1 10329 -1 10330 -1 10331 -1 10332 -1 10333 -1 10334 -1 10335 -1 10336 -1 10337 -1 10338 -1 10339 -1 10340 -1 10341 -1 10342 -1 10343 -1 10344 -1 10345 -1 10346 -1 10347 -1 10348 -1 10349 -1 10350 -1 10351 -1 10352 -1 10353 -1 10354 -1 10355 -1 10356 -1 10357 -1 10358 -1 10359 -1 10360 -1 10361 -1 10362 -1 10363 -1 10364 -1 10365 -1 10366 -1 10367 -1 10368 -1 10369 -1 10370 -1 10371 -1 10372 -1 10373 -1 10374 -1 10375 -1 10376 -1 10377 -1 10378 -1 10379 -1 10380 -1 10381 -1 10382 -1 10383 -1 10384 -1 10385 -1 10386 -1 10387 -1 10388 -1 10389 -1 10390 -1 10391 -1 10392 -1 10393 -1 10394 -1 10395 -1 10396 -1 10397 -1 10398 -1 10399 -1 10400 -1 10401 -1 10402 -1 10403 -1 10404 -1 10405 -1 10406 -1 10407 -1 10408 -1 10409 -1 10410 -1 10411 -1 10412 -1 10413 -1 10414 -1 10415 -1 10416 -1 10417 -1 10418 -1 10419 -1 10420 -1 10421 -1 10422 -1 10423 -1 10424 -1 10425 -1 10426 -1 10427 -1 10428 -1 10429 -1 10430 -1 10431 -1 10432 -1 10433 -1 10434 -1 10435 -1 10436 -1 10437 -1 10438 -1 10439 -1 10440 -1 10441 -1 10442 -1 10443 -1 10444 -1 10445 -1 10446 -1 10447 -1 10448 -1 10449 -1 10450 -1 10451 -1 10452 -1 10453 -1 10454 -1 10455 -1 10456 -1 10457 -1 10458 -1 10459 -1 10460 -1 10461 -1 10462 -1 10463 -1 10464 -1 10465 -1 10466 -1 10467 -1 10468 -1 10469 -1 10470 -1 10471 -1 10472 -1 10473 -1 10474 -1 10475 -1 10476 -1 10477 -1 10478 -1 10479 -1 10480 -1 10481 -1 10482 -1 10483 -1 10484 -1 10485 -1 10486 -1 10487 -1 10488 -1 10489 -1 10490 -1 10491 -1 10492 -1 10493 -1 10494 -1 10495 -1 10496 -1 10497 -1 10498 -1 10499 -1 10500 -1 10501 -1 10502 -1 10503 -1 10504 -1 10505 -1 10506 -1 10507 -1 10508 -1 10509 -1 10510 -1 10511 -1 10512 -1 10513 -1 10514 -1 10515 -1 10516 -1 10517 -1 10518 -1 10519 -1 10520 -1 10521 -1 10522 -1 10523 -1 10524 -1 10525 -1 10526 -1 10527 -1 10528 -1 10529 -1 10530 -1 10531 -1 10532 -1 10533 -1 10534 -1 10535 -1 10536 -1 10537 -1 10538 -1 10539 -1 10540 -1 10541 -1 10542 -1 10543 -1 10544 -1 10545 -1 10546 -1 10547 -1 10548 -1 10549 -1 10550 -1 10551 -1 10552 -1 10553 -1 10554 -1 10555 -1 10556 -1 10557 -1 10558 -1 10559 -1 10560 -1 10561 -1 10562 -1 10563 -1 10564 -1 10565 -1 10566 -1 10567 -1 10568 -1 10569 -1 10570 -1 10571 -1 10572 -1 10573 -1 10574 -1 10575 -1 10576 -1 10577 -1 10578 -1 10579 -1 10580 -1 10581 -1 10582 -1 10583 -1 10584 -1 10585 -1 10586 -1 10587 -1 10588 -1 10589 -1 10590 -1 10591 -1 10592 -1 10593 -1 10594 -1 10595 -1 10596 -1 10597 -1 10598 -1 10599 -1 10600 -1 10601 -1 10602 -1 10603 -1 10604 -1 10605 -1 10606 -1 10607 -1 10608 -1 10609 -1 10610 -1 10611 -1 10612 -1 10613 -1 10614 -1 10615 -1 10616 -1 10617 -1 10618 -1 10619 -1 10620 -1 10621 -1 10622 -1 10623 -1 10624 -1 10625 -1 10626 -1 10627 -1 10628 -1 10629 -1 10630 -1 10631 -1 10632 -1 10633 -1 10634 -1 10635 -1 10636 -1 10637 -1 10638 -1 10639 -1 10640 -1 10641 -1 10642 -1 10643 -1 10644 -1 10645 -1 10646 -1 10647 -1 10648 -1 10649 -1 10650 -1 10651 -1 10652 -1 10653 -1 10654 -1 10655 -1 10656 -1 10657 -1 10658 -1 10659 -1 10660 -1 10661 -1 10662 -1 10663 -1 10664 -1 10665 -1 10666 -1 10667 -1 10668 -1 10669 -1 10670 -1 10671 -1 10672 -1 10673 -1 10674 -1 10675 -1 10676 -1 10677 -1 10678 -1 10679 -1 10680 -1 10681 -1 10682 -1 10683 -1 10684 -1 10685 -1 10686 -1 10687 -1 10688 -1 10689 -1 10690 -1 10691 -1 10692 -1 10693 -1 10694 -1 10695 -1 10696 -1 10697 -1 10698 -1 10699 -1 10700 -1 10701 -1 10702 -1 10703 -1 10704 -1 10705 -1 10706 -1 10707 -1 10708 -1 10709 -1 10710 -1 10711 -1 10712 -1 10713 -1 10714 -1 10715 -1 10716 -1 10717 -1 10718 -1 10719 -1 10720 -1 10721 -1 10722 -1 10723 -1 10724 -1 10725 -1 10726 -1 10727 -1 10728 -1 10729 -1 10730 -1 10731 -1 10732 -1 10733 -1 10734 -1 10735 -1 10736 -1 10737 -1 10738 -1 10739 -1 10740 -1 10741 -1 10742 -1 10743 -1 10744 -1 10745 -1 10746 -1 10747 -1 10748 -1 10749 -1 10750 -1 10751 -1 10752 -1 10753 -1 10754 -1 10755 -1 10756 -1 10757 -1 10758 -1 10759 -1 10760 -1 10761 -1 10762 -1 10763 -1 10764 -1 10765 -1 10766 -1 10767 -1 10768 -1 10769 -1 10770 -1 10771 -1 10772 -1 10773 -1 10774 -1 10775 -1 10776 -1 10777 -1 10778 -1 10779 -1 10780 -1 10781 -1 10782 -1 10783 -1 10784 -1 10785 -1 10786 -1 10787 -1 10788 -1 10789 -1 10790 -1 10791 -1 10792 -1 10793 -1 10794 -1 10795 -1 10796 -1 10797 -1 10798 -1 10799 -1 10800 -1 10801 -1 10802 -1 10803 -1 10804 -1 10805 -1 10806 -1 10807 -1 10808 -1 10809 -1 10810 -1 10811 -1 10812 -1 10813 -1 10814 -1 10815 -1 10816 -1 10817 -1 10818 -1 10819 -1 10820 -1 10821 -1 10822 -1 10823 -1 10824 -1 10825 -1 10826 -1 10827 -1 10828 -1 10829 -1 10830 -1 10831 -1 10832 -1 10833 -1 10834 -1 10835 -1 10836 -1 10837 -1 10838 -1 10839 -1 10840 -1 10841 -1 10842 -1 10843 -1 10844 -1 10845 -1 10846 -1 10847 -1 10848 -1 10849 -1 10850 -1 10851 -1 10852 -1 10853 -1 10854 -1 10855 -1 10856 -1 10857 -1 10858 -1 10859 -1 10860 -1 10861 -1 10862 -1 10863 -1 10864 -1 10865 -1 10866 -1 10867 -1 10868 -1 10869 -1 10870 -1 10871 -1 10872 -1 10873 -1 10874 -1 10875 -1 10876 -1 10877 -1 10878 -1 10879 -1 10880 -1 10881 -1 10882 -1 10883 -1 10884 -1 10885 -1 10886 -1 10887 -1 10888 -1 10889 -1 10890 -1 10891 -1 10892 -1 10893 -1 10894 -1 10895 -1 10896 -1 10897 -1 10898 -1 10899 -1 10900 -1 10901 -1 10902 -1 10903 -1 10904 -1 10905 -1 10906 -1 10907 -1 10908 -1 10909 -1 10910 -1 10911 -1 10912 -1 10913 -1 10914 -1 10915 -1 10916 -1 10917 -1 10918 -1 10919 -1 10920 -1 10921 -1 10922 -1 10923 -1 10924 -1 10925 -1 10926 -1 10927 -1 10928 -1 10929 -1 10930 -1 10931 -1 10932 -1 10933 -1 10934 -1 10935 -1 10936 -1 10937 -1 10938 -1 10939 -1 10940 -1 10941 -1 10942 -1 10943 -1 10944 -1 10945 -1 10946 -1 10947 -1 10948 -1 10949 -1 10950 -1 10951 -1 10952 -1 10953 -1 10954 -1 10955 -1 10956 -1 10957 -1 10958 -1 10959 -1 10960 -1 10961 -1 10962 -1 10963 -1 10964 -1 10965 -1 10966 -1 10967 -1 10968 -1 10969 -1 10970 -1 10971 -1 10972 -1 10973 -1 10974 -1 10975 -1 10976 -1 10977 -1 10978 -1 10979 -1 10980 -1 10981 -1 10982 -1 10983 -1 10984 -1 10985 -1 10986 -1 10987 -1 10988 -1 10989 -1 10990 -1 10991 -1 10992 -1 10993 -1 10994 -1 10995 -1 10996 -1 10997 -1 10998 -1 10999 -1 11000 -1 11001 -1 11002 -1 11003 -1 11004 -1 11005 -1 11006 -1 11007 -1 11008 -1 11009 -1 11010 -1 11011 -1 11012 -1 11013 -1 11014 -1 11015 -1 11016 -1 11017 -1 11018 -1 11019 -1 11020 -1 11021 -1 11022 -1 11023 -1 11024 -1 11025 -1 11026 -1 11027 -1 11028 -1 11029 -1 11030 -1 11031 -1 11032 -1 11033 -1 11034 -1 11035 -1 11036 -1 11037 -1 11038 -1 11039 -1 11040 -1 11041 -1 11042 -1 11043 -1 11044 -1 11045 -1 11046 -1 11047 -1 11048 -1 11049 -1 11050 -1 11051 -1 11052 -1 11053 -1 11054 -1 11055 -1 11056 -1 11057 -1 11058 -1 11059 -1 11060 -1 11061 -1 11062 -1 11063 -1 11064 -1 11065 -1 11066 -1 11067 -1 11068 -1 11069 -1 11070 -1 11071 -1 11072 -1 11073 -1 11074 -1 11075 -1 11076 -1 11077 -1 11078 -1 11079 -1 11080 -1 11081 -1 11082 -1 11083 -1 11084 -1 11085 -1 11086 -1 11087 -1 11088 -1 11089 -1 11090 -1 11091 -1 11092 -1 11093 -1 11094 -1 11095 -1 11096 -1 11097 -1 11098 -1 11099 -1 11100 -1 11101 -1 11102 -1 11103 -1 11104 -1 11105 -1 11106 -1 11107 -1 11108 -1 11109 -1 11110 -1 11111 -1 11112 -1 11113 -1 11114 -1 11115 -1 11116 -1 11117 -1 11118 -1 11119 -1 11120 -1 11121 -1 11122 -1 11123 -1 11124 -1 11125 -1 11126 -1 11127 -1 11128 -1 11129 -1 11130 -1 11131 -1 11132 -1 11133 -1 11134 -1 11135 -1 11136 -1 11137 -1 11138 -1 11139 -1 11140 -1 11141 -1 11142 -1 11143 -1 11144 -1 11145 -1 11146 -1 11147 -1 11148 -1 11149 -1 11150 -1 11151 -1 11152 -1 11153 -1 11154 -1 11155 -1 11156 -1 11157 -1 11158 -1 11159 -1 11160 -1 11161 -1 11162 -1 11163 -1 11164 -1 11165 -1 11166 -1 11167 -1 11168 -1 11169 -1 11170 -1 11171 -1 11172 -1 11173 -1 11174 -1 11175 -1 11176 -1 11177 -1 11178 -1 11179 -1 11180 -1 11181 -1 11182 -1 11183 -1 11184 -1 11185 -1 11186 -1 11187 -1 11188 -1 11189 -1 11190 -1 11191 -1 11192 -1 11193 -1 11194 -1 11195 -1 11196 -1 11197 -1 11198 -1 11199 -1 11200 -1 11201 -1 11202 -1 11203 -1 11204 -1 11205 -1 11206 -1 11207 -1 11208 -1 11209 -1 11210 -1 11211 -1 11212 -1 11213 -1 11214 -1 11215 -1 11216 -1 11217 -1 11218 -1 11219 -1 11220 -1 11221 -1 11222 -1 11223 -1 11224 -1 11225 -1 11226 -1 11227 -1 11228 -1 11229 -1 11230 -1 11231 -1 11232 -1 11233 -1 11234 -1 11235 -1 11236 -1 11237 -1 11238 -1 11239 -1 11240 -1 11241 -1 11242 -1 11243 -1 11244 -1 11245 -1 11246 -1 11247 -1 11248 -1 11249 -1 11250 -1 11251 -1 11252 -1 11253 -1 11254 -1 11255 -1 11256 -1 11257 -1 11258 -1 11259 -1 11260 -1 11261 -1 11262 -1 11263 -1 11264 -1 11265 -1 11266 -1 11267 -1 11268 -1 11269 -1 11270 -1 11271 -1 11272 -1 11273 -1 11274 -1 11275 -1 11276 -1 11277 -1 11278 -1 11279 -1 11280 -1 11281 -1 11282 -1 11283 -1 11284 -1 11285 -1 11286 -1 11287 -1 11288 -1 11289 -1 11290 -1 11291 -1 11292 -1 11293 -1 11294 -1 11295 -1 11296 -1 11297 -1 11298 -1 11299 -1 11300 -1 11301 -1 11302 -1 11303 -1 11304 -1 11305 -1 11306 -1 11307 -1 11308 -1 11309 -1 11310 -1 11311 -1 11312 -1 11313 -1 11314 -1 11315 -1 11316 -1 11317 -1 11318 -1 11319 -1 11320 -1 11321 -1 11322 -1 11323 -1 11324 -1 11325 -1 11326 -1 11327 -1 11328 -1 11329 -1 11330 -1 11331 -1 11332 -1 11333 -1 11334 -1 11335 -1 11336 -1 11337 -1 11338 -1 11339 -1 11340 -1 11341 -1 11342 -1 11343 -1 11344 -1 11345 -1 11346 -1 11347 -1 11348 -1 11349 -1 11350 -1 11351 -1 11352 -1 11353 -1 11354 -1 11355 -1 11356 -1 11357 -1 11358 -1 11359 -1 11360 -1 11361 -1 11362 -1 11363 -1 11364 -1 11365 -1 11366 -1 11367 -1 11368 -1 11369 -1 11370 -1 11371 -1 11372 -1 11373 -1 11374 -1 11375 -1 11376 -1 11377 -1 11378 -1 11379 -1 11380 -1 11381 -1 11382 -1 11383 -1 11384 -1 11385 -1 11386 -1 11387 -1 11388 -1 11389 -1 11390 -1 11391 -1 11392 -1 11393 -1 11394 -1 11395 -1 11396 -1 11397 -1 11398 -1 11399 -1 11400 -1 11401 -1 11402 -1 11403 -1 11404 -1 11405 -1 11406 -1 11407 -1 11408 -1 11409 -1 11410 -1 11411 -1 11412 -1 11413 -1 11414 -1 11415 -1 11416 -1 11417 -1 11418 -1 11419 -1 11420 -1 11421 -1 11422 -1 11423 -1 11424 -1 11425 -1 11426 -1 11427 -1 11428 -1 11429 -1 11430 -1 11431 -1 11432 -1 11433 -1 11434 -1 11435 -1 11436 -1 11437 -1 11438 -1 11439 -1 11440 -1 11441 -1 11442 -1 11443 -1 11444 -1 11445 -1 11446 -1 11447 -1 11448 -1 11449 -1 11450 -1 11451 -1 11452 -1 11453 -1 11454 -1 11455 -1 11456 -1 11457 -1 11458 -1 11459 -1 11460 -1 11461 -1 11462 -1 11463 -1 11464 -1 11465 -1 11466 -1 11467 -1 11468 -1 11469 -1 11470 -1 11471 -1 11472 -1 11473 -1 11474 -1 11475 -1 11476 -1 11477 -1 11478 -1 11479 -1 11480 -1 11481 -1 11482 -1 11483 -1 11484 -1 11485 -1 11486 -1 11487 -1 11488 -1 11489 -1 11490 -1 11491 -1 11492 -1 11493 -1 11494 -1 11495 -1 11496 -1 11497 -1 11498 -1 11499 -1 11500 -1 11501 -1 11502 -1 11503 -1 11504 -1 11505 -1 11506 -1 11507 -1 11508 -1 11509 -1 11510 -1 11511 -1 11512 -1 11513 -1 11514 -1 11515 -1 11516 -1 11517 -1 11518 -1 11519 -1 11520 -1 11521 -1 11522 -1 11523 -1 11524 -1 11525 -1 11526 -1 11527 -1 11528 -1 11529 -1 11530 -1 11531 -1 11532 -1 11533 -1 11534 -1 11535 -1 11536 -1 11537 -1 11538 -1 11539 -1 11540 -1 11541 -1 11542 -1 11543 -1 11544 -1 11545 -1 11546 -1 11547 -1 11548 -1 11549 -1 11550 -1 11551 -1 11552 -1 11553 -1 11554 -1 11555 -1 11556 -1 11557 -1 11558 -1 11559 -1 11560 -1 11561 -1 11562 -1 11563 -1 11564 -1 11565 -1 11566 -1 11567 -1 11568 -1 11569 -1 11570 -1 11571 -1 11572 -1 11573 -1 11574 -1 11575 -1 11576 -1 11577 -1 11578 -1 11579 -1 11580 -1 11581 -1 11582 -1 11583 -1 11584 -1 11585 -1 11586 -1 11587 -1 11588 -1 11589 -1 11590 -1 11591 -1 11592 -1 11593 -1 11594 -1 11595 -1 11596 -1 11597 -1 11598 -1 11599 -1 11600 -1 11601 -1 11602 -1 11603 -1 11604 -1 11605 -1 11606 -1 11607 -1 11608 -1 11609 -1 11610 -1 11611 -1 11612 -1 11613 -1 11614 -1 11615 -1 11616 -1 11617 -1 11618 -1 11619 -1 11620 -1 11621 -1 11622 -1 11623 -1 11624 -1 11625 -1 11626 -1 11627 -1 11628 -1 11629 -1 11630 -1 11631 -1 11632 -1 11633 -1 11634 -1 11635 -1 11636 -1 11637 -1 11638 -1 11639 -1 11640 -1 11641 -1 11642 -1 11643 -1 11644 -1 11645 -1 11646 -1 11647 -1 11648 -1 11649 -1 11650 -1 11651 -1 11652 -1 11653 -1 11654 -1 11655 -1 11656 -1 11657 -1 11658 -1 11659 -1 11660 -1 11661 -1 11662 -1 11663 -1 11664 -1 11665 -1 11666 -1 11667 -1 11668 -1 11669 -1 11670 -1 11671 -1 11672 -1 11673 -1 11674 -1 11675 -1 11676 -1 11677 -1 11678 -1 11679 -1 11680 -1 11681 -1 11682 -1 11683 -1 11684 -1 11685 -1 11686 -1 11687 -1 11688 -1 11689 -1 11690 -1 11691 -1 11692 -1 11693 -1 11694 -1 11695 -1 11696 -1 11697 -1 11698 -1 11699 -1 11700 -1 11701 -1 11702 -1 11703 -1 11704 -1 11705 -1 11706 -1 11707 -1 11708 -1 11709 -1 11710 -1 11711 -1 11712 -1 11713 -1 11714 -1 11715 -1 11716 -1 11717 -1 11718 -1 11719 -1 11720 -1 11721 -1 11722 -1 11723 -1 11724 -1 11725 -1 11726 -1 11727 -1 11728 -1 11729 -1 11730 -1 11731 -1 11732 -1 11733 -1 11734 -1 11735 -1 11736 -1 11737 -1 11738 -1 11739 -1 11740 -1 11741 -1 11742 -1 11743 -1 11744 -1 11745 -1 11746 -1 11747 -1 11748 -1 11749 -1 11750 -1 11751 -1 11752 -1 11753 -1 11754 -1 11755 -1 11756 -1 11757 -1 11758 -1 11759 -1 11760 -1 11761 -1 11762 -1 11763 -1 11764 -1 11765 -1 11766 -1 11767 -1 11768 -1 11769 -1 11770 -1 11771 -1 11772 -1 11773 -1 11774 -1 11775 -1 11776 -1 11777 -1 11778 -1 11779 -1 11780 -1 11781 -1 11782 -1 11783 -1 11784 -1 11785 -1 11786 -1 11787 -1 11788 -1 11789 -1 11790 -1 11791 -1 11792 -1 11793 -1 11794 -1 11795 -1 11796 -1 11797 -1 11798 -1 11799 -1 11800 -1 11801 -1 11802 -1 11803 -1 11804 -1 11805 -1 11806 -1 11807 -1 11808 -1 11809 -1 11810 -1 11811 -1 11812 -1 11813 -1 11814 -1 11815 -1 11816 -1 11817 -1 11818 -1 11819 -1 11820 -1 11821 -1 11822 -1 11823 -1 11824 -1 11825 -1 11826 -1 11827 -1 11828 -1 11829 -1 11830 -1 11831 -1 11832 -1 11833 -1 11834 -1 11835 -1 11836 -1 11837 -1 11838 -1 11839 -1 11840 -1 11841 -1 11842 -1 11843 -1 11844 -1 11845 -1 11846 -1 11847 -1 11848 -1 11849 -1 11850 -1 11851 -1 11852 -1 11853 -1 11854 -1 11855 -1 11856 -1 11857 -1 11858 -1 11859 -1 11860 -1 11861 -1 11862 -1 11863 -1 11864 -1 11865 -1 11866 -1 11867 -1 11868 -1 11869 -1 11870 -1 11871 -1 11872 -1 11873 -1 11874 -1 11875 -1 11876 -1 11877 -1 11878 -1 11879 -1 11880 -1 11881 -1 11882 -1 11883 -1 11884 -1 11885 -1 11886 -1 11887 -1 11888 -1 11889 -1 11890 -1 11891 -1 11892 -1 11893 -1 11894 -1 11895 -1 11896 -1 11897 -1 11898 -1 11899 -1 11900 -1 11901 -1 11902 -1 11903 -1 11904 -1 11905 -1 11906 -1 11907 -1 11908 -1 11909 -1 11910 -1 11911 -1 11912 -1 11913 -1 11914 -1 11915 -1 11916 -1 11917 -1 11918 -1 11919 -1 11920 -1 11921 -1 11922 -1 11923 -1 11924 -1 11925 -1 11926 -1 11927 -1 11928 -1 11929 -1 11930 -1 11931 -1 11932 -1 11933 -1 11934 -1 11935 -1 11936 -1 11937 -1 11938 -1 11939 -1 11940 -1 11941 -1 11942 -1 11943 -1 11944 -1 11945 -1 11946 -1 11947 -1 11948 -1 11949 -1 11950 -1 11951 -1 11952 -1 11953 -1 11954 -1 11955 -1 11956 -1 11957 -1 11958 -1 11959 -1 11960 -1 11961 -1 11962 -1 11963 -1 11964 -1 11965 -1 11966 -1 11967 -1 11968 -1 11969 -1 11970 -1 11971 -1 11972 -1 11973 -1 11974 -1 11975 -1 11976 -1 11977 -1 11978 -1 11979 -1 11980 -1 11981 -1 11982 -1 11983 -1 11984 -1 11985 -1 11986 -1 11987 -1 11988 -1 11989 -1 11990 -1 11991 -1 11992 -1 11993 -1 11994 -1 11995 -1 11996 -1 11997 -1 11998 -1 11999 -1 12000 -1 12001 -1 12002 -1 12003 -1 12004 -1 12005 -1 12006 -1 12007 -1 12008 -1 12009 -1 12010 -1 12011 -1 12012 -1 12013 -1 12014 -1 12015 -1 12016 -1 12017 -1 12018 -1 12019 -1 12020 -1 12021 -1 12022 -1 12023 -1 12024 -1 12025 -1 12026 -1 12027 -1 12028 -1 12029 -1 12030 -1 12031 -1 12032 -1 12033 -1 12034 -1 12035 -1 12036 -1 12037 -1 12038 -1 12039 -1 12040 -1 12041 -1 12042 -1 12043 -1 12044 -1 12045 -1 12046 -1 12047 -1 12048 -1 12049 -1 12050 -1 12051 -1 12052 -1 12053 -1 12054 -1 12055 -1 12056 -1 12057 -1 12058 -1 12059 -1 12060 -1 12061 -1 12062 -1 12063 -1 12064 -1 12065 -1 12066 -1 12067 -1 12068 -1 12069 -1 12070 -1 12071 -1 12072 -1 12073 -1 12074 -1 12075 -1 12076 -1 12077 -1 12078 -1 12079 -1 12080 -1 12081 -1 12082 -1 12083 -1 12084 -1 12085 -1 12086 -1 12087 -1 12088 -1 12089 -1 12090 -1 12091 -1 12092 -1 12093 -1 12094 -1 12095 -1 12096 -1 12097 -1 12098 -1 12099 -1 12100 -1 12101 -1 12102 -1 12103 -1 12104 -1 12105 -1 12106 -1 12107 -1 12108 -1 12109 -1 12110 -1 12111 -1 12112 -1 12113 -1 12114 -1 12115 -1 12116 -1 12117 -1 12118 -1 12119 -1 12120 -1 12121 -1 12122 -1 12123 -1 12124 -1 12125 -1 12126 -1 12127 -1 12128 -1 12129 -1 12130 -1 12131 -1 12132 -1 12133 -1 12134 -1 12135 -1 12136 -1 12137 -1 12138 -1 12139 -1 12140 -1 12141 -1 12142 -1 12143 -1 12144 -1 12145 -1 12146 -1 12147 -1 12148 -1 12149 -1 12150 -1 12151 -1 12152 -1 12153 -1 12154 -1 12155 -1 12156 -1 12157 -1 12158 -1 12159 -1 12160 -1 12161 -1 12162 -1 12163 -1 12164 -1 12165 -1 12166 -1 12167 -1 12168 -1 12169 -1 12170 -1 12171 -1 12172 -1 12173 -1 12174 -1 12175 -1 12176 -1 12177 -1 12178 -1 12179 -1 12180 -1 12181 -1 12182 -1 12183 -1 12184 -1 12185 -1 12186 -1 12187 -1 12188 -1 12189 -1 12190 -1 12191 -1 12192 -1 12193 -1 12194 -1 12195 -1 12196 -1 12197 -1 12198 -1 12199 -1 12200 -1 12201 -1 12202 -1 12203 -1 12204 -1 12205 -1 12206 -1 12207 -1 12208 -1 12209 -1 12210 -1 12211 -1 12212 -1 12213 -1 12214 -1 12215 -1 12216 -1 12217 -1 12218 -1 12219 -1 12220 -1 12221 -1 12222 -1 12223 -1 12224 -1 12225 -1 12226 -1 12227 -1 12228 -1 12229 -1 12230 -1 12231 -1 12232 -1 12233 -1 12234 -1 12235 -1 12236 -1 12237 -1 12238 -1 12239 -1 12240 -1 12241 -1 12242 -1 12243 -1 12244 -1 12245 -1 12246 -1 12247 -1 12248 -1 12249 -1 12250 -1 12251 -1 12252 -1 12253 -1 12254 -1 12255 -1 12256 -1 12257 -1 12258 -1 12259 -1 12260 -1 12261 -1 12262 -1 12263 -1 12264 -1 12265 -1 12266 -1 12267 -1 12268 -1 12269 -1 12270 -1 12271 -1 12272 -1 12273 -1 12274 -1 12275 -1 12276 -1 12277 -1 12278 -1 12279 -1 12280 -1 12281 -1 12282 -1 12283 -1 12284 -1 12285 -1 12286 -1 12287 -1 12288 -1 12289 -1 12290 -1 12291 -1 12292 -1 12293 -1 12294 -1 12295 -1 12296 -1 12297 -1 12298 -1 12299 -1 12300 -1 12301 -1 12302 -1 12303 -1 12304 -1 12305 -1 12306 -1 12307 -1 12308 -1 12309 -1 12310 -1 12311 -1 12312 -1 12313 -1 12314 -1 12315 -1 12316 -1 12317 -1 12318 -1 12319 -1 12320 -1 12321 -1 12322 -1 12323 -1 12324 -1 12325 -1 12326 -1 12327 -1 12328 -1 12329 -1 12330 -1 12331 -1 12332 -1 12333 -1 12334 -1 12335 -1 12336 -1 12337 -1 12338 -1 12339 -1 12340 -1 12341 -1 12342 -1 12343 -1 12344 -1 12345 -1 12346 -1 12347 -1 12348 -1 12349 -1 12350 -1 12351 -1 12352 -1 12353 -1 12354 -1 12355 -1 12356 -1 12357 -1 12358 -1 12359 -1 12360 -1 12361 -1 12362 -1 12363 -1 12364 -1 12365 -1 12366 -1 12367 -1 12368 -1 12369 -1 12370 -1 12371 -1 12372 -1 12373 -1 12374 -1 12375 -1 12376 -1 12377 -1 12378 -1 12379 -1 12380 -1 12381 -1 12382 -1 12383 -1 12384 -1 12385 -1 12386 -1 12387 -1 12388 -1 12389 -1 12390 -1 12391 -1 12392 -1 12393 -1 12394 -1 12395 -1 12396 -1 12397 -1 12398 -1 12399 -1 12400 -1 12401 -1 12402 -1 12403 -1 12404 -1 12405 -1 12406 -1 12407 -1 12408 -1 12409 -1 12410 -1 12411 -1 12412 -1 12413 -1 12414 -1 12415 -1 12416 -1 12417 -1 12418 -1 12419 -1 12420 -1 12421 -1 12422 -1 12423 -1 12424 -1 12425 -1 12426 -1 12427 -1 12428 -1 12429 -1 12430 -1 12431 -1 12432 -1 12433 -1 12434 -1 12435 -1 12436 -1 12437 -1 12438 -1 12439 -1 12440 -1 12441 -1 12442 -1 12443 -1 12444 -1 12445 -1 12446 -1 12447 -1 12448 -1 12449 -1 12450 -1 12451 -1 12452 -1 12453 -1 12454 -1 12455 -1 12456 -1 12457 -1 12458 -1 12459 -1 12460 -1 12461 -1 12462 -1 12463 -1 12464 -1 12465 -1 12466 -1 12467 -1 12468 -1 12469 -1 12470 -1 12471 -1 12472 -1 12473 -1 12474 -1 12475 -1 12476 -1 12477 -1 12478 -1 12479 -1 12480 -1 12481 -1 12482 -1 12483 -1 12484 -1 12485 -1 12486 -1 12487 -1 12488 -1 12489 -1 12490 -1 12491 -1 12492 -1 12493 -1 12494 -1 12495 -1 12496 -1 12497 -1 12498 -1 12499 -1 12500 -1 12501 -1 12502 -1 12503 -1 12504 -1 12505 -1 12506 -1 12507 -1 12508 -1 12509 -1 12510 -1 12511 -1 12512 -1 12513 -1 12514 -1 12515 -1 12516 -1 12517 -1 12518 -1 12519 -1 12520 -1 12521 -1 12522 -1 12523 -1 12524 -1 12525 -1 12526 -1 12527 -1 12528 -1 12529 -1 12530 -1 12531 -1 12532 -1 12533 -1 12534 -1 12535 -1 12536 -1 12537 -1 12538 -1 12539 -1 12540 -1 12541 -1 12542 -1 12543 -1 12544 -1 12545 -1 12546 -1 12547 -1 12548 -1 12549 -1 12550 -1 12551 -1 12552 -1 12553 -1 12554 -1 12555 -1 12556 -1 12557 -1 12558 -1 12559 -1 12560 -1 12561 -1 12562 -1 12563 -1 12564 -1 12565 -1 12566 -1 12567 -1 12568 -1 12569 -1 12570 -1 12571 -1 12572 -1 12573 -1 12574 -1 12575 -1 12576 -1 12577 -1 12578 -1 12579 -1 12580 -1 12581 -1 12582 -1 12583 -1 12584 -1 12585 -1 12586 -1 12587 -1 12588 -1 12589 -1 12590 -1 12591 -1 12592 -1 12593 -1 12594 -1 12595 -1 12596 -1 12597 -1 12598 -1 12599 -1 12600 -1 12601 -1 12602 -1 12603 -1 12604 -1 12605 -1 12606 -1 12607 -1 12608 -1 12609 -1 12610 -1 12611 -1 12612 -1 12613 -1 12614 -1 12615 -1 12616 -1 12617 -1 12618 -1 12619 -1 12620 -1 12621 -1 12622 -1 12623 -1 12624 -1 12625 -1 12626 -1 12627 -1 12628 -1 12629 -1 12630 -1 12631 -1 12632 -1 12633 -1 12634 -1 12635 -1 12636 -1 12637 -1 12638 -1 12639 -1 12640 -1 12641 -1 12642 -1 12643 -1 12644 -1 12645 -1 12646 -1 12647 -1 12648 -1 12649 -1 12650 -1 12651 -1 12652 -1 12653 -1 12654 -1 12655 -1 12656 -1 12657 -1 12658 -1 12659 -1 12660 -1 12661 -1 12662 -1 12663 -1 12664 -1 12665 -1 12666 -1 12667 -1 12668 -1 12669 -1 12670 -1 12671 -1 12672 -1 12673 -1 12674 -1 12675 -1 12676 -1 12677 -1 12678 -1 12679 -1 12680 -1 12681 -1 12682 -1 12683 -1 12684 -1 12685 -1 12686 -1 12687 -1 12688 -1 12689 -1 12690 -1 12691 -1 12692 -1 12693 -1 12694 -1 12695 -1 12696 -1 12697 -1 12698 -1 12699 -1 12700 -1 12701 -1 12702 -1 12703 -1 12704 -1 12705 -1 12706 -1 12707 -1 12708 -1 12709 -1 12710 -1 12711 -1 12712 -1 12713 -1 12714 -1 12715 -1 12716 -1 12717 -1 12718 -1 12719 -1 12720 -1 12721 -1 12722 -1 12723 -1 12724 -1 12725 -1 12726 -1 12727 -1 12728 -1 12729 -1 12730 -1 12731 -1 12732 -1 12733 -1 12734 -1 12735 -1 12736 -1 12737 -1 12738 -1 12739 -1 12740 -1 12741 -1 12742 -1 12743 -1 12744 -1 12745 -1 12746 -1 12747 -1 12748 -1 12749 -1 12750 -1 12751 -1 12752 -1 12753 -1 12754 -1 12755 -1 12756 -1 12757 -1 12758 -1 12759 -1 12760 -1 12761 -1 12762 -1 12763 -1 12764 -1 12765 -1 12766 -1 12767 -1 12768 -1 12769 -1 12770 -1 12771 -1 12772 -1 12773 -1 12774 -1 12775 -1 12776 -1 12777 -1 12778 -1 12779 -1 12780 -1 12781 -1 12782 -1 12783 -1 12784 -1 12785 -1 12786 -1 12787 -1 12788 -1 12789 -1 12790 -1 12791 -1 12792 -1 12793 -1 12794 -1 12795 -1 12796 -1 12797 -1 12798 -1 12799 -1 12800 -1 12801 -1 12802 -1 12803 -1 12804 -1 12805 -1 12806 -1 12807 -1 12808 -1 12809 -1 12810 -1 12811 -1 12812 -1 12813 -1 12814 -1 12815 -1 12816 -1 12817 -1 12818 -1 12819 -1 12820 -1 12821 -1 12822 -1 12823 -1 12824 -1 12825 -1 12826 -1 12827 -1 12828 -1 12829 -1 12830 -1 12831 -1 12832 -1 12833 -1 12834 -1 12835 -1 12836 -1 12837 -1 12838 -1 12839 -1 12840 -1 12841 -1 12842 -1 12843 -1 12844 -1 12845 -1 12846 -1 12847 -1 12848 -1 12849 -1 12850 -1 12851 -1 12852 -1 12853 -1 12854 -1 12855 -1 12856 -1 12857 -1 12858 -1 12859 -1 12860 -1 12861 -1 12862 -1 12863 -1 12864 -1 12865 -1 12866 -1 12867 -1 12868 -1 12869 -1 12870 -1 12871 -1 12872 -1 12873 -1 12874 -1 12875 -1 12876 -1 12877 -1 12878 -1 12879 -1 12880 -1 12881 -1 12882 -1 12883 -1 12884 -1 12885 -1 12886 -1 12887 -1 12888 -1 12889 -1 12890 -1 12891 -1 12892 -1 12893 -1 12894 -1 12895 -1 12896 -1 12897 -1 12898 -1 12899 -1 12900 -1 12901 -1 12902 -1 12903 -1 12904 -1 12905 -1 12906 -1 12907 -1 12908 -1 12909 -1 12910 -1 12911 -1 12912 -1 12913 -1 12914 -1 12915 -1 12916 -1 12917 -1 12918 -1 12919 -1 12920 -1 12921 -1 12922 -1 12923 -1 12924 -1 12925 -1 12926 -1 12927 -1 12928 -1 12929 -1 12930 -1 12931 -1 12932 -1 12933 -1 12934 -1 12935 -1 12936 -1 12937 -1 12938 -1 12939 -1 12940 -1 12941 -1 12942 -1 12943 -1 12944 -1 12945 -1 12946 -1 12947 -1 12948 -1 12949 -1 12950 -1 12951 -1 12952 -1 12953 -1 12954 -1 12955 -1 12956 -1 12957 -1 12958 -1 12959 -1 12960 -1 12961 -1 12962 -1 12963 -1 12964 -1 12965 -1 12966 -1 12967 -1 12968 -1 12969 -1 12970 -1 12971 -1 12972 -1 12973 -1 12974 -1 12975 -1 12976 -1 12977 -1 12978 -1 12979 -1 12980 -1 12981 -1 12982 -1 12983 -1 12984 -1 12985 -1 12986 -1 12987 -1 12988 -1 12989 -1 12990 -1 12991 -1 12992 -1 12993 -1 12994 -1 12995 -1 12996 -1 12997 -1 12998 -1 12999 -1 13000 -1 13001 -1 13002 -1 13003 -1 13004 -1 13005 -1 13006 -1 13007 -1 13008 -1 13009 -1 13010 -1 13011 -1 13012 -1 13013 -1 13014 -1 13015 -1 13016 -1 13017 -1 13018 -1 13019 -1 13020 -1 13021 -1 13022 -1 13023 -1 13024 -1 13025 -1 13026 -1 13027 -1 13028 -1 13029 -1 13030 -1 13031 -1 13032 -1 13033 -1 13034 -1 13035 -1 13036 -1 13037 -1 13038 -1 13039 -1 13040 -1 13041 -1 13042 -1 13043 -1 13044 -1 13045 -1 13046 -1 13047 -1 13048 -1 13049 -1 13050 -1 13051 -1 13052 -1 13053 -1 13054 -1 13055 -1 13056 -1 13057 -1 13058 -1 13059 -1 13060 -1 13061 -1 13062 -1 13063 -1 13064 -1 13065 -1 13066 -1 13067 -1 13068 -1 13069 -1 13070 -1 13071 -1 13072 -1 13073 -1 13074 -1 13075 -1 13076 -1 13077 -1 13078 -1 13079 -1 13080 -1 13081 -1 13082 -1 13083 -1 13084 -1 13085 -1 13086 -1 13087 -1 13088 -1 13089 -1 13090 -1 13091 -1 13092 -1 13093 -1 13094 -1 13095 -1 13096 -1 13097 -1 13098 -1 13099 -1 13100 -1 13101 -1 13102 -1 13103 -1 13104 -1 13105 -1 13106 -1 13107 -1 13108 -1 13109 -1 13110 -1 13111 -1 13112 -1 13113 -1 13114 -1 13115 -1 13116 -1 13117 -1 13118 -1 13119 -1 13120 -1 13121 -1 13122 -1 13123 -1 13124 -1 13125 -1 13126 -1 13127 -1 13128 -1 13129 -1 13130 -1 13131 -1 13132 -1 13133 -1 13134 -1 13135 -1 13136 -1 13137 -1 13138 -1 13139 -1 13140 -1 13141 -1 13142 -1 13143 -1 13144 -1 13145 -1 13146 -1 13147 -1 13148 -1 13149 -1 13150 -1 13151 -1 13152 -1 13153 -1 13154 -1 13155 -1 13156 -1 13157 -1 13158 -1 13159 -1 13160 -1 13161 -1 13162 -1 13163 -1 13164 -1 13165 -1 13166 -1 13167 -1 13168 -1 13169 -1 13170 -1 13171 -1 13172 -1 13173 -1 13174 -1 13175 -1 13176 -1 13177 -1 13178 -1 13179 -1 13180 -1 13181 -1 13182 -1 13183 -1 13184 -1 13185 -1 13186 -1 13187 -1 13188 -1 13189 -1 13190 -1 13191 -1 13192 -1 13193 -1 13194 -1 13195 -1 13196 -1 13197 -1 13198 -1 13199 -1 13200 -1 13201 -1 13202 -1 13203 -1 13204 -1 13205 -1 13206 -1 13207 -1 13208 -1 13209 -1 13210 -1 13211 -1 13212 -1 13213 -1 13214 -1 13215 -1 13216 -1 13217 -1 13218 -1 13219 -1 13220 -1 13221 -1 13222 -1 13223 -1 13224 -1 13225 -1 13226 -1 13227 -1 13228 -1 13229 -1 13230 -1 13231 -1 13232 -1 13233 -1 13234 -1 13235 -1 13236 -1 13237 -1 13238 -1 13239 -1 13240 -1 13241 -1 13242 -1 13243 -1 13244 -1 13245 -1 13246 -1 13247 -1 13248 -1 13249 -1 13250 -1 13251 -1 13252 -1 13253 -1 13254 -1 13255 -1 13256 -1 13257 -1 13258 -1 13259 -1 13260 -1 13261 -1 13262 -1 13263 -1 13264 -1 13265 -1 13266 -1 13267 -1 13268 -1 13269 -1 13270 -1 13271 -1 13272 -1 13273 -1 13274 -1 13275 -1 13276 -1 13277 -1 13278 -1 13279 -1 13280 -1 13281 -1 13282 -1 13283 -1 13284 -1 13285 -1 13286 -1 13287 -1 13288 -1 13289 -1 13290 -1 13291 -1 13292 -1 13293 -1 13294 -1 13295 -1 13296 -1 13297 -1 13298 -1 13299 -1 13300 -1 13301 -1 13302 -1 13303 -1 13304 -1 13305 -1 13306 -1 13307 -1 13308 -1 13309 -1 13310 -1 13311 -1 13312 -1 13313 -1 13314 -1 13315 -1 13316 -1 13317 -1 13318 -1 13319 -1 13320 -1 13321 -1 13322 -1 13323 -1 13324 -1 13325 -1 13326 -1 13327 -1 13328 -1 13329 -1 13330 -1 13331 -1 13332 -1 13333 -1 13334 -1 13335 -1 13336 -1 13337 -1 13338 -1 13339 -1 13340 -1 13341 -1 13342 -1 13343 -1 13344 -1 13345 -1 13346 -1 13347 -1 13348 -1 13349 -1 13350 -1 13351 -1 13352 -1 13353 -1 13354 -1 13355 -1 13356 -1 13357 -1 13358 -1 13359 -1 13360 -1 13361 -1 13362 -1 13363 -1 13364 -1 13365 -1 13366 -1 13367 -1 13368 -1 13369 -1 13370 -1 13371 -1 13372 -1 13373 -1 13374 -1 13375 -1 13376 -1 13377 -1 13378 -1 13379 -1 13380 -1 13381 -1 13382 -1 13383 -1 13384 -1 13385 -1 13386 -1 13387 -1 13388 -1 13389 -1 13390 -1 13391 -1 13392 -1 13393 -1 13394 -1 13395 -1 13396 -1 13397 -1 13398 -1 13399 -1 13400 -1 13401 -1 13402 -1 13403 -1 13404 -1 13405 -1 13406 -1 13407 -1 13408 -1 13409 -1 13410 -1 13411 -1 13412 -1 13413 -1 13414 -1 13415 -1 13416 -1 13417 -1 13418 -1 13419 -1 13420 -1 13421 -1 13422 -1 13423 -1 13424 -1 13425 -1 13426 -1 13427 -1 13428 -1 13429 -1 13430 -1 13431 -1 13432 -1 13433 -1 13434 -1 13435 -1 13436 -1 13437 -1 13438 -1 13439 -1 13440 -1 13441 -1 13442 -1 13443 -1 13444 -1 13445 -1 13446 -1 13447 -1 13448 -1 13449 -1 13450 -1 13451 -1 13452 -1 13453 -1 13454 -1 13455 -1 13456 -1 13457 -1 13458 -1 13459 -1 13460 -1 13461 -1 13462 -1 13463 -1 13464 -1 13465 -1 13466 -1 13467 -1 13468 -1 13469 -1 13470 -1 13471 -1 13472 -1 13473 -1 13474 -1 13475 -1 13476 -1 13477 -1 13478 -1 13479 -1 13480 -1 13481 -1 13482 -1 13483 -1 13484 -1 13485 -1 13486 -1 13487 -1 13488 -1 13489 -1 13490 -1 13491 -1 13492 -1 13493 -1 13494 -1 13495 -1 13496 -1 13497 -1 13498 -1 13499 -1 13500 -1 13501 -1 13502 -1 13503 -1 13504 -1 13505 -1 13506 -1 13507 -1 13508 -1 13509 -1 13510 -1 13511 -1 13512 -1 13513 -1 13514 -1 13515 -1 13516 -1 13517 -1 13518 -1 13519 -1 13520 -1 13521 -1 13522 -1 13523 -1 13524 -1 13525 -1 13526 -1 13527 -1 13528 -1 13529 -1 13530 -1 13531 -1 13532 -1 13533 -1 13534 -1 13535 -1 13536 -1 13537 -1 13538 -1 13539 -1 13540 -1 13541 -1 13542 -1 13543 -1 13544 -1 13545 -1 13546 -1 13547 -1 13548 -1 13549 -1 13550 -1 13551 -1 13552 -1 13553 -1 13554 -1 13555 -1 13556 -1 13557 -1 13558 -1 13559 -1 13560 -1 13561 -1 13562 -1 13563 -1 13564 -1 13565 -1 13566 -1 13567 -1 13568 -1 13569 -1 13570 -1 13571 -1 13572 -1 13573 -1 13574 -1 13575 -1 13576 -1 13577 -1 13578 -1 13579 -1 13580 -1 13581 -1 13582 -1 13583 -1 13584 -1 13585 -1 13586 -1 13587 -1 13588 -1 13589 -1 13590 -1 13591 -1 13592 -1 13593 -1 13594 -1 13595 -1 13596 -1 13597 -1 13598 -1 13599 -1 13600 -1 13601 -1 13602 -1 13603 -1 13604 -1 13605 -1 13606 -1 13607 -1 13608 -1 13609 -1 13610 -1 13611 -1 13612 -1 13613 -1 13614 -1 13615 -1 13616 -1 13617 -1 13618 -1 13619 -1 13620 -1 13621 -1 13622 -1 13623 -1 13624 -1 13625 -1 13626 -1 13627 -1 13628 -1 13629 -1 13630 -1 13631 -1 13632 -1 13633 -1 13634 -1 13635 -1 13636 -1 13637 -1 13638 -1 13639 -1 13640 -1 13641 -1 13642 -1 13643 -1 13644 -1 13645 -1 13646 -1 13647 -1 13648 -1 13649 -1 13650 -1 13651 -1 13652 -1 13653 -1 13654 -1 13655 -1 13656 -1 13657 -1 13658 -1 13659 -1 13660 -1 13661 -1 13662 -1 13663 -1 13664 -1 13665 -1 13666 -1 13667 -1 13668 -1 13669 -1 13670 -1 13671 -1 13672 -1 13673 -1 13674 -1 13675 -1 13676 -1 13677 -1 13678 -1 13679 -1 13680 -1 13681 -1 13682 -1 13683 -1 13684 -1 13685 -1 13686 -1 13687 -1 13688 -1 13689 -1 13690 -1 13691 -1 13692 -1 13693 -1 13694 -1 13695 -1 13696 -1 13697 -1 13698 -1 13699 -1 13700 -1 13701 -1 13702 -1 13703 -1 13704 -1 13705 -1 13706 -1 13707 -1 13708 -1 13709 -1 13710 -1 13711 -1 13712 -1 13713 -1 13714 -1 13715 -1 13716 -1 13717 -1 13718 -1 13719 -1 13720 -1 13721 -1 13722 -1 13723 -1 13724 -1 13725 -1 13726 -1 13727 -1 13728 -1 13729 -1 13730 -1 13731 -1 13732 -1 13733 -1 13734 -1 13735 -1 13736 -1 13737 -1 13738 -1 13739 -1 13740 -1 13741 -1 13742 -1 13743 -1 13744 -1 13745 -1 13746 -1 13747 -1 13748 -1 13749 -1 13750 -1 13751 -1 13752 -1 13753 -1 13754 -1 13755 -1 13756 -1 13757 -1 13758 -1 13759 -1 13760 -1 13761 -1 13762 -1 13763 -1 13764 -1 13765 -1 13766 -1 13767 -1 13768 -1 13769 -1 13770 -1 13771 -1 13772 -1 13773 -1 13774 -1 13775 -1 13776 -1 13777 -1 13778 -1 13779 -1 13780 -1 13781 -1 13782 -1 13783 -1 13784 -1 13785 -1 13786 -1 13787 -1 13788 -1 13789 -1 13790 -1 13791 -1 13792 -1 13793 -1 13794 -1 13795 -1 13796 -1 13797 -1 13798 -1 13799 -1 13800 -1 13801 -1 13802 -1 13803 -1 13804 -1 13805 -1 13806 -1 13807 -1 13808 -1 13809 -1 13810 -1 13811 -1 13812 -1 13813 -1 13814 -1 13815 -1 13816 -1 13817 -1 13818 -1 13819 -1 13820 -1 13821 -1 13822 -1 13823 -1 13824 -1 13825 -1 13826 -1 13827 -1 13828 -1 13829 -1 13830 -1 13831 -1 13832 -1 13833 -1 13834 -1 13835 -1 13836 -1 13837 -1 13838 -1 13839 -1 13840 -1 13841 -1 13842 -1 13843 -1 13844 -1 13845 -1 13846 -1 13847 -1 13848 -1 13849 -1 13850 -1 13851 -1 13852 -1 13853 -1 13854 -1 13855 -1 13856 -1 13857 -1 13858 -1 13859 -1 13860 -1 13861 -1 13862 -1 13863 -1 13864 -1 13865 -1 13866 -1 13867 -1 13868 -1 13869 -1 13870 -1 13871 -1 13872 -1 13873 -1 13874 -1 13875 -1 13876 -1 13877 -1 13878 -1 13879 -1 13880 -1 13881 -1 13882 -1 13883 -1 13884 -1 13885 -1 13886 -1 13887 -1 13888 -1 13889 -1 13890 -1 13891 -1 13892 -1 13893 -1 13894 -1 13895 -1 13896 -1 13897 -1 13898 -1 13899 -1 13900 -1 13901 -1 13902 -1 13903 -1 13904 -1 13905 -1 13906 -1 13907 -1 13908 -1 13909 -1 13910 -1 13911 -1 13912 -1 13913 -1 13914 -1 13915 -1 13916 -1 13917 -1 13918 -1 13919 -1 13920 -1 13921 -1 13922 -1 13923 -1 13924 -1 13925 -1 13926 -1 13927 -1 13928 -1 13929 -1 13930 -1 13931 -1 13932 -1 13933 -1 13934 -1 13935 -1 13936 -1 13937 -1 13938 -1 13939 -1 13940 -1 13941 -1 13942 -1 13943 -1 13944 -1 13945 -1 13946 -1 13947 -1 13948 -1 13949 -1 13950 -1 13951 -1 13952 -1 13953 -1 13954 -1 13955 -1 13956 -1 13957 -1 13958 -1 13959 -1 13960 -1 13961 -1 13962 -1 13963 -1 13964 -1 13965 -1 13966 -1 13967 -1 13968 -1 13969 -1 13970 -1 13971 -1 13972 -1 13973 -1 13974 -1 13975 -1 13976 -1 13977 -1 13978 -1 13979 -1 13980 -1 13981 -1 13982 -1 13983 -1 13984 -1 13985 -1 13986 -1 13987 -1 13988 -1 13989 -1 13990 -1 13991 -1 13992 -1 13993 -1 13994 -1 13995 -1 13996 -1 13997 -1 13998 -1 13999 -1 14000 -1 14001 -1 14002 -1 14003 -1 14004 -1 14005 -1 14006 -1 14007 -1 14008 -1 14009 -1 14010 -1 14011 -1 14012 -1 14013 -1 14014 -1 14015 -1 14016 -1 14017 -1 14018 -1 14019 -1 14020 -1 14021 -1 14022 -1 14023 -1 14024 -1 14025 -1 14026 -1 14027 -1 14028 -1 14029 -1 14030 -1 14031 -1 14032 -1 14033 -1 14034 -1 14035 -1 14036 -1 14037 -1 14038 -1 14039 -1 14040 -1 14041 -1 14042 -1 14043 -1 14044 -1 14045 -1 14046 -1 14047 -1 14048 -1 14049 -1 14050 -1 14051 -1 14052 -1 14053 -1 14054 -1 14055 -1 14056 -1 14057 -1 14058 -1 14059 -1 14060 -1 14061 -1 14062 -1 14063 -1 14064 -1 14065 -1 14066 -1 14067 -1 14068 -1 14069 -1 14070 -1 14071 -1 14072 -1 14073 -1 14074 -1 14075 -1 14076 -1 14077 -1 14078 -1 14079 -1 14080 -1 14081 -1 14082 -1 14083 -1 14084 -1 14085 -1 14086 -1 14087 -1 14088 -1 14089 -1 14090 -1 14091 -1 14092 -1 14093 -1 14094 -1 14095 -1 14096 -1 14097 -1 14098 -1 14099 -1 14100 -1 14101 -1 14102 -1 14103 -1 14104 -1 14105 -1 14106 -1 14107 -1 14108 -1 14109 -1 14110 -1 14111 -1 14112 -1 14113 -1 14114 -1 14115 -1 14116 -1 14117 -1 14118 -1 14119 -1 14120 -1 14121 -1 14122 -1 14123 -1 14124 -1 14125 -1 14126 -1 14127 -1 14128 -1 14129 -1 14130 -1 14131 -1 14132 -1 14133 -1 14134 -1 14135 -1 14136 -1 14137 -1 14138 -1 14139 -1 14140 -1 14141 -1 14142 -1 14143 -1 14144 -1 14145 -1 14146 -1 14147 -1 14148 -1 14149 -1 14150 -1 14151 -1 14152 -1 14153 -1 14154 -1 14155 -1 14156 -1 14157 -1 14158 -1 14159 -1 14160 -1 14161 -1 14162 -1 14163 -1 14164 -1 14165 -1 14166 -1 14167 -1 14168 -1 14169 -1 14170 -1 14171 -1 14172 -1 14173 -1 14174 -1 14175 -1 14176 -1 14177 -1 14178 -1 14179 -1 14180 -1 14181 -1 14182 -1 14183 -1 14184 -1 14185 -1 14186 -1 14187 -1 14188 -1 14189 -1 14190 -1 14191 -1 14192 -1 14193 -1 14194 -1 14195 -1 14196 -1 14197 -1 14198 -1 14199 -1 14200 -1 14201 -1 14202 -1 14203 -1 14204 -1 14205 -1 14206 -1 14207 -1 14208 -1 14209 -1 14210 -1 14211 -1 14212 -1 14213 -1 14214 -1 14215 -1 14216 -1 14217 -1 14218 -1 14219 -1 14220 -1 14221 -1 14222 -1 14223 -1 14224 -1 14225 -1 14226 -1 14227 -1 14228 -1 14229 -1 14230 -1 14231 -1 14232 -1 14233 -1 14234 -1 14235 -1 14236 -1 14237 -1 14238 -1 14239 -1 14240 -1 14241 -1 14242 -1 14243 -1 14244 -1 14245 -1 14246 -1 14247 -1 14248 -1 14249 -1 14250 -1 14251 -1 14252 -1 14253 -1 14254 -1 14255 -1 14256 -1 14257 -1 14258 -1 14259 -1 14260 -1 14261 -1 14262 -1 14263 -1 14264 -1 14265 -1 14266 -1 14267 -1 14268 -1 14269 -1 14270 -1 14271 -1 14272 -1 14273 -1 14274 -1 14275 -1 14276 -1 14277 -1 14278 -1 14279 -1 14280 -1 14281 -1 14282 -1 14283 -1 14284 -1 14285 -1 14286 -1 14287 -1 14288 -1 14289 -1 14290 -1 14291 -1 14292 -1 14293 -1 14294 -1 14295 -1 14296 -1 14297 -1 14298 -1 14299 -1 14300 -1 14301 -1 14302 -1 14303 -1 14304 -1 14305 -1 14306 -1 14307 -1 14308 -1 14309 -1 14310 -1 14311 -1 14312 -1 14313 -1 14314 -1 14315 -1 14316 -1 14317 -1 14318 -1 14319 -1 14320 -1 14321 -1 14322 -1 14323 -1 14324 -1 14325 -1 14326 -1 14327 -1 14328 -1 14329 -1 14330 -1 14331 -1 14332 -1 14333 -1 14334 -1 14335 -1 14336 -1 14337 -1 14338 -1 14339 -1 14340 -1 14341 -1 14342 -1 14343 -1 14344 -1 14345 -1 14346 -1 14347 -1 14348 -1 14349 -1 14350 -1 14351 -1 14352 -1 14353 -1 14354 -1 14355 -1 14356 -1 14357 -1 14358 -1 14359 -1 14360 -1 14361 -1 14362 -1 14363 -1 14364 -1 14365 -1 14366 -1 14367 -1 14368 -1 14369 -1 14370 -1 14371 -1 14372 -1 14373 -1 14374 -1 14375 -1 14376 -1 14377 -1 14378 -1 14379 -1 14380 -1 14381 -1 14382 -1 14383 -1 14384 -1 14385 -1 14386 -1 14387 -1 14388 -1 14389 -1 14390 -1 14391 -1 14392 -1 14393 -1 14394 -1 14395 -1 14396 -1 14397 -1 14398 -1 14399 -1 14400 -1 14401 -1 14402 -1 14403 -1 14404 -1 14405 -1 14406 -1 14407 -1 14408 -1 14409 -1 14410 -1 14411 -1 14412 -1 14413 -1 14414 -1 14415 -1 14416 -1 14417 -1 14418 -1 14419 -1 14420 -1 14421 -1 14422 -1 14423 -1 14424 -1 14425 -1 14426 -1 14427 -1 14428 -1 14429 -1 14430 -1 14431 -1 14432 -1 14433 -1 14434 -1 14435 -1 14436 -1 14437 -1 14438 -1 14439 -1 14440 -1 14441 -1 14442 -1 14443 -1 14444 -1 14445 -1 14446 -1 14447 -1 14448 -1 14449 -1 14450 -1 14451 -1 14452 -1 14453 -1 14454 -1 14455 -1 14456 -1 14457 -1 14458 -1 14459 -1 14460 -1 14461 -1 14462 -1 14463 -1 14464 -1 14465 -1 14466 -1 14467 -1 14468 -1 14469 -1 14470 -1 14471 -1 14472 -1 14473 -1 14474 -1 14475 -1 14476 -1 14477 -1 14478 -1 14479 -1 14480 -1 14481 -1 14482 -1 14483 -1 14484 -1 14485 -1 14486 -1 14487 -1 14488 -1 14489 -1 14490 -1 14491 -1 14492 -1 14493 -1 14494 -1 14495 -1 14496 -1 14497 -1 14498 -1 14499 -1 14500 -1 14501 -1 14502 -1 14503 -1 14504 -1 14505 -1 14506 -1 14507 -1 14508 -1 14509 -1 14510 -1 14511 -1 14512 -1 14513 -1 14514 -1 14515 -1 14516 -1 14517 -1 14518 -1 14519 -1 14520 -1 14521 -1 14522 -1 14523 -1 14524 -1 14525 -1 14526 -1 14527 -1 14528 -1 14529 -1 14530 -1 14531 -1 14532 -1 14533 -1 14534 -1 14535 -1 14536 -1 14537 -1 14538 -1 14539 -1 14540 -1 14541 -1 14542 -1 14543 -1 14544 -1 14545 -1 14546 -1 14547 -1 14548 -1 14549 -1 14550 -1 14551 -1 14552 -1 14553 -1 14554 -1 14555 -1 14556 -1 14557 -1 14558 -1 14559 -1 14560 -1 14561 -1 14562 -1 14563 -1 14564 -1 14565 -1 14566 -1 14567 -1 14568 -1 14569 -1 14570 -1 14571 -1 14572 -1 14573 -1 14574 -1 14575 -1 14576 -1 14577 -1 14578 -1 14579 -1 14580 -1 14581 -1 14582 -1 14583 -1 14584 -1 14585 -1 14586 -1 14587 -1 14588 -1 14589 -1 14590 -1 14591 -1 14592 -1 14593 -1 14594 -1 14595 -1 14596 -1 14597 -1 14598 -1 14599 -1 14600 -1 14601 -1 14602 -1 14603 -1 14604 -1 14605 -1 14606 -1 14607 -1 14608 -1 14609 -1 14610 -1 14611 -1 14612 -1 14613 -1 14614 -1 14615 -1 14616 -1 14617 -1 14618 -1 14619 -1 14620 -1 14621 -1 14622 -1 14623 -1 14624 -1 14625 -1 14626 -1 14627 -1 14628 -1 14629 -1 14630 -1 14631 -1 14632 -1 14633 -1 14634 -1 14635 -1 14636 -1 14637 -1 14638 -1 14639 -1 14640 -1 14641 -1 14642 -1 14643 -1 14644 -1 14645 -1 14646 -1 14647 -1 14648 -1 14649 -1 14650 -1 14651 -1 14652 -1 14653 -1 14654 -1 14655 -1 14656 -1 14657 -1 14658 -1 14659 -1 14660 -1 14661 -1 14662 -1 14663 -1 14664 -1 14665 -1 14666 -1 14667 -1 14668 -1 14669 -1 14670 -1 14671 -1 14672 -1 14673 -1 14674 -1 14675 -1 14676 -1 14677 -1 14678 -1 14679 -1 14680 -1 14681 -1 14682 -1 14683 -1 14684 -1 14685 -1 14686 -1 14687 -1 14688 -1 14689 -1 14690 -1 14691 -1 14692 -1 14693 -1 14694 -1 14695 -1 14696 -1 14697 -1 14698 -1 14699 -1 14700 -1 14701 -1 14702 -1 14703 -1 14704 -1 14705 -1 14706 -1 14707 -1 14708 -1 14709 -1 14710 -1 14711 -1 14712 -1 14713 -1 14714 -1 14715 -1 14716 -1 14717 -1 14718 -1 14719 -1 14720 -1 14721 -1 14722 -1 14723 -1 14724 -1 14725 -1 14726 -1 14727 -1 14728 -1 14729 -1 14730 -1 14731 -1 14732 -1 14733 -1 14734 -1 14735 -1 14736 -1 14737 -1 14738 -1 14739 -1 14740 -1 14741 -1 14742 -1 14743 -1 14744 -1 14745 -1 14746 -1 14747 -1 14748 -1 14749 -1 14750 -1 14751 -1 14752 -1 14753 -1 14754 -1 14755 -1 14756 -1 14757 -1 14758 -1 14759 -1 14760 -1 14761 -1 14762 -1 14763 -1 14764 -1 14765 -1 14766 -1 14767 -1 14768 -1 14769 -1 14770 -1 14771 -1 14772 -1 14773 -1 14774 -1 14775 -1 14776 -1 14777 -1 14778 -1 14779 -1 14780 -1 14781 -1 14782 -1 14783 -1 14784 -1 14785 -1 14786 -1 14787 -1 14788 -1 14789 -1 14790 -1 14791 -1 14792 -1 14793 -1 14794 -1 14795 -1 14796 -1 14797 -1 14798 -1 14799 -1 14800 -1 14801 -1 14802 -1 14803 -1 14804 -1 14805 -1 14806 -1 14807 -1 14808 -1 14809 -1 14810 -1 14811 -1 14812 -1 14813 -1 14814 -1 14815 -1 14816 -1 14817 -1 14818 -1 14819 -1 14820 -1 14821 -1 14822 -1 14823 -1 14824 -1 14825 -1 14826 -1 14827 -1 14828 -1 14829 -1 14830 -1 14831 -1 14832 -1 14833 -1 14834 -1 14835 -1 14836 -1 14837 -1 14838 -1 14839 -1 14840 -1 14841 -1 14842 -1 14843 -1 14844 -1 14845 -1 14846 -1 14847 -1 14848 -1 14849 -1 14850 -1 14851 -1 14852 -1 14853 -1 14854 -1 14855 -1 14856 -1 14857 -1 14858 -1 14859 -1 14860 -1 14861 -1 14862 -1 14863 -1 14864 -1 14865 -1 14866 -1 14867 -1 14868 -1 14869 -1 14870 -1 14871 -1 14872 -1 14873 -1 14874 -1 14875 -1 14876 -1 14877 -1 14878 -1 14879 -1 14880 -1 14881 -1 14882 -1 14883 -1 14884 -1 14885 -1 14886 -1 14887 -1 14888 -1 14889 -1 14890 -1 14891 -1 14892 -1 14893 -1 14894 -1 14895 -1 14896 -1 14897 -1 14898 -1 14899 -1 14900 -1 14901 -1 14902 -1 14903 -1 14904 -1 14905 -1 14906 -1 14907 -1 14908 -1 14909 -1 14910 -1 14911 -1 14912 -1 14913 -1 14914 -1 14915 -1 14916 -1 14917 -1 14918 -1 14919 -1 14920 -1 14921 -1 14922 -1 14923 -1 14924 -1 14925 -1 14926 -1 14927 -1 14928 -1 14929 -1 14930 -1 14931 -1 14932 -1 14933 -1 14934 -1 14935 -1 14936 -1 14937 -1 14938 -1 14939 -1 14940 -1 14941 -1 14942 -1 14943 -1 14944 -1 14945 -1 14946 -1 14947 -1 14948 -1 14949 -1 14950 -1 14951 -1 14952 -1 14953 -1 14954 -1 14955 -1 14956 -1 14957 -1 14958 -1 14959 -1 14960 -1 14961 -1 14962 -1 14963 -1 14964 -1 14965 -1 14966 -1 14967 -1 14968 -1 14969 -1 14970 -1 14971 -1 14972 -1 14973 -1 14974 -1 14975 -1 14976 -1 14977 -1 14978 -1 14979 -1 14980 -1 14981 -1 14982 -1 14983 -1 14984 -1 14985 -1 14986 -1 14987 -1 14988 -1 14989 -1 14990 -1 14991 -1 14992 -1 14993 -1 14994 -1 14995 -1 14996 -1 14997 -1 14998 -1 14999 -1 15000 -1 15001 -1 15002 -1 15003 -1 15004 -1 15005 -1 15006 -1 15007 -1 15008 -1 15009 -1 15010 -1 15011 -1 15012 -1 15013 -1 15014 -1 15015 -1 15016 -1 15017 -1 15018 -1 15019 -1 15020 -1 15021 -1 15022 -1 15023 -1 15024 -1 15025 -1 15026 -1 15027 -1 15028 -1 15029 -1 15030 -1 15031 -1 15032 -1 15033 -1 15034 -1 15035 -1 15036 -1 15037 -1 15038 -1 15039 -1 15040 -1 15041 -1 15042 -1 15043 -1 15044 -1 15045 -1 15046 -1 15047 -1 15048 -1 15049 -1 15050 -1 15051 -1 15052 -1 15053 -1 15054 -1 15055 -1 15056 -1 15057 -1 15058 -1 15059 -1 15060 -1 15061 -1 15062 -1 15063 -1 15064 -1 15065 -1 15066 -1 15067 -1 15068 -1 15069 -1 15070 -1 15071 -1 15072 -1 15073 -1 15074 -1 15075 -1 15076 -1 15077 -1 15078 -1 15079 -1 15080 -1 15081 -1 15082 -1 15083 -1 15084 -1 15085 -1 15086 -1 15087 -1 15088 -1 15089 -1 15090 -1 15091 -1 15092 -1 15093 -1 15094 -1 15095 -1 15096 -1 15097 -1 15098 -1 15099 -1 15100 -1 15101 -1 15102 -1 15103 -1 15104 -1 15105 -1 15106 -1 15107 -1 15108 -1 15109 -1 15110 -1 15111 -1 15112 -1 15113 -1 15114 -1 15115 -1 15116 -1 15117 -1 15118 -1 15119 -1 15120 -1 15121 -1 15122 -1 15123 -1 15124 -1 15125 -1 15126 -1 15127 -1 15128 -1 15129 -1 15130 -1 15131 -1 15132 -1 15133 -1 15134 -1 15135 -1 15136 -1 15137 -1 15138 -1 15139 -1 15140 -1 15141 -1 15142 -1 15143 -1 15144 -1 15145 -1 15146 -1 15147 -1 15148 -1 15149 -1 15150 -1 15151 -1 15152 -1 15153 -1 15154 -1 15155 -1 15156 -1 15157 -1 15158 -1 15159 -1 15160 -1 15161 -1 15162 -1 15163 -1 15164 -1 15165 -1 15166 -1 15167 -1 15168 -1 15169 -1 15170 -1 15171 -1 15172 -1 15173 -1 15174 -1 15175 -1 15176 -1 15177 -1 15178 -1 15179 -1 15180 -1 15181 -1 15182 -1 15183 -1 15184 -1 15185 -1 15186 -1 15187 -1 15188 -1 15189 -1 15190 -1 15191 -1 15192 -1 15193 -1 15194 -1 15195 -1 15196 -1 15197 -1 15198 -1 15199 -1 15200 -1 15201 -1 15202 -1 15203 -1 15204 -1 15205 -1 15206 -1 15207 -1 15208 -1 15209 -1 15210 -1 15211 -1 15212 -1 15213 -1 15214 -1 15215 -1 15216 -1 15217 -1 15218 -1 15219 -1 15220 -1 15221 -1 15222 -1 15223 -1 15224 -1 15225 -1 15226 -1 15227 -1 15228 -1 15229 -1 15230 -1 15231 -1 15232 -1 15233 -1 15234 -1 15235 -1 15236 -1 15237 -1 15238 -1 15239 -1 15240 -1 15241 -1 15242 -1 15243 -1 15244 -1 15245 -1 15246 -1 15247 -1 15248 -1 15249 -1 15250 -1 15251 -1 15252 -1 15253 -1 15254 -1 15255 -1 15256 -1 15257 -1 15258 -1 15259 -1 15260 -1 15261 -1 15262 -1 15263 -1 15264 -1 15265 -1 15266 -1 15267 -1 15268 -1 15269 -1 15270 -1 15271 -1 15272 -1 15273 -1 15274 -1 15275 -1 15276 -1 15277 -1 15278 -1 15279 -1 15280 -1 15281 -1 15282 -1 15283 -1 15284 -1 15285 -1 15286 -1 15287 -1 15288 -1 15289 -1 15290 -1 15291 -1 15292 -1 15293 -1 15294 -1 15295 -1 15296 -1 15297 -1 15298 -1 15299 -1 15300 -1 15301 -1 15302 -1 15303 -1 15304 -1 15305 -1 15306 -1 15307 -1 15308 -1 15309 -1 15310 -1 15311 -1 15312 -1 15313 -1 15314 -1 15315 -1 15316 -1 15317 -1 15318 -1 15319 -1 15320 -1 15321 -1 15322 -1 15323 -1 15324 -1 15325 -1 15326 -1 15327 -1 15328 -1 15329 -1 15330 -1 15331 -1 15332 -1 15333 -1 15334 -1 15335 -1 15336 -1 15337 -1 15338 -1 15339 -1 15340 -1 15341 -1 15342 -1 15343 -1 15344 -1 15345 -1 15346 -1 15347 -1 15348 -1 15349 -1 15350 -1 15351 -1 15352 -1 15353 -1 15354 -1 15355 -1 15356 -1 15357 -1 15358 -1 15359 -1 15360 -1 15361 -1 15362 -1 15363 -1 15364 -1 15365 -1 15366 -1 15367 -1 15368 -1 15369 -1 15370 -1 15371 -1 15372 -1 15373 -1 15374 -1 15375 -1 15376 -1 15377 -1 15378 -1 15379 -1 15380 -1 15381 -1 15382 -1 15383 -1 15384 -1 15385 -1 15386 -1 15387 -1 15388 -1 15389 -1 15390 -1 15391 -1 15392 -1 15393 -1 15394 -1 15395 -1 15396 -1 15397 -1 15398 -1 15399 -1 15400 -1 15401 -1 15402 -1 15403 -1 15404 -1 15405 -1 15406 -1 15407 -1 15408 -1 15409 -1 15410 -1 15411 -1 15412 -1 15413 -1 15414 -1 15415 -1 15416 -1 15417 -1 15418 -1 15419 -1 15420 -1 15421 -1 15422 -1 15423 -1 15424 -1 15425 -1 15426 -1 15427 -1 15428 -1 15429 -1 15430 -1 15431 -1 15432 -1 15433 -1 15434 -1 15435 -1 15436 -1 15437 -1 15438 -1 15439 -1 15440 -1 15441 -1 15442 -1 15443 -1 15444 -1 15445 -1 15446 -1 15447 -1 15448 -1 15449 -1 15450 -1 15451 -1 15452 -1 15453 -1 15454 -1 15455 -1 15456 -1 15457 -1 15458 -1 15459 -1 15460 -1 15461 -1 15462 -1 15463 -1 15464 -1 15465 -1 15466 -1 15467 -1 15468 -1 15469 -1 15470 -1 15471 -1 15472 -1 15473 -1 15474 -1 15475 -1 15476 -1 15477 -1 15478 -1 15479 -1 15480 -1 15481 -1 15482 -1 15483 -1 15484 -1 15485 -1 15486 -1 15487 -1 15488 -1 15489 -1 15490 -1 15491 -1 15492 -1 15493 -1 15494 -1 15495 -1 15496 -1 15497 -1 15498 -1 15499 -1 15500 -1 15501 -1 15502 -1 15503 -1 15504 -1 15505 -1 15506 -1 15507 -1 15508 -1 15509 -1 15510 -1 15511 -1 15512 -1 15513 -1 15514 -1 15515 -1 15516 -1 15517 -1 15518 -1 15519 -1 15520 -1 15521 -1 15522 -1 15523 -1 15524 -1 15525 -1 15526 -1 15527 -1 15528 -1 15529 -1 15530 -1 15531 -1 15532 -1 15533 -1 15534 -1 15535 -1 15536 -1 15537 -1 15538 -1 15539 -1 15540 -1 15541 -1 15542 -1 15543 -1 15544 -1 15545 -1 15546 -1 15547 -1 15548 -1 15549 -1 15550 -1 15551 -1 15552 -1 15553 -1 15554 -1 15555 -1 15556 -1 15557 -1 15558 -1 15559 -1 15560 -1 15561 -1 15562 -1 15563 -1 15564 -1 15565 -1 15566 -1 15567 -1 15568 -1 15569 -1 15570 -1 15571 -1 15572 -1 15573 -1 15574 -1 15575 -1 15576 -1 15577 -1 15578 -1 15579 -1 15580 -1 15581 -1 15582 -1 15583 -1 15584 -1 15585 -1 15586 -1 15587 -1 15588 -1 15589 -1 15590 -1 15591 -1 15592 -1 15593 -1 15594 -1 15595 -1 15596 -1 15597 -1 15598 -1 15599 -1 15600 -1 15601 -1 15602 -1 15603 -1 15604 -1 15605 -1 15606 -1 15607 -1 15608 -1 15609 -1 15610 -1 15611 -1 15612 -1 15613 -1 15614 -1 15615 -1 15616 -1 15617 -1 15618 -1 15619 -1 15620 -1 15621 -1 15622 -1 15623 -1 15624 -1 15625 -1 15626 -1 15627 -1 15628 -1 15629 -1 15630 -1 15631 -1 15632 -1 15633 -1 15634 -1 15635 -1 15636 -1 15637 -1 15638 -1 15639 -1 15640 -1 15641 -1 15642 -1 15643 -1 15644 -1 15645 -1 15646 -1 15647 -1 15648 -1 15649 -1 15650 -1 15651 -1 15652 -1 15653 -1 15654 -1 15655 -1 15656 -1 15657 -1 15658 -1 15659 -1 15660 -1 15661 -1 15662 -1 15663 -1 15664 -1 15665 -1 15666 -1 15667 -1 15668 -1 15669 -1 15670 -1 15671 -1 15672 -1 15673 -1 15674 -1 15675 -1 15676 -1 15677 -1 15678 -1 15679 -1 15680 -1 15681 -1 15682 -1 15683 -1 15684 -1 15685 -1 15686 -1 15687 -1 15688 -1 15689 -1 15690 -1 15691 -1 15692 -1 15693 -1 15694 -1 15695 -1 15696 -1 15697 -1 15698 -1 15699 -1 15700 -1 15701 -1 15702 -1 15703 -1 15704 -1 15705 -1 15706 -1 15707 -1 15708 -1 15709 -1 15710 -1 15711 -1 15712 -1 15713 -1 15714 -1 15715 -1 15716 -1 15717 -1 15718 -1 15719 -1 15720 -1 15721 -1 15722 -1 15723 -1 15724 -1 15725 -1 15726 -1 15727 -1 15728 -1 15729 -1 15730 -1 15731 -1 15732 -1 15733 -1 15734 -1 15735 -1 15736 -1 15737 -1 15738 -1 15739 -1 15740 -1 15741 -1 15742 -1 15743 -1 15744 -1 15745 -1 15746 -1 15747 -1 15748 -1 15749 -1 15750 -1 15751 -1 15752 -1 15753 -1 15754 -1 15755 -1 15756 -1 15757 -1 15758 -1 15759 -1 15760 -1 15761 -1 15762 -1 15763 -1 15764 -1 15765 -1 15766 -1 15767 -1 15768 -1 15769 -1 15770 -1 15771 -1 15772 -1 15773 -1 15774 -1 15775 -1 15776 -1 15777 -1 15778 -1 15779 -1 15780 -1 15781 -1 15782 -1 15783 -1 15784 -1 15785 -1 15786 -1 15787 -1 15788 -1 15789 -1 15790 -1 15791 -1 15792 -1 15793 -1 15794 -1 15795 -1 15796 -1 15797 -1 15798 -1 15799 -1 15800 -1 15801 -1 15802 -1 15803 -1 15804 -1 15805 -1 15806 -1 15807 -1 15808 -1 15809 -1 15810 -1 15811 -1 15812 -1 15813 -1 15814 -1 15815 -1 15816 -1 15817 -1 15818 -1 15819 -1 15820 -1 15821 -1 15822 -1 15823 -1 15824 -1 15825 -1 15826 -1 15827 -1 15828 -1 15829 -1 15830 -1 15831 -1 15832 -1 15833 -1 15834 -1 15835 -1 15836 -1 15837 -1 15838 -1 15839 -1 15840 -1 15841 -1 15842 -1 15843 -1 15844 -1 15845 -1 15846 -1 15847 -1 15848 -1 15849 -1 15850 -1 15851 -1 15852 -1 15853 -1 15854 -1 15855 -1 15856 -1 15857 -1 15858 -1 15859 -1 15860 -1 15861 -1 15862 -1 15863 -1 15864 -1 15865 -1 15866 -1 15867 -1 15868 -1 15869 -1 15870 -1 15871 -1 15872 -1 15873 -1 15874 -1 15875 -1 15876 -1 15877 -1 15878 -1 15879 -1 15880 -1 15881 -1 15882 -1 15883 -1 15884 -1 15885 -1 15886 -1 15887 -1 15888 -1 15889 -1 15890 -1 15891 -1 15892 -1 15893 -1 15894 -1 15895 -1 15896 -1 15897 -1 15898 -1 15899 -1 15900 -1 15901 -1 15902 -1 15903 -1 15904 -1 15905 -1 15906 -1 15907 -1 15908 -1 15909 -1 15910 -1 15911 -1 15912 -1 15913 -1 15914 -1 15915 -1 15916 -1 15917 -1 15918 -1 15919 -1 15920 -1 15921 -1 15922 -1 15923 -1 15924 -1 15925 -1 15926 -1 15927 -1 15928 -1 15929 -1 15930 -1 15931 -1 15932 -1 15933 -1 15934 -1 15935 -1 15936 -1 15937 -1 15938 -1 15939 -1 15940 -1 15941 -1 15942 -1 15943 -1 15944 -1 15945 -1 15946 -1 15947 -1 15948 -1 15949 -1 15950 -1 15951 -1 15952 -1 15953 -1 15954 -1 15955 -1 15956 -1 15957 -1 15958 -1 15959 -1 15960 -1 15961 -1 15962 -1 15963 -1 15964 -1 15965 -1 15966 -1 15967 -1 15968 -1 15969 -1 15970 -1 15971 -1 15972 -1 15973 -1 15974 -1 15975 -1 15976 -1 15977 -1 15978 -1 15979 -1 15980 -1 15981 -1 15982 -1 15983 -1 15984 -1 15985 -1 15986 -1 15987 -1 15988 -1 15989 -1 15990 -1 15991 -1 15992 -1 15993 -1 15994 -1 15995 -1 15996 -1 15997 -1 15998 -1 15999 -1 16000 -1 16001 -1 16002 -1 16003 -1 16004 -1 16005 -1 16006 -1 16007 -1 16008 -1 16009 -1 16010 -1 16011 -1 16012 -1 16013 -1 16014 -1 16015 -1 16016 -1 16017 -1 16018 -1 16019 -1 16020 -1 16021 -1 16022 -1 16023 -1 16024 -1 16025 -1 16026 -1 16027 -1 16028 -1 16029 -1 16030 -1 16031 -1 16032 -1 16033 -1 16034 -1 16035 -1 16036 -1 16037 -1 16038 -1 16039 -1 16040 -1 16041 -1 16042 -1 16043 -1 16044 -1 16045 -1 16046 -1 16047 -1 16048 -1 16049 -1 16050 -1 16051 -1 16052 -1 16053 -1 16054 -1 16055 -1 16056 -1 16057 -1 16058 -1 16059 -1 16060 -1 16061 -1 16062 -1 16063 -1 16064 -1 16065 -1 16066 -1 16067 -1 16068 -1 16069 -1 16070 -1 16071 -1 16072 -1 16073 -1 16074 -1 16075 -1 16076 -1 16077 -1 16078 -1 16079 -1 16080 -1 16081 -1 16082 -1 16083 -1 16084 -1 16085 -1 16086 -1 16087 -1 16088 -1 16089 -1 16090 -1 16091 -1 16092 -1 16093 -1 16094 -1 16095 -1 16096 -1 16097 -1 16098 -1 16099 -1 16100 -1 16101 -1 16102 -1 16103 -1 16104 -1 16105 -1 16106 -1 16107 -1 16108 -1 16109 -1 16110 -1 16111 -1 16112 -1 16113 -1 16114 -1 16115 -1 16116 -1 16117 -1 16118 -1 16119 -1 16120 -1 16121 -1 16122 -1 16123 -1 16124 -1 16125 -1 16126 -1 16127 -1 16128 -1 16129 -1 16130 -1 16131 -1 16132 -1 16133 -1 16134 -1 16135 -1 16136 -1 16137 -1 16138 -1 16139 -1 16140 -1 16141 -1 16142 -1 16143 -1 16144 -1 16145 -1 16146 -1 16147 -1 16148 -1 16149 -1 16150 -1 16151 -1 16152 -1 16153 -1 16154 -1 16155 -1 16156 -1 16157 -1 16158 -1 16159 -1 16160 -1 16161 -1 16162 -1 16163 -1 16164 -1 16165 -1 16166 -1 16167 -1 16168 -1 16169 -1 16170 -1 16171 -1 16172 -1 16173 -1 16174 -1 16175 -1 16176 -1 16177 -1 16178 -1 16179 -1 16180 -1 16181 -1 16182 -1 16183 -1 16184 -1 16185 -1 16186 -1 16187 -1 16188 -1 16189 -1 16190 -1 16191 -1 16192 -1 16193 -1 16194 -1 16195 -1 16196 -1 16197 -1 16198 -1 16199 -1 16200 -1 16201 -1 16202 -1 16203 -1 16204 -1 16205 -1 16206 -1 16207 -1 16208 -1 16209 -1 16210 -1 16211 -1 16212 -1 16213 -1 16214 -1 16215 -1 16216 -1 16217 -1 16218 -1 16219 -1 16220 -1 16221 -1 16222 -1 16223 -1 16224 -1 16225 -1 16226 -1 16227 -1 16228 -1 16229 -1 16230 -1 16231 -1 16232 -1 16233 -1 16234 -1 16235 -1 16236 -1 16237 -1 16238 -1 16239 -1 16240 -1 16241 -1 16242 -1 16243 -1 16244 -1 16245 -1 16246 -1 16247 -1 16248 -1 16249 -1 16250 -1 16251 -1 16252 -1 16253 -1 16254 -1 16255 -1 16256 -1 16257 -1 16258 -1 16259 -1 16260 -1 16261 -1 16262 -1 16263 -1 16264 -1 16265 -1 16266 -1 16267 -1 16268 -1 16269 -1 16270 -1 16271 -1 16272 -1 16273 -1 16274 -1 16275 -1 16276 -1 16277 -1 16278 -1 16279 -1 16280 -1 16281 -1 16282 -1 16283 -1 16284 -1 16285 -1 16286 -1 16287 -1 16288 -1 16289 -1 16290 -1 16291 -1 16292 -1 16293 -1 16294 -1 16295 -1 16296 -1 16297 -1 16298 -1 16299 -1 16300 -1 16301 -1 16302 -1 16303 -1 16304 -1 16305 -1 16306 -1 16307 -1 16308 -1 16309 -1 16310 -1 16311 -1 16312 -1 16313 -1 16314 -1 16315 -1 16316 -1 16317 -1 16318 -1 16319 -1 16320 -1 16321 -1 16322 -1 16323 -1 16324 -1 16325 -1 16326 -1 16327 -1 16328 -1 16329 -1 16330 -1 16331 -1 16332 -1 16333 -1 16334 -1 16335 -1 16336 -1 16337 -1 16338 -1 16339 -1 16340 -1 16341 -1 16342 -1 16343 -1 16344 -1 16345 -1 16346 -1 16347 -1 16348 -1 16349 -1 16350 -1 16351 -1 16352 -1 16353 -1 16354 -1 16355 -1 16356 -1 16357 -1 16358 -1 16359 -1 16360 -1 16361 -1 16362 -1 16363 -1 16364 -1 16365 -1 16366 -1 16367 -1 16368 -1 16369 -1 16370 -1 16371 -1 16372 -1 16373 -1 16374 -1 16375 -1 16376 -1 16377 -1 16378 -1 16379 -1 16380 -1 16381 -1 16382 -1 16383 -1 16384 -1 16385 -1 16386 -1 16387 -1 16388 -1 16389 -1 16390 -1 16391 -1 16392 -1 16393 -1 16394 -1 16395 -1 16396 -1 16397 -1 16398 -1 16399 -1 16400 -1 16401 -1 16402 -1 16403 -1 16404 -1 16405 -1 16406 -1 16407 -1 16408 -1 16409 -1 16410 -1 16411 -1 16412 -1 16413 -1 16414 -1 16415 -1 16416 -1 16417 -1 16418 -1 16419 -1 16420 -1 16421 -1 16422 -1 16423 -1 16424 -1 16425 -1 16426 -1 16427 -1 16428 -1 16429 -1 16430 -1 16431 -1 16432 -1 16433 -1 16434 -1 16435 -1 16436 -1 16437 -1 16438 -1 16439 -1 16440 -1 16441 -1 16442 -1 16443 -1 16444 -1 16445 -1 16446 -1 16447 -1 16448 -1 16449 -1 16450 -1 16451 -1 16452 -1 16453 -1 16454 -1 16455 -1 16456 -1 16457 -1 16458 -1 16459 -1 16460 -1 16461 -1 16462 -1 16463 -1 16464 -1 16465 -1 16466 -1 16467 -1 16468 -1 16469 -1 16470 -1 16471 -1 16472 -1 16473 -1 16474 -1 16475 -1 16476 -1 16477 -1 16478 -1 16479 -1 16480 -1 16481 -1 16482 -1 16483 -1 16484 -1 16485 -1 16486 -1 16487 -1 16488 -1 16489 -1 16490 -1 16491 -1 16492 -1 16493 -1 16494 -1 16495 -1 16496 -1 16497 -1 16498 -1 16499 -1 16500 -1 16501 -1 16502 -1 16503 -1 16504 -1 16505 -1 16506 -1 16507 -1 16508 -1 16509 -1 16510 -1 16511 -1 16512 -1 16513 -1 16514 -1 16515 -1 16516 -1 16517 -1 16518 -1 16519 -1 16520 -1 16521 -1 16522 -1 16523 -1 16524 -1 16525 -1 16526 -1 16527 -1 16528 -1 16529 -1 16530 -1 16531 -1 16532 -1 16533 -1 16534 -1 16535 -1 16536 -1 16537 -1 16538 -1 16539 -1 16540 -1 16541 -1 16542 -1 16543 -1 16544 -1 16545 -1 16546 -1 16547 -1 16548 -1 16549 -1 16550 -1 16551 -1 16552 -1 16553 -1 16554 -1 16555 -1 16556 -1 16557 -1 16558 -1 16559 -1 16560 -1 16561 -1 16562 -1 16563 -1 16564 -1 16565 -1 16566 -1 16567 -1 16568 -1 16569 -1 16570 -1 16571 -1 16572 -1 16573 -1 16574 -1 16575 -1 16576 -1 16577 -1 16578 -1 16579 -1 16580 -1 16581 -1 16582 -1 16583 -1 16584 -1 16585 -1 16586 -1 16587 -1 16588 -1 16589 -1 16590 -1 16591 -1 16592 -1 16593 -1 16594 -1 16595 -1 16596 -1 16597 -1 16598 -1 16599 -1 16600 -1 16601 -1 16602 -1 16603 -1 16604 -1 16605 -1 16606 -1 16607 -1 16608 -1 16609 -1 16610 -1 16611 -1 16612 -1 16613 -1 16614 -1 16615 -1 16616 -1 16617 -1 16618 -1 16619 -1 16620 -1 16621 -1 16622 -1 16623 -1 16624 -1 16625 -1 16626 -1 16627 -1 16628 -1 16629 -1 16630 -1 16631 -1 16632 -1 16633 -1 16634 -1 16635 -1 16636 -1 16637 -1 16638 -1 16639 -1 16640 -1 16641 -1 16642 -1 16643 -1 16644 -1 16645 -1 16646 -1 16647 -1 16648 -1 16649 -1 16650 -1 16651 -1 16652 -1 16653 -1 16654 -1 16655 -1 16656 -1 16657 -1 16658 -1 16659 -1 16660 -1 16661 -1 16662 -1 16663 -1 16664 -1 16665 -1 16666 -1 16667 -1 16668 -1 16669 -1 16670 -1 16671 -1 16672 -1 16673 -1 16674 -1 16675 -1 16676 -1 16677 -1 16678 -1 16679 -1 16680 -1 16681 -1 16682 -1 16683 -1 16684 -1 16685 -1 16686 -1 16687 -1 16688 -1 16689 -1 16690 -1 16691 -1 16692 -1 16693 -1 16694 -1 16695 -1 16696 -1 16697 -1 16698 -1 16699 -1 16700 -1 16701 -1 16702 -1 16703 -1 16704 -1 16705 -1 16706 -1 16707 -1 16708 -1 16709 -1 16710 -1 16711 -1 16712 -1 16713 -1 16714 -1 16715 -1 16716 -1 16717 -1 16718 -1 16719 -1 16720 -1 16721 -1 16722 -1 16723 -1 16724 -1 16725 -1 16726 -1 16727 -1 16728 -1 16729 -1 16730 -1 16731 -1 16732 -1 16733 -1 16734 -1 16735 -1 16736 -1 16737 -1 16738 -1 16739 -1 16740 -1 16741 -1 16742 -1 16743 -1 16744 -1 16745 -1 16746 -1 16747 -1 16748 -1 16749 -1 16750 -1 16751 -1 16752 -1 16753 -1 16754 -1 16755 -1 16756 -1 16757 -1 16758 -1 16759 -1 16760 -1 16761 -1 16762 -1 16763 -1 16764 -1 16765 -1 16766 -1 16767 -1 16768 -1 16769 -1 16770 -1 16771 -1 16772 -1 16773 -1 16774 -1 16775 -1 16776 -1 16777 -1 16778 -1 16779 -1 16780 -1 16781 -1 16782 -1 16783 -1 16784 -1 16785 -1 16786 -1 16787 -1 16788 -1 16789 -1 16790 -1 16791 -1 16792 -1 16793 -1 16794 -1 16795 -1 16796 -1 16797 -1 16798 -1 16799 -1 16800 -1 16801 -1 16802 -1 16803 -1 16804 -1 16805 -1 16806 -1 16807 -1 16808 -1 16809 -1 16810 -1 16811 -1 16812 -1 16813 -1 16814 -1 16815 -1 16816 -1 16817 -1 16818 -1 16819 -1 16820 -1 16821 -1 16822 -1 16823 -1 16824 -1 16825 -1 16826 -1 16827 -1 16828 -1 16829 -1 16830 -1 16831 -1 16832 -1 16833 -1 16834 -1 16835 -1 16836 -1 16837 -1 16838 -1 16839 -1 16840 -1 16841 -1 16842 -1 16843 -1 16844 -1 16845 -1 16846 -1 16847 -1 16848 -1 16849 -1 16850 -1 16851 -1 16852 -1 16853 -1 16854 -1 16855 -1 16856 -1 16857 -1 16858 -1 16859 -1 16860 -1 16861 -1 16862 -1 16863 -1 16864 -1 16865 -1 16866 -1 16867 -1 16868 -1 16869 -1 16870 -1 16871 -1 16872 -1 16873 -1 16874 -1 16875 -1 16876 -1 16877 -1 16878 -1 16879 -1 16880 -1 16881 -1 16882 -1 16883 -1 16884 -1 16885 -1 16886 -1 16887 -1 16888 -1 16889 -1 16890 -1 16891 -1 16892 -1 16893 -1 16894 -1 16895 -1 16896 -1 16897 -1 16898 -1 16899 -1 16900 -1 16901 -1 16902 -1 16903 -1 16904 -1 16905 -1 16906 -1 16907 -1 16908 -1 16909 -1 16910 -1 16911 -1 16912 -1 16913 -1 16914 -1 16915 -1 16916 -1 16917 -1 16918 -1 16919 -1 16920 -1 16921 -1 16922 -1 16923 -1 16924 -1 16925 -1 16926 -1 16927 -1 16928 -1 16929 -1 16930 -1 16931 -1 16932 -1 16933 -1 16934 -1 16935 -1 16936 -1 16937 -1 16938 -1 16939 -1 16940 -1 16941 -1 16942 -1 16943 -1 16944 -1 16945 -1 16946 -1 16947 -1 16948 -1 16949 -1 16950 -1 16951 -1 16952 -1 16953 -1 16954 -1 16955 -1 16956 -1 16957 -1 16958 -1 16959 -1 16960 -1 16961 -1 16962 -1 16963 -1 16964 -1 16965 -1 16966 -1 16967 -1 16968 -1 16969 -1 16970 -1 16971 -1 16972 -1 16973 -1 16974 -1 16975 -1 16976 -1 16977 -1 16978 -1 16979 -1 16980 -1 16981 -1 16982 -1 16983 -1 16984 -1 16985 -1 16986 -1 16987 -1 16988 -1 16989 -1 16990 -1 16991 -1 16992 -1 16993 -1 16994 -1 16995 -1 16996 -1 16997 -1 16998 -1 16999 -1 17000 -1 17001 -1 17002 -1 17003 -1 17004 -1 17005 -1 17006 -1 17007 -1 17008 -1 17009 -1 17010 -1 17011 -1 17012 -1 17013 -1 17014 -1 17015 -1 17016 -1 17017 -1 17018 -1 17019 -1 17020 -1 17021 -1 17022 -1 17023 -1 17024 -1 17025 -1 17026 -1 17027 -1 17028 -1 17029 -1 17030 -1 17031 -1 17032 -1 17033 -1 17034 -1 17035 -1 17036 -1 17037 -1 17038 -1 17039 -1 17040 -1 17041 -1 17042 -1 17043 -1 17044 -1 17045 -1 17046 -1 17047 -1 17048 -1 17049 -1 17050 -1 17051 -1 17052 -1 17053 -1 17054 -1 17055 -1 17056 -1 17057 -1 17058 -1 17059 -1 17060 -1 17061 -1 17062 -1 17063 -1 17064 -1 17065 -1 17066 -1 17067 -1 17068 -1 17069 -1 17070 -1 17071 -1 17072 -1 17073 -1 17074 -1 17075 -1 17076 -1 17077 -1 17078 -1 17079 -1 17080 -1 17081 -1 17082 -1 17083 -1 17084 -1 17085 -1 17086 -1 17087 -1 17088 -1 17089 -1 17090 -1 17091 -1 17092 -1 17093 -1 17094 -1 17095 -1 17096 -1 17097 -1 17098 -1 17099 -1 17100 -1 17101 -1 17102 -1 17103 -1 17104 -1 17105 -1 17106 -1 17107 -1 17108 -1 17109 -1 17110 -1 17111 -1 17112 -1 17113 -1 17114 -1 17115 -1 17116 -1 17117 -1 17118 -1 17119 -1 17120 -1 17121 -1 17122 -1 17123 -1 17124 -1 17125 -1 17126 -1 17127 -1 17128 -1 17129 -1 17130 -1 17131 -1 17132 -1 17133 -1 17134 -1 17135 -1 17136 -1 17137 -1 17138 -1 17139 -1 17140 -1 17141 -1 17142 -1 17143 -1 17144 -1 17145 -1 17146 -1 17147 -1 17148 -1 17149 -1 17150 -1 17151 -1 17152 -1 17153 -1 17154 -1 17155 -1 17156 -1 17157 -1 17158 -1 17159 -1 17160 -1 17161 -1 17162 -1 17163 -1 17164 -1 17165 -1 17166 -1 17167 -1 17168 -1 17169 -1 17170 -1 17171 -1 17172 -1 17173 -1 17174 -1 17175 -1 17176 -1 17177 -1 17178 -1 17179 -1 17180 -1 17181 -1 17182 -1 17183 -1 17184 -1 17185 -1 17186 -1 17187 -1 17188 -1 17189 -1 17190 -1 17191 -1 17192 -1 17193 -1 17194 -1 17195 -1 17196 -1 17197 -1 17198 -1 17199 -1 17200 -1 17201 -1 17202 -1 17203 -1 17204 -1 17205 -1 17206 -1 17207 -1 17208 -1 17209 -1 17210 -1 17211 -1 17212 -1 17213 -1 17214 -1 17215 -1 17216 -1 17217 -1 17218 -1 17219 -1 17220 -1 17221 -1 17222 -1 17223 -1 17224 -1 17225 -1 17226 -1 17227 -1 17228 -1 17229 -1 17230 -1 17231 -1 17232 -1 17233 -1 17234 -1 17235 -1 17236 -1 17237 -1 17238 -1 17239 -1 17240 -1 17241 -1 17242 -1 17243 -1 17244 -1 17245 -1 17246 -1 17247 -1 17248 -1 17249 -1 17250 -1 17251 -1 17252 -1 17253 -1 17254 -1 17255 -1 17256 -1 17257 -1 17258 -1 17259 -1 17260 -1 17261 -1 17262 -1 17263 -1 17264 -1 17265 -1 17266 -1 17267 -1 17268 -1 17269 -1 17270 -1 17271 -1 17272 -1 17273 -1 17274 -1 17275 -1 17276 -1 17277 -1 17278 -1 17279 -1 17280 -1 17281 -1 17282 -1 17283 -1 17284 -1 17285 -1 17286 -1 17287 -1 17288 -1 17289 -1 17290 -1 17291 -1 17292 -1 17293 -1 17294 -1 17295 -1 17296 -1 17297 -1 17298 -1 17299 -1 17300 -1 17301 -1 17302 -1 17303 -1 17304 -1 17305 -1 17306 -1 17307 -1 17308 -1 17309 -1 17310 -1 17311 -1 17312 -1 17313 -1 17314 -1 17315 -1 17316 -1 17317 -1 17318 -1 17319 -1 17320 -1 17321 -1 17322 -1 17323 -1 17324 -1 17325 -1 17326 -1 17327 -1 17328 -1 17329 -1 17330 -1 17331 -1 17332 -1 17333 -1 17334 -1 17335 -1 17336 -1 17337 -1 17338 -1 17339 -1 17340 -1 17341 -1 17342 -1 17343 -1 17344 -1 17345 -1 17346 -1 17347 -1 17348 -1 17349 -1 17350 -1 17351 -1 17352 -1 17353 -1 17354 -1 17355 -1 17356 -1 17357 -1 17358 -1 17359 -1 17360 -1 17361 -1 17362 -1 17363 -1 17364 -1 17365 -1 17366 -1 17367 -1 17368 -1 17369 -1 17370 -1 17371 -1 17372 -1 17373 -1 17374 -1 17375 -1 17376 -1 17377 -1 17378 -1 17379 -1 17380 -1 17381 -1 17382 -1 17383 -1 17384 -1 17385 -1 17386 -1 17387 -1 17388 -1 17389 -1 17390 -1 17391 -1 17392 -1 17393 -1 17394 -1 17395 -1 17396 -1 17397 -1 17398 -1 17399 -1 17400 -1 17401 -1 17402 -1 17403 -1 17404 -1 17405 -1 17406 -1 17407 -1 17408 -1 17409 -1 17410 -1 17411 -1 17412 -1 17413 -1 17414 -1 17415 -1 17416 -1 17417 -1 17418 -1 17419 -1 17420 -1 17421 -1 17422 -1 17423 -1 17424 -1 17425 -1 17426 -1 17427 -1 17428 -1 17429 -1 17430 -1 17431 -1 17432 -1 17433 -1 17434 -1 17435 -1 17436 -1 17437 -1 17438 -1 17439 -1 17440 -1 17441 -1 17442 -1 17443 -1 17444 -1 17445 -1 17446 -1 17447 -1 17448 -1 17449 -1 17450 -1 17451 -1 17452 -1 17453 -1 17454 -1 17455 -1 17456 -1 17457 -1 17458 -1 17459 -1 17460 -1 17461 -1 17462 -1 17463 -1 17464 -1 17465 -1 17466 -1 17467 -1 17468 -1 17469 -1 17470 -1 17471 -1 17472 -1 17473 -1 17474 -1 17475 -1 17476 -1 17477 -1 17478 -1 17479 -1 17480 -1 17481 -1 17482 -1 17483 -1 17484 -1 17485 -1 17486 -1 17487 -1 17488 -1 17489 -1 17490 -1 17491 -1 17492 -1 17493 -1 17494 -1 17495 -1 17496 -1 17497 -1 17498 -1 17499 -1 17500 -1 17501 -1 17502 -1 17503 -1 17504 -1 17505 -1 17506 -1 17507 -1 17508 -1 17509 -1 17510 -1 17511 -1 17512 -1 17513 -1 17514 -1 17515 -1 17516 -1 17517 -1 17518 -1 17519 -1 17520 -1 17521 -1 17522 -1 17523 -1 17524 -1 17525 -1 17526 -1 17527 -1 17528 -1 17529 -1 17530 -1 17531 -1 17532 -1 17533 -1 17534 -1 17535 -1 17536 -1 17537 -1 17538 -1 17539 -1 17540 -1 17541 -1 17542 -1 17543 -1 17544 -1 17545 -1 17546 -1 17547 -1 17548 -1 17549 -1 17550 -1 17551 -1 17552 -1 17553 -1 17554 -1 17555 -1 17556 -1 17557 -1 17558 -1 17559 -1 17560 -1 17561 -1 17562 -1 17563 -1 17564 -1 17565 -1 17566 -1 17567 -1 17568 -1 17569 -1 17570 -1 17571 -1 17572 -1 17573 -1 17574 -1 17575 -1 17576 -1 17577 -1 17578 -1 17579 -1 17580 -1 17581 -1 17582 -1 17583 -1 17584 -1 17585 -1 17586 -1 17587 -1 17588 -1 17589 -1 17590 -1 17591 -1 17592 -1 17593 -1 17594 -1 17595 -1 17596 -1 17597 -1 17598 -1 17599 -1 17600 -1 17601 -1 17602 -1 17603 -1 17604 -1 17605 -1 17606 -1 17607 -1 17608 -1 17609 -1 17610 -1 17611 -1 17612 -1 17613 -1 17614 -1 17615 -1 17616 -1 17617 -1 17618 -1 17619 -1 17620 -1 17621 -1 17622 -1 17623 -1 17624 -1 17625 -1 17626 -1 17627 -1 17628 -1 17629 -1 17630 -1 17631 -1 17632 -1 17633 -1 17634 -1 17635 -1 17636 -1 17637 -1 17638 -1 17639 -1 17640 -1 17641 -1 17642 -1 17643 -1 17644 -1 17645 -1 17646 -1 17647 -1 17648 -1 17649 -1 17650 -1 17651 -1 17652 -1 17653 -1 17654 -1 17655 -1 17656 -1 17657 -1 17658 -1 17659 -1 17660 -1 17661 -1 17662 -1 17663 -1 17664 -1 17665 -1 17666 -1 17667 -1 17668 -1 17669 -1 17670 -1 17671 -1 17672 -1 17673 -1 17674 -1 17675 -1 17676 -1 17677 -1 17678 -1 17679 -1 17680 -1 17681 -1 17682 -1 17683 -1 17684 -1 17685 -1 17686 -1 17687 -1 17688 -1 17689 -1 17690 -1 17691 -1 17692 -1 17693 -1 17694 -1 17695 -1 17696 -1 17697 -1 17698 -1 17699 -1 17700 -1 17701 -1 17702 -1 17703 -1 17704 -1 17705 -1 17706 -1 17707 -1 17708 -1 17709 -1 17710 -1 17711 -1 17712 -1 17713 -1 17714 -1 17715 -1 17716 -1 17717 -1 17718 -1 17719 -1 17720 -1 17721 -1 17722 -1 17723 -1 17724 -1 17725 -1 17726 -1 17727 -1 17728 -1 17729 -1 17730 -1 17731 -1 17732 -1 17733 -1 17734 -1 17735 -1 17736 -1 17737 -1 17738 -1 17739 -1 17740 -1 17741 -1 17742 -1 17743 -1 17744 -1 17745 -1 17746 -1 17747 -1 17748 -1 17749 -1 17750 -1 17751 -1 17752 -1 17753 -1 17754 -1 17755 -1 17756 -1 17757 -1 17758 -1 17759 -1 17760 -1 17761 -1 17762 -1 17763 -1 17764 -1 17765 -1 17766 -1 17767 -1 17768 -1 17769 -1 17770 -1 17771 -1 17772 -1 17773 -1 17774 -1 17775 -1 17776 -1 17777 -1 17778 -1 17779 -1 17780 -1 17781 -1 17782 -1 17783 -1 17784 -1 17785 -1 17786 -1 17787 -1 17788 -1 17789 -1 17790 -1 17791 -1 17792 -1 17793 -1 17794 -1 17795 -1 17796 -1 17797 -1 17798 -1 17799 -1 17800 -1 17801 -1 17802 -1 17803 -1 17804 -1 17805 -1 17806 -1 17807 -1 17808 -1 17809 -1 17810 -1 17811 -1 17812 -1 17813 -1 17814 -1 17815 -1 17816 -1 17817 -1 17818 -1 17819 -1 17820 -1 17821 -1 17822 -1 17823 -1 17824 -1 17825 -1 17826 -1 17827 -1 17828 -1 17829 -1 17830 -1 17831 -1 17832 -1 17833 -1 17834 -1 17835 -1 17836 -1 17837 -1 17838 -1 17839 -1 17840 -1 17841 -1 17842 -1 17843 -1 17844 -1 17845 -1 17846 -1 17847 -1 17848 -1 17849 -1 17850 -1 17851 -1 17852 -1 17853 -1 17854 -1 17855 -1 17856 -1 17857 -1 17858 -1 17859 -1 17860 -1 17861 -1 17862 -1 17863 -1 17864 -1 17865 -1 17866 -1 17867 -1 17868 -1 17869 -1 17870 -1 17871 -1 17872 -1 17873 -1 17874 -1 17875 -1 17876 -1 17877 -1 17878 -1 17879 -1 17880 -1 17881 -1 17882 -1 17883 -1 17884 -1 17885 -1 17886 -1 17887 -1 17888 -1 17889 -1 17890 -1 17891 -1 17892 -1 17893 -1 17894 -1 17895 -1 17896 -1 17897 -1 17898 -1 17899 -1 17900 -1 17901 -1 17902 -1 17903 -1 17904 -1 17905 -1 17906 -1 17907 -1 17908 -1 17909 -1 17910 -1 17911 -1 17912 -1 17913 -1 17914 -1 17915 -1 17916 -1 17917 -1 17918 -1 17919 -1 17920 -1 17921 -1 17922 -1 17923 -1 17924 -1 17925 -1 17926 -1 17927 -1 17928 -1 17929 -1 17930 -1 17931 -1 17932 -1 17933 -1 17934 -1 17935 -1 17936 -1 17937 -1 17938 -1 17939 -1 17940 -1 17941 -1 17942 -1 17943 -1 17944 -1 17945 -1 17946 -1 17947 -1 17948 -1 17949 -1 17950 -1 17951 -1 17952 -1 17953 -1 17954 -1 17955 -1 17956 -1 17957 -1 17958 -1 17959 -1 17960 -1 17961 -1 17962 -1 17963 -1 17964 -1 17965 -1 17966 -1 17967 -1 17968 -1 17969 -1 17970 -1 17971 -1 17972 -1 17973 -1 17974 -1 17975 -1 17976 -1 17977 -1 17978 -1 17979 -1 17980 -1 17981 -1 17982 -1 17983 -1 17984 -1 17985 -1 17986 -1 17987 -1 17988 -1 17989 -1 17990 -1 17991 -1 17992 -1 17993 -1 17994 -1 17995 -1 17996 -1 17997 -1 17998 -1 17999 -1 18000 -1 18001 -1 18002 -1 18003 -1 18004 -1 18005 -1 18006 -1 18007 -1 18008 -1 18009 -1 18010 -1 18011 -1 18012 -1 18013 -1 18014 -1 18015 -1 18016 -1 18017 -1 18018 -1 18019 -1 18020 -1 18021 -1 18022 -1 18023 -1 18024 -1 18025 -1 18026 -1 18027 -1 18028 -1 18029 -1 18030 -1 18031 -1 18032 -1 18033 -1 18034 -1 18035 -1 18036 -1 18037 -1 18038 -1 18039 -1 18040 -1 18041 -1 18042 -1 18043 -1 18044 -1 18045 -1 18046 -1 18047 -1 18048 -1 18049 -1 18050 -1 18051 -1 18052 -1 18053 -1 18054 -1 18055 -1 18056 -1 18057 -1 18058 -1 18059 -1 18060 -1 18061 -1 18062 -1 18063 -1 18064 -1 18065 -1 18066 -1 18067 -1 18068 -1 18069 -1 18070 -1 18071 -1 18072 -1 18073 -1 18074 -1 18075 -1 18076 -1 18077 -1 18078 -1 18079 -1 18080 -1 18081 -1 18082 -1 18083 -1 18084 -1 18085 -1 18086 -1 18087 -1 18088 -1 18089 -1 18090 -1 18091 -1 18092 -1 18093 -1 18094 -1 18095 -1 18096 -1 18097 -1 18098 -1 18099 -1 18100 -1 18101 -1 18102 -1 18103 -1 18104 -1 18105 -1 18106 -1 18107 -1 18108 -1 18109 -1 18110 -1 18111 -1 18112 -1 18113 -1 18114 -1 18115 -1 18116 -1 18117 -1 18118 -1 18119 -1 18120 -1 18121 -1 18122 -1 18123 -1 18124 -1 18125 -1 18126 -1 18127 -1 18128 -1 18129 -1 18130 -1 18131 -1 18132 -1 18133 -1 18134 -1 18135 -1 18136 -1 18137 -1 18138 -1 18139 -1 18140 -1 18141 -1 18142 -1 18143 -1 18144 -1 18145 -1 18146 -1 18147 -1 18148 -1 18149 -1 18150 -1 18151 -1 18152 -1 18153 -1 18154 -1 18155 -1 18156 -1 18157 -1 18158 -1 18159 -1 18160 -1 18161 -1 18162 -1 18163 -1 18164 -1 18165 -1 18166 -1 18167 -1 18168 -1 18169 -1 18170 -1 18171 -1 18172 -1 18173 -1 18174 -1 18175 -1 18176 -1 18177 -1 18178 -1 18179 -1 18180 -1 18181 -1 18182 -1 18183 -1 18184 -1 18185 -1 18186 -1 18187 -1 18188 -1 18189 -1 18190 -1 18191 -1 18192 -1 18193 -1 18194 -1 18195 -1 18196 -1 18197 -1 18198 -1 18199 -1 18200 -1 18201 -1 18202 -1 18203 -1 18204 -1 18205 -1 18206 -1 18207 -1 18208 -1 18209 -1 18210 -1 18211 -1 18212 -1 18213 -1 18214 -1 18215 -1 18216 -1 18217 -1 18218 -1 18219 -1 18220 -1 18221 -1 18222 -1 18223 -1 18224 -1 18225 -1 18226 -1 18227 -1 18228 -1 18229 -1 18230 -1 18231 -1 18232 -1 18233 -1 18234 -1 18235 -1 18236 -1 18237 -1 18238 -1 18239 -1 18240 -1 18241 -1 18242 -1 18243 -1 18244 -1 18245 -1 18246 -1 18247 -1 18248 -1 18249 -1 18250 -1 18251 -1 18252 -1 18253 -1 18254 -1 18255 -1 18256 -1 18257 -1 18258 -1 18259 -1 18260 -1 18261 -1 18262 -1 18263 -1 18264 -1 18265 -1 18266 -1 18267 -1 18268 -1 18269 -1 18270 -1 18271 -1 18272 -1 18273 -1 18274 -1 18275 -1 18276 -1 18277 -1 18278 -1 18279 -1 18280 -1 18281 -1 18282 -1 18283 -1 18284 -1 18285 -1 18286 -1 18287 -1 18288 -1 18289 -1 18290 -1 18291 -1 18292 -1 18293 -1 18294 -1 18295 -1 18296 -1 18297 -1 18298 -1 18299 -1 18300 -1 18301 -1 18302 -1 18303 -1 18304 -1 18305 -1 18306 -1 18307 -1 18308 -1 18309 -1 18310 -1 18311 -1 18312 -1 18313 -1 18314 -1 18315 -1 18316 -1 18317 -1 18318 -1 18319 -1 18320 -1 18321 -1 18322 -1 18323 -1 18324 -1 18325 -1 18326 -1 18327 -1 18328 -1 18329 -1 18330 -1 18331 -1 18332 -1 18333 -1 18334 -1 18335 -1 18336 -1 18337 -1 18338 -1 18339 -1 18340 -1 18341 -1 18342 -1 18343 -1 18344 -1 18345 -1 18346 -1 18347 -1 18348 -1 18349 -1 18350 -1 18351 -1 18352 -1 18353 -1 18354 -1 18355 -1 18356 -1 18357 -1 18358 -1 18359 -1 18360 -1 18361 -1 18362 -1 18363 -1 18364 -1 18365 -1 18366 -1 18367 -1 18368 -1 18369 -1 18370 -1 18371 -1 18372 -1 18373 -1 18374 -1 18375 -1 18376 -1 18377 -1 18378 -1 18379 -1 18380 -1 18381 -1 18382 -1 18383 -1 18384 -1 18385 -1 18386 -1 18387 -1 18388 -1 18389 -1 18390 -1 18391 -1 18392 -1 18393 -1 18394 -1 18395 -1 18396 -1 18397 -1 18398 -1 18399 -1 18400 -1 18401 -1 18402 -1 18403 -1 18404 -1 18405 -1 18406 -1 18407 -1 18408 -1 18409 -1 18410 -1 18411 -1 18412 -1 18413 -1 18414 -1 18415 -1 18416 -1 18417 -1 18418 -1 18419 -1 18420 -1 18421 -1 18422 -1 18423 -1 18424 -1 18425 -1 18426 -1 18427 -1 18428 -1 18429 -1 18430 -1 18431 -1 18432 -1 18433 -1 18434 -1 18435 -1 18436 -1 18437 -1 18438 -1 18439 -1 18440 -1 18441 -1 18442 -1 18443 -1 18444 -1 18445 -1 18446 -1 18447 -1 18448 -1 18449 -1 18450 -1 18451 -1 18452 -1 18453 -1 18454 -1 18455 -1 18456 -1 18457 -1 18458 -1 18459 -1 18460 -1 18461 -1 18462 -1 18463 -1 18464 -1 18465 -1 18466 -1 18467 -1 18468 -1 18469 -1 18470 -1 18471 -1 18472 -1 18473 -1 18474 -1 18475 -1 18476 -1 18477 -1 18478 -1 18479 -1 18480 -1 18481 -1 18482 -1 18483 -1 18484 -1 18485 -1 18486 -1 18487 -1 18488 -1 18489 -1 18490 -1 18491 -1 18492 -1 18493 -1 18494 -1 18495 -1 18496 -1 18497 -1 18498 -1 18499 -1 18500 -1 18501 -1 18502 -1 18503 -1 18504 -1 18505 -1 18506 -1 18507 -1 18508 -1 18509 -1 18510 -1 18511 -1 18512 -1 18513 -1 18514 -1 18515 -1 18516 -1 18517 -1 18518 -1 18519 -1 18520 -1 18521 -1 18522 -1 18523 -1 18524 -1 18525 -1 18526 -1 18527 -1 18528 -1 18529 -1 18530 -1 18531 -1 18532 -1 18533 -1 18534 -1 18535 -1 18536 -1 18537 -1 18538 -1 18539 -1 18540 -1 18541 -1 18542 -1 18543 -1 18544 -1 18545 -1 18546 -1 18547 -1 18548 -1 18549 -1 18550 -1 18551 -1 18552 -1 18553 -1 18554 -1 18555 -1 18556 -1 18557 -1 18558 -1 18559 -1 18560 -1 18561 -1 18562 -1 18563 -1 18564 -1 18565 -1 18566 -1 18567 -1 18568 -1 18569 -1 18570 -1 18571 -1 18572 -1 18573 -1 18574 -1 18575 -1 18576 -1 18577 -1 18578 -1 18579 -1 18580 -1 18581 -1 18582 -1 18583 -1 18584 -1 18585 -1 18586 -1 18587 -1 18588 -1 18589 -1 18590 -1 18591 -1 18592 -1 18593 -1 18594 -1 18595 -1 18596 -1 18597 -1 18598 -1 18599 -1 18600 -1 18601 -1 18602 -1 18603 -1 18604 -1 18605 -1 18606 -1 18607 -1 18608 -1 18609 -1 18610 -1 18611 -1 18612 -1 18613 -1 18614 -1 18615 -1 18616 -1 18617 -1 18618 -1 18619 -1 18620 -1 18621 -1 18622 -1 18623 -1 18624 -1 18625 -1 18626 -1 18627 -1 18628 -1 18629 -1 18630 -1 18631 -1 18632 -1 18633 -1 18634 -1 18635 -1 18636 -1 18637 -1 18638 -1 18639 -1 18640 -1 18641 -1 18642 -1 18643 -1 18644 -1 18645 -1 18646 -1 18647 -1 18648 -1 18649 -1 18650 -1 18651 -1 18652 -1 18653 -1 18654 -1 18655 -1 18656 -1 18657 -1 18658 -1 18659 -1 18660 -1 18661 -1 18662 -1 18663 -1 18664 -1 18665 -1 18666 -1 18667 -1 18668 -1 18669 -1 18670 -1 18671 -1 18672 -1 18673 -1 18674 -1 18675 -1 18676 -1 18677 -1 18678 -1 18679 -1 18680 -1 18681 -1 18682 -1 18683 -1 18684 -1 18685 -1 18686 -1 18687 -1 18688 -1 18689 -1 18690 -1 18691 -1 18692 -1 18693 -1 18694 -1 18695 -1 18696 -1 18697 -1 18698 -1 18699 -1 18700 -1 18701 -1 18702 -1 18703 -1 18704 -1 18705 -1 18706 -1 18707 -1 18708 -1 18709 -1 18710 -1 18711 -1 18712 -1 18713 -1 18714 -1 18715 -1 18716 -1 18717 -1 18718 -1 18719 -1 18720 -1 18721 -1 18722 -1 18723 -1 18724 -1 18725 -1 18726 -1 18727 -1 18728 -1 18729 -1 18730 -1 18731 -1 18732 -1 18733 -1 18734 -1 18735 -1 18736 -1 18737 -1 18738 -1 18739 -1 18740 -1 18741 -1 18742 -1 18743 -1 18744 -1 18745 -1 18746 -1 18747 -1 18748 -1 18749 -1 18750 -1 18751 -1 18752 -1 18753 -1 18754 -1 18755 -1 18756 -1 18757 -1 18758 -1 18759 -1 18760 -1 18761 -1 18762 -1 18763 -1 18764 -1 18765 -1 18766 -1 18767 -1 18768 -1 18769 -1 18770 -1 18771 -1 18772 -1 18773 -1 18774 -1 18775 -1 18776 -1 18777 -1 18778 -1 18779 -1 18780 -1 18781 -1 18782 -1 18783 -1 18784 -1 18785 -1 18786 -1 18787 -1 18788 -1 18789 -1 18790 -1 18791 -1 18792 -1 18793 -1 18794 -1 18795 -1 18796 -1 18797 -1 18798 -1 18799 -1 18800 -1 18801 -1 18802 -1 18803 -1 18804 -1 18805 -1 18806 -1 18807 -1 18808 -1 18809 -1 18810 -1 18811 -1 18812 -1 18813 -1 18814 -1 18815 -1 18816 -1 18817 -1 18818 -1 18819 -1 18820 -1 18821 -1 18822 -1 18823 -1 18824 -1 18825 -1 18826 -1 18827 -1 18828 -1 18829 -1 18830 -1 18831 -1 18832 -1 18833 -1 18834 -1 18835 -1 18836 -1 18837 -1 18838 -1 18839 -1 18840 -1 18841 -1 18842 -1 18843 -1 18844 -1 18845 -1 18846 -1 18847 -1 18848 -1 18849 -1 18850 -1 18851 -1 18852 -1 18853 -1 18854 -1 18855 -1 18856 -1 18857 -1 18858 -1 18859 -1 18860 -1 18861 -1 18862 -1 18863 -1 18864 -1 18865 -1 18866 -1 18867 -1 18868 -1 18869 -1 18870 -1 18871 -1 18872 -1 18873 -1 18874 -1 18875 -1 18876 -1 18877 -1 18878 -1 18879 -1 18880 -1 18881 -1 18882 -1 18883 -1 18884 -1 18885 -1 18886 -1 18887 -1 18888 -1 18889 -1 18890 -1 18891 -1 18892 -1 18893 -1 18894 -1 18895 -1 18896 -1 18897 -1 18898 -1 18899 -1 18900 -1 18901 -1 18902 -1 18903 -1 18904 -1 18905 -1 18906 -1 18907 -1 18908 -1 18909 -1 18910 -1 18911 -1 18912 -1 18913 -1 18914 -1 18915 -1 18916 -1 18917 -1 18918 -1 18919 -1 18920 -1 18921 -1 18922 -1 18923 -1 18924 -1 18925 -1 18926 -1 18927 -1 18928 -1 18929 -1 18930 -1 18931 -1 18932 -1 18933 -1 18934 -1 18935 -1 18936 -1 18937 -1 18938 -1 18939 -1 18940 -1 18941 -1 18942 -1 18943 -1 18944 -1 18945 -1 18946 -1 18947 -1 18948 -1 18949 -1 18950 -1 18951 -1 18952 -1 18953 -1 18954 -1 18955 -1 18956 -1 18957 -1 18958 -1 18959 -1 18960 -1 18961 -1 18962 -1 18963 -1 18964 -1 18965 -1 18966 -1 18967 -1 18968 -1 18969 -1 18970 -1 18971 -1 18972 -1 18973 -1 18974 -1 18975 -1 18976 -1 18977 -1 18978 -1 18979 -1 18980 -1 18981 -1 18982 -1 18983 -1 18984 -1 18985 -1 18986 -1 18987 -1 18988 -1 18989 -1 18990 -1 18991 -1 18992 -1 18993 -1 18994 -1 18995 -1 18996 -1 18997 -1 18998 -1 18999 -1 19000 -1 19001 -1 19002 -1 19003 -1 19004 -1 19005 -1 19006 -1 19007 -1 19008 -1 19009 -1 19010 -1 19011 -1 19012 -1 19013 -1 19014 -1 19015 -1 19016 -1 19017 -1 19018 -1 19019 -1 19020 -1 19021 -1 19022 -1 19023 -1 19024 -1 19025 -1 19026 -1 19027 -1 19028 -1 19029 -1 19030 -1 19031 -1 19032 -1 19033 -1 19034 -1 19035 -1 19036 -1 19037 -1 19038 -1 19039 -1 19040 -1 19041 -1 19042 -1 19043 -1 19044 -1 19045 -1 19046 -1 19047 -1 19048 -1 19049 -1 19050 -1 19051 -1 19052 -1 19053 -1 19054 -1 19055 -1 19056 -1 19057 -1 19058 -1 19059 -1 19060 -1 19061 -1 19062 -1 19063 -1 19064 -1 19065 -1 19066 -1 19067 -1 19068 -1 19069 -1 19070 -1 19071 -1 19072 -1 19073 -1 19074 -1 19075 -1 19076 -1 19077 -1 19078 -1 19079 -1 19080 -1 19081 -1 19082 -1 19083 -1 19084 -1 19085 -1 19086 -1 19087 -1 19088 -1 19089 -1 19090 -1 19091 -1 19092 -1 19093 -1 19094 -1 19095 -1 19096 -1 19097 -1 19098 -1 19099 -1 19100 -1 19101 -1 19102 -1 19103 -1 19104 -1 19105 -1 19106 -1 19107 -1 19108 -1 19109 -1 19110 -1 19111 -1 19112 -1 19113 -1 19114 -1 19115 -1 19116 -1 19117 -1 19118 -1 19119 -1 19120 -1 19121 -1 19122 -1 19123 -1 19124 -1 19125 -1 19126 -1 19127 -1 19128 -1 19129 -1 19130 -1 19131 -1 19132 -1 19133 -1 19134 -1 19135 -1 19136 -1 19137 -1 19138 -1 19139 -1 19140 -1 19141 -1 19142 -1 19143 -1 19144 -1 19145 -1 19146 -1 19147 -1 19148 -1 19149 -1 19150 -1 19151 -1 19152 -1 19153 -1 19154 -1 19155 -1 19156 -1 19157 -1 19158 -1 19159 -1 19160 -1 19161 -1 19162 -1 19163 -1 19164 -1 19165 -1 19166 -1 19167 -1 19168 -1 19169 -1 19170 -1 19171 -1 19172 -1 19173 -1 19174 -1 19175 -1 19176 -1 19177 -1 19178 -1 19179 -1 19180 -1 19181 -1 19182 -1 19183 -1 19184 -1 19185 -1 19186 -1 19187 -1 19188 -1 19189 -1 19190 -1 19191 -1 19192 -1 19193 -1 19194 -1 19195 -1 19196 -1 19197 -1 19198 -1 19199 -1 19200 -1 19201 -1 19202 -1 19203 -1 19204 -1 19205 -1 19206 -1 19207 -1 19208 -1 19209 -1 19210 -1 19211 -1 19212 -1 19213 -1 19214 -1 19215 -1 19216 -1 19217 -1 19218 -1 19219 -1 19220 -1 19221 -1 19222 -1 19223 -1 19224 -1 19225 -1 19226 -1 19227 -1 19228 -1 19229 -1 19230 -1 19231 -1 19232 -1 19233 -1 19234 -1 19235 -1 19236 -1 19237 -1 19238 -1 19239 -1 19240 -1 19241 -1 19242 -1 19243 -1 19244 -1 19245 -1 19246 -1 19247 -1 19248 -1 19249 -1 19250 -1 19251 -1 19252 -1 19253 -1 19254 -1 19255 -1 19256 -1 19257 -1 19258 -1 19259 -1 19260 -1 19261 -1 19262 -1 19263 -1 19264 -1 19265 -1 19266 -1 19267 -1 19268 -1 19269 -1 19270 -1 19271 -1 19272 -1 19273 -1 19274 -1 19275 -1 19276 -1 19277 -1 19278 -1 19279 -1 19280 -1 19281 -1 19282 -1 19283 -1 19284 -1 19285 -1 19286 -1 19287 -1 19288 -1 19289 -1 19290 -1 19291 -1 19292 -1 19293 -1 19294 -1 19295 -1 19296 -1 19297 -1 19298 -1 19299 -1 19300 -1 19301 -1 19302 -1 19303 -1 19304 -1 19305 -1 19306 -1 19307 -1 19308 -1 19309 -1 19310 -1 19311 -1 19312 -1 19313 -1 19314 -1 19315 -1 19316 -1 19317 -1 19318 -1 19319 -1 19320 -1 19321 -1 19322 -1 19323 -1 19324 -1 19325 -1 19326 -1 19327 -1 19328 -1 19329 -1 19330 -1 19331 -1 19332 -1 19333 -1 19334 -1 19335 -1 19336 -1 19337 -1 19338 -1 19339 -1 19340 -1 19341 -1 19342 -1 19343 -1 19344 -1 19345 -1 19346 -1 19347 -1 19348 -1 19349 -1 19350 -1 19351 -1 19352 -1 19353 -1 19354 -1 19355 -1 19356 -1 19357 -1 19358 -1 19359 -1 19360 -1 19361 -1 19362 -1 19363 -1 19364 -1 19365 -1 19366 -1 19367 -1 19368 -1 19369 -1 19370 -1 19371 -1 19372 -1 19373 -1 19374 -1 19375 -1 19376 -1 19377 -1 19378 -1 19379 -1 19380 -1 19381 -1 19382 -1 19383 -1 19384 -1 19385 -1 19386 -1 19387 -1 19388 -1 19389 -1 19390 -1 19391 -1 19392 -1 19393 -1 19394 -1 19395 -1 19396 -1 19397 -1 19398 -1 19399 -1 19400 -1 19401 -1 19402 -1 19403 -1 19404 -1 19405 -1 19406 -1 19407 -1 19408 -1 19409 -1 19410 -1 19411 -1 19412 -1 19413 -1 19414 -1 19415 -1 19416 -1 19417 -1 19418 -1 19419 -1 19420 -1 19421 -1 19422 -1 19423 -1 19424 -1 19425 -1 19426 -1 19427 -1 19428 -1 19429 -1 19430 -1 19431 -1 19432 -1 19433 -1 19434 -1 19435 -1 19436 -1 19437 -1 19438 -1 19439 -1 19440 -1 19441 -1 19442 -1 19443 -1 19444 -1 19445 -1 19446 -1 19447 -1 19448 -1 19449 -1 19450 -1 19451 -1 19452 -1 19453 -1 19454 -1 19455 -1 19456 -1 19457 -1 19458 -1 19459 -1 19460 -1 19461 -1 19462 -1 19463 -1 19464 -1 19465 -1 19466 -1 19467 -1 19468 -1 19469 -1 19470 -1 19471 -1 19472 -1 19473 -1 19474 -1 19475 -1 19476 -1 19477 -1 19478 -1 19479 -1 19480 -1 19481 -1 19482 -1 19483 -1 19484 -1 19485 -1 19486 -1 19487 -1 19488 -1 19489 -1 19490 -1 19491 -1 19492 -1 19493 -1 19494 -1 19495 -1 19496 -1 19497 -1 19498 -1 19499 -1 19500 -1 19501 -1 19502 -1 19503 -1 19504 -1 19505 -1 19506 -1 19507 -1 19508 -1 19509 -1 19510 -1 19511 -1 19512 -1 19513 -1 19514 -1 19515 -1 19516 -1 19517 -1 19518 -1 19519 -1 19520 -1 19521 -1 19522 -1 19523 -1 19524 -1 19525 -1 19526 -1 19527 -1 19528 -1 19529 -1 19530 -1 19531 -1 19532 -1 19533 -1 19534 -1 19535 -1 19536 -1 19537 -1 19538 -1 19539 -1 19540 -1 19541 -1 19542 -1 19543 -1 19544 -1 19545 -1 19546 -1 19547 -1 19548 -1 19549 -1 19550 -1 19551 -1 19552 -1 19553 -1 19554 -1 19555 -1 19556 -1 19557 -1 19558 -1 19559 -1 19560 -1 19561 -1 19562 -1 19563 -1 19564 -1 19565 -1 19566 -1 19567 -1 19568 -1 19569 -1 19570 -1 19571 -1 19572 -1 19573 -1 19574 -1 19575 -1 19576 -1 19577 -1 19578 -1 19579 -1 19580 -1 19581 -1 19582 -1 19583 -1 19584 -1 19585 -1 19586 -1 19587 -1 19588 -1 19589 -1 19590 -1 19591 -1 19592 -1 19593 -1 19594 -1 19595 -1 19596 -1 19597 -1 19598 -1 19599 -1 19600 -1 19601 -1 19602 -1 19603 -1 19604 -1 19605 -1 19606 -1 19607 -1 19608 -1 19609 -1 19610 -1 19611 -1 19612 -1 19613 -1 19614 -1 19615 -1 19616 -1 19617 -1 19618 -1 19619 -1 19620 -1 19621 -1 19622 -1 19623 -1 19624 -1 19625 -1 19626 -1 19627 -1 19628 -1 19629 -1 19630 -1 19631 -1 19632 -1 19633 -1 19634 -1 19635 -1 19636 -1 19637 -1 19638 -1 19639 -1 19640 -1 19641 -1 19642 -1 19643 -1 19644 -1 19645 -1 19646 -1 19647 -1 19648 -1 19649 -1 19650 -1 19651 -1 19652 -1 19653 -1 19654 -1 19655 -1 19656 -1 19657 -1 19658 -1 19659 -1 19660 -1 19661 -1 19662 -1 19663 -1 19664 -1 19665 -1 19666 -1 19667 -1 19668 -1 19669 -1 19670 -1 19671 -1 19672 -1 19673 -1 19674 -1 19675 -1 19676 -1 19677 -1 19678 -1 19679 -1 19680 -1 19681 -1 19682 -1 19683 -1 19684 -1 19685 -1 19686 -1 19687 -1 19688 -1 19689 -1 19690 -1 19691 -1 19692 -1 19693 -1 19694 -1 19695 -1 19696 -1 19697 -1 19698 -1 19699 -1 19700 -1 19701 -1 19702 -1 19703 -1 19704 -1 19705 -1 19706 -1 19707 -1 19708 -1 19709 -1 19710 -1 19711 -1 19712 -1 19713 -1 19714 -1 19715 -1 19716 -1 19717 -1 19718 -1 19719 -1 19720 -1 19721 -1 19722 -1 19723 -1 19724 -1 19725 -1 19726 -1 19727 -1 19728 -1 19729 -1 19730 -1 19731 -1 19732 -1 19733 -1 19734 -1 19735 -1 19736 -1 19737 -1 19738 -1 19739 -1 19740 -1 19741 -1 19742 -1 19743 -1 19744 -1 19745 -1 19746 -1 19747 -1 19748 -1 19749 -1 19750 -1 19751 -1 19752 -1 19753 -1 19754 -1 19755 -1 19756 -1 19757 -1 19758 -1 19759 -1 19760 -1 19761 -1 19762 -1 19763 -1 19764 -1 19765 -1 19766 -1 19767 -1 19768 -1 19769 -1 19770 -1 19771 -1 19772 -1 19773 -1 19774 -1 19775 -1 19776 -1 19777 -1 19778 -1 19779 -1 19780 -1 19781 -1 19782 -1 19783 -1 19784 -1 19785 -1 19786 -1 19787 -1 19788 -1 19789 -1 19790 -1 19791 -1 19792 -1 19793 -1 19794 -1 19795 -1 19796 -1 19797 -1 19798 -1 19799 -1 19800 -1 19801 -1 19802 -1 19803 -1 19804 -1 19805 -1 19806 -1 19807 -1 19808 -1 19809 -1 19810 -1 19811 -1 19812 -1 19813 -1 19814 -1 19815 -1 19816 -1 19817 -1 19818 -1 19819 -1 19820 -1 19821 -1 19822 -1 19823 -1 19824 -1 19825 -1 19826 -1 19827 -1 19828 -1 19829 -1 19830 -1 19831 -1 19832 -1 19833 -1 19834 -1 19835 -1 19836 -1 19837 -1 19838 -1 19839 -1 19840 -1 19841 -1 19842 -1 19843 -1 19844 -1 19845 -1 19846 -1 19847 -1 19848 -1 19849 -1 19850 -1 19851 -1 19852 -1 19853 -1 19854 -1 19855 -1 19856 -1 19857 -1 19858 -1 19859 -1 19860 -1 19861 -1 19862 -1 19863 -1 19864 -1 19865 -1 19866 -1 19867 -1 19868 -1 19869 -1 19870 -1 19871 -1 19872 -1 19873 -1 19874 -1 19875 -1 19876 -1 19877 -1 19878 -1 19879 -1 19880 -1 19881 -1 19882 -1 19883 -1 19884 -1 19885 -1 19886 -1 19887 -1 19888 -1 19889 -1 19890 -1 19891 -1 19892 -1 19893 -1 19894 -1 19895 -1 19896 -1 19897 -1 19898 -1 19899 -1 19900 -1 19901 -1 19902 -1 19903 -1 19904 -1 19905 -1 19906 -1 19907 -1 19908 -1 19909 -1 19910 -1 19911 -1 19912 -1 19913 -1 19914 -1 19915 -1 19916 -1 19917 -1 19918 -1 19919 -1 19920 -1 19921 -1 19922 -1 19923 -1 19924 -1 19925 -1 19926 -1 19927 -1 19928 -1 19929 -1 19930 -1 19931 -1 19932 -1 19933 -1 19934 -1 19935 -1 19936 -1 19937 -1 19938 -1 19939 -1 19940 -1 19941 -1 19942 -1 19943 -1 19944 -1 19945 -1 19946 -1 19947 -1 19948 -1 19949 -1 19950 -1 19951 -1 19952 -1 19953 -1 19954 -1 19955 -1 19956 -1 19957 -1 19958 -1 19959 -1 19960 -1 19961 -1 19962 -1 19963 -1 19964 -1 19965 -1 19966 -1 19967 -1 19968 -1 19969 -1 19970 -1 19971 -1 19972 -1 19973 -1 19974 -1 19975 -1 19976 -1 19977 -1 19978 -1 19979 -1 19980 -1 19981 -1 19982 -1 19983 -1 19984 -1 19985 -1 19986 -1 19987 -1 19988 -1 19989 -1 19990 -1 19991 -1 19992 -1 19993 -1 19994 -1 19995 -1 19996 -1 19997 -1 19998 -1 19999 -1 20000 -1 20001 -1 20002 -1 20003 -1 20004 -1 20005 -1 20006 -1 20007 -1 20008 -1 20009 -1 20010 -1 20011 -1 20012 -1 20013 -1 20014 -1 20015 -1 20016 -1 20017 -1 20018 -1 20019 -1 20020 -1 20021 -1 20022 -1 20023 -1 20024 -1 20025 -1 20026 -1 20027 -1 20028 -1 20029 -1 20030 -1 20031 -1 20032 -1 20033 -1 20034 -1 20035 -1 20036 -1 20037 -1 20038 -1 20039 -1 20040 -1 20041 -1 20042 -1 20043 -1 20044 -1 20045 -1 20046 -1 20047 -1 20048 -1 20049 -1 20050 -1 20051 -1 20052 -1 20053 -1 20054 -1 20055 -1 20056 -1 20057 -1 20058 -1 20059 -1 20060 -1 20061 -1 20062 -1 20063 -1 20064 -1 20065 -1 20066 -1 20067 -1 20068 -1 20069 -1 20070 -1 20071 -1 20072 -1 20073 -1 20074 -1 20075 -1 20076 -1 20077 -1 20078 -1 20079 -1 20080 -1 20081 -1 20082 -1 20083 -1 20084 -1 20085 -1 20086 -1 20087 -1 20088 -1 20089 -1 20090 -1 20091 -1 20092 -1 20093 -1 20094 -1 20095 -1 20096 -1 20097 -1 20098 -1 20099 -1 20100 -1 20101 -1 20102 -1 20103 -1 20104 -1 20105 -1 20106 -1 20107 -1 20108 -1 20109 -1 20110 -1 20111 -1 20112 -1 20113 -1 20114 -1 20115 -1 20116 -1 20117 -1 20118 -1 20119 -1 20120 -1 20121 -1 20122 -1 20123 -1 20124 -1 20125 -1 20126 -1 20127 -1 20128 -1 20129 -1 20130 -1 20131 -1 20132 -1 20133 -1 20134 -1 20135 -1 20136 -1 20137 -1 20138 -1 20139 -1 20140 -1 20141 -1 20142 -1 20143 -1 20144 -1 20145 -1 20146 -1 20147 -1 20148 -1 20149 -1 20150 -1 20151 -1 20152 -1 20153 -1 20154 -1 20155 -1 20156 -1 20157 -1 20158 -1 20159 -1 20160 -1 20161 -1 20162 -1 20163 -1 20164 -1 20165 -1 20166 -1 20167 -1 20168 -1 20169 -1 20170 -1 20171 -1 20172 -1 20173 -1 20174 -1 20175 -1 20176 -1 20177 -1 20178 -1 20179 -1 20180 -1 20181 -1 20182 -1 20183 -1 20184 -1 20185 -1 20186 -1 20187 -1 20188 -1 20189 -1 20190 -1 20191 -1 20192 -1 20193 -1 20194 -1 20195 -1 20196 -1 20197 -1 20198 -1 20199 -1 20200 -1 20201 -1 20202 -1 20203 -1 20204 -1 20205 -1 20206 -1 20207 -1 20208 -1 20209 -1 20210 -1 20211 -1 20212 -1 20213 -1 20214 -1 20215 -1 20216 -1 20217 -1 20218 -1 20219 -1 20220 -1 20221 -1 20222 -1 20223 -1 20224 -1 20225 -1 20226 -1 20227 -1 20228 -1 20229 -1 20230 -1 20231 -1 20232 -1 20233 -1 20234 -1 20235 -1 20236 -1 20237 -1 20238 -1 20239 -1 20240 -1 20241 -1 20242 -1 20243 -1 20244 -1 20245 -1 20246 -1 20247 -1 20248 -1 20249 -1 20250 -1 20251 -1 20252 -1 20253 -1 20254 -1 20255 -1 20256 -1 20257 -1 20258 -1 20259 -1 20260 -1 20261 -1 20262 -1 20263 -1 20264 -1 20265 -1 20266 -1 20267 -1 20268 -1 20269 -1 20270 -1 20271 -1 20272 -1 20273 -1 20274 -1 20275 -1 20276 -1 20277 -1 20278 -1 20279 -1 20280 -1 20281 -1 20282 -1 20283 -1 20284 -1 20285 -1 20286 -1 20287 -1 20288 -1 20289 -1 20290 -1 20291 -1 20292 -1 20293 -1 20294 -1 20295 -1 20296 -1 20297 -1 20298 -1 20299 -1 20300 -1 20301 -1 20302 -1 20303 -1 20304 -1 20305 -1 20306 -1 20307 -1 20308 -1 20309 -1 20310 -1 20311 -1 20312 -1 20313 -1 20314 -1 20315 -1 20316 -1 20317 -1 20318 -1 20319 -1 20320 -1 20321 -1 20322 -1 20323 -1 20324 -1 20325 -1 20326 -1 20327 -1 20328 -1 20329 -1 20330 -1 20331 -1 20332 -1 20333 -1 20334 -1 20335 -1 20336 -1 20337 -1 20338 -1 20339 -1 20340 -1 20341 -1 20342 -1 20343 -1 20344 -1 20345 -1 20346 -1 20347 -1 20348 -1 20349 -1 20350 -1 20351 -1 20352 -1 20353 -1 20354 -1 20355 -1 20356 -1 20357 -1 20358 -1 20359 -1 20360 -1 20361 -1 20362 -1 20363 -1 20364 -1 20365 -1 20366 -1 20367 -1 20368 -1 20369 -1 20370 -1 20371 -1 20372 -1 20373 -1 20374 -1 20375 -1 20376 -1 20377 -1 20378 -1 20379 -1 20380 -1 20381 -1 20382 -1 20383 -1 20384 -1 20385 -1 20386 -1 20387 -1 20388 -1 20389 -1 20390 -1 20391 -1 20392 -1 20393 -1 20394 -1 20395 -1 20396 -1 20397 -1 20398 -1 20399 -1 20400 -1 20401 -1 20402 -1 20403 -1 20404 -1 20405 -1 20406 -1 20407 -1 20408 -1 20409 -1 20410 -1 20411 -1 20412 -1 20413 -1 20414 -1 20415 -1 20416 -1 20417 -1 20418 -1 20419 -1 20420 -1 20421 -1 20422 -1 20423 -1 20424 -1 20425 -1 20426 -1 20427 -1 20428 -1 20429 -1 20430 -1 20431 -1 20432 -1 20433 -1 20434 -1 20435 -1 20436 -1 20437 -1 20438 -1 20439 -1 20440 -1 20441 -1 20442 -1 20443 -1 20444 -1 20445 -1 20446 -1 20447 -1 20448 -1 20449 -1 20450 -1 20451 -1 20452 -1 20453 -1 20454 -1 20455 -1 20456 -1 20457 -1 20458 -1 20459 -1 20460 -1 20461 -1 20462 -1 20463 -1 20464 -1 20465 -1 20466 -1 20467 -1 20468 -1 20469 -1 20470 -1 20471 -1 20472 -1 20473 -1 20474 -1 20475 -1 20476 -1 20477 -1 20478 -1 20479 -1 20480 -1 20481 -1 20482 -1 20483 -1 20484 -1 20485 -1 20486 -1 20487 -1 20488 -1 20489 -1 20490 -1 20491 -1 20492 -1 20493 -1 20494 -1 20495 -1 20496 -1 20497 -1 20498 -1 20499 -1 20500 -1 20501 -1 20502 -1 20503 -1 20504 -1 20505 -1 20506 -1 20507 -1 20508 -1 20509 -1 20510 -1 20511 -1 20512 -1 20513 -1 20514 -1 20515 -1 20516 -1 20517 -1 20518 -1 20519 -1 20520 -1 20521 -1 20522 -1 20523 -1 20524 -1 20525 -1 20526 -1 20527 -1 20528 -1 20529 -1 20530 -1 20531 -1 20532 -1 20533 -1 20534 -1 20535 -1 20536 -1 20537 -1 20538 -1 20539 -1 20540 -1 20541 -1 20542 -1 20543 -1 20544 -1 20545 -1 20546 -1 20547 -1 20548 -1 20549 -1 20550 -1 20551 -1 20552 -1 20553 -1 20554 -1 20555 -1 20556 -1 20557 -1 20558 -1 20559 -1 20560 -1 20561 -1 20562 -1 20563 -1 20564 -1 20565 -1 20566 -1 20567 -1 20568 -1 20569 -1 20570 -1 20571 -1 20572 -1 20573 -1 20574 -1 20575 -1 20576 -1 20577 -1 20578 -1 20579 -1 20580 -1 20581 -1 20582 -1 20583 -1 20584 -1 20585 -1 20586 -1 20587 -1 20588 -1 20589 -1 20590 -1 20591 -1 20592 -1 20593 -1 20594 -1 20595 -1 20596 -1 20597 -1 20598 -1 20599 -1 20600 -1 20601 -1 20602 -1 20603 -1 20604 -1 20605 -1 20606 -1 20607 -1 20608 -1 20609 -1 20610 -1 20611 -1 20612 -1 20613 -1 20614 -1 20615 -1 20616 -1 20617 -1 20618 -1 20619 -1 20620 -1 20621 -1 20622 -1 20623 -1 20624 -1 20625 -1 20626 -1 20627 -1 20628 -1 20629 -1 20630 -1 20631 -1 20632 -1 20633 -1 20634 -1 20635 -1 20636 -1 20637 -1 20638 -1 20639 -1 20640 -1 20641 -1 20642 -1 20643 -1 20644 -1 20645 -1 20646 -1 20647 -1 20648 -1 20649 -1 20650 -1 20651 -1 20652 -1 20653 -1 20654 -1 20655 -1 20656 -1 20657 -1 20658 -1 20659 -1 20660 -1 20661 -1 20662 -1 20663 -1 20664 -1 20665 -1 20666 -1 20667 -1 20668 -1 20669 -1 20670 -1 20671 -1 20672 -1 20673 -1 20674 -1 20675 -1 20676 -1 20677 -1 20678 -1 20679 -1 20680 -1 20681 -1 20682 -1 20683 -1 20684 -1 20685 -1 20686 -1 20687 -1 20688 -1 20689 -1 20690 -1 20691 -1 20692 -1 20693 -1 20694 -1 20695 -1 20696 -1 20697 -1 20698 -1 20699 -1 20700 -1 20701 -1 20702 -1 20703 -1 20704 -1 20705 -1 20706 -1 20707 -1 20708 -1 20709 -1 20710 -1 20711 -1 20712 -1 20713 -1 20714 -1 20715 -1 20716 -1 20717 -1 20718 -1 20719 -1 20720 -1 20721 -1 20722 -1 20723 -1 20724 -1 20725 -1 20726 -1 20727 -1 20728 -1 20729 -1 20730 -1 20731 -1 20732 -1 20733 -1 20734 -1 20735 -1 20736 -1 20737 -1 20738 -1 20739 -1 20740 -1 20741 -1 20742 -1 20743 -1 20744 -1 20745 -1 20746 -1 20747 -1 20748 -1 20749 -1 20750 -1 20751 -1 20752 -1 20753 -1 20754 -1 20755 -1 20756 -1 20757 -1 20758 -1 20759 -1 20760 -1 20761 -1 20762 -1 20763 -1 20764 -1 20765 -1 20766 -1 20767 -1 20768 -1 20769 -1 20770 -1 20771 -1 20772 -1 20773 -1 20774 -1 20775 -1 20776 -1 20777 -1 20778 -1 20779 -1 20780 -1 20781 -1 20782 -1 20783 -1 20784 -1 20785 -1 20786 -1 20787 -1 20788 -1 20789 -1 20790 -1 20791 -1 20792 -1 20793 -1 20794 -1 20795 -1 20796 -1 20797 -1 20798 -1 20799 -1 20800 -1 20801 -1 20802 -1 20803 -1 20804 -1 20805 -1 20806 -1 20807 -1 20808 -1 20809 -1 20810 -1 20811 -1 20812 -1 20813 -1 20814 -1 20815 -1 20816 -1 20817 -1 20818 -1 20819 -1 20820 -1 20821 -1 20822 -1 20823 -1 20824 -1 20825 -1 20826 -1 20827 -1 20828 -1 20829 -1 20830 -1 20831 -1 20832 -1 20833 -1 20834 -1 20835 -1 20836 -1 20837 -1 20838 -1 20839 -1 20840 -1 20841 -1 20842 -1 20843 -1 20844 -1 20845 -1 20846 -1 20847 -1 20848 -1 20849 -1 20850 -1 20851 -1 20852 -1 20853 -1 20854 -1 20855 -1 20856 -1 20857 -1 20858 -1 20859 -1 20860 -1 20861 -1 20862 -1 20863 -1 20864 -1 20865 -1 20866 -1 20867 -1 20868 -1 20869 -1 20870 -1 20871 -1 20872 -1 20873 -1 20874 -1 20875 -1 20876 -1 20877 -1 20878 -1 20879 -1 20880 -1 20881 -1 20882 -1 20883 -1 20884 -1 20885 -1 20886 -1 20887 -1 20888 -1 20889 -1 20890 -1 20891 -1 20892 -1 20893 -1 20894 -1 20895 -1 20896 -1 20897 -1 20898 -1 20899 -1 20900 -1 20901 -1 20902 -1 20903 -1 20904 -1 20905 -1 20906 -1 20907 -1 20908 -1 20909 -1 20910 -1 20911 -1 20912 -1 20913 -1 20914 -1 20915 -1 20916 -1 20917 -1 20918 -1 20919 -1 20920 -1 20921 -1 20922 -1 20923 -1 20924 -1 20925 -1 20926 -1 20927 -1 20928 -1 20929 -1 20930 -1 20931 -1 20932 -1 20933 -1 20934 -1 20935 -1 20936 -1 20937 -1 20938 -1 20939 -1 20940 -1 20941 -1 20942 -1 20943 -1 20944 -1 20945 -1 20946 -1 20947 -1 20948 -1 20949 -1 20950 -1 20951 -1 20952 -1 20953 -1 20954 -1 20955 -1 20956 -1 20957 -1 20958 -1 20959 -1 20960 -1 20961 -1 20962 -1 20963 -1 20964 -1 20965 -1 20966 -1 20967 -1 20968 -1 20969 -1 20970 -1 20971 -1 20972 -1 20973 -1 20974 -1 20975 -1 20976 -1 20977 -1 20978 -1 20979 -1 20980 -1 20981 -1 20982 -1 20983 -1 20984 -1 20985 -1 20986 -1 20987 -1 20988 -1 20989 -1 20990 -1 20991 -1 20992 -1 20993 -1 20994 -1 20995 -1 20996 -1 20997 -1 20998 -1 20999 -1 21000 -1 21001 -1 21002 -1 21003 -1 21004 -1 21005 -1 21006 -1 21007 -1 21008 -1 21009 -1 21010 -1 21011 -1 21012 -1 21013 -1 21014 -1 21015 -1 21016 -1 21017 -1 21018 -1 21019 -1 21020 -1 21021 -1 21022 -1 21023 -1 21024 -1 21025 -1 21026 -1 21027 -1 21028 -1 21029 -1 21030 -1 21031 -1 21032 -1 21033 -1 21034 -1 21035 -1 21036 -1 21037 -1 21038 -1 21039 -1 21040 -1 21041 -1 21042 -1 21043 -1 21044 -1 21045 -1 21046 -1 21047 -1 21048 -1 21049 -1 21050 -1 21051 -1 21052 -1 21053 -1 21054 -1 21055 -1 21056 -1 21057 -1 21058 -1 21059 -1 21060 -1 21061 -1 21062 -1 21063 -1 21064 -1 21065 -1 21066 -1 21067 -1 21068 -1 21069 -1 21070 -1 21071 -1 21072 -1 21073 -1 21074 -1 21075 -1 21076 -1 21077 -1 21078 -1 21079 -1 21080 -1 21081 -1 21082 -1 21083 -1 21084 -1 21085 -1 21086 -1 21087 -1 21088 -1 21089 -1 21090 -1 21091 -1 21092 -1 21093 -1 21094 -1 21095 -1 21096 -1 21097 -1 21098 -1 21099 -1 21100 -1 21101 -1 21102 -1 21103 -1 21104 -1 21105 -1 21106 -1 21107 -1 21108 -1 21109 -1 21110 -1 21111 -1 21112 -1 21113 -1 21114 -1 21115 -1 21116 -1 21117 -1 21118 -1 21119 -1 21120 -1 21121 -1 21122 -1 21123 -1 21124 -1 21125 -1 21126 -1 21127 -1 21128 -1 21129 -1 21130 -1 21131 -1 21132 -1 21133 -1 21134 -1 21135 -1 21136 -1 21137 -1 21138 -1 21139 -1 21140 -1 21141 -1 21142 -1 21143 -1 21144 -1 21145 -1 21146 -1 21147 -1 21148 -1 21149 -1 21150 -1 21151 -1 21152 -1 21153 -1 21154 -1 21155 -1 21156 -1 21157 -1 21158 -1 21159 -1 21160 -1 21161 -1 21162 -1 21163 -1 21164 -1 21165 -1 21166 -1 21167 -1 21168 -1 21169 -1 21170 -1 21171 -1 21172 -1 21173 -1 21174 -1 21175 -1 21176 -1 21177 -1 21178 -1 21179 -1 21180 -1 21181 -1 21182 -1 21183 -1 21184 -1 21185 -1 21186 -1 21187 -1 21188 -1 21189 -1 21190 -1 21191 -1 21192 -1 21193 -1 21194 -1 21195 -1 21196 -1 21197 -1 21198 -1 21199 -1 21200 -1 21201 -1 21202 -1 21203 -1 21204 -1 21205 -1 21206 -1 21207 -1 21208 -1 21209 -1 21210 -1 21211 -1 21212 -1 21213 -1 21214 -1 21215 -1 21216 -1 21217 -1 21218 -1 21219 -1 21220 -1 21221 -1 21222 -1 21223 -1 21224 -1 21225 -1 21226 -1 21227 -1 21228 -1 21229 -1 21230 -1 21231 -1 21232 -1 21233 -1 21234 -1 21235 -1 21236 -1 21237 -1 21238 -1 21239 -1 21240 -1 21241 -1 21242 -1 21243 -1 21244 -1 21245 -1 21246 -1 21247 -1 21248 -1 21249 -1 21250 -1 21251 -1 21252 -1 21253 -1 21254 -1 21255 -1 21256 -1 21257 -1 21258 -1 21259 -1 21260 -1 21261 -1 21262 -1 21263 -1 21264 -1 21265 -1 21266 -1 21267 -1 21268 -1 21269 -1 21270 -1 21271 -1 21272 -1 21273 -1 21274 -1 21275 -1 21276 -1 21277 -1 21278 -1 21279 -1 21280 -1 21281 -1 21282 -1 21283 -1 21284 -1 21285 -1 21286 -1 21287 -1 21288 -1 21289 -1 21290 -1 21291 -1 21292 -1 21293 -1 21294 -1 21295 -1 21296 -1 21297 -1 21298 -1 21299 -1 21300 -1 21301 -1 21302 -1 21303 -1 21304 -1 21305 -1 21306 -1 21307 -1 21308 -1 21309 -1 21310 -1 21311 -1 21312 -1 21313 -1 21314 -1 21315 -1 21316 -1 21317 -1 21318 -1 21319 -1 21320 -1 21321 -1 21322 -1 21323 -1 21324 -1 21325 -1 21326 -1 21327 -1 21328 -1 21329 -1 21330 -1 21331 -1 21332 -1 21333 -1 21334 -1 21335 -1 21336 -1 21337 -1 21338 -1 21339 -1 21340 -1 21341 -1 21342 -1 21343 -1 21344 -1 21345 -1 21346 -1 21347 -1 21348 -1 21349 -1 21350 -1 21351 -1 21352 -1 21353 -1 21354 -1 21355 -1 21356 -1 21357 -1 21358 -1 21359 -1 21360 -1 21361 -1 21362 -1 21363 -1 21364 -1 21365 -1 21366 -1 21367 -1 21368 -1 21369 -1 21370 -1 21371 -1 21372 -1 21373 -1 21374 -1 21375 -1 21376 -1 21377 -1 21378 -1 21379 -1 21380 -1 21381 -1 21382 -1 21383 -1 21384 -1 21385 -1 21386 -1 21387 -1 21388 -1 21389 -1 21390 -1 21391 -1 21392 -1 21393 -1 21394 -1 21395 -1 21396 -1 21397 -1 21398 -1 21399 -1 21400 -1 21401 -1 21402 -1 21403 -1 21404 -1 21405 -1 21406 -1 21407 -1 21408 -1 21409 -1 21410 -1 21411 -1 21412 -1 21413 -1 21414 -1 21415 -1 21416 -1 21417 -1 21418 -1 21419 -1 21420 -1 21421 -1 21422 -1 21423 -1 21424 -1 21425 -1 21426 -1 21427 -1 21428 -1 21429 -1 21430 -1 21431 -1 21432 -1 21433 -1 21434 -1 21435 -1 21436 -1 21437 -1 21438 -1 21439 -1 21440 -1 21441 -1 21442 -1 21443 -1 21444 -1 21445 -1 21446 -1 21447 -1 21448 -1 21449 -1 21450 -1 21451 -1 21452 -1 21453 -1 21454 -1 21455 -1 21456 -1 21457 -1 21458 -1 21459 -1 21460 -1 21461 -1 21462 -1 21463 -1 21464 -1 21465 -1 21466 -1 21467 -1 21468 -1 21469 -1 21470 -1 21471 -1 21472 -1 21473 -1 21474 -1 21475 -1 21476 -1 21477 -1 21478 -1 21479 -1 21480 -1 21481 -1 21482 -1 21483 -1 21484 -1 21485 -1 21486 -1 21487 -1 21488 -1 21489 -1 21490 -1 21491 -1 21492 -1 21493 -1 21494 -1 21495 -1 21496 -1 21497 -1 21498 -1 21499 -1 21500 -1 21501 -1 21502 -1 21503 -1 21504 -1 21505 -1 21506 -1 21507 -1 21508 -1 21509 -1 21510 -1 21511 -1 21512 -1 21513 -1 21514 -1 21515 -1 21516 -1 21517 -1 21518 -1 21519 -1 21520 -1 21521 -1 21522 -1 21523 -1 21524 -1 21525 -1 21526 -1 21527 -1 21528 -1 21529 -1 21530 -1 21531 -1 21532 -1 21533 -1 21534 -1 21535 -1 21536 -1 21537 -1 21538 -1 21539 -1 21540 -1 21541 -1 21542 -1 21543 -1 21544 -1 21545 -1 21546 -1 21547 -1 21548 -1 21549 -1 21550 -1 21551 -1 21552 -1 21553 -1 21554 -1 21555 -1 21556 -1 21557 -1 21558 -1 21559 -1 21560 -1 21561 -1 21562 -1 21563 -1 21564 -1 21565 -1 21566 -1 21567 -1 21568 -1 21569 -1 21570 -1 21571 -1 21572 -1 21573 -1 21574 -1 21575 -1 21576 -1 21577 -1 21578 -1 21579 -1 21580 -1 21581 -1 21582 -1 21583 -1 21584 -1 21585 -1 21586 -1 21587 -1 21588 -1 21589 -1 21590 -1 21591 -1 21592 -1 21593 -1 21594 -1 21595 -1 21596 -1 21597 -1 21598 -1 21599 -1 21600 -1 21601 -1 21602 -1 21603 -1 21604 -1 21605 -1 21606 -1 21607 -1 21608 -1 21609 -1 21610 -1 21611 -1 21612 -1 21613 -1 21614 -1 21615 -1 21616 -1 21617 -1 21618 -1 21619 -1 21620 -1 21621 -1 21622 -1 21623 -1 21624 -1 21625 -1 21626 -1 21627 -1 21628 -1 21629 -1 21630 -1 21631 -1 21632 -1 21633 -1 21634 -1 21635 -1 21636 -1 21637 -1 21638 -1 21639 -1 21640 -1 21641 -1 21642 -1 21643 -1 21644 -1 21645 -1 21646 -1 21647 -1 21648 -1 21649 -1 21650 -1 21651 -1 21652 -1 21653 -1 21654 -1 21655 -1 21656 -1 21657 -1 21658 -1 21659 -1 21660 -1 21661 -1 21662 -1 21663 -1 21664 -1 21665 -1 21666 -1 21667 -1 21668 -1 21669 -1 21670 -1 21671 -1 21672 -1 21673 -1 21674 -1 21675 -1 21676 -1 21677 -1 21678 -1 21679 -1 21680 -1 21681 -1 21682 -1 21683 -1 21684 -1 21685 -1 21686 -1 21687 -1 21688 -1 21689 -1 21690 -1 21691 -1 21692 -1 21693 -1 21694 -1 21695 -1 21696 -1 21697 -1 21698 -1 21699 -1 21700 -1 21701 -1 21702 -1 21703 -1 21704 -1 21705 -1 21706 -1 21707 -1 21708 -1 21709 -1 21710 -1 21711 -1 21712 -1 21713 -1 21714 -1 21715 -1 21716 -1 21717 -1 21718 -1 21719 -1 21720 -1 21721 -1 21722 -1 21723 -1 21724 -1 21725 -1 21726 -1 21727 -1 21728 -1 21729 -1 21730 -1 21731 -1 21732 -1 21733 -1 21734 -1 21735 -1 21736 -1 21737 -1 21738 -1 21739 -1 21740 -1 21741 -1 21742 -1 21743 -1 21744 -1 21745 -1 21746 -1 21747 -1 21748 -1 21749 -1 21750 -1 21751 -1 21752 -1 21753 -1 21754 -1 21755 -1 21756 -1 21757 -1 21758 -1 21759 -1 21760 -1 21761 -1 21762 -1 21763 -1 21764 -1 21765 -1 21766 -1 21767 -1 21768 -1 21769 -1 21770 -1 21771 -1 21772 -1 21773 -1 21774 -1 21775 -1 21776 -1 21777 -1 21778 -1 21779 -1 21780 -1 21781 -1 21782 -1 21783 -1 21784 -1 21785 -1 21786 -1 21787 -1 21788 -1 21789 -1 21790 -1 21791 -1 21792 -1 21793 -1 21794 -1 21795 -1 21796 -1 21797 -1 21798 -1 21799 -1 21800 -1 21801 -1 21802 -1 21803 -1 21804 -1 21805 -1 21806 -1 21807 -1 21808 -1 21809 -1 21810 -1 21811 -1 21812 -1 21813 -1 21814 -1 21815 -1 21816 -1 21817 -1 21818 -1 21819 -1 21820 -1 21821 -1 21822 -1 21823 -1 21824 -1 21825 -1 21826 -1 21827 -1 21828 -1 21829 -1 21830 -1 21831 -1 21832 -1 21833 -1 21834 -1 21835 -1 21836 -1 21837 -1 21838 -1 21839 -1 21840 -1 21841 -1 21842 -1 21843 -1 21844 -1 21845 -1 21846 -1 21847 -1 21848 -1 21849 -1 21850 -1 21851 -1 21852 -1 21853 -1 21854 -1 21855 -1 21856 -1 21857 -1 21858 -1 21859 -1 21860 -1 21861 -1 21862 -1 21863 -1 21864 -1 21865 -1 21866 -1 21867 -1 21868 -1 21869 -1 21870 -1 21871 -1 21872 -1 21873 -1 21874 -1 21875 -1 21876 -1 21877 -1 21878 -1 21879 -1 21880 -1 21881 -1 21882 -1 21883 -1 21884 -1 21885 -1 21886 -1 21887 -1 21888 -1 21889 -1 21890 -1 21891 -1 21892 -1 21893 -1 21894 -1 21895 -1 21896 -1 21897 -1 21898 -1 21899 -1 21900 -1 21901 -1 21902 -1 21903 -1 21904 -1 21905 -1 21906 -1 21907 -1 21908 -1 21909 -1 21910 -1 21911 -1 21912 -1 21913 -1 21914 -1 21915 -1 21916 -1 21917 -1 21918 -1 21919 -1 21920 -1 21921 -1 21922 -1 21923 -1 21924 -1 21925 -1 21926 -1 21927 -1 21928 -1 21929 -1 21930 -1 21931 -1 21932 -1 21933 -1 21934 -1 21935 -1 21936 -1 21937 -1 21938 -1 21939 -1 21940 -1 21941 -1 21942 -1 21943 -1 21944 -1 21945 -1 21946 -1 21947 -1 21948 -1 21949 -1 21950 -1 21951 -1 21952 -1 21953 -1 21954 -1 21955 -1 21956 -1 21957 -1 21958 -1 21959 -1 21960 -1 21961 -1 21962 -1 21963 -1 21964 -1 21965 -1 21966 -1 21967 -1 21968 -1 21969 -1 21970 -1 21971 -1 21972 -1 21973 -1 21974 -1 21975 -1 21976 -1 21977 -1 21978 -1 21979 -1 21980 -1 21981 -1 21982 -1 21983 -1 21984 -1 21985 -1 21986 -1 21987 -1 21988 -1 21989 -1 21990 -1 21991 -1 21992 -1 21993 -1 21994 -1 21995 -1 21996 -1 21997 -1 21998 -1 21999 -1 22000 -1 22001 -1 22002 -1 22003 -1 22004 -1 22005 -1 22006 -1 22007 -1 22008 -1 22009 -1 22010 -1 22011 -1 22012 -1 22013 -1 22014 -1 22015 -1 22016 -1 22017 -1 22018 -1 22019 -1 22020 -1 22021 -1 22022 -1 22023 -1 22024 -1 22025 -1 22026 -1 22027 -1 22028 -1 22029 -1 22030 -1 22031 -1 22032 -1 22033 -1 22034 -1 22035 -1 22036 -1 22037 -1 22038 -1 22039 -1 22040 -1 22041 -1 22042 -1 22043 -1 22044 -1 22045 -1 22046 -1 22047 -1 22048 -1 22049 -1 22050 -1 22051 -1 22052 -1 22053 -1 22054 -1 22055 -1 22056 -1 22057 -1 22058 -1 22059 -1 22060 -1 22061 -1 22062 -1 22063 -1 22064 -1 22065 -1 22066 -1 22067 -1 22068 -1 22069 -1 22070 -1 22071 -1 22072 -1 22073 -1 22074 -1 22075 -1 22076 -1 22077 -1 22078 -1 22079 -1 22080 -1 22081 -1 22082 -1 22083 -1 22084 -1 22085 -1 22086 -1 22087 -1 22088 -1 22089 -1 22090 -1 22091 -1 22092 -1 22093 -1 22094 -1 22095 -1 22096 -1 22097 -1 22098 -1 22099 -1 22100 -1 22101 -1 22102 -1 22103 -1 22104 -1 22105 -1 22106 -1 22107 -1 22108 -1 22109 -1 22110 -1 22111 -1 22112 -1 22113 -1 22114 -1 22115 -1 22116 -1 22117 -1 22118 -1 22119 -1 22120 -1 22121 -1 22122 -1 22123 -1 22124 -1 22125 -1 22126 -1 22127 -1 22128 -1 22129 -1 22130 -1 22131 -1 22132 -1 22133 -1 22134 -1 22135 -1 22136 -1 22137 -1 22138 -1 22139 -1 22140 -1 22141 -1 22142 -1 22143 -1 22144 -1 22145 -1 22146 -1 22147 -1 22148 -1 22149 -1 22150 -1 22151 -1 22152 -1 22153 -1 22154 -1 22155 -1 22156 -1 22157 -1 22158 -1 22159 -1 22160 -1 22161 -1 22162 -1 22163 -1 22164 -1 22165 -1 22166 -1 22167 -1 22168 -1 22169 -1 22170 -1 22171 -1 22172 -1 22173 -1 22174 -1 22175 -1 22176 -1 22177 -1 22178 -1 22179 -1 22180 -1 22181 -1 22182 -1 22183 -1 22184 -1 22185 -1 22186 -1 22187 -1 22188 -1 22189 -1 22190 -1 22191 -1 22192 -1 22193 -1 22194 -1 22195 -1 22196 -1 22197 -1 22198 -1 22199 -1 22200 -1 22201 -1 22202 -1 22203 -1 22204 -1 22205 -1 22206 -1 22207 -1 22208 -1 22209 -1 22210 -1 22211 -1 22212 -1 22213 -1 22214 -1 22215 -1 22216 -1 22217 -1 22218 -1 22219 -1 22220 -1 22221 -1 22222 -1 22223 -1 22224 -1 22225 -1 22226 -1 22227 -1 22228 -1 22229 -1 22230 -1 22231 -1 22232 -1 22233 -1 22234 -1 22235 -1 22236 -1 22237 -1 22238 -1 22239 -1 22240 -1 22241 -1 22242 -1 22243 -1 22244 -1 22245 -1 22246 -1 22247 -1 22248 -1 22249 -1 22250 -1 22251 -1 22252 -1 22253 -1 22254 -1 22255 -1 22256 -1 22257 -1 22258 -1 22259 -1 22260 -1 22261 -1 22262 -1 22263 -1 22264 -1 22265 -1 22266 -1 22267 -1 22268 -1 22269 -1 22270 -1 22271 -1 22272 -1 22273 -1 22274 -1 22275 -1 22276 -1 22277 -1 22278 -1 22279 -1 22280 -1 22281 -1 22282 -1 22283 -1 22284 -1 22285 -1 22286 -1 22287 -1 22288 -1 22289 -1 22290 -1 22291 -1 22292 -1 22293 -1 22294 -1 22295 -1 22296 -1 22297 -1 22298 -1 22299 -1 22300 -1 22301 -1 22302 -1 22303 -1 22304 -1 22305 -1 22306 -1 22307 -1 22308 -1 22309 -1 22310 -1 22311 -1 22312 -1 22313 -1 22314 -1 22315 -1 22316 -1 22317 -1 22318 -1 22319 -1 22320 -1 22321 -1 22322 -1 22323 -1 22324 -1 22325 -1 22326 -1 22327 -1 22328 -1 22329 -1 22330 -1 22331 -1 22332 -1 22333 -1 22334 -1 22335 -1 22336 -1 22337 -1 22338 -1 22339 -1 22340 -1 22341 -1 22342 -1 22343 -1 22344 -1 22345 -1 22346 -1 22347 -1 22348 -1 22349 -1 22350 -1 22351 -1 22352 -1 22353 -1 22354 -1 22355 -1 22356 -1 22357 -1 22358 -1 22359 -1 22360 -1 22361 -1 22362 -1 22363 -1 22364 -1 22365 -1 22366 -1 22367 -1 22368 -1 22369 -1 22370 -1 22371 -1 22372 -1 22373 -1 22374 -1 22375 -1 22376 -1 22377 -1 22378 -1 22379 -1 22380 -1 22381 -1 22382 -1 22383 -1 22384 -1 22385 -1 22386 -1 22387 -1 22388 -1 22389 -1 22390 -1 22391 -1 22392 -1 22393 -1 22394 -1 22395 -1 22396 -1 22397 -1 22398 -1 22399 -1 22400 -1 22401 -1 22402 -1 22403 -1 22404 -1 22405 -1 22406 -1 22407 -1 22408 -1 22409 -1 22410 -1 22411 -1 22412 -1 22413 -1 22414 -1 22415 -1 22416 -1 22417 -1 22418 -1 22419 -1 22420 -1 22421 -1 22422 -1 22423 -1 22424 -1 22425 -1 22426 -1 22427 -1 22428 -1 22429 -1 22430 -1 22431 -1 22432 -1 22433 -1 22434 -1 22435 -1 22436 -1 22437 -1 22438 -1 22439 -1 22440 -1 22441 -1 22442 -1 22443 -1 22444 -1 22445 -1 22446 -1 22447 -1 22448 -1 22449 -1 22450 -1 22451 -1 22452 -1 22453 -1 22454 -1 22455 -1 22456 -1 22457 -1 22458 -1 22459 -1 22460 -1 22461 -1 22462 -1 22463 -1 22464 -1 22465 -1 22466 -1 22467 -1 22468 -1 22469 -1 22470 -1 22471 -1 22472 -1 22473 -1 22474 -1 22475 -1 22476 -1 22477 -1 22478 -1 22479 -1 22480 -1 22481 -1 22482 -1 22483 -1 22484 -1 22485 -1 22486 -1 22487 -1 22488 -1 22489 -1 22490 -1 22491 -1 22492 -1 22493 -1 22494 -1 22495 -1 22496 -1 22497 -1 22498 -1 22499 -1 22500 -1 22501 -1 22502 -1 22503 -1 22504 -1 22505 -1 22506 -1 22507 -1 22508 -1 22509 -1 22510 -1 22511 -1 22512 -1 22513 -1 22514 -1 22515 -1 22516 -1 22517 -1 22518 -1 22519 -1 22520 -1 22521 -1 22522 -1 22523 -1 22524 -1 22525 -1 22526 -1 22527 -1 22528 -1 22529 -1 22530 -1 22531 -1 22532 -1 22533 -1 22534 -1 22535 -1 22536 -1 22537 -1 22538 -1 22539 -1 22540 -1 22541 -1 22542 -1 22543 -1 22544 -1 22545 -1 22546 -1 22547 -1 22548 -1 22549 -1 22550 -1 22551 -1 22552 -1 22553 -1 22554 -1 22555 -1 22556 -1 22557 -1 22558 -1 22559 -1 22560 -1 22561 -1 22562 -1 22563 -1 22564 -1 22565 -1 22566 -1 22567 -1 22568 -1 22569 -1 22570 -1 22571 -1 22572 -1 22573 -1 22574 -1 22575 -1 22576 -1 22577 -1 22578 -1 22579 -1 22580 -1 22581 -1 22582 -1 22583 -1 22584 -1 22585 -1 22586 -1 22587 -1 22588 -1 22589 -1 22590 -1 22591 -1 22592 -1 22593 -1 22594 -1 22595 -1 22596 -1 22597 -1 22598 -1 22599 -1 22600 -1 22601 -1 22602 -1 22603 -1 22604 -1 22605 -1 22606 -1 22607 -1 22608 -1 22609 -1 22610 -1 22611 -1 22612 -1 22613 -1 22614 -1 22615 -1 22616 -1 22617 -1 22618 -1 22619 -1 22620 -1 22621 -1 22622 -1 22623 -1 22624 -1 22625 -1 22626 -1 22627 -1 22628 -1 22629 -1 22630 -1 22631 -1 22632 -1 22633 -1 22634 -1 22635 -1 22636 -1 22637 -1 22638 -1 22639 -1 22640 -1 22641 -1 22642 -1 22643 -1 22644 -1 22645 -1 22646 -1 22647 -1 22648 -1 22649 -1 22650 -1 22651 -1 22652 -1 22653 -1 22654 -1 22655 -1 22656 -1 22657 -1 22658 -1 22659 -1 22660 -1 22661 -1 22662 -1 22663 -1 22664 -1 22665 -1 22666 -1 22667 -1 22668 -1 22669 -1 22670 -1 22671 -1 22672 -1 22673 -1 22674 -1 22675 -1 22676 -1 22677 -1 22678 -1 22679 -1 22680 -1 22681 -1 22682 -1 22683 -1 22684 -1 22685 -1 22686 -1 22687 -1 22688 -1 22689 -1 22690 -1 22691 -1 22692 -1 22693 -1 22694 -1 22695 -1 22696 -1 22697 -1 22698 -1 22699 -1 22700 -1 22701 -1 22702 -1 22703 -1 22704 -1 22705 -1 22706 -1 22707 -1 22708 -1 22709 -1 22710 -1 22711 -1 22712 -1 22713 -1 22714 -1 22715 -1 22716 -1 22717 -1 22718 -1 22719 -1 22720 -1 22721 -1 22722 -1 22723 -1 22724 -1 22725 -1 22726 -1 22727 -1 22728 -1 22729 -1 22730 -1 22731 -1 22732 -1 22733 -1 22734 -1 22735 -1 22736 -1 22737 -1 22738 -1 22739 -1 22740 -1 22741 -1 22742 -1 22743 -1 22744 -1 22745 -1 22746 -1 22747 -1 22748 -1 22749 -1 22750 -1 22751 -1 22752 -1 22753 -1 22754 -1 22755 -1 22756 -1 22757 -1 22758 -1 22759 -1 22760 -1 22761 -1 22762 -1 22763 -1 22764 -1 22765 -1 22766 -1 22767 -1 22768 -1 22769 -1 22770 -1 22771 -1 22772 -1 22773 -1 22774 -1 22775 -1 22776 -1 22777 -1 22778 -1 22779 -1 22780 -1 22781 -1 22782 -1 22783 -1 22784 -1 22785 -1 22786 -1 22787 -1 22788 -1 22789 -1 22790 -1 22791 -1 22792 -1 22793 -1 22794 -1 22795 -1 22796 -1 22797 -1 22798 -1 22799 -1 22800 -1 22801 -1 22802 -1 22803 -1 22804 -1 22805 -1 22806 -1 22807 -1 22808 -1 22809 -1 22810 -1 22811 -1 22812 -1 22813 -1 22814 -1 22815 -1 22816 -1 22817 -1 22818 -1 22819 -1 22820 -1 22821 -1 22822 -1 22823 -1 22824 -1 22825 -1 22826 -1 22827 -1 22828 -1 22829 -1 22830 -1 22831 -1 22832 -1 22833 -1 22834 -1 22835 -1 22836 -1 22837 -1 22838 -1 22839 -1 22840 -1 22841 -1 22842 -1 22843 -1 22844 -1 22845 -1 22846 -1 22847 -1 22848 -1 22849 -1 22850 -1 22851 -1 22852 -1 22853 -1 22854 -1 22855 -1 22856 -1 22857 -1 22858 -1 22859 -1 22860 -1 22861 -1 22862 -1 22863 -1 22864 -1 22865 -1 22866 -1 22867 -1 22868 -1 22869 -1 22870 -1 22871 -1 22872 -1 22873 -1 22874 -1 22875 -1 22876 -1 22877 -1 22878 -1 22879 -1 22880 -1 22881 -1 22882 -1 22883 -1 22884 -1 22885 -1 22886 -1 22887 -1 22888 -1 22889 -1 22890 -1 22891 -1 22892 -1 22893 -1 22894 -1 22895 -1 22896 -1 22897 -1 22898 -1 22899 -1 22900 -1 22901 -1 22902 -1 22903 -1 22904 -1 22905 -1 22906 -1 22907 -1 22908 -1 22909 -1 22910 -1 22911 -1 22912 -1 22913 -1 22914 -1 22915 -1 22916 -1 22917 -1 22918 -1 22919 -1 22920 -1 22921 -1 22922 -1 22923 -1 22924 -1 22925 -1 22926 -1 22927 -1 22928 -1 22929 -1 22930 -1 22931 -1 22932 -1 22933 -1 22934 -1 22935 -1 22936 -1 22937 -1 22938 -1 22939 -1 22940 -1 22941 -1 22942 -1 22943 -1 22944 -1 22945 -1 22946 -1 22947 -1 22948 -1 22949 -1 22950 -1 22951 -1 22952 -1 22953 -1 22954 -1 22955 -1 22956 -1 22957 -1 22958 -1 22959 -1 22960 -1 22961 -1 22962 -1 22963 -1 22964 -1 22965 -1 22966 -1 22967 -1 22968 -1 22969 -1 22970 -1 22971 -1 22972 -1 22973 -1 22974 -1 22975 -1 22976 -1 22977 -1 22978 -1 22979 -1 22980 -1 22981 -1 22982 -1 22983 -1 22984 -1 22985 -1 22986 -1 22987 -1 22988 -1 22989 -1 22990 -1 22991 -1 22992 -1 22993 -1 22994 -1 22995 -1 22996 -1 22997 -1 22998 -1 22999 -1 23000 -1 23001 -1 23002 -1 23003 -1 23004 -1 23005 -1 23006 -1 23007 -1 23008 -1 23009 -1 23010 -1 23011 -1 23012 -1 23013 -1 23014 -1 23015 -1 23016 -1 23017 -1 23018 -1 23019 -1 23020 -1 23021 -1 23022 -1 23023 -1 23024 -1 23025 -1 23026 -1 23027 -1 23028 -1 23029 -1 23030 -1 23031 -1 23032 -1 23033 -1 23034 -1 23035 -1 23036 -1 23037 -1 23038 -1 23039 -1 23040 -1 23041 -1 23042 -1 23043 -1 23044 -1 23045 -1 23046 -1 23047 -1 23048 -1 23049 -1 23050 -1 23051 -1 23052 -1 23053 -1 23054 -1 23055 -1 23056 -1 23057 -1 23058 -1 23059 -1 23060 -1 23061 -1 23062 -1 23063 -1 23064 -1 23065 -1 23066 -1 23067 -1 23068 -1 23069 -1 23070 -1 23071 -1 23072 -1 23073 -1 23074 -1 23075 -1 23076 -1 23077 -1 23078 -1 23079 -1 23080 -1 23081 -1 23082 -1 23083 -1 23084 -1 23085 -1 23086 -1 23087 -1 23088 -1 23089 -1 23090 -1 23091 -1 23092 -1 23093 -1 23094 -1 23095 -1 23096 -1 23097 -1 23098 -1 23099 -1 23100 -1 23101 -1 23102 -1 23103 -1 23104 -1 23105 -1 23106 -1 23107 -1 23108 -1 23109 -1 23110 -1 23111 -1 23112 -1 23113 -1 23114 -1 23115 -1 23116 -1 23117 -1 23118 -1 23119 -1 23120 -1 23121 -1 23122 -1 23123 -1 23124 -1 23125 -1 23126 -1 23127 -1 23128 -1 23129 -1 23130 -1 23131 -1 23132 -1 23133 -1 23134 -1 23135 -1 23136 -1 23137 -1 23138 -1 23139 -1 23140 -1 23141 -1 23142 -1 23143 -1 23144 -1 23145 -1 23146 -1 23147 -1 23148 -1 23149 -1 23150 -1 23151 -1 23152 -1 23153 -1 23154 -1 23155 -1 23156 -1 23157 -1 23158 -1 23159 -1 23160 -1 23161 -1 23162 -1 23163 -1 23164 -1 23165 -1 23166 -1 23167 -1 23168 -1 23169 -1 23170 -1 23171 -1 23172 -1 23173 -1 23174 -1 23175 -1 23176 -1 23177 -1 23178 -1 23179 -1 23180 -1 23181 -1 23182 -1 23183 -1 23184 -1 23185 -1 23186 -1 23187 -1 23188 -1 23189 -1 23190 -1 23191 -1 23192 -1 23193 -1 23194 -1 23195 -1 23196 -1 23197 -1 23198 -1 23199 -1 23200 -1 23201 -1 23202 -1 23203 -1 23204 -1 23205 -1 23206 -1 23207 -1 23208 -1 23209 -1 23210 -1 23211 -1 23212 -1 23213 -1 23214 -1 23215 -1 23216 -1 23217 -1 23218 -1 23219 -1 23220 -1 23221 -1 23222 -1 23223 -1 23224 -1 23225 -1 23226 -1 23227 -1 23228 -1 23229 -1 23230 -1 23231 -1 23232 -1 23233 -1 23234 -1 23235 -1 23236 -1 23237 -1 23238 -1 23239 -1 23240 -1 23241 -1 23242 -1 23243 -1 23244 -1 23245 -1 23246 -1 23247 -1 23248 -1 23249 -1 23250 -1 23251 -1 23252 -1 23253 -1 23254 -1 23255 -1 23256 -1 23257 -1 23258 -1 23259 -1 23260 -1 23261 -1 23262 -1 23263 -1 23264 -1 23265 -1 23266 -1 23267 -1 23268 -1 23269 -1 23270 -1 23271 -1 23272 -1 23273 -1 23274 -1 23275 -1 23276 -1 23277 -1 23278 -1 23279 -1 23280 -1 23281 -1 23282 -1 23283 -1 23284 -1 23285 -1 23286 -1 23287 -1 23288 -1 23289 -1 23290 -1 23291 -1 23292 -1 23293 -1 23294 -1 23295 -1 23296 -1 23297 -1 23298 -1 23299 -1 23300 -1 23301 -1 23302 -1 23303 -1 23304 -1 23305 -1 23306 -1 23307 -1 23308 -1 23309 -1 23310 -1 23311 -1 23312 -1 23313 -1 23314 -1 23315 -1 23316 -1 23317 -1 23318 -1 23319 -1 23320 -1 23321 -1 23322 -1 23323 -1 23324 -1 23325 -1 23326 -1 23327 -1 23328 -1 23329 -1 23330 -1 23331 -1 23332 -1 23333 -1 23334 -1 23335 -1 23336 -1 23337 -1 23338 -1 23339 -1 23340 -1 23341 -1 23342 -1 23343 -1 23344 -1 23345 -1 23346 -1 23347 -1 23348 -1 23349 -1 23350 -1 23351 -1 23352 -1 23353 -1 23354 -1 23355 -1 23356 -1 23357 -1 23358 -1 23359 -1 23360 -1 23361 -1 23362 -1 23363 -1 23364 -1 23365 -1 23366 -1 23367 -1 23368 -1 23369 -1 23370 -1 23371 -1 23372 -1 23373 -1 23374 -1 23375 -1 23376 -1 23377 -1 23378 -1 23379 -1 23380 -1 23381 -1 23382 -1 23383 -1 23384 -1 23385 -1 23386 -1 23387 -1 23388 -1 23389 -1 23390 -1 23391 -1 23392 -1 23393 -1 23394 -1 23395 -1 23396 -1 23397 -1 23398 -1 23399 -1 23400 -1 23401 -1 23402 -1 23403 -1 23404 -1 23405 -1 23406 -1 23407 -1 23408 -1 23409 -1 23410 -1 23411 -1 23412 -1 23413 -1 23414 -1 23415 -1 23416 -1 23417 -1 23418 -1 23419 -1 23420 -1 23421 -1 23422 -1 23423 -1 23424 -1 23425 -1 23426 -1 23427 -1 23428 -1 23429 -1 23430 -1 23431 -1 23432 -1 23433 -1 23434 -1 23435 -1 23436 -1 23437 -1 23438 -1 23439 -1 23440 -1 23441 -1 23442 -1 23443 -1 23444 -1 23445 -1 23446 -1 23447 -1 23448 -1 23449 -1 23450 -1 23451 -1 23452 -1 23453 -1 23454 -1 23455 -1 23456 -1 23457 -1 23458 -1 23459 -1 23460 -1 23461 -1 23462 -1 23463 -1 23464 -1 23465 -1 23466 -1 23467 -1 23468 -1 23469 -1 23470 -1 23471 -1 23472 -1 23473 -1 23474 -1 23475 -1 23476 -1 23477 -1 23478 -1 23479 -1 23480 -1 23481 -1 23482 -1 23483 -1 23484 -1 23485 -1 23486 -1 23487 -1 23488 -1 23489 -1 23490 -1 23491 -1 23492 -1 23493 -1 23494 -1 23495 -1 23496 -1 23497 -1 23498 -1 23499 -1 23500 -1 23501 -1 23502 -1 23503 -1 23504 -1 23505 -1 23506 -1 23507 -1 23508 -1 23509 -1 23510 -1 23511 -1 23512 -1 23513 -1 23514 -1 23515 -1 23516 -1 23517 -1 23518 -1 23519 -1 23520 -1 23521 -1 23522 -1 23523 -1 23524 -1 23525 -1 23526 -1 23527 -1 23528 -1 23529 -1 23530 -1 23531 -1 23532 -1 23533 -1 23534 -1 23535 -1 23536 -1 23537 -1 23538 -1 23539 -1 23540 -1 23541 -1 23542 -1 23543 -1 23544 -1 23545 -1 23546 -1 23547 -1 23548 -1 23549 -1 23550 -1 23551 -1 23552 -1 23553 -1 23554 -1 23555 -1 23556 -1 23557 -1 23558 -1 23559 -1 23560 -1 23561 -1 23562 -1 23563 -1 23564 -1 23565 -1 23566 -1 23567 -1 23568 -1 23569 -1 23570 -1 23571 -1 23572 -1 23573 -1 23574 -1 23575 -1 23576 -1 23577 -1 23578 -1 23579 -1 23580 -1 23581 -1 23582 -1 23583 -1 23584 -1 23585 -1 23586 -1 23587 -1 23588 -1 23589 -1 23590 -1 23591 -1 23592 -1 23593 -1 23594 -1 23595 -1 23596 -1 23597 -1 23598 -1 23599 -1 23600 -1 23601 -1 23602 -1 23603 -1 23604 -1 23605 -1 23606 -1 23607 -1 23608 -1 23609 -1 23610 -1 23611 -1 23612 -1 23613 -1 23614 -1 23615 -1 23616 -1 23617 -1 23618 -1 23619 -1 23620 -1 23621 -1 23622 -1 23623 -1 23624 -1 23625 -1 23626 -1 23627 -1 23628 -1 23629 -1 23630 -1 23631 -1 23632 -1 23633 -1 23634 -1 23635 -1 23636 -1 23637 -1 23638 -1 23639 -1 23640 -1 23641 -1 23642 -1 23643 -1 23644 -1 23645 -1 23646 -1 23647 -1 23648 -1 23649 -1 23650 -1 23651 -1 23652 -1 23653 -1 23654 -1 23655 -1 23656 -1 23657 -1 23658 -1 23659 -1 23660 -1 23661 -1 23662 -1 23663 -1 23664 -1 23665 -1 23666 -1 23667 -1 23668 -1 23669 -1 23670 -1 23671 -1 23672 -1 23673 -1 23674 -1 23675 -1 23676 -1 23677 -1 23678 -1 23679 -1 23680 -1 23681 -1 23682 -1 23683 -1 23684 -1 23685 -1 23686 -1 23687 -1 23688 -1 23689 -1 23690 -1 23691 -1 23692 -1 23693 -1 23694 -1 23695 -1 23696 -1 23697 -1 23698 -1 23699 -1 23700 -1 23701 -1 23702 -1 23703 -1 23704 -1 23705 -1 23706 -1 23707 -1 23708 -1 23709 -1 23710 -1 23711 -1 23712 -1 23713 -1 23714 -1 23715 -1 23716 -1 23717 -1 23718 -1 23719 -1 23720 -1 23721 -1 23722 -1 23723 -1 23724 -1 23725 -1 23726 -1 23727 -1 23728 -1 23729 -1 23730 -1 23731 -1 23732 -1 23733 -1 23734 -1 23735 -1 23736 -1 23737 -1 23738 -1 23739 -1 23740 -1 23741 -1 23742 -1 23743 -1 23744 -1 23745 -1 23746 -1 23747 -1 23748 -1 23749 -1 23750 -1 23751 -1 23752 -1 23753 -1 23754 -1 23755 -1 23756 -1 23757 -1 23758 -1 23759 -1 23760 -1 23761 -1 23762 -1 23763 -1 23764 -1 23765 -1 23766 -1 23767 -1 23768 -1 23769 -1 23770 -1 23771 -1 23772 -1 23773 -1 23774 -1 23775 -1 23776 -1 23777 -1 23778 -1 23779 -1 23780 -1 23781 -1 23782 -1 23783 -1 23784 -1 23785 -1 23786 -1 23787 -1 23788 -1 23789 -1 23790 -1 23791 -1 23792 -1 23793 -1 23794 -1 23795 -1 23796 -1 23797 -1 23798 -1 23799 -1 23800 -1 23801 -1 23802 -1 23803 -1 23804 -1 23805 -1 23806 -1 23807 -1 23808 -1 23809 -1 23810 -1 23811 -1 23812 -1 23813 -1 23814 -1 23815 -1 23816 -1 23817 -1 23818 -1 23819 -1 23820 -1 23821 -1 23822 -1 23823 -1 23824 -1 23825 -1 23826 -1 23827 -1 23828 -1 23829 -1 23830 -1 23831 -1 23832 -1 23833 -1 23834 -1 23835 -1 23836 -1 23837 -1 23838 -1 23839 -1 23840 -1 23841 -1 23842 -1 23843 -1 23844 -1 23845 -1 23846 -1 23847 -1 23848 -1 23849 -1 23850 -1 23851 -1 23852 -1 23853 -1 23854 -1 23855 -1 23856 -1 23857 -1 23858 -1 23859 -1 23860 -1 23861 -1 23862 -1 23863 -1 23864 -1 23865 -1 23866 -1 23867 -1 23868 -1 23869 -1 23870 -1 23871 -1 23872 -1 23873 -1 23874 -1 23875 -1 23876 -1 23877 -1 23878 -1 23879 -1 23880 -1 23881 -1 23882 -1 23883 -1 23884 -1 23885 -1 23886 -1 23887 -1 23888 -1 23889 -1 23890 -1 23891 -1 23892 -1 23893 -1 23894 -1 23895 -1 23896 -1 23897 -1 23898 -1 23899 -1 23900 -1 23901 -1 23902 -1 23903 -1 23904 -1 23905 -1 23906 -1 23907 -1 23908 -1 23909 -1 23910 -1 23911 -1 23912 -1 23913 -1 23914 -1 23915 -1 23916 -1 23917 -1 23918 -1 23919 -1 23920 -1 23921 -1 23922 -1 23923 -1 23924 -1 23925 -1 23926 -1 23927 -1 23928 -1 23929 -1 23930 -1 23931 -1 23932 -1 23933 -1 23934 -1 23935 -1 23936 -1 23937 -1 23938 -1 23939 -1 23940 -1 23941 -1 23942 -1 23943 -1 23944 -1 23945 -1 23946 -1 23947 -1 23948 -1 23949 -1 23950 -1 23951 -1 23952 -1 23953 -1 23954 -1 23955 -1 23956 -1 23957 -1 23958 -1 23959 -1 23960 -1 23961 -1 23962 -1 23963 -1 23964 -1 23965 -1 23966 -1 23967 -1 23968 -1 23969 -1 23970 -1 23971 -1 23972 -1 23973 -1 23974 -1 23975 -1 23976 -1 23977 -1 23978 -1 23979 -1 23980 -1 23981 -1 23982 -1 23983 -1 23984 -1 23985 -1 23986 -1 23987 -1 23988 -1 23989 -1 23990 -1 23991 -1 23992 -1 23993 -1 23994 -1 23995 -1 23996 -1 23997 -1 23998 -1 23999 -1 24000 -1 24001 -1 24002 -1 24003 -1 24004 -1 24005 -1 24006 -1 24007 -1 24008 -1 24009 -1 24010 -1 24011 -1 24012 -1 24013 -1 24014 -1 24015 -1 24016 -1 24017 -1 24018 -1 24019 -1 24020 -1 24021 -1 24022 -1 24023 -1 24024 -1 24025 -1 24026 -1 24027 -1 24028 -1 24029 -1 24030 -1 24031 -1 24032 -1 24033 -1 24034 -1 24035 -1 24036 -1 24037 -1 24038 -1 24039 -1 24040 -1 24041 -1 24042 -1 24043 -1 24044 -1 24045 -1 24046 -1 24047 -1 24048 -1 24049 -1 24050 -1 24051 -1 24052 -1 24053 -1 24054 -1 24055 -1 24056 -1 24057 -1 24058 -1 24059 -1 24060 -1 24061 -1 24062 -1 24063 -1 24064 -1 24065 -1 24066 -1 24067 -1 24068 -1 24069 -1 24070 -1 24071 -1 24072 -1 24073 -1 24074 -1 24075 -1 24076 -1 24077 -1 24078 -1 24079 -1 24080 -1 24081 -1 24082 -1 24083 -1 24084 -1 24085 -1 24086 -1 24087 -1 24088 -1 24089 -1 24090 -1 24091 -1 24092 -1 24093 -1 24094 -1 24095 -1 24096 -1 24097 -1 24098 -1 24099 -1 24100 -1 24101 -1 24102 -1 24103 -1 24104 -1 24105 -1 24106 -1 24107 -1 24108 -1 24109 -1 24110 -1 24111 -1 24112 -1 24113 -1 24114 -1 24115 -1 24116 -1 24117 -1 24118 -1 24119 -1 24120 -1 24121 -1 24122 -1 24123 -1 24124 -1 24125 -1 24126 -1 24127 -1 24128 -1 24129 -1 24130 -1 24131 -1 24132 -1 24133 -1 24134 -1 24135 -1 24136 -1 24137 -1 24138 -1 24139 -1 24140 -1 24141 -1 24142 -1 24143 -1 24144 -1 24145 -1 24146 -1 24147 -1 24148 -1 24149 -1 24150 -1 24151 -1 24152 -1 24153 -1 24154 -1 24155 -1 24156 -1 24157 -1 24158 -1 24159 -1 24160 -1 24161 -1 24162 -1 24163 -1 24164 -1 24165 -1 24166 -1 24167 -1 24168 -1 24169 -1 24170 -1 24171 -1 24172 -1 24173 -1 24174 -1 24175 -1 24176 -1 24177 -1 24178 -1 24179 -1 24180 -1 24181 -1 24182 -1 24183 -1 24184 -1 24185 -1 24186 -1 24187 -1 24188 -1 24189 -1 24190 -1 24191 -1 24192 -1 24193 -1 24194 -1 24195 -1 24196 -1 24197 -1 24198 -1 24199 -1 24200 -1 24201 -1 24202 -1 24203 -1 24204 -1 24205 -1 24206 -1 24207 -1 24208 -1 24209 -1 24210 -1 24211 -1 24212 -1 24213 -1 24214 -1 24215 -1 24216 -1 24217 -1 24218 -1 24219 -1 24220 -1 24221 -1 24222 -1 24223 -1 24224 -1 24225 -1 24226 -1 24227 -1 24228 -1 24229 -1 24230 -1 24231 -1 24232 -1 24233 -1 24234 -1 24235 -1 24236 -1 24237 -1 24238 -1 24239 -1 24240 -1 24241 -1 24242 -1 24243 -1 24244 -1 24245 -1 24246 -1 24247 -1 24248 -1 24249 -1 24250 -1 24251 -1 24252 -1 24253 -1 24254 -1 24255 -1 24256 -1 24257 -1 24258 -1 24259 -1 24260 -1 24261 -1 24262 -1 24263 -1 24264 -1 24265 -1 24266 -1 24267 -1 24268 -1 24269 -1 24270 -1 24271 -1 24272 -1 24273 -1 24274 -1 24275 -1 24276 -1 24277 -1 24278 -1 24279 -1 24280 -1 24281 -1 24282 -1 24283 -1 24284 -1 24285 -1 24286 -1 24287 -1 24288 -1 24289 -1 24290 -1 24291 -1 24292 -1 24293 -1 24294 -1 24295 -1 24296 -1 24297 -1 24298 -1 24299 -1 24300 -1 24301 -1 24302 -1 24303 -1 24304 -1 24305 -1 24306 -1 24307 -1 24308 -1 24309 -1 24310 -1 24311 -1 24312 -1 24313 -1 24314 -1 24315 -1 24316 -1 24317 -1 24318 -1 24319 -1 24320 -1 24321 -1 24322 -1 24323 -1 24324 -1 24325 -1 24326 -1 24327 -1 24328 -1 24329 -1 24330 -1 24331 -1 24332 -1 24333 -1 24334 -1 24335 -1 24336 -1 24337 -1 24338 -1 24339 -1 24340 -1 24341 -1 24342 -1 24343 -1 24344 -1 24345 -1 24346 -1 24347 -1 24348 -1 24349 -1 24350 -1 24351 -1 24352 -1 24353 -1 24354 -1 24355 -1 24356 -1 24357 -1 24358 -1 24359 -1 24360 -1 24361 -1 24362 -1 24363 -1 24364 -1 24365 -1 24366 -1 24367 -1 24368 -1 24369 -1 24370 -1 24371 -1 24372 -1 24373 -1 24374 -1 24375 -1 24376 -1 24377 -1 24378 -1 24379 -1 24380 -1 24381 -1 24382 -1 24383 -1 24384 -1 24385 -1 24386 -1 24387 -1 24388 -1 24389 -1 24390 -1 24391 -1 24392 -1 24393 -1 24394 -1 24395 -1 24396 -1 24397 -1 24398 -1 24399 -1 24400 -1 24401 -1 24402 -1 24403 -1 24404 -1 24405 -1 24406 -1 24407 -1 24408 -1 24409 -1 24410 -1 24411 -1 24412 -1 24413 -1 24414 -1 24415 -1 24416 -1 24417 -1 24418 -1 24419 -1 24420 -1 24421 -1 24422 -1 24423 -1 24424 -1 24425 -1 24426 -1 24427 -1 24428 -1 24429 -1 24430 -1 24431 -1 24432 -1 24433 -1 24434 -1 24435 -1 24436 -1 24437 -1 24438 -1 24439 -1 24440 -1 24441 -1 24442 -1 24443 -1 24444 -1 24445 -1 24446 -1 24447 -1 24448 -1 24449 -1 24450 -1 24451 -1 24452 -1 24453 -1 24454 -1 24455 -1 24456 -1 24457 -1 24458 -1 24459 -1 24460 -1 24461 -1 24462 -1 24463 -1 24464 -1 24465 -1 24466 -1 24467 -1 24468 -1 24469 -1 24470 -1 24471 -1 24472 -1 24473 -1 24474 -1 24475 -1 24476 -1 24477 -1 24478 -1 24479 -1 24480 -1 24481 -1 24482 -1 24483 -1 24484 -1 24485 -1 24486 -1 24487 -1 24488 -1 24489 -1 24490 -1 24491 -1 24492 -1 24493 -1 24494 -1 24495 -1 24496 -1 24497 -1 24498 -1 24499 -1 24500 -1 24501 -1 24502 -1 24503 -1 24504 -1 24505 -1 24506 -1 24507 -1 24508 -1 24509 -1 24510 -1 24511 -1 24512 -1 24513 -1 24514 -1 24515 -1 24516 -1 24517 -1 24518 -1 24519 -1 24520 -1 24521 -1 24522 -1 24523 -1 24524 -1 24525 -1 24526 -1 24527 -1 24528 -1 24529 -1 24530 -1 24531 -1 24532 -1 24533 -1 24534 -1 24535 -1 24536 -1 24537 -1 24538 -1 24539 -1 24540 -1 24541 -1 24542 -1 24543 -1 24544 -1 24545 -1 24546 -1 24547 -1 24548 -1 24549 -1 24550 -1 24551 -1 24552 -1 24553 -1 24554 -1 24555 -1 24556 -1 24557 -1 24558 -1 24559 -1 24560 -1 24561 -1 24562 -1 24563 -1 24564 -1 24565 -1 24566 -1 24567 -1 24568 -1 24569 -1 24570 -1 24571 -1 24572 -1 24573 -1 24574 -1 24575 -1 24576 -1 24577 -1 24578 -1 24579 -1 24580 -1 24581 -1 24582 -1 24583 -1 24584 -1 24585 -1 24586 -1 24587 -1 24588 -1 24589 -1 24590 -1 24591 -1 24592 -1 24593 -1 24594 -1 24595 -1 24596 -1 24597 -1 24598 -1 24599 -1 24600 -1 24601 -1 24602 -1 24603 -1 24604 -1 24605 -1 24606 -1 24607 -1 24608 -1 24609 -1 24610 -1 24611 -1 24612 -1 24613 -1 24614 -1 24615 -1 24616 -1 24617 -1 24618 -1 24619 -1 24620 -1 24621 -1 24622 -1 24623 -1 24624 -1 24625 -1 24626 -1 24627 -1 24628 -1 24629 -1 24630 -1 24631 -1 24632 -1 24633 -1 24634 -1 24635 -1 24636 -1 24637 -1 24638 -1 24639 -1 24640 -1 24641 -1 24642 -1 24643 -1 24644 -1 24645 -1 24646 -1 24647 -1 24648 -1 24649 -1 24650 -1 24651 -1 24652 -1 24653 -1 24654 -1 24655 -1 24656 -1 24657 -1 24658 -1 24659 -1 24660 -1 24661 -1 24662 -1 24663 -1 24664 -1 24665 -1 24666 -1 24667 -1 24668 -1 24669 -1 24670 -1 24671 -1 24672 -1 24673 -1 24674 -1 24675 -1 24676 -1 24677 -1 24678 -1 24679 -1 24680 -1 24681 -1 24682 -1 24683 -1 24684 -1 24685 -1 24686 -1 24687 -1 24688 -1 24689 -1 24690 -1 24691 -1 24692 -1 24693 -1 24694 -1 24695 -1 24696 -1 24697 -1 24698 -1 24699 -1 24700 -1 24701 -1 24702 -1 24703 -1 24704 -1 24705 -1 24706 -1 24707 -1 24708 -1 24709 -1 24710 -1 24711 -1 24712 -1 24713 -1 24714 -1 24715 -1 24716 -1 24717 -1 24718 -1 24719 -1 24720 -1 24721 -1 24722 -1 24723 -1 24724 -1 24725 -1 24726 -1 24727 -1 24728 -1 24729 -1 24730 -1 24731 -1 24732 -1 24733 -1 24734 -1 24735 -1 24736 -1 24737 -1 24738 -1 24739 -1 24740 -1 24741 -1 24742 -1 24743 -1 24744 -1 24745 -1 24746 -1 24747 -1 24748 -1 24749 -1 24750 -1 24751 -1 24752 -1 24753 -1 24754 -1 24755 -1 24756 -1 24757 -1 24758 -1 24759 -1 24760 -1 24761 -1 24762 -1 24763 -1 24764 -1 24765 -1 24766 -1 24767 -1 24768 -1 24769 -1 24770 -1 24771 -1 24772 -1 24773 -1 24774 -1 24775 -1 24776 -1 24777 -1 24778 -1 24779 -1 24780 -1 24781 -1 24782 -1 24783 -1 24784 -1 24785 -1 24786 -1 24787 -1 24788 -1 24789 -1 24790 -1 24791 -1 24792 -1 24793 -1 24794 -1 24795 -1 24796 -1 24797 -1 24798 -1 24799 -1 24800 -1 24801 -1 24802 -1 24803 -1 24804 -1 24805 -1 24806 -1 24807 -1 24808 -1 24809 -1 24810 -1 24811 -1 24812 -1 24813 -1 24814 -1 24815 -1 24816 -1 24817 -1 24818 -1 24819 -1 24820 -1 24821 -1 24822 -1 24823 -1 24824 -1 24825 -1 24826 -1 24827 -1 24828 -1 24829 -1 24830 -1 24831 -1 24832 -1 24833 -1 24834 -1 24835 -1 24836 -1 24837 -1 24838 -1 24839 -1 24840 -1 24841 -1 24842 -1 24843 -1 24844 -1 24845 -1 24846 -1 24847 -1 24848 -1 24849 -1 24850 -1 24851 -1 24852 -1 24853 -1 24854 -1 24855 -1 24856 -1 24857 -1 24858 -1 24859 -1 24860 -1 24861 -1 24862 -1 24863 -1 24864 -1 24865 -1 24866 -1 24867 -1 24868 -1 24869 -1 24870 -1 24871 -1 24872 -1 24873 -1 24874 -1 24875 -1 24876 -1 24877 -1 24878 -1 24879 -1 24880 -1 24881 -1 24882 -1 24883 -1 24884 -1 24885 -1 24886 -1 24887 -1 24888 -1 24889 -1 24890 -1 24891 -1 24892 -1 24893 -1 24894 -1 24895 -1 24896 -1 24897 -1 24898 -1 24899 -1 24900 -1 24901 -1 24902 -1 24903 -1 24904 -1 24905 -1 24906 -1 24907 -1 24908 -1 24909 -1 24910 -1 24911 -1 24912 -1 24913 -1 24914 -1 24915 -1 24916 -1 24917 -1 24918 -1 24919 -1 24920 -1 24921 -1 24922 -1 24923 -1 24924 -1 24925 -1 24926 -1 24927 -1 24928 -1 24929 -1 24930 -1 24931 -1 24932 -1 24933 -1 24934 -1 24935 -1 24936 -1 24937 -1 24938 -1 24939 -1 24940 -1 24941 -1 24942 -1 24943 -1 24944 -1 24945 -1 24946 -1 24947 -1 24948 -1 24949 -1 24950 -1 24951 -1 24952 -1 24953 -1 24954 -1 24955 -1 24956 -1 24957 -1 24958 -1 24959 -1 24960 -1 24961 -1 24962 -1 24963 -1 24964 -1 24965 -1 24966 -1 24967 -1 24968 -1 24969 -1 24970 -1 24971 -1 24972 -1 24973 -1 24974 -1 24975 -1 24976 -1 24977 -1 24978 -1 24979 -1 24980 -1 24981 -1 24982 -1 24983 -1 24984 -1 24985 -1 24986 -1 24987 -1 24988 -1 24989 -1 24990 -1 24991 -1 24992 -1 24993 -1 24994 -1 24995 -1 24996 -1 24997 -1 24998 -1 24999 -1 25000 -1 25001 -1 25002 -1 25003 -1 25004 -1 25005 -1 25006 -1 25007 -1 25008 -1 25009 -1 25010 -1 25011 -1 25012 -1 25013 -1 25014 -1 25015 -1 25016 -1 25017 -1 25018 -1 25019 -1 25020 -1 25021 -1 25022 -1 25023 -1 25024 -1 25025 -1 25026 -1 25027 -1 25028 -1 25029 -1 25030 -1 25031 -1 25032 -1 25033 -1 25034 -1 25035 -1 25036 -1 25037 -1 25038 -1 25039 -1 25040 -1 25041 -1 25042 -1 25043 -1 25044 -1 25045 -1 25046 -1 25047 -1 25048 -1 25049 -1 25050 -1 25051 -1 25052 -1 25053 -1 25054 -1 25055 -1 25056 -1 25057 -1 25058 -1 25059 -1 25060 -1 25061 -1 25062 -1 25063 -1 25064 -1 25065 -1 25066 -1 25067 -1 25068 -1 25069 -1 25070 -1 25071 -1 25072 -1 25073 -1 25074 -1 25075 -1 25076 -1 25077 -1 25078 -1 25079 -1 25080 -1 25081 -1 25082 -1 25083 -1 25084 -1 25085 -1 25086 -1 25087 -1 25088 -1 25089 -1 25090 -1 25091 -1 25092 -1 25093 -1 25094 -1 25095 -1 25096 -1 25097 -1 25098 -1 25099 -1 25100 -1 25101 -1 25102 -1 25103 -1 25104 -1 25105 -1 25106 -1 25107 -1 25108 -1 25109 -1 25110 -1 25111 -1 25112 -1 25113 -1 25114 -1 25115 -1 25116 -1 25117 -1 25118 -1 25119 -1 25120 -1 25121 -1 25122 -1 25123 -1 25124 -1 25125 -1 25126 -1 25127 -1 25128 -1 25129 -1 25130 -1 25131 -1 25132 -1 25133 -1 25134 -1 25135 -1 25136 -1 25137 -1 25138 -1 25139 -1 25140 -1 25141 -1 25142 -1 25143 -1 25144 -1 25145 -1 25146 -1 25147 -1 25148 -1 25149 -1 25150 -1 25151 -1 25152 -1 25153 -1 25154 -1 25155 -1 25156 -1 25157 -1 25158 -1 25159 -1 25160 -1 25161 -1 25162 -1 25163 -1 25164 -1 25165 -1 25166 -1 25167 -1 25168 -1 25169 -1 25170 -1 25171 -1 25172 -1 25173 -1 25174 -1 25175 -1 25176 -1 25177 -1 25178 -1 25179 -1 25180 -1 25181 -1 25182 -1 25183 -1 25184 -1 25185 -1 25186 -1 25187 -1 25188 -1 25189 -1 25190 -1 25191 -1 25192 -1 25193 -1 25194 -1 25195 -1 25196 -1 25197 -1 25198 -1 25199 -1 25200 -1 25201 -1 25202 -1 25203 -1 25204 -1 25205 -1 25206 -1 25207 -1 25208 -1 25209 -1 25210 -1 25211 -1 25212 -1 25213 -1 25214 -1 25215 -1 25216 -1 25217 -1 25218 -1 25219 -1 25220 -1 25221 -1 25222 -1 25223 -1 25224 -1 25225 -1 25226 -1 25227 -1 25228 -1 25229 -1 25230 -1 25231 -1 25232 -1 25233 -1 25234 -1 25235 -1 25236 -1 25237 -1 25238 -1 25239 -1 25240 -1 25241 -1 25242 -1 25243 -1 25244 -1 25245 -1 25246 -1 25247 -1 25248 -1 25249 -1 25250 -1 25251 -1 25252 -1 25253 -1 25254 -1 25255 -1 25256 -1 25257 -1 25258 -1 25259 -1 25260 -1 25261 -1 25262 -1 25263 -1 25264 -1 25265 -1 25266 -1 25267 -1 25268 -1 25269 -1 25270 -1 25271 -1 25272 -1 25273 -1 25274 -1 25275 -1 25276 -1 25277 -1 25278 -1 25279 -1 25280 -1 25281 -1 25282 -1 25283 -1 25284 -1 25285 -1 25286 -1 25287 -1 25288 -1 25289 -1 25290 -1 25291 -1 25292 -1 25293 -1 25294 -1 25295 -1 25296 -1 25297 -1 25298 -1 25299 -1 25300 -1 25301 -1 25302 -1 25303 -1 25304 -1 25305 -1 25306 -1 25307 -1 25308 -1 25309 -1 25310 -1 25311 -1 25312 -1 25313 -1 25314 -1 25315 -1 25316 -1 25317 -1 25318 -1 25319 -1 25320 -1 25321 -1 25322 -1 25323 -1 25324 -1 25325 -1 25326 -1 25327 -1 25328 -1 25329 -1 25330 -1 25331 -1 25332 -1 25333 -1 25334 -1 25335 -1 25336 -1 25337 -1 25338 -1 25339 -1 25340 -1 25341 -1 25342 -1 25343 -1 25344 -1 25345 -1 25346 -1 25347 -1 25348 -1 25349 -1 25350 -1 25351 -1 25352 -1 25353 -1 25354 -1 25355 -1 25356 -1 25357 -1 25358 -1 25359 -1 25360 -1 25361 -1 25362 -1 25363 -1 25364 -1 25365 -1 25366 -1 25367 -1 25368 -1 25369 -1 25370 -1 25371 -1 25372 -1 25373 -1 25374 -1 25375 -1 25376 -1 25377 -1 25378 -1 25379 -1 25380 -1 25381 -1 25382 -1 25383 -1 25384 -1 25385 -1 25386 -1 25387 -1 25388 -1 25389 -1 25390 -1 25391 -1 25392 -1 25393 -1 25394 -1 25395 -1 25396 -1 25397 -1 25398 -1 25399 -1 25400 -1 25401 -1 25402 -1 25403 -1 25404 -1 25405 -1 25406 -1 25407 -1 25408 -1 25409 -1 25410 -1 25411 -1 25412 -1 25413 -1 25414 -1 25415 -1 25416 -1 25417 -1 25418 -1 25419 -1 25420 -1 25421 -1 25422 -1 25423 -1 25424 -1 25425 -1 25426 -1 25427 -1 25428 -1 25429 -1 25430 -1 25431 -1 25432 -1 25433 -1 25434 -1 25435 -1 25436 -1 25437 -1 25438 -1 25439 -1 25440 -1 25441 -1 25442 -1 25443 -1 25444 -1 25445 -1 25446 -1 25447 -1 25448 -1 25449 -1 25450 -1 25451 -1 25452 -1 25453 -1 25454 -1 25455 -1 25456 -1 25457 -1 25458 -1 25459 -1 25460 -1 25461 -1 25462 -1 25463 -1 25464 -1 25465 -1 25466 -1 25467 -1 25468 -1 25469 -1 25470 -1 25471 -1 25472 -1 25473 -1 25474 -1 25475 -1 25476 -1 25477 -1 25478 -1 25479 -1 25480 -1 25481 -1 25482 -1 25483 -1 25484 -1 25485 -1 25486 -1 25487 -1 25488 -1 25489 -1 25490 -1 25491 -1 25492 -1 25493 -1 25494 -1 25495 -1 25496 -1 25497 -1 25498 -1 25499 -1 25500 -1 25501 -1 25502 -1 25503 -1 25504 -1 25505 -1 25506 -1 25507 -1 25508 -1 25509 -1 25510 -1 25511 -1 25512 -1 25513 -1 25514 -1 25515 -1 25516 -1 25517 -1 25518 -1 25519 -1 25520 -1 25521 -1 25522 -1 25523 -1 25524 -1 25525 -1 25526 -1 25527 -1 25528 -1 25529 -1 25530 -1 25531 -1 25532 -1 25533 -1 25534 -1 25535 -1 25536 -1 25537 -1 25538 -1 25539 -1 25540 -1 25541 -1 25542 -1 25543 -1 25544 -1 25545 -1 25546 -1 25547 -1 25548 -1 25549 -1 25550 -1 25551 -1 25552 -1 25553 -1 25554 -1 25555 -1 25556 -1 25557 -1 25558 -1 25559 -1 25560 -1 25561 -1 25562 -1 25563 -1 25564 -1 25565 -1 25566 -1 25567 -1 25568 -1 25569 -1 25570 -1 25571 -1 25572 -1 25573 -1 25574 -1 25575 -1 25576 -1 25577 -1 25578 -1 25579 -1 25580 -1 25581 -1 25582 -1 25583 -1 25584 -1 25585 -1 25586 -1 25587 -1 25588 -1 25589 -1 25590 -1 25591 -1 25592 -1 25593 -1 25594 -1 25595 -1 25596 -1 25597 -1 25598 -1 25599 -1 25600 -1 25601 -1 25602 -1 25603 -1 25604 -1 25605 -1 25606 -1 25607 -1 25608 -1 25609 -1 25610 -1 25611 -1 25612 -1 25613 -1 25614 -1 25615 -1 25616 -1 25617 -1 25618 -1 25619 -1 25620 -1 25621 -1 25622 -1 25623 -1 25624 -1 25625 -1 25626 -1 25627 -1 25628 -1 25629 -1 25630 -1 25631 -1 25632 -1 25633 -1 25634 -1 25635 -1 25636 -1 25637 -1 25638 -1 25639 -1 25640 -1 25641 -1 25642 -1 25643 -1 25644 -1 25645 -1 25646 -1 25647 -1 25648 -1 25649 -1 25650 -1 25651 -1 25652 -1 25653 -1 25654 -1 25655 -1 25656 -1 25657 -1 25658 -1 25659 -1 25660 -1 25661 -1 25662 -1 25663 -1 25664 -1 25665 -1 25666 -1 25667 -1 25668 -1 25669 -1 25670 -1 25671 -1 25672 -1 25673 -1 25674 -1 25675 -1 25676 -1 25677 -1 25678 -1 25679 -1 25680 -1 25681 -1 25682 -1 25683 -1 25684 -1 25685 -1 25686 -1 25687 -1 25688 -1 25689 -1 25690 -1 25691 -1 25692 -1 25693 -1 25694 -1 25695 -1 25696 -1 25697 -1 25698 -1 25699 -1 25700 -1 25701 -1 25702 -1 25703 -1 25704 -1 25705 -1 25706 -1 25707 -1 25708 -1 25709 -1 25710 -1 25711 -1 25712 -1 25713 -1 25714 -1 25715 -1 25716 -1 25717 -1 25718 -1 25719 -1 25720 -1 25721 -1 25722 -1 25723 -1 25724 -1 25725 -1 25726 -1 25727 -1 25728 -1 25729 -1 25730 -1 25731 -1 25732 -1 25733 -1 25734 -1 25735 -1 25736 -1 25737 -1 25738 -1 25739 -1 25740 -1 25741 -1 25742 -1 25743 -1 25744 -1 25745 -1 25746 -1 25747 -1 25748 -1 25749 -1 25750 -1 25751 -1 25752 -1 25753 -1 25754 -1 25755 -1 25756 -1 25757 -1 25758 -1 25759 -1 25760 -1 25761 -1 25762 -1 25763 -1 25764 -1 25765 -1 25766 -1 25767 -1 25768 -1 25769 -1 25770 -1 25771 -1 25772 -1 25773 -1 25774 -1 25775 -1 25776 -1 25777 -1 25778 -1 25779 -1 25780 -1 25781 -1 25782 -1 25783 -1 25784 -1 25785 -1 25786 -1 25787 -1 25788 -1 25789 -1 25790 -1 25791 -1 25792 -1 25793 -1 25794 -1 25795 -1 25796 -1 25797 -1 25798 -1 25799 -1 25800 -1 25801 -1 25802 -1 25803 -1 25804 -1 25805 -1 25806 -1 25807 -1 25808 -1 25809 -1 25810 -1 25811 -1 25812 -1 25813 -1 25814 -1 25815 -1 25816 -1 25817 -1 25818 -1 25819 -1 25820 -1 25821 -1 25822 -1 25823 -1 25824 -1 25825 -1 25826 -1 25827 -1 25828 -1 25829 -1 25830 -1 25831 -1 25832 -1 25833 -1 25834 -1 25835 -1 25836 -1 25837 -1 25838 -1 25839 -1 25840 -1 25841 -1 25842 -1 25843 -1 25844 -1 25845 -1 25846 -1 25847 -1 25848 -1 25849 -1 25850 -1 25851 -1 25852 -1 25853 -1 25854 -1 25855 -1 25856 -1 25857 -1 25858 -1 25859 -1 25860 -1 25861 -1 25862 -1 25863 -1 25864 -1 25865 -1 25866 -1 25867 -1 25868 -1 25869 -1 25870 -1 25871 -1 25872 -1 25873 -1 25874 -1 25875 -1 25876 -1 25877 -1 25878 -1 25879 -1 25880 -1 25881 -1 25882 -1 25883 -1 25884 -1 25885 -1 25886 -1 25887 -1 25888 -1 25889 -1 25890 -1 25891 -1 25892 -1 25893 -1 25894 -1 25895 -1 25896 -1 25897 -1 25898 -1 25899 -1 25900 -1 25901 -1 25902 -1 25903 -1 25904 -1 25905 -1 25906 -1 25907 -1 25908 -1 25909 -1 25910 -1 25911 -1 25912 -1 25913 -1 25914 -1 25915 -1 25916 -1 25917 -1 25918 -1 25919 -1 25920 -1 25921 -1 25922 -1 25923 -1 25924 -1 25925 -1 25926 -1 25927 -1 25928 -1 25929 -1 25930 -1 25931 -1 25932 -1 25933 -1 25934 -1 25935 -1 25936 -1 25937 -1 25938 -1 25939 -1 25940 -1 25941 -1 25942 -1 25943 -1 25944 -1 25945 -1 25946 -1 25947 -1 25948 -1 25949 -1 25950 -1 25951 -1 25952 -1 25953 -1 25954 -1 25955 -1 25956 -1 25957 -1 25958 -1 25959 -1 25960 -1 25961 -1 25962 -1 25963 -1 25964 -1 25965 -1 25966 -1 25967 -1 25968 -1 25969 -1 25970 -1 25971 -1 25972 -1 25973 -1 25974 -1 25975 -1 25976 -1 25977 -1 25978 -1 25979 -1 25980 -1 25981 -1 25982 -1 25983 -1 25984 -1 25985 -1 25986 -1 25987 -1 25988 -1 25989 -1 25990 -1 25991 -1 25992 -1 25993 -1 25994 -1 25995 -1 25996 -1 25997 -1 25998 -1 25999 -1 26000 -1 26001 -1 26002 -1 26003 -1 26004 -1 26005 -1 26006 -1 26007 -1 26008 -1 26009 -1 26010 -1 26011 -1 26012 -1 26013 -1 26014 -1 26015 -1 26016 -1 26017 -1 26018 -1 26019 -1 26020 -1 26021 -1 26022 -1 26023 -1 26024 -1 26025 -1 26026 -1 26027 -1 26028 -1 26029 -1 26030 -1 26031 -1 26032 -1 26033 -1 26034 -1 26035 -1 26036 -1 26037 -1 26038 -1 26039 -1 26040 -1 26041 -1 26042 -1 26043 -1 26044 -1 26045 -1 26046 -1 26047 -1 26048 -1 26049 -1 26050 -1 26051 -1 26052 -1 26053 -1 26054 -1 26055 -1 26056 -1 26057 -1 26058 -1 26059 -1 26060 -1 26061 -1 26062 -1 26063 -1 26064 -1 26065 -1 26066 -1 26067 -1 26068 -1 26069 -1 26070 -1 26071 -1 26072 -1 26073 -1 26074 -1 26075 -1 26076 -1 26077 -1 26078 -1 26079 -1 26080 -1 26081 -1 26082 -1 26083 -1 26084 -1 26085 -1 26086 -1 26087 -1 26088 -1 26089 -1 26090 -1 26091 -1 26092 -1 26093 -1 26094 -1 26095 -1 26096 -1 26097 -1 26098 -1 26099 -1 26100 -1 26101 -1 26102 -1 26103 -1 26104 -1 26105 -1 26106 -1 26107 -1 26108 -1 26109 -1 26110 -1 26111 -1 26112 -1 26113 -1 26114 -1 26115 -1 26116 -1 26117 -1 26118 -1 26119 -1 26120 -1 26121 -1 26122 -1 26123 -1 26124 -1 26125 -1 26126 -1 26127 -1 26128 -1 26129 -1 26130 -1 26131 -1 26132 -1 26133 -1 26134 -1 26135 -1 26136 -1 26137 -1 26138 -1 26139 -1 26140 -1 26141 -1 26142 -1 26143 -1 26144 -1 26145 -1 26146 -1 26147 -1 26148 -1 26149 -1 26150 -1 26151 -1 26152 -1 26153 -1 26154 -1 26155 -1 26156 -1 26157 -1 26158 -1 26159 -1 26160 -1 26161 -1 26162 -1 26163 -1 26164 -1 26165 -1 26166 -1 26167 -1 26168 -1 26169 -1 26170 -1 26171 -1 26172 -1 26173 -1 26174 -1 26175 -1 26176 -1 26177 -1 26178 -1 26179 -1 26180 -1 26181 -1 26182 -1 26183 -1 26184 -1 26185 -1 26186 -1 26187 -1 26188 -1 26189 -1 26190 -1 26191 -1 26192 -1 26193 -1 26194 -1 26195 -1 26196 -1 26197 -1 26198 -1 26199 -1 26200 -1 26201 -1 26202 -1 26203 -1 26204 -1 26205 -1 26206 -1 26207 -1 26208 -1 26209 -1 26210 -1 26211 -1 26212 -1 26213 -1 26214 -1 26215 -1 26216 -1 26217 -1 26218 -1 26219 -1 26220 -1 26221 -1 26222 -1 26223 -1 26224 -1 26225 -1 26226 -1 26227 -1 26228 -1 26229 -1 26230 -1 26231 -1 26232 -1 26233 -1 26234 -1 26235 -1 26236 -1 26237 -1 26238 -1 26239 -1 26240 -1 26241 -1 26242 -1 26243 -1 26244 -1 26245 -1 26246 -1 26247 -1 26248 -1 26249 -1 26250 -1 26251 -1 26252 -1 26253 -1 26254 -1 26255 -1 26256 -1 26257 -1 26258 -1 26259 -1 26260 -1 26261 -1 26262 -1 26263 -1 26264 -1 26265 -1 26266 -1 26267 -1 26268 -1 26269 -1 26270 -1 26271 -1 26272 -1 26273 -1 26274 -1 26275 -1 26276 -1 26277 -1 26278 -1 26279 -1 26280 -1 26281 -1 26282 -1 26283 -1 26284 -1 26285 -1 26286 -1 26287 -1 26288 -1 26289 -1 26290 -1 26291 -1 26292 -1 26293 -1 26294 -1 26295 -1 26296 -1 26297 -1 26298 -1 26299 -1 26300 -1 26301 -1 26302 -1 26303 -1 26304 -1 26305 -1 26306 -1 26307 -1 26308 -1 26309 -1 26310 -1 26311 -1 26312 -1 26313 -1 26314 -1 26315 -1 26316 -1 26317 -1 26318 -1 26319 -1 26320 -1 26321 -1 26322 -1 26323 -1 26324 -1 26325 -1 26326 -1 26327 -1 26328 -1 26329 -1 26330 -1 26331 -1 26332 -1 26333 -1 26334 -1 26335 -1 26336 -1 26337 -1 26338 -1 26339 -1 26340 -1 26341 -1 26342 -1 26343 -1 26344 -1 26345 -1 26346 -1 26347 -1 26348 -1 26349 -1 26350 -1 26351 -1 26352 -1 26353 -1 26354 -1 26355 -1 26356 -1 26357 -1 26358 -1 26359 -1 26360 -1 26361 -1 26362 -1 26363 -1 26364 -1 26365 -1 26366 -1 26367 -1 26368 -1 26369 -1 26370 -1 26371 -1 26372 -1 26373 -1 26374 -1 26375 -1 26376 -1 26377 -1 26378 -1 26379 -1 26380 -1 26381 -1 26382 -1 26383 -1 26384 -1 26385 -1 26386 -1 26387 -1 26388 -1 26389 -1 26390 -1 26391 -1 26392 -1 26393 -1 26394 -1 26395 -1 26396 -1 26397 -1 26398 -1 26399 -1 26400 -1 26401 -1 26402 -1 26403 -1 26404 -1 26405 -1 26406 -1 26407 -1 26408 -1 26409 -1 26410 -1 26411 -1 26412 -1 26413 -1 26414 -1 26415 -1 26416 -1 26417 -1 26418 -1 26419 -1 26420 -1 26421 -1 26422 -1 26423 -1 26424 -1 26425 -1 26426 -1 26427 -1 26428 -1 26429 -1 26430 -1 26431 -1 26432 -1 26433 -1 26434 -1 26435 -1 26436 -1 26437 -1 26438 -1 26439 -1 26440 -1 26441 -1 26442 -1 26443 -1 26444 -1 26445 -1 26446 -1 26447 -1 26448 -1 26449 -1 26450 -1 26451 -1 26452 -1 26453 -1 26454 -1 26455 -1 26456 -1 26457 -1 26458 -1 26459 -1 26460 -1 26461 -1 26462 -1 26463 -1 26464 -1 26465 -1 26466 -1 26467 -1 26468 -1 26469 -1 26470 -1 26471 -1 26472 -1 26473 -1 26474 -1 26475 -1 26476 -1 26477 -1 26478 -1 26479 -1 26480 -1 26481 -1 26482 -1 26483 -1 26484 -1 26485 -1 26486 -1 26487 -1 26488 -1 26489 -1 26490 -1 26491 -1 26492 -1 26493 -1 26494 -1 26495 -1 26496 -1 26497 -1 26498 -1 26499 -1 26500 -1 26501 -1 26502 -1 26503 -1 26504 -1 26505 -1 26506 -1 26507 -1 26508 -1 26509 -1 26510 -1 26511 -1 26512 -1 26513 -1 26514 -1 26515 -1 26516 -1 26517 -1 26518 -1 26519 -1 26520 -1 26521 -1 26522 -1 26523 -1 26524 -1 26525 -1 26526 -1 26527 -1 26528 -1 26529 -1 26530 -1 26531 -1 26532 -1 26533 -1 26534 -1 26535 -1 26536 -1 26537 -1 26538 -1 26539 -1 26540 -1 26541 -1 26542 -1 26543 -1 26544 -1 26545 -1 26546 -1 26547 -1 26548 -1 26549 -1 26550 -1 26551 -1 26552 -1 26553 -1 26554 -1 26555 -1 26556 -1 26557 -1 26558 -1 26559 -1 26560 -1 26561 -1 26562 -1 26563 -1 26564 -1 26565 -1 26566 -1 26567 -1 26568 -1 26569 -1 26570 -1 26571 -1 26572 -1 26573 -1 26574 -1 26575 -1 26576 -1 26577 -1 26578 -1 26579 -1 26580 -1 26581 -1 26582 -1 26583 -1 26584 -1 26585 -1 26586 -1 26587 -1 26588 -1 26589 -1 26590 -1 26591 -1 26592 -1 26593 -1 26594 -1 26595 -1 26596 -1 26597 -1 26598 -1 26599 -1 26600 -1 26601 -1 26602 -1 26603 -1 26604 -1 26605 -1 26606 -1 26607 -1 26608 -1 26609 -1 26610 -1 26611 -1 26612 -1 26613 -1 26614 -1 26615 -1 26616 -1 26617 -1 26618 -1 26619 -1 26620 -1 26621 -1 26622 -1 26623 -1 26624 -1 26625 -1 26626 -1 26627 -1 26628 -1 26629 -1 26630 -1 26631 -1 26632 -1 26633 -1 26634 -1 26635 -1 26636 -1 26637 -1 26638 -1 26639 -1 26640 -1 26641 -1 26642 -1 26643 -1 26644 -1 26645 -1 26646 -1 26647 -1 26648 -1 26649 -1 26650 -1 26651 -1 26652 -1 26653 -1 26654 -1 26655 -1 26656 -1 26657 -1 26658 -1 26659 -1 26660 -1 26661 -1 26662 -1 26663 -1 26664 -1 26665 -1 26666 -1 26667 -1 26668 -1 26669 -1 26670 -1 26671 -1 26672 -1 26673 -1 26674 -1 26675 -1 26676 -1 26677 -1 26678 -1 26679 -1 26680 -1 26681 -1 26682 -1 26683 -1 26684 -1 26685 -1 26686 -1 26687 -1 26688 -1 26689 -1 26690 -1 26691 -1 26692 -1 26693 -1 26694 -1 26695 -1 26696 -1 26697 -1 26698 -1 26699 -1 26700 -1 26701 -1 26702 -1 26703 -1 26704 -1 26705 -1 26706 -1 26707 -1 26708 -1 26709 -1 26710 -1 26711 -1 26712 -1 26713 -1 26714 -1 26715 -1 26716 -1 26717 -1 26718 -1 26719 -1 26720 -1 26721 -1 26722 -1 26723 -1 26724 -1 26725 -1 26726 -1 26727 -1 26728 -1 26729 -1 26730 -1 26731 -1 26732 -1 26733 -1 26734 -1 26735 -1 26736 -1 26737 -1 26738 -1 26739 -1 26740 -1 26741 -1 26742 -1 26743 -1 26744 -1 26745 -1 26746 -1 26747 -1 26748 -1 26749 -1 26750 -1 26751 -1 26752 -1 26753 -1 26754 -1 26755 -1 26756 -1 26757 -1 26758 -1 26759 -1 26760 -1 26761 -1 26762 -1 26763 -1 26764 -1 26765 -1 26766 -1 26767 -1 26768 -1 26769 -1 26770 -1 26771 -1 26772 -1 26773 -1 26774 -1 26775 -1 26776 -1 26777 -1 26778 -1 26779 -1 26780 -1 26781 -1 26782 -1 26783 -1 26784 -1 26785 -1 26786 -1 26787 -1 26788 -1 26789 -1 26790 -1 26791 -1 26792 -1 26793 -1 26794 -1 26795 -1 26796 -1 26797 -1 26798 -1 26799 -1 26800 -1 26801 -1 26802 -1 26803 -1 26804 -1 26805 -1 26806 -1 26807 -1 26808 -1 26809 -1 26810 -1 26811 -1 26812 -1 26813 -1 26814 -1 26815 -1 26816 -1 26817 -1 26818 -1 26819 -1 26820 -1 26821 -1 26822 -1 26823 -1 26824 -1 26825 -1 26826 -1 26827 -1 26828 -1 26829 -1 26830 -1 26831 -1 26832 -1 26833 -1 26834 -1 26835 -1 26836 -1 26837 -1 26838 -1 26839 -1 26840 -1 26841 -1 26842 -1 26843 -1 26844 -1 26845 -1 26846 -1 26847 -1 26848 -1 26849 -1 26850 -1 26851 -1 26852 -1 26853 -1 26854 -1 26855 -1 26856 -1 26857 -1 26858 -1 26859 -1 26860 -1 26861 -1 26862 -1 26863 -1 26864 -1 26865 -1 26866 -1 26867 -1 26868 -1 26869 -1 26870 -1 26871 -1 26872 -1 26873 -1 26874 -1 26875 -1 26876 -1 26877 -1 26878 -1 26879 -1 26880 -1 26881 -1 26882 -1 26883 -1 26884 -1 26885 -1 26886 -1 26887 -1 26888 -1 26889 -1 26890 -1 26891 -1 26892 -1 26893 -1 26894 -1 26895 -1 26896 -1 26897 -1 26898 -1 26899 -1 26900 -1 26901 -1 26902 -1 26903 -1 26904 -1 26905 -1 26906 -1 26907 -1 26908 -1 26909 -1 26910 -1 26911 -1 26912 -1 26913 -1 26914 -1 26915 -1 26916 -1 26917 -1 26918 -1 26919 -1 26920 -1 26921 -1 26922 -1 26923 -1 26924 -1 26925 -1 26926 -1 26927 -1 26928 -1 26929 -1 26930 -1 26931 -1 26932 -1 26933 -1 26934 -1 26935 -1 26936 -1 26937 -1 26938 -1 26939 -1 26940 -1 26941 -1 26942 -1 26943 -1 26944 -1 26945 -1 26946 -1 26947 -1 26948 -1 26949 -1 26950 -1 26951 -1 26952 -1 26953 -1 26954 -1 26955 -1 26956 -1 26957 -1 26958 -1 26959 -1 26960 -1 26961 -1 26962 -1 26963 -1 26964 -1 26965 -1 26966 -1 26967 -1 26968 -1 26969 -1 26970 -1 26971 -1 26972 -1 26973 -1 26974 -1 26975 -1 26976 -1 26977 -1 26978 -1 26979 -1 26980 -1 26981 -1 26982 -1 26983 -1 26984 -1 26985 -1 26986 -1 26987 -1 26988 -1 26989 -1 26990 -1 26991 -1 26992 -1 26993 -1 26994 -1 26995 -1 26996 -1 26997 -1 26998 -1 26999 -1 27000 -1 27001 -1 27002 -1 27003 -1 27004 -1 27005 -1 27006 -1 27007 -1 27008 -1 27009 -1 27010 -1 27011 -1 27012 -1 27013 -1 27014 -1 27015 -1 27016 -1 27017 -1 27018 -1 27019 -1 27020 -1 27021 -1 27022 -1 27023 -1 27024 -1 27025 -1 27026 -1 27027 -1 27028 -1 27029 -1 27030 -1 27031 -1 27032 -1 27033 -1 27034 -1 27035 -1 27036 -1 27037 -1 27038 -1 27039 -1 27040 -1 27041 -1 27042 -1 27043 -1 27044 -1 27045 -1 27046 -1 27047 -1 27048 -1 27049 -1 27050 -1 27051 -1 27052 -1 27053 -1 27054 -1 27055 -1 27056 -1 27057 -1 27058 -1 27059 -1 27060 -1 27061 -1 27062 -1 27063 -1 27064 -1 27065 -1 27066 -1 27067 -1 27068 -1 27069 -1 27070 -1 27071 -1 27072 -1 27073 -1 27074 -1 27075 -1 27076 -1 27077 -1 27078 -1 27079 -1 27080 -1 27081 -1 27082 -1 27083 -1 27084 -1 27085 -1 27086 -1 27087 -1 27088 -1 27089 -1 27090 -1 27091 -1 27092 -1 27093 -1 27094 -1 27095 -1 27096 -1 27097 -1 27098 -1 27099 -1 27100 -1 27101 -1 27102 -1 27103 -1 27104 -1 27105 -1 27106 -1 27107 -1 27108 -1 27109 -1 27110 -1 27111 -1 27112 -1 27113 -1 27114 -1 27115 -1 27116 -1 27117 -1 27118 -1 27119 -1 27120 -1 27121 -1 27122 -1 27123 -1 27124 -1 27125 -1 27126 -1 27127 -1 27128 -1 27129 -1 27130 -1 27131 -1 27132 -1 27133 -1 27134 -1 27135 -1 27136 -1 27137 -1 27138 -1 27139 -1 27140 -1 27141 -1 27142 -1 27143 -1 27144 -1 27145 -1 27146 -1 27147 -1 27148 -1 27149 -1 27150 -1 27151 -1 27152 -1 27153 -1 27154 -1 27155 -1 27156 -1 27157 -1 27158 -1 27159 -1 27160 -1 27161 -1 27162 -1 27163 -1 27164 -1 27165 -1 27166 -1 27167 -1 27168 -1 27169 -1 27170 -1 27171 -1 27172 -1 27173 -1 27174 -1 27175 -1 27176 -1 27177 -1 27178 -1 27179 -1 27180 -1 27181 -1 27182 -1 27183 -1 27184 -1 27185 -1 27186 -1 27187 -1 27188 -1 27189 -1 27190 -1 27191 -1 27192 -1 27193 -1 27194 -1 27195 -1 27196 -1 27197 -1 27198 -1 27199 -1 27200 -1 27201 -1 27202 -1 27203 -1 27204 -1 27205 -1 27206 -1 27207 -1 27208 -1 27209 -1 27210 -1 27211 -1 27212 -1 27213 -1 27214 -1 27215 -1 27216 -1 27217 -1 27218 -1 27219 -1 27220 -1 27221 -1 27222 -1 27223 -1 27224 -1 27225 -1 27226 -1 27227 -1 27228 -1 27229 -1 27230 -1 27231 -1 27232 -1 27233 -1 27234 -1 27235 -1 27236 -1 27237 -1 27238 -1 27239 -1 27240 -1 27241 -1 27242 -1 27243 -1 27244 -1 27245 -1 27246 -1 27247 -1 27248 -1 27249 -1 27250 -1 27251 -1 27252 -1 27253 -1 27254 -1 27255 -1 27256 -1 27257 -1 27258 -1 27259 -1 27260 -1 27261 -1 27262 -1 27263 -1 27264 -1 27265 -1 27266 -1 27267 -1 27268 -1 27269 -1 27270 -1 27271 -1 27272 -1 27273 -1 27274 -1 27275 -1 27276 -1 27277 -1 27278 -1 27279 -1 27280 -1 27281 -1 27282 -1 27283 -1 27284 -1 27285 -1 27286 -1 27287 -1 27288 -1 27289 -1 27290 -1 27291 -1 27292 -1 27293 -1 27294 -1 27295 -1 27296 -1 27297 -1 27298 -1 27299 -1 27300 -1 27301 -1 27302 -1 27303 -1 27304 -1 27305 -1 27306 -1 27307 -1 27308 -1 27309 -1 27310 -1 27311 -1 27312 -1 27313 -1 27314 -1 27315 -1 27316 -1 27317 -1 27318 -1 27319 -1 27320 -1 27321 -1 27322 -1 27323 -1 27324 -1 27325 -1 27326 -1 27327 -1 27328 -1 27329 -1 27330 -1 27331 -1 27332 -1 27333 -1 27334 -1 27335 -1 27336 -1 27337 -1 27338 -1 27339 -1 27340 -1 27341 -1 27342 -1 27343 -1 27344 -1 27345 -1 27346 -1 27347 -1 27348 -1 27349 -1 27350 -1 27351 -1 27352 -1 27353 -1 27354 -1 27355 -1 27356 -1 27357 -1 27358 -1 27359 -1 27360 -1 27361 -1 27362 -1 27363 -1 27364 -1 27365 -1 27366 -1 27367 -1 27368 -1 27369 -1 27370 -1 27371 -1 27372 -1 27373 -1 27374 -1 27375 -1 27376 -1 27377 -1 27378 -1 27379 -1 27380 -1 27381 -1 27382 -1 27383 -1 27384 -1 27385 -1 27386 -1 27387 -1 27388 -1 27389 -1 27390 -1 27391 -1 27392 -1 27393 -1 27394 -1 27395 -1 27396 -1 27397 -1 27398 -1 27399 -1 27400 -1 27401 -1 27402 -1 27403 -1 27404 -1 27405 -1 27406 -1 27407 -1 27408 -1 27409 -1 27410 -1 27411 -1 27412 -1 27413 -1 27414 -1 27415 -1 27416 -1 27417 -1 27418 -1 27419 -1 27420 -1 27421 -1 27422 -1 27423 -1 27424 -1 27425 -1 27426 -1 27427 -1 27428 -1 27429 -1 27430 -1 27431 -1 27432 -1 27433 -1 27434 -1 27435 -1 27436 -1 27437 -1 27438 -1 27439 -1 27440 -1 27441 -1 27442 -1 27443 -1 27444 -1 27445 -1 27446 -1 27447 -1 27448 -1 27449 -1 27450 -1 27451 -1 27452 -1 27453 -1 27454 -1 27455 -1 27456 -1 27457 -1 27458 -1 27459 -1 27460 -1 27461 -1 27462 -1 27463 -1 27464 -1 27465 -1 27466 -1 27467 -1 27468 -1 27469 -1 27470 -1 27471 -1 27472 -1 27473 -1 27474 -1 27475 -1 27476 -1 27477 -1 27478 -1 27479 -1 27480 -1 27481 -1 27482 -1 27483 -1 27484 -1 27485 -1 27486 -1 27487 -1 27488 -1 27489 -1 27490 -1 27491 -1 27492 -1 27493 -1 27494 -1 27495 -1 27496 -1 27497 -1 27498 -1 27499 -1 27500 -1 27501 -1 27502 -1 27503 -1 27504 -1 27505 -1 27506 -1 27507 -1 27508 -1 27509 -1 27510 -1 27511 -1 27512 -1 27513 -1 27514 -1 27515 -1 27516 -1 27517 -1 27518 -1 27519 -1 27520 -1 27521 -1 27522 -1 27523 -1 27524 -1 27525 -1 27526 -1 27527 -1 27528 -1 27529 -1 27530 -1 27531 -1 27532 -1 27533 -1 27534 -1 27535 -1 27536 -1 27537 -1 27538 -1 27539 -1 27540 -1 27541 -1 27542 -1 27543 -1 27544 -1 27545 -1 27546 -1 27547 -1 27548 -1 27549 -1 27550 -1 27551 -1 27552 -1 27553 -1 27554 -1 27555 -1 27556 -1 27557 -1 27558 -1 27559 -1 27560 -1 27561 -1 27562 -1 27563 -1 27564 -1 27565 -1 27566 -1 27567 -1 27568 -1 27569 -1 27570 -1 27571 -1 27572 -1 27573 -1 27574 -1 27575 -1 27576 -1 27577 -1 27578 -1 27579 -1 27580 -1 27581 -1 27582 -1 27583 -1 27584 -1 27585 -1 27586 -1 27587 -1 27588 -1 27589 -1 27590 -1 27591 -1 27592 -1 27593 -1 27594 -1 27595 -1 27596 -1 27597 -1 27598 -1 27599 -1 27600 -1 27601 -1 27602 -1 27603 -1 27604 -1 27605 -1 27606 -1 27607 -1 27608 -1 27609 -1 27610 -1 27611 -1 27612 -1 27613 -1 27614 -1 27615 -1 27616 -1 27617 -1 27618 -1 27619 -1 27620 -1 27621 -1 27622 -1 27623 -1 27624 -1 27625 -1 27626 -1 27627 -1 27628 -1 27629 -1 27630 -1 27631 -1 27632 -1 27633 -1 27634 -1 27635 -1 27636 -1 27637 -1 27638 -1 27639 -1 27640 -1 27641 -1 27642 -1 27643 -1 27644 -1 27645 -1 27646 -1 27647 -1 27648 -1 27649 -1 27650 -1 27651 -1 27652 -1 27653 -1 27654 -1 27655 -1 27656 -1 27657 -1 27658 -1 27659 -1 27660 -1 27661 -1 27662 -1 27663 -1 27664 -1 27665 -1 27666 -1 27667 -1 27668 -1 27669 -1 27670 -1 27671 -1 27672 -1 27673 -1 27674 -1 27675 -1 27676 -1 27677 -1 27678 -1 27679 -1 27680 -1 27681 -1 27682 -1 27683 -1 27684 -1 27685 -1 27686 -1 27687 -1 27688 -1 27689 -1 27690 -1 27691 -1 27692 -1 27693 -1 27694 -1 27695 -1 27696 -1 27697 -1 27698 -1 27699 -1 27700 -1 27701 -1 27702 -1 27703 -1 27704 -1 27705 -1 27706 -1 27707 -1 27708 -1 27709 -1 27710 -1 27711 -1 27712 -1 27713 -1 27714 -1 27715 -1 27716 -1 27717 -1 27718 -1 27719 -1 27720 -1 27721 -1 27722 -1 27723 -1 27724 -1 27725 -1 27726 -1 27727 -1 27728 -1 27729 -1 27730 -1 27731 -1 27732 -1 27733 -1 27734 -1 27735 -1 27736 -1 27737 -1 27738 -1 27739 -1 27740 -1 27741 -1 27742 -1 27743 -1 27744 -1 27745 -1 27746 -1 27747 -1 27748 -1 27749 -1 27750 -1 27751 -1 27752 -1 27753 -1 27754 -1 27755 -1 27756 -1 27757 -1 27758 -1 27759 -1 27760 -1 27761 -1 27762 -1 27763 -1 27764 -1 27765 -1 27766 -1 27767 -1 27768 -1 27769 -1 27770 -1 27771 -1 27772 -1 27773 -1 27774 -1 27775 -1 27776 -1 27777 -1 27778 -1 27779 -1 27780 -1 27781 -1 27782 -1 27783 -1 27784 -1 27785 -1 27786 -1 27787 -1 27788 -1 27789 -1 27790 -1 27791 -1 27792 -1 27793 -1 27794 -1 27795 -1 27796 -1 27797 -1 27798 -1 27799 -1 27800 -1 27801 -1 27802 -1 27803 -1 27804 -1 27805 -1 27806 -1 27807 -1 27808 -1 27809 -1 27810 -1 27811 -1 27812 -1 27813 -1 27814 -1 27815 -1 27816 -1 27817 -1 27818 -1 27819 -1 27820 -1 27821 -1 27822 -1 27823 -1 27824 -1 27825 -1 27826 -1 27827 -1 27828 -1 27829 -1 27830 -1 27831 -1 27832 -1 27833 -1 27834 -1 27835 -1 27836 -1 27837 -1 27838 -1 27839 -1 27840 -1 27841 -1 27842 -1 27843 -1 27844 -1 27845 -1 27846 -1 27847 -1 27848 -1 27849 -1 27850 -1 27851 -1 27852 -1 27853 -1 27854 -1 27855 -1 27856 -1 27857 -1 27858 -1 27859 -1 27860 -1 27861 -1 27862 -1 27863 -1 27864 -1 27865 -1 27866 -1 27867 -1 27868 -1 27869 -1 27870 -1 27871 -1 27872 -1 27873 -1 27874 -1 27875 -1 27876 -1 27877 -1 27878 -1 27879 -1 27880 -1 27881 -1 27882 -1 27883 -1 27884 -1 27885 -1 27886 -1 27887 -1 27888 -1 27889 -1 27890 -1 27891 -1 27892 -1 27893 -1 27894 -1 27895 -1 27896 -1 27897 -1 27898 -1 27899 -1 27900 -1 27901 -1 27902 -1 27903 -1 27904 -1 27905 -1 27906 -1 27907 -1 27908 -1 27909 -1 27910 -1 27911 -1 27912 -1 27913 -1 27914 -1 27915 -1 27916 -1 27917 -1 27918 -1 27919 -1 27920 -1 27921 -1 27922 -1 27923 -1 27924 -1 27925 -1 27926 -1 27927 -1 27928 -1 27929 -1 27930 -1 27931 -1 27932 -1 27933 -1 27934 -1 27935 -1 27936 -1 27937 -1 27938 -1 27939 -1 27940 -1 27941 -1 27942 -1 27943 -1 27944 -1 27945 -1 27946 -1 27947 -1 27948 -1 27949 -1 27950 -1 27951 -1 27952 -1 27953 -1 27954 -1 27955 -1 27956 -1 27957 -1 27958 -1 27959 -1 27960 -1 27961 -1 27962 -1 27963 -1 27964 -1 27965 -1 27966 -1 27967 -1 27968 -1 27969 -1 27970 -1 27971 -1 27972 -1 27973 -1 27974 -1 27975 -1 27976 -1 27977 -1 27978 -1 27979 -1 27980 -1 27981 -1 27982 -1 27983 -1 27984 -1 27985 -1 27986 -1 27987 -1 27988 -1 27989 -1 27990 -1 27991 -1 27992 -1 27993 -1 27994 -1 27995 -1 27996 -1 27997 -1 27998 -1 27999 -1 28000 -1 28001 -1 28002 -1 28003 -1 28004 -1 28005 -1 28006 -1 28007 -1 28008 -1 28009 -1 28010 -1 28011 -1 28012 -1 28013 -1 28014 -1 28015 -1 28016 -1 28017 -1 28018 -1 28019 -1 28020 -1 28021 -1 28022 -1 28023 -1 28024 -1 28025 -1 28026 -1 28027 -1 28028 -1 28029 -1 28030 -1 28031 -1 28032 -1 28033 -1 28034 -1 28035 -1 28036 -1 28037 -1 28038 -1 28039 -1 28040 -1 28041 -1 28042 -1 28043 -1 28044 -1 28045 -1 28046 -1 28047 -1 28048 -1 28049 -1 28050 -1 28051 -1 28052 -1 28053 -1 28054 -1 28055 -1 28056 -1 28057 -1 28058 -1 28059 -1 28060 -1 28061 -1 28062 -1 28063 -1 28064 -1 28065 -1 28066 -1 28067 -1 28068 -1 28069 -1 28070 -1 28071 -1 28072 -1 28073 -1 28074 -1 28075 -1 28076 -1 28077 -1 28078 -1 28079 -1 28080 -1 28081 -1 28082 -1 28083 -1 28084 -1 28085 -1 28086 -1 28087 -1 28088 -1 28089 -1 28090 -1 28091 -1 28092 -1 28093 -1 28094 -1 28095 -1 28096 -1 28097 -1 28098 -1 28099 -1 28100 -1 28101 -1 28102 -1 28103 -1 28104 -1 28105 -1 28106 -1 28107 -1 28108 -1 28109 -1 28110 -1 28111 -1 28112 -1 28113 -1 28114 -1 28115 -1 28116 -1 28117 -1 28118 -1 28119 -1 28120 -1 28121 -1 28122 -1 28123 -1 28124 -1 28125 -1 28126 -1 28127 -1 28128 -1 28129 -1 28130 -1 28131 -1 28132 -1 28133 -1 28134 -1 28135 -1 28136 -1 28137 -1 28138 -1 28139 -1 28140 -1 28141 -1 28142 -1 28143 -1 28144 -1 28145 -1 28146 -1 28147 -1 28148 -1 28149 -1 28150 -1 28151 -1 28152 -1 28153 -1 28154 -1 28155 -1 28156 -1 28157 -1 28158 -1 28159 -1 28160 -1 28161 -1 28162 -1 28163 -1 28164 -1 28165 -1 28166 -1 28167 -1 28168 -1 28169 -1 28170 -1 28171 -1 28172 -1 28173 -1 28174 -1 28175 -1 28176 -1 28177 -1 28178 -1 28179 -1 28180 -1 28181 -1 28182 -1 28183 -1 28184 -1 28185 -1 28186 -1 28187 -1 28188 -1 28189 -1 28190 -1 28191 -1 28192 -1 28193 -1 28194 -1 28195 -1 28196 -1 28197 -1 28198 -1 28199 -1 28200 -1 28201 -1 28202 -1 28203 -1 28204 -1 28205 -1 28206 -1 28207 -1 28208 -1 28209 -1 28210 -1 28211 -1 28212 -1 28213 -1 28214 -1 28215 -1 28216 -1 28217 -1 28218 -1 28219 -1 28220 -1 28221 -1 28222 -1 28223 -1 28224 -1 28225 -1 28226 -1 28227 -1 28228 -1 28229 -1 28230 -1 28231 -1 28232 -1 28233 -1 28234 -1 28235 -1 28236 -1 28237 -1 28238 -1 28239 -1 28240 -1 28241 -1 28242 -1 28243 -1 28244 -1 28245 -1 28246 -1 28247 -1 28248 -1 28249 -1 28250 -1 28251 -1 28252 -1 28253 -1 28254 -1 28255 -1 28256 -1 28257 -1 28258 -1 28259 -1 28260 -1 28261 -1 28262 -1 28263 -1 28264 -1 28265 -1 28266 -1 28267 -1 28268 -1 28269 -1 28270 -1 28271 -1 28272 -1 28273 -1 28274 -1 28275 -1 28276 -1 28277 -1 28278 -1 28279 -1 28280 -1 28281 -1 28282 -1 28283 -1 28284 -1 28285 -1 28286 -1 28287 -1 28288 -1 28289 -1 28290 -1 28291 -1 28292 -1 28293 -1 28294 -1 28295 -1 28296 -1 28297 -1 28298 -1 28299 -1 28300 -1 28301 -1 28302 -1 28303 -1 28304 -1 28305 -1 28306 -1 28307 -1 28308 -1 28309 -1 28310 -1 28311 -1 28312 -1 28313 -1 28314 -1 28315 -1 28316 -1 28317 -1 28318 -1 28319 -1 28320 -1 28321 -1 28322 -1 28323 -1 28324 -1 28325 -1 28326 -1 28327 -1 28328 -1 28329 -1 28330 -1 28331 -1 28332 -1 28333 -1 28334 -1 28335 -1 28336 -1 28337 -1 28338 -1 28339 -1 28340 -1 28341 -1 28342 -1 28343 -1 28344 -1 28345 -1 28346 -1 28347 -1 28348 -1 28349 -1 28350 -1 28351 -1 28352 -1 28353 -1 28354 -1 28355 -1 28356 -1 28357 -1 28358 -1 28359 -1 28360 -1 28361 -1 28362 -1 28363 -1 28364 -1 28365 -1 28366 -1 28367 -1 28368 -1 28369 -1 28370 -1 28371 -1 28372 -1 28373 -1 28374 -1 28375 -1 28376 -1 28377 -1 28378 -1 28379 -1 28380 -1 28381 -1 28382 -1 28383 -1 28384 -1 28385 -1 28386 -1 28387 -1 28388 -1 28389 -1 28390 -1 28391 -1 28392 -1 28393 -1 28394 -1 28395 -1 28396 -1 28397 -1 28398 -1 28399 -1 28400 -1 28401 -1 28402 -1 28403 -1 28404 -1 28405 -1 28406 -1 28407 -1 28408 -1 28409 -1 28410 -1 28411 -1 28412 -1 28413 -1 28414 -1 28415 -1 28416 -1 28417 -1 28418 -1 28419 -1 28420 -1 28421 -1 28422 -1 28423 -1 28424 -1 28425 -1 28426 -1 28427 -1 28428 -1 28429 -1 28430 -1 28431 -1 28432 -1 28433 -1 28434 -1 28435 -1 28436 -1 28437 -1 28438 -1 28439 -1 28440 -1 28441 -1 28442 -1 28443 -1 28444 -1 28445 -1 28446 -1 28447 -1 28448 -1 28449 -1 28450 -1 28451 -1 28452 -1 28453 -1 28454 -1 28455 -1 28456 -1 28457 -1 28458 -1 28459 -1 28460 -1 28461 -1 28462 -1 28463 -1 28464 -1 28465 -1 28466 -1 28467 -1 28468 -1 28469 -1 28470 -1 28471 -1 28472 -1 28473 -1 28474 -1 28475 -1 28476 -1 28477 -1 28478 -1 28479 -1 28480 -1 28481 -1 28482 -1 28483 -1 28484 -1 28485 -1 28486 -1 28487 -1 28488 -1 28489 -1 28490 -1 28491 -1 28492 -1 28493 -1 28494 -1 28495 -1 28496 -1 28497 -1 28498 -1 28499 -1 28500 -1 28501 -1 28502 -1 28503 -1 28504 -1 28505 -1 28506 -1 28507 -1 28508 -1 28509 -1 28510 -1 28511 -1 28512 -1 28513 -1 28514 -1 28515 -1 28516 -1 28517 -1 28518 -1 28519 -1 28520 -1 28521 -1 28522 -1 28523 -1 28524 -1 28525 -1 28526 -1 28527 -1 28528 -1 28529 -1 28530 -1 28531 -1 28532 -1 28533 -1 28534 -1 28535 -1 28536 -1 28537 -1 28538 -1 28539 -1 28540 -1 28541 -1 28542 -1 28543 -1 28544 -1 28545 -1 28546 -1 28547 -1 28548 -1 28549 -1 28550 -1 28551 -1 28552 -1 28553 -1 28554 -1 28555 -1 28556 -1 28557 -1 28558 -1 28559 -1 28560 -1 28561 -1 28562 -1 28563 -1 28564 -1 28565 -1 28566 -1 28567 -1 28568 -1 28569 -1 28570 -1 28571 -1 28572 -1 28573 -1 28574 -1 28575 -1 28576 -1 28577 -1 28578 -1 28579 -1 28580 -1 28581 -1 28582 -1 28583 -1 28584 -1 28585 -1 28586 -1 28587 -1 28588 -1 28589 -1 28590 -1 28591 -1 28592 -1 28593 -1 28594 -1 28595 -1 28596 -1 28597 -1 28598 -1 28599 -1 28600 -1 28601 -1 28602 -1 28603 -1 28604 -1 28605 -1 28606 -1 28607 -1 28608 -1 28609 -1 28610 -1 28611 -1 28612 -1 28613 -1 28614 -1 28615 -1 28616 -1 28617 -1 28618 -1 28619 -1 28620 -1 28621 -1 28622 -1 28623 -1 28624 -1 28625 -1 28626 -1 28627 -1 28628 -1 28629 -1 28630 -1 28631 -1 28632 -1 28633 -1 28634 -1 28635 -1 28636 -1 28637 -1 28638 -1 28639 -1 28640 -1 28641 -1 28642 -1 28643 -1 28644 -1 28645 -1 28646 -1 28647 -1 28648 -1 28649 -1 28650 -1 28651 -1 28652 -1 28653 -1 28654 -1 28655 -1 28656 -1 28657 -1 28658 -1 28659 -1 28660 -1 28661 -1 28662 -1 28663 -1 28664 -1 28665 -1 28666 -1 28667 -1 28668 -1 28669 -1 28670 -1 28671 -1 28672 -1 28673 -1 28674 -1 28675 -1 28676 -1 28677 -1 28678 -1 28679 -1 28680 -1 28681 -1 28682 -1 28683 -1 28684 -1 28685 -1 28686 -1 28687 -1 28688 -1 28689 -1 28690 -1 28691 -1 28692 -1 28693 -1 28694 -1 28695 -1 28696 -1 28697 -1 28698 -1 28699 -1 28700 -1 28701 -1 28702 -1 28703 -1 28704 -1 28705 -1 28706 -1 28707 -1 28708 -1 28709 -1 28710 -1 28711 -1 28712 -1 28713 -1 28714 -1 28715 -1 28716 -1 28717 -1 28718 -1 28719 -1 28720 -1 28721 -1 28722 -1 28723 -1 28724 -1 28725 -1 28726 -1 28727 -1 28728 -1 28729 -1 28730 -1 28731 -1 28732 -1 28733 -1 28734 -1 28735 -1 28736 -1 28737 -1 28738 -1 28739 -1 28740 -1 28741 -1 28742 -1 28743 -1 28744 -1 28745 -1 28746 -1 28747 -1 28748 -1 28749 -1 28750 -1 28751 -1 28752 -1 28753 -1 28754 -1 28755 -1 28756 -1 28757 -1 28758 -1 28759 -1 28760 -1 28761 -1 28762 -1 28763 -1 28764 -1 28765 -1 28766 -1 28767 -1 28768 -1 28769 -1 28770 -1 28771 -1 28772 -1 28773 -1 28774 -1 28775 -1 28776 -1 28777 -1 28778 -1 28779 -1 28780 -1 28781 -1 28782 -1 28783 -1 28784 -1 28785 -1 28786 -1 28787 -1 28788 -1 28789 -1 28790 -1 28791 -1 28792 -1 28793 -1 28794 -1 28795 -1 28796 -1 28797 -1 28798 -1 28799 -1 28800 -1 28801 -1 28802 -1 28803 -1 28804 -1 28805 -1 28806 -1 28807 -1 28808 -1 28809 -1 28810 -1 28811 -1 28812 -1 28813 -1 28814 -1 28815 -1 28816 -1 28817 -1 28818 -1 28819 -1 28820 -1 28821 -1 28822 -1 28823 -1 28824 -1 28825 -1 28826 -1 28827 -1 28828 -1 28829 -1 28830 -1 28831 -1 28832 -1 28833 -1 28834 -1 28835 -1 28836 -1 28837 -1 28838 -1 28839 -1 28840 -1 28841 -1 28842 -1 28843 -1 28844 -1 28845 -1 28846 -1 28847 -1 28848 -1 28849 -1 28850 -1 28851 -1 28852 -1 28853 -1 28854 -1 28855 -1 28856 -1 28857 -1 28858 -1 28859 -1 28860 -1 28861 -1 28862 -1 28863 -1 28864 -1 28865 -1 28866 -1 28867 -1 28868 -1 28869 -1 28870 -1 28871 -1 28872 -1 28873 -1 28874 -1 28875 -1 28876 -1 28877 -1 28878 -1 28879 -1 28880 -1 28881 -1 28882 -1 28883 -1 28884 -1 28885 -1 28886 -1 28887 -1 28888 -1 28889 -1 28890 -1 28891 -1 28892 -1 28893 -1 28894 -1 28895 -1 28896 -1 28897 -1 28898 -1 28899 -1 28900 -1 28901 -1 28902 -1 28903 -1 28904 -1 28905 -1 28906 -1 28907 -1 28908 -1 28909 -1 28910 -1 28911 -1 28912 -1 28913 -1 28914 -1 28915 -1 28916 -1 28917 -1 28918 -1 28919 -1 28920 -1 28921 -1 28922 -1 28923 -1 28924 -1 28925 -1 28926 -1 28927 -1 28928 -1 28929 -1 28930 -1 28931 -1 28932 -1 28933 -1 28934 -1 28935 -1 28936 -1 28937 -1 28938 -1 28939 -1 28940 -1 28941 -1 28942 -1 28943 -1 28944 -1 28945 -1 28946 -1 28947 -1 28948 -1 28949 -1 28950 -1 28951 -1 28952 -1 28953 -1 28954 -1 28955 -1 28956 -1 28957 -1 28958 -1 28959 -1 28960 -1 28961 -1 28962 -1 28963 -1 28964 -1 28965 -1 28966 -1 28967 -1 28968 -1 28969 -1 28970 -1 28971 -1 28972 -1 28973 -1 28974 -1 28975 -1 28976 -1 28977 -1 28978 -1 28979 -1 28980 -1 28981 -1 28982 -1 28983 -1 28984 -1 28985 -1 28986 -1 28987 -1 28988 -1 28989 -1 28990 -1 28991 -1 28992 -1 28993 -1 28994 -1 28995 -1 28996 -1 28997 -1 28998 -1 28999 -1 29000 -1 29001 -1 29002 -1 29003 -1 29004 -1 29005 -1 29006 -1 29007 -1 29008 -1 29009 -1 29010 -1 29011 -1 29012 -1 29013 -1 29014 -1 29015 -1 29016 -1 29017 -1 29018 -1 29019 -1 29020 -1 29021 -1 29022 -1 29023 -1 29024 -1 29025 -1 29026 -1 29027 -1 29028 -1 29029 -1 29030 -1 29031 -1 29032 -1 29033 -1 29034 -1 29035 -1 29036 -1 29037 -1 29038 -1 29039 -1 29040 -1 29041 -1 29042 -1 29043 -1 29044 -1 29045 -1 29046 -1 29047 -1 29048 -1 29049 -1 29050 -1 29051 -1 29052 -1 29053 -1 29054 -1 29055 -1 29056 -1 29057 -1 29058 -1 29059 -1 29060 -1 29061 -1 29062 -1 29063 -1 29064 -1 29065 -1 29066 -1 29067 -1 29068 -1 29069 -1 29070 -1 29071 -1 29072 -1 29073 -1 29074 -1 29075 -1 29076 -1 29077 -1 29078 -1 29079 -1 29080 -1 29081 -1 29082 -1 29083 -1 29084 -1 29085 -1 29086 -1 29087 -1 29088 -1 29089 -1 29090 -1 29091 -1 29092 -1 29093 -1 29094 -1 29095 -1 29096 -1 29097 -1 29098 -1 29099 -1 29100 -1 29101 -1 29102 -1 29103 -1 29104 -1 29105 -1 29106 -1 29107 -1 29108 -1 29109 -1 29110 -1 29111 -1 29112 -1 29113 -1 29114 -1 29115 -1 29116 -1 29117 -1 29118 -1 29119 -1 29120 -1 29121 -1 29122 -1 29123 -1 29124 -1 29125 -1 29126 -1 29127 -1 29128 -1 29129 -1 29130 -1 29131 -1 29132 -1 29133 -1 29134 -1 29135 -1 29136 -1 29137 -1 29138 -1 29139 -1 29140 -1 29141 -1 29142 -1 29143 -1 29144 -1 29145 -1 29146 -1 29147 -1 29148 -1 29149 -1 29150 -1 29151 -1 29152 -1 29153 -1 29154 -1 29155 -1 29156 -1 29157 -1 29158 -1 29159 -1 29160 -1 29161 -1 29162 -1 29163 -1 29164 -1 29165 -1 29166 -1 29167 -1 29168 -1 29169 -1 29170 -1 29171 -1 29172 -1 29173 -1 29174 -1 29175 -1 29176 -1 29177 -1 29178 -1 29179 -1 29180 -1 29181 -1 29182 -1 29183 -1 29184 -1 29185 -1 29186 -1 29187 -1 29188 -1 29189 -1 29190 -1 29191 -1 29192 -1 29193 -1 29194 -1 29195 -1 29196 -1 29197 -1 29198 -1 29199 -1 29200 -1 29201 -1 29202 -1 29203 -1 29204 -1 29205 -1 29206 -1 29207 -1 29208 -1 29209 -1 29210 -1 29211 -1 29212 -1 29213 -1 29214 -1 29215 -1 29216 -1 29217 -1 29218 -1 29219 -1 29220 -1 29221 -1 29222 -1 29223 -1 29224 -1 29225 -1 29226 -1 29227 -1 29228 -1 29229 -1 29230 -1 29231 -1 29232 -1 29233 -1 29234 -1 29235 -1 29236 -1 29237 -1 29238 -1 29239 -1 29240 -1 29241 -1 29242 -1 29243 -1 29244 -1 29245 -1 29246 -1 29247 -1 29248 -1 29249 -1 29250 -1 29251 -1 29252 -1 29253 -1 29254 -1 29255 -1 29256 -1 29257 -1 29258 -1 29259 -1 29260 -1 29261 -1 29262 -1 29263 -1 29264 -1 29265 -1 29266 -1 29267 -1 29268 -1 29269 -1 29270 -1 29271 -1 29272 -1 29273 -1 29274 -1 29275 -1 29276 -1 29277 -1 29278 -1 29279 -1 29280 -1 29281 -1 29282 -1 29283 -1 29284 -1 29285 -1 29286 -1 29287 -1 29288 -1 29289 -1 29290 -1 29291 -1 29292 -1 29293 -1 29294 -1 29295 -1 29296 -1 29297 -1 29298 -1 29299 -1 29300 -1 29301 -1 29302 -1 29303 -1 29304 -1 29305 -1 29306 -1 29307 -1 29308 -1 29309 -1 29310 -1 29311 -1 29312 -1 29313 -1 29314 -1 29315 -1 29316 -1 29317 -1 29318 -1 29319 -1 29320 -1 29321 -1 29322 -1 29323 -1 29324 -1 29325 -1 29326 -1 29327 -1 29328 -1 29329 -1 29330 -1 29331 -1 29332 -1 29333 -1 29334 -1 29335 -1 29336 -1 29337 -1 29338 -1 29339 -1 29340 -1 29341 -1 29342 -1 29343 -1 29344 -1 29345 -1 29346 -1 29347 -1 29348 -1 29349 -1 29350 -1 29351 -1 29352 -1 29353 -1 29354 -1 29355 -1 29356 -1 29357 -1 29358 -1 29359 -1 29360 -1 29361 -1 29362 -1 29363 -1 29364 -1 29365 -1 29366 -1 29367 -1 29368 -1 29369 -1 29370 -1 29371 -1 29372 -1 29373 -1 29374 -1 29375 -1 29376 -1 29377 -1 29378 -1 29379 -1 29380 -1 29381 -1 29382 -1 29383 -1 29384 -1 29385 -1 29386 -1 29387 -1 29388 -1 29389 -1 29390 -1 29391 -1 29392 -1 29393 -1 29394 -1 29395 -1 29396 -1 29397 -1 29398 -1 29399 -1 29400 -1 29401 -1 29402 -1 29403 -1 29404 -1 29405 -1 29406 -1 29407 -1 29408 -1 29409 -1 29410 -1 29411 -1 29412 -1 29413 -1 29414 -1 29415 -1 29416 -1 29417 -1 29418 -1 29419 -1 29420 -1 29421 -1 29422 -1 29423 -1 29424 -1 29425 -1 29426 -1 29427 -1 29428 -1 29429 -1 29430 -1 29431 -1 29432 -1 29433 -1 29434 -1 29435 -1 29436 -1 29437 -1 29438 -1 29439 -1 29440 -1 29441 -1 29442 -1 29443 -1 29444 -1 29445 -1 29446 -1 29447 -1 29448 -1 29449 -1 29450 -1 29451 -1 29452 -1 29453 -1 29454 -1 29455 -1 29456 -1 29457 -1 29458 -1 29459 -1 29460 -1 29461 -1 29462 -1 29463 -1 29464 -1 29465 -1 29466 -1 29467 -1 29468 -1 29469 -1 29470 -1 29471 -1 29472 -1 29473 -1 29474 -1 29475 -1 29476 -1 29477 -1 29478 -1 29479 -1 29480 -1 29481 -1 29482 -1 29483 -1 29484 -1 29485 -1 29486 -1 29487 -1 29488 -1 29489 -1 29490 -1 29491 -1 29492 -1 29493 -1 29494 -1 29495 -1 29496 -1 29497 -1 29498 -1 29499 -1 29500 -1 29501 -1 29502 -1 29503 -1 29504 -1 29505 -1 29506 -1 29507 -1 29508 -1 29509 -1 29510 -1 29511 -1 29512 -1 29513 -1 29514 -1 29515 -1 29516 -1 29517 -1 29518 -1 29519 -1 29520 -1 29521 -1 29522 -1 29523 -1 29524 -1 29525 -1 29526 -1 29527 -1 29528 -1 29529 -1 29530 -1 29531 -1 29532 -1 29533 -1 29534 -1 29535 -1 29536 -1 29537 -1 29538 -1 29539 -1 29540 -1 29541 -1 29542 -1 29543 -1 29544 -1 29545 -1 29546 -1 29547 -1 29548 -1 29549 -1 29550 -1 29551 -1 29552 -1 29553 -1 29554 -1 29555 -1 29556 -1 29557 -1 29558 -1 29559 -1 29560 -1 29561 -1 29562 -1 29563 -1 29564 -1 29565 -1 29566 -1 29567 -1 29568 -1 29569 -1 29570 -1 29571 -1 29572 -1 29573 -1 29574 -1 29575 -1 29576 -1 29577 -1 29578 -1 29579 -1 29580 -1 29581 -1 29582 -1 29583 -1 29584 -1 29585 -1 29586 -1 29587 -1 29588 -1 29589 -1 29590 -1 29591 -1 29592 -1 29593 -1 29594 -1 29595 -1 29596 -1 29597 -1 29598 -1 29599 -1 29600 -1 29601 -1 29602 -1 29603 -1 29604 -1 29605 -1 29606 -1 29607 -1 29608 -1 29609 -1 29610 -1 29611 -1 29612 -1 29613 -1 29614 -1 29615 -1 29616 -1 29617 -1 29618 -1 29619 -1 29620 -1 29621 -1 29622 -1 29623 -1 29624 -1 29625 -1 29626 -1 29627 -1 29628 -1 29629 -1 29630 -1 29631 -1 29632 -1 29633 -1 29634 -1 29635 -1 29636 -1 29637 -1 29638 -1 29639 -1 29640 -1 29641 -1 29642 -1 29643 -1 29644 -1 29645 -1 29646 -1 29647 -1 29648 -1 29649 -1 29650 -1 29651 -1 29652 -1 29653 -1 29654 -1 29655 -1 29656 -1 29657 -1 29658 -1 29659 -1 29660 -1 29661 -1 29662 -1 29663 -1 29664 -1 29665 -1 29666 -1 29667 -1 29668 -1 29669 -1 29670 -1 29671 -1 29672 -1 29673 -1 29674 -1 29675 -1 29676 -1 29677 -1 29678 -1 29679 -1 29680 -1 29681 -1 29682 -1 29683 -1 29684 -1 29685 -1 29686 -1 29687 -1 29688 -1 29689 -1 29690 -1 29691 -1 29692 -1 29693 -1 29694 -1 29695 -1 29696 -1 29697 -1 29698 -1 29699 -1 29700 -1 29701 -1 29702 -1 29703 -1 29704 -1 29705 -1 29706 -1 29707 -1 29708 -1 29709 -1 29710 -1 29711 -1 29712 -1 29713 -1 29714 -1 29715 -1 29716 -1 29717 -1 29718 -1 29719 -1 29720 -1 29721 -1 29722 -1 29723 -1 29724 -1 29725 -1 29726 -1 29727 -1 29728 -1 29729 -1 29730 -1 29731 -1 29732 -1 29733 -1 29734 -1 29735 -1 29736 -1 29737 -1 29738 -1 29739 -1 29740 -1 29741 -1 29742 -1 29743 -1 29744 -1 29745 -1 29746 -1 29747 -1 29748 -1 29749 -1 29750 -1 29751 -1 29752 -1 29753 -1 29754 -1 29755 -1 29756 -1 29757 -1 29758 -1 29759 -1 29760 -1 29761 -1 29762 -1 29763 -1 29764 -1 29765 -1 29766 -1 29767 -1 29768 -1 29769 -1 29770 -1 29771 -1 29772 -1 29773 -1 29774 -1 29775 -1 29776 -1 29777 -1 29778 -1 29779 -1 29780 -1 29781 -1 29782 -1 29783 -1 29784 -1 29785 -1 29786 -1 29787 -1 29788 -1 29789 -1 29790 -1 29791 -1 29792 -1 29793 -1 29794 -1 29795 -1 29796 -1 29797 -1 29798 -1 29799 -1 29800 -1 29801 -1 29802 -1 29803 -1 29804 -1 29805 -1 29806 -1 29807 -1 29808 -1 29809 -1 29810 -1 29811 -1 29812 -1 29813 -1 29814 -1 29815 -1 29816 -1 29817 -1 29818 -1 29819 -1 29820 -1 29821 -1 29822 -1 29823 -1 29824 -1 29825 -1 29826 -1 29827 -1 29828 -1 29829 -1 29830 -1 29831 -1 29832 -1 29833 -1 29834 -1 29835 -1 29836 -1 29837 -1 29838 -1 29839 -1 29840 -1 29841 -1 29842 -1 29843 -1 29844 -1 29845 -1 29846 -1 29847 -1 29848 -1 29849 -1 29850 -1 29851 -1 29852 -1 29853 -1 29854 -1 29855 -1 29856 -1 29857 -1 29858 -1 29859 -1 29860 -1 29861 -1 29862 -1 29863 -1 29864 -1 29865 -1 29866 -1 29867 -1 29868 -1 29869 -1 29870 -1 29871 -1 29872 -1 29873 -1 29874 -1 29875 -1 29876 -1 29877 -1 29878 -1 29879 -1 29880 -1 29881 -1 29882 -1 29883 -1 29884 -1 29885 -1 29886 -1 29887 -1 29888 -1 29889 -1 29890 -1 29891 -1 29892 -1 29893 -1 29894 -1 29895 -1 29896 -1 29897 -1 29898 -1 29899 -1 29900 -1 29901 -1 29902 -1 29903 -1 29904 -1 29905 -1 29906 -1 29907 -1 29908 -1 29909 -1 29910 -1 29911 -1 29912 -1 29913 -1 29914 -1 29915 -1 29916 -1 29917 -1 29918 -1 29919 -1 29920 -1 29921 -1 29922 -1 29923 -1 29924 -1 29925 -1 29926 -1 29927 -1 29928 -1 29929 -1 29930 -1 29931 -1 29932 -1 29933 -1 29934 -1 29935 -1 29936 -1 29937 -1 29938 -1 29939 -1 29940 -1 29941 -1 29942 -1 29943 -1 29944 -1 29945 -1 29946 -1 29947 -1 29948 -1 29949 -1 29950 -1 29951 -1 29952 -1 29953 -1 29954 -1 29955 -1 29956 -1 29957 -1 29958 -1 29959 -1 29960 -1 29961 -1 29962 -1 29963 -1 29964 -1 29965 -1 29966 -1 29967 -1 29968 -1 29969 -1 29970 -1 29971 -1 29972 -1 29973 -1 29974 -1 29975 -1 29976 -1 29977 -1 29978 -1 29979 -1 29980 -1 29981 -1 29982 -1 29983 -1 29984 -1 29985 -1 29986 -1 29987 -1 29988 -1 29989 -1 29990 -1 29991 -1 29992 -1 29993 -1 29994 -1 29995 -1 29996 -1 29997 -1 29998 -1 29999 -1 30000 -1 30001 -1 30002 -1 30003 -1 30004 -1 30005 -1 30006 -1 30007 -1 30008 -1 30009 -1 30010 -1 30011 -1 30012 -1 30013 -1 30014 -1 30015 -1 30016 -1 30017 -1 30018 -1 30019 -1 30020 -1 30021 -1 30022 -1 30023 -1 30024 -1 30025 -1 30026 -1 30027 -1 30028 -1 30029 -1 30030 -1 30031 -1 30032 -1 30033 -1 30034 -1 30035 -1 30036 -1 30037 -1 30038 -1 30039 -1 30040 -1 30041 -1 30042 -1 30043 -1 30044 -1 30045 -1 30046 -1 30047 -1 30048 -1 30049 -1 30050 -1 30051 -1 30052 -1 30053 -1 30054 -1 30055 -1 30056 -1 30057 -1 30058 -1 30059 -1 30060 -1 30061 -1 30062 -1 30063 -1 30064 -1 30065 -1 30066 -1 30067 -1 30068 -1 30069 -1 30070 -1 30071 -1 30072 -1 30073 -1 30074 -1 30075 -1 30076 -1 30077 -1 30078 -1 30079 -1 30080 -1 30081 -1 30082 -1 30083 -1 30084 -1 30085 -1 30086 -1 30087 -1 30088 -1 30089 -1 30090 -1 30091 -1 30092 -1 30093 -1 30094 -1 30095 -1 30096 -1 30097 -1 30098 -1 30099 -1 30100 -1 30101 -1 30102 -1 30103 -1 30104 -1 30105 -1 30106 -1 30107 -1 30108 -1 30109 -1 30110 -1 30111 -1 30112 -1 30113 -1 30114 -1 30115 -1 30116 -1 30117 -1 30118 -1 30119 -1 30120 -1 30121 -1 30122 -1 30123 -1 30124 -1 30125 -1 30126 -1 30127 -1 30128 -1 30129 -1 30130 -1 30131 -1 30132 -1 30133 -1 30134 -1 30135 -1 30136 -1 30137 -1 30138 -1 30139 -1 30140 -1 30141 -1 30142 -1 30143 -1 30144 -1 30145 -1 30146 -1 30147 -1 30148 -1 30149 -1 30150 -1 30151 -1 30152 -1 30153 -1 30154 -1 30155 -1 30156 -1 30157 -1 30158 -1 30159 -1 30160 -1 30161 -1 30162 -1 30163 -1 30164 -1 30165 -1 30166 -1 30167 -1 30168 -1 30169 -1 30170 -1 30171 -1 30172 -1 30173 -1 30174 -1 30175 -1 30176 -1 30177 -1 30178 -1 30179 -1 30180 -1 30181 -1 30182 -1 30183 -1 30184 -1 30185 -1 30186 -1 30187 -1 30188 -1 30189 -1 30190 -1 30191 -1 30192 -1 30193 -1 30194 -1 30195 -1 30196 -1 30197 -1 30198 -1 30199 -1 30200 -1 30201 -1 30202 -1 30203 -1 30204 -1 30205 -1 30206 -1 30207 -1 30208 -1 30209 -1 30210 -1 30211 -1 30212 -1 30213 -1 30214 -1 30215 -1 30216 -1 30217 -1 30218 -1 30219 -1 30220 -1 30221 -1 30222 -1 30223 -1 30224 -1 30225 -1 30226 -1 30227 -1 30228 -1 30229 -1 30230 -1 30231 -1 30232 -1 30233 -1 30234 -1 30235 -1 30236 -1 30237 -1 30238 -1 30239 -1 30240 -1 30241 -1 30242 -1 30243 -1 30244 -1 30245 -1 30246 -1 30247 -1 30248 -1 30249 -1 30250 -1 30251 -1 30252 -1 30253 -1 30254 -1 30255 -1 30256 -1 30257 -1 30258 -1 30259 -1 30260 -1 30261 -1 30262 -1 30263 -1 30264 -1 30265 -1 30266 -1 30267 -1 30268 -1 30269 -1 30270 -1 30271 -1 30272 -1 30273 -1 30274 -1 30275 -1 30276 -1 30277 -1 30278 -1 30279 -1 30280 -1 30281 -1 30282 -1 30283 -1 30284 -1 30285 -1 30286 -1 30287 -1 30288 -1 30289 -1 30290 -1 30291 -1 30292 -1 30293 -1 30294 -1 30295 -1 30296 -1 30297 -1 30298 -1 30299 -1 30300 -1 30301 -1 30302 -1 30303 -1 30304 -1 30305 -1 30306 -1 30307 -1 30308 -1 30309 -1 30310 -1 30311 -1 30312 -1 30313 -1 30314 -1 30315 -1 30316 -1 30317 -1 30318 -1 30319 -1 30320 -1 30321 -1 30322 -1 30323 -1 30324 -1 30325 -1 30326 -1 30327 -1 30328 -1 30329 -1 30330 -1 30331 -1 30332 -1 30333 -1 30334 -1 30335 -1 30336 -1 30337 -1 30338 -1 30339 -1 30340 -1 30341 -1 30342 -1 30343 -1 30344 -1 30345 -1 30346 -1 30347 -1 30348 -1 30349 -1 30350 -1 30351 -1 30352 -1 30353 -1 30354 -1 30355 -1 30356 -1 30357 -1 30358 -1 30359 -1 30360 -1 30361 -1 30362 -1 30363 -1 30364 -1 30365 -1 30366 -1 30367 -1 30368 -1 30369 -1 30370 -1 30371 -1 30372 -1 30373 -1 30374 -1 30375 -1 30376 -1 30377 -1 30378 -1 30379 -1 30380 -1 30381 -1 30382 -1 30383 -1 30384 -1 30385 -1 30386 -1 30387 -1 30388 -1 30389 -1 30390 -1 30391 -1 30392 -1 30393 -1 30394 -1 30395 -1 30396 -1 30397 -1 30398 -1 30399 -1 30400 -1 30401 -1 30402 -1 30403 -1 30404 -1 30405 -1 30406 -1 30407 -1 30408 -1 30409 -1 30410 -1 30411 -1 30412 -1 30413 -1 30414 -1 30415 -1 30416 -1 30417 -1 30418 -1 30419 -1 30420 -1 30421 -1 30422 -1 30423 -1 30424 -1 30425 -1 30426 -1 30427 -1 30428 -1 30429 -1 30430 -1 30431 -1 30432 -1 30433 -1 30434 -1 30435 -1 30436 -1 30437 -1 30438 -1 30439 -1 30440 -1 30441 -1 30442 -1 30443 -1 30444 -1 30445 -1 30446 -1 30447 -1 30448 -1 30449 -1 30450 -1 30451 -1 30452 -1 30453 -1 30454 -1 30455 -1 30456 -1 30457 -1 30458 -1 30459 -1 30460 -1 30461 -1 30462 -1 30463 -1 30464 -1 30465 -1 30466 -1 30467 -1 30468 -1 30469 -1 30470 -1 30471 -1 30472 -1 30473 -1 30474 -1 30475 -1 30476 -1 30477 -1 30478 -1 30479 -1 30480 -1 30481 -1 30482 -1 30483 -1 30484 -1 30485 -1 30486 -1 30487 -1 30488 -1 30489 -1 30490 -1 30491 -1 30492 -1 30493 -1 30494 -1 30495 -1 30496 -1 30497 -1 30498 -1 30499 -1 30500 -1 30501 -1 30502 -1 30503 -1 30504 -1 30505 -1 30506 -1 30507 -1 30508 -1 30509 -1 30510 -1 30511 -1 30512 -1 30513 -1 30514 -1 30515 -1 30516 -1 30517 -1 30518 -1 30519 -1 30520 -1 30521 -1 30522 -1 30523 -1 30524 -1 30525 -1 30526 -1 30527 -1 30528 -1 30529 -1 30530 -1 30531 -1 30532 -1 30533 -1 30534 -1 30535 -1 30536 -1 30537 -1 30538 -1 30539 -1 30540 -1 30541 -1 30542 -1 30543 -1 30544 -1 30545 -1 30546 -1 30547 -1 30548 -1 30549 -1 30550 -1 30551 -1 30552 -1 30553 -1 30554 -1 30555 -1 30556 -1 30557 -1 30558 -1 30559 -1 30560 -1 30561 -1 30562 -1 30563 -1 30564 -1 30565 -1 30566 -1 30567 -1 30568 -1 30569 -1 30570 -1 30571 -1 30572 -1 30573 -1 30574 -1 30575 -1 30576 -1 30577 -1 30578 -1 30579 -1 30580 -1 30581 -1 30582 -1 30583 -1 30584 -1 30585 -1 30586 -1 30587 -1 30588 -1 30589 -1 30590 -1 30591 -1 30592 -1 30593 -1 30594 -1 30595 -1 30596 -1 30597 -1 30598 -1 30599 -1 30600 -1 30601 -1 30602 -1 30603 -1 30604 -1 30605 -1 30606 -1 30607 -1 30608 -1 30609 -1 30610 -1 30611 -1 30612 -1 30613 -1 30614 -1 30615 -1 30616 -1 30617 -1 30618 -1 30619 -1 30620 -1 30621 -1 30622 -1 30623 -1 30624 -1 30625 -1 30626 -1 30627 -1 30628 -1 30629 -1 30630 -1 30631 -1 30632 -1 30633 -1 30634 -1 30635 -1 30636 -1 30637 -1 30638 -1 30639 -1 30640 -1 30641 -1 30642 -1 30643 -1 30644 -1 30645 -1 30646 -1 30647 -1 30648 -1 30649 -1 30650 -1 30651 -1 30652 -1 30653 -1 30654 -1 30655 -1 30656 -1 30657 -1 30658 -1 30659 -1 30660 -1 30661 -1 30662 -1 30663 -1 30664 -1 30665 -1 30666 -1 30667 -1 30668 -1 30669 -1 30670 -1 30671 -1 30672 -1 30673 -1 30674 -1 30675 -1 30676 -1 30677 -1 30678 -1 30679 -1 30680 -1 30681 -1 30682 -1 30683 -1 30684 -1 30685 -1 30686 -1 30687 -1 30688 -1 30689 -1 30690 -1 30691 -1 30692 -1 30693 -1 30694 -1 30695 -1 30696 -1 30697 -1 30698 -1 30699 -1 30700 -1 30701 -1 30702 -1 30703 -1 30704 -1 30705 -1 30706 -1 30707 -1 30708 -1 30709 -1 30710 -1 30711 -1 30712 -1 30713 -1 30714 -1 30715 -1 30716 -1 30717 -1 30718 -1 30719 -1 30720 -1 30721 -1 30722 -1 30723 -1 30724 -1 30725 -1 30726 -1 30727 -1 30728 -1 30729 -1 30730 -1 30731 -1 30732 -1 30733 -1 30734 -1 30735 -1 30736 -1 30737 -1 30738 -1 30739 -1 30740 -1 30741 -1 30742 -1 30743 -1 30744 -1 30745 -1 30746 -1 30747 -1 30748 -1 30749 -1 30750 -1 30751 -1 30752 -1 30753 -1 30754 -1 30755 -1 30756 -1 30757 -1 30758 -1 30759 -1 30760 -1 30761 -1 30762 -1 30763 -1 30764 -1 30765 -1 30766 -1 30767 -1 30768 -1 30769 -1 30770 -1 30771 -1 30772 -1 30773 -1 30774 -1 30775 -1 30776 -1 30777 -1 30778 -1 30779 -1 30780 -1 30781 -1 30782 -1 30783 -1 30784 -1 30785 -1 30786 -1 30787 -1 30788 -1 30789 -1 30790 -1 30791 -1 30792 -1 30793 -1 30794 -1 30795 -1 30796 -1 30797 -1 30798 -1 30799 -1 30800 -1 30801 -1 30802 -1 30803 -1 30804 -1 30805 -1 30806 -1 30807 -1 30808 -1 30809 -1 30810 -1 30811 -1 30812 -1 30813 -1 30814 -1 30815 -1 30816 -1 30817 -1 30818 -1 30819 -1 30820 -1 30821 -1 30822 -1 30823 -1 30824 -1 30825 -1 30826 -1 30827 -1 30828 -1 30829 -1 30830 -1 30831 -1 30832 -1 30833 -1 30834 -1 30835 -1 30836 -1 30837 -1 30838 -1 30839 -1 30840 -1 30841 -1 30842 -1 30843 -1 30844 -1 30845 -1 30846 -1 30847 -1 30848 -1 30849 -1 30850 -1 30851 -1 30852 -1 30853 -1 30854 -1 30855 -1 30856 -1 30857 -1 30858 -1 30859 -1 30860 -1 30861 -1 30862 -1 30863 -1 30864 -1 30865 -1 30866 -1 30867 -1 30868 -1 30869 -1 30870 -1 30871 -1 30872 -1 30873 -1 30874 -1 30875 -1 30876 -1 30877 -1 30878 -1 30879 -1 30880 -1 30881 -1 30882 -1 30883 -1 30884 -1 30885 -1 30886 -1 30887 -1 30888 -1 30889 -1 30890 -1 30891 -1 30892 -1 30893 -1 30894 -1 30895 -1 30896 -1 30897 -1 30898 -1 30899 -1 30900 -1 30901 -1 30902 -1 30903 -1 30904 -1 30905 -1 30906 -1 30907 -1 30908 -1 30909 -1 30910 -1 30911 -1 30912 -1 30913 -1 30914 -1 30915 -1 30916 -1 30917 -1 30918 -1 30919 -1 30920 -1 30921 -1 30922 -1 30923 -1 30924 -1 30925 -1 30926 -1 30927 -1 30928 -1 30929 -1 30930 -1 30931 -1 30932 -1 30933 -1 30934 -1 30935 -1 30936 -1 30937 -1 30938 -1 30939 -1 30940 -1 30941 -1 30942 -1 30943 -1 30944 -1 30945 -1 30946 -1 30947 -1 30948 -1 30949 -1 30950 -1 30951 -1 30952 -1 30953 -1 30954 -1 30955 -1 30956 -1 30957 -1 30958 -1 30959 -1 30960 -1 30961 -1 30962 -1 30963 -1 30964 -1 30965 -1 30966 -1 30967 -1 30968 -1 30969 -1 30970 -1 30971 -1 30972 -1 30973 -1 30974 -1 30975 -1 30976 -1 30977 -1 30978 -1 30979 -1 30980 -1 30981 -1 30982 -1 30983 -1 30984 -1 30985 -1 30986 -1 30987 -1 30988 -1 30989 -1 30990 -1 30991 -1 30992 -1 30993 -1 30994 -1 30995 -1 30996 -1 30997 -1 30998 -1 30999 -1 31000 -1 31001 -1 31002 -1 31003 -1 31004 -1 31005 -1 31006 -1 31007 -1 31008 -1 31009 -1 31010 -1 31011 -1 31012 -1 31013 -1 31014 -1 31015 -1 31016 -1 31017 -1 31018 -1 31019 -1 31020 -1 31021 -1 31022 -1 31023 -1 31024 -1 31025 -1 31026 -1 31027 -1 31028 -1 31029 -1 31030 -1 31031 -1 31032 -1 31033 -1 31034 -1 31035 -1 31036 -1 31037 -1 31038 -1 31039 -1 31040 -1 31041 -1 31042 -1 31043 -1 31044 -1 31045 -1 31046 -1 31047 -1 31048 -1 31049 -1 31050 -1 31051 -1 31052 -1 31053 -1 31054 -1 31055 -1 31056 -1 31057 -1 31058 -1 31059 -1 31060 -1 31061 -1 31062 -1 31063 -1 31064 -1 31065 -1 31066 -1 31067 -1 31068 -1 31069 -1 31070 -1 31071 -1 31072 -1 31073 -1 31074 -1 31075 -1 31076 -1 31077 -1 31078 -1 31079 -1 31080 -1 31081 -1 31082 -1 31083 -1 31084 -1 31085 -1 31086 -1 31087 -1 31088 -1 31089 -1 31090 -1 31091 -1 31092 -1 31093 -1 31094 -1 31095 -1 31096 -1 31097 -1 31098 -1 31099 -1 31100 -1 31101 -1 31102 -1 31103 -1 31104 -1 31105 -1 31106 -1 31107 -1 31108 -1 31109 -1 31110 -1 31111 -1 31112 -1 31113 -1 31114 -1 31115 -1 31116 -1 31117 -1 31118 -1 31119 -1 31120 -1 31121 -1 31122 -1 31123 -1 31124 -1 31125 -1 31126 -1 31127 -1 31128 -1 31129 -1 31130 -1 31131 -1 31132 -1 31133 -1 31134 -1 31135 -1 31136 -1 31137 -1 31138 -1 31139 -1 31140 -1 31141 -1 31142 -1 31143 -1 31144 -1 31145 -1 31146 -1 31147 -1 31148 -1 31149 -1 31150 -1 31151 -1 31152 -1 31153 -1 31154 -1 31155 -1 31156 -1 31157 -1 31158 -1 31159 -1 31160 -1 31161 -1 31162 -1 31163 -1 31164 -1 31165 -1 31166 -1 31167 -1 31168 -1 31169 -1 31170 -1 31171 -1 31172 -1 31173 -1 31174 -1 31175 -1 31176 -1 31177 -1 31178 -1 31179 -1 31180 -1 31181 -1 31182 -1 31183 -1 31184 -1 31185 -1 31186 -1 31187 -1 31188 -1 31189 -1 31190 -1 31191 -1 31192 -1 31193 -1 31194 -1 31195 -1 31196 -1 31197 -1 31198 -1 31199 -1 31200 -1 31201 -1 31202 -1 31203 -1 31204 -1 31205 -1 31206 -1 31207 -1 31208 -1 31209 -1 31210 -1 31211 -1 31212 -1 31213 -1 31214 -1 31215 -1 31216 -1 31217 -1 31218 -1 31219 -1 31220 -1 31221 -1 31222 -1 31223 -1 31224 -1 31225 -1 31226 -1 31227 -1 31228 -1 31229 -1 31230 -1 31231 -1 31232 -1 31233 -1 31234 -1 31235 -1 31236 -1 31237 -1 31238 -1 31239 -1 31240 -1 31241 -1 31242 -1 31243 -1 31244 -1 31245 -1 31246 -1 31247 -1 31248 -1 31249 -1 31250 -1 31251 -1 31252 -1 31253 -1 31254 -1 31255 -1 31256 -1 31257 -1 31258 -1 31259 -1 31260 -1 31261 -1 31262 -1 31263 -1 31264 -1 31265 -1 31266 -1 31267 -1 31268 -1 31269 -1 31270 -1 31271 -1 31272 -1 31273 -1 31274 -1 31275 -1 31276 -1 31277 -1 31278 -1 31279 -1 31280 -1 31281 -1 31282 -1 31283 -1 31284 -1 31285 -1 31286 -1 31287 -1 31288 -1 31289 -1 31290 -1 31291 -1 31292 -1 31293 -1 31294 -1 31295 -1 31296 -1 31297 -1 31298 -1 31299 -1 31300 -1 31301 -1 31302 -1 31303 -1 31304 -1 31305 -1 31306 -1 31307 -1 31308 -1 31309 -1 31310 -1 31311 -1 31312 -1 31313 -1 31314 -1 31315 -1 31316 -1 31317 -1 31318 -1 31319 -1 31320 -1 31321 -1 31322 -1 31323 -1 31324 -1 31325 -1 31326 -1 31327 -1 31328 -1 31329 -1 31330 -1 31331 -1 31332 -1 31333 -1 31334 -1 31335 -1 31336 -1 31337 -1 31338 -1 31339 -1 31340 -1 31341 -1 31342 -1 31343 -1 31344 -1 31345 -1 31346 -1 31347 -1 31348 -1 31349 -1 31350 -1 31351 -1 31352 -1 31353 -1 31354 -1 31355 -1 31356 -1 31357 -1 31358 -1 31359 -1 31360 -1 31361 -1 31362 -1 31363 -1 31364 -1 31365 -1 31366 -1 31367 -1 31368 -1 31369 -1 31370 -1 31371 -1 31372 -1 31373 -1 31374 -1 31375 -1 31376 -1 31377 -1 31378 -1 31379 -1 31380 -1 31381 -1 31382 -1 31383 -1 31384 -1 31385 -1 31386 -1 31387 -1 31388 -1 31389 -1 31390 -1 31391 -1 31392 -1 31393 -1 31394 -1 31395 -1 31396 -1 31397 -1 31398 -1 31399 -1 31400 -1 31401 -1 31402 -1 31403 -1 31404 -1 31405 -1 31406 -1 31407 -1 31408 -1 31409 -1 31410 -1 31411 -1 31412 -1 31413 -1 31414 -1 31415 -1 31416 -1 31417 -1 31418 -1 31419 -1 31420 -1 31421 -1 31422 -1 31423 -1 31424 -1 31425 -1 31426 -1 31427 -1 31428 -1 31429 -1 31430 -1 31431 -1 31432 -1 31433 -1 31434 -1 31435 -1 31436 -1 31437 -1 31438 -1 31439 -1 31440 -1 31441 -1 31442 -1 31443 -1 31444 -1 31445 -1 31446 -1 31447 -1 31448 -1 31449 -1 31450 -1 31451 -1 31452 -1 31453 -1 31454 -1 31455 -1 31456 -1 31457 -1 31458 -1 31459 -1 31460 -1 31461 -1 31462 -1 31463 -1 31464 -1 31465 -1 31466 -1 31467 -1 31468 -1 31469 -1 31470 -1 31471 -1 31472 -1 31473 -1 31474 -1 31475 -1 31476 -1 31477 -1 31478 -1 31479 -1 31480 -1 31481 -1 31482 -1 31483 -1 31484 -1 31485 -1 31486 -1 31487 -1 31488 -1 31489 -1 31490 -1 31491 -1 31492 -1 31493 -1 31494 -1 31495 -1 31496 -1 31497 -1 31498 -1 31499 -1 31500 -1 31501 -1 31502 -1 31503 -1 31504 -1 31505 -1 31506 -1 31507 -1 31508 -1 31509 -1 31510 -1 31511 -1 31512 -1 31513 -1 31514 -1 31515 -1 31516 -1 31517 -1 31518 -1 31519 -1 31520 -1 31521 -1 31522 -1 31523 -1 31524 -1 31525 -1 31526 -1 31527 -1 31528 -1 31529 -1 31530 -1 31531 -1 31532 -1 31533 -1 31534 -1 31535 -1 31536 -1 31537 -1 31538 -1 31539 -1 31540 -1 31541 -1 31542 -1 31543 -1 31544 -1 31545 -1 31546 -1 31547 -1 31548 -1 31549 -1 31550 -1 31551 -1 31552 -1 31553 -1 31554 -1 31555 -1 31556 -1 31557 -1 31558 -1 31559 -1 31560 -1 31561 -1 31562 -1 31563 -1 31564 -1 31565 -1 31566 -1 31567 -1 31568 -1 31569 -1 31570 -1 31571 -1 31572 -1 31573 -1 31574 -1 31575 -1 31576 -1 31577 -1 31578 -1 31579 -1 31580 -1 31581 -1 31582 -1 31583 -1 31584 -1 31585 -1 31586 -1 31587 -1 31588 -1 31589 -1 31590 -1 31591 -1 31592 -1 31593 -1 31594 -1 31595 -1 31596 -1 31597 -1 31598 -1 31599 -1 31600 -1 31601 -1 31602 -1 31603 -1 31604 -1 31605 -1 31606 -1 31607 -1 31608 -1 31609 -1 31610 -1 31611 -1 31612 -1 31613 -1 31614 -1 31615 -1 31616 -1 31617 -1 31618 -1 31619 -1 31620 -1 31621 -1 31622 -1 31623 -1 31624 -1 31625 -1 31626 -1 31627 -1 31628 -1 31629 -1 31630 -1 31631 -1 31632 -1 31633 -1 31634 -1 31635 -1 31636 -1 31637 -1 31638 -1 31639 -1 31640 -1 31641 -1 31642 -1 31643 -1 31644 -1 31645 -1 31646 -1 31647 -1 31648 -1 31649 -1 31650 -1 31651 -1 31652 -1 31653 -1 31654 -1 31655 -1 31656 -1 31657 -1 31658 -1 31659 -1 31660 -1 31661 -1 31662 -1 31663 -1 31664 -1 31665 -1 31666 -1 31667 -1 31668 -1 31669 -1 31670 -1 31671 -1 31672 -1 31673 -1 31674 -1 31675 -1 31676 -1 31677 -1 31678 -1 31679 -1 31680 -1 31681 -1 31682 -1 31683 -1 31684 -1 31685 -1 31686 -1 31687 -1 31688 -1 31689 -1 31690 -1 31691 -1 31692 -1 31693 -1 31694 -1 31695 -1 31696 -1 31697 -1 31698 -1 31699 -1 31700 -1 31701 -1 31702 -1 31703 -1 31704 -1 31705 -1 31706 -1 31707 -1 31708 -1 31709 -1 31710 -1 31711 -1 31712 -1 31713 -1 31714 -1 31715 -1 31716 -1 31717 -1 31718 -1 31719 -1 31720 -1 31721 -1 31722 -1 31723 -1 31724 -1 31725 -1 31726 -1 31727 -1 31728 -1 31729 -1 31730 -1 31731 -1 31732 -1 31733 -1 31734 -1 31735 -1 31736 -1 31737 -1 31738 -1 31739 -1 31740 -1 31741 -1 31742 -1 31743 -1 31744 -1 31745 -1 31746 -1 31747 -1 31748 -1 31749 -1 31750 -1 31751 -1 31752 -1 31753 -1 31754 -1 31755 -1 31756 -1 31757 -1 31758 -1 31759 -1 31760 -1 31761 -1 31762 -1 31763 -1 31764 -1 31765 -1 31766 -1 31767 -1 31768 -1 31769 -1 31770 -1 31771 -1 31772 -1 31773 -1 31774 -1 31775 -1 31776 -1 31777 -1 31778 -1 31779 -1 31780 -1 31781 -1 31782 -1 31783 -1 31784 -1 31785 -1 31786 -1 31787 -1 31788 -1 31789 -1 31790 -1 31791 -1 31792 -1 31793 -1 31794 -1 31795 -1 31796 -1 31797 -1 31798 -1 31799 -1 31800 -1 31801 -1 31802 -1 31803 -1 31804 -1 31805 -1 31806 -1 31807 -1 31808 -1 31809 -1 31810 -1 31811 -1 31812 -1 31813 -1 31814 -1 31815 -1 31816 -1 31817 -1 31818 -1 31819 -1 31820 -1 31821 -1 31822 -1 31823 -1 31824 -1 31825 -1 31826 -1 31827 -1 31828 -1 31829 -1 31830 -1 31831 -1 31832 -1 31833 -1 31834 -1 31835 -1 31836 -1 31837 -1 31838 -1 31839 -1 31840 -1 31841 -1 31842 -1 31843 -1 31844 -1 31845 -1 31846 -1 31847 -1 31848 -1 31849 -1 31850 -1 31851 -1 31852 -1 31853 -1 31854 -1 31855 -1 31856 -1 31857 -1 31858 -1 31859 -1 31860 -1 31861 -1 31862 -1 31863 -1 31864 -1 31865 -1 31866 -1 31867 -1 31868 -1 31869 -1 31870 -1 31871 -1 31872 -1 31873 -1 31874 -1 31875 -1 31876 -1 31877 -1 31878 -1 31879 -1 31880 -1 31881 -1 31882 -1 31883 -1 31884 -1 31885 -1 31886 -1 31887 -1 31888 -1 31889 -1 31890 -1 31891 -1 31892 -1 31893 -1 31894 -1 31895 -1 31896 -1 31897 -1 31898 -1 31899 -1 31900 -1 31901 -1 31902 -1 31903 -1 31904 -1 31905 -1 31906 -1 31907 -1 31908 -1 31909 -1 31910 -1 31911 -1 31912 -1 31913 -1 31914 -1 31915 -1 31916 -1 31917 -1 31918 -1 31919 -1 31920 -1 31921 -1 31922 -1 31923 -1 31924 -1 31925 -1 31926 -1 31927 -1 31928 -1 31929 -1 31930 -1 31931 -1 31932 -1 31933 -1 31934 -1 31935 -1 31936 -1 31937 -1 31938 -1 31939 -1 31940 -1 31941 -1 31942 -1 31943 -1 31944 -1 31945 -1 31946 -1 31947 -1 31948 -1 31949 -1 31950 -1 31951 -1 31952 -1 31953 -1 31954 -1 31955 -1 31956 -1 31957 -1 31958 -1 31959 -1 31960 -1 31961 -1 31962 -1 31963 -1 31964 -1 31965 -1 31966 -1 31967 -1 31968 -1 31969 -1 31970 -1 31971 -1 31972 -1 31973 -1 31974 -1 31975 -1 31976 -1 31977 -1 31978 -1 31979 -1 31980 -1 31981 -1 31982 -1 31983 -1 31984 -1 31985 -1 31986 -1 31987 -1 31988 -1 31989 -1 31990 -1 31991 -1 31992 -1 31993 -1 31994 -1 31995 -1 31996 -1 31997 -1 31998 -1 31999 -1 32000 -1 32001 -1 32002 -1 32003 -1 32004 -1 32005 -1 32006 -1 32007 -1 32008 -1 32009 -1 32010 -1 32011 -1 32012 -1 32013 -1 32014 -1 32015 -1 32016 -1 32017 -1 32018 -1 32019 -1 32020 -1 32021 -1 32022 -1 32023 -1 32024 -1 32025 -1 32026 -1 32027 -1 32028 -1 32029 -1 32030 -1 32031 -1 32032 -1 32033 -1 32034 -1 32035 -1 32036 -1 32037 -1 32038 -1 32039 -1 32040 -1 32041 -1 32042 -1 32043 -1 32044 -1 32045 -1 32046 -1 32047 -1 32048 -1 32049 -1 32050 -1 32051 -1 32052 -1 32053 -1 32054 -1 32055 -1 32056 -1 32057 -1 32058 -1 32059 -1 32060 -1 32061 -1 32062 -1 32063 -1 32064 -1 32065 -1 32066 -1 32067 -1 32068 -1 32069 -1 32070 -1 32071 -1 32072 -1 32073 -1 32074 -1 32075 -1 32076 -1 32077 -1 32078 -1 32079 -1 32080 -1 32081 -1 32082 -1 32083 -1 32084 -1 32085 -1 32086 -1 32087 -1 32088 -1 32089 -1 32090 -1 32091 -1 32092 -1 32093 -1 32094 -1 32095 -1 32096 -1 32097 -1 32098 -1 32099 -1 32100 -1 32101 -1 32102 -1 32103 -1 32104 -1 32105 -1 32106 -1 32107 -1 32108 -1 32109 -1 32110 -1 32111 -1 32112 -1 32113 -1 32114 -1 32115 -1 32116 -1 32117 -1 32118 -1 32119 -1 32120 -1 32121 -1 32122 -1 32123 -1 32124 -1 32125 -1 32126 -1 32127 -1 32128 -1 32129 -1 32130 -1 32131 -1 32132 -1 32133 -1 32134 -1 32135 -1 32136 -1 32137 -1 32138 -1 32139 -1 32140 -1 32141 -1 32142 -1 32143 -1 32144 -1 32145 -1 32146 -1 32147 -1 32148 -1 32149 -1 32150 -1 32151 -1 32152 -1 32153 -1 32154 -1 32155 -1 32156 -1 32157 -1 32158 -1 32159 -1 32160 -1 32161 -1 32162 -1 32163 -1 32164 -1 32165 -1 32166 -1 32167 -1 32168 -1 32169 -1 32170 -1 32171 -1 32172 -1 32173 -1 32174 -1 32175 -1 32176 -1 32177 -1 32178 -1 32179 -1 32180 -1 32181 -1 32182 -1 32183 -1 32184 -1 32185 -1 32186 -1 32187 -1 32188 -1 32189 -1 32190 -1 32191 -1 32192 -1 32193 -1 32194 -1 32195 -1 32196 -1 32197 -1 32198 -1 32199 -1 32200 -1 32201 -1 32202 -1 32203 -1 32204 -1 32205 -1 32206 -1 32207 -1 32208 -1 32209 -1 32210 -1 32211 -1 32212 -1 32213 -1 32214 -1 32215 -1 32216 -1 32217 -1 32218 -1 32219 -1 32220 -1 32221 -1 32222 -1 32223 -1 32224 -1 32225 -1 32226 -1 32227 -1 32228 -1 32229 -1 32230 -1 32231 -1 32232 -1 32233 -1 32234 -1 32235 -1 32236 -1 32237 -1 32238 -1 32239 -1 32240 -1 32241 -1 32242 -1 32243 -1 32244 -1 32245 -1 32246 -1 32247 -1 32248 -1 32249 -1 32250 -1 32251 -1 32252 -1 32253 -1 32254 -1 32255 -1 32256 -1 32257 -1 32258 -1 32259 -1 32260 -1 32261 -1 32262 -1 32263 -1 32264 -1 32265 -1 32266 -1 32267 -1 32268 -1 32269 -1 32270 -1 32271 -1 32272 -1 32273 -1 32274 -1 32275 -1 32276 -1 32277 -1 32278 -1 32279 -1 32280 -1 32281 -1 32282 -1 32283 -1 32284 -1 32285 -1 32286 -1 32287 -1 32288 -1 32289 -1 32290 -1 32291 -1 32292 -1 32293 -1 32294 -1 32295 -1 32296 -1 32297 -1 32298 -1 32299 -1 32300 -1 32301 -1 32302 -1 32303 -1 32304 -1 32305 -1 32306 -1 32307 -1 32308 -1 32309 -1 32310 -1 32311 -1 32312 -1 32313 -1 32314 -1 32315 -1 32316 -1 32317 -1 32318 -1 32319 -1 32320 -1 32321 -1 32322 -1 32323 -1 32324 -1 32325 -1 32326 -1 32327 -1 32328 -1 32329 -1 32330 -1 32331 -1 32332 -1 32333 -1 32334 -1 32335 -1 32336 -1 32337 -1 32338 -1 32339 -1 32340 -1 32341 -1 32342 -1 32343 -1 32344 -1 32345 -1 32346 -1 32347 -1 32348 -1 32349 -1 32350 -1 32351 -1 32352 -1 32353 -1 32354 -1 32355 -1 32356 -1 32357 -1 32358 -1 32359 -1 32360 -1 32361 -1 32362 -1 32363 -1 32364 -1 32365 -1 32366 -1 32367 -1 32368 -1 32369 -1 32370 -1 32371 -1 32372 -1 32373 -1 32374 -1 32375 -1 32376 -1 32377 -1 32378 -1 32379 -1 32380 -1 32381 -1 32382 -1 32383 -1 32384 -1 32385 -1 32386 -1 32387 -1 32388 -1 32389 -1 32390 -1 32391 -1 32392 -1 32393 -1 32394 -1 32395 -1 32396 -1 32397 -1 32398 -1 32399 -1 32400 -1 32401 -1 32402 -1 32403 -1 32404 -1 32405 -1 32406 -1 32407 -1 32408 -1 32409 -1 32410 -1 32411 -1 32412 -1 32413 -1 32414 -1 32415 -1 32416 -1 32417 -1 32418 -1 32419 -1 32420 -1 32421 -1 32422 -1 32423 -1 32424 -1 32425 -1 32426 -1 32427 -1 32428 -1 32429 -1 32430 -1 32431 -1 32432 -1 32433 -1 32434 -1 32435 -1 32436 -1 32437 -1 32438 -1 32439 -1 32440 -1 32441 -1 32442 -1 32443 -1 32444 -1 32445 -1 32446 -1 32447 -1 32448 -1 32449 -1 32450 -1 32451 -1 32452 -1 32453 -1 32454 -1 32455 -1 32456 -1 32457 -1 32458 -1 32459 -1 32460 -1 32461 -1 32462 -1 32463 -1 32464 -1 32465 -1 32466 -1 32467 -1 32468 -1 32469 -1 32470 -1 32471 -1 32472 -1 32473 -1 32474 -1 32475 -1 32476 -1 32477 -1 32478 -1 32479 -1 32480 -1 32481 -1 32482 -1 32483 -1 32484 -1 32485 -1 32486 -1 32487 -1 32488 -1 32489 -1 32490 -1 32491 -1 32492 -1 32493 -1 32494 -1 32495 -1 32496 -1 32497 -1 32498 -1 32499 -1 32500 -1 32501 -1 32502 -1 32503 -1 32504 -1 32505 -1 32506 -1 32507 -1 32508 -1 32509 -1 32510 -1 32511 -1 32512 -1 32513 -1 32514 -1 32515 -1 32516 -1 32517 -1 32518 -1 32519 -1 32520 -1 32521 -1 32522 -1 32523 -1 32524 -1 32525 -1 32526 -1 32527 -1 32528 -1 32529 -1 32530 -1 32531 -1 32532 -1 32533 -1 32534 -1 32535 -1 32536 -1 32537 -1 32538 -1 32539 -1 32540 -1 32541 -1 32542 -1 32543 -1 32544 -1 32545 -1 32546 -1 32547 -1 32548 -1 32549 -1 32550 -1 32551 -1 32552 -1 32553 -1 32554 -1 32555 -1 32556 -1 32557 -1 32558 -1 32559 -1 32560 -1 32561 -1 32562 -1 32563 -1 32564 -1 32565 -1 32566 -1 32567 -1 32568 -1 32569 -1 32570 -1 32571 -1 32572 -1 32573 -1 32574 -1 32575 -1 32576 -1 32577 -1 32578 -1 32579 -1 32580 -1 32581 -1 32582 -1 32583 -1 32584 -1 32585 -1 32586 -1 32587 -1 32588 -1 32589 -1 32590 -1 32591 -1 32592 -1 32593 -1 32594 -1 32595 -1 32596 -1 32597 -1 32598 -1 32599 -1 32600 -1 32601 -1 32602 -1 32603 -1 32604 -1 32605 -1 32606 -1 32607 -1 32608 -1 32609 -1 32610 -1 32611 -1 32612 -1 32613 -1 32614 -1 32615 -1 32616 -1 32617 -1 32618 -1 32619 -1 32620 -1 32621 -1 32622 -1 32623 -1 32624 -1 32625 -1 32626 -1 32627 -1 32628 -1 32629 -1 32630 -1 32631 -1 32632 -1 32633 -1 32634 -1 32635 -1 32636 -1 32637 -1 32638 -1 32639 -1 32640 -1 32641 -1 32642 -1 32643 -1 32644 -1 32645 -1 32646 -1 32647 -1 32648 -1 32649 -1 32650 -1 32651 -1 32652 -1 32653 -1 32654 -1 32655 -1 32656 -1 32657 -1 32658 -1 32659 -1 32660 -1 32661 -1 32662 -1 32663 -1 32664 -1 32665 -1 32666 -1 32667 -1 32668 -1 32669 -1 32670 -1 32671 -1 32672 -1 32673 -1 32674 -1 32675 -1 32676 -1 32677 -1 32678 -1 32679 -1 32680 -1 32681 -1 32682 -1 32683 -1 32684 -1 32685 -1 32686 -1 32687 -1 32688 -1 32689 -1 32690 -1 32691 -1 32692 -1 32693 -1 32694 -1 32695 -1 32696 -1 32697 -1 32698 -1 32699 -1 32700 -1 32701 -1 32702 -1 32703 -1 32704 -1 32705 -1 32706 -1 32707 -1 32708 -1 32709 -1 32710 -1 32711 -1 32712 -1 32713 -1 32714 -1 32715 -1 32716 -1 32717 -1 32718 -1 32719 -1 32720 -1 32721 -1 32722 -1 32723 -1 32724 -1 32725 -1 32726 -1 32727 -1 32728 -1 32729 -1 32730 -1 32731 -1 32732 -1 32733 -1 32734 -1 32735 -1 32736 -1 32737 -1 32738 -1 32739 -1 32740 -1 32741 -1 32742 -1 32743 -1 32744 -1 32745 -1 32746 -1 32747 -1 32748 -1 32749 -1 32750 -1 32751 -1 32752 -1 32753 -1 32754 -1 32755 -1 32756 -1 32757 -1 32758 -1 32759 -1 32760 -1 32761 -1 32762 -1 32763 -1 32764 -1 32765 -1 32766 -1 32767 -1 32768 -1 32769 -1 32770 -1 32771 -1 32772 -1 32773 -1 32774 -1 32775 -1 32776 -1 32777 -1 32778 -1 32779 -1 32780 -1 32781 -1 32782 -1 32783 -1 32784 -1 32785 -1 32786 -1 32787 -1 32788 -1 32789 -1 32790 -1 32791 -1 32792 -1 32793 -1 32794 -1 32795 -1 32796 -1 32797 -1 32798 -1 32799 -1 32800 -1 32801 -1 32802 -1 32803 -1 32804 -1 32805 -1 32806 -1 32807 -1 32808 -1 32809 -1 32810 -1 32811 -1 32812 -1 32813 -1 32814 -1 32815 -1 32816 -1 32817 -1 32818 -1 32819 -1 32820 -1 32821 -1 32822 -1 32823 -1 32824 -1 32825 -1 32826 -1 32827 -1 32828 -1 32829 -1 32830 -1 32831 -1 32832 -1 32833 -1 32834 -1 32835 -1 32836 -1 32837 -1 32838 -1 32839 -1 32840 -1 32841 -1 32842 -1 32843 -1 32844 -1 32845 -1 32846 -1 32847 -1 32848 -1 32849 -1 32850 -1 32851 -1 32852 -1 32853 -1 32854 -1 32855 -1 32856 -1 32857 -1 32858 -1 32859 -1 32860 -1 32861 -1 32862 -1 32863 -1 32864 -1 32865 -1 32866 -1 32867 -1 32868 -1 32869 -1 32870 -1 32871 -1 32872 -1 32873 -1 32874 -1 32875 -1 32876 -1 32877 -1 32878 -1 32879 -1 32880 -1 32881 -1 32882 -1 32883 -1 32884 -1 32885 -1 32886 -1 32887 -1 32888 -1 32889 -1 32890 -1 32891 -1 32892 -1 32893 -1 32894 -1 32895 -1 32896 -1 32897 -1 32898 -1 32899 -1 32900 -1 32901 -1 32902 -1 32903 -1 32904 -1 32905 -1 32906 -1 32907 -1 32908 -1 32909 -1 32910 -1 32911 -1 32912 -1 32913 -1 32914 -1 32915 -1 32916 -1 32917 -1 32918 -1 32919 -1 32920 -1 32921 -1 32922 -1 32923 -1 32924 -1 32925 -1 32926 -1 32927 -1 32928 -1 32929 -1 32930 -1 32931 -1 32932 -1 32933 -1 32934 -1 32935 -1 32936 -1 32937 -1 32938 -1 32939 -1 32940 -1 32941 -1 32942 -1 32943 -1 32944 -1 32945 -1 32946 -1 32947 -1 32948 -1 32949 -1 32950 -1 32951 -1 32952 -1 32953 -1 32954 -1 32955 -1 32956 -1 32957 -1 32958 -1 32959 -1 32960 -1 32961 -1 32962 -1 32963 -1 32964 -1 32965 -1 32966 -1 32967 -1 32968 -1 32969 -1 32970 -1 32971 -1 32972 -1 32973 -1 32974 -1 32975 -1 32976 -1 32977 -1 32978 -1 32979 -1 32980 -1 32981 -1 32982 -1 32983 -1 32984 -1 32985 -1 32986 -1 32987 -1 32988 -1 32989 -1 32990 -1 32991 -1 32992 -1 32993 -1 32994 -1 32995 -1 32996 -1 32997 -1 32998 -1 32999 -1 33000 -1 33001 -1 33002 -1 33003 -1 33004 -1 33005 -1 33006 -1 33007 -1 33008 -1 33009 -1 33010 -1 33011 -1 33012 -1 33013 -1 33014 -1 33015 -1 33016 -1 33017 -1 33018 -1 33019 -1 33020 -1 33021 -1 33022 -1 33023 -1 33024 -1 33025 -1 33026 -1 33027 -1 33028 -1 33029 -1 33030 -1 33031 -1 33032 -1 33033 -1 33034 -1 33035 -1 33036 -1 33037 -1 33038 -1 33039 -1 33040 -1 33041 -1 33042 -1 33043 -1 33044 -1 33045 -1 33046 -1 33047 -1 33048 -1 33049 -1 33050 -1 33051 -1 33052 -1 33053 -1 33054 -1 33055 -1 33056 -1 33057 -1 33058 -1 33059 -1 33060 -1 33061 -1 33062 -1 33063 -1 33064 -1 33065 -1 33066 -1 33067 -1 33068 -1 33069 -1 33070 -1 33071 -1 33072 -1 33073 -1 33074 -1 33075 -1 33076 -1 33077 -1 33078 -1 33079 -1 33080 -1 33081 -1 33082 -1 33083 -1 33084 -1 33085 -1 33086 -1 33087 -1 33088 -1 33089 -1 33090 -1 33091 -1 33092 -1 33093 -1 33094 -1 33095 -1 33096 -1 33097 -1 33098 -1 33099 -1 33100 -1 33101 -1 33102 -1 33103 -1 33104 -1 33105 -1 33106 -1 33107 -1 33108 -1 33109 -1 33110 -1 33111 -1 33112 -1 33113 -1 33114 -1 33115 -1 33116 -1 33117 -1 33118 -1 33119 -1 33120 -1 33121 -1 33122 -1 33123 -1 33124 -1 33125 -1 33126 -1 33127 -1 33128 -1 33129 -1 33130 -1 33131 -1 33132 -1 33133 -1 33134 -1 33135 -1 33136 -1 33137 -1 33138 -1 33139 -1 33140 -1 33141 -1 33142 -1 33143 -1 33144 -1 33145 -1 33146 -1 33147 -1 33148 -1 33149 -1 33150 -1 33151 -1 33152 -1 33153 -1 33154 -1 33155 -1 33156 -1 33157 -1 33158 -1 33159 -1 33160 -1 33161 -1 33162 -1 33163 -1 33164 -1 33165 -1 33166 -1 33167 -1 33168 -1 33169 -1 33170 -1 33171 -1 33172 -1 33173 -1 33174 -1 33175 -1 33176 -1 33177 -1 33178 -1 33179 -1 33180 -1 33181 -1 33182 -1 33183 -1 33184 -1 33185 -1 33186 -1 33187 -1 33188 -1 33189 -1 33190 -1 33191 -1 33192 -1 33193 -1 33194 -1 33195 -1 33196 -1 33197 -1 33198 -1 33199 -1 33200 -1 33201 -1 33202 -1 33203 -1 33204 -1 33205 -1 33206 -1 33207 -1 33208 -1 33209 -1 33210 -1 33211 -1 33212 -1 33213 -1 33214 -1 33215 -1 33216 -1 33217 -1 33218 -1 33219 -1 33220 -1 33221 -1 33222 -1 33223 -1 33224 -1 33225 -1 33226 -1 33227 -1 33228 -1 33229 -1 33230 -1 33231 -1 33232 -1 33233 -1 33234 -1 33235 -1 33236 -1 33237 -1 33238 -1 33239 -1 33240 -1 33241 -1 33242 -1 33243 -1 33244 -1 33245 -1 33246 -1 33247 -1 33248 -1 33249 -1 33250 -1 33251 -1 33252 -1 33253 -1 33254 -1 33255 -1 33256 -1 33257 -1 33258 -1 33259 -1 33260 -1 33261 -1 33262 -1 33263 -1 33264 -1 33265 -1 33266 -1 33267 -1 33268 -1 33269 -1 33270 -1 33271 -1 33272 -1 33273 -1 33274 -1 33275 -1 33276 -1 33277 -1 33278 -1 33279 -1 33280 -1 33281 -1 33282 -1 33283 -1 33284 -1 33285 -1 33286 -1 33287 -1 33288 -1 33289 -1 33290 -1 33291 -1 33292 -1 33293 -1 33294 -1 33295 -1 33296 -1 33297 -1 33298 -1 33299 -1 33300 -1 33301 -1 33302 -1 33303 -1 33304 -1 33305 -1 33306 -1 33307 -1 33308 -1 33309 -1 33310 -1 33311 -1 33312 -1 33313 -1 33314 -1 33315 -1 33316 -1 33317 -1 33318 -1 33319 -1 33320 -1 33321 -1 33322 -1 33323 -1 33324 -1 33325 -1 33326 -1 33327 -1 33328 -1 33329 -1 33330 -1 33331 -1 33332 -1 33333 -1 33334 -1 33335 -1 33336 -1 33337 -1 33338 -1 33339 -1 33340 -1 33341 -1 33342 -1 33343 -1 33344 -1 33345 -1 33346 -1 33347 -1 33348 -1 33349 -1 33350 -1 33351 -1 33352 -1 33353 -1 33354 -1 33355 -1 33356 -1 33357 -1 33358 -1 33359 -1 33360 -1 33361 -1 33362 -1 33363 -1 33364 -1 33365 -1 33366 -1 33367 -1 33368 -1 33369 -1 33370 -1 33371 -1 33372 -1 33373 -1 33374 -1 33375 -1 33376 -1 33377 -1 33378 -1 33379 -1 33380 -1 33381 -1 33382 -1 33383 -1 33384 -1 33385 -1 33386 -1 33387 -1 33388 -1 33389 -1 33390 -1 33391 -1 33392 -1 33393 -1 33394 -1 33395 -1 33396 -1 33397 -1 33398 -1 33399 -1 33400 -1 33401 -1 33402 -1 33403 -1 33404 -1 33405 -1 33406 -1 33407 -1 33408 -1 33409 -1 33410 -1 33411 -1 33412 -1 33413 -1 33414 -1 33415 -1 33416 -1 33417 -1 33418 -1 33419 -1 33420 -1 33421 -1 33422 -1 33423 -1 33424 -1 33425 -1 33426 -1 33427 -1 33428 -1 33429 -1 33430 -1 33431 -1 33432 -1 33433 -1 33434 -1 33435 -1 33436 -1 33437 -1 33438 -1 33439 -1 33440 -1 33441 -1 33442 -1 33443 -1 33444 -1 33445 -1 33446 -1 33447 -1 33448 -1 33449 -1 33450 -1 33451 -1 33452 -1 33453 -1 33454 -1 33455 -1 33456 -1 33457 -1 33458 -1 33459 -1 33460 -1 33461 -1 33462 -1 33463 -1 33464 -1 33465 -1 33466 -1 33467 -1 33468 -1 33469 -1 33470 -1 33471 -1 33472 -1 33473 -1 33474 -1 33475 -1 33476 -1 33477 -1 33478 -1 33479 -1 33480 -1 33481 -1 33482 -1 33483 -1 33484 -1 33485 -1 33486 -1 33487 -1 33488 -1 33489 -1 33490 -1 33491 -1 33492 -1 33493 -1 33494 -1 33495 -1 33496 -1 33497 -1 33498 -1 33499 -1 33500 -1 33501 -1 33502 -1 33503 -1 33504 -1 33505 -1 33506 -1 33507 -1 33508 -1 33509 -1 33510 -1 33511 -1 33512 -1 33513 -1 33514 -1 33515 -1 33516 -1 33517 -1 33518 -1 33519 -1 33520 -1 33521 -1 33522 -1 33523 -1 33524 -1 33525 -1 33526 -1 33527 -1 33528 -1 33529 -1 33530 -1 33531 -1 33532 -1 33533 -1 33534 -1 33535 -1 33536 -1 33537 -1 33538 -1 33539 -1 33540 -1 33541 -1 33542 -1 33543 -1 33544 -1 33545 -1 33546 -1 33547 -1 33548 -1 33549 -1 33550 -1 33551 -1 33552 -1 33553 -1 33554 -1 33555 -1 33556 -1 33557 -1 33558 -1 33559 -1 33560 -1 33561 -1 33562 -1 33563 -1 33564 -1 33565 -1 33566 -1 33567 -1 33568 -1 33569 -1 33570 -1 33571 -1 33572 -1 33573 -1 33574 -1 33575 -1 33576 -1 33577 -1 33578 -1 33579 -1 33580 -1 33581 -1 33582 -1 33583 -1 33584 -1 33585 -1 33586 -1 33587 -1 33588 -1 33589 -1 33590 -1 33591 -1 33592 -1 33593 -1 33594 -1 33595 -1 33596 -1 33597 -1 33598 -1 33599 -1 33600 -1 33601 -1 33602 -1 33603 -1 33604 -1 33605 -1 33606 -1 33607 -1 33608 -1 33609 -1 33610 -1 33611 -1 33612 -1 33613 -1 33614 -1 33615 -1 33616 -1 33617 -1 33618 -1 33619 -1 33620 -1 33621 -1 33622 -1 33623 -1 33624 -1 33625 -1 33626 -1 33627 -1 33628 -1 33629 -1 33630 -1 33631 -1 33632 -1 33633 -1 33634 -1 33635 -1 33636 -1 33637 -1 33638 -1 33639 -1 33640 -1 33641 -1 33642 -1 33643 -1 33644 -1 33645 -1 33646 -1 33647 -1 33648 -1 33649 -1 33650 -1 33651 -1 33652 -1 33653 -1 33654 -1 33655 -1 33656 -1 33657 -1 33658 -1 33659 -1 33660 -1 33661 -1 33662 -1 33663 -1 33664 -1 33665 -1 33666 -1 33667 -1 33668 -1 33669 -1 33670 -1 33671 -1 33672 -1 33673 -1 33674 -1 33675 -1 33676 -1 33677 -1 33678 -1 33679 -1 33680 -1 33681 -1 33682 -1 33683 -1 33684 -1 33685 -1 33686 -1 33687 -1 33688 -1 33689 -1 33690 -1 33691 -1 33692 -1 33693 -1 33694 -1 33695 -1 33696 -1 33697 -1 33698 -1 33699 -1 33700 -1 33701 -1 33702 -1 33703 -1 33704 -1 33705 -1 33706 -1 33707 -1 33708 -1 33709 -1 33710 -1 33711 -1 33712 -1 33713 -1 33714 -1 33715 -1 33716 -1 33717 -1 33718 -1 33719 -1 33720 -1 33721 -1 33722 -1 33723 -1 33724 -1 33725 -1 33726 -1 33727 -1 33728 -1 33729 -1 33730 -1 33731 -1 33732 -1 33733 -1 33734 -1 33735 -1 33736 -1 33737 -1 33738 -1 33739 -1 33740 -1 33741 -1 33742 -1 33743 -1 33744 -1 33745 -1 33746 -1 33747 -1 33748 -1 33749 -1 33750 -1 33751 -1 33752 -1 33753 -1 33754 -1 33755 -1 33756 -1 33757 -1 33758 -1 33759 -1 33760 -1 33761 -1 33762 -1 33763 -1 33764 -1 33765 -1 33766 -1 33767 -1 33768 -1 33769 -1 33770 -1 33771 -1 33772 -1 33773 -1 33774 -1 33775 -1 33776 -1 33777 -1 33778 -1 33779 -1 33780 -1 33781 -1 33782 -1 33783 -1 33784 -1 33785 -1 33786 -1 33787 -1 33788 -1 33789 -1 33790 -1 33791 -1 33792 -1 33793 -1 33794 -1 33795 -1 33796 -1 33797 -1 33798 -1 33799 -1 33800 -1 33801 -1 33802 -1 33803 -1 33804 -1 33805 -1 33806 -1 33807 -1 33808 -1 33809 -1 33810 -1 33811 -1 33812 -1 33813 -1 33814 -1 33815 -1 33816 -1 33817 -1 33818 -1 33819 -1 33820 -1 33821 -1 33822 -1 33823 -1 33824 -1 33825 -1 33826 -1 33827 -1 33828 -1 33829 -1 33830 -1 33831 -1 33832 -1 33833 -1 33834 -1 33835 -1 33836 -1 33837 -1 33838 -1 33839 -1 33840 -1 33841 -1 33842 -1 33843 -1 33844 -1 33845 -1 33846 -1 33847 -1 33848 -1 33849 -1 33850 -1 33851 -1 33852 -1 33853 -1 33854 -1 33855 -1 33856 -1 33857 -1 33858 -1 33859 -1 33860 -1 33861 -1 33862 -1 33863 -1 33864 -1 33865 -1 33866 -1 33867 -1 33868 -1 33869 -1 33870 -1 33871 -1 33872 -1 33873 -1 33874 -1 33875 -1 33876 -1 33877 -1 33878 -1 33879 -1 33880 -1 33881 -1 33882 -1 33883 -1 33884 -1 33885 -1 33886 -1 33887 -1 33888 -1 33889 -1 33890 -1 33891 -1 33892 -1 33893 -1 33894 -1 33895 -1 33896 -1 33897 -1 33898 -1 33899 -1 33900 -1 33901 -1 33902 -1 33903 -1 33904 -1 33905 -1 33906 -1 33907 -1 33908 -1 33909 -1 33910 -1 33911 -1 33912 -1 33913 -1 33914 -1 33915 -1 33916 -1 33917 -1 33918 -1 33919 -1 33920 -1 33921 -1 33922 -1 33923 -1 33924 -1 33925 -1 33926 -1 33927 -1 33928 -1 33929 -1 33930 -1 33931 -1 33932 -1 33933 -1 33934 -1 33935 -1 33936 -1 33937 -1 33938 -1 33939 -1 33940 -1 33941 -1 33942 -1 33943 -1 33944 -1 33945 -1 33946 -1 33947 -1 33948 -1 33949 -1 33950 -1 33951 -1 33952 -1 33953 -1 33954 -1 33955 -1 33956 -1 33957 -1 33958 -1 33959 -1 33960 -1 33961 -1 33962 -1 33963 -1 33964 -1 33965 -1 33966 -1 33967 -1 33968 -1 33969 -1 33970 -1 33971 -1 33972 -1 33973 -1 33974 -1 33975 -1 33976 -1 33977 -1 33978 -1 33979 -1 33980 -1 33981 -1 33982 -1 33983 -1 33984 -1 33985 -1 33986 -1 33987 -1 33988 -1 33989 -1 33990 -1 33991 -1 33992 -1 33993 -1 33994 -1 33995 -1 33996 -1 33997 -1 33998 -1 33999 -1 34000 -1 34001 -1 34002 -1 34003 -1 34004 -1 34005 -1 34006 -1 34007 -1 34008 -1 34009 -1 34010 -1 34011 -1 34012 -1 34013 -1 34014 -1 34015 -1 34016 -1 34017 -1 34018 -1 34019 -1 34020 -1 34021 -1 34022 -1 34023 -1 34024 -1 34025 -1 34026 -1 34027 -1 34028 -1 34029 -1 34030 -1 34031 -1 34032 -1 34033 -1 34034 -1 34035 -1 34036 -1 34037 -1 34038 -1 34039 -1 34040 -1 34041 -1 34042 -1 34043 -1 34044 -1 34045 -1 34046 -1 34047 -1 34048 -1 34049 -1 34050 -1 34051 -1 34052 -1 34053 -1 34054 -1 34055 -1 34056 -1 34057 -1 34058 -1 34059 -1 34060 -1 34061 -1 34062 -1 34063 -1 34064 -1 34065 -1 34066 -1 34067 -1 34068 -1 34069 -1 34070 -1 34071 -1 34072 -1 34073 -1 34074 -1 34075 -1 34076 -1 34077 -1 34078 -1 34079 -1 34080 -1 34081 -1 34082 -1 34083 -1 34084 -1 34085 -1 34086 -1 34087 -1 34088 -1 34089 -1 34090 -1 34091 -1 34092 -1 34093 -1 34094 -1 34095 -1 34096 -1 34097 -1 34098 -1 34099 -1 34100 -1 34101 -1 34102 -1 34103 -1 34104 -1 34105 -1 34106 -1 34107 -1 34108 -1 34109 -1 34110 -1 34111 -1 34112 -1 34113 -1 34114 -1 34115 -1 34116 -1 34117 -1 34118 -1 34119 -1 34120 -1 34121 -1 34122 -1 34123 -1 34124 -1 34125 -1 34126 -1 34127 -1 34128 -1 34129 -1 34130 -1 34131 -1 34132 -1 34133 -1 34134 -1 34135 -1 34136 -1 34137 -1 34138 -1 34139 -1 34140 -1 34141 -1 34142 -1 34143 -1 34144 -1 34145 -1 34146 -1 34147 -1 34148 -1 34149 -1 34150 -1 34151 -1 34152 -1 34153 -1 34154 -1 34155 -1 34156 -1 34157 -1 34158 -1 34159 -1 34160 -1 34161 -1 34162 -1 34163 -1 34164 -1 34165 -1 34166 -1 34167 -1 34168 -1 34169 -1 34170 -1 34171 -1 34172 -1 34173 -1 34174 -1 34175 -1 34176 -1 34177 -1 34178 -1 34179 -1 34180 -1 34181 -1 34182 -1 34183 -1 34184 -1 34185 -1 34186 -1 34187 -1 34188 -1 34189 -1 34190 -1 34191 -1 34192 -1 34193 -1 34194 -1 34195 -1 34196 -1 34197 -1 34198 -1 34199 -1 34200 -1 34201 -1 34202 -1 34203 -1 34204 -1 34205 -1 34206 -1 34207 -1 34208 -1 34209 -1 34210 -1 34211 -1 34212 -1 34213 -1 34214 -1 34215 -1 34216 -1 34217 -1 34218 -1 34219 -1 34220 -1 34221 -1 34222 -1 34223 -1 34224 -1 34225 -1 34226 -1 34227 -1 34228 -1 34229 -1 34230 -1 34231 -1 34232 -1 34233 -1 34234 -1 34235 -1 34236 -1 34237 -1 34238 -1 34239 -1 34240 -1 34241 -1 34242 -1 34243 -1 34244 -1 34245 -1 34246 -1 34247 -1 34248 -1 34249 -1 34250 -1 34251 -1 34252 -1 34253 -1 34254 -1 34255 -1 34256 -1 34257 -1 34258 -1 34259 -1 34260 -1 34261 -1 34262 -1 34263 -1 34264 -1 34265 -1 34266 -1 34267 -1 34268 -1 34269 -1 34270 -1 34271 -1 34272 -1 34273 -1 34274 -1 34275 -1 34276 -1 34277 -1 34278 -1 34279 -1 34280 -1 34281 -1 34282 -1 34283 -1 34284 -1 34285 -1 34286 -1 34287 -1 34288 -1 34289 -1 34290 -1 34291 -1 34292 -1 34293 -1 34294 -1 34295 -1 34296 -1 34297 -1 34298 -1 34299 -1 34300 -1 34301 -1 34302 -1 34303 -1 34304 -1 34305 -1 34306 -1 34307 -1 34308 -1 34309 -1 34310 -1 34311 -1 34312 -1 34313 -1 34314 -1 34315 -1 34316 -1 34317 -1 34318 -1 34319 -1 34320 -1 34321 -1 34322 -1 34323 -1 34324 -1 34325 -1 34326 -1 34327 -1 34328 -1 34329 -1 34330 -1 34331 -1 34332 -1 34333 -1 34334 -1 34335 -1 34336 -1 34337 -1 34338 -1 34339 -1 34340 -1 34341 -1 34342 -1 34343 -1 34344 -1 34345 -1 34346 -1 34347 -1 34348 -1 34349 -1 34350 -1 34351 -1 34352 -1 34353 -1 34354 -1 34355 -1 34356 -1 34357 -1 34358 -1 34359 -1 34360 -1 34361 -1 34362 -1 34363 -1 34364 -1 34365 -1 34366 -1 34367 -1 34368 -1 34369 -1 34370 -1 34371 -1 34372 -1 34373 -1 34374 -1 34375 -1 34376 -1 34377 -1 34378 -1 34379 -1 34380 -1 34381 -1 34382 -1 34383 -1 34384 -1 34385 -1 34386 -1 34387 -1 34388 -1 34389 -1 34390 -1 34391 -1 34392 -1 34393 -1 34394 -1 34395 -1 34396 -1 34397 -1 34398 -1 34399 -1 34400 -1 34401 -1 34402 -1 34403 -1 34404 -1 34405 -1 34406 -1 34407 -1 34408 -1 34409 -1 34410 -1 34411 -1 34412 -1 34413 -1 34414 -1 34415 -1 34416 -1 34417 -1 34418 -1 34419 -1 34420 -1 34421 -1 34422 -1 34423 -1 34424 -1 34425 -1 34426 -1 34427 -1 34428 -1 34429 -1 34430 -1 34431 -1 34432 -1 34433 -1 34434 -1 34435 -1 34436 -1 34437 -1 34438 -1 34439 -1 34440 -1 34441 -1 34442 -1 34443 -1 34444 -1 34445 -1 34446 -1 34447 -1 34448 -1 34449 -1 34450 -1 34451 -1 34452 -1 34453 -1 34454 -1 34455 -1 34456 -1 34457 -1 34458 -1 34459 -1 34460 -1 34461 -1 34462 -1 34463 -1 34464 -1 34465 -1 34466 -1 34467 -1 34468 -1 34469 -1 34470 -1 34471 -1 34472 -1 34473 -1 34474 -1 34475 -1 34476 -1 34477 -1 34478 -1 34479 -1 34480 -1 34481 -1 34482 -1 34483 -1 34484 -1 34485 -1 34486 -1 34487 -1 34488 -1 34489 -1 34490 -1 34491 -1 34492 -1 34493 -1 34494 -1 34495 -1 34496 -1 34497 -1 34498 -1 34499 -1 34500 -1 34501 -1 34502 -1 34503 -1 34504 -1 34505 -1 34506 -1 34507 -1 34508 -1 34509 -1 34510 -1 34511 -1 34512 -1 34513 -1 34514 -1 34515 -1 34516 -1 34517 -1 34518 -1 34519 -1 34520 -1 34521 -1 34522 -1 34523 -1 34524 -1 34525 -1 34526 -1 34527 -1 34528 -1 34529 -1 34530 -1 34531 -1 34532 -1 34533 -1 34534 -1 34535 -1 34536 -1 34537 -1 34538 -1 34539 -1 34540 -1 34541 -1 34542 -1 34543 -1 34544 -1 34545 -1 34546 -1 34547 -1 34548 -1 34549 -1 34550 -1 34551 -1 34552 -1 34553 -1 34554 -1 34555 -1 34556 -1 34557 -1 34558 -1 34559 -1 34560 -1 34561 -1 34562 -1 34563 -1 34564 -1 34565 -1 34566 -1 34567 -1 34568 -1 34569 -1 34570 -1 34571 -1 34572 -1 34573 -1 34574 -1 34575 -1 34576 -1 34577 -1 34578 -1 34579 -1 34580 -1 34581 -1 34582 -1 34583 -1 34584 -1 34585 -1 34586 -1 34587 -1 34588 -1 34589 -1 34590 -1 34591 -1 34592 -1 34593 -1 34594 -1 34595 -1 34596 -1 34597 -1 34598 -1 34599 -1 34600 -1 34601 -1 34602 -1 34603 -1 34604 -1 34605 -1 34606 -1 34607 -1 34608 -1 34609 -1 34610 -1 34611 -1 34612 -1 34613 -1 34614 -1 34615 -1 34616 -1 34617 -1 34618 -1 34619 -1 34620 -1 34621 -1 34622 -1 34623 -1 34624 -1 34625 -1 34626 -1 34627 -1 34628 -1 34629 -1 34630 -1 34631 -1 34632 -1 34633 -1 34634 -1 34635 -1 34636 -1 34637 -1 34638 -1 34639 -1 34640 -1 34641 -1 34642 -1 34643 -1 34644 -1 34645 -1 34646 -1 34647 -1 34648 -1 34649 -1 34650 -1 34651 -1 34652 -1 34653 -1 34654 -1 34655 -1 34656 -1 34657 -1 34658 -1 34659 -1 34660 -1 34661 -1 34662 -1 34663 -1 34664 -1 34665 -1 34666 -1 34667 -1 34668 -1 34669 -1 34670 -1 34671 -1 34672 -1 34673 -1 34674 -1 34675 -1 34676 -1 34677 -1 34678 -1 34679 -1 34680 -1 34681 -1 34682 -1 34683 -1 34684 -1 34685 -1 34686 -1 34687 -1 34688 -1 34689 -1 34690 -1 34691 -1 34692 -1 34693 -1 34694 -1 34695 -1 34696 -1 34697 -1 34698 -1 34699 -1 34700 -1 34701 -1 34702 -1 34703 -1 34704 -1 34705 -1 34706 -1 34707 -1 34708 -1 34709 -1 34710 -1 34711 -1 34712 -1 34713 -1 34714 -1 34715 -1 34716 -1 34717 -1 34718 -1 34719 -1 34720 -1 34721 -1 34722 -1 34723 -1 34724 -1 34725 -1 34726 -1 34727 -1 34728 -1 34729 -1 34730 -1 34731 -1 34732 -1 34733 -1 34734 -1 34735 -1 34736 -1 34737 -1 34738 -1 34739 -1 34740 -1 34741 -1 34742 -1 34743 -1 34744 -1 34745 -1 34746 -1 34747 -1 34748 -1 34749 -1 34750 -1 34751 -1 34752 -1 34753 -1 34754 -1 34755 -1 34756 -1 34757 -1 34758 -1 34759 -1 34760 -1 34761 -1 34762 -1 34763 -1 34764 -1 34765 -1 34766 -1 34767 -1 34768 -1 34769 -1 34770 -1 34771 -1 34772 -1 34773 -1 34774 -1 34775 -1 34776 -1 34777 -1 34778 -1 34779 -1 34780 -1 34781 -1 34782 -1 34783 -1 34784 -1 34785 -1 34786 -1 34787 -1 34788 -1 34789 -1 34790 -1 34791 -1 34792 -1 34793 -1 34794 -1 34795 -1 34796 -1 34797 -1 34798 -1 34799 -1 34800 -1 34801 -1 34802 -1 34803 -1 34804 -1 34805 -1 34806 -1 34807 -1 34808 -1 34809 -1 34810 -1 34811 -1 34812 -1 34813 -1 34814 -1 34815 -1 34816 -1 34817 -1 34818 -1 34819 -1 34820 -1 34821 -1 34822 -1 34823 -1 34824 -1 34825 -1 34826 -1 34827 -1 34828 -1 34829 -1 34830 -1 34831 -1 34832 -1 34833 -1 34834 -1 34835 -1 34836 -1 34837 -1 34838 -1 34839 -1 34840 -1 34841 -1 34842 -1 34843 -1 34844 -1 34845 -1 34846 -1 34847 -1 34848 -1 34849 -1 34850 -1 34851 -1 34852 -1 34853 -1 34854 -1 34855 -1 34856 -1 34857 -1 34858 -1 34859 -1 34860 -1 34861 -1 34862 -1 34863 -1 34864 -1 34865 -1 34866 -1 34867 -1 34868 -1 34869 -1 34870 -1 34871 -1 34872 -1 34873 -1 34874 -1 34875 -1 34876 -1 34877 -1 34878 -1 34879 -1 34880 -1 34881 -1 34882 -1 34883 -1 34884 -1 34885 -1 34886 -1 34887 -1 34888 -1 34889 -1 34890 -1 34891 -1 34892 -1 34893 -1 34894 -1 34895 -1 34896 -1 34897 -1 34898 -1 34899 -1 34900 -1 34901 -1 34902 -1 34903 -1 34904 -1 34905 -1 34906 -1 34907 -1 34908 -1 34909 -1 34910 -1 34911 -1 34912 -1 34913 -1 34914 -1 34915 -1 34916 -1 34917 -1 34918 -1 34919 -1 34920 -1 34921 -1 34922 -1 34923 -1 34924 -1 34925 -1 34926 -1 34927 -1 34928 -1 34929 -1 34930 -1 34931 -1 34932 -1 34933 -1 34934 -1 34935 -1 34936 -1 34937 -1 34938 -1 34939 -1 34940 -1 34941 -1 34942 -1 34943 -1 34944 -1 34945 -1 34946 -1 34947 -1 34948 -1 34949 -1 34950 -1 34951 -1 34952 -1 34953 -1 34954 -1 34955 -1 34956 -1 34957 -1 34958 -1 34959 -1 34960 -1 34961 -1 34962 -1 34963 -1 34964 -1 34965 -1 34966 -1 34967 -1 34968 -1 34969 -1 34970 -1 34971 -1 34972 -1 34973 -1 34974 -1 34975 -1 34976 -1 34977 -1 34978 -1 34979 -1 34980 -1 34981 -1 34982 -1 34983 -1 34984 -1 34985 -1 34986 -1 34987 -1 34988 -1 34989 -1 34990 -1 34991 -1 34992 -1 34993 -1 34994 -1 34995 -1 34996 -1 34997 -1 34998 -1 34999 -1 35000 -1 35001 -1 35002 -1 35003 -1 35004 -1 35005 -1 35006 -1 35007 -1 35008 -1 35009 -1 35010 -1 35011 -1 35012 -1 35013 -1 35014 -1 35015 -1 35016 -1 35017 -1 35018 -1 35019 -1 35020 -1 35021 -1 35022 -1 35023 -1 35024 -1 35025 -1 35026 -1 35027 -1 35028 -1 35029 -1 35030 -1 35031 -1 35032 -1 35033 -1 35034 -1 35035 -1 35036 -1 35037 -1 35038 -1 35039 -1 35040 -1 35041 -1 35042 -1 35043 -1 35044 -1 35045 -1 35046 -1 35047 -1 35048 -1 35049 -1 35050 -1 35051 -1 35052 -1 35053 -1 35054 -1 35055 -1 35056 -1 35057 -1 35058 -1 35059 -1 35060 -1 35061 -1 35062 -1 35063 -1 35064 -1 35065 -1 35066 -1 35067 -1 35068 -1 35069 -1 35070 -1 35071 -1 35072 -1 35073 -1 35074 -1 35075 -1 35076 -1 35077 -1 35078 -1 35079 -1 35080 -1 35081 -1 35082 -1 35083 -1 35084 -1 35085 -1 35086 -1 35087 -1 35088 -1 35089 -1 35090 -1 35091 -1 35092 -1 35093 -1 35094 -1 35095 -1 35096 -1 35097 -1 35098 -1 35099 -1 35100 -1 35101 -1 35102 -1 35103 -1 35104 -1 35105 -1 35106 -1 35107 -1 35108 -1 35109 -1 35110 -1 35111 -1 35112 -1 35113 -1 35114 -1 35115 -1 35116 -1 35117 -1 35118 -1 35119 -1 35120 -1 35121 -1 35122 -1 35123 -1 35124 -1 35125 -1 35126 -1 35127 -1 35128 -1 35129 -1 35130 -1 35131 -1 35132 -1 35133 -1 35134 -1 35135 -1 35136 -1 35137 -1 35138 -1 35139 -1 35140 -1 35141 -1 35142 -1 35143 -1 35144 -1 35145 -1 35146 -1 35147 -1 35148 -1 35149 -1 35150 -1 35151 -1 35152 -1 35153 -1 35154 -1 35155 -1 35156 -1 35157 -1 35158 -1 35159 -1 35160 -1 35161 -1 35162 -1 35163 -1 35164 -1 35165 -1 35166 -1 35167 -1 35168 -1 35169 -1 35170 -1 35171 -1 35172 -1 35173 -1 35174 -1 35175 -1 35176 -1 35177 -1 35178 -1 35179 -1 35180 -1 35181 -1 35182 -1 35183 -1 35184 -1 35185 -1 35186 -1 35187 -1 35188 -1 35189 -1 35190 -1 35191 -1 35192 -1 35193 -1 35194 -1 35195 -1 35196 -1 35197 -1 35198 -1 35199 -1 35200 -1 35201 -1 35202 -1 35203 -1 35204 -1 35205 -1 35206 -1 35207 -1 35208 -1 35209 -1 35210 -1 35211 -1 35212 -1 35213 -1 35214 -1 35215 -1 35216 -1 35217 -1 35218 -1 35219 -1 35220 -1 35221 -1 35222 -1 35223 -1 35224 -1 35225 -1 35226 -1 35227 -1 35228 -1 35229 -1 35230 -1 35231 -1 35232 -1 35233 -1 35234 -1 35235 -1 35236 -1 35237 -1 35238 -1 35239 -1 35240 -1 35241 -1 35242 -1 35243 -1 35244 -1 35245 -1 35246 -1 35247 -1 35248 -1 35249 -1 35250 -1 35251 -1 35252 -1 35253 -1 35254 -1 35255 -1 35256 -1 35257 -1 35258 -1 35259 -1 35260 -1 35261 -1 35262 -1 35263 -1 35264 -1 35265 -1 35266 -1 35267 -1 35268 -1 35269 -1 35270 -1 35271 -1 35272 -1 35273 -1 35274 -1 35275 -1 35276 -1 35277 -1 35278 -1 35279 -1 35280 -1 35281 -1 35282 -1 35283 -1 35284 -1 35285 -1 35286 -1 35287 -1 35288 -1 35289 -1 35290 -1 35291 -1 35292 -1 35293 -1 35294 -1 35295 -1 35296 -1 35297 -1 35298 -1 35299 -1 35300 -1 35301 -1 35302 -1 35303 -1 35304 -1 35305 -1 35306 -1 35307 -1 35308 -1 35309 -1 35310 -1 35311 -1 35312 -1 35313 -1 35314 -1 35315 -1 35316 -1 35317 -1 35318 -1 35319 -1 35320 -1 35321 -1 35322 -1 35323 -1 35324 -1 35325 -1 35326 -1 35327 -1 35328 -1 35329 -1 35330 -1 35331 -1 35332 -1 35333 -1 35334 -1 35335 -1 35336 -1 35337 -1 35338 -1 35339 -1 35340 -1 35341 -1 35342 -1 35343 -1 35344 -1 35345 -1 35346 -1 35347 -1 35348 -1 35349 -1 35350 -1 35351 -1 35352 -1 35353 -1 35354 -1 35355 -1 35356 -1 35357 -1 35358 -1 35359 -1 35360 -1 35361 -1 35362 -1 35363 -1 35364 -1 35365 -1 35366 -1 35367 -1 35368 -1 35369 -1 35370 -1 35371 -1 35372 -1 35373 -1 35374 -1 35375 -1 35376 -1 35377 -1 35378 -1 35379 -1 35380 -1 35381 -1 35382 -1 35383 -1 35384 -1 35385 -1 35386 -1 35387 -1 35388 -1 35389 -1 35390 -1 35391 -1 35392 -1 35393 -1 35394 -1 35395 -1 35396 -1 35397 -1 35398 -1 35399 -1 35400 -1 35401 -1 35402 -1 35403 -1 35404 -1 35405 -1 35406 -1 35407 -1 35408 -1 35409 -1 35410 -1 35411 -1 35412 -1 35413 -1 35414 -1 35415 -1 35416 -1 35417 -1 35418 -1 35419 -1 35420 -1 35421 -1 35422 -1 35423 -1 35424 -1 35425 -1 35426 -1 35427 -1 35428 -1 35429 -1 35430 -1 35431 -1 35432 -1 35433 -1 35434 -1 35435 -1 35436 -1 35437 -1 35438 -1 35439 -1 35440 -1 35441 -1 35442 -1 35443 -1 35444 -1 35445 -1 35446 -1 35447 -1 35448 -1 35449 -1 35450 -1 35451 -1 35452 -1 35453 -1 35454 -1 35455 -1 35456 -1 35457 -1 35458 -1 35459 -1 35460 -1 35461 -1 35462 -1 35463 -1 35464 -1 35465 -1 35466 -1 35467 -1 35468 -1 35469 -1 35470 -1 35471 -1 35472 -1 35473 -1 35474 -1 35475 -1 35476 -1 35477 -1 35478 -1 35479 -1 35480 -1 35481 -1 35482 -1 35483 -1 35484 -1 35485 -1 35486 -1 35487 -1 35488 -1 35489 -1 35490 -1 35491 -1 35492 -1 35493 -1 35494 -1 35495 -1 35496 -1 35497 -1 35498 -1 35499 -1 35500 -1 35501 -1 35502 -1 35503 -1 35504 -1 35505 -1 35506 -1 35507 -1 35508 -1 35509 -1 35510 -1 35511 -1 35512 -1 35513 -1 35514 -1 35515 -1 35516 -1 35517 -1 35518 -1 35519 -1 35520 -1 35521 -1 35522 -1 35523 -1 35524 -1 35525 -1 35526 -1 35527 -1 35528 -1 35529 -1 35530 -1 35531 -1 35532 -1 35533 -1 35534 -1 35535 -1 35536 -1 35537 -1 35538 -1 35539 -1 35540 -1 35541 -1 35542 -1 35543 -1 35544 -1 35545 -1 35546 -1 35547 -1 35548 -1 35549 -1 35550 -1 35551 -1 35552 -1 35553 -1 35554 -1 35555 -1 35556 -1 35557 -1 35558 -1 35559 -1 35560 -1 35561 -1 35562 -1 35563 -1 35564 -1 35565 -1 35566 -1 35567 -1 35568 -1 35569 -1 35570 -1 35571 -1 35572 -1 35573 -1 35574 -1 35575 -1 35576 -1 35577 -1 35578 -1 35579 -1 35580 -1 35581 -1 35582 -1 35583 -1 35584 -1 35585 -1 35586 -1 35587 -1 35588 -1 35589 -1 35590 -1 35591 -1 35592 -1 35593 -1 35594 -1 35595 -1 35596 -1 35597 -1 35598 -1 35599 -1 35600 -1 35601 -1 35602 -1 35603 -1 35604 -1 35605 -1 35606 -1 35607 -1 35608 -1 35609 -1 35610 -1 35611 -1 35612 -1 35613 -1 35614 -1 35615 -1 35616 -1 35617 -1 35618 -1 35619 -1 35620 -1 35621 -1 35622 -1 35623 -1 35624 -1 35625 -1 35626 -1 35627 -1 35628 -1 35629 -1 35630 -1 35631 -1 35632 -1 35633 -1 35634 -1 35635 -1 35636 -1 35637 -1 35638 -1 35639 -1 35640 -1 35641 -1 35642 -1 35643 -1 35644 -1 35645 -1 35646 -1 35647 -1 35648 -1 35649 -1 35650 -1 35651 -1 35652 -1 35653 -1 35654 -1 35655 -1 35656 -1 35657 -1 35658 -1 35659 -1 35660 -1 35661 -1 35662 -1 35663 -1 35664 -1 35665 -1 35666 -1 35667 -1 35668 -1 35669 -1 35670 -1 35671 -1 35672 -1 35673 -1 35674 -1 35675 -1 35676 -1 35677 -1 35678 -1 35679 -1 35680 -1 35681 -1 35682 -1 35683 -1 35684 -1 35685 -1 35686 -1 35687 -1 35688 -1 35689 -1 35690 -1 35691 -1 35692 -1 35693 -1 35694 -1 35695 -1 35696 -1 35697 -1 35698 -1 35699 -1 35700 -1 35701 -1 35702 -1 35703 -1 35704 -1 35705 -1 35706 -1 35707 -1 35708 -1 35709 -1 35710 -1 35711 -1 35712 -1 35713 -1 35714 -1 35715 -1 35716 -1 35717 -1 35718 -1 35719 -1 35720 -1 35721 -1 35722 -1 35723 -1 35724 -1 35725 -1 35726 -1 35727 -1 35728 -1 35729 -1 35730 -1 35731 -1 35732 -1 35733 -1 35734 -1 35735 -1 35736 -1 35737 -1 35738 -1 35739 -1 35740 -1 35741 -1 35742 -1 35743 -1 35744 -1 35745 -1 35746 -1 35747 -1 35748 -1 35749 -1 35750 -1 35751 -1 35752 -1 35753 -1 35754 -1 35755 -1 35756 -1 35757 -1 35758 -1 35759 -1 35760 -1 35761 -1 35762 -1 35763 -1 35764 -1 35765 -1 35766 -1 35767 -1 35768 -1 35769 -1 35770 -1 35771 -1 35772 -1 35773 -1 35774 -1 35775 -1 35776 -1 35777 -1 35778 -1 35779 -1 35780 -1 35781 -1 35782 -1 35783 -1 35784 -1 35785 -1 35786 -1 35787 -1 35788 -1 35789 -1 35790 -1 35791 -1 35792 -1 35793 -1 35794 -1 35795 -1 35796 -1 35797 -1 35798 -1 35799 -1 35800 -1 35801 -1 35802 -1 35803 -1 35804 -1 35805 -1 35806 -1 35807 -1 35808 -1 35809 -1 35810 -1 35811 -1 35812 -1 35813 -1 35814 -1 35815 -1 35816 -1 35817 -1 35818 -1 35819 -1 35820 -1 35821 -1 35822 -1 35823 -1 35824 -1 35825 -1 35826 -1 35827 -1 35828 -1 35829 -1 35830 -1 35831 -1 35832 -1 35833 -1 35834 -1 35835 -1 35836 -1 35837 -1 35838 -1 35839 -1 35840 -1 35841 -1 35842 -1 35843 -1 35844 -1 35845 -1 35846 -1 35847 -1 35848 -1 35849 -1 35850 -1 35851 -1 35852 -1 35853 -1 35854 -1 35855 -1 35856 -1 35857 -1 35858 -1 35859 -1 35860 -1 35861 -1 35862 -1 35863 -1 35864 -1 35865 -1 35866 -1 35867 -1 35868 -1 35869 -1 35870 -1 35871 -1 35872 -1 35873 -1 35874 -1 35875 -1 35876 -1 35877 -1 35878 -1 35879 -1 35880 -1 35881 -1 35882 -1 35883 -1 35884 -1 35885 -1 35886 -1 35887 -1 35888 -1 35889 -1 35890 -1 35891 -1 35892 -1 35893 -1 35894 -1 35895 -1 35896 -1 35897 -1 35898 -1 35899 -1 35900 -1 35901 -1 35902 -1 35903 -1 35904 -1 35905 -1 35906 -1 35907 -1 35908 -1 35909 -1 35910 -1 35911 -1 35912 -1 35913 -1 35914 -1 35915 -1 35916 -1 35917 -1 35918 -1 35919 -1 35920 -1 35921 -1 35922 -1 35923 -1 35924 -1 35925 -1 35926 -1 35927 -1 35928 -1 35929 -1 35930 -1 35931 -1 35932 -1 35933 -1 35934 -1 35935 -1 35936 -1 35937 -1 35938 -1 35939 -1 35940 -1 35941 -1 35942 -1 35943 -1 35944 -1 35945 -1 35946 -1 35947 -1 35948 -1 35949 -1 35950 -1 35951 -1 35952 -1 35953 -1 35954 -1 35955 -1 35956 -1 35957 -1 35958 -1 35959 -1 35960 -1 35961 -1 35962 -1 35963 -1 35964 -1 35965 -1 35966 -1 35967 -1 35968 -1 35969 -1 35970 -1 35971 -1 35972 -1 35973 -1 35974 -1 35975 -1 35976 -1 35977 -1 35978 -1 35979 -1 35980 -1 35981 -1 35982 -1 35983 -1 35984 -1 35985 -1 35986 -1 35987 -1 35988 -1 35989 -1 35990 -1 35991 -1 35992 -1 35993 -1 35994 -1 35995 -1 35996 -1 35997 -1 35998 -1 35999 -1 36000 -1 36001 -1 36002 -1 36003 -1 36004 -1 36005 -1 36006 -1 36007 -1 36008 -1 36009 -1 36010 -1 36011 -1 36012 -1 36013 -1 36014 -1 36015 -1 36016 -1 36017 -1 36018 -1 36019 -1 36020 -1 36021 -1 36022 -1 36023 -1 36024 -1 36025 -1 36026 -1 36027 -1 36028 -1 36029 -1 36030 -1 36031 -1 36032 -1 36033 -1 36034 -1 36035 -1 36036 -1 36037 -1 36038 -1 36039 -1 36040 -1 36041 -1 36042 -1 36043 -1 36044 -1 36045 -1 36046 -1 36047 -1 36048 -1 36049 -1 36050 -1 36051 -1 36052 -1 36053 -1 36054 -1 36055 -1 36056 -1 36057 -1 36058 -1 36059 -1 36060 -1 36061 -1 36062 -1 36063 -1 36064 -1 36065 -1 36066 -1 36067 -1 36068 -1 36069 -1 36070 -1 36071 -1 36072 -1 36073 -1 36074 -1 36075 -1 36076 -1 36077 -1 36078 -1 36079 -1 36080 -1 36081 -1 36082 -1 36083 -1 36084 -1 36085 -1 36086 -1 36087 -1 36088 -1 36089 -1 36090 -1 36091 -1 36092 -1 36093 -1 36094 -1 36095 -1 36096 -1 36097 -1 36098 -1 36099 -1 36100 -1 36101 -1 36102 -1 36103 -1 36104 -1 36105 -1 36106 -1 36107 -1 36108 -1 36109 -1 36110 -1 36111 -1 36112 -1 36113 -1 36114 -1 36115 -1 36116 -1 36117 -1 36118 -1 36119 -1 36120 -1 36121 -1 36122 -1 36123 -1 36124 -1 36125 -1 36126 -1 36127 -1 36128 -1 36129 -1 36130 -1 36131 -1 36132 -1 36133 -1 36134 -1 36135 -1 36136 -1 36137 -1 36138 -1 36139 -1 36140 -1 36141 -1 36142 -1 36143 -1 36144 -1 36145 -1 36146 -1 36147 -1 36148 -1 36149 -1 36150 -1 36151 -1 36152 -1 36153 -1 36154 -1 36155 -1 36156 -1 36157 -1 36158 -1 36159 -1 36160 -1 36161 -1 36162 -1 36163 -1 36164 -1 36165 -1 36166 -1 36167 -1 36168 -1 36169 -1 36170 -1 36171 -1 36172 -1 36173 -1 36174 -1 36175 -1 36176 -1 36177 -1 36178 -1 36179 -1 36180 -1 36181 -1 36182 -1 36183 -1 36184 -1 36185 -1 36186 -1 36187 -1 36188 -1 36189 -1 36190 -1 36191 -1 36192 -1 36193 -1 36194 -1 36195 -1 36196 -1 36197 -1 36198 -1 36199 -1 36200 -1 36201 -1 36202 -1 36203 -1 36204 -1 36205 -1 36206 -1 36207 -1 36208 -1 36209 -1 36210 -1 36211 -1 36212 -1 36213 -1 36214 -1 36215 -1 36216 -1 36217 -1 36218 -1 36219 -1 36220 -1 36221 -1 36222 -1 36223 -1 36224 -1 36225 -1 36226 -1 36227 -1 36228 -1 36229 -1 36230 -1 36231 -1 36232 -1 36233 -1 36234 -1 36235 -1 36236 -1 36237 -1 36238 -1 36239 -1 36240 -1 36241 -1 36242 -1 36243 -1 36244 -1 36245 -1 36246 -1 36247 -1 36248 -1 36249 -1 36250 -1 36251 -1 36252 -1 36253 -1 36254 -1 36255 -1 36256 -1 36257 -1 36258 -1 36259 -1 36260 -1 36261 -1 36262 -1 36263 -1 36264 -1 36265 -1 36266 -1 36267 -1 36268 -1 36269 -1 36270 -1 36271 -1 36272 -1 36273 -1 36274 -1 36275 -1 36276 -1 36277 -1 36278 -1 36279 -1 36280 -1 36281 -1 36282 -1 36283 -1 36284 -1 36285 -1 36286 -1 36287 -1 36288 -1 36289 -1 36290 -1 36291 -1 36292 -1 36293 -1 36294 -1 36295 -1 36296 -1 36297 -1 36298 -1 36299 -1 36300 -1 36301 -1 36302 -1 36303 -1 36304 -1 36305 -1 36306 -1 36307 -1 36308 -1 36309 -1 36310 -1 36311 -1 36312 -1 36313 -1 36314 -1 36315 -1 36316 -1 36317 -1 36318 -1 36319 -1 36320 -1 36321 -1 36322 -1 36323 -1 36324 -1 36325 -1 36326 -1 36327 -1 36328 -1 36329 -1 36330 -1 36331 -1 36332 -1 36333 -1 36334 -1 36335 -1 36336 -1 36337 -1 36338 -1 36339 -1 36340 -1 36341 -1 36342 -1 36343 -1 36344 -1 36345 -1 36346 -1 36347 -1 36348 -1 36349 -1 36350 -1 36351 -1 36352 -1 36353 -1 36354 -1 36355 -1 36356 -1 36357 -1 36358 -1 36359 -1 36360 -1 36361 -1 36362 -1 36363 -1 36364 -1 36365 -1 36366 -1 36367 -1 36368 -1 36369 -1 36370 -1 36371 -1 36372 -1 36373 -1 36374 -1 36375 -1 36376 -1 36377 -1 36378 -1 36379 -1 36380 -1 36381 -1 36382 -1 36383 -1 36384 -1 36385 -1 36386 -1 36387 -1 36388 -1 36389 -1 36390 -1 36391 -1 36392 -1 36393 -1 36394 -1 36395 -1 36396 -1 36397 -1 36398 -1 36399 -1 36400 -1 36401 -1 36402 -1 36403 -1 36404 -1 36405 -1 36406 -1 36407 -1 36408 -1 36409 -1 36410 -1 36411 -1 36412 -1 36413 -1 36414 -1 36415 -1 36416 -1 36417 -1 36418 -1 36419 -1 36420 -1 36421 -1 36422 -1 36423 -1 36424 -1 36425 -1 36426 -1 36427 -1 36428 -1 36429 -1 36430 -1 36431 -1 36432 -1 36433 -1 36434 -1 36435 -1 36436 -1 36437 -1 36438 -1 36439 -1 36440 -1 36441 -1 36442 -1 36443 -1 36444 -1 36445 -1 36446 -1 36447 -1 36448 -1 36449 -1 36450 -1 36451 -1 36452 -1 36453 -1 36454 -1 36455 -1 36456 -1 36457 -1 36458 -1 36459 -1 36460 -1 36461 -1 36462 -1 36463 -1 36464 -1 36465 -1 36466 -1 36467 -1 36468 -1 36469 -1 36470 -1 36471 -1 36472 -1 36473 -1 36474 -1 36475 -1 36476 -1 36477 -1 36478 -1 36479 -1 36480 -1 36481 -1 36482 -1 36483 -1 36484 -1 36485 -1 36486 -1 36487 -1 36488 -1 36489 -1 36490 -1 36491 -1 36492 -1 36493 -1 36494 -1 36495 -1 36496 -1 36497 -1 36498 -1 36499 -1 36500 -1 36501 -1 36502 -1 36503 -1 36504 -1 36505 -1 36506 -1 36507 -1 36508 -1 36509 -1 36510 -1 36511 -1 36512 -1 36513 -1 36514 -1 36515 -1 36516 -1 36517 -1 36518 -1 36519 -1 36520 -1 36521 -1 36522 -1 36523 -1 36524 -1 36525 -1 36526 -1 36527 -1 36528 -1 36529 -1 36530 -1 36531 -1 36532 -1 36533 -1 36534 -1 36535 -1 36536 -1 36537 -1 36538 -1 36539 -1 36540 -1 36541 -1 36542 -1 36543 -1 36544 -1 36545 -1 36546 -1 36547 -1 36548 -1 36549 -1 36550 -1 36551 -1 36552 -1 36553 -1 36554 -1 36555 -1 36556 -1 36557 -1 36558 -1 36559 -1 36560 -1 36561 -1 36562 -1 36563 -1 36564 -1 36565 -1 36566 -1 36567 -1 36568 -1 36569 -1 36570 -1 36571 -1 36572 -1 36573 -1 36574 -1 36575 -1 36576 -1 36577 -1 36578 -1 36579 -1 36580 -1 36581 -1 36582 -1 36583 -1 36584 -1 36585 -1 36586 -1 36587 -1 36588 -1 36589 -1 36590 -1 36591 -1 36592 -1 36593 -1 36594 -1 36595 -1 36596 -1 36597 -1 36598 -1 36599 -1 36600 -1 36601 -1 36602 -1 36603 -1 36604 -1 36605 -1 36606 -1 36607 -1 36608 -1 36609 -1 36610 -1 36611 -1 36612 -1 36613 -1 36614 -1 36615 -1 36616 -1 36617 -1 36618 -1 36619 -1 36620 -1 36621 -1 36622 -1 36623 -1 36624 -1 36625 -1 36626 -1 36627 -1 36628 -1 36629 -1 36630 -1 36631 -1 36632 -1 36633 -1 36634 -1 36635 -1 36636 -1 36637 -1 36638 -1 36639 -1 36640 -1 36641 -1 36642 -1 36643 -1 36644 -1 36645 -1 36646 -1 36647 -1 36648 -1 36649 -1 36650 -1 36651 -1 36652 -1 36653 -1 36654 -1 36655 -1 36656 -1 36657 -1 36658 -1 36659 -1 36660 -1 36661 -1 36662 -1 36663 -1 36664 -1 36665 -1 36666 -1 36667 -1 36668 -1 36669 -POINT_DATA 36670 diff --git a/thirdparty/libpointmatcher/examples/icp_tutorial/icp_tutorial_cfg.yaml b/thirdparty/libpointmatcher/examples/icp_tutorial/icp_tutorial_cfg.yaml deleted file mode 100644 index d098891..0000000 --- a/thirdparty/libpointmatcher/examples/icp_tutorial/icp_tutorial_cfg.yaml +++ /dev/null @@ -1,36 +0,0 @@ -readingDataPointsFilters: - - RandomSamplingDataPointsFilter: - prob: 0.5 - -referenceDataPointsFilters: - - SamplingSurfaceNormalDataPointsFilter: - knn: 10 - -matcher: - KDTreeMatcher: - knn: 1 - -outlierFilters: - - TrimmedDistOutlierFilter: - ratio: 0.95 - -errorMinimizer: - PointToPlaneErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker: - maxIterationCount: 40 - - DifferentialTransformationChecker: - minDiffRotErr: 0.001 - minDiffTransErr: 0.01 - smoothLength: 4 - -inspector: - VTKFileInspector: - baseFileName : vissteps - dumpDataLinks : 1 - dumpReading : 1 - dumpReference : 1 - -logger: - FileLogger diff --git a/thirdparty/libpointmatcher/examples/icp_tutorial/icp_tutorial_empty.yaml b/thirdparty/libpointmatcher/examples/icp_tutorial/icp_tutorial_empty.yaml deleted file mode 100644 index 98e61a6..0000000 --- a/thirdparty/libpointmatcher/examples/icp_tutorial/icp_tutorial_empty.yaml +++ /dev/null @@ -1,23 +0,0 @@ -readingDataPointsFilters: - - IdentityDataPointsFilter - -referenceDataPointsFilters: - - IdentityDataPointsFilter - -matcher: - KDTreeMatcher - -outlierFilters: - - NullOutlierFilter - -errorMinimizer: - IdentityErrorMinimizer - -transformationCheckers: - - CounterTransformationChecker - -inspector: - NullInspector - -logger: - FileLogger diff --git a/thirdparty/libpointmatcher/examples/list_modules.cpp b/thirdparty/libpointmatcher/examples/list_modules.cpp deleted file mode 100644 index d6c19b9..0000000 --- a/thirdparty/libpointmatcher/examples/list_modules.cpp +++ /dev/null @@ -1,245 +0,0 @@ -// kate: replace-tabs off; indent-width 4; indent-mode normal -// vim: ts=4:sw=4:noexpandtab -/* - -Copyright (c) 2010--2012, -François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland -You can contact the authors at and - - -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 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 ETH-ASL 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. - -*/ - -#include "pointmatcher/PointMatcher.h" -#include "pointmatcher/Bibliography.h" - -using namespace std; -using namespace PointMatcherSupport; - -typedef PointMatcherSupport::Parametrizable::ParametersDoc ParametersDoc; -typedef PointMatcher PM; - -void printBibliographyHeader(const CurrentBibliography::Mode mode) -{ - switch (mode) - { - case CurrentBibliography::NORMAL: - cout << "* Bibliography *" << endl << endl; - break; - - case CurrentBibliography::ROSWIKI: - cout << "=== Bibliography ===" << endl << endl; - break; - - default: - break; - } -} - -void dumpWiki(const ParametersDoc& paramsDoc) -{ - cout << endl; - if (!paramsDoc.empty()) - for (BOOST_AUTO(it, paramsDoc.begin()); it != paramsDoc.end(); ++it) - { - cout << "`" << it->name << "` (default: `" << it->defaultValue << "`"; - if (!it->minValue.empty()) - cout << ", min: `" << it->minValue << "`"; - if (!it->maxValue.empty()) - cout << ", max: `" << it->maxValue << "`"; - cout << ")" << endl; - cout << endl; - cout << " . " << it->doc << endl; - cout << endl; - } - else - cout << " . no parameters" << endl; -} - -template -void dumpRegistrar(const PM& pm, const R& registrar, const std::string& name, CurrentBibliography& bib) -{ - if (bib.mode == CurrentBibliography::ROSWIKI) - cout << "=== " << name << " ===\n" << endl; - else - cout << "* " << name << " *\n" << endl; - for (BOOST_AUTO(it, registrar.begin()); it != registrar.end(); ++it) - { - if (bib.mode == CurrentBibliography::ROSWIKI) - cout << "==== " << it->first << " ====\n" << endl; - else - cout << it->first << endl; - - cout << getAndReplaceBibEntries(it->second->description(), bib) << endl; - if (bib.mode == CurrentBibliography::ROSWIKI) - dumpWiki(it->second->availableParameters()); - else - cout << it->second->availableParameters(); - cout << endl; - } - cout << endl; -} - - -#define DUMP_REGISTRAR_CONTENT(pm, name, bib) \ - dumpRegistrar(pm, pm.REG(name), # name, bib); - -void listModulesFull(const CurrentBibliography::Mode mode) -{ - CurrentBibliography bib(mode); - - DUMP_REGISTRAR_CONTENT(PM::get(), Transformation, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), DataPointsFilter, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), Matcher, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), OutlierFilter, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), ErrorMinimizer, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), TransformationChecker, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), Inspector, bib) - DUMP_REGISTRAR_CONTENT(PM::get(), Logger, bib) - - printBibliographyHeader(mode); - bib.dump(cout); -} - - -typedef vector ModuleNameList; - -template -void dumpRegistrarSummary(const PM& pm, const R& registrar, const std::string& name, ModuleNameList& nameList) -{ - nameList.push_back(name); - for (BOOST_AUTO(it, registrar.begin()); it != registrar.end(); ++it) - { - // TODO: remove title - nameList.push_back(it->first); - } -} - -#define DUMP_REGISTRAR_SUMMARY(pm, name, nameList) \ - dumpRegistrarSummary(pm, pm.REG(name), # name, nameList); - -void listModulesSummary(const CurrentBibliography::Mode mode) -{ - typedef vector ModulesNames; - - ModulesNames modulesNames; - modulesNames.resize(7); - - DUMP_REGISTRAR_SUMMARY(PM::get(), DataPointsFilter, modulesNames[0]) - DUMP_REGISTRAR_SUMMARY(PM::get(), Matcher, modulesNames[1]) - DUMP_REGISTRAR_SUMMARY(PM::get(), OutlierFilter, modulesNames[2]) - DUMP_REGISTRAR_SUMMARY(PM::get(), ErrorMinimizer, modulesNames[3]) - DUMP_REGISTRAR_SUMMARY(PM::get(), TransformationChecker, modulesNames[4]) - DUMP_REGISTRAR_SUMMARY(PM::get(), Inspector, modulesNames[5]) - DUMP_REGISTRAR_SUMMARY(PM::get(), Logger, modulesNames[6]) - - // strip names and count - ModulesNames strippedModulesNames; - strippedModulesNames.resize(modulesNames.size()); - unsigned maxCount(0); - for (size_t i(0); i < modulesNames.size(); ++i) - { - unsigned count(0); - for (BOOST_AUTO(jt, modulesNames[i].begin()); jt != modulesNames[i].end(); ++jt) - { - const string& name(*jt); - if (jt == modulesNames[i].begin()) - { - strippedModulesNames[i].push_back(name); - count++; - } - else - { - string strippedName(name.substr(0, name.length() - (modulesNames[i][0].length()))); - if ((strippedName != "Null") && (strippedName != "Identity")) - { - strippedModulesNames[i].push_back(strippedName); - count++; - } - } - } - maxCount = max(count, maxCount); - } - - // header - cout << "\\begin{tabularx}{\\textwidth}{"; - for (size_t i(0); isize()) - { - const string& name((*it)[row]); - cout << name; - } - if (it+1 != strippedModulesNames.end()) - cout << " & "; - } - if (row == 0) - cout << "\\\\\n\\midrule\n"; - else - cout << "\\\\\n"; - } - // footer - cout << "\\bottomrule\n\\end{tabularx}\n"; -} - -int main(int argc, char *argv[]) -{ - // choose bibliography mode - CurrentBibliography::Mode mode(CurrentBibliography::NORMAL); - if (argc == 2) - { - const string cmd(argv[1]); - if (cmd == "--latexsummary") - { - mode = CurrentBibliography::BIBTEX; - listModulesSummary(mode); - } - else if (cmd == "--roswiki") - { - mode = CurrentBibliography::ROSWIKI; - listModulesFull(mode); - } - else if (cmd == "--bibtex") - { - mode = CurrentBibliography::BIBTEX; - listModulesFull(mode); - } - else - { - cerr << "Invalid command " << cmd << endl; - return 1; - } - } - else - listModulesFull(mode); - - return 0; -} \ No newline at end of file diff --git a/thirdparty/libpointmatcher/libpointmatcherConfig.cmake.in b/thirdparty/libpointmatcher/libpointmatcherConfig.cmake.in index 7fdb49a..3d7eb14 100644 --- a/thirdparty/libpointmatcher/libpointmatcherConfig.cmake.in +++ b/thirdparty/libpointmatcher/libpointmatcherConfig.cmake.in @@ -3,17 +3,27 @@ # libpointmatcher_INCLUDE_DIRS - include directories for pointmatcher # libpointmatcher_LIBRARIES - libraries to link against +include(CMakeFindDependencyMacro) +find_dependency(libnabo REQUIRED) +find_package(Boost COMPONENTS thread filesystem system program_options date_time REQUIRED) +if (Boost_MINOR_VERSION GREATER 47) + find_package(Boost COMPONENTS thread filesystem system program_options date_time chrono REQUIRED) +endif () +include(${CMAKE_CURRENT_LIST_DIR}/libpointmatcher-config.cmake) +include(${CMAKE_CURRENT_LIST_DIR}/yaml-cpp-pm-targets.cmake) + # Compute paths get_filename_component(POINTMATCHER_CMAKE_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH) set(libpointmatcher_INCLUDE_DIRS "@CONF_INCLUDE_DIRS@") set(LIBPOINTMATCHER_INCLUDE_DIRS "@CONF_INCLUDE_DIRS@") set(pointmatcher_INCLUDE_DIRS "@CONF_INCLUDE_DIRS@") set(POINTMATCHER_INCLUDE_DIRS "@CONF_INCLUDE_DIRS@") +set(libpointmatcher_INCLUDE_DIR "@CONF_INCLUDE_DIRS@") -set(libpointmatcher_LIBRARIES "@POINTMATCHER_LIB@;@EXTERNAL_LIBS@") -set(LIBPOINTMATCHER_LIBRARIES "@POINTMATCHER_LIB@;@EXTERNAL_LIBS@") -set(pointmatcher_LIBRARIES "@POINTMATCHER_LIB@;@EXTERNAL_LIBS@") -set(POINTMATCHER_LIBRARIES "@POINTMATCHER_LIB@;@EXTERNAL_LIBS@") +set(libpointmatcher_LIBRARIES "@POINTMATCHER_LIB@;@libnabo_LIBRARIES@;@EXTERNAL_LIBS@;@Boost_LIBRARIES@") +set(LIBPOINTMATCHER_LIBRARIES "@POINTMATCHER_LIB@;@libnabo_LIBRARIES@;@EXTERNAL_LIBS@;@Boost_LIBRARIES@") +set(pointmatcher_LIBRARIES "@POINTMATCHER_LIB@;@libnabo_LIBRARIES@;@EXTERNAL_LIBS@;@Boost_LIBRARIES@") +set(POINTMATCHER_LIBRARIES "@POINTMATCHER_LIB@;@libnabo_LIBRARIES@;@EXTERNAL_LIBS@;@Boost_LIBRARIES@") # This causes catkin simple to link against these libraries set(libpointmatcher_FOUND_CATKIN_PROJECT true) diff --git a/thirdparty/libpointmatcher/mkdocs.yml b/thirdparty/libpointmatcher/mkdocs.yml index 39aa25a..102745e 100644 --- a/thirdparty/libpointmatcher/mkdocs.yml +++ b/thirdparty/libpointmatcher/mkdocs.yml @@ -1,28 +1,44 @@ site_name: libpointmatcher repo_url: https://github.com/ethz-asl/libpointmatcher +edit_uri: edit/master/doc site_description: An "Iterative Closest Point" library for 2-D/3-D mapping in robotic google_analytics: ['UA-70950258-1', 'libpointmatcher.readthedocs.org'] -pages: +docs_dir: 'doc' +theme: + name: mkdocs + hljs_style: atom-one-light + hljs_languages: + - bash + - cmake + - cpp + - yaml +nav: - Home: 'index.md' -- Introduction: +- Compilation: + - 'Ubuntu': 'CompilationUbuntu.md' + - 'Mac OS X': 'CompilationMac.md' + - 'Windows': 'CompilationWindows.md' +- Beginner: - 'What is libpointmatcher about?': 'Introduction.md' - 'What can I do with libpointmatcher': 'ApplicationsAndPub.md' - - 'What the different data filters do?': 'Datafilters.md' - - 'Example: applying a chain of data filters': 'ApplyingDatafilters.md' + - 'What the different data filters do?': 'DataFilters.md' + - 'Example: applying a chain of data filters': 'ApplyingDataFilters.md' + - 'What are the different outlier filters?' : 'OutlierFiltersFamilies.md' - 'Example: An introduction to ICP': 'ICPIntro.md' - 'The ICP chain configuration and its variants': 'DefaultICPConfig.md' - 'Configuring libpointmatcher using YAML': 'Configuration.md' - 'Supported file types and importing/exporting point clouds': 'ImportExport.md' -- Compilation: - - 'Ubuntu': 'Compilation.md' - - 'Windows': 'CompilationWindows.md' - - 'Mac OS X': 'CompilationMac.md' - Advanced: - 'How to link a project to libpointmatcher': 'LinkingProjects.md' - - 'How are point clouds represented?': 'Pointclouds.md' + - 'How to use libpointmatcher in ROS?': 'UsingInRos.md' + - 'How are point clouds represented?': 'PointClouds.md' - 'Example: Writing a program which performs ICP': 'BasicRegistration.md' - 'How to move a point cloud using a rigid transformation?': 'Transformations.md' + - 'Example: Configure an ICP solution without yaml': 'ICPWithoutYaml.md' - Developer: - 'Creating a DataPointsFilter': 'DataPointsFilterDev.md' - 'Creating a Transformation': 'TransformationDev.md' - 'Creating unit tests': 'UnitTestDev.md' +- Python: + - 'Compiling libpointmatcher with Python': 'CompilationPython.md' + - 'Using libpointmatcher with Python': 'PythonModule.md' diff --git a/thirdparty/libpointmatcher/package.xml b/thirdparty/libpointmatcher/package.xml index 4e3dd84..6e3d753 100644 --- a/thirdparty/libpointmatcher/package.xml +++ b/thirdparty/libpointmatcher/package.xml @@ -1,4 +1,4 @@ - + libpointmatcher 1.3.1 @@ -14,10 +14,10 @@ libnabo eigen - boost - libnabo - eigen - catkin + boost + libnabo + eigen + catkin cmake diff --git a/thirdparty/libpointmatcher/pointmatcher/Bibliography.cpp b/thirdparty/libpointmatcher/pointmatcher/Bibliography.cpp index 850188a..59a1d7c 100644 --- a/thirdparty/libpointmatcher/pointmatcher/Bibliography.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/Bibliography.cpp @@ -121,6 +121,17 @@ namespace PointMatcherSupport {"doi", "10.1109/ROBOT.1991.132043"}, {"fulltext", "http://ieeexplore.ieee.org/search/srchabstract.jsp?tp=&arnumber=132043"} }}, + {"Prakhya2015Point2Plane", { + {"type", "inproceedings"}, + {"title", "A closed-form estimate of 3D ICP covariance"}, + {"author", "Prakhya, S.M. and Bingbing, L. and Rui, Y. and Lin, W."}, + {"booktitle", "2015 14th IAPR International Conference on Machine Vision Applications (MVA)"}, + {"year", "2015"}, + {"pages", "526--529"}, + {"publisher", "IEEE Press"}, + {"doi", "10.1109/MVA.2015.7153246"}, + {"fulltext", "https://ieeexplore.ieee.org/search/srchabstract.jsp?tp=&arnumber=7153246"} + }}, {"Masuda1996Random", { {"type", "inproceedings"}, {"title", "Registration and integration of multiple range images for 3-D model construction"}, @@ -206,6 +217,19 @@ namespace PointMatcherSupport {"pages", "260--267"}, {"doi", "10.1109/IM.2003.1240258"}, {"publisher", "IEEE Computer Society"} + }}, + {"Labussiere2020", { + {"type", "article"}, + {"author", "Labussière, Mathieu and Laconte, Johann and Pomerleau, François"}, + {"title", "Geometry Preserving Sampling Method Based on Spectral Decomposition for Large-Scale Environments"}, + {"journal", "Frontiers in Robotics and AI"}, + {"month", "sep"}, + {"year", "2020"}, + {"volume", "7"}, + {"isbn", "2296-9144"}, + {"pages", "134--148"}, + {"doi", "10.3389/frobt.2020.572054"}, + {"fulltext", "https://www.frontiersin.org/article/10.3389/frobt.2020.572054"} }} }; } diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPoints.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPoints.cpp index a53edc0..0eba15c 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPoints.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/DataPoints.cpp @@ -164,7 +164,8 @@ unsigned PointMatcher::DataPoints::getNbPoints() const template unsigned PointMatcher::DataPoints::getEuclideanDim() const { - return (features.rows() - 1); + const size_t nbRows = features.rows(); + return (nbRows == 0) ? 0 : (nbRows - 1); } //! Return the dimension of the point cloud in homogeneous coordinates (one more than Euclidean dimension) diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilter.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilter.cpp index 24d110a..b01631c 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilter.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilter.cpp @@ -123,11 +123,11 @@ void PointMatcher::DataPointsFilters::apply(DataPoints& cloud) cloud.assertDescriptorConsistency(); const int nbPointsOut(cloud.features.cols()); - LOG_INFO_STREAM("* " << (*it)->className << " - " << nbPointsOut << " points out (-" << (100 - double(nbPointsOut*100.)/nbPointsIn) << "\%)"); + LOG_INFO_STREAM("* " << (*it)->className << " - " << nbPointsOut << " points out (-" << (100 - double(nbPointsOut*100.)/nbPointsIn) << "%)"); } const int nbPointsAfterFilters(cloud.features.cols()); - LOG_INFO_STREAM("Applied " << this->size() << " filters - " << nbPointsAfterFilters << " points out (-" << (100 - double(nbPointsAfterFilters*100.)/nbPointsBeforeFilters) << "\%)"); + LOG_INFO_STREAM("Applied " << this->size() << " filters - " << nbPointsAfterFilters << " points out (-" << (100 - double(nbPointsAfterFilters*100.)/nbPointsBeforeFilters) << "%)"); } template struct PointMatcher::DataPointsFilters; diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/CovarianceSampling.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/CovarianceSampling.cpp index 477e69a..8728bad 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/CovarianceSampling.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/CovarianceSampling.cpp @@ -55,7 +55,7 @@ CovarianceSamplingDataPointsFilter::CovarianceSamplingDataPointsFilter(const const std::uint8_t tnm = this->template get("torqueNorm"); normalizationMethod = TorqueNormMethod(tnm); } - catch (const InvalidParameter& e) + catch (const InvalidParameter&) { normalizationMethod = TorqueNormMethod::Lavg; } @@ -104,10 +104,10 @@ void CovarianceSamplingDataPointsFilter::inPlaceFilter(DataPoints& cloud) for(std::size_t i = 0; i < featDim - 1; ++i) center(i) = T(0.); for (std::size_t i = 0; i < nbCandidates; ++i) - for (std::size_t f = 0; f <= 3; ++f) + for (std::size_t f = 0; f < 3; ++f) center(f) += cloud.features(f,candidates[i]); - for(std::size_t i = 0; i <= 3; ++i) center(i) /= T(nbCandidates); + for(std::size_t i = 0; i < 3; ++i) center(i) /= T(nbCandidates); //Compute torque normalization T Lnorm = 1.0; diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Elipsoids.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Elipsoids.cpp index 20f28cf..a179c9a 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Elipsoids.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Elipsoids.cpp @@ -34,7 +34,8 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ #include "Elipsoids.h" -#include "utils.h" +#include "DataPointsFilters/utils/utils.h" + // Eigenvalues #include "Eigen/QR" #include "Eigen/Eigenvalues" diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Gestalt.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Gestalt.cpp index f427f3e..9fd90b3 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Gestalt.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Gestalt.cpp @@ -34,7 +34,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ #include "Gestalt.h" -#include "utils.h" +#include "DataPointsFilters/utils/utils.h" #include @@ -480,7 +480,7 @@ void GestaltDataPointsFilter::fuseRange( // sort points into Gestalt bins const T angularBinWidth = M_PI/4; const T radialBinWidth = radius/4; - Matrix indices(2, colCount); + Eigen::MatrixXi indices(2, colCount); gestaltMeans = Matrix::Zero(4, 8); gestaltVariances = Matrix::Zero(4, 8); numOfValues = Matrix::Zero(4, 8); diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/MaxPointCount.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/MaxPointCount.cpp index a22debf..8d9d5bf 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/MaxPointCount.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/MaxPointCount.cpp @@ -33,20 +33,21 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ #include "MaxPointCount.h" +#include // MaxPointCountDataPointsFilter // Constructor template MaxPointCountDataPointsFilter::MaxPointCountDataPointsFilter(const Parameters& params): - PointMatcher::DataPointsFilter("MaxPointCountDataPointsFilter", - MaxPointCountDataPointsFilter::availableParameters(), params), + PointMatcher::DataPointsFilter("MaxPointCountDataPointsFilter", + MaxPointCountDataPointsFilter::availableParameters(), params), maxCount(Parametrizable::get("maxCount")) { - try + try { seed = this->template get("seed"); - } - catch (const InvalidParameter& e) + } + catch (const InvalidParameter&) { seed = static_cast(1); // rand default seed number } @@ -54,8 +55,7 @@ MaxPointCountDataPointsFilter::MaxPointCountDataPointsFilter(const Parameters // Compute template -typename PointMatcher::DataPoints -MaxPointCountDataPointsFilter::filter(const DataPoints& input) +typename PointMatcher::DataPoints MaxPointCountDataPointsFilter::filter(const DataPoints& input) { DataPoints output(input); inPlaceFilter(output); @@ -66,35 +66,20 @@ MaxPointCountDataPointsFilter::filter(const DataPoints& input) template void MaxPointCountDataPointsFilter::inPlaceFilter(DataPoints& cloud) { - const size_t N = static_cast (cloud.features.cols() - 1); - - if (maxCount <= N) + const size_t N{static_cast(cloud.getNbPoints() - 1)}; + + if (maxCount <= N) { - //Re-init seed at each call, to ensure same results - std::srand(seed); - - for(size_t j=0; j(seed)); + std::uniform_real_distribution distribution{0, 1}; + + for (size_t j{0u}; j < maxCount; ++j) { //Get a random index in [j; N] - const size_t idx = j + static_cast((N-j)*(static_cast(std::rand()/static_cast(RAND_MAX)))); - - //Switch columns j and idx - const auto feat = cloud.features.col(j); - cloud.features.col(j) = cloud.features.col(idx); - cloud.features.col(idx) = feat; - - if (cloud.descriptors.cols() > 0) - { - const auto desc = cloud.descriptors.col(j); - cloud.descriptors.col(j) = cloud.descriptors.col(idx); - cloud.descriptors.col(idx) = desc; - } - if (cloud.times.cols() > 0) - { - const auto time = cloud.times.col(j); - cloud.times.col(j) = cloud.times.col(idx); - cloud.times.col(idx) = time; - } + const size_t index{j + static_cast((N - j) * distribution(randomNumberGenerator))}; + + //Switch columns j and index + cloud.swapCols(j, index); } //Resize the cloud cloud.conservativeResize(maxCount); @@ -103,4 +88,3 @@ void MaxPointCountDataPointsFilter::inPlaceFilter(DataPoints& cloud) template struct MaxPointCountDataPointsFilter; template struct MaxPointCountDataPointsFilter; - diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/MaxQuantileOnAxis.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/MaxQuantileOnAxis.cpp index 9e35e0d..34eccc8 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/MaxQuantileOnAxis.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/MaxQuantileOnAxis.cpp @@ -45,7 +45,8 @@ MaxQuantileOnAxisDataPointsFilter::MaxQuantileOnAxisDataPointsFilter( PointMatcher::DataPointsFilter("MaxQuantileOnAxisDataPointsFilter", MaxQuantileOnAxisDataPointsFilter::availableParameters(), params), dim(Parametrizable::get("dim")), - ratio(Parametrizable::get("ratio")) + ratio(Parametrizable::get("ratio")), + removeBeyond(Parametrizable::get("removeBeyond")) { } @@ -68,33 +69,64 @@ void MaxQuantileOnAxisDataPointsFilter::inPlaceFilter(DataPoints& cloud) throw InvalidParameter((boost::format("MaxQuantileOnAxisDataPointsFilter: Error, filtering on dimension number %1%, larger than feature dimensionality %2%") % dim % cloud.features.rows()).str()); const int nbPointsIn = cloud.features.cols(); - const int nbPointsOut = nbPointsIn * ratio; - - // build array - std::vector values; - values.reserve(nbPointsIn); - for (int x = 0; x < nbPointsIn; ++x) - values.push_back(cloud.features(dim, x)); - - // get quartiles value - std::nth_element(values.begin(), values.begin() + (values.size() * ratio), values.end()); - const T limit = values[nbPointsOut]; - - // copy towards beginning the elements we keep - int j = 0; - for (int i = 0; i < nbPointsIn; ++i) - { - if (cloud.features(dim, i) < limit) + + if (removeBeyond) { + const int nbPointsOut = nbPointsIn * ratio; + + // build array + std::vector values; + values.reserve(nbPointsIn); + for (int x = 0; x < nbPointsIn; ++x) + values.push_back(cloud.features(dim, x)); + + // get quartiles value + std::nth_element(values.begin(), values.begin() + (values.size() * ratio), values.end()); + const T limit = values[nbPointsOut]; + + // copy towards beginning the elements we keep + int j = 0; + for (int i = 0; i < nbPointsIn; ++i) { - assert(j <= i); - cloud.setColFrom(j, cloud, i); - ++j; + if (cloud.features(dim, i) < limit) + { + assert(j <= i); + cloud.setColFrom(j, cloud, i); + ++j; + } } + assert(j <= nbPointsOut); + + cloud.conservativeResize(j); } - assert(j <= nbPointsOut); + else { + const int nbPointsOut = nbPointsIn * (1 - ratio); + + // build array + std::vector values; + values.reserve(nbPointsIn); + for (int x = 0; x < nbPointsIn; ++x) + values.push_back(cloud.features(dim, x)); - cloud.conservativeResize(j); + // get quartiles value + std::nth_element(values.begin(), values.begin() + (values.size() * ratio), values.end()); + const T limit = values[nbPointsIn-nbPointsOut]; + + // copy towards beginning the elements we keep + int j = 0; + for (int i = 0; i < nbPointsIn; ++i) + { + if (cloud.features(dim, i) > limit) + { + assert(j <= i); + cloud.setColFrom(j, cloud, i); + ++j; + } + } + assert(j <= nbPointsOut); + + cloud.conservativeResize(j); + } } template struct MaxQuantileOnAxisDataPointsFilter; diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/MaxQuantileOnAxis.h b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/MaxQuantileOnAxis.h index d93002b..58a3a54 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/MaxQuantileOnAxis.h +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/MaxQuantileOnAxis.h @@ -51,18 +51,20 @@ struct MaxQuantileOnAxisDataPointsFilter: public PointMatcher::DataPointsFilt inline static const std::string description() { - return "Subsampling. Filter points beyond a maximum quantile measured on a specific axis."; + return "Subsampling. Filter points under or beyond a maximum quantile measured on a specific axis."; } inline static const ParametersDoc availableParameters() { return { {"dim", "dimension on which the filter will be applied. x=0, y=1, z=2", "0", "0", "2", &P::Comp}, - {"ratio", "maximum quantile authorized. All points beyond that will be filtered.", "0.5", "0.0000001", "0.9999999", &P::Comp} + {"ratio", "maximum quantile authorized. All points beyond that will be filtered.", "0.5", "0.0000001", "0.9999999", &P::Comp}, + {"removeBeyond", "If set to true (1), remove points beyond the quantile ratio; else (0), remove points under the quantile ratio", "1", "0", "1", P::Comp} }; } const unsigned dim; const T ratio; + const bool removeBeyond; //! Constructor, uses parameter interface MaxQuantileOnAxisDataPointsFilter(const Parameters& params = Parameters()); diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/NormalSpace.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/NormalSpace.cpp index 7185fe2..c62fd75 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/NormalSpace.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/NormalSpace.cpp @@ -34,11 +34,13 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ #include "NormalSpace.h" +#include #include #include #include #include #include +#include // NormalSpaceDataPointsFilter template @@ -48,7 +50,7 @@ NormalSpaceDataPointsFilter::NormalSpaceDataPointsFilter(const Parameters& pa nbSample{Parametrizable::get("nbSample")}, seed{Parametrizable::get("seed")}, epsilon{Parametrizable::get("epsilon")}, - nbBucket{std::size_t((2.0 * M_PI / epsilon) * (M_PI / epsilon))} + nbBucket{std::size_t(ceil(2.0 * M_PI / epsilon) * ceil(M_PI / epsilon))} { } @@ -66,8 +68,6 @@ NormalSpaceDataPointsFilter::filter(const DataPoints& input) template void NormalSpaceDataPointsFilter::inPlaceFilter(DataPoints& cloud) { - static const int alreadySampled = -1; - //check dimension const std::size_t featDim = cloud.features.rows(); if(featDim < 4) //3D case support only @@ -88,67 +88,62 @@ void NormalSpaceDataPointsFilter::inPlaceFilter(DataPoints& cloud) const auto& normals = cloud.getDescriptorViewByName("normals"); std::mt19937 gen(seed); //Standard mersenne_twister_engine seeded with seed - std::uniform_real_distribution<> uni01(0., 1.); - + //bucketed normal space - std::vector > idBuckets; //stock int so we can marked selected with -1 + std::vector > idBuckets; idBuckets.resize(nbBucket); std::vector keepIndexes; keepIndexes.reserve(nbSample); - + + // Generate a random sequence of indices so that elements are placed in buckets in random order + std::vector randIdcs(nbPoints); + std::iota(randIdcs.begin(), randIdcs.end(), 0); + std::random_shuffle(randIdcs.begin(), randIdcs.end()); + ///(1) put all points of the data into buckets based on their normal direction - for (int i = 0; i < nbPoints; ++i) + for (auto randIdx : randIdcs) { - assert(normals.col(i).head(3).norm() > 0.99999); - + // Allow for slight approximiation errors + assert(normals.col(randIdx).head(3).norm() >= 1.0-0.00001); + assert(normals.col(randIdx).head(3).norm() <= 1.0+0.00001); + // Catch errors where theta will be NaN + assert((normals(2,randIdx) <= 1.0) && (normals(2,randIdx) >= -1.0)); + //Theta = polar angle in [0 ; pi] - const T theta = std::acos(normals(2, i)); - //Phi = azimuthal angle in [0 ; 2pi] - const T phi = std::fmod(std::atan2(normals(1, i), normals(0, i)) + 2. * M_PI, 2. * M_PI); - - //assert(theta >= 0. and theta =< M_PI and phi >= 0. and phi <= 2.*M_PI); - - idBuckets[bucketIdx(theta, phi)].push_back(i); - } - ///(2) uniformly pick points from all the buckets until the desired number of points is selected - while(keepIndexes.size() < nbSample) - { - const T theta = std::acos(1 - 2 * uni01(gen)); - const T phi = 2. * M_PI * uni01(gen); + const T theta = std::acos(normals(2, randIdx)); + //Phi = azimuthal angle in [0 ; 2pi] + const T phi = std::fmod(std::atan2(normals(1, randIdx), normals(0, randIdx)) + 2. * M_PI, 2. * M_PI); - std::vector& curBucket = idBuckets[bucketIdx(theta, phi)]; + // Catch normal space hashing errors + assert(bucketIdx(theta, phi) < nbBucket); + idBuckets[bucketIdx(theta, phi)].push_back(randIdx); + } - //Check size - if(curBucket.empty()) - continue; - - const std::size_t bucketSize = curBucket.size(); + // Remove empty buckets + idBuckets.erase(std::remove_if(idBuckets.begin(), idBuckets.end(), + [](const std::vector& bucket) { return bucket.empty(); }), + idBuckets.end()); - //Check if not already all sampled - bool isEntireBucketSampled = true; - for(std::size_t id = 0; id < bucketSize and isEntireBucketSampled; ++id) - { - isEntireBucketSampled = isEntireBucketSampled and (curBucket[id] == alreadySampled); - } + ///(2) uniformly pick points from all the buckets until the desired number of points is selected + for (std::size_t i=0; i uniBucket(0,idBuckets.size()-1); + std::size_t curBucketIdx = uniBucket(gen); + std::vector& curBucket = idBuckets[curBucketIdx]; - if(isEntireBucketSampled) - continue; - ///(3) A point is randomly picked in a bucket that contains multiple points - int idToKeep = 0; - std::size_t idInBucket = 0; - do - { - idInBucket = static_cast(bucketSize * uni01(gen)); - idToKeep = curBucket[idInBucket]; - - } while(idToKeep == alreadySampled); - + int idToKeep = curBucket[curBucket.size()-1]; + curBucket.pop_back(); keepIndexes.push_back(static_cast(idToKeep)); - curBucket[idInBucket] = alreadySampled; //set sampled flag + // Remove the bucket if it is empty + if (curBucket.empty()) { + idBuckets.erase(idBuckets.begin()+curBucketIdx); + } } + //TODO: evaluate performances between this solution and sorting the indexes // We build map of (old index to new index), in case we sample pts at the begining of the pointcloud std::unordered_map mapidx; @@ -174,7 +169,15 @@ template std::size_t NormalSpaceDataPointsFilter::bucketIdx(T theta, T phi) const { //Theta = polar angle in [0 ; pi] and Phi = azimuthal angle in [0 ; 2pi] - return static_cast(theta / epsilon) * static_cast(2. * M_PI / epsilon) + static_cast(phi / epsilon); + assert( (theta >= 0.0) && (theta <= static_cast(M_PI)) && "Theta not in [0, Pi]"); + assert( (phi >= 0) && (phi <= 2*static_cast(M_PI)) && "Phi not in [0, 2Pi]"); + + // Wrap Theta at Pi + if (theta == static_cast(M_PI)) { theta = 0.0; }; + // Wrap Phi at 2Pi + if (phi == 2*static_cast(M_PI)) { phi = 0.0; }; + // block number block size element number + return static_cast( floor(theta/epsilon) * ceil(2.0*M_PI/epsilon) + floor(phi/epsilon) ); } template struct NormalSpaceDataPointsFilter; diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/OctreeGrid.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/OctreeGrid.cpp index 17bd55d..aa7b026 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/OctreeGrid.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/OctreeGrid.cpp @@ -295,7 +295,7 @@ OctreeGridDataPointsFilter::OctreeGridDataPointsFilter(const Parameters& para const int sm = this->template get("samplingMethod"); samplingMethod = SamplingMethod(sm); } - catch (const InvalidParameter& e) + catch (const InvalidParameter&) { samplingMethod = SamplingMethod::FIRST_PTS; } diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/RandomSampling.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/RandomSampling.cpp index 65e3aae..7814e15 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/RandomSampling.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/RandomSampling.cpp @@ -34,12 +34,16 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ #include "RandomSampling.h" +#include + // RandomSamplingDataPointsFilter // Constructor template RandomSamplingDataPointsFilter::RandomSamplingDataPointsFilter(const Parameters& params): PointMatcher::DataPointsFilter("RandomSamplingDataPointsFilter", RandomSamplingDataPointsFilter::availableParameters(), params), - prob(Parametrizable::get("prob")) + prob(Parametrizable::get("prob")), + randomSamplingMethod(Parametrizable::get("randomSamplingMethod")), + seed(Parametrizable::get("seed")) { } @@ -53,24 +57,54 @@ RandomSamplingDataPointsFilter::filter(const DataPoints& input) return output; } +// In-place filter +template +Eigen::VectorXf RandomSamplingDataPointsFilter::sampleRandomIndices(const size_t nbPoints) +{ + std::minstd_rand randomNumberGenerator; + if (seed == -1) + { + std::random_device randomDevice; + randomNumberGenerator = std::minstd_rand(randomDevice()); + } + else + { + randomNumberGenerator = std::minstd_rand(seed); + } + + switch(randomSamplingMethod) + { + default: // Direct RNG. + { + const float randomNumberRange{static_cast(randomNumberGenerator.max() - randomNumberGenerator.min())}; + return Eigen::VectorXf::NullaryExpr(nbPoints, [&](float){return static_cast(randomNumberGenerator() / randomNumberRange);}); + } + case 1: // Uniform distribution. + { + std::uniform_real_distribution distribution(0, 1); + return Eigen::VectorXf::NullaryExpr(nbPoints, [&](float){return distribution(randomNumberGenerator);}); + } + } +} + // In-place filter template void RandomSamplingDataPointsFilter::inPlaceFilter( DataPoints& cloud) { - const int nbPointsIn = cloud.features.cols(); + const size_t nbPointsIn = cloud.features.cols(); + const size_t nbPointsOut = nbPointsIn * prob; - int j = 0; - for (int i = 0; i < nbPointsIn; ++i) + const Eigen::VectorXf randomNumbers{sampleRandomIndices(nbPointsIn)}; + size_t j{0u}; + for (size_t i{0u}; i < nbPointsIn && j<=nbPointsOut; ++i) { - const float r = (float)std::rand()/(float)RAND_MAX; - if (r < prob) + if (randomNumbers(i) < prob) { cloud.setColFrom(j, cloud, i); ++j; } } - cloud.conservativeResize(j); } diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/RandomSampling.h b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/RandomSampling.h index e134df3..ff763f3 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/RandomSampling.h +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/RandomSampling.h @@ -58,14 +58,19 @@ struct RandomSamplingDataPointsFilter: public PointMatcher::DataPointsFilter inline static const ParametersDoc availableParameters() { return { - {"prob", "probability to keep a point, one over decimation factor ", "0.75", "0", "1", &P::Comp} + {"prob", "Probability to keep a point, one over decimation factor ", "0.75", "0", "1", &P::Comp}, + {"randomSamplingMethod", "Random sampling method: Direct RNG (0) (fastest), Uniform (1) (more accurate but slower)", "0", "0", "1", &P::Comp}, + {"seed", "Seed for random sampling (-1 means no seed is used)", "-1", "-1", "2147483647", &P::Comp} }; } const double prob; - + const int randomSamplingMethod; + const int seed; + RandomSamplingDataPointsFilter(const Parameters& params = Parameters()); virtual ~RandomSamplingDataPointsFilter() {}; virtual DataPoints filter(const DataPoints& input); virtual void inPlaceFilter(DataPoints& cloud); + Eigen::VectorXf sampleRandomIndices(const size_t nbPoints); }; diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Saliency.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Saliency.cpp new file mode 100644 index 0000000..7fc06a4 --- /dev/null +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Saliency.cpp @@ -0,0 +1,119 @@ +// kate: replace-tabs off; indent-width 4; indent-mode normal +// vim: ts=4:sw=4:noexpandtab +/* + +Copyright (c) 2010--2018, +François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland +You can contact the authors at and + + +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 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 ETH-ASL 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. + +*/ +#include "Saliency.h" +#include "utils/sparsetv.h" + + +// NormalSpaceDataPointsFilter +template +SaliencyDataPointsFilter::SaliencyDataPointsFilter(const Parameters& params) : + PointMatcher::DataPointsFilter("SaliencyDataPointsFilter", + SaliencyDataPointsFilter::availableParameters(), params), + k{Parametrizable::get("k")}, + sigma{Parametrizable::get("sigma")}, + keepNormals{Parametrizable::get("keepNormals")}, + keepLabels{Parametrizable::get("keepLabels")}, + keepTensors{Parametrizable::get("keepTensors")} +{ +} + +template +typename PointMatcher::DataPoints +SaliencyDataPointsFilter::filter(const DataPoints& input) +{ + DataPoints output(input); + inPlaceFilter(output); + return output; +} + +template +void SaliencyDataPointsFilter::inPlaceFilter(DataPoints& cloud) +{ + const std::size_t nbPts = cloud.getNbPoints(); + + TensorVoting tv{sigma, k}; + + //Refinement step + tv.refine(cloud); + + //Compute real saliencies + tv.disableBallComponent(); + tv.cfvote(cloud, false); + tv.decompose(); + tv.toDescriptors(); + + Matrix labels = Matrix::Zero(1, nbPts); + for(std::size_t i = 0; i < nbPts; ++i) + { + const T lambda1 = tv.surfaceness(i); + const T lambda2 = tv.curveness(i); + const T lambda3 = tv.pointness(i); + + int index; + Vector coeff = (Vector(3) << lambda3, (lambda2 - lambda3), (lambda1 - lambda2)).finished(); + coeff.maxCoeff(&index); + + labels(i) = index + 1 ; + } + + try + { + cloud.addDescriptor("surfaceness", tv.surfaceness); + cloud.addDescriptor("curveness", tv.curveness); + cloud.addDescriptor("pointness", tv.pointness); + + if(keepNormals) + { + cloud.addDescriptor("normals", tv.normals); + cloud.addDescriptor("tangents", tv.tangents); + } + if(keepLabels) + { + cloud.addDescriptor("labels", labels); + } + if(keepTensors) + { + cloud.addDescriptor("sticks", tv.sticks); + cloud.addDescriptor("plates", tv.plates); + cloud.addDescriptor("balls", tv.balls); + } + } + catch (...) { + std::cerr << "SaliencyDataPointsFilter::inPlaceFilter: Cannot add descriptors to pointcloud" << std::endl; + } +} + +template struct SaliencyDataPointsFilter; +template struct SaliencyDataPointsFilter; diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Saliency.h b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Saliency.h new file mode 100644 index 0000000..4dafc1e --- /dev/null +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Saliency.h @@ -0,0 +1,97 @@ +// kate: replace-tabs off; indent-width 4; indent-mode normal +// vim: ts=4:sw=4:noexpandtab +/* + +Copyright (c) 2010--2018, +François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland +You can contact the authors at and + + +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 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 ETH-ASL 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. + +*/ +#pragma once + +#include "PointMatcher.h" + +template +struct SaliencyDataPointsFilter : public PointMatcher::DataPointsFilter +{ + // Type definitions + typedef PointMatcher PM; + typedef typename PM::DataPoints DataPoints; + typedef typename PM::DataPointsFilter DataPointsFilter; + + typedef PointMatcherSupport::Parametrizable Parametrizable; + typedef PointMatcherSupport::Parametrizable P; + typedef Parametrizable::Parameters Parameters; + typedef Parametrizable::ParameterDoc ParameterDoc; + typedef Parametrizable::ParametersDoc ParametersDoc; + typedef Parametrizable::InvalidParameter InvalidParameter; + + typedef typename DataPoints::Index Index; + + typedef typename PointMatcher::DataPoints::InvalidField InvalidField; + + typedef typename PM::Matrix Matrix; + typedef typename PM::Vector Vector; + + inline static const std::string description() + { + return "Point cloud enhancement: compute geometric features saliencies throught Tensor Voting framework."; + } + + inline static const ParametersDoc availableParameters() + { + return { + {"k", "Number of neighbors to consider", "50", "6", "4294967295", &P::Comp}, + {"sigma", "Scale of the vote.", "0.2", "0.", "+inf", &P::Comp}, + {"keepNormals", "Flag to keep normals computed by TV.", "1", "0", "1", P::Comp}, + {"keepLabels", "Flag to keep labels computed by TV.", "1", "0", "1", P::Comp}, + {"keepTensors", "Flag to keep elements Tensors computed by TV.", "1", "0", "1", P::Comp} + }; + } + +public: + const std::size_t k; + const T sigma; + const bool keepNormals; + const bool keepLabels; + const bool keepTensors; + + //Ctor, uses parameter interface + SaliencyDataPointsFilter(const Parameters& params = Parameters()); + //SaliencyDataPointsFilter(); + + //Dtor + virtual ~SaliencyDataPointsFilter() {}; + + virtual DataPoints filter(const DataPoints& input); + virtual void inPlaceFilter(DataPoints& cloud); + +private: +}; + + diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SamplingSurfaceNormal.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SamplingSurfaceNormal.cpp index 998f29e..b5df96f 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SamplingSurfaceNormal.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SamplingSurfaceNormal.cpp @@ -33,8 +33,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ #include "SamplingSurfaceNormal.h" - -#include "utils.h" +#include "DataPointsFilters/utils/utils.h" // Eigenvalues #include "Eigen/QR" @@ -152,6 +151,8 @@ void SamplingSurfaceNormalDataPointsFilter::inPlaceFilter( cloud.features.col(i) = cloud.features.col(k); if (cloud.descriptors.rows() != 0) cloud.descriptors.col(i) = cloud.descriptors.col(k); + if (cloud.times.rows() != 0) + cloud.times.col(i) = cloud.times.col(k); if(keepNormals) buildData.normals->col(i) = buildData.normals->col(k); if(keepDensities) @@ -161,9 +162,7 @@ void SamplingSurfaceNormalDataPointsFilter::inPlaceFilter( if(keepEigenVectors) buildData.eigenVectors->col(i) = buildData.eigenVectors->col(k); } - cloud.features.conservativeResize(Eigen::NoChange, ptsOut); - cloud.descriptors.conservativeResize(Eigen::NoChange, ptsOut); - + cloud.conservativeResize(ptsOut); // warning if some points were dropped if(buildData.unfitPointsCount != 0) LOG_INFO_STREAM(" SamplingSurfaceNormalDataPointsFilter - Could not compute normal for " << buildData.unfitPointsCount << " pts."); @@ -246,7 +245,7 @@ void SamplingSurfaceNormalDataPointsFilter::fuseRange( const Matrix NN = (d.colwise() - mean); // compute covariance - const Matrix C(NN * NN.transpose()); + const Matrix C((NN * NN.transpose()) / T(colCount)); Vector eigenVa = Vector::Identity(featDim-1, 1); Matrix eigenVe = Matrix::Identity(featDim-1, featDim-1); // Ensure that the matrix is suited for eigenvalues calculation diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SpectralDecomposition.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SpectralDecomposition.cpp new file mode 100644 index 0000000..cddcbbc --- /dev/null +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SpectralDecomposition.cpp @@ -0,0 +1,356 @@ +// kate: replace-tabs off; indent-width 4; indent-mode normal +// vim: ts=4:sw=4:noexpandtab +/* + +Copyright (c) 2010--2018, +François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland +You can contact the authors at and + + +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 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 ETH-ASL 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. + +*/ +#include "SpectralDecomposition.h" + +#include + +// SpectralDecomposition +template +SpectralDecompositionDataPointsFilter::SpectralDecompositionDataPointsFilter(const Parameters& params) : + PointMatcher::DataPointsFilter("SpectralDecompositionDataPointsFilter", + SpectralDecompositionDataPointsFilter::availableParameters(), params), + k{Parametrizable::get("k")}, + sigma{Parametrizable::get("sigma")}, + radius{Parametrizable::get("radius")}, + itMax{Parametrizable::get("itMax")}, + keepNormals{Parametrizable::get("keepNormals")}, + keepLabels{Parametrizable::get("keepLabels")}, + keepLambdas{Parametrizable::get("keepLambdas")}, + keepTensors{Parametrizable::get("keepTensors")} +{ +} + +template +typename PointMatcher::DataPoints +SpectralDecompositionDataPointsFilter::filter(const DataPoints& input) +{ + DataPoints output(input); + inPlaceFilter(output); + return output; +} + +template +void SpectralDecompositionDataPointsFilter::inPlaceFilter(DataPoints& cloud) +{ + const std::size_t nbPts = cloud.getNbPoints(); + + if(k > nbPts) return; + + TensorVoting tv{sigma, k}; + +//--- 1. Vote to determine prefered orientation + density estimation ----------- + tv.encode(cloud, TensorVoting::Encoding::BALL); + tv.cfvote(cloud, true); + tv.decompose(); + tv.toDescriptors(); + addDescriptor(cloud, tv, false /*normals*/, false /*labels*/, true /*lambdas*/, false /*tensors*/); + +//--- 2. Filter iteratively on each measure (surfaceness, curveness, pointness) to uniformize density + std::size_t it = 0; + const std::size_t itMax_ = itMax; + const std::size_t k_ = k; + std::size_t oldnbPts = nbPts; + + auto checkConvergence = [&oldnbPts, &it, &itMax_, &k_](const DataPoints& pts, const std::size_t threshold) mutable ->bool{ + const std::size_t nbPts = pts.getNbPoints(); + bool ret = (oldnbPts - nbPts) < threshold; + + oldnbPts = nbPts; + + return ret or ++it >= itMax_ or k_ >= nbPts; + }; + + const T xi3 = xi_expectation(3, sigma, radius); + const T xi2 = xi_expectation(2, sigma, radius); + const T xi1 = xi_expectation(1, sigma, radius); + + do + { + // 2.1 On pointness + filterPointness(cloud, xi3, tv.k); + // 2.2 On curveness + filterCurveness(cloud, xi1, tv.k); + // 2.3 On surfaceness + filterSurfaceness(cloud, xi2, tv.k); + + //Re-compute vote... + tv.encode(cloud, TensorVoting::Encoding::BALL); + tv.cfvote(cloud, true); + tv.decompose(); + tv.toDescriptors(); + + addDescriptor(cloud, tv, false /*normals*/, false /*labels*/, true /*lambdas*/, false /*tensors*/); + } + while(not checkConvergence(cloud, 5 /*delta points*/)); + +//--- 3. Re-encode as Aware tensors + Re-vote ---------------------------------- + addDescriptor(cloud, tv, false /*normals*/, false /*labels*/, false /*lambdas*/, true /*tensors*/); + tv.encode(cloud, TensorVoting::Encoding::AWARE_TENSOR); + tv.cfvote(cloud); + tv.decompose(); + tv.toDescriptors(); + +//--- 4. Add descriptors + addDescriptor(cloud, tv, keepNormals, true, keepLambdas, keepTensors);//TODO: add remove not kept descriptors + +//--- 5. Remove outliers + removeOutlier(cloud, tv); +} + + +template +void SpectralDecompositionDataPointsFilter::addDescriptor(DataPoints& pts, const TensorVoting &tv, bool keepNormals_, bool keepLabels_, bool keepLambdas_, bool keepTensors_) const +{ + const std::size_t nbPts = pts.getNbPoints(); + + Matrix labels = Matrix::Zero(1, nbPts); + Matrix l1 = PM::Matrix::Zero(1, nbPts); + Matrix l2 = PM::Matrix::Zero(1, nbPts); + Matrix l3 = PM::Matrix::Zero(1, nbPts); + + if(keepLabels_ or keepLambdas_) + { + #pragma omp parallel for + for(std::size_t i = 0; i < nbPts; ++i) + { + const T lambda1 = tv.surfaceness(i) + tv.curveness(i) + tv.pointness(i); + const T lambda2 = tv.curveness(i) + tv.pointness(i); + const T lambda3 = tv.pointness(i); + + int index; + Vector coeff = (Vector(3) << lambda3, (lambda2 - lambda3), (lambda1 - lambda2)).finished(); + coeff.maxCoeff(&index); + + labels(i) = index + 1 ; + + l1(i) = lambda1 * k; + l2(i) = lambda2 * k; + l3(i) = lambda3 * k; + } + } + try + { + pts.addDescriptor("surfaceness", tv.surfaceness); + pts.addDescriptor("curveness", tv.curveness); + pts.addDescriptor("pointness", tv.pointness); + + if(keepLambdas_) + { + pts.addDescriptor("lambda1", l1); + pts.addDescriptor("lambda2", l2); + pts.addDescriptor("lambda3", l3); + } + + if(keepNormals_) + { + pts.addDescriptor("normals", tv.normals); + pts.addDescriptor("tangents", tv.tangents); + } + if(keepLabels_) + { + pts.addDescriptor("labels", labels); + } + if(keepTensors_) + { + pts.addDescriptor("sticks", tv.sticks); + pts.addDescriptor("plates", tv.plates); + pts.addDescriptor("balls", tv.balls); + } + } + catch (...) { + std::cerr << "SpectralDecomposition::inPlaceFilter::addDescriptor: Cannot add descriptors to pointcloud" << std::endl; + } + +} + + +//------------------------------------------------------------------------------ +// Outlier filter +//------------------------------------------------------------------------------ +template +void SpectralDecompositionDataPointsFilter::removeOutlier(DataPoints& pts, const TensorVoting &tv) const +{ + static constexpr int POINT = 0; + static constexpr int CURVE = 1; + static constexpr int SURFACE = 2; + + static constexpr T th = 0.1; //threshold at 10% + + const std::size_t nbPts = pts.getNbPoints(); + + const T th_p = (tv.pointness.maxCoeff() - tv.pointness.minCoeff()) * th + tv.pointness.minCoeff(); + const T th_c = (tv.curveness.maxCoeff() - tv.curveness.minCoeff()) * th + tv.curveness.minCoeff(); + const T th_s = (tv.surfaceness.maxCoeff() - tv.surfaceness.minCoeff()) * th + tv.surfaceness.minCoeff(); + + + std::size_t j = 0; + for (std::size_t i = 0; i < nbPts; ++i) + { + const T surfaceness = tv.surfaceness(i); + const T curveness = tv.curveness(i); + const T pointness = tv.pointness(i); + + int label; + (Vector(3) << pointness, curveness, surfaceness).finished().maxCoeff(&label); + + bool keepPt = ((label == POINT) and (pointness >= th_p)) + or ((label == CURVE) and (curveness >= th_c)) + or ((label == SURFACE) and (surfaceness >= th_s)); + + if (keepPt) + { + pts.setColFrom(j, pts, i); + ++j; + } + } + pts.conservativeResize(j); +} + +//------------------------------------------------------------------------------ +// Filter +//------------------------------------------------------------------------------ +template +void SpectralDecompositionDataPointsFilter::filterSurfaceness(DataPoints& pts, T xi, std::size_t k) const +{ + constexpr std::size_t seed = 1; + std::mt19937 gen(seed); //Standard mersenne_twister_engine seeded with seed + std::uniform_real_distribution<> uni01(0., 1.); + + const std::size_t nbPts = pts.getNbPoints(); + + // Check field exists + if (!pts.descriptorExists("lambda1") or !pts.descriptorExists("lambda2") or !pts.descriptorExists("lambda3")) + { + throw InvalidField("SpectralDecomposition::filter: Error, lambdas field not found in descriptors."); + } + + const auto& lambda1 = pts.getDescriptorViewByName("lambda1"); + const auto& lambda2 = pts.getDescriptorViewByName("lambda2"); + const auto& lambda3 = pts.getDescriptorViewByName("lambda3"); + + std::size_t j = 0; + for (std::size_t i = 0; i < nbPts; ++i) + { + const T randv = uni01(gen); + + const T nl1 = lambda1(0,i) / k; + const T nl2 = lambda2(0,i) / k; + const T nl3 = lambda3(0,i) / k; + + if (nl1 < xi or nl2 < 0.75 * xi or nl3 < 0.75 * xi or randv < 0.5) + { + pts.setColFrom(j, pts, i); + ++j; + } + } + pts.conservativeResize(j); +} + +template +void SpectralDecompositionDataPointsFilter::filterCurveness(DataPoints& pts, T xi, std::size_t k) const +{ + constexpr std::size_t seed = 1; + std::mt19937 gen(seed); //Standard mersenne_twister_engine seeded with seed + std::uniform_real_distribution<> uni01(0., 1.); + + const std::size_t nbPts = pts.getNbPoints(); + + // Check field exists + if (!pts.descriptorExists("lambda1") or !pts.descriptorExists("lambda2") or !pts.descriptorExists("lambda3")) + { + throw InvalidField("SpectralDecomposition::filter: Error, lambdas field not found in descriptors."); + } + + const auto& lambda1 = pts.getDescriptorViewByName("lambda1"); + const auto& lambda2 = pts.getDescriptorViewByName("lambda2"); + const auto& lambda3 = pts.getDescriptorViewByName("lambda3"); + + std::size_t j = 0; + for (std::size_t i = 0; i < nbPts; ++i) + { + const T randv = uni01(gen); + + const T nl1 = lambda1(0,i) / k; + const T nl2 = lambda2(0,i) / k; + const T nl3 = lambda3(0,i) / k; + + if (nl1 < xi or nl2 < xi or nl3 < 0.5 * xi or randv < 0.5) + { + pts.setColFrom(j, pts, i); + ++j; + } + } + pts.conservativeResize(j); +} + +template +void SpectralDecompositionDataPointsFilter::filterPointness(DataPoints& pts, T xi, std::size_t k) const +{ + constexpr std::size_t seed = 1; + std::mt19937 gen(seed); //Standard mersenne_twister_engine seeded with seed + std::uniform_real_distribution<> uni01(0., 1.); + + const std::size_t nbPts = pts.getNbPoints(); + + // Check field exists + if (!pts.descriptorExists("lambda1") or !pts.descriptorExists("lambda2") or !pts.descriptorExists("lambda3")) + { + throw InvalidField("SpectralDecomposition::filter: Error, lambdas field not found in descriptors."); + } + + const auto& lambda1 = pts.getDescriptorViewByName("lambda1"); + const auto& lambda2 = pts.getDescriptorViewByName("lambda2"); + const auto& lambda3 = pts.getDescriptorViewByName("lambda3"); + + std::size_t j = 0; + for (std::size_t i = 0; i < nbPts; ++i) + { + const T randv = uni01(gen); + + const T nl1 = lambda1(0,i) / k; + const T nl2 = lambda2(0,i) / k; + const T nl3 = lambda3(0,i) / k; + + if (nl1 < (5./6.) * xi or nl2 < (5./6.) * xi or nl3 < (5./6.) * xi or randv < 0.2) + { + pts.setColFrom(j, pts, i); + ++j; + } + } + pts.conservativeResize(j); +} + +template struct SpectralDecompositionDataPointsFilter; +template struct SpectralDecompositionDataPointsFilter; diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SpectralDecomposition.h b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SpectralDecomposition.h new file mode 100644 index 0000000..d097a69 --- /dev/null +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SpectralDecomposition.h @@ -0,0 +1,131 @@ +// kate: replace-tabs off; indent-width 4; indent-mode normal +// vim: ts=4:sw=4:noexpandtab +/* + +Copyright (c) 2010--2018, +François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland +You can contact the authors at and + + +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 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 ETH-ASL 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. + +*/ +#pragma once + +#include "PointMatcher.h" +#include "utils/sparsetv.h" + +/** + * Spectral Decomposition Filter (SpDF) is a sampling algorithm based on spectral decomposition analysis to derive local density measures for each geometric primitive. + * First, we identify the geometric primitives along with their saliencies using the tensor voting framework. + * Then, we derive density measures from saliencies: if the density for each geometric primitive is less than the desired density, we stop; else we sub-sample each over-represented geometric primitive, and re-iterate. + * As output, we have a uniform sampled point cloud enhanced with geometric information. + * + * Implemented by Mathieu Labussiere , Institut Pascal, Université Clermont Auvergne, 2020 + **/ +template +struct SpectralDecompositionDataPointsFilter : public PointMatcher::DataPointsFilter +{ + // Type definitions + typedef PointMatcher PM; + typedef typename PM::DataPoints DataPoints; + typedef typename PM::DataPoints DP; + typedef typename PM::DataPointsFilter DataPointsFilter; + + typedef PointMatcherSupport::Parametrizable Parametrizable; + typedef PointMatcherSupport::Parametrizable P; + typedef Parametrizable::Parameters Parameters; + typedef Parametrizable::ParameterDoc ParameterDoc; + typedef Parametrizable::ParametersDoc ParametersDoc; + typedef Parametrizable::InvalidParameter InvalidParameter; + + typedef typename DataPoints::Index Index; + + typedef typename PointMatcher::DataPoints::InvalidField InvalidField; + + typedef typename PM::Matrix Matrix; + typedef typename PM::Vector Vector; + + inline static const std::string description() + { + return "Point cloud sampling and enhancement: compute geometric features saliencies throught Tensor Voting framework and use them to sample the point cloud. \\cite{Labussiere2020}"; + } + + inline static const ParametersDoc availableParameters() + { + return { + {"k", "Number of neighbors to consider", "50", "6", "4294967295", &P::Comp}, + {"sigma", "Scale of the vote in TensorVoting.", "0.2", "0.", "+inf", &P::Comp}, + {"radius", "Radius to control the scale of the uniform distribution.", "0.4", "0.", "+inf", &P::Comp}, + {"itMax", "Number max of iterations to do", "10", "1", "4294967295", &P::Comp}, + {"keepNormals", "Flag to keep normals computed by TV.", "1", "0", "1", P::Comp}, + {"keepLabels", "Flag to keep labels computed by TV.", "1", "0", "1", P::Comp}, + {"keepLambdas", "Flag to keep lambdas computed by TV.", "1", "0", "1", P::Comp}, + {"keepTensors", "Flag to keep elements Tensors computed by TV.", "1", "0", "1", P::Comp} + }; + } + +public: + const std::size_t k; + const T sigma; + const T radius; + const std::size_t itMax; + const bool keepNormals; + const bool keepLabels; + const bool keepLambdas; + const bool keepTensors; + + //Ctor, uses parameter interface + SpectralDecompositionDataPointsFilter(const Parameters& params = Parameters()); + //SpectralDecompositionDataPointsFilter(); + + //Dtor + virtual ~SpectralDecompositionDataPointsFilter() {}; + + virtual DataPoints filter(const DataPoints& input); + virtual void inPlaceFilter(DataPoints& cloud); + +private: + static T xi_expectation(const std::size_t D, const T sigma_, const T radius_) + { + return (D == 1) ? //on a curve + (std::sqrt(M_PI * sigma_) * std::erf(radius_ / std::sqrt(sigma_))) / (2. * radius_) + : (D == 2) ? //on a surface + (sigma_ - sigma_ * std::exp(- radius_ * radius_ / sigma_)) / (radius_ * radius_) + : (D == 3) ?//on a sphere + 3. * sigma_ * (std::sqrt(M_PI * sigma_) * std::erf(radius_ / std::sqrt(sigma_)) - 2. * radius_ * std::exp(- radius_ * radius_ / sigma_)) / (4. * radius_ * radius_ * radius_) + : T(1.); //otherwise + } + + void addDescriptor(DataPoints& pts, const TensorVoting &tv, bool keepNormals_, bool keepLabels_, bool keepLambdas_, bool keepTensors_) const; + + void removeOutlier(DataPoints& pts, const TensorVoting &tv) const; + + void filterSurfaceness(DataPoints& pts, T xi, std::size_t k) const; + void filterCurveness(DataPoints& pts, T xi, std::size_t k) const; + void filterPointness(DataPoints& pts, T xi, std::size_t k) const; +}; + + diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Sphericality.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Sphericality.cpp new file mode 100644 index 0000000..584ace6 --- /dev/null +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Sphericality.cpp @@ -0,0 +1,180 @@ +// kate: replace-tabs off; indent-width 4; indent-mode normal +// vim: ts=4:sw=4:noexpandtab +/* + +Copyright (c) 2010--2018, +François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland +You can contact the authors at and + + +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 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 ETH-ASL 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. + +*/ +#include "Sphericality.h" + + +/* + The SphericalityDataPointFilter estimates a heuristic value which indicates how much local geometry around + a given point resemble a plane or a sphere (uniform distribution). The value can lie in <-1,1> interval, -1 for + perfect plane, 1 for perfectly uniform distribution. The estimation is based on three eigenvalues coming from another + data points filter (this filter can operate only on 3D data). In the case the largest eigenvalue is zero, the filter + outputs NaNs. If the middle eigenvalue is zero and the largest one is non-zero, the filter outputs zeros. + + Implemented by Vladimir Kubelka (kubelvla@gmail.com), NORLAB, Universite Laval, 2020 +*/ + +// Constructor +template +SphericalityDataPointsFilter::SphericalityDataPointsFilter(const Parameters& params): + PointMatcher::DataPointsFilter("SphericalityDataPointsFilter", + SphericalityDataPointsFilter::availableParameters(), params), + keepUnstructureness(Parametrizable::get("keepUnstructureness")), + keepStructureness(Parametrizable::get("keepStructureness")) +{ +} + +// Compute +template +typename PointMatcher::DataPoints +SphericalityDataPointsFilter::filter( + const DataPoints& input) +{ + DataPoints output(input); + inPlaceFilter(output); + return output; +} + +// In-place filter +template +void SphericalityDataPointsFilter::inPlaceFilter( + DataPoints& cloud) +{ + + typedef typename DataPoints::View View; + typedef typename DataPoints::Label Label; + typedef typename DataPoints::Labels Labels; + + const size_t pointsCount(cloud.features.cols()); + const size_t descDim(cloud.descriptors.rows()); + const size_t labelDim(cloud.descriptorLabels.size()); + + // Check that the required eigenValue descriptor exists in the pointcloud + if (!cloud.descriptorExists("eigValues")) + { + throw InvalidField("SphericalityDataPointsFilter: Error, no eigValues found in descriptors."); + } + + // Validate descriptors and labels + size_t insertDim(0); + for(unsigned int i = 0; i < labelDim ; ++i) + insertDim += cloud.descriptorLabels[i].span; + if (insertDim != descDim) + throw InvalidField("SurfaceNormalDataPointsFilter: Error, descriptor labels do not match descriptor data"); + + // Reserve memory for new descriptors + const size_t unidimensionalDescriptorDimension(1); + + + boost::optional sphericality; // these optionals may cause a compiler warning, but it is ok, + boost::optional unstructureness; // it is intended to be uninitialized + boost::optional structureness; + + Labels cloudLabels; + cloudLabels.push_back(Label("sphericality", unidimensionalDescriptorDimension)); + if (keepUnstructureness) + cloudLabels.push_back(Label("unstructureness", unidimensionalDescriptorDimension)); + if (keepStructureness) + cloudLabels.push_back(Label("structureness", unidimensionalDescriptorDimension)); + + // Reserve memory + cloud.allocateDescriptors(cloudLabels); + + // Get the views + const View eigValues = cloud.getDescriptorViewByName("eigValues"); + if (eigValues.rows() != 3) // And check the dimensions + { + throw InvalidField("SphericalityDataPointsFilter: Error, the number of eigValues is not 3."); + } + + sphericality = cloud.getDescriptorViewByName("sphericality"); + if (keepUnstructureness) + unstructureness = cloud.getDescriptorViewByName("unstructureness"); + if (keepStructureness) + structureness = cloud.getDescriptorViewByName("structureness"); + + // Iterate through the point cloud and evaluate the Sphericality + for (size_t i = 0; i < pointsCount; ++i) + { + // extract the three eigenvalues relevant to the current point + Vector eig_vals_col = eigValues.col(i); + // might be already sorted but sort anyway + std::sort(eig_vals_col.data(),eig_vals_col.data()+eig_vals_col.size()); + + // Finally, evaluate the Sphericality + T sphericalityVal; + T unstructurenessVal; + T structurenessVal; + + // First, avoid division by zero + //TODO: Is there a more suitable limit for considering the values almost-zero? (VK) + if (eig_vals_col(2) < std::numeric_limits::min() || + eig_vals_col(1) < 0.0 || + eig_vals_col(0) < 0.0) + { + // If the largest eigenvalue is zero or even worse -- any of them is negative, + // these descriptors are not well defined (0/0 or nonsense input) and assigned NaN + sphericalityVal = std::numeric_limits::quiet_NaN(); + unstructurenessVal = std::numeric_limits::quiet_NaN(); + structurenessVal = std::numeric_limits::quiet_NaN(); + + } else if (eig_vals_col(1) < std::numeric_limits::min()) { + // If there are two zero eigenvalues and one non-zero, we assign zeros to the heuristic + sphericalityVal = 0.0; + unstructurenessVal = 0.0; + structurenessVal = 0.0; + + } else { + // Otherwise, follow eq.(1) from Kubelka V. et al., "Radio propagation models for differential GNSS based + // on dense point clouds", JFR, hopefully published in 2020 + unstructurenessVal = eig_vals_col(0) / eig_vals_col(2); + structurenessVal = (eig_vals_col(1) / eig_vals_col(2)) * + ((eig_vals_col(1) - eig_vals_col(0)) / sqrt(eig_vals_col(0)*eig_vals_col(0) + eig_vals_col(1)*eig_vals_col(1))); + sphericalityVal = unstructurenessVal - structurenessVal; + } + + // store it in the pointcloud + // sphericality always + (sphericality.get())(0,i) = sphericalityVal; + // these two only when requested by the user + if (unstructureness) + (unstructureness.get())(0,i) = unstructurenessVal; + if (structureness) + (structureness.get())(0,i) = structurenessVal; + + } +} + +template struct SphericalityDataPointsFilter; +template struct SphericalityDataPointsFilter; \ No newline at end of file diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Sphericality.h b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Sphericality.h new file mode 100644 index 0000000..457fa93 --- /dev/null +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/Sphericality.h @@ -0,0 +1,87 @@ +// kate: replace-tabs off; indent-width 4; indent-mode normal +// vim: ts=4:sw=4:noexpandtab +/* + +Copyright (c) 2010--2018, +François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland +You can contact the authors at and + + +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 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 ETH-ASL 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. + +*/ +#pragma once + +#include "PointMatcher.h" + +/* + The SphericalityDataPointFilter estimates a heuristic value which indicates how much local geometry around + a given point resemble a plane or a sphere (uniform distribution). The value can lie in <-1,1> interval, -1 for + perfect plane, 1 for perfectly uniform distribution. The estimation is based on three eigenvalues coming from another + data points filter (this filter can operate only on 3D data). In the case the largest eigenvalue is zero, the filter + outputs NaNs. If the middle eigenvalue is zero and the largest one is non-zero, the filter outputs zeros. + + Implemented by Vladimir Kubelka (kubelvla@gmail.com), NORLAB, Universite Laval, 2020 +*/ + +template +struct SphericalityDataPointsFilter: public PointMatcher::DataPointsFilter +{ + typedef PointMatcherSupport::Parametrizable Parametrizable; + typedef PointMatcherSupport::Parametrizable P; + typedef Parametrizable::Parameters Parameters; + typedef Parametrizable::ParameterDoc ParameterDoc; + typedef Parametrizable::ParametersDoc ParametersDoc; + typedef Parametrizable::InvalidParameter InvalidParameter; + + typedef typename PointMatcher::Vector Vector; + typedef typename PointMatcher::Matrix Matrix; + typedef typename PointMatcher::DataPoints DataPoints; + typedef typename PointMatcher::DataPoints::InvalidField InvalidField; + + inline static const std::string description() + { + return "This filter computes the level of ’sphericality’ for each point. It describes the shape of local geometry, whether the surrounding points resemble a plane (the sphericality value goes towards -1) or a uniform distribution (the value towards +1). It is intended for 3D point clouds only. Sphericality is computed by subtracting the intermediate values of ‘unstructureness’ and ‘structureness’.\n\n" + "Required descriptors: eigValues (must be three, otherwise exception).\n" + "Produced descritors: sphericality, unstructureness(optional), structureness(optional).\n" + "Altered descriptors: none.\n" + "Altered features: none."; + } + inline static const ParametersDoc availableParameters() + { + return { + {"keepUnstructureness", "whether the value of the unstructureness should be added to the pointcloud", "0"}, + {"keepStructureness", "whether the value of the structureness should be added to the pointcloud", "0"}, + }; + } + + const bool keepUnstructureness; + const bool keepStructureness; + + SphericalityDataPointsFilter(const Parameters& params = Parameters()); + virtual ~SphericalityDataPointsFilter() {}; + virtual DataPoints filter(const DataPoints& input); + virtual void inPlaceFilter(DataPoints& cloud); +}; diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SurfaceNormal.cpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SurfaceNormal.cpp index ea9661f..e14f4c0 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SurfaceNormal.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/SurfaceNormal.cpp @@ -44,13 +44,13 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include -#include "utils.h" +#include "DataPointsFilters/utils/utils.h" // SurfaceNormalDataPointsFilter // Constructor template SurfaceNormalDataPointsFilter::SurfaceNormalDataPointsFilter(const Parameters& params): - PointMatcher::DataPointsFilter("SurfaceNormalDataPointsFilter", + PointMatcher::DataPointsFilter("SurfaceNormalDataPointsFilter", SurfaceNormalDataPointsFilter::availableParameters(), params), knn(Parametrizable::get("knn")), maxDist(Parametrizable::get("maxDist")), @@ -68,7 +68,7 @@ SurfaceNormalDataPointsFilter::SurfaceNormalDataPointsFilter(const Parameters // Compute template -typename PointMatcher::DataPoints +typename PointMatcher::DataPoints SurfaceNormalDataPointsFilter::filter( const DataPoints& input) { @@ -87,7 +87,7 @@ void SurfaceNormalDataPointsFilter::inPlaceFilter( typedef typename DataPoints::Labels Labels; typedef typename MatchersImpl::KDTreeMatcher KDTreeMatcher; typedef typename PointMatcher::Matches Matches; - + using namespace PointMatcherSupport; const int pointsCount(cloud.features.cols()); @@ -154,7 +154,7 @@ void SurfaceNormalDataPointsFilter::inPlaceFilter( boost::assign::insert(param) ( "knn", toParam(knn) ); boost::assign::insert(param) ( "epsilon", toParam(epsilon) ); boost::assign::insert(param) ( "maxDist", toParam(maxDist) ); - + KDTreeMatcher matcher(param); matcher.init(cloud); @@ -184,7 +184,7 @@ void SurfaceNormalDataPointsFilter::inPlaceFilter( const Vector mean = d.rowwise().sum() / T(realKnn); const Matrix NN = d.colwise() - mean; - const Matrix C(NN * NN.transpose()); + const Matrix C((NN * NN.transpose()) / T(realKnn)); Vector eigenVa = Vector::Zero(featDim-1, 1); Matrix eigenVe = Matrix::Zero(featDim-1, featDim-1); // Ensure that the matrix is suited for eigenvalues calculation @@ -202,10 +202,10 @@ void SurfaceNormalDataPointsFilter::inPlaceFilter( const size_t idxSize = idx.size(); Vector tmp_eigenVa = eigenVa; Matrix tmp_eigenVe = eigenVe; - for(size_t i=0; i::inPlaceFilter( normals->col(i) = eigenVe.col(0); else normals->col(i) = computeNormal(eigenVa, eigenVe); + + // clamp normals to [-1,1] to handle approximation errors + normals->col(i) = normals->col(i).cwiseMax(-1.0).cwiseMin(1.0); } if(keepDensities) { @@ -245,7 +248,7 @@ void SurfaceNormalDataPointsFilter::inPlaceFilter( (*meanDists)(0, i) = (point - mean).norm(); } } - + } if(keepMatchedIds) diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/utils/sparsetv.h b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/utils/sparsetv.h new file mode 100644 index 0000000..d6f2719 --- /dev/null +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/utils/sparsetv.h @@ -0,0 +1,183 @@ +// kate: replace-tabs off; indent-width 4; indent-mode normal +// vim: ts=4:sw=4:noexpandtab +/* + +Copyright (c) 2010--2018 + +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 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 ETH-ASL 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. + +*/ +#pragma once + +#include "pointmatcher/PointMatcher.h" + +#include +#include + +#include + +/*! + * \class sparsetv.h + * \brief Tensor Voting framework for inference of structures + * + * \author Mathieu Labussiere () + * \date 27/07/2018 + * \version 0.1 + * + */ +//Sparse Tensor Voting +template +struct TensorVoting +{ +//--types + using PM = PointMatcher; + using DP = typename PM::DataPoints; + + using InvalidField = typename DP::InvalidField; + + using SparseTensor = Eigen::Matrix; // (saliency, ex,ey,ez) + using Tensor = Eigen::Matrix; + + using Field = Eigen::Matrix< Tensor, Eigen::Dynamic, 1>; + using Tensors = Eigen::Matrix< Tensor, Eigen::Dynamic, 1>; + using SparseTensors = Eigen::Matrix< SparseTensor, Eigen::Dynamic, 1>; + + using Vector3 = Eigen::Matrix; + using Matrix33 = Eigen::Matrix; + + using Matrix = typename PM::Matrix; + using Vector = typename PM::Vector; + + using NNS = Nabo::NearestNeighbourSearch; + using Index = typename NNS::Index; + using IndexMatrix = typename NNS::IndexMatrix; + + enum Encoding : std::uint8_t { ZERO, UBALL, BALL, SBALL, UPLATE, PLATE, SPLATE, USTICK, STICK, SSTICK, AWARE_TENSOR}; + +public: +//--attributes + const T sigma; //control the scale of the voting field + std::size_t k; //number of neighbors + + Tensors tensors; + + SparseTensors sparseStick; + SparseTensors sparsePlate; + SparseTensors sparseBall; + +public: +//--resulting descriptors + Matrix surfaceness; //surface saliency map (stick) + Matrix curveness; //curve saliency map (plate) + Matrix pointness; //junction saliency map (ball) + + Matrix normals; //normals (stick orientation) + Matrix tangents; //tangents (plate orientation) + + Matrix sticks; //(s,n) + Matrix plates; //(s,n1,n2) + Matrix balls; // (s) +private: +//knn + IndexMatrix indices; + Matrix dist; + +public: +//--ctor + TensorVoting(T sigma_ = T(0.2), std::size_t k_ = 50); +//--dtor + ~TensorVoting(); + +//--methods + +///Voting methods + void vote(const DP& pts); + void refine(const DP& pts); + + void encode(const DP& pts, Encoding encoding = Encoding::UBALL); + + void disableBallComponent(); + + void ballVote(const DP& pts, bool doKnn = true); + void stickVote(const DP& pts, bool doKnn = true); + void plateVote(const DP& pts, bool doKnn = true); + + void cfvote(const DP& pts, bool doKnn = true); + + void decompose(); + + void toDescriptors(); + +///Kernel methods + struct DecayFunction + { + static inline T sradial(const T z) + { + if(z < 3.) + return std::pow(z, 2) * std::pow(z - 3, 4) / 16.; + else + return 0.; + } + + static inline T radial(const T z) + { + return std::exp(-std::pow(z, 2)); + } + + static inline T angular(const T theta) + { + return std::pow(std::cos(theta), 8); + } + + /*************************************************************************** + * See Eq (1) in : + * G. Guy and G. Medioni, “Inference of surfaces, 3D curves, and junctions + * from sparse, noisy, 3D Data,” 1997. + **************************************************************************/ + static inline T diabolo(const T s, const T c, const T k, const T sigma) + { + return std::exp(-1. * std::pow(s, 2) / std::pow(sigma, 2) - c * std::pow(k, 2) ); + } + + /*************************************************************************** + * See Eq (1) and Eq (2) in : + * T.-P. Wu, S.-K. Yeung, J. Jia, C.-K. Tang, and G. Medioni, + * “A Closed-Form Solution to Tensor Voting: Theory and Applications,” 2016. + ***************************************************************************/ + static inline T eta(const T vv, const T sigma, const T vvn) + { + return cij(vv, sigma) * (1. - vvn * vvn); + } + + static inline T cij(const T vv, const T sigma) + { + return std::exp(- std::pow(vv, 2) / sigma); + } + }; +private: + void computeKnn(const DP& pts); +}; + +#include "sparsetv.hpp" diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/utils/sparsetv.hpp b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/utils/sparsetv.hpp new file mode 100644 index 0000000..b75e990 --- /dev/null +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/utils/sparsetv.hpp @@ -0,0 +1,526 @@ +// kate: replace-tabs off; indent-width 4; indent-mode normal +// vim: ts=4:sw=4:noexpandtab +/* + +Copyright (c) 2010--2018 + +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 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 ETH-ASL 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 "and", "or", "not" macros +#include + +//--ctor +template +TensorVoting::TensorVoting(T sigma_, std::size_t k_) : sigma{sigma_}, k{k_} +{ +} +//--dtor +template +TensorVoting::~TensorVoting(){} + +//--methods + +///Voting methods +template +void TensorVoting::vote(const DP& pts) +{ + refine(pts); +} + +template +void TensorVoting::encode(const DP& pts, Encoding encoding) +{ + const std::size_t nbPts = pts.getNbPoints(); + tensors.resize(nbPts, 1); + + switch(encoding) + { + case Encoding::ZERO: + { +#pragma omp parallel for + for(std::size_t i = 0; i < nbPts; ++i) + tensors(i) = Tensor::Zero(); + break; + } +//------ + case Encoding::UBALL: + case Encoding::BALL: + { +#pragma omp parallel for + for(std::size_t i = 0; i < nbPts; ++i) + tensors(i) = Tensor::Identity(); + break; + } + case Encoding::SBALL: + { + //Check if there is plates info + if (not pts.descriptorExists("balls")) + throw InvalidField("TensorVoting::encode: Error, cannot find balls in descriptors."); + + const auto& balls_ = pts.getDescriptorViewByName("balls"); +#pragma omp parallel for + for(std::size_t i = 0; i < nbPts; ++i) + tensors(i) = Tensor::Identity() * balls_(0,i); + + break; + } +//------ + case Encoding::UPLATE: + { +#pragma omp parallel for + for(std::size_t i = 0; i < nbPts; ++i) + tensors(i) << + 1., 0., 0., + 0., 1., 0., + 0., 0., 0.; + break; + } + case Encoding::PLATE: + case Encoding::SPLATE: + { + //Check if there is plates info + if (not pts.descriptorExists("plates")) + throw InvalidField("TensorVoting::encode: Error, cannot find plates in descriptors."); + + const auto& plates_ = pts.getDescriptorViewByName("plates"); +#pragma omp parallel for + for(std::size_t i = 0; i < nbPts; ++i) + { + const Vector3 n1 = plates_.col(i).segment(1,3); + const Vector3 n2 = plates_.col(i).tail(3); + + tensors(i) = (encoding == Encoding::SPLATE ? plates_(0,i) : 1.) * (n1 * n1.transpose() + n2 * n2.transpose()); + } + break; + } +//------ + case Encoding::USTICK: + { +#pragma omp parallel for + for(std::size_t i = 0; i < nbPts; ++i) + tensors(i) << + 1., 0., 0., + 0., 0., 0., + 0., 0., 0.; + break; + } + case Encoding::STICK: + case Encoding::SSTICK: + { + //Check if there is normals info + if (not pts.descriptorExists("sticks")) + throw InvalidField("TensorVoting::encode: Error, cannot find sticks in descriptors."); + + const auto& sticks_ = pts.getDescriptorViewByName("sticks"); +#pragma omp parallel for + for(std::size_t i = 0; i < nbPts; ++i) + { + const Vector3 n = sticks_.col(i).tail(3); + tensors(i) = (encoding == Encoding::SSTICK ? sticks_(0,i) : 1.) * (n * n.transpose()); + } + break; + } +//------ + case Encoding::AWARE_TENSOR: + { + //Check if there is normals info + if (not pts.descriptorExists("sticks")) + throw InvalidField("TensorVoting::encode: Error, cannot find sticks in descriptors."); + //Check if there is normals info + if (not pts.descriptorExists("plates")) + throw InvalidField("TensorVoting::encode: Error, cannot find plates in descriptors."); + + const auto& sticks_ = pts.getDescriptorViewByName("sticks"); + const auto& plates_ = pts.getDescriptorViewByName("plates"); +#pragma omp parallel for + for(std::size_t i = 0; i < nbPts; ++i) + { + const Tensor S = sticks_.col(i).tail(3) * sticks_.col(i).tail(3).transpose(); + const Tensor P = plates_.col(i).segment(1,3) * plates_.col(i).segment(1,3).transpose() + plates_.col(i).tail(3) * plates_.col(i).tail(3).transpose(); + + tensors(i) = (sticks_(0,i) / k) * S + (plates_(0,i) / k) * P; + } + break; + } + } +} + +template +void TensorVoting::disableBallComponent() +{ + const std::size_t nbPts = tensors.rows(); +#pragma omp parallel for + for(std::size_t i = 0; i < nbPts; ++i) + { + const Tensor S = sticks.col(i).tail(3) * sticks.col(i).tail(3).transpose(); + const Tensor P = plates.col(i).segment(1,3) * plates.col(i).segment(1,3).transpose() + plates.col(i).tail(3) * plates.col(i).tail(3).transpose(); + + tensors(i) = (sticks(0,i) / k) * S + (plates(0,i) / k) * P; + } +} + +template +void TensorVoting::refine(const DP& pts) +{ + //pts = input token (x,y,z) + // | + encode(pts); + // | + //tensors = unit ball tensors token (sparse) + // | + ballVote(pts, true); + // | + //tensors = generic 2nd order tensors refined tokens (sparse) + // | + decompose(); + // | + //sparseStick = tensors (saliency, nx, ny, nz) + //sparsePlate = tensors (saliency, tx, ty, tz) + //sparseBall = tensors (saliency, 0, 0, 0) + // | + toDescriptors(); +} + +/************ Ball Vote ******************************************************** + * The ball vote can be constructed by subtracting the direct product of + * the tangent vector from a full rank tensor with equal eigenvalues + * (i.e. the identity matrix). The resulting tensor is attenuated by the same + * Gaussian weight according to the distance between the voter and the receiver + ******************************************************************************/ +template +void TensorVoting::ballVote(const DP& pts, bool doKnn) +{ + const std::size_t nbPts = pts.getNbPoints(); + + const Tensor I = Tensor::Identity(); + + if(doKnn) computeKnn(pts); + + for(std::size_t voter = 0; voter < nbPts; ++voter) + { + for(std::size_t j = 0; j < k ; j++) + { + Index votee = indices(j,voter); + + if(votee == NNS::InvalidIndex) break; + if(votee == Index(voter)) continue; + + const Vector3 v = pts.features.col(votee).head(3) - pts.features.col(voter).head(3); + const T normDist = v.norm()/sigma; + + if(normDist > 0. and normDist < 3.) //if not too far + { + const Tensor vv = v * v.transpose(); //outer product for projection in direction of voter + const T normVv = vv.norm(); //frobenius norm + if(normVv > 0.) + { + //accumulate vote a votee location with decay function weighting voter vote + const Tensor acc = tensors(votee) + DecayFunction::sradial(normDist) * (I - vv / normVv); + tensors(votee) = acc; + } + } + } + } +} + + +template +void TensorVoting::stickVote(const DP& pts, bool doKnn) +{ + //Check if there is normals info + if (not pts.descriptorExists("sticks")) + throw InvalidField("TensorVoting::stickVote: Error, cannot find sticks in descriptors."); + + const auto& sticks_ = pts.getDescriptorViewByName("sticks"); + + const std::size_t nbPts = pts.getNbPoints(); + + if(doKnn) computeKnn(pts); + + for(std::size_t voter = 0; voter < nbPts; ++voter) + { + Vector3 vn = sticks_.col(voter).tail(3).normalized(); //normal + const Vector3 O = pts.features.col(voter).head(3); //voter coord + + for(std::size_t j = 0; j < k ; j++) + { + Index votee = indices(j,voter); + + if(votee == NNS::InvalidIndex) break; + if(votee == Index(voter)) continue; + + Vector3 v = pts.features.col(votee).head(3) - O; // v = P - O + + const T normDist = v.norm()/sigma; + + if(normDist > 0. and normDist < 3.) //if not too far + { + v.normalize(); + + const T vvn = v.dot(vn); // size of point + if(vvn < 0.) vn *= -1.; //reorient normal + + const T theta = std::asin(vvn); //sepatation angle votee--voter along tangent in [- PI/2; PI/2] + + //cast vote only if smaller than 45deg + if (std::fabs(theta) <= M_PI / 4. or std::fabs(theta) >= 3. * M_PI / 4.) + { + //get tangent vector to osculating circle + Vector3 vt = vn.cross(v.cross(vn)).normalized(); + + const T vvt = v.dot(vt); // size of point + if(vvt < 0.) vt *= -1.; //reorient tangent + + //most likely normal at P + const Vector3 vc = vn * std::cos(2. * theta) - vt * std::sin(2. * theta); //vote cast + + //accumulate vote a votee location with decay function weighting voter vote + const Tensor acc = tensors(votee) + sticks_(0, voter) * DecayFunction::eta(normDist * sigma, sigma, vvn) * (vc * vc.transpose()); + tensors(votee) = acc; + } + } + } + } +} + +//FIXME: not sure of the implementation... +template +void TensorVoting::plateVote(const DP& pts, bool doKnn) +{ + //Check if there is normals info + if (not pts.descriptorExists("plates")) + throw InvalidField("TensorVoting::stickVote: Error, cannot find plates in descriptors."); + + const auto& plates_ = pts.getDescriptorViewByName("plates"); + + const std::size_t nbPts = pts.getNbPoints(); + + if(doKnn) computeKnn(pts); + + for(std::size_t voter = 0; voter < nbPts; ++voter) + { + Matrix U(3,2); U << plates_.col(voter).segment(1,3), plates_.col(voter).tail(3); + const Matrix Ns = U*U.transpose(); //normalspace + + for(std::size_t d = 0; d <= 1 ; ++d) + { + Vector3 vn = Ns.col(d).normalized(); //vector basis in normal space + const Vector3 O = pts.features.col(voter).head(3); //voter coord + + for(std::size_t j = 0; j < k ; j++) + { + Index votee = indices(j,voter); + + if(votee == NNS::InvalidIndex) break; + if(votee == Index(voter)) continue; + + Vector3 v = pts.features.col(votee).head(3) - O; // v = P - O + + const T normDist = v.norm()/sigma; + + if(normDist > 0. and normDist < 3.) //if not too far + { + v.normalize(); + + const T vvn = v.dot(vn); // size of point + if(vvn < 0.) vn *= -1.; //reorient normal + + const T theta = std::asin(vvn); //sepatation angle voter--votee + + //cast vote only if smaller than 45deg + if (std::fabs(theta) <= M_PI / 4. or std::fabs(theta) >= 3. * M_PI / 4.) + { + //get tangent vector to osculating circle + Vector3 vt = vn.cross(v.cross(vn)).normalized(); + + const T vvt = v.dot(vt); // size of point + if(vvt < 0.) vt *= -1.; //reorient tangent + + const Vector3 vc = vn * std::cos(2. * theta) - vt * std::sin(2. * theta); //vote cast + + //accumulate vote a votee location with decay function weighting voter vote + const Tensor acc = tensors(votee) + plates_(0, voter) * DecayFunction::eta(normDist*sigma, sigma, vvn) * (vc * vc.transpose()); + tensors(votee) = acc; + } + } + } + } + } +} + +/******************************************************************************* + * See Eq (11) in: + * T.-P. Wu, S.-K. Yeung, J. Jia, C.-K. Tang, and G. Medioni, + * “A Closed-Form Solution to Tensor Voting: Theory and Applications,” 2016. + ******************************************************************************/ +template +void TensorVoting::cfvote(const DP& pts, bool doKnn) +{ + const std::size_t nbPts = pts.getNbPoints(); + + if(doKnn) computeKnn(pts); + + const Tensors K = tensors; //save old tensors values + encode(pts, Encoding::ZERO); //all tensors are zero + +#pragma omp parallel for + for(std::size_t votee = 0; votee < nbPts; ++votee) //vote sites + { + const Vector3 x_i = pts.features.col(votee).head(3); + + for(std::size_t j = 0; j < k ; j++) //voters + { + const Index voter = indices(j,votee); //get voter at site Xi + + if(voter == NNS::InvalidIndex) continue; + if(voter == Index(votee)) continue; + + const Vector3 x_j = pts.features.col(voter).head(3); + Vector3 r_ij = x_i - x_j; + + const T normDist = r_ij.norm() / sigma; + + if(normDist > 0. and normDist < 3.) //if not too far + { + r_ij.normalize(); + + const Tensor rrt = r_ij * r_ij.transpose(); + const Tensor R_ij = (Tensor::Identity() - 2. * rrt); + const Tensor Rp_ij = (Tensor::Identity() - .5 * rrt) * R_ij; + const T c_ij = DecayFunction::cij((x_i - x_j).norm(), sigma); + + //accumulate vote a voter location with decay function weighting voter vote + const Tensor S_ij = c_ij * R_ij * K(voter) * Rp_ij; + + const Tensor acc = tensors(votee) + S_ij; + tensors(votee) = acc; + } + } + } +} + +template +void TensorVoting::decompose() +{ + const std::size_t nbPts = tensors.rows(); + + sparseStick.resize(nbPts); + sparsePlate.resize(nbPts); + sparseBall.resize(nbPts); + +#pragma omp parallel for + for(std::size_t i = 0; i < nbPts; ++i) + { + Eigen::SelfAdjointEigenSolver solver(tensors(i)); + + const Matrix33 eigenVe = solver.eigenvectors(); + const Vector3 eigenVa = solver.eigenvalues().array().abs(); + + // lambda1 > lambda2 > lambda3 > 0 + int lambda1_idx; const T lambda1 = eigenVa.maxCoeff(&lambda1_idx); + int lambda3_idx; const T lambda3 = eigenVa.minCoeff(&lambda3_idx); + const int lambda2_idx = (0+1+2) - (lambda1_idx + lambda3_idx); + const T lambda2 = eigenVa(lambda2_idx); + + const T norm = 1; + + if(not (lambda1 >= lambda2 and lambda2 >= lambda3) or lambda2_idx > 2. or lambda2_idx < 0.) + { + sparseStick(i) << 0.0001,0.,0.,0.; + sparsePlate(i) << 0.0001,0.,0.,0.; + sparseBall(i) << 0.0001,0.,0.,0.; + + //std::cerr << "Warning: eigen values not ordered ("< +void TensorVoting::toDescriptors() +{ + const std::size_t nbPts = tensors.rows(); + + pointness = PM::Matrix::Zero(1, nbPts); + curveness = PM::Matrix::Zero(1, nbPts); + surfaceness = PM::Matrix::Zero(1, nbPts); + + normals = PM::Matrix::Zero(3, nbPts); + tangents = PM::Matrix::Zero(3, nbPts); + + sticks = PM::Matrix::Zero(4, nbPts); + plates = PM::Matrix::Zero(7, nbPts); + balls = PM::Matrix::Zero(1, nbPts); + +#pragma omp parallel for + for(std::size_t i = 0; i < nbPts; i++) + { + surfaceness(i) = sparseStick(i)(0) / k; + curveness(i) = sparsePlate(i)(0) / k; + pointness(i) = sparseBall(i)(0) / k; + + normals.col(i) = sparseStick(i).tail(3); + tangents.col(i) = sparsePlate(i).tail(3); + + sticks.col(i) = sparseStick(i); //s + e1 + + plates(0,i) = sparsePlate(i)(0); //s + plates.col(i).segment(1,3) = sparseStick(i).tail(3); //e1 + plates.col(i).tail(3) = sparseBall(i).tail(3); //e2 + + balls(i) = sparseBall(i)(0); //s + } +} + +template +void TensorVoting::computeKnn(const DP& pts) +{ + const std::size_t nbPts = pts.getNbPoints(); + + if(k >= nbPts) k = nbPts - 1; + + std::shared_ptr knn( + NNS::create(pts.features, pts.features.rows() - 1, + (k<30? NNS::SearchType::KDTREE_LINEAR_HEAP : NNS::SearchType::KDTREE_TREE_HEAP) + ) + ); + + indices = IndexMatrix::Zero(k, nbPts); + dist = Matrix::Zero(k, nbPts); + + knn->knn(pts.features, indices, dist, Index(k)); +} diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/utils/utils.h b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/utils/utils.h index 954e113..58fe8f0 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/utils/utils.h +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFilters/utils/utils.h @@ -62,7 +62,7 @@ struct IdxCompare template -std::vector +std::vector sortIndexes(const typename PointMatcher::Vector& v) { // initialize original index locations @@ -87,17 +87,15 @@ sortEigenValues(const typename PointMatcher::Vector& eigenVa) } template -typename PointMatcher::Vector +typename PointMatcher::Vector serializeEigVec(const typename PointMatcher::Matrix& eigenVe) { - // serialize row major + // Serialize the eigen vectors column major const int eigenVeDim = eigenVe.cols(); typename PointMatcher::Vector output(eigenVeDim*eigenVeDim); - for(int k=0; k < eigenVeDim; ++k) - { - output.segment(k*eigenVeDim, eigenVeDim) = - eigenVe.row(k).transpose(); - } + + for (int k = 0; k < eigenVeDim; ++k) + output.segment(k * eigenVeDim, eigenVeDim) = eigenVe.col(k); return output; } diff --git a/thirdparty/libpointmatcher/pointmatcher/DataPointsFiltersImpl.h b/thirdparty/libpointmatcher/pointmatcher/DataPointsFiltersImpl.h index 022452b..8f66129 100644 --- a/thirdparty/libpointmatcher/pointmatcher/DataPointsFiltersImpl.h +++ b/thirdparty/libpointmatcher/pointmatcher/DataPointsFiltersImpl.h @@ -62,6 +62,9 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include "DataPointsFilters/CovarianceSampling.h" #include "DataPointsFilters/DistanceLimit.h" #include "DataPointsFilters/RemoveSensorBias.h" +#include "DataPointsFilters/Sphericality.h" +#include "DataPointsFilters/Saliency.h" +#include "DataPointsFilters/SpectralDecomposition.h" template struct DataPointsFiltersImpl @@ -92,7 +95,9 @@ struct DataPointsFiltersImpl typedef ::CovarianceSamplingDataPointsFilter CovarianceSamplingDataPointsFilter; typedef ::DistanceLimitDataPointsFilter DistanceLimitDataPointsFilter; typedef ::RemoveSensorBiasDataPointsFilter RemoveSensorBiasDataPointsFilter; - + typedef ::SphericalityDataPointsFilter SphericalityDataPointsFilter; + typedef ::SaliencyDataPointsFilter SaliencyDataPointsFilter; + typedef ::SpectralDecompositionDataPointsFilter SpectralDecompositionDataPointsFilter; }; // DataPointsFiltersImpl #endif // __POINTMATCHER_DATAPOINTSFILTERS_H diff --git a/thirdparty/libpointmatcher/pointmatcher/ErrorMinimizers/PointToPlane.cpp b/thirdparty/libpointmatcher/pointmatcher/ErrorMinimizers/PointToPlane.cpp index 41f4589..590d7b4 100644 --- a/thirdparty/libpointmatcher/pointmatcher/ErrorMinimizers/PointToPlane.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/ErrorMinimizers/PointToPlane.cpp @@ -53,17 +53,55 @@ typedef Parametrizable::ParametersDoc ParametersDoc; template PointToPlaneErrorMinimizer::PointToPlaneErrorMinimizer(const Parameters& params): ErrorMinimizer(name(), availableParameters(), params), - force2D(Parametrizable::get("force2D")) + force2D(Parametrizable::get("force2D")), + force4DOF(Parametrizable::get("force4DOF")) { - LOG_INFO_STREAM("PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 2D."); + if(force2D) + { + if (force4DOF) + { + throw PointMatcherSupport::ConfigurationError("Force 2D cannot be used together with force4DOF."); + } + else + { + LOG_INFO_STREAM("PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 2D."); + } + } + else if(force4DOF) + { + LOG_INFO_STREAM("PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 4-DOF (yaw,x,y,z)."); + } + else + { + LOG_INFO_STREAM("PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 3D."); + } } template PointToPlaneErrorMinimizer::PointToPlaneErrorMinimizer(const ParametersDoc paramsDoc, const Parameters& params): ErrorMinimizer(name(), paramsDoc, params), - force2D(Parametrizable::get("force2D")) + force2D(Parametrizable::get("force2D")), + force4DOF(Parametrizable::get("force4DOF")) { - LOG_INFO_STREAM("PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 2D."); + if(force2D) + { + if (force4DOF) + { + throw PointMatcherSupport::ConfigurationError("Force 2D cannot be used together with force4DOF."); + } + else + { + LOG_INFO_STREAM("PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 2D."); + } + } + else if(force4DOF) + { + LOG_INFO_STREAM("PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 4-DOF (yaw,x,y,z)."); + } + else + { + LOG_INFO_STREAM("PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 3D."); + } } @@ -154,7 +192,23 @@ typename PointMatcher::TransformationParameters PointToPlaneErrorMinimizer assert(normalRef.rows() > 0); // Compute cross product of cross = cross(reading X normalRef) - const Matrix cross = this->crossProduct(mPts.reading.features, normalRef); + Matrix cross; + Matrix matrixGamma(3,3); + if(!force4DOF) + { + // Compute cross product of cross = cross(reading X normalRef) + cross = this->crossProduct(mPts.reading.features, normalRef); + } + else + { + //VK: Instead for "cross" as in 3D, we need only a dot product with the matrixGamma factor for 4DOF + //VK: This should be published in 2020 or 2021 + matrixGamma << 0,-1, 0, + 1, 0, 0, + 0, 0, 0; + cross = ((matrixGamma*mPts.reading.features.block(0, 0, 3, nbPts)).transpose()*normalRef).diagonal().transpose(); + } + // wF = [weights*cross, weights*normals] // F = [cross, normals] @@ -203,14 +257,30 @@ typename PointMatcher::TransformationParameters PointToPlaneErrorMinimizer * Eigen::AngleAxis(x(1), Eigen::Matrix::UnitY()) * Eigen::AngleAxis(x(2), Eigen::Matrix::UnitZ());*/ - transform = Eigen::AngleAxis(x.head(3).norm(),x.head(3).normalized()); + // Normal 6DOF takes the whole rotation vector from the solution to construct the output quaternion + if (!force4DOF) + { + transform = Eigen::AngleAxis(x.head(3).norm(), x.head(3).normalized()); //x=[alpha,beta,gamma,x,y,z] + } else // 4DOF needs only one number, the rotation around the Z axis + { + Vector unitZ(3,1); + unitZ << 0,0,1; + transform = Eigen::AngleAxis(x(0), unitZ); //x=[gamma,x,y,z] + } // Reverse roll-pitch-yaw conversion, very useful piece of knowledge, keep it with you all time! /*const T pitch = -asin(transform(2,0)); const T roll = atan2(transform(2,1), transform(2,2)); const T yaw = atan2(transform(1,0) / cos(pitch), transform(0,0) / cos(pitch)); std::cerr << "d angles" << x(0) - roll << ", " << x(1) - pitch << "," << x(2) - yaw << std::endl;*/ - transform.translation() = x.segment(3, 3); + if (!force4DOF) + { + transform.translation() = x.segment(3, 3); //x=[alpha,beta,gamma,x,y,z] + } else + { + transform.translation() = x.segment(1, 3); //x=[gamma,x,y,z] + } + mOut = transform.matrix(); if (mOut != mOut) @@ -371,7 +441,7 @@ T PointToPlaneErrorMinimizer::getOverlap() const { // NOTE: we tried with the projected distance over the normal vector before: // projectionDist = delta dotProduct n.normalized() - // but this doesn't make sense + // but this doesn't make sense if(PointMatcherSupport::anyabs(dists(i, 0)) < (uncertainties(0,i))) diff --git a/thirdparty/libpointmatcher/pointmatcher/ErrorMinimizers/PointToPlane.h b/thirdparty/libpointmatcher/pointmatcher/ErrorMinimizers/PointToPlane.h index 52a690f..0fb6464 100644 --- a/thirdparty/libpointmatcher/pointmatcher/ErrorMinimizers/PointToPlane.h +++ b/thirdparty/libpointmatcher/pointmatcher/ErrorMinimizers/PointToPlane.h @@ -69,11 +69,14 @@ struct PointToPlaneErrorMinimizer: public PointMatcher::ErrorMinimizer inline static const ParametersDoc availableParameters() { return { - {"force2D", "If set to true(1), the minimization will be force to give a solution in 2D (i.e., on the XY-plane) even with 3D inputs.", "0", "0", "1", &P::Comp} - }; + {"force2D", "If set to true(1), the minimization will be forced to give a solution in 2D (i.e., on the XY-plane) even with 3D inputs.", "0", "0", "1", &P::Comp}, + {"force4DOF", "If set to true(1), the minimization will optimize only yaw and translation, pitch and roll will follow the prior.", "0", "0", "1", &P::Comp} + + }; } const bool force2D; + const bool force4DOF; PointToPlaneErrorMinimizer(const Parameters& params = Parameters()); PointToPlaneErrorMinimizer(const ParametersDoc paramsDoc, const Parameters& params); diff --git a/thirdparty/libpointmatcher/pointmatcher/ErrorMinimizers/PointToPlaneWithCov.h b/thirdparty/libpointmatcher/pointmatcher/ErrorMinimizers/PointToPlaneWithCov.h index f37dc04..caac4a8 100644 --- a/thirdparty/libpointmatcher/pointmatcher/ErrorMinimizers/PointToPlaneWithCov.h +++ b/thirdparty/libpointmatcher/pointmatcher/ErrorMinimizers/PointToPlaneWithCov.h @@ -64,13 +64,14 @@ struct PointToPlaneWithCovErrorMinimizer: public PointToPlaneErrorMinimizer inline static const std::string description() { - return "Point-to-plane error (or point-to-line in 2D). Based on \\cite{Chen1991Point2Plane}. Covariance estimation based on \\cite{Censi2007ICPCovariance}."; + return "Point-to-plane error (or point-to-line in 2D). Based on \\cite{Chen1991Point2Plane}. Covariance estimation based on \\cite{Censi2007ICPCovariance}. Implementation based on \\cite{Prakhya2015Point2Plane}."; } static inline const ParametersDoc availableParameters() { return { {"force2D", "If set to true(1), the minimization will be force to give a solution in 2D (i.e., on the XY-plane) even with 3D inputs.", "0", "0", "1", &P::Comp}, + {"force4DOF", "If set to true(1), the minimization will optimize only yaw and translation, pitch and roll will follow the prior.", "0", "0", "1", &P::Comp}, {"sensorStdDev", "sensor standard deviation", "0.01", "0.", "inf", &P::Comp} }; } diff --git a/thirdparty/libpointmatcher/pointmatcher/Exceptions.cpp b/thirdparty/libpointmatcher/pointmatcher/Exceptions.cpp index 9023b63..6fdae58 100644 --- a/thirdparty/libpointmatcher/pointmatcher/Exceptions.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/Exceptions.cpp @@ -41,7 +41,11 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. template PointMatcher::ConvergenceError::ConvergenceError(const std::string& reason): runtime_error(reason) -{} +{} + +PointMatcherSupport::ConfigurationError::ConfigurationError(const std::string& reason): + runtime_error(reason) +{} template struct PointMatcher::ConvergenceError; template struct PointMatcher::ConvergenceError; diff --git a/thirdparty/libpointmatcher/pointmatcher/Histogram.cpp b/thirdparty/libpointmatcher/pointmatcher/Histogram.cpp index 26e05d6..97728f8 100644 --- a/thirdparty/libpointmatcher/pointmatcher/Histogram.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/Histogram.cpp @@ -32,6 +32,7 @@ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ +#include "PointMatcherPrivate.h" #include "Histogram.h" @@ -68,13 +69,13 @@ namespace PointMatcherSupport if (!filePrefix.empty()) { - std::cerr << "writing to " << (filePrefix + name + "Stats.csv") << std::endl; + LOG_INFO_STREAM("writing to " << (filePrefix + name + "Stats.csv")); std::ofstream ofs_stats((filePrefix + name + "Stats.csv").c_str()); dumpStatsHeader(ofs_stats); ofs_stats << endl; dumpStats(ofs_stats); - std::cerr << "writing to " << (filePrefix + name + ".csv") << std::endl; + LOG_INFO_STREAM("writing to " << (filePrefix + name + ".csv")); std::ofstream ofs((filePrefix + name + ".csv").c_str()); for (size_t i = 0; i < this->size(); ++i) ofs << ((*this)[i]) << "\n"; @@ -146,14 +147,15 @@ namespace PointMatcherSupport } varV /= T(this->size()); // median - const Iterator lowQtIt(this->begin() + (this->size() / 4)); - const Iterator medianIt(this->begin() + (this->size() / 2)); - const Iterator highQtIt(this->begin() + (3*this->size() / 4)); - std::nth_element(this->begin(), medianIt, this->end()); + std::vector hystCpy((*this)); + const Iterator lowQtIt(hystCpy.begin() + (hystCpy.size() / 4)); + const Iterator medianIt(hystCpy.begin() + (hystCpy.size() / 2)); + const Iterator highQtIt(hystCpy.begin() + (3*hystCpy.size() / 4)); + std::nth_element(hystCpy.begin(), medianIt, hystCpy.end()); medianV = *medianIt; - std::nth_element(this->begin(), lowQtIt, this->end()); + std::nth_element(hystCpy.begin(), lowQtIt, hystCpy.end()); lowQt = *lowQtIt; - std::nth_element(this->begin(), highQtIt, this->end()); + std::nth_element(hystCpy.begin(), highQtIt, hystCpy.end()); highQt = *highQtIt; } else diff --git a/thirdparty/libpointmatcher/pointmatcher/ICP.cpp b/thirdparty/libpointmatcher/pointmatcher/ICP.cpp index 7757589..adc119c 100644 --- a/thirdparty/libpointmatcher/pointmatcher/ICP.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/ICP.cpp @@ -420,7 +420,7 @@ typename PointMatcher::TransformationParameters PointMatcher::ICP::compute { this->transformationCheckers.check(T_iter, iterate); } - catch(const typename TransformationCheckersImpl::CounterTransformationChecker::MaxNumIterationsReached & e) + catch(const typename TransformationCheckersImpl::CounterTransformationChecker::MaxNumIterationsReached &) { iterate = false; this->maxNumIterationsReached = true; @@ -516,6 +516,28 @@ void PointMatcher::ICPSequence::clearMap() mapPointCloud = DataPoints(); } +template +void PointMatcher::ICPSequence::setDefault() +{ + ICPChainBase::setDefault(); + + if(mapPointCloud.getNbPoints() > 0) + { + this->matcher->init(mapPointCloud); + } +} + +template +void PointMatcher::ICPSequence::loadFromYaml(std::istream& in) +{ + ICPChainBase::loadFromYaml(in); + + if(mapPointCloud.getNbPoints() > 0) + { + this->matcher->init(mapPointCloud); + } +} + //! Return the map, in global coordinates (slow) template const typename PointMatcher::DataPoints PointMatcher::ICPSequence::getPrefilteredMap() const diff --git a/thirdparty/libpointmatcher/pointmatcher/IO.cpp b/thirdparty/libpointmatcher/pointmatcher/IO.cpp index a67ccd4..c4288c9 100644 --- a/thirdparty/libpointmatcher/pointmatcher/IO.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/IO.cpp @@ -1401,7 +1401,7 @@ typename PointMatcherIO::DataPoints PointMatcherIO::loadPLY(std::istream& { elem_num = boost::lexical_cast(elem_num_s); } - catch (boost::bad_lexical_cast& e) + catch (boost::bad_lexical_cast&) { throw runtime_error(string("PLY parse error: bad number of elements ") + elem_num_s + string(" for element ") + elem_name); } @@ -1780,9 +1780,9 @@ template class PointMatcherIO::PLYElement; template -class PointMatcherIO::PLYProperty; +struct PointMatcherIO::PLYProperty; template -class PointMatcherIO::PLYProperty; +struct PointMatcherIO::PLYProperty; template @@ -1983,7 +1983,7 @@ typename PointMatcherIO::DataPoints PointMatcherIO::loadPCD(std::istream& { header.width = boost::lexical_cast(tokens[1]); } - catch (boost::bad_lexical_cast& e) + catch (boost::bad_lexical_cast&) { throw runtime_error("PCD Parse Error: invalid WIDTH"); } @@ -1996,7 +1996,7 @@ typename PointMatcherIO::DataPoints PointMatcherIO::loadPCD(std::istream& { header.height= boost::lexical_cast(tokens[1]); } - catch (boost::bad_lexical_cast& e) + catch (boost::bad_lexical_cast&) { throw runtime_error("PCD Parse Error: invalid HEIGHT"); } @@ -2014,7 +2014,7 @@ typename PointMatcherIO::DataPoints PointMatcherIO::loadPCD(std::istream& { header.viewPoint(i-1, 0) = boost::lexical_cast(tokens[i]); } - catch (boost::bad_lexical_cast& e) + catch (boost::bad_lexical_cast&) { stringstream ss; ss << "PCD Parse Error: invalid value(" << tokens[i] << ") of VIEWPOINT"; @@ -2030,7 +2030,7 @@ typename PointMatcherIO::DataPoints PointMatcherIO::loadPCD(std::istream& { header.nbPoints = boost::lexical_cast(tokens[1]); } - catch (boost::bad_lexical_cast& e) + catch (boost::bad_lexical_cast&) { stringstream ss; ss << "PCD Parse Error: the value in the element POINTS (" << tokens[1] << ") could not be cast as unsigned int"; diff --git a/thirdparty/libpointmatcher/pointmatcher/Matches.cpp b/thirdparty/libpointmatcher/pointmatcher/Matches.cpp index 4df57c7..8b0c6c6 100644 --- a/thirdparty/libpointmatcher/pointmatcher/Matches.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/Matches.cpp @@ -73,11 +73,11 @@ T PointMatcher::Matches::getDistsQuantile(const T quantile) const } } } - if (values.size() == 0) - throw ConvergenceError("no outlier to filter"); + if (values.empty()) + throw ConvergenceError("No matches available for computing distance quantiles"); if (quantile < 0.0 || quantile > 1.0) - throw ConvergenceError("quantile must be between 0 and 1"); + throw ConvergenceError("Distance quantile of matches must lie in the range [0,1]"); // get quantile if (quantile == 1.0) @@ -105,7 +105,7 @@ T PointMatcher::Matches::getMedianAbsDeviation() const } } if (values.size() == 0) - throw ConvergenceError("no outlier to filter"); + throw ConvergenceError("[getMedianAbsDeviation] no outlier to filter"); nth_element(values.begin(), values.begin() + (values.size() / 2), values.end()); const T median = values[values.size() / 2]; diff --git a/thirdparty/libpointmatcher/pointmatcher/OutlierFiltersImpl.cpp b/thirdparty/libpointmatcher/pointmatcher/OutlierFiltersImpl.cpp index a08f3b1..5dc0b24 100644 --- a/thirdparty/libpointmatcher/pointmatcher/OutlierFiltersImpl.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/OutlierFiltersImpl.cpp @@ -181,9 +181,9 @@ T OutlierFiltersImpl::VarTrimmedDistOutlierFilter::optimizeInlierRatio(const { typedef typename PointMatcher::ConvergenceError ConvergenceError; typedef typename Eigen::Array LineArray; - + const int points_nbr = matches.dists.rows() * matches.dists.cols(); - + // vector containing the squared distances of the matches std::vector tmpSortedDist; tmpSortedDist.reserve(points_nbr); @@ -191,9 +191,9 @@ T OutlierFiltersImpl::VarTrimmedDistOutlierFilter::optimizeInlierRatio(const for (int y = 0; y < matches.dists.rows(); ++y) if ((matches.dists(y, x) != numeric_limits::infinity()) && (matches.dists(y, x) > 0)) tmpSortedDist.push_back(matches.dists(y, x)); - if (tmpSortedDist.size() == 0) - throw ConvergenceError("no outlier to filter"); - + if (tmpSortedDist.empty()) + throw ConvergenceError("Inlier ratio optimization failed due to absence of matches"); + std::sort(tmpSortedDist.begin(), tmpSortedDist.end()); std::vector tmpCumSumSortedDist; tmpCumSumSortedDist.reserve(points_nbr); @@ -215,7 +215,7 @@ T OutlierFiltersImpl::VarTrimmedDistOutlierFilter::optimizeInlierRatio(const int minIndex(0);// = FRMS.minCoeff(); FRMS.minCoeff(&minIndex); const T optRatio = (float)(minIndex + minEl)/ (float)points_nbr; - + return optRatio; } @@ -240,7 +240,7 @@ typename PointMatcher::OutlierWeights OutlierFiltersImpl::SurfaceNormalOut { const BOOST_AUTO(normalsReading, filteredReading.getDescriptorViewByName("normals")); const BOOST_AUTO(normalsReference, filteredReference.getDescriptorViewByName("normals")); - + // select weight from median OutlierWeights w(input.dists.rows(), input.dists.cols()); @@ -250,7 +250,7 @@ typename PointMatcher::OutlierWeights OutlierFiltersImpl::SurfaceNormalOut { const Vector normalRead = normalsReading.col(x).normalized(); - for (int y = 0; y < w.rows(); ++y) // knn + for (int y = 0; y < w.rows(); ++y) // knn { const int idRef = input.ids(y, x); @@ -261,7 +261,7 @@ typename PointMatcher::OutlierWeights OutlierFiltersImpl::SurfaceNormalOut const Vector normalRef = normalsReference.col(idRef).normalized(); - const T value = anyabs(normalRead.dot(normalRef)); + const T value = normalRead.dot(normalRef); if(value < eps) // test to keep the points w(y, x) = 0; @@ -314,7 +314,7 @@ typename PointMatcher::OutlierWeights OutlierFiltersImpl::GenericDescripto const int knn = input.dists.rows(); const int readPtsCount = input.dists.cols(); - + OutlierWeights w(knn, readPtsCount); const DataPoints *cloud; @@ -322,7 +322,7 @@ typename PointMatcher::OutlierWeights OutlierFiltersImpl::GenericDescripto if(source == "reference") cloud = &filteredReference; else - cloud = &filteredReference; + cloud = &filteredReading; ConstView desc(cloud->getDescriptorViewByName(descName)); @@ -336,23 +336,31 @@ typename PointMatcher::OutlierWeights OutlierFiltersImpl::GenericDescripto { for(int i=0; i < readPtsCount; i++) { - const int idRead = input.ids(k, i); - if (idRead == MatchersImpl::NNS::InvalidIndex){ - w(k,i) = 0; - continue; + int point_id; + if (source == "reference") { + point_id = input.ids(k, i); + if (point_id == MatchersImpl::NNS::InvalidIndex){ + LOG_INFO_STREAM("Invalid Index in GenericOutlierFilter, setting weight to 0."); + w(k,i) = 0; + continue; + } + } else { + // We don't need to look up corresponding points in the reference + //, we index into the reading PC directly. + point_id = i; } if(useSoftThreshold == false) { if(useLargerThan == true) { - if (desc(0, idRead) > threshold) + if (desc(0, point_id) > threshold) w(k,i) = 1; else w(k,i) = 0; } else { - if (desc(0, idRead) < threshold) + if (desc(0, point_id) < threshold) w(k,i) = 1; else w(k,i) = 0; @@ -361,7 +369,7 @@ typename PointMatcher::OutlierWeights OutlierFiltersImpl::GenericDescripto else { // use soft threshold by assigning the weight using the descriptor - w(k,i) = desc(0, idRead); + w(k,i) = desc(0, point_id); } } } diff --git a/thirdparty/libpointmatcher/pointmatcher/OutlierFiltersImpl.h b/thirdparty/libpointmatcher/pointmatcher/OutlierFiltersImpl.h index 38a9147..e237e46 100644 --- a/thirdparty/libpointmatcher/pointmatcher/OutlierFiltersImpl.h +++ b/thirdparty/libpointmatcher/pointmatcher/OutlierFiltersImpl.h @@ -177,7 +177,7 @@ struct OutlierFiltersImpl { inline static const std::string description() { - return "Hard rejection threshold using the angle between the surface normal vector of the reading and the reference. If normal vectors or not in the descriptor for both of the point clouds, does nothing."; + return "Hard rejection threshold using the angle between the surface normal vector of the reading and the reference. Usually used in combination with `OrientNormalDataPointsFilter`. If normal vectors are not in the descriptor for both of the point clouds, does nothing."; } inline static const ParametersDoc availableParameters() { diff --git a/thirdparty/libpointmatcher/pointmatcher/PointMatcher.h b/thirdparty/libpointmatcher/pointmatcher/PointMatcher.h index 8045a47..f26aa2c 100644 --- a/thirdparty/libpointmatcher/pointmatcher/PointMatcher.h +++ b/thirdparty/libpointmatcher/pointmatcher/PointMatcher.h @@ -91,6 +91,14 @@ namespace PointMatcherSupport //! return an exception when a transformation has invalid parameters TransformationError(const std::string& reason); }; + + //! An expception thrown when the yaml config file contains invalid configuration (e.g., mutually exclusive settings) + struct ConfigurationError: std::runtime_error + { + //! return an exception when a transformation has invalid parameters + ConfigurationError(const std::string& reason); + }; + //! The logger interface, used to output warnings and informations struct Logger: public Parametrizable @@ -402,6 +410,9 @@ struct PointMatcher //! Transform input using the transformation matrix virtual DataPoints compute(const DataPoints& input, const TransformationParameters& parameters) const = 0; + //! Transform point cloud in-place using the transformation matrix + virtual void inPlaceCompute(const TransformationParameters& parameters, DataPoints& cloud) const = 0; + //! Return whether the given parameters respect the expected constraints virtual bool checkParameters(const TransformationParameters& parameters) const = 0; @@ -658,7 +669,7 @@ struct PointMatcher virtual void setDefault(); - void loadFromYaml(std::istream& in); + virtual void loadFromYaml(std::istream& in); unsigned getPrefilteredReadingPtsCount() const; unsigned getPrefilteredReferencePtsCount() const; @@ -733,6 +744,8 @@ struct PointMatcher bool hasMap() const; bool setMap(const DataPoints& map); void clearMap(); + virtual void setDefault(); + virtual void loadFromYaml(std::istream& in); PM_DEPRECATED("Use getPrefilteredInternalMap instead. " "Function now always returns map with filter chain applied. " "This may have altered your program behavior." diff --git a/thirdparty/libpointmatcher/pointmatcher/PointMatcherPrivate.h b/thirdparty/libpointmatcher/pointmatcher/PointMatcherPrivate.h index 6782d5c..bdd5e59 100644 --- a/thirdparty/libpointmatcher/pointmatcher/PointMatcherPrivate.h +++ b/thirdparty/libpointmatcher/pointmatcher/PointMatcherPrivate.h @@ -36,6 +36,8 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #ifndef __POINTMATCHER_PRIVATE_H #define __POINTMATCHER_PRIVATE_H +#include "PointMatcher.h" + namespace PointMatcherSupport { //! Mutex to protect creation and deletion of logger diff --git a/thirdparty/libpointmatcher/pointmatcher/Registrar.h b/thirdparty/libpointmatcher/pointmatcher/Registrar.h index 027144c..706211f 100644 --- a/thirdparty/libpointmatcher/pointmatcher/Registrar.h +++ b/thirdparty/libpointmatcher/pointmatcher/Registrar.h @@ -70,14 +70,14 @@ namespace PointMatcherSupport { InvalidElement(const std::string& reason); }; - + //! A factor for subclasses of Interface template struct Registrar { public: typedef Interface TargetType; //!< alias to recover the template parameter - + //! The interface for class descriptors struct ClassDescriptor { @@ -90,7 +90,7 @@ namespace PointMatcherSupport //! Return the available parameters for this class virtual const Parametrizable::ParametersDoc availableParameters() const = 0; }; - + //! A descriptor for a class C that provides parameters template struct GenericClassDescriptor: public ClassDescriptor @@ -98,72 +98,71 @@ namespace PointMatcherSupport virtual std::shared_ptr createInstance(const std::string& className, const Parametrizable::Parameters& params) const { std::shared_ptr instance = std::make_shared(params); - + // check that all parameters were set - for (BOOST_AUTO(it, params.begin()); it != params.end() ;++it) + for (const auto& param : params) { - if (instance->parametersUsed.find(it->first) == instance->parametersUsed.end()){ + if (instance->parametersUsed.find(param.first) == instance->parametersUsed.end()){ throw Parametrizable::InvalidParameter( - (boost::format("Parameter %1% for module %2% was set but is not used") % it->first % className).str() + (boost::format("Parameter %1% for module %2% was set but is not used") % param.first % className).str() ); } } - return instance; } + virtual const std::string description() const { return C::description(); } + virtual const Parametrizable::ParametersDoc availableParameters() const { return C::availableParameters(); } }; - + //! A descriptor for a class C that does not provide any parameter template struct GenericClassDescriptorNoParam: public ClassDescriptor { virtual std::shared_ptr createInstance(const std::string& className, const Parametrizable::Parameters& params) const { - for (BOOST_AUTO(it, params.begin()); it != params.end() ;++it) + for (const auto& param : params) throw Parametrizable::InvalidParameter( - (boost::format("Parameter %1% was set but module %2% dos not use any parameter") % it->first % className).str() + (boost::format("Parameter %1% was set but module %2% dos not use any parameter") % param.first % className).str() ); + return std::make_shared(); } + virtual const std::string description() const { return C::description(); } + virtual const Parametrizable::ParametersDoc availableParameters() const { return Parametrizable::ParametersDoc(); } }; - + protected: - typedef std::map DescriptorMap; //!< descriptors for sub-classes of Interface, indexed by their names + typedef std::map> DescriptorMap; //!< descriptors for sub-classes of Interface, indexed by their names DescriptorMap classes; //!< known classes that can be constructed - + public: - //! Destructor, remove all classes descriptors - ~Registrar() - { - for (BOOST_AUTO(it, classes.begin()); it != classes.end(); ++it) - delete it->second; - } //! Register a class by storing an instance of a descriptor helper class - void reg(const std::string &name, ClassDescriptor* descriptor) + void reg(const std::string &name, std::shared_ptr descriptor) { - classes[name] = descriptor; + classes.insert(std::make_pair(name, descriptor)); } - + //! Return a descriptor following a name, throw an exception if name is invalid - const ClassDescriptor* getDescriptor(const std::string& name) const + std::shared_ptr getDescriptor(const std::string& name) const { - BOOST_AUTO(it, classes.find(name)); + auto it = classes.find(name); + if (it == classes.end()) { std::cerr << "No element named " << name << " is registered. Known ones are:\n"; @@ -174,42 +173,43 @@ namespace PointMatcherSupport } return it->second; } - + //! Create an instance std::shared_ptr create(const std::string& name, const Parametrizable::Parameters& params = Parametrizable::Parameters()) const { return getDescriptor(name)->createInstance(name, params); } - + //! Create an instance from a YAML node - std::shared_ptr createFromYAML(const YAML::Node& module) const + std::shared_ptr createFromYAML(const YAML::Node& module) const { std::string name; Parametrizable::Parameters params; getNameParamsFromYAML(module, name, params); - + return create(name, params); } - + //! Get the description of a class const std::string getDescription(const std::string& name) const { return getDescriptor(name)->description(); } - + //! Print the list of registered classes to stream void dump(std::ostream &stream) const { - for (BOOST_AUTO(it, classes.begin()); it != classes.end(); ++it) - stream << "- " << it->first << "\n"; + for (const auto& it : classes) + stream << "- " << it.first << "\n"; } - + //! begin for const iterator over classes descriptions typename DescriptorMap::const_iterator begin() const - { + { return classes.begin(); } + //! end for const iterator over classes descriptions typename DescriptorMap::const_iterator end() const { @@ -222,11 +222,11 @@ namespace PointMatcherSupport #define DEF_REGISTRAR_IFACE(name, ifaceName) PointMatcherSupport::Registrar< ifaceName > name##Registrar; #define ADD_TO_REGISTRAR(name, elementName, element) { \ typedef typename PointMatcherSupport::Registrar< name >::template GenericClassDescriptor< element > Desc; \ - name##Registrar.reg(# elementName, new Desc() ); \ + name##Registrar.reg(# elementName, std::make_shared() ); \ } #define ADD_TO_REGISTRAR_NO_PARAM(name, elementName, element) { \ typedef typename PointMatcherSupport::Registrar< name >::template GenericClassDescriptorNoParam< element > Desc; \ - name##Registrar.reg(# elementName, new Desc() ); \ + name##Registrar.reg(# elementName, std::make_shared() ); \ } } // namespace PointMatcherSupport diff --git a/thirdparty/libpointmatcher/pointmatcher/Registry.cpp b/thirdparty/libpointmatcher/pointmatcher/Registry.cpp index bdd44e0..512b2ae 100644 --- a/thirdparty/libpointmatcher/pointmatcher/Registry.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/Registry.cpp @@ -62,6 +62,7 @@ PointMatcher::PointMatcher() { ADD_TO_REGISTRAR_NO_PARAM(Transformation, RigidTransformation, typename TransformationsImpl::RigidTransformation) ADD_TO_REGISTRAR_NO_PARAM(Transformation, PureTranslation, typename TransformationsImpl::PureTranslation) + ADD_TO_REGISTRAR_NO_PARAM(Transformation, SimilarityTransformation, typename TransformationsImpl::SimilarityTransformation) ADD_TO_REGISTRAR_NO_PARAM(DataPointsFilter, IdentityDataPointsFilter, typename DataPointsFiltersImpl::IdentityDataPointsFilter) ADD_TO_REGISTRAR_NO_PARAM(DataPointsFilter, RemoveNaNDataPointsFilter, typename DataPointsFiltersImpl::RemoveNaNDataPointsFilter) @@ -89,6 +90,9 @@ PointMatcher::PointMatcher() ADD_TO_REGISTRAR(DataPointsFilter, CovarianceSamplingDataPointsFilter, typename DataPointsFiltersImpl::CovarianceSamplingDataPointsFilter) ADD_TO_REGISTRAR(DataPointsFilter, DistanceLimitDataPointsFilter, typename DataPointsFiltersImpl::DistanceLimitDataPointsFilter) ADD_TO_REGISTRAR(DataPointsFilter, RemoveSensorBiasDataPointsFilter, typename DataPointsFiltersImpl::RemoveSensorBiasDataPointsFilter) + ADD_TO_REGISTRAR(DataPointsFilter, SphericalityDataPointsFilter, typename DataPointsFiltersImpl::SphericalityDataPointsFilter) + ADD_TO_REGISTRAR(DataPointsFilter, SaliencyDataPointsFilter, typename DataPointsFiltersImpl::SaliencyDataPointsFilter) + ADD_TO_REGISTRAR(DataPointsFilter, SpectralDecompositionDataPointsFilter, typename DataPointsFiltersImpl::SpectralDecompositionDataPointsFilter) ADD_TO_REGISTRAR_NO_PARAM(Matcher, NullMatcher, typename MatchersImpl::NullMatcher) ADD_TO_REGISTRAR(Matcher, KDTreeMatcher, typename MatchersImpl::KDTreeMatcher) diff --git a/thirdparty/libpointmatcher/pointmatcher/Transformation.cpp b/thirdparty/libpointmatcher/pointmatcher/Transformation.cpp index 3c58082..734c47d 100644 --- a/thirdparty/libpointmatcher/pointmatcher/Transformation.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/Transformation.cpp @@ -66,12 +66,9 @@ void PointMatcher::Transformations::apply(DataPoints& cloud, const Transforma // TODO: This API must be re-written to not even have the concept // of chain for this classs. int num_iter = 0; - - DataPoints transformedCloud; for (TransformationsConstIt it = this->begin(); it != this->end(); ++it) { - transformedCloud = (*it)->compute(cloud, parameters); - swapDataPoints(cloud, transformedCloud); + (*it)->inPlaceCompute(parameters, cloud); num_iter++; } if (num_iter != 1) diff --git a/thirdparty/libpointmatcher/pointmatcher/TransformationsImpl.cpp b/thirdparty/libpointmatcher/pointmatcher/TransformationsImpl.cpp index 562f063..640819f 100644 --- a/thirdparty/libpointmatcher/pointmatcher/TransformationsImpl.cpp +++ b/thirdparty/libpointmatcher/pointmatcher/TransformationsImpl.cpp @@ -51,39 +51,61 @@ typename PointMatcher::DataPoints TransformationsImpl::RigidTransformation const DataPoints& input, const TransformationParameters& parameters) const { - assert(input.features.rows() == parameters.rows()); + DataPoints transformedCloud = input; + inPlaceCompute(parameters, transformedCloud); + return transformedCloud; +} + +//! RigidTransformation +template +void TransformationsImpl::RigidTransformation::inPlaceCompute( + const TransformationParameters& parameters, + DataPoints& cloud) const +{ + assert(cloud.features.rows() == parameters.rows()); assert(parameters.rows() == parameters.cols()); + if(this->checkParameters(parameters) == false) + throw TransformationError("RigidTransformation: Error, rotation matrix is not orthogonal."); + + // Apply the transformation to features + cloud.features.applyOnTheLeft(parameters); + + // Apply the rotation to descriptors const unsigned int nbRows = parameters.rows()-1; const unsigned int nbCols = parameters.cols()-1; - const TransformationParameters R(parameters.topLeftCorner(nbRows, nbCols)); - if(this->checkParameters(parameters) == false) - throw TransformationError("RigidTransformation: Error, rotation matrix is not orthogonal."); - - //DataPoints transformedCloud(input.featureLabels, input.descriptorLabels, input.timeLabels, input.features.cols()); - DataPoints transformedCloud = input; - - // Apply the transformation to features - transformedCloud.features = parameters * input.features; - - // Apply the transformation to descriptors - int row(0); - const int descCols(input.descriptors.cols()); - for (size_t i = 0; i < input.descriptorLabels.size(); ++i) + int descStartingRow(0); + const int descCols(cloud.descriptors.cols()); + + for (size_t i = 0; i < cloud.descriptorLabels.size(); ++i) { - const int span(input.descriptorLabels[i].span); - const std::string& name(input.descriptorLabels[i].text); - const BOOST_AUTO(inputDesc, input.descriptors.block(row, 0, span, descCols)); - BOOST_AUTO(outputDesc, transformedCloud.descriptors.block(row, 0, span, descCols)); - if (name == "normals" || name == "observationDirections") - outputDesc = R * inputDesc; - - row += span; - } + const int descSpan(cloud.descriptorLabels[i].span); + const std::string& descName(cloud.descriptorLabels[i].text); - return transformedCloud; + if (descName == "normals" || descName == "observationDirections") + { + cloud.descriptors.block(descStartingRow, 0, descSpan, descCols).applyOnTheLeft(R); + } + else if (descName == "eigVectors") + { + int vectorSpan = std::sqrt(descSpan); + int vectorStartingRow = descStartingRow; + + cloud.descriptors.block(vectorStartingRow, 0, vectorSpan, descCols).applyOnTheLeft(R); + vectorStartingRow += vectorSpan; + cloud.descriptors.block(vectorStartingRow, 0, vectorSpan, descCols).applyOnTheLeft(R); + + if (vectorSpan == 3) + { + vectorStartingRow += vectorSpan; + cloud.descriptors.block(vectorStartingRow, 0, vectorSpan, descCols).applyOnTheLeft(R); + } + } + + descStartingRow += descSpan; + } } //! Ensure orthogonality of the rotation matrix @@ -96,7 +118,7 @@ bool TransformationsImpl::RigidTransformation::checkParameters(const Transfor const unsigned int nbCols = parameters.cols()-1; const TransformationParameters R(parameters.topLeftCorner(nbRows, nbCols)); - + if(anyabs(1 - R.determinant()) > epsilon) return false; else @@ -133,9 +155,9 @@ typename PointMatcher::TransformationParameters TransformationsImpl::Rigid { throw TransformationError("RigidTransformation: Error, only proper rigid transformations are supported."); } - + // mean of a and b - T a = (parameters(0,0) + parameters(1,1))/2; + T a = (parameters(0,0) + parameters(1,1))/2; T b = (-parameters(1,0) + parameters(0,1))/2; T sum = sqrt(pow(a,2) + pow(b,2)); @@ -159,39 +181,61 @@ typename PointMatcher::DataPoints TransformationsImpl::SimilarityTransform const DataPoints& input, const TransformationParameters& parameters) const { - assert(input.features.rows() == parameters.rows()); - assert(parameters.rows() == parameters.cols()); - - const unsigned int nbRows = parameters.rows()-1; - const unsigned int nbCols = parameters.cols()-1; + DataPoints transformedCloud = input; + inPlaceCompute(parameters, transformedCloud); + return transformedCloud; +} - const TransformationParameters R(parameters.topLeftCorner(nbRows, nbCols)); +//! SimilarityTransformation +template +void TransformationsImpl::SimilarityTransformation::inPlaceCompute( + const TransformationParameters& parameters, + DataPoints& cloud) const +{ + assert(cloud.features.rows() == parameters.rows()); + assert(parameters.rows() == parameters.cols()); if(this->checkParameters(parameters) == false) throw TransformationError("SimilarityTransformation: Error, invalid similarity transform."); - - //DataPoints transformedCloud(input.featureLabels, input.descriptorLabels, input.timeLabels, input.features.cols()); - DataPoints transformedCloud = input; - + // Apply the transformation to features - transformedCloud.features = parameters * input.features; - - // Apply the transformation to descriptors - int row(0); - const int descCols(input.descriptors.cols()); - for (size_t i = 0; i < input.descriptorLabels.size(); ++i) + cloud.features.applyOnTheLeft(parameters); + + // Apply the rotation to descriptors + const unsigned int nbRows = parameters.rows() - 1; + const unsigned int nbCols = parameters.cols() - 1; + const TransformationParameters R(parameters.topLeftCorner(nbRows, nbCols)); + + int descStartingRow(0); + const int descCols(cloud.descriptors.cols()); + + for (size_t i = 0; i < cloud.descriptorLabels.size(); ++i) { - const int span(input.descriptorLabels[i].span); - const std::string& name(input.descriptorLabels[i].text); - const BOOST_AUTO(inputDesc, input.descriptors.block(row, 0, span, descCols)); - BOOST_AUTO(outputDesc, transformedCloud.descriptors.block(row, 0, span, descCols)); - if (name == "normals" || name == "observationDirections") - outputDesc = R * inputDesc; - - row += span; - } + const int descSpan(cloud.descriptorLabels[i].span); + const std::string& descName(cloud.descriptorLabels[i].text); - return transformedCloud; + if (descName == "normals" || descName == "observationDirections") + { + cloud.descriptors.block(descStartingRow, 0, descSpan, descCols).applyOnTheLeft(R); + } + else if (descName == "eigVectors") + { + int vectorSpan = std::sqrt(descSpan); + int vectorStartingRow = descStartingRow; + + cloud.descriptors.block(vectorStartingRow, 0, vectorSpan, descCols).applyOnTheLeft(R); + vectorStartingRow += vectorSpan; + cloud.descriptors.block(vectorStartingRow, 0, vectorSpan, descCols).applyOnTheLeft(R); + + if (vectorSpan == 3) + { + vectorStartingRow += vectorSpan; + cloud.descriptors.block(vectorStartingRow, 0, vectorSpan, descCols).applyOnTheLeft(R); + } + } + + descStartingRow += descSpan; + } } //! Nothing to check for a similarity transform @@ -215,19 +259,23 @@ template struct TransformationsImpl::SimilarityTransformation; template typename PointMatcher::DataPoints TransformationsImpl::PureTranslation::compute(const DataPoints& input, const TransformationParameters& parameters) const { - assert(input.features.rows() == parameters.rows()); + DataPoints transformedCloud = input; + inPlaceCompute(parameters, transformedCloud); + return transformedCloud; +} + +template +void TransformationsImpl::PureTranslation::inPlaceCompute( + const TransformationParameters& parameters, + DataPoints& cloud) const { + assert(cloud.features.rows() == parameters.rows()); assert(parameters.rows() == parameters.cols()); if(this->checkParameters(parameters) == false) throw PointMatcherSupport::TransformationError("PureTranslation: Error, left part not identity."); - //DataPoints transformedCloud(input.featureLabels, input.descriptorLabels, input.features.cols()); - DataPoints transformedCloud = input; - // Apply the transformation to features - transformedCloud.features = parameters * input.features; - - return transformedCloud; + cloud.features.applyOnTheLeft(parameters); } template diff --git a/thirdparty/libpointmatcher/pointmatcher/TransformationsImpl.h b/thirdparty/libpointmatcher/pointmatcher/TransformationsImpl.h index faf156e..0e2998d 100644 --- a/thirdparty/libpointmatcher/pointmatcher/TransformationsImpl.h +++ b/thirdparty/libpointmatcher/pointmatcher/TransformationsImpl.h @@ -60,6 +60,7 @@ struct TransformationsImpl RigidTransformation() : Transformation("RigidTransformation", ParametersDoc(), Parameters()) {} virtual DataPoints compute(const DataPoints& input, const TransformationParameters& parameters) const; + virtual void inPlaceCompute(const TransformationParameters& parameters, DataPoints& cloud) const; virtual bool checkParameters(const TransformationParameters& parameters) const; virtual TransformationParameters correctParameters(const TransformationParameters& parameters) const; }; @@ -71,7 +72,9 @@ struct TransformationsImpl return "Similarity transformation (rotation + translation + scale)."; } + SimilarityTransformation() : Transformation("SimilarityTransformation", ParametersDoc(), Parameters()) {} virtual DataPoints compute(const DataPoints& input, const TransformationParameters& parameters) const; + virtual void inPlaceCompute(const TransformationParameters& parameters, DataPoints& cloud) const; virtual bool checkParameters(const TransformationParameters& parameters) const; virtual TransformationParameters correctParameters(const TransformationParameters& parameters) const; }; @@ -85,6 +88,7 @@ struct TransformationsImpl PureTranslation() : Transformation("PureTranslation", ParametersDoc(), Parameters()) {} virtual DataPoints compute(const DataPoints& input, const TransformationParameters& parameters) const; + virtual void inPlaceCompute(const TransformationParameters& parameters, DataPoints& cloud) const; virtual bool checkParameters(const TransformationParameters& parameters) const; virtual TransformationParameters correctParameters(const TransformationParameters& parameters) const; }; diff --git a/thirdparty/libpointmatcher/utest/CMakeLists.txt b/thirdparty/libpointmatcher/utest/CMakeLists.txt deleted file mode 100644 index ed41214..0000000 --- a/thirdparty/libpointmatcher/utest/CMakeLists.txt +++ /dev/null @@ -1,23 +0,0 @@ -enable_testing() - -include_directories(../contrib/gtest) -add_executable(utest - utest.cpp - ui/IO.cpp - ui/DataFilters.cpp - ui/Matcher.cpp - ui/Outliers.cpp - ui/ErrorMinimizers.cpp - ui/Transformations.cpp - ui/DataPoints.cpp - ui/Inspectors.cpp - ui/Loggers.cpp) - -find_package (Threads) -target_link_libraries(utest gtest pointmatcher ${CMAKE_THREAD_LIBS_INIT}) - -add_test(utest ${CMAKE_CURRENT_BINARY_DIR}/utest --gtest_output=xml:${CMAKE_CURRENT_BINARY_DIR}/test_results.xml --path "${CMAKE_SOURCE_DIR}/examples/data/") - -if (UNIX) - configure_file(CTestCustom.cmake ${CMAKE_BINARY_DIR}) -endif (UNIX) diff --git a/thirdparty/libpointmatcher/utest/CTestCustom.cmake b/thirdparty/libpointmatcher/utest/CTestCustom.cmake deleted file mode 100644 index f716429..0000000 --- a/thirdparty/libpointmatcher/utest/CTestCustom.cmake +++ /dev/null @@ -1 +0,0 @@ -set(CTEST_CUSTOM_POST_TEST "cat Testing/Temporary/LastTest.log") diff --git a/thirdparty/libpointmatcher/utest/listVersionsUbuntu.sh b/thirdparty/libpointmatcher/utest/listVersionsUbuntu.sh deleted file mode 100755 index 2ba05ec..0000000 --- a/thirdparty/libpointmatcher/utest/listVersionsUbuntu.sh +++ /dev/null @@ -1,15 +0,0 @@ -#!/bin/bash - -echo -e "\n Copy-paste those information when reporting a bug in libpointmatcher:\n" - -echo -e "Name \t\t| Version" -echo -e "----------------|-------------------------------" -echo -e "ubuntu: \t|" $(lsb_release -d) -echo -e "architecture: \t|" $(getconf LONG_BIT)"-bit" -echo -e "gcc: \t\t|" $(gcc --version | grep gcc) -echo -e "git: \t\t|" $(git --version) -echo -e "cmake: \t\t|" $(cmake --version) -echo -e "boost: \t\t|" $(dpkg -s libboost-dev | grep Version) -echo -e "eigen3: \t|" $(dpkg -s libeigen3-dev | grep Version) -echo -e "doxygen: \t|" $(dpkg -s doxygen | grep Version) -echo -e "\n\n" diff --git a/thirdparty/libpointmatcher/utest/ui/DataFilters.cpp b/thirdparty/libpointmatcher/utest/ui/DataFilters.cpp deleted file mode 100644 index ba14ce7..0000000 --- a/thirdparty/libpointmatcher/utest/ui/DataFilters.cpp +++ /dev/null @@ -1,893 +0,0 @@ -#include "../utest.h" -#include -#include - -using namespace std; -using namespace PointMatcherSupport; - -//--------------------------- -// DataFilter modules -//--------------------------- - -// Utility classes -class DataFilterTest: public IcpHelper -{ -public: - // Will be called for every tests - virtual void SetUp() - { - icp.setDefault(); - // Uncomment for console outputs - //setLogger(PM::get().LoggerRegistrar.create("FileLogger")); - - // We'll test the filters on reading point cloud - icp.readingDataPointsFilters.clear(); - } - - // Will be called for every tests - virtual void TearDown() {} - - void addFilter(string name, PM::Parameters params) - { - std::shared_ptr testedDataPointFilter = - PM::get().DataPointsFilterRegistrar.create(name, params); - - icp.readingDataPointsFilters.push_back(testedDataPointFilter); - } - - void addFilter(string name) - { - std::shared_ptr testedDataPointFilter = - PM::get().DataPointsFilterRegistrar.create(name); - - icp.readingDataPointsFilters.push_back(testedDataPointFilter); - } - - DP generateRandomDataPoints(int nbPoints = 100) - { - const int dimFeatures = 4; - const int dimDescriptors = 3; - const int dimTime = 2; - - PM::Matrix randFeat = PM::Matrix::Random(dimFeatures, nbPoints); - DP::Labels featLabels; - featLabels.push_back(DP::Label("x", 1)); - featLabels.push_back(DP::Label("y", 1)); - featLabels.push_back(DP::Label("z", 1)); - featLabels.push_back(DP::Label("pad", 1)); - - PM::Matrix randDesc = PM::Matrix::Random(dimDescriptors, nbPoints); - DP::Labels descLabels; - descLabels.push_back(DP::Label("dummyDesc", 3)); - - PM::Int64Matrix randTimes = PM::Int64Matrix::Random(dimTime, nbPoints); - DP::Labels timeLabels; - timeLabels.push_back(DP::Label("dummyTime", 2)); - - // Construct the point cloud from the generated matrices - DP pointCloud = DP(randFeat, featLabels, randDesc, descLabels, randTimes, timeLabels); - - return pointCloud; - } -}; - -TEST_F(DataFilterTest, IdentityDataPointsFilter) -{ - // build test cloud - DP ref2DCopy(ref2D); - - // apply and checked - addFilter("IdentityDataPointsFilter"); - icp.readingDataPointsFilters.apply(ref2DCopy); - EXPECT_TRUE(ref2D == ref2DCopy); -} - -TEST_F(DataFilterTest, RemoveNaNDataPointsFilter) -{ - // build test cloud - DP ref2DCopy(ref2D); - int goodCount(0); - const float nan(std::numeric_limits::quiet_NaN()); - for (int i(0); i < ref2DCopy.features.cols(); ++i) - { - if (rand() % 3 == 0) - { - ref2DCopy.features(rand() % ref2DCopy.features.rows(), i) = nan; - } - else - ++goodCount; - } - - // apply and checked - addFilter("RemoveNaNDataPointsFilter"); - icp.readingDataPointsFilters.apply(ref2DCopy); - EXPECT_TRUE(ref2DCopy.features.cols() == goodCount); -} - -TEST_F(DataFilterTest, MaxDistDataPointsFilter) -{ - // Max dist has been selected to not affect the points - params = PM::Parameters(); - params["dim"] = "0"; - params["maxDist"] = toParam(6.0); - - // Filter on x axis - params["dim"] = "0"; - icp.readingDataPointsFilters.clear(); - addFilter("MaxDistDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - - // Filter on y axis - params["dim"] = "1"; - icp.readingDataPointsFilters.clear(); - addFilter("MaxDistDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - - // Filter on z axis (not existing) - params["dim"] = "2"; - icp.readingDataPointsFilters.clear(); - addFilter("MaxDistDataPointsFilter", params); - EXPECT_ANY_THROW(validate2dTransformation()); - validate3dTransformation(); - - // Filter on a radius - params["dim"] = "-1"; - icp.readingDataPointsFilters.clear(); - addFilter("MaxDistDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - - // Parameter outside valid range - params["dim"] = "3"; - //TODO: specify the exception, move that to GenericTest - EXPECT_ANY_THROW(addFilter("MaxDistDataPointsFilter", params)); - -} - -TEST_F(DataFilterTest, MinDistDataPointsFilter) -{ - // Min dist has been selected to not affect the points too much - params = PM::Parameters(); - params["dim"] = "0"; - params["minDist"] = toParam(0.05); - - // Filter on x axis - params["dim"] = "0"; - icp.readingDataPointsFilters.clear(); - addFilter("MinDistDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - - // Filter on y axis - params["dim"] = "1"; - icp.readingDataPointsFilters.clear(); - addFilter("MinDistDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - - //TODO: move that to specific 2D test - // Filter on z axis (not existing) - params["dim"] = "2"; - icp.readingDataPointsFilters.clear(); - addFilter("MinDistDataPointsFilter", params); - EXPECT_ANY_THROW(validate2dTransformation()); - validate3dTransformation(); - - // Filter on a radius - params["dim"] = "-1"; - icp.readingDataPointsFilters.clear(); - addFilter("MinDistDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - -} - -TEST_F(DataFilterTest, MaxQuantileOnAxisDataPointsFilter) -{ - // Ratio has been selected to not affect the points too much - string ratio = "0.95"; - params = PM::Parameters(); - params["dim"] = "0"; - params["ratio"] = ratio; - - // Filter on x axis - params["dim"] = "0"; - icp.readingDataPointsFilters.clear(); - addFilter("MaxQuantileOnAxisDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - - // Filter on y axis - params["dim"] = "1"; - icp.readingDataPointsFilters.clear(); - addFilter("MaxQuantileOnAxisDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - - // Filter on z axis (not existing) - params["dim"] = "2"; - icp.readingDataPointsFilters.clear(); - addFilter("MaxQuantileOnAxisDataPointsFilter", params); - EXPECT_ANY_THROW(validate2dTransformation()); - validate3dTransformation(); -} - - - -TEST_F(DataFilterTest, SurfaceNormalDataPointsFilter) -{ - // This filter create descriptor, so parameters should'nt impact results - params = PM::Parameters(); - params["knn"] = "5"; - params["epsilon"] = "0.1"; - params["keepNormals"] = "1"; - params["keepDensities"] = "1"; - params["keepEigenValues"] = "1"; - params["keepEigenVectors"] = "1" ; - params["keepMatchedIds"] = "1" ; - // FIXME: the parameter keepMatchedIds seems to do nothing... - - addFilter("SurfaceNormalDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - - // TODO: standardize how filter are tested: - // 1- impact on number of points - // 2- impact on descriptors - // 3- impact on ICP (that's what we test now) -} - -TEST_F(DataFilterTest, MaxDensityDataPointsFilter) -{ - // Ratio has been selected to not affect the points too much - vector ratio = {100, 1000, 5000}; - - for(unsigned i=0; i < ratio.size(); i++) - { - icp.readingDataPointsFilters.clear(); - params = PM::Parameters(); - params["knn"] = "5"; - params["epsilon"] = "0.1"; - params["keepNormals"] = "0"; - params["keepDensities"] = "1"; - params["keepEigenValues"] = "0"; - params["keepEigenVectors"] = "0" ; - params["keepMatchedIds"] = "0" ; - - addFilter("SurfaceNormalDataPointsFilter", params); - - params = PM::Parameters(); - params["maxDensity"] = toParam(ratio[i]); - - addFilter("MaxDensityDataPointsFilter", params); - - // FIXME BUG: the density in 2D is not well computed - //validate2dTransformation(); - - //double nbInitPts = data2D.features.cols(); - //double nbRemainingPts = icp.getPrefilteredReadingPtsCount(); - //EXPECT_TRUE(nbRemainingPts < nbInitPts); - - validate3dTransformation(); - - double nbInitPts = data3D.features.cols(); - double nbRemainingPts = icp.getPrefilteredReadingPtsCount(); - EXPECT_TRUE(nbRemainingPts < nbInitPts); - } -} - -TEST_F(DataFilterTest, SamplingSurfaceNormalDataPointsFilter) -{ - // This filter create descriptor AND subsample - params = PM::Parameters(); - params["knn"] = "5"; - params["averageExistingDescriptors"] = "1"; - params["keepNormals"] = "1"; - params["keepDensities"] = "1"; - params["keepEigenValues"] = "1"; - params["keepEigenVectors"] = "1"; - - addFilter("SamplingSurfaceNormalDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - -} - -//TODO: this filter is broken, fix it! -/* -TEST_F(DataFilterTest, ElipsoidsDataPointsFilter) -{ - // This filter creates descriptor AND subsamples - params = PM::Parameters(); - params["knn"] = "5"; - params["averageExistingDescriptors"] = "1"; - params["keepNormals"] = "1"; - params["keepDensities"] = "1"; - params["keepEigenValues"] = "1"; - params["keepEigenVectors"] = "1"; - params["maxBoxDim"] = "inf"; - params["maxTimeWindow"] = "10"; - params["minPlanarity"] = "0"; - params["keepMeans"] = "1"; - params["keepCovariances"] = "1"; - params["keepWeights"] = "1"; - params["keepShapes"] = "1"; - params["keepIndices"] = "1"; - - addFilter("ElipsoidsDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); -} -*/ - -TEST_F(DataFilterTest, GestaltDataPointsFilter) -{ - // This filter creates descriptor AND subsamples - params = PM::Parameters(); - params["knn"] = "5"; - params["averageExistingDescriptors"] = "1"; - params["keepNormals"] = "1"; - params["keepEigenValues"] = "1"; - params["keepEigenVectors"] = "1"; - params["maxBoxDim"] = "1"; - params["keepMeans"] = "1"; - params["keepCovariances"] = "1"; - params["keepGestaltFeatures"] = "1"; - params["radius"] = "1"; - params["ratio"] = "0.5"; - - addFilter("GestaltDataPointsFilter", params); - validate3dTransformation(); -} - -TEST_F(DataFilterTest, OrientNormalsDataPointsFilter) -{ - // Used to create normal for reading point cloud - std::shared_ptr extraDataPointFilter; - extraDataPointFilter = PM::get().DataPointsFilterRegistrar.create( - "SurfaceNormalDataPointsFilter"); - icp.readingDataPointsFilters.push_back(extraDataPointFilter); - addFilter("ObservationDirectionDataPointsFilter"); - addFilter("OrientNormalsDataPointsFilter", { - {"towardCenter", toParam(false)} - } - ); - validate2dTransformation(); - validate3dTransformation(); -} - - -TEST_F(DataFilterTest, RandomSamplingDataPointsFilter) -{ - vector prob = {0.80, 0.85, 0.90, 0.95}; - for(unsigned i = 0; i < prob.size(); i++) - { - // Try to avoid to low value for the reduction to avoid under sampling - params = PM::Parameters(); - params["prob"] = toParam(prob[i]); - - icp.readingDataPointsFilters.clear(); - addFilter("RandomSamplingDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - } -} - -TEST_F(DataFilterTest, FixStepSamplingDataPointsFilter) -{ - vector steps = {1, 2, 3}; - for(unsigned i=0; i maxPtsFilter = - PM::get().DataPointsFilterRegistrar.create("MaxPointCountDataPointsFilter", params); - - DP filteredCloud = maxPtsFilter->filter(cloud); - - //Check number of points - EXPECT_GT(cloud.getNbPoints(), filteredCloud.getNbPoints()); - EXPECT_EQ(cloud.getDescriptorDim(), filteredCloud.getDescriptorDim()); - EXPECT_EQ(cloud.getTimeDim(), filteredCloud.getTimeDim()); - - EXPECT_EQ(filteredCloud.getNbPoints(), maxCount); - - //Same seed should result same filtered cloud - DP filteredCloud2 = maxPtsFilter->filter(cloud); - - EXPECT_TRUE(filteredCloud == filteredCloud2); - - //Different seeds should not result same filtered cloud but same number - params.clear(); - params["seed"] = "1"; - params["maxCount"] = toParam(maxCount); - - std::shared_ptr maxPtsFilter2 = - PM::get().DataPointsFilterRegistrar.create("MaxPointCountDataPointsFilter", params); - - DP filteredCloud3 = maxPtsFilter2->filter(cloud); - - EXPECT_FALSE(filteredCloud3 == filteredCloud2); - - EXPECT_EQ(filteredCloud3.getNbPoints(), maxCount); - - EXPECT_EQ(filteredCloud3.getNbPoints(), filteredCloud2.getNbPoints()); - EXPECT_EQ(filteredCloud3.getDescriptorDim(), filteredCloud2.getDescriptorDim()); - EXPECT_EQ(filteredCloud3.getTimeDim(), filteredCloud2.getTimeDim()); - - //Validate transformation - icp.readingDataPointsFilters.clear(); - addFilter("MaxPointCountDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); -} - -TEST_F(DataFilterTest, OctreeGridDataPointsFilter) -{ - const unsigned int nbPts = 60000; - const DP cloud = generateRandomDataPoints(nbPts); - params = PM::Parameters(); - - std::shared_ptr octreeFilter; - - for(const int meth : {0,1,2,3}) - for(const size_t maxData : {1,5}) - for(const float maxSize : {0.,0.05}) - { - params.clear(); - params["maxPointByNode"] = toParam(maxData); - params["maxSizeByNode"] = toParam(maxSize); - params["samplingMethod"] = toParam(meth); - params["buildParallel"] = "1"; - - octreeFilter = PM::get().DataPointsFilterRegistrar.create("OctreeGridDataPointsFilter", params); - - const DP filteredCloud = octreeFilter->filter(cloud); - - if(maxData==1 and maxSize==0.) - { - // 1/pts by octants + validate parallel build - // the number of point should not change - // the sampling methods should not change anything - //Check number of points - EXPECT_EQ(cloud.getNbPoints(), filteredCloud.getNbPoints()); - EXPECT_EQ(cloud.getDescriptorDim(), filteredCloud.getDescriptorDim()); - EXPECT_EQ(cloud.getTimeDim(), filteredCloud.getTimeDim()); - - EXPECT_EQ(filteredCloud.getNbPoints(), nbPts); - } - else - { - //Check number of points - EXPECT_GT(cloud.getNbPoints(), filteredCloud.getNbPoints()); - } - //Validate transformation - icp.readingDataPointsFilters.clear(); - addFilter("OctreeGridDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - } -} - -TEST_F(DataFilterTest, NormalSpaceDataPointsFilter) -{ - const size_t nbPts = 60000; - DP cloud = generateRandomDataPoints(nbPts); - params = PM::Parameters(); - - //const size_t nbPts2D = ref2D.getNbPoints(); - const size_t nbPts3D = ref3D.getNbPoints(); - - std::shared_ptr nssFilter; - - //Compute normals - auto paramsNorm = PM::Parameters(); - paramsNorm["knn"] = "5"; - paramsNorm["epsilon"] = "0.1"; - paramsNorm["keepNormals"] = "1"; - std::shared_ptr normalFilter = PM::get().DataPointsFilterRegistrar.create("SurfaceNormalDataPointsFilter", paramsNorm); - - normalFilter->inPlaceFilter(cloud); - - //Evaluate filter - std::vector samples = {/* 2*nbPts2D/3, nbPts2D,*/ 1500, 5000, nbPts, nbPts3D}; - for(const float epsilon : {M_PI/6., M_PI/32., M_PI/64.}) - for(const size_t nbSample : samples) - { - icp.readingDataPointsFilters.clear(); - - params.clear(); - params["epsilon"] = toParam(epsilon); - params["nbSample"] = toParam(nbSample); - - nssFilter = PM::get().DataPointsFilterRegistrar.create("NormalSpaceDataPointsFilter", params); - - addFilter("SurfaceNormalDataPointsFilter", paramsNorm); - addFilter("NormalSpaceDataPointsFilter", params); - - const DP filteredCloud = nssFilter->filter(cloud); - - /* - if(nbSample <= nbPts2D) - { - validate2dTransformation(); - EXPECT_LE(filteredCloud.getNbPoints(), nbPts2D); - continue; - } - else if (nbSample == nbPts3D) - { - EXPECT_EQ(filteredCloud.getNbPoints(), nbPts3D); - } - else */ - if (nbSample == nbPts) - { - //Check number of points - EXPECT_EQ(cloud.getNbPoints(), filteredCloud.getNbPoints()); - EXPECT_EQ(cloud.getDescriptorDim(), filteredCloud.getDescriptorDim()); - EXPECT_EQ(cloud.getTimeDim(), filteredCloud.getTimeDim()); - - EXPECT_EQ(filteredCloud.getNbPoints(), nbPts); - } - - validate3dTransformation(); - EXPECT_GE(cloud.getNbPoints(), filteredCloud.getNbPoints()); - } -} - -TEST_F(DataFilterTest, CovarianceSamplingDataPointsFilter) -{ - const size_t nbPts = 60000; - DP cloud = generateRandomDataPoints(nbPts); - params = PM::Parameters(); - - const size_t nbPts3D = ref3D.getNbPoints(); - - std::shared_ptr covsFilter; - - //Compute normals - auto paramsNorm = PM::Parameters(); - paramsNorm["knn"] = "5"; - paramsNorm["epsilon"] = "0.1"; - paramsNorm["keepNormals"] = "1"; - std::shared_ptr normalFilter = PM::get().DataPointsFilterRegistrar.create("SurfaceNormalDataPointsFilter", paramsNorm); - - normalFilter->inPlaceFilter(cloud); - - //Evaluate filter - std::vector samples = {500, 1500, 5000, nbPts, nbPts3D}; - for(const size_t nbSample : samples) - { - icp.readingDataPointsFilters.clear(); - - params.clear(); - params["nbSample"] = toParam(nbSample); - - covsFilter = PM::get().DataPointsFilterRegistrar.create("CovarianceSamplingDataPointsFilter", params); - - addFilter("SurfaceNormalDataPointsFilter", paramsNorm); - addFilter("CovarianceSamplingDataPointsFilter", params); - - const DP filteredCloud = covsFilter->filter(cloud); - - if (nbSample == nbPts3D) - { - EXPECT_EQ(filteredCloud.getNbPoints(), nbPts3D); - } - else if (nbSample == nbPts) - { - //Check number of points - EXPECT_EQ(cloud.getNbPoints(), filteredCloud.getNbPoints()); - EXPECT_EQ(cloud.getDescriptorDim(), filteredCloud.getDescriptorDim()); - EXPECT_EQ(cloud.getTimeDim(), filteredCloud.getTimeDim()); - - EXPECT_EQ(filteredCloud.getNbPoints(), nbPts); - } - - validate3dTransformation(); - EXPECT_GE(cloud.getNbPoints(), filteredCloud.getNbPoints()); - } -} - -TEST_F(DataFilterTest, VoxelGridDataPointsFilter) -{ - // Test with point cloud - DP cloud = generateRandomDataPoints(); - - params = PM::Parameters(); - params["vSizeX"] = "0.5"; - params["vSizeY"] = "0.5"; - params["vSizeZ"] = "0.5"; - params["useCentroid"] = toParam(true); - params["averageExistingDescriptors"] = toParam(true); - - std::shared_ptr voxelFilter = - PM::get().DataPointsFilterRegistrar.create("VoxelGridDataPointsFilter", params); - - DP filteredCloud = voxelFilter->filter(cloud); - - EXPECT_GT(cloud.getNbPoints(), filteredCloud.getNbPoints()); - EXPECT_EQ(cloud.getDescriptorDim(), filteredCloud.getDescriptorDim()); - EXPECT_EQ(cloud.getTimeDim(), filteredCloud.getTimeDim()); - - // Test with ICP - vector useCentroid = {false, true}; - vector averageExistingDescriptors = {false, true}; - for (unsigned i = 0 ; i < useCentroid.size() ; i++) - { - for (unsigned j = 0; j < averageExistingDescriptors.size(); j++) - { - params = PM::Parameters(); - params["vSizeX"] = "0.02"; - params["vSizeY"] = "0.02"; - params["vSizeZ"] = "0.02"; - params["useCentroid"] = toParam(true); - params["averageExistingDescriptors"] = toParam(true); - - icp.readingDataPointsFilters.clear(); - addFilter("VoxelGridDataPointsFilter", params); - validate2dTransformation(); - } - } - - for (unsigned i = 0 ; i < useCentroid.size() ; i++) - { - for (unsigned j = 0; j < averageExistingDescriptors.size(); j++) - { - params = PM::Parameters(); - params["vSizeX"] = "1"; - params["vSizeY"] = "1"; - params["vSizeZ"] = "1"; - params["useCentroid"] = toParam(true); - params["averageExistingDescriptors"] = toParam(true); - - icp.readingDataPointsFilters.clear(); - addFilter("VoxelGridDataPointsFilter", params); - validate3dTransformation(); - } - } -} - -TEST_F(DataFilterTest, CutAtDescriptorThresholdDataPointsFilter) -{ - // Copied from density ratio above - vector thresholds = {100, 1000, 5000}; - - DP ref3Ddensities = ref3D; - // Adding descriptor "densities" - icp.readingDataPointsFilters.clear(); - params = PM::Parameters(); - params["knn"] = "5"; - params["epsilon"] = "0.1"; - params["keepNormals"] = "0"; - params["keepDensities"] = "1"; - params["keepEigenValues"] = "0"; - params["keepEigenVectors"] = "0"; - params["keepMatchedIds"] = "0"; - - - addFilter("SurfaceNormalDataPointsFilter", params); - icp.readingDataPointsFilters.apply(ref3Ddensities); - - for(unsigned i=0; i < thresholds.size(); i++) - { - int belowCount=0; - int aboveCount=0; - - // counting points above and below - PM::DataPoints::View densities = ref3Ddensities.getDescriptorViewByName("densities"); - for (unsigned j=0; j < densities.cols(); ++j) - { - if (densities(0, j) <= thresholds[i]) - { - ++belowCount; - } - if (densities(0, j) >= thresholds[i]) - { - ++aboveCount; - } - } - - for(bool useLargerThan(true); useLargerThan; useLargerThan=false) - { - DP ref3DCopy = ref3Ddensities; - - icp.readingDataPointsFilters.clear(); - params = PM::Parameters(); - params["descName"] = toParam("densities"); - params["useLargerThan"] = toParam(useLargerThan); - params["threshold"] = toParam(thresholds[i]); - - - addFilter("CutAtDescriptorThresholdDataPointsFilter", params); - icp.readingDataPointsFilters.apply(ref3DCopy); - if (useLargerThan) - { - EXPECT_TRUE(ref3DCopy.features.cols() == belowCount); - } - else - { - EXPECT_TRUE(ref3DCopy.features.cols() == aboveCount); - } - } - } -} - -TEST_F(DataFilterTest, DistanceLimitDataPointsFilter) -{ - params = PM::Parameters(); - params["dim"] = "0"; - params["dist"] = toParam(6.0); - params["removeInside"] = "0"; - - // Filter on x axis - params["dim"] = "0"; - icp.readingDataPointsFilters.clear(); - addFilter("DistanceLimitDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - - // Filter on y axis - params["dim"] = "1"; - icp.readingDataPointsFilters.clear(); - addFilter("DistanceLimitDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - - // Filter on z axis (not existing) - params["dim"] = "2"; - icp.readingDataPointsFilters.clear(); - addFilter("DistanceLimitDataPointsFilter", params); - EXPECT_ANY_THROW(validate2dTransformation()); - validate3dTransformation(); - - // Filter on a radius - params["dim"] = "-1"; - icp.readingDataPointsFilters.clear(); - addFilter("DistanceLimitDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - - // Parameter outside valid range - params["dim"] = "3"; - //TODO: specify the exception, move that to GenericTest - EXPECT_ANY_THROW(addFilter("DistanceLimitDataPointsFilter", params)); - - - params = PM::Parameters(); - params["dim"] = "0"; - params["dist"] = toParam(0.05); - params["removeInside"] = "1"; - - // Filter on x axis - params["dim"] = "0"; - icp.readingDataPointsFilters.clear(); - addFilter("DistanceLimitDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - - // Filter on y axis - params["dim"] = "1"; - icp.readingDataPointsFilters.clear(); - addFilter("DistanceLimitDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); - - //TODO: move that to specific 2D test - // Filter on z axis (not existing) - params["dim"] = "2"; - icp.readingDataPointsFilters.clear(); - addFilter("DistanceLimitDataPointsFilter", params); - EXPECT_ANY_THROW(validate2dTransformation()); - validate3dTransformation(); - - // Filter on a radius - params["dim"] = "-1"; - icp.readingDataPointsFilters.clear(); - addFilter("DistanceLimitDataPointsFilter", params); - validate2dTransformation(); - validate3dTransformation(); -} - -TEST_F(DataFilterTest, SameFilterInstanceTwice) -{ - params = PM::Parameters(); - - std::shared_ptr df = PM::get().DataPointsFilterRegistrar.create("MaxPointCountDataPointsFilter", params); - - icp.referenceDataPointsFilters.push_back(df); - icp.readingDataPointsFilters.push_back(df); -} - -TEST_F(DataFilterTest, RemoveSensorBiasDataPointsFilter) -{ - const size_t nbPts = 6; - const double expectedErrors_LMS1xx[6] = {0., -0.0015156, -0.059276, - 0., -0.002311, -0.163689}; - const double expectedErrors_HDL32E[6] = {0., -0.002945, -0.075866, - 0., -0.002998,-0.082777 }; - - PM::Matrix points = (PM::Matrix(3,6) << 1, 1, 1, 5, 5, 5, - 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0).finished(); - DP::Labels pointsLabels; - pointsLabels.push_back(DP::Label("x", 1)); - pointsLabels.push_back(DP::Label("y", 1)); - pointsLabels.push_back(DP::Label("z", 1)); - pointsLabels.push_back(DP::Label("pad", 1)); - - PM::Matrix desc = (PM::Matrix(4,6) << 0., 0.7854, 1.4835, 0., 0.7854, 1.4835, //0,45,85 degrees - -1, -1, -1, -5, -5, -5, - 0, 0, 0, 0, 0, 0, // observation : point to sensor - 0, 0, 0, 0, 0, 0).finished(); - - PM::Matrix desc2 = (PM::Matrix(4,6) << 0., 0.7854, std::nanf(""), 0., 0.7854, M_PI_2, //0,45,90 degrees - -1, -1, -1, -5, -5, -5, - 0, 0, 0, 0, 0, 0, // observation : point to sensor - 0, 0, 0, 0, 0, 0).finished(); - DP::Labels descLabels; - descLabels.push_back(DP::Label("incidenceAngles", 1)); - descLabels.push_back(DP::Label("observationDirections", 3)); - - PM::Int64Matrix randTimes = PM::Int64Matrix::Random(2, nbPts); - DP::Labels timeLabels; - timeLabels.push_back(DP::Label("dummyTime", 2)); - - // Construct the point cloud from the generated matrices - DP pointCloud = DP(points, pointsLabels, desc, descLabels, randTimes, timeLabels); - - - PM::Parameters parameters; - parameters["sensorType"] = toParam(0); //LMS_1xx - std::shared_ptr removeSensorBiasFilter = PM::get().DataPointsFilterRegistrar.create("RemoveSensorBiasDataPointsFilter", parameters); - DP resultCloud = removeSensorBiasFilter->filter(pointCloud); - EXPECT_EQ(pointCloud.getNbPoints(), resultCloud.getNbPoints()); - - for(std::size_t i = 0; i< nbPts; ++i) - { - const double error = pointCloud.features.col(i).norm() - resultCloud.features.col(i).norm(); - EXPECT_NEAR(expectedErrors_LMS1xx[i], error, 1e-3); // below mm - } - - parameters["sensorType"] = toParam(1); //HDL32E - removeSensorBiasFilter = PM::get().DataPointsFilterRegistrar.create("RemoveSensorBiasDataPointsFilter", parameters); - resultCloud = removeSensorBiasFilter->filter(pointCloud); - - for(std::size_t i = 0; i< nbPts; ++i) - { - const double error = pointCloud.features.col(i).norm() - resultCloud.features.col(i).norm(); - EXPECT_NEAR(expectedErrors_HDL32E[i], error, 1e-4); // below mm - } - - - //test points rejection - pointCloud = DP(points, pointsLabels, desc2, descLabels, randTimes, timeLabels); - - parameters["sensorType"] = toParam(0); //LMS_1xx - parameters["angleThreshold"] = toParam(30.); - removeSensorBiasFilter = PM::get().DataPointsFilterRegistrar.create("RemoveSensorBiasDataPointsFilter", parameters); - resultCloud = removeSensorBiasFilter->filter(pointCloud); - - //four points should have been rejected - EXPECT_EQ(pointCloud.getNbPoints()-4, resultCloud.getNbPoints()); -} diff --git a/thirdparty/libpointmatcher/utest/ui/DataPoints.cpp b/thirdparty/libpointmatcher/utest/ui/DataPoints.cpp deleted file mode 100644 index 3da11b5..0000000 --- a/thirdparty/libpointmatcher/utest/ui/DataPoints.cpp +++ /dev/null @@ -1,347 +0,0 @@ -#include "../utest.h" - -using namespace std; -using namespace PointMatcherSupport; - -//--------------------------- -// Point-cloud structures -//--------------------------- - -TEST(PointCloudTest, CopyConstructor2D) -{ - const DP ref2DCopy(ref2D); - EXPECT_TRUE(ref2DCopy.features == ref2D.features); - EXPECT_TRUE(ref2DCopy.featureLabels == ref2D.featureLabels); - EXPECT_TRUE(ref2DCopy.descriptors == ref2D.descriptors); - EXPECT_TRUE(ref2DCopy.descriptorLabels == ref2D.descriptorLabels); - EXPECT_TRUE(ref2DCopy == ref2D); -} - - -TEST(PointCloudTest, FeatureConstructor2D) -{ - const DP ref2DCopy(ref2D.features, ref2D.featureLabels); - EXPECT_TRUE(ref2DCopy.features == ref2D.features); - EXPECT_TRUE(ref2DCopy.featureLabels == ref2D.featureLabels); - EXPECT_TRUE(ref2DCopy == ref2D); - EXPECT_TRUE(ref2DCopy.descriptors.rows() == 0); - EXPECT_TRUE(ref2DCopy.descriptors.cols() == 0); -} - -TEST(PointCloudTest, FeatureConstructor3D) -{ - // Note: this test cover also the operator == - - ////// 1-Empty constructor - DP ref3DCopy = DP(); - EXPECT_TRUE(ref3DCopy.features.rows() == 0); - EXPECT_TRUE(ref3DCopy.features.cols() == 0); - EXPECT_TRUE(ref3DCopy.descriptors.rows() == 0); - EXPECT_TRUE(ref3DCopy.descriptors.cols() == 0); - EXPECT_TRUE(ref3DCopy.times.rows() == 0); - EXPECT_TRUE(ref3DCopy.times.cols() == 0); - - - ////// 2-Constructor with only features - ref3DCopy = DP(ref3D.features, ref3D.featureLabels); - EXPECT_TRUE(ref3DCopy.features == ref3D.features); - EXPECT_TRUE(ref3DCopy.featureLabels == ref3D.featureLabels); - - // descriptor missing in ref3DCopy - EXPECT_FALSE(ref3DCopy == ref3D); - - EXPECT_TRUE(ref3DCopy.descriptors.rows() == 0); - EXPECT_TRUE(ref3DCopy.descriptors.cols() == 0); - - ////// 3-Constructor with features and descriptors - ref3DCopy = DP(ref3D.features, ref3D.featureLabels, ref3D.descriptors, ref3D.descriptorLabels); - - EXPECT_TRUE(ref3DCopy.features == ref3D.features); - EXPECT_TRUE(ref3DCopy.featureLabels == ref3D.featureLabels); - EXPECT_TRUE(ref3DCopy.descriptors== ref3D.descriptors); - EXPECT_TRUE(ref3DCopy.descriptorLabels == ref3D.descriptorLabels); - - - EXPECT_TRUE(ref3DCopy == ref3D); - - ////// 4-Copy constructor - ref3DCopy = DP(ref3D); - - EXPECT_TRUE(ref3DCopy.features == ref3D.features); - EXPECT_TRUE(ref3DCopy.featureLabels == ref3D.featureLabels); - EXPECT_TRUE(ref3DCopy.descriptors== ref3D.descriptors); - EXPECT_TRUE(ref3DCopy.descriptorLabels == ref3D.descriptorLabels); - - - EXPECT_TRUE(ref3DCopy == ref3D); -} - - -TEST(PointCloudTest, ConstructorWithData) -{ - const int nbPoints = 100; - const int dimFeatures = 4; - const int dimDescriptors = 3; - const int dimTime = 2; - - PM::Matrix randFeat = PM::Matrix::Random(dimFeatures, nbPoints); - DP::Labels featLabels; - featLabels.push_back(DP::Label("x", 1)); - featLabels.push_back(DP::Label("y", 1)); - featLabels.push_back(DP::Label("z", 1)); - featLabels.push_back(DP::Label("pad", 1)); - - PM::Matrix randDesc = PM::Matrix::Random(dimDescriptors, nbPoints); - DP::Labels descLabels; - descLabels.push_back(DP::Label("dummyDesc", 3)); - - PM::Int64Matrix randTimes = PM::Int64Matrix::Random(dimTime, nbPoints); - DP::Labels timeLabels; - timeLabels.push_back(DP::Label("dummyTime", 2)); - - // Construct the point cloud from the generated matrices - DP pointCloud = DP(randFeat, featLabels, randDesc, descLabels, randTimes, timeLabels); - - EXPECT_EQ(pointCloud.features.rows(), dimFeatures); - EXPECT_EQ(pointCloud.features.cols(), nbPoints); - EXPECT_EQ(pointCloud.descriptors.rows(), dimDescriptors); - EXPECT_EQ(pointCloud.descriptors.cols(), nbPoints); - EXPECT_EQ(pointCloud.times.rows(), dimTime); - EXPECT_EQ(pointCloud.times.cols(), nbPoints); - - - -} - -TEST(PointCloudTest, ConcatenateFeatures2D) -{ - const int leftPoints(ref2D.features.cols() / 2); - const int rightPoints(ref2D.features.cols() - leftPoints); - DP lefts( - ref2D.features.leftCols(leftPoints), - ref2D.featureLabels - ); - DP rights( - ref2D.features.rightCols(rightPoints), - ref2D.featureLabels - ); - lefts.concatenate(rights); - EXPECT_TRUE(lefts == ref2D); -} - -TEST(PointCloudTest, ConcatenateFeatures3D) -{ - const int leftPoints(ref3D.features.cols() / 2); - const int rightPoints(ref3D.features.cols() - leftPoints); - DP lefts( - ref3D.features.leftCols(leftPoints), - ref3D.featureLabels - ); - DP rights( - ref3D.features.rightCols(rightPoints), - ref3D.featureLabels - ); - lefts.concatenate(rights); - EXPECT_TRUE(lefts.features == ref3D.features); -} - -TEST(PointCloudTest, ConcatenateDescSame) -{ - typedef DP::Label Label; - typedef DP::Labels Labels; - - const int leftPoints(ref2D.features.cols() / 2); - const int rightPoints(ref2D.features.cols() - leftPoints); - DP lefts( - ref2D.features.leftCols(leftPoints), - ref2D.featureLabels, - PM::Matrix::Random(5, leftPoints), - Labels(Label("Desc5D", 5)) - ); - DP rights( - ref2D.features.rightCols(rightPoints), - ref2D.featureLabels, - PM::Matrix::Random(5, rightPoints), - Labels(Label("Desc5D", 5)) - ); - lefts.concatenate(rights); - EXPECT_TRUE(lefts.descriptors.rows() == 5); - EXPECT_TRUE(lefts.descriptors.cols() == lefts.features.cols()); -} - -TEST(PointCloudTest, ConcatenateDescSame2) -{ - typedef DP::Label Label; - - DP ref3DCopy(ref3D.features, ref3D.featureLabels); - ref3DCopy.descriptorLabels.push_back(Label("Desc5D", 5)); - ref3DCopy.descriptors = PM::Matrix::Random(5, ref3DCopy.features.cols()); - - const int leftPoints(ref3DCopy.features.cols() / 2); - const int rightPoints(ref3DCopy.features.cols() - leftPoints); - DP lefts( - ref3DCopy.features.leftCols(leftPoints), - ref3DCopy.featureLabels, - ref3DCopy.descriptors.leftCols(leftPoints), - ref3DCopy.descriptorLabels - ); - DP rights( - ref3DCopy.features.rightCols(rightPoints), - ref3DCopy.featureLabels, - ref3DCopy.descriptors.rightCols(rightPoints), - ref3DCopy.descriptorLabels - ); - lefts.concatenate(rights); - EXPECT_TRUE(lefts == ref3DCopy); -} - -TEST(PointCloudTest, ConcatenateDescDiffName) -{ - typedef DP::Label Label; - typedef DP::Labels Labels; - - const int leftPoints(ref2D.features.cols() / 2); - const int rightPoints(ref2D.features.cols() - leftPoints); - DP lefts( - ref2D.features.leftCols(leftPoints), - ref2D.featureLabels, - PM::Matrix::Random(5, leftPoints), - Labels(Label("MyDesc5D", 5)) - ); - DP rights( - ref2D.features.rightCols(rightPoints), - ref2D.featureLabels, - PM::Matrix::Random(5, rightPoints), - Labels(Label("YourDesc5D", 5)) - ); - lefts.concatenate(rights); - EXPECT_TRUE(lefts.descriptors.rows() == 0); - EXPECT_TRUE(lefts.descriptors.cols() == 0); -} - -TEST(PointCloudTest, ConcatenateDescDiffSize) -{ - typedef DP::Label Label; - typedef DP::Labels Labels; - - const int leftPoints(ref2D.features.cols() / 2); - const int rightPoints(ref2D.features.cols() - leftPoints); - DP lefts( - ref2D.features.leftCols(leftPoints), - ref2D.featureLabels, - PM::Matrix::Random(3, leftPoints), - Labels(Label("DescND", 3)) - ); - DP rights( - ref2D.features.rightCols(rightPoints), - ref2D.featureLabels, - PM::Matrix::Random(5, rightPoints), - Labels(Label("DescND", 5)) - ); - EXPECT_THROW(lefts.concatenate(rights), DP::InvalidField); -} - -TEST(PointCloudTest, AssertConsistency) -{ - DP ref2DCopy(ref2D); - - // Point cloud is in order after loading it - EXPECT_NO_THROW(ref2DCopy.assertDescriptorConsistency()); - - // We add only a descriptor label without descriptor - PM::DataPoints::Labels labels; - labels.push_back(PM::DataPoints::Label("FakeDesc", 2)); - ref2DCopy.descriptorLabels = labels; - EXPECT_THROW(ref2DCopy.assertDescriptorConsistency(), std::runtime_error); - - - // We add a descriptor with the wrong number of points - PM::Matrix descriptors = PM::Matrix::Random(2, 10); - ref2DCopy.descriptors = descriptors; - - EXPECT_THROW(ref2DCopy.assertDescriptorConsistency(), std::runtime_error); - - // We add a descriptor with the wrong dimension - descriptors = PM::Matrix::Random(1, ref2DCopy.getNbPoints()); - ref2DCopy.descriptors = descriptors; - EXPECT_THROW(ref2DCopy.assertDescriptorConsistency(), std::runtime_error); - -} - -TEST(PointCloudTest, GetInfo) -{ - //cerr << ref2D.features.rows() << endl; - //cerr << ref2D.features.cols() << endl; - //cerr << ref2D.descriptors.rows() << endl; - //cerr << ref2D.descriptors.cols() << endl; - - EXPECT_EQ(ref3D.getNbPoints(), 24989u); - EXPECT_EQ(ref3D.getEuclideanDim(), 3u); - EXPECT_EQ(ref3D.getHomogeneousDim(), 4u); - EXPECT_EQ(ref3D.getNbGroupedDescriptors(), 1u); - EXPECT_EQ(ref3D.getDescriptorDim(), 3u); - - EXPECT_EQ(ref2D.getNbPoints(), 361u); - EXPECT_EQ(ref2D.getEuclideanDim(), 2u); - EXPECT_EQ(ref2D.getHomogeneousDim(), 3u); - EXPECT_EQ(ref2D.getNbGroupedDescriptors(), 0u); - EXPECT_EQ(ref2D.getDescriptorDim(), 0u); - -} - -TEST(PointCloudTest, AddRemove) -{ - DP ref3DCopy = ref3D; - const int testedValue = 9; - - //////Add features - PM::Matrix newFeature = PM::Matrix::Ones(1,ref3DCopy.getNbPoints())*testedValue; - ref3DCopy.addFeature("testF", newFeature); - - //Is the new row added? - EXPECT_EQ(ref3DCopy.getHomogeneousDim(), ref3D.getHomogeneousDim()+1); - - //Is padding still at the end? - EXPECT_EQ(ref3DCopy.featureLabels.back().text, "pad"); - - //Is the value right? - DP::View newFeatureView = ref3DCopy.getFeatureViewByName("testF"); - EXPECT_EQ(newFeatureView(0,0), testedValue); - - //////Remove features - ref3DCopy.removeFeature("testF"); - - // Is the extra data removed? - EXPECT_TRUE(ref3DCopy.features.isApprox(ref3D.features)); - - - //////Add descriptors - const int testedValue2 = 88; - PM::Matrix newDescriptor4D = PM::Matrix::Ones(4,ref3DCopy.getNbPoints())*testedValue; - PM::Matrix newDescriptor2D = PM::Matrix::Ones(2,ref3DCopy.getNbPoints())*testedValue2; - - ref3DCopy.addDescriptor("test4D", newDescriptor4D); - ref3DCopy.addDescriptor("test2D", newDescriptor2D); - - //Is the new row added? - EXPECT_EQ(ref3DCopy.getDescriptorDim(), ref3D.getDescriptorDim()+6); - EXPECT_EQ(ref3DCopy.getNbGroupedDescriptors(), ref3D.getNbGroupedDescriptors()+2); - - //Is the value right? - DP::View newDescriptor4DView = ref3DCopy.getDescriptorViewByName("test4D"); - EXPECT_EQ(newDescriptor4DView(0,0), testedValue); - DP::View newDescriptor2DView = ref3DCopy.getDescriptorViewByName("test2D"); - EXPECT_EQ(newDescriptor2DView(0,0), testedValue2); - - - //////Remove descriptors - ref3DCopy.removeDescriptor("test4D"); - ref3DCopy.removeDescriptor("test2D"); - - //removing random name shoudn't have any effect - ref3DCopy.removeDescriptor("grrrrr"); - - // Is the extra data removed? - EXPECT_TRUE(ref3DCopy.descriptors.isApprox(ref3D.descriptors)); - -} diff --git a/thirdparty/libpointmatcher/utest/ui/ErrorMinimizers.cpp b/thirdparty/libpointmatcher/utest/ui/ErrorMinimizers.cpp deleted file mode 100644 index 3a5d461..0000000 --- a/thirdparty/libpointmatcher/utest/ui/ErrorMinimizers.cpp +++ /dev/null @@ -1,107 +0,0 @@ -#include "../utest.h" - -using namespace std; -using namespace PointMatcherSupport; - -//--------------------------- -// Error modules -//--------------------------- - -// Utility classes -class ErrorMinimizerTest: public IcpHelper -{ -public: - std::shared_ptr errorMin; - - // Will be called for every tests - virtual void SetUp() - { - icp.setDefault(); - // Uncomment for consol outputs - //setLogger(PM::get().LoggerRegistrar.create("FileLogger")); - } - - // Will be called for every tests - virtual void TearDown(){} - - void setError(string name) - { - errorMin = PM::get().ErrorMinimizerRegistrar.create(name); - icp.errorMinimizer = errorMin; - } -}; - - -TEST_F(ErrorMinimizerTest, PointToPointErrorMinimizer) -{ - setError("PointToPointErrorMinimizer"); - validate2dTransformation(); - validate3dTransformation(); -} - -TEST_F(ErrorMinimizerTest, PointToPlaneErrorMinimizer) -{ - setError("PointToPlaneErrorMinimizer"); - validate2dTransformation(); - validate3dTransformation(); -} - -TEST_F(ErrorMinimizerTest, ErrorElements) -{ - const unsigned int nbPoints = 100; - const unsigned int dimFeatures = 4; - const unsigned int dimDescriptors = 3; - const unsigned int dimTime = 2; - - // Fake DataPoints - PM::Matrix randFeat = PM::Matrix::Random(dimFeatures, nbPoints); - DP::Labels featLabels; - featLabels.push_back(DP::Label("x", 1)); - featLabels.push_back(DP::Label("y", 1)); - featLabels.push_back(DP::Label("z", 1)); - featLabels.push_back(DP::Label("pad", 1)); - - PM::Matrix randDesc = PM::Matrix::Random(dimDescriptors, nbPoints); - DP::Labels descLabels; - descLabels.push_back(DP::Label("dummyDesc", 3)); - - PM::Int64Matrix randTimes = PM::Int64Matrix::Random(dimTime, nbPoints); - DP::Labels timeLabels; - timeLabels.push_back(DP::Label("dummyTime", 2)); - - // Construct the point cloud from the generated matrices - DP request = DP(randFeat, featLabels, randDesc, descLabels, randTimes, timeLabels); - DP source = DP(randFeat, featLabels, randDesc, descLabels, randTimes, timeLabels); - - // Fake Weights - PM::OutlierWeights weights = PM::OutlierWeights::Ones(1, nbPoints); - - // Fake Matches - PM::Matches::Ids ids(1, nbPoints); - PM::Matches::Dists dists(1, nbPoints); - - for(unsigned int i=0; i IO; - std::istringstream is; - std::ostringstream os; - DP pts; - - // too many elements on a line - os.clear(); - os.str(""); - os << - "x, y\n" - "1, 2\n" - "1, 2, 3\n" - "1, 2\n" - ; - - is.clear(); - is.str(os.str()); - EXPECT_THROW(IO::loadCSV(is), runtime_error); - - // not enough elements on a line - os.clear(); - os.str(""); - os << - "x, y\n" - "1, 2\n" - "1, \n" - "1, 2\n" - ; - - is.clear(); - is.str(os.str()); - EXPECT_THROW(IO::loadCSV(is), runtime_error); - - // 2D data - os.clear(); - os.str(""); - os << - "x, y\n" - "1, 2\n" - "1, 2\n" - "8, 2\n" - "1, 2\n" - ; - - is.clear(); - is.str(os.str()); - pts = IO::loadCSV(is); - EXPECT_EQ(4u, pts.getNbPoints()); - EXPECT_EQ(2u, pts.getEuclideanDim()); - EXPECT_EQ(0u, pts.getDescriptorDim()); - EXPECT_EQ(0u, pts.getTimeDim()); - EXPECT_EQ(8.0, pts.features(0,2)); - - // 3D data - os.clear(); - os.str(""); - os << - "x, y, z\n" - "1, 2, 3\n" - "1, 2, 3\n" - "8, 2, 3\n" - "1, 2, 3\n" - ; - - is.clear(); - is.str(os.str()); - pts = IO::loadCSV(is); - EXPECT_EQ(4u, pts.getNbPoints()); - EXPECT_EQ(3u, pts.getEuclideanDim()); - EXPECT_EQ(0u, pts.getDescriptorDim()); - EXPECT_EQ(0u, pts.getTimeDim()); - EXPECT_EQ(8.0, pts.features(0,2)); - - // 3D data with unknown descriptor - os.clear(); - os.str(""); - os << - "x, y, z, dummy\n" - "1, 2, 3, 4\n" - "1, 2, 3, 4\n" - "8, 2, 3, 4\n" - "1, 2, 3, 4\n" - ; - - is.clear(); - is.str(os.str()); - pts = IO::loadCSV(is); - EXPECT_EQ(4u, pts.getNbPoints()); - EXPECT_EQ(3u, pts.getEuclideanDim()); - EXPECT_EQ(1u, pts.getDescriptorDim()); - EXPECT_EQ(0u, pts.getTimeDim()); - EXPECT_TRUE(pts.descriptorExists("dummy")); - - // 3D data with known descriptor - os.clear(); - os.str(""); - os << - "x, y, z, nx, ny, nz\n" - "1, 2, 3, 4, 5, 6\n" - "1, 2, 3, 4, 5, 6\n" - "8, 2, 3, 4, 5, 6\n" - "1, 2, 3, 4, 5, 6\n" - ; - - is.clear(); - is.str(os.str()); - pts = IO::loadCSV(is); - EXPECT_EQ(4u, pts.getNbPoints()); - EXPECT_EQ(3u, pts.getEuclideanDim()); - EXPECT_EQ(3u, pts.getDescriptorDim()); - EXPECT_EQ(1u, pts.getNbGroupedDescriptors()); - EXPECT_EQ(0u, pts.getTimeDim()); - EXPECT_TRUE(pts.descriptorExists("normals")); - - // csv with time - int64_t time0 = 1410264593275569438; - int64_t time1 = 1410264593325569391; - int64_t time2 = 1410264593425569295; - int64_t time3 = 1410264593522569417; - - os.clear(); - os.str(""); - os << - "x, y, z, time\n" - "1, 1, 1, " << time0 << "\n" - "2, 1, 1, " << time1 << "\n" - "3, 1, 1, " << time2 << "\n" - "4, 1, 1, " << time3 << "\n" - ; - - is.clear(); - is.str(os.str()); - - pts = IO::loadCSV(is); - EXPECT_EQ(4u, pts.getNbPoints()); - EXPECT_EQ(3u, pts.getEuclideanDim()); - EXPECT_EQ(0u, pts.getDescriptorDim()); - EXPECT_EQ(1u, pts.getTimeDim()); - EXPECT_EQ(time3, pts.times(0,3)); - - //cout << "dim: " << pts.getEuclideanDim() << endl; - //cout << "nb pts: " << pts.getNbPoints() << endl; - //cout << "desc dim: " << pts.getDescriptorDim() << endl; - //cout << "time dim: " << pts.getTimeDim() << endl; - - - -} - -TEST(IOTest, loadPLY) -{ - typedef PointMatcherIO IO; - std::istringstream is; - - is.str( - "" - ); - - EXPECT_THROW(IO::loadPLY(is), runtime_error); - - is.clear(); - is.str( - "ply\n" - "format binary_big_endian 1.0\n" - ); - - EXPECT_THROW(IO::loadPLY(is), runtime_error); - - is.clear(); - is.str( - "ply\n" - "format ascii 2.0\n" - ); - - EXPECT_THROW(IO::loadPLY(is), runtime_error); - - is.clear(); - is.str( - "ply\n" - "format ascii 1.0\n" - ); - - EXPECT_THROW(IO::loadPLY(is), runtime_error); - - is.clear(); - is.str( - "ply\n" - "format ascii 1.0\n" - "element vertex 5\n" - "\n" //empty line - "property float z\n" // wrong order - "property float y\n" - "property float x\n" - "property float grrrr\n" //unknown property - "property float nz\n" // wrong order - "property float ny\n" - "property float nx\n" - "end_header\n" - "3 2 1 99 33 22 11\n" - "3 2 1 99 33 22 11\n" - "\n" //empty line - "3 2 1 99 33 22 11 3 2 1 99 33 22 11\n" // no line break - "3 2 1 99 33 22 11\n" - - ); - - DP pointCloud = IO::loadPLY(is); - - // Confirm sizes and dimensions - EXPECT_TRUE(pointCloud.features.cols() == 5); - EXPECT_TRUE(pointCloud.features.rows() == 4); //x, y, z, pad - EXPECT_TRUE(pointCloud.descriptors.cols() == 5); - EXPECT_TRUE(pointCloud.descriptors.rows() == 4);//nx, ny, nz, grrrr - - // Random value check - EXPECT_TRUE(pointCloud.features(0, 0) == 1); - EXPECT_TRUE(pointCloud.features(2, 2) == 3); - EXPECT_TRUE(pointCloud.descriptors(1, 1) == 22); - EXPECT_TRUE(pointCloud.descriptors(2, 4) == 33); - -} - - -TEST(IOTest, loadPCD) -{ - typedef PointMatcherIO IO; - std::istringstream is; - - // Empty file - is.str( - "" - ); - - EXPECT_THROW(IO::loadPCD(is), runtime_error); - - // Partial header - is.clear(); - is.str( - "# .PCD v.7 - Point Cloud Data file format\n" - "VERSION .7\n" - ); - - EXPECT_THROW(IO::loadPCD(is), runtime_error); - - // Missing data - is.clear(); - is.str( - "# .PCD v.7 - Point Cloud Data file format\n" - "VERSION .7\n" - "FIELDS x y z\n" - "SIZE 4 4 4\n" - "TYPE F F F\n" - "COUNT 1 1 1\n" - "WIDTH 18\n" - "HEIGHT 1\n" - "VIEWPOINT 0 0 0 1 0 0 0\n" - "POINTS 18\n" - "DATA ascii\n" - ); - - EXPECT_THROW(IO::loadPCD(is), runtime_error); - - - is.clear(); - is.str( - "# .PCD v.7 - Point Cloud Data file format\n" - "VERSION .7\n" - "FIELDS x y z grrr\n" - "SIZE 4 4 4 4\n" - "TYPE F F F F\n" - "COUNT 1 1 1 1\n" - "WIDTH 18\n" - "HEIGHT 1\n" - "VIEWPOINT 0 0 0 1 0 0 0\n" - "POINTS 18\n" - "DATA ascii\n" - "0.44912094 0.49084857 1.153 22\n" - "0.34907714 0.48914573 1.149 22\n" - "0.33813429 0.48914573 1.149 22\n" - "0.32833049 0.49084857 1.153 22\n" - "0.24395333 0.42856666 0.98900002 22\n" - "0.20816095 0.42856666 0.98900002 22\n" - "0.1987419 0.42291525 0.98900002 22\n" - "0.18178761 0.42291525 0.98900002 22\n" - "0.17990381 0.42291525 0.98900002 22\n" - "-0.035590474 0.42997143 1.01 22\n" - "-0.035907622 0.43962574 1.0190001 22\n" - "-0.043542858 0.43639618 1.016 22\n" - "-0.15246001 0.36058003 0.84700006 22\n" - "0.21956001 0.44007048 0.99800003 22\n" - "-0.16635144 0.3699457 0.86900002 22\n" - "-0.33879143 0.36143145 0.84900004 22\n" - "-0.35055432 0.36853144 0.85800004 22\n" - "-0.39932001 0.38058859 0.89400005 22\n" - ); - - DP pointCloud = IO::loadPCD(is); - - // Confirm sizes and dimensions - EXPECT_TRUE(pointCloud.features.cols() == 18); - EXPECT_TRUE(pointCloud.features.rows() == 4); - EXPECT_TRUE(pointCloud.descriptors.cols() == 18); - EXPECT_TRUE(pointCloud.descriptors.rows() == 1); - - // Random value check - EXPECT_NEAR(pointCloud.features(0, 0), 0.449121, 0.0000001); - EXPECT_NEAR(pointCloud.features(2, 2), 1.149, 0.0000001); - EXPECT_NEAR(pointCloud.descriptors(0, 10), 22, 0.0000001); - -} - -class IOLoadSaveTest : public testing::Test -{ - -public: - virtual void SetUp() - { - nbPts = 10; - addRandomFeature("x", 1); - addRandomFeature("y", 1); - addRandomFeature("z", 1); - ptCloud.addFeature("pad", PM::Matrix::Ones(1, nbPts)); - - addRandomDescriptor("normals",3); - addRandomDescriptor("eigValues",3); - addRandomDescriptor("eigVectors",9); - addRandomDescriptor("color",4); - } - - void addRandomFeature(const string& featureName, const int rows) - { - ptCloud.addFeature(featureName,PM::Matrix::Random(rows, nbPts)); - } - - void addRandomDescriptor(const string& descriptorName, const int rows) - { - ptCloud.addDescriptor(descriptorName, PM::Matrix::Random(rows, nbPts)); - } - - virtual void loadSaveTest(const string& testFileName, bool plyFormat = false, const int nbPts = 10, bool binary = false) - { - this->testFileName = testFileName; - - if (plyFormat || binary) { - // make sure random values generated for colors are within ply format range - int pointCount(ptCloud.features.cols()); - int descRows(ptCloud.descriptors.rows()); - bool datawithColor = ptCloud.descriptorExists("color"); - int colorStartingRow = ptCloud.getDescriptorStartingRow("color"); - int colorEndRow = colorStartingRow + ptCloud.getDescriptorDimension("color"); - for (int p = 0; p < pointCount; ++p) - { - for (int d = 0; d < descRows; ++d) - { - if (datawithColor && d >= colorStartingRow && d < colorEndRow) { - if (ptCloud.descriptors(d, p) < 0) { ptCloud.descriptors.coeffRef(d, p) = -(ptCloud.descriptors(d, p)); } - ptCloud.descriptors.coeffRef(d, p) = (static_cast(ptCloud.descriptors(d, p) * 255.0)) / 255.0; - } - } - } - } - - ptCloud.save(testFileName, binary); - - ptCloudFromFile = DP::load(testFileName); - - EXPECT_TRUE(ptCloudFromFile.features.cols() == ptCloud.features.cols()); - EXPECT_TRUE(ptCloudFromFile.descriptorExists("normals",3)); - EXPECT_TRUE(ptCloudFromFile.getDescriptorViewByName("normals").isApprox(ptCloud.getDescriptorViewByName("normals"))); - EXPECT_TRUE(ptCloudFromFile.descriptorExists("eigValues",3)); - EXPECT_TRUE(ptCloudFromFile.getDescriptorViewByName("eigValues").isApprox(ptCloud.getDescriptorViewByName("eigValues"))); - EXPECT_TRUE(ptCloudFromFile.descriptorExists("eigVectors",9)); - EXPECT_TRUE(ptCloudFromFile.getDescriptorViewByName("eigVectors").isApprox(ptCloud.getDescriptorViewByName("eigVectors"))); - EXPECT_TRUE(ptCloudFromFile.descriptorExists("color",4)); - if (plyFormat || binary) { - EXPECT_TRUE(((ptCloudFromFile.getDescriptorViewByName("color") * 255.0)).isApprox((ptCloud.getDescriptorViewByName("color") * 255.0), 1.0)); - } else { - EXPECT_TRUE(ptCloudFromFile.getDescriptorViewByName("color").isApprox(ptCloud.getDescriptorViewByName("color"))); - } - - EXPECT_TRUE(ptCloudFromFile.features.isApprox(ptCloud.features)); - - } - - virtual void TearDown() - { - EXPECT_TRUE(boost::filesystem::remove(boost::filesystem::path(testFileName))); - } - - -protected: - int nbPts; - DP::Labels featureLabels; - DP ptCloud; - DP ptCloudFromFile; - string testFileName; - -}; - -TEST_F(IOLoadSaveTest, VTK) -{ - ptCloud.addDescriptor("genericScalar", PM::Matrix::Random(1, nbPts)); - ptCloud.addDescriptor("genericVector", PM::Matrix::Random(3, nbPts)); - ptCloud.addTime("genericTime", PM::Int64Matrix::Random(1, nbPts)); - - loadSaveTest(dataPath + "unit_test.vtk"); - - EXPECT_TRUE(ptCloudFromFile.descriptorExists("genericScalar",1)); - EXPECT_TRUE(ptCloudFromFile.descriptorExists("genericVector",3)); - EXPECT_TRUE(ptCloudFromFile.timeExists("genericTime",1)); - -} - -TEST_F(IOLoadSaveTest, VTKBinary) -{ - ptCloud.addDescriptor("genericScalar", PM::Matrix::Random(1, nbPts)); - ptCloud.addDescriptor("genericVector", PM::Matrix::Random(3, nbPts)); - ptCloud.addTime("genericTime", PM::Int64Matrix::Random(1, nbPts)); - - loadSaveTest(dataPath + "unit_test.bin.vtk", false, 10, true); - - EXPECT_TRUE(ptCloudFromFile.descriptorExists("genericScalar",1)); - EXPECT_TRUE(ptCloudFromFile.descriptorExists("genericVector",3)); - EXPECT_TRUE(ptCloudFromFile.timeExists("genericTime",1)); -} - -TEST_F(IOLoadSaveTest, PLY) -{ - loadSaveTest(dataPath + "unit_test.ply", true); -} - -TEST_F(IOLoadSaveTest, PCD) -{ - loadSaveTest(dataPath + "unit_test.pcd"); -} - -TEST_F(IOLoadSaveTest, CSV) -{ - loadSaveTest(dataPath + "unit_test.csv"); -} diff --git a/thirdparty/libpointmatcher/utest/ui/Inspectors.cpp b/thirdparty/libpointmatcher/utest/ui/Inspectors.cpp deleted file mode 100644 index 448da5c..0000000 --- a/thirdparty/libpointmatcher/utest/ui/Inspectors.cpp +++ /dev/null @@ -1,35 +0,0 @@ -#include "../utest.h" - -using namespace std; -using namespace PointMatcherSupport; - -//--------------------------- -// Inspectors -//--------------------------- -TEST(Inspectors, PerformanceInspector) -{ - std::shared_ptr performances = - PM::get().REG(Inspector).create( - "PerformanceInspector", { - {"baseFileName", "/tmp/utest_performances"}, - {"dumpPerfOnExit", "1"} - } - ) - ; - - performances->init(); - - //TODO: we only test constructor here, check other things... -} - -TEST(Inspectors, VTKFileInspector) -{ - std::shared_ptr vtkFile = - PM::get().REG(Inspector).create( - "VTKFileInspector", { - {"baseFileName", "/tmp/utest_vtk"}, - {"dumpPerfOnExit", "1"} - } - ); - //TODO: we only test constructor here, check other things... -} diff --git a/thirdparty/libpointmatcher/utest/ui/Loggers.cpp b/thirdparty/libpointmatcher/utest/ui/Loggers.cpp deleted file mode 100644 index bb93c60..0000000 --- a/thirdparty/libpointmatcher/utest/ui/Loggers.cpp +++ /dev/null @@ -1,88 +0,0 @@ -#include "../utest.h" - -using namespace std; -using namespace PointMatcherSupport; - -//--------------------------- -// Loggers -//--------------------------- - -TEST(Loggers, FileLogger) -{ - string infoFileName = "utest_info"; - string warningFileName = "utest_warn"; - - std::shared_ptr fileLog = - PM::get().REG(Logger).create( - "FileLogger", { - {"infoFileName", infoFileName}, - { "warningFileName", warningFileName }, - { "displayLocation", "1" } - } - ); - - fileLog.reset(); // The logger needs to release the files to allow them to be removed - - EXPECT_TRUE(boost::filesystem::remove(boost::filesystem::path(infoFileName))); - EXPECT_TRUE(boost::filesystem::remove(boost::filesystem::path(warningFileName))); -} - -TEST(Loggers, FileLoggerInfoToConsole) -{ - std::shared_ptr fileLog = - PM::get().REG(Logger).create( - "FileLogger", { - { "displayLocation", "1" } - } - ); - EXPECT_NO_THROW((*fileLog->infoStream()) << "TEST\n"); -} - -TEST(Loggers, FileLoggerWarningToConsole) -{ - std::shared_ptr fileLog = - PM::get().REG(Logger).create( - "FileLogger", { - { "displayLocation", "1" } - } - ); - EXPECT_NO_THROW((*fileLog->warningStream()) << "TEST\n"); -} - -TEST(Loggers, FileLoggerInfoToFile) -{ - string infoFileName = "utest_info"; - - std::shared_ptr fileLog = - PM::get().REG(Logger).create( - "FileLogger", { - {"infoFileName", infoFileName}, - { "displayLocation", "1" } - } - ); - - EXPECT_NO_THROW((*fileLog->infoStream()) << "TEST"); - - fileLog.reset(); // The logger needs to release the file to allow it to be removed - - EXPECT_TRUE(boost::filesystem::remove(boost::filesystem::path(infoFileName))); -} - -TEST(Loggers, FileLoggerWarningToFile) -{ - string warningFileName = "utest_warn"; - - std::shared_ptr fileLog = - PM::get().REG(Logger).create( - "FileLogger", { - { "warningFileName", warningFileName }, - { "displayLocation", "1" } - } - ); - - EXPECT_NO_THROW((*fileLog->warningStream()) << "TEST"); - - fileLog.reset(); // The logger needs to release the file to allow it to be removed - - EXPECT_TRUE(boost::filesystem::remove(boost::filesystem::path(warningFileName))); -} diff --git a/thirdparty/libpointmatcher/utest/ui/Matcher.cpp b/thirdparty/libpointmatcher/utest/ui/Matcher.cpp deleted file mode 100644 index 5ce4f5d..0000000 --- a/thirdparty/libpointmatcher/utest/ui/Matcher.cpp +++ /dev/null @@ -1,63 +0,0 @@ -#include "../utest.h" - -using namespace std; -using namespace PointMatcherSupport; - -//--------------------------- -// Matcher modules -//--------------------------- - -// Utility classes -class MatcherTest: public IcpHelper -{ - -public: - - std::shared_ptr testedMatcher; - - // Will be called for every tests - virtual void SetUp() - { - icp.setDefault(); - // Uncomment for consol outputs - //setLogger(PM::get().LoggerRegistrar.create("FileLogger")); - } - - // Will be called for every tests - virtual void TearDown(){} - - void addFilter(string name, PM::Parameters params) - { - testedMatcher = - PM::get().MatcherRegistrar.create(name, params); - icp.matcher = testedMatcher; - } - -}; - -TEST_F(MatcherTest, KDTreeMatcher) -{ - vector knn = {1, 2, 3}; - vector epsilon = {0.0, 0.2}; - vector maxDist = {1.0, 0.5}; - - for(unsigned i=0; i < knn.size(); i++) - { - for(unsigned j=0; j < epsilon.size(); j++) - { - for(unsigned k=0; k < maxDist.size(); k++) - { - params = PM::Parameters(); - params["knn"] = toParam(knn[i]); // remove end parenthesis for bug - params["epsilon"] = toParam(epsilon[j]); - params["searchType"] = "1"; - params["maxDist"] = toParam(maxDist[k]); - - - addFilter("KDTreeMatcher", params); - validate2dTransformation(); - validate3dTransformation(); - } - } - } -} diff --git a/thirdparty/libpointmatcher/utest/ui/Outliers.cpp b/thirdparty/libpointmatcher/utest/ui/Outliers.cpp deleted file mode 100644 index 99aa29e..0000000 --- a/thirdparty/libpointmatcher/utest/ui/Outliers.cpp +++ /dev/null @@ -1,152 +0,0 @@ -#include "../utest.h" -#include "pointmatcher/OutlierFiltersImpl.h" - -using namespace std; -using namespace PointMatcherSupport; - -//--------------------------- -// Outlier modules -//--------------------------- - -// Utility classes -class OutlierFilterTest: public IcpHelper -{ -public: - std::shared_ptr testedOutlierFilter; - - // Will be called for every tests - virtual void SetUp() - { - icp.setDefault(); - // Uncomment for console outputs - //setLogger(PM::get().LoggerRegistrar.create("FileLogger")); - - icp.outlierFilters.clear(); - } - - // Will be called for every tests - virtual void TearDown(){} - - void addFilter(string name, PM::Parameters params) - { - testedOutlierFilter = - PM::get().OutlierFilterRegistrar.create(name, params); - icp.outlierFilters.push_back(testedOutlierFilter); - } - -}; - -//No commun parameters were found for 2D and 3D, tests are spliced -TEST_F(OutlierFilterTest, MaxDistOutlierFilter2D) -{ - addFilter("MaxDistOutlierFilter", { - {"maxDist", toParam(0.10)} - } - ); - validate2dTransformation(); -} - -TEST_F(OutlierFilterTest, MaxDistOutlierFilter3D) -{ - addFilter("MaxDistOutlierFilter", { - {"maxDist", toParam(1.0)} - } - ); - validate3dTransformation(); -} - -//No commun parameters were found for 2D and 3D, tests are spliced -TEST_F(OutlierFilterTest, MinDistOutlierFilter2D) -{ - // Since not sure how useful is that filter, we keep the - // MaxDistOutlierFilter with it - std::shared_ptr extraOutlierFilter; - - extraOutlierFilter = - PM::get().OutlierFilterRegistrar.create( - "MaxDistOutlierFilter", { - {"maxDist", toParam(0.10)} - } - ); - icp.outlierFilters.push_back(extraOutlierFilter); - - addFilter("MinDistOutlierFilter", {{"minDist", toParam(0.0002)}}); - - validate2dTransformation(); -} - -TEST_F(OutlierFilterTest, MinDistOutlierFilter3D) -{ - // Since not sure how useful is that filter, we keep the - // MaxDistOutlierFilter with it - std::shared_ptr extraOutlierFilter; - - extraOutlierFilter = - PM::get().OutlierFilterRegistrar.create( - "MaxDistOutlierFilter", { - {"maxDist", toParam(1.0)} - } - ) - ; - icp.outlierFilters.push_back(extraOutlierFilter); - - addFilter("MinDistOutlierFilter", {{"minDist", toParam(0.0002)}}); - - validate3dTransformation(); -} - -TEST_F(OutlierFilterTest, MedianDistOutlierFilter) -{ - addFilter("MedianDistOutlierFilter", {{"factor", toParam(3.5)}}); - validate2dTransformation(); - validate3dTransformation(); -} - - -TEST_F(OutlierFilterTest, TrimmedDistOutlierFilter) -{ - addFilter("TrimmedDistOutlierFilter", {{"ratio", toParam(0.85)}}); - validate2dTransformation(); - validate3dTransformation(); -} - - -TEST_F(OutlierFilterTest, VarTrimmedDistOutlierFilter) -{ - addFilter("VarTrimmedDistOutlierFilter", { - {"minRatio", toParam(0.60)}, - {"maxRatio", toParam(0.80)}, - {"lambda", toParam(0.9)} - } - ); - validate2dTransformation(); - validate3dTransformation(); -} - -OutlierFiltersImpl::OutlierWeights VarTrimLambdaTest(const float lambda) { - OutlierFiltersImpl::VarTrimmedDistOutlierFilter filter({{"minRatio", toParam(0.0000001)}, - {"maxRatio", toParam(1.0)}, - {"lambda", toParam(lambda)}}); - PointMatcher::DataPoints filteredReading; - PointMatcher::DataPoints filteredReference; - - // Create a vector a distance - PointMatcher::Matches::Dists dists(1, 5); - dists << 4, 5, 5, 5, 5; - PointMatcher::Matches::Ids ids(1, 5); - PointMatcher::Matches input(dists, ids); - return filter.compute(filteredReading, filteredReference, input); -} - -TEST_F(OutlierFilterTest, VarTrimmedDistOutlierFilterParameters) -{ - // A lambda parameter of zero, all matches will be reject except for the minimum - OutlierFiltersImpl::OutlierWeights weights = VarTrimLambdaTest(0.0); - // The minimum is the first value - ASSERT_EQ(1.0f, weights(0, 0)); - ASSERT_EQ(0.0f, weights(0, 1)); - - weights = VarTrimLambdaTest(1.0); - ASSERT_EQ(1.0f, weights(0, 0)); - ASSERT_EQ(1.0f, weights(0, 1)); -} diff --git a/thirdparty/libpointmatcher/utest/ui/Transformations.cpp b/thirdparty/libpointmatcher/utest/ui/Transformations.cpp deleted file mode 100644 index 2c17b8f..0000000 --- a/thirdparty/libpointmatcher/utest/ui/Transformations.cpp +++ /dev/null @@ -1,131 +0,0 @@ -#include "../utest.h" - -using namespace std; -using namespace PointMatcherSupport; - - -//--------------------------- -// Transformation Checker modules -//--------------------------- - -// Utility classes -class TransformationCheckerTest: public IcpHelper -{ -public: - std::shared_ptr transformCheck; - - // Will be called for every tests - virtual void SetUp() - { - icp.setDefault(); - // Uncomment for consol outputs - //setLogger(PM::get().LoggerRegistrar.create("FileLogger")); - - icp.transformationCheckers.clear(); - } - - // Will be called for every tests - virtual void TearDown(){} - - void addFilter(string name, PM::Parameters params) - { - transformCheck = - PM::get().TransformationCheckerRegistrar.create(name, params); - - icp.transformationCheckers.push_back(transformCheck); - } -}; - - -TEST_F(TransformationCheckerTest, CounterTransformationChecker) -{ - addFilter("CounterTransformationChecker", {{"maxIterationCount", toParam(20)}}); - validate2dTransformation(); -} - -TEST_F(TransformationCheckerTest, DifferentialTransformationChecker) -{ - addFilter("DifferentialTransformationChecker", { - {"minDiffRotErr", toParam(0.001)}, - {"minDiffTransErr", toParam(0.001)}, - {"smoothLength", toParam(4)} - } - ); - validate2dTransformation(); -} - -TEST_F(TransformationCheckerTest, BoundTransformationChecker) -{ - // Since that transChecker is trigger when the distance is growing - // and that we do not expect that to happen in the test dataset, we - // keep the Counter to get out of the looop - std::shared_ptr extraTransformCheck; - - extraTransformCheck = PM::get().TransformationCheckerRegistrar.create( - "CounterTransformationChecker" - ); - icp.transformationCheckers.push_back(extraTransformCheck); - - addFilter("BoundTransformationChecker", { - {"maxRotationNorm", toParam(1.0)}, - {"maxTranslationNorm", toParam(1.0)} - } - ); - validate2dTransformation(); -} - -//--------------------------- -// Transformation -//--------------------------- -TEST(Transformation, RigidTransformation) -{ - std::shared_ptr rigidTrans; - rigidTrans = PM::get().REG(Transformation).create("RigidTransformation"); - - //------------------------------------- - // Construct a 3D non-orthogonal matrix - PM::Matrix T_3D = PM::Matrix::Identity(4,4); - //T_3D(0,0) = 2.3; - //T_3D(0,1) = 0.03; - T_3D << 0.99935116, 0.13669771, 0.03436585, 1.71138524, - -0.02633967, 0.99326295, -0.04907545, -0.10860933, - -0.03615132, 0.04400287, 0.99820427, -0.04454497, - 0. , 0. , 0. , 1.; - - EXPECT_FALSE(rigidTrans->checkParameters(T_3D)); - - EXPECT_THROW(rigidTrans->compute(data3D, T_3D), TransformationError); - - // Check stability over iterations - for(int i = 0; i < 10; i++) - { - T_3D = rigidTrans->correctParameters(T_3D); - ASSERT_TRUE(rigidTrans->checkParameters(T_3D)); - } - - //------------------------------------- - // Construct a 2D non-orthogonal matrix - PM::Matrix T_2D_non_ortho = PM::Matrix::Identity(3,3); - T_2D_non_ortho(0,0) = 0.8; - T_2D_non_ortho(0,1) = -0.5; - T_2D_non_ortho(1,0) = 0.5; - T_2D_non_ortho(1,1) = 0.8; - - EXPECT_FALSE(rigidTrans->checkParameters(T_2D_non_ortho)); - - EXPECT_THROW(rigidTrans->compute(data2D, T_2D_non_ortho), TransformationError); - - // Check stability over iterations - for(int i = 0; i < 10; i++) - { - T_2D_non_ortho = rigidTrans->correctParameters(T_2D_non_ortho); - EXPECT_TRUE(rigidTrans->checkParameters(T_2D_non_ortho)); - } - - //------------------------------------- - // Construct a 2D reflection matrix - PM::Matrix T_2D_reflection = PM::Matrix::Identity(3,3); - T_2D_reflection(1,1) = -1; - - EXPECT_THROW(rigidTrans->correctParameters(T_2D_reflection), TransformationError); -} diff --git a/thirdparty/libpointmatcher/utest/utest.cpp b/thirdparty/libpointmatcher/utest/utest.cpp deleted file mode 100644 index 4ddc1c6..0000000 --- a/thirdparty/libpointmatcher/utest/utest.cpp +++ /dev/null @@ -1,364 +0,0 @@ -// kate: replace-tabs off; indent-width 4; indent-mode normal -// vim: ts=4:sw=4:noexpandtab -/* - -Copyright (c) 2010--2012, -François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland -You can contact the authors at and - - -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 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 ETH-ASL 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. - -*/ - -#include "utest.h" - -using namespace std; -using namespace PointMatcherSupport; - -// TODO: avoid global by using testing::Environment - -std::string dataPath; - -DP ref2D; -DP data2D; -DP ref3D; -DP data3D; -PM::TransformationParameters validT2d; -PM::TransformationParameters validT3d; - -//--------------------------- -// Test ICP with all existing filters. - -// Algorithm: -// 1. Iterate over all yaml files in -// libpointmatcher/examples/data/icp_data, each file tests ICP -// with one or more filters. -// 2. Run ICP with the given yaml file. The filters in the yaml -// file are applied along the way. -// 3. Write the obtained ICP transform to disk, to the same directory, -// with file extension .cur_trans (for easy future comparisons). -// 4. Load the reference (known as correct) ICP transform from disk, -// from the same directory, with file extension .ref_trans. -// 5. See if the current and reference transforms are equal. - -// To update an existing test or add a new test, simply add/modify -// the desired yaml file, run the tests (they may fail this time), then -// copy the (just written) desired current transform file on top of the -// corresponding reference transform file. Run the tests again. This -// time they will succeed. -//--------------------------- - -// Find the median coefficient of a matrix -double median_coeff(Eigen::MatrixXf& A){ - Eigen::Map v(A.data(),A.size()); - std::sort(v.data(), v.data() + v.size()); - return v[v.size()/2]; -} - -TEST(icpTest, icpTest) -{ - DP ref = DP::load(dataPath + "cloud.00000.vtk"); - DP data = DP::load(dataPath + "cloud.00001.vtk"); - - namespace fs = boost::filesystem; - fs::path config_dir(dataPath + "icp_data"); - EXPECT_TRUE( fs::exists(config_dir) && fs::is_directory(config_dir) ); - - fs::directory_iterator end_iter; - for( fs::directory_iterator d(config_dir); d != end_iter; ++d) - { - if (!fs::is_regular_file(d->status()) ) continue; - - std::cout << "Testing file " << d->path().string() << std::endl; - // Load config file, and form ICP object - PM::ICP icp; - std::string config_file = d->path().string(); - if (fs::extension(config_file) != ".yaml") continue; - std::ifstream ifs(config_file.c_str()); - EXPECT_NO_THROW(icp.loadFromYaml(ifs)) << "This error was caused by the test file:" << endl << " " << config_file; - - // Compute current ICP transform - PM::TransformationParameters curT = icp(data, ref); - - // Write current transform to disk (to easily compare it - // with reference transform offline) - fs::path cur_file = d->path(); - cur_file.replace_extension(".cur_trans"); - //std::cout << "Writing: " << cur_file << std::endl; - std::ofstream otfs(cur_file.c_str()); - otfs.precision(16); - otfs << curT; - otfs.close(); - - // Load reference transform - fs::path ref_file = d->path(); - ref_file.replace_extension(".ref_trans"); - PM::TransformationParameters refT = 0*curT; - //std::cout << "Reading: " << ref_file << std::endl; - std::ifstream itfs(ref_file.c_str()); - EXPECT_TRUE(itfs.good()) << "Could not find " << ref_file - << ". If this is the first time this test is run, " - << "create it as a copy of " << cur_file; - - for (int row = 0; row < refT.cols(); row++) - { - for (int col = 0; col < refT.cols(); col++) - { - itfs >>refT(row, col); - } - } - - // Dump the reference transform and current one - //std::cout.precision(17); - //std::cout << "refT:\n" << refT << std::endl; - //std::cout << "curT:\n" << curT << std::endl; - - // We need to compare the stored icp transform vs the computed one. - // Since the icp solution is not unique, they may differ a lot. - // Yet, the point of icp is - // curT*data = ref, and refT*data = ref - // so no matter what, the difference curT*data - refT*data - // must be small, which is what we will test for. - - // Find the median absolute difference between curT*data and refT*data - Eigen::MatrixXf AbsDiff = (curT*data.features - refT*data.features).array().abs(); - double median_diff = median_coeff(AbsDiff); - - // Find the median absolute value of curT*data - Eigen::MatrixXf Data = (curT*data.features).array().abs(); - double median_data = median_coeff(Data); - - // Find the relative error - double rel_err = median_diff/median_data; - - // A relative error of 3% is probably acceptable. - EXPECT_LT(rel_err, 0.03) << "This error was caused by the test file:" << endl << " " << config_file; - } -} - -TEST(icpTest, icpSingular) -{ - // Here we test point-to-plane ICP where the point clouds underdetermine transformation - // This situation requires special treatment in the algorithm. - - // create a x-y- planar grid point cloud in points - const size_t nX = 10, nY = nX; - Eigen::MatrixXf points(4, nX * nY); - const float d = 0.1; - const float oX = -(nX * d / 2), oY = -(nY * d / 2); - - for(size_t x = 0; x < nX; x++){ - for(size_t y = 0; y < nY; y++){ - points.col( x * nY + y) << d * x + oX, d * y + oY, 0, 1; - } - } - - DP pts0; - pts0.features = points; - DP pts1; - points.row(2).setOnes(); - pts1.features = points; // pts1 is pts0 shifted by one in z-direction - - PM::ICP icp; - std::string config_file = dataPath + "default-identity.yaml"; - EXPECT_TRUE(boost::filesystem::exists(config_file)); - - std::ifstream ifs(config_file.c_str()); - EXPECT_NO_THROW(icp.loadFromYaml(ifs)) << "This error was caused by the test file:" << endl << " " << config_file; - - // Compute ICP transform - PM::TransformationParameters curT = icp(pts0, pts1); - - PM::Matrix expectedT = PM::Matrix::Identity(4,4); - expectedT(2,3) = 1; - EXPECT_TRUE(expectedT.isApprox(curT)) << "Expecting pure translation in z-direction of unit distance." << endl; -} - -TEST(icpTest, icpIdentity) -{ - // Here we test point-to-plane ICP where we expect the output transform to be - // the identity. This situation requires special treatment in the algorithm. - const float epsilon = 0.0001; - - DP pts0 = DP::load(dataPath + "cloud.00000.vtk"); - DP pts1 = DP::load(dataPath + "cloud.00000.vtk"); - - PM::ICP icp; - std::string config_file = dataPath + "default-identity.yaml"; - EXPECT_TRUE(boost::filesystem::exists(config_file)); - - std::ifstream ifs(config_file.c_str()); - EXPECT_NO_THROW(icp.loadFromYaml(ifs)) << "This error was caused by the test file:" << endl << " " << config_file; - - // Compute current ICP transform - PM::TransformationParameters curT = icp(pts0, pts1); - - EXPECT_TRUE(curT.isApprox(PM::Matrix::Identity(4, 4), epsilon)) << "Expecting identity transform." << endl; -} - -TEST(icpTest, similarityTransform) -{ - // Here we test similarity point-to-point ICP. - - DP pts0 = DP::load(dataPath + "car_cloud400.csv"); - DP pts1 = DP::load(dataPath + "car_cloud400_scaled.csv"); - - PM::ICP icp; - std::string config_file = dataPath + "icp_data/defaultSimilarityPointToPointMinDistDataPointsFilter.yaml"; - EXPECT_TRUE(boost::filesystem::exists(config_file)); - - std::ifstream ifs(config_file.c_str()); - EXPECT_NO_THROW(icp.loadFromYaml(ifs)) << "This error was caused by the test file:" << endl << " " << config_file; - - // Compute current ICP transform - PM::TransformationParameters curT = icp(pts0, pts1); - - // We know the scale we're looking for is 1.04. - double scale = pow(curT.determinant(), 1.0/3.0); - EXPECT_LT( std::abs(scale - 1.04), 0.001) - << "Expecting the similarity transform scale to be 1.04."; -} - -TEST(icpTest, icpSequenceTest) -{ - DP pts0 = DP::load(dataPath + "cloud.00000.vtk"); - DP pts1 = DP::load(dataPath + "cloud.00001.vtk"); - DP pts2 = DP::load(dataPath + "cloud.00002.vtk"); - - PM::TransformationParameters Ticp = PM::Matrix::Identity(4,4); - - PM::ICPSequence icpSequence; - - std::ifstream ifs((dataPath + "default.yaml").c_str()); - icpSequence.loadFromYaml(ifs); - - EXPECT_FALSE(icpSequence.hasMap()); - - DP map = icpSequence.getPrefilteredInternalMap(); - EXPECT_EQ(map.getNbPoints(), 0u); - EXPECT_EQ(map.getHomogeneousDim(), 0u); - - map = icpSequence.getPrefilteredMap(); - EXPECT_EQ(map.getNbPoints(), 0u); - EXPECT_EQ(map.getHomogeneousDim(), 0u); - - icpSequence.setMap(pts0); - map = icpSequence.getPrefilteredInternalMap(); - EXPECT_LE(map.getNbPoints(), pts0.getNbPoints()); - EXPECT_GT(map.getNbPoints(), 0u); - EXPECT_EQ(map.getHomogeneousDim(), pts0.getHomogeneousDim()); - - Ticp = icpSequence(pts1); - map = icpSequence.getPrefilteredMap(); - EXPECT_LE(map.getNbPoints(), pts0.getNbPoints()); - EXPECT_GT(map.getNbPoints(), 0u); - EXPECT_EQ(map.getHomogeneousDim(), pts0.getHomogeneousDim()); - - Ticp = icpSequence(pts2); - map = icpSequence.getPrefilteredMap(); - EXPECT_LE(map.getNbPoints(), pts0.getNbPoints()); - EXPECT_GT(map.getNbPoints(), 0u); - EXPECT_EQ(map.getHomogeneousDim(), pts0.getHomogeneousDim()); - - icpSequence.clearMap(); - map = icpSequence.getPrefilteredInternalMap(); - EXPECT_EQ(map.getNbPoints(), 0u); - EXPECT_EQ(map.getHomogeneousDim(), 0u); -} - -// Utility classes -class GenericTest: public IcpHelper -{ - -public: - - // Will be called for every tests - virtual void SetUp() - { - icp.setDefault(); - // Uncomment for consol outputs - //setLogger(PM::get().LoggerRegistrar.create("FileLogger")); - } - - // Will be called for every tests - virtual void TearDown() - { - } -}; - -//--------------------------- -// Generic tests -//--------------------------- - -TEST_F(GenericTest, ICP_default) -{ - validate2dTransformation(); - validate3dTransformation(); -} - -//--------------------------- -// Main -//--------------------------- -int main(int argc, char **argv) -{ - dataPath = ""; - for(int i=1; i < argc; i++) - { - if (strcmp(argv[i], "--path") == 0 && i+1 < argc) - dataPath = argv[i+1]; - } - - if(dataPath == "") - { - cerr << "Missing the flag --path ./path/to/examples/data\n Please give the path to the test data folder which should be included with the source code. The folder is named 'examples/data'." << endl; - return -1; - } - - // Load point cloud for all test - ref2D = DP::load(dataPath + "2D_oneBox.csv"); - data2D = DP::load(dataPath + "2D_twoBoxes.csv"); - ref3D = DP::load(dataPath + "car_cloud400.csv"); - data3D = DP::load(dataPath + "car_cloud401.csv"); - - // Result of data express in ref (from visual inspection) - validT2d = PM::TransformationParameters(3,3); - validT2d << 0.987498, 0.157629, 0.0859918, - -0.157629, 0.987498, 0.203247, - 0, 0, 1; - - validT3d = PM::TransformationParameters(4,4); - validT3d << 0.982304, 0.166685, -0.0854066, 0.0446816, - -0.150189, 0.973488, 0.172524, 0.191998, - 0.111899, -0.156644, 0.981296, -0.0356313, - 0, 0, 0, 1; - - testing::GTEST_FLAG(print_time) = true; - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} - - - diff --git a/thirdparty/libpointmatcher/utest/utest.h b/thirdparty/libpointmatcher/utest/utest.h deleted file mode 100644 index 43844ab..0000000 --- a/thirdparty/libpointmatcher/utest/utest.h +++ /dev/null @@ -1,90 +0,0 @@ -#ifndef UTEST_HPP_ -#define UTEST_HPP_ - -#include "pointmatcher/PointMatcher.h" -#include "pointmatcher/IO.h" -#include "../contrib/gtest/gtest.h" - -#include -#include - -#include "boost/filesystem.hpp" -#include "boost/filesystem/path.hpp" -#include "boost/filesystem/operations.hpp" - -typedef PointMatcher PM; -typedef PM::DataPoints DP; - -extern std::string dataPath; - -extern DP ref2D; -extern DP data2D; -extern DP ref3D; -extern DP data3D; -extern PM::TransformationParameters validT2d; -extern PM::TransformationParameters validT3d; - -//--------------------------- -// Base for ICP tests -//--------------------------- - -class IcpHelper: public testing::Test -{ -public: - - PM::ICP icp; - - PM::Parameters params; - - virtual void dumpVTK() - { - // Make available a VTK inspector for manual inspection - icp.inspector = - PM::get().InspectorRegistrar.create( - "VTKFileInspector", - {{"baseFileName", "./unitTest"}} - ); - } - - void validate2dTransformation() - { - const PM::TransformationParameters testT = icp(data2D, ref2D); - const int dim = validT2d.cols(); - - const BOOST_AUTO(validTrans, validT2d.block(0, dim-1, dim-1, 1).norm()); - const BOOST_AUTO(testTrans, testT.block(0, dim-1, dim-1, 1).norm()); - - const BOOST_AUTO(validAngle, acos(validT2d(0,0))); - const BOOST_AUTO(testAngle, acos(testT(0,0))); - - EXPECT_NEAR(validTrans, testTrans, 0.05); - EXPECT_NEAR(validAngle, testAngle, 0.05); - } - - void validate3dTransformation() - { - //dumpVTK(); - - const PM::TransformationParameters testT = icp(data3D, ref3D); - const int dim = validT2d.cols(); - - const BOOST_AUTO(validTrans, validT3d.block(0, dim-1, dim-1, 1).norm()); - const BOOST_AUTO(testTrans, testT.block(0, dim-1, dim-1, 1).norm()); - - const BOOST_AUTO(testRotation, Eigen::Quaternion(Eigen::Matrix(testT.topLeftCorner(3,3)))); - const BOOST_AUTO(validRotation, Eigen::Quaternion(Eigen::Matrix(validT3d.topLeftCorner(3,3)))); - - const BOOST_AUTO(angleDist, validRotation.angularDistance(testRotation)); - - //cout << testT << endl; - //cout << "angleDist: " << angleDist << endl; - //cout << "transDist: " << abs(validTrans-testTrans) << endl; - EXPECT_NEAR(validTrans, testTrans, 0.1); - EXPECT_NEAR(angleDist, 0.0, 0.1); - - } -}; - -#endif /* UTEST_HPP_ */ - -